Repository: tiev-tongji/LOG-LIO Branch: main Commit: a2f49d66b9e3 Files: 75 Total size: 13.7 MB Directory structure: gitextract_jallgs7z/ ├── CMakeLists.txt ├── LICENSE ├── Log/ │ ├── dbg.txt │ ├── fast_lio_time_log.csv │ ├── fast_lio_time_log_analysis.m │ ├── guide.md │ ├── imu.txt │ ├── mat_out.txt │ ├── mat_pre.txt │ ├── plot.py │ └── pos_log.txt ├── README.md ├── config/ │ ├── m2dgr/ │ │ ├── ring32_M_0.xml │ │ ├── ring32_M_1.xml │ │ ├── ring32_M_2.xml │ │ ├── ring32_M_3.xml │ │ ├── ring32_M_4.xml │ │ ├── ring32_M_5.xml │ │ ├── ring32_M_6.xml │ │ ├── ring32_M_7.xml │ │ ├── ring32_M_8.xml │ │ └── ring32_v.xml │ ├── ouster64.yaml │ ├── rs128.yaml │ ├── velodyne.yaml │ ├── velodyne_m2dgr.yaml │ ├── viral/ │ │ ├── ring16_M_0.xml │ │ ├── ring16_M_1.xml │ │ ├── ring16_M_2.xml │ │ ├── ring16_M_3.xml │ │ ├── ring16_M_4.xml │ │ ├── ring16_M_5.xml │ │ ├── ring16_M_6.xml │ │ ├── ring16_M_7.xml │ │ ├── ring16_M_8.xml │ │ └── ring16_v.xml │ └── viral.yaml ├── include/ │ ├── Exp_mat.h │ ├── IKFoM_toolkit/ │ │ ├── esekfom/ │ │ │ ├── esekfom.hpp │ │ │ └── util.hpp │ │ └── mtk/ │ │ ├── build_manifold.hpp │ │ ├── src/ │ │ │ ├── SubManifold.hpp │ │ │ ├── mtkmath.hpp │ │ │ └── vectview.hpp │ │ ├── startIdx.hpp │ │ └── types/ │ │ ├── S2.hpp │ │ ├── SOn.hpp │ │ ├── vect.hpp │ │ └── wrapped_cv_mat.hpp │ ├── common_lib.h │ ├── ikd-Tree/ │ │ ├── ikd_Tree.cpp │ │ └── ikd_Tree.h │ ├── matplotlibcpp.h │ ├── point_type.h │ ├── so3_math.h │ ├── use-ikfom.hpp │ └── voxel_map_util.hpp ├── launch/ │ ├── gdb_debug_example.launch │ ├── mapping_m2dgr.launch │ ├── mapping_ouster64.launch │ ├── mapping_rs.launch │ ├── mapping_velodyne.launch │ └── mapping_viral.launch ├── msg/ │ └── Pose6D.msg ├── package.xml └── src/ ├── IMU_Processing.hpp ├── cloud_process.hpp ├── laserMapping.cpp ├── preprocess.cpp ├── preprocess.h ├── ring_fals/ │ ├── Image_normals.hpp │ ├── precomp.h │ ├── range_image.cpp │ └── range_image.h └── tic_toc.h ================================================ FILE CONTENTS ================================================ ================================================ FILE: CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(log_lio) SET(CMAKE_BUILD_TYPE "Debug") ADD_COMPILE_OPTIONS(-std=c++14 ) ADD_COMPILE_OPTIONS(-std=c++14 ) set( CMAKE_CXX_FLAGS "-std=c++14 -O3" ) add_definitions(-DROOT_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/\") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fexceptions" ) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -pthread -std=c++0x -std=c++14 -fexceptions") message("Current CPU archtecture: ${CMAKE_SYSTEM_PROCESSOR}") if(CMAKE_SYSTEM_PROCESSOR MATCHES "(x86)|(X86)|(amd64)|(AMD64)" ) include(ProcessorCount) ProcessorCount(N) message("Processer number: ${N}") if(N GREATER 4) add_definitions(-DMP_EN) add_definitions(-DMP_PROC_NUM=3) message("core for MP: 3") elseif(N GREATER 3) add_definitions(-DMP_EN) add_definitions(-DMP_PROC_NUM=2) message("core for MP: 2") else() add_definitions(-DMP_PROC_NUM=1) endif() else() add_definitions(-DMP_PROC_NUM=1) endif() find_package(OpenMP QUIET) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") find_package(PythonLibs REQUIRED) find_path(MATPLOTLIB_CPP_INCLUDE_DIRS "matplotlibcpp.h") find_package(catkin REQUIRED COMPONENTS geometry_msgs nav_msgs sensor_msgs roscpp rospy std_msgs pcl_ros tf # livox_ros_driver message_generation eigen_conversions ) find_package(Eigen3 REQUIRED) find_package(PCL 1.7 REQUIRED) ## set OpenCV DIR if ($ENV{ROS_DISTRO} STREQUAL "kinetic") Set(OpenCV_DIR "/home/hk/opencv-3.3.1/build") # important find opencv version else() Set(OpenCV_DIR "/home/autolab/opencv-3.2.0/build") # important find opencv version, Neotic endif () find_package(OpenCV 3.2 QUIET) message(Eigen: ${EIGEN3_INCLUDE_DIR}) include_directories( ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR} ${PCL_INCLUDE_DIRS} ${PYTHON_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS} include ) add_message_files( FILES Pose6D.msg ) generate_messages( DEPENDENCIES geometry_msgs ) catkin_package( CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs message_runtime DEPENDS EIGEN3 PCL INCLUDE_DIRS ) add_executable(loglio_mapping src/laserMapping.cpp include/ikd-Tree/ikd_Tree.cpp src/preprocess.cpp src/ring_fals/range_image.cpp ) target_link_libraries(loglio_mapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES} ${OpenCV_LIBRARIES} ) target_include_directories(loglio_mapping PRIVATE ${PYTHON_INCLUDE_DIRS}) ================================================ FILE: LICENSE ================================================ GNU GENERAL PUBLIC LICENSE Version 2, June 1991 Copyright (C) 1989, 1991 Free Software Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA Everyone is permitted to copy and distribute verbatim copies of this license document, but changing it is not allowed. Preamble The licenses for most software are designed to take away your freedom to share and change it. By contrast, the GNU General Public License is intended to guarantee your freedom to share and change free software--to make sure the software is free for all its users. This General Public License applies to most of the Free Software Foundation's software and to any other program whose authors commit to using it. (Some other Free Software Foundation software is covered by the GNU Lesser General Public License instead.) You can apply it to your programs, too. When we speak of free software, we are referring to freedom, not price. Our General Public Licenses are designed to make sure that you have the freedom to distribute copies of free software (and charge for this service if you wish), that you receive source code or can get it if you want it, that you can change the software or use pieces of it in new free programs; and that you know you can do these things. To protect your rights, we need to make restrictions that forbid anyone to deny you these rights or to ask you to surrender the rights. These restrictions translate to certain responsibilities for you if you distribute copies of the software, or if you modify it. For example, if you distribute copies of such a program, whether gratis or for a fee, you must give the recipients all the rights that you have. You must make sure that they, too, receive or can get the source code. And you must show them these terms so they know their rights. We protect your rights with two steps: (1) copyright the software, and (2) offer you this license which gives you legal permission to copy, distribute and/or modify the software. Also, for each author's protection and ours, we want to make certain that everyone understands that there is no warranty for this free software. If the software is modified by someone else and passed on, we want its recipients to know that what they have is not the original, so that any problems introduced by others will not reflect on the original authors' reputations. Finally, any free program is threatened constantly by software patents. We wish to avoid the danger that redistributors of a free program will individually obtain patent licenses, in effect making the program proprietary. To prevent this, we have made it clear that any patent must be licensed for everyone's free use or not licensed at all. The precise terms and conditions for copying, distribution and modification follow. GNU GENERAL PUBLIC LICENSE TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION 0. This License applies to any program or other work which contains a notice placed by the copyright holder saying it may be distributed under the terms of this General Public License. The "Program", below, refers to any such program or work, and a "work based on the Program" means either the Program or any derivative work under copyright law: that is to say, a work containing the Program or a portion of it, either verbatim or with modifications and/or translated into another language. (Hereinafter, translation is included without limitation in the term "modification".) Each licensee is addressed as "you". Activities other than copying, distribution and modification are not covered by this License; they are outside its scope. The act of running the Program is not restricted, and the output from the Program is covered only if its contents constitute a work based on the Program (independent of having been made by running the Program). Whether that is true depends on what the Program does. 1. You may copy and distribute verbatim copies of the Program's source code as you receive it, in any medium, provided that you conspicuously and appropriately publish on each copy an appropriate copyright notice and disclaimer of warranty; keep intact all the notices that refer to this License and to the absence of any warranty; and give any other recipients of the Program a copy of this License along with the Program. You may charge a fee for the physical act of transferring a copy, and you may at your option offer warranty protection in exchange for a fee. 2. You may modify your copy or copies of the Program or any portion of it, thus forming a work based on the Program, and copy and distribute such modifications or work under the terms of Section 1 above, provided that you also meet all of these conditions: a) You must cause the modified files to carry prominent notices stating that you changed the files and the date of any change. b) You must cause any work that you distribute or publish, that in whole or in part contains or is derived from the Program or any part thereof, to be licensed as a whole at no charge to all third parties under the terms of this License. c) If the modified program normally reads commands interactively when run, you must cause it, when started running for such interactive use in the most ordinary way, to print or display an announcement including an appropriate copyright notice and a notice that there is no warranty (or else, saying that you provide a warranty) and that users may redistribute the program under these conditions, and telling the user how to view a copy of this License. (Exception: if the Program itself is interactive but does not normally print such an announcement, your work based on the Program is not required to print an announcement.) These requirements apply to the modified work as a whole. If identifiable sections of that work are not derived from the Program, and can be reasonably considered independent and separate works in themselves, then this License, and its terms, do not apply to those sections when you distribute them as separate works. But when you distribute the same sections as part of a whole which is a work based on the Program, the distribution of the whole must be on the terms of this License, whose permissions for other licensees extend to the entire whole, and thus to each and every part regardless of who wrote it. Thus, it is not the intent of this section to claim rights or contest your rights to work written entirely by you; rather, the intent is to exercise the right to control the distribution of derivative or collective works based on the Program. In addition, mere aggregation of another work not based on the Program with the Program (or with a work based on the Program) on a volume of a storage or distribution medium does not bring the other work under the scope of this License. 3. You may copy and distribute the Program (or a work based on it, under Section 2) in object code or executable form under the terms of Sections 1 and 2 above provided that you also do one of the following: a) Accompany it with the complete corresponding machine-readable source code, which must be distributed under the terms of Sections 1 and 2 above on a medium customarily used for software interchange; or, b) Accompany it with a written offer, valid for at least three years, to give any third party, for a charge no more than your cost of physically performing source distribution, a complete machine-readable copy of the corresponding source code, to be distributed under the terms of Sections 1 and 2 above on a medium customarily used for software interchange; or, c) Accompany it with the information you received as to the offer to distribute corresponding source code. (This alternative is allowed only for noncommercial distribution and only if you received the program in object code or executable form with such an offer, in accord with Subsection b above.) The source code for a work means the preferred form of the work for making modifications to it. For an executable work, complete source code means all the source code for all modules it contains, plus any associated interface definition files, plus the scripts used to control compilation and installation of the executable. However, as a special exception, the source code distributed need not include anything that is normally distributed (in either source or binary form) with the major components (compiler, kernel, and so on) of the operating system on which the executable runs, unless that component itself accompanies the executable. If distribution of executable or object code is made by offering access to copy from a designated place, then offering equivalent access to copy the source code from the same place counts as distribution of the source code, even though third parties are not compelled to copy the source along with the object code. 4. You may not copy, modify, sublicense, or distribute the Program except as expressly provided under this License. Any attempt otherwise to copy, modify, sublicense or distribute the Program is void, and will automatically terminate your rights under this License. However, parties who have received copies, or rights, from you under this License will not have their licenses terminated so long as such parties remain in full compliance. 5. You are not required to accept this License, since you have not signed it. However, nothing else grants you permission to modify or distribute the Program or its derivative works. These actions are prohibited by law if you do not accept this License. Therefore, by modifying or distributing the Program (or any work based on the Program), you indicate your acceptance of this License to do so, and all its terms and conditions for copying, distributing or modifying the Program or works based on it. 6. Each time you redistribute the Program (or any work based on the Program), the recipient automatically receives a license from the original licensor to copy, distribute or modify the Program subject to these terms and conditions. You may not impose any further restrictions on the recipients' exercise of the rights granted herein. You are not responsible for enforcing compliance by third parties to this License. 7. If, as a consequence of a court judgment or allegation of patent infringement or for any other reason (not limited to patent issues), conditions are imposed on you (whether by court order, agreement or otherwise) that contradict the conditions of this License, they do not excuse you from the conditions of this License. If you cannot distribute so as to satisfy simultaneously your obligations under this License and any other pertinent obligations, then as a consequence you may not distribute the Program at all. For example, if a patent license would not permit royalty-free redistribution of the Program by all those who receive copies directly or indirectly through you, then the only way you could satisfy both it and this License would be to refrain entirely from distribution of the Program. If any portion of this section is held invalid or unenforceable under any particular circumstance, the balance of the section is intended to apply and the section as a whole is intended to apply in other circumstances. It is not the purpose of this section to induce you to infringe any patents or other property right claims or to contest validity of any such claims; this section has the sole purpose of protecting the integrity of the free software distribution system, which is implemented by public license practices. Many people have made generous contributions to the wide range of software distributed through that system in reliance on consistent application of that system; it is up to the author/donor to decide if he or she is willing to distribute software through any other system and a licensee cannot impose that choice. This section is intended to make thoroughly clear what is believed to be a consequence of the rest of this License. 8. If the distribution and/or use of the Program is restricted in certain countries either by patents or by copyrighted interfaces, the original copyright holder who places the Program under this License may add an explicit geographical distribution limitation excluding those countries, so that distribution is permitted only in or among countries not thus excluded. In such case, this License incorporates the limitation as if written in the body of this License. 9. The Free Software Foundation may publish revised and/or new versions of the General Public License from time to time. Such new versions will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. Each version is given a distinguishing version number. If the Program specifies a version number of this License which applies to it and "any later version", you have the option of following the terms and conditions either of that version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of this License, you may choose any version ever published by the Free Software Foundation. 10. If you wish to incorporate parts of the Program into other free programs whose distribution conditions are different, write to the author to ask for permission. For software which is copyrighted by the Free Software Foundation, write to the Free Software Foundation; we sometimes make exceptions for this. Our decision will be guided by the two goals of preserving the free status of all derivatives of our free software and of promoting the sharing and reuse of software generally. NO WARRANTY 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. END OF TERMS AND CONDITIONS How to Apply These Terms to Your New Programs If you develop a new program, and you want it to be of the greatest possible use to the public, the best way to achieve this is to make it free software which everyone can redistribute and change under these terms. To do so, attach the following notices to the program. It is safest to attach them to the start of each source file to most effectively convey the exclusion of warranty; and each file should have at least the "copyright" line and a pointer to where the full notice is found. Copyright (C) This program is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program; if not, write to the Free Software Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. Also add information on how to contact you by electronic and paper mail. If the program is interactive, make it output a short notice like this when it starts in an interactive mode: Gnomovision version 69, Copyright (C) year name of author Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. This is free software, and you are welcome to redistribute it under certain conditions; type `show c' for details. The hypothetical commands `show w' and `show c' should show the appropriate parts of the General Public License. Of course, the commands you use may be called something other than `show w' and `show c'; they could even be mouse-clicks or menu items--whatever suits your program. You should also get your employer (if you work as a programmer) or your school, if any, to sign a "copyright disclaimer" for the program, if necessary. Here is a sample; alter the names: Yoyodyne, Inc., hereby disclaims all copyright interest in the program `Gnomovision' (which makes passes at compilers) written by James Hacker. , 1 April 1989 Ty Coon, President of Vice This General Public License does not permit incorporating your program into proprietary programs. If your program is a subroutine library, you may consider it more useful to permit linking proprietary applications with the library. If this is what you want to do, use the GNU Lesser General Public License instead of this License. ================================================ FILE: Log/dbg.txt ================================================ ================================================ FILE: Log/fast_lio_time_log.csv ================================================ time_stamp, total time, scan point size, incremental time, search time, delete size, delete time, tree size st, tree size end, add point size, preprocess time ================================================ FILE: Log/fast_lio_time_log_analysis.m ================================================ clear close all Color_red = [0.6350 0.0780 0.1840]; Color_blue = [0 0.4470 0.7410]; Color_orange = [0.8500 0.3250 0.0980]; Color_green = [0.4660 0.6740 0.1880]; Color_lightblue = [0.3010 0.7450 0.9330]; Color_purple = [0.4940 0.1840 0.5560]; Color_yellow = [0.9290 0.6940 0.1250]; fast_lio_ikdtree = csvread("./fast_lio_time_log.csv",1,0); timestamp_ikd = fast_lio_ikdtree(:,1); timestamp_ikd = timestamp_ikd - min(timestamp_ikd); total_time_ikd = fast_lio_ikdtree(:,2)*1e3; scan_num = fast_lio_ikdtree(:,3); incremental_time_ikd = fast_lio_ikdtree(:,4)*1e3; search_time_ikd = fast_lio_ikdtree(:,5)*1e3; delete_size_ikd = fast_lio_ikdtree(:,6); delete_time_ikd = fast_lio_ikdtree(:,7) * 1e3; tree_size_ikd_st = fast_lio_ikdtree(:,8); tree_size_ikd = fast_lio_ikdtree(:,9); add_points = fast_lio_ikdtree(:,10); fast_lio_forest = csvread("fast_lio_time_log.csv",1,0); fov_check_time_forest = fast_lio_forest(:,5)*1e3; average_time_forest = fast_lio_forest(:,2)*1e3; total_time_forest = fast_lio_forest(:,6)*1e3; incremental_time_forest = fast_lio_forest(:,3)*1e3; search_time_forest = fast_lio_forest(:,4)*1e3; timestamp_forest = fast_lio_forest(:,1); % Use slide window to calculate average L = 1; % Length of slide window for i = 1:length(timestamp_ikd) if (i 0); search_time_ikd = search_time_ikd(index_ikd); index_forest = find(search_time_forest > 0); search_time_forest = search_time_forest(index_forest); t = nexttile; hold on; boxplot_data_ikd = [incremental_time_ikd,total_time_ikd]; boxplot_data_forest = [incremental_time_forest,total_time_forest]; Colors_ikd = [Color_blue;Color_blue;Color_blue]; Colors_forest = [Color_orange;Color_orange;Color_orange]; % xticks([3,8,13]) h_search_ikd = boxplot(search_time_ikd,'Whisker',50,'Positions',1,'Colors',Color_blue,'Widths',0.3); h_search_forest = boxplot(search_time_forest,'Whisker',50,'Positions',1.5,'Colors',Color_orange,'Widths',0.3); h_ikd = boxplot(boxplot_data_ikd,'Whisker',50,'Positions',[3,5],'Colors',Color_blue,'Widths',0.3); h_forest = boxplot(boxplot_data_forest,'Whisker',50,'Positions',[3.5,5.5],'Colors',Color_orange,'Widths',0.3); ax2 = gca; ax2.YAxis.Scale = 'log'; xlim([0.5,6.0]) ylim([0.0008,100]) xticks([1.25 3.25 5.25]) xticklabels({'Nearest Search',' Incremental Updates','Total Time'}); yticks([1e-3,1e-2,1e-1,1e0,1e1,1e2]) ax2.YAxis.FontSize = 12; ax2.XAxis.FontSize = 14.5; % ax.XAxis.FontWeight = 'bold'; ylabel('Run Time/ms','FontSize',14,'FontName','Times New Roman') box_vars = [findall(h_search_ikd,'Tag','Box');findall(h_ikd,'Tag','Box');findall(h_search_forest,'Tag','Box');findall(h_forest,'Tag','Box')]; for j=1:length(box_vars) if (j<=3) Color = Color_blue; else Color = Color_orange; end patch(get(box_vars(j),'XData'),get(box_vars(j),'YData'),Color,'FaceAlpha',0.25,'EdgeColor',Color); end Lg = legend(box_vars([1,4]), {'ikd-Tree','ikd-Forest'},'Location',[0.6707 0.4305 0.265 0.07891],'fontsize',14,'fontname','Times New Roman'); grid on set(gca,'YMinorGrid','off') nexttile; hold on; grid on; box on; set(gca,'FontSize',12,'FontName','Times New Roman') plot(timestamp_ikd, alpha_bal_ikd,'-','Color',Color_blue,'LineWidth',1.2); plot(timestamp_ikd, alpha_del_ikd,'--','Color',Color_orange, 'LineWidth', 1.2); plot(timestamp_ikd, 0.6*ones(size(alpha_bal_ikd)), ':','Color','black','LineWidth',1.2); lg = legend("\alpha_{bal}", "\alpha_{del}",'location',[0.7871 0.1131 0.1433 0.069],'fontsize',14,'fontname','Times New Roman') title("Re-balancing Criterion",'FontSize',16,'FontName','Times New Roman') xlabel("time/s",'FontSize',16,'FontName','Times New Roman') yl = ylabel("\alpha",'FontSize',15, 'Position',[285.7 0.4250 -1]) xlim([32,390]); ylim([0,0.85]); ax3 = gca; ax3.YAxis.FontSize = 12; ax3.XAxis.FontSize = 12; % print('./Figures/fastlio_exp_combine','-depsc','-r1200') % exportgraphics(f,'./Figures/fastlio_exp_combine_1.pdf','ContentType','vector') ================================================ FILE: Log/guide.md ================================================ Here saved the debug records which can be drew by the ../Log/plot.py. The record function can be found frm the MACRO: DEBUG_FILE_DIR(name) in common_lib.h. ================================================ FILE: Log/imu.txt ================================================ ================================================ FILE: Log/mat_out.txt ================================================ ================================================ FILE: Log/mat_pre.txt ================================================ ================================================ FILE: Log/plot.py ================================================ # import matplotlib # matplotlib.use('Agg') import numpy as np import matplotlib.pyplot as plt #######for ikfom fig, axs = plt.subplots(4,2) lab_pre = ['', 'pre-x', 'pre-y', 'pre-z'] lab_out = ['', 'out-x', 'out-y', 'out-z'] plot_ind = range(7,10) a_pre=np.loadtxt('mat_pre.txt') a_out=np.loadtxt('mat_out.txt') time=a_pre[:,0] axs[0,0].set_title('Attitude') axs[1,0].set_title('Translation') axs[2,0].set_title('Extrins-R') axs[3,0].set_title('Extrins-T') axs[0,1].set_title('Velocity') axs[1,1].set_title('bg') axs[2,1].set_title('ba') axs[3,1].set_title('Gravity') for i in range(1,4): for j in range(8): axs[j%4, j/4].plot(time, a_pre[:,i+j*3],'.-', label=lab_pre[i]) axs[j%4, j/4].plot(time, a_out[:,i+j*3],'.-', label=lab_out[i]) for j in range(8): # axs[j].set_xlim(386,389) axs[j%4, j/4].grid() axs[j%4, j/4].legend() plt.grid() #######for ikfom####### #### Draw IMU data # fig, axs = plt.subplots(2) # imu=np.loadtxt('imu.txt') # time=imu[:,0] # axs[0].set_title('Gyroscope') # axs[1].set_title('Accelerameter') # lab_1 = ['gyr-x', 'gyr-y', 'gyr-z'] # lab_2 = ['acc-x', 'acc-y', 'acc-z'] # for i in range(3): # # if i==1: # axs[0].plot(time, imu[:,i+1],'.-', label=lab_1[i]) # axs[1].plot(time, imu[:,i+4],'.-', label=lab_2[i]) # for i in range(2): # # axs[i].set_xlim(386,389) # axs[i].grid() # axs[i].legend() # plt.grid() # #### Draw time calculation # plt.figure(3) # fig = plt.figure() # font1 = {'family' : 'Times New Roman', # 'weight' : 'normal', # 'size' : 12, # } # c="red" # a_out1=np.loadtxt('Log/mat_out_time_indoor1.txt') # a_out2=np.loadtxt('Log/mat_out_time_indoor2.txt') # a_out3=np.loadtxt('Log/mat_out_time_outdoor.txt') # # n = a_out[:,1].size # # time_mean = a_out[:,1].mean() # # time_se = a_out[:,1].std() / np.sqrt(n) # # time_err = a_out[:,1] - time_mean # # feat_mean = a_out[:,2].mean() # # feat_err = a_out[:,2] - feat_mean # # feat_se = a_out[:,2].std() / np.sqrt(n) # ax1 = fig.add_subplot(111) # ax1.set_ylabel('Effective Feature Numbers',font1) # ax1.boxplot(a_out1[:,2], showfliers=False, positions=[0.9]) # ax1.boxplot(a_out2[:,2], showfliers=False, positions=[1.9]) # ax1.boxplot(a_out3[:,2], showfliers=False, positions=[2.9]) # ax1.set_ylim([0, 3000]) # ax2 = ax1.twinx() # ax2.spines['right'].set_color('red') # ax2.set_ylabel('Compute Time (ms)',font1) # ax2.yaxis.label.set_color('red') # ax2.tick_params(axis='y', colors='red') # ax2.boxplot(a_out1[:,1]*1000, showfliers=False, positions=[1.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) # ax2.boxplot(a_out2[:,1]*1000, showfliers=False, positions=[2.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) # ax2.boxplot(a_out3[:,1]*1000, showfliers=False, positions=[3.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) # ax2.set_xlim([0.5, 3.5]) # ax2.set_ylim([0, 100]) # plt.xticks([1,2,3], ('Outdoor Scene', 'Indoor Scene 1', 'Indoor Scene 2')) # # # print(time_se) # # # print(a_out3[:,2]) # plt.grid() # plt.savefig("time.pdf", dpi=1200) plt.show() ================================================ FILE: Log/pos_log.txt ================================================ ================================================ FILE: README.md ================================================ # LOG-LIO ---------------------------- Our recent work [LOG-LIO2](https://github.com/tiev-tongji/LOG-LIO2) is now available! The trajectory file will be saved in **TUM** format in the file named "/Log/target_path.txt". And a more detailed readme is coming soon! **Related video:** [Ring FALS](https://youtu.be/cxTLywI7X7M). ## 1. Prerequisites ### 1.1 **Ubuntu** and **ROS** **Ubuntu >= 16.04** For **Ubuntu 18.04 or higher**, the **default** PCL and Eigen is enough for FAST-LIO to work normally. [//]: # () [//]: # (ROS >= Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation)) ### 1.2 Ring FALS Normal Estimator Compile follow [Ring FALS normal estimator](https://github.com/tiev-tongji/RingFalsNormal). ## 2. Build Clone the repository and catkin_make: ``` cd ~/$A_ROS_DIR$/src git clone https://github.com/tiev-tongji/LOG-LIO.git cd .. catkin_make source devel/setup.bash ``` ## 3. run We conduct experiments on the [M2DGR](https://github.com/SJTU-ViSYS/M2DGR) and [NTU VIRAL](https://github.com/ntu-aris/ntu_viral_dataset) datasets. The corresponding launch and yaml file is provided. Note that the timestamp in the NTU VARIL dataset is the **_end time_**. ``` cd ~/$LOG_LIO_ROS_DIR$ source devel/setup.bash # for the M2DGR dataset roslaunch log_lio mapping_m2dgr.launch # for the NTU VIRAL dataset roslaunch log_lio mapping_viral.launch ``` ## 4. Acknowledgments Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), [Fast-LIO2](https://github.com/hku-mars/FAST_LIO), [ikd-Tree](https://github.com/hku-mars/ikd-Tree) and [VoxelMap](https://github.com/hku-mars/VoxelMap). ## Citation ``` @article{huang2023log, title={LOG-LIO: A LiDAR-Inertial Odometry with Efficient Local Geometric Information Estimation}, author={Huang, Kai and Zhao, Junqiao and Zhu, Zhongyang and Ye, Chen and Feng, Tiantian}, journal={IEEE Robotics and Automation Letters}, volume={9}, number={1}, pages={459--466}, year={2023}, publisher={IEEE} } ``` ================================================ FILE: config/m2dgr/ring32_M_0.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -53277544. -31713004. 5.89056969e+01 5.42770386e+01 4.67164383e+01 5.01008072e+01 5.54935913e+01 6.51706238e+01 7.08822403e+01 7.78253174e+01 8.39664154e+01 8.92136612e+01 1.00354286e+02 1.12935059e+02 1.18434074e+02 1.26564240e+02 1.39150131e+02 1.50813736e+02 1.62278183e+02 1.68102417e+02 1.73886688e+02 1.89103653e+02 2.06883575e+02 2.21666458e+02 2.32775146e+02 2.40424942e+02 2.53722153e+02 2.76058472e+02 2.97179718e+02 3.01698151e+02 3.03454193e+02 3.23766174e+02 3.49979614e+02 3.63273193e+02 3.78258087e+02 3.97399353e+02 4.02803711e+02 4.27065826e+02 4.56071838e+02 4.55266937e+02 4.71605865e+02 5.05957245e+02 5.44924377e+02 5.69078613e+02 5.49952087e+02 5.49943176e+02 5.87676147e+02 6.34716919e+02 6.63465881e+02 6.59374817e+02 6.79587646e+02 7.24101562e+02 7.38430420e+02 7.61298645e+02 7.74208557e+02 7.70576782e+02 8.21622375e+02 8.76109924e+02 8.73345398e+02 8.93360107e+02 9.35883301e+02 9.43412170e+02 9.87210999e+02 1.02559827e+03 1.01218182e+03 1.02996179e+03 1.08082092e+03 1.14609546e+03 1.16486047e+03 1.15373120e+03 1.18936938e+03 1.21164197e+03 1.25237573e+03 1.31141028e+03 1.29416882e+03 1.31440222e+03 1.38628516e+03 1.43546094e+03 1.47148547e+03 1.46545105e+03 1.43968066e+03 1.48988696e+03 1.57037793e+03 1.63096521e+03 1.66118286e+03 1.66169556e+03 1.67111597e+03 1.74666711e+03 1.81222766e+03 1.78512463e+03 1.76898987e+03 1.83548303e+03 1.93606616e+03 1.98797986e+03 1.99698999e+03 1.98185449e+03 1.98083301e+03 2.08465137e+03 2.17268140e+03 2.12582202e+03 2.16361475e+03 2.26681860e+03 2.34517944e+03 2.37610571e+03 2.30455103e+03 2.27718140e+03 2.39215308e+03 2.48887451e+03 2.51914893e+03 2.54085449e+03 2.58890454e+03 2.66876807e+03 2.65525488e+03 2.68188159e+03 2.78249707e+03 2.75217651e+03 2.77364282e+03 2.88646558e+03 2.95631543e+03 3.00291919e+03 2.99101001e+03 2.94894922e+03 3.01513745e+03 3.13557642e+03 3.23605298e+03 3.24404468e+03 3.26517041e+03 3.55252124e+03 4.65722705e+03 5.26700732e+03 1.63385812e+06 -1.89803188e+06 -2.68424475e+06 4023138. 5.07077100e+03 4.96513623e+03 4319. 4.13366748e+03 3.99687061e+03 5.21072656e+03 5.77067041e+03 -13004994. 57971428. -1706275. -28101918. -1314003. 1.74120525e+06 -5.15597450e+06 3.45788975e+06 1.61959412e+06 -1.98462338e+06 6.05256738e+03 5.78707812e+03 4.99238965e+03 5.00352930e+03 4.70965576e+03 4.48341064e+03 4.50895947e+03 4.88228467e+03 5.02618604e+03 4.86697363e+03 4.73880176e+03 4.88002148e+03 5.10397900e+03 5.13486475e+03 4.94588477e+03 5.00601367e+03 5.22787256e+03 5.29792676e+03 5.32355322e+03 5.42532959e+03 5.48539014e+03 5.31171729e+03 5.49511572e+03 5.70652979e+03 5.49336426e+03 5.52548926e+03 5.73377441e+03 5.82857715e+03 5.92081934e+03 5.86045752e+03 5.69475293e+03 5.80240771e+03 6.02679248e+03 6.31029883e+03 6.34040088e+03 6.03384521e+03 6.12097852e+03 6.49203809e+03 6.40661133e+03 6.17629688e+03 6.26207715e+03 6.49912305e+03 6.64737207e+03 6.77736328e+03 6.80067285e+03 6.65865869e+03 6.53415869e+03 6.79961279e+03 7.01419580e+03 6.84322900e+03 6.87653369e+03 7.09897412e+03 7.25872607e+03 7.29702832e+03 7.15571875e+03 7.00892480e+03 7.14124219e+03 7.37274854e+03 7.64601855e+03 7.66454297e+03 7.32886328e+03 7.41497363e+03 7.65632910e+03 7.75110156e+03 7.74341064e+03 7.63605664e+03 7.68122852e+03 7.96868213e+03 8.13891064e+03 8.09463086e+03 7.95121777e+03 7.88836670e+03 8.14077832e+03 8.34193652e+03 8.18202295e+03 8.29155078e+03 8.50136914e+03 8.51651465e+03 8.73081445e+03 8.46443164e+03 8.30994043e+03 8.58281738e+03 8.67819922e+03 8.86538867e+03 8.66939746e+03 8.51044727e+03 8.93287988e+03 9.25651953e+03 9.15952832e+03 8.97936230e+03 9.12506641e+03 9.01290625e+03 9.05511426e+03 9.34099316e+03 9.67981348e+03 9.43687695e+03 9.24678418e+03 9.59651562e+03 9.48901172e+03 9.61925684e+03 9.67798535e+03 9.40893555e+03 9.74977832e+03 1.00020918e+04 9.71290625e+03 9.57907715e+03 9.85064355e+03 1.02692529e+04 1.03848076e+04 9.89864062e+03 9.87084766e+03 1.01824795e+04 1.03733574e+04 1.05547373e+04 1.02927041e+04 1.02976270e+04 1.02718379e+04 1.03552178e+04 1.08494473e+04 1.07297188e+04 1.03261768e+04 1.06131689e+04 1.10741846e+04 1.07234805e+04 1.06987080e+04 1.06316855e+04 1.06315957e+04 1.11677666e+04 1.14045869e+04 1.10402666e+04 1.09197715e+04 1.10973506e+04 1.13628848e+04 1.15607520e+04 1.12655352e+04 1.14773330e+04 1.16015371e+04 1.11379932e+04 1.13046094e+04 1.14756904e+04 1.15496973e+04 1.17842705e+04 1.17385527e+04 1.17247598e+04 1.20081602e+04 1.18078594e+04 1.16183359e+04 1.19129609e+04 1.21841152e+04 1.21794863e+04 1.17866455e+04 1.18168701e+04 1.23744434e+04 1.25771123e+04 1.20908740e+04 1.19509609e+04 1.21581240e+04 1.25465234e+04 1.27426982e+04 1.23439014e+04 1.23584492e+04 1.23315576e+04 1.26093643e+04 1.29035439e+04 1.25341611e+04 1.25820508e+04 1.27027510e+04 1.26868877e+04 1.29094590e+04 1.32034912e+04 1.29015547e+04 1.25609336e+04 1.31801924e+04 1.36489072e+04 1.29514453e+04 1.25133438e+04 1.29596182e+04 1.33026211e+04 1.33100010e+04 1.31219395e+04 1.30299355e+04 1.31922891e+04 1.35587471e+04 1.36967959e+04 1.33620098e+04 1.33425410e+04 1.33772246e+04 1.37497588e+04 1.37604414e+04 1.33702451e+04 1.35552510e+04 1.35843672e+04 1.35453027e+04 1.38510996e+04 1.39256211e+04 1.36443398e+04 1.36448496e+04 1.40079902e+04 1.40540918e+04 1.37409902e+04 1.37056426e+04 1.39009316e+04 1.42254209e+04 1.41916738e+04 1.37408721e+04 1.38232656e+04 1.41045811e+04 1.45140840e+04 1.46186602e+04 1.41500742e+04 1.44594062e+04 1.43133047e+04 1.37708115e+04 1.40093926e+04 1.42674268e+04 1.47326719e+04 1.46785059e+04 1.40268027e+04 1.39415762e+04 1.44246055e+04 1.49237686e+04 1.48612256e+04 1.45942812e+04 1.45332588e+04 1.44254277e+04 1.43215332e+04 1.43195117e+04 1.47728164e+04 1.50239385e+04 1.45708477e+04 1.45530010e+04 1.46151543e+04 1.48027812e+04 1.49923359e+04 1.49221855e+04 1.52465938e+04 1.48207490e+04 1.42453438e+04 1.44755029e+04 1.49427471e+04 1.53276953e+04 1.55001992e+04 1.50062314e+04 1.42476387e+04 1.45726865e+04 1.50853496e+04 1.49967461e+04 1.53823574e+04 1.52732139e+04 1.46938428e+04 1.51574756e+04 1.53334795e+04 1.49906611e+04 1.51582100e+04 1.49957461e+04 1.48230371e+04 1.48767627e+04 1.49744912e+04 1.51395234e+04 1.55862891e+04 1.59906719e+04 1.52661445e+04 1.46182656e+04 1.47654990e+04 1.51562383e+04 1.56664336e+04 1.55812432e+04 1.48815918e+04 1.47312881e+04 1.51871016e+04 1.56710664e+04 1.57361650e+04 1.53070537e+04 1.52419385e+04 1.52279678e+04 1.50728945e+04 1.50352461e+04 1.54139443e+04 1.56144590e+04 1.53966328e+04 1.55520186e+04 1.50909863e+04 1.50146006e+04 1.55053057e+04 1.55245977e+04 1.57509697e+04 1.53015703e+04 1.47702012e+04 1.49891338e+04 1.54021855e+04 1.57462256e+04 1.58964404e+04 1.53809863e+04 1.47200703e+04 1.50208672e+04 1.52624590e+04 1.50609404e+04 1.54643164e+04 1.57459658e+04 1.51691846e+04 1.50005791e+04 1.51870742e+04 1.54702842e+04 1.56517295e+04 1.54042461e+04 1.53818477e+04 1.49069609e+04 1.48151250e+04 1.52814883e+04 1.53687627e+04 1.55798125e+04 1.55602197e+04 1.50776650e+04 1.47409258e+04 1.51048457e+04 1.56190977e+04 1.54594629e+04 1.51933047e+04 1.51500205e+04 1.48659014e+04 1.49935596e+04 1.52974092e+04 1.51807549e+04 1.52152578e+04 1.50453252e+04 1.48241250e+04 1.48171523e+04 1.52219346e+04 1.53038359e+04 1.50775615e+04 1.51679248e+04 1.47360488e+04 1.48948203e+04 1.51408633e+04 1.49540742e+04 1.53252520e+04 1.49834229e+04 1.44448193e+04 1.45759033e+04 1.46015596e+04 1.49340439e+04 1.55538945e+04 1.51944316e+04 1.45159043e+04 1.44150928e+04 1.44354365e+04 1.44143311e+04 1.48359590e+04 1.50254424e+04 1.45103760e+04 1.43865186e+04 1.44022246e+04 1.46729551e+04 1.49116660e+04 1.46801680e+04 1.50321875e+04 1.46399512e+04 1.37726885e+04 1.40017998e+04 1.45112920e+04 1.47282676e+04 1.48621973e+04 1.42982246e+04 1.35822705e+04 1.40245498e+04 1.47186475e+04 1.44884551e+04 1.42362246e+04 1.40750596e+04 1.38548584e+04 1.41132451e+04 1.41748008e+04 1.39485947e+04 1.43144727e+04 1.40989697e+04 1.38872109e+04 1.39471729e+04 1.36002930e+04 1.37070312e+04 1.39590996e+04 1.43213809e+04 1.39232158e+04 1.31606699e+04 1.33293750e+04 1.37212197e+04 1.39431602e+04 1.38631719e+04 1.33990693e+04 1.31339551e+04 1.34059023e+04 1.36600518e+04 1.37389414e+04 1.35947363e+04 1.34165244e+04 1.32462207e+04 1.32804111e+04 1.32365049e+04 1.31485830e+04 1.32795967e+04 1.32527861e+04 1.33139658e+04 1.28624756e+04 1.28380273e+04 1.31923193e+04 1.30386475e+04 1.32730869e+04 1.30190117e+04 1.24132910e+04 1.24421084e+04 1.26896934e+04 1.30585010e+04 1.32689102e+04 1.27094561e+04 1.22450576e+04 1.23602617e+04 1.25287871e+04 1.25375332e+04 1.25416699e+04 1.25383193e+04 1.22166826e+04 1.20123145e+04 1.21752002e+04 1.23437773e+04 1.24598486e+04 1.22938896e+04 1.22595967e+04 1.19617529e+04 1.15495361e+04 1.17503428e+04 1.19160391e+04 1.21665801e+04 1.21286426e+04 1.14435420e+04 1.12868857e+04 1.16305254e+04 1.20457744e+04 1.18400547e+04 1.15919209e+04 1.14971348e+04 1.11378672e+04 1.13489648e+04 1.16239287e+04 1.13664541e+04 1.12586250e+04 1.11517705e+04 1.11781543e+04 1.11669102e+04 1.10582188e+04 1.10705791e+04 1.10587227e+04 1.09754248e+04 1.06851436e+04 1.07494717e+04 1.08790732e+04 1.07481201e+04 1.10856992e+04 1.07199902e+04 1.02819521e+04 1.04000547e+04 1.02347793e+04 1.05341484e+04 1.09559219e+04 1.06129180e+04 9.98844629e+03 9.83915820e+03 1.01742432e+04 1.02212910e+04 1.04432969e+04 1.00967061e+04 1.13974111e+04 1.08962188e+04 1.88135430e+04 3.14941367e+04 3491344. 50722428. 1.86595375e+06 1.58151288e+06 -510279296. 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. 0. 0. 0. 0. 0. 0. 0. 377009568. 7.99991016e+04 1.38523262e+04 9.00598145e+03 7.85230566e+03 7.32541309e+03 7.51477686e+03 7.42843018e+03 7.33790137e+03 6.94588184e+03 7.03282422e+03 7.39780664e+03 7.30309033e+03 6.90306396e+03 6.61188037e+03 6.64426562e+03 6.93252441e+03 7.11760352e+03 6.81226953e+03 6.50678711e+03 6.43357080e+03 6.41518018e+03 6.64937451e+03 6.65581641e+03 6.36479150e+03 6.19793066e+03 6.14214160e+03 6.20345752e+03 6.20431982e+03 6.05800586e+03 6.00773535e+03 6.18579688e+03 6.24973242e+03 5.89743262e+03 5.56073340e+03 5.63648096e+03 5.89065186e+03 6.04124902e+03 5.71779639e+03 5.37042334e+03 5.37097705e+03 5.56914502e+03 5.75255566e+03 5.51011621e+03 5.10998779e+03 5.10838281e+03 5.26174414e+03 5.33355811e+03 5.29912402e+03 5.16459033e+03 4.94256543e+03 4.89233936e+03 5.02521631e+03 4.81205078e+03 4.69368018e+03 4.88639355e+03 4.88677539e+03 4.77978320e+03 4.57033643e+03 4.34276172e+03 4.53129883e+03 4.78593896e+03 4.62255566e+03 4.29406934e+03 4.08930103e+03 4.13062939e+03 4.33900732e+03 4.45545361e+03 4.26963135e+03 4.12337500e+03 4.01006299e+03 3.85194897e+03 3.94074609e+03 4.03917041e+03 3.85997046e+03 3.78483594e+03 3.77504272e+03 3.76245410e+03 3.66244067e+03 3.58134668e+03 3.64544287e+03 3.62107568e+03 3.59207886e+03 3.46551489e+03 3.27591895e+03 3.24713281e+03 3.38530054e+03 3.48900659e+03 3.29511035e+03 3.05269092e+03 3.05621997e+03 3.11292603e+03 3.15060669e+03 3.13372729e+03 2.98006543e+03 2.91126367e+03 2.86495581e+03 2.86321582e+03 2.87620312e+03 2.77940771e+03 2.71890308e+03 2.66281958e+03 2.65379419e+03 2.63158374e+03 2.56233691e+03 2.54734229e+03 2.52512061e+03 2.52382739e+03 2.41778394e+03 2.27459009e+03 2.28145508e+03 2.37006177e+03 2.37947534e+03 2.22663916e+03 2.08122632e+03 2.05965308e+03 2.14525122e+03 2.21555713e+03 2.07608447e+03 1.94472620e+03 1.94671741e+03 1.90647241e+03 1.88290613e+03 1.87460339e+03 1.81849756e+03 1.81678760e+03 1.75953430e+03 1.71661389e+03 1.69560840e+03 1.62277112e+03 1.62000818e+03 1.65017615e+03 1.61686206e+03 1.52531445e+03 1.44064050e+03 1.41675549e+03 1.44750818e+03 1.47661328e+03 1.38631531e+03 1.28076392e+03 1.27290942e+03 1.30739783e+03 1.31389673e+03 1.23428772e+03 1.17197705e+03 1.15470728e+03 1.12328760e+03 1.11926343e+03 1.10107605e+03 1.02820898e+03 1.00039984e+03 1.01045203e+03 9.97364685e+02 9.58757202e+02 9.14082642e+02 8.91679382e+02 8.78841675e+02 8.78432190e+02 8.36044250e+02 7.68351685e+02 7.56888184e+02 7.53725769e+02 7.42437866e+02 7.20011475e+02 6.73551758e+02 6.49105591e+02 6.39122925e+02 6.31037598e+02 6.09958191e+02 5.75293152e+02 5.62044189e+02 5.40910828e+02 5.21579956e+02 5.01554840e+02 4.70741547e+02 4.61715149e+02 4.59536987e+02 4.44490509e+02 4.10166016e+02 3.77037689e+02 3.64258820e+02 3.65409241e+02 3.63208191e+02 3.32759216e+02 3.00358276e+02 2.89497284e+02 2.83696930e+02 2.75962677e+02 2.62280151e+02 2.38604721e+02 2.23616058e+02 2.15224731e+02 2.05202927e+02 1.93701447e+02 1.80493484e+02 1.70030380e+02 1.56547974e+02 1.47230255e+02 1.38433014e+02 1.27313637e+02 1.18636795e+02 1.09733902e+02 1.01367889e+02 8.96927261e+01 8.03655930e+01 7.59073868e+01 7.12231369e+01 6.47012253e+01 5.56207008e+01 4.73059654e+01 4.20062485e+01 3.88632812e+01 3.54288521e+01 2.97123184e+01 2.43325653e+01 2.00219975e+01 1.64181690e+01 1.38165913e+01 1.13873472e+01 8.82421017e+00 6.67844105e+00 4.98846197e+00 3.70077014e+00 2.76494503e+00 2.22535372e+00 2.04080439e+00 2.23410106e+00 2.83139873e+00 3.80830812e+00 4.98790932e+00 6.68707657e+00 8.89749908e+00 1.13124952e+01 1.42379551e+01 1.73564358e+01 2.12479305e+01 2.53776016e+01 2.85466633e+01 3.21674500e+01 3.77691498e+01 4.52592735e+01 5.26366196e+01 5.80033684e+01 6.12291031e+01 6.63507919e+01 7.50073395e+01 8.61491547e+01 9.67698975e+01 1.03640900e+02 1.07258575e+02 1.15536377e+02 1.31671371e+02 1.42041946e+02 1.45418777e+02 1.55458786e+02 1.69871521e+02 1.81108932e+02 1.98228485e+02 2.05633575e+02 2.11453003e+02 2.29765961e+02 2.36586426e+02 2.56366791e+02 2.79183746e+02 2.78789062e+02 2.97535583e+02 3.23470673e+02 3.30966797e+02 3.44931366e+02 3.60295410e+02 3.78151459e+02 3.99899048e+02 4.11595428e+02 4.15328461e+02 4.36636871e+02 4.76611359e+02 5.05721222e+02 5.12360657e+02 5.11115997e+02 5.18525452e+02 5.48047546e+02 5.94557495e+02 6.31424622e+02 6.40026123e+02 6.27028015e+02 6.47265320e+02 6.95008423e+02 7.14605042e+02 7.26946960e+02 7.49359192e+02 7.75090393e+02 7.98078857e+02 8.53787659e+02 8.59357117e+02 8.49381531e+02 8.91727051e+02 8.96383484e+02 9.56426575e+02 1.00703076e+03 1.00003253e+03 1.06285400e+03 1.06458838e+03 1.04685242e+03 1.10722839e+03 1.11400366e+03 1.16411499e+03 1.26983850e+03 1.23371411e+03 1.19639343e+03 1.25222485e+03 1.33257092e+03 1.41008960e+03 1.41940942e+03 1.37445996e+03 1.35454297e+03 1.41845630e+03 1.54010278e+03 1.61883215e+03 1.61688684e+03 1.56299414e+03 1.57693127e+03 1.67781262e+03 1.74029346e+03 1.71362378e+03 1.72274695e+03 1.79039026e+03 1.83062012e+03 1.91314062e+03 1.94335059e+03 1.90613452e+03 1.95831848e+03 1.98205579e+03 2.01589258e+03 2.09768726e+03 2.12174707e+03 2.20581860e+03 2.20086841e+03 2.15549976e+03 2.25231909e+03 2.24026611e+03 2.32984521e+03 2.53617212e+03 2.44930786e+03 2.32155737e+03 2.40492505e+03 2.57467261e+03 2.68891260e+03 2.74659839e+03 2.65105225e+03 2.56551123e+03 2.64476367e+03 2.82930005e+03 3.00846436e+03 2.94978613e+03 2.81429883e+03 2.83244507e+03 2.96022412e+03 3.08346167e+03 3.21642261e+03 3.23351294e+03 3.08562646e+03 3.08761646e+03 3.26780542e+03 3.35960767e+03 3.36678589e+03 3.38466968e+03 3.37986157e+03 3.39159692e+03 3.59667676e+03 3.66966602e+03 3.53095508e+03 3.55562036e+03 3.70098950e+03 3.75141040e+03 3.79952734e+03 3.80889746e+03 3.93809326e+03 4.00705298e+03 3.93258154e+03 3.95846362e+03 3.94294824e+03 4.12737891e+03 4.36029150e+03 4.34717529e+03 4.17737012e+03 4.10806104e+03 4.31940381e+03 4.60646484e+03 4.48366309e+03 4.30619043e+03 4.44020020e+03 4.60720117e+03 4.75826514e+03 4.94245264e+03 4.91055615e+03 4.67906104e+03 4.58836328e+03 4.81582422e+03 5.09495703e+03 5126. 5.02828467e+03 5.06956738e+03 5.13129492e+03 5.27206445e+03 5.24431494e+03 5.17331885e+03 5.26868457e+03 5.29048828e+03 5.52866699e+03 5.72629980e+03 5.56561035e+03 5.60099072e+03 5.66548828e+03 5.86267920e+03 5.78401514e+03 5.53178125e+03 5.82642041e+03 6.20934033e+03 6.04047070e+03 5.77774707e+03 5.98557715e+03 6.36662646e+03 6.34785840e+03 6.26036572e+03 6.34223877e+03 6.19497510e+03 6.20422607e+03 6.60320312e+03 6.72936035e+03 6.50468896e+03 6.36736914e+03 6.34126709e+03 6.73119092e+03 7.12803516e+03 6.87279443e+03 6.71761670e+03 6.92024414e+03 6.96968604e+03 7.23749902e+03 7.33576318e+03 6.95624463e+03 6.94762500e+03 7.17415918e+03 7.27994092e+03 7.38767285e+03 7.44899512e+03 7.66509668e+03 7.66885059e+03 7.39127881e+03 7.43513135e+03 7.37798340e+03 7.74081934e+03 8.25400098e+03 8.07889941e+03 7.67804541e+03 7.66549219e+03 7.97922754e+03 8.55865918e+03 9.16716797e+03 1.01117949e+04 8.93730371e+03 1.68441152e+04 1.18033516e+05 -65294976. 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. 0. 0. 0. 0. 0. 0. -10844378. 6.60784609e+04 1.45811904e+04 1.18812402e+04 1.05591104e+04 1.04639307e+04 1.07266768e+04 1.06153779e+04 1.03377305e+04 1.03616797e+04 1.08656533e+04 1.10181289e+04 1.07686123e+04 1.09234238e+04 1.10033301e+04 1.09285957e+04 1.10289912e+04 1.10397949e+04 1.10739053e+04 1.11532715e+04 1.11805273e+04 1.12075430e+04 1.10351436e+04 1.09753262e+04 1.16297617e+04 1.17243613e+04 1.11918438e+04 1.11715166e+04 1.18391426e+04 1.19824570e+04 1.16860664e+04 1.17438848e+04 1.17380127e+04 1.17622246e+04 1.18200166e+04 1.18280244e+04 1.18963359e+04 1.18980146e+04 1.16794824e+04 1.16810938e+04 1.23716436e+04 1.24739727e+04 1.21834961e+04 1.21847158e+04 1.22534609e+04 1.23337832e+04 1.23223193e+04 1.23217939e+04 1.24652588e+04 1.21545020e+04 1.20673809e+04 1.25598848e+04 1.26181934e+04 1.30123115e+04 1.31385791e+04 1.27146924e+04 1.23958877e+04 1.23698008e+04 1.32091680e+04 1.33813213e+04 1.28880947e+04 1.27853438e+04 1.29094307e+04 1.30371797e+04 1.29375059e+04 1.33384883e+04 1.33532441e+04 1.27369873e+04 1.27012285e+04 1.34430186e+04 1.37956934e+04 1.34748242e+04 1.33543936e+04 1.33997109e+04 1.33992451e+04 1.32517998e+04 1.33026299e+04 1.36481934e+04 1.36646455e+04 1.34067139e+04 1.34776768e+04 1.37086191e+04 1.36809756e+04 1.40393115e+04 1.40121367e+04 1.36201826e+04 1.38631338e+04 1.38769912e+04 1.40009531e+04 1.41714355e+04 1.39796221e+04 1.39711562e+04 1.37550010e+04 1.36080547e+04 1.42135039e+04 1.42235537e+04 1.35816689e+04 1.38080635e+04 1.45946592e+04 1.51376377e+04 1.46572314e+04 1.42744521e+04 1.40838184e+04 1.40409150e+04 1.42349658e+04 1.42663643e+04 1.44807393e+04 1.44367061e+04 1.46982520e+04 1.46449980e+04 1.43085244e+04 1.46580908e+04 1.42437598e+04 1.42430049e+04 1.51288291e+04 1.50344658e+04 1.46801104e+04 1.43303369e+04 1.42392715e+04 1.50739258e+04 1.51698281e+04 1.47229619e+04 1.43770371e+04 1.43941348e+04 1.48180771e+04 1.48208398e+04 1.52455527e+04 1.53583887e+04 1.49085449e+04 1.47852803e+04 1.48230986e+04 1.51146465e+04 1.51386201e+04 1.49437666e+04 1.47524512e+04 1.47975752e+04 1.50809346e+04 1.46799648e+04 1.47020322e+04 1.55663506e+04 1.55287520e+04 1.51278418e+04 1.46810791e+04 1.46827891e+04 1.56006680e+04 1.55898066e+04 1.51896670e+04 1.48045859e+04 1.47052109e+04 1.52418125e+04 1.51928799e+04 1.51666611e+04 1.48930176e+04 1.51642002e+04 1.59121104e+04 1.55371484e+04 1.53479570e+04 1.54051035e+04 1.53463799e+04 1.51469014e+04 1.50741406e+04 1.52991523e+04 1.53598252e+04 1.54300078e+04 1.48973818e+04 1.49197393e+04 1.59613457e+04 1.53870146e+04 1.48141572e+04 1.52618525e+04 1.52668008e+04 1.58015586e+04 1.54899805e+04 1.48471914e+04 1.56703350e+04 1.58003525e+04 1.53063271e+04 1.50665654e+04 1.50724346e+04 1.52266367e+04 1.52577354e+04 1.53821191e+04 1.49388252e+04 1.52107764e+04 1.60653711e+04 1.57687305e+04 1.52494170e+04 1.47547705e+04 1.49356777e+04 1.58825762e+04 1.57835938e+04 1.53249404e+04 1.50092490e+04 1.48923652e+04 1.52298965e+04 1.52535127e+04 1.56381006e+04 1.53317285e+04 1.48639668e+04 1.52585049e+04 1.52422881e+04 1.55432656e+04 1.53452510e+04 1.49155791e+04 1.51044756e+04 1.50899932e+04 1.52274609e+04 1.48026514e+04 1.50823320e+04 1.60312559e+04 1.55280020e+04 1.51123223e+04 1.47411406e+04 1.45896660e+04 1.54619570e+04 1.55858623e+04 1.50975801e+04 1.45945107e+04 1.45821299e+04 1.50838701e+04 1.50481143e+04 1.54085127e+04 1.53178330e+04 1.49441416e+04 1.45283301e+04 1.44050098e+04 1.53109453e+04 1.51290928e+04 1.46413027e+04 1.45992002e+04 1.45434736e+04 1.51737842e+04 1.52103174e+04 1.44613721e+04 1.43187715e+04 1.49835000e+04 1.51232822e+04 1.43356143e+04 1.42284609e+04 1.49651289e+04 1.49928652e+04 1.45514541e+04 1.42307178e+04 1.41436895e+04 1.48989326e+04 1.47136094e+04 1.41841816e+04 1.42834092e+04 1.42996934e+04 1.46636025e+04 1.45835547e+04 1.40712988e+04 1.37286904e+04 1.41623496e+04 1.49434092e+04 1.44945000e+04 1.42408691e+04 1.43701562e+04 1.41997246e+04 1.41632354e+04 1.40910459e+04 1.40091465e+04 1.36511973e+04 1.35624355e+04 1.38912041e+04 1.39611143e+04 1.43733574e+04 1.39032646e+04 1.32947666e+04 1.36366318e+04 1.39315791e+04 1.42856826e+04 1.39304004e+04 1.35061836e+04 1.34809961e+04 1.33653936e+04 1.36209062e+04 1.35847705e+04 1.37664502e+04 1.37225820e+04 1.33841455e+04 1.31711113e+04 1.27641641e+04 1.32741074e+04 1.40782920e+04 1.37181436e+04 1.32534707e+04 1.28370488e+04 1.25477646e+04 1.31324102e+04 1.37661357e+04 1.33216377e+04 1.26424775e+04 1.25537412e+04 1.28830010e+04 1.29385645e+04 1.31339043e+04 1.30255820e+04 1.26969229e+04 1.25900117e+04 1.24815391e+04 1.29035391e+04 1.28898809e+04 1.21916025e+04 1.21477168e+04 1.28086387e+04 1.26620479e+04 1.19860840e+04 1.21450332e+04 1.27441279e+04 1.26015127e+04 1.22084287e+04 1.18774971e+04 1.18353594e+04 1.24401855e+04 1.24304023e+04 1.20464229e+04 1.16879209e+04 1.15361367e+04 1.18243350e+04 1.18564434e+04 1.17367549e+04 1.14061172e+04 1.16448828e+04 1.20275049e+04 1.16209863e+04 1.17971826e+04 1.17030088e+04 1.12991943e+04 1.14369902e+04 1.14337432e+04 1.13585762e+04 1.11490264e+04 1.09162031e+04 1.07379189e+04 1.11751338e+04 1.17211250e+04 1.10761191e+04 1.05400371e+04 1.08256953e+04 1.09572520e+04 1.12719648e+04 1.09082266e+04 1.04854971e+04 1.09236367e+04 1.08862002e+04 1.02673691e+04 1.01456260e+04 1.07454092e+04 1.07815117e+04 1.03683623e+04 1.01564453e+04 9.69168848e+03 1.01367871e+04 1.08259551e+04 1.04170645e+04 1.00472510e+04 9.73150879e+03 9.53280469e+03 9.97745605e+03 1.04490498e+04 1.01213311e+04 9.55351172e+03 9.43784668e+03 9.63594043e+03 9.64753223e+03 9.85379785e+03 9.57484570e+03 9.24933496e+03 9.41005957e+03 9.35649219e+03 9.57838867e+03 9.48039453e+03 9.11939941e+03 9.09649707e+03 9.00648438e+03 9.14773145e+03 8.90520801e+03 8.76618945e+03 9.19755566e+03 9.08347949e+03 8.71104297e+03 8.45934082e+03 8.47234082e+03 8.95293164e+03 8.81370898e+03 8.52454004e+03 8.26821191e+03 8.14704688e+03 8.32464551e+03 8.29910156e+03 8.25230078e+03 8.00323877e+03 8.10596484e+03 8.35816406e+03 8.05402197e+03 8.20587891e+03 8.15492578e+03 7.88552148e+03 7.72790820e+03 7.59984424e+03 7.83142383e+03 7.80012256e+03 7.44557178e+03 7.32704785e+03 7.69296924e+03 7740. 7.21452393e+03 6.98949463e+03 7.12080518e+03 7.35729395e+03 7.54927002e+03 7.22235645e+03 6.82171289e+03 7.09793750e+03 7.21308838e+03 6.98608789e+03 6.79839160e+03 6.74801221e+03 6.62984375e+03 6.59473730e+03 6.66546973e+03 6.41384912e+03 6.52293848e+03 6.78513623e+03 6.49919043e+03 6.43958643e+03 6.26060303e+03 6.13415283e+03 6.39050928e+03 6.32273193e+03 6.13523486e+03 5.92889355e+03 5.71721484e+03 5.79782812e+03 6.04081299e+03 6.19480176e+03 5.83372363e+03 5.58784033e+03 5.65961572e+03 5.65765039e+03 5.78212549e+03 5.71308496e+03 5.48708643e+03 5.40059961e+03 5.32666699e+03 5.27910645e+03 5.12175732e+03 5.22451416e+03 5.38082373e+03 5.16406396e+03 5.15784668e+03 5.03912354e+03 4.85786084e+03 5.09521924e+03 5.06940967e+03 4.84359766e+03 4.68749316e+03 4.57015527e+03 4.67758057e+03 4.62265527e+03 4.72054980e+03 4.71825293e+03 4.49286328e+03 4.34286084e+03 4.34699463e+03 4.50192432e+03 4.38262939e+03 4.24725342e+03 4.13042090e+03 4.07568384e+03 4.09038794e+03 4.02724390e+03 4.08243213e+03 4.04929395e+03 3.87299585e+03 3.94737109e+03 3.95268555e+03 3.80989771e+03 3.74654370e+03 3.70594946e+03 3.66405713e+03 3.52472388e+03 3.43711694e+03 3.57472925e+03 3.56986011e+03 3.33786963e+03 3.19350562e+03 3.32070410e+03 3.48217822e+03 3.37714624e+03 3.13265381e+03 3.04344727e+03 3.18106982e+03 3.13976904e+03 2.99519067e+03 3.02969238e+03 2.91400610e+03 2.73885913e+03 2.79064648e+03 2.90468115e+03 2.92203345e+03 2.72606152e+03 2.55433179e+03 2.66567627e+03 2.75342871e+03 2.63511108e+03 2.47240137e+03 2.39795581e+03 2.43322974e+03 2.41820630e+03 2.43751953e+03 2.38980957e+03 2.26919897e+03 2.24418213e+03 2.20702417e+03 2.23896948e+03 2.15830884e+03 2.06256885e+03 2.10001660e+03 2.05269458e+03 2.03315259e+03 1.96352368e+03 1.88978442e+03 1.95968176e+03 1.87897803e+03 1.76395349e+03 1.77397058e+03 1.77393518e+03 1.74924365e+03 1.69112097e+03 1.69458313e+03 1.67630212e+03 1.60403113e+03 1.52310413e+03 1.48393250e+03 1.52826416e+03 1.46789990e+03 1.39821533e+03 1.40683508e+03 1.37509375e+03 1.34069373e+03 1.30537561e+03 1.31180798e+03 1.26884521e+03 1.20009875e+03 1.21431030e+03 1.19192993e+03 1.14380884e+03 1.11762695e+03 1.08602722e+03 1.04920007e+03 9.96294800e+02 9.53084900e+02 9.74584961e+02 1.00499554e+03 9.29055176e+02 8.48873352e+02 8.63550049e+02 8.94298035e+02 8.58646240e+02 7.88426941e+02 7.46973938e+02 7.66070129e+02 7.43689697e+02 6.94843506e+02 7.01386169e+02 6.78061951e+02 6.22891785e+02 6.00587097e+02 6.09754395e+02 6.04829041e+02 5.57259155e+02 5.15597351e+02 5.16490479e+02 5.26338684e+02 4.96852295e+02 4.55430817e+02 4.26295959e+02 4.26931610e+02 4.29368225e+02 3.99550476e+02 3.70764435e+02 3.57641571e+02 3.45432709e+02 3.28046997e+02 3.21710632e+02 2.99788269e+02 2.76515808e+02 2.69503448e+02 2.56601257e+02 2.48219604e+02 2.29878784e+02 2.11203018e+02 2.04982941e+02 1.87867905e+02 1.77202103e+02 1.72688995e+02 1.59940140e+02 1.48151184e+02 1.36741531e+02 1.31350128e+02 1.22346115e+02 1.08912498e+02 9.77528839e+01 8.98027496e+01 8.68405304e+01 7.67315063e+01 6.63899460e+01 6.22644615e+01 6.14025497e+01 6.04529572e+01 4.08842621e+01 3.89997482e+01 9.82159653e+01 1.36735886e+02 3.67012525e+06 17673576. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -106555088. -63426008. 1.15066589e+02 7.51065750e+01 6.60931244e+01 5.06410484e+01 5.68313789e+01 6.83060455e+01 6.90511169e+01 7.31182175e+01 8.14590759e+01 8.92289276e+01 9.85177994e+01 1.10658241e+02 1.18697739e+02 1.23626312e+02 1.35624405e+02 1.49208496e+02 1.55612473e+02 1.63932663e+02 1.75159866e+02 1.88956833e+02 2.05645096e+02 2.19367477e+02 2.26414749e+02 2.31862045e+02 2.50621078e+02 2.73158081e+02 2.83197998e+02 2.96400208e+02 3.07831421e+02 3.20961700e+02 3.47259369e+02 3.56382416e+02 3.60952515e+02 3.83499908e+02 4.00497223e+02 4.23170441e+02 4.45679230e+02 4.51162201e+02 4.68452026e+02 5.02735107e+02 5.44078369e+02 5.49123718e+02 5.30775452e+02 5.49773682e+02 5.86797974e+02 6.19662109e+02 6.52080811e+02 6.61767334e+02 6.64901001e+02 7.03477844e+02 7.36031494e+02 7.37682617e+02 7.53665649e+02 7.75701599e+02 8.24855103e+02 8.79015686e+02 8.60674255e+02 8.54343994e+02 9.01275635e+02 9.47023682e+02 9.89642700e+02 1.00170593e+03 1.00167316e+03 1.01635187e+03 1.06789600e+03 1.14418384e+03 1.14018958e+03 1.11398071e+03 1.16381360e+03 1.21461499e+03 1.24248743e+03 1.28775952e+03 1.29798865e+03 1.29511792e+03 1.35776453e+03 1.41686584e+03 1.42079126e+03 1.43020728e+03 1.44792297e+03 1.48756860e+03 1.56413611e+03 1.63612207e+03 1.62665259e+03 1.59696045e+03 1.65877673e+03 1.73703149e+03 1.73829150e+03 1.74597900e+03 1.78151819e+03 1.84846350e+03 1.93933984e+03 1.94388928e+03 1.90647327e+03 1.93449463e+03 1.98117920e+03 2.06380884e+03 2.11700122e+03 2.11817725e+03 2.15146924e+03 2.24640747e+03 2.33838550e+03 2.31854028e+03 2.23344043e+03 2.27946729e+03 2.39786304e+03 2.46264722e+03 2.50263208e+03 2.49351050e+03 2.49546582e+03 2.61828955e+03 2.67244824e+03 2.63529565e+03 2.69173047e+03 2.74857495e+03 2.77989893e+03 2.88163818e+03 2.90966333e+03 2.87718701e+03 2.91720361e+03 2.96212183e+03 3.01214233e+03 3.12409546e+03 3.23673877e+03 3.19694067e+03 3.17298657e+03 3.50003442e+03 4.49918604e+03 4.66740479e+03 4.82300537e+03 4.79048828e+03 4.91230322e+03 5.11088428e+03 4.74711963e+03 4.72010303e+03 4.21090771e+03 4.08813013e+03 3.92703442e+03 4.97685449e+03 5.35034229e+03 5.55829688e+03 5.59989062e+03 5.74989453e+03 5.75512207e+03 5.71274170e+03 5.86123730e+03 5.98443164e+03 6.13170117e+03 6.28470801e+03 6.16469629e+03 5.59785889e+03 5.63349219e+03 4.97271191e+03 4.83082227e+03 4.58649121e+03 4.46497314e+03 4.48857715e+03 4.83617139e+03 4.89967529e+03 4.71264648e+03 4.69050439e+03 4.92851318e+03 5.06681445e+03 4.97787158e+03 4.87983838e+03 4.97093115e+03 5.19116260e+03 5.34435596e+03 5.20315186e+03 5.18074170e+03 5.28260156e+03 5.30705127e+03 5.46198096e+03 5.56491211e+03 5.47402588e+03 5.54900977e+03 5.71995508e+03 5.78545605e+03 5.69429932e+03 5.67625684e+03 5.72817334e+03 5.79630225e+03 5.97484863e+03 6.21579053e+03 6.28617041e+03 5.92963818e+03 6.06916699e+03 6.41370068e+03 6.23043604e+03 6.14211963e+03 6.26361475e+03 6.35373779e+03 6.59977246e+03 6.68660303e+03 6.48829492e+03 6.44769141e+03 6.56765381e+03 6.75742383e+03 6.86273193e+03 6.76392480e+03 6.83121094e+03 7.07913135e+03 7.18859521e+03 6.97797461e+03 6.95425830e+03 7.00006104e+03 7.15699756e+03 7.30856104e+03 7.51315967e+03 7.59334717e+03 7.27084131e+03 7.35552441e+03 7.60577051e+03 7.55260645e+03 7.55337598e+03 7.62548730e+03 7.68599414e+03 7.94344482e+03 8.02415088e+03 7.79546826e+03 7.82327979e+03 7.87465039e+03 8.00449023e+03 8.20004102e+03 8.11508301e+03 8.16947656e+03 8.31885254e+03 8.48956836e+03 8.59865039e+03 8.26685645e+03 8.19947559e+03 8.47969141e+03 8.59001172e+03 8.75983008e+03 8.70434082e+03 8.48745215e+03 8.77038574e+03 9.12626953e+03 8.88121094e+03 8.80619043e+03 9.00513770e+03 9.03882715e+03 9.10695508e+03 9.07781934e+03 9.35263965e+03 9.39262109e+03 9.19412109e+03 9.47715723e+03 9.30524023e+03 9.38590039e+03 9.68491211e+03 9.42225684e+03 9.54578613e+03 9.78894141e+03 9.70145703e+03 9.44987500e+03 9.58145898e+03 1.01406396e+04 1.03545635e+04 9.81219629e+03 9.76303711e+03 1.01682461e+04 1.01578184e+04 1.02838301e+04 1.00547734e+04 1.00503018e+04 1.03162363e+04 1.05860186e+04 1.05467803e+04 1.03957197e+04 1.03479629e+04 1.05483467e+04 1.08106348e+04 1.05822939e+04 1.04509297e+04 1.05445996e+04 1.05961191e+04 1.09083184e+04 1.12565771e+04 1.10737188e+04 1.07187744e+04 1.07483389e+04 1.13184854e+04 1.14539482e+04 1.09186865e+04 1.12560254e+04 1.16404570e+04 1.11220713e+04 1.12045312e+04 1.12191445e+04 1.12805918e+04 1.18128672e+04 1.16701797e+04 1.13706748e+04 1.17507822e+04 1.18382441e+04 1.15573721e+04 1.17843955e+04 1.19359385e+04 1.19402744e+04 1.16840693e+04 1.16442363e+04 1.20514277e+04 1.23087227e+04 1.21761621e+04 1.18495996e+04 1.19054561e+04 1.23785068e+04 1.25604854e+04 1.21483525e+04 1.21117051e+04 1.22866309e+04 1.25558125e+04 1.27437578e+04 1.22634580e+04 1.23330957e+04 1.27669834e+04 1.28399707e+04 1.25379707e+04 1.27973291e+04 1.28643750e+04 1.25695059e+04 1.30505068e+04 1.32572070e+04 1.26913594e+04 1.23630234e+04 1.26931309e+04 1.30902646e+04 1.31867432e+04 1.31116221e+04 1.29078301e+04 1.29554785e+04 1.34451191e+04 1.35792441e+04 1.31020391e+04 1.30158164e+04 1.34308066e+04 1.38465078e+04 1.34691094e+04 1.31127783e+04 1.34517559e+04 1.34821387e+04 1.34359727e+04 1.35261299e+04 1.36585635e+04 1.36613467e+04 1.35180254e+04 1.36994639e+04 1.37847607e+04 1.37041104e+04 1.34993350e+04 1.35982900e+04 1.39001709e+04 1.39640254e+04 1.37714590e+04 1.37897803e+04 1.39220762e+04 1.43110859e+04 1.43575049e+04 1.38545752e+04 1.40335312e+04 1.42053076e+04 1.41446777e+04 1.40342119e+04 1.39516270e+04 1.43472900e+04 1.43831660e+04 1.40425752e+04 1.37552158e+04 1.42303955e+04 1.47129072e+04 1.45237471e+04 1.44508350e+04 1.43747783e+04 1.45336680e+04 1.42548330e+04 1.38160264e+04 1.42938115e+04 1.46586182e+04 1.47208467e+04 1.46514209e+04 1.41996758e+04 1.43643438e+04 1.46905449e+04 1.48839189e+04 1.50924219e+04 1.46490537e+04 1.43384131e+04 1.42780439e+04 1.46981035e+04 1.51461162e+04 1.50237666e+04 1.48134844e+04 1.42039199e+04 1.45463281e+04 1.50727656e+04 1.47815615e+04 1.49631953e+04 1.47540850e+04 1.46597500e+04 1.51250039e+04 1.48138135e+04 1.46532598e+04 1.51809229e+04 1.52954834e+04 1.47724600e+04 1.43992275e+04 1.46412285e+04 1.49191865e+04 1.53809531e+04 1.56446074e+04 1.50862705e+04 1.47374551e+04 1.45519287e+04 1.49778154e+04 1.55438320e+04 1.52148555e+04 1.48162764e+04 1.45421270e+04 1.47994678e+04 1.52661631e+04 1.54776025e+04 1.53321719e+04 1.50800684e+04 1.52728428e+04 1.50205977e+04 1.45532520e+04 1.49396289e+04 1.52347061e+04 1.53431963e+04 1.57032441e+04 1.50259102e+04 1.45088623e+04 1.50098516e+04 1.55486025e+04 15597. 1.49985957e+04 1.48349570e+04 1.48418252e+04 1.51379561e+04 1.55354883e+04 1.54201504e+04 1.51906719e+04 1.48099727e+04 1.51163320e+04 1.51200898e+04 1.46496338e+04 1.49905000e+04 1.53612363e+04 1.52608906e+04 1.51411758e+04 1.48380225e+04 1.49784971e+04 1.53478506e+04 1.53736943e+04 1.53255781e+04 1.47063330e+04 1.46138057e+04 1.50156162e+04 1.52938672e+04 1.54617910e+04 1.51781650e+04 1.50037148e+04 1.45734824e+04 1.48752295e+04 1.55127480e+04 1.50950449e+04 1.49600830e+04 1.49639033e+04 1.48155928e+04 1.47124336e+04 1.47907334e+04 1.49813105e+04 1.51505137e+04 1.52390361e+04 1.47953945e+04 1.44082275e+04 1.47037295e+04 1.49387207e+04 1.50228135e+04 1.51012920e+04 1.46871475e+04 1.47140186e+04 1.46556133e+04 1.47394434e+04 1.51505303e+04 1.47914795e+04 1.46528848e+04 1.45524531e+04 1.41657598e+04 1.44514463e+04 1.52225352e+04 1.50079209e+04 1.44241064e+04 1.45922842e+04 1.43997354e+04 1.40074883e+04 1.43900947e+04 1.46514590e+04 1.45622959e+04 1.45504785e+04 1.41533828e+04 1.42406387e+04 1.45264092e+04 1.45924072e+04 1.50078037e+04 1.45728008e+04 1.37581768e+04 1.37177510e+04 1.42281982e+04 1.45301084e+04 1.44237471e+04 1.41884346e+04 1.35919990e+04 1.39000986e+04 1.44676094e+04 1.41434580e+04 1.40438848e+04 1.38134082e+04 1.37925322e+04 1.41179893e+04 1.37249648e+04 1.36282979e+04 1.42866709e+04 1.42515342e+04 1.38850254e+04 1.35068184e+04 1.31324463e+04 1.34334463e+04 1.39314756e+04 1.42526426e+04 1.39116064e+04 1.31579297e+04 1.30366553e+04 1.34718721e+04 1.37846992e+04 1.35280820e+04 1.33436484e+04 1.30303457e+04 1.30744775e+04 1.34134150e+04 1.35568213e+04 1.34756572e+04 1.32446455e+04 1.33074639e+04 1.31261729e+04 1.27007402e+04 1.29078633e+04 1.31390967e+04 1.31828359e+04 1.33357793e+04 1.28284189e+04 1.24480801e+04 1.27945605e+04 1.29454688e+04 1.31908105e+04 1.29624463e+04 1.23917959e+04 1.22050547e+04 1.25454043e+04 1.29949014e+04 1.30009111e+04 1.25292754e+04 1.22667666e+04 1.22648438e+04 1.21549043e+04 1.22068955e+04 1.24178584e+04 1.25414023e+04 1.22365410e+04 1.19019180e+04 1.17938438e+04 1.19826836e+04 1.22651416e+04 1.23374951e+04 1.21970859e+04 1.17253291e+04 1.13720615e+04 1.15750615e+04 1.18736045e+04 1.21297607e+04 1.19234512e+04 1.13971562e+04 1.11104932e+04 1.14458721e+04 1.18703623e+04 1.15501572e+04 1.15367949e+04 1.13389287e+04 1.10148809e+04 1.12333418e+04 1.13290547e+04 1.12391680e+04 1.10804844e+04 1.11342236e+04 1.11065156e+04 1.08774082e+04 1.08829785e+04 1.08655850e+04 1.10507559e+04 1.09582002e+04 1.06012461e+04 1.05592021e+04 1.04189248e+04 1.05393799e+04 1.10580801e+04 1.07321631e+04 1.02067236e+04 1.01008291e+04 1.02112295e+04 1.05269756e+04 1.06926074e+04 1.03105117e+04 9.92504492e+03 9.99539355e+03 1.01457148e+04 9.93697070e+03 1.00980742e+04 9.98824707e+03 1.12033418e+04 1.06470361e+04 1.19250361e+04 2.25031895e+04 3.25421426e+04 50722428. 1.86595375e+06 1.58151288e+06 -510279296. 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. 0. 0. 0. 0. 0. 0. 0. 754019136. 1.60929688e+05 2.51388652e+04 1.05782988e+04 1.00701973e+04 8.13096436e+03 7.59513525e+03 7.36426270e+03 7.32013477e+03 6.78320312e+03 6.92580566e+03 7.28997363e+03 7.16836230e+03 6.82388867e+03 6.59466113e+03 6.51935889e+03 6.77525732e+03 7.05589941e+03 6.75161914e+03 6.45589160e+03 6.34467969e+03 6.35429590e+03 6.59429980e+03 6.52263574e+03 6.23981104e+03 6.12143945e+03 6.22940625e+03 6.12567334e+03 5.93345898e+03 5.93820898e+03 6.05490430e+03 6.18312842e+03 6.12412012e+03 5.76380371e+03 5.46315869e+03 5.57362988e+03 5.85827930e+03 5.93397656e+03 5.65425781e+03 5.36153369e+03 5.25606543e+03 5.44825928e+03 5.68747119e+03 5.46704150e+03 5.09338086e+03 5.06997266e+03 5.29128857e+03 5.22240674e+03 5.05704883e+03 5.03174121e+03 4.92972412e+03 4.97479883e+03 4.94902002e+03 4.66950781e+03 4.63268945e+03 4.83452344e+03 4.91174219e+03 4.74809082e+03 4.46434375e+03 4.27625537e+03 4.48611279e+03 4.72244141e+03 4.56446387e+03 4.28533496e+03 4.09498120e+03 4.01826147e+03 4.22960205e+03 4.41115723e+03 4.24124805e+03 4.07366675e+03 3.99397070e+03 3.85395728e+03 3.87567529e+03 3.95953247e+03 3.79029224e+03 3.69242700e+03 3.77838257e+03 3.68454150e+03 3.49793823e+03 3.51666406e+03 3.63574805e+03 3.64113989e+03 3.55377148e+03 3.42601025e+03 3.27016797e+03 3.18438550e+03 3.31218896e+03 3.45226733e+03 3.26800879e+03 3.03643823e+03 2.98352515e+03 3.07287500e+03 3.16164111e+03 3.10612109e+03 2.92300977e+03 2.83979883e+03 2.87903955e+03 2.83192407e+03 2.77863159e+03 2.74919556e+03 2.69192651e+03 2.67658374e+03 2.63195386e+03 2.51645190e+03 2.50571777e+03 2.53119116e+03 2.53475439e+03 2.49021484e+03 2.39337305e+03 2.26820337e+03 2.24620923e+03 2.33593286e+03 2.33170776e+03 2.19260400e+03 2.08397437e+03 2.02384631e+03 2.09664160e+03 2.17820020e+03 2.06218921e+03 1.92367407e+03 1.89784973e+03 1.91142480e+03 1.87466626e+03 1.80613831e+03 1.77738708e+03 1.80760876e+03 1.78511780e+03 1.70218958e+03 1.62291956e+03 1.58742542e+03 1.62573853e+03 1.65405066e+03 1.59167200e+03 1.50032666e+03 1.43505847e+03 1.38498657e+03 1.41422571e+03 1.45714941e+03 1.37518713e+03 1.28191968e+03 1.24788867e+03 1.27348608e+03 1.29570947e+03 1.22872400e+03 1.16143384e+03 1.13452820e+03 1.12175293e+03 1.11118481e+03 1.07782092e+03 1.01958563e+03 9.84065796e+02 1.00003845e+03 9.90285522e+02 9.29901245e+02 8.85981018e+02 8.76298035e+02 8.75257629e+02 8.71066040e+02 8.30708618e+02 7.63482178e+02 7.45280273e+02 7.51037537e+02 7.34662659e+02 7.00902344e+02 6.69196411e+02 6.45502991e+02 6.27210266e+02 6.18763245e+02 5.90596069e+02 5.59945801e+02 5.57661865e+02 5.47184143e+02 5.15478088e+02 4.82681305e+02 4.63831848e+02 4.59587585e+02 4.55880280e+02 4.36049957e+02 4.04918732e+02 3.75273499e+02 3.56198029e+02 3.56640228e+02 3.58621460e+02 3.30726105e+02 2.97713501e+02 2.82695435e+02 2.79868347e+02 2.75329254e+02 2.58457397e+02 2.37820648e+02 2.23034622e+02 2.11408264e+02 1.98175842e+02 1.87791260e+02 1.78099487e+02 1.66480682e+02 1.56485886e+02 1.45164902e+02 1.32120361e+02 1.23411423e+02 1.17086105e+02 1.09254288e+02 1.00307846e+02 8.80374451e+01 7.82883759e+01 7.47078400e+01 7.06250534e+01 6.25247459e+01 5.40702171e+01 4.66158867e+01 4.04683380e+01 3.72142525e+01 3.40924606e+01 2.84686260e+01 2.28428402e+01 1.88005295e+01 1.58846884e+01 1.30538740e+01 1.02457409e+01 7.76730776e+00 5.69293690e+00 4.02652740e+00 2.71421790e+00 1.78373432e+00 1.26131928e+00 1.09584236e+00 1.30024254e+00 1.89597034e+00 2.82174301e+00 3.96646619e+00 5.56898642e+00 7.79491806e+00 1.04774933e+01 1.32517109e+01 1.61019325e+01 2.00367184e+01 2.41611423e+01 2.72351093e+01 3.08145866e+01 3.64377785e+01 4.38303223e+01 5.10798874e+01 5.63640976e+01 5.94573364e+01 6.43386154e+01 7.28770828e+01 8.43319855e+01 9.54246597e+01 1.01711914e+02 1.04680672e+02 1.12989647e+02 1.29581451e+02 1.39533279e+02 1.43394150e+02 1.53560577e+02 1.64966324e+02 1.76281662e+02 1.94541702e+02 2.02658524e+02 2.08561050e+02 2.25416809e+02 2.32604401e+02 2.53353943e+02 2.73931519e+02 2.73086182e+02 2.93779755e+02 3.17991913e+02 3.24526031e+02 3.39077484e+02 3.56246429e+02 3.73411011e+02 3.91884460e+02 4.05700470e+02 4.11060181e+02 4.29541321e+02 4.69307434e+02 5.00340820e+02 5.06083740e+02 5.01860626e+02 5.09835693e+02 5.42695251e+02 5.87701172e+02 6.21148193e+02 6.28582092e+02 6.17627319e+02 6.40835632e+02 6.84563843e+02 7.01179932e+02 7.19544128e+02 7.43825012e+02 7.64007141e+02 7.87295837e+02 8.44074280e+02 8.45923950e+02 8.37224854e+02 8.83442749e+02 8.88731812e+02 9.44607666e+02 9.91375488e+02 9.83411621e+02 1.04908374e+03 1.04816968e+03 1.03199316e+03 1.09456372e+03 1.09740063e+03 1.14578320e+03 1.25368335e+03 1.21945227e+03 1.17555786e+03 1.22693420e+03 1.31135413e+03 1.39909204e+03 1.40671973e+03 1.35801074e+03 1.34124438e+03 1.40084253e+03 1.51096350e+03 1.58936487e+03 1.59428149e+03 1.54439209e+03 1.56138123e+03 1.64342322e+03 1.69889600e+03 1.70433630e+03 1.71244995e+03 1.76505371e+03 1.81020532e+03 1.89088330e+03 1.92083435e+03 1.86783020e+03 1.91126526e+03 1.96446948e+03 2.00521252e+03 2.06599170e+03 2.09945508e+03 2.18637354e+03 2.17509399e+03 2.13000293e+03 2.22739648e+03 2.20966797e+03 2.29826978e+03 2.49511108e+03 2.41589038e+03 2.30605176e+03 2.38152539e+03 2.53795581e+03 2.66230884e+03 2.69368896e+03 2.60188159e+03 2.53603882e+03 2.61904370e+03 2.79857471e+03 2.93880298e+03 2.89374683e+03 2.78279834e+03 2.80752539e+03 2.93217578e+03 3.03187744e+03 3.15821265e+03 3.20031982e+03 3.04154712e+03 3.04940527e+03 3.25433447e+03 3.34037769e+03 3.25241968e+03 3.28627612e+03 3.37430322e+03 3.38656201e+03 3.54544141e+03 3.63162329e+03 3.47228418e+03 3.51847388e+03 3.65965845e+03 3.70762549e+03 3.74856299e+03 3.74440015e+03 3.86108057e+03 3.98436914e+03 3.94363184e+03 3.88951294e+03 3.84353076e+03 4.05409106e+03 4.31605127e+03 4.29291113e+03 4.12528662e+03 4.05668188e+03 4.22494775e+03 4.54144922e+03 4.47924707e+03 4.27098779e+03 4.35379248e+03 4.53041406e+03 4.70402539e+03 4.91547363e+03 4.82087451e+03 4.61205957e+03 4.55986523e+03 4.75680957e+03 5.02811719e+03 5.05998438e+03 4.99863281e+03 5.00743896e+03 5.06799268e+03 5.22720312e+03 5.23958301e+03 5.15878760e+03 5.19940088e+03 5.14904297e+03 5.43524219e+03 5.66500049e+03 5.49205127e+03 5.52802637e+03 5.61710889e+03 5.77154395e+03 5.67467383e+03 5.48250244e+03 5.76431885e+03 6.11927881e+03 6.01496631e+03 5.77288379e+03 5.86438770e+03 6.24030713e+03 6.26987988e+03 6.19009766e+03 6.24741699e+03 6.06715088e+03 6.09588770e+03 6.57886621e+03 6.60636377e+03 6.41371143e+03 6.29122754e+03 6.30797266e+03 6.65112158e+03 7.01765820e+03 6.77442236e+03 6.66039648e+03 6.83702295e+03 6.86435303e+03 7.17366064e+03 7.20214844e+03 6.86656934e+03 6.88578223e+03 7.14208984e+03 7.21325586e+03 7.26743750e+03 7.31339404e+03 7.54705566e+03 7.47767090e+03 7.26999805e+03 7.43405127e+03 7.32645459e+03 7.67527344e+03 8.16312012e+03 7.99666846e+03 7.54686279e+03 7.59248096e+03 7.96501660e+03 8.23366309e+03 8.45574414e+03 9.46077441e+03 9.08110254e+03 1.08313125e+04 4.92088164e+04 -18319470. 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. 0. 0. 0. 0. 0. 0. -22455362. 1.02842570e+05 1.66749336e+04 1.44968281e+04 1.16314053e+04 1.13224756e+04 1.05000723e+04 1.04058906e+04 1.04857939e+04 1.02430361e+04 1.06923184e+04 1.07352109e+04 1.05312812e+04 1.08415166e+04 1.09206807e+04 1.08069150e+04 1.08748730e+04 1.08912520e+04 1.09440742e+04 1.10289219e+04 1.10555059e+04 1.10443193e+04 1.09056230e+04 1.09402744e+04 1.14347305e+04 1.15527656e+04 1.10599492e+04 1.10517314e+04 1.17064990e+04 1.17849902e+04 1.15455742e+04 1.15859727e+04 1.15648740e+04 1.16621455e+04 1.16909463e+04 1.17067676e+04 1.17440537e+04 1.17387998e+04 1.15578965e+04 1.15905215e+04 1.21810420e+04 1.22538965e+04 1.20023535e+04 1.20567393e+04 1.21220527e+04 1.22033428e+04 1.21894531e+04 1.21856855e+04 1.22805908e+04 1.19836602e+04 1.20006240e+04 1.23508799e+04 1.23637539e+04 1.28473252e+04 1.29792490e+04 1.26009795e+04 1.21987002e+04 1.21397969e+04 1.30584746e+04 1.32208525e+04 1.27364365e+04 1.25938691e+04 1.27447227e+04 1.27494336e+04 1.26553857e+04 1.32858564e+04 1.32621621e+04 1.25150107e+04 1.25387363e+04 1.32416055e+04 1.37468467e+04 1.34126016e+04 1.31826182e+04 1.32867666e+04 1.32461592e+04 1.31694902e+04 1.32776611e+04 1.34591523e+04 1.34486533e+04 1.31684756e+04 1.31913193e+04 1.35077432e+04 1.35028057e+04 1.38792812e+04 1.37102930e+04 1.33681602e+04 1.36253125e+04 1.36542969e+04 1.39593477e+04 1.41029365e+04 1.38351748e+04 1.37966260e+04 1.35234551e+04 1.32815996e+04 1.39888975e+04 1.41926650e+04 1.34896094e+04 1.36228779e+04 1.44368076e+04 1.48671445e+04 1.44657783e+04 1.40844160e+04 1.40344814e+04 1.40639189e+04 1.39758145e+04 1.39870527e+04 1.42925059e+04 1.42528428e+04 1.45081826e+04 1.43742188e+04 1.40816748e+04 1.44204209e+04 1.40437422e+04 1.42658281e+04 1.50951816e+04 1.48615488e+04 1.45040381e+04 1.40864844e+04 1.40306416e+04 1.48931357e+04 1.50210879e+04 1.45425098e+04 1.41721133e+04 1.41801943e+04 1.45956406e+04 1.46094062e+04 1.50557246e+04 1.51735205e+04 1.46774082e+04 1.44417500e+04 1.45108164e+04 1.50561885e+04 1.50617891e+04 1.47477178e+04 1.44993486e+04 1.44978760e+04 1.48467891e+04 1.44762061e+04 1.46458027e+04 1.55764346e+04 1.53658096e+04 1.49294229e+04 1.45243203e+04 1.44723330e+04 1.53914209e+04 1.54443594e+04 1.50094658e+04 1.45782939e+04 1.44869893e+04 1.50431113e+04 1.50386113e+04 1.49668877e+04 1.46579023e+04 1.49398574e+04 1.55792285e+04 1.51891562e+04 1.52748672e+04 1.54155273e+04 1.51437480e+04 1.47865986e+04 1.47657236e+04 1.51292490e+04 1.51497656e+04 1.51977324e+04 1.47058662e+04 1.48575273e+04 1.58743643e+04 1.52028789e+04 1.46687686e+04 1.50956729e+04 1.50869697e+04 1.55314375e+04 1.52799521e+04 1.47135215e+04 1.54400723e+04 1.55633271e+04 1.51724814e+04 1.51005244e+04 1.50226299e+04 1.48577246e+04 1.48910527e+04 1.51683623e+04 1.47315000e+04 1.50200566e+04 1.59482139e+04 1.56284004e+04 1.49116260e+04 1.43901670e+04 1.48552568e+04 1.58602578e+04 1.55489268e+04 1.50783115e+04 1.48122363e+04 1.46981221e+04 1.50738740e+04 1.50575742e+04 1.53922021e+04 1.51529844e+04 1.46710283e+04 1.50526416e+04 1.50713789e+04 1.53506006e+04 1.52670801e+04 1.48796729e+04 1.47914502e+04 1.47729561e+04 1.50698613e+04 1.46533740e+04 1.48781348e+04 1.57441543e+04 1.53516172e+04 1.49339092e+04 1.45378330e+04 1.44480762e+04 1.52638379e+04 1.53361055e+04 1.49021582e+04 1.44423691e+04 1.44219062e+04 1.48815713e+04 1.48733691e+04 1.52167666e+04 1.51334385e+04 1.47651416e+04 1.42964854e+04 1.42306104e+04 1.51663691e+04 1.50109570e+04 1.45311777e+04 1.43585225e+04 1.42887246e+04 1.49679814e+04 1.50372881e+04 1.42747158e+04 1.41438721e+04 1.48668994e+04 1.48910762e+04 1.41189492e+04 1.40563037e+04 1.48126191e+04 1.48211221e+04 1.43178516e+04 1.39876660e+04 1.39399053e+04 1.47287480e+04 1.46512764e+04 1.41162539e+04 1.40749287e+04 1.39827119e+04 1.42160020e+04 1.42611719e+04 1.40790117e+04 1.37019561e+04 1.39985059e+04 1.45959678e+04 1.41369404e+04 1.41981406e+04 1.43405615e+04 1.40079932e+04 1.39850039e+04 1.39510332e+04 1.37999385e+04 1.35021270e+04 1.34266230e+04 1.37266963e+04 1.37580166e+04 1.41419639e+04 1.36902324e+04 1.32339150e+04 1.35643555e+04 1.36299736e+04 1.40046162e+04 1.37624922e+04 1.33405918e+04 1.33140547e+04 1.32260225e+04 1.33962363e+04 1.33746201e+04 1.36099238e+04 1.34577852e+04 1.30756025e+04 1.31239014e+04 1.27228145e+04 1.31166094e+04 1.38789541e+04 1.34486230e+04 1.30455908e+04 1.26988711e+04 1.24564307e+04 1.30919043e+04 1.34773496e+04 1.30379922e+04 1.25089482e+04 1.23989561e+04 1.27409795e+04 1.26946680e+04 1.29421641e+04 1.27793848e+04 1.23958477e+04 1.25327412e+04 1.24713779e+04 1.27618994e+04 1.27459697e+04 1.20144482e+04 1.20078369e+04 1.26247031e+04 1.23876484e+04 1.17123125e+04 1.20551162e+04 1.26773340e+04 1.24371475e+04 1.20587773e+04 1.17025664e+04 1.16951494e+04 1.23043076e+04 1.22483535e+04 1.18602197e+04 1.14888066e+04 1.13678691e+04 1.17579932e+04 1.16851855e+04 1.16157197e+04 1.13078301e+04 1.15272783e+04 1.18605898e+04 1.14718184e+04 1.16267070e+04 1.13934863e+04 1.10500293e+04 1.12350859e+04 1.12768008e+04 1.12206006e+04 1.10627148e+04 1.08815225e+04 1.06925293e+04 1.09554980e+04 1.15733184e+04 1.09200723e+04 1.03211309e+04 1.06203828e+04 1.09151396e+04 1.11492051e+04 1.08252715e+04 1.04868223e+04 1.06882002e+04 1.06690049e+04 1.02081816e+04 1.00123477e+04 1.05277451e+04 1.05489062e+04 1.01294287e+04 1.01060029e+04 9.69897852e+03 1.00170361e+04 1.05718369e+04 1.02102598e+04 9.96280664e+03 9.60010547e+03 9.42386426e+03 9.93251367e+03 1.03439639e+04 9.97936328e+03 9.40279102e+03 9.32259473e+03 9.50679199e+03 9.48461328e+03 9.72810156e+03 9.40776758e+03 9.11310352e+03 9.34410156e+03 9.23692383e+03 9.41224805e+03 9.28620312e+03 8.91469238e+03 9.10711035e+03 9.07127051e+03 8.92976172e+03 8.62200781e+03 8.68933594e+03 9.15624316e+03 8.96042188e+03 8.55534473e+03 8.33009570e+03 8.45650586e+03 8.89742090e+03 8.72419629e+03 8.37760840e+03 8.14027881e+03 8.08040967e+03 8.23858594e+03 8.28887109e+03 8.17297656e+03 7.92586377e+03 8.00951514e+03 8.26565723e+03 7.93760547e+03 8.04474170e+03 8.03037305e+03 7.75844824e+03 7.67895215e+03 7.66719971e+03 7.61006250e+03 7.54715674e+03 7.41268750e+03 7.34660791e+03 7.59743018e+03 7.59906592e+03 7.11139062e+03 6.98991211e+03 7.07751025e+03 7.20430908e+03 7.40081494e+03 7.16347461e+03 6.69764502e+03 6.91422363e+03 7.16406152e+03 6.97971240e+03 6.62516406e+03 6.55923047e+03 6.56722021e+03 6.57950293e+03 6.56097607e+03 6.32265088e+03 6.41744971e+03 6.68067236e+03 6.49067871e+03 6.26550439e+03 6.11001221e+03 6.07410840e+03 6.34669873e+03 6.25624463e+03 6.04988818e+03 5.88622461e+03 5.64790234e+03 5.69964600e+03 5.99812158e+03 6.14593848e+03 5.73987744e+03 5.44957275e+03 5.56092188e+03 5.62176025e+03 5.75884668e+03 5.59665381e+03 5.34352393e+03 5.39978076e+03 5.34082422e+03 5.23429590e+03 5.06788721e+03 5.13221777e+03 5.30577539e+03 5.16637158e+03 5.04964795e+03 4.89531104e+03 4.84043701e+03 5.04034863e+03 4.98890088e+03 4.81521240e+03 4.62824951e+03 4.52584912e+03 4.61839209e+03 4.55718945e+03 4.65494678e+03 4.65527979e+03 4.38417822e+03 4.24605811e+03 4.35381055e+03 4.45832666e+03 4.29285498e+03 4.17876514e+03 4.11309912e+03 4.05938867e+03 4.00051172e+03 3.88529175e+03 3.98961060e+03 4.01932227e+03 3.84309253e+03 3.89588794e+03 3.87809082e+03 3.79038208e+03 3.72459082e+03 3.65238867e+03 3.59700464e+03 3.47719727e+03 3.39217285e+03 3.49814404e+03 3.54229541e+03 3.33117505e+03 3.16087549e+03 3.25477515e+03 3.39652563e+03 3.34685864e+03 3.12866748e+03 2.97406128e+03 3.09316382e+03 3.16413501e+03 3.04129028e+03 2.98165918e+03 2.84940137e+03 2.69973389e+03 2.77487915e+03 2.90161572e+03 2.87072681e+03 2.66921777e+03 2.53157104e+03 2.64276050e+03 2.71273804e+03 2.59530859e+03 2.43434521e+03 2.33130762e+03 2.38092651e+03 2.39072412e+03 2.40932373e+03 2.39703320e+03 2.28117529e+03 2.19499048e+03 2.15730420e+03 2.21717554e+03 2.12781128e+03 2.03312769e+03 2.08987207e+03 2.04488232e+03 1.98651208e+03 1.90657849e+03 1.87029407e+03 1.93780005e+03 1.84678491e+03 1.72234509e+03 1.73642419e+03 1.76924670e+03 1.73860083e+03 1.67074060e+03 1.67243994e+03 1.65413586e+03 1.57881384e+03 1.50018750e+03 1.46107275e+03 1.51349194e+03 1.45414368e+03 1.38010706e+03 1.38970044e+03 1.35669238e+03 1.32173828e+03 1.27499219e+03 1.27596387e+03 1.25704126e+03 1.19709778e+03 1.18805420e+03 1.16083093e+03 1.14104114e+03 1.11150488e+03 1.06864722e+03 1.02443335e+03 9.71588196e+02 9.48728516e+02 9.74111755e+02 9.95463013e+02 9.16262146e+02 8.35590881e+02 8.44723022e+02 8.72656738e+02 8.52312012e+02 7.85003540e+02 7.28913940e+02 7.44853699e+02 7.38601746e+02 6.91362976e+02 6.94707275e+02 6.62706604e+02 6.03556702e+02 5.99585022e+02 6.13831421e+02 5.93190308e+02 5.44575012e+02 5.05792511e+02 5.08620422e+02 5.20775879e+02 4.90043915e+02 4.47163269e+02 4.18483154e+02 4.20786224e+02 4.18489624e+02 3.89792511e+02 3.69174103e+02 3.54156403e+02 3.40090057e+02 3.23409271e+02 3.16180206e+02 2.95397644e+02 2.71906189e+02 2.65162079e+02 2.52511002e+02 2.44275146e+02 2.26222427e+02 2.07853180e+02 2.04166229e+02 1.86160065e+02 1.70586823e+02 1.66417221e+02 1.58241119e+02 1.46863129e+02 1.34450089e+02 1.28803802e+02 1.19824570e+02 1.06717003e+02 9.58319016e+01 8.74287491e+01 8.44901276e+01 7.54343033e+01 6.42550354e+01 6.03968315e+01 5.93548584e+01 5.36103477e+01 4.49369240e+01 4.15440559e+01 8.59484406e+01 1.24206108e+02 3.67012525e+06 17673576. 0. 0. 0. 0. 0. -24383056. -9181428. 2.26183950e+06 -6553048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -106555088. -63426008. 2.05119858e+02 1.04767822e+02 5.54486237e+01 5.09550400e+01 5.70319824e+01 6.30175095e+01 6.67617645e+01 7.27910995e+01 7.91310959e+01 8.40885544e+01 9.42230530e+01 1.05905785e+02 1.11096512e+02 1.18381462e+02 1.30077972e+02 1.41330338e+02 1.51816376e+02 1.57525116e+02 1.63511597e+02 1.77345245e+02 1.93133926e+02 2.06254517e+02 2.16351196e+02 2.23826630e+02 2.37046265e+02 2.58295532e+02 2.76768494e+02 2.81889374e+02 2.84553284e+02 3.02004395e+02 3.25905670e+02 3.38133911e+02 3.51588074e+02 3.70554108e+02 3.77162598e+02 3.99372253e+02 4.25819977e+02 4.25568268e+02 4.41469971e+02 4.72892303e+02 5.08539307e+02 5.29676941e+02 5.12943665e+02 5.14747437e+02 5.49405334e+02 5.92695251e+02 6.20190796e+02 6.16080322e+02 6.32962769e+02 6.75488708e+02 6.91372070e+02 7.10272766e+02 7.22783813e+02 7.21951111e+02 7.68270508e+02 8.18181885e+02 8.13508545e+02 8.29930054e+02 8.73805542e+02 8.83978088e+02 9.22773926e+02 9.54499695e+02 9.46290405e+02 9.64981323e+02 1.00952130e+03 1.06881836e+03 1.08727527e+03 1.07559229e+03 1.11029639e+03 1.13322742e+03 1.17136621e+03 1.22689001e+03 1.21307678e+03 1.22774170e+03 1.29107092e+03 1.33827124e+03 1.37587842e+03 1.36884253e+03 1.34929907e+03 1.39191284e+03 1.46886511e+03 1.52590222e+03 1.54803735e+03 1.54873792e+03 1.56075647e+03 1.62886426e+03 1.69306677e+03 1.67194751e+03 1.65582703e+03 1.71940588e+03 1.81486243e+03 1.85320593e+03 1.85835718e+03 1.84441748e+03 1.85396436e+03 1.95297717e+03 2.02370667e+03 1.98588354e+03 2.01902454e+03 2.11230225e+03 2.19496875e+03 2.22488672e+03 2.15265210e+03 2.13168262e+03 2.24147095e+03 2.31257056e+03 2.34250830e+03 2.36419873e+03 2.41876245e+03 2.49852051e+03 2.49033813e+03 2.50456079e+03 2.59489771e+03 2.57591382e+03 2.59622437e+03 2.71078101e+03 2.75156177e+03 2.80025659e+03 2.79318921e+03 2.75715601e+03 2.83351660e+03 2.93035864e+03 3.02265186e+03 3.02601782e+03 2.99684570e+03 3.06928662e+03 3.18831689e+03 3.24609766e+03 3.18347314e+03 3.13439404e+03 3.22683008e+03 3.35531592e+03 3.41048120e+03 3.40869116e+03 3.42649731e+03 3.46089331e+03 3.59457690e+03 3.67877808e+03 3.65360718e+03 3.65956250e+03 3.64973315e+03 3.73212695e+03 3.79924316e+03 3.78166235e+03 3.86275928e+03 3.93624219e+03 4.05793213e+03 4.16430469e+03 4.05442041e+03 4.00185327e+03 4.12108350e+03 4.24267676e+03 4.34436377e+03 4.34977002e+03 4.21722607e+03 4.27254541e+03 4.53019873e+03 4.68703516e+03 4.53199463e+03 4.44098975e+03 4.56320752e+03 4.77768945e+03 4.77204053e+03 4.61708203e+03 4.68814209e+03 4.89199463e+03 4.94557617e+03 4.96533643e+03 5.04075635e+03 5.11324805e+03 4.97108154e+03 5.14675830e+03 5.30846289e+03 5.12175244e+03 5.19699902e+03 5.36796289e+03 5.43095312e+03 5.52261670e+03 5.46457812e+03 5.33459766e+03 5.40923877e+03 5.63668115e+03 5.87472266e+03 5.93421826e+03 5.62467041e+03 5.70349561e+03 6.07210547e+03 5.96002881e+03 5.78907910e+03 5.86821045e+03 6.03474316e+03 6.18219141e+03 6.35827539e+03 6.34391650e+03 6.20334375e+03 6.09059375e+03 6.37453906e+03 6.53726416e+03 6.40711475e+03 6.43872119e+03 6.61004980e+03 6.77704736e+03 6.81194775e+03 6.66664990e+03 6.53443408e+03 6.65620752e+03 6.87400146e+03 7.08642676e+03 7.18213135e+03 6.85724365e+03 6.92872168e+03 7.22224561e+03 7.29146875e+03 7.21779346e+03 7.15490283e+03 7.23350830e+03 7.48016162e+03 7.57996387e+03 7.55020947e+03 7.42178809e+03 7.35738916e+03 7.55204004e+03 7.76267090e+03 7.64000146e+03 7.76402588e+03 7.88630762e+03 7.98085449e+03 8.16320557e+03 7.88543115e+03 7.75059717e+03 8.04637793e+03 8.10345117e+03 8.27149121e+03 8.07463135e+03 7.97726416e+03 8.34304492e+03 8.62268262e+03 8.54932227e+03 8.36540137e+03 8.50115234e+03 8.41416406e+03 8.44555078e+03 8.72470020e+03 9.02826074e+03 8.86399414e+03 8.58589160e+03 8.93918262e+03 8.87948828e+03 8.93768848e+03 9.03604102e+03 8.79085547e+03 9.10592480e+03 9.35172852e+03 9.09464551e+03 8.92107910e+03 9.17390918e+03 9.59237207e+03 9.70588379e+03 9.25124805e+03 9.19660938e+03 9.51775586e+03 9.68734668e+03 9.80621191e+03 9.59118359e+03 9.63907812e+03 9.59280859e+03 9.66826953e+03 1.00933896e+04 1.00083652e+04 9658. 9.94763574e+03 1.03224160e+04 1.00347852e+04 1.00020371e+04 9.95091699e+03 9.93035547e+03 1.04262256e+04 1.06702188e+04 1.03042852e+04 1.01869189e+04 1.03548691e+04 1.06392559e+04 1.07886230e+04 1.04865352e+04 1.07519756e+04 1.08435283e+04 1.03844346e+04 1.05298604e+04 1.07014883e+04 1.07562734e+04 1.10238330e+04 1.09781357e+04 1.09346064e+04 1.12273535e+04 1.10441455e+04 1.08724248e+04 1.11626318e+04 1.13445352e+04 1.13230459e+04 1.10034814e+04 1.10073008e+04 1.15387051e+04 1.17582256e+04 1.13240615e+04 1.11444805e+04 1.13533330e+04 1.17158887e+04 1.18845830e+04 1.15485098e+04 1.15144404e+04 1.15438828e+04 1.17860596e+04 1.20476133e+04 1.17046309e+04 1.17268223e+04 1.18339053e+04 1.18562363e+04 1.20448691e+04 1.23066455e+04 1.20746377e+04 1.17451318e+04 1.22835205e+04 1.26978496e+04 1.21671191e+04 1.17170840e+04 1.20595908e+04 1.24276650e+04 1.24676074e+04 1.22747119e+04 1.22057871e+04 1.23286045e+04 1.26463662e+04 1.27523096e+04 1.24440615e+04 1.24438545e+04 1.25542520e+04 1.28676484e+04 1.27541016e+04 1.24812822e+04 1.27163965e+04 1.26680645e+04 1.26671221e+04 1.29644746e+04 1.30023037e+04 1.27407412e+04 1.27355957e+04 1.30554141e+04 1.31450918e+04 1.28707031e+04 1.27930059e+04 1.29642139e+04 1.32973711e+04 1.32740723e+04 1.28291172e+04 1.29024609e+04 1.31773398e+04 1.35699434e+04 1.36635957e+04 1.31810742e+04 1.34776387e+04 1.33744551e+04 1.29193164e+04 1.30967617e+04 1.33167461e+04 1.37048555e+04 1.36905322e+04 1.31476982e+04 1.30276719e+04 1.34562520e+04 13942. 1.38819287e+04 1.36260898e+04 1.35578477e+04 1.34733867e+04 1.33699717e+04 1.33552080e+04 1.37976162e+04 1.40172607e+04 1.36417725e+04 1.36161006e+04 1.36204961e+04 1.38141250e+04 1.39762188e+04 1.39514355e+04 1.42595645e+04 1.38264688e+04 1.33216777e+04 1.35049785e+04 1.39284482e+04 1.43196611e+04 1.44582158e+04 1.40282236e+04 1.33249102e+04 1.36328232e+04 1.40928711e+04 1.39736318e+04 1.43153770e+04 1.42646982e+04 1.37568857e+04 1.41624814e+04 1.43076904e+04 1.39905107e+04 1.41580488e+04 1.40252197e+04 1.38540352e+04 1.38676953e+04 1.39690176e+04 1.41380273e+04 1.45553799e+04 1.49185088e+04 1.42627832e+04 1.36719648e+04 1.37754717e+04 1.41729326e+04 1.46439141e+04 1.45377891e+04 1.39036631e+04 1.37318486e+04 1.41563926e+04 1.46194033e+04 1.46905977e+04 1.43382744e+04 1.42443330e+04 1.42199609e+04 1.40852480e+04 1.40181279e+04 1.43745986e+04 1.45800977e+04 1.43886533e+04 1.45550303e+04 1.41050693e+04 1.39877773e+04 1.44473564e+04 1.45466016e+04 1.47240850e+04 1.42201836e+04 1.38252617e+04 1.40223223e+04 1.43675293e+04 1.47106787e+04 1.48127539e+04 1.43646035e+04 1.37689482e+04 1.40442637e+04 1.42726943e+04 1.40577031e+04 1.44149893e+04 1.46771367e+04 1.41901465e+04 1.40218535e+04 1.41466748e+04 1.44371514e+04 1.46420635e+04 1.44150635e+04 1.43817061e+04 1.39090352e+04 1.38208359e+04 1.42925898e+04 1.43386543e+04 1.45406006e+04 1.45589346e+04 1.41072227e+04 1.37499775e+04 1.40757393e+04 1.46087910e+04 1.44260303e+04 1.41740938e+04 1.41412246e+04 1.38981270e+04 1.40038975e+04 1.42439355e+04 1.41655322e+04 1.42379590e+04 1.40914482e+04 1.38454941e+04 1.38049756e+04 1.41909775e+04 1.42774404e+04 1.40853770e+04 1.41952100e+04 1.37855420e+04 1.38941455e+04 1.41167637e+04 1.39751992e+04 1.43193115e+04 1.39889160e+04 1.35269326e+04 1.36288457e+04 1.36197617e+04 1.39231846e+04 1.45064668e+04 1.41897314e+04 1.35585225e+04 1.34877051e+04 1.34852441e+04 1.34450312e+04 1.38405459e+04 1.40062002e+04 1.35709375e+04 1.34562754e+04 1.34494229e+04 1.37215361e+04 1.38777227e+04 1.36857520e+04 1.40700801e+04 1.36920840e+04 1.28444551e+04 1.30764902e+04 1.35725967e+04 1.37584658e+04 1.38445029e+04 1.33505156e+04 1.27002012e+04 1.30768945e+04 1.37212227e+04 1.35722734e+04 1.32857676e+04 1.31732100e+04 1.29272432e+04 1.31606689e+04 1.32713574e+04 1.29720469e+04 1.33855859e+04 1.31921250e+04 1.29902617e+04 1.30528633e+04 1.26597656e+04 1.28150850e+04 1.30662559e+04 1.33689004e+04 1.30433555e+04 1.22933320e+04 1.24279053e+04 1.28053164e+04 1.30302598e+04 1.29281113e+04 1.24885146e+04 1.22871211e+04 1.25215332e+04 1.27565186e+04 1.28140820e+04 1.26988730e+04 1.25272002e+04 1.23756484e+04 1.23924863e+04 1.23487656e+04 1.23042852e+04 1.23870166e+04 1.24026572e+04 1.24571514e+04 1.20380361e+04 1.19487705e+04 1.22777227e+04 1.21631553e+04 1.24088125e+04 1.21688281e+04 1.16058369e+04 1.16307969e+04 1.18581357e+04 1.21888389e+04 1.24098066e+04 1.18574336e+04 1.14437852e+04 1.15631055e+04 1.16992510e+04 1.17122695e+04 1.17022695e+04 1.17321787e+04 1.14128770e+04 1.11862549e+04 1.13398672e+04 1.15083184e+04 1.16681504e+04 1.15246191e+04 1.14843672e+04 1.11398105e+04 1.07654307e+04 1.09679014e+04 1.11517012e+04 1.13915742e+04 1.13319766e+04 1.06798955e+04 1.05600576e+04 1.08826436e+04 1.12379473e+04 1.10214482e+04 1.08276826e+04 1.07634688e+04 1.03610264e+04 1.05879951e+04 1.08600859e+04 1.06120674e+04 1.04841738e+04 1.04038955e+04 1.04635713e+04 1.04273926e+04 1.02980059e+04 1.03537314e+04 1.03693115e+04 1.02541318e+04 9.98054297e+03 1.00290498e+04 1.01175205e+04 1.00573389e+04 1.03250723e+04 1.00086387e+04 9.62136230e+03 9.71199805e+03 9.55703125e+03 9.90214746e+03 1.02200410e+04 9.83112598e+03 9.38347949e+03 9.23959961e+03 9.58216504e+03 9.94364941e+03 9.60849219e+03 9.21243945e+03 1.40655869e+04 1.40297295e+04 2.29393086e+04 1.47948609e+05 -38374660. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 754019136. 1.62608750e+05 2.36723516e+04 9.02182129e+03 8.62030957e+03 7.55005957e+03 6.99986865e+03 6.93314307e+03 7.04645947e+03 6.46725244e+03 6.55689844e+03 6.87195557e+03 6.78234375e+03 6.47364355e+03 6.18089014e+03 6.22143066e+03 6.49360254e+03 6.67196533e+03 6.38149805e+03 6.07363770e+03 6.00702197e+03 6.00282910e+03 6.22161035e+03 6.22560693e+03 5.93228516e+03 5.81110986e+03 5.74150781e+03 5.78763525e+03 5.76560010e+03 5.62079834e+03 5.60583545e+03 5.77410449e+03 5.83380322e+03 5.51099072e+03 5.18310107e+03 5.28635303e+03 5.50382275e+03 5.61785205e+03 5.33335449e+03 5.02515332e+03 5.01068066e+03 5.18320850e+03 5.39182373e+03 5.13593164e+03 4.77403955e+03 4.77822998e+03 4.94518457e+03 4.99767578e+03 4.93985449e+03 4.81489062e+03 4.60472314e+03 4.60726367e+03 4.70010889e+03 4.48006152e+03 4.38787549e+03 4.56766357e+03 4.56433740e+03 4.47134814e+03 4.25731641e+03 4.06465527e+03 4.24719189e+03 4.46025146e+03 4.31968506e+03 4.00078613e+03 3.81973730e+03 3.85437988e+03 4.06578735e+03 4.16617676e+03 3.98958350e+03 3.85430518e+03 3.73489575e+03 3.59668921e+03 3.67381079e+03 3.77499585e+03 3.61965552e+03 3.53750171e+03 3.53608887e+03 3.51308325e+03 3.40227417e+03 3.33476587e+03 3.39449341e+03 3.39435010e+03 3.36678003e+03 3.24867554e+03 3.07034375e+03 3.03193457e+03 3.16075244e+03 3.26358496e+03 3.06589209e+03 2.84941772e+03 2.84744287e+03 2.91061084e+03 2.94333887e+03 2.92926782e+03 2.78858740e+03 2.71912964e+03 2.68003687e+03 2.67144336e+03 2.68197168e+03 2.59811157e+03 2.54302905e+03 2.49374146e+03 2.47656714e+03 2.45090527e+03 2.38764966e+03 2.37576050e+03 2.36193945e+03 2.35421826e+03 2.26022949e+03 2.13011060e+03 2.13428271e+03 2.21103125e+03 2.21986621e+03 2.07936597e+03 1.94696667e+03 1.92186987e+03 2.00251636e+03 2.06267383e+03 1.94532117e+03 1.81652844e+03 1.81408740e+03 1.77935571e+03 1.76601233e+03 1.75141321e+03 1.69340820e+03 1.69596936e+03 1.65116052e+03 1.60444983e+03 1.58230103e+03 1.51253589e+03 1.51748987e+03 1.54535864e+03 1.50821704e+03 1.42408105e+03 1.35073267e+03 1.32587183e+03 1.34937866e+03 1.37820618e+03 1.29294995e+03 1.19816675e+03 1.19045154e+03 1.21937341e+03 1.22735437e+03 1.15502185e+03 1.09405481e+03 1.07855493e+03 1.05086780e+03 1.04671289e+03 1.02927197e+03 9.61384338e+02 9.34833496e+02 9.44662842e+02 9.32920288e+02 8.95850525e+02 8.52180481e+02 8.32070129e+02 8.20256653e+02 8.20853271e+02 7.81364502e+02 7.19442627e+02 7.06939392e+02 7.05342834e+02 6.96078003e+02 6.73107239e+02 6.29990234e+02 6.06933411e+02 5.97571106e+02 5.90507568e+02 5.69282043e+02 5.35933533e+02 5.24320496e+02 5.06903107e+02 4.87670471e+02 4.68067841e+02 4.39771423e+02 4.31355042e+02 4.29713654e+02 4.15192810e+02 3.84099426e+02 3.53313782e+02 3.40705933e+02 3.41330017e+02 3.39217377e+02 3.11193970e+02 2.81059387e+02 2.70713043e+02 2.65743530e+02 2.58848846e+02 2.45738144e+02 2.23996155e+02 2.10076065e+02 2.02385162e+02 1.92405075e+02 1.80880768e+02 1.68683578e+02 1.58894760e+02 1.46793472e+02 1.38050278e+02 1.29336395e+02 1.18608688e+02 1.10632965e+02 1.02770103e+02 9.52256317e+01 8.43463669e+01 7.55187759e+01 7.14498749e+01 6.71913834e+01 6.09285812e+01 5.23873634e+01 4.46383820e+01 3.96133537e+01 3.66233788e+01 3.33246117e+01 2.80054531e+01 2.28604221e+01 1.88430653e+01 1.56553812e+01 1.32964878e+01 1.09692411e+01 8.46742725e+00 6.42500687e+00 4.85650301e+00 3.62756824e+00 2.73945928e+00 2.23907471e+00 2.08478618e+00 2.27714944e+00 2.83111477e+00 3.70178366e+00 4.77807665e+00 6.39206409e+00 8.52080250e+00 1.08326969e+01 1.35040817e+01 1.63438168e+01 1.99880314e+01 2.38606243e+01 2.68601131e+01 3.02433186e+01 3.54684372e+01 4.24480667e+01 4.93446655e+01 5.43191528e+01 5.73163643e+01 6.21340790e+01 7.03255234e+01 8.08398056e+01 9.07372208e+01 9.70384521e+01 1.00255600e+02 1.08069405e+02 1.23270523e+02 1.32927826e+02 1.35895767e+02 1.45145447e+02 1.58443466e+02 1.69022766e+02 1.85318359e+02 1.92363678e+02 1.97717026e+02 2.14662033e+02 2.21014023e+02 2.39412674e+02 2.60744812e+02 2.60469574e+02 2.78280060e+02 3.02273224e+02 3.09125336e+02 3.22081970e+02 3.37090485e+02 3.53877167e+02 3.73664917e+02 3.84882690e+02 3.88042816e+02 4.07990417e+02 4.45461700e+02 4.72414429e+02 4.78855835e+02 4.77912720e+02 4.84252014e+02 5.12058533e+02 5.55768677e+02 5.89806335e+02 5.97699280e+02 5.86128967e+02 6.04896240e+02 6.50360046e+02 6.68674683e+02 6.79104980e+02 7.00224060e+02 7.24063049e+02 7.46078064e+02 7.97433899e+02 8.01791565e+02 7.94271973e+02 8.33466187e+02 8.35993835e+02 8.91966858e+02 9.42332642e+02 9.35552551e+02 9.92136841e+02 9.94489014e+02 9.77124939e+02 1.03371777e+03 1.03957849e+03 1.08742126e+03 1.18568579e+03 1.15249231e+03 1.11756714e+03 1.16854248e+03 1.24460571e+03 1.31614099e+03 1.32753345e+03 1.28526050e+03 1.26588684e+03 1.32406482e+03 1.43473743e+03 1.51146985e+03 1.50786292e+03 1.46202014e+03 1.47465430e+03 1.56651099e+03 1.62410828e+03 1.59859973e+03 1.60755005e+03 1.66854407e+03 1.71112915e+03 1.78985254e+03 1.82473352e+03 1.78259302e+03 1.82128943e+03 1.85118262e+03 1.87998804e+03 1.96026477e+03 1.98739685e+03 2.06522778e+03 2.05553442e+03 2.01462537e+03 2.10823169e+03 2.09269434e+03 2.17412280e+03 2.36832983e+03 2.29196826e+03 2.16897852e+03 2.24648511e+03 2.40179858e+03 2.51230957e+03 2.56279370e+03 2.47521558e+03 2.39390210e+03 2.47000513e+03 2.64352271e+03 2.80623169e+03 2.75320630e+03 2.63054102e+03 2.63945239e+03 2.75540894e+03 2.87572583e+03 3.00696948e+03 3.01590820e+03 2.88460620e+03 2.88784863e+03 3.05476001e+03 3.14006909e+03 3.13777979e+03 3.16653174e+03 3.16163013e+03 3.17331030e+03 3.36428955e+03 3.42852441e+03 3.29255225e+03 3.33143921e+03 3.44839722e+03 3.50546387e+03 3.55477930e+03 3.56115430e+03 3.67096313e+03 3.75420337e+03 3.68629907e+03 3.67106177e+03 3.66725781e+03 3.84917944e+03 4.08828979e+03 4.06784009e+03 3.89817090e+03 3.84363135e+03 4.03530835e+03 4.29115088e+03 4.19339111e+03 4.03038477e+03 4.14126318e+03 4.30764746e+03 4.44582666e+03 4.61357715e+03 4.58283838e+03 4.37883838e+03 4.29787793e+03 4.49033643e+03 4.76817871e+03 4.79603076e+03 4.68926465e+03 4.72802979e+03 4.78012061e+03 4.92002588e+03 4.92410889e+03 4.83046680e+03 4.90466162e+03 4.91267773e+03 5.19305078e+03 5.34556055e+03 5.18637207e+03 5.20628662e+03 5.28534229e+03 5.46254150e+03 5.38333057e+03 5.18473730e+03 5.43882129e+03 5.81540137e+03 5.65483838e+03 5.41471387e+03 5.57724023e+03 5.94379980e+03 5.92191211e+03 5.87914551e+03 5.89710742e+03 5.77659326e+03 5.78411572e+03 6.19113525e+03 6.24874854e+03 6.04206885e+03 5.93719873e+03 5.96648730e+03 6.31191162e+03 6.65053174e+03 6.42400098e+03 6.26807080e+03 6.44305811e+03 6.48792969e+03 6.77990918e+03 6.81463623e+03 6.48262842e+03 6.51229346e+03 6.69610010e+03 6.80933887e+03 6.91961035e+03 6.92793018e+03 7.13012744e+03 7.11531152e+03 6.88801318e+03 6.97125195e+03 6.93855811e+03 7.27829150e+03 7.64854395e+03 7.51205176e+03 7.21446533e+03 7.18685400e+03 7.77842041e+03 7.94631641e+03 7.94423242e+03 8.97184570e+03 1.03443037e+04 1.37000312e+04 1.17200852e+05 15472212. 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. 0. 0. 0. 0. 0. 0. -81713512. 1.93474547e+05 2.43688770e+04 1.30902793e+04 1.09052764e+04 1.07973652e+04 1.03111309e+04 9.88236621e+03 9.87604590e+03 9.68580176e+03 1.01541934e+04 1.02470264e+04 1.00705264e+04 1.01874004e+04 1.02523809e+04 1.02380850e+04 1.03275664e+04 1.03198232e+04 1.03501631e+04 1.04286396e+04 1.04332441e+04 1.04818828e+04 1.03102705e+04 1.02599863e+04 1.08210605e+04 1.09477246e+04 1.04137480e+04 1.04495996e+04 1.10252334e+04 1.11733838e+04 1.09347441e+04 1.09741680e+04 1.09378975e+04 1.10028154e+04 1.10360430e+04 1.10536143e+04 1.11488594e+04 1.11471797e+04 1.09479131e+04 1.09528096e+04 1.15170420e+04 1.16263242e+04 1.13727344e+04 1.13872139e+04 1.14677568e+04 1.15560059e+04 1.15074395e+04 1.14856758e+04 1.16202275e+04 1.13311914e+04 1.12486553e+04 1.17521387e+04 1.17685752e+04 1.21290176e+04 1.22573555e+04 1.18890117e+04 1.15612080e+04 1.15307217e+04 1.23307441e+04 1.24827197e+04 1.20345225e+04 1.19194316e+04 1.20481758e+04 1.21537529e+04 1.20989346e+04 1.24928271e+04 1.24917695e+04 1.19059824e+04 1.18923057e+04 1.25699209e+04 1.29137305e+04 1.25858848e+04 1.24557744e+04 1.25208213e+04 1.25272744e+04 1.23866943e+04 1.24199170e+04 1.27095566e+04 1.27480352e+04 1.25324561e+04 1.26161631e+04 1.27847256e+04 1.27779932e+04 1.31373896e+04 1.30921729e+04 1.27515361e+04 1.29417705e+04 1.29274990e+04 1.31003096e+04 1.32520713e+04 1.30665723e+04 1.30437354e+04 1.28447441e+04 1.27109248e+04 1.32919238e+04 1.32796035e+04 1.26822002e+04 1.28776299e+04 1.36555156e+04 1.41270684e+04 1.36768604e+04 1.33178672e+04 1.31726768e+04 1.31365273e+04 1.32916250e+04 1.33059678e+04 1.35243105e+04 1.34774756e+04 1.37243369e+04 1.36867783e+04 1.33804248e+04 1.36662080e+04 1.32849385e+04 1.33319678e+04 1.41521768e+04 1.40481328e+04 1.37196436e+04 1.33880879e+04 1.33005410e+04 1.40817559e+04 1.41862930e+04 1.37584971e+04 1.34351357e+04 1.34413408e+04 1.38233691e+04 1.38245361e+04 1.42273203e+04 1.43561084e+04 1.39138711e+04 1.37965967e+04 1.38505586e+04 1.41173828e+04 1.41264600e+04 1.39548877e+04 1.37647324e+04 1.37926152e+04 1.41098584e+04 1.37185859e+04 1.37403945e+04 1.45724883e+04 1.45256650e+04 1.41129902e+04 1.37011660e+04 1.37009580e+04 1.45643271e+04 1.45671064e+04 1.41890332e+04 1.38262188e+04 1.37374639e+04 1.42407178e+04 1.41919629e+04 1.41635625e+04 1.39033838e+04 14159. 1.48454053e+04 1.44978398e+04 1.43379502e+04 1.44127988e+04 1.43231797e+04 1.41283389e+04 1.40709727e+04 1.42808271e+04 1.43615801e+04 1.44171787e+04 1.39021299e+04 1.39319961e+04 1.48991963e+04 1.43696553e+04 1.38480752e+04 1.42629844e+04 1.42635273e+04 1.47563066e+04 1.44544834e+04 1.38713086e+04 1.46371611e+04 1.47375732e+04 1.43015635e+04 1.40930078e+04 1.40894658e+04 1.42166328e+04 1.42305957e+04 1.43513496e+04 1.39603135e+04 1.42204180e+04 1.50217852e+04 1.47276904e+04 1.42180283e+04 1.37701826e+04 1.39518867e+04 1.48414707e+04 1.47351719e+04 1.43087041e+04 1.40084746e+04 1.38970195e+04 1.42400371e+04 1.42413486e+04 1.45983848e+04 1.43273242e+04 1.38692246e+04 1.42431387e+04 1.42481484e+04 1.45273965e+04 1.43404971e+04 1.39383584e+04 1.41020547e+04 1.40947207e+04 1.42326357e+04 1.38239883e+04 1.40845391e+04 1.49593350e+04 1.44924375e+04 1.41145996e+04 1.37784814e+04 1.36292529e+04 1.44154512e+04 1.45538564e+04 1.41050059e+04 1.36202783e+04 1.36307119e+04 1.40975820e+04 1.40613154e+04 1.43800771e+04 1.42994307e+04 1.39790527e+04 1.35677227e+04 1.34446738e+04 1.43141846e+04 1.41303867e+04 1.36832100e+04 1.36388203e+04 1.35825537e+04 1.41554307e+04 1.41910244e+04 1.35044199e+04 1.33761318e+04 1.40175645e+04 1.41201201e+04 1.33767568e+04 1.32888262e+04 1.39988574e+04 1.39983740e+04 1.35767627e+04 1.32803115e+04 1.32079678e+04 1.39231211e+04 1.37426855e+04 1.32529590e+04 1.33655977e+04 1.33238467e+04 1.36510625e+04 1.36113945e+04 1.31493613e+04 1.28316484e+04 1.32416602e+04 1.39775264e+04 1.34828711e+04 1.32637236e+04 1.34307969e+04 1.32728633e+04 1.32250361e+04 1.31834775e+04 1.30899160e+04 1.27684570e+04 1.26761406e+04 1.29479609e+04 1.30678750e+04 1.34087480e+04 1.29950557e+04 1.24363760e+04 1.27615176e+04 1.29756055e+04 1.33441934e+04 1.30286709e+04 1.26169707e+04 1.25988027e+04 1.25205010e+04 1.27101777e+04 1.26605850e+04 1.28725742e+04 1.28184375e+04 1.24687158e+04 1.22907617e+04 1.19300918e+04 1.23953184e+04 1.31359219e+04 1.27732920e+04 1.23920361e+04 1.20018008e+04 1.17081826e+04 1.22643672e+04 1.28254961e+04 1.24163809e+04 1.17912217e+04 1.17225547e+04 1.20429912e+04 1.20127158e+04 1.22583555e+04 1.22004160e+04 1.18185078e+04 1.17568027e+04 1.17042305e+04 1.20506973e+04 1.20658682e+04 1.14082656e+04 1.13410752e+04 1.19632988e+04 1.17991172e+04 1.11878965e+04 1.13593477e+04 1.19234746e+04 1.17309160e+04 1.13836045e+04 1.10797158e+04 1.10410020e+04 1.16166953e+04 1.15815850e+04 1.12456924e+04 1.08902715e+04 1.07504072e+04 1.10536211e+04 1.10632842e+04 1.09778203e+04 1.06614629e+04 1.08885352e+04 1.12100195e+04 1.08490586e+04 1.10028008e+04 1.09362637e+04 1.05472510e+04 1.06506123e+04 1.06582393e+04 1.05851543e+04 1.04551172e+04 1.01984580e+04 1.00359355e+04 1.03968604e+04 1.09156875e+04 1.03344971e+04 9.84359277e+03 1.01307812e+04 1.02467920e+04 1.04877500e+04 1.01868633e+04 9.80700977e+03 1.01792500e+04 1.01743438e+04 9.60561816e+03 9.48610547e+03 1.00421533e+04 9.98490137e+03 9.65690332e+03 9.44782129e+03 9.09652734e+03 9.46779199e+03 1.00893379e+04 9.78184277e+03 9.38841016e+03 9.06735840e+03 8.88379297e+03 9.30313086e+03 9.81059277e+03 9.47145898e+03 8.91594043e+03 8.80221289e+03 9.00116504e+03 9.01017676e+03 9.15746387e+03 8.91457324e+03 8.63938965e+03 8.84395801e+03 8.72002539e+03 8.93398730e+03 8.82851270e+03 8.51100195e+03 8.49712793e+03 8.40851172e+03 8.55483691e+03 8.32193750e+03 8.18040527e+03 8.52833203e+03 8.51311230e+03 8.17107373e+03 7.89655176e+03 7.90971582e+03 8.32639648e+03 8.24560254e+03 7.97742871e+03 7.69819189e+03 7.64861670e+03 7.82026416e+03 7.79140967e+03 7.76641992e+03 7.45112549e+03 7.59240771e+03 7.84127100e+03 7.50201807e+03 7.65336523e+03 7.64159863e+03 7.33017773e+03 7.17808545e+03 7.12060498e+03 7.30028711e+03 7.25918896e+03 6.95875342e+03 6.89375049e+03 7.21356836e+03 7.22529980e+03 6.75746094e+03 6.53527637e+03 6.63399268e+03 6.87355322e+03 7.09334961e+03 6.77125000e+03 6.39919922e+03 6.61299756e+03 6.72783691e+03 6.49882861e+03 6.34948975e+03 6.28587695e+03 6.18884131e+03 6.18345020e+03 6.23190674e+03 6.01059912e+03 6.09048145e+03 6.32680225e+03 6.04715088e+03 6.01054150e+03 5.85040576e+03 5.70534570e+03 5.94556055e+03 5.91451270e+03 5.71504346e+03 5.54466211e+03 5.34297803e+03 5.41206836e+03 5.66404834e+03 5.80215088e+03 5.46092725e+03 5.17668213e+03 5.30353223e+03 5.29827637e+03 5.42173633e+03 5.33977930e+03 5.11353564e+03 5.01668945e+03 4.97706836e+03 4.95461230e+03 4.80869531e+03 4.87454883e+03 5.03923730e+03 4.85699268e+03 4.80281885e+03 4.67044775e+03 4.52721875e+03 4.77132178e+03 4.70950586e+03 4.50796094e+03 4.36851660e+03 4.28438818e+03 4.37119580e+03 4.32858936e+03 4.39719873e+03 4.39531543e+03 4.19019531e+03 4.04346948e+03 4.06783960e+03 4.20924805e+03 4.11209912e+03 3.96963330e+03 3.87043115e+03 3.81467407e+03 3.80942310e+03 3.74856079e+03 3.81290698e+03 3.77968384e+03 3.60906079e+03 3.68556152e+03 3.68591089e+03 3.55441626e+03 3.50938989e+03 3.45447852e+03 3.41980078e+03 3.28532739e+03 3.20583057e+03 3.33734277e+03 3.33580225e+03 3.11085205e+03 2.98160669e+03 3.10409399e+03 3.24584180e+03 3.14474048e+03 2.92661743e+03 2.83424536e+03 2.95666455e+03 2.93885596e+03 2.80287231e+03 2.84088062e+03 2.72122534e+03 2.56306763e+03 2.60732495e+03 2.71787012e+03 2.73069702e+03 2.54616675e+03 2.38744385e+03 2.49077881e+03 2.57280444e+03 2.46363501e+03 2.31134497e+03 2.23808521e+03 2.26967603e+03 2.25303467e+03 2.28110034e+03 2.23506958e+03 2.12366870e+03 2.09441895e+03 2.05875757e+03 2.09257715e+03 2.01533936e+03 1.92532910e+03 1.96312158e+03 1.91973267e+03 1.89584766e+03 1.82946973e+03 1.76344690e+03 1.82922046e+03 1.75095288e+03 1.64713098e+03 1.65394543e+03 1.65738184e+03 1.63497327e+03 1.58148376e+03 1.58332092e+03 1.56534570e+03 1.49765698e+03 1.42195154e+03 1.38527100e+03 1.43044275e+03 1.37071057e+03 1.30757092e+03 1.31661438e+03 1.28582263e+03 1.25339758e+03 1.21687842e+03 1.22008350e+03 1.18301099e+03 1.11922314e+03 1.13254224e+03 1.11048682e+03 1.07040125e+03 1.04350110e+03 1.01431537e+03 9.76750977e+02 9.28908569e+02 8.90434326e+02 9.11641052e+02 9.39927612e+02 8.66893555e+02 7.92372925e+02 8.05643372e+02 8.34521118e+02 8.01577026e+02 7.36277161e+02 6.96577637e+02 7.13516724e+02 6.93644043e+02 6.49507690e+02 6.55144531e+02 6.32521973e+02 5.80516602e+02 5.60839905e+02 5.70166870e+02 5.65098572e+02 5.20816772e+02 4.81449707e+02 4.81876465e+02 4.91888763e+02 4.64744995e+02 4.25129120e+02 3.97380005e+02 3.98375427e+02 4.00578156e+02 3.72086853e+02 3.46401703e+02 3.34135315e+02 3.22040375e+02 3.06027710e+02 3.00653778e+02 2.80293182e+02 2.58285492e+02 2.51840607e+02 2.39634369e+02 2.32086609e+02 2.14812454e+02 1.97222763e+02 1.92355103e+02 1.76175949e+02 1.65360458e+02 1.61505096e+02 1.49860107e+02 1.38621445e+02 1.27284454e+02 1.22724838e+02 1.14915947e+02 1.02126091e+02 9.16326447e+01 8.46657639e+01 8.23666916e+01 7.24788589e+01 6.31080627e+01 6.57480164e+01 8.49566193e+01 7.58976135e+01 7.07819901e+01 6.33936462e+01 2.39093643e+02 4.78728050e+06 0. 0. 0. 0. 0. 94236312. 94236312. -5244872. -9181428. 2.26183950e+06 -6553048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -14836884. 2.74484528e+02 8.72124939e+01 5.51513634e+01 5.67709160e+01 6.75936127e+01 6.81286163e+01 7.14942245e+01 7.81987686e+01 8.51761017e+01 9.38978195e+01 1.05042084e+02 1.12437744e+02 1.17072357e+02 1.28237701e+02 1.40887024e+02 1.46672363e+02 1.54133545e+02 1.64741379e+02 1.77988724e+02 1.93193024e+02 2.05885193e+02 2.12556015e+02 2.17258209e+02 2.35002747e+02 2.56415588e+02 2.64343842e+02 2.76737213e+02 2.88451965e+02 3.00229279e+02 3.24664917e+02 3.33247467e+02 3.36960358e+02 3.57311890e+02 3.74147400e+02 3.94651855e+02 4.14920990e+02 4.20553192e+02 4.37449707e+02 4.69607086e+02 5.07372986e+02 5.11307159e+02 4.94108093e+02 5.12406311e+02 5.46445129e+02 5.76512817e+02 6.07123596e+02 6.16175537e+02 6.18489868e+02 6.55312744e+02 6.86197021e+02 6.85954651e+02 7.00399902e+02 7.21587219e+02 7.66919006e+02 8.18965210e+02 8.00007141e+02 7.94284668e+02 8.38684082e+02 8.80660645e+02 9.19922058e+02 9.28276611e+02 9.31492065e+02 9.46014832e+02 9.94457336e+02 1.06294202e+03 1.06007202e+03 1.03443091e+03 1.08235742e+03 1.12844824e+03 1.15722998e+03 1.19719666e+03 1.20873511e+03 1.20386353e+03 1.25960962e+03 1.31645398e+03 1.32220642e+03 1.32793518e+03 1.34472095e+03 1.38022363e+03 1.45268079e+03 1.52214624e+03 1.50917041e+03 1.48441467e+03 1.53846716e+03 1.61455200e+03 1.61463147e+03 1.62444373e+03 1.65683972e+03 1.71992078e+03 1.80793970e+03 1.80760498e+03 1.76311987e+03 1.78639209e+03 1.84080371e+03 1.91481787e+03 1.96285815e+03 1.96277112e+03 1.99382629e+03 2.08155957e+03 2.17515820e+03 2.15438159e+03 2.07277148e+03 2.11723975e+03 2.22861450e+03 2.28103784e+03 2.31399268e+03 2.31205542e+03 2.32216089e+03 2.43259009e+03 2.48324780e+03 2.44664551e+03 2.50775391e+03 2.55776050e+03 2.57593970e+03 2.67547021e+03 2.70474390e+03 2.66999438e+03 2.70818896e+03 2.75114062e+03 2.79477905e+03 2.90478589e+03 3.00814404e+03 2.96291064e+03 2.90095020e+03 3.00463306e+03 3.12912109e+03 3.10986987e+03 3.09717725e+03 3.12260791e+03 3.18279712e+03 3.31841382e+03 3.38173706e+03 3.31204468e+03 3.32212988e+03 3.40216772e+03 3.51848804e+03 3.58270874e+03 3.56599609e+03 3.58326904e+03 3.65340845e+03 3.75273511e+03 3.71282080e+03 3.67022168e+03 3.77956299e+03 3.86076782e+03 3.94791943e+03 4.07067847e+03 4.02371387e+03 3.90625903e+03 4.04845386e+03 4.19844775e+03 4.20270605e+03 4.19243066e+03 4.15877197e+03 4.23217725e+03 4.46345459e+03 4.55851562e+03 4.37230176e+03 4.33256396e+03 4.57179346e+03 4.70250928e+03 4.63664795e+03 4.53974512e+03 4.62237256e+03 4.83670801e+03 4.95477246e+03 4.83509180e+03 4.81296094e+03 4.91737061e+03 4.93098486e+03 5.07687305e+03 5.17908984e+03 5.09077002e+03 5.15623096e+03 5.30931592e+03 5.34238086e+03 5.29685645e+03 5.28281055e+03 5.32951514e+03 5.38711230e+03 5.55576367e+03 5.78795850e+03 5.82584717e+03 5.51360156e+03 5.62649951e+03 5.95120264e+03 5.75967676e+03 5.71550684e+03 5.82551367e+03 5.91203613e+03 6.14056982e+03 6.20667969e+03 5.97830859e+03 5.96553125e+03 6.08447021e+03 6.25484375e+03 6.36632910e+03 6.29128027e+03 6.34843311e+03 6.60831055e+03 6.61698730e+03 6.48655713e+03 6.44094678e+03 6.53645654e+03 6.60830127e+03 6.81402246e+03 6.93833789e+03 6.99267285e+03 6.72681641e+03 6.83595996e+03 7.08208643e+03 6.99823828e+03 6.98068945e+03 7.08515820e+03 7.14599023e+03 7.41345898e+03 7.48142627e+03 7.23492920e+03 7.26192432e+03 7.30114062e+03 7.44764941e+03 7.61265381e+03 7.52694629e+03 7.61773779e+03 7.69925342e+03 7.87223682e+03 8.02024756e+03 7.64246484e+03 7.62415723e+03 7.89853906e+03 7.96976855e+03 8.12634277e+03 8.05954004e+03 7.87852881e+03 8.14714648e+03 8.46550293e+03 8.22115527e+03 8.18604150e+03 8.35365723e+03 8.40200586e+03 8.46390039e+03 8.45326855e+03 8.72902051e+03 8.72447754e+03 8.53555371e+03 8.78568652e+03 8.61174219e+03 8.70425586e+03 8.96621191e+03 8.76169141e+03 8.84066699e+03 9.05735742e+03 8.94929395e+03 8.75671973e+03 8.88127832e+03 9.37737305e+03 9.60857617e+03 9.08901758e+03 9.05756055e+03 9.40876172e+03 9.47222656e+03 9.52775293e+03 9.29946484e+03 9.35506738e+03 9.61547949e+03 9.82166992e+03 9.74176270e+03 9.63509570e+03 9.66909570e+03 9.77446582e+03 1.00393604e+04 9.79946875e+03 9.71269531e+03 9.77249512e+03 9.81781348e+03 1.00940088e+04 1.04527568e+04 1.02925215e+04 9.87806738e+03 9.98334375e+03 1.05136426e+04 1.06563838e+04 1.01604590e+04 1.04442471e+04 1.07524590e+04 1.03242109e+04 1.04518936e+04 1.04222666e+04 1.04655273e+04 1.09540771e+04 1.08523799e+04 1.05238867e+04 1.09365791e+04 1.10322109e+04 1.07280732e+04 1.09793809e+04 1.10764141e+04 1.10177441e+04 1.08231768e+04 1.08080557e+04 1.11697559e+04 1.14477871e+04 1.13024600e+04 1.10160400e+04 1.10407139e+04 1.14901680e+04 1.16439258e+04 1.12514990e+04 1.12022656e+04 1.13468613e+04 1.16836777e+04 1.17863330e+04 1.13524277e+04 1.14134238e+04 1.18108633e+04 1.18517871e+04 1.16426084e+04 1.18886885e+04 1.19388525e+04 1.16666582e+04 1.20822451e+04 1.23231113e+04 1.18279600e+04 1.14896973e+04 1.17407305e+04 1.20998350e+04 1.22449658e+04 1.21668135e+04 1.19974971e+04 1.20214180e+04 1.24292666e+04 1.25792041e+04 1.21431084e+04 1.20854541e+04 1.24888467e+04 1.28372148e+04 1.24173008e+04 1.21860518e+04 1.25556299e+04 1.25084570e+04 1.24608545e+04 1.25378398e+04 1.26975156e+04 1.26444590e+04 1.25121895e+04 1.26946133e+04 1.28054414e+04 1.27234326e+04 1.25186709e+04 1.26205371e+04 1.29258008e+04 1.29819316e+04 1.27713281e+04 1.27471055e+04 1.28794248e+04 1.33031738e+04 1.33042500e+04 1.28252598e+04 1.30180488e+04 1.32057705e+04 1.31507598e+04 1.30332578e+04 1.29770195e+04 1.32503594e+04 1.33153359e+04 1.30487637e+04 1.27609912e+04 1.31851914e+04 1.36635303e+04 1.34580654e+04 1.33988574e+04 1.33201982e+04 1.34562773e+04 1.32273672e+04 1.28035176e+04 1.32614170e+04 1.36326396e+04 1.36794355e+04 1.35779258e+04 1.31487061e+04 1.33131074e+04 1.36245537e+04 1.38333672e+04 1.40338750e+04 1.35369619e+04 1.32864805e+04 1.32581875e+04 1.36322871e+04 1.40677061e+04 1.39017891e+04 1.37310986e+04 1.31899072e+04 1.35102227e+04 1.39940264e+04 1.36901191e+04 1.38655879e+04 1.37056748e+04 1.36069619e+04 1.40048193e+04 1.37394375e+04 1.35960312e+04 1.40629092e+04 1.41851484e+04 1.37127510e+04 1.33625088e+04 1.35876689e+04 1.38272803e+04 1.42561201e+04 1.45199902e+04 1.39960029e+04 1.36536455e+04 1.34992295e+04 1.39122119e+04 1.44385566e+04 1.41093525e+04 1.37168271e+04 1.34693584e+04 1.37186318e+04 1.41718779e+04 1.43751904e+04 1.42238311e+04 1.39645137e+04 1.41631494e+04 1.39492842e+04 1.35044580e+04 1.38465537e+04 1.41343320e+04 1.42563340e+04 1.45677031e+04 1.39206328e+04 1.34370088e+04 1.39180264e+04 1.44457139e+04 1.44783047e+04 1.38933848e+04 1.37694668e+04 1.37819492e+04 1.40448467e+04 1.44135273e+04 1.42836426e+04 1.40764990e+04 1.37285264e+04 1.40279111e+04 1.40413154e+04 1.35803223e+04 1.39020801e+04 1.42536318e+04 1.41694043e+04 1.40263145e+04 1.37338848e+04 1.39202314e+04 1.42557471e+04 1.42680283e+04 1.42091602e+04 1.36353672e+04 1.35478027e+04 1.39308828e+04 1.41770205e+04 1.43352666e+04 1.41041729e+04 1.38966270e+04 1.35224678e+04 1.38293838e+04 1.43650459e+04 1.39906406e+04 1.38938887e+04 1.38728145e+04 1.37286191e+04 1.36372676e+04 1.36995410e+04 1.38931572e+04 1.40824199e+04 1.41501162e+04 1.37277500e+04 1.33557461e+04 1.36258467e+04 1.38362148e+04 1.39268047e+04 1.40302783e+04 1.36460391e+04 1.36574648e+04 1.35843389e+04 1.36739482e+04 1.40676934e+04 1.36991621e+04 1.36090176e+04 1.35109561e+04 1.31670977e+04 1.33966211e+04 1.40829375e+04 1.39383750e+04 1.33681816e+04 1.35405391e+04 1.33629785e+04 1.29792695e+04 1.33377480e+04 1.35823887e+04 1.35101582e+04 1.34873633e+04 1.31368955e+04 1.31951816e+04 1.34408223e+04 1.35263877e+04 1.39305791e+04 1.35187012e+04 1.27378945e+04 1.27268398e+04 1.32120732e+04 1.34850264e+04 1.33788115e+04 1.31475928e+04 1.26176670e+04 1.28699512e+04 1.34245225e+04 1.31663408e+04 1.30461826e+04 1.28296074e+04 1.27753105e+04 1.30805996e+04 1.27723701e+04 1.26441621e+04 1.32440225e+04 1.32584111e+04 1.29353760e+04 1.25490684e+04 1.21641338e+04 1.24549932e+04 1.29132529e+04 1.32229307e+04 1.29197695e+04 1.22120107e+04 1.20449512e+04 1.24705654e+04 1.27897158e+04 1.25468281e+04 1.23651670e+04 1.20706904e+04 1.21499180e+04 1.24351807e+04 1.25425127e+04 1.25294756e+04 1.22864961e+04 1.23342256e+04 1.21507070e+04 1.17851406e+04 1.19516455e+04 1.21649258e+04 1.22315830e+04 1.24229375e+04 1.18971582e+04 1.15272393e+04 1.18365518e+04 1.20152812e+04 1.22377178e+04 1.20352080e+04 1.14802080e+04 1.13487900e+04 1.16422422e+04 1.20416631e+04 1.20431719e+04 1.16194590e+04 1.13825586e+04 1.13574043e+04 1.12666924e+04 1.13184014e+04 1.15474619e+04 1.16252461e+04 1.13544248e+04 1.10381738e+04 1.09145625e+04 1.11161426e+04 1.14000361e+04 1.14455938e+04 1.13084893e+04 1.08861709e+04 1.05287744e+04 1.07230078e+04 1.10545430e+04 1.12205850e+04 1.10706152e+04 1.05440098e+04 1.02871602e+04 1.06565215e+04 1.10489160e+04 1.06858877e+04 1.06454912e+04 1.05207461e+04 1.01848867e+04 1.04200938e+04 1.05637646e+04 1.03872676e+04 1.02391348e+04 1.03240664e+04 1.03246953e+04 1.00624424e+04 1.00861934e+04 1.00984980e+04 1.02792939e+04 1.01778789e+04 9.80014062e+03 9.80168066e+03 9.66670508e+03 9.80010352e+03 1.02114766e+04 9.95891113e+03 9.44231055e+03 9.40783789e+03 9.46343164e+03 9.86256543e+03 9.92537793e+03 9.43071680e+03 9.20210840e+03 9.28004688e+03 9.43637598e+03 9.58121973e+03 9.42209180e+03 9.17533008e+03 1.26253994e+04 1.21652471e+04 2.34852754e+04 1.52845422e+05 -38374660. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -42032836. -2279398. 2.62107969e+04 1.90437891e+04 1.18677109e+04 8.83946582e+03 8.80497266e+03 7.16589844e+03 6.47005762e+03 6.51000488e+03 6.79592627e+03 6.65013379e+03 6.34556592e+03 6.17484766e+03 6.02298584e+03 6.28730176e+03 6.58326855e+03 6.31204346e+03 6.02922949e+03 5.90113672e+03 5.89067773e+03 6.11071631e+03 6.06825391e+03 5.76940967e+03 5.66947607e+03 5.74471924e+03 5.69305762e+03 5.52264551e+03 5.51011816e+03 5.59835059e+03 5.70789990e+03 5.68718359e+03 5.34039795e+03 5.04750635e+03 5.18045264e+03 5.43252637e+03 5.52510449e+03 5.26201221e+03 4.97784082e+03 4.86103711e+03 5.04205566e+03 5.27451074e+03 5.04396631e+03 4.72216113e+03 4.71019873e+03 4.90102637e+03 4.82425537e+03 4.69048193e+03 4.67481104e+03 4.57536279e+03 4.61372656e+03 4.60212256e+03 4.32522021e+03 4.30685449e+03 4.47558936e+03 4.53869922e+03 4.41423730e+03 4.15567139e+03 3.98078149e+03 4.15132861e+03 4.38489062e+03 4.23078174e+03 3.97685327e+03 3.79398950e+03 3.72569092e+03 3.92128882e+03 4.09077100e+03 3.91821484e+03 3.78879932e+03 3.70555518e+03 3.58007764e+03 3.60124707e+03 3.66583740e+03 3.52578247e+03 3.42478320e+03 3.52305444e+03 3.41926440e+03 3.23753857e+03 3.25487695e+03 3.37200391e+03 3.37695996e+03 3.29871899e+03 3.17541772e+03 3.03539404e+03 2.95796289e+03 3.06830859e+03 3.19797437e+03 3.03408423e+03 2.81038330e+03 2.77705908e+03 2.85111084e+03 2.91785425e+03 2.87852393e+03 2.71484082e+03 2.63818384e+03 2.67509668e+03 2.62796436e+03 2.56966504e+03 2.54828467e+03 2.49935962e+03 2.49344507e+03 2.44363892e+03 2.33697803e+03 2.32031592e+03 2.35709766e+03 2.35558936e+03 2.31343579e+03 2.22036743e+03 2.10795361e+03 2.08793750e+03 2.16822827e+03 2.16410083e+03 2.03532690e+03 1.93418079e+03 1.88137415e+03 1.94056726e+03 2.02279712e+03 1.92447119e+03 1.78411108e+03 1.76045752e+03 1.77373230e+03 1.74284717e+03 1.67417639e+03 1.64633887e+03 1.68184399e+03 1.66083350e+03 1.57934973e+03 1.50565479e+03 1.47413623e+03 1.50743896e+03 1.53727844e+03 1.47542236e+03 1.39332458e+03 1.33621716e+03 1.28760022e+03 1.31324500e+03 1.35374011e+03 1.27918445e+03 1.19211841e+03 1.16010315e+03 1.18223645e+03 1.20517822e+03 1.14210620e+03 1.07956848e+03 1.05488989e+03 1.04393359e+03 1.03242749e+03 9.99981506e+02 9.49849304e+02 9.15898499e+02 9.30806885e+02 9.20346008e+02 8.64963318e+02 8.23816772e+02 8.15661011e+02 8.14281921e+02 8.10479431e+02 7.72156738e+02 7.10548828e+02 6.92995422e+02 6.98640503e+02 6.82623901e+02 6.53141968e+02 6.23824646e+02 5.99832703e+02 5.83923401e+02 5.76368164e+02 5.50137268e+02 5.21437256e+02 5.19496155e+02 5.10328156e+02 4.80429321e+02 4.49926849e+02 4.32283112e+02 4.28767365e+02 4.25141571e+02 4.06535065e+02 3.78359497e+02 3.50783783e+02 3.32963776e+02 3.33024963e+02 3.34553833e+02 3.09226135e+02 2.78402649e+02 2.64757385e+02 2.62067047e+02 2.57757080e+02 2.42050339e+02 2.22921951e+02 2.09106049e+02 1.98517014e+02 1.86519516e+02 1.76266693e+02 1.67435043e+02 1.56730820e+02 1.47416840e+02 1.37028305e+02 1.24914871e+02 1.16717545e+02 1.11016418e+02 1.03892479e+02 9.54774933e+01 8.40340805e+01 7.50204773e+01 7.16616669e+01 6.78832092e+01 6.03700142e+01 5.24863243e+01 4.56155891e+01 3.99109116e+01 3.69011040e+01 3.40288239e+01 2.88231506e+01 2.35842133e+01 1.98297863e+01 1.71269798e+01 1.44868374e+01 1.18881702e+01 9.59835815e+00 7.68042088e+00 6.13099432e+00 4.91059971e+00 4.04800272e+00 3.56506777e+00 3.41208220e+00 3.60107493e+00 4.15288591e+00 5.00989676e+00 6.07665968e+00 7.55696869e+00 9.62081337e+00 1.21185427e+01 1.47073078e+01 1.73268108e+01 2.09420643e+01 2.47731609e+01 2.76686287e+01 3.09968395e+01 3.61991997e+01 4.30003967e+01 4.97465477e+01 5.46733398e+01 5.75489807e+01 6.20538216e+01 6.99304504e+01 8.05878601e+01 9.10088348e+01 9.68373718e+01 9.94320450e+01 1.07146965e+02 1.22593063e+02 1.31839447e+02 1.35399277e+02 1.44832474e+02 1.55524765e+02 1.65891357e+02 1.82711487e+02 1.90308075e+02 1.95711121e+02 2.11312210e+02 2.18233780e+02 2.36832214e+02 2.56419525e+02 2.56152252e+02 2.74887238e+02 2.97131927e+02 3.03040192e+02 3.16878815e+02 3.33266724e+02 3.48760925e+02 3.65527557e+02 3.78887238e+02 3.83990570e+02 4.00797943e+02 4.36935242e+02 4.65932648e+02 4.72164368e+02 4.68080475e+02 4.75203003e+02 5.04787048e+02 5.47201416e+02 5.78257629e+02 5.86349243e+02 5.74058350e+02 5.95939819e+02 6.39305176e+02 6.53974548e+02 6.69349792e+02 6.91808716e+02 7.11253479e+02 7.32300232e+02 7.83721924e+02 7.86486023e+02 7.78963989e+02 8.21213440e+02 8.26503113e+02 8.77796265e+02 9.20332275e+02 9.14667114e+02 9.75164734e+02 9.74567200e+02 9.59027039e+02 1.01675000e+03 1.02134711e+03 1.06372791e+03 1.16390247e+03 1.13321631e+03 1.09463770e+03 1.14081189e+03 1.21924695e+03 1.29823328e+03 1.30475989e+03 1.26275244e+03 1.24467834e+03 1.30380884e+03 1.40403223e+03 1.47681165e+03 1.47838000e+03 1.43602576e+03 1.45405713e+03 1.53027808e+03 1.57576135e+03 1.57878308e+03 1.59229688e+03 1.63640039e+03 1.68130566e+03 1.75678882e+03 1.79064587e+03 1.73517383e+03 1.76879077e+03 1.82148486e+03 1.86074121e+03 1.92200122e+03 1.94683630e+03 2.03503088e+03 2.01995105e+03 1.97889099e+03 2.06990698e+03 2.04947314e+03 2.13487476e+03 2.31779517e+03 2.24504712e+03 2.13912842e+03 2.20761499e+03 2.35865967e+03 2.46847363e+03 2.50889062e+03 2.41408569e+03 2.34933496e+03 2.43002637e+03 2.59520044e+03 2.72766113e+03 2.69249805e+03 2.57941333e+03 2.59579980e+03 2.71664307e+03 2.81516724e+03 2.94007080e+03 2.97282642e+03 2.82528174e+03 2.83351147e+03 3.03519189e+03 3.10132056e+03 3.01010400e+03 3.05335303e+03 3.13408691e+03 3.14965161e+03 3.29815039e+03 3.36160547e+03 3.22612231e+03 3.25918018e+03 3.39006958e+03 3.42842529e+03 3.48178125e+03 3.47004834e+03 3.58936304e+03 3.71161011e+03 3.67249170e+03 3.60467090e+03 3.57009644e+03 3.75298340e+03 4.00766382e+03 3.98156909e+03 3.82595020e+03 3.75606641e+03 3.92738062e+03 4.20322754e+03 4.14743311e+03 3.96887695e+03 4.04209912e+03 4.20505420e+03 4.35613086e+03 4.55403369e+03 4.48650635e+03 4.29104980e+03 4.21875146e+03 4.40109277e+03 4.65920020e+03 4.71199609e+03 4.62585938e+03 4.63694238e+03 4.68312256e+03 4.84174121e+03 4.86542090e+03 4.80818652e+03 4.79833545e+03 4.75988135e+03 5.04904150e+03 5.26847656e+03 5.08574902e+03 5.14354785e+03 5.21609521e+03 5.36160986e+03 5.28804248e+03 5.08208936e+03 5.32193359e+03 5.69105762e+03 5.59346582e+03 5.35765527e+03 5.43238770e+03 5.78920117e+03 5.83844092e+03 5.71809131e+03 5.76967773e+03 5.63408105e+03 5.65086182e+03 6.08057812e+03 6.14454492e+03 5.94611426e+03 5.82841309e+03 5.85954785e+03 6.16451465e+03 6.47880127e+03 6.27568115e+03 6.17950098e+03 6.35376025e+03 6.39395410e+03 6.62437549e+03 6.66235596e+03 6.35913623e+03 6.39783545e+03 6.62656738e+03 6.68072510e+03 6.76968115e+03 6.76406885e+03 6.98984961e+03 6.96961963e+03 6.75426416e+03 6.91333691e+03 6.89196484e+03 7.11795947e+03 7.47858789e+03 7.35842090e+03 7.13099121e+03 7.11792529e+03 7.57658154e+03 7.70865771e+03 7.65301318e+03 8.17809033e+03 9.47308496e+03 1.02337881e+04 6.21556680e+04 -9298881. 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. 0. 0. 0. 0. 0. 0. 0. 81189112. 1.56236141e+05 2.88965000e+04 1.73916289e+04 1.68087324e+04 1.52593037e+04 1.23089873e+04 1.25323682e+04 1.02433174e+04 1.03330635e+04 1.00446943e+04 9.79905957e+03 1.01218467e+04 1.02126084e+04 9.98521094e+03 1.00757119e+04 1.01269385e+04 1.01442520e+04 1.02230830e+04 1.02479316e+04 1.02359551e+04 1.01217881e+04 1.01564248e+04 1.05997256e+04 1.06992158e+04 1.02595137e+04 1.02521699e+04 1.08389648e+04 1.09613105e+04 1.07369424e+04 1.07459365e+04 1.06945439e+04 1.07852148e+04 1.08410137e+04 1.08448975e+04 1.09012803e+04 1.08900029e+04 1.07440244e+04 1.07844307e+04 1.12642891e+04 1.13354316e+04 1.11202236e+04 1.11656836e+04 1.12668096e+04 1.13272666e+04 1.12992402e+04 1.12810957e+04 1.13474453e+04 1.11179033e+04 1.11518359e+04 1.14416377e+04 1.14242393e+04 1.18757500e+04 1.20475117e+04 1.16744902e+04 1.13149521e+04 1.12692031e+04 1.20968408e+04 1.22209639e+04 1.17711572e+04 1.16764297e+04 1.17982197e+04 1.18205059e+04 1.17428926e+04 1.23189707e+04 1.23056582e+04 1.16113643e+04 1.16221816e+04 1.22791172e+04 1.27566816e+04 1.24660322e+04 1.22045488e+04 1.23399863e+04 1.22979883e+04 1.22045449e+04 1.22786377e+04 1.24777676e+04 1.24407734e+04 1.22267188e+04 1.22839805e+04 1.25575645e+04 1.25150391e+04 1.28609248e+04 1.27618760e+04 1.23856387e+04 1.26239160e+04 1.26639912e+04 1.29492012e+04 1.30801787e+04 1.28611279e+04 1.27917520e+04 1.25383096e+04 1.23518877e+04 1.29913281e+04 1.31871396e+04 1.25176240e+04 1.26307383e+04 1.34177168e+04 1.37964316e+04 1.33990439e+04 1.30444795e+04 1.30395566e+04 1.30667998e+04 1.29557402e+04 1.29500078e+04 1.32472500e+04 1.32391553e+04 1.34315537e+04 1.33343369e+04 1.30880869e+04 1.33696396e+04 1.30091133e+04 1.32397930e+04 1.40070723e+04 1.37491748e+04 1.34441094e+04 1.30762480e+04 1.30117969e+04 1.38213857e+04 1.39504336e+04 1.34771182e+04 1.31364258e+04 1.31811426e+04 1.35287344e+04 1.35268311e+04 1.39440312e+04 1.40697168e+04 1.36328789e+04 1.34013330e+04 1.34594619e+04 1.39671260e+04 1.39729639e+04 1.36943838e+04 1.34223438e+04 1.34229414e+04 1.37911328e+04 1.34263281e+04 1.35858252e+04 1.44737324e+04 1.42663154e+04 1.38344941e+04 1.34638584e+04 1.34195273e+04 1.42697031e+04 1.43340068e+04 1.39194453e+04 1.35203604e+04 1.34577207e+04 1.39615537e+04 1.39414883e+04 1.38781787e+04 1.35963945e+04 1.38399131e+04 1.44310977e+04 1.40903457e+04 1.41695244e+04 1.43150889e+04 1.40527314e+04 1.36917783e+04 1.36912402e+04 1.40288164e+04 1.40631602e+04 1.41157031e+04 1.36328350e+04 1.37708379e+04 1.47070117e+04 1.41092061e+04 1.36131250e+04 1.40103486e+04 1.40055332e+04 1.44076533e+04 1.41657900e+04 1.36422969e+04 1.43330674e+04 1.44357383e+04 1.40594824e+04 1.40000283e+04 1.39427783e+04 1.37880010e+04 1.38017051e+04 1.40638135e+04 1.36674658e+04 1.39298311e+04 1.48108770e+04 1.45126729e+04 1.38119238e+04 1.33513799e+04 1.37836152e+04 1.46790742e+04 1.44250020e+04 1.40066455e+04 1.37343340e+04 1.36230908e+04 1.39769062e+04 1.39603564e+04 1.42939688e+04 1.40682598e+04 1.35792920e+04 1.39470391e+04 1.40015254e+04 1.42487783e+04 1.41457480e+04 1.37984277e+04 1.37278984e+04 1.37152324e+04 1.39833350e+04 1.36020020e+04 1.38073281e+04 1.45765791e+04 1.42265957e+04 1.38672197e+04 1.34987803e+04 1.33989180e+04 1.41278701e+04 1.42368623e+04 1.38330381e+04 1.33842627e+04 1.33959404e+04 1.38043262e+04 1.37742891e+04 1.41166748e+04 1.40414033e+04 1.37001621e+04 1.32599756e+04 1.31983428e+04 1.40706787e+04 1.39140322e+04 1.34706221e+04 1.33289062e+04 1.32632031e+04 1.38646123e+04 1.39466436e+04 1.32289072e+04 1.31139971e+04 1.38111055e+04 1.38076504e+04 1.30969111e+04 1.30352676e+04 1.37432393e+04 1.37499287e+04 1.32857080e+04 1.29709072e+04 1.29022109e+04 1.36920449e+04 1.35762168e+04 1.30702178e+04 1.30908379e+04 1.29466270e+04 1.31433369e+04 1.32218740e+04 1.30520039e+04 1.27120596e+04 1.29954082e+04 1.35599941e+04 1.31015225e+04 1.31693369e+04 1.32970918e+04 1.29728379e+04 1.29885430e+04 1.29354180e+04 1.28051221e+04 1.25412705e+04 1.24640879e+04 1.27174941e+04 1.27702969e+04 1.31265205e+04 1.27114287e+04 1.22853779e+04 1.25846641e+04 1.26324521e+04 1.30038984e+04 1.27546855e+04 1.23503496e+04 1.23667607e+04 1.22936191e+04 1.24625654e+04 1.24067539e+04 1.26629814e+04 1.25062461e+04 1.21231504e+04 1.21868145e+04 1.17814629e+04 1.21501279e+04 1.28609629e+04 1.25117803e+04 1.20949404e+04 1.17364414e+04 1.15871660e+04 1.21296318e+04 1.24671035e+04 1.20783242e+04 1.15836982e+04 1.15415664e+04 1.18531025e+04 1.17545049e+04 1.19773975e+04 1.18620430e+04 1.14831846e+04 1.16331387e+04 1.15648145e+04 1.18663076e+04 1.18573574e+04 1.11689502e+04 1.11299814e+04 1.17342041e+04 1.14887266e+04 1.08704443e+04 1.11954893e+04 1.17813311e+04 1.15123809e+04 1.11538223e+04 1.08617637e+04 1.08487080e+04 1.14013789e+04 1.13337939e+04 1.10076494e+04 1.06999531e+04 1.05753574e+04 1.08704727e+04 1.08618057e+04 1.07608740e+04 1.04995234e+04 1.06937822e+04 1.09827812e+04 1.06693564e+04 1.07818711e+04 1.05754473e+04 1.02461650e+04 1.04312998e+04 1.04568008e+04 1.04208330e+04 1.02605498e+04 1.01347041e+04 9.90515039e+03 1.01307148e+04 1.07367314e+04 1.01160674e+04 9.59836719e+03 9.83410449e+03 1.01403301e+04 1.03513828e+04 1.00082754e+04 9.72061328e+03 9.90186230e+03 9.90183887e+03 9.45427148e+03 9.30558398e+03 9.79984082e+03 9.72525098e+03 9.36262305e+03 9.37219629e+03 9.02112598e+03 9.28274023e+03 9.84410938e+03 9.53572949e+03 9.22549512e+03 8.91459082e+03 8.76294336e+03 9.20301562e+03 9.64282324e+03 9.25190820e+03 8.73388965e+03 8.64502344e+03 8.81095215e+03 8.79753809e+03 9.01595020e+03 8.73526953e+03 8.44514355e+03 8.66911523e+03 8.55151367e+03 8.74729102e+03 8.62816992e+03 8.22757422e+03 8.47660840e+03 8.42012207e+03 8.27152734e+03 7.99860010e+03 8.05617188e+03 8.45642383e+03 8.30166309e+03 7.91018359e+03 7.70744141e+03 7.86591016e+03 8.24565430e+03 8.10146387e+03 7.80840381e+03 7.52669287e+03 7.45357617e+03 7.64512988e+03 7.63393408e+03 7.59510645e+03 7.31879492e+03 7.43645508e+03 7.62866309e+03 7.36235156e+03 7.49690576e+03 7.41259277e+03 7.17628857e+03 7.16156055e+03 7.12366357e+03 7.03804541e+03 6.97165967e+03 6.85689062e+03 6.81245361e+03 7.03537354e+03 6.98340186e+03 6.62156250e+03 6.47594092e+03 6.56748438e+03 6.72297998e+03 6.89101270e+03 6.61332764e+03 6.21759961e+03 6.42208594e+03 6.65894824e+03 6.48180127e+03 6.14807373e+03 6.11278223e+03 6.15063867e+03 6.12813330e+03 6.10080566e+03 5.90201611e+03 5.98294629e+03 6.19726709e+03 6.00719092e+03 5.84948779e+03 5.67223340e+03 5.66485645e+03 5.87105615e+03 5.79848486e+03 5.64016016e+03 5.45592676e+03 5.24958838e+03 5.30826660e+03 5.55914014e+03 5.71095312e+03 5.33453662e+03 5.06019336e+03 5.15481299e+03 5.22018994e+03 5.36770801e+03 5.20200195e+03 4.95222510e+03 4.99930908e+03 4.93502344e+03 4.87456152e+03 4.72065869e+03 4.74585010e+03 4.92989844e+03 4.80937158e+03 4.68943311e+03 4.53610107e+03 4.48029248e+03 4.67741064e+03 4.64033936e+03 4.45687451e+03 4.29317920e+03 4.21474609e+03 4.29534229e+03 4.24406055e+03 4.32479248e+03 4.32564893e+03 4.06877051e+03 3.93471777e+03 4.03740430e+03 4.15181689e+03 3.98324463e+03 3.88010352e+03 3.82228394e+03 3.77606592e+03 3.70813281e+03 3.59196948e+03 3.69917261e+03 3.72459448e+03 3.57036768e+03 3.60325244e+03 3.58834595e+03 3.50885034e+03 3.46631567e+03 3.39410083e+03 3.35346240e+03 3.23548438e+03 3.15260474e+03 3.25399414e+03 3.28464722e+03 3.09765942e+03 2.92988843e+03 3.02012354e+03 3.15874585e+03 3.10218140e+03 2.90565332e+03 2.76191724e+03 2.86348975e+03 2.93029395e+03 2.82389160e+03 2.77173169e+03 2.63870776e+03 2.50906226e+03 2.57198145e+03 2.69544727e+03 2.65636548e+03 2.46889014e+03 2.35544263e+03 2.46178784e+03 2.51458960e+03 2.40281348e+03 2.25980249e+03 2.17120044e+03 2.20996997e+03 2.21458813e+03 2.23299829e+03 2.23126514e+03 2.12030322e+03 2.03262854e+03 2.00565662e+03 2.05666895e+03 1.97080701e+03 1.88729980e+03 1.93755737e+03 1.89986267e+03 1.84580591e+03 1.77005383e+03 1.73638757e+03 1.80235303e+03 1.71446423e+03 1.60001245e+03 1.61211951e+03 1.64133826e+03 1.61726318e+03 1.54874036e+03 1.55324719e+03 1.53715417e+03 1.46628552e+03 1.39271265e+03 1.35584656e+03 1.40798596e+03 1.35319238e+03 1.28218079e+03 1.29526111e+03 1.26123474e+03 1.22547180e+03 1.18499402e+03 1.18498682e+03 1.16870154e+03 1.11314734e+03 1.10161353e+03 1.07914209e+03 1.06044971e+03 1.03457715e+03 9.94999268e+02 9.53773804e+02 9.02455811e+02 8.83029602e+02 9.06628357e+02 9.25343994e+02 8.51855103e+02 7.77536926e+02 7.85210571e+02 8.10048218e+02 7.92410583e+02 7.30096741e+02 6.77421570e+02 6.93044495e+02 6.87752869e+02 6.44205994e+02 6.46054016e+02 6.16782654e+02 5.63205811e+02 5.58136658e+02 5.71358276e+02 5.53036316e+02 5.08018707e+02 4.71054413e+02 4.73192322e+02 4.85933624e+02 4.57128357e+02 4.16732574e+02 3.90204987e+02 3.93195923e+02 3.90520142e+02 3.62975037e+02 3.45146027e+02 3.31258667e+02 3.17447144e+02 3.02238373e+02 2.95426636e+02 2.76673553e+02 2.54844986e+02 2.47958710e+02 2.36539658e+02 2.29006638e+02 2.12004318e+02 1.95208038e+02 1.92184601e+02 1.75093170e+02 1.60311478e+02 1.57026840e+02 1.49770691e+02 1.38666260e+02 1.26304932e+02 1.21620033e+02 1.13964340e+02 1.01705864e+02 9.16026840e+01 8.40996780e+01 8.18264084e+01 7.24474564e+01 6.23084106e+01 6.38093491e+01 7.27984924e+01 6.49144135e+01 1.59639252e+02 1.92353119e+02 -3.85809525e+06 -14028706. 0. 0. 0. 0. 0. 94236312. -7.81941309e+03 4.96526833e+01 4.49329559e+02 2.26183950e+06 -6553048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -103217192. 9.69024841e+02 6.57860107e+01 5.47682991e+01 5.77123489e+01 5.68718300e+01 6.47671432e+01 6.85952606e+01 7.49709015e+01 8.01050262e+01 8.46809464e+01 9.48333740e+01 1.06004395e+02 1.10944252e+02 1.18275002e+02 1.29370178e+02 1.40214340e+02 1.50731140e+02 1.55977966e+02 1.61514877e+02 1.75377258e+02 1.90666595e+02 2.03510849e+02 2.13383591e+02 2.20142227e+02 2.33436859e+02 2.54501678e+02 2.71505615e+02 2.76697937e+02 2.79950104e+02 2.96649994e+02 3.19684326e+02 3.31185455e+02 3.45099487e+02 3.63486694e+02 3.69034241e+02 3.90890991e+02 4.16326660e+02 4.16107697e+02 4.32090546e+02 4.62963196e+02 4.97493042e+02 5.17438416e+02 5.01260193e+02 5.02618500e+02 5.36343872e+02 5.77808716e+02 6.05492859e+02 6.01294312e+02 6.18922668e+02 6.59913635e+02 6.74995178e+02 6.93981812e+02 7.05297729e+02 7.04349548e+02 7.49460388e+02 7.97382385e+02 7.92595764e+02 8.11457886e+02 8.50900513e+02 8.61212402e+02 8.99082397e+02 9.30299500e+02 9.22937744e+02 9.39301025e+02 9.84708130e+02 1.04098547e+03 1.05966248e+03 1.04632690e+03 1.08178931e+03 1.10440527e+03 1.14261987e+03 1.19405408e+03 1.17959192e+03 1.19741052e+03 1.25451099e+03 1.30239844e+03 1.34019958e+03 1.33372815e+03 1.31250330e+03 1.35370447e+03 1.43158984e+03 1.48568823e+03 1.50766943e+03 1.50720520e+03 1.51797607e+03 1.58633496e+03 1.64513379e+03 1.62646484e+03 1.60944080e+03 1.67431287e+03 1.76594031e+03 1.80756580e+03 1.80185400e+03 1.79312598e+03 1.80674805e+03 1.89787976e+03 1.96622437e+03 1.93657507e+03 1.96151746e+03 2.05024487e+03 2.13591870e+03 2.16742163e+03 2.09552832e+03 2.07255127e+03 2.17469263e+03 2.25762085e+03 2.28142822e+03 2.30584204e+03 2.35479419e+03 2.43165576e+03 2.41430054e+03 2.43587378e+03 2.52828638e+03 2.50749756e+03 2.52381494e+03 2.62585107e+03 2.68549854e+03 2.73287573e+03 2.71648975e+03 2.68115015e+03 2.74500708e+03 2.84950928e+03 2.94152100e+03 2.95213159e+03 2.91985620e+03 2.98013403e+03 3.09904077e+03 3.16369922e+03 3.09616138e+03 3.05103833e+03 3.13053906e+03 3.25811035e+03 3.32184033e+03 3.32500439e+03 3.33024316e+03 3.36913184e+03 3.49181958e+03 3.56843896e+03 3.54365479e+03 3.56765601e+03 3.55573218e+03 3.63555322e+03 3.68928735e+03 3.68430225e+03 3.75529150e+03 3.82039551e+03 3.94585400e+03 4.05745020e+03 3.94227051e+03 3.87612476e+03 3.99097729e+03 4.12082129e+03 4.23572656e+03 4.22718604e+03 4.10189600e+03 4.16166553e+03 4.40782520e+03 4.54226172e+03 4.41810938e+03 4.29775635e+03 4.42987109e+03 4.64530908e+03 4.65332178e+03 4.48217090e+03 4.54700732e+03 4.72934668e+03 4.81328613e+03 4.82064990e+03 4.92049219e+03 4.93510596e+03 4.80256885e+03 5.00954248e+03 5.13993799e+03 4.97261475e+03 5.04656885e+03 5.22539209e+03 5.27507275e+03 5.37174854e+03 5.31521094e+03 5.18265869e+03 5.26005371e+03 5.49137598e+03 5.73432910e+03 5.79707715e+03 5.45578027e+03 5.53963281e+03 5.89377344e+03 5.79827832e+03 5.60761914e+03 5.69014844e+03 5.86594629e+03 6.04916016e+03 6.15927783e+03 6.14919873e+03 6.00387988e+03 5.91475049e+03 6.18469824e+03 6.34151807e+03 6.18899609e+03 6.26387988e+03 6.45978223e+03 6.56622510e+03 6.64763037e+03 6.47261523e+03 6.34011768e+03 6.50803857e+03 6.67361670e+03 6.90856641e+03 6.95157275e+03 6.68723975e+03 6.74433984e+03 6.97551904e+03 7.04807617e+03 7.04543164e+03 6.92357129e+03 6.97460010e+03 7.26241602e+03 7.38699072e+03 7.29811328e+03 7.24672461e+03 7.15394189e+03 7.39470605e+03 7.55151562e+03 7.39084033e+03 7.54556152e+03 7.65394775e+03 7.75215088e+03 7.99447656e+03 7.65307568e+03 7.55460107e+03 7.80610254e+03 7.89546533e+03 8.06715918e+03 7.85723193e+03 7.76064893e+03 8.10239160e+03 8.33817676e+03 8.33562598e+03 8.13429834e+03 8.26106543e+03 8.21750098e+03 8.19937500e+03 8.46801270e+03 8.78204785e+03 8.61193262e+03 8.32128027e+03 8.64963086e+03 8.60101758e+03 8.71885547e+03 8.77098535e+03 8.54140723e+03 8.83014648e+03 9.07623145e+03 8.77244238e+03 8.73606055e+03 8.94785547e+03 9.24790234e+03 9.43324219e+03 8.95965332e+03 8.93534766e+03 9.30884863e+03 9.42908496e+03 9.57119727e+03 9.28712695e+03 9.30385645e+03 9.34751270e+03 9.41611328e+03 9.75810742e+03 9.73198047e+03 9.42747559e+03 9.65856738e+03 9.99029590e+03 9.71165723e+03 9.67617480e+03 9.68205273e+03 9.68724902e+03 1.01091143e+04 1.03734248e+04 1.00454219e+04 9.90837305e+03 1.00865820e+04 1.02788643e+04 1.04745088e+04 1.02429775e+04 1.04278574e+04 1.05223477e+04 1.00801494e+04 1.02495205e+04 1.03996045e+04 1.04589131e+04 1.06916377e+04 1.06873789e+04 1.05947617e+04 1.09086279e+04 1.07497100e+04 1.05466396e+04 1.08597363e+04 1.10570762e+04 1.09996670e+04 1.07105752e+04 1.07064893e+04 1.12246367e+04 1.14419111e+04 1.10595371e+04 1.08112480e+04 1.10529043e+04 1.14130195e+04 1.15745176e+04 1.12051074e+04 1.12105176e+04 1.11718975e+04 1.14275342e+04 1.16844170e+04 1.13868438e+04 1.14360059e+04 1.15140576e+04 1.15040117e+04 1.17087715e+04 1.19616016e+04 1.17110059e+04 1.13705859e+04 1.19414580e+04 1.23904727e+04 1.18407822e+04 1.14101211e+04 1.16831885e+04 1.20127939e+04 1.21274248e+04 1.18978438e+04 1.18802666e+04 1.19975215e+04 1.22996133e+04 1.23654355e+04 1.21259902e+04 1.20824824e+04 1.21891660e+04 1.25058887e+04 1.23581240e+04 1.21414834e+04 1.23819551e+04 1.23313867e+04 1.22738848e+04 1.25874160e+04 1.26757764e+04 1.24005293e+04 1.23477871e+04 1.26974297e+04 1.27619248e+04 1.25016182e+04 1.24209883e+04 1.25957275e+04 1.29170469e+04 1.29064824e+04 1.24656553e+04 1.25190898e+04 1.27737188e+04 1.31979912e+04 1.32664375e+04 1.28177568e+04 1.30965010e+04 1.29926582e+04 1.25608516e+04 1.27611768e+04 1.29928135e+04 1.32933418e+04 1.32697383e+04 1.27525547e+04 1.26539932e+04 1.30760234e+04 1.35561094e+04 1.34886660e+04 1.32436865e+04 1.32051719e+04 1.30710996e+04 1.29662607e+04 1.29632773e+04 1.34024092e+04 1.36623037e+04 1.32503428e+04 1.31963955e+04 1.32166562e+04 1.34127021e+04 1.36077490e+04 1.35872539e+04 1.38872295e+04 1.33850938e+04 1.29291338e+04 1.31624238e+04 1.35501230e+04 1.39235020e+04 1.40028916e+04 1.36144453e+04 1.29632402e+04 1.32349092e+04 1.37116494e+04 1.35726709e+04 1.39107178e+04 1.38965215e+04 1.33454814e+04 1.37218242e+04 1.39124863e+04 1.36026064e+04 1.37329404e+04 1.36354824e+04 1.34568145e+04 1.34794570e+04 1.36047861e+04 1.37183740e+04 1.41198691e+04 1.45225918e+04 1.38649785e+04 1.32581709e+04 1.33967842e+04 1.37633223e+04 1.42469219e+04 1.41485615e+04 1.34859004e+04 1.33436211e+04 1.37505439e+04 1.42134863e+04 1.42885928e+04 1.38991553e+04 1.38160869e+04 1.38343389e+04 1.37026709e+04 1.36346475e+04 1.39536143e+04 1.41594854e+04 1.40155352e+04 1.41120811e+04 1.36718398e+04 1.36075430e+04 1.40450645e+04 1.41373477e+04 1.42919980e+04 1.38191113e+04 1.34286162e+04 1.36531836e+04 1.39771016e+04 1.42714150e+04 1.43875762e+04 1.39431191e+04 1.33715674e+04 1.36528535e+04 1.38671533e+04 1.36326641e+04 1.40184619e+04 1.42848760e+04 1.37731055e+04 1.36323838e+04 1.37539473e+04 1.40386338e+04 1.42213496e+04 1.39890244e+04 1.39618848e+04 1.35287100e+04 1.34230977e+04 1.38418037e+04 1.39481025e+04 1.41581641e+04 1.41471279e+04 1.36499971e+04 1.33861396e+04 1.37686113e+04 1.41419766e+04 1.39803154e+04 1.38139512e+04 1.37475371e+04 1.34785957e+04 1.35752529e+04 1.38389336e+04 1.37927676e+04 1.38425527e+04 1.36682275e+04 1.34412861e+04 1.34209512e+04 1.37999453e+04 1.38589336e+04 1.36639014e+04 1.37941699e+04 1.33959785e+04 1.35262939e+04 1.37261680e+04 1.35717842e+04 1.39345918e+04 1.35526211e+04 1.31353252e+04 1.32551289e+04 1.32509229e+04 1.35400215e+04 1.40633389e+04 1.37923750e+04 1.31706035e+04 1.31019766e+04 1.30993418e+04 1.30627314e+04 1.34413262e+04 1.36249873e+04 1.31926602e+04 1.30492461e+04 1.30746523e+04 1.33228203e+04 1.34571943e+04 1.33028701e+04 1.36790322e+04 1.32892627e+04 1.24671270e+04 1.27124561e+04 1.32105205e+04 1.33780986e+04 1.34390840e+04 1.29946895e+04 1.23385684e+04 1.26904717e+04 1.33528867e+04 1.32035840e+04 1.28989658e+04 1.27796602e+04 1.25469561e+04 1.28117861e+04 1.29060146e+04 1.26218350e+04 1.30102393e+04 1.28638799e+04 1.26280693e+04 1.26552344e+04 1.22759180e+04 1.24267178e+04 1.27113535e+04 1.29987783e+04 1.26527314e+04 1.19501279e+04 1.20518555e+04 1.24397314e+04 1.26835068e+04 1.25559639e+04 1.21156982e+04 1.19303135e+04 1.21615312e+04 1.24119170e+04 1.24161436e+04 1.23203418e+04 1.21958770e+04 1.20250342e+04 1.20142041e+04 1.19837861e+04 1.19901523e+04 1.20419971e+04 1.20201357e+04 1.21343027e+04 1.16846250e+04 1.16101641e+04 1.19255967e+04 1.18078848e+04 1.20756006e+04 1.18491318e+04 1.12364453e+04 1.13117393e+04 1.15249766e+04 1.18360576e+04 1.20271025e+04 1.15248643e+04 1.11381094e+04 1.11880381e+04 1.13350127e+04 1.14108018e+04 1.13900732e+04 1.13804385e+04 1.10722939e+04 1.09110791e+04 1.09823115e+04 1.11875273e+04 1.13632686e+04 1.11587773e+04 1.11124766e+04 1.08658691e+04 1.04772266e+04 1.06683809e+04 1.08586377e+04 1.10685117e+04 1.09773486e+04 1.03843086e+04 1.02352754e+04 1.05913887e+04 1.09586641e+04 1.07307412e+04 1.05122715e+04 1.04429092e+04 1.00655020e+04 1.03013799e+04 1.05385225e+04 1.03087900e+04 1.01805674e+04 1.00721084e+04 1.01704453e+04 1.01203584e+04 1.00236729e+04 1.00786465e+04 1.01061738e+04 1.00087979e+04 9.66357520e+03 9.74522559e+03 9.84376562e+03 9.75695410e+03 1.00191152e+04 9.73456250e+03 9.32318066e+03 9.43722949e+03 9.35691211e+03 9.68528516e+03 9.99137402e+03 9.50722949e+03 9.13293164e+03 9.00455078e+03 9.34981836e+03 9.90905762e+03 9.67860352e+03 8.86786035e+03 1.62361953e+04 1.82764082e+04 1.16751762e+06 -558735680. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -12698302. 6.07164766e+04 1.28686426e+04 1.11260723e+04 1.02646162e+04 7.62262256e+03 8.28896875e+03 7.06361084e+03 6.48289600e+03 6.49844238e+03 6.71173389e+03 6.58571045e+03 6.28919775e+03 6.05478955e+03 6.03058105e+03 6.28921045e+03 6.46811621e+03 6.19837451e+03 5.94244678e+03 5.85787695e+03 5.84043555e+03 6.03824658e+03 6.02807861e+03 5.78357275e+03 5.62128369e+03 5.59379639e+03 5.65187842e+03 5.62213135e+03 5.47072949e+03 5.46642529e+03 5.59419629e+03 5.67503613e+03 5.36420410e+03 5.02259912e+03 5.12991504e+03 5.36332959e+03 5.46750732e+03 5.18904199e+03 4.85588867e+03 4.87162939e+03 5.05883154e+03 5.23619092e+03 4.97442822e+03 4.62560010e+03 4.64061475e+03 4.81796436e+03 4.83588184e+03 4.78156836e+03 4.64717041e+03 4.48683154e+03 4.47227686e+03 4.57007520e+03 4.36734424e+03 4.27567773e+03 4.43305566e+03 4.42905127e+03 4.36077197e+03 4.14276562e+03 3.93673535e+03 4.12051855e+03 4.33993408e+03 4.17548242e+03 3.89417114e+03 3.71295215e+03 3.74518384e+03 3.95028955e+03 4.04260767e+03 3.87043115e+03 3.74370825e+03 3.63035815e+03 3.49852319e+03 3.59297388e+03 3.65750195e+03 3.50577612e+03 3.42707837e+03 3.44094604e+03 3.41615649e+03 3.29839502e+03 3.23387476e+03 3.29344629e+03 3.30241040e+03 3.28110986e+03 3.15663794e+03 2.97924292e+03 2.94614282e+03 3.07573193e+03 3.17754126e+03 2.99203613e+03 2.77184717e+03 2.77106714e+03 2.82103247e+03 2.86410156e+03 2.84998657e+03 2.71497192e+03 2.64503296e+03 2.60578467e+03 2.60327979e+03 2.60764893e+03 2.53049390e+03 2.47557300e+03 2.42578467e+03 2.41138184e+03 2.38583984e+03 2.31897021e+03 2.31171558e+03 2.30336694e+03 2.28986499e+03 2.20478076e+03 2.06882080e+03 2.07659814e+03 2.15504419e+03 2.15436450e+03 2.02311584e+03 1.89339514e+03 1.87757117e+03 1.94775928e+03 2.00845740e+03 1.89823853e+03 1.76559937e+03 1.76621313e+03 1.73446021e+03 1.71452551e+03 1.70003467e+03 1.64787817e+03 1.65202661e+03 1.60430017e+03 1.56318640e+03 1.54010913e+03 1.47286316e+03 1.47662000e+03 1.50354272e+03 1.46716296e+03 1.38636646e+03 1.31263074e+03 1.29201465e+03 1.31817615e+03 1.34082349e+03 1.26393005e+03 1.17026147e+03 1.15652161e+03 1.18666333e+03 1.19535254e+03 1.12149536e+03 1.06660120e+03 1.05159863e+03 1.02562891e+03 1.02070160e+03 1.00191534e+03 9.37001953e+02 9.12960876e+02 9.23021545e+02 9.09167175e+02 8.72162354e+02 8.30982605e+02 8.11155212e+02 8.01070068e+02 8.00876831e+02 7.61553162e+02 7.01719238e+02 6.90214355e+02 6.87690674e+02 6.77408508e+02 6.57152710e+02 6.15719604e+02 5.92745911e+02 5.83641479e+02 5.76354553e+02 5.56315979e+02 5.23787598e+02 5.12286926e+02 4.95588562e+02 4.76820435e+02 4.57517487e+02 4.29847961e+02 4.22108124e+02 4.20344574e+02 4.05953156e+02 3.76180237e+02 3.46333557e+02 3.34292267e+02 3.34898956e+02 3.32142456e+02 3.05373322e+02 2.76034454e+02 2.66089935e+02 2.61377686e+02 2.54505585e+02 2.41722046e+02 2.20324249e+02 2.07079590e+02 1.99857605e+02 1.90198074e+02 1.78827850e+02 1.66914581e+02 1.57303741e+02 1.45665466e+02 1.37212997e+02 1.28874237e+02 1.18311722e+02 1.10488754e+02 1.02867409e+02 9.55993423e+01 8.50974121e+01 7.64009018e+01 7.24151688e+01 6.82588577e+01 6.22183075e+01 5.39103012e+01 4.64038811e+01 4.15413399e+01 3.86803055e+01 3.54521294e+01 3.02698498e+01 2.52434387e+01 2.13546066e+01 1.82510338e+01 1.59536304e+01 1.37116394e+01 1.12635899e+01 9.28131390e+00 7.75815201e+00 6.56719637e+00 5.71109009e+00 5.22582293e+00 5.07536554e+00 5.26264095e+00 5.80214310e+00 6.64854860e+00 7.69652939e+00 9.26189804e+00 1.13289146e+01 1.35676136e+01 1.61656551e+01 1.89422665e+01 2.24709682e+01 2.62148647e+01 2.91248913e+01 3.24355125e+01 3.75330162e+01 4.42773018e+01 5.08911591e+01 5.57718849e+01 5.87337875e+01 6.34094772e+01 7.13830872e+01 8.14130096e+01 9.12041016e+01 9.76764069e+01 1.00509407e+02 1.07943886e+02 1.22726677e+02 1.32214600e+02 1.35061340e+02 1.43981705e+02 1.57019577e+02 1.67419769e+02 1.83182541e+02 1.89880096e+02 1.94698837e+02 2.11484726e+02 2.17955856e+02 2.35259827e+02 2.56378357e+02 2.56389099e+02 2.73397797e+02 2.95949585e+02 3.03226532e+02 3.17087616e+02 3.30419800e+02 3.46447693e+02 3.65970734e+02 3.77155518e+02 3.80520325e+02 3.99461426e+02 4.35331696e+02 4.61705719e+02 4.69246277e+02 4.68134491e+02 4.73187042e+02 4.99221252e+02 5.42190491e+02 5.76208679e+02 5.85157654e+02 5.70049438e+02 5.89696045e+02 6.37712341e+02 6.53369812e+02 6.62288086e+02 6.83450867e+02 7.07382019e+02 7.28002441e+02 7.77159607e+02 7.80723206e+02 7.74161926e+02 8.13161255e+02 8.17068604e+02 8.70547241e+02 9.16055908e+02 9.13167664e+02 9.66330139e+02 9.66880493e+02 9.55127014e+02 1.00575854e+03 1.01130133e+03 1.05825171e+03 1.15492542e+03 1.12262793e+03 1.08820630e+03 1.14131360e+03 1.21265002e+03 1.28233923e+03 1.29267859e+03 1.25255811e+03 1.23230664e+03 1.28621082e+03 1.39741516e+03 1.47067322e+03 1.46807446e+03 1.41955310e+03 1.43640686e+03 1.52759937e+03 1.57607898e+03 1.55413733e+03 1.56603320e+03 1.62153796e+03 1.66117102e+03 1.74586658e+03 1.77673096e+03 1.73824939e+03 1.76706360e+03 1.79619080e+03 1.83299548e+03 1.90567004e+03 1.93330481e+03 2.00821484e+03 2.00119312e+03 1.96041418e+03 2.05296851e+03 2.03679871e+03 2.11422046e+03 2.29802881e+03 2.22918262e+03 2.11077075e+03 2.18436035e+03 2.33625122e+03 2.43171899e+03 2.49076221e+03 2.40990527e+03 2.33336230e+03 2.40507349e+03 2.57125146e+03 2.72945874e+03 2.68573291e+03 2.55342310e+03 2.56938354e+03 2.68093848e+03 2.80084888e+03 2.92767017e+03 2.92910913e+03 2.79555859e+03 2.80726001e+03 2.97926538e+03 3.04718555e+03 3.04165039e+03 3.07892261e+03 3.07179492e+03 3.08101196e+03 3.26670288e+03 3.33514038e+03 3.20836475e+03 3.23056470e+03 3.34332593e+03 3.40812793e+03 3.44952490e+03 3.46008569e+03 3.57057275e+03 3.66930005e+03 3.60049976e+03 3.57489185e+03 3.56244946e+03 3.73864453e+03 3.97946021e+03 3.94091479e+03 3.78995312e+03 3.73391528e+03 3.91921118e+03 4.17875781e+03 4.07794360e+03 3.90387598e+03 4.01839453e+03 4.18599658e+03 4.32320752e+03 4.49868848e+03 4.45648242e+03 4.24145703e+03 4.18031250e+03 4.35465430e+03 4.63518262e+03 4.66422266e+03 4.58847461e+03 4.58578564e+03 4.64892627e+03 4.81845801e+03 4.80601953e+03 4.68910693e+03 4.73312842e+03 4.77392969e+03 5.03804248e+03 5.20125928e+03 5.06701025e+03 5.06997266e+03 5.14143408e+03 5.32647461e+03 5.26124365e+03 5.02606152e+03 5.28990137e+03 5.65177490e+03 5.48483936e+03 5.27785107e+03 5.42776318e+03 5.77163086e+03 5.80032959e+03 5.69132178e+03 5.72320801e+03 5.59241064e+03 5.64554492e+03 6.02229590e+03 6.06350439e+03 5.88765576e+03 5.76285254e+03 5.81899512e+03 6.11171680e+03 6.47602783e+03 6.25205811e+03 6.12713916e+03 6.28646484e+03 6.31958838e+03 6.57051123e+03 6.59809082e+03 6.29431299e+03 6.31485840e+03 6.51325098e+03 6.60908398e+03 6.70885938e+03 6.74748242e+03 6.97759326e+03 6.94505029e+03 6.69845459e+03 6.74718652e+03 6.76000049e+03 7.08540479e+03 7.39132178e+03 7.29836719e+03 7.08796680e+03 7.03419336e+03 7.55776562e+03 7.74753809e+03 7.95131250e+03 8.50380469e+03 1.01680410e+04 1.39568262e+04 1.27513500e+05 -44591940. 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. 0. 0. 0. 0. 0. 0. 0. 81189112. 1.55476578e+05 2.96672656e+04 1.68306738e+04 1.53562070e+04 1.50772139e+04 1.08899072e+04 1.11562666e+04 1.01305479e+04 1.02963682e+04 1.01128779e+04 9.74219727e+03 9.93957324e+03 1.00359570e+04 9.91750586e+03 1.00323516e+04 1.00177295e+04 1.00703506e+04 1.01416055e+04 1.01544033e+04 1.01426855e+04 1.00124932e+04 9.97837012e+03 1.05244072e+04 1.06101211e+04 1.00966084e+04 1.01307959e+04 1.07411357e+04 1.08389648e+04 1.06292998e+04 1.06637852e+04 1.06215547e+04 1.07169688e+04 1.07033896e+04 1.07364209e+04 1.08245312e+04 1.08532881e+04 1.06621426e+04 1.06269551e+04 1.11965400e+04 1.12995137e+04 1.10335303e+04 1.10480469e+04 1.11046709e+04 1.11983438e+04 1.11830127e+04 1.11648320e+04 1.12602246e+04 1.10104268e+04 1.09755205e+04 1.13725449e+04 1.13601123e+04 1.17737295e+04 1.19422070e+04 1.15542119e+04 1.12430527e+04 1.11902285e+04 1.19983428e+04 1.21321211e+04 1.16924111e+04 1.15710449e+04 1.17145195e+04 1.18119062e+04 1.17450391e+04 1.21310088e+04 1.21458613e+04 1.15632734e+04 1.15379102e+04 1.21783877e+04 1.25251514e+04 1.22273184e+04 1.20921162e+04 1.21824199e+04 1.21754902e+04 1.20186768e+04 1.20572061e+04 1.23293330e+04 1.23581152e+04 1.21874834e+04 1.22540557e+04 1.24484961e+04 1.23964229e+04 1.27528496e+04 1.27172119e+04 1.23577764e+04 1.25846865e+04 1.26010674e+04 1.27140156e+04 1.28337441e+04 1.27108867e+04 1.26459668e+04 1.24710918e+04 1.23503535e+04 1.29135107e+04 1.29158994e+04 1.23062959e+04 1.25111982e+04 1.32789863e+04 1.37513262e+04 1.32951982e+04 1.29330879e+04 1.27757041e+04 1.27691436e+04 1.29111260e+04 1.29395020e+04 1.31556191e+04 1.31102617e+04 1.33200420e+04 1.33114307e+04 1.29947959e+04 1.32758623e+04 1.28951719e+04 1.29628018e+04 1.37478115e+04 1.36062021e+04 1.33152803e+04 1.30208359e+04 1.29124463e+04 1.36870693e+04 1.38071602e+04 1.33361621e+04 1.30396426e+04 1.30850410e+04 1.34469561e+04 1.34282637e+04 1.38199658e+04 1.39327393e+04 1.35436562e+04 1.34215986e+04 1.34405283e+04 1.37242988e+04 1.37403545e+04 1.35761963e+04 1.33487598e+04 1.33841143e+04 1.37079658e+04 1.33149561e+04 1.33612607e+04 1.41734580e+04 1.41041494e+04 1.37071592e+04 1.33167031e+04 1.33181465e+04 1.41564209e+04 1.41630459e+04 1.37715068e+04 1.34337754e+04 1.33704775e+04 1.38316348e+04 1.37863477e+04 1.37612949e+04 1.35030303e+04 1.37466396e+04 1.44178467e+04 1.40798984e+04 1.39335127e+04 1.40037207e+04 1.39195576e+04 1.37144971e+04 1.36696084e+04 1.38850908e+04 1.39499346e+04 1.40099414e+04 1.35056299e+04 1.35263213e+04 1.44629053e+04 1.39796631e+04 1.34585723e+04 1.38595674e+04 1.38682168e+04 1.43353838e+04 1.40462061e+04 1.34645723e+04 1.42308105e+04 1.43292568e+04 1.38856875e+04 1.36841016e+04 1.36921387e+04 1.38217578e+04 1.38184902e+04 1.39476016e+04 1.35609248e+04 1.38016748e+04 1.46082852e+04 1.43417646e+04 1.38083789e+04 1.33829648e+04 1.35539766e+04 1.43755449e+04 1.43331240e+04 1.39234932e+04 1.36112920e+04 1.35027080e+04 1.38108975e+04 1.38328896e+04 1.42140273e+04 1.39343369e+04 1.34589453e+04 1.38213359e+04 1.38474307e+04 1.41191709e+04 1.39119004e+04 1.35342686e+04 1.37176045e+04 1.37074463e+04 1.38284766e+04 1.34454639e+04 1.36875312e+04 1.45113848e+04 1.40896729e+04 1.37290137e+04 1.33816250e+04 1.32419658e+04 1.39990518e+04 1.41358398e+04 1.37174033e+04 1.32475254e+04 1.32484443e+04 1.36840693e+04 1.36465088e+04 1.39813438e+04 1.38987373e+04 1.35697178e+04 1.31725410e+04 1.30671904e+04 1.39189375e+04 1.37187236e+04 1.32839551e+04 1.32611377e+04 1.31948691e+04 1.37482471e+04 1.37939395e+04 1.31154385e+04 1.29863604e+04 1.36281084e+04 1.37246631e+04 1.30014883e+04 1.29073330e+04 1.36041562e+04 1.36238105e+04 1.32000557e+04 1.29029902e+04 1.28202324e+04 1.35423408e+04 1.33419434e+04 1.28726533e+04 1.30192344e+04 1.29642178e+04 1.32216465e+04 1.32243496e+04 1.27746855e+04 1.24670381e+04 1.28616602e+04 1.35548486e+04 1.31408438e+04 1.29032783e+04 1.30178975e+04 1.28661953e+04 1.28670078e+04 1.28150078e+04 1.27210713e+04 1.24223047e+04 1.23220264e+04 1.25464990e+04 1.27005234e+04 1.30531377e+04 1.26412910e+04 1.20884346e+04 1.23936250e+04 1.26149756e+04 1.29829482e+04 1.26695371e+04 1.22323809e+04 1.22001045e+04 1.21676904e+04 1.23507061e+04 1.22649531e+04 1.25263125e+04 1.24740811e+04 1.21147881e+04 1.19564541e+04 1.15733584e+04 1.20615273e+04 1.27716689e+04 1.24351553e+04 1.20116162e+04 1.16302734e+04 1.13775879e+04 1.19181162e+04 1.24783037e+04 1.20652100e+04 1.14754385e+04 1.14197119e+04 1.17055830e+04 1.16537197e+04 1.19069541e+04 1.18191426e+04 1.14699990e+04 1.14159404e+04 1.13556855e+04 1.17323125e+04 1.17508389e+04 1.10895605e+04 1.10049951e+04 1.15893623e+04 1.14695576e+04 1.08492363e+04 1.10439961e+04 1.15816924e+04 1.14259658e+04 1.10646953e+04 1.07649844e+04 1.07089746e+04 1.13096328e+04 1.12386660e+04 1.09217734e+04 1.06349346e+04 1.04618701e+04 1.07269805e+04 1.07915752e+04 1.06411875e+04 1.03363643e+04 1.05886367e+04 1.08836035e+04 1.05444707e+04 1.06858896e+04 1.05666465e+04 1.02696484e+04 1.03510996e+04 1.03638613e+04 1.03375107e+04 1.01885732e+04 9.93213672e+03 9.74709668e+03 1.01017373e+04 1.06679639e+04 1.00665586e+04 9.54396973e+03 9.80627148e+03 9.98640430e+03 1.02137988e+04 9.88686035e+03 9.50989551e+03 9.91264355e+03 9.92872559e+03 9.34723730e+03 9.23887305e+03 9.74719043e+03 9.71383984e+03 9.34739160e+03 9.19071973e+03 8.80213379e+03 9.18119531e+03 9.77549609e+03 9.47737305e+03 9.11762305e+03 8.82049316e+03 8.64071680e+03 9.03731152e+03 9.54718066e+03 9.17450488e+03 8.66329199e+03 8.55543262e+03 8.77923828e+03 8.77385938e+03 8.94949121e+03 8.68078613e+03 8.39626367e+03 8.56033203e+03 8.48643066e+03 8.72007520e+03 8.60177637e+03 8.26892578e+03 8.24841113e+03 8.16055127e+03 8.31012891e+03 8.01897119e+03 7.88718359e+03 8.33910156e+03 8.25072754e+03 7.88683838e+03 7.65455664e+03 7.72830615e+03 8.09832812e+03 8.03602295e+03 7.75765820e+03 7.49497363e+03 7.40472314e+03 7.59100146e+03 7.51069922e+03 7.51177930e+03 7.26339941e+03 7.37323975e+03 7.62273047e+03 7.27321338e+03 7.41857861e+03 7.39834131e+03 7.16945020e+03 6.98799707e+03 6.87854932e+03 7.10957617e+03 7.06514941e+03 6.73503076e+03 6.65432861e+03 6.96864258e+03 6.98101123e+03 6.56003809e+03 6.33618652e+03 6.46471533e+03 6.66335156e+03 6.87843018e+03 6.53189111e+03 6.20839209e+03 6.41130566e+03 6.50771582e+03 6.33726611e+03 6.16559424e+03 6.09617041e+03 6.03671289e+03 5.99727637e+03 6.04607031e+03 5.81342285e+03 5.91725293e+03 6.14801416e+03 5.93486719e+03 5.84433105e+03 5.67969580e+03 5.55388672e+03 5.78290381e+03 5.73141162e+03 5.56739209e+03 5.39346289e+03 5.18400879e+03 5.24633740e+03 5.47915771e+03 5.61496924e+03 5.29800488e+03 5.05206885e+03 5.13642480e+03 5.13555225e+03 5.29219238e+03 5.18852393e+03 4.97039062e+03 4.89819727e+03 4.83715967e+03 4.79126074e+03 4.64993311e+03 4.74285547e+03 4.88640967e+03 4.70429688e+03 4.68453906e+03 4.55502246e+03 4.40441016e+03 4.63187598e+03 4.57473145e+03 4.39183057e+03 4.25337305e+03 4.16215283e+03 4.25613477e+03 4.20878662e+03 4.28305273e+03 4.27961230e+03 4.07010352e+03 3.94569214e+03 3.95567749e+03 4.09907812e+03 3.98552222e+03 3.85814404e+03 3.76851294e+03 3.71340186e+03 3.70216919e+03 3.64684961e+03 3.70027002e+03 3.66653906e+03 3.52330664e+03 3.58699805e+03 3.57820728e+03 3.46273438e+03 3.40692798e+03 3.36988867e+03 3.32602856e+03 3.20300269e+03 3.11992505e+03 3.25076709e+03 3.24258374e+03 3.02297803e+03 2.89944214e+03 3.00969116e+03 3.16140747e+03 3.05920825e+03 2.84506909e+03 2.75461206e+03 2.87804419e+03 2.86047192e+03 2.73421997e+03 2.76379663e+03 2.64456128e+03 2.49361401e+03 2.52977686e+03 2.63949072e+03 2.65160962e+03 2.47509668e+03 2.32800854e+03 2.42958813e+03 2.49877686e+03 2.38522974e+03 2.24873779e+03 2.18052002e+03 2.21638843e+03 2.19227881e+03 2.21500903e+03 2.17123706e+03 2.06868921e+03 2.03704028e+03 2.00249182e+03 2.03538159e+03 1.95436816e+03 1.86864136e+03 1.90838342e+03 1.86431567e+03 1.84462207e+03 1.77718701e+03 1.71726831e+03 1.78292126e+03 1.70098816e+03 1.60372681e+03 1.61220410e+03 1.60929224e+03 1.58962732e+03 1.53792188e+03 1.53878357e+03 1.52191333e+03 1.45466699e+03 1.38585962e+03 1.34675037e+03 1.39038635e+03 1.33708325e+03 1.27204834e+03 1.28158789e+03 1.24998999e+03 1.21869202e+03 1.18518774e+03 1.18747021e+03 1.15346899e+03 1.09440002e+03 1.10209363e+03 1.08092468e+03 1.04166248e+03 1.01850250e+03 9.89484741e+02 9.52910339e+02 9.03348083e+02 8.67094910e+02 8.87084229e+02 9.16079895e+02 8.45541016e+02 7.73599060e+02 7.85670044e+02 8.11330750e+02 7.80761169e+02 7.19574829e+02 6.78948425e+02 6.96094360e+02 6.77658142e+02 6.35129211e+02 6.38568481e+02 6.16518555e+02 5.67398987e+02 5.47169800e+02 5.56990295e+02 5.52836426e+02 5.09623596e+02 4.70346069e+02 4.70360321e+02 4.80732483e+02 4.54078156e+02 4.15738770e+02 3.89525146e+02 3.90477631e+02 3.92265076e+02 3.63907745e+02 3.39081940e+02 3.27441132e+02 3.16106506e+02 3.00725189e+02 2.95034302e+02 2.75643097e+02 2.54403503e+02 2.47080582e+02 2.35855423e+02 2.28271881e+02 2.11225647e+02 1.94845474e+02 1.90328949e+02 1.74321243e+02 1.63715332e+02 1.59810028e+02 1.48143723e+02 1.37151794e+02 1.26679558e+02 1.22305130e+02 1.15186630e+02 1.02516830e+02 9.19449768e+01 8.49667664e+01 8.32206039e+01 7.61994858e+01 6.79053726e+01 5.53142929e+01 5.49572945e+01 8.05382385e+01 6.90412842e+02 -9350246. 0. 0. 0. 0. 0. -56120612. -34281240. 4.39358635e+01 3.63138847e+01 4.88976974e+01 27309112. 0. 0. 38412828. 38412828. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -103217192. -78265800. 7.72790604e+01 8.37588348e+01 8.52596054e+01 5.75899506e+01 6.43815231e+01 7.25209579e+01 8.05782242e+01 8.28804245e+01 8.83400726e+01 9.60803146e+01 1.04297958e+02 1.10856766e+02 1.20069443e+02 1.31378998e+02 1.39621414e+02 1.48858093e+02 1.57674973e+02 1.65674988e+02 1.79804199e+02 1.91139938e+02 2.00379883e+02 2.13053238e+02 2.22633270e+02 2.36347061e+02 2.56911285e+02 2.69501862e+02 2.74221649e+02 2.85748718e+02 3.03930756e+02 3.18477051e+02 3.30166962e+02 3.44843201e+02 3.61601959e+02 3.74768005e+02 3.95799591e+02 4.10606201e+02 4.11998474e+02 4.34108887e+02 4.66598511e+02 4.88338593e+02 5.03911804e+02 5.02798584e+02 5.14147278e+02 5.49051453e+02 5.71053528e+02 5.83569275e+02 5.99005737e+02 6.19680969e+02 6.51657776e+02 6.80279541e+02 6.92111877e+02 6.91009399e+02 7.10476257e+02 7.69802002e+02 7.93972900e+02 7.74252380e+02 7.98520935e+02 8.42965149e+02 8.74869568e+02 9.07121704e+02 9.13216187e+02 9.07144958e+02 9.41397705e+02 9.91236023e+02 1.02308154e+03 1.03564087e+03 1.04289502e+03 1.08745520e+03 1.12952759e+03 1.13834338e+03 1.15326001e+03 1.17633264e+03 1.21329456e+03 1.25944226e+03 1.28190540e+03 1.31989124e+03 1.33177490e+03 1.32356067e+03 1.37232617e+03 1.42582898e+03 1.44876428e+03 1.48182861e+03 1.49681592e+03 1.52983679e+03 1.60023035e+03 1.61924475e+03 1.59365222e+03 1.62908008e+03 1.69819324e+03 1.74660962e+03 1.76889966e+03 1.77349915e+03 1.80154431e+03 1.84998279e+03 1.90628711e+03 1.91808594e+03 1.90765552e+03 1.96756042e+03 2.05707446e+03 2.09052466e+03 2.10960449e+03 2.09476025e+03 2.11787231e+03 2.21426025e+03 2.24566455e+03 2.23254077e+03 2.26753979e+03 2.31737085e+03 2.40206274e+03 2.43868457e+03 2.44344434e+03 2.48368408e+03 2.51011646e+03 2.57550562e+03 2.62232007e+03 2.61730078e+03 2.66427759e+03 2.70376025e+03 2.72048096e+03 2.79067578e+03 2.83896143e+03 2.87146924e+03 2.92874072e+03 2.93561865e+03 2.95391406e+03 3.03478125e+03 3.09911792e+03 3.11478979e+03 3.12640991e+03 3.13647925e+03 3.18732349e+03 3.28142407e+03 3.30531055e+03 3.31047754e+03 3.37928003e+03 3.50015527e+03 3.54460278e+03 3.47709375e+03 3.54497217e+03 3.61328931e+03 3.62571680e+03 3.65462866e+03 3.67260425e+03 3.73867114e+03 3.82981030e+03 3.93721704e+03 3.96041895e+03 3.90020972e+03 3.89803906e+03 3.98944458e+03 4.13018066e+03 4.15461963e+03 4.16586377e+03 4.15867676e+03 4.25884521e+03 4.36078711e+03 4.37450781e+03 4.34990479e+03 4.33478271e+03 4.43239697e+03 4.64260693e+03 4.61052197e+03 4.45651953e+03 4.56300830e+03 4.76077881e+03 4.76959570e+03 4.74718066e+03 4.83351221e+03 4.87037793e+03 4.88251172e+03 5.02183496e+03 4.98853027e+03 4.97754590e+03 5.14545947e+03 5.24698096e+03 5.20318213e+03 5.24249609e+03 5.31616699e+03 5.23334619e+03 5.38467529e+03 5.42327637e+03 5.48687695e+03 5.64956055e+03 5.44734082e+03 5.53606104e+03 5.81329443e+03 5.74178809e+03 5.66024463e+03 5.78254785e+03 5.89951514e+03 5.93323828e+03 5.99433398e+03 6.02287988e+03 5.94292285e+03 6.00220166e+03 6.24557568e+03 6.35467334e+03 6.13060059e+03 6.25298340e+03 6.47608252e+03 6.42140723e+03 6.43361475e+03 6.41380322e+03 6.41452734e+03 6.63780176e+03 6.66727539e+03 6.67188232e+03 6.73260693e+03 6.70351367e+03 6.81317188e+03 7.02116992e+03 6.90996826e+03 6.94349219e+03 7.02587744e+03 7.04990234e+03 7.14532227e+03 7.20842822e+03 7.17771973e+03 7.21971143e+03 7.29094287e+03 7.38134277e+03 7.43800098e+03 7.37510986e+03 7.55994141e+03 7.65841406e+03 7.63615430e+03 7.80461865e+03 7.70104541e+03 7.53563965e+03 7.78686963e+03 7.89312402e+03 7.88495166e+03 7.83498633e+03 7.85195215e+03 8.04830078e+03 8.22981641e+03 8.19926855e+03 8.12809863e+03 8.29626855e+03 8.39631445e+03 8.24166211e+03 8.22050879e+03 8.51464355e+03 8.52364160e+03 8.39417969e+03 8.73283789e+03 8.67125684e+03 8.53259961e+03 8.73618457e+03 8.68954883e+03 8.69286328e+03 8.85418066e+03 8.85458691e+03 8.82492188e+03 8.99835352e+03 9.10198730e+03 9.22346387e+03 9.01125098e+03 8.96529297e+03 9.29348047e+03 9.24972461e+03 9.33864844e+03 9.36221777e+03 9.31284082e+03 9.40372559e+03 9.48099805e+03 9.68209180e+03 9.54400879e+03 9.36787109e+03 9.69419434e+03 1.00144766e+04 9.66769629e+03 9.53131152e+03 9.71206152e+03 9.74734180e+03 9.99153906e+03 1.01044561e+04 9.93964648e+03 9.92229492e+03 1.01280498e+04 1.01611455e+04 1.02744502e+04 1.02349404e+04 1.03377197e+04 1.04398623e+04 1.00838096e+04 1.02571240e+04 1.04681748e+04 1.03648877e+04 1.06112881e+04 1.05750713e+04 1.04663496e+04 1.07170420e+04 1.06252520e+04 1.06468867e+04 1.10473730e+04 1.09351934e+04 1.07414385e+04 1.07396240e+04 1.06584492e+04 1.09552246e+04 1.11896123e+04 1.10228838e+04 1.09711084e+04 1.12152324e+04 1.12955918e+04 1.12828271e+04 1.11327686e+04 1.11166631e+04 1.12065957e+04 1.14317441e+04 1.15333750e+04 1.12251641e+04 1.12747373e+04 1.15271523e+04 1.16360283e+04 1.16483311e+04 1.16900420e+04 1.15922881e+04 1.15408701e+04 1.19724727e+04 1.20872842e+04 1.16713242e+04 1.15582734e+04 1.16501318e+04 1.18651787e+04 1.19349365e+04 1.18283301e+04 1.19855000e+04 1.21068320e+04 1.20727812e+04 1.22071748e+04 1.21223838e+04 1.20447871e+04 1.22381436e+04 1.23943486e+04 1.21790068e+04 1.20549609e+04 1.22803760e+04 1.23067295e+04 1.23261172e+04 1.25021104e+04 1.24431318e+04 1.23036406e+04 1.24583125e+04 1.27830264e+04 1.26120869e+04 1.23826992e+04 1.25552705e+04 1.26617520e+04 1.26318721e+04 1.26101592e+04 1.25293955e+04 1.26102891e+04 1.27277979e+04 1.29377529e+04 1.30515098e+04 1.28202754e+04 1.28517422e+04 1.28543320e+04 1.27910215e+04 1.28841562e+04 1.28262754e+04 1.29951797e+04 1.30867705e+04 1.29435791e+04 1.28560146e+04 1.29161943e+04 1.32252998e+04 1.33709619e+04 1.33593242e+04 1.31868340e+04 1.30804365e+04 1.31162354e+04 1.30053018e+04 1.31272744e+04 1.33379268e+04 1.33186475e+04 1.32743145e+04 1.30854219e+04 1.30847988e+04 1.34595889e+04 1.36392363e+04 1.36938359e+04 1.33545938e+04 1.31113281e+04 1.33602891e+04 1.34530068e+04 1.34091455e+04 1.35195127e+04 1.36538037e+04 1.34480020e+04 1.33074902e+04 1.33421680e+04 1.33833223e+04 1.38165195e+04 1.39352578e+04 1.35133223e+04 1.36322852e+04 1.35381455e+04 1.32814062e+04 1.37506230e+04 1.38911777e+04 1.35028193e+04 1.35302803e+04 1.35224912e+04 1.33613379e+04 1.37835195e+04 1.41764482e+04 1.37850605e+04 1.35763184e+04 1.37069951e+04 1.36869590e+04 1.37822754e+04 1.37839004e+04 1.37129268e+04 1.37056982e+04 1.37684209e+04 1.38344014e+04 1.37975234e+04 1.37021504e+04 1.38651396e+04 1.40292090e+04 1.37711221e+04 1.35643721e+04 1.36181826e+04 1.39322188e+04 1.41452979e+04 1.40603125e+04 1.36569424e+04 1.33907119e+04 1.37080596e+04 1.40549990e+04 1.42223877e+04 1.38665127e+04 1.35740986e+04 1.38580225e+04 1.38823877e+04 1.37749707e+04 1.39340811e+04 1.38225146e+04 1.36673975e+04 1.40078301e+04 1.38047158e+04 1.33246582e+04 1.38421094e+04 1.43443945e+04 1.38249795e+04 1.35730068e+04 1.37066826e+04 1.37347373e+04 1.39157158e+04 1.39692002e+04 1.38186924e+04 1.35482412e+04 1.36064062e+04 1.37983242e+04 1.37751250e+04 1.39276553e+04 1.39363945e+04 1.36642764e+04 1.35756318e+04 1.38820635e+04 1.38212373e+04 1.36308154e+04 1.38393438e+04 1.38863047e+04 1.36347090e+04 1.33995332e+04 1.34293682e+04 1.36183477e+04 1.38954463e+04 1.38559443e+04 1.34632090e+04 1.33750098e+04 1.34791553e+04 1.35856797e+04 1.37704268e+04 1.36386582e+04 1.32825322e+04 1.35711973e+04 1.36834385e+04 1.33754502e+04 1.37132930e+04 1.36575371e+04 1.32858281e+04 13386. 1.32286025e+04 1.31394316e+04 1.35836680e+04 1.35678887e+04 1.33058291e+04 1.34483906e+04 1.32945186e+04 1.29110918e+04 1.30375020e+04 1.33183672e+04 1.32748662e+04 1.32687490e+04 1.31143799e+04 1.30213770e+04 1.31675547e+04 1.32113867e+04 1.35716973e+04 1.32689072e+04 1.26575928e+04 1.27938848e+04 1.29522490e+04 1.30443877e+04 1.32258613e+04 1.29302490e+04 1.25963633e+04 1.28507705e+04 1.30350615e+04 1.28916514e+04 1.28833730e+04 1.28069863e+04 1.25761338e+04 1.27766318e+04 1.28049795e+04 1.25012949e+04 1.29021777e+04 1.29634990e+04 1.26163428e+04 1.25147832e+04 1.21550352e+04 1.21970293e+04 1.25826992e+04 1.29020439e+04 1.27210752e+04 1.20451602e+04 1.20750850e+04 1.25075234e+04 1.23945488e+04 1.22591924e+04 1.22384863e+04 1.21265830e+04 1.21822529e+04 1.22433770e+04 1.22184727e+04 1.21158125e+04 1.20870947e+04 1.22108809e+04 1.19939141e+04 1.18285127e+04 1.18100908e+04 1.18011348e+04 1.19253799e+04 1.21685820e+04 1.18867812e+04 1.14691582e+04 1.16253428e+04 1.17470781e+04 1.19920771e+04 1.18621133e+04 1.13511934e+04 1.14494531e+04 1.15269258e+04 1.16056973e+04 1.17407402e+04 1.14759336e+04 1.13362168e+04 1.12723066e+04 1.11228447e+04 1.11121299e+04 1.13282246e+04 1.14668896e+04 1.11570752e+04 1.10022354e+04 1.08539189e+04 1.08694629e+04 1.11898945e+04 1.11816084e+04 1.09990762e+04 1.08554873e+04 1.05913369e+04 1.06619336e+04 1.07450762e+04 1.09114873e+04 1.09395840e+04 1.04547207e+04 1.03485117e+04 1.05219502e+04 1.05606299e+04 1.04937158e+04 1.05371562e+04 1.05518379e+04 1.02368809e+04 1.02423271e+04 1.02283330e+04 1.01770781e+04 1.02017012e+04 1.01968486e+04 1.01466963e+04 9.99883008e+03 9.87454004e+03 9.94765527e+03 1.01474355e+04 9.99050879e+03 9.71667480e+03 9.68989648e+03 9.68375781e+03 9.59728809e+03 9.89640039e+03 9.80272656e+03 9.36046777e+03 9.55844922e+03 9.38652637e+03 9.49827246e+03 9.70073535e+03 9.38014258e+03 9.22784473e+03 9.22987891e+03 9.31167578e+03 9.29891309e+03 9.41902832e+03 9.09277344e+03 1.14698506e+04 1.18148975e+04 2.22252793e+04 3.93371875e+04 2854715. -212644064. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -38775816. 4.02248450e+06 -22724712. 4258047. -4.63787366e+09 1.06009404e+04 1.17286699e+04 7.46191992e+03 6.63043799e+03 6.46612695e+03 6.67977490e+03 6.49939062e+03 6.30746582e+03 6.09536572e+03 6.09558057e+03 6.22647754e+03 6.28480469e+03 6.15352246e+03 5.95545020e+03 5.90148242e+03 5.88359570e+03 5.96888184e+03 5.88545801e+03 5.61376611e+03 5.62342334e+03 5.73786523e+03 5.67560010e+03 5.49206982e+03 5.33685693e+03 5.47585742e+03 5.67416211e+03 5.60306348e+03 5.26677637e+03 4.98443652e+03 5.10616455e+03 5.30578857e+03 5.36461621e+03 5.20600879e+03 4.94505225e+03 4.93957129e+03 4.99708057e+03 5.06859375e+03 4.93597607e+03 4.64681494e+03 4.68923242e+03 4.90146338e+03 4.75588867e+03 4.57396680e+03 4.57305713e+03 4.53812402e+03 4.58812256e+03 4.53522168e+03 4.32061963e+03 4.21137354e+03 4.37481836e+03 4.42485156e+03 4.33061182e+03 4.13477051e+03 3.99517773e+03 4.14865918e+03 4.23749756e+03 4.07933813e+03 3.91521143e+03 3.72575854e+03 3.76410889e+03 3.92002612e+03 3.93532104e+03 3.83278931e+03 3.73368921e+03 3.67968262e+03 3.57122046e+03 3.58166553e+03 3.57211108e+03 3.41461084e+03 3.41247632e+03 3.50773267e+03 3.41516821e+03 3.23094067e+03 3.17177661e+03 3.29033472e+03 3.34772900e+03 3.25963721e+03 3.11181812e+03 2.98436914e+03 2.96414844e+03 3.00490088e+03 3.09815137e+03 3.00516846e+03 2.80619873e+03 2.80971069e+03 2.81112354e+03 2.79364600e+03 2.80672192e+03 2.68124390e+03 2.62400391e+03 2.65735156e+03 2.61951611e+03 2.53771777e+03 2.46951147e+03 2.46403711e+03 2.48065674e+03 2.43042969e+03 2.33328638e+03 2.25813550e+03 2.29443188e+03 2.32578394e+03 2.26755762e+03 2.18659326e+03 2.09606836e+03 2.09693018e+03 2.12324658e+03 2.08658105e+03 2.01365918e+03 1.90531494e+03 1.88530054e+03 1.94120105e+03 1.95707849e+03 1.88381677e+03 1.76246240e+03 1.74604456e+03 1.77373230e+03 1.73252087e+03 1.66419250e+03 1.61209058e+03 1.64294385e+03 1.63439783e+03 1.55936047e+03 1.51495959e+03 1.46209741e+03 1.47585388e+03 1.50324377e+03 1.44147253e+03 1.37515564e+03 1.32351160e+03 1.30745471e+03 1.30408594e+03 1.30077502e+03 1.25775610e+03 1.17980664e+03 1.15707849e+03 1.18021350e+03 1.16949670e+03 1.11455005e+03 1.06037500e+03 1.04847571e+03 1.04887878e+03 1.02464307e+03 9.81427734e+02 9.23212585e+02 9.12010620e+02 9.25323486e+02 8.99762329e+02 8.62030334e+02 8.19314087e+02 8.01855713e+02 7.99598572e+02 7.95540100e+02 7.63711243e+02 7.10446716e+02 6.95582092e+02 6.87432434e+02 6.68094299e+02 6.49402893e+02 6.17601929e+02 6.03320068e+02 5.87430908e+02 5.63056091e+02 5.41663940e+02 5.21032837e+02 5.16868042e+02 5.05891663e+02 4.81124176e+02 4.50322266e+02 4.26512848e+02 4.24976257e+02 4.23512970e+02 4.02192627e+02 3.76323120e+02 3.50727814e+02 3.31618500e+02 3.29126404e+02 3.29130981e+02 3.05482452e+02 2.76852814e+02 2.68251770e+02 2.64499908e+02 2.53678619e+02 2.39241272e+02 2.21297577e+02 2.10208740e+02 2.01687714e+02 1.88152161e+02 1.75603333e+02 1.66336899e+02 1.58646927e+02 1.48882019e+02 1.38269958e+02 1.28551895e+02 1.19061073e+02 1.12362503e+02 1.06056541e+02 9.77825394e+01 8.70319977e+01 7.84953079e+01 7.47823181e+01 6.93334503e+01 6.20503922e+01 5.50269852e+01 4.81446953e+01 4.34797859e+01 4.04383698e+01 3.66298103e+01 3.16353149e+01 2.67013016e+01 2.32209854e+01 2.06141605e+01 1.79380894e+01 1.52927103e+01 1.30321903e+01 1.12558336e+01 9.75914383e+00 8.60607910e+00 7.76575327e+00 7.25419855e+00 7.07410622e+00 7.25740385e+00 7.81485939e+00 8.72159100e+00 9.78370857e+00 1.11952696e+01 1.30002594e+01 1.51536064e+01 1.79638996e+01 2.08338623e+01 2.43436852e+01 2.79748497e+01 3.08028011e+01 3.46489944e+01 3.98445206e+01 4.61860313e+01 5.27611885e+01 5.73079567e+01 6.01816483e+01 6.47406693e+01 7.28950882e+01 8.33213348e+01 9.28819733e+01 9.87660294e+01 1.01466743e+02 1.09099419e+02 1.24480461e+02 1.33779251e+02 1.36508270e+02 1.45494873e+02 1.58233871e+02 1.68795395e+02 1.84263840e+02 1.90979111e+02 1.95614624e+02 2.12742615e+02 2.19773346e+02 2.36538513e+02 2.56647949e+02 2.56413513e+02 2.75302948e+02 2.97278809e+02 3.03106873e+02 3.17157440e+02 3.30930481e+02 3.46974731e+02 3.64078125e+02 3.77636108e+02 3.83527863e+02 3.98154480e+02 4.32236725e+02 4.62865265e+02 4.71056366e+02 4.66077972e+02 4.72556946e+02 4.98932526e+02 5.41366028e+02 5.76616333e+02 5.84889343e+02 5.68903137e+02 5.88699829e+02 6.34723083e+02 6.49737976e+02 6.61215820e+02 6.82074341e+02 7.05816772e+02 7.27530090e+02 7.73609802e+02 7.77505798e+02 7.73899109e+02 8.14935303e+02 8.19305481e+02 8.68255981e+02 9.07823425e+02 9.11371887e+02 9.64207214e+02 9.58858887e+02 9.54480896e+02 1.00548230e+03 1.00779712e+03 1.05296826e+03 1.15175293e+03 1.11870190e+03 1.08191724e+03 1.13315869e+03 1.21048315e+03 1.28477429e+03 1.28676282e+03 1.24251172e+03 1.22957214e+03 1.29080933e+03 1.39291809e+03 1.46480493e+03 1.46002966e+03 1.40938831e+03 1.42736938e+03 1.51155139e+03 1.56607544e+03 1.55821863e+03 1.56831970e+03 1.62255713e+03 1.66155786e+03 1.74110950e+03 1.76826123e+03 1.71663452e+03 1.74931836e+03 1.79842773e+03 1.83975891e+03 1.89424463e+03 1.92363782e+03 1.99902722e+03 1.99410742e+03 1.96091248e+03 2.03698169e+03 2.02525964e+03 2.11661182e+03 2.28903589e+03 2.20045410e+03 2.10386230e+03 2.18129834e+03 2.32901294e+03 2.44004199e+03 2.47085913e+03 2.37718286e+03 2.31664209e+03 2.40022168e+03 2.56666016e+03 2.70825513e+03 2.66348706e+03 2.56021777e+03 2.57058936e+03 2.68234668e+03 2.76733154e+03 2.88334424e+03 2.90577954e+03 2.78315356e+03 2.81270337e+03 2.99938770e+03 3.05869873e+03 2.98765210e+03 3.01973804e+03 3.06529858e+03 3.09199561e+03 3.26685205e+03 3.32537402e+03 3.20016577e+03 3.22011694e+03 3.29763647e+03 3.37316479e+03 3.43568091e+03 3.43787598e+03 3.56634985e+03 3.65297656e+03 3.58435938e+03 3.54939648e+03 3.52966235e+03 3.70207471e+03 3.95678613e+03 3.92735132e+03 3.76589136e+03 3.69962134e+03 3.90820386e+03 4.16740869e+03 4.06020190e+03 3.88358228e+03 3.98185425e+03 4.15124316e+03 4.30828076e+03 4.47045215e+03 4.42047363e+03 4.21856006e+03 4.19087695e+03 4.36688037e+03 4.55895703e+03 4.62212500e+03 4.58051904e+03 4.56910352e+03 4.63046826e+03 4.78685840e+03 4.78972998e+03 4.69206250e+03 4.71424756e+03 4.74927588e+03 5.02086914e+03 5.12510254e+03 5.00061279e+03 5.06220947e+03 5.14569092e+03 5.29674951e+03 5.21091260e+03 4.98779932e+03 5.28670996e+03 5.61743994e+03 5.52152832e+03 5.28499805e+03 5.38299512e+03 5.68714404e+03 5.74645361e+03 5.66666699e+03 5.69932227e+03 5.59194336e+03 5.60707715e+03 5.95507031e+03 6.03474902e+03 5.78370410e+03 5.71708984e+03 5.77838379e+03 6.13992139e+03 6.43503076e+03 6.20969385e+03 6.04221094e+03 6.24814160e+03 6.30456982e+03 6.56395215e+03 6.54513965e+03 6.21761035e+03 6.36372607e+03 6.60095801e+03 6.57543164e+03 6.65926318e+03 6.63796973e+03 6.83114551e+03 6.89931299e+03 6.71795557e+03 6.79571338e+03 6.78288037e+03 6.98278369e+03 7.31315137e+03 7.23671777e+03 6.95376318e+03 7.00890625e+03 7.33448926e+03 7.65250537e+03 8.06302979e+03 8.21938281e+03 7.46150000e+03 9.00071484e+03 1.66706953e+04 1.29479797e+05 9566066. 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. 0. 0. 0. 0. 0. 0. 0. -48046348. -4266036. -1.02103375e+06 -3.33407825e+06 3.03557988e+04 1.54779717e+04 1.29424521e+04 1.04856084e+04 1.02545146e+04 1.00759600e+04 9.61271387e+03 9.99475488e+03 1.01549814e+04 9.88825000e+03 9.94362598e+03 9.96812598e+03 9.98834961e+03 1.00739688e+04 1.00573906e+04 1.00216025e+04 1.00763848e+04 1.01085498e+04 1.03548213e+04 1.04439824e+04 1.00811816e+04 1.01262471e+04 1.06655166e+04 1.07627559e+04 1.05388691e+04 1.05853203e+04 1.05881855e+04 1.06649785e+04 1.06547998e+04 1.06857695e+04 1.07361543e+04 1.07743789e+04 1.07134521e+04 1.07286748e+04 1.10469580e+04 1.11369082e+04 1.10032559e+04 1.10339922e+04 1.11031289e+04 1.11302246e+04 1.11333174e+04 1.11556045e+04 1.12226406e+04 1.09353848e+04 1.09587627e+04 1.12596084e+04 1.13015332e+04 1.17557139e+04 1.18465254e+04 1.14676865e+04 1.11629307e+04 1.11564277e+04 1.19519473e+04 1.20826504e+04 1.16432256e+04 1.14702090e+04 1.15226045e+04 1.16836318e+04 1.16727217e+04 1.21237529e+04 1.21823555e+04 1.14984932e+04 1.13939092e+04 1.20592559e+04 1.25978115e+04 1.22695254e+04 1.20250225e+04 1.21396523e+04 1.21246064e+04 1.20174541e+04 1.21193066e+04 1.21317803e+04 1.21028066e+04 1.21980293e+04 1.22047168e+04 1.23871162e+04 1.23669590e+04 1.26423281e+04 1.26725342e+04 1.23341289e+04 1.24925342e+04 1.25669414e+04 1.26225537e+04 1.27193564e+04 1.26497871e+04 1.26375166e+04 1.23845586e+04 1.21621006e+04 1.27690664e+04 1.29750195e+04 1.23280254e+04 1.24568574e+04 1.32041045e+04 1.35630479e+04 1.31786523e+04 1.28564521e+04 1.28206934e+04 1.28396025e+04 1.27684951e+04 1.27508281e+04 1.30381885e+04 1.30079160e+04 1.33286855e+04 1.32854277e+04 1.29476025e+04 1.31793320e+04 1.28664688e+04 1.29331016e+04 1.36293105e+04 1.35186104e+04 1.32384580e+04 1.29760459e+04 1.27732246e+04 1.35209561e+04 1.38254199e+04 1.33677061e+04 1.29799785e+04 1.30440684e+04 1.33826260e+04 1.33579668e+04 1.37856484e+04 1.38733467e+04 1.34415107e+04 1.32055557e+04 1.32169727e+04 1.37771768e+04 1.38107461e+04 1.35068740e+04 1.33466807e+04 1.33735938e+04 1.35732031e+04 1.32215010e+04 1.33111328e+04 1.41162920e+04 1.40012129e+04 1.36315781e+04 1.32855850e+04 1.32190254e+04 1.40524229e+04 1.41144336e+04 1.36985586e+04 1.33719883e+04 1.33025977e+04 1.37056836e+04 1.37261133e+04 1.37184854e+04 1.33801123e+04 1.36674736e+04 1.43940166e+04 1.40177920e+04 1.38833652e+04 1.39608438e+04 1.38388271e+04 1.36466309e+04 1.36467852e+04 1.38236494e+04 1.38114570e+04 1.37563057e+04 1.33564180e+04 1.35870791e+04 1.44415391e+04 1.38926455e+04 1.34273633e+04 1.38190605e+04 1.37985068e+04 1.42284727e+04 1.39718623e+04 1.34030322e+04 1.41707168e+04 1.42736875e+04 1.38369111e+04 1.37687695e+04 1.37289688e+04 1.37147686e+04 1.37371465e+04 1.37687861e+04 1.33652725e+04 1.37161885e+04 1.45734580e+04 1.42759492e+04 1.37446162e+04 1.33320312e+04 1.34813164e+04 1.42896797e+04 1.42625488e+04 1.38811094e+04 1.35010107e+04 1.34059775e+04 1.37981934e+04 1.37775127e+04 1.41146191e+04 1.38264111e+04 1.33601963e+04 1.37729766e+04 1.37933535e+04 1.40681582e+04 1.39893047e+04 1.36034619e+04 1.36061494e+04 1.36016865e+04 1.37646260e+04 1.33941758e+04 1.35322920e+04 1.42622158e+04 1.40028857e+04 1.36620986e+04 1.32978193e+04 1.32076895e+04 1.39522227e+04 1.40110342e+04 1.36090225e+04 1.32118789e+04 1.31845781e+04 1.36028828e+04 1.35939150e+04 1.39024961e+04 1.37170781e+04 1.33671670e+04 1.32194297e+04 1.31379580e+04 1.38299453e+04 1.37310010e+04 1.32887910e+04 1.32291953e+04 1.32158643e+04 1.35844141e+04 1.36075508e+04 1.30297451e+04 1.29619727e+04 1.36319648e+04 1.36091689e+04 1.29213320e+04 1.28286504e+04 1.35398164e+04 1.35677480e+04 1.31039834e+04 1.27854072e+04 1.27543506e+04 1.35008818e+04 1.33610195e+04 1.29260537e+04 1.30129482e+04 1.29352881e+04 1.28957441e+04 1.28724844e+04 1.28446211e+04 1.25135479e+04 1.28051631e+04 1.34958008e+04 1.30670811e+04 1.28590283e+04 1.29343975e+04 1.27985273e+04 1.27754473e+04 1.27375967e+04 1.26778730e+04 1.23499463e+04 1.21207646e+04 1.23858594e+04 1.26975791e+04 1.30817334e+04 1.25786162e+04 1.20977529e+04 1.23855098e+04 1.25025576e+04 1.28439600e+04 1.26449805e+04 1.22442100e+04 1.21341914e+04 1.20517305e+04 1.22681289e+04 1.22167822e+04 1.24779775e+04 1.24061514e+04 1.20525059e+04 1.18885889e+04 1.15330957e+04 1.20004775e+04 1.26684268e+04 1.23678281e+04 1.19718086e+04 1.16055088e+04 1.14336602e+04 1.19759316e+04 1.23057656e+04 1.18921133e+04 1.14102725e+04 1.13777168e+04 1.16922598e+04 1.15905176e+04 1.18677266e+04 1.17925801e+04 1.14170371e+04 1.14221758e+04 1.13645107e+04 1.15796914e+04 1.15826279e+04 1.10322773e+04 1.09906260e+04 1.15683184e+04 1.13163047e+04 1.07038896e+04 1.10175049e+04 1.15988154e+04 1.13861172e+04 1.09985576e+04 1.07220840e+04 1.06951055e+04 1.12724102e+04 1.12087285e+04 1.07959414e+04 1.05518682e+04 1.04287490e+04 1.06896797e+04 1.06545684e+04 1.06124580e+04 1.03368428e+04 1.05160293e+04 1.09227363e+04 1.06131455e+04 1.05871982e+04 1.04755459e+04 1.02454541e+04 1.02971260e+04 1.02931484e+04 1.02506230e+04 1.01779199e+04 1.00077998e+04 9.77068457e+03 9.95404688e+03 1.04798926e+04 1.00133701e+04 9.54327539e+03 9.80739648e+03 9.91091504e+03 1.01673311e+04 9.96881836e+03 9.58658203e+03 9.77730957e+03 9.73440234e+03 9.28782129e+03 9.20200781e+03 9.74043945e+03 9.66731445e+03 9.33879883e+03 9.17329297e+03 8.83440625e+03 9.17620508e+03 9.72435254e+03 9.36419043e+03 9.10509082e+03 8.80142090e+03 8.71916602e+03 9.08981836e+03 9.35255469e+03 9.06388184e+03 8.57540234e+03 8.46045020e+03 8.66524023e+03 8.75855566e+03 8.94880273e+03 8.74344141e+03 8.41408301e+03 8.55326270e+03 8.45559766e+03 8.59199902e+03 8.48094043e+03 8.23054395e+03 8.29182910e+03 8.20525781e+03 8.15745361e+03 7.83743604e+03 7.91402148e+03 8.40375000e+03 8.17489893e+03 7.83029395e+03 7.63614209e+03 7.67867578e+03 8.05082617e+03 7.99083643e+03 7.71938574e+03 7.46670996e+03 7.38442236e+03 7.53933057e+03 7.47383594e+03 7.47017480e+03 7.22406396e+03 7.32538330e+03 7.62149268e+03 7.32413135e+03 7.33888135e+03 7.30358838e+03 7.07349609e+03 7.03175830e+03 6.98564600e+03 6.94168164e+03 6.88190234e+03 6.86856396e+03 6.78884375e+03 6.89059766e+03 6.88232910e+03 6.51583594e+03 6.35345996e+03 6.47497656e+03 6.60716309e+03 6.73101562e+03 6.50058496e+03 6.18053760e+03 6.39110107e+03 6.49988818e+03 6.30124658e+03 6.09922754e+03 6.04179883e+03 6.08434131e+03 6.08796387e+03 5.99335449e+03 5.77736133e+03 5.90344482e+03 6.14984912e+03 5.94942969e+03 5.79802100e+03 5.60125537e+03 5.54074268e+03 5.79835742e+03 5.74902832e+03 5.54781494e+03 5.36275000e+03 5.19624121e+03 5.29092676e+03 5.43825830e+03 5.53957764e+03 5.27715088e+03 4.99363721e+03 5.09924756e+03 5.13143896e+03 5.23875684e+03 5.09280225e+03 4.86371338e+03 4.96387402e+03 4.90766162e+03 4.75013574e+03 4.58352881e+03 4.71516797e+03 4.91758154e+03 4.74039209e+03 4.62277734e+03 4.45971875e+03 4.39362939e+03 4.60155371e+03 4.55327344e+03 4.37994141e+03 4.22152979e+03 4.13767920e+03 4.23471533e+03 4.18953906e+03 4.26537598e+03 4.24332227e+03 4.03138232e+03 3.92429150e+03 3.92403638e+03 4.06084448e+03 3.92593750e+03 3.78325903e+03 3.80626660e+03 3.77432129e+03 3.66464526e+03 3.57782715e+03 3.69266113e+03 3.64027539e+03 3.49085107e+03 3.58706812e+03 3.57075854e+03 3.44955957e+03 3.38889844e+03 3.34036108e+03 3.31131543e+03 3.19257080e+03 3.10681055e+03 3.22949048e+03 3.22598462e+03 3.02586719e+03 2.88603271e+03 2.99275488e+03 3.13905566e+03 3.04066211e+03 2.84724634e+03 2.75491797e+03 2.86229785e+03 2.86727197e+03 2.74955713e+03 2.72817578e+03 2.61132642e+03 2.50128467e+03 2.56828027e+03 2.63830786e+03 2.59462158e+03 2.45229565e+03 2.34813330e+03 2.43479517e+03 2.46977515e+03 2.35954639e+03 2.23539038e+03 2.17618042e+03 2.20709204e+03 2.19205615e+03 2.21129175e+03 2.16879834e+03 2.04812329e+03 2.04123218e+03 2.02456702e+03 2.02542212e+03 1.92826453e+03 1.85588989e+03 1.90570044e+03 1.87221899e+03 1.81519946e+03 1.73991650e+03 1.72613342e+03 1.79443958e+03 1.69143445e+03 1.59426917e+03 1.60932373e+03 1.61149878e+03 1.58058704e+03 1.53178699e+03 1.53746338e+03 1.51899500e+03 1.44684705e+03 1.37629919e+03 1.34210327e+03 1.38796045e+03 1.33505920e+03 1.26684558e+03 1.28654639e+03 1.25926501e+03 1.20670581e+03 1.16964014e+03 1.18355481e+03 1.15056934e+03 1.09147180e+03 1.08996533e+03 1.06445459e+03 1.04527112e+03 1.02228638e+03 9.87083740e+02 9.52129578e+02 9.03259094e+02 8.77649841e+02 8.99599670e+02 9.05609802e+02 8.35037964e+02 7.73568665e+02 7.84384277e+02 8.05611328e+02 7.78857666e+02 7.21042908e+02 6.73815552e+02 6.86380249e+02 6.86076172e+02 6.46817993e+02 6.35674744e+02 6.12262756e+02 5.72896606e+02 5.58217651e+02 5.60144897e+02 5.44197266e+02 5.03614838e+02 4.72984924e+02 4.76258911e+02 4.79244690e+02 4.49621887e+02 4.14413818e+02 3.91930634e+02 3.95480896e+02 3.91770905e+02 3.63300659e+02 3.39794800e+02 3.26228394e+02 3.16568115e+02 3.01507446e+02 2.95197662e+02 2.75534576e+02 2.54212769e+02 2.50202362e+02 2.38896347e+02 2.28033722e+02 2.11075821e+02 1.95891617e+02 1.91916977e+02 1.76665070e+02 1.64429108e+02 1.59450775e+02 1.49228775e+02 1.39165527e+02 1.29321075e+02 1.23701530e+02 1.15698349e+02 1.04004852e+02 9.35617676e+01 8.61697540e+01 8.39078064e+01 7.74404068e+01 6.83837662e+01 5.59179344e+01 5.45169220e+01 7.72713776e+01 3.65143677e+02 8.01840625e+03 0. 0. 0. 0. 0. -56120612. -34281240. 6.52675850e+06 3.40030098e+01 1.89090118e+01 1.26296749e+01 -2704380. -18916922. 38412828. 38412828. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -103217192. -78265800. 8824339. 3.13379852e+02 1.86389740e+02 8.17611465e+01 5.69053612e+01 7.77539215e+01 8.05823593e+01 8.58389511e+01 9.22694168e+01 9.94334946e+01 1.07255394e+02 1.12885963e+02 1.21422340e+02 1.32538971e+02 1.41193802e+02 1.50931610e+02 1.60394531e+02 1.68977890e+02 1.82205109e+02 1.92189453e+02 1.99865952e+02 2.12045670e+02 2.21581039e+02 2.34120193e+02 2.55764725e+02 2.71066833e+02 2.75637634e+02 2.86258484e+02 3.02224426e+02 3.17128296e+02 3.26955170e+02 3.39881073e+02 3.62345490e+02 3.78122711e+02 3.99871460e+02 4.14028168e+02 4.14791962e+02 4.35385559e+02 4.66922485e+02 4.87343750e+02 5.01159149e+02 5.02188507e+02 5.15247925e+02 5.49891846e+02 5.73028442e+02 5.84378845e+02 5.98351135e+02 6.18190857e+02 6.50980103e+02 6.79703491e+02 6.91903137e+02 6.92925659e+02 7.14426331e+02 7.70655945e+02 7.91198547e+02 7.71550903e+02 7.93701599e+02 8.42294678e+02 8.75481873e+02 9.07960327e+02 9.12372437e+02 9.07122498e+02 9.40612122e+02 9.88622009e+02 1.01957947e+03 1.03037061e+03 1.03908167e+03 1.08691113e+03 1.12972461e+03 1.13836389e+03 1.15333508e+03 1.17294812e+03 1.20898999e+03 1.25729407e+03 1.27970984e+03 1.31450977e+03 1.33431848e+03 1.32928796e+03 1.37412732e+03 1.41989026e+03 1.44363293e+03 1.47358398e+03 1.49147729e+03 1.52613708e+03 1.59320581e+03 1.61819250e+03 1.59442419e+03 1.63353638e+03 1.69186865e+03 1.73927844e+03 1.75926453e+03 1.76528284e+03 1.79850061e+03 1.85295178e+03 1.90709863e+03 1.92564050e+03 1.90927600e+03 1.96732593e+03 2.05220679e+03 2.08627490e+03 2.10494238e+03 2.08798145e+03 2.11501221e+03 2.21256812e+03 2.23869067e+03 2.22066211e+03 2.25927759e+03 2.31481128e+03 2.39626025e+03 2.42945532e+03 2.43838037e+03 2.47732397e+03 2.51234131e+03 2.58113965e+03 2.61508936e+03 2.60467261e+03 2.65347119e+03 2.70148193e+03 2.72062695e+03 2.78442676e+03 2.83034595e+03 2.86202197e+03 2.91587378e+03 2.92301367e+03 2.93910474e+03 3.02594189e+03 3.09390186e+03 3.10017480e+03 3.12803662e+03 3.13819336e+03 3.17367456e+03 3.27253638e+03 3.28614062e+03 3.30674927e+03 3.37295728e+03 3.49607031e+03 3.53554321e+03 3.47219336e+03 3.53880591e+03 3.61033301e+03 3.61451831e+03 3.61767139e+03 3.66832373e+03 3.74182104e+03 3.81993823e+03 3.92584839e+03 3.92830518e+03 3.90132495e+03 3.89334888e+03 3.98422266e+03 4.10420703e+03 4.14819092e+03 4.15802734e+03 4.14419336e+03 4.23221094e+03 4.35314648e+03 4.36008984e+03 4.33226318e+03 4.32762842e+03 4.44503809e+03 4.58592188e+03 4.57967627e+03 4.45647705e+03 4.55340576e+03 4.73913623e+03 4.77048779e+03 4.73410010e+03 4.78300342e+03 4.86503955e+03 4.90419678e+03 4.99126855e+03 4.99562451e+03 4.93212500e+03 5.10161426e+03 5.26190088e+03 5.20907422e+03 5.23059229e+03 5.28214893e+03 5.24833252e+03 5.37952148e+03 5.41806348e+03 5.48537109e+03 5.62490137e+03 5.45533203e+03 5.50615332e+03 5.79059033e+03 5.71595508e+03 5.62057812e+03 5.76105176e+03 5.91261328e+03 5.93423340e+03 5.96405029e+03 5.99360596e+03 5.94786279e+03 5.95936572e+03 6.22680127e+03 6.34113135e+03 6.11628906e+03 6.19485059e+03 6.43493750e+03 6.39431445e+03 6.45579248e+03 6.39405664e+03 6.41124609e+03 6.60466113e+03 6.62470557e+03 6.66982910e+03 6.73997559e+03 6.68113477e+03 6.77592188e+03 6.94232812e+03 6.91136572e+03 6.91671289e+03 6.98215918e+03 7.07512500e+03 7.09830371e+03 7.12827979e+03 7.16041260e+03 7.19933203e+03 7.23502686e+03 7.37543848e+03 7.41301611e+03 7.38320557e+03 7.52369336e+03 7.66101270e+03 7.59570117e+03 7.83174268e+03 7.69792822e+03 7.51282471e+03 7.73622510e+03 7.87139209e+03 7.88694775e+03 7.80538135e+03 7.79882666e+03 8.00551123e+03 8.22234473e+03 8.16756836e+03 8.07853125e+03 8.27052344e+03 8.41448633e+03 8.21882910e+03 8.21401172e+03 8.48959375e+03 8.49313477e+03 8.33962695e+03 8.66789844e+03 8.59770605e+03 8.52289941e+03 8.69537012e+03 8.68353906e+03 8.67420312e+03 8.78003613e+03 8.82347852e+03 8.79587305e+03 8.96772852e+03 9.13252246e+03 9.21367285e+03 8.94834375e+03 8.94277539e+03 9.26627930e+03 9.21479980e+03 9.30063574e+03 9.32638086e+03 9.25617383e+03 9.34001855e+03 9.48919629e+03 9.63606348e+03 9.48938086e+03 9.32184961e+03 9.61858301e+03 9.98693750e+03 9.65078027e+03 9.49865918e+03 9.72575488e+03 9.73851562e+03 9.93654102e+03 1.00799893e+04 9.90628711e+03 9.93025391e+03 1.00749385e+04 1.01277676e+04 1.02465557e+04 1.02357051e+04 1.03100674e+04 1.04651416e+04 1.00615332e+04 1.02473564e+04 1.04386729e+04 1.03108994e+04 1.05835693e+04 1.05574834e+04 1.04208252e+04 1.06527666e+04 1.05915781e+04 1.06074561e+04 1.09923525e+04 1.09096592e+04 1.07322217e+04 1.06849854e+04 1.06666221e+04 1.09295283e+04 1.11367314e+04 1.09436729e+04 1.09396230e+04 1.12230400e+04 1.12814736e+04 1.12129531e+04 1.10935225e+04 1.11458867e+04 1.11853330e+04 1.13576719e+04 1.14909609e+04 1.11998359e+04 1.12492979e+04 1.15176689e+04 1.15884854e+04 1.16046338e+04 1.16468604e+04 1.15480703e+04 1.14964131e+04 1.19281201e+04 1.20516621e+04 1.16477881e+04 1.15213662e+04 1.16309111e+04 1.18350244e+04 1.18936914e+04 1.17946982e+04 1.19727344e+04 1.20547080e+04 1.20468379e+04 1.21752881e+04 1.20953311e+04 1.19834102e+04 1.21869053e+04 1.23768906e+04 1.21770186e+04 1.19774365e+04 1.22099463e+04 1.22574951e+04 1.23073154e+04 1.25052637e+04 1.23884443e+04 1.22664180e+04 1.24205625e+04 1.27430068e+04 1.25725732e+04 1.23404697e+04 1.25094814e+04 1.26021426e+04 1.26068428e+04 1.25874609e+04 1.24833242e+04 1.26055840e+04 1.27457676e+04 1.28810332e+04 1.30039521e+04 1.27626787e+04 1.28221426e+04 1.28366445e+04 1.27625869e+04 1.27874131e+04 1.27550498e+04 1.29873750e+04 1.30277041e+04 1.29082402e+04 1.28294541e+04 1.28793398e+04 1.31831748e+04 1.33270527e+04 1.33363525e+04 1.31388740e+04 1.30427246e+04 1.30844883e+04 1.29529170e+04 1.30894033e+04 1.32965332e+04 1.32613555e+04 1.32347568e+04 1.30523262e+04 1.30532266e+04 1.34121953e+04 1.35934717e+04 1.36307539e+04 1.33329395e+04 1.30776826e+04 1.32991094e+04 1.34181895e+04 1.33528135e+04 1.34986299e+04 1.36261250e+04 1.33826143e+04 1.32525527e+04 1.33092754e+04 1.33372793e+04 1.37864453e+04 1.38993223e+04 1.34507051e+04 1.35832812e+04 1.35129150e+04 1.32364990e+04 1.36988271e+04 1.38621182e+04 1.34677197e+04 1.34676865e+04 1.34654043e+04 1.33335361e+04 1.37299805e+04 1.41132334e+04 1.37662051e+04 1.35434873e+04 1.36358916e+04 1.36407500e+04 1.37583584e+04 1.37073916e+04 1.36845820e+04 1.36810596e+04 1.36732178e+04 1.37897646e+04 1.38181475e+04 1.36660820e+04 1.37977539e+04 1.40007461e+04 1.37397461e+04 1.35034727e+04 1.35674824e+04 1.38930723e+04 1.40818516e+04 1.40218320e+04 1.36269990e+04 1.33405781e+04 1.36528311e+04 1.40300371e+04 1.41859492e+04 1.38090146e+04 1.35281279e+04 1.38061738e+04 1.38342236e+04 1.37176641e+04 1.38906064e+04 1.38056729e+04 1.36318730e+04 1.39561543e+04 1.37916748e+04 1.32786396e+04 1.37753945e+04 1.42822939e+04 1.37645615e+04 1.35408359e+04 1.36639277e+04 1.36968896e+04 1.38846221e+04 1.39313848e+04 1.37998613e+04 1.34906719e+04 1.35297158e+04 1.37577881e+04 1.37228213e+04 1.38889375e+04 1.39195859e+04 1.36474951e+04 1.35419902e+04 1.37894170e+04 1.37497490e+04 1.36152891e+04 1.37930156e+04 1.38389502e+04 1.36033037e+04 1.33600527e+04 1.33851777e+04 1.35945615e+04 1.38256660e+04 1.37749082e+04 1.34486123e+04 1.33542451e+04 1.34230840e+04 1.35301064e+04 1.37232139e+04 1.36165127e+04 1.32426465e+04 1.34916289e+04 1.36319395e+04 1.33486641e+04 1.36969854e+04 1.36132832e+04 1.32371895e+04 1.33851992e+04 1.31430156e+04 1.30541631e+04 1.35648818e+04 1.35434609e+04 1.32750791e+04 1.33900166e+04 1.32522109e+04 1.28960088e+04 1.29921875e+04 1.32921221e+04 1.32280654e+04 1.32199307e+04 1.30804404e+04 1.29818594e+04 1.31038271e+04 1.31769053e+04 1.35293545e+04 1.32292529e+04 1.26282236e+04 1.27594141e+04 1.28857432e+04 1.30194863e+04 1.31936543e+04 1.28940352e+04 1.25508408e+04 1.28139678e+04 1.29847695e+04 1.28384473e+04 1.28583047e+04 1.27422217e+04 1.25395078e+04 1.27816445e+04 1.27294346e+04 1.24663213e+04 1.29062070e+04 1.29076523e+04 1.25487188e+04 1.24830508e+04 1.21200225e+04 1.21582979e+04 1.25180361e+04 1.28639736e+04 1.27092305e+04 1.19879883e+04 1.20158311e+04 1.24643896e+04 1.23551875e+04 1.22030088e+04 1.22009492e+04 1.20712676e+04 1.21408936e+04 1.21963271e+04 1.21828096e+04 1.20466426e+04 1.20541699e+04 1.21742773e+04 1.19614463e+04 1.17764209e+04 1.17810889e+04 1.17882363e+04 1.18852148e+04 1.20903389e+04 1.18073916e+04 1.14706738e+04 1.16156230e+04 1.17136172e+04 1.19246104e+04 1.18022188e+04 1.13217988e+04 1.14212656e+04 1.14934697e+04 1.15466914e+04 1.17169336e+04 1.14600400e+04 1.12777803e+04 1.12447559e+04 1.10813740e+04 1.10193145e+04 1.12861045e+04 1.14563242e+04 1.11543047e+04 1.09580596e+04 1.08180830e+04 1.08433242e+04 1.11657324e+04 1.11227881e+04 1.09698750e+04 1.08078457e+04 1.05215898e+04 1.05997842e+04 1.07214053e+04 1.08925557e+04 1.09060342e+04 1.04410557e+04 1.03589844e+04 1.04994863e+04 1.05245254e+04 1.04864219e+04 1.05126797e+04 1.04981445e+04 1.02227549e+04 1.01557109e+04 1.01604346e+04 1.01500312e+04 1.01961787e+04 1.01900605e+04 1.01103799e+04 9.97702246e+03 9.88333984e+03 9.89274219e+03 1.00871035e+04 9.95215918e+03 9.68025195e+03 9.63471582e+03 9.62911328e+03 9.54594434e+03 9.88905469e+03 9.75562891e+03 9.35769238e+03 9.52405469e+03 9.34396484e+03 9.42475391e+03 9.67541699e+03 9.34086816e+03 9.20091504e+03 9.18643262e+03 9.31758496e+03 9.32629980e+03 9.37015234e+03 9.01367090e+03 1.20796084e+04 1.26509990e+04 2.19850410e+04 4.13365781e+04 2854715. -212644064. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -38775816. 4.02248450e+06 2.54136172e+04 1.74068867e+04 9.17053125e+03 7.07957617e+03 8.92572949e+03 7.43522266e+03 6.49456982e+03 6.44665967e+03 6.62719287e+03 6.51602539e+03 6.27682812e+03 6.08454834e+03 6.10238477e+03 6.23090479e+03 6.26459619e+03 6.14704492e+03 5.94988770e+03 5.88071045e+03 5.84439941e+03 5.93518701e+03 5.87920801e+03 5.57202783e+03 5.62376709e+03 5.74372656e+03 5.66710010e+03 5.49693945e+03 5.36039062e+03 5.46554883e+03 5.63202100e+03 5.60005078e+03 5.22262451e+03 4.96904346e+03 5.10202637e+03 5.28032910e+03 5.35021875e+03 5.19271826e+03 4.93244238e+03 4.93830811e+03 4.98420215e+03 5.03355957e+03 4.94774951e+03 4.64358154e+03 4.67927441e+03 4.87794824e+03 4.76949268e+03 4.57586377e+03 4.57575830e+03 4.54647168e+03 4.57862305e+03 4.52617529e+03 4.30812109e+03 4.19878613e+03 4.36259473e+03 4.42036670e+03 4.33755273e+03 4.12285889e+03 3.97668970e+03 4.12081348e+03 4.22181396e+03 4.08557935e+03 3.91855469e+03 3.74438892e+03 3.76805981e+03 3.91765259e+03 3.92035571e+03 3.82924121e+03 3.72235669e+03 3.67990869e+03 3.58647192e+03 3.56181445e+03 3.56808667e+03 3.41452197e+03 3.42567676e+03 3.51956519e+03 3.41927515e+03 3.21937769e+03 3.15470459e+03 3.27644019e+03 3.33737036e+03 3.25503320e+03 3.10661743e+03 2.98292798e+03 2.96125928e+03 2.99980127e+03 3.08387085e+03 3.00154443e+03 2.80164160e+03 2.79621851e+03 2.80801221e+03 2.79181030e+03 2.80591528e+03 2.67193481e+03 2.62124121e+03 2.65388135e+03 2.61254321e+03 2.53706689e+03 2.46185132e+03 2.45814966e+03 2.47473950e+03 2.43135229e+03 2.33361377e+03 2.25152197e+03 2.28247412e+03 2.32316162e+03 2.26834644e+03 2.18665283e+03 2.08769019e+03 2.10079297e+03 2.12418066e+03 2.08878198e+03 2.01352100e+03 1.90158435e+03 1.88518311e+03 1.94267920e+03 1.95376282e+03 1.87356213e+03 1.76005859e+03 1.74776697e+03 1.77055542e+03 1.72919470e+03 1.66166309e+03 1.60829333e+03 1.63621887e+03 1.63488086e+03 1.56050806e+03 1.50921814e+03 1.45578442e+03 1.47103760e+03 1.50317078e+03 1.44337402e+03 1.37209814e+03 1.32360278e+03 1.30512305e+03 1.29890295e+03 1.29582373e+03 1.25873022e+03 1.17827234e+03 1.15614722e+03 1.17886365e+03 1.16516858e+03 1.11318115e+03 1.06281665e+03 1.04891003e+03 1.04845850e+03 1.02597974e+03 9.83679321e+02 9.25169373e+02 9.13597168e+02 9.26804565e+02 9.00914551e+02 8.62834839e+02 8.20955750e+02 7.99488708e+02 7.98724792e+02 7.96008057e+02 7.65302551e+02 7.12535767e+02 6.95835449e+02 6.88942444e+02 6.71099670e+02 6.49846924e+02 6.19230042e+02 6.07377686e+02 5.88799866e+02 5.63090332e+02 5.42136719e+02 5.20051636e+02 5.16030273e+02 5.06347717e+02 4.81037476e+02 4.50649567e+02 4.26331421e+02 4.24829529e+02 4.23948883e+02 4.03273224e+02 3.77617188e+02 3.52424591e+02 3.33336578e+02 3.29983643e+02 3.30665588e+02 3.07738281e+02 2.79760834e+02 2.70362976e+02 2.66176086e+02 2.55547470e+02 2.42210403e+02 2.25274628e+02 2.14081833e+02 2.06040421e+02 1.90877548e+02 1.77525909e+02 1.68060516e+02 1.60395905e+02 1.51287415e+02 1.40361023e+02 1.29909653e+02 1.19770325e+02 1.13215431e+02 1.07569038e+02 9.97064133e+01 8.91878891e+01 8.04470673e+01 7.66998978e+01 7.17012787e+01 6.45497360e+01 5.76961250e+01 5.07460861e+01 4.58251610e+01 4.25339966e+01 3.84924164e+01 3.36422348e+01 2.86051369e+01 2.50043736e+01 2.26223545e+01 2.01309166e+01 1.74530487e+01 1.49896460e+01 1.30958033e+01 1.15877657e+01 1.03426943e+01 9.47210884e+00 8.98811722e+00 8.86597919e+00 9.06974411e+00 9.59690857e+00 1.03772612e+01 1.13973207e+01 1.29992743e+01 1.50452623e+01 1.72501087e+01 1.98031654e+01 2.25000401e+01 2.61433163e+01 2.96926155e+01 3.24013214e+01 3.61868172e+01 4.14016685e+01 4.78830414e+01 5.45054283e+01 5.89718056e+01 6.18284874e+01 6.63536530e+01 7.46914291e+01 8.52621002e+01 9.46574249e+01 1.00360184e+02 1.03146866e+02 1.10542877e+02 1.25798927e+02 1.35642990e+02 1.37588120e+02 1.46051788e+02 1.58631500e+02 1.69364105e+02 1.85679550e+02 1.92277191e+02 1.96422089e+02 2.13379318e+02 2.20666260e+02 2.37406403e+02 2.57241730e+02 2.56794830e+02 2.75594910e+02 2.97883820e+02 3.04351715e+02 3.18419983e+02 3.31485352e+02 3.47094940e+02 3.64757843e+02 3.79077209e+02 3.84103149e+02 3.98832092e+02 4.33508759e+02 4.62944550e+02 4.71181915e+02 4.66846771e+02 4.73178986e+02 4.99145691e+02 5.41048218e+02 5.76229004e+02 5.84605225e+02 5.70687744e+02 5.90377563e+02 6.33922607e+02 6.50367310e+02 6.62512695e+02 6.81615723e+02 7.04901245e+02 7.27261902e+02 7.73035400e+02 7.77501770e+02 7.74509216e+02 8.14493225e+02 8.18705261e+02 8.64666077e+02 9.06522522e+02 9.09912537e+02 9.60528137e+02 9.56968262e+02 9.51965149e+02 1.00603839e+03 1.00519183e+03 1.05129102e+03 1.15083081e+03 1.11820483e+03 1.07915979e+03 1.13010400e+03 1.21041687e+03 1.28465515e+03 1.28258228e+03 1.23935107e+03 1.22981665e+03 1.28785938e+03 1.38576672e+03 1.46081177e+03 1.45559192e+03 1.40836890e+03 1.42601416e+03 1.50871777e+03 1.56266992e+03 1.55720398e+03 1.56220032e+03 1.61835095e+03 1.65662842e+03 1.72965405e+03 1.76315222e+03 1.71387732e+03 1.74391479e+03 1.79700867e+03 1.83873389e+03 1.89441223e+03 1.91867981e+03 1.99263208e+03 1.99105164e+03 1.95766187e+03 2.03205518e+03 2.02216528e+03 2.11456665e+03 2.28340894e+03 2.19999609e+03 2.09497607e+03 2.17845215e+03 2.32776001e+03 2.43530225e+03 2.46525708e+03 2.36815503e+03 2.31042749e+03 2.38780200e+03 2.55353052e+03 2.70134814e+03 2.66288599e+03 2.54978320e+03 2.56889648e+03 2.68094336e+03 2.75537500e+03 2.87555664e+03 2.89681323e+03 2.77978955e+03 2.79871118e+03 2.98766382e+03 3.04682471e+03 2.98060449e+03 3.01138770e+03 3.06352930e+03 3.07899219e+03 3.25133765e+03 3.32290039e+03 3.19648560e+03 3.21459497e+03 3.29114111e+03 3.36491528e+03 3.43013086e+03 3.43680396e+03 3.56566577e+03 3.65874438e+03 3.57419214e+03 3.54331470e+03 3.50827734e+03 3.69578882e+03 3.95130884e+03 3.90870630e+03 3.75566626e+03 3.70086865e+03 3.88995630e+03 4.14900928e+03 4.06422314e+03 3.88094629e+03 3.99704688e+03 4.13571875e+03 4.31147168e+03 4.46438281e+03 4.41791797e+03 4.20330322e+03 4.17191504e+03 4.35214209e+03 4.54810352e+03 4.59033057e+03 4.57208350e+03 4.59900439e+03 4.61983887e+03 4.75931982e+03 4.77674512e+03 4.67630518e+03 4.67839209e+03 4.74987988e+03 5.02631494e+03 5.10740869e+03 5.00940137e+03 5.06469678e+03 5.13841113e+03 5.24960400e+03 5.20674072e+03 4.98017285e+03 5.26289014e+03 5.60920947e+03 5.49903320e+03 5.26107861e+03 5.32420508e+03 5.65681934e+03 5.73186523e+03 5.66909375e+03 5.67925781e+03 5.57214795e+03 5.62457861e+03 5.95868018e+03 6.01382031e+03 5.79242285e+03 5.72230225e+03 5.79347803e+03 6.10956494e+03 6.40098877e+03 6.16277832e+03 6.02828760e+03 6.20600977e+03 6.29010547e+03 6.52781445e+03 6.54065039e+03 6.17578564e+03 6.33070801e+03 6.58138721e+03 6.58411914e+03 6.64576611e+03 6.63150293e+03 6.84263525e+03 6.86682715e+03 6.70849121e+03 6.77974902e+03 6.69648584e+03 6.98708838e+03 7.35866602e+03 7.21143164e+03 6.95526660e+03 6.91124072e+03 7.32353027e+03 7.62608105e+03 8.06170996e+03 8.58055762e+03 7.69344971e+03 9.38482129e+03 1.45109707e+04 1.26861180e+05 9566066. 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. 0. 0. 0. 0. 0. 0. 0. -48046348. -4266036. -1.02103375e+06 -3.33407825e+06 3.03557988e+04 2.35677363e+04 1.33478301e+04 1.30239414e+04 1.05433682e+04 1.03307695e+04 9.91283887e+03 1.01404814e+04 1.00234697e+04 9.70558496e+03 9.98239648e+03 1.00186758e+04 1.03586074e+04 1.04589785e+04 9.59509082e+03 9.50972363e+03 9.79749121e+03 1.00816387e+04 9.99660352e+03 9.86714746e+03 1.06334229e+04 1.03900400e+04 1.01465166e+04 1.06663262e+04 1.06719736e+04 1.03523096e+04 1.07383408e+04 1.11292041e+04 1.08530352e+04 1.07243516e+04 1.07380664e+04 1.07280820e+04 1.06767305e+04 1.07440723e+04 1.10781025e+04 1.11281172e+04 1.09938340e+04 1.10031631e+04 1.10451240e+04 1.10916318e+04 1.10965703e+04 1.11142910e+04 1.11848506e+04 1.09045615e+04 1.08905684e+04 1.12394238e+04 1.12809160e+04 1.17242998e+04 1.17975010e+04 1.14238164e+04 1.11265928e+04 1.11344629e+04 1.18903271e+04 1.20452334e+04 1.16138350e+04 1.14125781e+04 1.14882031e+04 1.16771562e+04 1.16533584e+04 1.20922656e+04 1.21272588e+04 1.14755156e+04 1.13835986e+04 1.20304590e+04 1.25340039e+04 1.22386621e+04 1.19754365e+04 1.20785889e+04 1.20797041e+04 1.19615781e+04 1.20682383e+04 1.21270752e+04 1.20811973e+04 1.21287705e+04 1.21481084e+04 1.23380127e+04 1.23178516e+04 1.26270137e+04 1.26184893e+04 1.22552822e+04 1.24789453e+04 1.25274014e+04 1.26045586e+04 1.26789365e+04 1.26130234e+04 1.26251533e+04 1.23666807e+04 1.20939678e+04 1.27219385e+04 1.29313076e+04 1.22912314e+04 1.24076738e+04 1.31502188e+04 1.35516650e+04 1.31576074e+04 1.28104307e+04 1.27800957e+04 1.28016016e+04 1.27446494e+04 1.27206289e+04 1.29889648e+04 1.29688096e+04 1.33007510e+04 1.32475889e+04 1.28987900e+04 1.31436846e+04 1.28111875e+04 1.28747646e+04 1.35883779e+04 1.34895713e+04 1.32064541e+04 1.29193984e+04 1.27304971e+04 1.34977090e+04 1.37694844e+04 1.32962578e+04 1.29450156e+04 1.30114023e+04 1.33606953e+04 1.33034238e+04 1.37303604e+04 1.38553818e+04 1.33779570e+04 1.31377344e+04 1.31780322e+04 1.37385225e+04 1.37749717e+04 1.34441738e+04 1.33136299e+04 1.33556787e+04 1.35177656e+04 1.31839326e+04 1.32798340e+04 1.40670469e+04 1.39599180e+04 1.35940146e+04 1.32566738e+04 1.31665840e+04 1.39900195e+04 1.40768389e+04 1.36612363e+04 1.33351172e+04 1.32548984e+04 1.36485107e+04 1.36856016e+04 1.36813721e+04 1.33300596e+04 1.36284043e+04 1.43558662e+04 1.39811592e+04 1.38548545e+04 1.39134170e+04 1.37803691e+04 1.36017178e+04 1.36047588e+04 1.37959863e+04 1.37718037e+04 1.36918594e+04 1.33101943e+04 1.35591514e+04 1.44091660e+04 1.38425977e+04 1.33866094e+04 1.37693994e+04 1.37509648e+04 1.41873281e+04 1.39302588e+04 1.33749023e+04 1.41192285e+04 1.42100049e+04 1.37986680e+04 1.37346123e+04 1.36950654e+04 1.36684648e+04 1.36853936e+04 1.37176865e+04 1.33247275e+04 1.36959209e+04 1.45272480e+04 1.41993848e+04 1.37015625e+04 1.32863291e+04 1.34381221e+04 1.42841338e+04 1.42336396e+04 1.38249814e+04 1.34469473e+04 1.33577217e+04 1.37713857e+04 1.37386826e+04 1.40478203e+04 1.37725762e+04 1.33237969e+04 1.37348467e+04 1.37493643e+04 1.40299141e+04 1.39446250e+04 1.35661016e+04 1.35606807e+04 1.35386074e+04 1.37256699e+04 1.33537568e+04 1.34799502e+04 1.42233721e+04 1.39544951e+04 1.36170352e+04 1.32657656e+04 1.31652852e+04 1.39098330e+04 1.39620762e+04 1.35635176e+04 1.31748301e+04 1.31341562e+04 1.35700889e+04 1.35765254e+04 1.38450479e+04 1.36629990e+04 1.33513164e+04 1.31876768e+04 1.30890742e+04 1.37952891e+04 1.36908193e+04 1.32477324e+04 1.31824688e+04 1.31736064e+04 1.35536504e+04 1.35660273e+04 1.29931494e+04 1.29184541e+04 1.35762871e+04 1.35602090e+04 1.28871064e+04 1.28047568e+04 1.34930781e+04 1.35367334e+04 1.30573330e+04 1.27458672e+04 1.27266748e+04 1.34535889e+04 1.33133896e+04 1.29038311e+04 1.29360693e+04 1.28696289e+04 1.28739980e+04 1.28287988e+04 1.28019385e+04 1.24632910e+04 1.27711338e+04 1.34649111e+04 1.30302949e+04 1.28224531e+04 1.29101113e+04 1.27886738e+04 1.27539258e+04 1.26980508e+04 1.26497109e+04 1.23105723e+04 1.20895137e+04 1.23486191e+04 1.26450791e+04 1.30194414e+04 1.25239834e+04 1.20540322e+04 1.23497451e+04 1.24741914e+04 1.28144873e+04 1.26068799e+04 1.22077812e+04 1.20866104e+04 1.19775303e+04 1.22143564e+04 1.21895703e+04 1.24059668e+04 1.23512842e+04 1.20281172e+04 1.18650713e+04 1.15044219e+04 1.19566816e+04 1.26085254e+04 1.23262910e+04 1.19191670e+04 1.15556465e+04 1.13996289e+04 1.19568896e+04 1.22338604e+04 1.18527090e+04 1.13871211e+04 1.13601455e+04 1.16287607e+04 1.15744209e+04 1.18631152e+04 1.17699395e+04 1.13724043e+04 1.14029980e+04 1.13388008e+04 1.15180986e+04 1.15334307e+04 1.10159199e+04 1.09623447e+04 1.15551367e+04 1.12816543e+04 1.06616484e+04 1.09964180e+04 1.15420195e+04 1.13135850e+04 1.09813408e+04 1.06774307e+04 1.06657002e+04 1.12528066e+04 1.11400635e+04 1.07794854e+04 1.04918760e+04 1.03946719e+04 1.06776689e+04 1.06342803e+04 1.05542842e+04 1.03023535e+04 1.04946064e+04 1.08993525e+04 1.05525205e+04 1.05226016e+04 1.04410244e+04 1.01927539e+04 1.02517373e+04 1.02209551e+04 1.02178320e+04 1.01148838e+04 9.98417676e+03 9.74676270e+03 9.93700195e+03 1.04692139e+04 9.95428809e+03 9.45826172e+03 9.71576953e+03 9.91547656e+03 1.01498936e+04 9.88998730e+03 9.55235547e+03 9.74775098e+03 9.72122852e+03 9.27706934e+03 9.13273926e+03 9.63735059e+03 9.63413770e+03 9.31554004e+03 9.11091699e+03 8.79739648e+03 9.12850195e+03 9.67303711e+03 9.35892090e+03 9.06598145e+03 8.77844727e+03 8.65514062e+03 9.07997754e+03 9.33505371e+03 9.02655371e+03 8.55365527e+03 8.47357910e+03 8.65646484e+03 8.74616309e+03 8.88542969e+03 8.68638184e+03 8.39292871e+03 8.50442871e+03 8.42215820e+03 8.51466406e+03 8.40071094e+03 8.22245020e+03 8.24489844e+03 8.17338916e+03 8.09033105e+03 7.81744482e+03 7.93195801e+03 8.37751660e+03 8.14860303e+03 7.80651123e+03 7.61017920e+03 7.66289160e+03 8.05935938e+03 7.96687744e+03 7.69786719e+03 7.44858936e+03 7.37213086e+03 7.50033643e+03 7.47164746e+03 7.41876172e+03 7.19705127e+03 7.29286475e+03 7.57069092e+03 7.28287012e+03 7.29408545e+03 7.27736719e+03 7.05234033e+03 7.00468652e+03 6.95712744e+03 6.88175195e+03 6.83698682e+03 6.80970850e+03 6.75769580e+03 6.87954102e+03 6.86185889e+03 6.46905713e+03 6.35452539e+03 6.49236914e+03 6.61343359e+03 6.73994189e+03 6.46674805e+03 6.14823584e+03 6.38794580e+03 6.47975488e+03 6.26927246e+03 6.07725146e+03 6.00591699e+03 6.09398584e+03 6.06836084e+03 5.96288721e+03 5.75514551e+03 5.88598486e+03 6.12574463e+03 5.94512256e+03 5.78499756e+03 5.60747021e+03 5.48615430e+03 5.77039453e+03 5.70137988e+03 5.51748975e+03 5.35667480e+03 5.15570312e+03 5.26043115e+03 5.42881299e+03 5.54320264e+03 5.26197412e+03 4.98087646e+03 5.07690137e+03 5.11562061e+03 5.21450732e+03 5.06572168e+03 4.85958350e+03 4.95236523e+03 4.89265723e+03 4.75459570e+03 4.57977930e+03 4.68836914e+03 4.89651709e+03 4.73823779e+03 4.62971387e+03 4.45494043e+03 4.39292236e+03 4.57565283e+03 4.54621338e+03 4.35677344e+03 4.20554492e+03 4.13891357e+03 4.23510107e+03 4.18384521e+03 4.25857812e+03 4.21245117e+03 4.02193555e+03 3.90739551e+03 3.91417261e+03 4.04188403e+03 3.90889648e+03 3.78305542e+03 3.79705029e+03 3.77005518e+03 3.65061206e+03 3.56211841e+03 3.66824219e+03 3.61331128e+03 3.47008691e+03 3.57261182e+03 3.55448560e+03 3.44318042e+03 3.38840747e+03 3.33437378e+03 3.29458667e+03 3.17013843e+03 3.09714844e+03 3.21430664e+03 3.22562427e+03 3.01676050e+03 2.88674756e+03 2.98224487e+03 3.11539307e+03 3.03227710e+03 2.84482642e+03 2.74757178e+03 2.84815479e+03 2.85807422e+03 2.73960034e+03 2.72659180e+03 2.61012988e+03 2.49850195e+03 2.56109912e+03 2.63645654e+03 2.59396851e+03 2.45279712e+03 2.34252466e+03 2.42551782e+03 2.46592188e+03 2.35734717e+03 2.23093848e+03 2.16430737e+03 2.19753394e+03 2.17586133e+03 2.19430591e+03 2.15576294e+03 2.04335791e+03 2.04079272e+03 2.02033630e+03 2.01622534e+03 1.92507617e+03 1.85072107e+03 1.90470410e+03 1.87596387e+03 1.81808447e+03 1.74002722e+03 1.72111023e+03 1.78823096e+03 1.68921106e+03 1.58641162e+03 1.59694971e+03 1.60270825e+03 1.57593030e+03 1.52781946e+03 1.53183630e+03 1.51350781e+03 1.43948792e+03 1.37132312e+03 1.34030627e+03 1.38327795e+03 1.33115515e+03 1.26577283e+03 1.28287769e+03 1.25545288e+03 1.20584790e+03 1.16633557e+03 1.17745874e+03 1.14320422e+03 1.08616077e+03 1.08867700e+03 1.06248413e+03 1.04184448e+03 1.01920013e+03 9.82980713e+02 9.50722778e+02 9.00887146e+02 8.71997192e+02 8.93115601e+02 9.04414429e+02 8.35692749e+02 7.72404724e+02 7.81639099e+02 8.04622131e+02 7.76662231e+02 7.18614380e+02 6.73665344e+02 6.84601746e+02 6.84335327e+02 6.43505981e+02 6.34752136e+02 6.11647949e+02 5.68882751e+02 5.55263428e+02 5.58036011e+02 5.43582397e+02 5.03641235e+02 4.72058136e+02 4.75086365e+02 4.77579407e+02 4.48966003e+02 4.14476654e+02 3.91613617e+02 3.93798615e+02 3.89862366e+02 3.61623749e+02 3.38004364e+02 3.25527863e+02 3.17505432e+02 3.02332031e+02 2.96117310e+02 2.76611847e+02 2.54900223e+02 2.51240524e+02 2.39487015e+02 2.28531250e+02 2.11959793e+02 1.97005981e+02 1.93932556e+02 1.79213425e+02 1.65988495e+02 1.59934235e+02 1.49520554e+02 1.40255798e+02 1.30906891e+02 1.25531487e+02 1.17477425e+02 1.05367355e+02 9.47701645e+01 8.76310425e+01 8.51420517e+01 7.75894852e+01 6.71793365e+01 5.72874565e+01 5.91622162e+01 8.65624466e+01 4.08719574e+02 1.40129600e+04 0. 0. 0. 0. 0. -56120612. -34281240. 6.52675850e+06 1.17130249e+02 1.21747452e+02 -3518827. -2704380. -18916922. 38412828. 38412828. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2252586. -9053570. -5391015. 8.21303787e+01 9.34806747e+01 6.93586044e+01 5.51434364e+01 7.31151352e+01 7.69148254e+01 8.28887100e+01 9.03535995e+01 9.87065659e+01 1.06926979e+02 1.12293060e+02 1.20489937e+02 1.31979370e+02 1.39926041e+02 1.48272659e+02 1.57214920e+02 1.66468597e+02 1.81632126e+02 1.93065094e+02 2.01102432e+02 2.13343811e+02 2.21751312e+02 2.33604904e+02 2.54730972e+02 2.69740295e+02 2.73016785e+02 2.84202820e+02 3.03038300e+02 3.18635559e+02 3.27814728e+02 3.39767059e+02 3.59148682e+02 3.75211975e+02 3.98809753e+02 4.13670166e+02 4.14138672e+02 4.34979767e+02 4.69156433e+02 4.89126801e+02 4.99739166e+02 4.98683075e+02 5.12843079e+02 5.50969910e+02 5.75834412e+02 5.84620361e+02 5.98198303e+02 6.17820923e+02 6.49627563e+02 6.77581604e+02 6.89187683e+02 6.89421875e+02 7.09683411e+02 7.70749878e+02 7.96949585e+02 7.76692383e+02 7.94920593e+02 8.38640625e+02 8.74082092e+02 9.07762329e+02 9.14738586e+02 9.06294373e+02 9.39860291e+02 9.90106262e+02 1.01807855e+03 1.02884644e+03 1.03729724e+03 1.07999219e+03 1.12176758e+03 1.13938684e+03 1.15301624e+03 1.16718872e+03 1.20522253e+03 1.25658508e+03 1.27706995e+03 1.30978882e+03 1.32916809e+03 1.32300244e+03 1.37577100e+03 1.42046594e+03 1.44525378e+03 1.47418494e+03 1.48688696e+03 1.51909290e+03 1.59218152e+03 1.61278967e+03 1.58501562e+03 1.62291235e+03 1.68887683e+03 1.74053174e+03 1.75757361e+03 1.75356604e+03 1.78644739e+03 1.84457507e+03 1.89867041e+03 1.92012341e+03 1.90404834e+03 1.96257056e+03 2.05493530e+03 2.07699097e+03 2.09266138e+03 2.07148096e+03 2.09858032e+03 2.21593774e+03 2.23365918e+03 2.22682983e+03 2.25776465e+03 2.30631885e+03 2.38673511e+03 2.41899365e+03 2.42182373e+03 2.45795435e+03 2.49723267e+03 2.57361353e+03 2.61587036e+03 2.60444556e+03 2.64365503e+03 2.68314575e+03 2.70404175e+03 2.77907666e+03 2.82675928e+03 2.85332227e+03 2.89882983e+03 2.91349097e+03 2.93053540e+03 3.01437622e+03 3.08804321e+03 3.08323560e+03 3.10920435e+03 3.11812061e+03 3.17125244e+03 3.26563721e+03 3.27752661e+03 3.30262378e+03 3.35269849e+03 3.46660034e+03 3.51810645e+03 3.47472998e+03 3.53368311e+03 3.59120044e+03 3.60900781e+03 3.60893921e+03 3.65584351e+03 3.72835645e+03 3.82005542e+03 3.90126050e+03 3.93340479e+03 3.88934424e+03 3.87365479e+03 4.00179272e+03 4.08477832e+03 4.11329248e+03 4.15175635e+03 4.14114111e+03 4.23292285e+03 4.34024072e+03 4.35508936e+03 4.31716943e+03 4.29483643e+03 4.44452295e+03 4.59564258e+03 4.59241699e+03 4.45985938e+03 4.54492480e+03 4.74071387e+03 4.78097559e+03 4.73603809e+03 4.79348145e+03 4.85540479e+03 4.86609082e+03 4.97800977e+03 4.97227930e+03 4.90981104e+03 5.08419531e+03 5.23428613e+03 5.19505713e+03 5.23055957e+03 5.28460352e+03 5.23516797e+03 5.33608252e+03 5.42694043e+03 5.51228516e+03 5.62544287e+03 5.42911133e+03 5.50134961e+03 5.76443066e+03 5.70830273e+03 5.60419287e+03 5.74899463e+03 5.91247217e+03 5.92105127e+03 5.96663818e+03 5.98722314e+03 5.95530273e+03 5.97817529e+03 6.21278516e+03 6.34939600e+03 6.13974902e+03 6.21066211e+03 6.45751904e+03 6.40634473e+03 6.40871045e+03 6.39067041e+03 6.35870508e+03 6.59432666e+03 6.60705566e+03 6.62597314e+03 6.72363818e+03 6.64632520e+03 6.74283984e+03 6.94299072e+03 6.84521875e+03 6.88223779e+03 7.00069629e+03 7.04460107e+03 7.05411475e+03 7.14825439e+03 7.17603564e+03 7.17113672e+03 7.22869775e+03 7.38368115e+03 7.40133740e+03 7.33898242e+03 7.50346191e+03 7.64293799e+03 7.58031348e+03 7.75241895e+03 7.66394434e+03 7.52720898e+03 7.75067578e+03 7.81595020e+03 7.86963379e+03 7.81360742e+03 7.80605273e+03 8.04785498e+03 8.24708203e+03 8.13485059e+03 8.05242090e+03 8.21135938e+03 8.35422461e+03 8.23031348e+03 8.19244141e+03 8.49653613e+03 8.49016113e+03 8.31436230e+03 8.60559863e+03 8.57461133e+03 8.56134668e+03 8.69436816e+03 8.60641699e+03 8.66532520e+03 8.79782129e+03 8.79977637e+03 8.82403418e+03 8.96727539e+03 9.08382129e+03 9.17077148e+03 8.91425000e+03 8.90589355e+03 9.20694629e+03 9.21079297e+03 9.29825977e+03 9.30323633e+03 9.22790625e+03 9.36097754e+03 9.47221875e+03 9.68788672e+03 9.51109473e+03 9.27313281e+03 9.57275684e+03 1.00402285e+04 9.66380176e+03 9.48921973e+03 9.67324316e+03 9.71696777e+03 9.91302930e+03 1.00670010e+04 9.86291504e+03 9.89767090e+03 1.00456982e+04 1.01101152e+04 1.02736709e+04 1.01597832e+04 1.02709131e+04 1.04409014e+04 1.00458105e+04 1.02204414e+04 1.04103086e+04 1.03069189e+04 1.05833652e+04 1.05452773e+04 1.04164521e+04 1.06342051e+04 1.05345254e+04 1.05966465e+04 1.09985107e+04 1.08823525e+04 1.06954688e+04 1.06616514e+04 1.06288643e+04 1.09197305e+04 1.10999551e+04 1.09689814e+04 1.09519316e+04 1.11798594e+04 1.12627979e+04 1.12188936e+04 1.10567129e+04 1.10559736e+04 1.12047803e+04 1.13671543e+04 1.14747920e+04 1.12005156e+04 1.12126084e+04 1.14584639e+04 1.15625605e+04 1.15816875e+04 1.16261719e+04 1.15335918e+04 1.14642383e+04 1.18557646e+04 1.20380449e+04 1.16649004e+04 1.14563643e+04 1.15822441e+04 1.18362734e+04 1.18621230e+04 1.17613652e+04 1.19626367e+04 1.20360752e+04 1.20012803e+04 1.21635576e+04 1.20634697e+04 1.19744902e+04 1.21623311e+04 1.23627021e+04 1.21370986e+04 1.19348965e+04 1.21923301e+04 1.22327842e+04 1.22965127e+04 1.24791777e+04 1.23728145e+04 1.22164043e+04 1.23924102e+04 1.27053838e+04 1.25643105e+04 1.23287705e+04 1.24550967e+04 1.25564072e+04 1.25731240e+04 1.25573789e+04 1.24684512e+04 1.25985605e+04 1.27135332e+04 1.28622734e+04 1.29832021e+04 1.27384883e+04 1.27667852e+04 1.27801729e+04 1.27346475e+04 1.27855830e+04 1.27020898e+04 1.29372598e+04 1.30343477e+04 1.28859375e+04 1.27861553e+04 1.28511328e+04 1.31331855e+04 1.32948730e+04 1.33196562e+04 1.30995459e+04 1.30241309e+04 1.30672812e+04 1.29153252e+04 1.30718760e+04 1.32878623e+04 1.32372490e+04 1.31722080e+04 1.30403467e+04 1.30705488e+04 1.33754502e+04 1.35506484e+04 1.35954951e+04 1.33024736e+04 1.30526748e+04 1.32761631e+04 1.33856992e+04 1.33511787e+04 1.34859609e+04 1.35690498e+04 1.33412627e+04 1.32621357e+04 1.32534736e+04 1.33035762e+04 1.37991230e+04 1.38441377e+04 1.34351104e+04 1.35711729e+04 1.34786475e+04 1.31976230e+04 1.36764072e+04 1.38454688e+04 1.34434883e+04 1.34409580e+04 1.34278545e+04 1.33093564e+04 1.36995869e+04 1.40926328e+04 1.37380615e+04 1.34937100e+04 1.36153135e+04 1.36319180e+04 1.37270361e+04 1.36700664e+04 1.36529434e+04 1.36585117e+04 1.36558682e+04 1.37635801e+04 1.38031914e+04 1.36453760e+04 1.37436621e+04 1.39685107e+04 1.37285049e+04 1.34744570e+04 1.35294141e+04 1.38669844e+04 1.40479102e+04 1.39850430e+04 1.36097676e+04 1.33052500e+04 1.36226445e+04 1.39626748e+04 1.41574941e+04 1.38539189e+04 1.34955801e+04 1.37386924e+04 1.38294150e+04 1.36963623e+04 1.38474062e+04 1.37914199e+04 1.36123496e+04 1.39324873e+04 1.37334570e+04 1.32465723e+04 1.37560078e+04 1.42548926e+04 1.37326875e+04 1.34929824e+04 1.36320791e+04 1.36663457e+04 1.38536250e+04 1.39134951e+04 1.37757637e+04 1.34431885e+04 1.35236836e+04 1.37403770e+04 1.36708594e+04 1.38350830e+04 1.38930068e+04 1.36540391e+04 1.35046934e+04 1.37371787e+04 1.37271914e+04 1.35865547e+04 1.37626943e+04 1.38040830e+04 1.35771240e+04 1.33557744e+04 1.33556846e+04 1.35366992e+04 1.37915039e+04 1.37599199e+04 1.34297461e+04 1.33115000e+04 1.33539463e+04 1.34967236e+04 1.36986172e+04 1.35979316e+04 1.32707295e+04 1.34604189e+04 1.35468262e+04 1.32914746e+04 1.36647256e+04 1.36320508e+04 1.31986484e+04 1.33375840e+04 1.31282295e+04 1.30100254e+04 1.35264482e+04 1.35318740e+04 1.32677402e+04 1.33556182e+04 1.32253506e+04 1.28599219e+04 1.29564463e+04 1.32520889e+04 1.32108223e+04 1.31973457e+04 1.30332246e+04 1.29560879e+04 1.31101963e+04 1.31266738e+04 1.34842979e+04 1.32152480e+04 1.26116025e+04 1.27390859e+04 1.28462637e+04 1.29921084e+04 1.31527217e+04 1.28668945e+04 1.25333984e+04 1.27988027e+04 1.29238486e+04 1.28016484e+04 1.28477334e+04 1.27150557e+04 1.24935020e+04 1.27255381e+04 1.27177285e+04 1.24202637e+04 1.28734941e+04 1.28700049e+04 1.25044170e+04 1.24744883e+04 1.21146963e+04 1.21408945e+04 1.25137666e+04 1.28802041e+04 1.26946143e+04 1.19450957e+04 1.19744111e+04 1.24277715e+04 1.23139189e+04 1.21799766e+04 1.21969131e+04 1.20472842e+04 1.21207129e+04 1.21579375e+04 1.21554170e+04 1.20799521e+04 1.20472783e+04 1.21466660e+04 1.19110293e+04 1.17581201e+04 1.17464502e+04 1.17529814e+04 1.18669805e+04 1.20724990e+04 1.18024238e+04 1.14374932e+04 1.16128594e+04 1.17201475e+04 1.19179521e+04 1.17951621e+04 1.12911562e+04 1.13762520e+04 1.14739414e+04 1.15344844e+04 1.16952246e+04 1.14382520e+04 1.12227217e+04 1.12320410e+04 1.10869697e+04 1.09538184e+04 1.12803730e+04 1.14548350e+04 1.10876523e+04 1.09082168e+04 1.08030645e+04 1.08328174e+04 1.11488613e+04 1.11131709e+04 1.09492529e+04 1.08083701e+04 1.05021299e+04 1.06216592e+04 1.06799551e+04 1.08567520e+04 1.08844023e+04 1.04292744e+04 1.03474424e+04 1.04696602e+04 1.04923291e+04 1.04637275e+04 1.05011172e+04 1.04716113e+04 1.01755410e+04 1.01524355e+04 1.01619336e+04 1.01351768e+04 1.01635264e+04 1.01717500e+04 1.00800215e+04 9.98054980e+03 9.86771582e+03 9.90779590e+03 1.00725879e+04 9.91251074e+03 9.65584570e+03 9.61906152e+03 9.62985059e+03 9.57822656e+03 9.89920801e+03 9.87906348e+03 9.39439551e+03 9.40794434e+03 9.28256543e+03 9.34532227e+03 9.66234180e+03 9.69265527e+03 9.10042969e+03 8.40450879e+03 1.15199307e+04 1.27609541e+04 1.37975576e+04 1.40682920e+04 1.47479062e+04 1.36973535e+04 2.19850410e+04 4.13365781e+04 2854715. -212644064. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -84796424. 3.04958535e+04 1.12117334e+04 9.98038574e+03 8.84449902e+03 1.02320918e+04 7.50911426e+03 6.42597803e+03 6.39234033e+03 6.64455859e+03 6.50124902e+03 6.25574902e+03 6.07245020e+03 6.05041602e+03 6.20242773e+03 6.24192529e+03 6.13722412e+03 5.92712402e+03 5.83250732e+03 5.80522412e+03 5.92267383e+03 5.83451709e+03 5.58540869e+03 5.61742773e+03 5.73779150e+03 5.63294141e+03 5.46587891e+03 5.33966016e+03 5.46433105e+03 5.66110156e+03 5.58401270e+03 5.20236133e+03 4.96011865e+03 5.08273145e+03 5.27024023e+03 5.33143115e+03 5.20454639e+03 4.90725391e+03 4.90598193e+03 4.94450684e+03 5.03916162e+03 4.92394189e+03 4.62875537e+03 4.64787988e+03 4.84603467e+03 4.72740283e+03 4.57749268e+03 4.57192773e+03 4.55145020e+03 4.54059277e+03 4.49551562e+03 4.29806543e+03 4.20765918e+03 4.34755518e+03 4.43856299e+03 4.31240967e+03 4.12334473e+03 3.95551831e+03 4.09734717e+03 4.21022607e+03 4.08431689e+03 3.89793945e+03 3.71849976e+03 3.74245020e+03 3.91151367e+03 3.91559448e+03 3.82261548e+03 3.70791016e+03 3.65956323e+03 3.56841968e+03 3.55184424e+03 3.54234033e+03 3.40198364e+03 3.42042139e+03 3.49772876e+03 3.40419922e+03 3.20277271e+03 3.15212915e+03 3.27611182e+03 3.34117432e+03 3.23610059e+03 3.09705542e+03 2.97833911e+03 2.93827393e+03 2.98346362e+03 3.07684253e+03 2.99326465e+03 2.79257544e+03 2.78550854e+03 2.79720557e+03 2.78052832e+03 2.79305786e+03 2.66053418e+03 2.61345947e+03 2.65057153e+03 2.60594165e+03 2.51737085e+03 2.45183179e+03 2.46077441e+03 2.46769043e+03 2.41651636e+03 2.31914575e+03 2.24937915e+03 2.28384448e+03 2.31710767e+03 2.26080859e+03 2.17527710e+03 2.08228125e+03 2.08533081e+03 2.11420068e+03 2.08107300e+03 2.00340771e+03 1.89786719e+03 1.87875000e+03 1.93267615e+03 1.94419897e+03 1.87305188e+03 1.75505640e+03 1.74669092e+03 1.76908838e+03 1.72080518e+03 1.65314771e+03 1.60298755e+03 1.63557397e+03 1.63365625e+03 1.55159229e+03 1.50005957e+03 1.45622510e+03 1.46861975e+03 1.49682300e+03 1.44078088e+03 1.36767603e+03 1.32013831e+03 1.30034436e+03 1.29226465e+03 1.29403503e+03 1.25653650e+03 1.17470679e+03 1.15124268e+03 1.17474792e+03 1.16421582e+03 1.11298633e+03 1.06365112e+03 1.04851184e+03 1.04451660e+03 1.01771356e+03 9.76999390e+02 9.22006287e+02 9.08899048e+02 9.21100769e+02 8.96539429e+02 8.59267273e+02 8.18504089e+02 8.01692383e+02 8.00719666e+02 7.97715759e+02 7.65364197e+02 7.10156067e+02 6.90120605e+02 6.82887085e+02 6.66633606e+02 6.46239136e+02 6.15337952e+02 6.02948059e+02 5.82586609e+02 5.57932800e+02 5.40874146e+02 5.20573303e+02 5.16995972e+02 5.04359406e+02 4.76900604e+02 4.47744476e+02 4.25209747e+02 4.23399139e+02 4.21035583e+02 4.01075653e+02 3.75821991e+02 3.49768738e+02 3.30370331e+02 3.28512817e+02 3.30901581e+02 3.08395447e+02 2.78767731e+02 2.68526215e+02 2.64299316e+02 2.53122620e+02 2.39549973e+02 2.22996643e+02 2.10469986e+02 2.00980469e+02 1.87720352e+02 1.76019699e+02 1.67963821e+02 1.60565521e+02 1.49845306e+02 1.38957962e+02 1.28723251e+02 1.19927528e+02 1.13518478e+02 1.06916946e+02 9.78401947e+01 8.68254776e+01 7.85245819e+01 7.44664154e+01 6.94524689e+01 6.29231758e+01 5.65312309e+01 4.96264000e+01 4.44103012e+01 4.12452812e+01 3.76423569e+01 3.31081390e+01 2.84692173e+01 2.46746540e+01 2.17134724e+01 1.88183231e+01 1.63063602e+01 1.43114071e+01 1.25381804e+01 1.09346828e+01 9.71328735e+00 8.87779140e+00 8.41402531e+00 8.26453304e+00 8.43284512e+00 8.95308781e+00 9.80451488e+00 1.09182405e+01 1.25862637e+01 1.45861969e+01 1.67250404e+01 1.92836399e+01 2.19999828e+01 2.56034012e+01 2.90553608e+01 3.15696869e+01 3.52855034e+01 4.04946213e+01 4.72099609e+01 5.39365349e+01 5.85262375e+01 6.13665848e+01 6.55774612e+01 7.35179443e+01 8.43276520e+01 9.39851456e+01 9.95019073e+01 1.02403885e+02 1.09712044e+02 1.24838066e+02 1.34767563e+02 1.36939331e+02 1.45962936e+02 1.58373459e+02 1.68310349e+02 1.84330093e+02 1.91033783e+02 1.95273590e+02 2.12229492e+02 2.19522156e+02 2.36593277e+02 2.56028137e+02 2.55775497e+02 2.74315186e+02 2.96657806e+02 3.03012451e+02 3.16197571e+02 3.30233459e+02 3.46168701e+02 3.62417572e+02 3.75796387e+02 3.81882080e+02 3.97044586e+02 4.30864288e+02 4.60869141e+02 4.68806061e+02 4.64685059e+02 4.71099640e+02 4.96734161e+02 5.38972168e+02 5.73613403e+02 5.80961182e+02 5.69326477e+02 5.88418335e+02 6.30546082e+02 6.47503235e+02 6.59664917e+02 6.78338867e+02 7.00063110e+02 7.24090820e+02 7.70357849e+02 7.73294067e+02 7.71598450e+02 8.13673889e+02 8.16029602e+02 8.63758606e+02 9.05118469e+02 9.05297668e+02 9.59516785e+02 9.55799255e+02 9.47154358e+02 1.00303308e+03 1.00434241e+03 1.04930725e+03 1.14606958e+03 1.11176331e+03 1.07800269e+03 1.12642395e+03 1.20539380e+03 1.28026465e+03 1.27982532e+03 1.23052527e+03 1.22793347e+03 1.29035828e+03 1.38091248e+03 1.45961902e+03 1.45329382e+03 1.40302197e+03 1.42237036e+03 1.50315771e+03 1.55407019e+03 1.54733545e+03 1.55677563e+03 1.61476685e+03 1.65736353e+03 1.72750671e+03 1.76259277e+03 1.70505530e+03 1.73656372e+03 1.79266980e+03 1.83388867e+03 1.88938538e+03 1.91241785e+03 1.98263184e+03 1.98998474e+03 1.95805518e+03 2.02505994e+03 2.01574902e+03 2.11198975e+03 2.28034326e+03 2.19048315e+03 2.08786646e+03 2.17683667e+03 2.32522876e+03 2.43312573e+03 2.46009814e+03 2.37012109e+03 2.30708813e+03 2.38376172e+03 2.55054761e+03 2.69172095e+03 2.65803955e+03 2.54602515e+03 2.55691895e+03 2.66492725e+03 2.76416675e+03 2.86960767e+03 2.89253394e+03 2.77860132e+03 2.79489868e+03 2.97971655e+03 3.05343628e+03 2.98194287e+03 3.00869971e+03 3.03957300e+03 3.07039746e+03 3.25478711e+03 3.31364014e+03 3.18825659e+03 3.20537134e+03 3.29374146e+03 3.34875269e+03 3.42148071e+03 3.43248413e+03 3.56523926e+03 3.64145142e+03 3.56020239e+03 3.53172339e+03 3.50209155e+03 3.68538501e+03 3.94899585e+03 3.90882568e+03 3.73364404e+03 3.68953101e+03 3.88397583e+03 4.15081152e+03 4.05383325e+03 3.85807397e+03 3.97944507e+03 4.11973340e+03 4.27368506e+03 4.45601953e+03 4.38997900e+03 4.19761475e+03 4.14206250e+03 4.34817188e+03 4.54780957e+03 4.58906152e+03 4.54769043e+03 4.56056689e+03 4.59916309e+03 4.74830664e+03 4.75387744e+03 4.65894092e+03 4.66934229e+03 4.72625830e+03 4.99976221e+03 5.11603711e+03 4.97701270e+03 5.04511768e+03 5.11519189e+03 5.24328467e+03 5.19277148e+03 4.97753125e+03 5.23348193e+03 5.55245703e+03 5.47940869e+03 5.25230713e+03 5.32428369e+03 5.66920215e+03 5.73545752e+03 5.61514111e+03 5.66161768e+03 5.55049854e+03 5.61288525e+03 5.95374365e+03 5.98583691e+03 5.76290625e+03 5.69491455e+03 5.75084863e+03 6.08709521e+03 6.40429346e+03 6.16729053e+03 6.03285059e+03 6.20820752e+03 6.26693555e+03 6.51137451e+03 6.51319189e+03 6.15491357e+03 6.32696631e+03 6.55277979e+03 6.55027344e+03 6.63198096e+03 6.63394385e+03 6.89907422e+03 7.05011035e+03 6.86744336e+03 6.81627393e+03 6.32043408e+03 8.54705176e+03 9.89952539e+03 1.08437285e+04 1.03875928e+04 1.03066934e+04 1.08129863e+04 1.13262822e+04 1.19505225e+04 1.23799941e+04 1.10681152e+04 1.09717705e+04 2.06626738e+04 1.26861180e+05 9566066. 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. 0. 0. 0. 0. 0. 0. 0. 0. -63503240. 2.36063775e+06 1.41073362e+06 3.14196680e+04 2.33877344e+04 1.07547930e+04 1.14126670e+04 1.04238838e+04 1.02711250e+04 9.90021777e+03 1.01554766e+04 9.93583105e+03 9.66482715e+03 9.97116406e+03 9.98850977e+03 1.03022793e+04 1.04582021e+04 9.58270410e+03 9.49160645e+03 9.73099121e+03 1.00213770e+04 9.94068359e+03 9.80432227e+03 1.05215312e+04 1.03331670e+04 1.00850674e+04 1.05917559e+04 1.05630811e+04 1.02729395e+04 1.06476494e+04 1.10501016e+04 1.08115527e+04 1.07477090e+04 1.07064170e+04 1.07268203e+04 1.06687959e+04 1.07295332e+04 1.10148525e+04 1.10917178e+04 1.09497158e+04 1.09708330e+04 1.10451357e+04 1.10803389e+04 1.10657607e+04 1.11068711e+04 1.11660078e+04 1.08914775e+04 1.08851797e+04 1.12146260e+04 1.12410215e+04 1.16965645e+04 1.17691025e+04 1.13970889e+04 1.10997598e+04 1.11004453e+04 1.18793164e+04 1.20179854e+04 1.16027559e+04 1.13799658e+04 1.14503027e+04 1.16912812e+04 1.16223516e+04 1.20490635e+04 1.20906982e+04 1.14358398e+04 1.13477432e+04 1.20167539e+04 1.25044971e+04 1.22140352e+04 1.19787510e+04 1.20625791e+04 1.20684072e+04 1.19300410e+04 1.20359424e+04 1.20927480e+04 1.20208926e+04 1.21134521e+04 1.21495684e+04 1.22948271e+04 1.23053818e+04 1.25984844e+04 1.25827354e+04 1.22298623e+04 1.24206494e+04 1.24983018e+04 1.26200938e+04 1.26491719e+04 1.25654619e+04 1.25932402e+04 1.23427852e+04 1.20626260e+04 1.27074473e+04 1.29071689e+04 1.22600420e+04 1.24020889e+04 1.31285410e+04 1.35021650e+04 1.30976182e+04 1.27675254e+04 1.27690977e+04 1.27923438e+04 1.26970410e+04 1.26712393e+04 1.29631309e+04 1.29380371e+04 1.32749922e+04 1.32120293e+04 1.28948408e+04 1.31197637e+04 1.27919570e+04 1.28242080e+04 1.35615244e+04 1.34610264e+04 1.31723193e+04 1.28991826e+04 1.27086709e+04 1.34564053e+04 1.37335098e+04 1.32985449e+04 1.29275186e+04 1.29737139e+04 1.33228467e+04 1.32626797e+04 1.37050938e+04 1.38485625e+04 1.33537373e+04 1.30980225e+04 1.31426826e+04 1.37126387e+04 1.37458311e+04 1.34016846e+04 1.32683770e+04 1.33139854e+04 1.35209600e+04 1.31875693e+04 1.32296650e+04 1.40038906e+04 1.39232822e+04 1.35814414e+04 1.32276250e+04 1.31316328e+04 1.39606904e+04 1.40586143e+04 1.36401064e+04 1.33016895e+04 1.32168809e+04 1.36237402e+04 1.36590723e+04 1.36397637e+04 1.32979453e+04 1.35964785e+04 1.43142051e+04 1.39589580e+04 1.38202139e+04 1.38708447e+04 1.37747432e+04 1.35751641e+04 1.35489307e+04 1.37676113e+04 1.37639912e+04 1.36563418e+04 1.32741758e+04 1.35332656e+04 1.43719395e+04 1.38032461e+04 1.33616680e+04 1.37341465e+04 1.37104980e+04 1.41624756e+04 1.39020781e+04 1.33399385e+04 1.40842510e+04 1.41758154e+04 1.37625186e+04 1.37067695e+04 1.36775977e+04 1.36428145e+04 1.36463691e+04 1.36806455e+04 1.33034277e+04 1.36782402e+04 1.44889326e+04 1.41517930e+04 1.36767861e+04 1.32515537e+04 1.34063936e+04 1.42689639e+04 1.42033223e+04 1.37874365e+04 1.34114961e+04 1.33286660e+04 1.37528115e+04 1.37192412e+04 1.40015010e+04 1.37392725e+04 1.33002100e+04 1.37076680e+04 1.37297539e+04 1.39801504e+04 1.39067852e+04 1.35424531e+04 1.35349902e+04 1.35157041e+04 1.36853096e+04 1.33269863e+04 1.34584834e+04 1.41791816e+04 1.39134961e+04 1.35927529e+04 1.32512549e+04 1.31380488e+04 1.38578516e+04 1.39427842e+04 1.35336279e+04 1.31264072e+04 1.31086475e+04 1.35350400e+04 1.35399297e+04 1.38232822e+04 1.36504600e+04 1.33208262e+04 1.31559971e+04 1.30661934e+04 1.37524893e+04 1.36580400e+04 1.32170234e+04 1.31385332e+04 1.31342354e+04 1.35299258e+04 1.35197051e+04 1.29736289e+04 1.29140439e+04 1.35245039e+04 1.34795449e+04 1.28710273e+04 1.27990381e+04 1.34577002e+04 1.35001338e+04 1.30292422e+04 1.27176250e+04 1.26893105e+04 1.34139541e+04 1.32868711e+04 1.28589795e+04 1.29136143e+04 1.28447275e+04 1.28622500e+04 1.28135068e+04 1.27762012e+04 1.24406279e+04 1.27426230e+04 1.34142080e+04 1.29867021e+04 1.28049541e+04 1.28861133e+04 1.27575010e+04 1.27270615e+04 1.26697441e+04 1.25986221e+04 1.22575449e+04 1.20810752e+04 1.23584043e+04 1.26066768e+04 1.30030293e+04 1.25194893e+04 1.20414502e+04 1.23194805e+04 1.24415508e+04 1.27783721e+04 1.25368760e+04 1.21955068e+04 1.20816494e+04 1.19366865e+04 1.21711738e+04 1.21926807e+04 1.23837705e+04 1.23261943e+04 1.20181641e+04 1.18343818e+04 1.14632031e+04 1.19162246e+04 1.25538604e+04 1.22842100e+04 1.18842207e+04 1.15491357e+04 1.13470176e+04 1.18978906e+04 1.22219688e+04 1.18485693e+04 1.13494385e+04 1.13224893e+04 1.15823633e+04 1.15332402e+04 1.18338779e+04 1.17198789e+04 1.13386143e+04 1.13588672e+04 1.13075664e+04 1.14904922e+04 1.15118369e+04 1.09799111e+04 1.09601533e+04 1.15471787e+04 1.12462783e+04 1.06397227e+04 1.09884834e+04 1.15652930e+04 1.13003535e+04 1.09403652e+04 1.06493037e+04 1.06355010e+04 1.11946797e+04 1.11437852e+04 1.07661621e+04 1.04820068e+04 1.03785117e+04 1.06422041e+04 1.06263906e+04 1.05786592e+04 1.02801016e+04 1.04704180e+04 1.09018125e+04 1.05470898e+04 1.05003408e+04 1.04419385e+04 1.01660234e+04 1.02415010e+04 1.02482852e+04 1.01745068e+04 1.00654189e+04 9.94257422e+03 9.71922559e+03 9.91912695e+03 1.04350537e+04 9.90031445e+03 9.48118555e+03 9.71128809e+03 9.83784668e+03 1.01168213e+04 9.86017480e+03 9.53142773e+03 9.74549023e+03 9.74597461e+03 9.22375586e+03 9.14521973e+03 9.59178027e+03 9.64019727e+03 9.32014453e+03 9.07801172e+03 8.77599512e+03 9.14451660e+03 9.63347461e+03 9.37088379e+03 9.01764844e+03 8.74777051e+03 8.66824512e+03 9.02034766e+03 9.33217383e+03 8.96455762e+03 8.54992578e+03 8.42850098e+03 8.60859180e+03 8.68664551e+03 8.88713086e+03 8.62083789e+03 8.34459961e+03 8.49692090e+03 8.41855664e+03 8.50899902e+03 8.40885938e+03 8.21877051e+03 8.22741504e+03 8.14054199e+03 8.07704248e+03 7.80507031e+03 7.89073291e+03 8.37059570e+03 8.14437793e+03 7.80462598e+03 7.59252441e+03 7.60870947e+03 8.03109033e+03 7.92623926e+03 7.64717041e+03 7.43441992e+03 7.30449463e+03 7.53505615e+03 7.46775537e+03 7.44226855e+03 7.21513965e+03 7.28840430e+03 7.54019092e+03 7.31503613e+03 7.28446338e+03 7.24804395e+03 7.05136377e+03 6.97838721e+03 6.91660547e+03 6.87940967e+03 6.84204541e+03 6.82151416e+03 6.76728809e+03 6.85748584e+03 6.83762793e+03 6.49887256e+03 6.33179248e+03 6.49702246e+03 6.59031934e+03 6.67091260e+03 6.49010742e+03 6.10845117e+03 6.36543457e+03 6.48434277e+03 6.24306592e+03 6.06793066e+03 5.99590137e+03 6.06273096e+03 6.05683252e+03 5.94227295e+03 5.70811035e+03 5.82941406e+03 6.10168945e+03 5.90652393e+03 5.77323877e+03 5.57899414e+03 5.50014844e+03 5.77250488e+03 5.68745947e+03 5.49634424e+03 5.33109033e+03 5.16320801e+03 5.26951123e+03 5.39364893e+03 5.54243799e+03 5.24095508e+03 4.97291455e+03 5.09874023e+03 5.11028613e+03 5.20874072e+03 5.07659424e+03 4.83954443e+03 4.93465527e+03 4.88741260e+03 4.73296240e+03 4.57779980e+03 4.69618604e+03 4.86482471e+03 4.70648438e+03 4.60589502e+03 4.46142480e+03 4.37004932e+03 4.56876367e+03 4.53853760e+03 4.35029541e+03 4.21111182e+03 4.14036084e+03 4.21793555e+03 4.16605713e+03 4.21471240e+03 4.20009961e+03 4.01531396e+03 3.90421216e+03 3.90984790e+03 4.06534204e+03 3.91697632e+03 3.76683765e+03 3.79962964e+03 3.75754053e+03 3.64928076e+03 3.55604370e+03 3.66189429e+03 3.61559424e+03 3.47576855e+03 3.57514722e+03 3.55793970e+03 3.43283228e+03 3.37288037e+03 3.32685376e+03 3.28615649e+03 3.17097339e+03 3.09179980e+03 3.21492212e+03 3.22566626e+03 3.00858691e+03 2.87957202e+03 2.97721411e+03 3.11342676e+03 3.03427808e+03 2.84486768e+03 2.73983008e+03 2.84341675e+03 2.84665454e+03 2.72853857e+03 2.70962500e+03 2.60110278e+03 2.48383789e+03 2.55278906e+03 2.62317285e+03 2.57403174e+03 2.43920825e+03 2.33284766e+03 2.41368774e+03 2.45691406e+03 2.34667090e+03 2.21515601e+03 2.15742261e+03 2.19423584e+03 2.17000488e+03 2.19146997e+03 2.15189819e+03 2.03628918e+03 2.02719983e+03 2.01184192e+03 2.00747791e+03 1.91702405e+03 1.84777478e+03 1.89653760e+03 1.86078271e+03 1.81183105e+03 1.73462756e+03 1.71993677e+03 1.78373547e+03 1.68319592e+03 1.58704858e+03 1.59558948e+03 1.60169360e+03 1.57308203e+03 1.52403418e+03 1.52731042e+03 1.51013635e+03 1.43836841e+03 1.36969873e+03 1.33867834e+03 1.38209546e+03 1.33027454e+03 1.26161609e+03 1.27835095e+03 1.25219458e+03 1.20269934e+03 1.16321448e+03 1.17639417e+03 1.14190125e+03 1.08444275e+03 1.08807605e+03 1.06449963e+03 1.04552710e+03 1.02033563e+03 9.80964294e+02 9.48240784e+02 9.01080261e+02 8.72167419e+02 8.89638184e+02 8.98751892e+02 8.33559387e+02 7.71440735e+02 7.79920776e+02 8.03587952e+02 7.75805176e+02 7.16793823e+02 6.72548157e+02 6.84964661e+02 6.84749695e+02 6.42266907e+02 6.32065125e+02 6.09212952e+02 5.66805481e+02 5.52596802e+02 5.53463562e+02 5.39200867e+02 4.99755127e+02 4.70453979e+02 4.73826569e+02 4.75886871e+02 4.47346436e+02 4.13722443e+02 3.90166931e+02 3.92829102e+02 3.89151337e+02 3.60965118e+02 3.38350922e+02 3.25825836e+02 3.17441650e+02 3.01705292e+02 2.95293488e+02 2.76596497e+02 2.54586273e+02 2.50597168e+02 2.38617737e+02 2.27372055e+02 2.11043915e+02 1.96117508e+02 1.92809692e+02 1.82897095e+02 1.78444382e+02 1.61295486e+02 1.54443832e+02 2.13587799e+02 2.20563766e+02 2.12346375e+02 1.99981003e+02 1.13591103e+02 8.86847000e+01 8.09550858e+01 8.75953674e+01 1.13395508e+02 1.19807220e+02 1.20723022e+02 1.23129219e+02 1.35531296e+02 5.07266815e+02 7989604. 0. 0. 0. 0. 0. 0. 0. 0. 296138944. 5431394. -3518827. -2704380. -18916922. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -128530912. 3.59249425e+06 1.69060654e+02 1.29538147e+02 1.39578247e+02 1.38638123e+02 6.47738266e+01 6.10878754e+01 6.06428833e+01 7.47927322e+01 7.80975723e+01 8.46001129e+01 9.07068024e+01 9.90413437e+01 1.10143242e+02 1.18708855e+02 1.22628761e+02 1.30189148e+02 1.42791168e+02 1.52516220e+02 1.60871353e+02 1.70405548e+02 1.79838440e+02 1.90360519e+02 2.07255936e+02 2.21313675e+02 2.23633499e+02 2.35272308e+02 2.56314240e+02 2.71017029e+02 2.82764130e+02 2.89505219e+02 2.98394379e+02 3.22334778e+02 3.38402191e+02 3.46953522e+02 3.58342041e+02 3.72795441e+02 3.98686523e+02 4.13849121e+02 4.22646729e+02 4.35789642e+02 4.55489807e+02 4.92286438e+02 5.09148010e+02 5.02818207e+02 5.18848145e+02 5.45598267e+02 5.67439575e+02 5.95201111e+02 6.11006165e+02 6.18159973e+02 6.47926331e+02 6.71885437e+02 6.89317322e+02 7.10400818e+02 7.16898743e+02 7.44806335e+02 7.79870300e+02 7.92820984e+02 8.11386719e+02 8.28727661e+02 8.56463196e+02 8.96987000e+02 9.23739563e+02 9.39995483e+02 9.43412598e+02 9.58321228e+02 1.01375208e+03 1.04563159e+03 1.04511328e+03 1.07403455e+03 1.10297058e+03 1.13798425e+03 1.18616809e+03 1.20150977e+03 1.19460767e+03 1.22112793e+03 1.28371118e+03 1.32128186e+03 1.31272095e+03 1.31692993e+03 1.36181128e+03 1.41033191e+03 1.47526074e+03 1.50038330e+03 1.47233752e+03 1.50816333e+03 1.58197876e+03 1.60777502e+03 1.62296899e+03 1.61988196e+03 1.64345569e+03 1.73426843e+03 1.77843921e+03 1.76067236e+03 1.79358130e+03 1.83877307e+03 1.87034338e+03 1.90099548e+03 1.93015881e+03 1.98253918e+03 2.01610193e+03 2.07571411e+03 2.11358813e+03 2.07136353e+03 2.10185425e+03 2.19023145e+03 2.20702515e+03 2.24457788e+03 2.28010547e+03 2.31695459e+03 2.39037769e+03 2.40102173e+03 2.40815723e+03 2.48013745e+03 2.54038330e+03 2.52314355e+03 2.55335132e+03 2.61885352e+03 2.66493970e+03 2.68283594e+03 2.69053223e+03 2.74458813e+03 2.80339136e+03 2.90933838e+03 2.93439502e+03 2.86085327e+03 2.91807837e+03 3.03973682e+03 3.07474536e+03 3.07720410e+03 3.08281958e+03 3.08756421e+03 3.20088599e+03 3.31916504e+03 3.30273315e+03 3.27832104e+03 3.31456836e+03 3.43985547e+03 3.50922363e+03 3.55902148e+03 3.51909302e+03 3.47613086e+03 3.58938281e+03 3.64525000e+03 3.68212476e+03 3.76387866e+03 3.75001465e+03 3.83271167e+03 3.98580347e+03 3.96319604e+03 3.84982861e+03 3.91597119e+03 4.04983691e+03 4.13299023e+03 4.20872852e+03 4.19256885e+03 4.14237012e+03 4.22583545e+03 4.41252881e+03 4.35488916e+03 4.26199072e+03 4.39759473e+03 4.56340918e+03 4.59624219e+03 4.55827832e+03 4.54203076e+03 4.59337744e+03 4.70222998e+03 4.74807959e+03 4.81485498e+03 4.91678955e+03 4.85321680e+03 4.93355713e+03 5.08213232e+03 5.01787842e+03 4.99448145e+03 5.10232910e+03 5.23645410e+03 5.27140137e+03 5.29423486e+03 5.23589404e+03 5.23615674e+03 5.37525049e+03 5.66245557e+03 5.70837744e+03 5.41379346e+03 5.47242871e+03 5.76335107e+03 5.78140137e+03 5.69709131e+03 5.71013184e+03 5.73807178e+03 5.89930420e+03 6.03783301e+03 5.98104492e+03 5.96316992e+03 5.93857471e+03 6.09759717e+03 6.28491504e+03 6.31836914e+03 6.22213232e+03 6.24673438e+03 6.38223291e+03 6.44280518e+03 6.43115088e+03 6.42653760e+03 6.50373535e+03 6.55155176e+03 6.75507275e+03 6.87151318e+03 6.59442725e+03 6.65721191e+03 6.88730762e+03 6.96442090e+03 6.99651514e+03 6.86475977e+03 6.99665137e+03 7.23957373e+03 7.14153320e+03 7.20303613e+03 7.10304736e+03 7.05124268e+03 7.31277979e+03 7.52123438e+03 7.43006152e+03 7.45772852e+03 7.56425195e+03 7.54573145e+03 7.72653027e+03 7.75507324e+03 7.56920898e+03 7.56560010e+03 7.66960693e+03 7.93855811e+03 7.95395020e+03 7.87258301e+03 7.92269434e+03 8.12837842e+03 8.20294727e+03 8.09424316e+03 8.05229053e+03 8.14823145e+03 8.32513184e+03 8.31861621e+03 8.58392676e+03 8.41470215e+03 8.31186230e+03 8.57277344e+03 8.43832520e+03 8.56562891e+03 8.73396875e+03 8.62750098e+03 8.66127832e+03 8.70042090e+03 8.82205176e+03 8.88686719e+03 8.72736719e+03 9.11681348e+03 9.32791016e+03 8.93690137e+03 8.92590332e+03 9.10641797e+03 9.19357520e+03 9.41738184e+03 9.33989160e+03 9.15328613e+03 9.28845703e+03 9.58054199e+03 9.55375195e+03 9.53012207e+03 9.46792871e+03 9.52588574e+03 9.71775391e+03 9.63568359e+03 9.64100293e+03 9.65780176e+03 9.67714160e+03 9.81988574e+03 1.00388037e+04 1.00037354e+04 9.87675195e+03 9.84915039e+03 1.01407988e+04 1.03922607e+04 1.00392734e+04 1.01932471e+04 1.03224844e+04 1.00248887e+04 1.03262607e+04 1.04526885e+04 1.03000352e+04 1.04628174e+04 1.05416143e+04 1.04895146e+04 1.07385869e+04 1.06307217e+04 1.04904180e+04 1.06413008e+04 1.08037461e+04 1.09086943e+04 1.06222451e+04 1.06747891e+04 1.09015908e+04 1.10373301e+04 1.10734678e+04 1.09491826e+04 1.08537998e+04 1.11832236e+04 1.14738066e+04 1.11655850e+04 1.09848203e+04 1.10249717e+04 1.13643838e+04 1.15733154e+04 1.12627646e+04 1.12013076e+04 1.13553975e+04 1.14682637e+04 1.14509355e+04 1.16513184e+04 1.15634102e+04 1.13631660e+04 1.16831680e+04 1.19815332e+04 1.17535078e+04 1.13451396e+04 1.15095801e+04 1.18819609e+04 1.19490830e+04 1.19689609e+04 1.18817236e+04 1.17690410e+04 1.21120420e+04 1.23648203e+04 1.20458652e+04 1.19244873e+04 1.20224951e+04 1.23974180e+04 1.22924932e+04 1.19009814e+04 1.19814912e+04 1.22034199e+04 1.23219629e+04 1.23623369e+04 1.24608525e+04 1.23258789e+04 1.24004785e+04 1.24481260e+04 1.22517480e+04 1.23021201e+04 1.23027568e+04 1.25512148e+04 1.27818770e+04 1.24861943e+04 1.23295352e+04 1.25409414e+04 1.28010938e+04 1.31441621e+04 1.30567002e+04 1.25133018e+04 1.25703633e+04 1.28024453e+04 1.28211240e+04 1.27268770e+04 1.27675586e+04 1.29121094e+04 1.29916621e+04 1.28997529e+04 1.26292500e+04 1.28743945e+04 1.32441826e+04 1.33019971e+04 1.31185605e+04 1.28032969e+04 1.29782002e+04 1.29496172e+04 1.28591943e+04 1.33847832e+04 1.33892861e+04 1.29244043e+04 1.29377461e+04 1.31626230e+04 1.35214814e+04 1.35489463e+04 1.32966289e+04 1.32225215e+04 1.32454609e+04 1.32199873e+04 1.31293770e+04 1.33356240e+04 1.34518545e+04 1.36006133e+04 1.35591885e+04 1.30083613e+04 1.32256611e+04 1.34267393e+04 1.34331104e+04 1.38271289e+04 1.34339326e+04 1.31544150e+04 1.36824199e+04 1.38622822e+04 1.35359014e+04 1.34620244e+04 1.34079082e+04 1.33039746e+04 1.34473867e+04 1.35821621e+04 1.35441904e+04 1.37834307e+04 1.39618545e+04 1.36999307e+04 1.34608311e+04 1.33595205e+04 1.36419395e+04 1.39594180e+04 1.37769580e+04 1.34308135e+04 1.33655557e+04 1.35855781e+04 1.38871885e+04 1.41605908e+04 1.37687061e+04 1.34090293e+04 1.36863359e+04 1.37166318e+04 1.35639844e+04 1.39091572e+04 1.38885322e+04 1.35561318e+04 1.37885410e+04 1.37526484e+04 1.37014268e+04 1.38751494e+04 1.38024551e+04 1.37079014e+04 1.36757988e+04 1.36728975e+04 1.35583740e+04 1.37586230e+04 1.38452783e+04 1.38467227e+04 1.38021787e+04 1.34756904e+04 1.36798408e+04 1.37163398e+04 1.35652412e+04 1.38313945e+04 1.38278984e+04 1.35860479e+04 1.36316094e+04 1.36816543e+04 1.39699355e+04 1.40871758e+04 1.37198164e+04 1.35622803e+04 1.34412305e+04 1.35340283e+04 1.36611338e+04 1.37527490e+04 1.37815156e+04 1.36989980e+04 1.36104893e+04 1.34431582e+04 1.35766797e+04 1.39018965e+04 1.38512637e+04 1.35216875e+04 1.34513564e+04 1.34636055e+04 1.34683818e+04 1.36451719e+04 1.37414697e+04 1.35466592e+04 1.34532119e+04 1.34108799e+04 1.34001475e+04 1.35933242e+04 1.35512471e+04 1.35581309e+04 1.35723369e+04 1.33621455e+04 1.34497051e+04 1.32570049e+04 1.32710146e+04 1.36872451e+04 1.33843135e+04 1.31602900e+04 1.33780303e+04 1.32009502e+04 1.30978965e+04 1.36527686e+04 1.36556807e+04 1.30311396e+04 1.30121045e+04 1.31542412e+04 1.30543535e+04 1.33352852e+04 1.32910596e+04 1.28677090e+04 1.29728467e+04 1.30752754e+04 1.32618672e+04 1.33188379e+04 1.30385439e+04 1.31521846e+04 1.29619150e+04 1.25995859e+04 1.27699893e+04 1.31013301e+04 1.29810332e+04 1.30007959e+04 1.29582207e+04 1.24326846e+04 1.26208652e+04 1.30923691e+04 1.30667549e+04 1.28129580e+04 1.23231387e+04 1.24213223e+04 1.29256855e+04 1.27873574e+04 1.26003604e+04 1.27602754e+04 1.25301602e+04 1.24761104e+04 1.25798672e+04 1.21681504e+04 1.22250439e+04 1.25624111e+04 1.26588799e+04 1.24402031e+04 1.20187529e+04 1.20182305e+04 1.23258320e+04 1.24952236e+04 1.23324609e+04 1.20212666e+04 1.18537852e+04 1.20095020e+04 1.22326465e+04 1.24012979e+04 1.21906279e+04 1.18413965e+04 1.19083447e+04 1.18385342e+04 1.18139336e+04 1.19449092e+04 1.17878203e+04 1.18183916e+04 1.19473369e+04 1.17064121e+04 1.16170625e+04 1.17338057e+04 1.16614746e+04 1.16992666e+04 1.15641523e+04 1.13213164e+04 1.13375156e+04 1.15048066e+04 1.16530156e+04 1.16309365e+04 1.13312549e+04 1.10760898e+04 1.11905850e+04 1.11257529e+04 1.11511035e+04 1.13499736e+04 1.10885381e+04 1.08783096e+04 1.08870977e+04 1.09361689e+04 1.10652988e+04 1.12220264e+04 1.10582861e+04 1.08620508e+04 1.06969834e+04 1.04489727e+04 1.05923672e+04 1.07862520e+04 1.08211758e+04 1.07469473e+04 1.04069082e+04 1.03207441e+04 1.04834189e+04 1.05646455e+04 1.04479795e+04 1.04040020e+04 1.02659688e+04 1.00566006e+04 1.02201445e+04 1.03925283e+04 1.02503770e+04 9.97876660e+03 9.99429980e+03 1.00016475e+04 1.00392588e+04 1.00468203e+04 9.87978223e+03 9.99896973e+03 9.77041504e+03 9.63352344e+03 9.81670508e+03 9.75760156e+03 9.64454590e+03 9.81443457e+03 9.64268164e+03 9.36401855e+03 9.48548242e+03 9.58128516e+03 9.54980371e+03 1.05098691e+04 1.03775557e+04 1.10599229e+04 1.00132480e+04 2.04897246e+04 2.76277832e+04 -4.38491550e+06 -1809698. -1.00585050e+06 -1.15336112e+06 -6356985. -63816292. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -30456054. 2369677. 2.81209883e+04 1.31476426e+04 7.34238330e+03 6.59145264e+03 6.29139062e+03 7.20970361e+03 7.02833887e+03 6.35438281e+03 6.37586572e+03 6.56956543e+03 6.42051758e+03 6.22753564e+03 6.11868115e+03 5.98225977e+03 6.23272168e+03 6.36417920e+03 6.05167236e+03 5.76498193e+03 5.76453613e+03 5.85085352e+03 5.88639697e+03 5.93351123e+03 5.68515234e+03 5.54362207e+03 5.64647656e+03 5.61176318e+03 5.56709619e+03 5.43135400e+03 5.34038379e+03 5.48537891e+03 5.55556787e+03 5.37706104e+03 5.06294434e+03 5.07238965e+03 5.21799805e+03 5.21299268e+03 5.07270850e+03 4.88995117e+03 4.88972217e+03 5.00352051e+03 5.06800293e+03 4.90714941e+03 4.61883252e+03 4.66146533e+03 4.82398877e+03 4.71670312e+03 4.70637354e+03 4.58938770e+03 4.36859473e+03 4.43062402e+03 4.49504492e+03 4.39300195e+03 4.30953711e+03 4.36616162e+03 4.32881934e+03 4.26388574e+03 4.14787646e+03 3.95634619e+03 4.02016602e+03 4.20841064e+03 4.05797485e+03 3.86919409e+03 3.78358154e+03 3.75510425e+03 3.90906982e+03 3.94986987e+03 3.77397437e+03 3.63604199e+03 3.58466479e+03 3.52565259e+03 3.57299219e+03 3.64333301e+03 3.47395801e+03 3.37917896e+03 3.42988354e+03 3.35954346e+03 3.26348389e+03 3.24153442e+03 3.26097949e+03 3.27109521e+03 3.18930835e+03 3.14495312e+03 3.02552173e+03 2.91397510e+03 3.03659302e+03 3.08347510e+03 2.88774561e+03 2.75375659e+03 2.79914990e+03 2.83392749e+03 2.82068286e+03 2.81028931e+03 2.67497168e+03 2.59231274e+03 2.62191284e+03 2.58651685e+03 2.55117505e+03 2.49852051e+03 2.41754395e+03 2.38756372e+03 2.40289795e+03 2.38810791e+03 2.32492188e+03 2.29898535e+03 2.27417310e+03 2.22237012e+03 2.18363672e+03 2.09332520e+03 2.05694678e+03 2.13361035e+03 2.10754712e+03 1.96204028e+03 1.89441992e+03 1.89404626e+03 1.95362158e+03 1.96645947e+03 1.86281287e+03 1.75460327e+03 1.72928894e+03 1.72494604e+03 1.71359180e+03 1.69648694e+03 1.65200098e+03 1.62419128e+03 1.58390015e+03 1.54913623e+03 1.52957690e+03 1.47503040e+03 1.46280029e+03 1.47927368e+03 1.43032629e+03 1.36957080e+03 1.32657715e+03 1.28855835e+03 1.31359424e+03 1.31774927e+03 1.23007996e+03 1.17173047e+03 1.16476514e+03 1.18619128e+03 1.17938220e+03 1.11522742e+03 1.06078540e+03 1.03310352e+03 1.01616034e+03 1.01547290e+03 1.00235834e+03 9.43178345e+02 8.96803467e+02 9.00551147e+02 9.03206177e+02 8.72985413e+02 8.37532288e+02 8.15322876e+02 7.93670532e+02 7.77243286e+02 7.53594910e+02 7.14682434e+02 6.89838196e+02 6.86249451e+02 6.74953064e+02 6.46276123e+02 6.10201172e+02 5.98021545e+02 5.87496521e+02 5.68742798e+02 5.57074463e+02 5.25670227e+02 5.10905457e+02 5.00341125e+02 4.75634247e+02 4.58481842e+02 4.36259796e+02 4.19277039e+02 4.11358734e+02 4.03747467e+02 3.85051971e+02 3.52747772e+02 3.35334290e+02 3.35091370e+02 3.29831177e+02 3.10229370e+02 2.82820831e+02 2.68583374e+02 2.63022369e+02 2.54473785e+02 2.42000870e+02 2.22473358e+02 2.07077866e+02 1.99209106e+02 1.92263290e+02 1.84024460e+02 1.71744080e+02 1.59789383e+02 1.50160233e+02 1.40992844e+02 1.33028900e+02 1.24944794e+02 1.17016632e+02 1.07194977e+02 9.70222702e+01 8.84718018e+01 8.17413330e+01 7.76173553e+01 7.34203644e+01 6.62998199e+01 5.81123581e+01 5.11955147e+01 4.68315010e+01 4.43711281e+01 4.06534081e+01 3.53738632e+01 3.06330528e+01 2.67704411e+01 2.39510021e+01 2.15335941e+01 1.90756397e+01 1.69091911e+01 1.50739222e+01 1.35662403e+01 1.24433632e+01 1.16314430e+01 1.11454649e+01 1.09588585e+01 1.11213684e+01 1.16682901e+01 1.25965271e+01 1.36915884e+01 1.51869192e+01 1.70695057e+01 1.91756897e+01 2.18229446e+01 2.46480656e+01 2.81803360e+01 3.18806973e+01 3.46941109e+01 3.80397720e+01 4.30305939e+01 4.96488419e+01 5.64035416e+01 6.11141014e+01 6.41343994e+01 6.85246964e+01 7.58706207e+01 8.60587997e+01 9.57865982e+01 1.01780396e+02 1.05042030e+02 1.12291359e+02 1.26658203e+02 1.36597107e+02 1.39816589e+02 1.49106003e+02 1.61014328e+02 1.70483200e+02 1.86728287e+02 1.94455124e+02 1.98406601e+02 2.14703995e+02 2.22014526e+02 2.38670410e+02 2.58174774e+02 2.59618622e+02 2.76372467e+02 2.97171997e+02 3.05058075e+02 3.18599365e+02 3.33292053e+02 3.49010071e+02 3.65221680e+02 3.76338470e+02 3.81165802e+02 3.98699463e+02 4.36189453e+02 4.63807587e+02 4.69838837e+02 4.67085022e+02 4.71599976e+02 4.97790771e+02 5.40578613e+02 5.74247131e+02 5.81512451e+02 5.70796814e+02 5.89840454e+02 6.30455017e+02 6.47286133e+02 6.62690979e+02 6.81903687e+02 7.02734436e+02 7.27135742e+02 7.73098938e+02 7.73867371e+02 7.73619202e+02 8.13831177e+02 8.11684937e+02 8.62635620e+02 9.14068909e+02 9.06676514e+02 9.57870117e+02 9.59161072e+02 9.46065063e+02 1.00285474e+03 1.00883270e+03 1.05066663e+03 1.14647534e+03 1.11451233e+03 1.07881213e+03 1.12569006e+03 1.20665698e+03 1.28125195e+03 1.28261658e+03 1.24156885e+03 1.23878540e+03 1.28049731e+03 1.36691687e+03 1.45090051e+03 1.45160571e+03 1.41336462e+03 1.42616333e+03 1.50327771e+03 1.54630542e+03 1.55032080e+03 1.57173743e+03 1.60839648e+03 1.64919153e+03 1.73206140e+03 1.76938794e+03 1.70665710e+03 1.72622620e+03 1.79423181e+03 1.83018994e+03 1.88034229e+03 1.90754187e+03 1.99467004e+03 1.98024414e+03 1.94583301e+03 2.04892432e+03 2.02265259e+03 2.09872827e+03 2.27558423e+03 2.19453223e+03 2.09175146e+03 2.18455518e+03 2.32808447e+03 2.42490210e+03 2.44556177e+03 2.35504565e+03 2.30431372e+03 2.39182227e+03 2.55440137e+03 2.68486230e+03 2.65110718e+03 2.53501929e+03 2.55646826e+03 2.68171362e+03 2.76047949e+03 2.86652222e+03 2.90588696e+03 2.77510083e+03 2.78250854e+03 2.95669531e+03 3.03280835e+03 2.97471533e+03 2.99921997e+03 3.06167920e+03 3.07945093e+03 3.24126172e+03 3.30472290e+03 3.18612451e+03 3.22148853e+03 3.30264844e+03 3.33284375e+03 3.40529761e+03 3.42908447e+03 3.54874561e+03 3.61961035e+03 3.56255444e+03 3.52447998e+03 3.50101929e+03 3.69958911e+03 3.93026099e+03 3.89449170e+03 3.74832202e+03 3.69865381e+03 3.87441846e+03 4.11824658e+03 4.03727051e+03 3.85325366e+03 3.97934106e+03 4.14820068e+03 4.27076660e+03 4.46735693e+03 4.41227148e+03 4.20436621e+03 4.15233936e+03 4.32372217e+03 4.51564697e+03 4.56410010e+03 4.53732812e+03 4.55357227e+03 4.61359570e+03 4.74518652e+03 4.73652148e+03 4.64523096e+03 4.73348047e+03 4.73841650e+03 4.98061377e+03 5.13564648e+03 4.99594043e+03 5.05012598e+03 5.12203564e+03 5.15250586e+03 5.12315186e+03 5.01309619e+03 5.29347266e+03 5.58215625e+03 5.47223877e+03 5.25404492e+03 5.29788672e+03 5.63039893e+03 5.75608740e+03 5.67844287e+03 5.66789307e+03 5.52851855e+03 5.55467139e+03 5.88613574e+03 5.94866943e+03 5.84033936e+03 5.74661133e+03 5.72996582e+03 6.12673779e+03 6.37649219e+03 6.08456396e+03 6.00807031e+03 6.19154150e+03 6.26113184e+03 6.47281689e+03 6.54901953e+03 6.23381445e+03 6.25459277e+03 6.44189453e+03 6.54685400e+03 6.72924023e+03 6.89787305e+03 7.01969580e+03 6.82994678e+03 6.69081055e+03 6.74386084e+03 8.03938916e+03 1.49850488e+04 2.11540410e+04 5752442. -1.53819412e+06 2.14722250e+06 9080293. 9826914. 27903018. 1.64722175e+06 -2.48916950e+06 2.93547975e+06 -2.61630650e+06 126316656. 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. 0. 0. 0. 0. 0. 0. 0. 60725064. 3.45647175e+06 3.25881387e+04 2.47304062e+04 1.63745654e+04 1.50014775e+04 1.45902871e+04 1.25807031e+04 1.23024307e+04 1.04680781e+04 1.01340723e+04 9.87084277e+03 1.01221885e+04 9.89638672e+03 9.66796289e+03 9.96317871e+03 1.00309824e+04 1.02921465e+04 1.04397646e+04 9.60885449e+03 9.51951172e+03 9.71133203e+03 9.96818848e+03 9.99636133e+03 9.81700195e+03 1.05014688e+04 1.03239932e+04 1.01214580e+04 1.06070117e+04 1.06100918e+04 1.02528975e+04 1.06020859e+04 1.09813164e+04 1.07804277e+04 1.07293613e+04 1.07131123e+04 1.07147461e+04 1.05200498e+04 1.05559092e+04 1.10899062e+04 1.11972783e+04 1.08882275e+04 1.09492139e+04 1.10014609e+04 1.10821191e+04 1.10565371e+04 1.10574961e+04 1.11764307e+04 1.09922412e+04 1.09798594e+04 1.11503701e+04 1.11581846e+04 1.16248281e+04 1.17361523e+04 1.14269805e+04 1.11165850e+04 1.10876660e+04 1.17985205e+04 1.19557275e+04 1.15827549e+04 1.13760518e+04 1.14900166e+04 1.16922539e+04 1.16431787e+04 1.20387471e+04 1.20619629e+04 1.14345547e+04 1.13286699e+04 1.19892373e+04 1.24830361e+04 1.21894277e+04 1.19577314e+04 1.19994482e+04 1.19810781e+04 1.20310664e+04 1.20790068e+04 1.22119678e+04 1.22070518e+04 1.20567891e+04 1.20860273e+04 1.21989600e+04 1.21898164e+04 1.26286064e+04 1.26226738e+04 1.22584678e+04 1.22797812e+04 1.23013301e+04 1.27383145e+04 1.28169434e+04 1.24924746e+04 1.25480049e+04 1.23182881e+04 1.21563418e+04 1.27701924e+04 1.27609912e+04 1.21258428e+04 1.23293271e+04 1.30879707e+04 1.35563721e+04 1.31750098e+04 1.27421719e+04 1.26682236e+04 1.27176357e+04 1.28013887e+04 1.28154014e+04 1.28798525e+04 1.28280186e+04 1.32172100e+04 1.32063154e+04 1.28846016e+04 1.29736475e+04 1.26040684e+04 1.29027256e+04 1.37246787e+04 1.34744473e+04 1.31685752e+04 1.28134512e+04 1.27537227e+04 1.35714072e+04 1.36268652e+04 1.31943037e+04 1.29346982e+04 1.29129004e+04 1.32408213e+04 1.32253828e+04 1.36658252e+04 1.38185693e+04 1.33448076e+04 1.32292959e+04 1.32686709e+04 1.35311904e+04 1.35746211e+04 1.34149385e+04 1.32483418e+04 1.33120479e+04 1.33960723e+04 1.30200088e+04 1.33334668e+04 1.41132129e+04 1.39122451e+04 1.35764688e+04 1.32364658e+04 1.31552393e+04 1.39258516e+04 1.39981006e+04 1.35942744e+04 1.32627637e+04 1.32268613e+04 1.36924951e+04 1.36218887e+04 1.35857207e+04 1.33232119e+04 1.35850898e+04 1.42752451e+04 1.39359053e+04 1.37829209e+04 1.38487949e+04 1.37673311e+04 1.35256426e+04 1.34962510e+04 1.36234053e+04 1.36193389e+04 1.37628057e+04 1.33663877e+04 1.35273369e+04 1.44076816e+04 1.38145693e+04 1.33325967e+04 1.36852295e+04 1.36859961e+04 1.41057969e+04 1.39693252e+04 1.34539551e+04 1.39110996e+04 1.40207334e+04 1.37732305e+04 1.36897637e+04 1.36861289e+04 1.36302021e+04 1.35825801e+04 1.36358721e+04 1.33117021e+04 1.37025889e+04 1.44705693e+04 1.41335332e+04 1.36464307e+04 1.32226250e+04 1.34116748e+04 1.42472227e+04 1.41536904e+04 1.37311592e+04 1.34143213e+04 1.33239375e+04 1.36965469e+04 1.37123115e+04 1.39782959e+04 1.38608906e+04 1.34547783e+04 1.35461748e+04 1.35351523e+04 1.39470791e+04 1.38977295e+04 1.35010020e+04 1.35455010e+04 1.35458604e+04 1.35251504e+04 1.31674053e+04 1.35031104e+04 1.43142988e+04 1.39653350e+04 1.35568506e+04 1.32075078e+04 1.30901846e+04 1.38184980e+04 1.39406641e+04 1.35322812e+04 1.31238672e+04 1.30780186e+04 1.34985283e+04 1.34737852e+04 1.37553975e+04 1.37808291e+04 1.34205996e+04 1.29878701e+04 1.29274688e+04 1.37394902e+04 1.36648447e+04 1.32308711e+04 1.30229648e+04 1.29617510e+04 1.36359932e+04 1.36589775e+04 1.28993203e+04 1.28513828e+04 1.35165820e+04 1.35036748e+04 1.28452412e+04 1.28066436e+04 1.34265879e+04 1.34845986e+04 1.30271035e+04 1.26996172e+04 1.27150430e+04 1.33495010e+04 1.31812090e+04 1.27654512e+04 1.29454453e+04 1.28771377e+04 1.28535332e+04 1.28407568e+04 1.27615498e+04 1.24493965e+04 1.27224492e+04 1.32714980e+04 1.28985840e+04 1.29311025e+04 1.29600811e+04 1.27109922e+04 1.26888457e+04 1.26031562e+04 1.25131221e+04 1.22885654e+04 1.22444570e+04 1.24679043e+04 1.24801895e+04 1.28169277e+04 1.24210205e+04 1.19979688e+04 1.23146270e+04 1.24167666e+04 1.27787471e+04 1.25532705e+04 1.21486172e+04 1.20314658e+04 1.19473389e+04 1.21823750e+04 1.21506445e+04 1.23496191e+04 1.23096250e+04 1.19880195e+04 1.19067500e+04 1.15438359e+04 1.18479238e+04 1.24848643e+04 1.22616270e+04 1.19145557e+04 1.15381982e+04 1.13294561e+04 1.18479844e+04 1.21813701e+04 1.18433203e+04 1.13628154e+04 1.13162197e+04 1.15146445e+04 1.15341279e+04 1.17919268e+04 1.16740410e+04 1.13730449e+04 1.12773398e+04 1.11945576e+04 1.16427881e+04 1.16255039e+04 1.09459990e+04 1.09011455e+04 1.14937988e+04 1.13280059e+04 1.07056191e+04 1.08796328e+04 1.14060312e+04 1.12927324e+04 1.09887686e+04 1.06418848e+04 1.06047334e+04 1.11430869e+04 1.11196250e+04 1.07871572e+04 1.05305479e+04 1.03391738e+04 1.05293877e+04 1.06799688e+04 1.05935830e+04 1.02165449e+04 1.04196279e+04 1.08608242e+04 1.05054541e+04 1.04816709e+04 1.04321699e+04 1.01860615e+04 1.02219824e+04 1.02472617e+04 1.02009180e+04 1.00765293e+04 9.89015527e+03 9.64562402e+03 9.94966406e+03 1.04059121e+04 9.81065625e+03 9.37670801e+03 9.69073242e+03 9.92166211e+03 1.01582783e+04 9.86939941e+03 9.54105078e+03 9.69455762e+03 9.67019141e+03 9.32638672e+03 9.17595703e+03 9.53141113e+03 9.51605371e+03 9.22536914e+03 9.10954980e+03 8.80912207e+03 9.08392090e+03 9.63228320e+03 9.33278516e+03 9.00741699e+03 8.75383984e+03 8.62757812e+03 9.01407812e+03 9.31791504e+03 9.00506152e+03 8.60981836e+03 8.54278809e+03 8.60208105e+03 8.59033203e+03 8.75887500e+03 8.63595996e+03 8.33784473e+03 8.40799902e+03 8.29052051e+03 8.58590234e+03 8.47895117e+03 8.20095508e+03 8.17564355e+03 8.12759033e+03 8.13745068e+03 7.90411035e+03 7.86697314e+03 8.17414648e+03 8.10004150e+03 7.89481299e+03 7.63149365e+03 7.62625195e+03 8.04068701e+03 7.94589355e+03 7.65614502e+03 7.46389404e+03 7.39514893e+03 7.43391113e+03 7.39435791e+03 7.44799463e+03 7.22606396e+03 7.26457764e+03 7.47219287e+03 7.22990039e+03 7.32976465e+03 7.31714746e+03 7.07525049e+03 7.01136914e+03 6.88340674e+03 6.93439941e+03 6.86206787e+03 6.76028662e+03 6.67675781e+03 6.87738477e+03 6.84780518e+03 6.45668506e+03 6.33188818e+03 6.46873389e+03 6.53647021e+03 6.66751416e+03 6.51534326e+03 6.20668896e+03 6.32018066e+03 6.41114844e+03 6.24034570e+03 6.11431934e+03 6.06182324e+03 5.98954395e+03 5.89923877e+03 5.99064209e+03 5.82887793e+03 5.82259277e+03 6.05566748e+03 5.91018945e+03 5.74706934e+03 5.57012939e+03 5.52052295e+03 5.73023535e+03 5.65653223e+03 5.53423535e+03 5.36158936e+03 5.17117432e+03 5.25042139e+03 5.40176367e+03 5.53530322e+03 5.29280811e+03 5.06300684e+03 5.06391943e+03 5.06295703e+03 5.20261475e+03 5.12096094e+03 4.89919824e+03 4.83353516e+03 4.75686572e+03 4.78310693e+03 4.67405615e+03 4.65809180e+03 4.81641406e+03 4.69601074e+03 4.60136572e+03 4.45739307e+03 4.36541016e+03 4.58540527e+03 4.53267432e+03 4.34809912e+03 4.20911426e+03 4.13518555e+03 4.20030029e+03 4.15833008e+03 4.25857275e+03 4.22640381e+03 4.03261816e+03 3.86656421e+03 3.89977466e+03 4.07021045e+03 3.95720923e+03 3.80856421e+03 3.75348730e+03 3.69430518e+03 3.66460986e+03 3.58699854e+03 3.63720825e+03 3.58812769e+03 3.47380054e+03 3.56371216e+03 3.56121338e+03 3.44658350e+03 3.37227368e+03 3.31204907e+03 3.28276440e+03 3.15853589e+03 3.08898950e+03 3.21650806e+03 3.21735596e+03 2.99657910e+03 2.90146265e+03 3.01036890e+03 3.08127734e+03 3.00138770e+03 2.84588623e+03 2.74498193e+03 2.82420898e+03 2.83954517e+03 2.74342798e+03 2.70847974e+03 2.59730762e+03 2.45729980e+03 2.53066650e+03 2.64870190e+03 2.60204395e+03 2.42762939e+03 2.32034570e+03 2.41949561e+03 2.45785303e+03 2.34336230e+03 2.23525024e+03 2.17876611e+03 2.18038623e+03 2.16641992e+03 2.20496411e+03 2.17162158e+03 2.06508569e+03 2.00449329e+03 1.97533069e+03 2.01736865e+03 1.94272241e+03 1.85815881e+03 1.90723022e+03 1.87104602e+03 1.81433691e+03 1.74686267e+03 1.69963635e+03 1.76127332e+03 1.68309375e+03 1.59383215e+03 1.60492285e+03 1.60297913e+03 1.57638696e+03 1.52593542e+03 1.52964661e+03 1.51041956e+03 1.43935010e+03 1.36969629e+03 1.33686292e+03 1.38558167e+03 1.34151306e+03 1.27735400e+03 1.25873413e+03 1.22745740e+03 1.22259473e+03 1.19222632e+03 1.17267676e+03 1.13686536e+03 1.08547424e+03 1.09653918e+03 1.07594385e+03 1.03790710e+03 1.01264868e+03 9.81352783e+02 9.49906250e+02 9.02186462e+02 8.75771973e+02 8.96533569e+02 9.03831665e+02 8.37510925e+02 7.78063354e+02 7.91873413e+02 8.03534607e+02 7.71520142e+02 7.17687317e+02 6.81236816e+02 6.95614319e+02 6.78037720e+02 6.34871460e+02 6.39575195e+02 6.15439819e+02 5.65395935e+02 5.54353638e+02 5.63463074e+02 5.49360229e+02 5.03431610e+02 4.72940979e+02 4.80289276e+02 4.81030792e+02 4.50761932e+02 4.15767670e+02 3.92838989e+02 3.97686523e+02 3.89142761e+02 3.60725800e+02 3.48258514e+02 3.36683533e+02 3.17455750e+02 3.00201080e+02 2.96344757e+02 2.78636475e+02 2.56548950e+02 2.52755615e+02 2.42632080e+02 2.31153641e+02 2.14622574e+02 1.99035202e+02 2.01411438e+02 1.97911926e+02 1.78639450e+02 1.71049591e+02 2.39114410e+02 4.87552582e+02 6.82932251e+02 2761675. -3.99599675e+06 1.93396011e+02 1.41337875e+02 1.30896637e+02 1.48825851e+02 2.56855011e+02 3.76250061e+02 3.21102650e+06 -26947704. 19845154. -7.06277950e+06 -7817197. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -128530912. 3.59249425e+06 1.69060654e+02 1.29538147e+02 1.39578247e+02 1.25291611e+02 1.04283340e+02 7.20233459e+01 6.29173660e+01 8.40561066e+01 9.86866913e+01 9.75332565e+01 1.02286186e+02 1.08166901e+02 1.15907249e+02 1.24475319e+02 1.33254761e+02 1.41163315e+02 1.49712753e+02 1.62455704e+02 1.73894287e+02 1.81844025e+02 1.90931091e+02 1.95221893e+02 2.06980179e+02 2.25998016e+02 2.35730652e+02 2.44910492e+02 2.64175049e+02 2.83987579e+02 2.90046387e+02 2.96840088e+02 3.09340851e+02 3.19986755e+02 3.40255432e+02 3.64413605e+02 3.73648163e+02 3.85825500e+02 4.08812531e+02 4.19025208e+02 4.25091766e+02 4.45196716e+02 4.62583252e+02 4.81847076e+02 5.10137909e+02 5.19933594e+02 5.32769836e+02 5.59278870e+02 5.70808411e+02 5.85805664e+02 6.04295471e+02 6.29284485e+02 6.57598999e+02 6.79747375e+02 7.10265015e+02 7.18149658e+02 7.24197021e+02 7.62203857e+02 7.66998413e+02 7.77499329e+02 8.26448486e+02 8.50090210e+02 8.66210449e+02 9.02257263e+02 9.22629761e+02 9.30774780e+02 9.54908325e+02 9.73787537e+02 9.92966248e+02 1.03701794e+03 1.07355298e+03 1.10022034e+03 1.12407996e+03 1.14095984e+03 1.15929797e+03 1.18620349e+03 1.22601587e+03 1.24455713e+03 1.27294336e+03 1.34321387e+03 1.34440454e+03 1.31943213e+03 1.38036450e+03 1.40911560e+03 1.42446606e+03 1.49154248e+03 1.51218933e+03 1.52401624e+03 1.59488989e+03 1.64075793e+03 1.62874500e+03 1.62554663e+03 1.65349463e+03 1.70018225e+03 1.76059839e+03 1.80100488e+03 1.84372864e+03 1.88117114e+03 1.89759998e+03 1.89184705e+03 1.90623596e+03 1.98843958e+03 2.02641943e+03 2.02597742e+03 2.10613794e+03 2.12679468e+03 2.14161450e+03 2.21720972e+03 2.20613135e+03 2.19166626e+03 2.25643457e+03 2.35571216e+03 2.40587207e+03 2.39866504e+03 2.45069580e+03 2.51059424e+03 2.54477661e+03 2.56841162e+03 2.54312354e+03 2.57043921e+03 2.69608862e+03 2.73725879e+03 2.72508887e+03 2.78745264e+03 2.78550635e+03 2.81060083e+03 2.91882666e+03 2.94111719e+03 2.91529907e+03 2.98965942e+03 3.11220996e+03 3.15766968e+03 3.14355249e+03 3.10314478e+03 3.12801416e+03 3.26043872e+03 3.34663452e+03 3.31402026e+03 3.33794238e+03 3.47880835e+03 3.52909253e+03 3.52266919e+03 3.54024194e+03 3.48608984e+03 3.51369775e+03 3.62094995e+03 3.73415137e+03 3.76697607e+03 3.78913086e+03 3.88811255e+03 3.92621753e+03 3.89742261e+03 3.88769360e+03 3.93431201e+03 4.03715381e+03 4.15439307e+03 4.25526172e+03 4.24921729e+03 4.23211084e+03 4.18065527e+03 4.29641064e+03 4.38999365e+03 4.30084033e+03 4.36427441e+03 4.53563965e+03 4.64249023e+03 4.57546484e+03 4.57083398e+03 4.61472266e+03 4.60287109e+03 4.74466455e+03 4.90869629e+03 4.93228027e+03 4.89622266e+03 4.93287549e+03 5.00532764e+03 4.98508691e+03 5.01211035e+03 5.07987305e+03 5.12716504e+03 5.34163037e+03 5.42816699e+03 5.24266016e+03 5.24892822e+03 5.34655615e+03 5.48415576e+03 5.60082471e+03 5.42637500e+03 5.44161426e+03 5.70683887e+03 5.80998145e+03 5.72604834e+03 5.77056396e+03 5.77896631e+03 5.75500732e+03 5.93052588e+03 6.10724072e+03 6.00716602e+03 5.97356006e+03 6.17751416e+03 6.33023730e+03 6.24288721e+03 6.22388818e+03 6.24241846e+03 6.27672705e+03 6.50279639e+03 6.48155371e+03 6.44271631e+03 6.59532227e+03 6.58101270e+03 6.53510010e+03 6.69141699e+03 6.64224072e+03 6.71732227e+03 6.90876709e+03 6.94231494e+03 7.01002344e+03 6.95399609e+03 7.01315283e+03 7.01807178e+03 7.02415918e+03 7.23309766e+03 7.21787842e+03 7.12202148e+03 7.36631494e+03 7.43488135e+03 7.38087061e+03 7.45707812e+03 7.58610107e+03 7.51235938e+03 7.65625195e+03 7.83641016e+03 7.68863184e+03 7.61066748e+03 7.73899365e+03 7.74636084e+03 7.83274805e+03 7.91280371e+03 7.95661035e+03 8.06162354e+03 8.19488965e+03 8.17816699e+03 8.14755029e+03 8.23090918e+03 8.21912012e+03 8.28417969e+03 8.51152637e+03 8.32190039e+03 8.29454883e+03 8.59837988e+03 8.58396875e+03 8.52749707e+03 8.64097852e+03 8.69122070e+03 8.63185352e+03 8.67157129e+03 8.81576953e+03 9.01552539e+03 8.93574902e+03 9.02087402e+03 9.12098145e+03 8.89522070e+03 8.97895020e+03 9.07105371e+03 9.05473926e+03 9.35950684e+03 9.47616211e+03 9.30455176e+03 9.21537402e+03 9.36140137e+03 9.58494922e+03 9.59114258e+03 9.20926758e+03 9.51100098e+03 9.89428320e+03 9.67783789e+03 9.64617383e+03 9.66881543e+03 9.73091406e+03 9.82330566e+03 9.84769141e+03 9.78055371e+03 1.00396299e+04 1.01232812e+04 1.00329170e+04 1.01850693e+04 1.02385244e+04 1.02227900e+04 1.01919668e+04 9.95420801e+03 1.03058398e+04 1.06485527e+04 1.03008750e+04 1.03352002e+04 1.04212480e+04 1.05664961e+04 1.07101016e+04 1.04183262e+04 1.06215361e+04 1.08766279e+04 1.08041914e+04 1.07495830e+04 1.06397275e+04 1.06856143e+04 1.09025996e+04 1.09291914e+04 1.09334033e+04 1.10910303e+04 1.11343486e+04 1.11417451e+04 1.12809395e+04 1.12446445e+04 1.10785273e+04 1.10544492e+04 1.12976670e+04 1.14883486e+04 1.12670127e+04 1.12079395e+04 1.12476221e+04 1.13577881e+04 1.16275127e+04 1.15940498e+04 1.13935615e+04 1.14317334e+04 1.17209219e+04 1.18969775e+04 1.17477549e+04 1.14418262e+04 1.16073740e+04 1.18586768e+04 1.17656748e+04 1.18013135e+04 1.20535986e+04 1.20050127e+04 1.19474961e+04 1.21497695e+04 1.22025938e+04 1.20580225e+04 1.19455527e+04 1.21364189e+04 1.22162275e+04 1.19434209e+04 1.18893701e+04 1.21427871e+04 1.23887266e+04 1.25036680e+04 1.23637197e+04 1.21664688e+04 1.25059482e+04 1.26655059e+04 1.22521943e+04 1.21741455e+04 1.25212910e+04 1.28114990e+04 1.26802510e+04 1.23374062e+04 1.23132539e+04 1.25370674e+04 1.27902373e+04 1.29896602e+04 1.29813389e+04 1.26957559e+04 1.25532422e+04 1.26611611e+04 1.26447061e+04 1.27198867e+04 1.27525781e+04 1.27944111e+04 1.29606533e+04 1.29692842e+04 1.28931797e+04 1.28107598e+04 1.29931348e+04 1.33905254e+04 1.32314756e+04 1.28081104e+04 1.27584150e+04 1.30345342e+04 1.32607598e+04 1.34366943e+04 1.32462676e+04 1.27571543e+04 1.28341016e+04 1.33000254e+04 1.34779238e+04 1.35110820e+04 1.32787021e+04 1.30869492e+04 1.32302783e+04 1.32289922e+04 1.33843174e+04 1.32999668e+04 1.30015430e+04 1.34499668e+04 1.36993379e+04 1.34209150e+04 1.32218535e+04 1.29606914e+04 1.32807500e+04 1.39343467e+04 1.38248984e+04 1.33040381e+04 1.35198926e+04 1.38239922e+04 1.33875938e+04 1.32985010e+04 1.32606221e+04 1.33009395e+04 1.38198379e+04 1.36778398e+04 1.32735127e+04 1.35646436e+04 1.38264717e+04 1.36189092e+04 1.35399531e+04 1.37750127e+04 1.36586230e+04 1.34837637e+04 1.36478730e+04 1.36019033e+04 1.37485410e+04 1.38446318e+04 1.37386885e+04 1.37369678e+04 13461. 1.35215215e+04 1.36936855e+04 1.36946299e+04 1.38288486e+04 1.38957598e+04 1.38781367e+04 1.35835820e+04 1.35291875e+04 1.37063613e+04 1.38070049e+04 1.38296650e+04 1.36043965e+04 1.36653535e+04 1.38099277e+04 1.36863623e+04 1.38064219e+04 1.37701387e+04 1.34669102e+04 1.36728467e+04 1.37229766e+04 1.36055996e+04 1.38422500e+04 1.36632109e+04 1.35172217e+04 1.39373018e+04 1.40570176e+04 1.35045000e+04 1.33598818e+04 1.37579238e+04 1.39948564e+04 1.39398643e+04 1.35768037e+04 1.34018008e+04 1.35381367e+04 1.37639922e+04 1.37919229e+04 1.35415176e+04 1.35360889e+04 1.36756562e+04 1.35716504e+04 1.36870312e+04 1.37039648e+04 1.36104932e+04 1.37364316e+04 1.35968096e+04 1.36351650e+04 1.35647852e+04 1.34235273e+04 1.35375752e+04 1.35822891e+04 1.35813633e+04 1.34080596e+04 1.33310264e+04 1.35892744e+04 1.35950557e+04 1.35307012e+04 1.36056689e+04 1.32741631e+04 1.31790439e+04 1.36086484e+04 1.34940303e+04 1.31509365e+04 1.35048350e+04 1.35149951e+04 1.30395068e+04 1.33675117e+04 1.34767061e+04 1.30791758e+04 1.33319307e+04 1.34771357e+04 1.31353701e+04 1.31039863e+04 1.32718438e+04 1.31397090e+04 1.31878691e+04 1.31762480e+04 1.27936797e+04 1.29498945e+04 1.32520322e+04 1.32936064e+04 1.32442764e+04 1.29296846e+04 1.29708965e+04 1.28847754e+04 1.26517373e+04 1.29870703e+04 1.30386172e+04 1.27611602e+04 1.29890801e+04 1.28866670e+04 1.25944482e+04 1.27711533e+04 1.28414170e+04 1.29464375e+04 1.28012910e+04 1.25254619e+04 1.24071934e+04 1.27318799e+04 1.30211133e+04 1.26034141e+04 1.25288193e+04 1.23373301e+04 1.24065293e+04 1.27666162e+04 1.23076582e+04 1.21685586e+04 1.23925713e+04 1.25105049e+04 1.23941348e+04 1.20270254e+04 1.22378506e+04 1.24683555e+04 1.22491885e+04 1.22308594e+04 1.20453418e+04 1.20266367e+04 1.22062002e+04 1.21950176e+04 1.22237588e+04 1.19621807e+04 1.18158887e+04 1.19297314e+04 1.19123867e+04 1.20346543e+04 1.18702725e+04 1.16083691e+04 1.16631963e+04 1.18262725e+04 1.18243711e+04 1.17009609e+04 1.16412783e+04 1.15712979e+04 1.16553447e+04 1.15438848e+04 1.13720908e+04 1.15745898e+04 1.15292119e+04 1.13495000e+04 1.15352412e+04 1.13267480e+04 1.11496162e+04 1.12957295e+04 1.11365059e+04 1.10606240e+04 1.12583457e+04 1.11274541e+04 1.08655293e+04 1.09542197e+04 1.10419395e+04 1.09572002e+04 1.11194219e+04 1.09366299e+04 1.07355762e+04 1.07561172e+04 1.05869639e+04 1.06889570e+04 1.06319404e+04 1.06633945e+04 1.07802393e+04 1.04470869e+04 1.05312842e+04 1.05223076e+04 1.02519697e+04 1.03072236e+04 1.04195312e+04 1.04506992e+04 1.02707861e+04 1.01601533e+04 1.02680879e+04 1.01722969e+04 1.00487900e+04 1.00131055e+04 9.99787891e+03 1.01091816e+04 9.93302148e+03 9.94368262e+03 9.99245801e+03 9.69276465e+03 9.64871387e+03 9.90813379e+03 9.86723828e+03 9.54265527e+03 9.57152539e+03 9.59193848e+03 9.44772949e+03 9.67024414e+03 9.61087207e+03 9.36055566e+03 1.03506338e+04 1.01695508e+04 9.95567090e+03 9.09635547e+03 2.00609980e+04 2.63004570e+04 -6783612. -21232836. -1.67904425e+06 -6590804. 19865352. -9.93942562e+05 -6.59038350e+06 60736984. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -30456054. 2369677. 2.81209883e+04 1.34698584e+04 6.62491895e+03 8.40655469e+03 6.95482715e+03 7.33940039e+03 6.91910352e+03 6.42653809e+03 6.44680176e+03 6.52929248e+03 6.33437939e+03 6.19469531e+03 6.17718164e+03 6.20410303e+03 6.22720166e+03 6.14725342e+03 6.00264600e+03 5.82229688e+03 5.95101807e+03 5.95627295e+03 5.87736719e+03 5.84019092e+03 5.63100342e+03 5.56131299e+03 5.64773730e+03 5.63026807e+03 5.59534912e+03 5.35558496e+03 5.31270801e+03 5.52416504e+03 5.59787695e+03 5.34925098e+03 5.07381494e+03 5.04825977e+03 5.16904883e+03 5.16510840e+03 5.09098535e+03 4.92781152e+03 5.02867236e+03 5.01413770e+03 4.93556641e+03 4.87942480e+03 4.63997754e+03 4.70600439e+03 4.88785205e+03 4.73565039e+03 4.66245557e+03 4.53799951e+03 4.40134082e+03 4.43906299e+03 4.52069531e+03 4.45376611e+03 4.26252979e+03 4.33083936e+03 4.29656885e+03 4.23074170e+03 4.19206787e+03 4.04955176e+03 4.07199536e+03 4.12640723e+03 3.96783081e+03 3.87914380e+03 3.82148291e+03 3.87449048e+03 3.96854663e+03 3.87457520e+03 3.72717017e+03 3.63113306e+03 3.63891333e+03 3.58498511e+03 3.60405835e+03 3.60663135e+03 3.44067407e+03 3.41256470e+03 3.48501929e+03 3.41050732e+03 3.31894385e+03 3.18720972e+03 3.20946533e+03 3.28157129e+03 3.21698291e+03 3.13728101e+03 3.02669897e+03 2.97339771e+03 3.02117212e+03 3.03652368e+03 2.90160107e+03 2.79851099e+03 2.88183447e+03 2.83356982e+03 2.73765283e+03 2.78763745e+03 2.68209082e+03 2.62439404e+03 2.65042456e+03 2.61420825e+03 2.57090771e+03 2.46044116e+03 2.42779712e+03 2.42982031e+03 2.44328418e+03 2.41527490e+03 2.29600269e+03 2.28017822e+03 2.25451807e+03 2.20484644e+03 2.19252100e+03 2.11932715e+03 2.09708350e+03 2.12468286e+03 2.07862817e+03 1.97930798e+03 1.89937183e+03 1.93467297e+03 1.98073840e+03 1.93409375e+03 1.85653369e+03 1.76031897e+03 1.73610876e+03 1.75265588e+03 1.74073010e+03 1.71884106e+03 1.63607263e+03 1.60752661e+03 1.58187488e+03 1.55426233e+03 1.56665759e+03 1.48653650e+03 1.45334387e+03 1.46894055e+03 1.42203406e+03 1.38175269e+03 1.34407056e+03 1.33117590e+03 1.32500452e+03 1.28474658e+03 1.23037000e+03 1.17803711e+03 1.18958142e+03 1.20285217e+03 1.16186426e+03 1.10877112e+03 1.05921619e+03 1.04417517e+03 1.04240308e+03 1.03074158e+03 1.00333691e+03 9.36925232e+02 9.08699402e+02 9.14399170e+02 9.05540527e+02 8.90344116e+02 8.44205811e+02 8.11810791e+02 7.89276917e+02 7.75810669e+02 7.65072449e+02 7.27492493e+02 7.09717834e+02 6.94182251e+02 6.76629211e+02 6.59215942e+02 6.20514099e+02 6.14092285e+02 6.07927795e+02 5.73690918e+02 5.59456238e+02 5.33248108e+02 5.14625916e+02 5.08122589e+02 4.91341522e+02 4.68983368e+02 4.38697632e+02 4.25357697e+02 4.21506226e+02 4.13661743e+02 3.95960510e+02 3.62293152e+02 3.43398285e+02 3.40620575e+02 3.32687714e+02 3.15720184e+02 2.90637360e+02 2.80717621e+02 2.74210602e+02 2.60551849e+02 2.50680969e+02 2.32607300e+02 2.20442963e+02 2.15203629e+02 2.05516312e+02 1.92186371e+02 1.77683167e+02 1.68487106e+02 1.59707138e+02 1.50796341e+02 1.44047516e+02 1.32069687e+02 1.23430649e+02 1.16238678e+02 1.07628273e+02 1.00345840e+02 9.36658478e+01 8.90368195e+01 8.29392319e+01 7.54901810e+01 6.77960510e+01 6.08694611e+01 5.75611687e+01 5.45149574e+01 4.93577271e+01 4.42232399e+01 3.94989281e+01 3.59653511e+01 3.37057457e+01 3.16357841e+01 2.88565502e+01 2.62206135e+01 2.43773499e+01 2.29583092e+01 2.18004303e+01 2.09237862e+01 2.03859291e+01 2.02344551e+01 2.04494286e+01 2.10046654e+01 2.18554096e+01 2.28296947e+01 2.43143539e+01 2.61453152e+01 2.80867367e+01 3.08730488e+01 3.37594299e+01 3.72646904e+01 4.08993263e+01 4.38937378e+01 4.78296585e+01 5.27940750e+01 5.88577461e+01 6.55432281e+01 6.98438873e+01 7.29928818e+01 7.78221817e+01 8.57944183e+01 9.62708817e+01 1.05322754e+02 1.10518219e+02 1.13818047e+02 1.21790443e+02 1.36395630e+02 1.45601929e+02 1.47261612e+02 1.56217712e+02 1.70367203e+02 1.80575073e+02 1.95982010e+02 2.02958145e+02 2.06855377e+02 2.24152237e+02 2.32019958e+02 2.46565552e+02 2.66564667e+02 2.68727661e+02 2.86012390e+02 3.06895966e+02 3.14098907e+02 3.27780914e+02 3.41776154e+02 3.59278717e+02 3.75444458e+02 3.87247314e+02 3.91555115e+02 4.06889221e+02 4.44067963e+02 4.72527405e+02 4.79576080e+02 4.77397766e+02 4.82341064e+02 5.06376312e+02 5.48541138e+02 5.84946228e+02 5.93415222e+02 5.80970581e+02 5.97250122e+02 6.40504456e+02 6.61293640e+02 6.68308228e+02 6.86250549e+02 7.13510376e+02 7.36171936e+02 7.79209595e+02 7.84218506e+02 7.84075562e+02 8.22649658e+02 8.20652161e+02 8.66492065e+02 9.16249878e+02 9.17064697e+02 9.67235168e+02 9.69267395e+02 9.55084167e+02 1.01011560e+03 1.01436926e+03 1.05662537e+03 1.15301514e+03 1.12240015e+03 1.08494434e+03 1.13842102e+03 1.22076526e+03 1.28625293e+03 1.28674048e+03 1.24514038e+03 1.24667261e+03 1.29179761e+03 1.37581433e+03 1.46334119e+03 1.45778394e+03 1.41040100e+03 1.42878613e+03 1.51734473e+03 1.56471753e+03 1.54948352e+03 1.57380981e+03 1.62192712e+03 1.65325903e+03 1.73984827e+03 1.77409619e+03 1.70859668e+03 1.74048352e+03 1.80551282e+03 1.84080945e+03 1.88390271e+03 1.91308838e+03 1.98982080e+03 1.98672803e+03 1.95613306e+03 2.04340222e+03 2.02824890e+03 2.10910010e+03 2.28376050e+03 2.18664453e+03 2.08643701e+03 2.18764966e+03 2.33960791e+03 2.43382690e+03 2.45175317e+03 2.36075854e+03 2.30142065e+03 2.39663110e+03 2.56637280e+03 2.69908276e+03 2.65445020e+03 2.55675903e+03 2.56640063e+03 2.67571655e+03 2.75769116e+03 2.85479004e+03 2.88423926e+03 2.78309253e+03 2.80506665e+03 2.95771069e+03 3.01880493e+03 3.00256958e+03 3.02761743e+03 3.04292139e+03 3.07875146e+03 3.23907910e+03 3.30971313e+03 3.22692578e+03 3.23095410e+03 3.25761548e+03 3.31252930e+03 3.42180957e+03 3.46217407e+03 3.57842090e+03 3.62204053e+03 3.52783521e+03 3.52436060e+03 3.50988672e+03 3.71363232e+03 3.94146826e+03 3.89986548e+03 3.73474023e+03 3.69534351e+03 3.89780249e+03 4.15265479e+03 4.02229346e+03 3.85580542e+03 3.99411938e+03 4.16340479e+03 4.27043164e+03 4.45333984e+03 4.37749268e+03 4.19145361e+03 4.17116797e+03 4.37032178e+03 4.47769824e+03 4.53697705e+03 4.56051562e+03 4.58110352e+03 4.59461377e+03 4.72360059e+03 4.72832080e+03 4.60743457e+03 4.71806445e+03 4.78244678e+03 5.01930811e+03 5.06961475e+03 4.97166602e+03 5.08347168e+03 5.09610205e+03 5.14505908e+03 5.11725537e+03 4.99754932e+03 5.30009619e+03 5.56559619e+03 5.43058691e+03 5.23390576e+03 5.31334863e+03 5.61923633e+03 5.74641992e+03 5.71294385e+03 5.64739209e+03 5.53605225e+03 5.61755273e+03 5.84654980e+03 5.89352490e+03 5.83512305e+03 5.74724121e+03 5.76159424e+03 6.16210986e+03 6.43817090e+03 6.11581982e+03 5.96573291e+03 6.20060107e+03 6.25777881e+03 6.47018457e+03 6.52383008e+03 6.17832520e+03 6.29202783e+03 6.50083447e+03 6.57053418e+03 6.72465869e+03 6.84303076e+03 7.01440967e+03 6.88804492e+03 6.76201855e+03 6.84057764e+03 7.89646338e+03 1.35962969e+04 2.28102637e+04 3.72953650e+06 1.91384112e+06 10386023. 1.64160062e+06 20654974. -20074570. -3.35345625e+06 2.28361675e+06 -1364773. -3.41740425e+06 -6759607. -70004648. 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. 0. 0. 0. 0. 0. 0. 60725064. 3.45647175e+06 3.25881387e+04 2.47304062e+04 1.63745654e+04 1.27120156e+04 1.27773438e+04 1.02409355e+04 9.74363965e+03 1.00986602e+04 9.89323828e+03 9.57461133e+03 9.94697559e+03 9.94931641e+03 9.86033984e+03 9.90119727e+03 9.95258398e+03 9.93533105e+03 9.95752930e+03 9.95947363e+03 9.96826367e+03 1.00456426e+04 1.00237559e+04 1.02248027e+04 1.03388799e+04 9.97947852e+03 1.00403311e+04 1.06410332e+04 1.06969082e+04 1.04425566e+04 1.04607246e+04 1.04915625e+04 1.05457734e+04 1.06173623e+04 1.06424990e+04 1.06594199e+04 1.07086016e+04 1.06173271e+04 1.06025654e+04 1.09935518e+04 1.11169131e+04 1.08877783e+04 1.09227354e+04 1.10223506e+04 1.10797158e+04 1.10249414e+04 1.10473818e+04 1.11816650e+04 1.09777803e+04 1.09236143e+04 1.11206855e+04 1.11895537e+04 1.16411768e+04 1.17281953e+04 1.13483965e+04 1.11339844e+04 1.11113623e+04 1.18109785e+04 1.19591621e+04 1.15389814e+04 1.13453066e+04 1.13698506e+04 1.17220645e+04 1.17509229e+04 1.20088848e+04 1.20680996e+04 1.14698369e+04 1.12506885e+04 1.19260400e+04 1.24798193e+04 1.21608457e+04 1.19413047e+04 1.19488496e+04 1.19477900e+04 1.19931523e+04 1.20596533e+04 1.20293340e+04 1.20247568e+04 1.21675605e+04 1.22435664e+04 1.21747383e+04 1.21856279e+04 1.25895010e+04 1.26842041e+04 1.23752246e+04 1.22777109e+04 1.23124883e+04 1.26349541e+04 1.26565664e+04 1.24967686e+04 1.25694238e+04 1.23011074e+04 1.21230742e+04 1.27346670e+04 1.27333301e+04 1.21471113e+04 1.23282246e+04 1.30401963e+04 1.35392910e+04 1.31302568e+04 1.27207051e+04 1.26541982e+04 1.26910654e+04 1.27831836e+04 1.27843877e+04 1.28500059e+04 1.28205156e+04 1.32880537e+04 1.33265615e+04 1.29204434e+04 1.29490684e+04 1.26158682e+04 1.27717764e+04 1.35372656e+04 1.34144688e+04 1.31393154e+04 1.28883037e+04 1.26964414e+04 1.33979756e+04 1.36897695e+04 1.33044521e+04 1.29461963e+04 1.29238145e+04 1.32408457e+04 1.32273877e+04 1.36879697e+04 1.38224473e+04 1.33405225e+04 1.32006416e+04 1.32275400e+04 1.35260166e+04 1.35753428e+04 1.34058008e+04 1.33576494e+04 1.34045215e+04 1.33568965e+04 1.30323770e+04 1.32275020e+04 1.39262451e+04 1.38570791e+04 1.35379043e+04 1.31872695e+04 1.31454941e+04 1.39140537e+04 1.39537607e+04 1.35794531e+04 1.32618740e+04 1.32280713e+04 1.36636436e+04 1.35850449e+04 1.35931836e+04 1.33007842e+04 1.35883477e+04 1.44171963e+04 1.40646631e+04 1.36621885e+04 1.36780674e+04 1.37726699e+04 1.36742871e+04 1.36270449e+04 1.35758750e+04 1.35505732e+04 1.36159893e+04 1.32822363e+04 1.35133477e+04 1.43240293e+04 1.37760137e+04 1.33265166e+04 1.36825820e+04 1.36565654e+04 1.41239121e+04 1.39456973e+04 1.33902139e+04 1.39286455e+04 1.40463662e+04 1.37480938e+04 1.36380615e+04 1.36621328e+04 1.37486445e+04 1.37108350e+04 1.35247627e+04 1.31806797e+04 1.36747314e+04 1.44194355e+04 1.40857100e+04 1.37532168e+04 1.33763369e+04 1.33054199e+04 1.40706367e+04 1.41592070e+04 1.37802559e+04 1.33723965e+04 1.32836289e+04 1.36938398e+04 1.37043779e+04 1.39918301e+04 1.38082188e+04 1.34111240e+04 1.35602500e+04 1.35168799e+04 1.39429893e+04 1.39161699e+04 1.34960918e+04 1.36191152e+04 1.36180645e+04 1.34935615e+04 1.31323301e+04 1.34015488e+04 1.41885576e+04 1.39327344e+04 1.35390898e+04 1.31862812e+04 1.30698389e+04 1.38211865e+04 1.39064844e+04 1.34942891e+04 1.31299043e+04 1.30539570e+04 1.35040361e+04 1.34682803e+04 1.37195830e+04 1.36569199e+04 1.32574629e+04 1.31405293e+04 1.30759453e+04 1.36560332e+04 1.36365273e+04 1.32346846e+04 1.31267090e+04 1.30747617e+04 1.35166670e+04 1.35129658e+04 1.28600449e+04 1.28584443e+04 1.35250732e+04 1.35017393e+04 1.28555664e+04 1.27609961e+04 1.33770498e+04 1.34867197e+04 1.30424629e+04 1.26877441e+04 1.26941182e+04 1.33584424e+04 1.31592334e+04 1.27661982e+04 1.30411143e+04 1.29981152e+04 1.27639219e+04 1.26851855e+04 1.27131377e+04 1.24194727e+04 1.27265977e+04 1.34106826e+04 1.30020811e+04 1.27837588e+04 1.27785107e+04 1.26913320e+04 1.26658789e+04 1.25740791e+04 1.25565713e+04 1.23045762e+04 1.20803242e+04 1.23482676e+04 1.26026270e+04 1.29080811e+04 1.24407275e+04 1.19682656e+04 1.22970645e+04 1.24247480e+04 1.27859854e+04 1.26142949e+04 1.22257090e+04 1.19657559e+04 1.18089678e+04 1.21510137e+04 1.21457852e+04 1.23271113e+04 1.24039678e+04 1.20500664e+04 1.17653926e+04 1.14487881e+04 1.18239258e+04 1.24542852e+04 1.22685205e+04 1.19091504e+04 1.15433018e+04 1.13383379e+04 1.18566045e+04 1.21438242e+04 1.18218389e+04 1.13660107e+04 1.12990322e+04 1.15099512e+04 1.15334463e+04 1.18276904e+04 1.17870361e+04 1.14316709e+04 1.12457246e+04 1.11351055e+04 1.14978340e+04 1.15094482e+04 1.09589570e+04 1.08961621e+04 1.14681494e+04 1.13260693e+04 1.07015771e+04 1.08528457e+04 1.13892178e+04 1.12664238e+04 1.09676230e+04 1.06215049e+04 1.05861982e+04 1.11491240e+04 1.11185605e+04 1.07752451e+04 1.04674053e+04 1.03093398e+04 1.05173789e+04 1.05865801e+04 1.06124326e+04 1.02219600e+04 1.04313516e+04 1.09210332e+04 1.05880283e+04 1.04298213e+04 1.04461885e+04 1.02889688e+04 1.02269658e+04 1.01735127e+04 1.01693379e+04 1.00463232e+04 9.85901562e+03 9.64277637e+03 9.89416699e+03 1.02889062e+04 9.86192871e+03 9.48841797e+03 9.76756543e+03 9.80317285e+03 1.00497373e+04 9.91466699e+03 9.53169629e+03 9.70593262e+03 9.64512207e+03 9.28930664e+03 9.24940918e+03 9.59775781e+03 9.52417480e+03 9.27539062e+03 9.04440723e+03 8.72918457e+03 9.09527344e+03 9.68348828e+03 9.34765039e+03 8.98518164e+03 8.76986816e+03 8.69125195e+03 9.11998535e+03 9.19046777e+03 8.91459668e+03 8.59295605e+03 8.51027930e+03 8.60851855e+03 8.58008594e+03 8.80102637e+03 8.74812012e+03 8.41989551e+03 8.36895898e+03 8.33013867e+03 8.47508496e+03 8.47212598e+03 8.25548633e+03 8.14850195e+03 8.06156299e+03 8.09453613e+03 7.85054297e+03 7.87468555e+03 8.22497168e+03 8.06585547e+03 7.93984033e+03 7.69779297e+03 7.54343311e+03 8.00982324e+03 7.91600537e+03 7.62564648e+03 7.47586865e+03 7.37467969e+03 7.42078027e+03 7.34588574e+03 7.41059180e+03 7.20086328e+03 7.30858594e+03 7.56171924e+03 7.24606982e+03 7.25455615e+03 7.29340625e+03 7.08755273e+03 6.94839697e+03 6.88762451e+03 6.88965332e+03 6.86241846e+03 6.79610742e+03 6.74953223e+03 6.77963574e+03 6.79558887e+03 6.46988330e+03 6.31582373e+03 6.47017236e+03 6.55686475e+03 6.67105615e+03 6.49443359e+03 6.23123486e+03 6.40147119e+03 6.30344482e+03 6.15007227e+03 6.17117822e+03 6.10921289e+03 6.01732764e+03 5.92149121e+03 5.94496045e+03 5.81296387e+03 5.82040576e+03 6.03087646e+03 5.91937451e+03 5.78741504e+03 5.59953076e+03 5.45610010e+03 5.72728857e+03 5.69874023e+03 5.51586865e+03 5.32156348e+03 5.19653418e+03 5.31294385e+03 5.34138428e+03 5.48619043e+03 5.27346631e+03 5.05762891e+03 5.10596826e+03 5.03442285e+03 5.13616748e+03 5.07240967e+03 4.87942285e+03 4.83438232e+03 4.80987744e+03 4.78217285e+03 4.63163379e+03 4.67373682e+03 4.87467822e+03 4.73449707e+03 4.62516699e+03 4.45084082e+03 4.33531348e+03 4.56840576e+03 4.51204102e+03 4.33390723e+03 4.21165186e+03 4.14102246e+03 4.19745703e+03 4.17346191e+03 4.26137988e+03 4.20418262e+03 4.03847461e+03 3.91921387e+03 3.85123657e+03 4.03901782e+03 3.96270117e+03 3.78502783e+03 3.78765820e+03 3.74979346e+03 3.66955249e+03 3.60731885e+03 3.67623389e+03 3.53932300e+03 3.42113477e+03 3.58422314e+03 3.57457886e+03 3.40467188e+03 3.34793555e+03 3.30926440e+03 3.29676978e+03 3.15769531e+03 3.08920630e+03 3.24180298e+03 3.20861182e+03 2.97970532e+03 2.89779077e+03 3.02309961e+03 3.10463574e+03 2.98510693e+03 2.84155981e+03 2.78913330e+03 2.85892212e+03 2.80862500e+03 2.71021655e+03 2.71484180e+03 2.60568311e+03 2.49684302e+03 2.58156909e+03 2.64583325e+03 2.58794434e+03 2.44754028e+03 2.35363965e+03 2.44062720e+03 2.46120288e+03 2.34252832e+03 2.24575903e+03 2.21676685e+03 2.20197754e+03 2.16726709e+03 2.20897827e+03 2.13710156e+03 2.03395312e+03 2.04648279e+03 2.01786316e+03 2.01462329e+03 1.93310645e+03 1.86160364e+03 1.90579395e+03 1.87674866e+03 1.81842749e+03 1.74214575e+03 1.71470740e+03 1.78512451e+03 1.69409375e+03 1.61011670e+03 1.62138196e+03 1.58906445e+03 1.56387158e+03 1.53395312e+03 1.53824487e+03 1.51816077e+03 1.44551428e+03 1.37655554e+03 1.34479395e+03 1.39056824e+03 1.34459570e+03 1.27824170e+03 1.27141602e+03 1.24887183e+03 1.22481482e+03 1.19343530e+03 1.18596533e+03 1.12939893e+03 1.07772400e+03 1.10108618e+03 1.07776611e+03 1.03838928e+03 1.01850189e+03 9.89281006e+02 9.63237244e+02 9.15543823e+02 8.83124146e+02 9.05451660e+02 9.01080200e+02 8.37576904e+02 7.90841675e+02 8.04187927e+02 8.12099915e+02 7.68878723e+02 7.19730408e+02 6.89561523e+02 6.98624695e+02 6.84992249e+02 6.48067383e+02 6.42782227e+02 6.23665161e+02 5.86528992e+02 5.66508057e+02 5.64937561e+02 5.54887024e+02 5.11293243e+02 4.84884094e+02 4.93441315e+02 4.85753387e+02 4.53859314e+02 4.21980713e+02 4.03082550e+02 4.08761169e+02 3.98628998e+02 3.68577911e+02 3.50508209e+02 3.39008057e+02 3.23344757e+02 3.07123077e+02 3.05082550e+02 2.85784576e+02 2.63554504e+02 2.63119019e+02 2.53176239e+02 2.38217972e+02 2.21502243e+02 2.06915222e+02 2.08053101e+02 2.02178864e+02 1.80043961e+02 1.67324722e+02 1.86629288e+02 2.20608734e+02 2.59690552e+02 3685234. 2.95948925e+06 4.74293427e+02 2.68015900e+02 1.47877991e+02 1.67355988e+02 1.55686295e+02 1.41644363e+02 2.56344425e+06 29125094. 5575581. 18315728. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 65945016. 65945016. 32972508. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -128530912. 3.59249425e+06 4.43184050e+06 -14803007. 2.41779984e+02 1.33748215e+02 8.73618240e+01 1.08420044e+02 6.19737129e+01 8.47536926e+01 8.82307053e+01 9.20590744e+01 1.01065392e+02 1.06448357e+02 1.13713158e+02 1.23529243e+02 1.29807785e+02 1.38054794e+02 1.47104599e+02 1.53987564e+02 1.67116974e+02 1.82458450e+02 1.92639053e+02 1.96981476e+02 2.05609711e+02 2.19170776e+02 2.26383926e+02 2.40395508e+02 2.60030579e+02 2.69879791e+02 2.83707123e+02 2.99524536e+02 3.06138184e+02 3.17390991e+02 3.34322693e+02 3.47478180e+02 3.60880096e+02 3.86215027e+02 4.09551849e+02 4.14896423e+02 4.27305878e+02 4.48198761e+02 4.66284271e+02 4.84172729e+02 4.94714966e+02 5.01645569e+02 5.34657471e+02 5.66934204e+02 5.68106140e+02 5.83895996e+02 6.11135315e+02 6.19611755e+02 6.42409180e+02 6.79830566e+02 6.93082947e+02 7.06089478e+02 7.38977295e+02 7.79234863e+02 7.81209717e+02 777. 7.99861084e+02 8.29139771e+02 8.78541077e+02 9.14405457e+02 9.13677002e+02 9.29594299e+02 9.53975647e+02 9.77200317e+02 1.00217792e+03 1.02342633e+03 1.04071021e+03 1.08328711e+03 1.14064539e+03 1.14528381e+03 1.14899548e+03 1.19682007e+03 1.22308313e+03 1.24070581e+03 1.27727551e+03 1.30765698e+03 1.32523645e+03 1.34193652e+03 1.39627295e+03 1.41936584e+03 1.44594885e+03 1.47830017e+03 1.46962292e+03 1.52846558e+03 1.59997388e+03 1.59406323e+03 1.61193774e+03 1.65840906e+03 1.68034961e+03 1.71573438e+03 1.73951953e+03 1.74704260e+03 1.81773340e+03 1.90236328e+03 1.90223560e+03 1.87842834e+03 1.91851782e+03 2.00351770e+03 2.03095007e+03 2.03744849e+03 2.06483130e+03 2.08289868e+03 2.16981982e+03 2.26069141e+03 2.21840186e+03 2.20419604e+03 2.24245264e+03 2.29832495e+03 2.37206445e+03 2.43144507e+03 2.43198584e+03 2.45971875e+03 2.57096655e+03 2.60357471e+03 2.57338452e+03 2.55947803e+03 2.59922852e+03 2.69642480e+03 2.77375977e+03 2.81603394e+03 2.81149170e+03 2.85435864e+03 2.91285547e+03 2.88906714e+03 2.91347363e+03 2.98281836e+03 3.01709839e+03 3.11048926e+03 3.19548779e+03 3.12735498e+03 3.14881763e+03 3.27893384e+03 3.30100439e+03 3.25792065e+03 3.34384033e+03 3.47735254e+03 3.50189062e+03 3.51030396e+03 3.53495752e+03 3.55310107e+03 3.59706665e+03 3.59823413e+03 3.66902954e+03 3.74838281e+03 3.78459448e+03 3.84173633e+03 3.90329370e+03 3.94095020e+03 3.84714429e+03 3.94611890e+03 4.08899512e+03 4.08371851e+03 4.17411328e+03 4.28607959e+03 4.28262305e+03 4.22116650e+03 4.27353613e+03 4.28705127e+03 4.30623877e+03 4.43046924e+03 4.53431592e+03 4.54703467e+03 4.56272656e+03 4.59558203e+03 4.61178076e+03 4.66159424e+03 4.69638037e+03 4.73966895e+03 4.84807227e+03 4.95104785e+03 4.92849121e+03 4.95078467e+03 5.01540283e+03 5.08965332e+03 5.12123486e+03 5.14569092e+03 5.19414453e+03 5.29047510e+03 5.31783643e+03 5.34722607e+03 5.37515137e+03 5.47595752e+03 5.58297070e+03 5.41989844e+03 5.47824121e+03 5.71468555e+03 5.67599756e+03 5.74772021e+03 5.81480762e+03 5.75279199e+03 5.79059619e+03 5.88482910e+03 5.87781299e+03 5.91623730e+03 6.05004248e+03 6.20558838e+03 6.30356934e+03 6.26517627e+03 6.25690723e+03 6.29298877e+03 6.26301758e+03 6.30474805e+03 6.37564062e+03 6.53066211e+03 6.72257129e+03 6.56829639e+03 6.50420117e+03 6.70749902e+03 6.62017969e+03 6.75638965e+03 6.93934570e+03 6.82581445e+03 6.89510889e+03 6.97205908e+03 7.07387158e+03 7.09900781e+03 7.06130762e+03 7.06122510e+03 7.07975391e+03 7.20734766e+03 7.34118555e+03 7.40377686e+03 7.43283643e+03 7.49164062e+03 7.55163721e+03 7.55208057e+03 7.65765039e+03 7.72598291e+03 7.63607422e+03 7.59903516e+03 7.74017725e+03 7.84822461e+03 7.91302930e+03 7.90961230e+03 7.94794043e+03 8.01424072e+03 8.02890332e+03 8.15052490e+03 8.20841113e+03 8.35514453e+03 8.36338379e+03 8.11862646e+03 8.30144238e+03 8.37357227e+03 8.41361621e+03 8.57540527e+03 8.44392578e+03 8.41691113e+03 8.77046094e+03 8.82975195e+03 8.53823828e+03 8.56739941e+03 8.88655957e+03 8.96858105e+03 8.81760547e+03 8.95674512e+03 9.16389746e+03 8.95951953e+03 8.99932617e+03 9.12391504e+03 9.02262598e+03 9.20210352e+03 9.37807031e+03 9.18281250e+03 9.39347754e+03 9.59830371e+03 9.51280957e+03 9.39362109e+03 9.29854004e+03 9.59172656e+03 9.79878711e+03 9.59409961e+03 9.56197656e+03 9.76312891e+03 9.81828711e+03 9.78559180e+03 9.84640430e+03 9.94856445e+03 9.97700586e+03 9.93560059e+03 1.00782920e+04 1.02756553e+04 1.01258223e+04 1.01133750e+04 1.02626152e+04 1.00572764e+04 1.03740020e+04 1.05443613e+04 1.02229072e+04 1.04589619e+04 1.04910283e+04 1.03590576e+04 1.05949834e+04 1.05928115e+04 1.06605420e+04 1.08921826e+04 1.07232119e+04 1.07083984e+04 1.06967920e+04 1.06570654e+04 1.07760264e+04 1.08541152e+04 1.10200049e+04 1.11387686e+04 1.10910176e+04 1.11238672e+04 1.12745430e+04 1.11893916e+04 1.10366982e+04 1.10972344e+04 1.13664463e+04 1.15291777e+04 1.11811689e+04 1.10683027e+04 1.14047021e+04 1.16324277e+04 1.14764766e+04 1.14117305e+04 1.14985635e+04 1.15558965e+04 1.17916309e+04 1.17430322e+04 1.16104590e+04 1.14414668e+04 1.15680635e+04 1.18061104e+04 1.17635068e+04 1.19173320e+04 1.20567002e+04 1.19338701e+04 1.19673389e+04 1.22468506e+04 1.21153516e+04 1.19408232e+04 1.21157451e+04 1.23137578e+04 1.21877959e+04 1.18891289e+04 1.18836230e+04 1.22023799e+04 1.24285566e+04 1.23636514e+04 1.22450977e+04 1.22695586e+04 1.25325859e+04 1.25221357e+04 1.21748779e+04 1.22715898e+04 1.24586113e+04 1.26878623e+04 1.25740098e+04 1.22476406e+04 1.24597861e+04 1.26257471e+04 1.27794824e+04 1.29542861e+04 1.28780566e+04 1.25912207e+04 1.23659316e+04 1.27238262e+04 1.31308848e+04 1.28852383e+04 1.26565137e+04 1.26317422e+04 1.28378086e+04 1.31431016e+04 1.28772480e+04 1.28024834e+04 1.29705654e+04 1.32060322e+04 1.32888223e+04 1.27796748e+04 1.29810020e+04 1.31681641e+04 1.29620146e+04 1.31722979e+04 1.30897490e+04 1.30253877e+04 1.30812090e+04 1.30804609e+04 1.32213672e+04 1.34158428e+04 1.34220156e+04 1.31152549e+04 1.32273535e+04 1.34517500e+04 1.33783291e+04 1.32740596e+04 1.29725225e+04 1.31971367e+04 1.37010264e+04 1.35377002e+04 1.33234502e+04 1.31087480e+04 1.32817002e+04 1.37542725e+04 1.35216367e+04 1.34013584e+04 1.36260605e+04 1.35348359e+04 1.32605996e+04 1.34470527e+04 1.36350186e+04 1.34357344e+04 1.35812061e+04 1.35084805e+04 1.32091094e+04 1.35821729e+04 1.37372617e+04 1.36147549e+04 1.37966611e+04 1.37278369e+04 1.36857129e+04 1.35238750e+04 1.34456406e+04 1.37360557e+04 1.37591807e+04 1.36171240e+04 1.35679102e+04 1.37412666e+04 1.35976514e+04 1.35166006e+04 1.39212012e+04 1.37894814e+04 1.35638750e+04 1.36677529e+04 1.36917568e+04 1.36804209e+04 1.38253789e+04 1.38010059e+04 1.34879062e+04 1.35838262e+04 1.38021348e+04 1.36956445e+04 1.36936143e+04 1.38976621e+04 1.38363604e+04 1.36839824e+04 1.34543047e+04 1.34610430e+04 1.37130625e+04 1.38506465e+04 1.40986064e+04 1.37193916e+04 1.33320537e+04 1.36551211e+04 1.38480703e+04 1.37846680e+04 1.36241016e+04 1.35725391e+04 1.37872168e+04 1.38387090e+04 1.36555430e+04 1.35255225e+04 1.35429678e+04 1.36877275e+04 1.37046738e+04 1.36452432e+04 1.36381709e+04 1.34658271e+04 1.36015342e+04 1.37783174e+04 1.36545254e+04 1.36439492e+04 1.36174619e+04 1.35841338e+04 1.36288926e+04 1.36231943e+04 1.33248926e+04 1.33196914e+04 1.35751289e+04 1.36572402e+04 1.37130322e+04 1.34724326e+04 1.34204639e+04 1.33204688e+04 1.33598262e+04 1.36770947e+04 1.33329580e+04 1.32946221e+04 1.36219844e+04 1.32399307e+04 1.31539375e+04 1.35182852e+04 1.34838145e+04 1.33823428e+04 1.35235166e+04 1.31960508e+04 1.28269814e+04 1.32653115e+04 1.34771357e+04 1.31848027e+04 1.34287725e+04 1.34222900e+04 1.28984082e+04 1.29560293e+04 1.30379043e+04 1.29781309e+04 1.32420996e+04 1.32018770e+04 1.30423506e+04 1.30627275e+04 1.30300938e+04 1.31089795e+04 1.29472734e+04 1.27908994e+04 1.29215996e+04 1.29453760e+04 1.27596426e+04 1.27981729e+04 1.29179004e+04 1.27030742e+04 1.28281699e+04 1.28568125e+04 1.27672129e+04 1.28206084e+04 1.24332871e+04 1.25196689e+04 1.29100850e+04 1.27149092e+04 1.25340781e+04 1.26075986e+04 1.25847041e+04 1.25565566e+04 1.25487637e+04 1.20867275e+04 1.20490635e+04 1.24903955e+04 1.26208809e+04 1.25293047e+04 1.21624141e+04 1.20714053e+04 1.23908809e+04 1.22619736e+04 1.20824199e+04 1.21404727e+04 1.20676055e+04 1.20655283e+04 1.21067812e+04 1.21937227e+04 1.20109854e+04 1.17791904e+04 1.21131904e+04 1.19402471e+04 1.17262178e+04 1.17563857e+04 1.15961670e+04 1.17611963e+04 1.20086709e+04 1.18817822e+04 1.15137197e+04 1.14556133e+04 1.16430967e+04 1.16877461e+04 1.16277842e+04 1.14392451e+04 1.15197852e+04 1.15169717e+04 1.14176182e+04 1.14552129e+04 1.13640479e+04 1.13224014e+04 1.13581064e+04 1.09169873e+04 1.08783613e+04 1.13407559e+04 1.12239473e+04 1.10525293e+04 1.09888154e+04 1.08339492e+04 1.07721504e+04 1.10727744e+04 1.11154561e+04 1.08184043e+04 1.06761602e+04 1.05731562e+04 1.06280303e+04 1.07567324e+04 1.07330420e+04 1.07072725e+04 1.05151074e+04 1.05382598e+04 1.04543086e+04 1.02156953e+04 1.02495850e+04 1.04665625e+04 1.04525059e+04 1.02430430e+04 1.01768350e+04 1.01650518e+04 1.01267559e+04 9.96695508e+03 1.00885693e+04 1.00595469e+04 9.95445410e+03 9.89307715e+03 9.81700488e+03 1.00742705e+04 9.77230762e+03 9.65137988e+03 9.85305957e+03 9.58506641e+03 9.46581445e+03 9.61513574e+03 9.63589746e+03 9.44599707e+03 9.67897461e+03 9.71898828e+03 9.44780078e+03 1.00715479e+04 9.68399121e+03 1.12196982e+04 1.19834941e+04 1.36545684e+04 1.34162568e+04 1.36132002e+04 1.40292773e+04 1.49926436e+04 1.30814199e+04 2.40733672e+04 4.12665625e+04 -6.59038350e+06 60736984. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -30456054. 2369677. -13130286. 3.41636225e+06 1.93701309e+04 1.44628223e+04 9.63803320e+03 7.99207617e+03 7.03618750e+03 6.54100781e+03 6.51175537e+03 6.54740967e+03 6.31446094e+03 6.21637939e+03 6.23223975e+03 6.13725684e+03 6.19635596e+03 6.14622900e+03 5.96681006e+03 5.85953662e+03 5.95393848e+03 5.94606250e+03 5.86100586e+03 5.82924463e+03 5.60524609e+03 5.55993359e+03 5.78903613e+03 5.61481982e+03 5.42390625e+03 5.31669287e+03 5.39071973e+03 5.56218994e+03 5.56365918e+03 5.32916943e+03 5.07693457e+03 5070. 5.17691504e+03 5.15496387e+03 5.09468945e+03 4.99759619e+03 4.97987158e+03 4.97277783e+03 4.94052539e+03 4.88883643e+03 4.67744922e+03 4.70010449e+03 4.95938818e+03 4.68103516e+03 4.50920557e+03 4.50874805e+03 4.43965039e+03 4.59082666e+03 4.55460352e+03 4.34941650e+03 4.25940967e+03 4.32975586e+03 4.38688916e+03 4.23336377e+03 4.14787109e+03 4.02812793e+03 4.07839233e+03 4.14715527e+03 3.97615747e+03 3.95367456e+03 3.87717090e+03 3.80591724e+03 3.88195728e+03 3.85428540e+03 3.74424683e+03 3.64687549e+03 3.67402686e+03 3.65983545e+03 3.58996509e+03 3.57359155e+03 3.40204541e+03 3.37619336e+03 3.52166699e+03 3.38080249e+03 3.20991040e+03 3.15167920e+03 3.25247705e+03 3.33101196e+03 3.19181226e+03 3.12463672e+03 3.04137183e+03 2.94210791e+03 2.98082959e+03 3.02246680e+03 2.92161230e+03 2.81455078e+03 2.85272412e+03 2.81451001e+03 2.75632397e+03 2.79295996e+03 2.65443457e+03 2.60328711e+03 2.69175903e+03 2.59896606e+03 2.50588599e+03 2.45716602e+03 2.41565576e+03 2.46795361e+03 2.44658911e+03 2.33057422e+03 2.27000659e+03 2.29471484e+03 2.27852344e+03 2.21036816e+03 2.19663550e+03 2.13600024e+03 2.08015063e+03 2.11230566e+03 2.06259863e+03 1.97248157e+03 1.92365649e+03 1.92172241e+03 1.95070361e+03 1.92540771e+03 1.85433081e+03 1.76056824e+03 1.71589185e+03 1.77518811e+03 1.74616101e+03 1.66701440e+03 1.61405347e+03 1.60753638e+03 1.61279700e+03 1.55368481e+03 1.51690332e+03 1.46621960e+03 1.46224768e+03 1.48193420e+03 1.41673816e+03 1.37982544e+03 1.35424243e+03 1.30619556e+03 1.30191248e+03 1.27730383e+03 1.23457983e+03 1.19640149e+03 1.17853943e+03 1.18337854e+03 1.15194141e+03 1.11561548e+03 1.06596973e+03 1.03616492e+03 1.05055127e+03 1.03320471e+03 9.90304993e+02 9.38416687e+02 9.06162720e+02 9.15400452e+02 9.08503296e+02 8.71776733e+02 8.27353760e+02 8.04406616e+02 7.90790222e+02 7.79391235e+02 7.70354797e+02 7.28893616e+02 7.01654480e+02 6.96296021e+02 6.71629333e+02 6.44657776e+02 6.21911926e+02 6.11897705e+02 5.96159729e+02 5.65800293e+02 5.44077332e+02 5.22350708e+02 5.13754822e+02 5.14482666e+02 4.87064575e+02 4.51919037e+02 4.32980499e+02 4.25518158e+02 4.21225800e+02 4.09198456e+02 3.92920654e+02 3.61754883e+02 3.35437347e+02 3.33527924e+02 3.31437256e+02 3.15906952e+02 2.90595612e+02 2.74938599e+02 2.68998444e+02 2.58876221e+02 2.48982056e+02 2.33431030e+02 2.20601929e+02 2.12169937e+02 1.99211304e+02 1.86666840e+02 1.75172592e+02 1.65331482e+02 1.59058746e+02 1.48039246e+02 1.36760239e+02 1.26969986e+02 1.19730011e+02 1.13618469e+02 1.04892464e+02 9.74411316e+01 8.98097153e+01 8.47011337e+01 7.92938690e+01 7.12923355e+01 6.47193985e+01 5.87486343e+01 5.38254471e+01 5.03004379e+01 4.56538811e+01 4.11142654e+01 3.66030655e+01 3.30736122e+01 3.08491116e+01 2.80914268e+01 2.50458832e+01 2.27845783e+01 2.10508022e+01 1.94936771e+01 1.82207756e+01 1.73294315e+01 1.68563519e+01 1.67450523e+01 1.69481106e+01 1.74675102e+01 1.82185841e+01 1.92070827e+01 2.08666725e+01 2.29732094e+01 2.51979713e+01 2.76482162e+01 3.01990547e+01 3.38483582e+01 3.73675728e+01 4.00145302e+01 4.38900375e+01 4.90050850e+01 5.54146385e+01 6.22425423e+01 6.65947800e+01 6.96468964e+01 7.42055054e+01 8.21034698e+01 9.28118820e+01 1.02895905e+02 1.07800880e+02 1.10257202e+02 1.18049904e+02 1.33623535e+02 1.42140976e+02 1.44712418e+02 1.53638672e+02 1.65034241e+02 1.75453262e+02 1.91470520e+02 1.99772385e+02 2.03368546e+02 2.19522598e+02 2.28781570e+02 2.44998627e+02 2.62532990e+02 2.63687866e+02 2.82471497e+02 3.03110718e+02 3.09998627e+02 3.23249512e+02 3.38655334e+02 3.55215363e+02 3.70475433e+02 3.83393463e+02 3.89487305e+02 4.04208466e+02 4.39945343e+02 4.70222107e+02 4.76674896e+02 4.72065582e+02 4.78117249e+02 5.04715240e+02 5.45214478e+02 5.79924133e+02 5.86314087e+02 5.75857971e+02 5.97197205e+02 6.34800110e+02 6.52362000e+02 6.65913574e+02 6.87016785e+02 7.10628723e+02 7.30101013e+02 7.74312927e+02 7.79840271e+02 7.81084045e+02 8.20905457e+02 8.22787048e+02 8.65632568e+02 9.09505249e+02 9.08698059e+02 9.63904968e+02 9.64944702e+02 9.48635681e+02 1.00828198e+03 1.01097510e+03 1.05057300e+03 1.15043823e+03 1.12187524e+03 1.07709863e+03 1.12333386e+03 1.21171008e+03 1.28913818e+03 1.28404382e+03 1.24542188e+03 1.24578503e+03 1.29102063e+03 1.37292712e+03 1.45253516e+03 1.45044067e+03 1.40594153e+03 1.43311804e+03 1.50512781e+03 1.53915894e+03 1.55305823e+03 1.57759521e+03 1.61661780e+03 1.64852783e+03 1.73361841e+03 1.76868140e+03 1.68976123e+03 1.71919861e+03 1.81613464e+03 1.84753333e+03 1.87856616e+03 1.91184351e+03 1.99381836e+03 1.98257678e+03 1.94984741e+03 2.03724475e+03 2.01411047e+03 2.10737061e+03 2.27258252e+03 2.17881152e+03 2.09400464e+03 2.19121777e+03 2.33644922e+03 2.44524072e+03 2.45135205e+03 2.34318408e+03 2.30019434e+03 2.39924731e+03 2.56064404e+03 2.67443750e+03 2.64057275e+03 2.53915747e+03 2.58017261e+03 2.69860107e+03 2.75235425e+03 2.83377075e+03 2.88549365e+03 2.77849341e+03 2.79917212e+03 2.98168921e+03 3.03979175e+03 2.94056445e+03 2.95860962e+03 3.07633643e+03 3.10668335e+03 3.22955737e+03 3.30622632e+03 3.21259912e+03 3.23692749e+03 3.27148242e+03 3.30884082e+03 3.40964600e+03 3.43240845e+03 3.56402588e+03 3.66039307e+03 3.57761279e+03 3.50954004e+03 3.48905200e+03 3.69382422e+03 3.94132544e+03 3.88011328e+03 3.74490356e+03 3.67163940e+03 3.85818677e+03 4.12845801e+03 4.05329541e+03 3.86907153e+03 3.95501392e+03 4.12813135e+03 4.28945947e+03 4.48074170e+03 4.39293018e+03 4.17524561e+03 4.19467529e+03 4.37497266e+03 4.45969531e+03 4.53830566e+03 4.55565234e+03 4.58598828e+03 4.58425098e+03 4.73374463e+03 4.76177832e+03 4.66445264e+03 4.71499072e+03 4.72376465e+03 4.96146240e+03 5.08104688e+03 4.95811426e+03 5.09625684e+03 5.12284668e+03 5.12233887e+03 5.07613916e+03 5.03023828e+03 5.27256201e+03 5.57720117e+03 5.50185107e+03 5.30019971e+03 5.26740918e+03 5.56409180e+03 5.75406836e+03 5.70611230e+03 5.67386523e+03 5.52412549e+03 5.57808203e+03 5.84284131e+03 5.90670947e+03 5.78158838e+03 5.73456396e+03 5.75499512e+03 6.14782520e+03 6.39763281e+03 6.10058643e+03 5.98655713e+03 6.23372461e+03 6.28479492e+03 6.48825732e+03 6.49319238e+03 6.18361035e+03 6.28775391e+03 6.53895459e+03 6.56424316e+03 6.68063525e+03 6.82325244e+03 6.84228271e+03 6.61568555e+03 6.44866553e+03 6.78526660e+03 8.98545020e+03 9.73045605e+03 1.10891777e+04 1.08509688e+04 1.03840645e+04 1.04049883e+04 1.08692148e+04 1.18640039e+04 1.15672197e+04 1.15353457e+04 1.14662207e+04 1.78084336e+04 2.62268027e+04 -6759607. -70004648. 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. 0. 0. 0. 0. 0. 0. 60725064. 3.45647175e+06 -1.26415812e+06 -1.09636838e+06 -22893362. 3.04674453e+04 2.53525273e+04 1.50505361e+04 1.06904561e+04 1.02186416e+04 9.70268848e+03 9.43098340e+03 9.97786328e+03 1.00246953e+04 9.80820020e+03 9.89191016e+03 9.90415625e+03 9.92224609e+03 9.99052246e+03 9.99031348e+03 9.97193457e+03 1.00903984e+04 1.00701318e+04 1.02144229e+04 1.02922705e+04 1.00027744e+04 1.00688486e+04 1.06138057e+04 1.06497939e+04 1.04434922e+04 1.04207217e+04 1.04804287e+04 1.05400244e+04 1.06577520e+04 1.06602559e+04 1.06126162e+04 1.06485098e+04 1.05793115e+04 1.06010430e+04 1.09953672e+04 1.10601826e+04 1.08949990e+04 1.09300430e+04 1.10109473e+04 1.10748779e+04 1.10219199e+04 1.10464941e+04 1.11294619e+04 1.10171816e+04 1.10165801e+04 1.10864229e+04 1.10977949e+04 1.16537568e+04 1.17456006e+04 1.13979932e+04 1.10686484e+04 1.10757715e+04 1.18187900e+04 1.19209824e+04 1.15287012e+04 1.13073506e+04 1.13609697e+04 1.16246553e+04 1.16086367e+04 1.20801328e+04 1.20946982e+04 1.13925459e+04 1.12374316e+04 1.18647725e+04 1.25849189e+04 1.22632529e+04 1.19504961e+04 1.19800186e+04 1.19075840e+04 1.20485527e+04 1.21777002e+04 1.20402686e+04 1.19867256e+04 1.20778730e+04 1.21132402e+04 1.21830791e+04 1.21847207e+04 1.25556611e+04 1.25968086e+04 1.22918271e+04 1.22232070e+04 1.22811875e+04 1.26917588e+04 1.27416338e+04 1.25035879e+04 1.25692354e+04 1.22617295e+04 1.19966318e+04 1.26580039e+04 1.28717773e+04 1.22111680e+04 1.23175020e+04 1.30583418e+04 1.34604219e+04 1.30951689e+04 1.27089883e+04 1.27655576e+04 1.28545811e+04 1.27076328e+04 1.26847822e+04 1.28413633e+04 1.27902402e+04 1.32578760e+04 1.32418027e+04 1.28840781e+04 1.28876699e+04 1.26045068e+04 1.29384619e+04 1.36616309e+04 1.34430674e+04 1.31304561e+04 1.28160898e+04 1.26649893e+04 1.34346943e+04 1.37095527e+04 1.32775000e+04 1.29087490e+04 1.28898193e+04 1.32082617e+04 1.32181934e+04 1.36724893e+04 1.38121387e+04 1.33090049e+04 1.30545508e+04 1.30945264e+04 1.36359766e+04 1.36777051e+04 1.33957305e+04 1.33306787e+04 1.33161904e+04 1.32772588e+04 1.29687041e+04 1.33321484e+04 1.41025156e+04 1.38802822e+04 1.35168779e+04 1.31886504e+04 1.31297324e+04 1.39150449e+04 1.39892529e+04 1.35809189e+04 1.32110459e+04 1.31812490e+04 1.36446846e+04 1.36034609e+04 1.35924326e+04 1.32519658e+04 1.35589121e+04 1.42948301e+04 1.39154502e+04 1.37545127e+04 1.38474424e+04 1.37679238e+04 1.34988643e+04 1.35235830e+04 1.35770938e+04 1.34932217e+04 1.35751182e+04 1.32821602e+04 1.36356270e+04 1.44320918e+04 1.37789150e+04 1.33293008e+04 1.36909473e+04 1.36716221e+04 1.40520596e+04 1.39207627e+04 1.34357422e+04 1.39001240e+04 1.40352471e+04 1.37858711e+04 1.37913457e+04 1.37844199e+04 1.35851016e+04 1.35570674e+04 1.35084805e+04 1.31336875e+04 1.36497998e+04 1.44905488e+04 1.41355146e+04 1.36068496e+04 1.32100352e+04 1.34037412e+04 1.42171309e+04 1.41227881e+04 1.37301748e+04 1.33750098e+04 1.32736523e+04 1.36867051e+04 1.36783018e+04 1.39524336e+04 1.37843154e+04 1.33845117e+04 1.35724961e+04 1.35292480e+04 1.39495049e+04 1.40093174e+04 1.36091367e+04 1.35012471e+04 1.34773145e+04 1.35021201e+04 1.31567207e+04 1.33953828e+04 1.41209316e+04 1.39247285e+04 1.35317432e+04 1.31636729e+04 1.30939678e+04 1.38360615e+04 1.38577383e+04 1.34656777e+04 1.31645371e+04 1.30720312e+04 1.34810869e+04 1.34652822e+04 1.37118750e+04 1.36531621e+04 1.32473398e+04 1.31057061e+04 1.30852705e+04 1.36630518e+04 1.36872109e+04 1.32873125e+04 1.30730537e+04 1.30199600e+04 1.34872109e+04 1.35178066e+04 1.28427930e+04 1.28415361e+04 1.36094863e+04 1.34965684e+04 1.27967920e+04 1.27317246e+04 1.33799551e+04 1.34858154e+04 1.29913467e+04 1.26309961e+04 1.26726689e+04 1.33791611e+04 1.32572051e+04 1.28731035e+04 1.29945947e+04 1.28708994e+04 1.25485068e+04 1.25532393e+04 1.28624395e+04 1.25425049e+04 1.27082461e+04 1.32068047e+04 1.28881973e+04 1.29449404e+04 1.28900225e+04 1.26431953e+04 1.26529570e+04 1.25717539e+04 12545. 1.22820820e+04 1.21029277e+04 1.23233359e+04 1.25533115e+04 1.28879648e+04 1.24013662e+04 1.20442090e+04 1.23810654e+04 1.23334287e+04 1.26528516e+04 1.25803096e+04 1.22011670e+04 1.19499766e+04 1.18395010e+04 1.21557383e+04 1.21215938e+04 1.23260557e+04 1.23046621e+04 1.19609072e+04 1.18637002e+04 1.15410596e+04 1.18359404e+04 1.24286250e+04 1.22200566e+04 1.18555107e+04 1.15353164e+04 1.14609990e+04 1.19548613e+04 1.20151602e+04 1.17196836e+04 1.13805283e+04 1.12865361e+04 1.15026113e+04 1.15113789e+04 1.17825957e+04 1.16764941e+04 1.13434463e+04 1.13112793e+04 1.12223896e+04 1.14887656e+04 1.15147500e+04 1.09305801e+04 1.08835117e+04 1.14930928e+04 1.12249375e+04 1.05945381e+04 1.09052939e+04 1.14517656e+04 1.13138506e+04 1.09804092e+04 1.05925791e+04 1.05952705e+04 1.11625283e+04 1.10774766e+04 1.07240049e+04 1.04649697e+04 1.03354736e+04 1.05416270e+04 1.05939082e+04 1.05789219e+04 1.02682119e+04 1.04164688e+04 1.08970068e+04 1.05949053e+04 1.03961426e+04 1.03143467e+04 1.01790693e+04 1.01970723e+04 1.01563379e+04 1.01704766e+04 1.00694824e+04 9.99104102e+03 9.72342871e+03 9.78540918e+03 1.02848906e+04 9.82598828e+03 9.44687988e+03 9.64780273e+03 9.91413574e+03 1.01224287e+04 9.90991406e+03 9.62020508e+03 9.63889453e+03 9.51987012e+03 9.29603516e+03 9.22604883e+03 9.49476270e+03 9.48099902e+03 9.20049316e+03 9.10376953e+03 8.83743848e+03 9.08161719e+03 9.59496387e+03 9.26394629e+03 9.01226465e+03 8.75260547e+03 8.69386816e+03 9.12290625e+03 9.20446289e+03 8.86791211e+03 8.59838184e+03 8.50751367e+03 8.58782324e+03 8.57680664e+03 8.80006055e+03 8.68674707e+03 8.38724902e+03 8.36074805e+03 8.31536621e+03 8.45664062e+03 8.41637598e+03 8.14495166e+03 8.24897363e+03 8.20821680e+03 8.00354541e+03 7.73571729e+03 7.93207715e+03 8.27984082e+03 8.11016162e+03 7.88321973e+03 7629. 7.58474219e+03 7.99463281e+03 7.94740283e+03 7.60965869e+03 7.43070703e+03 7.33035449e+03 7.39904590e+03 7.34355127e+03 7.39397705e+03 7.21922510e+03 7.30102100e+03 7.53922754e+03 7.23220654e+03 7.25437061e+03 7.25787256e+03 7.03996191e+03 7.05356006e+03 6.97151367e+03 6.74002539e+03 6.71222852e+03 6.85968213e+03 6.85903076e+03 6.80881201e+03 6.74143311e+03 6.47051514e+03 6.37199561e+03 6.53776074e+03 6.51391260e+03 6.62701514e+03 6.49241504e+03 6.20749951e+03 6.29757910e+03 6.35265967e+03 6.25304834e+03 6.09858643e+03 6.00616748e+03 6.07163428e+03 6.01475049e+03 5.91192871e+03 5.78066650e+03 5.81364209e+03 6.04338379e+03 5.95612256e+03 5.71895117e+03 5.50585400e+03 5.50970654e+03 5.72365527e+03 5.67383936e+03 5.50780371e+03 5.32015332e+03 5.17451025e+03 5.29546338e+03 5.36264697e+03 5.49896777e+03 5.26507275e+03 4.99103760e+03 5.04175732e+03 5.05608398e+03 5.16238184e+03 5.01734863e+03 4.82702832e+03 4.91871387e+03 4.86862744e+03 4.80601221e+03 4.64382422e+03 4.62553662e+03 4.84482080e+03 4.76005273e+03 4.56564014e+03 4.39910254e+03 4.38842285e+03 4.57979248e+03 4.51126611e+03 4.35809766e+03 4.21014795e+03 4.13440381e+03 4.20881592e+03 4.16223145e+03 4.26886572e+03 4.18948682e+03 3.98926978e+03 3.87093896e+03 3.87770679e+03 4.04436987e+03 3.91544678e+03 3.77503857e+03 3.80385767e+03 3.78210620e+03 3.61978052e+03 3.52088721e+03 3.62358667e+03 3.55279150e+03 3.43469214e+03 3.56855811e+03 3.56643896e+03 3.42089282e+03 3.35885254e+03 3.30786279e+03 3.28010767e+03 3.16275732e+03 3.10214966e+03 3.20705005e+03 3.20971313e+03 3.00910547e+03 2.90737720e+03 2.99482520e+03 3.06574023e+03 3.00221094e+03 2.86779150e+03 2.75622827e+03 2.80993140e+03 2.84803271e+03 2.76822119e+03 2.69496558e+03 2.58161035e+03 2.48267871e+03 2.57863159e+03 2.66270947e+03 2.56378467e+03 2.42046069e+03 2.35717676e+03 2.44487988e+03 2.44036011e+03 2.32454395e+03 2.22665479e+03 2.17503418e+03 2.16911499e+03 2.15562402e+03 2.20174243e+03 2.16278101e+03 2.05651904e+03 2.02411572e+03 1.98843201e+03 2.00124866e+03 1.92750476e+03 1.85686841e+03 1.91165662e+03 1.88788147e+03 1.79628003e+03 1.70929932e+03 1.71378931e+03 1.78393445e+03 1.68403198e+03 1.58416357e+03 1.60048511e+03 1.60098718e+03 1.57211255e+03 1.52657947e+03 1.53442981e+03 1.51896948e+03 1.43911865e+03 1.36627124e+03 1.34146692e+03 1.38807178e+03 1.34070935e+03 1.27286731e+03 1.26507190e+03 1.24154382e+03 1.21051587e+03 1.17266113e+03 1.16609180e+03 1.12980273e+03 1.08683337e+03 1.09102600e+03 1.06548547e+03 1.04588025e+03 1.02265747e+03 9.85476013e+02 9.51671448e+02 9.00399780e+02 8.85224304e+02 9.07515320e+02 8.94558167e+02 8.29978516e+02 7.83814941e+02 7.89416199e+02 7.96297485e+02 7.67689392e+02 7.21366150e+02 6.79103638e+02 6.87223328e+02 6.84835388e+02 6.46153381e+02 6.39912476e+02 6.12935791e+02 5.70757202e+02 5.64166931e+02 5.65912781e+02 5.43068481e+02 5.01628387e+02 4.76501892e+02 4.84401031e+02 4.79292175e+02 4.47403412e+02 4.16332245e+02 3.97585510e+02 4.03627380e+02 3.88762756e+02 3.60984283e+02 3.50029022e+02 3.36410248e+02 3.19397461e+02 3.04101746e+02 3.01925140e+02 2.83270325e+02 2.60720612e+02 2.59724731e+02 2.48616699e+02 2.32600525e+02 2.16918961e+02 2.03350052e+02 2.04153854e+02 1.91549622e+02 1.63316116e+02 1.60986481e+02 1.74218170e+02 1.50740295e+02 2.45040588e+02 2.33898422e+02 2.21104767e+02 2.05337204e+02 1.89573761e+02 1.77219498e+02 1.77061661e+02 1.67848114e+02 1.57997650e+02 1.59328201e+02 1.23901451e+02 1.19166885e+02 4.67897339e+02 247711712. 0. 0. 0. 0. 0. 0. 0. 19229018. 40745600. -2.39244050e+06 1.94760483e+02 2.15743683e+02 4006584. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38727436. 5310773. 9.64823914e+01 5.78663368e+01 6.73605957e+01 8.12460175e+01 5.83339272e+01 7.65059357e+01 8.24701691e+01 8.69811859e+01 9.57387390e+01 1.04282921e+02 1.11756874e+02 1.16705482e+02 1.24881630e+02 1.37211472e+02 1.45309753e+02 1.52875336e+02 1.61635559e+02 1.70792389e+02 1.86508621e+02 1.98765640e+02 2.05797897e+02 2.16501099e+02 2.25493317e+02 2.38594009e+02 2.59388458e+02 2.72787567e+02 2.77311676e+02 2.88514709e+02 3.06955444e+02 3.22292542e+02 3.32455872e+02 3.45606079e+02 3.63080505e+02 3.79266174e+02 4.00796539e+02 4.16169098e+02 4.18277405e+02 4.39788422e+02 4.72610413e+02 4.92666412e+02 5.06049896e+02 5.02538727e+02 5.15663452e+02 5.53034058e+02 5.79515381e+02 5.92096130e+02 5.99717285e+02 6.19542114e+02 6.51140625e+02 6.78002075e+02 6.93310120e+02 6.93373535e+02 7.11255005e+02 7.72334167e+02 7.98876770e+02 7.79597595e+02 7.95654785e+02 8.39360657e+02 8.75936584e+02 9.13764954e+02 9.16176270e+02 9.07015442e+02 9.40362915e+02 9.89723206e+02 1.02236432e+03 1.03434131e+03 1.03782251e+03 1.07537097e+03 1.12131531e+03 1.14150830e+03 1.15340149e+03 1.16097571e+03 1.20501514e+03 1.25984985e+03 1.28044824e+03 1.30844092e+03 1.32244910e+03 1.32021594e+03 1.37664612e+03 1.42458630e+03 1.44675684e+03 1.47801111e+03 1.48827820e+03 1.51413928e+03 1.58348035e+03 1.60863770e+03 1.58766321e+03 1.62303259e+03 1.68864563e+03 1.73185010e+03 1.75802759e+03 1.75893481e+03 1.78660876e+03 1.84113501e+03 1.89277844e+03 1.91576001e+03 1.89962646e+03 1.95977197e+03 2.04400647e+03 2.06194092e+03 2.07933374e+03 2.07281274e+03 2.10925049e+03 2.21536084e+03 2.23279492e+03 2.21961792e+03 2.25171143e+03 2.30301880e+03 2.38080420e+03 2.40849170e+03 2.41449683e+03 2.46311597e+03 2.49961548e+03 2.56082300e+03 2.60793726e+03 2.59498877e+03 2.63470923e+03 2.68454297e+03 2.69544824e+03 2.77606177e+03 2.81915503e+03 2.85014502e+03 2.88219897e+03 2.89446338e+03 2.93770581e+03 3.00672754e+03 3.05358350e+03 3.08293896e+03 3.10137012e+03 3.11837744e+03 3.16363208e+03 3.24832812e+03 3.27225391e+03 3.27691821e+03 3.33403271e+03 3.46337549e+03 3.51011011e+03 3.45021411e+03 3.51386133e+03 3.57758325e+03 3.60787549e+03 3.62006519e+03 3.64418457e+03 3.70050781e+03 3.79969116e+03 3.89842334e+03 3.92391284e+03 3.88998047e+03 3.85409033e+03 3.96002881e+03 4.06825366e+03 4.11486035e+03 4.12763672e+03 4.12096777e+03 4.20504199e+03 4.31587354e+03 4.35927637e+03 4.28225684e+03 4.27553760e+03 4.40335840e+03 4.57950977e+03 4.58981494e+03 4.45506787e+03 4.51585107e+03 4.71041748e+03 4.75838428e+03 4.74394043e+03 4.79578027e+03 4.86726855e+03 4.87385059e+03 4.94875439e+03 4.96201807e+03 4.91662061e+03 5.08267041e+03 5.18838818e+03 5.17247119e+03 5.23393604e+03 5.26568555e+03 5.24053027e+03 5.30273877e+03 5.42846045e+03 5.51405518e+03 5.58062207e+03 5.43435156e+03 5.47025977e+03 5.78021436e+03 5.67799902e+03 5.58306689e+03 5.75301514e+03 5.85175537e+03 5.90945996e+03 5.92895068e+03 5.96163330e+03 5.92633984e+03 5.93268799e+03 6.17142334e+03 6.31312598e+03 6.07748145e+03 6.20003174e+03 6.41802051e+03 6.36918945e+03 6.40194873e+03 6.35366406e+03 6.34712402e+03 6.56561426e+03 6.66827734e+03 6.57380273e+03 6.67478174e+03 6.61308154e+03 6.74693799e+03 6.93163965e+03 6.84856396e+03 6.88394629e+03 6.96447363e+03 7.06064990e+03 7.03446875e+03 7.08937744e+03 7.13279639e+03 7.11084473e+03 7.17335742e+03 7.34906396e+03 7.35796094e+03 7.32879980e+03 7.51766650e+03 7.60197119e+03 7.59176953e+03 7.73115234e+03 7.56577441e+03 7.49050391e+03 7.73472412e+03 7.81930029e+03 7.80891797e+03 7.75079199e+03 7.72412109e+03 7.96721191e+03 8.19875586e+03 8.05498486e+03 8.02840088e+03 8.23523047e+03 8.25159375e+03 8.18462793e+03 8.16315088e+03 8.45151270e+03 8.44383203e+03 8.31587305e+03 8.59254297e+03 8.55566895e+03 8.51474219e+03 8.66602148e+03 8.62610547e+03 8.61092480e+03 8.77300391e+03 8.76101660e+03 8.77449512e+03 8.99295215e+03 9.04724902e+03 9.08709180e+03 8.93547461e+03 8.90621582e+03 9.16917090e+03 9.14643359e+03 9.26572266e+03 9.26198828e+03 9.23446680e+03 9.28231348e+03 9.39501074e+03 9.64808203e+03 9.48028418e+03 9.14421777e+03 9.58343457e+03 1.00431289e+04 9.64466406e+03 9.45661914e+03 9.64539258e+03 9.68532129e+03 9.94501172e+03 1.00050225e+04 9.80876367e+03 9.81488086e+03 1.00442227e+04 1.01101562e+04 1.02286582e+04 1.01474072e+04 1.02040645e+04 1.03749238e+04 9.99396680e+03 1.01828828e+04 1.04428066e+04 1.02725762e+04 1.05564629e+04 1.05225752e+04 1.03412002e+04 1.05844463e+04 1.05312832e+04 1.06141416e+04 1.09597949e+04 1.08274062e+04 1.06858730e+04 1.06195137e+04 1.05556104e+04 1.09218340e+04 1.11218301e+04 1.08579385e+04 1.08824326e+04 1.11603496e+04 1.11714775e+04 1.11719502e+04 1.10319893e+04 1.10616523e+04 1.11476758e+04 1.12969814e+04 1.14496953e+04 1.11642988e+04 1.11111826e+04 1.14108340e+04 1.15307646e+04 1.15245605e+04 1.15725332e+04 1.14804365e+04 1.14136104e+04 1.18543643e+04 1.20212422e+04 1.16196973e+04 1.13063896e+04 1.15549717e+04 1.18247139e+04 1.17893701e+04 1.17501240e+04 1.18865537e+04 1.19827158e+04 1.20004268e+04 1.21240254e+04 1.20047764e+04 1.19353018e+04 1.21400010e+04 1.22460645e+04 1.21100762e+04 1.19375605e+04 1.21226436e+04 1.21656260e+04 1.22493701e+04 1.24330811e+04 1.22971299e+04 1.21663730e+04 1.23464521e+04 1.26050576e+04 1.25229053e+04 1.23606338e+04 1.24222451e+04 1.24869463e+04 1.25297402e+04 1.25199756e+04 1.24129570e+04 1.24932520e+04 1.26911768e+04 1.28051973e+04 1.29149824e+04 1.27204502e+04 1.26865371e+04 1.27238428e+04 1.26881045e+04 1.27389971e+04 1.26787520e+04 1.28871172e+04 1.29779072e+04 1.28116963e+04 1.27059199e+04 1.28157822e+04 1.30538857e+04 1.32226064e+04 1.33003779e+04 1.30287461e+04 1.29769062e+04 1.30415781e+04 1.28698525e+04 1.30112988e+04 1.32043994e+04 1.31831572e+04 1.31209404e+04 1.29731943e+04 1.30279668e+04 1.32916406e+04 1.35189951e+04 1.35258984e+04 1.32298828e+04 1.30464502e+04 1.32621816e+04 1.33336377e+04 1.32032998e+04 1.34330127e+04 1.35963877e+04 1.32909785e+04 1.31604062e+04 1.32149863e+04 1.33006504e+04 1.37468799e+04 1.37922695e+04 1.33681543e+04 1.34975625e+04 1.34428857e+04 1.31521572e+04 1.35510762e+04 1.37162666e+04 1.34326934e+04 1.34291641e+04 1.33351836e+04 1.32135303e+04 1.37133379e+04 1.41089219e+04 1.36417119e+04 1.34199551e+04 1.35499238e+04 1.36429287e+04 1.36661680e+04 1.35666318e+04 1.36603203e+04 1.36288936e+04 1.35394932e+04 1.37103193e+04 1.38041689e+04 1.35329443e+04 1.36946865e+04 1.39590430e+04 1.36143770e+04 1.34062334e+04 1.35353018e+04 1.38172568e+04 1.39554365e+04 1.39459834e+04 1.35790527e+04 1.32212764e+04 1.35622432e+04 1.39561953e+04 1.40980801e+04 1.37196494e+04 1.34552168e+04 1.37198467e+04 1.37513086e+04 1.36858408e+04 1.37903330e+04 1.37076416e+04 1.35736963e+04 1.39072900e+04 1.36822188e+04 1.32268223e+04 1.36591836e+04 1.40725986e+04 1.37991094e+04 1.35217354e+04 1.34608672e+04 1.36645264e+04 1.38165977e+04 1.37443799e+04 1.37847100e+04 1.34211133e+04 1.33958545e+04 1.36958418e+04 1.36291143e+04 1.38483809e+04 1.37354316e+04 1.35364102e+04 1.35768115e+04 1.36266006e+04 1.36638623e+04 1.35599316e+04 1.37156104e+04 1.37670830e+04 1.34691973e+04 1.33184941e+04 1.33731943e+04 1.34537734e+04 1.37575371e+04 1.36932432e+04 1.33511836e+04 1.33229316e+04 1.32781543e+04 1.34816436e+04 1.36374980e+04 1.33786016e+04 1.32445879e+04 1.34988574e+04 1.34402461e+04 1.32493672e+04 1.36018193e+04 1.35321797e+04 1.31895410e+04 1.32825410e+04 1.30190840e+04 1.30343965e+04 1.35292793e+04 1.34364062e+04 1.32170664e+04 1.33130693e+04 1.31975957e+04 1.27913516e+04 1.28818008e+04 1.31979424e+04 1.31320752e+04 1.31702881e+04 1.30158906e+04 1.28730596e+04 1.30559463e+04 1.31757910e+04 1.34142480e+04 1.30809697e+04 1.25542549e+04 1.27097354e+04 1.28483311e+04 1.29655107e+04 1.30789414e+04 1.27942129e+04 1.24491152e+04 1.28069053e+04 1.29749023e+04 1.26224717e+04 1.27786514e+04 1.27445771e+04 1.24913398e+04 1.26607842e+04 1.26530469e+04 1.24057539e+04 1.27761377e+04 1.27496973e+04 1.24674678e+04 1.24198486e+04 1.20412852e+04 1.20970117e+04 1.24997773e+04 1.28306729e+04 1.25972080e+04 1.19070879e+04 1.19382891e+04 1.23715430e+04 1.22678242e+04 1.21137158e+04 1.21117197e+04 1.19917979e+04 1.20738242e+04 1.21019922e+04 1.21103604e+04 1.19867295e+04 1.19531113e+04 1.21128809e+04 1.19174326e+04 1.17054609e+04 1.17023320e+04 1.17155098e+04 1.18316279e+04 1.19728633e+04 1.17206572e+04 1.13853184e+04 1.15683857e+04 1.16796299e+04 1.18957412e+04 1.17483154e+04 1.12091836e+04 1.13469912e+04 1.14371250e+04 1.14873604e+04 1.16370615e+04 1.14465273e+04 1.11513428e+04 1.11440645e+04 1.10295146e+04 1.09174561e+04 1.12897871e+04 1.14309717e+04 1.10837480e+04 1.08485977e+04 1.07580801e+04 1.07900615e+04 1.11131143e+04 1.10787451e+04 1.09001914e+04 1.07291709e+04 1.04536240e+04 1.05598652e+04 1.06603369e+04 1.08278223e+04 1.08018027e+04 1.03921797e+04 1.04005371e+04 1.03589707e+04 1.03985898e+04 1.04832734e+04 1.04492793e+04 1.04788486e+04 1.01452412e+04 1.00699912e+04 1.01459160e+04 1.00801074e+04 1.00715635e+04 1.01299619e+04 1.01024580e+04 9.98364844e+03 9.81105859e+03 9.85942090e+03 1.00362549e+04 9.89836719e+03 9.62103711e+03 9.60872949e+03 9.59610254e+03 9.48884082e+03 9.81337012e+03 9.70148730e+03 9.33240527e+03 9.49282031e+03 9.29297363e+03 9.22660352e+03 9.58457422e+03 9.35238477e+03 9.32026367e+03 9.41848535e+03 9.31313086e+03 9.80209961e+03 1.21880928e+04 1.24403506e+04 1.49926436e+04 1.30814199e+04 2.40733672e+04 4.12665625e+04 -6.59038350e+06 60736984. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 32584642. 1.04656398e+05 1.42467236e+04 9.28241699e+03 8.34872070e+03 7.03214502e+03 6.48927002e+03 6.54085596e+03 6.62970508e+03 6.41366406e+03 6.26168164e+03 6.06308154e+03 6.04142578e+03 6.17433838e+03 6.23856738e+03 6.07091797e+03 5.93215527e+03 5.85259326e+03 5.82847900e+03 5.92199072e+03 5.80877002e+03 5.57677393e+03 5.58113818e+03 5.68623730e+03 5.61730566e+03 5.42928125e+03 5.31465234e+03 5.44232715e+03 5.62424268e+03 5.55284277e+03 5.22228223e+03 4.98057666e+03 5.07337549e+03 5.24277490e+03 5.32690186e+03 5.17310840e+03 4.91607764e+03 4.88319141e+03 4.92714307e+03 5.03756006e+03 4.91814160e+03 4.63051807e+03 4.65023975e+03 4.84818262e+03 4.70955762e+03 4.52260254e+03 4.54341553e+03 4.52022070e+03 4.53795801e+03 4.49840820e+03 4.26455078e+03 4.17213525e+03 4.35454395e+03 4.43135840e+03 4.31450635e+03 4.08953027e+03 3.94486401e+03 4.11647607e+03 4.20392725e+03 4.04328687e+03 3.89452466e+03 3.72884888e+03 3.74019824e+03 3.88275757e+03 3.89822974e+03 3.79808472e+03 3.69621729e+03 3.65869849e+03 3.57629590e+03 3.53391479e+03 3.52923315e+03 3.38163184e+03 3.38913794e+03 3.48430322e+03 3.38615845e+03 3.20512183e+03 3.13886450e+03 3.26447192e+03 3.32947339e+03 3.21002661e+03 3.08404028e+03 2.96853076e+03 2.93058691e+03 2.98678345e+03 3.07820483e+03 2.98575073e+03 2.78608447e+03 2.77499072e+03 2.77406543e+03 2.76499902e+03 2.78614600e+03 2.64791357e+03 2.62619995e+03 2.66346753e+03 2.58290356e+03 2.50977441e+03 2.45767920e+03 2.44525586e+03 2.46954199e+03 2.41013574e+03 2.30143774e+03 2.25213330e+03 2.29405835e+03 2.29577295e+03 2.25119214e+03 2.18055713e+03 2.08008545e+03 2.06871948e+03 2.11562720e+03 2.08155664e+03 2.00589429e+03 1.89803638e+03 1.87166504e+03 1.92695068e+03 1.94571741e+03 1.86399902e+03 1.75662573e+03 1.73844714e+03 1.76458582e+03 1.72103259e+03 1.65196313e+03 1.60622485e+03 1.62813477e+03 1.62525354e+03 1.54380664e+03 1.50638965e+03 1.46424829e+03 1.46789539e+03 1.49358691e+03 1.43726819e+03 1.37241211e+03 1.31905798e+03 1.29582825e+03 1.29432129e+03 1.29319202e+03 1.25707446e+03 1.17654773e+03 1.15249109e+03 1.17849121e+03 1.16518799e+03 1.11544861e+03 1.06471606e+03 1.04707239e+03 1.04368787e+03 1.02010138e+03 9.78705261e+02 9.21627258e+02 9.11204712e+02 9.22090210e+02 8.98671875e+02 8.60028137e+02 8.22332214e+02 8.06749756e+02 8.01557556e+02 7.99659424e+02 7.69640198e+02 7.06562317e+02 6.91314392e+02 6.90908997e+02 6.67427185e+02 6.47663574e+02 6.20631592e+02 6.00502625e+02 5.82015930e+02 5.66186340e+02 5.44391724e+02 5.23399841e+02 5.19715637e+02 5.07118134e+02 4.82317230e+02 4.48294800e+02 4.27549286e+02 4.29533630e+02 4.26202057e+02 4.05470764e+02 3.79034027e+02 3.52716248e+02 3.34303619e+02 3.33903137e+02 3.34572693e+02 3.12048126e+02 2.83849121e+02 2.73411865e+02 2.66719788e+02 2.56824005e+02 2.45498123e+02 2.28180710e+02 2.14449097e+02 2.04255051e+02 1.92488556e+02 1.80769180e+02 1.72471939e+02 1.65686798e+02 1.54438751e+02 1.43989883e+02 1.33754837e+02 1.24337051e+02 1.18530304e+02 1.11861542e+02 1.02327385e+02 9.19714050e+01 8.35860214e+01 7.90201797e+01 7.41288223e+01 6.79041748e+01 6.17468948e+01 5.48039589e+01 4.94502907e+01 4.63559151e+01 4.29228210e+01 3.84252510e+01 3.38326149e+01 3.00422802e+01 2.69806042e+01 2.40324078e+01 2.15689526e+01 1.96521015e+01 1.79052315e+01 1.62612991e+01 1.50455341e+01 1.42268877e+01 1.37788553e+01 1.36259117e+01 1.37843390e+01 1.43031397e+01 1.51550255e+01 1.62713776e+01 1.79600334e+01 1.99834652e+01 2.21132317e+01 2.46423702e+01 2.73170071e+01 3.08841743e+01 3.42780647e+01 3.67565231e+01 4.04735413e+01 4.56316376e+01 5.23669624e+01 5.91685486e+01 6.36152344e+01 6.64044724e+01 7.07836990e+01 7.82930069e+01 8.90347748e+01 9.92367935e+01 1.04771202e+02 1.07093315e+02 1.14603477e+02 1.30790680e+02 1.38762802e+02 1.41522827e+02 1.50790359e+02 1.62786697e+02 1.73227005e+02 1.88550690e+02 1.96183060e+02 1.99902740e+02 2.15949265e+02 2.24286957e+02 2.41943069e+02 2.60239105e+02 2.59853668e+02 2.77889526e+02 3.00255554e+02 3.07749115e+02 3.20012878e+02 3.33058960e+02 3.49803894e+02 3.67313477e+02 3.78282166e+02 3.85105438e+02 4.02910126e+02 4.36324524e+02 4.63201263e+02 4.70443542e+02 4.68357269e+02 4.75224762e+02 5.00656830e+02 5.41529358e+02 5.76877136e+02 5.81321411e+02 5.71899963e+02 5.94340210e+02 6.33479187e+02 6.49102539e+02 6.59913879e+02 6.82920471e+02 7.02871643e+02 7.23476624e+02 7.72244751e+02 7.76943604e+02 7.75222229e+02 8.13662476e+02 8.17738037e+02 8.67776367e+02 9.08916199e+02 9.03554199e+02 9.57751099e+02 9.62890808e+02 9.47160828e+02 1.00499524e+03 1.00617432e+03 1.04634766e+03 1.14629492e+03 1.11803259e+03 1.07994751e+03 1.12496643e+03 1.20518103e+03 1.28063599e+03 1.27845142e+03 1.23436487e+03 1.22752075e+03 1.28892346e+03 1.38259058e+03 1.45762585e+03 1.45034070e+03 1.39701428e+03 1.42457898e+03 1.50501208e+03 1.55301001e+03 1.54308875e+03 1.55304846e+03 1.61554529e+03 1.64800342e+03 1.72463220e+03 1.76365808e+03 1.70482593e+03 1.73123059e+03 1.78933044e+03 1.82883545e+03 1.88062061e+03 1.90592810e+03 1.98398706e+03 1.99021558e+03 1.95141235e+03 2.01914612e+03 2.00800635e+03 2.10852588e+03 2.27515088e+03 2.18285010e+03 2.08529907e+03 2.17554956e+03 2.32021899e+03 2.42449097e+03 2.46276929e+03 2.37007227e+03 2.30312036e+03 2.38543921e+03 2.54784277e+03 2.69013110e+03 2.64790625e+03 2.53504248e+03 2.55813135e+03 2.67081665e+03 2.75966479e+03 2.84722046e+03 2.87591260e+03 2.76781079e+03 2.79278589e+03 2.95653687e+03 3.03789014e+03 2.99219409e+03 3.00525562e+03 3.04083984e+03 3.06588159e+03 3.22511670e+03 3.30769287e+03 3.19585571e+03 3.20294604e+03 3.27607397e+03 3.33289087e+03 3.40944922e+03 3.41656714e+03 3.54957715e+03 3.64627173e+03 3.54330469e+03 3.51258423e+03 3.50042188e+03 3.68787158e+03 3.94387158e+03 3.88863086e+03 3.72081836e+03 3.67859595e+03 3.85564648e+03 4.12092041e+03 4.04602612e+03 3.86834839e+03 3.97127051e+03 4.10140283e+03 4.26857080e+03 4.45856250e+03 4.37466455e+03 4.17360107e+03 4.14274072e+03 4.34775195e+03 4.51733008e+03 4.57282617e+03 4.54807910e+03 4.55994971e+03 4.57585840e+03 4.72895850e+03 4.76469287e+03 4.66448291e+03 4.69271777e+03 4.72487012e+03 4.98615137e+03 5.10353809e+03 4.95701172e+03 5.02928467e+03 5.10417627e+03 5.24323193e+03 5.15804736e+03 4.94799951e+03 5.23849072e+03 5.56227490e+03 5.45361084e+03 5.22905322e+03 5.31611621e+03 5.62799170e+03 5.69534863e+03 5.63623047e+03 5.64857861e+03 5.50939746e+03 5.57364648e+03 5.91707324e+03 5.97328320e+03 5.76177002e+03 5.67063770e+03 5.74511328e+03 6.05961475e+03 6.37264600e+03 6.15006592e+03 5.97580225e+03 6.21665869e+03 6.25845654e+03 6.47925244e+03 6.51452637e+03 6.19233350e+03 6.26683984e+03 6.51120459e+03 6.52787695e+03 6.63733203e+03 6.60718848e+03 6.80080273e+03 6.94629688e+03 6.68616016e+03 6.91645020e+03 6.61768213e+03 6.92867578e+03 9.64814062e+03 7.67851514e+03 1.01484014e+04 8.51463965e+03 1.08692148e+04 1.18640039e+04 1.15672197e+04 1.15353457e+04 1.14662207e+04 1.78084336e+04 2.62268027e+04 -6759607. -70004648. 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. 0. 0. 0. 0. 0. 0. 0. 0. -78969712. 2.65177775e+06 -1294419. 3.21281641e+04 1.96220547e+04 1.31601562e+04 1.06915664e+04 1.02664736e+04 9.80335352e+03 9.51828809e+03 9.89930469e+03 9.94242676e+03 9.77458887e+03 9.90612109e+03 9.90338086e+03 9.87049219e+03 1.00116260e+04 9.98831250e+03 9.95296973e+03 9.99145898e+03 9.95770801e+03 1.02840400e+04 1.04113262e+04 9.99289941e+03 1.00254346e+04 1.05522490e+04 1.06669160e+04 1.04861670e+04 1.04752617e+04 1.04926299e+04 1.05322148e+04 1.05769404e+04 1.06288350e+04 1.06462666e+04 1.06824834e+04 1.06123301e+04 1.06203105e+04 1.09841016e+04 1.10643418e+04 1.08920781e+04 1.09364121e+04 1.09912881e+04 1.10464072e+04 1.10178525e+04 1.10405596e+04 1.11156191e+04 1.08991084e+04 1.08589902e+04 1.11727998e+04 1.12006758e+04 1.16684902e+04 1.17130400e+04 1.13448047e+04 1.10261084e+04 1.10549043e+04 1.18524824e+04 1.19687627e+04 1.15366504e+04 1.13648018e+04 1.14319521e+04 1.16533779e+04 1.15934512e+04 1.20026211e+04 1.20291748e+04 1.13724150e+04 1.13037559e+04 1.19676943e+04 1.24456875e+04 1.21743643e+04 1.19619561e+04 1.20269316e+04 1.19725303e+04 1.18711025e+04 1.20009971e+04 1.20556182e+04 1.20098252e+04 1.20632197e+04 1.20808633e+04 1.22558174e+04 1.22690723e+04 1.25411699e+04 1.25170078e+04 1.22100225e+04 1.23867773e+04 1.24576055e+04 1.25268545e+04 1.26039424e+04 1.25192246e+04 1.25688857e+04 1.23131621e+04 1.20027695e+04 1.26504150e+04 1.28489814e+04 1.22221016e+04 1.23414150e+04 1.30709434e+04 1.34628447e+04 1.30422871e+04 1.27260625e+04 1.27347002e+04 1.27383662e+04 1.26294707e+04 1.26409307e+04 1.29417461e+04 1.29029199e+04 1.32207979e+04 1.31577939e+04 1.28072119e+04 1.30382402e+04 1.27490645e+04 1.27913027e+04 1.35097695e+04 1.34092539e+04 1.31084131e+04 1.28484092e+04 1.26672246e+04 1.33968037e+04 1.36621768e+04 1.32460820e+04 1.28803311e+04 1.28986709e+04 1.32449492e+04 1.32378174e+04 1.36662637e+04 1.37995625e+04 1.33166260e+04 1.30319336e+04 1.30844199e+04 1.36814570e+04 1.36879189e+04 1.33520010e+04 1.32609209e+04 1.32428418e+04 1.34258398e+04 1.31389951e+04 1.31764785e+04 1.39378672e+04 1.38691562e+04 1.35140322e+04 1.31324736e+04 1.31037178e+04 1.39682871e+04 1.39925625e+04 1.36006553e+04 1.32102217e+04 1.31262861e+04 1.36186230e+04 1.35980107e+04 1.36020303e+04 1.32663555e+04 1.35281035e+04 1.42668730e+04 1.39054893e+04 1.37266309e+04 1.38225059e+04 1.37591816e+04 1.35006934e+04 1.34932988e+04 1.37029502e+04 1.36686445e+04 1.35971904e+04 1.32619170e+04 1.34918447e+04 1.42946406e+04 1.37460508e+04 1.32843447e+04 1.36883848e+04 1.36770791e+04 1.40938789e+04 1.38201064e+04 1.32753604e+04 1.40440918e+04 1.41749512e+04 1.37243564e+04 1.36233730e+04 1.36297656e+04 1.35794160e+04 1.36004414e+04 1.36493984e+04 1.32332188e+04 1.36077119e+04 1.44247441e+04 1.41143750e+04 1.36089170e+04 1.32007539e+04 1.33761025e+04 1.42082715e+04 1.41377188e+04 1.37147178e+04 1.33849785e+04 1.32977686e+04 1.36390088e+04 1.36536309e+04 1.39869541e+04 1.36535459e+04 1.32397686e+04 1.36894619e+04 1.36772539e+04 1.39297148e+04 1.38457979e+04 1.34847354e+04 1.34896182e+04 1.34493877e+04 1.36206025e+04 1.32689287e+04 1.34238779e+04 1.41668096e+04 1.38492002e+04 1.34858516e+04 1.31964316e+04 1.31029521e+04 1.38377031e+04 1.38585273e+04 1.34657061e+04 1.31404014e+04 1.30695303e+04 1.34748770e+04 1.34643975e+04 1.37637900e+04 1.36209961e+04 1.32360703e+04 1.31068115e+04 1.30433887e+04 1.36575693e+04 1.35733037e+04 1.31887803e+04 1.31234482e+04 1.30754395e+04 1.34493223e+04 1.34863545e+04 1.29274775e+04 1.28455156e+04 1.34854717e+04 1.34821543e+04 1.28065303e+04 1.27102100e+04 1.33627002e+04 1.34470400e+04 1.30092012e+04 1.26643887e+04 1.26285527e+04 1.33598311e+04 1.32303125e+04 1.28288291e+04 1.28974434e+04 1.27847852e+04 1.27494727e+04 1.27529336e+04 1.27245068e+04 1.23876543e+04 1.26892021e+04 1.33429893e+04 1.29620127e+04 1.27503848e+04 1.28148203e+04 1.26602627e+04 1.26674834e+04 1.26146553e+04 1.25563652e+04 1.22308945e+04 1.20306299e+04 1.23263223e+04 1.25744482e+04 1.29006445e+04 1.24483486e+04 1.19812705e+04 1.23061006e+04 1.23777676e+04 1.27169658e+04 1.25334004e+04 1.21158838e+04 1.20011357e+04 1.19022988e+04 1.21332607e+04 1.21501719e+04 1.23478809e+04 1.22953301e+04 1.19630010e+04 1.17698066e+04 1.14221777e+04 1.18742754e+04 1.25608867e+04 1.22510811e+04 1.18578926e+04 1.15184980e+04 1.13355625e+04 1.18728174e+04 1.21479092e+04 1.18157891e+04 1.13317314e+04 1.12332617e+04 1.15254443e+04 1.15064316e+04 1.17835156e+04 1.17001641e+04 1.13288818e+04 1.13321484e+04 1.12438047e+04 1.14607773e+04 1.14509951e+04 1.09225527e+04 1.09136768e+04 1.14536436e+04 1.12130820e+04 1.06221807e+04 1.09274395e+04 1.15142764e+04 1.12750742e+04 1.09094209e+04 1.06084531e+04 1.06218838e+04 1.11940322e+04 1.10799375e+04 1.07474648e+04 1.04360391e+04 1.03202627e+04 1.06113906e+04 1.05286426e+04 1.05390488e+04 1.02322861e+04 1.04163750e+04 1.08108359e+04 1.05046836e+04 1.04694990e+04 1.03699775e+04 1.01350635e+04 1.01808730e+04 1.01756768e+04 1.01716611e+04 1.00603945e+04 9.90921973e+03 9.66394629e+03 9.81948730e+03 1.04151035e+04 9.91710547e+03 9.44215039e+03 9.68318164e+03 9.79127246e+03 1.00782217e+04 9.85265527e+03 9.48455176e+03 9.67606250e+03 9.64142773e+03 9.22102246e+03 9.11629102e+03 9.63637109e+03 9.56679004e+03 9.24183008e+03 9.06185449e+03 8.74933887e+03 9.07423145e+03 9.59502246e+03 9.30492773e+03 9.01425586e+03 8.76929785e+03 8.60184473e+03 9.00379980e+03 9.27521387e+03 8.97422656e+03 8.50049512e+03 8.40273438e+03 8.61641699e+03 8.65619336e+03 8.86238281e+03 8.60900488e+03 8.31197070e+03 8.46489258e+03 8.38823145e+03 8.46336230e+03 8.39469434e+03 8.18177490e+03 8.16986475e+03 8.15337988e+03 8.08394531e+03 7.78362842e+03 7.90877051e+03 8.34721582e+03 8.13678955e+03 7.75860596e+03 7.54172607e+03 7.59472119e+03 8.00447852e+03 7.88317773e+03 7.62804053e+03 7.38150049e+03 7.33390430e+03 7.50482373e+03 7.44198486e+03 7.40914209e+03 7.15216357e+03 7.30303662e+03 7.54590674e+03 7.25503418e+03 7.26165186e+03 7.22420605e+03 7.07536572e+03 6.97269434e+03 6.86260547e+03 6.86966016e+03 6.80150391e+03 6.79466309e+03 6.71342920e+03 6.83450635e+03 6.80545361e+03 6.48213330e+03 6.32571582e+03 6.43094678e+03 6.52093701e+03 6.70306055e+03 6.44145996e+03 6.12538330e+03 6.35288525e+03 6.46033691e+03 6.24683154e+03 6.04111377e+03 5.98147998e+03 6.02033740e+03 5.98595215e+03 5.89565820e+03 5.69803320e+03 5.84197021e+03 6.08255371e+03 5.88703027e+03 5.72216895e+03 5.57371191e+03 5.47387939e+03 5.72646484e+03 5.69754736e+03 5.47765576e+03 5.29517285e+03 5.13001611e+03 5.23371436e+03 5.38364355e+03 5.51238037e+03 5.24021143e+03 4.96501855e+03 5.07722607e+03 5.07675244e+03 5.20185449e+03 5.04004248e+03 4.84489307e+03 4.92685156e+03 4.86820605e+03 4.70849121e+03 4.57769092e+03 4.68584668e+03 4.87217920e+03 4.72234814e+03 4.58993262e+03 4.42990869e+03 4.36019531e+03 4.54697461e+03 4.51594922e+03 4.34765576e+03 4.18901514e+03 4.10500537e+03 4.19080176e+03 4.17892529e+03 4.22248926e+03 4.19885596e+03 4.01324536e+03 3.88824658e+03 3.88641602e+03 4.04345972e+03 3.91743530e+03 3.77018604e+03 3.78553906e+03 3.75175171e+03 3.62791064e+03 3.53791064e+03 3.65717822e+03 3.60076294e+03 3.45837500e+03 3.56446582e+03 3.54633374e+03 3.42471460e+03 3.36591162e+03 3.31860620e+03 3.27530273e+03 3.16353296e+03 3.09841382e+03 3.20916333e+03 3.19680029e+03 2.99588916e+03 2.86799707e+03 2.97865356e+03 3.10587866e+03 3.02969531e+03 2.83772925e+03 2.73432568e+03 2.84020776e+03 2.84420312e+03 2.71730298e+03 2.70270312e+03 2.59972168e+03 2.48605347e+03 2.54037085e+03 2.61438208e+03 2.56573267e+03 2.42872046e+03 2.32611328e+03 2.41289600e+03 2.44645850e+03 2.33714941e+03 2.21026172e+03 2.15117432e+03 2.19256128e+03 2.16957837e+03 2.18816577e+03 2.14919873e+03 2.03639209e+03 2.03316846e+03 1.99850146e+03 1.99533691e+03 1.92133411e+03 1.84518213e+03 1.89182971e+03 1.86233484e+03 1.80301782e+03 1.72631750e+03 1.71437085e+03 1.78423865e+03 1.68487524e+03 1.58320093e+03 1.59010315e+03 1.59563367e+03 1.56938806e+03 1.52194580e+03 1.52831323e+03 1.51325183e+03 1.43912439e+03 1.36533923e+03 1.34079675e+03 1.38205359e+03 1.32715332e+03 1.25879456e+03 1.27409021e+03 1.25442029e+03 1.20158740e+03 1.16148962e+03 1.18042053e+03 1.14227563e+03 1.08435400e+03 1.08820569e+03 1.06689221e+03 1.04685730e+03 1.01937732e+03 9.83336182e+02 9.51634644e+02 9.00079895e+02 8.73891418e+02 8.92292847e+02 8.97494324e+02 8.34584961e+02 7.72308960e+02 7.81783020e+02 8.04618469e+02 7.77740112e+02 7.19809021e+02 6.75044189e+02 6.87422607e+02 6.86072021e+02 6.43188171e+02 6.35056274e+02 6.12069031e+02 5.70703003e+02 5.56859436e+02 5.55398804e+02 5.39452332e+02 5.03925262e+02 4.74802856e+02 4.75903992e+02 4.78853180e+02 4.50492523e+02 4.16330688e+02 3.94067749e+02 3.97369110e+02 3.93092224e+02 3.64585815e+02 3.41379211e+02 3.29733276e+02 3.21825836e+02 3.06207275e+02 3.00218964e+02 2.80458038e+02 2.58622345e+02 2.55221313e+02 2.43701996e+02 2.31234833e+02 2.15195389e+02 2.00851715e+02 1.96983261e+02 1.81505325e+02 1.68614227e+02 1.64621902e+02 1.58135559e+02 1.53327621e+02 1.42472687e+02 1.35688736e+02 1.26311409e+02 9.90761108e+01 9.21959915e+01 9.19772186e+01 9.29621201e+01 8.79872208e+01 7.40652924e+01 6.64196854e+01 8.70974731e+01 1.12224274e+02 4.67897339e+02 247711712. 0. 0. 0. 0. -54994276. -54994276. 32267176. 11923223. 4.58289032e+02 -2.39244050e+06 1.94760483e+02 2.15743683e+02 4006584. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8609375. -4.29897350e+06 1.13514610e+02 1.10710861e+02 4.40920486e+01 6.50218658e+01 5.51984711e+01 5.99573097e+01 6.21169205e+01 7.51219788e+01 7.83891296e+01 8.38758621e+01 9.00710220e+01 9.91627121e+01 1.09788948e+02 1.17527771e+02 1.21773544e+02 1.29454636e+02 1.42459793e+02 1.52366211e+02 1.61049805e+02 1.69950500e+02 1.78502335e+02 1.90080231e+02 2.06437515e+02 2.18667496e+02 2.22374557e+02 2.34827316e+02 2.55611404e+02 2.70053040e+02 2.82894379e+02 2.88589752e+02 2.96608154e+02 3.19438324e+02 3.37809052e+02 3.48822906e+02 3.57736298e+02 3.71827820e+02 3.95004944e+02 4.10099518e+02 4.22640137e+02 4.34469330e+02 4.52124207e+02 4.88936188e+02 5.11005707e+02 5.03814606e+02 5.14455811e+02 5.42141113e+02 5.66438904e+02 5.95087341e+02 6.09224792e+02 6.14527039e+02 6.42416870e+02 6.69572449e+02 6.89020996e+02 7.10799866e+02 7.17162231e+02 7.40217041e+02 7.72927551e+02 7.89429932e+02 8.09461304e+02 8.26442261e+02 8.54139771e+02 8.99561401e+02 9.20551331e+02 9.30922546e+02 9.36405212e+02 9.58943176e+02 1.01685773e+03 1.04535815e+03 1.03960059e+03 1.07019434e+03 1.09853723e+03 1.13455798e+03 1.18698999e+03 1.19429443e+03 1.18880701e+03 1.22018933e+03 1.28171387e+03 1.31273047e+03 1.30865308e+03 1.31150879e+03 1.35417688e+03 1.40572461e+03 1.47222266e+03 1.50130786e+03 1.47064209e+03 1.49959705e+03 1.57358594e+03 1.60166553e+03 1.61897815e+03 1.61411328e+03 1.63367188e+03 1.72764514e+03 1.77614441e+03 1.76358655e+03 1.79455615e+03 1.83218750e+03 1.86019116e+03 1.89581055e+03 1.92370605e+03 1.97020715e+03 2.00320728e+03 2.06359570e+03 2.10075415e+03 2.06959717e+03 2.10853345e+03 2.18360693e+03 2.19523682e+03 2.24254077e+03 2.27138135e+03 2.30664600e+03 2.38257104e+03 2.39784155e+03 2.39743164e+03 2.48307935e+03 2.52659497e+03 2.50867773e+03 2.54395459e+03 2.60795508e+03 2.66533130e+03 2.68131396e+03 2.68035449e+03 2.72603857e+03 2.79579639e+03 2.91292627e+03 2.92066846e+03 2.85202295e+03 2.92922778e+03 3.02269531e+03 3.05742578e+03 3.07818164e+03 3.07589380e+03 3.09113843e+03 3.19105957e+03 3.29928223e+03 3.29943042e+03 3.25274658e+03 3.29498926e+03 3.42376318e+03 3.50309961e+03 3.54946118e+03 3.50889233e+03 3.46445459e+03 3.57921289e+03 3.63549780e+03 3.67811987e+03 3.74147388e+03 3.74160913e+03 3.81500708e+03 3.97709448e+03 3.93355225e+03 3.83904443e+03 3.92356128e+03 4.05046265e+03 4.11093945e+03 4.19932324e+03 4.16695605e+03 4.13295166e+03 4.21743311e+03 4.40433447e+03 4.36232959e+03 4.25585400e+03 4.36404492e+03 4.55476562e+03 4.56917725e+03 4.55938525e+03 4.50368994e+03 4.58169141e+03 4.69902930e+03 4.77190088e+03 4.80635010e+03 4.88727197e+03 4.83142285e+03 4.89054053e+03 5.08532422e+03 5.02422363e+03 4.96054590e+03 5.07044189e+03 5.20497754e+03 5.28848584e+03 5.28364502e+03 5.20759473e+03 5.23802295e+03 5.38411279e+03 5.62171533e+03 5.68527490e+03 5.40564062e+03 5.45243115e+03 5.77001514e+03 5.73290723e+03 5.65723633e+03 5.66960742e+03 5.69900146e+03 5.88363574e+03 6.00374707e+03 5.97434131e+03 5.98274902e+03 5.89377783e+03 6.07235889e+03 6.25658496e+03 6.26281445e+03 6.21054590e+03 6.22630908e+03 6.36224365e+03 6.44629443e+03 6.39888965e+03 6.40852246e+03 6.47960498e+03 6.56832910e+03 6.74338867e+03 6.84427637e+03 6.57307129e+03 6.65353125e+03 6.86625049e+03 6.91790479e+03 6.97610645e+03 6.84724902e+03 6.94320947e+03 7.20159766e+03 7.17597217e+03 7.19719141e+03 7.06140967e+03 7.04531689e+03 7.34433057e+03 7.46188770e+03 7.43385400e+03 7.41949512e+03 7.49754102e+03 7.54498633e+03 7.71636768e+03 7.70164111e+03 7.57550195e+03 7.53030273e+03 7.66343408e+03 7.93694531e+03 7.89482227e+03 7.79471240e+03 7.91034424e+03 8.12219727e+03 8.15180371e+03 8.12662842e+03 8.10765723e+03 8.09004102e+03 8.22774414e+03 8.30496680e+03 8.48361035e+03 8.39716797e+03 8.32439551e+03 8.59372559e+03 8.41237109e+03 8.49142676e+03 8.73992871e+03 8.53543848e+03 8.61050781e+03 8.76059766e+03 8.81286523e+03 8.75402441e+03 8.73458496e+03 9.08514160e+03 9.25102930e+03 8.90343652e+03 8.92644336e+03 9.08805566e+03 9.15375977e+03 9.36154883e+03 9.29937793e+03 9.15567383e+03 9.23441992e+03 9.51214746e+03 9.58725781e+03 9.49601465e+03 9.39060449e+03 9.56148730e+03 9.73227051e+03 9.58837207e+03 9.63539258e+03 9.60695996e+03 9.64937891e+03 9.81896289e+03 9.99715137e+03 1.00096768e+04 9.87527539e+03 9.84294238e+03 1.01654834e+04 1.03761162e+04 1.00872686e+04 1.01392471e+04 1.02687979e+04 9.96532617e+03 1.02761484e+04 1.04970215e+04 1.02162695e+04 1.03912979e+04 1.05657568e+04 1.04499932e+04 1.06947461e+04 1.06332334e+04 1.05216719e+04 1.06295127e+04 1.07591260e+04 1.08940537e+04 1.06674824e+04 1.05715850e+04 1.08297129e+04 1.10927441e+04 1.10415371e+04 1.09242578e+04 1.08417822e+04 1.10876953e+04 1.14703525e+04 1.11838613e+04 1.09687646e+04 1.09935186e+04 1.13451523e+04 1.15975098e+04 1.12638564e+04 1.10986045e+04 1.13408027e+04 1.14563018e+04 1.13974648e+04 1.16183115e+04 1.15657832e+04 1.13354551e+04 1.16219834e+04 1.19796953e+04 1.17419414e+04 1.12409434e+04 1.15063096e+04 1.19162148e+04 1.19068740e+04 1.19072666e+04 1.18191719e+04 1.17463203e+04 1.20585459e+04 1.23266104e+04 1.19907949e+04 1.18831904e+04 1.20082227e+04 1.22754668e+04 1.22416973e+04 1.18941064e+04 1.19399482e+04 1.21897490e+04 1.22958350e+04 1.23678350e+04 1.24124023e+04 1.22752100e+04 1.23791016e+04 1.23449854e+04 1.22080596e+04 1.23052881e+04 1.22738418e+04 1.24966924e+04 1.27530381e+04 1.24891318e+04 1.22791172e+04 1.24443916e+04 1.27779160e+04 1.31143291e+04 1.30016279e+04 1.25190889e+04 1.24933418e+04 1.27749521e+04 1.28027285e+04 1.26762305e+04 1.27649932e+04 1.28705166e+04 1.29373711e+04 1.28211328e+04 1.25742080e+04 1.28969424e+04 1.31828721e+04 1.32380967e+04 1.30952959e+04 1.27453770e+04 1.29550508e+04 1.29663174e+04 1.28195137e+04 1.32975332e+04 1.33547705e+04 1.29308027e+04 1.29126621e+04 1.30768740e+04 1.34845928e+04 1.35000996e+04 1.32303516e+04 1.31864883e+04 1.32106387e+04 1.32221416e+04 1.30786270e+04 1.32769775e+04 1.33973066e+04 1.35218555e+04 1.35421162e+04 1.29949424e+04 1.31514043e+04 1.33715801e+04 1.34417793e+04 1.38276357e+04 1.33899805e+04 1.30845488e+04 1.36087578e+04 1.38353379e+04 1.35129648e+04 1.34028623e+04 1.32999365e+04 1.32803047e+04 1.34569160e+04 1.35202451e+04 1.34366807e+04 1.37803350e+04 1.40009473e+04 1.36555869e+04 1.34346309e+04 1.32598037e+04 1.36249678e+04 1.39362275e+04 1.37195918e+04 1.34043848e+04 1.33300107e+04 1.35487627e+04 1.38272852e+04 1.41439609e+04 1.36748975e+04 1.33759238e+04 1.36758701e+04 1.36035166e+04 1.35150752e+04 1.38998076e+04 1.38394297e+04 1.35327939e+04 1.37368887e+04 1.37093623e+04 1.36698379e+04 1.38438887e+04 1.37928291e+04 1.36453906e+04 1.35868408e+04 1.36342207e+04 1.35391660e+04 1.36941699e+04 1.38365547e+04 1.38022031e+04 1.37469678e+04 1.34511885e+04 1.36489805e+04 1.36887930e+04 1.35673809e+04 1.38110508e+04 1.36966719e+04 1.35861494e+04 1.36592949e+04 1.35823613e+04 1.39705703e+04 1.40313496e+04 1.35682490e+04 1.35695469e+04 1.34250205e+04 1.34453125e+04 1.36040605e+04 1.36986943e+04 1.38211484e+04 1.36196494e+04 1.35029189e+04 1.34570146e+04 1.35419414e+04 1.38748311e+04 1.37965117e+04 1.35288311e+04 1.33825469e+04 1.33036777e+04 1.34609678e+04 1.37007139e+04 1.36822930e+04 1.35339072e+04 1.34282412e+04 1.33225615e+04 1.34021006e+04 1.35763398e+04 1.34890752e+04 1.34445596e+04 1.34467402e+04 1.34038047e+04 1.34621094e+04 1.31714336e+04 1.32349004e+04 1.36054824e+04 1.33287822e+04 1.31677129e+04 1.33410479e+04 1.31346387e+04 1.31029688e+04 1.36681816e+04 1.35802773e+04 1.29410264e+04 1.29781670e+04 1.31329473e+04 1.30146787e+04 1.33096934e+04 1.32438848e+04 1.28403320e+04 1.29496709e+04 1.30245596e+04 1.32011787e+04 1.32686768e+04 1.30504844e+04 1.31056172e+04 1.28534893e+04 1.25605244e+04 1.27818330e+04 1.30613232e+04 1.29512578e+04 1.29297197e+04 1.28936904e+04 1.23594561e+04 1.26171885e+04 1.31484346e+04 1.29508301e+04 1.27232422e+04 1.23470146e+04 1.24083164e+04 1.28323770e+04 1.27436934e+04 1.25648740e+04 1.26948730e+04 1.25050400e+04 1.24645537e+04 1.25272891e+04 1.21859941e+04 1.22081729e+04 1.25474951e+04 1.26092480e+04 1.23321543e+04 1.19791396e+04 1.19788535e+04 1.22924580e+04 1.24689570e+04 1.22860537e+04 1.19701436e+04 1.18026182e+04 1.20003428e+04 1.22269639e+04 1.24091611e+04 1.21261602e+04 1.17863887e+04 1.18722188e+04 1.18253828e+04 1.17738545e+04 1.19133477e+04 1.17859131e+04 1.17816689e+04 1.19220693e+04 1.16370381e+04 1.15659658e+04 1.16957900e+04 1.16529570e+04 1.16726973e+04 1.14816133e+04 1.11960117e+04 1.13096348e+04 1.15029990e+04 1.16091680e+04 1.16306816e+04 1.13381846e+04 1.10310518e+04 1.11424463e+04 1.10656113e+04 1.11153838e+04 1.13566797e+04 1.10664561e+04 1.08909277e+04 1.08155615e+04 1.08365605e+04 1.10667822e+04 1.12210918e+04 1.10094355e+04 1.07972471e+04 1.06627676e+04 1.04007100e+04 1.05537148e+04 1.07890088e+04 1.08354062e+04 1.06828643e+04 1.03613965e+04 1.03025830e+04 1.04038828e+04 1.04943926e+04 1.04327871e+04 1.03900303e+04 1.02560127e+04 1.00463828e+04 1.01946875e+04 1.03701426e+04 1.02398320e+04 9.90002930e+03 9.96519141e+03 1.00148994e+04 1.00102012e+04 9.98481543e+03 9.87012695e+03 9.93910254e+03 9.78939746e+03 9.58910840e+03 9.78691895e+03 9.72389844e+03 9.55829785e+03 9.71457227e+03 9.49303613e+03 9.22441699e+03 9.48784082e+03 9.41430078e+03 9.39157715e+03 9.74547168e+03 9.55594531e+03 9.08036621e+03 9.21658105e+03 1.25515283e+04 1.48353301e+04 2.49308945e+04 3.03329824e+04 -8742338. -2.12158850e+06 3925872. 22398254. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 40084008. -16955768. 1.73686638e+06 7.42091850e+06 4.18928675e+06 2.27267305e+04 1.78085996e+04 9.52578223e+03 8.83296777e+03 7.38079443e+03 6.92866943e+03 6.37409277e+03 6.39202832e+03 6.53274854e+03 6.36444922e+03 6.18699902e+03 6.06095801e+03 5.98113672e+03 6.24333447e+03 6.29629248e+03 5.97530469e+03 5.75210840e+03 5.79260010e+03 5.85698340e+03 5.89784131e+03 5.92015625e+03 5.69685156e+03 5.52379883e+03 5.55840332e+03 5.55221484e+03 5.54699316e+03 5.39638232e+03 5.29263379e+03 5.46700879e+03 5.56585986e+03 5.36803955e+03 5.09245312e+03 5.04714111e+03 5.21446777e+03 5.20983252e+03 5.03487061e+03 4.87693848e+03 4.86246338e+03 5.00490479e+03 5.06582861e+03 4.86924170e+03 4.59414111e+03 4.63777148e+03 4.82537695e+03 4.71002832e+03 4.65435791e+03 4.58216846e+03 4.37268018e+03 4.41965088e+03 4.52920264e+03 4.38456543e+03 4.27961768e+03 4.34259668e+03 4.34271289e+03 4.24294531e+03 4.15142578e+03 3.97553442e+03 4.01801929e+03 4.16161279e+03 4.03989282e+03 3.87717505e+03 3.78506396e+03 3.75712817e+03 3.88895337e+03 3.94704932e+03 3.77216382e+03 3.62497363e+03 3.56809448e+03 3.51829590e+03 3.56308105e+03 3.61466406e+03 3.44208984e+03 3.35708716e+03 3.41009790e+03 3.34673560e+03 3.26514697e+03 3.21723975e+03 3.23930249e+03 3.25667798e+03 3.18523535e+03 3.13139990e+03 3.00403320e+03 2.91800024e+03 3.03609058e+03 3.06727197e+03 2.88114429e+03 2.75599463e+03 2.77907104e+03 2.81756030e+03 2.82219824e+03 2.79345386e+03 2.65644409e+03 2.59864624e+03 2.62051465e+03 2.56514185e+03 2.55145264e+03 2.50554590e+03 2.39076294e+03 2.38230103e+03 2.39571509e+03 2.37251636e+03 2.33393457e+03 2.29574414e+03 2.25619434e+03 2.22056616e+03 2.18041724e+03 2.08040869e+03 2.04814185e+03 2.13411230e+03 2.09855859e+03 1.96072498e+03 1.89016223e+03 1.89065686e+03 1.94542810e+03 1.96006213e+03 1.85436938e+03 1.75491565e+03 1.72308643e+03 1.72101965e+03 1.70818909e+03 1.69653003e+03 1.64910474e+03 1.60892749e+03 1.57615051e+03 1.54602979e+03 1.53275110e+03 1.47152063e+03 1.45871350e+03 1.47621484e+03 1.42373376e+03 1.36872424e+03 1.32273218e+03 1.28193030e+03 1.30742078e+03 1.31303003e+03 1.22632263e+03 1.16937756e+03 1.15974731e+03 1.18468445e+03 1.17835437e+03 1.11484424e+03 1.05868640e+03 1.02595581e+03 1.01292010e+03 1.01194910e+03 9.99355469e+02 9.39852234e+02 8.95087952e+02 8.98973450e+02 9.00827881e+02 8.68129639e+02 8.34696472e+02 8.14544434e+02 7.87987793e+02 7.73608887e+02 7.54228210e+02 7.08886047e+02 6.88310425e+02 6.91895325e+02 6.71299255e+02 6.42210938e+02 6.11285156e+02 5.93489014e+02 5.83544678e+02 5.71002258e+02 5.55567688e+02 5.24113281e+02 5.09886139e+02 4.97677124e+02 4.74592834e+02 4.56006348e+02 4.34218384e+02 4.19888428e+02 4.12432373e+02 4.02232788e+02 3.81654114e+02 3.51522888e+02 3.34930878e+02 3.34656372e+02 3.27803406e+02 3.08030731e+02 2.82240692e+02 2.68264709e+02 2.61416412e+02 2.54004990e+02 2.42672623e+02 2.22211655e+02 2.06344025e+02 1.98221863e+02 1.91712585e+02 1.83582520e+02 1.70751556e+02 1.59169662e+02 1.49388901e+02 1.40447800e+02 1.32932098e+02 1.24078186e+02 1.15956146e+02 1.06586853e+02 9.67566757e+01 8.84042816e+01 8.14353714e+01 7.71919708e+01 7.29481888e+01 6.59815598e+01 5.79479103e+01 5.08592072e+01 4.65934563e+01 4.41942101e+01 4.05047607e+01 3.51409798e+01 3.03070946e+01 2.64653244e+01 2.37172012e+01 2.13516121e+01 1.89283600e+01 1.67475281e+01 1.48667212e+01 1.33547602e+01 1.22292356e+01 1.14298601e+01 1.09396772e+01 1.07604170e+01 1.09234257e+01 1.14579134e+01 1.23791924e+01 1.34740677e+01 1.49772310e+01 1.68580456e+01 1.89898949e+01 2.16127548e+01 2.44188900e+01 2.79616833e+01 3.16498909e+01 3.43780136e+01 3.77069321e+01 4.26503448e+01 4.93031807e+01 5.60442467e+01 6.06749496e+01 6.36479530e+01 6.82215805e+01 7.53270950e+01 8.53888626e+01 9.54204788e+01 1.02118828e+02 1.04296188e+02 1.11434311e+02 1.27120537e+02 1.35440201e+02 1.39433472e+02 1.48587036e+02 1.60121078e+02 1.70328308e+02 1.85753876e+02 1.93842407e+02 1.97771378e+02 2.13069305e+02 2.21313263e+02 2.39038239e+02 2.57210327e+02 2.58207397e+02 2.73920288e+02 2.95354034e+02 3.05257385e+02 3.17620148e+02 3.30867828e+02 3.46794525e+02 3.65242432e+02 3.73237701e+02 3.78447571e+02 4.00010834e+02 4.35602692e+02 4.61319000e+02 4.67526367e+02 4.65554871e+02 4.70895996e+02 4.97535431e+02 5.38376038e+02 5.73129761e+02 5.76556580e+02 5.67167175e+02 5.91634155e+02 6.28962524e+02 6.44581299e+02 6.58290100e+02 6.80634827e+02 7.01838196e+02 7.24648499e+02 7.70288818e+02 7.71856995e+02 7.72767151e+02 8.11264404e+02 8.10862915e+02 8.59783325e+02 9.12201172e+02 9.00875244e+02 9.51769958e+02 9.62900146e+02 9.41991577e+02 9.98546265e+02 1.00498199e+03 1.04425330e+03 1.14057043e+03 1.11384302e+03 1.07745520e+03 1.12322180e+03 1.20630676e+03 1.27468469e+03 1.27374780e+03 1.24198523e+03 1.23623694e+03 1.27810962e+03 1.36427100e+03 1.44331555e+03 1.44989148e+03 1.40445374e+03 1.42571655e+03 1.50266003e+03 1.54152466e+03 1.54360461e+03 1.56233704e+03 1.60644751e+03 1.63807861e+03 1.72457812e+03 1.76489111e+03 1.70277515e+03 1.72190283e+03 1.79017151e+03 1.82758301e+03 1.87617896e+03 1.90595935e+03 1.98607593e+03 1.97483264e+03 1.93085461e+03 2.03603748e+03 2.01099231e+03 2.09203394e+03 2.27398096e+03 2.18333472e+03 2.09414331e+03 2.17442139e+03 2.32022241e+03 2.41839429e+03 2.44402271e+03 2.35046802e+03 2.30460962e+03 2.38870825e+03 2.54105054e+03 2.67428467e+03 2.63863696e+03 2.52310791e+03 2.55168262e+03 2.67206201e+03 2.75156445e+03 2.84796460e+03 2.87962207e+03 2.76704468e+03 2.77130151e+03 2.94172900e+03 3.02458008e+03 2.98040356e+03 2.99721509e+03 3.05542432e+03 3.06361963e+03 3.22683496e+03 3.30118970e+03 3.18559277e+03 3.21699243e+03 3.29378271e+03 3.31436279e+03 3.39216895e+03 3.41863037e+03 3.54170068e+03 3.62351904e+03 3.54932324e+03 3.51375415e+03 3.50284009e+03 3.69179810e+03 3.91336035e+03 3.88278271e+03 3.74679761e+03 3.68137646e+03 3.85335864e+03 4.10442578e+03 4.02020093e+03 3.85819019e+03 3.96653101e+03 4.12158350e+03 4.25052979e+03 4.42872070e+03 4.37283350e+03 4.18413916e+03 4.15062305e+03 4.34198730e+03 4.51817188e+03 4.54837939e+03 4.52746680e+03 4.55102637e+03 4.59066260e+03 4.73623291e+03 4.72111768e+03 4.63092188e+03 4.73802832e+03 4.71085303e+03 4.94812646e+03 5.13587891e+03 4.96831055e+03 5.05946289e+03 5.08732178e+03 5.14235596e+03 5.07849854e+03 5.00527783e+03 5.27296631e+03 5.57850879e+03 5.46812500e+03 5.23458936e+03 5.28200146e+03 5.63593457e+03 5.72841406e+03 5.64090674e+03 5.65837842e+03 5.51719482e+03 5.52639648e+03 5.86502490e+03 5.90255762e+03 5.81246094e+03 5.75673389e+03 5.72186768e+03 6.05071680e+03 6.38326074e+03 6.12688574e+03 5.95391309e+03 6.17977734e+03 6.25347998e+03 6.47144189e+03 6.54977393e+03 6.20687012e+03 6.23074609e+03 6.48227783e+03 6.51151855e+03 6.62325830e+03 6.77628662e+03 6.67317188e+03 7.23128320e+03 7.18595410e+03 6.73496924e+03 8.39274707e+03 9.40340039e+03 1.82804688e+04 1.20098457e+04 2.02317090e+04 1.90003613e+04 2.93680450e+06 5907728. -2584863. 3.42012675e+06 -5.87784950e+06 -1920636. 68287536. 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. 0. 0. -400063488. -400063488. -400063488. 0. 0. 140856864. -2.52312950e+06 -1.49443050e+06 2.71786504e+04 2.29087168e+04 1.56351777e+04 1.52124785e+04 1.23842646e+04 1.20850029e+04 1.00137412e+04 1.00228799e+04 9.76682520e+03 9.52691406e+03 9.90514551e+03 9.88713379e+03 9.74954688e+03 9.87569531e+03 9.91288086e+03 9.89765527e+03 9.98456348e+03 1.00158643e+04 9.97863672e+03 9.92902637e+03 9.93037891e+03 1.02940479e+04 1.04090293e+04 9.96085156e+03 1.00160479e+04 1.05476348e+04 1.06561865e+04 1.04974082e+04 1.04866904e+04 1.04976230e+04 1.04981982e+04 1.05768613e+04 1.06537871e+04 1.06736807e+04 1.06769619e+04 1.04704033e+04 1.04523994e+04 1.10620605e+04 1.11552627e+04 1.08302041e+04 1.08818945e+04 1.09590234e+04 1.10682676e+04 1.10310635e+04 1.10154346e+04 1.11020283e+04 1.09899424e+04 1.10047158e+04 1.11039746e+04 1.11117607e+04 1.15882354e+04 1.17108398e+04 1.13626328e+04 1.10742852e+04 1.10464932e+04 1.17729385e+04 1.18828203e+04 1.15290820e+04 1.13803857e+04 1.14751406e+04 1.16799912e+04 1.15989189e+04 1.19557822e+04 1.20162539e+04 1.13961797e+04 1.13094287e+04 1.19384795e+04 1.24364902e+04 1.21706494e+04 1.19508145e+04 1.19532549e+04 1.19258193e+04 1.19632842e+04 1.20448223e+04 1.22109092e+04 1.21870049e+04 1.20029990e+04 1.20471396e+04 1.21250303e+04 1.21745508e+04 1.25532012e+04 1.25412988e+04 1.22241445e+04 1.22625156e+04 1.22784639e+04 1.26743330e+04 1.27724746e+04 1.24834072e+04 1.25014307e+04 1.22951406e+04 1.21147646e+04 1.27461768e+04 1.27137432e+04 1.20861543e+04 1.23118848e+04 1.30388252e+04 1.35275693e+04 1.30787090e+04 1.27388252e+04 1.26840156e+04 1.26763340e+04 1.27726660e+04 1.27849199e+04 1.28215801e+04 1.27888330e+04 1.31770801e+04 1.31476396e+04 1.28236953e+04 1.29322871e+04 1.25886348e+04 1.28608398e+04 1.36973525e+04 1.34560342e+04 1.31213643e+04 1.27725479e+04 1.27143311e+04 1.35159932e+04 1.35953428e+04 1.31666377e+04 1.28841094e+04 1.28484678e+04 1.31852002e+04 1.32238281e+04 1.36397041e+04 1.37481299e+04 1.33016660e+04 1.31668281e+04 1.32212607e+04 1.35368887e+04 1.35486855e+04 1.33602539e+04 1.32544287e+04 1.32539766e+04 1.33326611e+04 1.29861709e+04 1.32939014e+04 1.40778535e+04 1.38288076e+04 1.35071543e+04 1.31660244e+04 1.31403223e+04 1.39491426e+04 1.39568408e+04 1.35511279e+04 1.31885225e+04 1.31596855e+04 1.36722764e+04 1.35939512e+04 1.35869961e+04 1.32833916e+04 1.35217402e+04 1.42711719e+04 1.38862705e+04 1.36867002e+04 1.38370352e+04 1.37338887e+04 1.34404453e+04 1.34664307e+04 1.35846758e+04 1.35518838e+04 1.37304824e+04 1.33682598e+04 1.34827012e+04 1.43482393e+04 1.37764707e+04 1.32602578e+04 1.36552510e+04 1.36668994e+04 1.40450957e+04 1.39042510e+04 1.33870586e+04 1.38961846e+04 1.40451416e+04 1.37394463e+04 1.36294131e+04 1.36291562e+04 1.35665127e+04 1.35594795e+04 1.36324609e+04 1.32772500e+04 1.36170977e+04 1.43984346e+04 1.41274209e+04 1.36009541e+04 1.31957256e+04 1.33755605e+04 1.41642832e+04 1.41164023e+04 1.36967002e+04 1.33914385e+04 1.32914512e+04 1.36176328e+04 1.36777119e+04 1.39510205e+04 1.37846299e+04 1.34195996e+04 1.35233467e+04 1.35057871e+04 1.39366270e+04 1.38637715e+04 1.34485117e+04 1.34830342e+04 1.34901104e+04 1.34650947e+04 1.31101016e+04 1.35211123e+04 1.43298271e+04 1.38629102e+04 1.34627314e+04 1.31702402e+04 1.30514043e+04 1.38258789e+04 1.38797295e+04 1.34828281e+04 1.31577217e+04 1.30480439e+04 1.34381084e+04 1.34041230e+04 1.37195352e+04 1.37439932e+04 1.33604316e+04 1.29651543e+04 1.29022363e+04 1.36810117e+04 1.35901865e+04 1.31914033e+04 1.29920088e+04 1.29083828e+04 1.36087441e+04 1.36484434e+04 1.28611074e+04 1.28036641e+04 1.35147012e+04 1.34733086e+04 1.27813350e+04 1.27330059e+04 1.33616240e+04 1.34386211e+04 1.29961475e+04 1.26710801e+04 1.26652090e+04 1.32998037e+04 1.31528779e+04 1.27385166e+04 1.29141611e+04 1.28712227e+04 1.27805732e+04 1.27715117e+04 1.27469102e+04 1.24176143e+04 1.26793242e+04 1.31872178e+04 1.28802363e+04 1.29147812e+04 1.29434600e+04 1.26316904e+04 1.26162510e+04 1.26047842e+04 1.25072363e+04 1.22346133e+04 1.22033525e+04 1.24465420e+04 1.24519160e+04 1.27495996e+04 1.24049414e+04 1.19855488e+04 1.23157803e+04 1.23823633e+04 1.26837920e+04 1.25254111e+04 1.20961045e+04 1.20172021e+04 1.19095381e+04 1.21256387e+04 1.21076299e+04 1.23226699e+04 1.22771660e+04 1.19699971e+04 1.18670732e+04 1.15075879e+04 1.18296631e+04 1.24371201e+04 1.22590811e+04 1.18514180e+04 1.14845342e+04 1.12923682e+04 1.18298779e+04 1.21330791e+04 1.18099434e+04 1.13329414e+04 1.12755400e+04 1.15199492e+04 1.15281328e+04 1.17242764e+04 1.16444375e+04 1.13284531e+04 1.12478154e+04 1.11834092e+04 1.15712715e+04 1.16033691e+04 1.09181055e+04 1.08719658e+04 1.14161172e+04 1.13241328e+04 1.06887041e+04 1.08074004e+04 1.13819297e+04 1.12682871e+04 1.09706699e+04 1.06205518e+04 1.05564609e+04 1.11408975e+04 1.10745391e+04 1.07363145e+04 1.04469434e+04 1.02933223e+04 1.05116855e+04 1.05735713e+04 1.06055352e+04 1.02165049e+04 1.04047109e+04 1.08142412e+04 1.05009717e+04 1.04918838e+04 1.03594648e+04 1.01291543e+04 1.02178340e+04 1.02148721e+04 1.01831709e+04 1.00454160e+04 9.85379102e+03 9.63640137e+03 9.86550781e+03 1.03264229e+04 9.82505664e+03 9.37034277e+03 9.65035547e+03 9.85383691e+03 1.01705205e+04 9.84528613e+03 9.49611914e+03 9.67091309e+03 9.61265723e+03 9.31067480e+03 9.18533691e+03 9.50593750e+03 9.42301660e+03 9.21958203e+03 9.12065527e+03 8.81115332e+03 9.05370020e+03 9.60453809e+03 9.29011133e+03 8.98033789e+03 8.71812500e+03 8.57496582e+03 8.98941602e+03 9.34687891e+03 8.97950586e+03 8.56313281e+03 8531. 8.57145020e+03 8.55598633e+03 8.78257812e+03 8.60897070e+03 8.31871387e+03 8.36485156e+03 8.29205273e+03 8.52483203e+03 8.45752539e+03 8.15394922e+03 8.12344629e+03 8.09643555e+03 8.15231348e+03 7.90700586e+03 7.85503906e+03 8.15598145e+03 8.04123535e+03 7.85811768e+03 7.60075488e+03 7.57478955e+03 8.05355957e+03 7.94792725e+03 7.62405273e+03 7.43167383e+03 7.34164307e+03 7.39028027e+03 7.39278760e+03 7.40798584e+03 7.19687354e+03 7.24428027e+03 7.49951318e+03 7.19061328e+03 7.27756787e+03 7.28729492e+03 7.04127051e+03 6.95387158e+03 6.86566553e+03 6.90437549e+03 6.86150879e+03 6.72765820e+03 6.68898730e+03 6.80824561e+03 6.84069824e+03 6.45421436e+03 6.33949365e+03 6.45969043e+03 6.55651562e+03 6.71127148e+03 6.49720264e+03 6.18660156e+03 6.30157324e+03 6.39486865e+03 6.24083838e+03 6.11432520e+03 6.04569141e+03 5.93481836e+03 5.88414600e+03 5.94722363e+03 5.79649023e+03 5.80930664e+03 6.01610791e+03 5.88905762e+03 5.70006738e+03 5.58014502e+03 5.52999902e+03 5.72301270e+03 5.66939062e+03 5.48627588e+03 5.30677686e+03 5.14885303e+03 5.21954004e+03 5.40605176e+03 5.49964258e+03 5.26319482e+03 5.03064941e+03 5.03293164e+03 5.01789795e+03 5.18562109e+03 5.09113135e+03 4.88785400e+03 4.81976953e+03 4.74613330e+03 4.78930029e+03 4.67555225e+03 4.63474219e+03 4.79172607e+03 4.69499512e+03 4.57459033e+03 4.42631104e+03 4.36137793e+03 4.57157129e+03 4.52117285e+03 4.32362988e+03 4.20295068e+03 4.11710742e+03 4.17917334e+03 4.17846045e+03 4.25778955e+03 4.18910498e+03 4.01384692e+03 3.85608960e+03 3.88197290e+03 4.05363159e+03 3.94296094e+03 3.80475024e+03 3.73786328e+03 3.69713940e+03 3.64749341e+03 3.57706665e+03 3.63164038e+03 3.57953809e+03 3.46141235e+03 3.54362939e+03 3.54438306e+03 3.43208740e+03 3.35501343e+03 3.29886646e+03 3.27237109e+03 3.15260352e+03 3.08383472e+03 3.20466504e+03 3.18754883e+03 2.97868262e+03 2.88968311e+03 3.00963892e+03 3.08262036e+03 2.99447998e+03 2.84318237e+03 2.74804272e+03 2.81563135e+03 2.81446558e+03 2.72417334e+03 2.69542017e+03 2.59840210e+03 2.46143799e+03 2.51982227e+03 2.63702832e+03 2.59383911e+03 2.41545166e+03 2.31530420e+03 2.41932300e+03 2.45236377e+03 2.33709106e+03 2.22606836e+03 2.16494727e+03 2.17055225e+03 2.15380762e+03 2.19864307e+03 2.16778271e+03 2.05827661e+03 2.00214771e+03 1.96579077e+03 2.00554602e+03 1.93996387e+03 1.85384619e+03 1.89815393e+03 1.86568689e+03 1.80574475e+03 1.73852136e+03 1.69714343e+03 1.76108069e+03 1.68331958e+03 1.58408289e+03 1.59509326e+03 1.59879102e+03 1.56940356e+03 1.51902307e+03 1.52656641e+03 1.50534412e+03 1.43593530e+03 1.36586865e+03 1.33424670e+03 1.38053845e+03 1.33684729e+03 1.27491357e+03 1.25482666e+03 1.22460229e+03 1.21610718e+03 1.18415906e+03 1.17214453e+03 1.13179150e+03 1.08233972e+03 1.09228284e+03 1.07464233e+03 1.03360669e+03 1.00474683e+03 9.80067322e+02 9.48444275e+02 8.97855347e+02 8.73663940e+02 8.95413696e+02 9.01903137e+02 8.34391357e+02 7.76990295e+02 7.88164001e+02 7.99327026e+02 7.66937744e+02 7.17367981e+02 6.79046326e+02 6.93445068e+02 6.74591492e+02 6.31658142e+02 6.39728821e+02 6.14471619e+02 5.64655518e+02 5.53275696e+02 5.60957031e+02 5.45635254e+02 5.03590668e+02 4.73398010e+02 4.77377930e+02 4.78833313e+02 4.50204132e+02 4.13399078e+02 3.91147583e+02 3.97423645e+02 3.87417603e+02 3.58900085e+02 3.46635559e+02 3.35290649e+02 3.16157043e+02 2.99246307e+02 2.95855835e+02 2.76889557e+02 2.55315353e+02 2.52488968e+02 2.41738037e+02 2.30312927e+02 2.13545547e+02 1.97563980e+02 1.94485931e+02 1.79917297e+02 1.65756500e+02 1.62820435e+02 1.62588120e+02 1.55826538e+02 1.31610672e+02 1.32719284e+02 1.33690201e+02 1.00133575e+02 9.57830200e+01 8.97558136e+01 8.90068741e+01 1.35371094e+02 1.29694473e+02 1.18087921e+02 1.95577347e+02 3.58435699e+02 -15570818. 247711712. 0. 0. 0. 0. -54994276. -54994276. 32267176. 11923223. 4.58289032e+02 -2.39244050e+06 -5.82414750e+06 -14737156. -15271625. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8609375. -4.29897350e+06 1.13514610e+02 1.10710861e+02 9.49249878e+01 8.52495804e+01 9.54324799e+01 1.07390556e+02 9.52578735e+01 7.51470795e+01 8.83636246e+01 8.50308838e+01 8.96881714e+01 9.71603851e+01 1.04539421e+02 1.12057068e+02 1.21425209e+02 1.28671097e+02 1.36783142e+02 1.50307968e+02 1.61351059e+02 1.69435272e+02 1.78350006e+02 1.84013718e+02 1.95972000e+02 2.13311874e+02 2.23344086e+02 2.32463394e+02 2.51246078e+02 2.71164948e+02 2.77741089e+02 2.83486115e+02 2.95823242e+02 3.07998932e+02 3.29075104e+02 3.51941711e+02 3.60818390e+02 3.74435394e+02 3.95460571e+02 4.04867157e+02 4.14408112e+02 4.33346619e+02 4.49160065e+02 4.68584961e+02 4.99690735e+02 5.10114441e+02 5.18698914e+02 5.47869385e+02 5.60583252e+02 5.72822021e+02 5.94566956e+02 6.15386353e+02 6.42052979e+02 6.68229370e+02 6.96596802e+02 7.06817383e+02 7.13759644e+02 7.46972839e+02 7.52485840e+02 7.65570435e+02 8.16853699e+02 8.36314392e+02 8.52686890e+02 8.90524902e+02 9.10773376e+02 9.17182068e+02 9.40252869e+02 9.61414062e+02 9.85601990e+02 1.02624841e+03 1.05560461e+03 1.08276453e+03 1.10909436e+03 1.12720850e+03 1.15239294e+03 1.17710754e+03 1.21061780e+03 1.23225330e+03 1.26244519e+03 1.32641553e+03 1.32747717e+03 1.30337207e+03 1.35959253e+03 1.39273975e+03 1.41404077e+03 1.48334814e+03 1.49359546e+03 1.50581616e+03 1.57760779e+03 1.63030701e+03 1.61884851e+03 1.60672913e+03 1.63692957e+03 1.68482532e+03 1.74684485e+03 1.78539624e+03 1.82358679e+03 1.86307812e+03 1.88332605e+03 1.88661682e+03 1.89031689e+03 1.96881445e+03 2.01176062e+03 2.00564392e+03 2.08063550e+03 2.11371558e+03 2.12898096e+03 2.19379712e+03 2.19374292e+03 2.19026099e+03 2.24682007e+03 2.33231641e+03 2.38643457e+03 2.39189478e+03 2.43075684e+03 2.48625977e+03 2.52645166e+03 2.54920288e+03 2.52899121e+03 2.54473315e+03 2.68375342e+03 2.72461377e+03 2.68951270e+03 2.76241479e+03 2.77394995e+03 2.79393701e+03 2.89786108e+03 2.92736426e+03 2.91041089e+03 2.97717896e+03 3.09389014e+03 3.13798242e+03 3.13192114e+03 3.07545215e+03 3.11042871e+03 3.25583667e+03 3.32327319e+03 3.27962476e+03 3.33868994e+03 3.47065039e+03 3.49729541e+03 3.50910596e+03 3.51851318e+03 3.47326196e+03 3.50220654e+03 3.60188989e+03 3.72249561e+03 3.75204517e+03 3.76097192e+03 3.86756567e+03 3.90017676e+03 3.86977246e+03 3.88268774e+03 3.93717896e+03 4.00295923e+03 4.10711523e+03 4.22393945e+03 4.22598242e+03 4.21737695e+03 4.18290674e+03 4.30952002e+03 4.37321338e+03 4.26685400e+03 4.31353613e+03 4.50397168e+03 4.63380908e+03 4.52881836e+03 4.53258008e+03 4.57133594e+03 4.60611475e+03 4.74653320e+03 4.88534082e+03 4.89957764e+03 4.86798438e+03 4.92270898e+03 4.99507227e+03 4.96195166e+03 4.99851465e+03 5.06536328e+03 5.10252979e+03 5.29688330e+03 5.39671875e+03 5.22027734e+03 5.25545557e+03 5.35107715e+03 5.42490576e+03 5.57026953e+03 5.40073828e+03 5.40155225e+03 5.70279346e+03 5.78945654e+03 5.70370117e+03 5.70499902e+03 5.76115625e+03 5.77000537e+03 5.86610010e+03 6.03553027e+03 6.05501562e+03 5.96278955e+03 6.09970801e+03 6.30571924e+03 6.20960986e+03 6.19419385e+03 6.22127295e+03 6.26208252e+03 6.49729004e+03 6.44440332e+03 6.41810449e+03 6.63946533e+03 6.48847168e+03 6.51093555e+03 6.71125342e+03 6.61472705e+03 6.67390088e+03 6.89161963e+03 6.93584082e+03 6.97199023e+03 6.90587500e+03 7.02084082e+03 6.99419873e+03 7.01064697e+03 7.25509766e+03 7.10678125e+03 7.09647607e+03 7.34429297e+03 7.43649609e+03 7.36506787e+03 7.48444141e+03 7.60881592e+03 7.44594043e+03 7.62213672e+03 7.88378418e+03 7.62397363e+03 7.57251904e+03 7.71939307e+03 7.80042676e+03 7.75917773e+03 7.80192432e+03 7.90660156e+03 8.03559863e+03 8.17741846e+03 8.20059863e+03 8.12602246e+03 8.17542285e+03 8.20081152e+03 8.19909668e+03 8.43500586e+03 8.30748730e+03 8.35052148e+03 8.64666797e+03 8.50613867e+03 8.45792773e+03 8.60284277e+03 8.64958398e+03 8.58841406e+03 8.67821094e+03 8.82206055e+03 8.94723340e+03 8.94599512e+03 8.92284766e+03 9.05756641e+03 8.90343262e+03 8.93881348e+03 9.05613672e+03 8.98890137e+03 9.30634668e+03 9.51664453e+03 9.25320605e+03 9.16728223e+03 9.30452832e+03 9.64895215e+03 9.58090137e+03 9.19951855e+03 9.51984766e+03 9.85393359e+03 9.63917188e+03 9.60097559e+03 9.64037988e+03 9.71514062e+03 9.79189941e+03 9.80793359e+03 9.75160840e+03 1.00768398e+04 1.01146113e+04 9.98355664e+03 1.01776924e+04 1.02235859e+04 1.01641504e+04 1.01884844e+04 9.92322559e+03 1.02819678e+04 1.06707715e+04 1.02645430e+04 1.02235039e+04 1.03955947e+04 1.05311807e+04 1.06196455e+04 1.04124668e+04 1.06239824e+04 1.08582793e+04 1.07602695e+04 1.07772402e+04 1.07083984e+04 1.06402676e+04 1.07972070e+04 1.09474580e+04 1.08988691e+04 1.10471680e+04 1.11416211e+04 1.10342754e+04 1.12051807e+04 1.12276709e+04 1.10513203e+04 1.10557363e+04 1.12854961e+04 1.14451533e+04 1.12385732e+04 1.11559355e+04 1.12105674e+04 1.13804336e+04 1.15874590e+04 1.15538994e+04 1.13593506e+04 1.14179238e+04 1.16729385e+04 1.19334014e+04 1.17380596e+04 1.14071484e+04 1.16324561e+04 1.18335859e+04 1.17193652e+04 1.17845605e+04 1.19621592e+04 1.19783350e+04 1.19093135e+04 1.21000352e+04 1.21806328e+04 1.19875098e+04 1.19586406e+04 1.20500342e+04 1.21842783e+04 1.19361914e+04 1.18200088e+04 1.21482900e+04 1.23355547e+04 1.24698730e+04 1.23539893e+04 1.21511230e+04 1.24742803e+04 1.26158125e+04 1.22296299e+04 1.21893906e+04 1.24795488e+04 1.27108955e+04 1.26545723e+04 1.23634922e+04 1.22662617e+04 1.24382861e+04 1.27627158e+04 1.29405566e+04 1.29834580e+04 1.26868857e+04 1.24846025e+04 1.26427275e+04 1.26077803e+04 1.26589502e+04 1.27794229e+04 1.27941143e+04 1.29208623e+04 1.28933877e+04 1.28560703e+04 1.28243574e+04 1.29411680e+04 1.33279502e+04 1.31858330e+04 1.27644863e+04 1.27736904e+04 1.30370088e+04 1.32160869e+04 1.33499307e+04 1.32341846e+04 1.27927168e+04 1.28031621e+04 1.32269580e+04 1.34521318e+04 1.34721660e+04 1.32519023e+04 1.30100527e+04 1.32000703e+04 1.32582070e+04 1.33376543e+04 1.32700137e+04 1.29624424e+04 1.33739170e+04 1.36593945e+04 1.33777578e+04 1.31623252e+04 1.29633232e+04 1.32770928e+04 1.39377725e+04 1.37912744e+04 1.32209678e+04 1.34458906e+04 1.38194111e+04 1.34080352e+04 1.32699346e+04 1.31726162e+04 1.32565752e+04 1.38055918e+04 1.36725781e+04 1.32386416e+04 1.34973633e+04 1.37857012e+04 1.36035527e+04 1.35613789e+04 1.36811973e+04 1.35920186e+04 1.34780801e+04 1.36356875e+04 1.35452881e+04 1.36957373e+04 1.38171318e+04 1.37191904e+04 1.37455908e+04 1.33893438e+04 1.34941895e+04 1.36775029e+04 1.36045361e+04 1.37679414e+04 1.38829355e+04 1.38817559e+04 1.35576240e+04 1.34581406e+04 1.36839053e+04 1.37997744e+04 1.37566221e+04 1.35862266e+04 1.36557520e+04 1.37631641e+04 1.36636035e+04 1.37445771e+04 1.37018359e+04 1.34575938e+04 1.36190547e+04 1.37210771e+04 1.35810381e+04 1.37709893e+04 1.36577910e+04 1.34982451e+04 1.39163662e+04 1.39997178e+04 1.35048994e+04 1.33687871e+04 1.36925342e+04 1.39807461e+04 1.39129395e+04 1.34978896e+04 1.33853086e+04 1.35425771e+04 1.36935146e+04 1.36682646e+04 1.34869307e+04 1.35748701e+04 1.36515566e+04 1.35242354e+04 1.36652939e+04 1.36619043e+04 1.35760898e+04 1.37076270e+04 1.35989404e+04 1.35579189e+04 1.34664238e+04 1.34307588e+04 1.35484307e+04 1.35523203e+04 1.35824092e+04 1.33938525e+04 1.32645732e+04 1.35545586e+04 1.35804082e+04 1.35044932e+04 1.35058535e+04 1.31989385e+04 1.32319238e+04 1.35756934e+04 1.34262061e+04 1.31246641e+04 1.34569668e+04 1.34733779e+04 1.30365879e+04 1.33945205e+04 1.33967021e+04 1.30238896e+04 1.33715674e+04 1.34432666e+04 1.30578311e+04 1.30610332e+04 1.32521299e+04 1.31488105e+04 1.31786211e+04 1.31191836e+04 1.27748379e+04 1.29140332e+04 1.32176104e+04 1.32138506e+04 1.31622344e+04 1.29472041e+04 1.29448516e+04 1.28620293e+04 1.26514121e+04 1.29606230e+04 1.30028809e+04 1.26977324e+04 1.29247314e+04 1.29069209e+04 1.25703174e+04 1.28006201e+04 1.28945820e+04 1.28047041e+04 1.27450674e+04 1.25024844e+04 1.23519727e+04 1.27349980e+04 1.29861299e+04 1.25674814e+04 1.24931475e+04 1.23480088e+04 1.23635498e+04 1.27136797e+04 1.23674619e+04 1.21322705e+04 1.23785371e+04 1.25053242e+04 1.23448848e+04 1.19608271e+04 1.22298066e+04 1.24356309e+04 1.21743145e+04 1.22112842e+04 1.20087764e+04 1.19923867e+04 1.22278916e+04 1.21415830e+04 1.21993760e+04 1.19009541e+04 1.17548809e+04 1.19027275e+04 1.18409111e+04 1.19872783e+04 1.18460645e+04 1.15683506e+04 1.16778643e+04 1.18521689e+04 1.17828936e+04 1.16321934e+04 1.16053076e+04 1.15737480e+04 1.15938896e+04 1.14957246e+04 1.12794062e+04 1.15666191e+04 1.15070039e+04 1.13407383e+04 1.15259707e+04 1.13069404e+04 1.10874043e+04 1.13206436e+04 1.10967139e+04 1.10092314e+04 1.12566182e+04 1.10685195e+04 1.08981406e+04 1.09242705e+04 1.09793516e+04 1.09528145e+04 1.10935059e+04 1.09051650e+04 1.07135225e+04 1.07406973e+04 1.05628291e+04 1.06164717e+04 1.06146445e+04 1.06633359e+04 1.07475469e+04 1.03998936e+04 1.05205576e+04 1.04936836e+04 1.02285840e+04 1.03242637e+04 1.03528711e+04 1.04318965e+04 1.02611533e+04 1.00878281e+04 1.02265010e+04 1.01339102e+04 1.00290889e+04 9.97433691e+03 9.97325488e+03 1.01192148e+04 9.92003809e+03 9.82659863e+03 9.91622266e+03 9.68640039e+03 9.58684570e+03 9.81538672e+03 9.81990430e+03 9.48607617e+03 9.53139258e+03 9.44349316e+03 9.28695996e+03 9.73260645e+03 9.50972852e+03 9.21855078e+03 9.67542871e+03 9.49081641e+03 9.18028027e+03 9.18155273e+03 1.16957451e+04 1.25383535e+04 2.27315645e+04 2.67803730e+04 1.07761112e+06 -5.08126950e+06 3.06350950e+06 -3.74683325e+06 5842296. -53043152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 40084008. -16955768. 1.73686638e+06 7.42091850e+06 4.18928675e+06 2.27267305e+04 1.78085996e+04 1.06664082e+04 8.21282910e+03 8.60734473e+03 7.14475098e+03 6.46222363e+03 6.33060547e+03 6.43942529e+03 6.31858643e+03 6.20719775e+03 6.13735205e+03 6.16333887e+03 6.19628320e+03 6.14705273e+03 5.96177441e+03 5.78452734e+03 5.93241748e+03 5.96502344e+03 5.84165039e+03 5.83177734e+03 5.63413574e+03 5.57793799e+03 5.61839307e+03 5.61490234e+03 5.59855225e+03 5.35931250e+03 5.24518408e+03 5.47847070e+03 5.56013330e+03 5.36372803e+03 5.06143652e+03 5.03233643e+03 5.18061279e+03 5.17563086e+03 5.04070947e+03 4.89967969e+03 4.98570215e+03 5.03907275e+03 4.93222168e+03 4.85650146e+03 4.61315625e+03 4.66686133e+03 4.84567090e+03 4.70316846e+03 4.62094141e+03 4.54084717e+03 4.38671045e+03 4.44220605e+03 4.54720312e+03 4.43590723e+03 4.23337354e+03 4.29708057e+03 4.29691260e+03 4.19503369e+03 4.17637939e+03 4.02985474e+03 4.09058521e+03 4.08777417e+03 3.96500903e+03 3.87442773e+03 3.79141724e+03 3.85310596e+03 3.92735107e+03 3.84601074e+03 3.72636401e+03 3.60816406e+03 3.60841284e+03 3.58110107e+03 3.59016479e+03 3.57308008e+03 3.41012231e+03 3.40756860e+03 3.44881812e+03 3.38287720e+03 3.31467407e+03 3.18124341e+03 3.19005566e+03 3.25270874e+03 3.19944849e+03 3.11068750e+03 2.99734570e+03 2.96944971e+03 3.00766162e+03 3.01144165e+03 2.89608081e+03 2.79374951e+03 2.85710474e+03 2.80930664e+03 2.73452466e+03 2.76708960e+03 2.65672070e+03 2.62029492e+03 2.63838062e+03 2.57898413e+03 2.55631567e+03 2.45964429e+03 2.37598413e+03 2.41278320e+03 2.42625806e+03 2.38809375e+03 2.29626538e+03 2.25648535e+03 2.23682495e+03 2.20947461e+03 2.17704175e+03 2.08889844e+03 2.08272852e+03 2.11660425e+03 2.06303223e+03 1.96802661e+03 1.89168579e+03 1.91366772e+03 1.97002490e+03 1.91542578e+03 1.83130261e+03 1.75133398e+03 1.72828906e+03 1.73665845e+03 1.72812024e+03 1.71107288e+03 1.62481189e+03 1.58689929e+03 1.56873389e+03 1.54748438e+03 1.55342505e+03 1.47097205e+03 1.43789172e+03 1.45611230e+03 1.40498596e+03 1.36268506e+03 1.33160266e+03 1.31295715e+03 1.30725171e+03 1.27164575e+03 1.21514209e+03 1.16468677e+03 1.17491016e+03 1.19407666e+03 1.14924341e+03 1.09388257e+03 1.04639172e+03 1.03178979e+03 1.02910413e+03 1.01311664e+03 9.87258484e+02 9.24411072e+02 8.97875183e+02 8.99422668e+02 8.93813110e+02 8.76779846e+02 8.35666443e+02 8.01562378e+02 7.72545105e+02 7.61597412e+02 7.53214417e+02 7.17176147e+02 6.96666504e+02 6.82869934e+02 6.60739197e+02 6.44842224e+02 6.10624329e+02 5.97138672e+02 5.90749390e+02 5.61121521e+02 5.46899048e+02 5.21693787e+02 5.03330475e+02 4.93679688e+02 4.76501373e+02 4.56527802e+02 4.25469910e+02 4.13389160e+02 4.10890564e+02 4.00934387e+02 3.80759613e+02 3.49062500e+02 3.32602325e+02 3.28942352e+02 3.20092377e+02 3.03686737e+02 2.79407959e+02 2.68825592e+02 2.61450226e+02 2.48406830e+02 2.39075989e+02 2.20218109e+02 2.07928024e+02 2.02641388e+02 1.92562714e+02 1.79569092e+02 1.65607849e+02 1.56870056e+02 1.47208206e+02 1.38315628e+02 1.32268890e+02 1.20051430e+02 1.10850258e+02 1.04054054e+02 9.57509003e+01 8.80172348e+01 8.12589569e+01 7.64056244e+01 7.02780991e+01 6.31014099e+01 5.58087387e+01 4.88587189e+01 4.54285469e+01 4.24809952e+01 3.73648872e+01 3.23233147e+01 2.76220207e+01 2.40604992e+01 2.16642551e+01 1.94491348e+01 1.67640667e+01 1.42626848e+01 1.24170399e+01 1.09618435e+01 9.79386330e+00 8.93645954e+00 8.41665936e+00 8.26539898e+00 8.46228027e+00 8.99574947e+00 9.83677292e+00 1.08681231e+01 1.24248943e+01 1.42926931e+01 1.62314415e+01 1.89460945e+01 2.18364792e+01 2.53466988e+01 2.89484348e+01 3.17736721e+01 3.56450424e+01 4.05925827e+01 4.68768578e+01 5.35984230e+01 5.79127808e+01 6.10059395e+01 6.57462997e+01 7.36133118e+01 8.38896790e+01 9.28762894e+01 9.92066650e+01 1.01483368e+02 1.08960388e+02 1.24742073e+02 1.33501984e+02 1.35974777e+02 1.44163742e+02 1.57659592e+02 1.68495987e+02 1.83764709e+02 1.90848160e+02 1.94645599e+02 2.11989685e+02 2.19999161e+02 2.35295013e+02 2.54568069e+02 2.55956161e+02 2.72129761e+02 2.93942261e+02 3.02857422e+02 3.15428009e+02 3.28675110e+02 3.44863129e+02 3.63809723e+02 3.73559662e+02 3.77603180e+02 3.96663971e+02 4.31748138e+02 4.59713379e+02 4.65913940e+02 4.63473633e+02 4.69363556e+02 4.94676331e+02 5.35033386e+02 5.72235229e+02 5.77336060e+02 5.68160645e+02 5.87777161e+02 6.27130737e+02 6.45650330e+02 6.52807617e+02 6.75131775e+02 7.01265869e+02 7.24008728e+02 7.65399841e+02 7.70522522e+02 7.73224609e+02 8.10470276e+02 8.06716370e+02 8.51247131e+02 9.06705750e+02 9.00738037e+02 9.46638550e+02 9.61797302e+02 9.45023193e+02 9.97621887e+02 1.00032642e+03 1.03736523e+03 1.13962012e+03 1.10893579e+03 1.07390674e+03 1.12865283e+03 1.20656348e+03 1.27137585e+03 1.26834875e+03 1.23473376e+03 1.23536536e+03 1.27938489e+03 1.36215369e+03 1.44032739e+03 1.44343628e+03 1.39798706e+03 1.41406519e+03 1.50127087e+03 1.54855249e+03 1.53810193e+03 1.55484839e+03 1.60792957e+03 1.63695215e+03 1.72421558e+03 1.76282214e+03 1.69787878e+03 1.72796216e+03 1.79214478e+03 1.82641333e+03 1.87539673e+03 1.90164111e+03 1.97242126e+03 1.96784558e+03 1.93465344e+03 2.02709717e+03 2.00511047e+03 2.09548145e+03 2.26700146e+03 2.16739990e+03 2.07484790e+03 2.17935156e+03 2.32307471e+03 2.41327881e+03 2.45205176e+03 2.34653027e+03 2.28700635e+03 2.38561060e+03 2.54636230e+03 2.67858838e+03 2.65073804e+03 2.53257349e+03 2.54622559e+03 2.66716943e+03 2.74258032e+03 2.82456958e+03 2.86070801e+03 2.75956885e+03 2.79169800e+03 2.94607007e+03 3.00934448e+03 2.98314575e+03 3.00767188e+03 3.02375488e+03 3.05513037e+03 3.22300293e+03 3.30879712e+03 3.21101318e+03 3.21265747e+03 3.24472852e+03 3.28109644e+03 3.39647778e+03 3.43201733e+03 3.57627783e+03 3.61046094e+03 3.51378540e+03 3.49266553e+03 3.49722266e+03 3.69226978e+03 3.91900439e+03 3.87731836e+03 3.73984790e+03 3.66643774e+03 3.87546313e+03 4.14383203e+03 3.98099585e+03 3.83113599e+03 3.97513940e+03 4.12631689e+03 4.26493701e+03 4.40667480e+03 4.37834473e+03 4.16227051e+03 4.14422266e+03 4.37782178e+03 4.48706152e+03 4.52133984e+03 4.53180127e+03 4.55748877e+03 4.56396143e+03 4.72031641e+03 4.67936035e+03 4.61014307e+03 4.68834375e+03 4.78275781e+03 5.00893018e+03 5.05203955e+03 4.95065771e+03 5.07532715e+03 5.08698584e+03 5.12800977e+03 5.08134814e+03 4.97233057e+03 5.29811816e+03 5.59663330e+03 5.41284912e+03 5.21925879e+03 5.28003564e+03 5.61428955e+03 5.72661133e+03 5.68128125e+03 5.61598926e+03 5.51010596e+03 5.56698389e+03 5.83304639e+03 5.88986035e+03 5.81796582e+03 5.72448926e+03 5.72533594e+03 6.07086377e+03 6.43301660e+03 6.14217236e+03 5.96415771e+03 6.17675049e+03 6.24277490e+03 6.46589941e+03 6.49454297e+03 6.13177490e+03 6.25316162e+03 6.52547363e+03 6.53277002e+03 6.59768457e+03 6.77421777e+03 6.59303564e+03 7.24058643e+03 7.28831055e+03 6.77622510e+03 7.79953662e+03 8.25014551e+03 1.88595977e+04 1.22061104e+04 2.08009785e+04 2.13900781e+04 2788980. 2.71868475e+06 -10862900. 1.99332962e+06 4.31715950e+06 -1.57832712e+06 -16059672. 12998406. 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. 0. -400063488. -400063488. -400063488. 0. 0. 140856864. -2.52312950e+06 -1.49443050e+06 2.71786504e+04 2.29087168e+04 1.56351777e+04 1.52124785e+04 1.25587002e+04 1.22837051e+04 1.00535605e+04 1.00233945e+04 9.82569531e+03 9.57536914e+03 9.86115918e+03 9.96048047e+03 9.74759082e+03 9.85655371e+03 9.95898438e+03 9.90600781e+03 9.96273340e+03 9.92924609e+03 9.92579297e+03 1.00085811e+04 1.00482900e+04 1.02035547e+04 1.03054961e+04 9.97142676e+03 1.00278145e+04 1.05322803e+04 1.05871816e+04 1.04509326e+04 1.04792656e+04 1.04810400e+04 1.05453115e+04 1.05474873e+04 1.06225801e+04 1.06373916e+04 1.06604717e+04 1.05809395e+04 1.05544297e+04 1.09756807e+04 1.11053389e+04 1.08847217e+04 1.08674814e+04 1.09459111e+04 1.10444863e+04 1.10191719e+04 1.10590664e+04 1.11134404e+04 1.09469150e+04 1.09262061e+04 1.11194658e+04 1.11283359e+04 1.16161338e+04 1.16696074e+04 1.13140938e+04 1.10868135e+04 1.10716523e+04 1.17680947e+04 1.19025273e+04 1.15725117e+04 1.13335430e+04 1.13810195e+04 1.16658379e+04 1.16760029e+04 1.19719922e+04 1.20574658e+04 1.14183613e+04 1.12575020e+04 1.19118096e+04 1.24804893e+04 1.21277412e+04 1.19204541e+04 1.19322520e+04 1.19095811e+04 1.19391396e+04 1.20319775e+04 1.20422803e+04 1.19865996e+04 1.21274629e+04 1.21855684e+04 1.21629375e+04 1.21585986e+04 1.25645596e+04 1.26374307e+04 1.23292695e+04 1.22688926e+04 1.23085781e+04 1.25792881e+04 1.26305410e+04 1.24504297e+04 1.25246787e+04 1.22710977e+04 1.21312598e+04 1.27354463e+04 1.27021514e+04 1.21039150e+04 1.22854658e+04 1.30180010e+04 1.34916992e+04 1.30811592e+04 1.27057471e+04 1.26213281e+04 1.26403389e+04 1.27649307e+04 1.27745723e+04 1.27925889e+04 1.27999453e+04 1.32304219e+04 1.32791064e+04 1.29060303e+04 1.29243574e+04 1.25939639e+04 1.27223105e+04 1.35131846e+04 1.34098750e+04 1.31311611e+04 1.28632422e+04 1.26682002e+04 1.33677285e+04 1.36544424e+04 1.32680264e+04 1.28909277e+04 1.28760693e+04 1.32051719e+04 1.32038340e+04 1.36541953e+04 1.37708936e+04 1.33015469e+04 1.31502041e+04 1.31839512e+04 1.35316875e+04 1.35754404e+04 1.33679775e+04 1.33405820e+04 1.33572969e+04 1.33179600e+04 1.29973848e+04 1.31981816e+04 1.39191348e+04 1.37682754e+04 1.34789346e+04 1.31772227e+04 1.31327773e+04 1.39072109e+04 1.38993047e+04 1.35286602e+04 1.32221465e+04 1.31899170e+04 1.36414219e+04 1.35518760e+04 1.36046436e+04 1.33045723e+04 1.35009385e+04 1.43782139e+04 1.40422744e+04 1.36009619e+04 1.36721543e+04 1.37104248e+04 1.36188691e+04 1.36167568e+04 1.35359785e+04 1.35252031e+04 1.35976074e+04 1.32580762e+04 1.34795283e+04 1.42854580e+04 1.37395977e+04 1.32783271e+04 1.36596816e+04 1.36518213e+04 1.40586201e+04 1.38830059e+04 1.33510781e+04 1.39265850e+04 1.40475322e+04 1.37085332e+04 1.36194199e+04 1.36014873e+04 1.36615781e+04 1.36942363e+04 1.35314863e+04 1.31689316e+04 1.35982090e+04 1.43533115e+04 1.40855723e+04 1.37264131e+04 1.33464531e+04 1.32597676e+04 1.40046904e+04 1.41354746e+04 1.37740586e+04 1.33441367e+04 1.32309941e+04 1.36565137e+04 1.36961904e+04 1.39656504e+04 1.37580938e+04 1.33740254e+04 1.34962188e+04 1.34787715e+04 1.39652227e+04 1.39121572e+04 1.34386562e+04 1.35491494e+04 1.35904453e+04 1.34653926e+04 1.30680615e+04 1.34088203e+04 1.42032910e+04 1.38029873e+04 1.34599619e+04 1.31834697e+04 1.30606123e+04 1.38279707e+04 1.38480645e+04 1.34702139e+04 1.31442734e+04 1.30265068e+04 1.34466426e+04 1.33975859e+04 1.36898516e+04 1.36141982e+04 1.32218428e+04 1.31154717e+04 1.30249111e+04 1.36250781e+04 1.35872783e+04 1.32096777e+04 1.31130625e+04 1.30345029e+04 1.34913623e+04 1.35033799e+04 1.28550674e+04 1.28156729e+04 1.34942598e+04 1.34988984e+04 1.28025732e+04 1.27084697e+04 1.33554863e+04 1.34571377e+04 1.29951367e+04 1.26416318e+04 1.26612520e+04 1.33199277e+04 1.31228750e+04 1.27446807e+04 1.29864053e+04 1.29727305e+04 1.27786504e+04 1.26468145e+04 1.26864746e+04 1.23724932e+04 1.26885068e+04 1.33813164e+04 1.29643125e+04 1.27437061e+04 1.27785400e+04 1.26450029e+04 1.26096025e+04 1.26026553e+04 1.25734756e+04 1.22152393e+04 1.20312637e+04 1.23195039e+04 1.25398662e+04 1.28419102e+04 1.24244365e+04 1.19693965e+04 1.22902256e+04 1.23986133e+04 1.27288242e+04 1.25884287e+04 1.21865264e+04 1.19391592e+04 1.18096143e+04 1.21091699e+04 1.21271211e+04 1.23077568e+04 1.23285273e+04 1.20442070e+04 1.17430967e+04 1.14028994e+04 1.18122412e+04 1.23846025e+04 1.22288008e+04 1.18567324e+04 1.14958555e+04 1.12959453e+04 1.18440781e+04 1.21439121e+04 1.17572656e+04 1.12991221e+04 1.12766104e+04 1.15341699e+04 1.15044688e+04 1.17412295e+04 1.17430654e+04 1.14284814e+04 1.12191396e+04 1.11191709e+04 1.14858975e+04 1.15031660e+04 1.09316846e+04 1.08776914e+04 1.14303506e+04 1.13002471e+04 1.06831367e+04 1.08193223e+04 1.13373438e+04 1.12241279e+04 1.09455547e+04 1.06151719e+04 1.05217119e+04 1.11302197e+04 1.11051572e+04 1.07459092e+04 1.04015049e+04 1.02899121e+04 1.05309258e+04 1.05649688e+04 1.05409688e+04 1.02081328e+04 1.04188447e+04 1.08677119e+04 1.05388789e+04 1.04540693e+04 1.03907422e+04 1.02468682e+04 1.02115039e+04 1.01700557e+04 1.01354678e+04 1.00339648e+04 9.89182715e+03 9.65925586e+03 9.84922559e+03 1.02220371e+04 9.81534570e+03 9.47458691e+03 9.72124902e+03 9.80452148e+03 1.00572471e+04 9.84418555e+03 9.52104883e+03 9.67044043e+03 9.57075684e+03 9.26398047e+03 9.20826270e+03 9.53828906e+03 9.47518652e+03 9.22770801e+03 9.04138379e+03 8.75026367e+03 9.05328711e+03 9.61674023e+03 9.36219434e+03 8.95722168e+03 8.76624902e+03 8.64613867e+03 9.03054004e+03 9.19856250e+03 8.87108105e+03 8.57420996e+03 8.47931055e+03 8.56767480e+03 8.54112500e+03 8.78166309e+03 8.70044629e+03 8.39637207e+03 8.39068359e+03 8.31488867e+03 8.47156738e+03 8.43622363e+03 8.26770020e+03 8.08944580e+03 8.05846680e+03 8.07255713e+03 7.85859473e+03 7.83358496e+03 8.18627100e+03 8.01994238e+03 7.87764404e+03 7.63365576e+03 7.52291699e+03 7.94573389e+03 7.91805957e+03 7.60564014e+03 7.42719678e+03 7.37457910e+03 7.37040771e+03 7.33363721e+03 7.35608838e+03 7.16120557e+03 7.28722803e+03 7.53142383e+03 7.23674609e+03 7.24483936e+03 7.22930957e+03 7.07555859e+03 6.97969580e+03 6.83981055e+03 6.86654297e+03 6.85807422e+03 6.80011719e+03 6.74414014e+03 6.77295752e+03 6.80337891e+03 6435. 6.30337939e+03 6.46863672e+03 6.53541260e+03 6.66207910e+03 6.46778223e+03 6.22632715e+03 6.37652148e+03 6.31053418e+03 6.10360156e+03 6.14229834e+03 6.06771777e+03 5.98098340e+03 5.91026074e+03 5.95216650e+03 5.76978906e+03 5.84965967e+03 6.02474072e+03 5.85510303e+03 5.74216260e+03 5.60070654e+03 5.47598730e+03 5.66511426e+03 5.68107666e+03 5.49660205e+03 5.30645166e+03 5.15730371e+03 5.27732227e+03 5.34772217e+03 5.43184961e+03 5.24785352e+03 5.02932422e+03 5.07768066e+03 5.01050342e+03 5.16323730e+03 5.09149756e+03 4.86463770e+03 4.82243213e+03 4.75091943e+03 4.77995264e+03 4.63181885e+03 4.65634131e+03 4.83707373e+03 4.69595508e+03 4.59371094e+03 4.42727637e+03 4.32135645e+03 4.56225586e+03 4.49239404e+03 4.30078223e+03 4.19029736e+03 4.12277246e+03 4.19337695e+03 4.16775342e+03 4.22250439e+03 4.17196240e+03 4.02025146e+03 3.88303320e+03 3.83387183e+03 4.01387744e+03 3.92097754e+03 3.77072437e+03 3.76865894e+03 3.72940137e+03 3.65777271e+03 3.58923315e+03 3.65104858e+03 3.53956274e+03 3.42542480e+03 3.56485767e+03 3.55504175e+03 3.40339600e+03 3.32655811e+03 3.30433130e+03 3.27839624e+03 3.13515112e+03 3.07084399e+03 3.21303882e+03 3.17970020e+03 2.95479810e+03 2.87949805e+03 3.01770898e+03 3.10053418e+03 2.96218213e+03 2.81750879e+03 2.77411206e+03 2.83733569e+03 2.78392383e+03 2.68827368e+03 2.69863403e+03 2.60306641e+03 2.48101758e+03 2.54872339e+03 2.62660303e+03 2.57202295e+03 2.42374243e+03 2.32917920e+03 2.42672778e+03 2.44812695e+03 2.32365674e+03 2.22871460e+03 2.19455884e+03 2.18904248e+03 2.15039795e+03 2.19141479e+03 2.13275366e+03 2.01383398e+03 2.03056140e+03 2.00012866e+03 1.99587500e+03 1.92000208e+03 1.84038708e+03 1.88782690e+03 1.86337903e+03 1.79606775e+03 1.72706970e+03 1.70534521e+03 1.76770325e+03 1.68408679e+03 1.59708704e+03 1.60193127e+03 1.57378235e+03 1.54851147e+03 1.51698108e+03 1.52349695e+03 1.50211462e+03 1.43229114e+03 1.36132739e+03 1.33292468e+03 1.37467505e+03 1.33265076e+03 1.26673145e+03 1.25612012e+03 1.23397229e+03 1.20884558e+03 1.17668738e+03 1.17247327e+03 1.11883691e+03 1.06666284e+03 1.08906738e+03 1.06490576e+03 1.02700549e+03 1.00265833e+03 9.76641296e+02 9.49807556e+02 9.02128967e+02 8.69179932e+02 8.92621033e+02 8.89103943e+02 8.23202454e+02 7.76898376e+02 7.88538574e+02 7.96273132e+02 7.56518188e+02 7.09139526e+02 6.77280457e+02 6.87223511e+02 6.72325134e+02 6.33755432e+02 6.30615723e+02 6.11923279e+02 5.73588074e+02 5.52272339e+02 5.49737915e+02 5.39092834e+02 4.99739136e+02 4.73465210e+02 4.79225677e+02 4.70282074e+02 4.41500946e+02 4.08960175e+02 3.90003723e+02 3.97037231e+02 3.84162292e+02 3.55727173e+02 3.39358978e+02 3.26600098e+02 3.10609009e+02 2.95399597e+02 2.93359772e+02 2.73265930e+02 2.51445999e+02 2.51527039e+02 2.40364548e+02 2.25624466e+02 2.09201324e+02 1.94336166e+02 1.91169907e+02 1.77910629e+02 1.65149963e+02 1.60335205e+02 1.55466843e+02 1.46550476e+02 1.24088280e+02 1.23434006e+02 1.21428818e+02 9.12712250e+01 9.02786713e+01 9.09253159e+01 8.63860245e+01 1.11082901e+02 7.95765915e+01 7.31773682e+01 1.02144150e+02 1.44420929e+02 2917101. -4.46943950e+06 0. 0. 0. 0. -54994276. -54994276. 32267176. -30224724. 8.82142375e+05 4621649. 4621649. 8468770. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8609375. -4.29897350e+06 -6.21338650e+06 20989598. -2.94700025e+06 2.26855423e+02 1.63311615e+02 8.42965240e+01 7.67738342e+01 1.13408432e+02 8.81363068e+01 8.20303802e+01 8.93465271e+01 9.56269302e+01 1.03048950e+02 1.12802559e+02 1.19324493e+02 1.26470200e+02 1.35702576e+02 1.43769821e+02 1.56066452e+02 1.71318207e+02 1.81352661e+02 1.85651886e+02 1.95093445e+02 2.08411148e+02 2.16333374e+02 2.30462082e+02 2.49122604e+02 2.59878510e+02 2.73327271e+02 2.87836914e+02 2.95268311e+02 3.07835388e+02 3.25186035e+02 3.37794189e+02 3.50904175e+02 3.75210205e+02 3.96563171e+02 4.02561432e+02 4.16643921e+02 4.36349884e+02 4.53105682e+02 4.73163940e+02 4.86213593e+02 4.93044250e+02 5.22296814e+02 5.57130981e+02 5.56354858e+02 5.69252380e+02 6.02788208e+02 6.07999756e+02 6.30627441e+02 6.71923889e+02 6.80509705e+02 6.93614929e+02 7.27437378e+02 7.65749146e+02 7.66518799e+02 7.66930603e+02 7.91192261e+02 8.15824280e+02 8.64583984e+02 9.01857483e+02 9.04668518e+02 9.18169922e+02 9.41558167e+02 9.62837219e+02 9.94463257e+02 1.01339532e+03 1.02441870e+03 1.07299353e+03 1.12875903e+03 1.13327539e+03 1.14260352e+03 1.18908276e+03 1.20462292e+03 1.22325732e+03 1.26619714e+03 1.29632837e+03 1.30971094e+03 1.32715039e+03 1.38175806e+03 1.40726733e+03 1.43091528e+03 1.46346082e+03 1.45275464e+03 1.51535205e+03 1.59139807e+03 1.58259229e+03 1.59798145e+03 1.63685400e+03 1.66862549e+03 1.71323999e+03 1.72624500e+03 1.72166858e+03 1.80752502e+03 1.88749780e+03 1.88636438e+03 1.87027332e+03 1.90648413e+03 1.98671826e+03 2.01572144e+03 2.02123816e+03 2.04883545e+03 2.06632812e+03 2.15150903e+03 2.23333179e+03 2.20074121e+03 2.19750391e+03 2.23067261e+03 2.27856348e+03 2.35510767e+03 2.41924829e+03 2.41707764e+03 2.44779272e+03 2.54955762e+03 2.59051587e+03 2.55178760e+03 2.54033154e+03 2.59890137e+03 2.68742603e+03 2.74898267e+03 2.78849902e+03 2.80040649e+03 2.83740283e+03 2.88547363e+03 2.87665356e+03 2.90469653e+03 2.97585352e+03 3.00326245e+03 3.09093579e+03 3.17868311e+03 3.09513989e+03 3.12663696e+03 3.28838916e+03 3.28962720e+03 3.23233252e+03 3.34207397e+03 3.46790381e+03 3.47537231e+03 3.48588940e+03 3.51438672e+03 3.54019409e+03 3.56756958e+03 3.57690479e+03 3.67644482e+03 3.73051685e+03 3.75230005e+03 3.82427295e+03 3.89003296e+03 3.91401904e+03 3.86657910e+03 3.94943481e+03 4.06733032e+03 4.03170532e+03 4.14868750e+03 4.25970312e+03 4.26623389e+03 4.21268457e+03 4.25487354e+03 4.31258887e+03 4.28430371e+03 4.40887598e+03 4.54043457e+03 4.54537598e+03 4.55283887e+03 4.57258936e+03 4.61106396e+03 4.68257275e+03 4.70646045e+03 4.70703467e+03 4.80609668e+03 4.91480078e+03 4.93067822e+03 4.95723193e+03 5.01345068e+03 5.03966211e+03 5.10927734e+03 5.13652539e+03 5.14849219e+03 5.29708838e+03 5.30471191e+03 5.29448877e+03 5.38300684e+03 5.46056055e+03 5.58537012e+03 5.37216797e+03 5.45517432e+03 5.70131982e+03 5.63241162e+03 5.77031494e+03 5.79194971e+03 5.73437939e+03 5.84240576e+03 5.85842139e+03 5.83784863e+03 5.95374170e+03 6.04462207e+03 6.14008154e+03 6.27551953e+03 6.28209277e+03 6.24096338e+03 6.28992725e+03 6.26440820e+03 6.29613574e+03 6.37527979e+03 6.50513281e+03 6.68986621e+03 6.52756250e+03 6.50542285e+03 6.68961377e+03 6.57806738e+03 6.75287549e+03 6.94443604e+03 6.82065918e+03 6.84077100e+03 6.95735059e+03 7.07462451e+03 7.09499365e+03 7.04178467e+03 7.05861670e+03 7.07891357e+03 7.21183643e+03 7.37820947e+03 7.40763965e+03 7.40096924e+03 7.45131592e+03 7.55701025e+03 7.47545752e+03 7.60027295e+03 7.80567773e+03 7.59850488e+03 7.60717383e+03 7.72907715e+03 7.81647559e+03 7.89098486e+03 7.90648145e+03 7.91227539e+03 7.98676123e+03 8.04852393e+03 8.09184521e+03 8.16697412e+03 8.39780664e+03 8.37711523e+03 8.08187061e+03 8.26098633e+03 8.34260156e+03 8.41119336e+03 8.64223340e+03 8.44665820e+03 8.38034961e+03 8.71208301e+03 8.73003906e+03 8.57589258e+03 8.61687207e+03 8.84460156e+03 8.95037500e+03 8.80586719e+03 8.93169629e+03 9.11790820e+03 8.96065234e+03 8.97904688e+03 9.12153418e+03 8.98582910e+03 9.19726465e+03 9.42543750e+03 9.16191113e+03 9.35450879e+03 9.60051465e+03 9.48399512e+03 9.35939160e+03 9.31091699e+03 9.51926758e+03 9.78448730e+03 9.63494141e+03 9.50426465e+03 9.71277246e+03 9.76200391e+03 9.74983691e+03 9.78801855e+03 9.91227441e+03 9.95814941e+03 9.91930859e+03 1.00276406e+04 1.02176602e+04 1.00943506e+04 1.01170693e+04 1.02747949e+04 1.00770342e+04 1.03985146e+04 1.05344648e+04 1.01710137e+04 1.04016270e+04 1.04606719e+04 1.03276699e+04 1.05513066e+04 1.05349141e+04 1.06451484e+04 1.08391162e+04 1.07007842e+04 1.06887861e+04 1.07277549e+04 1.06471855e+04 1.06755508e+04 1.08248496e+04 1.10480820e+04 1.10839688e+04 1.10425215e+04 1.10701318e+04 1.11870967e+04 1.11524697e+04 1.09883809e+04 1.11536631e+04 1.13787305e+04 1.14037002e+04 1.11610576e+04 1.10785215e+04 1.13616416e+04 1.16384189e+04 1.14167402e+04 1.13209941e+04 1.14989131e+04 1.15500869e+04 1.17288164e+04 1.17605068e+04 1.16280996e+04 1.14398379e+04 1.15574932e+04 1.17556797e+04 1.17113311e+04 1.18762012e+04 1.19602295e+04 1.19268555e+04 1.19163389e+04 1.21479238e+04 1.20792920e+04 1.18895977e+04 1.21276553e+04 1.22657412e+04 1.21303105e+04 1.18582031e+04 1.18470410e+04 1.22008418e+04 1.23805889e+04 1.23181738e+04 1.22450625e+04 1.22542461e+04 1.24993047e+04 1.25172695e+04 1.21510703e+04 1.22296592e+04 1.24537441e+04 1.26485186e+04 1.25383311e+04 1.22870938e+04 1.24324727e+04 1.25768105e+04 1.27645156e+04 1.29071650e+04 1.28758887e+04 1.25531475e+04 1.23195635e+04 1.27237207e+04 1.30878145e+04 1.28372158e+04 1.26797930e+04 1.26397842e+04 1.28100586e+04 1.30282656e+04 1.28393535e+04 1.28112129e+04 1.29416934e+04 1.31860791e+04 1.32289102e+04 1.27747783e+04 1.29981465e+04 1.31408662e+04 1.28977461e+04 1.30926240e+04 1.31027354e+04 1.30435127e+04 1.30672822e+04 1.30351396e+04 1.31754258e+04 1.33660781e+04 1.33695957e+04 1.30763721e+04 1.31835879e+04 1.34725029e+04 1.33295254e+04 1.32406348e+04 1.29962930e+04 1.31250264e+04 1.36267383e+04 1.35007158e+04 1.33289502e+04 1.30723613e+04 1.32562803e+04 1.37789590e+04 1.34875938e+04 1.33392256e+04 1.35683252e+04 1.35255869e+04 1.32833486e+04 1.34581152e+04 1.35715371e+04 1.33586182e+04 1.35482715e+04 1.35414717e+04 1.31989688e+04 1.34620371e+04 1.36530576e+04 1.36200625e+04 1.38476748e+04 1.36896602e+04 1.35879053e+04 1.35248066e+04 1.34753779e+04 1.36152832e+04 1.37013887e+04 1.36662520e+04 1.35340947e+04 1.36818652e+04 1.35427900e+04 1.35018203e+04 1.39190039e+04 1.37301465e+04 1.35340645e+04 1.36450254e+04 1.36677969e+04 1.36416250e+04 1.37599014e+04 1.37985205e+04 1.34970547e+04 1.35112754e+04 1.37472871e+04 1.36836045e+04 1.37068760e+04 1.39071045e+04 1.37716758e+04 1.36380410e+04 1.34476494e+04 1.33979971e+04 1.36980703e+04 1.38558730e+04 1.40096279e+04 1.36941611e+04 1.33020811e+04 1.36573799e+04 1.38658105e+04 1.37148555e+04 1.35752959e+04 1.35697354e+04 1.37496475e+04 1.38014912e+04 1.36489775e+04 1.34830918e+04 1.35425000e+04 1.36939326e+04 1.35804893e+04 1.36053184e+04 1.36658887e+04 1.34519404e+04 1.35714648e+04 1.36850342e+04 1.36307012e+04 1.36536436e+04 1.35770879e+04 1.35691377e+04 1.35672236e+04 1.35821768e+04 1.32960889e+04 1.32534004e+04 1.35412266e+04 1.36791680e+04 1.37520596e+04 1.34222832e+04 1.33355635e+04 1.33109492e+04 1.33277939e+04 1.36522451e+04 1.33336426e+04 1.32899902e+04 1.36516992e+04 1.32108945e+04 1.30241484e+04 1.34600117e+04 1.35121768e+04 1.33481924e+04 1.34916104e+04 1.31814414e+04 1.27773252e+04 1.32521025e+04 1.34612139e+04 1.31182812e+04 1.33786758e+04 1.34129775e+04 1.28967275e+04 1.29421758e+04 1.30030537e+04 1.29422275e+04 1.32177920e+04 1.31393438e+04 1.29746299e+04 1.30106855e+04 1.30140098e+04 1.30846133e+04 1.29276191e+04 1.27901191e+04 1.29018057e+04 1.29256943e+04 1.26800332e+04 1.27370850e+04 1.29085654e+04 1.27437939e+04 1.28114834e+04 1.28332598e+04 1.27341377e+04 1.27444678e+04 1.24280137e+04 1.24442266e+04 1.28649668e+04 1.27543008e+04 1.24881494e+04 1.25588486e+04 1.26312627e+04 1.25354883e+04 1.24691055e+04 1.20822686e+04 1.20328604e+04 1.24692305e+04 1.25668379e+04 1.24789961e+04 1.21174336e+04 1.21214629e+04 1.23388643e+04 1.22005303e+04 1.21012197e+04 1.21147090e+04 1.20379766e+04 1.21159365e+04 1.20701445e+04 1.21443525e+04 1.19837881e+04 1.17760303e+04 1.20995732e+04 1.18438955e+04 1.16541602e+04 1.17408027e+04 1.15950420e+04 1.17411387e+04 1.20418662e+04 1.19016768e+04 1.14421973e+04 1.14250049e+04 1.16430820e+04 1.16633701e+04 1.15533691e+04 1.14192314e+04 1.14730918e+04 1.15161641e+04 1.14230312e+04 1.14364238e+04 1.12954736e+04 1.12440752e+04 1.13602891e+04 1.08882861e+04 1.08000186e+04 1.12751123e+04 1.11994033e+04 1.10856562e+04 1.10146621e+04 1.08022412e+04 1.07699932e+04 1.10669912e+04 1.10938994e+04 1.07847090e+04 1.06500049e+04 1.05459307e+04 1.05987295e+04 1.07368779e+04 1.07366201e+04 1.06937305e+04 1.04874619e+04 1.04629541e+04 1.04560762e+04 1.02177256e+04 1.02120117e+04 1.04242402e+04 1.03787490e+04 1.02358955e+04 1.01612373e+04 1.01284102e+04 1.01297432e+04 9.94907812e+03 1.01071885e+04 1.00140947e+04 9.95303320e+03 9.89744336e+03 9.82949902e+03 1.00356426e+04 9.78852930e+03 9.63015430e+03 9.80457422e+03 9.61255371e+03 9.39542578e+03 9.58495703e+03 9.55169531e+03 9.39720020e+03 9.51715430e+03 9.51851172e+03 9.39199219e+03 9.49643945e+03 9.29056543e+03 9.03019336e+03 9.28560449e+03 1.18971416e+04 1.22094951e+04 1.38261885e+04 1.37342559e+04 1.47085723e+04 1.27705078e+04 2.61591035e+04 3.96918711e+04 5842296. -53043152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 40084008. -16955768. 1.73686638e+06 7.42091850e+06 4.18928675e+06 -6217707. -14316113. 1.87330625e+04 1.28066631e+04 9.27030469e+03 7.39684473e+03 6.53236963e+03 6.37036133e+03 6.46725391e+03 6.28368408e+03 6.23995410e+03 6.20515625e+03 6.17428027e+03 6.18426611e+03 6.11751904e+03 5.99927148e+03 5.82169434e+03 5.93095752e+03 5.92454883e+03 5.83064258e+03 5.79481543e+03 5.60121143e+03 5.56002539e+03 5.76790576e+03 5.59503125e+03 5.43527588e+03 5.31618848e+03 5.38039551e+03 5.54926758e+03 5.53229980e+03 5.32848779e+03 5.06246143e+03 5.03864893e+03 5.19406494e+03 5.15030518e+03 5.09883594e+03 4.97661377e+03 4.95480518e+03 4.98015430e+03 4.92903711e+03 4.87755762e+03 4.66153857e+03 4.68959180e+03 4.91445898e+03 4.66947461e+03 4.48899072e+03 4.49240479e+03 4.42874365e+03 4.54396191e+03 4.52718359e+03 4.35070117e+03 4.21349902e+03 4.29215039e+03 4.33613916e+03 4.21905078e+03 4.12436475e+03 4.02660278e+03 4.06794556e+03 4.11411768e+03 3.96781592e+03 3.93347217e+03 3.84941309e+03 3.77085620e+03 3.85360303e+03 3.85111987e+03 3.73148047e+03 3.63240796e+03 3.63788794e+03 3.62260083e+03 3.57563037e+03 3.55255249e+03 3.39525684e+03 3.37852783e+03 3.48230493e+03 3.36691235e+03 3.20251147e+03 3.16043848e+03 3.22894971e+03 3.30993311e+03 3.19456616e+03 3.10099976e+03 3.02174219e+03 2.93905664e+03 2.96134424e+03 3.00682837e+03 2.92417725e+03 2.81341968e+03 2.81846704e+03 2.79796777e+03 2.76402832e+03 2.77324878e+03 2.63566113e+03 2.57757007e+03 2.67654663e+03 2.58574927e+03 2.49886743e+03 2.45603320e+03 2.38622217e+03 2.45138550e+03 2.43466113e+03 2.31303027e+03 2.26937476e+03 2.27516455e+03 2.27185767e+03 2.20922339e+03 2.17455176e+03 2.11258740e+03 2.07398047e+03 2.10232812e+03 2.03908179e+03 1.95967932e+03 1.91025684e+03 1.90756738e+03 1.94574023e+03 1.90242725e+03 1.83627832e+03 1.75306445e+03 1.71428357e+03 1.76408044e+03 1.73397388e+03 1.65425574e+03 1.60246985e+03 1.59319849e+03 1.60290686e+03 1.55252319e+03 1.49936365e+03 1.44979089e+03 1.45172046e+03 1.47643701e+03 1.39896082e+03 1.35698242e+03 1.34288623e+03 1.29640625e+03 1.29151636e+03 1.27117261e+03 1.22519043e+03 1.17813733e+03 1.16189734e+03 1.17494153e+03 1.14802222e+03 1.10309631e+03 1.04886707e+03 1.02398547e+03 1.04086694e+03 1.01782263e+03 9.76127502e+02 9.27490295e+02 8.92977112e+02 9.01212646e+02 8.96687744e+02 8.60028809e+02 8.18370178e+02 7.95758728e+02 7.79556152e+02 7.66226501e+02 7.56600708e+02 7.18730164e+02 6.90914673e+02 6.85063965e+02 6.59532043e+02 6.33791931e+02 6.12154724e+02 5.99734009e+02 5.82816650e+02 5.53502625e+02 5.35087219e+02 5.13453247e+02 5.03404297e+02 5.03575409e+02 4.74779999e+02 4.42311493e+02 4.23181976e+02 4.13936859e+02 4.09953491e+02 3.98324493e+02 3.79719482e+02 3.49944519e+02 3.27102905e+02 3.23320129e+02 3.19937225e+02 3.05348572e+02 2.79167480e+02 2.64272064e+02 2.59012451e+02 2.48128540e+02 2.36972031e+02 2.20741486e+02 2.08654480e+02 2.00567520e+02 1.86594696e+02 1.75131149e+02 1.64902206e+02 1.54809402e+02 1.47814651e+02 1.36785965e+02 1.26501595e+02 1.16989182e+02 1.09056808e+02 1.03102692e+02 9.45126038e+01 8.60943985e+01 7.85627518e+01 7.40112457e+01 6.83851242e+01 6.02549782e+01 5.39472046e+01 4.78458862e+01 4.30957108e+01 3.96950493e+01 3.49657974e+01 3.03990116e+01 2.58042717e+01 2.22912331e+01 2.01175404e+01 1.73337784e+01 1.43510885e+01 1.21289530e+01 1.03784819e+01 8.83670521e+00 7.60026789e+00 6.72602272e+00 6.25106907e+00 6.12329483e+00 6.32223368e+00 6.85760546e+00 7.62699890e+00 8.64248657e+00 1.02398510e+01 1.23103256e+01 1.45069818e+01 1.70185986e+01 1.96190205e+01 2.32138271e+01 2.67569370e+01 2.94772224e+01 3.32568779e+01 3.82800293e+01 4.47350731e+01 5.15511971e+01 5.59902573e+01 5.89638214e+01 6.33869820e+01 7.11281509e+01 8.18532791e+01 9.18156433e+01 9.75462418e+01 9.92705307e+01 1.06354668e+02 1.22775177e+02 1.31578430e+02 1.34604187e+02 1.43289062e+02 1.53731018e+02 1.64642731e+02 1.80970016e+02 1.88666397e+02 1.92544922e+02 2.09258423e+02 2.17811432e+02 2.33806580e+02 2.51761948e+02 2.53071487e+02 2.70831207e+02 2.91729431e+02 2.99125977e+02 3.12117004e+02 3.27602203e+02 3.43751373e+02 3.59492126e+02 3.70531891e+02 3.77959412e+02 3.93829346e+02 4.28568878e+02 4.59119659e+02 4.65188293e+02 4.59305481e+02 4.65574341e+02 4.94593903e+02 5.34520264e+02 5.67720154e+02 5.74153931e+02 5.63787842e+02 5.85302673e+02 6.23635864e+02 6.41506226e+02 6.54281128e+02 6.74330078e+02 6.97320740e+02 7.21399719e+02 7.64010925e+02 7.65975098e+02 7.70670532e+02 8.09829651e+02 8.08663452e+02 8.52641479e+02 9.01694580e+02 8.94079590e+02 9.42834839e+02 9.56088318e+02 9.39966003e+02 9.96124878e+02 9.97258972e+02 1.03421155e+03 1.13639136e+03 1.11064526e+03 1.06850708e+03 1.11678442e+03 1.20235950e+03 1.27583606e+03 1.26857227e+03 1.23390771e+03 1.23555103e+03 1.28763391e+03 1.35773999e+03 1.43111157e+03 1.44102869e+03 1.39458545e+03 1.41472571e+03 1.48236755e+03 1.53561035e+03 1.54271033e+03 1.56083704e+03 1.60667322e+03 1.63534827e+03 1.72694946e+03 1.75172656e+03 1.68257568e+03 1.70524170e+03 1.79821851e+03 1.84128406e+03 1.87588855e+03 1.89851990e+03 1.97252588e+03 1.96785925e+03 1.93477087e+03 2.02188586e+03 2.00115295e+03 2.09226685e+03 2.26400098e+03 2.16135620e+03 2.08183423e+03 2.18258130e+03 2.32321924e+03 2.42496045e+03 2.43899121e+03 2.33876758e+03 2.29006494e+03 2.39005811e+03 2.53713184e+03 2.65260474e+03 2.63124268e+03 2.52938672e+03 2.55595557e+03 2.69016211e+03 2.73928540e+03 2.81112891e+03 2.85997559e+03 2.75765063e+03 2.78631299e+03 2.97497754e+03 3.02749854e+03 2.92773267e+03 2.95961987e+03 3.06699634e+03 3.07637451e+03 3.23186328e+03 3.29718652e+03 3.20097632e+03 3.21988599e+03 3.26143481e+03 3.30406006e+03 3.38560571e+03 3.41815625e+03 3.55707129e+03 3.64531812e+03 3.56435962e+03 3.49084448e+03 3.45802466e+03 3.67580347e+03 3.91186768e+03 3.88504956e+03 3.74057690e+03 3.65447559e+03 3.86086182e+03 4.12533643e+03 4.02892456e+03 3.83169287e+03 3.96452026e+03 4.13751660e+03 4.26619141e+03 4.41896436e+03 4.37715186e+03 4.14265576e+03 4.17282715e+03 4.36329736e+03 4.44949170e+03 4.50456006e+03 4.52507910e+03 4.59329541e+03 4.58801660e+03 4.70723828e+03 4.72525000e+03 4.65307910e+03 4.70361328e+03 4.71504736e+03 4.92666406e+03 5.04479248e+03 4.96023584e+03 5.04727832e+03 5.11266162e+03 5.13419629e+03 5.06657568e+03 5.00441895e+03 5.25081885e+03 5.54926367e+03 5.47408301e+03 5.24934619e+03 5.25873389e+03 5.54422803e+03 5.70978320e+03 5.65207227e+03 5.62943848e+03 5.50418457e+03 5.56460205e+03 5.83923730e+03 5.88602490e+03 5.78004150e+03 5.70644873e+03 5.72146289e+03 6.08939941e+03 6.40436377e+03 6.09540723e+03 5.97087646e+03 6.17815234e+03 6.24771533e+03 6.48679980e+03 6.49812402e+03 6.15861670e+03 6.28113867e+03 6.52545850e+03 6.54667627e+03 6.62219189e+03 6.73828467e+03 6.55537061e+03 7.06782227e+03 7.19350000e+03 6.67754688e+03 8.63209863e+03 9.33899121e+03 1.11206436e+04 1.08562344e+04 1.04475703e+04 1.08322646e+04 1.07687988e+04 1.14318398e+04 1.20870781e+04 1.13196211e+04 1.93387344e+04 2.94667930e+04 -16059672. 12998406. 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. 0. -400063488. -400063488. -400063488. 0. 0. 140856864. -2.52312950e+06 -1.49443050e+06 -1.70737475e+06 8.15760650e+06 -3113725. -1.90079712e+06 2.56375723e+04 2.01969746e+04 1.13631787e+04 1.04297031e+04 9.75758691e+03 9.49223340e+03 9.94205957e+03 1.00358125e+04 9.74431738e+03 9.82410645e+03 9.94927441e+03 9.91236035e+03 9.94219238e+03 9.96850195e+03 9.90509180e+03 1.00520205e+04 1.01178389e+04 1.01905498e+04 1.02722314e+04 9.95781348e+03 1.00658066e+04 1.05669170e+04 1.05935977e+04 1.04648955e+04 1.04515117e+04 1.04916787e+04 1.05661035e+04 1.05541533e+04 1.06191133e+04 1.06280908e+04 1.06152451e+04 1.05585752e+04 1.06080615e+04 1.09521182e+04 1.10118311e+04 1.08445293e+04 1.08645889e+04 1.09921650e+04 1.10821387e+04 1.10236406e+04 1.10457393e+04 1.11032920e+04 1.09932119e+04 1.10130684e+04 1.09988271e+04 1.10293535e+04 1.16388633e+04 1.17304111e+04 1.13549775e+04 1.10813320e+04 1.10455537e+04 1.17506064e+04 1.18966357e+04 1.15453408e+04 1.13035615e+04 1.13438682e+04 1.15473721e+04 1.15639170e+04 1.20702744e+04 1.20732705e+04 1.13684111e+04 1.12335176e+04 1.18568096e+04 1.25253594e+04 1.22508027e+04 1.19622363e+04 1.19563174e+04 1.19193086e+04 1.20232979e+04 1.21309326e+04 1.20221582e+04 1.19344385e+04 1.20519736e+04 1.20902383e+04 1.21349473e+04 1.21424531e+04 1.25394863e+04 1.25676641e+04 1.22407988e+04 1.22048662e+04 1.22613232e+04 1.26608271e+04 1.27322344e+04 1.24790332e+04 1.25217607e+04 1.22459834e+04 1.20190967e+04 1.26501504e+04 1.28286729e+04 1.21822529e+04 1.22864932e+04 1.30153760e+04 1.34003789e+04 1.30591963e+04 1.27174463e+04 1.26957178e+04 1.27879150e+04 1.27032051e+04 1.26472881e+04 1.27888428e+04 1.27959443e+04 1.32230137e+04 1.31819248e+04 1.28875400e+04 1.28878535e+04 1.25609688e+04 1.28752705e+04 1.36528535e+04 1.34419922e+04 1.31105986e+04 1.27882109e+04 1.26270801e+04 1.33897695e+04 1.36964902e+04 1.32742246e+04 1.28508564e+04 1.28524561e+04 1.31694053e+04 1.31709248e+04 1.36389043e+04 1.37761836e+04 1.32719473e+04 1.30073682e+04 1.30711084e+04 1.36340586e+04 1.36778574e+04 1.33843574e+04 1.32883926e+04 1.32655557e+04 1.32602637e+04 1.29370801e+04 1.33060820e+04 1.40965342e+04 1.37994697e+04 1.34839805e+04 1.31812900e+04 1.30835547e+04 1.38881943e+04 1.39422266e+04 1.35226621e+04 1.31982363e+04 1.31785938e+04 1.36162754e+04 1.35651543e+04 1.35915889e+04 1.32636709e+04 1.34848887e+04 1.42322129e+04 1.39042363e+04 1.37076201e+04 1.38185645e+04 1.37108438e+04 1.34804717e+04 1.35129072e+04 1.35459404e+04 1.34974219e+04 1.35621064e+04 1.32427725e+04 1.35874717e+04 1.44075059e+04 1.37456182e+04 1.32967568e+04 1.36450234e+04 1.36429307e+04 1.40218242e+04 1.38826318e+04 1.33993027e+04 1.38907842e+04 1.40009375e+04 1.37418438e+04 1.38108018e+04 1.37292373e+04 1.35212607e+04 1.35345273e+04 1.34902705e+04 1.31351768e+04 1.35921992e+04 1.44256963e+04 1.41419385e+04 1.35984697e+04 1.31648594e+04 1.33601943e+04 1.41720811e+04 1.40881982e+04 1.37343057e+04 1.33503643e+04 1.32005781e+04 1.36701377e+04 1.36772842e+04 1.39052012e+04 1.37818701e+04 1.33832520e+04 1.34818398e+04 1.34760264e+04 1.39732930e+04 1.40050312e+04 1.35533838e+04 1.34446982e+04 1.34741143e+04 1.34843135e+04 1.30904043e+04 1.33903701e+04 1.41072666e+04 1.38368174e+04 1.35003975e+04 1.31528086e+04 1.30715859e+04 1.38033008e+04 1.38239932e+04 1.34673828e+04 1.31536631e+04 1.30371201e+04 1.34427979e+04 1.34095977e+04 1.36788057e+04 1.35961191e+04 1.32185801e+04 1.30887920e+04 1.30419346e+04 1.36412178e+04 1.36506309e+04 1.32856807e+04 1.30513691e+04 1.29675947e+04 1.34747539e+04 1.34966074e+04 1.28063936e+04 1.28335518e+04 1.35561826e+04 1.34527539e+04 1.27816074e+04 1.26977588e+04 1.33528135e+04 1.34599473e+04 1.29487188e+04 1.25809756e+04 1.26335723e+04 1.33472715e+04 1.32269150e+04 1.28488389e+04 1.29023916e+04 1.28116084e+04 1.25832646e+04 1.25250957e+04 1.28462275e+04 1.24775693e+04 1.26822764e+04 1.32676963e+04 1.28614248e+04 1.28827266e+04 1.28794355e+04 1.26311377e+04 1.26258096e+04 1.25964658e+04 1.25294854e+04 1.21861992e+04 1.20360518e+04 1.23171963e+04 1.24990566e+04 1.28489580e+04 1.23897295e+04 1.20326377e+04 1.23879697e+04 1.23217920e+04 1.26326025e+04 1.25402773e+04 1.21649922e+04 1.19486396e+04 1.18379375e+04 1.21125693e+04 1.20965840e+04 1.23085049e+04 1.23065615e+04 1.19735879e+04 1.18386328e+04 1.15232568e+04 1.18123760e+04 1.23817969e+04 1.21998857e+04 1.17917822e+04 1.14911504e+04 1.13796338e+04 1.19312285e+04 1.20888896e+04 1.16818594e+04 1.12981299e+04 1.12950479e+04 1.15716826e+04 1.14730820e+04 1.17198086e+04 1.16198018e+04 1.13050596e+04 1.12966748e+04 1.12040479e+04 1.14861162e+04 1.14922812e+04 1.09092383e+04 1.08588809e+04 1.14584307e+04 1.12122500e+04 1.05634268e+04 1.08768838e+04 1.14021904e+04 1.12492578e+04 1.09365684e+04 1.05689873e+04 1.05555078e+04 1.11347969e+04 1.10451113e+04 1.07187656e+04 1.04250449e+04 1.03108994e+04 1.05632119e+04 1.05492031e+04 1.05641318e+04 1.02229678e+04 1.03807979e+04 1.08217617e+04 1.05369307e+04 1.04424756e+04 1.03049365e+04 1.01459277e+04 1.01559648e+04 1.01419814e+04 1.01520195e+04 1.00599121e+04 9.97613965e+03 9.69839648e+03 9.78218359e+03 1.02651514e+04 9.75449316e+03 9.42630957e+03 9.68336230e+03 9.85273730e+03 1.01068447e+04 9.89259766e+03 9.59712988e+03 9.63112695e+03 9.49678711e+03 9.29351172e+03 9.19088965e+03 9.56139648e+03 9.40786621e+03 9.16269727e+03 9.12426172e+03 8.83209277e+03 9.08366406e+03 9.56993457e+03 9.25032812e+03 8.97278516e+03 8.69909375e+03 8.63837012e+03 9.09118652e+03 9.22046094e+03 8.84735938e+03 8.56837305e+03 8.48028809e+03 8.55884570e+03 8.55961914e+03 8.80700391e+03 8.65124121e+03 8.37546094e+03 8.33756348e+03 8.29311719e+03 8.41194043e+03 8.34107422e+03 8.16549121e+03 8.21377344e+03 8.16553027e+03 7.98920898e+03 7.73531934e+03 7.87132520e+03 8.24411523e+03 8.04844922e+03 7.81079932e+03 7.61342090e+03 7.58159912e+03 8.00519824e+03 7.89782275e+03 7.59139111e+03 7.42708105e+03 7.34762598e+03 7.36868311e+03 7.33642871e+03 7.40306299e+03 7.14591504e+03 7.23662939e+03 7.45821533e+03 7.21923096e+03 7.23301562e+03 7.17703174e+03 7.03326709e+03 7.04754150e+03 6.97020752e+03 6.74158301e+03 6.70728418e+03 6.87438965e+03 6.81254980e+03 6.77767334e+03 6.69506152e+03 6.43341162e+03 6.34220166e+03 6.51303711e+03 6.49032617e+03 6.61252490e+03 6.47898975e+03 6.16881787e+03 6.29387793e+03 6.32593604e+03 6.20157471e+03 6.06197510e+03 5.99408057e+03 6.03893164e+03 5.96985059e+03 5.94177539e+03 5.75168750e+03 5.83313330e+03 6.06755273e+03 5.91040332e+03 5.70292822e+03 5.49426758e+03 5.44305273e+03 5.73007666e+03 5.66383740e+03 5.48026709e+03 5.28323877e+03 5.15303271e+03 5.28950146e+03 5.35332666e+03 5.46546387e+03 5.22590967e+03 4.97666504e+03 5.01577686e+03 5.05099170e+03 5.16984570e+03 5.00693457e+03 4.80143213e+03 4.88266309e+03 4.84981104e+03 4.75988330e+03 4.60648145e+03 4.64011475e+03 4.84720850e+03 4.74785498e+03 4.53853760e+03 4.35944482e+03 4.35603271e+03 4.56919287e+03 4.50772266e+03 4.34080127e+03 4.19155664e+03 4.11663379e+03 4.20304541e+03 4.15777539e+03 4.22713916e+03 4.17451758e+03 3.97338672e+03 3.85216431e+03 3.87265894e+03 4.03958740e+03 3.90700830e+03 3.75526782e+03 3.80850171e+03 3.75416309e+03 3.61495850e+03 3.51798364e+03 3.59381323e+03 3.54336987e+03 3.43740918e+03 3.55434009e+03 3.53302002e+03 3.41041187e+03 3.34595386e+03 3.29570239e+03 3.26490381e+03 3.14674023e+03 3.06936938e+03 3.18340747e+03 3.19804175e+03 3.00516675e+03 2.88772583e+03 2.98005029e+03 3.05366919e+03 2.98010718e+03 2.84696069e+03 2.74689014e+03 2.79720532e+03 2.82956665e+03 2.74431665e+03 2.68085010e+03 2.56703125e+03 2.47904150e+03 2.56074097e+03 2.64093921e+03 2.55146362e+03 2.39710986e+03 2.33546338e+03 2.42845703e+03 2.43013330e+03 2.31349341e+03 2.22173193e+03 2.16624658e+03 2.15399268e+03 2.14507422e+03 2.18260229e+03 2.15558545e+03 2.04058081e+03 1.99871497e+03 1.97782544e+03 1.99697241e+03 1.91755359e+03 1.83989880e+03 1.89576685e+03 1.87100281e+03 1.77610608e+03 1.70120789e+03 1.70503894e+03 1.76533997e+03 1.67121802e+03 1.57837085e+03 1.58815442e+03 1.58464026e+03 1.56151025e+03 1.51351318e+03 1.52211914e+03 1.50220093e+03 1.42490027e+03 1.35451257e+03 1.33134961e+03 1.37593555e+03 1.32822437e+03 1.26198059e+03 1.25227063e+03 1.23073694e+03 1.20125659e+03 1.16308533e+03 1.15326074e+03 1.12191797e+03 1.07569861e+03 1.07666187e+03 1.05239209e+03 1.03665723e+03 1.01197675e+03 9.70577637e+02 9.38924988e+02 8.90079834e+02 8.72218384e+02 8.97163269e+02 8.87238953e+02 8.18662903e+02 7.72049866e+02 7.76885864e+02 7.85115417e+02 7.58904663e+02 7.11534546e+02 6.69250793e+02 6.77320984e+02 6.74488586e+02 6.36004761e+02 6.28934692e+02 6.02930786e+02 5.60056885e+02 5.53297485e+02 5.55046753e+02 5.31397400e+02 4.90759552e+02 4.66922821e+02 4.75014557e+02 4.68151215e+02 4.36715271e+02 4.04861115e+02 3.87490906e+02 3.94011414e+02 3.76626434e+02 3.50453705e+02 3.41386719e+02 3.25922699e+02 3.08253571e+02 2.93363037e+02 2.90819641e+02 2.72366608e+02 2.50089874e+02 2.49441315e+02 2.37859009e+02 2.22596741e+02 2.06631851e+02 1.92312042e+02 1.90619308e+02 1.76597412e+02 1.59293808e+02 1.54516098e+02 1.51493790e+02 1.39822586e+02 1.20570091e+02 1.21560539e+02 1.20927971e+02 1.00978027e+02 9.20645752e+01 8.06054840e+01 8.14450684e+01 9.18711319e+01 6.47058334e+01 7.18597946e+01 7.56747665e+01 8.55662460e+01 2.79829010e+02 5.14280150e+06 0. 0. 0. 0. 0. 0. 12921689. 12921689. 9.54277267e+01 1.39233459e+02 1.39233459e+02 8468770. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 15460166. 4.57521088e+02 1.02144958e+02 6.52925568e+01 8.20389252e+01 8.28493271e+01 7.94258575e+01 8.59930038e+01 9.39191742e+01 1.01640839e+02 1.07632668e+02 1.16326263e+02 1.27497711e+02 1.35610962e+02 1.43973190e+02 1.52103058e+02 1.62174210e+02 1.77599548e+02 1.87960922e+02 1.95420944e+02 2.06384598e+02 2.16378418e+02 2.30364182e+02 2.50101669e+02 2.63825684e+02 2.67753540e+02 2.77832001e+02 2.96486542e+02 3.12401855e+02 3.23492523e+02 3.35999542e+02 3.54688324e+02 3.69840332e+02 3.90304504e+02 4.05559509e+02 4.07080353e+02 4.28593231e+02 4.60350342e+02 4.81839294e+02 4.94798065e+02 4.91759033e+02 5.05770172e+02 5.45377075e+02 5.66912842e+02 5.75599060e+02 5.90689392e+02 6.10412598e+02 6.42271057e+02 6.71788086e+02 6.81335754e+02 6.78912903e+02 7.01860840e+02 7.62925171e+02 7.85008850e+02 7.69781433e+02 7.88396851e+02 8.29955933e+02 8.61175232e+02 8.95296509e+02 9.02427246e+02 9.00394470e+02 9.32280457e+02 9.76617676e+02 1.00887518e+03 1.02523743e+03 1.02376892e+03 1.06471814e+03 1.11624524e+03 1.13159448e+03 1.14478687e+03 1.15573560e+03 1.19126685e+03 1.24375928e+03 1.27379761e+03 1.30172559e+03 1.30697888e+03 1.30683521e+03 1.36792773e+03 1.41091174e+03 1.42893909e+03 1.45914807e+03 1.47124963e+03 1.51223926e+03 1.57830774e+03 1.59684412e+03 1.57043225e+03 1.60283215e+03 1.68233740e+03 1.72924573e+03 1.74312695e+03 1.73932227e+03 1.78308765e+03 1.82902454e+03 1.87815369e+03 1.90319116e+03 1.88722839e+03 1.95232983e+03 2.02849121e+03 2.05539551e+03 2.07689941e+03 2.06141455e+03 2.09360010e+03 2.19410498e+03 2.21913623e+03 2.19951978e+03 2.23038184e+03 2.28758984e+03 2.36644604e+03 2.40313623e+03 2.41493188e+03 2.44822632e+03 2.48272827e+03 2.55973755e+03 2.59236816e+03 2.57157275e+03 2.62388745e+03 2.67725952e+03 2.68338550e+03 2.75467163e+03 2.81160938e+03 2.82684619e+03 2.86241040e+03 2.89056982e+03 2.92902905e+03 3.00697607e+03 3.04658374e+03 3.06710864e+03 3.09968359e+03 3.10208374e+03 3.15502271e+03 3.25768115e+03 3.25981421e+03 3.26300293e+03 3.35454761e+03 3.47728027e+03 3.48510986e+03 3.43847241e+03 3.50227173e+03 3.58161499e+03 3.56705420e+03 3.58116284e+03 3.63581909e+03 3.67910107e+03 3.79180957e+03 3.88625635e+03 3.88448511e+03 3.87070190e+03 3.87128076e+03 3.96884814e+03 4.07302319e+03 4.09816650e+03 4.10973682e+03 4.11186719e+03 4.20521777e+03 4.31704053e+03 4.32860107e+03 4.28118408e+03 4.25359961e+03 4.38743115e+03 4.55272168e+03 4.55940479e+03 4.41113281e+03 4.50128613e+03 4.70172900e+03 4.72919238e+03 4.70351953e+03 4.76068896e+03 4.82052393e+03 4.83879395e+03 4.95392578e+03 4.96248877e+03 4.91590625e+03 5.07046387e+03 5.18410059e+03 5.14954102e+03 5.23116748e+03 5.24083447e+03 5.19944678e+03 5.27883838e+03 5.37534424e+03 5.48059766e+03 5.59108301e+03 5.42204443e+03 5.45411230e+03 5.71514258e+03 5.65519824e+03 5.56827783e+03 5.70280371e+03 5.82261133e+03 5.90969922e+03 5.93855322e+03 5.92815527e+03 5.91343506e+03 5.94166260e+03 6.13956982e+03 6.23333545e+03 6.10074023e+03 6.19742725e+03 6.42515625e+03 6.37130371e+03 6.40770557e+03 6.35597607e+03 6.32841113e+03 6.57060547e+03 6.56511523e+03 6.56951904e+03 6.69909863e+03 6.61476807e+03 6.72594043e+03 6.98108740e+03 6.82056494e+03 6.83297363e+03 6.94612598e+03 7.01589355e+03 7.02918262e+03 7.09308350e+03 7.10096582e+03 7.13850391e+03 7.17278174e+03 7.30557373e+03 7.33151953e+03 7.27895947e+03 7.42499463e+03 7.60342041e+03 7.51125244e+03 7.70967773e+03 7.67123730e+03 7.44464355e+03 7.68385400e+03 7.80771826e+03 7.80858398e+03 7.74146436e+03 7.67483447e+03 7.99114209e+03 8.22537402e+03 8.03177344e+03 7.95516211e+03 8.20088281e+03 8.36101074e+03 8.19527734e+03 8.09217871e+03 8.39763086e+03 8.40413184e+03 8.31532520e+03 8.61454492e+03 8.49991406e+03 8.46273926e+03 8.60692188e+03 8.58970605e+03 8.65202246e+03 8.78943848e+03 8.69860840e+03 8.75767676e+03 8.92439453e+03 9.06269824e+03 9.10230762e+03 8.85508984e+03 8.89291211e+03 9.20357812e+03 9.13524609e+03 9.24395996e+03 9.24772070e+03 9.22074512e+03 9.30085449e+03 9.38934766e+03 9.58857617e+03 9.46580078e+03 9.19327051e+03 9.51040234e+03 9.93975488e+03 9.59372461e+03 9.41100977e+03 9.62952930e+03 9.65578516e+03 9.85468848e+03 1.00160244e+04 9.79564258e+03 9.86534277e+03 9.99672754e+03 1.00220811e+04 1.01623330e+04 1.01241016e+04 1.02473877e+04 1.03537559e+04 9.97013965e+03 1.01908594e+04 1.03654375e+04 1.02108672e+04 1.05495361e+04 1.04609434e+04 1.03441035e+04 1.05344082e+04 1.04498564e+04 1.05836191e+04 1.09415742e+04 1.07711787e+04 1.06543984e+04 1.06396953e+04 1.05813662e+04 1.08627773e+04 1.10403281e+04 1.08753369e+04 1.08434150e+04 1.11229346e+04 1.11698799e+04 1.11139980e+04 1.09694854e+04 1.10435879e+04 1.12270225e+04 1.12890225e+04 1.13467129e+04 1.11272412e+04 1.11566328e+04 1.13977998e+04 1.15685225e+04 1.15364189e+04 1.15096553e+04 1.14147891e+04 1.13239004e+04 1.18868623e+04 1.20231445e+04 1.15293379e+04 1.13790859e+04 1.15460244e+04 1.17135420e+04 1.17814268e+04 1.17104658e+04 1.18111182e+04 1.20006006e+04 1.19814521e+04 1.20374980e+04 1.19841230e+04 1.19334697e+04 1.21126504e+04 1.22235869e+04 1.21203359e+04 1.19038643e+04 1.20716885e+04 1.21536641e+04 1.21932041e+04 1.23988730e+04 1.22823633e+04 1.21510723e+04 1.22968135e+04 1.26064072e+04 1.24993555e+04 1.23126592e+04 1.23902705e+04 1.24789814e+04 1.24806738e+04 1.25124053e+04 1.24225771e+04 1.24728057e+04 1.26582314e+04 1.27832090e+04 1.28750059e+04 1.26374512e+04 1.26729658e+04 1.27454932e+04 1.26341836e+04 1.26731377e+04 1.26487412e+04 1.29153154e+04 1.29187461e+04 1.27593770e+04 1.27058242e+04 1.27705723e+04 1.30561963e+04 1.31908076e+04 1.32610166e+04 1.30343574e+04 1.29579346e+04 1.29986426e+04 1.28192598e+04 1.29604658e+04 13192. 1.31616973e+04 1.31116348e+04 1.29461543e+04 1.30009980e+04 1.32826270e+04 1.35007383e+04 1.34656387e+04 1.31848994e+04 1.30435107e+04 1.32374443e+04 1.33454570e+04 1.31925957e+04 1.33457812e+04 1.35563955e+04 1.32634658e+04 1.31525527e+04 1.31947324e+04 1.32808350e+04 1.37365576e+04 1.37243252e+04 1.33383076e+04 1.34969922e+04 1.34261035e+04 1.31600762e+04 1.35628994e+04 1.36520820e+04 1.33636035e+04 1.33852139e+04 1.33753086e+04 1.32559121e+04 1.35737715e+04 1.39970127e+04 1.36449697e+04 1.34377051e+04 1.35994854e+04 1.35611904e+04 1.35864326e+04 1.35600107e+04 1.36172217e+04 1.36023027e+04 1.35285332e+04 1.36910146e+04 1.37551895e+04 1.34836191e+04 1.36896953e+04 1.39620840e+04 1.35943008e+04 1.34099463e+04 1.34956797e+04 1.37733467e+04 1.38809590e+04 1.39106426e+04 1.35993965e+04 1.32128994e+04 1.34986299e+04 1.39117490e+04 1.41120273e+04 1.36992637e+04 1.34847295e+04 1.36715127e+04 1.36947490e+04 1.36981650e+04 1.37258535e+04 1.36837383e+04 1.36034883e+04 1.38159111e+04 1.36242891e+04 1.31837725e+04 1.36103486e+04 1.41410781e+04 1.37839150e+04 1.34217715e+04 1.34638496e+04 1.36307822e+04 1.37760088e+04 1.37906543e+04 1.37171074e+04 1.34398672e+04 1.34409854e+04 1.35850908e+04 1.35912510e+04 1.38627471e+04 1.36863086e+04 1.35226455e+04 1.35306553e+04 1.35961289e+04 1.36771025e+04 1.35165869e+04 1.36663740e+04 1.37455469e+04 1.35072910e+04 1.32408223e+04 1.32386807e+04 1.34265000e+04 1.37867949e+04 1.37538584e+04 1.33170205e+04 1.32198809e+04 1.32533330e+04 1.34581191e+04 1.36780781e+04 1.34017715e+04 1.31644834e+04 1.35643408e+04 1.34852275e+04 1.30793398e+04 1.35376396e+04 1.36006328e+04 1.31530830e+04 1.32422949e+04 1.30006006e+04 1.29569658e+04 1.35248887e+04 1.34299199e+04 1.31281758e+04 1.33025264e+04 1.32175488e+04 1.27715703e+04 1.28632559e+04 1.31514834e+04 1.31315254e+04 1.31929287e+04 1.29223691e+04 1.28106689e+04 1.30458770e+04 1.31026260e+04 1.34130674e+04 1.30996143e+04 1.25137490e+04 1.26700449e+04 1.28768008e+04 1.28966885e+04 1.30040889e+04 1.27853975e+04 1.24755342e+04 1.27557852e+04 1.29274775e+04 1.26688408e+04 1.26726787e+04 1.27048828e+04 1.24121709e+04 1.26300098e+04 1.27082666e+04 1.23766992e+04 1.27298809e+04 1.27943066e+04 1.24580293e+04 1.23878574e+04 1.20293564e+04 1.20531016e+04 1.24688750e+04 1.28164297e+04 1.25595713e+04 1.18649307e+04 1.19758652e+04 1.23347529e+04 1.22326719e+04 1.21253848e+04 1.20871660e+04 1.19963174e+04 1.21213760e+04 1.20822354e+04 1.20393975e+04 1.19695645e+04 1.19406104e+04 1.21256113e+04 1.18634268e+04 1.16232490e+04 1.16505791e+04 1.17179062e+04 1.18322559e+04 1.20094658e+04 1.17247129e+04 1.13655342e+04 1.15079082e+04 1.16424014e+04 1.18624688e+04 1.17190039e+04 1.12631152e+04 1.12798066e+04 1.13831943e+04 1.14893018e+04 1.16326738e+04 1.13821904e+04 1.10943457e+04 1.11551943e+04 1.10321338e+04 1.08820791e+04 1.12024932e+04 1.13614658e+04 1.11171719e+04 1.08694902e+04 1.07388809e+04 1.07341514e+04 1.10927988e+04 1.10892246e+04 1.08852510e+04 1.06966875e+04 1.04323320e+04 1.05113584e+04 1.06554326e+04 1.08438340e+04 1.07546592e+04 1.03432324e+04 1.03320264e+04 1.03295762e+04 1.03794092e+04 1.04279795e+04 1.04086182e+04 1.04198105e+04 1.01360703e+04 1.00985605e+04 1.01511006e+04 1.00758809e+04 1.00751865e+04 1.01036191e+04 1.00265684e+04 9.92466309e+03 9.78709668e+03 9.84741211e+03 9.99199609e+03 9.87704004e+03 9.59668359e+03 9.58249121e+03 9.57090918e+03 9.52561328e+03 9.77652637e+03 9.67414844e+03 9.39327832e+03 9.47780859e+03 9.30174902e+03 9.28125684e+03 9.51357910e+03 9.44268262e+03 9.29747461e+03 9.25805078e+03 8.78521289e+03 8.93656738e+03 9.16025879e+03 8.80267480e+03 1.27091621e+04 1.19923770e+04 2.61591035e+04 3.96918711e+04 5842296. -53043152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 22076218. 3.11208925e+06 3.47450050e+06 -3.47651975e+06 2.91575391e+04 1.94606270e+04 1.07565078e+04 7.31103662e+03 6.47983838e+03 6.46896191e+03 6.59974561e+03 6.44949805e+03 6.26064551e+03 6.01398926e+03 6.04745801e+03 6.16177734e+03 6.15053320e+03 6.07249512e+03 5.90469873e+03 5.85539307e+03 5.82150928e+03 5.87157568e+03 5.81504639e+03 5.58764941e+03 5.58995117e+03 5.66800830e+03 5.60707812e+03 5.44210547e+03 5.30635498e+03 5.43075146e+03 5.61205615e+03 5.53634912e+03 5.20989014e+03 4.94495508e+03 5.04645020e+03 5.22587207e+03 5.30068066e+03 5.13941162e+03 4.90364453e+03 4.86497314e+03 4.95661670e+03 5.01716162e+03 4.89389746e+03 4.61398486e+03 4.58441357e+03 4.79165527e+03 4.72337695e+03 4.52093359e+03 4.52838135e+03 4.52640186e+03 4.51763867e+03 4.49246680e+03 4.26898828e+03 4.15495508e+03 4.34906445e+03 4.41229248e+03 4.26403027e+03 4.07762134e+03 3.92593188e+03 4.09184741e+03 4.17741211e+03 4.05368018e+03 3.88223169e+03 3.71164062e+03 3.70900195e+03 3.86715210e+03 3.89102368e+03 3.79306226e+03 3.67440771e+03 3.63131885e+03 3.55804468e+03 3.52664771e+03 3.51313501e+03 3.38431152e+03 3.38455762e+03 3.47195947e+03 3.37853589e+03 3.19465991e+03 3.12552954e+03 3.25081201e+03 3.31075415e+03 3.21825366e+03 3.06506274e+03 2.95563770e+03 2.92895020e+03 2.96346265e+03 3.06697119e+03 2.98184058e+03 2.77676123e+03 2.75917700e+03 2.76299878e+03 2.77231274e+03 2.77833398e+03 2.63846558e+03 2.59390967e+03 2.63486353e+03 2.57184009e+03 2.50442554e+03 2.45168872e+03 2.42813623e+03 2.44458667e+03 2.40104126e+03 2.28820410e+03 2.24688623e+03 2.28432593e+03 2.28849072e+03 2.23524707e+03 2.15981909e+03 2.07226636e+03 2.06645312e+03 2.09656348e+03 2.06934351e+03 1.99549536e+03 1.87953369e+03 1.85974902e+03 1.92511768e+03 1.92576245e+03 1.85161060e+03 1.74875232e+03 1.73077734e+03 1.75297717e+03 1.71401978e+03 1.64381213e+03 1.59377563e+03 1.61767920e+03 1.61107568e+03 1.53884534e+03 1.49081030e+03 1.44463708e+03 1.45359399e+03 1.49232324e+03 1.42517981e+03 1.35195349e+03 1.30947827e+03 1.28856067e+03 1.28833667e+03 1.28547925e+03 1.24190356e+03 1.16096960e+03 1.14148022e+03 1.17242285e+03 1.15760107e+03 1.09968152e+03 1.04938562e+03 1.03929993e+03 1.03686499e+03 1.00864532e+03 9.64533569e+02 9.14082581e+02 9.01148804e+02 9.10011902e+02 8.90858765e+02 8.50953064e+02 8.09658630e+02 7.95389709e+02 7.91670288e+02 7.85037964e+02 7.57710144e+02 6.99800293e+02 6.81297668e+02 6.79797913e+02 6.61515076e+02 6.38794434e+02 6.11343994e+02 5.90896973e+02 5.71880859e+02 5.55682251e+02 5.35734375e+02 5.12643066e+02 5.07295898e+02 4.99984955e+02 4.72802155e+02 4.39511230e+02 4.19668945e+02 4.17934509e+02 4.14435089e+02 3.97178894e+02 3.69132202e+02 3.42494385e+02 3.26044861e+02 3.23943604e+02 3.24022247e+02 3.02015808e+02 2.72905212e+02 2.63791840e+02 2.58146729e+02 2.46933517e+02 2.35063553e+02 2.17893967e+02 2.05682327e+02 1.95957672e+02 1.82891617e+02 1.71187424e+02 1.63094559e+02 1.55420288e+02 1.44511108e+02 1.34289429e+02 1.24580490e+02 1.15181473e+02 1.08597649e+02 1.02233429e+02 9.36440582e+01 8.27931442e+01 7.42261734e+01 7.03062592e+01 6.53645172e+01 5.86118851e+01 5.22865868e+01 4.55079727e+01 4.03007584e+01 3.71737175e+01 3.35258675e+01 2.89074879e+01 2.42481098e+01 2.05827198e+01 1.77261333e+01 1.48292685e+01 1.22989006e+01 1.02900915e+01 8.51333618e+00 6.93341637e+00 5.72136450e+00 4.88591385e+00 4.42116833e+00 4.27233458e+00 4.44530821e+00 4.97184229e+00 5.82248116e+00 6.91071463e+00 8.51240540e+00 1.05137682e+01 1.26522980e+01 1.52595730e+01 1.79424934e+01 2.14600105e+01 2.48795280e+01 2.75350494e+01 3.12153950e+01 3.62971611e+01 4.29652939e+01 4.95780029e+01 5.41707993e+01 5.70238991e+01 6.13890915e+01 6.89392471e+01 7.98747940e+01 8.99563217e+01 9.53649521e+01 9.72889633e+01 1.04446297e+02 1.21200005e+02 1.29462509e+02 1.32384552e+02 1.42147446e+02 1.52903214e+02 1.63382538e+02 1.79212738e+02 1.86152374e+02 1.90186493e+02 2.07088654e+02 2.14986328e+02 2.31736710e+02 2.50486710e+02 2.49895050e+02 2.69035767e+02 2.91664093e+02 2.97424744e+02 3.09876160e+02 3.22861145e+02 3.41278656e+02 3.57987488e+02 3.66212769e+02 3.75910645e+02 3.93073242e+02 4.26977661e+02 4.55186768e+02 4.60443146e+02 4.57588684e+02 4.65420135e+02 4.91566406e+02 5.32117126e+02 5.66097534e+02 5.71129822e+02 5.61256409e+02 5.83310669e+02 6.23458801e+02 6.38629272e+02 6.51084900e+02 6.74182251e+02 6.89295166e+02 7.14971802e+02 7.65840271e+02 7.66566101e+02 7.66069702e+02 8.02471802e+02 8.04332153e+02 8.54378113e+02 9.02643066e+02 8.91650452e+02 9.40633301e+02 9.53819641e+02 9.37649780e+02 9.95312134e+02 9.95213501e+02 1.03359692e+03 1.13515283e+03 1.10642017e+03 1.07062891e+03 1.11961255e+03 1.19582886e+03 1.26641113e+03 1.26781726e+03 1.21822815e+03 1.21676624e+03 1.29109131e+03 1.36750916e+03 1.43924768e+03 1.44518164e+03 1.38508752e+03 1.40860864e+03 1.49093689e+03 1.55345581e+03 1.52966248e+03 1.53261462e+03 1.60519397e+03 1.63925146e+03 1.71682483e+03 1.74605090e+03 1.69749646e+03 1.72498047e+03 1.77921375e+03 1.82174023e+03 1.88021985e+03 1.89249927e+03 1.97008508e+03 1.97559583e+03 1.94010803e+03 2.00771191e+03 1.99779761e+03 2.09502881e+03 2.25857031e+03 2.17193115e+03 2.07598315e+03 2.16443066e+03 2.30691870e+03 2.40527100e+03 2.45618652e+03 2.35959277e+03 2.29655127e+03 2.38521411e+03 2.51887183e+03 2.66861035e+03 2.64366235e+03 2.51630273e+03 2.53999487e+03 2.67300293e+03 2.75023120e+03 2.83435742e+03 2.86288550e+03 2.75084912e+03 2.78835669e+03 2.95514917e+03 3.01102417e+03 2.97438867e+03 2.99337524e+03 3.02964819e+03 3.04216479e+03 3.22727563e+03 3.29293848e+03 3.16203833e+03 3.19090894e+03 3.27139551e+03 3.34201636e+03 3.39113867e+03 3.40705884e+03 3.53760181e+03 3.62920728e+03 3.53947437e+03 3.50643701e+03 3.47648999e+03 3.65190576e+03 3.91209888e+03 3.88530664e+03 3.70692261e+03 3.67232275e+03 3.85601294e+03 4.10915674e+03 4.02518262e+03 3.85267358e+03 3.95685767e+03 4.11894385e+03 4.24216064e+03 4.41963037e+03 4.38305469e+03 4.17025537e+03 4.13145459e+03 4.31811475e+03 4.52828662e+03 4.54674268e+03 4.52904639e+03 4.55570703e+03 4.56830371e+03 4.71000635e+03 4.71688477e+03 4.64716748e+03 4.65904980e+03 4.72530859e+03 4.94841943e+03 5.05797070e+03 4.95678760e+03 5.02867676e+03 5.09306787e+03 5.22771631e+03 5.13642432e+03 4.91869824e+03 5.20760352e+03 5.55673389e+03 5.44736035e+03 5.20814746e+03 5.31989160e+03 5.61238867e+03 5.66318506e+03 5.61524414e+03 5.60807080e+03 5.50394873e+03 5.55876465e+03 5.91836084e+03 5.97525049e+03 5.75074561e+03 5.63890820e+03 5.72740771e+03 6.05373535e+03 6.36220996e+03 6.11734277e+03 5.99744531e+03 6.16814355e+03 6.22493506e+03 6.47774268e+03 6.51448779e+03 6.17467139e+03 6.25061719e+03 6.47762158e+03 6.53345752e+03 6.60220752e+03 6.55214209e+03 6.77837744e+03 6.98169824e+03 6.98786963e+03 7.10305713e+03 8.50079395e+03 8.74982324e+03 1.11206436e+04 1.08562344e+04 1.04475703e+04 1.08322646e+04 1.07687988e+04 1.14318398e+04 1.20870781e+04 1.13196211e+04 1.93387344e+04 2.94667930e+04 -16059672. 12998406. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 108750536. 1.97838962e+06 4.64193650e+06 2.76625742e+04 1.97842520e+04 1.13634092e+04 1.04227285e+04 9.84720312e+03 9.52150684e+03 9.88159082e+03 9.90522070e+03 9.74862305e+03 9.84199414e+03 9.92446582e+03 9.89355664e+03 9.97095020e+03 9.98247363e+03 9.93112207e+03 9.96682227e+03 9.97830371e+03 1.02535068e+04 1.03945020e+04 9.96737402e+03 9.99515332e+03 1.05960137e+04 1.06390273e+04 1.04477617e+04 1.04488311e+04 1.04851221e+04 1.05644512e+04 1.05038828e+04 1.05879395e+04 1.06693740e+04 1.05777910e+04 1.06001201e+04 1.06393457e+04 1.09172021e+04 1.10060498e+04 1.08553838e+04 1.08835020e+04 1.09715234e+04 1.10307168e+04 1.10148262e+04 1.10159551e+04 1.10803262e+04 1.08679951e+04 1.08505684e+04 1.10888486e+04 1.11125400e+04 1.16783330e+04 1.17577900e+04 1.13142920e+04 1.10420195e+04 1.10291582e+04 1.17661680e+04 1.19505312e+04 1.15654736e+04 1.13452119e+04 1.14016865e+04 1.15936055e+04 1.15602822e+04 1.20088398e+04 1.19927480e+04 1.13336670e+04 1.13017217e+04 1.19411025e+04 1.24457305e+04 1.21544648e+04 1.19408818e+04 1.19960137e+04 1.19632920e+04 1.18625791e+04 1.19819268e+04 1.20413037e+04 1.19463643e+04 1.20342793e+04 1.20906816e+04 1.22356455e+04 1.22130664e+04 1.24986758e+04 1.25528750e+04 1.22076846e+04 1.23641816e+04 1.24288584e+04 1.25014062e+04 1.26122920e+04 1.24836406e+04 1.24908740e+04 1.22551875e+04 1.19963398e+04 1.26278691e+04 1.27728564e+04 1.22222500e+04 1.23175322e+04 1.30380547e+04 1.34388574e+04 1.30621982e+04 1.27332725e+04 1.26546914e+04 1.26725449e+04 1.26424697e+04 1.26191914e+04 1.29080557e+04 1.28982168e+04 1.31953066e+04 1.31216074e+04 1.28239277e+04 1.30308506e+04 1.26838027e+04 1.27460928e+04 1.34933975e+04 1.34156006e+04 1.30890342e+04 1.28167598e+04 1.26580928e+04 1.33493936e+04 1.36462969e+04 1.32710117e+04 1.28432686e+04 1.28532900e+04 1.31837676e+04 1.31960791e+04 1.36427051e+04 1.37606318e+04 1.33066807e+04 1.30041729e+04 1.30340459e+04 1.36480225e+04 1.36968262e+04 1.33830713e+04 1.31807178e+04 1.31758125e+04 1.34399609e+04 1.31046182e+04 1.31652617e+04 1.39381631e+04 13855. 1.35282529e+04 1.30929287e+04 1.30256113e+04 1.39352129e+04 1.39446230e+04 1.35355225e+04 1.32234639e+04 1.31417607e+04 1.35733389e+04 1.35522578e+04 1.35796348e+04 1.32970840e+04 1.34869170e+04 1.41679502e+04 1.38980518e+04 1.37084326e+04 1.37782119e+04 1.37197715e+04 1.35180352e+04 1.34960439e+04 1.36510117e+04 1.36605156e+04 1.35826367e+04 1.32130693e+04 1.34577246e+04 1.42919170e+04 1.37206094e+04 1.32559941e+04 1.36224658e+04 1.36418047e+04 1.40742266e+04 1.37963281e+04 1.32739570e+04 1.40343691e+04 1.41014668e+04 1.36642441e+04 1.36641670e+04 1.36091143e+04 1.35405537e+04 1.35725215e+04 1.36167188e+04 1.32217744e+04 1.35671816e+04 1.43821699e+04 1.41130469e+04 1.36165986e+04 1.31390889e+04 1.33190059e+04 1.41955625e+04 1.40992324e+04 1.37194375e+04 1.33698955e+04 1.32176230e+04 1.36223486e+04 1.36417451e+04 1.39617383e+04 1.36865215e+04 1.32385742e+04 1.35936992e+04 1.36053564e+04 1.39431602e+04 1.38576904e+04 1.34397529e+04 1.34560811e+04 1.34613369e+04 1.36102666e+04 1.32112402e+04 1.33900420e+04 1.41323242e+04 1.38165039e+04 1.34790176e+04 1.31742490e+04 1.30784873e+04 1.37975820e+04 1.38497881e+04 1.34548193e+04 1.30967705e+04 1.30403545e+04 1.34293652e+04 1.34436660e+04 1.37660176e+04 1.35476123e+04 1.31984697e+04 1.31066357e+04 1.30105576e+04 1.36537861e+04 1.35610449e+04 1.31731680e+04 1.31215859e+04 1.30279521e+04 1.34253086e+04 1.34582607e+04 1.28726426e+04 1.28426670e+04 1.34375889e+04 1.34400645e+04 1.28064141e+04 1.26827217e+04 1.33690527e+04 1.34191650e+04 1.29551270e+04 1.26151016e+04 1.26267012e+04 1.33719072e+04 1.32033896e+04 1.28137891e+04 1.28216973e+04 1.27179580e+04 1.27984355e+04 1.27346738e+04 1.26949717e+04 1.23362812e+04 1.26760244e+04 1.33776318e+04 1.29289648e+04 1.27136699e+04 1.27694229e+04 1.26454941e+04 1.26564746e+04 1.25995195e+04 1.25319414e+04 1.21757285e+04 1.19915391e+04 1.22764912e+04 1.25290771e+04 1.29030088e+04 1.24342236e+04 1.19669258e+04 1.23000312e+04 1.23799365e+04 1.26720020e+04 1.24920869e+04 1.21031240e+04 1.19568633e+04 1.18760098e+04 1.21337168e+04 1.21217607e+04 1.23267393e+04 1.22664639e+04 1.19921797e+04 1.17720947e+04 1.13991689e+04 1.18420527e+04 1.25200889e+04 1.22218574e+04 1.17965752e+04 1.14625215e+04 1.12779160e+04 1.18463408e+04 1.21878154e+04 1.17706182e+04 1.12676660e+04 1.12382295e+04 1.15360264e+04 1.14951338e+04 1.17650586e+04 1.16409521e+04 1.12756104e+04 1.13127441e+04 1.12343145e+04 1.14494521e+04 1.14194199e+04 1.09107754e+04 1.08924229e+04 1.14661064e+04 1.12178184e+04 1.05808457e+04 1.09148555e+04 1.14605557e+04 1.12240928e+04 1.08819805e+04 1.05591914e+04 1.05790186e+04 1.11380518e+04 1.10694150e+04 1.07159111e+04 1.03955596e+04 1.03096328e+04 1.06307432e+04 1.05493350e+04 1.04947549e+04 1.02151973e+04 1.03905918e+04 1.07782598e+04 1.04354512e+04 1.04918438e+04 1.03818594e+04 1.01119238e+04 1.01462773e+04 1.01777432e+04 1.01558809e+04 1.00280850e+04 9.88545215e+03 9.67239746e+03 9.89635840e+03 1.03765879e+04 9.84684863e+03 9.37953418e+03 9.66203906e+03 9.80280273e+03 1.00277041e+04 9.78600293e+03 9.50513672e+03 9.65918457e+03 9.59461328e+03 9.16089941e+03 9.06895605e+03 9.63313770e+03 9.57639453e+03 9.18550000e+03 9.04901562e+03 8.71983789e+03 9.08278223e+03 9.63342578e+03 9.29223242e+03 9.00818262e+03 8.71154395e+03 8.56348633e+03 8.96000293e+03 9.26124902e+03 8.96498438e+03 8.49913574e+03 8.40209668e+03 8.58641992e+03 8.61277051e+03 8.83193945e+03 8.62442676e+03 8.27229883e+03 8.40486914e+03 8.37656055e+03 8.43879102e+03 8.36417285e+03 8.14166406e+03 8.17375928e+03 8.12170459e+03 8.05387988e+03 7.79217725e+03 7.84800195e+03 8.29539160e+03 8.11096729e+03 7.75816406e+03 7.52306299e+03 7.57801953e+03 7.94837891e+03 7.91460840e+03 7.64346191e+03 7.38075049e+03 7.28719141e+03 7.44241602e+03 7.43198242e+03 7.42339990e+03 7.17247900e+03 7.25407812e+03 7.48514404e+03 7.22357178e+03 7.26499756e+03 7.20793457e+03 6.98010010e+03 6.96352148e+03 6.87255078e+03 6.83015039e+03 6.81741064e+03 6.76978174e+03 6.69403857e+03 6.81772363e+03 6.76948535e+03 6.45910645e+03 6.31830518e+03 6.44672705e+03 6.54831152e+03 6.69583057e+03 6.45332520e+03 6.09813232e+03 6.35830615e+03 6.42290723e+03 6.21702734e+03 6.01625537e+03 5.94605078e+03 6.02953223e+03 5.97500781e+03 5.93135791e+03 5.68392676e+03 5.83596045e+03 6.04587891e+03 5.85691260e+03 5.73855762e+03 5.57648242e+03 5.46202246e+03 5.69846484e+03 5.69807666e+03 5.45967529e+03 5.28418457e+03 5.13771924e+03 5.23973145e+03 5.38489600e+03 5.49359229e+03 5.19585840e+03 4.93843408e+03 5.06009912e+03 5.07867432e+03 5.17775732e+03 5.03087402e+03 4.79168018e+03 4.89047070e+03 4.86861182e+03 4.70305859e+03 4.56848486e+03 4.66080908e+03 4.84814600e+03 4.69021680e+03 4.57131250e+03 4.39338232e+03 4.34748193e+03 4.55826123e+03 4.49641064e+03 4.31654248e+03 4.17071387e+03 4.10144189e+03 4.17898193e+03 4.13413281e+03 4.19922705e+03 4.17707471e+03 3.99169995e+03 3.88321118e+03 3.89925732e+03 4.00470190e+03 3.88836353e+03 3.75986475e+03 3.76358447e+03 3.72605933e+03 3.61459521e+03 3.52876880e+03 3.63647266e+03 3.57929395e+03 3.45596875e+03 3.54818481e+03 3.51700806e+03 3.41014551e+03 3.35063794e+03 3.30951880e+03 3.26300146e+03 3.14115137e+03 3.07661694e+03 3.17691406e+03 3.20191187e+03 2.99676733e+03 2.85478760e+03 2.95925488e+03 3.08804639e+03 3.00684229e+03 2.81878589e+03 2.72887354e+03 2.82605566e+03 2.82877612e+03 2.70852026e+03 2.69297876e+03 2.58449878e+03 2.47358301e+03 2.52791309e+03 2.60204736e+03 2.57231079e+03 2.41225806e+03 2.30600903e+03 2.40525806e+03 2.44515283e+03 2.32664355e+03 2.20521606e+03 2.14247705e+03 2.17256470e+03 2.15786279e+03 2.17371997e+03 2.13710938e+03 2.02556360e+03 2.01117798e+03 1.99763110e+03 1.99019617e+03 1.90979199e+03 1.83695679e+03 1.87993945e+03 1.84698352e+03 1.79158679e+03 1.71586426e+03 1.70797131e+03 1.76771631e+03 1.67103503e+03 1.57875781e+03 1.58120862e+03 1.58111584e+03 1.56075195e+03 1.51559363e+03 1.51547302e+03 1.49762061e+03 1.42579907e+03 1.35603479e+03 1.33348865e+03 1.36931836e+03 1.31094299e+03 1.25128296e+03 1.26340503e+03 1.24152942e+03 1.19303186e+03 1.15262549e+03 1.16409521e+03 1.13325061e+03 1.07385144e+03 1.07535645e+03 1.05272754e+03 1.03834692e+03 1.01210284e+03 9.70214722e+02 9.38890503e+02 8.90788696e+02 8.61619507e+02 8.85132812e+02 8.92662354e+02 8.23482849e+02 7.62112793e+02 7.70424561e+02 7.94662720e+02 7.69879578e+02 7.08987732e+02 6.65243042e+02 6.77370789e+02 6.74484497e+02 6.35177734e+02 6.25025330e+02 6.01063843e+02 5.60788818e+02 5.47503540e+02 5.47855652e+02 5.31418701e+02 4.93554901e+02 4.65249268e+02 4.68667969e+02 4.69159760e+02 4.40021393e+02 4.05429413e+02 3.85590668e+02 3.88306458e+02 3.81477020e+02 3.55309540e+02 3.33446533e+02 3.19993134e+02 3.10515594e+02 2.95560059e+02 2.89852386e+02 2.70892456e+02 2.48888565e+02 2.45140015e+02 2.34062668e+02 2.22098038e+02 2.06274536e+02 1.91798752e+02 1.87588058e+02 1.72521362e+02 1.60205872e+02 1.61568771e+02 1.51002853e+02 1.36021545e+02 1.79560791e+02 1.93166275e+02 1.84347092e+02 1.75769501e+02 1.61752701e+02 1.06570282e+02 1.03665428e+02 1.09385681e+02 9.26648712e+01 7.18597946e+01 7.56747665e+01 8.55662460e+01 2.79829010e+02 5.14280150e+06 0. 0. 0. 0. 0. 0. 12921689. 12921689. 9.54277267e+01 1.39233459e+02 1.39233459e+02 8468770. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 8.35270050e+06 -3125617. 2.34385650e+06 9.99447327e+01 9.40303268e+01 7.94194107e+01 5.60778046e+01 7.66611786e+01 7.46185379e+01 7.70200958e+01 8.23642883e+01 9.04592743e+01 1.01372284e+02 1.10263863e+02 1.14504852e+02 1.21517166e+02 1.33977875e+02 1.44195282e+02 1.52196060e+02 1.62208221e+02 1.72135971e+02 1.82244400e+02 1.97465118e+02 2.09253510e+02 2.13756592e+02 2.26967682e+02 2.47281631e+02 2.61256836e+02 2.72614014e+02 2.79565826e+02 2.88427948e+02 3.10167145e+02 3.28307434e+02 3.38846161e+02 3.49736542e+02 3.63709747e+02 3.86993774e+02 4.03395111e+02 4.14363373e+02 4.27344482e+02 4.43787842e+02 4.79425781e+02 5.00318909e+02 4.91692841e+02 5.05474365e+02 5.37395325e+02 5.57633057e+02 5.83441650e+02 6.00678467e+02 6.06190369e+02 6.36277100e+02 6.61360229e+02 6.76568298e+02 6.97732910e+02 7.09114563e+02 7.36088074e+02 7.66602173e+02 7.80374939e+02 7.99368896e+02 8.17572937e+02 8.44448669e+02 8.85494263e+02 9.10973145e+02 9.24676941e+02 9.32395996e+02 9.50523132e+02 1.00307660e+03 1.03233655e+03 1.02676843e+03 1.06193457e+03 1.09374365e+03 1.12344812e+03 1.17597095e+03 1.18910974e+03 1.17632117e+03 1.20640198e+03 1.27425452e+03 1.31461255e+03 1.29509485e+03 1.29944287e+03 1.35783789e+03 1.39994397e+03 1.45711304e+03 1.48033606e+03 1.45876538e+03 1.50285083e+03 1.56974487e+03 1.58989868e+03 1.60097339e+03 1.60347803e+03 1.63227039e+03 1.72429333e+03 1.76328149e+03 1.74693201e+03 1.78877393e+03 1.83001965e+03 1.85306250e+03 1.88226624e+03 1.91701428e+03 1.97414453e+03 1.99348889e+03 2.05295972e+03 2.09247607e+03 2.05175854e+03 2.09259277e+03 2.17556885e+03 2.19862915e+03 2.21588477e+03 2.25575879e+03 2.30189038e+03 2.36898535e+03 2.38880054e+03 2.39716895e+03 2.47017114e+03 2.52245801e+03 2.50619580e+03 2.53644312e+03 2.59018726e+03 2.64377271e+03 2.67684546e+03 2.67135547e+03 2.71111646e+03 2.78718384e+03 2.89007764e+03 2.90835474e+03 2.83600952e+03 2.91548218e+03 3.02807886e+03 3.04115039e+03 3.06772900e+03 3.05925439e+03 3.07551953e+03 3.18574341e+03 3.30100244e+03 3.29688257e+03 3.24548486e+03 3.29375903e+03 3.43612085e+03 3.47741040e+03 3.52738184e+03 3.50049658e+03 3.46614722e+03 3.55930835e+03 3.61650757e+03 3.65930762e+03 3.71580981e+03 3.72546460e+03 3.80705444e+03 3.95920068e+03 3.92580640e+03 3.82666504e+03 3.91419580e+03 4.05195483e+03 4.08715747e+03 4.18392383e+03 4.17643359e+03 4.10631201e+03 4.21451270e+03 4.38157959e+03 4.37159912e+03 4.21770361e+03 4.34087061e+03 4.52391699e+03 4.54624902e+03 4.54314453e+03 4.52220020e+03 4.54680908e+03 4.67992871e+03 4.73286768e+03 4.79246533e+03 4.86626562e+03 4.78690332e+03 4.91642529e+03 5.05635400e+03 5.01142578e+03 4.94972510e+03 5.05057080e+03 5.18319043e+03 5.25949463e+03 5.26043945e+03 5.19741992e+03 5.18371973e+03 5.33891455e+03 5.61269385e+03 5.66561279e+03 5.37707275e+03 5.43467920e+03 5.70278711e+03 5.71054688e+03 5.70952148e+03 5.69082568e+03 5.65431445e+03 5.85778760e+03 6.02334375e+03 5.98595850e+03 5.90333643e+03 5.92895410e+03 6.04185498e+03 6.21534473e+03 6.31561963e+03 6.23653809e+03 6.21271875e+03 6.32791504e+03 6.38560889e+03 6.41221045e+03 6.42801660e+03 6.49013867e+03 6.46913916e+03 6.69444287e+03 6.84950732e+03 6.52914697e+03 6.61138184e+03 6.90076562e+03 6.88967139e+03 6.94779688e+03 6.81834570e+03 6.90342822e+03 7.20607031e+03 7.15639893e+03 7.11840576e+03 7.04554639e+03 7.03417676e+03 7.27355811e+03 7.48606396e+03 7.39045312e+03 7.37566309e+03 7.56571777e+03 7.52757422e+03 7.70729395e+03 7.70986865e+03 7.51223877e+03 7.55396777e+03 7.62706641e+03 7.92721191e+03 7.91816309e+03 7.79630566e+03 7.89576514e+03 8.07835156e+03 8.12509961e+03 8.08259326e+03 8.10520654e+03 8.16348193e+03 8.27118262e+03 8.25714258e+03 8.46100293e+03 8.38161914e+03 8.26068750e+03 8.57330273e+03 8.39837109e+03 8.49820215e+03 8.73282324e+03 8.57435059e+03 8.64060059e+03 8.75331543e+03 8.77273145e+03 8.77101660e+03 8.69032617e+03 9.07819629e+03 9.32199414e+03 8.86167578e+03 8.90030273e+03 9.07749512e+03 9.13775488e+03 9.36671094e+03 9.32249512e+03 9.14295703e+03 9.22604688e+03 9.47584180e+03 9.54204492e+03 9.49986523e+03 9.36709082e+03 9.48585059e+03 9.61616113e+03 9.56888574e+03 9.62440625e+03 9.59581250e+03 9.62780273e+03 9.80237402e+03 9.98622754e+03 1.00057861e+04 9.85794531e+03 9.81442383e+03 1.01078408e+04 1.03374775e+04 1.00605195e+04 1.02024629e+04 1.02267500e+04 9.95089746e+03 1.03154131e+04 1.03656260e+04 1.02012754e+04 1.04068037e+04 1.04822061e+04 1.04348379e+04 1.06957910e+04 1.05430264e+04 1.04925498e+04 1.06156357e+04 1.07459326e+04 1.08284033e+04 1.06245850e+04 1.06027070e+04 1.08331084e+04 1.10018174e+04 1.10208779e+04 1.09258223e+04 1.08169395e+04 1.11320264e+04 1.14506660e+04 1.11512080e+04 1.09542861e+04 1.10033857e+04 1.13156768e+04 1.14807217e+04 1.12227646e+04 1.11718057e+04 1.13174512e+04 1.14272734e+04 1.14192080e+04 1.15802520e+04 1.15452705e+04 1.12613428e+04 1.16124209e+04 1.19724551e+04 1.16856660e+04 1.12995117e+04 1.14680615e+04 1.17625107e+04 1.19290781e+04 1.19090420e+04 1.17636367e+04 1.17358389e+04 1.20462520e+04 1.22992090e+04 1.19748711e+04 1.18380693e+04 1.19771602e+04 1.23411523e+04 1.22684678e+04 1.18610010e+04 1.18974561e+04 1.21248262e+04 1.22091660e+04 1.23516670e+04 1.24323994e+04 1.22616240e+04 1.23304912e+04 1.23693604e+04 1.21716133e+04 1.22473398e+04 1.22778389e+04 1.25268877e+04 1.26992471e+04 1.24662246e+04 1.22886846e+04 1.24472383e+04 1.27875303e+04 1.31256602e+04 1.29238887e+04 1.23990986e+04 1.25536152e+04 1.28070791e+04 1.27188740e+04 1.26453701e+04 1.27494287e+04 1.28390566e+04 1.28842852e+04 1.28105479e+04 1.25859355e+04 1.28346738e+04 1.31310820e+04 1.32162500e+04 1.30734062e+04 1.27497393e+04 1.29169062e+04 1.29591875e+04 1.28379219e+04 1.32614971e+04 1.32611143e+04 1.28838320e+04 1.29598096e+04 1.30588105e+04 1.34503018e+04 1.34817998e+04 1.31792119e+04 1.31814297e+04 1.32203867e+04 1.31770244e+04 1.30620938e+04 1.33014932e+04 1.33586084e+04 1.34799756e+04 1.35245420e+04 1.29934824e+04 1.31566602e+04 1.33380693e+04 1.33875078e+04 1.37913184e+04 1.33628799e+04 1.30472461e+04 1.36106289e+04 1.38091611e+04 1.35194033e+04 1.34092695e+04 1.32610225e+04 1.32587842e+04 1.33899053e+04 1.35349492e+04 1.34713877e+04 1.36513271e+04 1.38998594e+04 1.36330107e+04 1.34503906e+04 1.33710771e+04 1.35835088e+04 1.38522266e+04 1.36501045e+04 1.33725820e+04 1.33748047e+04 1.35457383e+04 1.37810879e+04 1.40750645e+04 1.36809531e+04 1.33697773e+04 1.36768594e+04 1.35874160e+04 1.35167090e+04 1.38623193e+04 1.37495254e+04 1.34836611e+04 1.37344404e+04 1.37098486e+04 1.36515684e+04 1.38228887e+04 1.37718145e+04 1.36502324e+04 1.35413584e+04 1.36412744e+04 1.35342207e+04 1.36783887e+04 1.38535176e+04 1.37344824e+04 1.36664580e+04 1.34707109e+04 1.35880391e+04 1.36244736e+04 1.35536689e+04 1.37750703e+04 1.37451846e+04 1.35511113e+04 1.35808525e+04 1.35872295e+04 1.38944824e+04 1.39802822e+04 1.36486836e+04 1.35021270e+04 1.34206992e+04 1.35136104e+04 1.35557900e+04 1.36821387e+04 1.37992646e+04 1.35723828e+04 1.34826328e+04 1.34178945e+04 13561. 1.38728818e+04 1.37170332e+04 1.34705674e+04 1.33992842e+04 1.33888613e+04 1.33665254e+04 1.35556895e+04 1.36795400e+04 1.35482520e+04 1.34586172e+04 1.33348799e+04 1.33388496e+04 1.35096113e+04 1.34438418e+04 1.35243271e+04 1.34820996e+04 1.32473809e+04 1.35465215e+04 1.32644180e+04 1.30542598e+04 1.35233633e+04 1.33821338e+04 1.31433662e+04 1.32821816e+04 1.31597783e+04 1.30554971e+04 1.36052422e+04 1.35820439e+04 1.28858564e+04 1.30042305e+04 1.31698535e+04 1.29926113e+04 1.32706611e+04 1.31868887e+04 1.28088633e+04 1.29467383e+04 1.29321016e+04 1.31549160e+04 1.33153379e+04 1.30367822e+04 1.30996543e+04 1.28273779e+04 1.24644824e+04 1.27352832e+04 1.30961162e+04 1.29100996e+04 1.29074688e+04 1.28280283e+04 12376. 1.25804795e+04 1.31613350e+04 1.29876846e+04 1.25991279e+04 1.23803535e+04 1.23367617e+04 1.27521172e+04 1.28293213e+04 1.25095625e+04 1.26327227e+04 1.24605752e+04 1.24600557e+04 1.25376719e+04 1.20832891e+04 1.21994941e+04 1.25719424e+04 1.26061094e+04 1.23109590e+04 1.19675957e+04 1.19696660e+04 1.22280791e+04 1.24345908e+04 1.23240449e+04 1.19530645e+04 1.17683418e+04 1.20427676e+04 1.22072148e+04 1.23478428e+04 1.21240947e+04 1.17339346e+04 1.19002773e+04 1.17928535e+04 1.16953779e+04 1.18779824e+04 1.17741055e+04 1.17268545e+04 1.19362031e+04 1.16699004e+04 1.15228545e+04 1.16416367e+04 1.16276514e+04 1.16891045e+04 1.14471699e+04 1.12457861e+04 1.12744072e+04 1.14571592e+04 1.16116318e+04 1.15754570e+04 1.13339404e+04 1.10359697e+04 1.10830713e+04 1.10732100e+04 1.11466895e+04 1.12438115e+04 1.10211025e+04 1.09068682e+04 1.08801064e+04 1.08567676e+04 1.09930303e+04 1.12350811e+04 1.10089434e+04 1.06991621e+04 1.06368857e+04 1.04060215e+04 1.05108857e+04 1.07717393e+04 1.08141953e+04 1.06664297e+04 1.03666387e+04 1.02906084e+04 1.03462363e+04 1.04754170e+04 1.04263242e+04 1.03946045e+04 1.02531562e+04 1.00017314e+04 1.01783018e+04 1.04023506e+04 1.02683701e+04 9.87110742e+03 9.94438184e+03 9.96755078e+03 9.98480371e+03 9.97481348e+03 9.86709766e+03 9.92114551e+03 9.71810938e+03 9.55550000e+03 9.79229102e+03 9.70497168e+03 9.61930566e+03 9.68743750e+03 9.38699512e+03 9.24406641e+03 9.47593848e+03 9.41405176e+03 9.43029980e+03 9.69396484e+03 9.56313086e+03 9.21290723e+03 8.96264258e+03 9.08652637e+03 9.53395117e+03 1.18372266e+04 1.14678682e+04 2.27428164e+04 2.39533555e+04 -1.88733650e+06 14400814. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 675334528. -4.39045850e+06 2.69257949e+04 1.45479062e+04 7.16516455e+03 9.09119043e+03 1.06493838e+04 9.17526562e+03 7.39817773e+03 6.98111377e+03 6.40166650e+03 6.34493506e+03 6.51652197e+03 6.35064355e+03 6.22436963e+03 6.05420215e+03 5.98686865e+03 6.20027441e+03 6.29000928e+03 6.01387402e+03 5.79188672e+03 5.79753711e+03 5.84535938e+03 5.90093115e+03 5.92363818e+03 5.66836035e+03 5.53279590e+03 5.56810498e+03 5.55484229e+03 5.50709473e+03 5.38153271e+03 5.31237891e+03 5.46556738e+03 5.52257178e+03 5.35840479e+03 5.06323145e+03 5.01195703e+03 5.18451465e+03 5.18386963e+03 5.03594043e+03 4.84874316e+03 4.85508057e+03 5.03205811e+03 5.06833984e+03 4.88853760e+03 4.58084424e+03 4.61332471e+03 4.79467334e+03 4.71541553e+03 4.66230420e+03 4.52345020e+03 4.35136426e+03 4.39103223e+03 4.50630469e+03 4.36735645e+03 4.24251221e+03 4.35130322e+03 4.32035303e+03 4.21733789e+03 4.13189062e+03 3.94219775e+03 4.01583521e+03 4.18025635e+03 4.03248340e+03 3.85504492e+03 3.77535034e+03 3.72781836e+03 3.86217603e+03 3.93856372e+03 3.76151709e+03 3.61045776e+03 3.54614160e+03 3.50014990e+03 3.55309204e+03 3.61663062e+03 3.45943750e+03 3.33928564e+03 3.39796387e+03 3.34721094e+03 3.24120605e+03 3.20419043e+03 3.22727783e+03 3.24617334e+03 3.17940015e+03 3.12471680e+03 3.00566626e+03 2.89664355e+03 3.01807861e+03 3.08421313e+03 2.87740967e+03 2.74184155e+03 2.76053345e+03 2.80586768e+03 2.80863525e+03 2.79218335e+03 2.65396875e+03 2.57233691e+03 2.60187378e+03 2.56594263e+03 2.54788062e+03 2.48831104e+03 2.38506348e+03 2.36654272e+03 2.39469800e+03 2.36028760e+03 2.31526392e+03 2.29258374e+03 2.24935498e+03 2.19464697e+03 2.16680444e+03 2.08272046e+03 2.03422375e+03 2.11154736e+03 2.09569702e+03 1.95105139e+03 1.87404626e+03 1.87950891e+03 1.94046472e+03 1.93970972e+03 1.84195251e+03 1.74898730e+03 1.71414917e+03 1.70871997e+03 1.70415173e+03 1.67897363e+03 1.63791833e+03 1.60445142e+03 1.56659143e+03 1.53795898e+03 1.51539844e+03 1.45440527e+03 1.44741382e+03 1.47432483e+03 1.40986182e+03 1.35083398e+03 1.31860107e+03 1.27374280e+03 1.30070081e+03 1.30057288e+03 1.21478076e+03 1.16012744e+03 1.15245764e+03 1.17812964e+03 1.17008447e+03 1.10339697e+03 1.04509253e+03 1.01787646e+03 1.00454907e+03 1.00445227e+03 9.88672668e+02 9.30328369e+02 8.85552917e+02 8.91264221e+02 8.95617798e+02 8.62952820e+02 8.20158386e+02 8.01888428e+02 7.84113281e+02 7.61978333e+02 7.46665771e+02 6.99741943e+02 6.78077026e+02 6.85172119e+02 6.62343445e+02 6.32521790e+02 6.03856689e+02 5.85633911e+02 5.73449341e+02 5.60828491e+02 5.46722412e+02 5.14278870e+02 4.97870911e+02 4.91980927e+02 4.68563141e+02 4.44698242e+02 4.26677063e+02 4.10457092e+02 4.02144257e+02 3.96288788e+02 3.73140961e+02 3.42298462e+02 3.26947266e+02 3.26536255e+02 3.19723572e+02 2.99979553e+02 2.72821625e+02 2.60132263e+02 2.54346130e+02 2.45179306e+02 2.33288452e+02 2.14342926e+02 2.00251999e+02 1.91397690e+02 1.83945358e+02 1.75934753e+02 1.63059601e+02 1.51053574e+02 1.41541519e+02 1.32435135e+02 1.24474167e+02 1.15832596e+02 1.07414520e+02 9.81484299e+01 8.92185898e+01 8.08151703e+01 7.36008224e+01 6.94687881e+01 6.53849335e+01 5.81776810e+01 4.99535294e+01 4.31585579e+01 3.87702560e+01 3.61354675e+01 3.23908463e+01 2.71902847e+01 2.24042606e+01 1.85851269e+01 1.58939543e+01 1.34884958e+01 1.09951134e+01 8.80187988e+00 6.93383932e+00 5.38534546e+00 4.24274874e+00 3.42220616e+00 2.94083333e+00 2.77431679e+00 2.94514441e+00 3.47700858e+00 4.37075472e+00 5.42997503e+00 6.92110157e+00 8.91234779e+00 1.10808983e+01 1.36452360e+01 1.64269180e+01 1.99882164e+01 2.35589943e+01 2.64308014e+01 2.97711048e+01 3.47134514e+01 4.12829018e+01 4.78147316e+01 5.26352501e+01 5.57975998e+01 6.03094482e+01 6.72047195e+01 7.75175552e+01 8.77920227e+01 9.38484879e+01 9.62199097e+01 1.03220543e+02 1.19252296e+02 1.26918854e+02 1.30771896e+02 1.41446167e+02 1.51753723e+02 1.61849487e+02 1.77920563e+02 1.85383957e+02 1.89161850e+02 2.05448303e+02 2.13544525e+02 2.29879669e+02 2.48557449e+02 2.49854813e+02 2.67851044e+02 2.88604828e+02 2.95774841e+02 3.09507233e+02 3.21707336e+02 3.41249634e+02 3.56042664e+02 3.62371368e+02 3.72034576e+02 3.91055267e+02 4.28307343e+02 4.54948608e+02 4.58720276e+02 4.56277557e+02 4.63278442e+02 4.89605804e+02 5.29502808e+02 5.64794067e+02 5.69343750e+02 5.56384155e+02 5.81993408e+02 6.24343994e+02 6.35193604e+02 6.52920898e+02 6.76041809e+02 6.85475891e+02 7.13211914e+02 7.66609619e+02 7.62737366e+02 7.64233093e+02 8.03026489e+02 8.00664246e+02 8.51669983e+02 9.06085266e+02 8.89634216e+02 9.37755920e+02 9.52318298e+02 9.36875427e+02 9.91485962e+02 9.91526978e+02 1.03974146e+03 1.13691357e+03 1.09865491e+03 1.06945190e+03 1.11656116e+03 1.19508228e+03 1.26383374e+03 1.27291199e+03 1.22757239e+03 1.22097034e+03 1.27749915e+03 1.34967407e+03 1.43765881e+03 1.44077478e+03 1.39013562e+03 1.41939246e+03 1.48721545e+03 1.54361646e+03 1.53005371e+03 1.54443958e+03 1.59548999e+03 1.62750659e+03 1.71660583e+03 1.75527454e+03 1.69668372e+03 1.70768762e+03 1.77930505e+03 1.82026758e+03 1.87078516e+03 1.88950854e+03 1.97631323e+03 1.97140454e+03 1.92578467e+03 2.01911121e+03 2.00263672e+03 2.08251196e+03 2.25836548e+03 2.17596460e+03 2.07503564e+03 2.16194482e+03 2.31712769e+03 2.40733838e+03 2.42943213e+03 2.34245117e+03 2.30377759e+03 2.38826245e+03 2.51155859e+03 2.66259277e+03 2.63298730e+03 2.51036646e+03 2.53739478e+03 2.67058667e+03 2.73535352e+03 2.83881860e+03 2.88815698e+03 2.74664478e+03 2.77652148e+03 2.92876758e+03 2.99735498e+03 2.97400342e+03 3.00082446e+03 3.04492383e+03 3.03486035e+03 3.23446924e+03 3.27308423e+03 3.15960376e+03 3.19673291e+03 3.26972803e+03 3.32040503e+03 3.37135938e+03 3.40858691e+03 3.54358691e+03 3.61413745e+03 3.55116870e+03 3.51433569e+03 3.47771973e+03 3.67234790e+03 3.89735181e+03 3.86293115e+03 3.70426416e+03 3.67463843e+03 3.83900488e+03 4.08466577e+03 4.02272290e+03 3.83557373e+03 3.97346094e+03 4.15605273e+03 4.21632520e+03 4.41834912e+03 4.37835107e+03 4.16360107e+03 4.12930713e+03 4.30033887e+03 4.49856738e+03 4.56009082e+03 4.51774609e+03 4.54492236e+03 4.58265674e+03 4.71516016e+03 4.71218311e+03 4.65201953e+03 4.71835400e+03 4.69145312e+03 4.92603369e+03 5.10821924e+03 4.95614111e+03 5.02960596e+03 5.10595361e+03 5.14664502e+03 5.06253564e+03 5.01982080e+03 5.26382666e+03 5.53286572e+03 5.41984326e+03 5.21402832e+03 5.30264160e+03 5.59756299e+03 5.71666260e+03 5.66231104e+03 5.65783252e+03 5.50085742e+03 5.53715820e+03 5.83291162e+03 5.90306543e+03 5.82817188e+03 5.74625586e+03 5.71597217e+03 6.04902783e+03 6.33119678e+03 6.09306738e+03 5.98422412e+03 6.19537061e+03 6.17653760e+03 6.46051514e+03 6.51988037e+03 6.23998682e+03 6.19255859e+03 6.42389893e+03 6.50232275e+03 6.61110010e+03 6.59404688e+03 6.81403516e+03 6.99386914e+03 6.96762695e+03 7.26156201e+03 7.83890479e+03 7.29774951e+03 1.10529570e+04 1.05570244e+04 1.59784883e+04 2.22539258e+04 -5323589. -2.57037125e+06 -2.54422925e+06 5228936. -8529687. 30089492. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -34787364. -1.43508650e+06 3.87283086e+04 2.48610293e+04 1.65667148e+04 1.35029541e+04 1.24263701e+04 1.02933516e+04 1.01555244e+04 9.79419336e+03 9.51705469e+03 9.81325391e+03 9.85784277e+03 9.74883496e+03 9.87207812e+03 9.86916895e+03 9.88461621e+03 9.92923438e+03 9.98111914e+03 9.96720508e+03 9.92403125e+03 9.93432715e+03 1.02819561e+04 1.03974785e+04 9.93316895e+03 9.96854785e+03 1.05873633e+04 1.06819014e+04 1.04346484e+04 1.04301387e+04 1.05184238e+04 1.05266348e+04 1.04572881e+04 1.06288447e+04 1.06550459e+04 1.05989141e+04 1.04715918e+04 1.05169277e+04 1.10159053e+04 1.11237041e+04 1.08063779e+04 1.08696338e+04 1.09610752e+04 1.10238398e+04 1.09658643e+04 1.09754346e+04 1.11092520e+04 1.10168809e+04 1.09598555e+04 1.10495166e+04 1.10500186e+04 1.16057754e+04 1.17057275e+04 1.13182012e+04 1.10551846e+04 1.10454639e+04 1.17724258e+04 1.18900723e+04 1.15066582e+04 1.13582168e+04 1.14455020e+04 1.16396631e+04 1.15454014e+04 1.19698154e+04 1.19939912e+04 1.13667148e+04 1.12965898e+04 1.19000967e+04 1.24244814e+04 1.21548965e+04 1.19030703e+04 1.19489336e+04 1.19408115e+04 1.19610547e+04 1.19869072e+04 1.21430264e+04 1.21598623e+04 1.19953408e+04 1.20259258e+04 1.21176367e+04 1.21036406e+04 1.25604707e+04 1.25412969e+04 1.22205244e+04 1.22210547e+04 1.22774141e+04 1.26366221e+04 1.27436943e+04 1.24355957e+04 1.24508154e+04 1.22680693e+04 1.20938926e+04 1.27121992e+04 1.26790029e+04 1.20773799e+04 1.23089229e+04 1.30177529e+04 1.34547861e+04 1.30823936e+04 1.27492988e+04 1.26115859e+04 1.26176982e+04 1.27328271e+04 1.27677178e+04 1.28189121e+04 1.27931924e+04 1.31536377e+04 1.31407070e+04 1.28298896e+04 1.29073936e+04 1.25351904e+04 1.28543740e+04 1.36979717e+04 1.34189395e+04 1.30580889e+04 1.27707354e+04 1.27342412e+04 1.34730195e+04 1.35413604e+04 1.31703809e+04 1.28704883e+04 1.28219277e+04 1.31187646e+04 1.31979414e+04 1.36337256e+04 1.37294580e+04 1.32946328e+04 1.31328555e+04 1.31804385e+04 1.34811475e+04 1.35535850e+04 1.34059385e+04 1.31764658e+04 1.32129150e+04 1.33520371e+04 1.29382549e+04 1.32635332e+04 1.40813252e+04 1.38549736e+04 1.35244385e+04 1.31050791e+04 1.30479873e+04 1.39223379e+04 1.39400078e+04 1.34997002e+04 1.32176436e+04 1.31831357e+04 1.36160430e+04 1.35312588e+04 1.35455771e+04 1.33035605e+04 1.35023271e+04 1.41974580e+04 1.38780156e+04 1.36757051e+04 1.37987627e+04 1.37206650e+04 1.34551797e+04 1.34633389e+04 1.35560771e+04 1.35047207e+04 1.36847148e+04 1.33392441e+04 1.34678242e+04 1.43500137e+04 1.37466094e+04 1.32265156e+04 1.35873936e+04 1.36258008e+04 1.40581572e+04 1.39056836e+04 1.33866836e+04 1.38805303e+04 1.39660205e+04 1.36863320e+04 1.36536660e+04 1.36182041e+04 1.35694639e+04 1.35378604e+04 1.35791387e+04 1.32623818e+04 1.36142705e+04 1.43610361e+04 1.40917109e+04 1.36112598e+04 1.31459756e+04 1.33366016e+04 1.41714121e+04 1.40814131e+04 1.36833438e+04 1.33764805e+04 1.32324238e+04 1.35737002e+04 1.36497500e+04 1.39476523e+04 1.38107148e+04 1.34218838e+04 1.34790410e+04 1.34467852e+04 1.39284951e+04 1.38619756e+04 1.34190244e+04 1.34653154e+04 1.34823672e+04 1.34655459e+04 1.30824922e+04 1.34715654e+04 1.42991406e+04 1.38814795e+04 1.34596025e+04 1.31321074e+04 1.30087949e+04 1.37836641e+04 1.38880547e+04 1.34494834e+04 1.30909941e+04 1.30396406e+04 1.34081250e+04 1.33982500e+04 1.37125586e+04 1.36878584e+04 1.33452354e+04 1.29630088e+04 1.28902949e+04 1.36561885e+04 1.35789023e+04 1.31880508e+04 1.29802812e+04 1.28641963e+04 1.35912734e+04 1.36377783e+04 1.28068252e+04 1.27672979e+04 1.34672881e+04 1.34481660e+04 1.27593350e+04 1.27291299e+04 1.33591309e+04 1.34176084e+04 1.29703438e+04 1.26377705e+04 1.26587676e+04 1.33177246e+04 1.31102129e+04 1.26825205e+04 1.28655527e+04 1.28176494e+04 1.27878740e+04 1.27811865e+04 1.27524434e+04 1.23580117e+04 1.26428779e+04 1.32419717e+04 1.28366562e+04 1.28799023e+04 1.29109307e+04 1.26439785e+04 1.26270293e+04 1.25830420e+04 1.25049238e+04 1.22090752e+04 1.21690186e+04 1.24114834e+04 1.23888711e+04 1.27875977e+04 1.24132256e+04 1.19343799e+04 1.22630098e+04 1.23403369e+04 1.27072363e+04 1.25005166e+04 1.20906816e+04 1.19474746e+04 1.18990010e+04 1.21005498e+04 1.20575537e+04 1.23353721e+04 1.22477969e+04 1.19377725e+04 1.18686797e+04 1.14781240e+04 1.17809609e+04 1.24331504e+04 1.22558535e+04 1.18207373e+04 1.14533652e+04 1.12695420e+04 1.18037002e+04 1.21694443e+04 1.18091455e+04 1.12766768e+04 1.12652109e+04 1.15380605e+04 1.14876055e+04 1.17141982e+04 1.16441807e+04 1.12716738e+04 1.12343076e+04 1.11930234e+04 1.15333887e+04 1.15469336e+04 1.09031191e+04 1.08390420e+04 1.14329785e+04 1.13095303e+04 1.06799600e+04 1.08261758e+04 1.13185869e+04 1.12363516e+04 1.09705049e+04 1.06062246e+04 1.05142861e+04 1.10704277e+04 1.10686143e+04 1.07328184e+04 1.04115996e+04 1.02685840e+04 1.05422373e+04 1.05931494e+04 1.05412607e+04 1.01883047e+04 1.03612744e+04 1.07864092e+04 1.04865186e+04 1.04921104e+04 1.03553213e+04 1.01209121e+04 1.01534062e+04 1.01432178e+04 1.01798623e+04 1.00728350e+04 9.83496387e+03 9.59873535e+03 9.85794629e+03 1.03179414e+04 9.74308203e+03 9.36140918e+03 9.65243457e+03 9.84572754e+03 1.01281758e+04 9.79722754e+03 9.44803711e+03 9.63880176e+03 9.65706934e+03 9.30651855e+03 9.14805957e+03 9.51580762e+03 9.43609375e+03 9.13948438e+03 9.12624121e+03 8.77245801e+03 9.08056348e+03 9.59432617e+03 9.30537500e+03 9.00383105e+03 8.70900586e+03 8.55741602e+03 8.96323730e+03 9.28474414e+03 8.95637500e+03 8.53047656e+03 8.51622754e+03 8.56122363e+03 8.49286230e+03 8.73376758e+03 8.59837012e+03 8.30262500e+03 8.33860156e+03 8.28312402e+03 8.49378906e+03 8.48734570e+03 8.13368652e+03 8.12018506e+03 8.10485840e+03 8.12367090e+03 7.91970996e+03 7.85106055e+03 8.11393555e+03 8.01250293e+03 7.88312744e+03 7.61274951e+03 7.58543213e+03 8.00671777e+03 7.90469385e+03 7.63012305e+03 7.42052344e+03 7.29856836e+03 7.33410889e+03 7.32338965e+03 7.39805322e+03 7.19520605e+03 7.21905762e+03 7.42793701e+03 7.14672168e+03 7.28123584e+03 7.28805615e+03 7.02775928e+03 6.94722217e+03 6.90918164e+03 6.86047412e+03 6.85706592e+03 6.73930518e+03 6.68736426e+03 6.82339502e+03 6.78150928e+03 6.42012939e+03 6.35445996e+03 6.43800879e+03 6.50637598e+03 6.69671924e+03 6.47159570e+03 6.12510059e+03 6.30749219e+03 6.38713623e+03 6.17328564e+03 6.11141113e+03 6.04268262e+03 5.92636768e+03 5.89162695e+03 5.98210889e+03 5.78247070e+03 5.78610352e+03 6.04023926e+03 5.84118799e+03 5.71020947e+03 5.56820361e+03 5.48006201e+03 5.69658252e+03 5.64682422e+03 5.46754297e+03 5.28341162e+03 5.11370068e+03 5.23832617e+03 5.37037891e+03 5.47811084e+03 5.24708691e+03 5.03847656e+03 4.99992822e+03 5.01832275e+03 5.16053906e+03 5.07850635e+03 4.86494727e+03 4.80485352e+03 4.74430176e+03 4.77310742e+03 4.64421191e+03 4.64354102e+03 4.80639600e+03 4.67967041e+03 4.56850000e+03 4.42065186e+03 4.34046289e+03 4.55868115e+03 4.50227783e+03 4.30663916e+03 4.18557275e+03 4.13203271e+03 4.17278174e+03 4.11016016e+03 4.22689062e+03 4.21109229e+03 4.00089258e+03 3.86377563e+03 3.85631592e+03 4.03945459e+03 3.93986792e+03 3.78661938e+03 3.71174487e+03 3.67121387e+03 3.62881934e+03 3.56592114e+03 3.61832690e+03 3.55020850e+03 3.44444507e+03 3.52930322e+03 3.52780859e+03 3.40695215e+03 3.35797681e+03 3.28375562e+03 3.25586963e+03 3.13599487e+03 3.07440112e+03 3.17840381e+03 3.18691016e+03 2.99515942e+03 2.88318823e+03 2.98403076e+03 3.06020996e+03 2.99105640e+03 2.82919678e+03 2.72248047e+03 2.80045532e+03 2.81213696e+03 2.71145874e+03 2.69242798e+03 2.57560840e+03 2.44955493e+03 2.50995532e+03 2.63364209e+03 2.58717407e+03 2.39900977e+03 2.30112231e+03 2.40364844e+03 2.44524023e+03 2.33089160e+03 2.21352368e+03 2.15504272e+03 2.15572021e+03 2.14879224e+03 2.18110400e+03 2.15701147e+03 2.05430176e+03 1.98566528e+03 1.95289160e+03 1.99843994e+03 1.92437292e+03 1.84544226e+03 1.89140674e+03 1.85265173e+03 1.79577954e+03 1.72190527e+03 1.68818579e+03 1.75284851e+03 1.66877576e+03 1.57731128e+03 1.59101562e+03 1.57977087e+03 1.56071021e+03 1.51480176e+03 1.51595239e+03 1.49300928e+03 1.42759497e+03 1.35325488e+03 1.32780554e+03 1.37263489e+03 1.31928259e+03 1.26168579e+03 1.24494983e+03 1.21414343e+03 1.20934607e+03 1.17587134e+03 1.15447253e+03 1.12409277e+03 1.07237915e+03 1.07954871e+03 1.06089807e+03 1.02898193e+03 1.00127234e+03 9.66951294e+02 9.37181091e+02 8.88032654e+02 8.59439880e+02 8.88124268e+02 8.95895569e+02 8.22568665e+02 7.66906738e+02 7.78292847e+02 7.90151489e+02 7.60406067e+02 7.07393982e+02 6.70688538e+02 6.82634766e+02 6.63104309e+02 6.24628479e+02 6.30459167e+02 6.02766541e+02 5.53218750e+02 5.43688660e+02 5.52744629e+02 5.37119446e+02 4.93841492e+02 4.63884949e+02 4.68997498e+02 4.69275208e+02 4.39934448e+02 4.04322876e+02 3.83710144e+02 3.87896393e+02 3.76738190e+02 3.50423920e+02 3.38758789e+02 3.26487823e+02 3.06830963e+02 2.89872955e+02 2.86736481e+02 2.69379089e+02 2.47824448e+02 2.43399384e+02 2.33231262e+02 2.22086700e+02 2.04817230e+02 1.89366669e+02 1.86012848e+02 1.71372070e+02 1.58105270e+02 1.58623703e+02 1.48324799e+02 1.40388809e+02 1.61907562e+02 1.40490631e+02 1.56286560e+02 1.56870316e+02 1.54918884e+02 1.05087624e+02 1.04092018e+02 1.54013855e+02 1.77117523e+02 -10052639. -4429931. -3.53763375e+06 9168474. -1341259136. 0. 0. 0. 0. 0. 0. 12921689. 12921689. -16745002. 24974414. 24974414. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 8.35270050e+06 -3125617. 2.34385650e+06 1.00314713e+02 1.08313271e+02 8.68455048e+01 8.78501434e+01 9.20724411e+01 7.88212509e+01 8.43880310e+01 8.73226013e+01 9.03582077e+01 9.78983536e+01 1.05936653e+02 1.14967758e+02 1.22162903e+02 1.30168030e+02 1.43210434e+02 1.53360916e+02 1.62352539e+02 1.72734314e+02 1.77990540e+02 1.89138519e+02 2.06037949e+02 2.16472260e+02 2.25675873e+02 2.44835129e+02 2.65167114e+02 2.69461884e+02 2.75720886e+02 2.89627319e+02 3.01309113e+02 3.22719208e+02 3.43706879e+02 3.53291809e+02 3.67401093e+02 3.89973938e+02 4.00892303e+02 4.07937531e+02 4.26524109e+02 4.42544495e+02 4.62125641e+02 4.93028351e+02 5.01296661e+02 5.11555023e+02 5.44363098e+02 5.54777649e+02 5.65964478e+02 5.86568115e+02 6.07922974e+02 6.36537598e+02 6.61990967e+02 6.87637268e+02 6.96877930e+02 7.07358337e+02 7.43140930e+02 7.51788269e+02 7.58686951e+02 8.05696350e+02 8.29036743e+02 8.45886780e+02 8.84541138e+02 9.06193115e+02 9.11142273e+02 9.36010376e+02 9.60374329e+02 9.75207397e+02 1.01321088e+03 1.04633777e+03 1.07825476e+03 1.10616760e+03 1.11553931e+03 1.14427527e+03 1.16788757e+03 1.20005530e+03 1.22494397e+03 1.25595728e+03 1.32400696e+03 1.31523364e+03 1.29354980e+03 1.36531445e+03 1.39268408e+03 1.40318591e+03 1.46629272e+03 1.48481921e+03 1.50643860e+03 1.57412109e+03 1.61496753e+03 1594. 1.59519482e+03 1.63502063e+03 1.68130957e+03 1.74242017e+03 1.78053674e+03 1.82017383e+03 1.85831714e+03 1.87374695e+03 1.87100879e+03 1.88644592e+03 1.96476990e+03 1.99335791e+03 2.00017908e+03 2.07614502e+03 2.10185352e+03 2.11458252e+03 2.18860083e+03 2.20013647e+03 2.16459985e+03 2.22572461e+03 2.33323169e+03 2.37065503e+03 2.37721704e+03 2.42554541e+03 2.47947021e+03 2.52351245e+03 2.55106250e+03 2.51705640e+03 2.53273486e+03 2.66308691e+03 2.71371216e+03 2.69142700e+03 2.75599341e+03 2.76870386e+03 2.79289404e+03 2.88793994e+03 2.90347363e+03 2.89958252e+03 2.96965894e+03 3.06761523e+03 3.11525146e+03 3.11632007e+03 3.08472900e+03 3.09833350e+03 3.22436157e+03 3.32103687e+03 3.26805859e+03 3.31742993e+03 3.47754736e+03 3.49408447e+03 3.48757251e+03 3.49706641e+03 3.47381494e+03 3.48773853e+03 3.57757910e+03 3.71233618e+03 3.74433594e+03 3.76007031e+03 3.83803345e+03 3.89174390e+03 3.87524072e+03 3.83537085e+03 3.90703198e+03 4.04179004e+03 4.12475000e+03 4.20796191e+03 4.21334229e+03 4.19494580e+03 4.18045605e+03 4.28763867e+03 4.37315332e+03 4.26463916e+03 4.30937256e+03 4.50307471e+03 4.60371631e+03 4.54326660e+03 4.54399609e+03 4.56762012e+03 4.57549658e+03 4.71683252e+03 4.88444531e+03 4.91038867e+03 4.86151123e+03 4.90821143e+03 4.97252734e+03 4.96375146e+03 4.99085254e+03 5.07833252e+03 5.09235303e+03 5.27775439e+03 5.38833936e+03 5.18780664e+03 5.26082373e+03 5.33145752e+03 5.40286328e+03 5.55045898e+03 5.44233740e+03 5.42104297e+03 5.62697266e+03 5.73975244e+03 5.74206396e+03 5.74113525e+03 5.73239014e+03 5.74321924e+03 5.86763770e+03 6.00101514e+03 6.03555518e+03 5.93937695e+03 6.10525977e+03 6.26429688e+03 6.19831055e+03 6.21110693e+03 6.21247314e+03 6.27008398e+03 6.45344971e+03 6.41659131e+03 6.42740625e+03 6.62827393e+03 6.47085986e+03 6.47937451e+03 6.71318994e+03 6.58964795e+03 6.68665332e+03 6.91654297e+03 6.91029590e+03 6.96852441e+03 6.89465381e+03 6.96549854e+03 6.99825684e+03 7.05280811e+03 7.22930566e+03 7.12817969e+03 7.05522510e+03 7.34326953e+03 7.45652637e+03 7.31930957e+03 7.45765576e+03 7.60372559e+03 7.39912988e+03 7.58827148e+03 7.79799658e+03 7.60400977e+03 7.59840625e+03 7.74360889e+03 7.79389600e+03 7.78371484e+03 7.85766309e+03 7.88134473e+03 8.00075488e+03 8.14786719e+03 8.14546875e+03 8.16947412e+03 8.19700293e+03 8.18973242e+03 8.22380078e+03 8.44518848e+03 8.28311328e+03 8.28973145e+03 8.61289551e+03 8.52966602e+03 8.40488379e+03 8.58715137e+03 8.59808496e+03 8.58368848e+03 8.68355664e+03 8.79211914e+03 8.93045410e+03 8.92639062e+03 8.97228125e+03 9.06527246e+03 8.87982715e+03 8.98789160e+03 9.09499219e+03 9.03159961e+03 9.28365918e+03 9.47658594e+03 9.24343164e+03 9.15226172e+03 9.28316992e+03 9.59552734e+03 9.52719141e+03 9.22506250e+03 9.51274121e+03 9.79906250e+03 9.62466016e+03 9.66533691e+03 9.67347754e+03 9.65671387e+03 9.81782812e+03 9.76235547e+03 9.76781152e+03 1.00540488e+04 1.01489443e+04 1.00196367e+04 1.01368184e+04 1.01784814e+04 1.02846689e+04 1.01102471e+04 9.90900391e+03 1.02753203e+04 1.05612891e+04 1.02560752e+04 1.02396055e+04 1.03704414e+04 1.05739629e+04 1.06079521e+04 1.02989502e+04 1.06099424e+04 1.08453447e+04 1.07135635e+04 1.07325391e+04 1.06987764e+04 1.06270342e+04 1.07944102e+04 1.09002598e+04 1.08388311e+04 1.11186523e+04 1.11413730e+04 1.10628154e+04 1.12123936e+04 1.11679561e+04 1.10082793e+04 1.10377266e+04 1.12729658e+04 1.14116982e+04 1.12491816e+04 1.11675137e+04 1.11872676e+04 1.13160400e+04 1.15649375e+04 1.15884707e+04 1.13827139e+04 1.13499072e+04 1.16859131e+04 1.18875498e+04 1.16395361e+04 1.14808125e+04 1.15247256e+04 1.17363975e+04 1.17818643e+04 1.17274258e+04 1.19818496e+04 1.19748740e+04 1.18928096e+04 1.21677520e+04 1.21434229e+04 1.19213203e+04 1.19357910e+04 1.21119150e+04 1.21775674e+04 1.18593818e+04 1.17704189e+04 1.21121641e+04 1.22975391e+04 1.24766133e+04 1.23569307e+04 1.20873896e+04 1.24522002e+04 1.26211260e+04 1.22043330e+04 1.21230400e+04 1.24874258e+04 1.27434678e+04 1.25717949e+04 1.23096484e+04 1.22732754e+04 1.24599238e+04 1.27430801e+04 1.29460898e+04 1.29033984e+04 1.25923467e+04 1.25256748e+04 1.26714863e+04 1.26076182e+04 1.26665283e+04 1.27177002e+04 1.26999688e+04 1.28426182e+04 1.29267197e+04 1.28808154e+04 1.27638516e+04 1.29062598e+04 1.33308818e+04 1.32031982e+04 1.27434834e+04 1.27280879e+04 1.30318467e+04 1.32352842e+04 1.33598760e+04 1.31394277e+04 1.27201133e+04 1.28458496e+04 1.32298369e+04 1.34413887e+04 1.34534502e+04 1.31625605e+04 1.30463350e+04 1.32548408e+04 1.31883359e+04 1.33064375e+04 1.32764639e+04 1.29426826e+04 1.33391406e+04 1.36410273e+04 1.34111006e+04 1.31837080e+04 1.29241738e+04 1.32017070e+04 1.38883369e+04 1.37808301e+04 1.32136416e+04 1.34695635e+04 1.37728652e+04 1.33705596e+04 1.32617627e+04 1.31572588e+04 1.32644541e+04 1.37547012e+04 1.36670303e+04 1.32590117e+04 1.34252559e+04 1.37422422e+04 1.35847686e+04 1.35371611e+04 1.37651357e+04 1.35719238e+04 1.33930869e+04 1.35592695e+04 1.35687920e+04 1.37682793e+04 1.37609238e+04 1.36472168e+04 1.37090938e+04 1.34340439e+04 1.34907148e+04 1.36281934e+04 1.35970186e+04 1.38246016e+04 1.38357998e+04 1.37565723e+04 1.35711787e+04 1.34649209e+04 1.36423428e+04 1.37859482e+04 1.37787998e+04 1.35666719e+04 1.36203545e+04 1.37365332e+04 1.36514326e+04 1.37328564e+04 1.36895625e+04 1.34534043e+04 1.36023125e+04 1.36603867e+04 1.35878682e+04 1.37472607e+04 1.35973564e+04 1.34823877e+04 1.38957305e+04 1.40551855e+04 1.34603809e+04 1.32974385e+04 1.37040879e+04 1.38913857e+04 1.38404658e+04 1.35377363e+04 1.33533760e+04 1.35343086e+04 1.37475977e+04 1.36797305e+04 1.34674512e+04 1.35164023e+04 1.36060088e+04 1.35316582e+04 1.36504883e+04 1.37048145e+04 1.35579717e+04 1.35829404e+04 1.35939062e+04 1.36050195e+04 1.34929775e+04 1.33457441e+04 1.34574424e+04 1.35410703e+04 1.35569854e+04 1.33841299e+04 1.32825645e+04 1.35510234e+04 1.35496953e+04 1.34278252e+04 1.35263730e+04 1.32209766e+04 1.30949131e+04 1.36312217e+04 1.35359092e+04 1.30400518e+04 1.33826533e+04 1.34684443e+04 1.30318838e+04 1.33401973e+04 1.34160977e+04 1.30202881e+04 1.33080625e+04 1.34019609e+04 1.29875352e+04 1.31133115e+04 1.32623037e+04 1.31249951e+04 1.31650527e+04 1.30466133e+04 1.27575479e+04 1.29033965e+04 1.31177021e+04 1.32005889e+04 1.32322812e+04 1.29086211e+04 1.29314385e+04 1.28492412e+04 1.25687402e+04 1.29335801e+04 1.29995312e+04 1.27242275e+04 1.29323164e+04 1.28111748e+04 1.25422754e+04 1.27660449e+04 1.29026260e+04 1.28761650e+04 1.26629775e+04 1.25449697e+04 1.23515596e+04 1.26734873e+04 1.30415352e+04 1.24872207e+04 1.24463965e+04 1.23482100e+04 1.23526758e+04 1.26941143e+04 1.23067393e+04 1.21236201e+04 1.23707549e+04 1.24902891e+04 1.23153242e+04 1.19548838e+04 1.21548740e+04 1.23972578e+04 1.22044297e+04 1.22037998e+04 1.19977480e+04 1.19831426e+04 1.22189951e+04 1.21337842e+04 1.21750215e+04 1.18827178e+04 1.17051650e+04 1.18728203e+04 1.18755820e+04 1.19502539e+04 1.18435635e+04 1.15736104e+04 1.16360996e+04 1.18175137e+04 1.18006494e+04 1.16542090e+04 1.15878652e+04 1.15245635e+04 1.16215840e+04 1.14917051e+04 1.12798115e+04 1.15264385e+04 1.15323408e+04 1.13112646e+04 1.14671221e+04 1.13369717e+04 1.11041875e+04 1.11667539e+04 1.10615117e+04 1.10884219e+04 1.12060137e+04 1.10362852e+04 1.08547500e+04 1.09295146e+04 1.09454775e+04 1.09090957e+04 1.11464424e+04 1.08896406e+04 1.05978672e+04 1.07356035e+04 1.05819209e+04 1.05873906e+04 1.06086133e+04 1.06245342e+04 1.07227910e+04 1.04462188e+04 1.05187734e+04 1.04221357e+04 1.01885771e+04 1.02730312e+04 1.04336709e+04 1.04148682e+04 1.01862734e+04 1.01134297e+04 1.02338047e+04 1.01156299e+04 9.99352734e+03 9.97734766e+03 9.94403320e+03 1.00916924e+04 9.92673242e+03 9.83305078e+03 9.87817383e+03 9.66223047e+03 9.58549707e+03 9.84272754e+03 9.81294531e+03 9.56510547e+03 9.50203711e+03 9.33174023e+03 9.34616016e+03 9.71060059e+03 9.47992285e+03 9.21466211e+03 9.54707129e+03 9.54706738e+03 9.37656738e+03 9.03870215e+03 9.09277441e+03 9.49940918e+03 1.03663691e+04 1.00772080e+04 2.19597500e+04 2.85319766e+04 2.68697325e+06 3148385. -50108404. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 675334528. -4.39045850e+06 2.69257949e+04 1.45479062e+04 7.16516455e+03 9.09119043e+03 1.16112666e+04 1.01565713e+04 8.80127441e+03 8.53551562e+03 6.35498047e+03 6.40895166e+03 6.58893408e+03 6.39974902e+03 6.23157666e+03 6.12300488e+03 6.13470703e+03 6.23348242e+03 6.13707373e+03 5.95090137e+03 5.77602930e+03 5.90998779e+03 5.90364600e+03 5.81730518e+03 5.81853857e+03 5.63058105e+03 5.56883545e+03 5.64171924e+03 5.60694385e+03 5.54196436e+03 5.32625000e+03 5.26143457e+03 5.48097559e+03 5.54796484e+03 5.34729736e+03 5.05834424e+03 5.01246631e+03 5.15899902e+03 5.14880420e+03 5.05029639e+03 4.90889795e+03 4.99073291e+03 5.01127734e+03 4.92206445e+03 4.83927930e+03 4.61768457e+03 4.64045996e+03 4.85666699e+03 4.70549756e+03 4.62914502e+03 4.52867432e+03 4.39963721e+03 4.41570361e+03 4.52822021e+03 4.43616260e+03 4.22209717e+03 4.29119043e+03 4.27870459e+03 4.19435107e+03 4.15787061e+03 4.01274048e+03 4.05298828e+03 4.09626660e+03 3.95440015e+03 3.87717456e+03 3.79059448e+03 3.82705566e+03 3.92406152e+03 3.84864380e+03 3.72198730e+03 3.59677734e+03 3.59117993e+03 3.55097192e+03 3.56866455e+03 3.57075586e+03 3.40501392e+03 3.39123633e+03 3.45444946e+03 3.38711060e+03 3.28583716e+03 3.15295044e+03 3.17239917e+03 3.24986670e+03 3.19639697e+03 3.10406836e+03 2.98655518e+03 2.95130713e+03 2.98887061e+03 3.01188867e+03 2.88124194e+03 2.77030640e+03 2.83924878e+03 2.80144287e+03 2.71957544e+03 2.76371167e+03 2.65649634e+03 2.59351416e+03 2.61227539e+03 2.57142700e+03 2.54852124e+03 2.44523291e+03 2.38345996e+03 2.39169897e+03 2.41307422e+03 2.38713989e+03 2.28284961e+03 2.26694775e+03 2.23645020e+03 2.18118091e+03 2.17121802e+03 2.09813892e+03 2.06645410e+03 2.09310156e+03 2.05782739e+03 1.95867273e+03 1.87205750e+03 1.90445813e+03 1.96462146e+03 1.90690454e+03 1.82590405e+03 1.74432312e+03 1.72045251e+03 1.73175610e+03 1.72005115e+03 1.69056897e+03 1.61481763e+03 1.58364758e+03 1.55751575e+03 1.53903394e+03 1.54604028e+03 1.45933655e+03 1.42760779e+03 1.45779553e+03 1.39576086e+03 1.35418665e+03 1.32594141e+03 1.30442798e+03 1.30332080e+03 1.26177612e+03 1.20147607e+03 1.15581226e+03 1.16702271e+03 1.18933289e+03 1.14523108e+03 1.08832434e+03 1.04093311e+03 1.02559229e+03 1.01931946e+03 1.00660822e+03 9.78979126e+02 9.16294006e+02 8.89378967e+02 8.98098694e+02 8.86802673e+02 8.71062988e+02 8.22621521e+02 7.92658936e+02 7.74570557e+02 7.55328857e+02 7.48968872e+02 7.07218079e+02 6.86797180e+02 6.78077332e+02 6.51709717e+02 6.35162354e+02 6.02476501e+02 5.90978271e+02 5.83063965e+02 5.52885071e+02 5.38484802e+02 5.14811890e+02 4.96262054e+02 4.88469177e+02 4.70497833e+02 4.46672729e+02 4.21279846e+02 4.06905792e+02 4.01960785e+02 3.94967590e+02 3.72865082e+02 3.41450714e+02 3.24800262e+02 3.22771759e+02 3.14779694e+02 2.97418793e+02 2.71756134e+02 2.62556152e+02 2.55656860e+02 2.40932404e+02 2.30172409e+02 2.13227295e+02 2.02224838e+02 1.94149246e+02 1.83940903e+02 1.73473846e+02 1.59814041e+02 1.50245132e+02 1.40761963e+02 1.31685196e+02 1.25067650e+02 1.13909851e+02 1.04814011e+02 9.69848404e+01 8.84686279e+01 8.06940155e+01 7.39340744e+01 6.93203506e+01 6.34750061e+01 5.64171906e+01 4.90339928e+01 4.21814842e+01 3.84843864e+01 3.54053688e+01 3.06974201e+01 2.57294693e+01 2.11453552e+01 1.75543156e+01 1.49681721e+01 1.25919361e+01 9.95776081e+00 7.61813688e+00 5.80495405e+00 4.27541161e+00 3.10836649e+00 2.26762891e+00 1.76670563e+00 1.61433816e+00 1.80198765e+00 2.32950401e+00 3.19021487e+00 4.22156763e+00 5.78389120e+00 7.73296642e+00 9.68579674e+00 1.23265085e+01 1.52062702e+01 1.87956791e+01 2.22619209e+01 2.50445957e+01 2.88743267e+01 3.39159126e+01 4.02336578e+01 4.67462311e+01 5.12185822e+01 5.44327202e+01 5.89919395e+01 6.65261917e+01 7.71669540e+01 8.64953232e+01 9.22506943e+01 9.48471756e+01 1.02118927e+02 1.18235504e+02 1.26281746e+02 1.28377441e+02 1.38221970e+02 1.51506561e+02 1.61847855e+02 1.76986450e+02 1.83768158e+02 1.86941147e+02 2.04436615e+02 2.13190842e+02 2.28233963e+02 2.47302261e+02 2.48854645e+02 2.66746826e+02 2.88472687e+02 2.95802490e+02 3.08207397e+02 3.20266998e+02 3.40158997e+02 3.54434662e+02 3.63493500e+02 3.72440674e+02 3.88983521e+02 4.24979706e+02 4.53742279e+02 4.58482941e+02 4.55535156e+02 4.64061981e+02 4.86825653e+02 5.26287048e+02 5.65850647e+02 5.69016602e+02 5.57617920e+02 5.82487427e+02 6.23701477e+02 6.36479492e+02 6.48060974e+02 6.71027039e+02 6.84997314e+02 7.12505127e+02 7.63990784e+02 7.64256042e+02 7.65334961e+02 8.02387634e+02 8.01153198e+02 8.46697021e+02 8.99364563e+02 8.90280090e+02 9.34987976e+02 9.54768311e+02 9.40088440e+02 9.87646240e+02 9.86915894e+02 1.03641785e+03 1.13483997e+03 1.09818408e+03 1.06690808e+03 1.12119666e+03 1.19871924e+03 1.26280847e+03 1.26677258e+03 1.22249280e+03 1.22081860e+03 1.27816699e+03 1.35142883e+03 1.44373486e+03 1.43949878e+03 1.37695435e+03 1.41202222e+03 1.49191321e+03 1.54294531e+03 1.52592236e+03 1.54409570e+03 1.59289148e+03 1.62723145e+03 1.72291541e+03 1.75821643e+03 1.69080640e+03 1.71347900e+03 1.78278528e+03 1.81975928e+03 1.86137378e+03 1.88925403e+03 1.97310815e+03 1.97048572e+03 1.92906091e+03 2.01319995e+03 1.99936389e+03 2.09332056e+03 2.25743018e+03 2.16242920e+03 2.06736841e+03 2.16642188e+03 2.32222778e+03 2.41415723e+03 2.43109595e+03 2.33051709e+03 2.29283423e+03 2.37985205e+03 2.51947998e+03 2.66259375e+03 2.64037549e+03 2.51726001e+03 2.53443042e+03 2.67167847e+03 2.72253467e+03 2.81964087e+03 2.87324048e+03 2.74370386e+03 2.78692749e+03 2.93609595e+03 2.99908789e+03 2.98867163e+03 3.00438916e+03 3.02105664e+03 3.01898511e+03 3.23984912e+03 3.28286743e+03 3.18248901e+03 3.21019800e+03 3.23373901e+03 3.29371704e+03 3.37455298e+03 3.40594336e+03 3.57184033e+03 3.61409009e+03 3.50663818e+03 3.50017480e+03 3.48355493e+03 3.66907983e+03 3.91857544e+03 3.86233936e+03 3.69804907e+03 3.68569189e+03 3.87726465e+03 4.09440503e+03 3.99013452e+03 3.81808301e+03 3.97418506e+03 4.12952637e+03 4.24017432e+03 4.42081934e+03 4.34281982e+03 4.15799414e+03 4.17253711e+03 4.34060107e+03 4.46326270e+03 4.52820215e+03 4.51207031e+03 4.54217969e+03 4.58073145e+03 4.71116211e+03 4.68743262e+03 4.60607715e+03 4.68750830e+03 4.74595850e+03 4.99478809e+03 5.06862598e+03 4.96080566e+03 5.02284912e+03 5.07328906e+03 5.14183740e+03 5.04400146e+03 5.00205273e+03 5.26839844e+03 5.54285889e+03 5.41752441e+03 5.20352490e+03 5.30082715e+03 5.60099365e+03 5.71764502e+03 5.66115723e+03 5.59588623e+03 5.51069824e+03 5.59545752e+03 5.82540186e+03 5.85241113e+03 5.78365869e+03 5.70970801e+03 5.73678467e+03 6.07239111e+03 6.37366016e+03 6.08086914e+03 5.95533643e+03 6.17541113e+03 6.20592969e+03 6.45395361e+03 6.46375391e+03 6.15612061e+03 6.25008838e+03 6.50881445e+03 6.50417285e+03 6.56847266e+03 6.57660986e+03 6.75625586e+03 7.06069727e+03 7.03131641e+03 7.32329443e+03 8.95204883e+03 8.57064941e+03 1.08588164e+04 1.05620557e+04 1.61714756e+04 2.14748184e+04 -6.69654250e+06 -23465656. -27570792. -3590639. -6.11310250e+06 -43394564. -1.79721050e+06 -100529800. 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. 0. 0. 0. 0. 0. 0. 0. 0. -34787364. -1.43508650e+06 3.87283086e+04 2.48610293e+04 1.65667148e+04 1.54815078e+04 1.23580781e+04 1.17628184e+04 1.01918193e+04 1.04173662e+04 9.64711816e+03 9.91164062e+03 9.96673633e+03 9.78453320e+03 9.84266211e+03 9.90710449e+03 9.89231152e+03 9.92608105e+03 9.91775586e+03 9.89771191e+03 1.00394453e+04 1.00291436e+04 1.01586562e+04 1.03090283e+04 9.94548633e+03 9.98038574e+03 1.06213799e+04 1.06412334e+04 1.03866895e+04 1.04102773e+04 1.05314785e+04 1.05238125e+04 1.05074541e+04 1.05848672e+04 1.06235791e+04 1.06427305e+04 1.05407422e+04 1.05791172e+04 1.09645908e+04 1.10532773e+04 1.08513984e+04 1.08677539e+04 1.09371348e+04 1.09950234e+04 1.09748633e+04 1.09908760e+04 1.11504141e+04 1.09772891e+04 1.09057930e+04 1.10482070e+04 1.11161123e+04 1.16212090e+04 1.16793447e+04 1.12820127e+04 1.10539268e+04 1.10852773e+04 1.17645527e+04 1.18968643e+04 1.15206436e+04 1.13165410e+04 1.13366006e+04 1.16494629e+04 1.16853271e+04 1.19530684e+04 1.20433340e+04 1.14414775e+04 1.12487100e+04 1.18761826e+04 1.24116807e+04 1.21409629e+04 1.18907656e+04 1.19186777e+04 1.19090273e+04 1.19235010e+04 1.20098838e+04 1.19975938e+04 1.19766738e+04 1.21160664e+04 1.21671289e+04 1.21441963e+04 1.21293643e+04 1.25547588e+04 1.26352178e+04 1.23351035e+04 1.22242900e+04 1.23093125e+04 1.25313809e+04 1.25932461e+04 1.24627129e+04 1.24943418e+04 1.22916807e+04 1.21050996e+04 1.26849619e+04 1.26716592e+04 1.20794248e+04 1.22941387e+04 1.29893115e+04 1.34507090e+04 1.30656689e+04 1.27500654e+04 1.26042070e+04 1.26048359e+04 1.27445986e+04 1.27696211e+04 1.27999062e+04 1.27494541e+04 1.32237910e+04 1.32841631e+04 1.28660684e+04 1.28646221e+04 1.25648496e+04 1.27540273e+04 1.35196445e+04 1.33668867e+04 1.30684717e+04 1.28338018e+04 1.26945664e+04 1.33220547e+04 1.35852959e+04 1.32953945e+04 1.29210791e+04 1.28667734e+04 1.31362197e+04 1.31868330e+04 1.36556787e+04 1.37659512e+04 1.33042637e+04 1.31377119e+04 1.31344492e+04 1.34599229e+04 1.35705400e+04 1.33989756e+04 1.32969277e+04 1.33363594e+04 1.33455781e+04 1.29466689e+04 1.31518438e+04 1.39399912e+04 1.38043926e+04 1.34671660e+04 1.31221523e+04 1.30797578e+04 1.38836338e+04 1.39188633e+04 1.34900312e+04 1.32207881e+04 1.32070020e+04 1.35779727e+04 1.34971768e+04 1.35705586e+04 1.32948936e+04 1.35238066e+04 1.43617119e+04 1.40045537e+04 1.36005137e+04 1.36544766e+04 1.36706084e+04 1.36086846e+04 1.36285234e+04 1.35278164e+04 1.34637666e+04 1.35540508e+04 1.32435117e+04 1.34582207e+04 1.42831387e+04 1.37199102e+04 1.32587568e+04 1.36144590e+04 1.36018721e+04 1.40641260e+04 1.39042715e+04 1.33654297e+04 1.39011035e+04 1.39636992e+04 1.36615039e+04 1.36284863e+04 1.35978408e+04 1.36793945e+04 1.36881953e+04 1.34771309e+04 1.31424756e+04 1.36095059e+04 1.43165732e+04 1.40495576e+04 1.37499990e+04 1.33168232e+04 1.32114297e+04 1.39843799e+04 1.41298906e+04 1.37738838e+04 1.33361836e+04 1.31968066e+04 1.35967246e+04 1.36643486e+04 1.39631133e+04 1.37554307e+04 1.33851992e+04 1.35045117e+04 1.34381553e+04 1.39231631e+04 1.38970352e+04 1.34338379e+04 1.35339697e+04 1.35528789e+04 1.34630879e+04 1.30631973e+04 1.33643799e+04 1.41777588e+04 1.38535342e+04 1.34736104e+04 1.31297402e+04 1.30124727e+04 1.38028555e+04 1.38702871e+04 1.34238506e+04 1.31085039e+04 1.30373330e+04 1.34002910e+04 1.34041211e+04 1.36785498e+04 1.35671191e+04 1.32236328e+04 1.30991699e+04 1.30206816e+04 1.36106328e+04 1.35918945e+04 1.31841719e+04 1.30665449e+04 1.30116768e+04 1.34917402e+04 1.35057637e+04 1.27906582e+04 1.27743379e+04 1.34893633e+04 1.34409062e+04 1.27668037e+04 1.27194492e+04 1.33524023e+04 1.34393887e+04 1.29719287e+04 1.26492158e+04 1.26674629e+04 1.33195820e+04 1.30923711e+04 1.27036768e+04 1.29726514e+04 1.29509502e+04 1.27749287e+04 1.26327031e+04 1.26788223e+04 1.23287236e+04 1.26495928e+04 1.33648740e+04 1.29322217e+04 1.27175771e+04 1.27635352e+04 1.26433965e+04 1.26068838e+04 1.25499453e+04 1.25426484e+04 1.22257529e+04 1.20088662e+04 1.22950078e+04 1.25548350e+04 1.28756338e+04 1.24167715e+04 1.19259365e+04 1.22396348e+04 1.23611836e+04 1.27522061e+04 1.25741504e+04 1.21459941e+04 1.18858555e+04 1.17707959e+04 1.21004561e+04 1.21006104e+04 1.23214502e+04 1.23047637e+04 1.20224609e+04 1.17775850e+04 1.13994043e+04 1.17543164e+04 1.23831943e+04 1.22333877e+04 1.18617256e+04 1.14742373e+04 1.12916465e+04 1.18254854e+04 1.21294707e+04 1.17540430e+04 1.13094346e+04 1.12748154e+04 1.15131641e+04 1.14910713e+04 1.17768691e+04 1.17481699e+04 1.13641611e+04 1.11991699e+04 1.11276484e+04 1.14341025e+04 1.14491699e+04 1.09219854e+04 1.08770859e+04 1.14364170e+04 1.12875996e+04 1.06709492e+04 1.07939893e+04 1.13129717e+04 1.12127637e+04 1.09496494e+04 1.06129707e+04 1.04900820e+04 1.10630410e+04 1.10871533e+04 1.07427646e+04 1.04042373e+04 1.03037441e+04 1.05243291e+04 1.05554805e+04 1.05421719e+04 1.01755938e+04 1.03489453e+04 1.08779307e+04 1.05688711e+04 1.04052500e+04 1.03922607e+04 1.02360898e+04 1.01516787e+04 1.01277334e+04 1.01226250e+04 1.00381035e+04 9.87960352e+03 9.58286328e+03 9.82899512e+03 1.02510508e+04 9.76061816e+03 9.45788184e+03 9.72741992e+03 9.78919922e+03 1.00589375e+04 9.84988086e+03 9.46159961e+03 9.64844824e+03 9.61838770e+03 9.26760449e+03 9.15666895e+03 9.58688574e+03 9.46319824e+03 9.17556836e+03 8.97773633e+03 8.74241406e+03 9.09032324e+03 9.60443945e+03 9.33138281e+03 8.94942285e+03 8.71637598e+03 8.60401562e+03 9.02635449e+03 9.18082812e+03 8.88835547e+03 8.54246582e+03 8.47156641e+03 8.51895312e+03 8.57950293e+03 8.76702246e+03 8.66398047e+03 8.40072070e+03 8.35409961e+03 8.28271191e+03 8.43383691e+03 8.45349316e+03 8.24666992e+03 8.11025488e+03 8.01994727e+03 8.10131934e+03 7.87389502e+03 7.84672705e+03 8.15132715e+03 8.03906445e+03 7.87335156e+03 7.66452295e+03 7.51090088e+03 7.95202734e+03 7.89263086e+03 7.61386279e+03 7.42055713e+03 7.31931055e+03 7.36511377e+03 7.35588135e+03 7.35177686e+03 7.19195459e+03 7.26118652e+03 7.48346973e+03 7.21738525e+03 7.23155908e+03 7.23154395e+03 7.05822510e+03 6.97982275e+03 6.83799023e+03 6.83050488e+03 6.83398291e+03 6.79101758e+03 6.72472363e+03 6.76239990e+03 6.75936035e+03 6.45876807e+03 6.32472070e+03 6.43513037e+03 6.49979688e+03 6.64075146e+03 6.43022803e+03 6.21421484e+03 6.37318213e+03 6.28803955e+03 6.14941846e+03 6.12246631e+03 6.05550586e+03 5.95717090e+03 5.90590332e+03 5.93452979e+03 5.73151416e+03 5.78374658e+03 6.00821777e+03 5.84350928e+03 5.73748584e+03 5.60266602e+03 5.44483496e+03 5.68854248e+03 5.64739160e+03 5.48816064e+03 5.30040479e+03 5.15368262e+03 5.27109375e+03 5.31505371e+03 5.43378662e+03 5.22152100e+03 5.02640625e+03 5.05944531e+03 4.99943018e+03 5.12254443e+03 5.05488281e+03 4.84605566e+03 4.83215918e+03 4.76547559e+03 4.76624854e+03 4.60879590e+03 4.63986328e+03 4.83312695e+03 4.71201123e+03 4.58832422e+03 4.42265283e+03 4.30836719e+03 4.53061230e+03 4.50584082e+03 4.31142432e+03 4.16407861e+03 4.12553516e+03 4.20327734e+03 4.15287744e+03 4.20452441e+03 4.17209766e+03 4.01856226e+03 3.89723486e+03 3.82322266e+03 3.99870190e+03 3.94269800e+03 3.76958423e+03 3.75067432e+03 3.72230371e+03 3.63240625e+03 3.59122241e+03 3.64925488e+03 3.51167261e+03 3.40086523e+03 3.55869751e+03 3.53254614e+03 3.39585889e+03 3.33068530e+03 3.28667651e+03 3.26293164e+03 3.12769946e+03 3.06756812e+03 3.19968237e+03 3.17525122e+03 2.96809033e+03 2.88441699e+03 2.99538599e+03 3.07200659e+03 2.96748145e+03 2.81243970e+03 2.75236621e+03 2.82651440e+03 2.77603491e+03 2.68036914e+03 2.68775854e+03 2.58974292e+03 2.47408691e+03 2.53829321e+03 2.62474023e+03 2.55480249e+03 2.40430884e+03 2.33251831e+03 2.41130420e+03 2.42994116e+03 2.32029272e+03 2.22075977e+03 2.18054761e+03 2.17628589e+03 2.14517090e+03 2.18249072e+03 2.11972778e+03 2.00813025e+03 2.01780676e+03 1.99961194e+03 1.98338452e+03 1.90648865e+03 1.83707434e+03 1.88072766e+03 1.85204407e+03 1.78730444e+03 1.70846643e+03 1.69892114e+03 1.76277490e+03 1.66536353e+03 1.59085840e+03 1.60002429e+03 1.56220337e+03 1.54426587e+03 1.51452173e+03 1.51188281e+03 1.49378467e+03 1.42502783e+03 1.35025305e+03 1.32699854e+03 1.37287207e+03 1.31751917e+03 1.25431592e+03 1.25134619e+03 1.22372522e+03 1.20141284e+03 1.17236597e+03 1.16218481e+03 1.11303394e+03 1.05993237e+03 1.07843286e+03 1.05592847e+03 1.02091693e+03 9.98406616e+02 9.67883240e+02 9.44035034e+02 8.94267761e+02 8.60083679e+02 8.85918884e+02 8.81090698e+02 8.13052490e+02 7.67057251e+02 7.82244141e+02 7.90973145e+02 7.51174927e+02 7.02589539e+02 6.71938843e+02 6.79195496e+02 6.62840332e+02 6.27675598e+02 6.23478699e+02 6.02259644e+02 5.64272461e+02 5.44690369e+02 5.42294861e+02 5.32137085e+02 4.91300323e+02 4.65404327e+02 4.72709412e+02 4.62883850e+02 4.33480774e+02 4.01672119e+02 3.84147156e+02 3.89993805e+02 3.76953339e+02 3.48838867e+02 3.32465271e+02 3.20251282e+02 3.03883453e+02 2.88604431e+02 2.86406464e+02 2.67411011e+02 2.45446915e+02 2.44182358e+02 2.33980072e+02 2.19247787e+02 2.02255127e+02 1.87588364e+02 1.83487991e+02 1.70660309e+02 1.59121567e+02 1.57810028e+02 1.44566498e+02 1.35314270e+02 1.61930634e+02 1.43262848e+02 1.52958130e+02 1.57216141e+02 1.61258514e+02 1.25335258e+02 8.58029785e+01 8.76652298e+01 3.78255554e+02 10317907. -31103018. -323636864. -323636864. 29024692. 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. 8.35270050e+06 -3125617. 2.34385650e+06 1.67320638e+06 3.00053950e+06 3755298. 1.41877563e+02 1.10722275e+02 6.78336639e+01 7.69737015e+01 8.13341446e+01 8.70085754e+01 1.01160858e+02 1.23349113e+02 1.11407890e+02 1.16265640e+02 1.34103607e+02 1.32346573e+02 1.45992844e+02 1.75959808e+02 1.84060150e+02 1.81095810e+02 1.91402863e+02 2.03910477e+02 2.12616776e+02 2.26364227e+02 2.44743774e+02 2.55831955e+02 2.67368591e+02 2.82888000e+02 2.91719055e+02 3.03489441e+02 3.20553131e+02 3.32017487e+02 3.44359375e+02 3.69806885e+02 3.92527802e+02 3.97639557e+02 4.09713593e+02 4.29989746e+02 4.46924561e+02 4.67574646e+02 4.82189240e+02 4.89656372e+02 5.18275452e+02 5.50441162e+02 5.49916443e+02 5.64805725e+02 5.96683655e+02 6.01011230e+02 6.25783569e+02 6.66402405e+02 6.75136353e+02 6.89725159e+02 7.20435852e+02 7.55215210e+02 7.65083252e+02 7.63367920e+02 7.82075562e+02 8.08046082e+02 8.58269409e+02 8.98132202e+02 8.99532471e+02 9.10464661e+02 9.31645630e+02 9.61594727e+02 9.88381287e+02 1.00358466e+03 1.02080072e+03 1.06843384e+03 1.12483447e+03 1.12087268e+03 1.13313550e+03 1.18338782e+03 1.20275378e+03 1.22057935e+03 1.25263184e+03 1.29158984e+03 1.30477344e+03 1.31803088e+03 1.37649792e+03 1.39986292e+03 1.42555591e+03 1.45577466e+03 1.45183752e+03 1.50905115e+03 1.58411682e+03 1.57416724e+03 1.58078625e+03 1.62658984e+03 1.66120459e+03 1.70539612e+03 1.72715076e+03 1.72354871e+03 1.79508997e+03 1.88031213e+03 1.87821484e+03 1.85764893e+03 1.89693872e+03 1.97707666e+03 2.00817944e+03 2.02459473e+03 2.04241248e+03 2.06147729e+03 2.14142578e+03 2.23044531e+03 2.20258813e+03 2.17982666e+03 2.22398218e+03 2.27430322e+03 2.34800830e+03 2.41378052e+03 2.41351294e+03 2.43576685e+03 2.54841089e+03 2.58290552e+03 2.53137012e+03 2.53033936e+03 2.58868726e+03 2.67887256e+03 2.73856909e+03 2.77450903e+03 2.79540576e+03 2.83203979e+03 2.88744800e+03 2.85591772e+03 2.88573877e+03 2.97088867e+03 3.00074561e+03 3.08195410e+03 3.15864478e+03 3.10468896e+03 3.13378955e+03 3.25484399e+03 3.27690259e+03 3.23676294e+03 3.33711206e+03 3.46298901e+03 3.47108057e+03 3.47482812e+03 3.49282861e+03 3.53499316e+03 3.57097095e+03 3.56820825e+03 3.65807812e+03 3.73173120e+03 3.76559888e+03 3.81133862e+03 3.86541553e+03 3.90764771e+03 3.82544434e+03 3.93861841e+03 4.05414624e+03 4.06543970e+03 4.14023047e+03 4.24807129e+03 4.25476172e+03 4.19143750e+03 4.22504443e+03 4.29490186e+03 4.27489453e+03 4.38772412e+03 4.52423389e+03 4.51138818e+03 4.55339160e+03 4.59363037e+03 4.59858984e+03 4.64261523e+03 4.68041992e+03 4.72345752e+03 4.81334521e+03 4.90841895e+03 4.93370996e+03 4.90490674e+03 5.03088770e+03 5.05181641e+03 5.09416211e+03 5.10815430e+03 5.13842480e+03 5.28049609e+03 5.25761963e+03 5.30840869e+03 5.36685400e+03 5.42504590e+03 5.53577490e+03 5.38788818e+03 5.47809717e+03 5.68157178e+03 5.65519580e+03 5.76946777e+03 5.81540674e+03 5.74554834e+03 5.80115430e+03 5.77856836e+03 5.82969434e+03 5.93281396e+03 6.05538477e+03 6.14017725e+03 6.19022363e+03 6.24331934e+03 6.27089453e+03 6.26337402e+03 6.25698438e+03 6.22482324e+03 6.30978369e+03 6.54070801e+03 6.69521533e+03 6.49867188e+03 6.47752832e+03 6.73643066e+03 6.58448975e+03 6.73228564e+03 6.92599072e+03 6.79625098e+03 6.81776660e+03 6.95443896e+03 7.05080908e+03 7.08408105e+03 7.06055762e+03 7.07932910e+03 7.00279688e+03 7.12908936e+03 7.32360645e+03 7.35638525e+03 7.35745508e+03 7.40325439e+03 7.53561182e+03 7.45677588e+03 7.57761182e+03 7.69814258e+03 7.58671484e+03 7.56984912e+03 7.70357568e+03 7.79041846e+03 7.88594971e+03 7.89929883e+03 7.88019531e+03 7.99771875e+03 8.02731738e+03 8.07994873e+03 8.10615771e+03 8.33798438e+03 8.38024902e+03 8.07507080e+03 8.27823242e+03 8.36830371e+03 8.36415723e+03 8.60325293e+03 8.40030566e+03 8.34521582e+03 8.74887891e+03 8.76762109e+03 8.53256250e+03 8.60200488e+03 8.82841602e+03 8.93640820e+03 8.78466504e+03 8.95943750e+03 9.12741113e+03 8.90701172e+03 8.95358496e+03 9.15810938e+03 8.94648340e+03 9.15908789e+03 9.37441211e+03 9.13931445e+03 9.35142480e+03 9.58152441e+03 9.46986426e+03 9.35887793e+03 9.38652441e+03 9.54694336e+03 9.72691309e+03 9.61574805e+03 9.52721289e+03 9.68044629e+03 9.74819629e+03 9.73377246e+03 9.75178223e+03 9.88844824e+03 9.92559180e+03 9.94483203e+03 1.00785391e+04 1.01759482e+04 1.00529707e+04 1.01474941e+04 1.02207871e+04 1.00342529e+04 1.03653555e+04 1.04780059e+04 1.01660732e+04 1.03800049e+04 1.04753916e+04 1.03674756e+04 1.05638115e+04 1.04685020e+04 1.06376523e+04 1.08388008e+04 1.07042979e+04 1.06589326e+04 1.06997949e+04 1.06551406e+04 1.06653555e+04 1.07772588e+04 1.10380986e+04 1.11762324e+04 1.10371924e+04 1.10188350e+04 1.12196797e+04 1.11021377e+04 1.09417832e+04 1.11100508e+04 1.13702852e+04 1.14415684e+04 1.11781689e+04 1.10632559e+04 1.13706934e+04 1.15558145e+04 1.14057812e+04 1.13713984e+04 1.14583809e+04 1.15339414e+04 1.17351348e+04 1.16797598e+04 1.15750732e+04 1.14852676e+04 1.15041357e+04 1.16980518e+04 1.17242783e+04 1.17953477e+04 1.20146631e+04 1.18893594e+04 1.18959424e+04 1.22313037e+04 1.20567910e+04 1.18124277e+04 1.20786699e+04 1.23398936e+04 1.21033057e+04 1.17879482e+04 1.18360674e+04 1.22047471e+04 1.23941846e+04 1.23310977e+04 1.22654160e+04 1.21731709e+04 1.24650752e+04 1.25323213e+04 1.21068271e+04 1.21618486e+04 1.24818125e+04 1.26411582e+04 1.24560605e+04 1.22546670e+04 1.24209541e+04 1.25954658e+04 1.27593223e+04 1.29017568e+04 1.28482080e+04 1.25449756e+04 1.23418555e+04 1.27465859e+04 1.31209883e+04 1.28200137e+04 1.26200078e+04 1.25422773e+04 1.27595410e+04 1.30879707e+04 1.28573291e+04 1.27726445e+04 1.29001689e+04 1.31717705e+04 1.32180410e+04 1.27495352e+04 1.29787324e+04 1.31427100e+04 1.29176738e+04 1.31048809e+04 1.29846162e+04 1.29828789e+04 1.31268105e+04 1.30548945e+04 1.31654189e+04 1.33228223e+04 1.33157090e+04 1.31259434e+04 1.32398936e+04 1.33793516e+04 1.33026973e+04 1.32321465e+04 1.29616904e+04 1.31354609e+04 1.35753994e+04 1.35035205e+04 1.33666230e+04 1.30543105e+04 1.31750488e+04 1.37221631e+04 1.35011221e+04 1.33060244e+04 1.35599736e+04 1.35158701e+04 1.32699141e+04 1.34337158e+04 1.35949590e+04 1.33779346e+04 1.35080098e+04 1.35321416e+04 1.32008340e+04 1.34221592e+04 1.35909805e+04 1.36062783e+04 1.38566172e+04 1.37422148e+04 1.36022363e+04 1.34625879e+04 1.33989434e+04 1.36193672e+04 1.37838301e+04 1.36247266e+04 1.34313320e+04 1.36612422e+04 1.36337881e+04 1.35041787e+04 1.38306309e+04 1.37197588e+04 1.35621084e+04 1.36074502e+04 1.35851377e+04 1.36948232e+04 1.37784707e+04 1.37343125e+04 1.34734756e+04 1.35153105e+04 1.37089971e+04 1.36564307e+04 1.37312920e+04 1.38803408e+04 1.37365654e+04 1.36259111e+04 1.34132725e+04 1.34015518e+04 1.36879561e+04 1.38305967e+04 1.39917773e+04 1.36376670e+04 1.33068164e+04 1.36805977e+04 1.38852119e+04 1.36860811e+04 1.35477402e+04 1.35676602e+04 1.36330078e+04 1.37516270e+04 1.36886289e+04 1.34320225e+04 1.35336660e+04 1.37424170e+04 1.36101885e+04 1.35811807e+04 1.35515303e+04 1.34706230e+04 1.36179229e+04 1.36271826e+04 1.36871318e+04 1.36334570e+04 1.34715967e+04 1.35802920e+04 1.36032422e+04 1.35944551e+04 1.32673545e+04 1.32096133e+04 1.35410225e+04 1.36605771e+04 1.37055732e+04 1.34209023e+04 1.33477158e+04 1.32830156e+04 1.32967734e+04 1.36237031e+04 1.33318135e+04 1.32308164e+04 1.36056963e+04 1.32738330e+04 1.30483486e+04 1.34459258e+04 1.34765273e+04 1.33355732e+04 1.34588193e+04 1.32289521e+04 1.27767480e+04 1.31587744e+04 1.34045459e+04 1.30773135e+04 1.34346064e+04 1.33864199e+04 1.29296133e+04 1.29565527e+04 1.28937588e+04 1.29233008e+04 1.31991797e+04 1.30789336e+04 1.29599600e+04 1.30598984e+04 1.30395791e+04 1.30900557e+04 1.29117441e+04 1.27167285e+04 1.28300264e+04 1.28815479e+04 1.27071113e+04 1.27604199e+04 1.28571367e+04 1.26718711e+04 1.28068262e+04 1.28457305e+04 1.27435752e+04 1.26952852e+04 1.24505732e+04 1.24710547e+04 1.28361445e+04 1.27933057e+04 1.24287236e+04 1.25490947e+04 1.26141895e+04 1.25038018e+04 1.24604619e+04 1.20750186e+04 1.20321328e+04 1.24568516e+04 1.25970977e+04 1.24465752e+04 1.21064092e+04 1.20454199e+04 1.23169961e+04 1.21815586e+04 1.20683633e+04 1.21108193e+04 1.20306475e+04 1.20867051e+04 1.20773105e+04 1.21615947e+04 1.19448818e+04 1.17267305e+04 1.20679014e+04 1.18614385e+04 1.16618838e+04 1.17387314e+04 1.15703232e+04 1.16816943e+04 1.20036885e+04 1.18986182e+04 1.14614355e+04 1.14140146e+04 1.16106230e+04 1.16510332e+04 1.15691611e+04 1.14018311e+04 1.14230820e+04 1.15287676e+04 1.14405518e+04 1.14194902e+04 1.13348770e+04 1.12778066e+04 1.12416426e+04 1.08874453e+04 1.08959287e+04 1.12373174e+04 1.11790850e+04 1.10310410e+04 1.09806650e+04 1.08021787e+04 1.07416670e+04 1.10832949e+04 1.10326719e+04 1.06918770e+04 1.06586348e+04 1.05505146e+04 1.06223359e+04 1.06594023e+04 1.06638145e+04 1.07295557e+04 1.05461934e+04 1.04548213e+04 1.03905889e+04 1.01944766e+04 1.01498711e+04 1.04530654e+04 1.04392969e+04 10176. 1.01286377e+04 1.01150645e+04 1.00872041e+04 9.98069824e+03 1.00822256e+04 9.95330078e+03 9.91136816e+03 9.90492676e+03 9.84508984e+03 9.97395020e+03 9.74646875e+03 9.61962305e+03 9.80986328e+03 9.57885645e+03 9.46359863e+03 9.56709570e+03 9.45407227e+03 9.39397852e+03 9.52518652e+03 9.54964551e+03 9.33485449e+03 9.37718848e+03 9.29391895e+03 9.21281934e+03 9.15433984e+03 9.58431836e+03 9.59179199e+03 1.13944053e+04 1.21351934e+04 1.45250420e+04 1.21972041e+04 2.01044668e+04 1.17828477e+05 -50108404. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 675334528. -4.39045850e+06 2.86634975e+06 -7801145. 9172946. -3.16252175e+06 -11956783. -5854288. 1.89324727e+04 1.60695762e+04 8.48040234e+03 6.74043750e+03 6.56309717e+03 8.17427441e+03 6.63096094e+03 8.31113965e+03 5.87736035e+03 5.65444824e+03 6.11774805e+03 5.94451611e+03 5.74241895e+03 5.96929102e+03 6.06363574e+03 5.93204785e+03 5.78812549e+03 5.56695508e+03 5.58427490e+03 5.79651025e+03 5.55503125e+03 5.40412793e+03 5.30668555e+03 5.36763965e+03 5.56566943e+03 5.48773926e+03 5.28376562e+03 5.02982861e+03 5.01422070e+03 5.17193555e+03 5.14030615e+03 5.06415625e+03 4.97748584e+03 4.95395215e+03 4.95514844e+03 4.90157227e+03 4.88167725e+03 4.65076025e+03 4.67704248e+03 4.89442188e+03 4.63915674e+03 4.46892578e+03 4.47731201e+03 4.44084961e+03 4.55030957e+03 4.52052490e+03 4.35343457e+03 4.22656445e+03 4.28882031e+03 4.31326660e+03 4.20755127e+03 4.12045801e+03 4.00186011e+03 4.06799976e+03 4.12041260e+03 3.94737939e+03 3.89014551e+03 3.83964185e+03 3.77838940e+03 3.86918384e+03 3.85322266e+03 3.73149146e+03 3.61057861e+03 3.62650879e+03 3.61064087e+03 3.56786377e+03 3.53220386e+03 3.38666284e+03 3.35815283e+03 3.48230640e+03 3.34268237e+03 3.20116577e+03 3.14997852e+03 3.20664502e+03 3.30590967e+03 3.19658887e+03 3.09533838e+03 3.01341626e+03 2.93184106e+03 2.96179346e+03 3.00198193e+03 2.89842749e+03 2.78769946e+03 2.82297729e+03 2.80636011e+03 2.75066919e+03 2.76036035e+03 2.63273804e+03 2.57102490e+03 2.65570898e+03 2.58310791e+03 2.50046069e+03 2.43573218e+03 2.38295801e+03 2.43833081e+03 2.42349805e+03 2.31161597e+03 2.25947168e+03 2.27845850e+03 2.26247095e+03 2.19296387e+03 2.17871289e+03 2.11416772e+03 2.05731104e+03 2.09564233e+03 2.04238342e+03 1.95483203e+03 1.89656812e+03 1.89448511e+03 1.93991357e+03 1.90332837e+03 1.84021704e+03 1.74823157e+03 1.69776025e+03 1.75262244e+03 1.73038562e+03 1.64089832e+03 1.60219836e+03 1.59669336e+03 1.59308789e+03 1.54077832e+03 1.49835583e+03 1.44416956e+03 1.44425977e+03 1.47663501e+03 1.39230286e+03 1.34941211e+03 1.33696838e+03 1.29068701e+03 1.28459363e+03 1.25823132e+03 1.21370862e+03 1.17252441e+03 1.15752332e+03 1.16846521e+03 1.14318530e+03 1.09523474e+03 1.04508191e+03 1.01942023e+03 1.02951428e+03 1.01031476e+03 9.70686951e+02 9.22294983e+02 8.84873535e+02 8.97035034e+02 8.91494080e+02 8.54732727e+02 8.09431335e+02 7.89510010e+02 7.78454407e+02 7.58925476e+02 7.54732117e+02 7.11299438e+02 6.84591492e+02 6.82344849e+02 6.50335327e+02 6.25483276e+02 6.06734802e+02 5.95006653e+02 5.78992981e+02 5.48331909e+02 5.27243652e+02 5.08005371e+02 4.99772705e+02 4.98387634e+02 4.70024963e+02 4.36551117e+02 4.19386200e+02 4.08924408e+02 4.04542480e+02 3.93019501e+02 3.71721527e+02 3.43755615e+02 3.21748474e+02 3.18879974e+02 3.14086456e+02 2.99704559e+02 2.73972809e+02 2.58949554e+02 2.54445480e+02 2.42472504e+02 2.29792664e+02 2.15020813e+02 2.03218079e+02 1.92523758e+02 1.79596710e+02 1.70252182e+02 1.60177719e+02 1.49298584e+02 1.42248459e+02 1.31240707e+02 1.20858284e+02 1.12019791e+02 1.04684372e+02 9.77001266e+01 8.82330704e+01 7.98935165e+01 7.27713547e+01 6.84757080e+01 6.30047340e+01 5.48937073e+01 4.82500877e+01 4.20815659e+01 3.74473114e+01 3.41586952e+01 2.97017498e+01 2.49667263e+01 2.03401012e+01 1.68694839e+01 1.46086702e+01 1.18434420e+01 8.91106892e+00 6.73988867e+00 5.01018476e+00 3.44914675e+00 2.24504089e+00 1.40440881e+00 9.19310987e-01 7.77994871e-01 9.66211736e-01 1.49154031e+00 2.32100511e+00 3.36581254e+00 4.91319990e+00 6.91399145e+00 9.09447575e+00 1.16179771e+01 1.42748032e+01 1.79385567e+01 2.14514141e+01 2.40829735e+01 2.79010773e+01 3.30619431e+01 3.94493179e+01 4.60031700e+01 5.04970169e+01 5.35920753e+01 5.79613152e+01 6.54982910e+01 7.63486633e+01 8.61169510e+01 9.17963181e+01 9.38251495e+01 1.01043007e+02 1.17921738e+02 1.25886627e+02 1.28152252e+02 1.38446228e+02 1.49277740e+02 1.59474670e+02 1.75849609e+02 1.83064331e+02 1.86618195e+02 2.03267670e+02 2.12145874e+02 2.27976990e+02 2.46233505e+02 2.47837982e+02 2.65948486e+02 2.86672821e+02 2.94177063e+02 3.06506256e+02 3.20664673e+02 3.39133331e+02 3.51777924e+02 3.63608032e+02 3.72034851e+02 3.87679382e+02 4.24182800e+02 4.53900177e+02 4.59243622e+02 4.52697754e+02 4.61197083e+02 4.87740784e+02 5.26325562e+02 5.62932556e+02 5.66381592e+02 5.56596924e+02 5.82868164e+02 6.21431946e+02 6.32437927e+02 6.47205200e+02 6.73629456e+02 6.86721191e+02 7.08832520e+02 7.60920593e+02 7.66034912e+02 7.61931213e+02 8.01819397e+02 8.06088745e+02 8.49820801e+02 8.95198120e+02 8.85323669e+02 9.34082703e+02 9.53637024e+02 9.39836426e+02 9.87494568e+02 9.86602478e+02 1.03347571e+03 1.13070032e+03 1.09886292e+03 1.06266101e+03 1.10690247e+03 1.19429248e+03 1.27070203e+03 1.26719788e+03 1.22409668e+03 1.22563708e+03 1.27547046e+03 1.34915149e+03 1.43818823e+03 1.43566846e+03 1.38048096e+03 1.41036060e+03 1.47799792e+03 1.52653430e+03 1.54132642e+03 1.56321594e+03 1.59213354e+03 1.62088611e+03 1.72110925e+03 1.75490393e+03 1.67179004e+03 1.69245715e+03 1.79946570e+03 1.83571094e+03 1.85560938e+03 1.89109534e+03 1.97845264e+03 1.97214392e+03 1.92693591e+03 2.01069641e+03 1.99371545e+03 2.09082739e+03 2.26348901e+03 2.16080518e+03 2.07257104e+03 2.18051270e+03 2.32425220e+03 2.42500879e+03 2.43336914e+03 2.30872534e+03 2.28942114e+03 2.38772412e+03 2.51812085e+03 2.64205908e+03 2.64073242e+03 2.51355493e+03 2.53594629e+03 2.68213599e+03 2.71964624e+03 2.81173901e+03 2.87714600e+03 2.75072241e+03 2.76954150e+03 2.95980469e+03 3.02786670e+03 2.92898071e+03 2.94981006e+03 3.06817773e+03 3.05988232e+03 3.20910059e+03 3.27708374e+03 3.19022852e+03 3.21034351e+03 3.24449292e+03 3.29816211e+03 3.35852026e+03 3.38579004e+03 3.54949927e+03 3.63734375e+03 3.56461694e+03 3.49823438e+03 3.44768115e+03 3.64589282e+03 3.90404224e+03 3.86002515e+03 3.69548511e+03 3.66609741e+03 3.84201025e+03 4.09302295e+03 4.02154858e+03 3.82919653e+03 3.95984399e+03 4.12576709e+03 4.24579102e+03 4.44286279e+03 4.34287695e+03 4.11616211e+03 4.17826904e+03 4.32966943e+03 4.44371387e+03 4.53116064e+03 4.52870312e+03 4.56818945e+03 4.58761035e+03 4.70210986e+03 4.72506250e+03 4.64293066e+03 4.69287207e+03 4.71128760e+03 4.97081982e+03 5.06308984e+03 4.92360254e+03 5.05992676e+03 5.10373438e+03 5.12379395e+03 5.02767676e+03 4.99201953e+03 5.28500488e+03 5.53186523e+03 5.47910205e+03 5.25875342e+03 5.26016211e+03 5.56260059e+03 5.71290869e+03 5.65888281e+03 5.59448535e+03 5.49022705e+03 5.56807910e+03 5.83424023e+03 5.87667578e+03 5.78924658e+03 5.70285205e+03 5.71117285e+03 6.04797168e+03 6.36705225e+03 6.10428760e+03 5.96936768e+03 6.17201611e+03 6.20694678e+03 6.44917529e+03 6.44700098e+03 6.16839062e+03 6.27328906e+03 6.51322803e+03 6.57212744e+03 6.57139062e+03 6.55901270e+03 6.73678906e+03 6.81628662e+03 6.60626611e+03 6.95614648e+03 6.79942236e+03 6.56867871e+03 7.33369580e+03 7.31297412e+03 8.97460840e+03 9.24466699e+03 1.06329883e+04 1.24217803e+04 1.84219883e+04 2.09366914e+04 -6.11310250e+06 -43394564. -1.79721050e+06 -100529800. 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. 0. 0. 0. 0. 0. 0. 0. 0. -34787364. -1.43508650e+06 -4.04644125e+06 -6624930. -2.48451350e+06 7.06970938e+05 2.82295742e+04 2.21752363e+04 1.57271523e+04 1.59862646e+04 1.44669609e+04 1.49658848e+04 1.50959375e+04 1.46923555e+04 1.47427207e+04 1.48036250e+04 1.27967803e+04 1.31200527e+04 1.07810488e+04 1.02254600e+04 1.02094854e+04 1.00982197e+04 1.02108193e+04 1.02859307e+04 1.00171035e+04 1.00669121e+04 1.05914326e+04 1.06498066e+04 1.04046553e+04 1.03663320e+04 1.05053457e+04 1.05672090e+04 1.05391602e+04 1.05921191e+04 1.06035264e+04 1.06096230e+04 1.05440586e+04 1.05820918e+04 1.09838096e+04 1.10166602e+04 1.08187812e+04 1.08639150e+04 1.09550098e+04 1.10620176e+04 1.09698584e+04 1.10286523e+04 1.11075352e+04 1.10110342e+04 1.09769854e+04 1.10275391e+04 1.10519170e+04 1.15932266e+04 1.16889668e+04 1.13165498e+04 1.10641973e+04 1.10424131e+04 1.17823457e+04 1.18902383e+04 1.14992930e+04 1.12879834e+04 1.13528086e+04 1.15278223e+04 1.15207363e+04 1.20689795e+04 1.20845859e+04 1.13731553e+04 1.12523594e+04 1.18562734e+04 1.24912871e+04 1.22711553e+04 1.19249326e+04 1.19158340e+04 1.19023711e+04 1.20112373e+04 1.21304141e+04 1.19805127e+04 1.19506133e+04 1.20332559e+04 1.20639170e+04 1.21208936e+04 1.21398711e+04 1.25579971e+04 1.25408828e+04 1.21880439e+04 1.21977891e+04 1.22803350e+04 1.26140195e+04 1.26676885e+04 1.24861084e+04 1.24630361e+04 1.22423760e+04 1.19809502e+04 1.26269434e+04 1.28220410e+04 1.21656885e+04 1.22689326e+04 1.29939502e+04 1.33715908e+04 1.30086318e+04 1.27019756e+04 1.27447744e+04 1.28082363e+04 1.26529424e+04 1.26521963e+04 1.27996445e+04 1.27555146e+04 1.32096377e+04 1.31716104e+04 1.28231201e+04 1.28456621e+04 1.25607549e+04 1.29289199e+04 1.36550498e+04 1.33691738e+04 1.30684805e+04 1.27832803e+04 1.26398711e+04 1.33540391e+04 1.36380742e+04 1.32609766e+04 1.28752666e+04 1.28369082e+04 1.31459580e+04 1.31682490e+04 1.36444922e+04 1.37680332e+04 1.32581699e+04 1.30145361e+04 1.30317100e+04 1.35563701e+04 1.36815869e+04 1.34034785e+04 1.32549072e+04 1.32815479e+04 1.32774238e+04 1.28727734e+04 1.32470654e+04 1.41179268e+04 1.38028242e+04 1.34414678e+04 1.31716045e+04 1.30858174e+04 1.38606855e+04 1.39552373e+04 1.35036416e+04 1.31699697e+04 1.31714873e+04 1.35979902e+04 1.35315068e+04 1.35540332e+04 1.32349199e+04 1.34896709e+04 1.42575586e+04 1.38598232e+04 1.37091230e+04 1.38377451e+04 1.36726855e+04 1.34398877e+04 1.34990801e+04 1.35684619e+04 1.34640430e+04 1.35140986e+04 1.32055850e+04 1.35783691e+04 1.44198291e+04 1.37293057e+04 1.32774912e+04 1.36287725e+04 1.36309385e+04 1.40148340e+04 1.38775010e+04 1.34095918e+04 1.38642588e+04 1.39474141e+04 1.37273115e+04 1.37957207e+04 1.37070107e+04 1.35277666e+04 1.35606221e+04 1.34500391e+04 1.30987686e+04 1.36126201e+04 1.44014551e+04 1.41039072e+04 1.36056982e+04 1.31571201e+04 1.33305801e+04 1.41401377e+04 1.40802773e+04 1.37310986e+04 1.33370303e+04 1.31983955e+04 1.36276885e+04 1.36567666e+04 1.39069873e+04 1.37245859e+04 1.33759766e+04 1.35424092e+04 1.34588906e+04 1.39097979e+04 1.39806787e+04 1.35548506e+04 1.34302529e+04 1.34305400e+04 1.34836963e+04 1.31089756e+04 1.33556670e+04 1.40924824e+04 1.38679824e+04 1.34992520e+04 1.31202188e+04 1.30431523e+04 1.37846748e+04 1.38286982e+04 1.34237832e+04 1.31134795e+04 1.30506875e+04 1.34041221e+04 1.34314355e+04 1.36756602e+04 1.35746797e+04 1.32293252e+04 1.30495215e+04 1.30038535e+04 1.36253701e+04 1.36764551e+04 1.32559111e+04 1.30024102e+04 1.29634316e+04 1.34925723e+04 1.34991270e+04 1.27739600e+04 1.27717773e+04 1.35602139e+04 1.34298398e+04 1.27334346e+04 1.27155586e+04 1.33425420e+04 1.34467275e+04 1.29401279e+04 1.26022920e+04 1.26290166e+04 1.33295059e+04 1.32129033e+04 1.27853730e+04 1.29184990e+04 1.28379023e+04 1.25557764e+04 1.24954824e+04 1.28161133e+04 1.24713613e+04 1.26382480e+04 1.32227041e+04 1.28287598e+04 1.28642012e+04 1.28986182e+04 1.26182207e+04 1.25951221e+04 1.25678193e+04 1.25422158e+04 1.22006660e+04 1.20297422e+04 1.23156787e+04 1.25256523e+04 1.28314326e+04 1.23793066e+04 1.20100703e+04 1.23165029e+04 1.22710918e+04 1.26545957e+04 1.25725977e+04 1.21395352e+04 1.19184570e+04 1.18149023e+04 1.20799746e+04 1.20863438e+04 1.23249951e+04 1.22365205e+04 1.19317920e+04 1.18866621e+04 1.15034941e+04 1.17659355e+04 1.23597490e+04 1.22172285e+04 1.18290312e+04 1.14882627e+04 1.13954248e+04 1.19284951e+04 1.20134600e+04 1.16803486e+04 1.13060645e+04 1.12877734e+04 1.15255557e+04 1.14578125e+04 1.17289043e+04 1.16560176e+04 1.12807734e+04 1.12864932e+04 1.12023789e+04 1.14435254e+04 1.14193916e+04 1.08843750e+04 1.08708906e+04 1.14482168e+04 1.12227275e+04 1.05676113e+04 1.08652803e+04 1.14010771e+04 1.12533350e+04 1.09609805e+04 1.06266680e+04 1.05216504e+04 1.10880234e+04 1.10751045e+04 1.07189883e+04 1.03938682e+04 1.03152119e+04 1.05476465e+04 1.05596416e+04 1.05572920e+04 1.02317344e+04 1.03728965e+04 1.08584844e+04 1.05377627e+04 1.03970195e+04 1.02844561e+04 1.01382178e+04 1.01596914e+04 1.01070967e+04 1.01441406e+04 1.00676113e+04 9.96819434e+03 9.65738672e+03 9.76093750e+03 1.02287598e+04 9.78534375e+03 9.32564551e+03 9.64004883e+03 9.86510156e+03 1.00905078e+04 9.86824805e+03 9.55589551e+03 9.57113867e+03 9.54402344e+03 9.28917578e+03 9.19883398e+03 9.50700684e+03 9.41625879e+03 9.18379395e+03 9.07108398e+03 8.78742188e+03 9.09670215e+03 9.54082227e+03 9.26348730e+03 9.01257422e+03 8.73068555e+03 8.63010645e+03 9.07374805e+03 9.19616309e+03 8.87662109e+03 8.53800586e+03 8.44828906e+03 8.53527539e+03 8.51157227e+03 8.79686621e+03 8.65143359e+03 8.35809082e+03 8.34481738e+03 8.25767676e+03 8.41955273e+03 8.38565625e+03 8.14396094e+03 8.19093994e+03 8.14385010e+03 7.94717432e+03 7.72078027e+03 7.84707959e+03 8.21053125e+03 8.01868994e+03 7.81337598e+03 7.59704004e+03 7.60236914e+03 7.99372266e+03 7.91668506e+03 7.61894482e+03 7.37617334e+03 7.29164258e+03 7.36869824e+03 7.33323096e+03 7.40502051e+03 7.15561523e+03 7.24644385e+03 7.44633936e+03 7.21166260e+03 7.22188086e+03 7.22415771e+03 7.01506396e+03 7.03717236e+03 6.99370117e+03 6.72882471e+03 6.66188281e+03 6.86462256e+03 6.83221484e+03 6.76866016e+03 6.69182031e+03 6.44902832e+03 6.35476465e+03 6.51469189e+03 6.47429297e+03 6.61090283e+03 6.48320166e+03 6.15572363e+03 6.25730078e+03 6.35186377e+03 6.23144678e+03 6.07835547e+03 5.96264941e+03 6.04686084e+03 6.00027588e+03 5.91358496e+03 5.73976709e+03 5.78829492e+03 6.07012598e+03 5.89259277e+03 5.68152832e+03 5.51315332e+03 5.46140479e+03 5.71211035e+03 5.64701318e+03 5.47368408e+03 5.27154053e+03 5.15847070e+03 5.26675732e+03 5.34948291e+03 5.44086182e+03 5.26047510e+03 4.98015381e+03 4.99761475e+03 5.00288037e+03 5.14977637e+03 4.99999854e+03 4.80954102e+03 4.89799365e+03 4.86002393e+03 4.76202588e+03 4.59837305e+03 4.62940088e+03 4.81956299e+03 4.73752637e+03 4.52588721e+03 4.37466846e+03 4.34830957e+03 4.52779297e+03 4.50931299e+03 4.34100781e+03 4.17063965e+03 4.12083350e+03 4.18409814e+03 4.13261523e+03 4.21261475e+03 4.17577246e+03 3.98725708e+03 3.85549146e+03 3.85942603e+03 4.03680615e+03 3.92464624e+03 3.74255835e+03 3.78869263e+03 3.75983740e+03 3.59723877e+03 3.51547705e+03 3.60308301e+03 3.54285010e+03 3.41953027e+03 3.55240039e+03 3.52756982e+03 3.40715039e+03 3.34934375e+03 3.28674756e+03 3.24883691e+03 3.13574487e+03 3.06197534e+03 3.18339136e+03 3.17634961e+03 3.00168652e+03 2.89154956e+03 2.96515894e+03 3.04558716e+03 2.98769775e+03 2.83695776e+03 2.72495825e+03 2.79247412e+03 2.83209180e+03 2.74804370e+03 2.66186914e+03 2.55726782e+03 2.46824097e+03 2.54825732e+03 2.64375488e+03 2.53612988e+03 2.38525073e+03 2.33860376e+03 2.41715039e+03 2.42163428e+03 2.31540479e+03 2.20658862e+03 2.15158691e+03 2.15774219e+03 2.14702100e+03 2.18009082e+03 2.14719727e+03 2.04292749e+03 1.99628357e+03 1.97918127e+03 1.98524988e+03 1.89754395e+03 1.83672021e+03 1.89481006e+03 1.86358081e+03 1.77141150e+03 1.68969055e+03 1.70302551e+03 1.76778625e+03 1.65543250e+03 1.56990344e+03 1.58639612e+03 1.58029736e+03 1.55941187e+03 1.51178992e+03 1.51388391e+03 1.49710071e+03 1.41844421e+03 1.34593042e+03 1.32083765e+03 1.37324316e+03 1.32296155e+03 1.25676477e+03 1.25147437e+03 1.22378284e+03 1.19739795e+03 1.16262683e+03 1.14896912e+03 1.11877600e+03 1.07041248e+03 1.07197534e+03 1.04827527e+03 1.02741418e+03 1.00644330e+03 9.65435974e+02 9.35956543e+02 8.86405273e+02 8.67951538e+02 8.94563538e+02 8.82780029e+02 8.12435059e+02 7.65519287e+02 7.73291809e+02 7.80674500e+02 7.54673889e+02 7.09147278e+02 6.63501587e+02 6.69428711e+02 6.67767029e+02 6.29862732e+02 6.24657227e+02 5.97948608e+02 5.54197144e+02 5.48841492e+02 5.51042969e+02 5.27463379e+02 4.85695160e+02 4.60884430e+02 4.69597992e+02 4.62927063e+02 4.32040466e+02 4.00594360e+02 3.82212189e+02 3.88530090e+02 3.72243103e+02 3.44927338e+02 3.35723206e+02 3.21632507e+02 3.02722717e+02 2.88140961e+02 2.85462433e+02 2.67636780e+02 2.44868118e+02 2.43083008e+02 2.32546707e+02 2.17921432e+02 2.01339615e+02 1.86488708e+02 1.84306076e+02 1.70943161e+02 1.55012329e+02 1.49497025e+02 1.42666763e+02 1.39373840e+02 1.27178429e+02 1.12028114e+02 1.05948051e+02 1.01681480e+02 9.86693726e+01 8.29546814e+01 6.71418381e+01 7.24815063e+01 2.21167999e+02 1.15345375e+02 32617870. 7.87268250e+02 -323636864. 29024692. 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. 0. 0. 0. 1.63235352e+02 1.18617683e+02 6.90081940e+01 7.58858414e+01 7.86051559e+01 8.38950882e+01 9.88338852e+01 1.17255058e+02 1.09467094e+02 1.18292084e+02 1.35142395e+02 1.32567413e+02 1.41838394e+02 1.65870300e+02 1.80543716e+02 1.83631012e+02 1.91380783e+02 2.02725540e+02 2.13873764e+02 2.27077377e+02 2.45755386e+02 2.60819122e+02 2.64941376e+02 2.74491211e+02 2.92956024e+02 3.07578491e+02 3.17729218e+02 3.31110840e+02 3.50287140e+02 3.65401672e+02 3.86482605e+02 4.00732849e+02 4.01764160e+02 4.24024170e+02 4.55394379e+02 4.76305725e+02 4.91896118e+02 4.90287994e+02 5.02601288e+02 5.37506409e+02 5.59990845e+02 5.71150269e+02 5.85366455e+02 6.03883057e+02 6.35276123e+02 6.66099976e+02 6.78816772e+02 6.79733337e+02 6.98233215e+02 7.54947571e+02 7.80749939e+02 7.62755371e+02 7.81177734e+02 8.24935425e+02 8.55936096e+02 8.90832947e+02 9.01519653e+02 8.93788330e+02 9.22867676e+02 9.74743042e+02 1.00566992e+03 1.01429181e+03 1.02277332e+03 1.06547021e+03 1.11408313e+03 1.12024658e+03 1.13120581e+03 1.15010425e+03 1.19293347e+03 1.24317310e+03 1.26288843e+03 1.29652661e+03 1.30972913e+03 1.30587671e+03 1.35604187e+03 1.40430151e+03 1.42139453e+03 1.45750378e+03 1.47287988e+03 1.50009863e+03 1.56991382e+03 1.59783777e+03 1.56970093e+03 1.59853052e+03 1.67240674e+03 1.71737256e+03 1.74474585e+03 1.74565466e+03 1.77528931e+03 1.82287512e+03 1.87471228e+03 1.90214539e+03 1.88306152e+03 1.93593445e+03 2.02368591e+03 2.06135229e+03 2.07434644e+03 2.05535571e+03 2.08480127e+03 2.19210278e+03 2.21483228e+03 2.19958594e+03 2.23472192e+03 2.28507739e+03 2.36658252e+03 2.39410571e+03 2.41155542e+03 2.44825391e+03 2.48564062e+03 2.54904834e+03 2.57624902e+03 2.56832764e+03 2.61516211e+03 2.67117236e+03 2.69065063e+03 2.75137183e+03 2.80870825e+03 2.82926514e+03 2.86684155e+03 2.87740601e+03 2.91296680e+03 2.98966113e+03 3.05185938e+03 3.06081177e+03 3.08747485e+03 3.11358252e+03 3.15344019e+03 3.22365283e+03 3.24920386e+03 3.26460132e+03 3.34641968e+03 3.46601929e+03 3.48874243e+03 3.42753564e+03 3.48153149e+03 3.57726294e+03 3.56897754e+03 3.58276538e+03 3.60893188e+03 3.69801367e+03 3.78567578e+03 3.87167041e+03 3.87318188e+03 3.84332715e+03 3.85298804e+03 3.97347729e+03 4.05360815e+03 4.08670410e+03 4.11758984e+03 4.09523047e+03 4.20422852e+03 4.31045703e+03 4.33052295e+03 4.26370264e+03 4.25404199e+03 4.40443311e+03 4.56724023e+03 4.54596143e+03 4.40767822e+03 4.52625146e+03 4.72023193e+03 4.71697021e+03 4.69348926e+03 4.73307129e+03 4.81858643e+03 4.85944141e+03 4.92044922e+03 4.95847998e+03 4.90553662e+03 5.09319971e+03 5.17087988e+03 5.14400977e+03 5.19338330e+03 5.26328662e+03 5.16032129e+03 5.28363184e+03 5.37912256e+03 5.45927979e+03 5.56724561e+03 5.37980518e+03 5.44741797e+03 5.70462793e+03 5.64131641e+03 5.57128906e+03 5.71746533e+03 5.85069580e+03 5.83902490e+03 5.86323193e+03 5.91152490e+03 5.90347461e+03 5.98107129e+03 6.11909766e+03 6.18861719e+03 6.05382373e+03 6.19930469e+03 6.36792676e+03 6.41718799e+03 6.34678418e+03 6.28916211e+03 6.39940088e+03 6.60489404e+03 6.52942969e+03 6.52578564e+03 6.69606201e+03 6.60595068e+03 6.72925977e+03 6.94433447e+03 6.84062061e+03 6.83018262e+03 6.93500928e+03 7.00119727e+03 7.01143066e+03 7.12760547e+03 7.14869092e+03 7.06724316e+03 7.15743506e+03 7.30352734e+03 7.34356836e+03 7.26038867e+03 7.43084570e+03 7.61372656e+03 7.56338672e+03 7.72112305e+03 7.61988916e+03 7.48006934e+03 7.69768359e+03 7.81106592e+03 7.81521582e+03 7.72854688e+03 7.67779004e+03 7.97478467e+03 8.13516016e+03 8.07891602e+03 7.97667285e+03 8.21097461e+03 8.29632910e+03 8.19041357e+03 8.12298047e+03 8.41956445e+03 8.41732031e+03 8.27887402e+03 8.55666309e+03 8.49147656e+03 8.45664551e+03 8.64265820e+03 8.58750879e+03 8.60494043e+03 8.75161914e+03 8.71690723e+03 8.70718750e+03 8.92208301e+03 9.05719727e+03 9.09954395e+03 8.83184766e+03 8.88963477e+03 9.12153223e+03 9.09685645e+03 9.22897949e+03 9.23042188e+03 9.21787305e+03 9.27807715e+03 9.40512988e+03 9.59696191e+03 9.45045801e+03 9.24126660e+03 9.53985059e+03 9.93643066e+03 9.58850781e+03 9.45396777e+03 9.64502539e+03 9.66586328e+03 9.88051172e+03 9.92853906e+03 9.79923047e+03 9.85914648e+03 1.00085420e+04 1.00928770e+04 1.01186748e+04 1.00249326e+04 1.02364580e+04 1.03679355e+04 1.00179795e+04 1.01324414e+04 1.03137754e+04 1.02717061e+04 1.05108447e+04 1.04527812e+04 1.03865186e+04 1.05918848e+04 1.04330537e+04 1.05409229e+04 1.09569102e+04 1.07928008e+04 1.06208076e+04 1.05813633e+04 1.05508574e+04 1.08665039e+04 1.10468076e+04 1.08576748e+04 1.09185537e+04 1.11148311e+04 1.11404385e+04 1.11055225e+04 1.09479844e+04 1.09675996e+04 1.11615225e+04 1.13126172e+04 1.14128691e+04 1.11377266e+04 1.11148682e+04 1.13771504e+04 1.14559951e+04 1.15042715e+04 1.15643223e+04 1.14073877e+04 1.13967656e+04 1.18642832e+04 1.19350293e+04 1.15772939e+04 1.13770801e+04 1.14964990e+04 1.17695049e+04 1.17555967e+04 1.16259590e+04 1.18334346e+04 1.19575684e+04 1.19813652e+04 1.21091875e+04 1.19777422e+04 1.18907158e+04 1.21156318e+04 1.22427646e+04 1.20527178e+04 1.18656768e+04 1.20881279e+04 1.22243271e+04 1.22218066e+04 1.24154814e+04 1.22863838e+04 1.21165752e+04 1.22395391e+04 1.26062119e+04 1.24719033e+04 1.22491670e+04 1.24708730e+04 1.24879961e+04 1.23958555e+04 1.25345078e+04 1.24154785e+04 1.24379365e+04 1.26155850e+04 1.27417354e+04 1.29184111e+04 1.26805342e+04 1.26622568e+04 1.27390801e+04 1.26904951e+04 1.26842158e+04 1.26039961e+04 1.28349062e+04 1.29052656e+04 1.27901191e+04 1.27042676e+04 1.27724121e+04 1.30650938e+04 1.31984980e+04 1.32284492e+04 1.30147744e+04 1.29511143e+04 1.29723652e+04 1.28173535e+04 1.29965176e+04 1.31341797e+04 1.31259883e+04 1.31455684e+04 1.29879482e+04 1.29726328e+04 1.32172422e+04 1.34763438e+04 1.35152363e+04 1.31934658e+04 1.29915479e+04 1.32093975e+04 1.32960938e+04 1.32298184e+04 1.33716855e+04 1.34801113e+04 1.32619688e+04 1.31992637e+04 1.31574062e+04 1.32075254e+04 1.37095254e+04 1.37512461e+04 1.33524023e+04 1.34817246e+04 1.34036514e+04 1.31140859e+04 1.35682783e+04 1.37056152e+04 1.33244658e+04 1.33668291e+04 1.33619121e+04 1.32433008e+04 1.35951895e+04 1.39348086e+04 1.36394814e+04 1.34906084e+04 1.35694414e+04 1.35448398e+04 1.35919326e+04 1.35525625e+04 1.35726631e+04 1.36320830e+04 1.35322539e+04 1.36058926e+04 1.37473662e+04 1.35362646e+04 1.36765479e+04 1.38847656e+04 1.35710635e+04 1.34184287e+04 1.34897881e+04 1.37388486e+04 1.39556943e+04 1.39301768e+04 1.35233701e+04 1.31890635e+04 1.34965771e+04 1.38849199e+04 1.40674453e+04 1.37330889e+04 1.34528779e+04 1.36256270e+04 1.36805615e+04 1.36381279e+04 1.37691240e+04 1.37136680e+04 1.35570918e+04 1.38200283e+04 1.36155576e+04 1.31793799e+04 1.36562227e+04 1.41602510e+04 1.37197637e+04 1.33823320e+04 1.34874932e+04 1.35821211e+04 1.37631680e+04 1.37698545e+04 1.36491709e+04 1.34112363e+04 1.34789141e+04 1.36582412e+04 1.35640146e+04 1.37422119e+04 1.37214844e+04 1.35533975e+04 1.34733027e+04 1.36410762e+04 1.36652510e+04 1.34696729e+04 1.36868311e+04 1.37575576e+04 1.34480049e+04 1.32335459e+04 1.32642246e+04 1.34166211e+04 1.37520020e+04 1.36933350e+04 1.32922617e+04 1.32589404e+04 1.32759180e+04 1.34258721e+04 1.36259033e+04 1.34262959e+04 1.31452832e+04 1.34672861e+04 1.35092373e+04 1.31666191e+04 1.35544365e+04 1.35577188e+04 1.31586826e+04 1.32117363e+04 1.30102930e+04 1.29788604e+04 1.34547559e+04 1.33538271e+04 1.31155508e+04 1.33411426e+04 1.31906309e+04 1.27944160e+04 1.28827607e+04 1.31049092e+04 1.30801260e+04 1.31190117e+04 1.29568447e+04 1.28394941e+04 1.30164902e+04 1.30876328e+04 1.34297334e+04 1.31204111e+04 1.25521250e+04 1.26205342e+04 1.27652109e+04 1.29265391e+04 1.30522480e+04 1.27629482e+04 1.24391543e+04 1.27295840e+04 1.29009678e+04 1.26804170e+04 1.26846416e+04 1.26679600e+04 1.24537383e+04 1.26382529e+04 1.26763457e+04 1.23632021e+04 1.26812920e+04 1.27986699e+04 1.24594453e+04 1.23688105e+04 1.20502959e+04 1.20574307e+04 1.24064736e+04 1.28035400e+04 1.25735947e+04 1.18649463e+04 1.19049521e+04 1.23277842e+04 1.22366836e+04 1.20775850e+04 1.21001445e+04 1.20347939e+04 1.20730498e+04 1.20561250e+04 1.20339111e+04 1.19641748e+04 1.19041035e+04 1.20745000e+04 1.18778418e+04 1.16421133e+04 1.16524453e+04 1.16778213e+04 1.17957783e+04 1.19792139e+04 1.16963584e+04 1.14075645e+04 1.15031455e+04 1.15928672e+04 1.18696104e+04 1.17354150e+04 1.12245010e+04 1.12345166e+04 1.13992236e+04 1.15026943e+04 1.16419521e+04 1.13751533e+04 1.11309658e+04 1.11070361e+04 1.10321025e+04 1.09403848e+04 1.11790908e+04 1.13667881e+04 1.10725566e+04 1.08456768e+04 1.07034873e+04 1.07424932e+04 1.11110137e+04 1.10327734e+04 1.08478750e+04 1.06900273e+04 1.04633535e+04 1.05550566e+04 1.05981035e+04 1.07796104e+04 1.08030498e+04 1.03745029e+04 1.02791494e+04 1.03648984e+04 1.04269189e+04 1.03756250e+04 1.04426484e+04 1.03881963e+04 1.01143555e+04 1.01150215e+04 1.01225898e+04 1.00625518e+04 1.00846865e+04 1.01281807e+04 1.00148447e+04 9.85734180e+03 9.75904004e+03 9.88190527e+03 1.00032637e+04 9.79582715e+03 9.62572266e+03 9.56046680e+03 9.59584766e+03 9.51891797e+03 9.73630859e+03 9.65581250e+03 9.34806445e+03 9.43034473e+03 9.35968652e+03 9.31373145e+03 9.47417480e+03 9.36242285e+03 9.20634473e+03 9.18694043e+03 9.19473438e+03 9.66625293e+03 8.82251270e+03 8.19053027e+03 1.23560742e+04 1.14225908e+04 2.01044668e+04 1.17828477e+05 -50108404. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.00225645e+04 1.25545928e+04 7.61056836e+03 6.78326562e+03 6.66198096e+03 8.09873633e+03 6.62832227e+03 7.77429883e+03 5.83294922e+03 5.68087744e+03 6.13790576e+03 6.01134619e+03 5.81687012e+03 5.90546338e+03 5.95363086e+03 5.99215820e+03 5.81505469e+03 5.53791748e+03 5.59254443e+03 5.69212354e+03 5.55578857e+03 5.39659668e+03 5.30710596e+03 5.43082324e+03 5.64256787e+03 5.52226904e+03 5.17800977e+03 4.93565625e+03 5.03062695e+03 5.21972559e+03 5.30080908e+03 5.15900635e+03 4.88383838e+03 4.88202930e+03 4.91183447e+03 4.97912549e+03 4.91004785e+03 4.60662646e+03 4.60270068e+03 4.79634082e+03 4.69524756e+03 4.52166797e+03 4.53124707e+03 4.51349463e+03 4.52206299e+03 4.48717627e+03 4.27906006e+03 4.14920850e+03 4.30697412e+03 4.38624463e+03 4.27008936e+03 4.07615161e+03 3.92310059e+03 4.08069482e+03 4.20088672e+03 4.04158960e+03 3.86171216e+03 3.68559644e+03 3.72657544e+03 3.87489526e+03 3.89835986e+03 3.79407275e+03 3.66295898e+03 3.63910474e+03 3.55010620e+03 3.52049487e+03 3.50216235e+03 3.37803760e+03 3.39320312e+03 3.45452954e+03 3.37013428e+03 3.18949512e+03 3.12952319e+03 3.23825098e+03 3.30636816e+03 3.21788916e+03 3.06742529e+03 2.94543970e+03 2.93244849e+03 2.96586743e+03 3.05454370e+03 2.96680273e+03 2.75834717e+03 2.76539844e+03 2.77644019e+03 2.76586108e+03 2.77307715e+03 2.62637354e+03 2.59789453e+03 2.62421802e+03 2.56919507e+03 2.50216504e+03 2.43908423e+03 2.43223096e+03 2.44021387e+03 2.39653955e+03 2.29399927e+03 2.23927686e+03 2.27437109e+03 2.27865356e+03 2.23646338e+03 2.16592627e+03 2.06912646e+03 2.05805713e+03 2.08790063e+03 2.06992236e+03 1.99035767e+03 1.87907410e+03 1.85730981e+03 1.91737195e+03 1.92936902e+03 1.84458240e+03 1.74180310e+03 1.72491235e+03 1.74872229e+03 1.70436230e+03 1.63180920e+03 1.59079297e+03 1.61769934e+03 1.60700842e+03 1.53865112e+03 1.48716174e+03 1.43418542e+03 1.44812451e+03 1.48685608e+03 1.41888562e+03 1.34671753e+03 1.30527527e+03 1.28710657e+03 1.28290112e+03 1.27680627e+03 1.23771155e+03 1.15772852e+03 1.13750769e+03 1.16224170e+03 1.14821216e+03 1.09714050e+03 1.04505164e+03 1.03556897e+03 1.03133801e+03 1.00489758e+03 9.63217957e+02 9.09317810e+02 8.92923950e+02 9.08295471e+02 8.87372925e+02 8.45756165e+02 8.02866638e+02 7.89358826e+02 7.86918762e+02 7.78935303e+02 7.54124390e+02 6.94118835e+02 6.79106689e+02 6.76182251e+02 6.52798035e+02 6.32972290e+02 6.05954102e+02 5.88719910e+02 5.73861389e+02 5.51921265e+02 5.27458862e+02 5.07971771e+02 5.03229034e+02 4.93094147e+02 4.69449951e+02 4.37284332e+02 4.16083496e+02 4.13595917e+02 4.10846802e+02 3.92913910e+02 3.64611237e+02 3.38379120e+02 3.21769043e+02 3.20397797e+02 3.18860107e+02 2.96766693e+02 2.68905762e+02 2.59215210e+02 2.54679871e+02 2.43420975e+02 2.30466827e+02 2.14500885e+02 2.02506882e+02 1.91629211e+02 1.78643616e+02 1.67631027e+02 1.59167099e+02 1.50477219e+02 1.40397644e+02 1.30751587e+02 1.20213913e+02 1.10707535e+02 1.04697433e+02 9.78196564e+01 8.93586807e+01 7.93054504e+01 7.08618927e+01 6.70578461e+01 6.18349609e+01 5.47406807e+01 4.83017578e+01 4.14483833e+01 3.63459663e+01 3.31883507e+01 2.96050396e+01 2.47987595e+01 1.99664688e+01 1.64676571e+01 1.37552376e+01 1.10337467e+01 8.45260048e+00 6.28149652e+00 4.48758364e+00 2.93070507e+00 1.74158514e+00 9.06705678e-01 4.27167922e-01 2.77913183e-01 4.59282935e-01 9.86642420e-01 1.84344506e+00 2.90646005e+00 4.43478680e+00 6.39171505e+00 8.57409668e+00 1.11983023e+01 1.38519821e+01 1.74203644e+01 2.09408970e+01 2.35818005e+01 2.73374958e+01 3.25137215e+01 3.90052986e+01 4.55530930e+01 4.99972343e+01 5.28211174e+01 5.73687134e+01 6.49655380e+01 7.58941345e+01 8.56201782e+01 9.11662369e+01 9.35844040e+01 1.00566475e+02 1.17095016e+02 1.25571739e+02 1.27664215e+02 1.37820480e+02 1.49647354e+02 1.59467529e+02 1.75026093e+02 1.81969147e+02 1.86151352e+02 2.02411194e+02 2.10536255e+02 2.27555954e+02 2.47089111e+02 2.47231827e+02 2.63770264e+02 2.87096405e+02 2.95116577e+02 3.05401733e+02 3.19894318e+02 3.37195862e+02 3.50691803e+02 3.64901001e+02 3.71836487e+02 3.86360931e+02 4.23385162e+02 4.52537262e+02 4.57623444e+02 4.52798981e+02 4.61620605e+02 4.87310669e+02 5.26363098e+02 5.61893127e+02 5.65384094e+02 5.57803589e+02 5.82897827e+02 6.22016174e+02 6.32978516e+02 6.45683655e+02 6.71522766e+02 6.86242615e+02 7.05080994e+02 7.59308838e+02 7.69926880e+02 7.60202026e+02 7.94394226e+02 8.03860291e+02 8.52936218e+02 8.97743896e+02 8.84734802e+02 9.34717834e+02 9.53537537e+02 9.37716736e+02 9.89480042e+02 9.87052979e+02 1.03226001e+03 1.13064148e+03 1.09468396e+03 1.06575562e+03 1.11204810e+03 1.19105835e+03 1.26498718e+03 1.26901416e+03 1.21726599e+03 1.20967590e+03 1.27879346e+03 1.36332861e+03 1.44380066e+03 1.43462146e+03 1.37771631e+03 1.40784167e+03 1.48771667e+03 1.53731921e+03 1.53296570e+03 1.54816406e+03 1.59569458e+03 1.63113745e+03 1.71735083e+03 1.74336389e+03 1.68444287e+03 1.71283899e+03 1.78004749e+03 1.81563354e+03 1.86763977e+03 1.89337378e+03 1.97227869e+03 1.97260986e+03 1.92984790e+03 1.99993408e+03 1.99370215e+03 2.09268140e+03 2.26723096e+03 2.16409570e+03 2.06549536e+03 2.16017212e+03 2.31109985e+03 2.41535449e+03 2.44506177e+03 2.34240991e+03 2.29352856e+03 2.37418481e+03 2.50924292e+03 2.65839917e+03 2.64843774e+03 2.51598340e+03 2.52239380e+03 2.66572192e+03 2.72603394e+03 2.82933813e+03 2.86977344e+03 2.73520312e+03 2.77348096e+03 2.94539771e+03 3.01394751e+03 2.96831665e+03 2.99130493e+03 3.03436523e+03 3.04129370e+03 3.22277856e+03 3.26360425e+03 3.16506763e+03 3.17218970e+03 3.25830176e+03 3.33568164e+03 3.37234644e+03 3.38392676e+03 3.53549438e+03 3.61309790e+03 3.53962817e+03 3.50424683e+03 3.46060327e+03 3.64175122e+03 3.91992603e+03 3.88064136e+03 3.70542017e+03 3.65952954e+03 3.85057935e+03 4.11510986e+03 4.01202319e+03 3.83268921e+03 3.94315576e+03 4.10131592e+03 4.24575146e+03 4.44544434e+03 4.34179004e+03 4.16297070e+03 4.13855225e+03 4.30538916e+03 4.48473926e+03 4.55629785e+03 4.54240479e+03 4.51920410e+03 4.53924951e+03 4.70847656e+03 4.73227197e+03 4.63313574e+03 4.66174756e+03 4.70651025e+03 5.00190625e+03 5.06013232e+03 4.93049854e+03 5.00645996e+03 5.09438525e+03 5.23272412e+03 5.10589697e+03 4.91069092e+03 5.23131934e+03 5.54659961e+03 5.43385596e+03 5.21573291e+03 5.31683057e+03 5.63786963e+03 5.65568896e+03 5.58478906e+03 5.63331982e+03 5.49915088e+03 5.57206738e+03 5.90713770e+03 5.91048145e+03 5.73554395e+03 5.64030957e+03 5.69281348e+03 6.02397803e+03 6.36664990e+03 6.11643896e+03 5.97647168e+03 6.20455957e+03 6.19572754e+03 6.46769385e+03 6.45963525e+03 6.17910889e+03 6.21729102e+03 6.45588232e+03 6.51628711e+03 6.58041504e+03 6.60586426e+03 6.79805615e+03 6.97968506e+03 7.15475146e+03 7.01579883e+03 6.48037744e+03 7.19508789e+03 9.58603125e+03 9.58741602e+03 1.06789619e+04 9.89254395e+03 1.06329883e+04 1.24217803e+04 1.84219883e+04 2.09366914e+04 -6.11310250e+06 -43394564. -1.79721050e+06 -100529800. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.78508594e+04 2.22341113e+04 1.57472471e+04 1.61380762e+04 1.47305859e+04 1.48930020e+04 1.48929844e+04 1.46745537e+04 1.47561152e+04 1.47915449e+04 1.06296758e+04 1.16611992e+04 1.06544229e+04 1.02221152e+04 1.01215469e+04 9.94863770e+03 1.03050127e+04 1.03981709e+04 1.00200967e+04 1.00184580e+04 1.05581787e+04 1.06741064e+04 1.04266328e+04 1.04049316e+04 1.04767070e+04 1.05686455e+04 1.05515127e+04 1.05563037e+04 1.06018652e+04 1.06355322e+04 1.05591904e+04 1.05810068e+04 1.09389482e+04 1.10308701e+04 1.08280322e+04 1.08627891e+04 1.09429170e+04 1.10175391e+04 1.09920938e+04 1.10070752e+04 1.10892939e+04 1.08539180e+04 1.08324785e+04 1.11227041e+04 1.11442559e+04 1.16225381e+04 1.17259111e+04 1.13217188e+04 1.10408389e+04 1.10352354e+04 1.17849854e+04 1.18960508e+04 1.15055293e+04 1.13090703e+04 1.14029512e+04 1.15637227e+04 1.15003105e+04 1.19778701e+04 1.19981455e+04 1.13547930e+04 1.13176904e+04 1.19123066e+04 1.24000811e+04 1.21341846e+04 1.19336318e+04 1.19665400e+04 1.19336123e+04 1.18410391e+04 1.19740547e+04 1.20226934e+04 1.19737783e+04 1.20231523e+04 1.20736699e+04 1.22235117e+04 1.22293037e+04 1.25153604e+04 1.24608955e+04 1.21462188e+04 1.23735283e+04 1.24223945e+04 1.24802119e+04 1.25716357e+04 1.24794150e+04 1.24708369e+04 1.22640215e+04 1.19985176e+04 1.26101191e+04 1.28181592e+04 1.21952578e+04 1.22974697e+04 1.30371396e+04 1.33893867e+04 1.30047969e+04 1.27122881e+04 1.26704062e+04 1.26946465e+04 1.26232988e+04 1.25927305e+04 1.28992158e+04 1.28578398e+04 1.31821943e+04 1.31028457e+04 1.27727637e+04 1.30117061e+04 1.27092217e+04 1.27907480e+04 1.34702559e+04 1.33744727e+04 1.30683262e+04 1.27991475e+04 1.26509375e+04 1.33354297e+04 1.36334512e+04 1.32366025e+04 1.28411953e+04 1.28601689e+04 1.31852002e+04 1.31864521e+04 1.36316299e+04 1.37488779e+04 1.32876318e+04 1.30264590e+04 1.30418105e+04 1.36043652e+04 1.36777559e+04 1.33581807e+04 1.31923896e+04 1.32163145e+04 1.34244951e+04 1.30578838e+04 1.31178057e+04 1.39505176e+04 1.38387617e+04 1.34360176e+04 1.31103613e+04 1.30903701e+04 1.38835264e+04 1.39630254e+04 1.35623057e+04 1.31662529e+04 1.30994062e+04 1.35693047e+04 1.35498809e+04 1.35585918e+04 1.32406816e+04 1.34952295e+04 1.42181592e+04 1.38389404e+04 1.37311299e+04 1.38049746e+04 1.36549014e+04 1.34672080e+04 1.34939189e+04 1.36934980e+04 1.36599023e+04 1.35713564e+04 1.31622393e+04 1.34268691e+04 1.43058574e+04 1.37026016e+04 1.32565146e+04 1.36330127e+04 1.36191133e+04 1.40743955e+04 1.37913467e+04 1.32683350e+04 1.40001592e+04 1.40611006e+04 1.36793574e+04 1.36331455e+04 1.35666807e+04 1.35469785e+04 1.36178184e+04 1.35985654e+04 1.31859199e+04 1.35806416e+04 1.43582646e+04 1.40872119e+04 1.36093086e+04 1.31493506e+04 1.33152168e+04 1.41432656e+04 1.40846904e+04 1.37442549e+04 1.33712363e+04 1.32158574e+04 1.36090410e+04 1.36287129e+04 1.39328730e+04 1.36125752e+04 1.32369990e+04 1.36608477e+04 1.36017617e+04 1.38882148e+04 1.38187275e+04 1.34524883e+04 1.34424346e+04 1.34048340e+04 1.36077139e+04 1.32394053e+04 1.33665732e+04 1.41058027e+04 1.38637734e+04 1.34965371e+04 1.31239160e+04 1.30499043e+04 1.37996602e+04 1.38598613e+04 1.34388145e+04 1.30764248e+04 1.30355547e+04 1.34153662e+04 1.34506396e+04 1.37571162e+04 1.35425518e+04 1.32069268e+04 1.30608193e+04 1.29746826e+04 1.36316006e+04 1.35962471e+04 1.31742490e+04 1.30436006e+04 1.30317842e+04 1.34422988e+04 1.34493984e+04 1.28506494e+04 1.27842402e+04 1.34692871e+04 1.34536543e+04 1.27687344e+04 1.26809219e+04 1.33522686e+04 1.34053359e+04 1.29537549e+04 1.26235791e+04 1.26085693e+04 1.33477617e+04 1.32197119e+04 1.27785381e+04 1.28109092e+04 1.27625527e+04 1.27981787e+04 1.27030938e+04 1.26680186e+04 1.23593066e+04 1.26408193e+04 1.33472012e+04 1.28972080e+04 1.27162354e+04 1.28082861e+04 1.26508740e+04 1.26179248e+04 1.25949746e+04 1.25395537e+04 1.21914365e+04 1.19705557e+04 1.22992217e+04 1.25807314e+04 1.28855742e+04 1.23975381e+04 1.19263867e+04 1.22503994e+04 1.23632422e+04 1.27300186e+04 1.24820205e+04 1.20612148e+04 1.20001055e+04 1.18556445e+04 1.20855371e+04 1.21319463e+04 1.23303115e+04 1.22162920e+04 1.19357363e+04 1.17821602e+04 1.13903340e+04 1.18260596e+04 1.25025400e+04 1.22091729e+04 1.18226514e+04 1.14993789e+04 1.12822188e+04 1.18336104e+04 1.21524600e+04 1.17453184e+04 1.13033311e+04 1.12214805e+04 1.15218184e+04 1.14641016e+04 1.17579746e+04 1.16614307e+04 1.12755371e+04 1.13252188e+04 1.12455781e+04 1.14327148e+04 1.13719492e+04 1.08735586e+04 1.08925518e+04 1.14334600e+04 1.11800234e+04 1.06016543e+04 1.08963740e+04 1.14588018e+04 1.12246455e+04 1.09060146e+04 1.06034736e+04 1.05445645e+04 1.11254912e+04 1.10823740e+04 1.07079766e+04 1.03782471e+04 1.03211533e+04 1.05883418e+04 1.05464678e+04 1.04926416e+04 1.02144414e+04 1.03743633e+04 1.07836221e+04 1.04439600e+04 1.04729434e+04 1.03291621e+04 1.00861865e+04 1.01801230e+04 1.01849658e+04 1.01218418e+04 1.00350996e+04 9.90624512e+03 9.63347754e+03 9.85163379e+03 1.04023232e+04 9.85832227e+03 9.36924707e+03 9.64954297e+03 9.78269336e+03 1.00649531e+04 9.81722656e+03 9.50383691e+03 9.69458984e+03 9.58652734e+03 9.20934473e+03 9.07897559e+03 9.57198535e+03 9.55347461e+03 9.22144238e+03 9.06206250e+03 8.68710742e+03 9.06206934e+03 9.58948145e+03 9.24897070e+03 8.97204688e+03 8.69146191e+03 8.55620801e+03 9.02012207e+03 9.23619336e+03 8.93005078e+03 8.52226270e+03 8.37485840e+03 8.53359180e+03 8.60832422e+03 8.80509668e+03 8.59139160e+03 8.29500195e+03 8.42987598e+03 8.33717188e+03 8.44122363e+03 8.34705859e+03 8.13810254e+03 8.17388477e+03 8.08365527e+03 8.00962695e+03 7.74740039e+03 7.83856494e+03 8.32834863e+03 8.08148633e+03 7.72041748e+03 7.51861523e+03 7.53626855e+03 7.97748242e+03 7.86270020e+03 7.63486719e+03 7.37775830e+03 7.30780811e+03 7.47438965e+03 7.43823730e+03 7.37302832e+03 7.16852295e+03 7.25204492e+03 7.47391162e+03 7.24727148e+03 7.25207227e+03 7.21210547e+03 7.03580225e+03 6.92514209e+03 6.89408936e+03 6.83055127e+03 6.76954150e+03 6.78332031e+03 6.73843164e+03 6.85152295e+03 6.76568945e+03 6.41502295e+03 6.29880859e+03 6.42942920e+03 6.52206543e+03 6.67475098e+03 6.39905029e+03 6.09948828e+03 6.31949414e+03 6.42389844e+03 6.22655713e+03 6.04354883e+03 5.97078760e+03 6.01508838e+03 6.00366211e+03 5.90202588e+03 5.67323291e+03 5.78640576e+03 6.09397607e+03 5.83948242e+03 5.73601660e+03 5.54452051e+03 5.42817090e+03 5.73109717e+03 5.65047754e+03 5.47036182e+03 5.28493604e+03 5.11929443e+03 5.24990332e+03 5.33989404e+03 5.47079785e+03 5.19836572e+03 4.91063330e+03 5.05130176e+03 5.05400244e+03 5.18377832e+03 5.03579932e+03 4.80783008e+03 4.89991797e+03 4.85917969e+03 4.70161182e+03 4.53229492e+03 4.66046777e+03 4.83481006e+03 4.70510840e+03 4.55424951e+03 4.40674561e+03 4.36022461e+03 4.53292773e+03 4.47744141e+03 4.31414404e+03 4.18373926e+03 4.08362695e+03 4.16887646e+03 4.14682275e+03 4.20115186e+03 4.18303711e+03 3.99934106e+03 3.85846265e+03 3.85984448e+03 4.02195972e+03 3.89843018e+03 3.73623999e+03 3.77489844e+03 3.72363379e+03 3.61459619e+03 3.53246411e+03 3.61991455e+03 3.58303027e+03 3.44321558e+03 3.53217358e+03 3.52344434e+03 3.40169653e+03 3.33027856e+03 3.29849585e+03 3.26446094e+03 3.14036426e+03 3.06311792e+03 3.17887842e+03 3.18722485e+03 2.98850098e+03 2.85302515e+03 2.94927344e+03 3.09556348e+03 3.00668384e+03 2.80210938e+03 2.71595728e+03 2.82346558e+03 2.82731152e+03 2.71422046e+03 2.68195166e+03 2.58938379e+03 2.46735107e+03 2.52413818e+03 2.60887500e+03 2.55518481e+03 2.41592114e+03 2.31790308e+03 2.39502222e+03 2.43223047e+03 2.33370386e+03 2.20024365e+03 2.13715991e+03 2.17269678e+03 2.15439087e+03 2.17178906e+03 2.12553809e+03 2.02061597e+03 2.01295105e+03 1.99360693e+03 1.98873401e+03 1.89726416e+03 1.83255090e+03 1.88102600e+03 1.84082861e+03 1.78500208e+03 1.71094836e+03 1.70129602e+03 1.76260767e+03 1.65735376e+03 1.56765137e+03 1.57950024e+03 1.58061011e+03 1.55452966e+03 1.51117041e+03 1.51110901e+03 1.49777734e+03 1.42249646e+03 1.35201001e+03 1.32487488e+03 1.36256006e+03 1.30877991e+03 1.24428491e+03 1.26339380e+03 1.23687549e+03 1.18903333e+03 1.15223389e+03 1.16059790e+03 1.12744678e+03 1.06873792e+03 1.07114514e+03 1.04929309e+03 1.02722900e+03 1.00276190e+03 9.67757324e+02 9.34951660e+02 8.86565308e+02 8.59244690e+02 8.78994507e+02 8.87877075e+02 8.19030701e+02 7.56763306e+02 7.68345337e+02 7.90460205e+02 7.63393433e+02 7.06846497e+02 6.61168030e+02 6.70998291e+02 6.68386169e+02 6.29382141e+02 6.22332520e+02 5.99266113e+02 5.56743591e+02 5.43420105e+02 5.44316040e+02 5.29436035e+02 4.89715332e+02 4.59968658e+02 4.64673615e+02 4.64585266e+02 4.34894318e+02 4.02458252e+02 3.80889496e+02 3.83694977e+02 3.78329620e+02 3.50250122e+02 3.28598663e+02 3.15757477e+02 3.05396881e+02 2.91067352e+02 2.85633484e+02 2.67181183e+02 2.44547318e+02 2.40409088e+02 2.29826035e+02 2.18358170e+02 2.02164780e+02 1.87185715e+02 1.83078812e+02 1.68420944e+02 1.57409409e+02 1.56784241e+02 1.43725433e+02 1.34719299e+02 1.24365685e+02 1.55687119e+02 1.62922729e+02 1.24276215e+02 1.24485504e+02 1.21206108e+02 6.84212265e+01 9.23072052e+01 4.60269623e+02 1.15345375e+02 32617870. 7.87268250e+02 -323636864. 29024692. 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. 17319506. 4.62730408e+02 1.29754242e+02 8.69713593e+01 7.74911423e+01 7.79109116e+01 7.70410461e+01 6.52029495e+01 7.05411835e+01 7.38615189e+01 8.36729584e+01 1.01746315e+02 1.22811920e+02 1.09430260e+02 1.14437714e+02 1.34755737e+02 1.33709213e+02 1.43379089e+02 1.68523270e+02 1.77204803e+02 1.80197250e+02 1.94966599e+02 2.06639160e+02 2.11618668e+02 2.24687088e+02 2.43308792e+02 2.57614136e+02 2.70893280e+02 2.77433502e+02 2.85393463e+02 3.05831940e+02 3.23363678e+02 3.35001617e+02 3.45880737e+02 3.60657684e+02 3.85247864e+02 4.01136597e+02 4.11516998e+02 4.25541504e+02 4.41938568e+02 4.75875793e+02 4.96257233e+02 4.88828583e+02 5.03325623e+02 5.32946106e+02 5.54429871e+02 5.81392761e+02 5.96655579e+02 6.02745850e+02 6.30857605e+02 6.55638550e+02 6.74795715e+02 6.97671753e+02 7.07631958e+02 7.32917969e+02 7.61923767e+02 7.77801941e+02 7.96233276e+02 8.15132812e+02 8.40041931e+02 8.79980225e+02 9.08534607e+02 9.24123169e+02 9.26705688e+02 9.47854675e+02 1.00186621e+03 1.02642529e+03 1.02539014e+03 1.06024561e+03 1.09299719e+03 1.11907837e+03 1.16230713e+03 1.18635632e+03 1.18437097e+03 1.20517749e+03 1.26729578e+03 1.30645312e+03 1.30071912e+03 1.30373242e+03 1.34549670e+03 1.39071130e+03 1.45357666e+03 1.48339050e+03 1.45993201e+03 1.49318994e+03 1.56532080e+03 1.59559558e+03 1.60832227e+03 1.60462622e+03 1.62604456e+03 1.71395801e+03 1.76229480e+03 1.74705945e+03 1.78095300e+03 1.82443726e+03 1.85784460e+03 1.88679712e+03 1.91172644e+03 1.95840393e+03 1.99970117e+03 2.05945410e+03 2.08440015e+03 2.05206519e+03 2.09197314e+03 2.17776831e+03 2.18650269e+03 2.22309839e+03 2.26203027e+03 2.28900952e+03 2.37445630e+03 2.37866431e+03 2.38673828e+03 2.47433179e+03 2.51965991e+03 2.50313940e+03 2.52720361e+03 2.58870239e+03 2.63848218e+03 2.66952856e+03 2.68117261e+03 2.72039575e+03 2.78133984e+03 2.88472217e+03 2.90415161e+03 2.83411157e+03 2.90278882e+03 3.01785913e+03 3.04866089e+03 3.05313037e+03 3.05075781e+03 3.07018335e+03 3.18429053e+03 3.29367114e+03 3.28464722e+03 3.24246802e+03 3.29898389e+03 3.42594019e+03 3.48786475e+03 3.53003809e+03 3.48879736e+03 3.45786646e+03 3.55286157e+03 3.61673975e+03 3.64910620e+03 3.73435400e+03 3.73192847e+03 3.80396729e+03 3.93755859e+03 3.91864624e+03 3.82032690e+03 3.91355078e+03 4.04615063e+03 4.10107764e+03 4.17060303e+03 4.16722217e+03 4.12786328e+03 4.21690088e+03 4.39522852e+03 4.33933691e+03 4.20337500e+03 4.35671387e+03 4.53252393e+03 4.56539404e+03 4.52803223e+03 4.49721777e+03 4.55655469e+03 4.69865625e+03 4.72531738e+03 4.78161035e+03 4.86540527e+03 4.79423389e+03 4.88263428e+03 5.05127100e+03 4.98878906e+03 4.97222656e+03 5.04291357e+03 5.16665820e+03 5.25574023e+03 5.28918896e+03 5.18625586e+03 5.16078906e+03 5.35868604e+03 5.60310449e+03 5.67677295e+03 5.38397705e+03 5.41940186e+03 5.74977002e+03 5.69376074e+03 5.67660645e+03 5.69432568e+03 5.67302832e+03 5.81489062e+03 5.93348975e+03 5.97660547e+03 5.91419434e+03 5.93146484e+03 6.06122119e+03 6.22745508e+03 6.24075098e+03 6.19951904e+03 6.22319434e+03 6.34935156e+03 6.37588232e+03 6.29478418e+03 6.41180762e+03 6.51669678e+03 6.46152051e+03 6.67099219e+03 6.88463330e+03 6.56611182e+03 6.63613818e+03 6.88531250e+03 6.88964404e+03 6.94127637e+03 6.80738916e+03 6.90177539e+03 7.15343115e+03 7.19811182e+03 7.16239844e+03 7.01337549e+03 6.99491064e+03 7.26087256e+03 7.44605078e+03 7.39867139e+03 7.36160107e+03 7.52408984e+03 7.55118018e+03 7.70808301e+03 7.67102686e+03 7.54493457e+03 7.55299365e+03 7.66872754e+03 7.93910498e+03 7.86076660e+03 7.77123682e+03 7.89822266e+03 8.08606152e+03 8.14380664e+03 8.12356592e+03 8.04022168e+03 8.10596143e+03 8.28565918e+03 8.24987598e+03 8.48316211e+03 8.38436426e+03 8.28812012e+03 8.52007617e+03 8.34829395e+03 8.46949121e+03 8.77297363e+03 8.60412500e+03 8.60225977e+03 8.68486426e+03 8.81435254e+03 8.72703613e+03 8.67762207e+03 9.07957422e+03 9.28084277e+03 8.84145703e+03 8.89294336e+03 9.04269824e+03 9.09122754e+03 9.35772949e+03 9.30525000e+03 9.10874512e+03 9.24694043e+03 9.47854102e+03 9.49663770e+03 9.48460742e+03 9.34976758e+03 9.50801172e+03 9.68307812e+03 9.56348340e+03 9.62928125e+03 9.59506934e+03 9.62709766e+03 9.81164453e+03 9.94985645e+03 9.91960254e+03 9.81138867e+03 9.82405957e+03 1.01397715e+04 1.03281719e+04 1.00073271e+04 1.01434189e+04 1.02463789e+04 9.99681348e+03 1.02594775e+04 1.03794639e+04 1.01644512e+04 1.04115215e+04 1.05015938e+04 1.04784492e+04 1.07534443e+04 1.05413076e+04 1.04421826e+04 1.06101377e+04 1.07515176e+04 1.08257393e+04 1.05674248e+04 1.06065527e+04 1.08661074e+04 1.09461631e+04 1.10120498e+04 1.09514697e+04 1.08238604e+04 1.10960537e+04 1.14089902e+04 1.11161260e+04 1.09056406e+04 1.10086973e+04 1.13979287e+04 1.15466113e+04 1.11823369e+04 1.11682539e+04 1.13138525e+04 1.13776143e+04 1.14031777e+04 1.15464199e+04 1.14908838e+04 1.13700342e+04 1.15990273e+04 1.19003330e+04 1.16920684e+04 1.12919141e+04 1.15124268e+04 11821. 1.18334131e+04 1.18543721e+04 1.17565645e+04 1.17278545e+04 1.20941846e+04 1.22918701e+04 1.20045732e+04 1.18368525e+04 1.19689150e+04 1.23074502e+04 1.22422646e+04 1.18374629e+04 1.19123037e+04 1.21752559e+04 1.22474551e+04 1.23045400e+04 1.24445381e+04 1.22097578e+04 1.22974541e+04 1.23561602e+04 1.21531084e+04 1.22084277e+04 1.23480283e+04 1.25075586e+04 1.26313711e+04 1.24863447e+04 1.22707266e+04 1.23811523e+04 1.27263096e+04 1.30907441e+04 1.30080752e+04 1.24422988e+04 1.24864941e+04 1.27940391e+04 1.27599912e+04 1.26524932e+04 1.26991406e+04 1.28107158e+04 1.28973584e+04 1.28310469e+04 1.25613857e+04 1.28310566e+04 1.31744248e+04 1.32175840e+04 1.30388848e+04 1.27398828e+04 1.28919736e+04 1.29234980e+04 1.28590049e+04 1.32603965e+04 1.32602432e+04 1.28976826e+04 1.29482412e+04 1.31014404e+04 1.34125010e+04 1.34060742e+04 1.32267139e+04 1.32140146e+04 1.31807773e+04 1.31374531e+04 1.30506729e+04 1.32757510e+04 1.33670371e+04 1.35038867e+04 1.34566309e+04 1.29680078e+04 1.31948174e+04 1.33146191e+04 1.33505469e+04 1.37489590e+04 1.33567197e+04 1.30955996e+04 1.36003750e+04 1.37894375e+04 1.34988496e+04 1.34023135e+04 1.32961758e+04 1.32137705e+04 1.33921621e+04 1.35227393e+04 1.34583223e+04 1.37154688e+04 1.38428740e+04 1.36211113e+04 1.34803896e+04 1.33303838e+04 1.35849131e+04 1.38456426e+04 1.36606006e+04 1.33492871e+04 1.33662900e+04 1.35629648e+04 1.37620020e+04 1.41023594e+04 1.36871338e+04 1.33409004e+04 1.36162920e+04 1.35733232e+04 1.35127559e+04 1.38776387e+04 1.37772793e+04 1.34918936e+04 1.37465967e+04 1.36805576e+04 1.36219092e+04 1.37939258e+04 1.37541113e+04 1.36589033e+04 1.35341387e+04 1.35919707e+04 1.34973760e+04 1.36632012e+04 1.38084404e+04 1.37739482e+04 1.37230781e+04 1.34185098e+04 1.35826309e+04 1.36228389e+04 1.35331230e+04 1.38134609e+04 1.37741055e+04 1.35267305e+04 1.35400107e+04 1.36050439e+04 1.39024473e+04 1.39902363e+04 1.36289238e+04 1.34475654e+04 1.33843564e+04 1.35200400e+04 1.36266953e+04 1.36583486e+04 1.36994199e+04 1.36123408e+04 1.35044453e+04 1.33794023e+04 1.35430801e+04 1.38700459e+04 1.37530439e+04 1.34541055e+04 1.33882490e+04 1.33559893e+04 1.33754580e+04 1.35905615e+04 1.36779443e+04 1.35148037e+04 1.34093252e+04 1.33048574e+04 1.33407061e+04 1.35370010e+04 1.34743594e+04 1.34868252e+04 1.34579668e+04 1.32518613e+04 1.34376641e+04 1.32461309e+04 1.31678926e+04 1.35881084e+04 1.33568203e+04 1.31208174e+04 1.32630664e+04 1.31253311e+04 1.30624229e+04 1.35980352e+04 1.35309580e+04 1.28973496e+04 1.29924180e+04 1.30983096e+04 1.30105410e+04 1.32960791e+04 1.31980703e+04 1.27826729e+04 1.29025820e+04 1.30224932e+04 1.31824697e+04 1.32391074e+04 1.29857734e+04 1.30910693e+04 1.28846689e+04 1.25293574e+04 1.27077559e+04 1.30000889e+04 1.29126670e+04 1.29571777e+04 1.28483262e+04 1.23196006e+04 1.25500869e+04 1.30991416e+04 1.30296191e+04 1.26527432e+04 1.23254326e+04 1.23921572e+04 1.27837393e+04 1.27954219e+04 1.25391885e+04 1.25966299e+04 1.24499229e+04 1.24346299e+04 1.25100273e+04 1.21486084e+04 1.21958477e+04 1.24976758e+04 1.25851123e+04 1.23421553e+04 1.19523350e+04 1.19607510e+04 1.22728848e+04 1.24396953e+04 1.22438418e+04 1.19571758e+04 1.17909053e+04 1.19797793e+04 1.21724121e+04 1.23385938e+04 1.21110273e+04 1.17441660e+04 1.18787393e+04 1.18172119e+04 1.17085098e+04 1.18580391e+04 1.17675957e+04 1.17538467e+04 1.19044326e+04 1.16393662e+04 1.15670938e+04 1.16589463e+04 1.16354375e+04 1.16541934e+04 1.14767451e+04 1.12340146e+04 1.12455498e+04 1.14643184e+04 1.16340850e+04 1.15961787e+04 1.12785918e+04 1.10239912e+04 1.11074512e+04 1.10467822e+04 1.11456377e+04 1.12432627e+04 1.10527764e+04 1.08412695e+04 1.08134893e+04 1.08379092e+04 1.09781230e+04 1.11692471e+04 1.09953418e+04 1.07466445e+04 1.06136660e+04 1.03902793e+04 1.05444932e+04 1.06973867e+04 1.07513096e+04 1.07145957e+04 1.03753887e+04 1.02198291e+04 1.04094736e+04 1.05264922e+04 1.03462529e+04 1.03630811e+04 1.02109805e+04 9.99292773e+03 1.02292588e+04 1.03771377e+04 1.02049443e+04 9.93572070e+03 9.92086914e+03 9.98505176e+03 9.98340332e+03 9.93947949e+03 9.86352637e+03 9.91420020e+03 9.74415039e+03 9.55688965e+03 9.79788770e+03 9.74102539e+03 9.54615527e+03 9.69285742e+03 9.41128906e+03 9.22746094e+03 9.51464941e+03 9.51491895e+03 9.40408398e+03 9.65434277e+03 9.65862109e+03 8.73513867e+03 8.19733789e+03 9.72842285e+03 1.11483457e+04 1.17679648e+04 1.04828447e+04 2.21369844e+04 2.13570879e+04 -28961754. -25951300. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -45978132. 1.78991325e+06 2.38355352e+04 1.76284258e+04 1.13994932e+04 1.10370713e+04 1.05831035e+04 9.56437012e+03 9.95046973e+03 8.92501465e+03 8.28115430e+03 6.59705664e+03 6.41770996e+03 8.18823535e+03 6.61467773e+03 8.10486914e+03 5.77386377e+03 5.70649805e+03 6.22937305e+03 5.99790967e+03 5.69227539e+03 5.84664990e+03 5.97610010e+03 5.97710449e+03 5.94080176e+03 5.67335938e+03 5.55568848e+03 5.57950488e+03 5.53151904e+03 5.49837793e+03 5.38368408e+03 5.32266846e+03 5.44694238e+03 5.55145605e+03 5.35203906e+03 5.06378027e+03 5.03571680e+03 5.19852881e+03 5.18974072e+03 5.01890869e+03 4.84848535e+03 4.85850684e+03 4.98930762e+03 5.03034180e+03 4.87788232e+03 4.60581787e+03 4.64012451e+03 4.76657471e+03 4.67756641e+03 4.65945459e+03 4.54090283e+03 4.33404834e+03 4.38599170e+03 4.53674805e+03 4.38596875e+03 4.24169043e+03 4.31322510e+03 4.28732715e+03 4.20947314e+03 4.11797168e+03 3.93728589e+03 4.00599585e+03 4.19170801e+03 4.03937427e+03 3.85151733e+03 3.78219312e+03 3.73510815e+03 3.86895532e+03 3.93344312e+03 3.76924268e+03 3.60456909e+03 3.55153931e+03 3.49525049e+03 3.54874902e+03 3.62064526e+03 3.45211450e+03 3.35639722e+03 3.39468359e+03 3.33692383e+03 3.24530200e+03 3.19865015e+03 3.21518701e+03 3.23040356e+03 3.18328467e+03 3.12063989e+03 2.98767065e+03 2.90287549e+03 3.01303345e+03 3.06288232e+03 2.86535303e+03 2.73843042e+03 2.77350049e+03 2.81219287e+03 2.81213306e+03 2.78771191e+03 2.64702539e+03 2.56892700e+03 2.58886768e+03 2.55912207e+03 2.54777783e+03 2.48264355e+03 2.38713940e+03 2.36339014e+03 2.38849341e+03 2.36613403e+03 2.30810132e+03 2.26980908e+03 2.23427466e+03 2.20756836e+03 2.17690332e+03 2.07310864e+03 2.02739453e+03 2.10545557e+03 2.08544751e+03 1.94661841e+03 1.88200146e+03 1.87900818e+03 1.93270837e+03 1.94215686e+03 1.83974353e+03 1.74022217e+03 1.71034387e+03 1.70327063e+03 1.69940503e+03 1.67671448e+03 1.63371729e+03 1.60341565e+03 1.56409705e+03 1.53913586e+03 1.51527283e+03 1.44734875e+03 1.44322375e+03 1.46847961e+03 1.41094556e+03 1.35325891e+03 1.31532007e+03 1.27153198e+03 1.29392505e+03 1.29595105e+03 1.21310999e+03 1.15581238e+03 1.15153076e+03 1.17147070e+03 1.15969104e+03 1.10136169e+03 1.04736816e+03 1.01677411e+03 1.00098425e+03 1.00281897e+03 9.88832825e+02 9.29120544e+02 8.81201721e+02 8.86909668e+02 8.94450134e+02 8.61271423e+02 8.18905640e+02 7.97910461e+02 7.76561768e+02 7.59219971e+02 7.42806030e+02 7.00061035e+02 6.77586609e+02 6.77926758e+02 6.58014465e+02 6.29961304e+02 6.00971741e+02 5.83969482e+02 5.75271362e+02 5.57062866e+02 5.39628296e+02 5.10421509e+02 4.94061371e+02 4.86570465e+02 4.65875763e+02 4.44001526e+02 4.22747498e+02 4.05162537e+02 4.00342621e+02 3.94989380e+02 3.70932037e+02 3.38948242e+02 3.23189545e+02 3.24119141e+02 3.15353729e+02 2.97147827e+02 2.72233887e+02 2.56347504e+02 2.51399704e+02 2.42200882e+02 2.31038406e+02 2.13146759e+02 1.97672821e+02 1.89866928e+02 1.82397415e+02 1.73278976e+02 1.60262527e+02 1.47819321e+02 1.39053665e+02 1.30311646e+02 1.21294739e+02 1.12244614e+02 1.04345642e+02 9.52585754e+01 8.67299271e+01 7.89332123e+01 7.14239044e+01 6.71411285e+01 6.27082367e+01 5.55332222e+01 4.78053856e+01 4.08746681e+01 3.62328644e+01 3.34976654e+01 2.96644459e+01 2.45491562e+01 1.98147812e+01 1.60474243e+01 1.33192148e+01 1.09663181e+01 8.45787811e+00 6.15058088e+00 4.26843929e+00 2.74768138e+00 1.58533680e+00 7.43535399e-01 2.62175083e-01 1.11431092e-01 2.93164492e-01 8.23538363e-01 1.66725087e+00 2.69721127e+00 4.22242260e+00 6.26314449e+00 8.49747849e+00 1.10042810e+01 1.36757345e+01 1.72276459e+01 2.09118690e+01 2.37383976e+01 2.70585728e+01 3.21163139e+01 3.86824150e+01 4.51886559e+01 4.99072495e+01 5.28936768e+01 5.75619087e+01 6.48725128e+01 7.51345215e+01 8.50409546e+01 9.11272278e+01 9.40405731e+01 1.00872192e+02 1.16101028e+02 1.24484459e+02 1.27742584e+02 1.38341125e+02 1.49533951e+02 1.58726059e+02 1.74646240e+02 1.82228470e+02 1.86414963e+02 2.02391586e+02 2.10661545e+02 2.27573883e+02 2.46221054e+02 2.47507706e+02 2.64282562e+02 2.86021667e+02 2.94096558e+02 3.06160065e+02 3.20632080e+02 3.36421295e+02 3.52316681e+02 3.65373993e+02 3.68113647e+02 3.84761810e+02 4.25440125e+02 4.53681213e+02 4.57670776e+02 4.53769104e+02 4.59823334e+02 4.86479095e+02 5.26785339e+02 5.59542542e+02 5.66517456e+02 5.58674072e+02 5.79521851e+02 6.19381958e+02 6.32883179e+02 6.46651062e+02 6.72560486e+02 6.89944397e+02 7.06678711e+02 7.58944458e+02 7.66529419e+02 7.58700195e+02 7.96442444e+02 8.00143311e+02 8.49183411e+02 8.99811279e+02 8.86288879e+02 9.37584778e+02 9.48620117e+02 9.33302124e+02 9.90855774e+02 9.90948120e+02 1.03594324e+03 1.12764380e+03 1.09184473e+03 1.06088123e+03 1.11075659e+03 1.19175879e+03 1.26643774e+03 1.27290186e+03 1.23032397e+03 1.22011865e+03 1.26294836e+03 1.35022937e+03 1.43796790e+03 1.43442456e+03 1.39165405e+03 1.41729199e+03 1.48197571e+03 1.52781860e+03 1.53365332e+03 1.55698169e+03 1.59225720e+03 1.62360437e+03 1.71536462e+03 1.75106506e+03 1.67965356e+03 1.70300403e+03 1.78502380e+03 1.81495557e+03 1.86346643e+03 1.88914221e+03 1.98017212e+03 1.96317419e+03 1.91634351e+03 2.02015149e+03 1.99660193e+03 2.08107275e+03 2.26387354e+03 2.16944458e+03 2.06759521e+03 2.16171729e+03 2.30516748e+03 2.40501831e+03 2.43473633e+03 2.32844092e+03 2.29331104e+03 2.38730469e+03 2.50809277e+03 2.65184448e+03 2.63932520e+03 2.51397290e+03 2.53040088e+03 2.65652075e+03 2.73732397e+03 2.84509106e+03 2.87082007e+03 2.73969946e+03 2.75680762e+03 2.93991846e+03 3.01469702e+03 2.95423730e+03 2.97641602e+03 3.05292480e+03 3.06183984e+03 3.20259888e+03 3.26651294e+03 3.17448975e+03 3.18929297e+03 3.26630200e+03 3.32709375e+03 3.36817358e+03 3.40117114e+03 3.52756201e+03 3.60210767e+03 3.56312793e+03 3.49757764e+03 3.47611914e+03 3.66700806e+03 3.89934448e+03 3.87942236e+03 3.72553638e+03 3.66637329e+03 3.83184253e+03 4.10334424e+03 4.01234033e+03 3.81384790e+03 3.95698022e+03 4.11281299e+03 4.23864551e+03 4.43290576e+03 4.34266309e+03 4.12804150e+03 4.15139209e+03 4.32939648e+03 4.47343457e+03 4.54149512e+03 4.52430273e+03 4.54304541e+03 4.54867188e+03 4.69851562e+03 4.68940430e+03 4.62674316e+03 4.70705469e+03 4.70556787e+03 4.92979590e+03 5.08504199e+03 4.93788916e+03 5.06343750e+03 5.10730127e+03 5.12087549e+03 5.03015088e+03 4.97669824e+03 5.29474219e+03 5.51137158e+03 5.38728320e+03 5.22166943e+03 5.26933301e+03 5.60383545e+03 5.74108740e+03 5.61773730e+03 5.62720410e+03 5.50060986e+03 5.55151123e+03 5.86305811e+03 5.87368311e+03 5.81045459e+03 5.75347607e+03 5.68972607e+03 6.06117090e+03 6.32490625e+03 6.08137695e+03 5.99478125e+03 6.18617871e+03 6.19636768e+03 6.45702002e+03 6.48729199e+03 6.22699219e+03 6.16810059e+03 6.44253125e+03 6.53964648e+03 6.61411670e+03 6.74807031e+03 7.02137451e+03 7.07386670e+03 6.94432324e+03 6.93558252e+03 6.53399951e+03 7.40909619e+03 7.96972168e+03 7.49652148e+03 1.02170742e+04 1.40748828e+04 1.33104551e+04 2.96853047e+04 1.52692031e+05 44289408. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 57798184. 57798184. 2.34777625e+06 8.14286250e+04 2.36812676e+04 1.85975742e+04 1.60365615e+04 1.43251318e+04 1.38989756e+04 1.37233398e+04 1.46049365e+04 1.47277598e+04 1.43153770e+04 1.47375234e+04 1.47450098e+04 1.46277285e+04 1.48115566e+04 1.49024590e+04 1.26304531e+04 1.30431855e+04 1.07955254e+04 1.02883164e+04 1.01034932e+04 9.92638477e+03 1.02907090e+04 1.03875488e+04 9.98492871e+03 1.00628262e+04 1.05571777e+04 1.06567861e+04 1.04340850e+04 1.03928008e+04 1.04757617e+04 1.05355127e+04 1.05700977e+04 1.06091426e+04 1.05943350e+04 1.05936309e+04 1.04544590e+04 1.04560801e+04 1.10351338e+04 1.11399609e+04 1.07858564e+04 1.08491562e+04 1.09589150e+04 1.10144590e+04 1.09686943e+04 1.09666113e+04 1.11010615e+04 1.09778145e+04 1.09776523e+04 1.10542939e+04 1.10612686e+04 1.15902412e+04 1.16848018e+04 1.13159229e+04 1.10504854e+04 1.10605498e+04 1.17975068e+04 1.18517490e+04 1.15016992e+04 1.13443076e+04 1.14398906e+04 1.16364404e+04 1.15099512e+04 1.19233721e+04 1.20038535e+04 1.13693398e+04 1.13041211e+04 1.19207441e+04 1.24068262e+04 1.21152988e+04 1.18911660e+04 1.19240088e+04 1.19100898e+04 1.19597148e+04 1.19970391e+04 1.21237539e+04 1.21587764e+04 1.20120830e+04 1.20155801e+04 1.20823154e+04 1.21319424e+04 1.25858613e+04 1.25027188e+04 1.21600498e+04 1.22433984e+04 1.23084023e+04 1.26393018e+04 1.27107080e+04 1.24388867e+04 1.24286963e+04 1.22736494e+04 1.21163564e+04 1.27185996e+04 1.27322295e+04 1.20615088e+04 1.22608623e+04 1.30248164e+04 1.34576104e+04 1.30704707e+04 1.26786768e+04 1.26147451e+04 1.26293154e+04 1.27408936e+04 1.27711211e+04 1.28030098e+04 1.27565381e+04 1.31574697e+04 1.31400840e+04 1.27875264e+04 1.29102734e+04 1.25570605e+04 1.28678711e+04 1.36660117e+04 1.34360303e+04 1.30881826e+04 1.27546846e+04 1.27063340e+04 1.34757041e+04 1.35472393e+04 1.31365508e+04 1.28509385e+04 1.28198350e+04 1.31223818e+04 1.31778828e+04 1.36408691e+04 1.37065195e+04 1.32808105e+04 1.31874717e+04 1.31886875e+04 1.34526543e+04 1.35395801e+04 1.33820225e+04 1.31871074e+04 1.32438916e+04 1.33270205e+04 1.29180283e+04 1.32348975e+04 1.40741279e+04 1.38679521e+04 1.34577256e+04 1.31199629e+04 1.31070293e+04 1.38698828e+04 1.39354639e+04 1.35423008e+04 1.31779668e+04 1.31081924e+04 1.36175488e+04 1.35800479e+04 1.35319434e+04 1.32417705e+04 1.34993916e+04 1.41959434e+04 1.38288740e+04 1.37249111e+04 1.38202783e+04 1.36705596e+04 1.34308145e+04 1.34617305e+04 1.35935508e+04 1.35200557e+04 1.36750146e+04 1.32981406e+04 1.34517266e+04 1.43741045e+04 1.37371387e+04 1.32085576e+04 1.36035811e+04 1.36235283e+04 1.40483809e+04 1.38769580e+04 1.33932969e+04 1.38754531e+04 1.39354014e+04 1.37083760e+04 1.36192100e+04 1.35907471e+04 1.35637764e+04 1.35682607e+04 1.35946846e+04 1.32259785e+04 1.36094971e+04 1.43684072e+04 1.40716484e+04 1.35655107e+04 1.31513682e+04 1.33719482e+04 1.41494727e+04 1.40295078e+04 1.36838770e+04 1.33919863e+04 1.32456865e+04 1.35941250e+04 1.36481172e+04 1.39265459e+04 1.37571865e+04 1.34032754e+04 1.34894160e+04 1.34548916e+04 1.39119053e+04 1.38191738e+04 1.34086875e+04 1.34594902e+04 1.34657568e+04 1.34498145e+04 1.30969697e+04 1.34601416e+04 1.42807363e+04 1.39202988e+04 1.34646328e+04 1.31005146e+04 1.30027852e+04 1.37715371e+04 1.38933008e+04 1.34541523e+04 1.30689062e+04 1.30115605e+04 1.33982168e+04 1.34077344e+04 1.37378555e+04 1.36867695e+04 1.33252666e+04 1.29239600e+04 1.28660088e+04 1.36420332e+04 1.35877959e+04 1.31952021e+04 1.29438438e+04 1.28672627e+04 1.35758408e+04 1.36327354e+04 1.27941758e+04 1.27210293e+04 1.35021826e+04 1.35032559e+04 1.27477705e+04 1.27042861e+04 1.33393125e+04 1.34038389e+04 1.29705703e+04 1.26287646e+04 1.26249492e+04 1.33020547e+04 1.31659482e+04 1.26860381e+04 1.28501270e+04 1.28347275e+04 1.27669961e+04 1.27335908e+04 1.27214434e+04 1.23929814e+04 1.26610879e+04 1.32027676e+04 1.28152070e+04 1.28911484e+04 1.29277275e+04 1.26090615e+04 1.25979697e+04 1.25669678e+04 1.24853330e+04 1.22361680e+04 1.21660977e+04 1.24150615e+04 1.24474385e+04 1.27487471e+04 1.23663535e+04 1.19434707e+04 1.22345469e+04 1.23326846e+04 1.26979971e+04 1.25171611e+04 1.20777334e+04 1.19622480e+04 1.18643262e+04 1.20961592e+04 1.20638926e+04 1.23104111e+04 1.22437744e+04 1.19124932e+04 1.18780449e+04 1.14825527e+04 1.17808223e+04 1.24189736e+04 1.22152969e+04 1.18397188e+04 1.14784600e+04 1.12740957e+04 1.17824805e+04 1.21501553e+04 1.18120928e+04 1.13026045e+04 1.12609102e+04 1.15239678e+04 1.14575986e+04 1.17012793e+04 1.16215459e+04 1.12794229e+04 1.12272559e+04 1.11562676e+04 1.15504072e+04 1.15574053e+04 1.08813213e+04 1.08155801e+04 1.14070156e+04 1.12891133e+04 1.06753467e+04 1.07897168e+04 1.13062070e+04 1.12542529e+04 1.09390010e+04 1.06224521e+04 1.04997373e+04 1.10406914e+04 1.10874492e+04 1.07444473e+04 1.04188291e+04 1.02758750e+04 1.05296855e+04 1.05751113e+04 1.05384424e+04 1.01899795e+04 1.04013887e+04 1.07825693e+04 1.04674053e+04 1.04644150e+04 1.03156777e+04 1.01069736e+04 1.01845859e+04 1.01435420e+04 1.01591758e+04 1.00323232e+04 9.84075000e+03 9.58743750e+03 9.90124512e+03 1.03380469e+04 9.80027832e+03 9.31651270e+03 9.61951172e+03 9.87173047e+03 1.01351211e+04 9.78789453e+03 9.45400586e+03 9.67924512e+03 9.64819629e+03 9.28798730e+03 9.12302637e+03 9.45230078e+03 9.38482324e+03 9.20712012e+03 9.06364258e+03 8.74202344e+03 9.07203711e+03 9.59564844e+03 9.29288867e+03 8.98836133e+03 8.69871094e+03 8.55026562e+03 9.00176367e+03 9.24134961e+03 8.91862988e+03 8.57826172e+03 8.52787598e+03 8.52286230e+03 8.48847168e+03 8.72945898e+03 8.58249902e+03 8.31219434e+03 8.36031348e+03 8.24849219e+03 8.49979688e+03 8.48109180e+03 8.14827393e+03 8.12212500e+03 8.06573193e+03 8.08012256e+03 7.86612402e+03 7.84209570e+03 8.16680371e+03 8.04010889e+03 7.84824609e+03 7.56991992e+03 7.56412158e+03 7.99310449e+03 7.91210156e+03 7.62629834e+03 7.43829102e+03 7.31605273e+03 7.35879688e+03 7.35176611e+03 7.38841406e+03 7.17015332e+03 7.19324609e+03 7.45649512e+03 7.16954688e+03 7.29480762e+03 7.24875537e+03 7.01297363e+03 6.93237305e+03 6.88345752e+03 6.85817969e+03 6.81159473e+03 6.71705176e+03 6.70141113e+03 6.78910596e+03 6.78524219e+03 6.42920557e+03 6.35497705e+03 6.42515332e+03 6.49470312e+03 6.65815771e+03 6.49428174e+03 6.13680713e+03 6.27868896e+03 6.35633447e+03 6.21620264e+03 6.09369336e+03 6.01346973e+03 5.92348340e+03 5.88640576e+03 6.00187988e+03 5.75544092e+03 5.78816016e+03 6.02730566e+03 5.86237500e+03 5.68317090e+03 5.55212695e+03 5.47308105e+03 5.72029102e+03 5.63862842e+03 5.46187451e+03 5.32214941e+03 5.11915869e+03 5.19398438e+03 5.38164990e+03 5.48785254e+03 5.23691260e+03 5.02962256e+03 5.01977148e+03 5.00152686e+03 5.15337744e+03 5.07613330e+03 4.85969971e+03 4.81778564e+03 4.76367188e+03 4.74991895e+03 4.62337891e+03 4.62547461e+03 4.77109912e+03 4.67018311e+03 4.56055713e+03 4.43421240e+03 4.34621631e+03 4.54775293e+03 4.49935889e+03 4.32491699e+03 4.17409375e+03 4.11524658e+03 4.15656641e+03 4.14450293e+03 4.20467090e+03 4.18248779e+03 3.98311035e+03 3.84852271e+03 3.85138062e+03 4.01640552e+03 3.92895264e+03 3.79654443e+03 3.73577271e+03 3.67248853e+03 3.62957568e+03 3.56296997e+03 3.61117651e+03 3.55681543e+03 3.44463989e+03 3.52100391e+03 3.51950366e+03 3.40825928e+03 3.33513770e+03 3.28834131e+03 3.25840625e+03 3.14433008e+03 3.06619312e+03 3.18655664e+03 3.18107983e+03 2.98281812e+03 2.87298145e+03 2.98463403e+03 3.06786377e+03 2.97728003e+03 2.82387305e+03 2.72107642e+03 2.79804321e+03 2.80432910e+03 2.71575293e+03 2.67674390e+03 2.58164917e+03 2.44376440e+03 2.50128076e+03 2.62339014e+03 2.58865820e+03 2.41444800e+03 2.31026099e+03 2.39678149e+03 2.43484692e+03 2.32471997e+03 2.21731348e+03 2.16121167e+03 2.15078564e+03 2.14013477e+03 2.17688696e+03 2.14772583e+03 2.04550476e+03 1.98404236e+03 1.94743250e+03 1.99408960e+03 1.92263770e+03 1.84153149e+03 1.88634131e+03 1.84462476e+03 1.79130884e+03 1.72570630e+03 1.68702539e+03 1.74461707e+03 1.66340259e+03 1.57174414e+03 1.57998962e+03 1.58349451e+03 1.55640845e+03 1.50814636e+03 1.50943469e+03 1.49346997e+03 1.42457678e+03 1.35189941e+03 1.32009045e+03 1.37087061e+03 1.32020386e+03 1.25696680e+03 1.24370789e+03 1.21208325e+03 1.20631262e+03 1.17389209e+03 1.15347913e+03 1.11791516e+03 1.06682056e+03 1.07789868e+03 1.05928870e+03 1.01987225e+03 9.94265137e+02 9.67088562e+02 9.32620850e+02 8.85215942e+02 8.60006226e+02 8.81394226e+02 8.89339783e+02 8.18124207e+02 7.61486816e+02 7.76944641e+02 7.84172546e+02 7.52967834e+02 7.05566772e+02 6.66766541e+02 6.79453918e+02 6.61275696e+02 6.18835999e+02 6.26566406e+02 6.02423401e+02 5.49831848e+02 5.38402283e+02 5.48488037e+02 5.34997559e+02 4.90495087e+02 4.59371979e+02 4.65121307e+02 4.64290527e+02 4.35769470e+02 4.03023895e+02 3.80128937e+02 3.83819336e+02 3.74124329e+02 3.47148987e+02 3.35289825e+02 3.22565918e+02 3.03098816e+02 2.87223633e+02 2.84586700e+02 2.67211456e+02 2.44701706e+02 2.40182510e+02 2.29761551e+02 2.18810989e+02 2.02028488e+02 1.86726456e+02 1.83375717e+02 1.68303329e+02 1.57500839e+02 1.63125687e+02 1.50290268e+02 1.36587234e+02 1.21392151e+02 2.21782471e+02 3.32481415e+02 2.50909546e+02 2.20992981e+02 2.30488373e+02 1.17823944e+02 3.18690399e+02 1.94947144e+03 -18561808. -4.17077550e+06 -4.17077550e+06 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. 17319506. 4.62730408e+02 1.29754242e+02 8.69713593e+01 7.74911423e+01 6.85718842e+01 7.69611511e+01 7.42130661e+01 8.10876389e+01 8.14861603e+01 8.91453857e+01 9.77364197e+01 1.04293243e+02 1.13068192e+02 1.21020592e+02 1.29023010e+02 1.41627335e+02 1.51456451e+02 1.60164795e+02 1.71849991e+02 1.77358429e+02 1.87464020e+02 2.05422485e+02 2.14700699e+02 2.24249832e+02 2.43281509e+02 2.62686096e+02 2.68961517e+02 2.74673431e+02 2.87825775e+02 2.99529449e+02 3.21137268e+02 3.43059174e+02 3.51013306e+02 3.65094482e+02 3.89502014e+02 4.00522705e+02 4.06324799e+02 4.26383240e+02 4.43184265e+02 4.61759674e+02 4.92470703e+02 4.99577637e+02 5.10363098e+02 5.43857727e+02 5.55636414e+02 5.65520813e+02 5.85147217e+02 6.08114319e+02 6.35509827e+02 6.56717102e+02 6.87061707e+02 6.95595276e+02 7.06264099e+02 7.44421814e+02 7.49887146e+02 7.60894348e+02 8.06482300e+02 8.28636841e+02 8.43606628e+02 8.82712341e+02 9.03589539e+02 9.11245850e+02 9.37575500e+02 9.57540344e+02 9.73311096e+02 1.01421350e+03 1.04460608e+03 1.07454810e+03 1.10622241e+03 1.11704150e+03 1.13531885e+03 1.16668896e+03 1.20362170e+03 1.21987927e+03 1.24867993e+03 1.31799231e+03 1.31933752e+03 1.29789160e+03 1.35594873e+03 1.38702271e+03 1.40447278e+03 1.46883411e+03 1.48900049e+03 1.49883057e+03 1.57042969e+03 1.61728467e+03 1.60335657e+03 1.59901025e+03 1.62686951e+03 1.67495630e+03 1.74248633e+03 1.77847595e+03 1.80692200e+03 1.85743896e+03 1.87673853e+03 1.87228528e+03 1.88029285e+03 1.95288098e+03 1.99527600e+03 2.00594299e+03 2.06891626e+03 2.09656714e+03 2.11120728e+03 2.19149292e+03 2.18839844e+03 2.17809961e+03 2.24053223e+03 2.31825659e+03 2.36976123e+03 2.36502197e+03 2.40891089e+03 2.48417920e+03 2.52406763e+03 2.53255005e+03 2.51180103e+03 2.54657202e+03 2.65559473e+03 2.70374976e+03 2.69472217e+03 2.75228027e+03 2.76513916e+03 2.78059033e+03 2.89002563e+03 2.90970044e+03 2.89343677e+03 2.96161938e+03 3.06809326e+03 3.12223145e+03 3.11851099e+03 3.07530713e+03 3.10223291e+03 3.22216187e+03 3.31334937e+03 3.26196973e+03 3.32031860e+03 3.47628784e+03 3.48183350e+03 3.47514209e+03 3.49765771e+03 3.45987769e+03 3.50335107e+03 3.58858374e+03 3.68962183e+03 3.73615503e+03 3.76896289e+03 3.85369580e+03 3.87768799e+03 3.84988843e+03 3.85928931e+03 3.90947876e+03 4.01270972e+03 4.09795166e+03 4.19024756e+03 4.20854883e+03 4.19582275e+03 4.19946924e+03 4.27500781e+03 4.36385840e+03 4.25096436e+03 4.32665918e+03 4.52067334e+03 4.59821875e+03 4.53210449e+03 4.54769775e+03 4.57913867e+03 4.59625488e+03 4.71067969e+03 4.86526660e+03 4.91086670e+03 4.86415186e+03 4.89856543e+03 4.96737744e+03 4.94619385e+03 4.99991064e+03 5.06820654e+03 5.08180664e+03 5.29228955e+03 5.40264844e+03 5.18158594e+03 5.25280957e+03 5.33358301e+03 5.42049072e+03 5.56558154e+03 5.41009131e+03 5.42351758e+03 5.69558203e+03 5.74836865e+03 5.72836523e+03 5.73135693e+03 5.72845215e+03 5.73050049e+03 5.89440283e+03 6.05885254e+03 5.99493457e+03 5.92594775e+03 6.12483691e+03 6.31510449e+03 6.16148682e+03 6.14659180e+03 6.23040576e+03 6.23104736e+03 6.43786230e+03 6.39386914e+03 6.42718652e+03 6.61902783e+03 6.47809863e+03 6.52390186e+03 6.67109424e+03 6.57076562e+03 6.66879443e+03 6.84242578e+03 6.91245801e+03 6.95834131e+03 6.91428516e+03 6.96358447e+03 6.97339404e+03 7.07346289e+03 7.23598438e+03 7.09314990e+03 7.05859814e+03 7.28841602e+03 7.44554150e+03 7.33836816e+03 7.46567920e+03 7.56553662e+03 7.39962109e+03 7.59194873e+03 7.79513574e+03 7.61840381e+03 7.54007129e+03 7.73909277e+03 7.76559424e+03 7.78346582e+03 7.80475049e+03 7.88126709e+03 7.99613184e+03 8.14826953e+03 8.17912061e+03 8.13677051e+03 8.17734473e+03 8.21942969e+03 8.19710254e+03 8.44515527e+03 8.23302148e+03 8.26205762e+03 8.62460547e+03 8.49473340e+03 8.45478223e+03 8.58327637e+03 8.66078125e+03 8.56880371e+03 8.65054492e+03 8.77622559e+03 8.95007031e+03 8.89283887e+03 8.93496289e+03 9.03595215e+03 8.87860938e+03 8.91869531e+03 9.03011523e+03 9.00860449e+03 9.27686523e+03 9.48842578e+03 9.27594824e+03 9.16846191e+03 9.30711621e+03 9.59162109e+03 9.55724023e+03 9.19723242e+03 9.50795898e+03 9.82631934e+03 9.66841211e+03 9.67256250e+03 9.64761230e+03 9.65071777e+03 9.82151270e+03 9.77727734e+03 9.73542383e+03 1.00433730e+04 1.00783408e+04 9.96887012e+03 1.01457549e+04 1.01710557e+04 1.01945879e+04 1.01325537e+04 9.93279395e+03 1.02609854e+04 1.05065039e+04 1.02144189e+04 1.02577676e+04 1.03855293e+04 1.05582119e+04 1.06672227e+04 1.03574863e+04 1.05617139e+04 1.08653262e+04 1.07330303e+04 1.06876387e+04 1.06819268e+04 1.06430967e+04 1.08243105e+04 1.08590146e+04 1.08134160e+04 1.10474346e+04 1.11387295e+04 1.10986953e+04 1.11923730e+04 1.11704824e+04 1.10133457e+04 1.10387715e+04 1.13127354e+04 1.14290654e+04 1.12139629e+04 1.11752715e+04 1.11911270e+04 1.12841738e+04 1.15731406e+04 1.15161738e+04 1.13494795e+04 1.14462334e+04 1.16971885e+04 1.18407617e+04 1.16866631e+04 1.14838193e+04 1.15727373e+04 1.17637129e+04 1.17029717e+04 1.17149189e+04 1.18985596e+04 1.19504834e+04 1.19427305e+04 1.21488457e+04 1.21257227e+04 1.19165254e+04 1.19002295e+04 1.21115508e+04 1.21974521e+04 1.18826279e+04 1.17879971e+04 1.21332617e+04 1.23194658e+04 1.24259658e+04 1.23631055e+04 1.21180820e+04 1.24077031e+04 1.26095742e+04 1.21817139e+04 1.20914756e+04 1.25181416e+04 1.27475127e+04 1.25444922e+04 1.23474834e+04 1.22559844e+04 1.23989766e+04 1.27377246e+04 1.29488477e+04 1.29382441e+04 1.25985713e+04 1.24932012e+04 1.26279600e+04 1.25991963e+04 1.26918711e+04 1.27307354e+04 1.27370977e+04 1.28983516e+04 1.29303271e+04 1.28309531e+04 1.27730107e+04 1.29361475e+04 1.33007266e+04 1.31807314e+04 1.27662236e+04 1.26871348e+04 1.29869863e+04 1.32829316e+04 1.33382129e+04 1.31734180e+04 1.27681133e+04 1.28273633e+04 1.32584180e+04 1.33919912e+04 1.34005293e+04 1.32085176e+04 1.30694404e+04 1.32444307e+04 1.31601436e+04 1.32897363e+04 1.32608154e+04 1.29326719e+04 1.33427139e+04 1.36339199e+04 1.34155000e+04 1.31820566e+04 1.28846631e+04 1.32096865e+04 1.38611182e+04 1.37595420e+04 1.32899648e+04 1.34844277e+04 1.37253320e+04 1.33426182e+04 1.32602168e+04 1.31670420e+04 1.32455518e+04 1.37923984e+04 1.36432656e+04 1.32255557e+04 1.35004531e+04 1.37102266e+04 1.35634229e+04 1.35661230e+04 1.37128037e+04 1.35583281e+04 1.34265381e+04 1.35862930e+04 1.35426162e+04 1.37362012e+04 1.38216885e+04 1.36901084e+04 1.36864141e+04 1.33975947e+04 1.34711328e+04 1.36325703e+04 1.35751504e+04 1.37831553e+04 1.38808076e+04 1.37837656e+04 1.35429990e+04 1.34806914e+04 1.36396260e+04 1.37591875e+04 1.37900273e+04 1.35727627e+04 1.36195635e+04 1.37128535e+04 1.35780859e+04 1.37012178e+04 1.37127783e+04 1.34504863e+04 1.36245781e+04 1.36693154e+04 1.35312773e+04 1.37699170e+04 1.36215078e+04 1.34515684e+04 1.39198320e+04 1.40803994e+04 1.34263145e+04 1.32605498e+04 1.37274248e+04 1.39506797e+04 1.38844482e+04 1.35415596e+04 1.33168945e+04 1.34391396e+04 1.37366006e+04 1.37720938e+04 1.34639512e+04 1.34587969e+04 1.36031250e+04 1.35160947e+04 1.36456016e+04 1.37041328e+04 1.35595459e+04 1.36311348e+04 1.35581885e+04 1.35758018e+04 1.34651025e+04 1.33504863e+04 1.35401182e+04 1.35439561e+04 1.34961982e+04 1.33434727e+04 1.32699834e+04 1.35678857e+04 1.35707930e+04 1.34415957e+04 1.35482900e+04 1.32153154e+04 1.30837949e+04 1.35754941e+04 1.35010225e+04 1.30984941e+04 1.34220371e+04 1.34404863e+04 1.30192617e+04 1.33350283e+04 1.33801768e+04 1.30476309e+04 1.33192061e+04 1.33820762e+04 1.30166348e+04 1.30913604e+04 1.32016152e+04 1.31065605e+04 1.31669531e+04 1.31367070e+04 1.27415176e+04 1.28125078e+04 1.32287041e+04 1.32719805e+04 1.31693320e+04 1.28840078e+04 1.29139004e+04 1.28559863e+04 1.26101094e+04 1.28999131e+04 1.29208379e+04 1.27427305e+04 1.29933975e+04 1.28314062e+04 1.25098467e+04 1.27104443e+04 1.28390225e+04 1.28933389e+04 1.27215605e+04 1.25194932e+04 1.23860332e+04 1.26500127e+04 1.30148623e+04 1.25399521e+04 1.24079609e+04 1.23246523e+04 1.23533271e+04 1.26845156e+04 1.23580713e+04 1.21215547e+04 1.23022031e+04 1.24607832e+04 1.23483438e+04 1.19753975e+04 1.21552070e+04 1.24061738e+04 1.22010645e+04 1.21973018e+04 1.19951289e+04 1.19895723e+04 1.21931982e+04 1.21219424e+04 1.21525039e+04 1.19085342e+04 1.17572744e+04 1.18992217e+04 1.18934668e+04 1.19481914e+04 1.18197422e+04 1.15801797e+04 1.16312617e+04 1.18307246e+04 1.17772217e+04 1.16458506e+04 1.16001484e+04 1.15434170e+04 1.15771973e+04 1.14805195e+04 1.12981064e+04 1.14991250e+04 1.14890498e+04 1.13159805e+04 1.15211729e+04 1.13033467e+04 1.10998291e+04 1.12297930e+04 1.10556240e+04 1.10605947e+04 1.12024473e+04 1.10817021e+04 1.08496025e+04 1.08647871e+04 1.09482256e+04 1.09095947e+04 1.10912070e+04 1.09433721e+04 1.06905947e+04 1.07075840e+04 1.05536738e+04 1.06173672e+04 1.05955293e+04 1.06442588e+04 1.07388984e+04 1.03980156e+04 1.04531797e+04 1.04781172e+04 1.02759268e+04 1.02961045e+04 1.03810488e+04 1.03687031e+04 1.01719746e+04 1.01622549e+04 1.02284307e+04 1.01348398e+04 9.99521875e+03 9.96913086e+03 9.93165625e+03 1.00345684e+04 9.88226270e+03 9.82709961e+03 9.91404785e+03 9.65857324e+03 9.58726855e+03 9.85965820e+03 9.82726758e+03 9.49787012e+03 9.46447852e+03 9.39781934e+03 9.28956445e+03 9.74954297e+03 9.51868359e+03 9.17335645e+03 9.59409766e+03 9.67262891e+03 8.89009961e+03 8.21116895e+03 9.60510254e+03 1.11861787e+04 1.03990791e+04 9.04184961e+03 2.30128301e+04 2.25880039e+04 4529738. 2.98854375e+06 -4.81705650e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -45978132. 1.78991325e+06 2.38355352e+04 1.76284258e+04 1.13994932e+04 1.10370713e+04 1.05831035e+04 9.56437012e+03 9.02138770e+03 8.53906641e+03 6.32564600e+03 6.49868018e+03 6.55330322e+03 6.33376123e+03 6.22680664e+03 6.10044287e+03 6.17575977e+03 6.21478418e+03 6.11819580e+03 5.94802148e+03 5.77464307e+03 5.89879834e+03 5.91908643e+03 5.84414062e+03 5.81987305e+03 5.59436719e+03 5.56900830e+03 5.63828955e+03 5.56074463e+03 5.54903125e+03 5.34247266e+03 5.22849365e+03 5.50032910e+03 5.55852197e+03 5.31243018e+03 5.06502686e+03 5.04491309e+03 5.13841895e+03 5.14878076e+03 5.03689990e+03 4.89769727e+03 5.00675928e+03 4.97768115e+03 4.88949854e+03 4.83206396e+03 4.60351660e+03 4.65715820e+03 4.83820703e+03 4.69119775e+03 4.63229932e+03 4.51154053e+03 4.39132324e+03 4.41721191e+03 4.52768652e+03 4.42995264e+03 4.23045557e+03 4.28375195e+03 4.24434521e+03 4.17754199e+03 4.14711035e+03 4.02242505e+03 4.04439136e+03 4.09737256e+03 3.94801001e+03 3.86578784e+03 3.77368115e+03 3.82239258e+03 3.90507129e+03 3.82331323e+03 3.70928296e+03 3.60731519e+03 3.57926929e+03 3.54604736e+03 3.55684985e+03 3.57169849e+03 3.39962329e+03 3.38677393e+03 3.43822095e+03 3.38170605e+03 3.27767139e+03 3.15736060e+03 3.16984546e+03 3.24606470e+03 3.19116553e+03 3.09552783e+03 2.98950195e+03 2.94608643e+03 2.98084595e+03 3.00847192e+03 2.88657544e+03 2.77090845e+03 2.83787939e+03 2.80230005e+03 2.71684937e+03 2.75794214e+03 2.65267896e+03 2.59255225e+03 2.59938599e+03 2.56979175e+03 2.54768872e+03 2.43436694e+03 2.38164551e+03 2.39439551e+03 2.41083374e+03 2.38678027e+03 2.28711011e+03 2.25218628e+03 2.22290088e+03 2.18221631e+03 2.17798608e+03 2.09315698e+03 2.05941772e+03 2.09118066e+03 2.04968726e+03 1.95308118e+03 1.87730603e+03 1.91040698e+03 1.95828516e+03 1.90816980e+03 1.81857642e+03 1.74274695e+03 1.72382581e+03 1.72668164e+03 1.71220508e+03 1.68319141e+03 1.61384985e+03 1.58272534e+03 1.55875195e+03 1.53865649e+03 1.54064795e+03 1.45596436e+03 1.42825488e+03 1.45243384e+03 1.39398279e+03 1.35382202e+03 1.32549866e+03 1.30240015e+03 1.29613281e+03 1.25957861e+03 1.20830505e+03 1.15561340e+03 1.16497852e+03 1.18548755e+03 1.14078528e+03 1.08771375e+03 1.04429321e+03 1.02418079e+03 1.01679907e+03 1.00456317e+03 9.79075073e+02 9.13674072e+02 8.86962158e+02 8.90973267e+02 8.82961853e+02 8.73065613e+02 8.25269104e+02 7.92649963e+02 7.71886719e+02 7.55801636e+02 7.44064453e+02 7.05894470e+02 6.88339966e+02 6.71861816e+02 6.48179443e+02 6.33819397e+02 5.99897034e+02 5.89853333e+02 5.83661865e+02 5.50130188e+02 5.35826660e+02 5.15681519e+02 4.95572784e+02 4.84654755e+02 4.69559753e+02 4.46099792e+02 4.18361053e+02 4.05092773e+02 4.01104065e+02 3.93038635e+02 3.71877167e+02 3.39363892e+02 3.21667755e+02 3.21884918e+02 3.13143677e+02 2.96290619e+02 2.71986389e+02 2.60894714e+02 2.54398300e+02 2.38949081e+02 2.29165375e+02 2.11832733e+02 1.98943558e+02 1.92418076e+02 1.82929489e+02 1.71849747e+02 1.58454453e+02 1.49195419e+02 1.39670868e+02 1.30224792e+02 1.23099655e+02 1.12607895e+02 1.04143974e+02 9.55776367e+01 8.67566528e+01 7.91476059e+01 7.21116409e+01 6.75062943e+01 6.15141640e+01 5.47836227e+01 4.80676193e+01 4.09316864e+01 3.69097672e+01 3.39017868e+01 2.92838078e+01 2.45919800e+01 2.00563583e+01 1.63351517e+01 1.35661173e+01 1.11024933e+01 8.54962540e+00 6.27517986e+00 4.46574783e+00 2.92757034e+00 1.76123929e+00 9.18811738e-01 4.30104733e-01 2.77783543e-01 4.55870062e-01 9.79966879e-01 1.83861721e+00 2.89937234e+00 4.51993179e+00 6.49811935e+00 8.45447445e+00 1.10592699e+01 1.39108496e+01 1.74258575e+01 2.09005775e+01 2.36108818e+01 2.73837795e+01 3.25483284e+01 3.89159088e+01 4.55123367e+01 5.00468178e+01 5.29905128e+01 5.75302620e+01 6.52195969e+01 7.57414932e+01 8.51744919e+01 9.10167618e+01 9.40662613e+01 1.01041771e+02 1.16081787e+02 1.25011566e+02 1.27069534e+02 1.36939468e+02 1.50873520e+02 1.60282089e+02 1.74721771e+02 1.81980469e+02 1.86171677e+02 2.03047852e+02 2.11637726e+02 2.27212601e+02 2.45560211e+02 2.47475891e+02 2.64564484e+02 2.86780304e+02 2.94735931e+02 3.06083893e+02 3.21101318e+02 3.37384430e+02 3.50917999e+02 3.66880157e+02 3.70176208e+02 3.82834442e+02 4.23142242e+02 4.53825836e+02 4.58310333e+02 4.54502594e+02 4.61342041e+02 4.84577423e+02 5.25277893e+02 5.60582886e+02 5.70100342e+02 5.60711975e+02 5.77565735e+02 6.18623291e+02 6.36838867e+02 6.46833252e+02 6.67063354e+02 6.88921082e+02 7.08951660e+02 7.55580688e+02 7.66367737e+02 7.60959534e+02 8.00989502e+02 8.02735107e+02 8.45061584e+02 8.95952026e+02 8.87617981e+02 9.37319519e+02 9.48286987e+02 9.39472107e+02 9.92961914e+02 9.86223816e+02 1.03397864e+03 1.13166431e+03 1.09170117e+03 1.06163208e+03 1.11667920e+03 1.19430579e+03 1.26162976e+03 1.27067725e+03 1.22420789e+03 1.21618958e+03 1.26798816e+03 1.35323425e+03 1.44561719e+03 1.43182336e+03 1.37939856e+03 1.41324609e+03 1.48322681e+03 1.53368042e+03 1.53136047e+03 1.55230396e+03 1.59779968e+03 1.62038818e+03 1.71845898e+03 1.76169080e+03 1.68352454e+03 1.70867542e+03 1.78421179e+03 1.81527515e+03 1.86319446e+03 1.88607776e+03 1.96976001e+03 1.96483667e+03 1.92722900e+03 2.01204626e+03 2.00073193e+03 2.08824585e+03 2.26546924e+03 2.16297876e+03 2.05768628e+03 2.15335205e+03 2.31357959e+03 2.41174976e+03 2.44179199e+03 2.34144238e+03 2.29411816e+03 2.37880127e+03 2.51507861e+03 2.65663647e+03 2.63905811e+03 2.51917188e+03 2.53446411e+03 2.67133276e+03 2.72859058e+03 2.82110303e+03 2.86328247e+03 2.73832397e+03 2.77886646e+03 2.93378613e+03 2.99974731e+03 2.98149512e+03 3.00347241e+03 3.02482056e+03 3.02701831e+03 3.21253369e+03 3.27677856e+03 3.19507129e+03 3.20760620e+03 3.23044165e+03 3.30777539e+03 3.37262964e+03 3.41027271e+03 3.56170630e+03 3.59092090e+03 3.52232422e+03 3.50183350e+03 3.47606787e+03 3.67449878e+03 3.91250073e+03 3.85322070e+03 3.70868555e+03 3.67882690e+03 3.85279150e+03 4.10361133e+03 3.98178174e+03 3.81449121e+03 3.95670947e+03 4.14862646e+03 4.25965430e+03 4.42285205e+03 4.34479346e+03 4.16740039e+03 4.16796631e+03 4.32210254e+03 4.44293604e+03 4.51736133e+03 4.53254541e+03 4.55310889e+03 4.56365381e+03 4.68325586e+03 4.67474707e+03 4.61639551e+03 4.69398096e+03 4.75185303e+03 4.97604102e+03 5.06425635e+03 4.94680273e+03 5.03373193e+03 5.07756250e+03 5.12660205e+03 5.05210400e+03 4.99173828e+03 5.29866992e+03 5.54894775e+03 5.40376660e+03 5.20689600e+03 5.29956689e+03 5.62357471e+03 5.72076562e+03 5.61519092e+03 5.63827197e+03 5.53406689e+03 5.56827246e+03 5.83576807e+03 5.82758350e+03 5.79293604e+03 5.71003613e+03 5.73970752e+03 6.11239502e+03 6.34911963e+03 6.06193408e+03 5.96724072e+03 6.15460352e+03 6.22196777e+03 6.45177832e+03 6.45392480e+03 6.17131738e+03 6.24725098e+03 6.49297656e+03 6.53918408e+03 6.58550977e+03 6.69695068e+03 6.98369824e+03 7.11647949e+03 7.02478613e+03 7.03452637e+03 6.62523145e+03 7.53203174e+03 8.89504980e+03 8.57163086e+03 1.00709297e+04 1.55577568e+04 1.48260625e+04 2.12709004e+04 1.89910977e+04 2.87361975e+06 6.43096850e+06 2.35016775e+06 4487981. -100529800. 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. 0. 0. 0. 0. 0. 0. 57798184. 57798184. 2.34777625e+06 8.14286250e+04 2.36812676e+04 1.85975742e+04 1.35599834e+04 1.21209395e+04 9.08793555e+03 9.43460840e+03 1.06232041e+04 1.01374004e+04 9.52515039e+03 9.85438867e+03 9.94275195e+03 9.74692578e+03 9.77867285e+03 9.87941309e+03 9.90050879e+03 9.89993359e+03 9.91213965e+03 9.93424023e+03 1.00148223e+04 1.00250010e+04 1.02089854e+04 1.03191045e+04 9.96435938e+03 9.98348730e+03 1.05225469e+04 1.06236758e+04 1.03799668e+04 1.04118467e+04 1.04735391e+04 1.05135146e+04 1.05795303e+04 1.05912236e+04 1.05737910e+04 1.06441074e+04 1.05478203e+04 1.05484922e+04 1.09534316e+04 1.10578057e+04 1.08612480e+04 1.08560742e+04 1.09538574e+04 1.09832744e+04 1.09878389e+04 1.10304238e+04 1.11236006e+04 1.09778320e+04 1.09028857e+04 1.10248711e+04 1.10836543e+04 1.16383594e+04 1.17166006e+04 1.12790107e+04 1.10642773e+04 1.10852988e+04 1.17823457e+04 1.18754316e+04 1.14980723e+04 1.13057607e+04 1.13238711e+04 1.16844521e+04 1.16380781e+04 1.19248203e+04 1.20709004e+04 1.14344658e+04 1.12235312e+04 1.19013789e+04 1.24658916e+04 1.21234346e+04 1.18757773e+04 1.19193828e+04 1.19263145e+04 1.19529248e+04 1.20168643e+04 1.19765000e+04 1.19806963e+04 1.21250068e+04 1.21344824e+04 1.21167705e+04 1.21593701e+04 1.25369043e+04 1.26086328e+04 1.23060303e+04 1.22565703e+04 1.23102012e+04 1.25313818e+04 1.25701836e+04 1.24529482e+04 1.24864941e+04 1.22720332e+04 1.20835449e+04 1.26798994e+04 1.27169707e+04 1.20803945e+04 1.22676377e+04 1.30055137e+04 1.34180674e+04 1.30749219e+04 1.27151543e+04 1.25858691e+04 1.25861826e+04 1.27465195e+04 1.27588750e+04 1.27609141e+04 1.27616553e+04 1.32211514e+04 1.32739668e+04 1.28591162e+04 1.28984033e+04 1.25631641e+04 1.27231504e+04 1.35133867e+04 1.34218125e+04 1.30989346e+04 1.28310830e+04 1.26637607e+04 1.33253203e+04 1.36054482e+04 1.32528359e+04 1.28947725e+04 1.28655586e+04 1.31441621e+04 1.31872441e+04 1.36510010e+04 1.37146328e+04 1.32959639e+04 1.31877686e+04 1.31675352e+04 1.34519473e+04 1.35354414e+04 1.33705869e+04 1.33172842e+04 1.33468887e+04 1.32987979e+04 1.29654805e+04 1.31499658e+04 1.39041533e+04 1.38257812e+04 1.34311357e+04 1.31350957e+04 1.31293271e+04 1.38370244e+04 1.39045430e+04 1.35343672e+04 1.32186934e+04 1.31522275e+04 1.35546299e+04 1.35510684e+04 1.35779668e+04 1.32348330e+04 1.35213789e+04 1.43553877e+04 1.39855527e+04 1.36367598e+04 1.36450020e+04 1.36421230e+04 1.36092559e+04 1.36302881e+04 1.35339834e+04 1.34722061e+04 1.35637812e+04 1.32297236e+04 1.34606299e+04 1.42792539e+04 1.36882119e+04 1.32567373e+04 1.36497852e+04 1.35778838e+04 1.40677383e+04 1.39106270e+04 1.33564727e+04 1.39014043e+04 1.39590645e+04 1.36847617e+04 1.35869570e+04 1.35735801e+04 1.36805713e+04 1.36930566e+04 1.34976260e+04 1.31345586e+04 1.36026602e+04 1.43310479e+04 1.40238643e+04 1.36981436e+04 1.33319004e+04 1.32562021e+04 1.39842344e+04 1.40741826e+04 1.37532617e+04 1.33501436e+04 1.32170479e+04 1.36395576e+04 1.36678770e+04 1.39330869e+04 1.37412588e+04 1.33672402e+04 1.34788438e+04 1.34528018e+04 1.39453721e+04 1.38729316e+04 1.33964941e+04 1.35301377e+04 1.35639258e+04 1.34441680e+04 1.30660518e+04 1.33585977e+04 1.41685488e+04 1.38880693e+04 1.34674424e+04 1.31042441e+04 1.30093340e+04 1.37975947e+04 1.38846719e+04 1.34235576e+04 1.30673760e+04 1.30099414e+04 1.34144473e+04 1.34070664e+04 1.36898320e+04 1.35787949e+04 1.32195664e+04 1.30791504e+04 1.30072363e+04 1.36034365e+04 1.35976797e+04 1.32052959e+04 1.30421582e+04 1.29876279e+04 1.34578682e+04 1.35016807e+04 1.28000088e+04 1.27419023e+04 1.35164980e+04 1.35089326e+04 1.27665811e+04 1.26973271e+04 1.33267363e+04 1.34259570e+04 1.29899160e+04 1.26135186e+04 1.26394336e+04 1.33108623e+04 1.31362637e+04 1.27072764e+04 1.29570420e+04 1.29563887e+04 1.27516357e+04 1.26344824e+04 1.26814443e+04 1.23522471e+04 1.26528848e+04 1.33561836e+04 1.29021562e+04 1.27307266e+04 1.27842422e+04 1.26374961e+04 1.26105117e+04 1.25214395e+04 1.25389238e+04 1.22344717e+04 1.19907900e+04 1.22659746e+04 1.25602314e+04 1.28517041e+04 1.24130732e+04 1.19245879e+04 1.22200674e+04 1.23666719e+04 1.27133691e+04 1.25679658e+04 1.21705205e+04 1.19251172e+04 1.17925107e+04 1.20846631e+04 1.20945449e+04 1.23300957e+04 1.23228184e+04 1.19614619e+04 1.17200322e+04 1.14331299e+04 1.17747373e+04 1.24086973e+04 1.22134482e+04 1.18553203e+04 1.15090771e+04 1.12719844e+04 1.18133955e+04 1.21095703e+04 1.17524229e+04 1.13403018e+04 1.12742471e+04 1.15008193e+04 1.14682393e+04 1.17339287e+04 1.17507812e+04 1.13873711e+04 1.11890986e+04 1.11064932e+04 1.14814248e+04 1.14260791e+04 1.09039922e+04 1.08285664e+04 1.14433145e+04 1.12939189e+04 1.06661074e+04 1.07886055e+04 1.12756152e+04 1.12146094e+04 1.09642285e+04 1.05953652e+04 1.04894033e+04 1.10363262e+04 1.10967393e+04 1.07168174e+04 1.03869521e+04 1.02861348e+04 1.05342539e+04 1.06011367e+04 1.05314453e+04 1.01753428e+04 1.03512617e+04 1.08925410e+04 1.05507275e+04 1.04121221e+04 1.03902832e+04 1.02339590e+04 1.01626787e+04 1.01513779e+04 1.01079668e+04 1.00142363e+04 9.85192480e+03 9.59756934e+03 9.80951074e+03 1.02579160e+04 9.84680273e+03 9.42129199e+03 9.68679590e+03 9.80389160e+03 1.00180273e+04 9.82908789e+03 9.45512988e+03 9.62755664e+03 9.65285254e+03 9.25419238e+03 9.19842383e+03 9.51349219e+03 9.45182129e+03 9.23172754e+03 9.01044922e+03 8.71598633e+03 9.08535449e+03 9.60492773e+03 9.33401855e+03 8.96032324e+03 8.71645898e+03 8.62875098e+03 9.00116992e+03 9.16447852e+03 8.82092188e+03 8.56166699e+03 8.47894531e+03 8.52795508e+03 8.55543262e+03 8.74629785e+03 8.65948438e+03 8.41775879e+03 8.38940723e+03 8.27459082e+03 8.45425879e+03 8.43585645e+03 8.24254297e+03 8.05168701e+03 7.96941309e+03 8.04640137e+03 7.84397168e+03 7.84232471e+03 8.17159424e+03 8.07345410e+03 7.90593994e+03 7.62962695e+03 7.49275537e+03 7.91802783e+03 7.88913916e+03 7.63799414e+03 7.45100391e+03 7.30837158e+03 7.39941016e+03 7.31571094e+03 7.38030420e+03 7.17629248e+03 7.27586719e+03 7.51237500e+03 7.24411377e+03 7.25749512e+03 7.20895996e+03 7.03007861e+03 6.92922266e+03 6.81070361e+03 6.79355713e+03 6.81379736e+03 6.81307764e+03 6.75101416e+03 6.74391357e+03 6.73664648e+03 6.45422412e+03 6.29972461e+03 6.44349414e+03 6.49248584e+03 6.64236279e+03 6.46315820e+03 6.21471094e+03 6.35864600e+03 6.28302002e+03 6.11545605e+03 6.10268652e+03 6.06211182e+03 5.95412256e+03 5.91043604e+03 5.91049463e+03 5.75322559e+03 5.79901953e+03 6.01837891e+03 5.87702588e+03 5.72379590e+03 5.58448975e+03 5.43627441e+03 5.71726611e+03 5.65958594e+03 5.47796289e+03 5.27807227e+03 5.14180664e+03 5.28250928e+03 5.32699707e+03 5.42535400e+03 5.22218359e+03 5.03251465e+03 5.07543066e+03 4.97270117e+03 5.10283203e+03 5.04096436e+03 4.84000391e+03 4.81282422e+03 4.75080371e+03 4.77130518e+03 4.58621045e+03 4.64834424e+03 4.84033154e+03 4.67446143e+03 4.58357812e+03 4.44583936e+03 4.31907910e+03 4.51709668e+03 4.49698682e+03 4.30749707e+03 4.17739502e+03 4.12596289e+03 4.17045654e+03 4.15868701e+03 4.21869385e+03 4.16949512e+03 4.01830713e+03 3.88024780e+03 3.81646167e+03 4.01603662e+03 3.94225024e+03 3.76522021e+03 3.77468042e+03 3.71996680e+03 3.62990112e+03 3.58895703e+03 3.63344067e+03 3.52023291e+03 3.41087744e+03 3.54676611e+03 3.54854077e+03 3.38713525e+03 3.31590308e+03 3.29645312e+03 3.26697705e+03 3.13114380e+03 3.07253076e+03 3.20288257e+03 3.17171167e+03 2.94846899e+03 2.87177832e+03 3.00716504e+03 3.08572876e+03 2.96337427e+03 2.81710889e+03 2.75740039e+03 2.83592944e+03 2.77363892e+03 2.67133301e+03 2.67933667e+03 2.58462207e+03 2.46977271e+03 2.53386035e+03 2.60686060e+03 2.55351709e+03 2.41968433e+03 2.32239185e+03 2.40912915e+03 2.41986450e+03 2.31049365e+03 2.22603271e+03 2.18235571e+03 2.16794971e+03 2.14217871e+03 2.17972681e+03 2.11230371e+03 2.00432751e+03 2.01757129e+03 1.98782874e+03 1.97828967e+03 1.90620227e+03 1.83348865e+03 1.87636951e+03 1.84144629e+03 1.79320166e+03 1.71511658e+03 1.69508850e+03 1.76167432e+03 1.66503467e+03 1.58524780e+03 1.59565808e+03 1.56766357e+03 1.53988342e+03 1.51026782e+03 1.51303625e+03 1.49218860e+03 1.42366479e+03 1.35229236e+03 1.32129553e+03 1.36814417e+03 1.31903625e+03 1.25189929e+03 1.25045532e+03 1.22358130e+03 1.19610156e+03 1.17131262e+03 1.16409436e+03 1.10853101e+03 1.06046545e+03 1.08035986e+03 1.05818884e+03 1.01854248e+03 9.96233154e+02 9.70239990e+02 9.43247620e+02 8.92641541e+02 8.59182312e+02 8.81836426e+02 8.77816833e+02 8.09820312e+02 7.65278503e+02 7.84410461e+02 7.88378540e+02 7.46338684e+02 6.99764160e+02 6.70184387e+02 6.80641785e+02 6.64564453e+02 6.24454102e+02 6.20045166e+02 6.01365479e+02 5.63128967e+02 5.41907654e+02 5.39358582e+02 5.29262207e+02 4.90168762e+02 4.63272980e+02 4.70138000e+02 4.59328674e+02 4.30614227e+02 4.02401825e+02 3.82989899e+02 3.87805359e+02 3.75856598e+02 3.47630463e+02 3.31500977e+02 3.18763214e+02 3.02947296e+02 2.87907898e+02 2.85576965e+02 2.66259918e+02 2.43980011e+02 2.42921951e+02 2.32290161e+02 2.17452698e+02 2.00377762e+02 1.86773331e+02 1.83016373e+02 1.68927139e+02 1.59547592e+02 1.64304672e+02 1.48816910e+02 1.35186584e+02 1.21221046e+02 2.19725113e+02 3.23265869e+02 2.13731461e+02 2.46249863e+02 2.55351700e+02 1.26408028e+02 2.05707260e+02 6.41789734e+02 24524366. 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. 0. 0. 17319506. -25894714. 15371226. 4.51073050e+06 1.28847168e+02 1.03239418e+02 8.08736191e+01 7.66742325e+01 8.19737854e+01 8.39219208e+01 8.98603821e+01 9.78338470e+01 1.06648170e+02 1.13114250e+02 1.20705544e+02 1.30317001e+02 1.39141693e+02 1.51294281e+02 1.64529053e+02 1.77667603e+02 1.81543594e+02 1.88482773e+02 2.06593414e+02 2.12664780e+02 2.17699722e+02 2.39965927e+02 2.61368744e+02 2.72888519e+02 2.82261688e+02 2.88858032e+02 3.03521088e+02 3.22974243e+02 3.34400635e+02 3.44999969e+02 3.69299622e+02 3.91140259e+02 3.97400116e+02 4.09631622e+02 4.29671387e+02 4.47553284e+02 4.68350983e+02 4.82809479e+02 4.90122314e+02 5.19565674e+02 5.51340637e+02 5.50125000e+02 5.64829407e+02 5.96448730e+02 6.03605225e+02 6.27495728e+02 6.65278015e+02 6.76584534e+02 6.88034302e+02 7.19069702e+02 7.55227051e+02 7.62356506e+02 7.62616516e+02 7.83922607e+02 8.08667419e+02 8.60024780e+02 8.98938171e+02 8.97250732e+02 9.13798218e+02 9.35152954e+02 9.57157104e+02 9.86438599e+02 1.00486584e+03 1.02369940e+03 1.06812805e+03 1.12499036e+03 1.12535193e+03 1.13042041e+03 1.18000159e+03 1.20209668e+03 1.21796375e+03 1.25292847e+03 1.28954688e+03 1.30611267e+03 1.32191199e+03 1.37389844e+03 1.40055310e+03 1.42795825e+03 1.45833105e+03 1.45292883e+03 1.50677307e+03 1.58070300e+03 1.58136389e+03 1.58492224e+03 1.62837659e+03 1.65590271e+03 1.69726245e+03 1.72499500e+03 1.72834558e+03 1.79074951e+03 1.87760559e+03 1.87578418e+03 1.85264099e+03 1.89709863e+03 1.97027747e+03 2.00518030e+03 2.02280945e+03 2.05283521e+03 2.06069702e+03 2.13917822e+03 2.22205176e+03 2.19184375e+03 2.18925659e+03 2.22892676e+03 2.26962402e+03 2.35411523e+03 2.40496021e+03 2.40442627e+03 2.45220361e+03 2.54631030e+03 2.56925220e+03 2.54068359e+03 2.55066211e+03 2.59098145e+03 2.66323828e+03 2.73682324e+03 2.78206812e+03 2.78124438e+03 2.83214868e+03 2.88571753e+03 2.86244019e+03 2.89494629e+03 2.97959912e+03 3.00413354e+03 3.08968579e+03 3.16960718e+03 3.09593091e+03 3.13836646e+03 3.26049243e+03 3.26307910e+03 3.23579028e+03 3.32323047e+03 3.46436182e+03 3.47501147e+03 3.47962720e+03 3.49558350e+03 3.52519312e+03 3.57469507e+03 3.58629736e+03 3.65766699e+03 3.73788696e+03 3.76476929e+03 3.79970752e+03 3.89443335e+03 3.90888550e+03 3.83155957e+03 3.93472607e+03 4.07390552e+03 4.05232300e+03 4.13586328e+03 4.23247803e+03 4.25940576e+03 4.19642822e+03 4.23382422e+03 4.29703271e+03 4.28030664e+03 4.41256543e+03 4.54226221e+03 4.53934229e+03 4.53739746e+03 4.55797314e+03 4.61197217e+03 4.68408936e+03 4.69643408e+03 4.69329102e+03 4.80252490e+03 4.92373145e+03 4.90182715e+03 4.91801514e+03 5.02714795e+03 5.02998584e+03 5.13720605e+03 5.11537939e+03 5.14178906e+03 5.27187354e+03 5.28450000e+03 5.33047266e+03 5.34360889e+03 5.42572021e+03 5.55855273e+03 5.38822217e+03 5.46735791e+03 5.70587695e+03 5.65369678e+03 5.74999463e+03 5.76449854e+03 5.75308105e+03 5.79269043e+03 5.81424170e+03 5.84458936e+03 5.90685791e+03 6.04152783e+03 6.17089258e+03 6.29843994e+03 6.24394189e+03 6.23103809e+03 6.26539795e+03 6.22400635e+03 6.24168018e+03 6.33495557e+03 6.51844043e+03 6.68514600e+03 6.50692871e+03 6.50430811e+03 6.68884082e+03 6.56133398e+03 6.72068945e+03 6.90391650e+03 6.82118750e+03 6.84747266e+03 6.96234082e+03 7.06508691e+03 7.07878027e+03 7.02431689e+03 7.09784766e+03 7.03779541e+03 7.16703564e+03 7.31496338e+03 7.41455078e+03 7.38691699e+03 7.46045068e+03 7.53035889e+03 7.46086621e+03 7.58062402e+03 7.73645312e+03 7.61760254e+03 7.53481445e+03 7.74226709e+03 7.81031299e+03 7.90575684e+03 7.87871191e+03 7.82846484e+03 8.02012012e+03 8.01250391e+03 8.11985059e+03 8.13891455e+03 8.30026172e+03 8.33339258e+03 8.08310107e+03 8.26029980e+03 8.35089941e+03 8.34052148e+03 8.61478516e+03 8.45159570e+03 8.37231250e+03 8.75494043e+03 8.80717676e+03 8.50791797e+03 8.53673535e+03 8.87684375e+03 8.92684473e+03 8.77612598e+03 8.92796875e+03 9.17500684e+03 8.95286719e+03 8.95730273e+03 9.07247949e+03 8.95310059e+03 9.19431445e+03 9.36962598e+03 9.19809863e+03 9.36621484e+03 9.55430469e+03 9.43109961e+03 9.36056348e+03 9.37009180e+03 9.53816699e+03 9.76946289e+03 9.59069629e+03 9.53448438e+03 9.67115234e+03 9.78128809e+03 9.73134375e+03 9.76680469e+03 9.88130957e+03 9.94566211e+03 9.91866406e+03 1.00670947e+04 1.02280879e+04 1.00454111e+04 1.01047920e+04 1.02452422e+04 1.00558223e+04 1.03921914e+04 1.04437852e+04 1.01238594e+04 1.04233545e+04 1.04510098e+04 1.03567520e+04 1.05919004e+04 1.05274814e+04 1.05971191e+04 1.08404717e+04 1.06624648e+04 1.06674326e+04 1.07102793e+04 1.06264531e+04 1.06867012e+04 1.07686035e+04 1.09916738e+04 1.11158984e+04 1.10827490e+04 1.10502861e+04 1.11613730e+04 1.11080361e+04 1.09532002e+04 1.10995225e+04 1.14431162e+04 1.14172627e+04 1.11359629e+04 1.10959648e+04 1.13768096e+04 1.15686055e+04 1.14084033e+04 1.13127832e+04 1.14554629e+04 1.15957324e+04 1.17654004e+04 1.16837500e+04 1.15344414e+04 1.14669639e+04 1.15346543e+04 1.17072168e+04 1.17025996e+04 1.18432178e+04 1.19830088e+04 1.18551211e+04 1.19463145e+04 1.22161670e+04 1.20813721e+04 1.18041650e+04 1.20371914e+04 1.23733887e+04 1.21866592e+04 1.18007168e+04 1.18197070e+04 1.21884668e+04 1.23888848e+04 1.22799297e+04 1.22665605e+04 1.22778955e+04 1.24885723e+04 1.25143232e+04 1.20997168e+04 1.21594990e+04 1.24784697e+04 1.26503047e+04 1.24579844e+04 1.22521309e+04 1.24638154e+04 1.25495967e+04 1.27126270e+04 1.29126641e+04 1.28568643e+04 1.25314883e+04 1.23051201e+04 1.27178975e+04 1.31095723e+04 1.28562295e+04 1.26329102e+04 1.25701084e+04 1.28037695e+04 1.31228271e+04 1.28175840e+04 1.27805381e+04 1.29529189e+04 1.31514443e+04 1.31892744e+04 1.27721465e+04 1.29432148e+04 1.31059268e+04 1.29703555e+04 1.30793389e+04 1.30307676e+04 1.30208223e+04 1.30819746e+04 1.30742549e+04 1.31305439e+04 1.33019678e+04 1.33423906e+04 1.31253486e+04 1.32639717e+04 1.33795244e+04 1.32404277e+04 1.32265635e+04 1.29443320e+04 1.31163496e+04 1.36469863e+04 1.35359395e+04 1.33001348e+04 1.30527549e+04 1.32088877e+04 1.36782031e+04 1.34759033e+04 1.34089414e+04 1.36020156e+04 1.34357783e+04 1.32552305e+04 1.34468408e+04 1.35586836e+04 1.33665508e+04 1.35473633e+04 1.35202285e+04 1.31925869e+04 1.34819678e+04 1.36138779e+04 1.35845039e+04 1.38119346e+04 1.36978994e+04 1.35817100e+04 1.34868154e+04 1.34580117e+04 1.36425977e+04 1.37214160e+04 1.36526162e+04 1.35253760e+04 1.36176250e+04 1.35658438e+04 1.35218369e+04 1.38390967e+04 1.37390107e+04 1.35491807e+04 1.35995293e+04 1.36116914e+04 1.36454473e+04 1.37818271e+04 1.37658682e+04 1.34683154e+04 1.35594170e+04 1.37067061e+04 1.36342021e+04 1.37018643e+04 1.38134473e+04 1.37209414e+04 1.36443066e+04 1.34386299e+04 1.34293496e+04 1.36872031e+04 1.37841426e+04 1.40188174e+04 1.36740605e+04 1.32568867e+04 1.36744336e+04 1.39262148e+04 1.36818936e+04 1.35242783e+04 1.35883076e+04 1.36880742e+04 1.37618076e+04 1.36988740e+04 1.34561406e+04 1.34391816e+04 1.36884092e+04 1.36926494e+04 1.35923896e+04 1.35004395e+04 1.34808252e+04 1.36257158e+04 1.36199980e+04 1.36490918e+04 1.36531387e+04 1.35590596e+04 1.35105537e+04 1.35751777e+04 1.36067783e+04 1.32579609e+04 1.32507676e+04 1.35733486e+04 1.36019434e+04 1.36680693e+04 1.34184189e+04 1.33646709e+04 1.33316240e+04 1.33090762e+04 1.36396250e+04 1.32919814e+04 1.32230010e+04 1.36033359e+04 1.32233086e+04 1.30906475e+04 1.34526348e+04 1.34085811e+04 1.33474434e+04 1.34564346e+04 1.32127852e+04 1.28192764e+04 1.31833135e+04 1.34283086e+04 1.31053438e+04 1.33992490e+04 1.33714307e+04 1.28925420e+04 1.29540684e+04 1.29648301e+04 1.29352939e+04 1.31361260e+04 1.31165039e+04 1.30554004e+04 1.30445293e+04 1.29870303e+04 1.30593320e+04 1.29283301e+04 1.27377920e+04 1.28035742e+04 1.28571318e+04 1.27194150e+04 1.28122148e+04 1.28765996e+04 1.26571787e+04 1.27461797e+04 1.28049033e+04 1.27917695e+04 1.27508096e+04 1.24037617e+04 1.24841289e+04 1.28298896e+04 1.27487432e+04 1.24415186e+04 1.25257520e+04 1.26166152e+04 1.25196045e+04 1.24664893e+04 1.20863193e+04 1.20201826e+04 1.24060732e+04 1.25397793e+04 1.24858535e+04 1.21176924e+04 1.20846270e+04 1.23115557e+04 1.21909658e+04 1.21202715e+04 1.21114219e+04 1.20045000e+04 1.20482988e+04 1.20644902e+04 1.21691035e+04 1.19715068e+04 1.17551201e+04 1.20698926e+04 1.18871445e+04 1.17122188e+04 1.16999238e+04 1.15609189e+04 1.17299395e+04 1.19932881e+04 1.18801348e+04 1.14219863e+04 1.14089941e+04 1.16646230e+04 1.16068018e+04 1.15471455e+04 1.14275264e+04 1.14964404e+04 1.14952158e+04 1.13922900e+04 1.14393418e+04 1.12554814e+04 1.12632275e+04 1.13759551e+04 1.08592061e+04 1.08354404e+04 1.12357842e+04 1.12180508e+04 1.10273086e+04 1.09305039e+04 1.07788906e+04 1.07692012e+04 1.10098750e+04 1.10807012e+04 1.07986885e+04 1.06052100e+04 1.05080674e+04 1.06030342e+04 1.06914014e+04 1.07204258e+04 1.07067510e+04 1.04634189e+04 1.04434951e+04 1.04707334e+04 1.02434775e+04 1.01867227e+04 1.04219189e+04 1.03822500e+04 1.02133428e+04 1.01589170e+04 1.01037803e+04 1.01074219e+04 9.97934766e+03 1.00718887e+04 9.95441406e+03 9.95624219e+03 9.88500293e+03 9.75613770e+03 1.00719258e+04 9.74555078e+03 9.61576074e+03 9.85374121e+03 9.56631250e+03 9.46309277e+03 9.57574023e+03 9.54671289e+03 9.34056152e+03 9.52466699e+03 9.57336133e+03 9.31672656e+03 9.52097949e+03 9.56051074e+03 8.81184082e+03 8.30733301e+03 9.81530664e+03 1.05429951e+04 1.11568252e+04 1.21688721e+04 1.59889814e+04 1.18991084e+04 1.95131035e+04 1.81418609e+05 -4.81705650e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -45978132. 1.78991325e+06 -2.16381750e+06 5644062. 51703816. -1.02719238e+06 -2.75465475e+06 1.89772051e+04 1.49609443e+04 8.65057227e+03 6.15841162e+03 6.58344727e+03 6.62776758e+03 6.36606445e+03 6.25658545e+03 6.21137109e+03 6.11486523e+03 6.18183887e+03 6.18174902e+03 5.99371826e+03 5.78732471e+03 5.86187646e+03 5.90446729e+03 5.84110742e+03 5.78105273e+03 5.51254785e+03 5.52580762e+03 5.75241846e+03 5.57506250e+03 5.41486963e+03 5.32378906e+03 5.32121436e+03 5.51432275e+03 5.50342920e+03 5.28860938e+03 5.02614746e+03 5.06576172e+03 5.18243457e+03 5.14800293e+03 5.04670850e+03 4.94764795e+03 4.96956201e+03 4.95337646e+03 4.89331836e+03 4.88135400e+03 4.63900244e+03 4.68685303e+03 4.89219678e+03 4.64720020e+03 4.50608838e+03 4.47492285e+03 4.41787842e+03 4.53186914e+03 4.49667285e+03 4.32106934e+03 4.21423486e+03 4.30583740e+03 4.33300342e+03 4.20837158e+03 4.11643506e+03 4.00669092e+03 4.05710156e+03 4.11859961e+03 3.94168921e+03 3.90705078e+03 3.83678589e+03 3.76740454e+03 3.84879199e+03 3.84039478e+03 3.72748389e+03 3.60883789e+03 3.61652173e+03 3.59459644e+03 3.56480933e+03 3.54361792e+03 3.38252124e+03 3.35175928e+03 3.48940259e+03 3.35265332e+03 3.18817944e+03 3.15190479e+03 3.22872046e+03 3.28575439e+03 3.18749756e+03 3.09976538e+03 3.01002393e+03 2.93498145e+03 2.96448169e+03 3.00239038e+03 2.90533008e+03 2.79271802e+03 2.82454102e+03 2.79957031e+03 2.74736646e+03 2.77083228e+03 2.63044775e+03 2.56802783e+03 2.64448560e+03 2.58656543e+03 2.49506494e+03 2.44012988e+03 2.38893945e+03 2.43463013e+03 2.41629199e+03 2.31436035e+03 2.26879370e+03 2.28205615e+03 2.25301318e+03 2.18988354e+03 2.18398340e+03 2.11139233e+03 2.05227100e+03 2.09324609e+03 2.03700732e+03 1.94441113e+03 1.89984216e+03 1.89754053e+03 1.93747119e+03 1.90838135e+03 1.83723389e+03 1.74188745e+03 1.69911523e+03 1.75003406e+03 1.72598511e+03 1.64650220e+03 1.60222412e+03 1.59695532e+03 1.59377551e+03 1.54278796e+03 1.49731055e+03 1.44699878e+03 1.44796448e+03 1.47247668e+03 1.39516589e+03 1.35316809e+03 1.33512512e+03 1.28974988e+03 1.28496130e+03 1.26322607e+03 1.21777502e+03 1.16854297e+03 1.15441858e+03 1.17175037e+03 1.14359326e+03 1.09891248e+03 1.04761853e+03 1.01911688e+03 1.02812170e+03 1.00647162e+03 9.73249756e+02 9.21957947e+02 8.86661987e+02 8.93311768e+02 8.87961182e+02 8.57993225e+02 8.13655457e+02 7.92906128e+02 7.78844238e+02 7.60853760e+02 7.47830688e+02 7.11451416e+02 6.86706177e+02 6.77392578e+02 6.50760010e+02 6.27601990e+02 6.04063721e+02 5.95929871e+02 5.80715820e+02 5.47058044e+02 5.29401367e+02 5.08985382e+02 5.00274323e+02 4.99370178e+02 4.69510223e+02 4.38008240e+02 4.19488983e+02 4.08709442e+02 4.04570435e+02 3.92174622e+02 3.72086029e+02 3.43345428e+02 3.20542664e+02 3.19093231e+02 3.13675598e+02 2.99839874e+02 2.74568268e+02 2.58957184e+02 2.55133087e+02 2.42115189e+02 2.29634399e+02 2.14233643e+02 2.00587616e+02 1.91813522e+02 1.79870911e+02 1.70020203e+02 1.59914856e+02 1.49142151e+02 1.42246384e+02 1.30936951e+02 1.20668480e+02 1.12608192e+02 1.05276154e+02 9.80271072e+01 8.82723083e+01 7.91760712e+01 7.21134109e+01 6.83347626e+01 6.27087097e+01 5.47581711e+01 4.83138466e+01 4.17341537e+01 3.72228203e+01 3.42379417e+01 2.96826477e+01 2.49667358e+01 2.03177090e+01 1.67462940e+01 1.44465714e+01 1.17270594e+01 8.88486004e+00 6.71201658e+00 4.96156836e+00 3.43387938e+00 2.25597215e+00 1.42218626e+00 9.36108470e-01 7.77122498e-01 9.57233548e-01 1.49508786e+00 2.35225439e+00 3.42016792e+00 4.94171762e+00 6.86253405e+00 9.00516891e+00 1.16309538e+01 1.43117599e+01 1.78985481e+01 2.14906559e+01 2.41225052e+01 2.78893509e+01 3.31031532e+01 3.94039383e+01 4.58955078e+01 5.06282387e+01 5.36687965e+01 5.76994095e+01 6.54431763e+01 7.63801727e+01 8.61085358e+01 9.16122742e+01 9.40105362e+01 1.01143784e+02 1.17177338e+02 1.26004341e+02 1.28124878e+02 1.38580719e+02 1.49889923e+02 1.59649734e+02 1.75405411e+02 1.82779648e+02 1.87063080e+02 2.03512878e+02 2.12013367e+02 2.28839767e+02 2.45304047e+02 2.46012955e+02 2.66312714e+02 2.87323425e+02 2.93615326e+02 3.07245483e+02 3.21306580e+02 3.36137909e+02 3.52654907e+02 3.67304108e+02 3.70643372e+02 3.84669861e+02 4.23447327e+02 4.54722107e+02 4.60012207e+02 4.53101379e+02 4.60049713e+02 4.86883942e+02 5.27897156e+02 5.61148010e+02 5.67140015e+02 5.61444885e+02 5.79374817e+02 6.14801147e+02 6.34861511e+02 6.49247253e+02 6.70960938e+02 6.90313721e+02 7.10013977e+02 7.60038635e+02 7.65687439e+02 7.61964111e+02 8.05611389e+02 8.08394531e+02 8.49754028e+02 8.88601013e+02 8.83559387e+02 9.43109314e+02 9.50442688e+02 9.33636230e+02 9.92161560e+02 9.91367249e+02 1.02756067e+03 1.12945142e+03 1.09989148e+03 1.05911609e+03 1.10720825e+03 1.19769543e+03 1.27149390e+03 1.26719641e+03 1.22268689e+03 1.22546838e+03 1.26968188e+03 1.35122583e+03 1.43588184e+03 1.43591028e+03 1.38365942e+03 1.40736658e+03 1.48077905e+03 1.52337378e+03 1.54297815e+03 1.57074890e+03 1.59983887e+03 1.62139551e+03 1.71493408e+03 1.75016296e+03 1.67155347e+03 1.70000293e+03 1.79688684e+03 1.83278003e+03 1.86327649e+03 1.88930054e+03 1.97341272e+03 1.96723682e+03 1.92423242e+03 2.01547864e+03 1.99832715e+03 2.08459009e+03 2.26393213e+03 2.16387769e+03 2.06519482e+03 2.17004028e+03 2.31641821e+03 2.41380518e+03 2.43669507e+03 2.32285791e+03 2.28506250e+03 2.38606250e+03 2.52636914e+03 2.63921997e+03 2.62847095e+03 2.51632251e+03 2.54219604e+03 2.68062183e+03 2.73444116e+03 2.81823535e+03 2.86938135e+03 2.75256494e+03 2.76784814e+03 2.95543896e+03 3.01182788e+03 2.92634131e+03 2.95530225e+03 3.06213135e+03 3.06169678e+03 3.21109229e+03 3.27464160e+03 3.18409937e+03 3.20833643e+03 3.23892725e+03 3.31026587e+03 3.37857324e+03 3.38295410e+03 3.53151709e+03 3.63308740e+03 3.55806128e+03 3.49147095e+03 3.44680615e+03 3.66017969e+03 3.93296240e+03 3.87032227e+03 3.68559155e+03 3.65915698e+03 3.83544580e+03 4.10589844e+03 4.04162598e+03 3.83731689e+03 3.94777295e+03 4.10953174e+03 4.27639795e+03 4.41926172e+03 4.33676416e+03 4.13770605e+03 4.18628564e+03 4.34135352e+03 4.43890039e+03 4.49833008e+03 4.52692822e+03 4.56769824e+03 4.57966846e+03 4.68169629e+03 4.68430859e+03 4.65942871e+03 4.70917920e+03 4.69503467e+03 4.93047168e+03 5.02564453e+03 4.93384277e+03 5.07301465e+03 5.12366846e+03 5.10467236e+03 5.04558057e+03 4.97597949e+03 5.26956104e+03 5.54331787e+03 5.46223389e+03 5.26587109e+03 5.23845361e+03 5.57845508e+03 5.73258398e+03 5.61548633e+03 5.61277441e+03 5.49956787e+03 5.53310352e+03 5.85390771e+03 5.86227539e+03 5.78968408e+03 5.71489990e+03 5.69994678e+03 6.08649512e+03 6.35316113e+03 6.03241699e+03 5.96422607e+03 6.19481250e+03 6.24358447e+03 6.47655273e+03 6.45077734e+03 6.13339111e+03 6.26371533e+03 6.54324561e+03 6.50591895e+03 6.57803320e+03 6.66490869e+03 6.95377930e+03 6.87133545e+03 6.41818164e+03 6.73431934e+03 6.81876855e+03 7.17459375e+03 6.91418311e+03 6.76201123e+03 6.80751514e+03 8.94052637e+03 8.91911035e+03 1.08134316e+04 9.02204688e+03 1.36017334e+04 2.43222539e+04 3.27031230e+04 4487981. -100529800. 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. 0. 0. 0. 0. 0. 0. 57798184. 57798184. 2.34777625e+06 3603766. 2917443. 1.23226288e+06 2.91709082e+04 2.26886797e+04 1.18809453e+04 9.67448047e+03 1.13708662e+04 1.02331221e+04 9.46594531e+03 9.91098828e+03 9.98716211e+03 9.75209961e+03 9.80887793e+03 9.88809277e+03 1.00710322e+04 1.02288457e+04 9.93720801e+03 9.63846973e+03 1.00405908e+04 1.00708145e+04 9.46048242e+03 1.00755996e+04 1.04683213e+04 9.70128516e+03 1.03315518e+04 1.08554844e+04 1.03949297e+04 1.01961621e+04 1.04908701e+04 1.07889932e+04 1.06644092e+04 1.06600762e+04 1.06271885e+04 1.06508369e+04 1.05335430e+04 1.05886016e+04 1.09383281e+04 1.10204707e+04 1.08669385e+04 1.08637852e+04 1.09566016e+04 1.10356455e+04 1.09808633e+04 1.10186377e+04 1.10849746e+04 1.09847217e+04 1.09980781e+04 1.09938994e+04 1.10314561e+04 1.16313125e+04 1.16944414e+04 1.13116133e+04 1.10454961e+04 1.10603760e+04 1.17954922e+04 1.19004805e+04 1.15006738e+04 1.12410820e+04 1.13285088e+04 1.15610928e+04 1.15452139e+04 1.20392275e+04 1.21149844e+04 1.13732090e+04 1.12165703e+04 1.18388779e+04 1.25334590e+04 1.22391582e+04 1.18839736e+04 1.19293564e+04 1.19194062e+04 1.20354219e+04 1.21615352e+04 1.20062480e+04 1.19388740e+04 1.20539766e+04 1.20582207e+04 1.20961660e+04 1.21470840e+04 1.25383359e+04 1.25142031e+04 1.22114561e+04 1.22132012e+04 1.22361572e+04 1.26079863e+04 1.26719043e+04 1.24708936e+04 1.25191367e+04 1.22369531e+04 1.19786221e+04 1.26115469e+04 1.28484766e+04 1.21798857e+04 1.22645342e+04 1.29903027e+04 1.33980957e+04 1.30435156e+04 1.26922549e+04 1.27285459e+04 1.27673066e+04 1.26524189e+04 1.26437188e+04 1.27945293e+04 1.27685859e+04 1.32245020e+04 1.31699805e+04 1.28024668e+04 1.28733965e+04 1.25674229e+04 1.28671680e+04 1.36432139e+04 1.34543057e+04 1.31192334e+04 1.27661953e+04 1.26072217e+04 1.33233525e+04 1.36508574e+04 1.32808779e+04 1.28801016e+04 1.28489189e+04 1.31518555e+04 1.31595059e+04 1.36384883e+04 1.37274463e+04 1.32509746e+04 1.30595322e+04 1.30441914e+04 1.35526445e+04 1.36603750e+04 1.33714824e+04 1.32606660e+04 1.32700527e+04 1.32490195e+04 1.29183955e+04 1.32636943e+04 1.40896572e+04 1.38343252e+04 1.34435195e+04 1.31729492e+04 1.30876953e+04 1.38443105e+04 1.39371162e+04 1.35192793e+04 13199. 1.31467510e+04 1.35713125e+04 1.35948252e+04 1.35742764e+04 1.31778730e+04 1.34790762e+04 1.42586533e+04 1.38787480e+04 1.37255918e+04 1.38083848e+04 1.36622148e+04 1.34683555e+04 1.35123965e+04 1.35530547e+04 1.34464453e+04 1.35160098e+04 1.32444355e+04 1.35774385e+04 1.43894883e+04 1.37247207e+04 1.32732246e+04 1.36602783e+04 1.36210059e+04 1.39853643e+04 1.38988809e+04 1.34229248e+04 1.38582588e+04 1.39499795e+04 1.37393154e+04 1.37784004e+04 1.36980928e+04 1.35157100e+04 1.35420947e+04 1.34763643e+04 1.31088486e+04 1.36027227e+04 1.44228184e+04 1.40819023e+04 1.35694443e+04 1.31678115e+04 1.33634395e+04 1.41542949e+04 1.40390898e+04 1.37059385e+04 1.33436221e+04 1.32268770e+04 1.36724307e+04 1.36706738e+04 1.38995996e+04 1.37451240e+04 1.33527891e+04 1.34742988e+04 1.34831484e+04 1.39410996e+04 1.39789678e+04 1.35165088e+04 1.34273242e+04 1.34747266e+04 1.34618906e+04 1.30934512e+04 1.33530117e+04 1.40927354e+04 1.38899102e+04 1.34859512e+04 1.31171152e+04 1.30483740e+04 1.37804365e+04 1.38389482e+04 1.34125703e+04 1.31091865e+04 1.30342842e+04 1.34131426e+04 1.34384463e+04 1.36782568e+04 1.35828486e+04 1.32220303e+04 1.30538916e+04 1.30190293e+04 1.36150234e+04 1.36538447e+04 1.32576123e+04 1.30030635e+04 1.29586250e+04 1.34523574e+04 1.35031689e+04 1.28064277e+04 1.27547930e+04 1.35685264e+04 1.34543955e+04 1.27399150e+04 1.27308047e+04 1.33286875e+04 1.34290488e+04 1.29550566e+04 1.25827109e+04 1.26121279e+04 1.33234561e+04 1.32419971e+04 1.27861318e+04 1.29139922e+04 1.28457627e+04 1.25465791e+04 1.25143857e+04 1.28328281e+04 1.24734170e+04 1.26703926e+04 1.32090967e+04 1.28194180e+04 1.29090439e+04 1.28635488e+04 1.26254619e+04 1.26372793e+04 1.25504648e+04 1.24991426e+04 1.22594863e+04 1.20383525e+04 1.22714805e+04 1.25021260e+04 1.28400059e+04 1.24032822e+04 1.20033506e+04 1.23270557e+04 1.23083086e+04 1.26160605e+04 1.25510791e+04 1.21588408e+04 1.19484521e+04 1.18332471e+04 1.20900566e+04 1.20691465e+04 1.23414229e+04 1.22781973e+04 1.18915352e+04 1.18399062e+04 1.15127549e+04 1.17822480e+04 1.23909785e+04 1.21829229e+04 1.18256982e+04 1.15080752e+04 1.13665791e+04 1.18710547e+04 1.20159824e+04 1.16852842e+04 1.13307559e+04 1.12829482e+04 1.15436025e+04 1.14213691e+04 1.17241533e+04 1.16352881e+04 1.12790879e+04 1.12696963e+04 1.12305283e+04 1.15007568e+04 1.14305371e+04 1.08810908e+04 1.08683115e+04 1.14540059e+04 1.12160762e+04 1.05651855e+04 1.08427568e+04 1.13859727e+04 1.12575869e+04 1.09654492e+04 1.06075615e+04 1.05244043e+04 1.10613066e+04 1.10674316e+04 1.06997031e+04 1.04009004e+04 1.03070996e+04 1.05562197e+04 1.05448184e+04 1.05166924e+04 1.02438027e+04 1.04081309e+04 1.08287656e+04 1.05578008e+04 1.03828467e+04 1.02936006e+04 1.01909092e+04 1.01727803e+04 1.01799180e+04 1.01298232e+04 1.00636572e+04 9.96611523e+03 9.67819434e+03 9.76200684e+03 1.02359053e+04 9.82437500e+03 9.36335156e+03 9.61533887e+03 9.85781738e+03 1.00880186e+04 9.89062012e+03 9.58998633e+03 9.57625977e+03 9.56066797e+03 9.27594141e+03 9.18838574e+03 9.47200781e+03 9.42956250e+03 9.18112695e+03 9.07387109e+03 8.77331836e+03 9.10289941e+03 9.54957812e+03 9.23055469e+03 8.96822656e+03 8.72292383e+03 8.67976855e+03 9.07176855e+03 9.17461035e+03 8.86657324e+03 8.59024316e+03 8.48227344e+03 8.48818164e+03 8.55650781e+03 8.78051758e+03 8.64124707e+03 8.39164551e+03 8.36993750e+03 8.29989062e+03 8.37947754e+03 8.34643848e+03 8.13856250e+03 8.17869727e+03 8.16436377e+03 7.97076123e+03 7.72946484e+03 7.89530859e+03 8.21317871e+03 8.08105176e+03 7.81924414e+03 7.60522119e+03 7.58892676e+03 7.99607178e+03 7.90629785e+03 7.58382520e+03 7.42409521e+03 7.32180127e+03 7.36550098e+03 7.36027979e+03 7.36349854e+03 7.15387598e+03 7.24342432e+03 7.52985596e+03 7.19724121e+03 7.22948096e+03 7.20965527e+03 7.04603223e+03 6.98721484e+03 6.95893066e+03 6.70829199e+03 6.68373291e+03 6.86292920e+03 6.85769434e+03 6.77513867e+03 6.72344629e+03 6.43946045e+03 6.32944873e+03 6.48987500e+03 6.47312451e+03 6.61829980e+03 6.49772852e+03 6.14981055e+03 6.27785645e+03 6.32212598e+03 6.19268701e+03 6.06358838e+03 5.99139990e+03 6.02517773e+03 6.01245068e+03 5.91352002e+03 5.72473682e+03 5.79467236e+03 6.05336963e+03 5.89366406e+03 5.67245410e+03 5.49893896e+03 5.45068262e+03 5.74895947e+03 5.63378906e+03 5.49015918e+03 5.27067480e+03 5.13714160e+03 5.29214209e+03 5.36040723e+03 5.44553613e+03 5.22817529e+03 4.97125439e+03 5.01782666e+03 5.00837354e+03 5.16257959e+03 4.99383252e+03 4.81484277e+03 4.88652734e+03 4.84532178e+03 4.74212842e+03 4.60025781e+03 4.62403125e+03 4.84419238e+03 4.71232324e+03 4.52828516e+03 4.36950635e+03 4.34872852e+03 4.52939600e+03 4.49272119e+03 4.32703613e+03 4.19249951e+03 4.10433838e+03 4.17505762e+03 4.15652441e+03 4.22050537e+03 4.18070215e+03 3.97698682e+03 3.85396948e+03 3.88736523e+03 4.01453247e+03 3.89317163e+03 3.76851343e+03 3.80198340e+03 3.73815771e+03 3.60211353e+03 3.51613745e+03 3.60742432e+03 3.54722754e+03 3.44313770e+03 3.54954883e+03 3.53380347e+03 3.39943921e+03 3.34496753e+03 3.30420239e+03 3.24474023e+03 3.12226636e+03 3.07063232e+03 3.17377051e+03 3.18760913e+03 2.98797217e+03 2.87720532e+03 2.97727417e+03 3.05717529e+03 2.98474561e+03 2.84430396e+03 2.74184985e+03 2.79895215e+03 2.82467651e+03 2.73509155e+03 2.66620166e+03 2.55335474e+03 2.46595679e+03 2.55380518e+03 2.63253247e+03 2.54284424e+03 2.40151611e+03 2.33356519e+03 2.41956372e+03 2.41775903e+03 2.31205884e+03 2.21168042e+03 2.15465747e+03 2.15524658e+03 2.14374463e+03 2.18256226e+03 2.14682837e+03 2.03729285e+03 1.99779309e+03 1.97059741e+03 1.98041455e+03 1.90405322e+03 1.83867188e+03 1.89599182e+03 1.86131494e+03 1.77971570e+03 1.69745728e+03 1.69684131e+03 1.76098743e+03 1.66141064e+03 1.56828882e+03 1.59031787e+03 1.58458618e+03 1.55737585e+03 1.50943408e+03 1.51394580e+03 1.49562537e+03 1.41831909e+03 1.34510962e+03 1.32355896e+03 1.37653943e+03 1.32252332e+03 1.25636157e+03 1.25388831e+03 1.22800208e+03 1.19191980e+03 1.15951501e+03 1.15351648e+03 1.11910327e+03 1.07074902e+03 1.07322046e+03 1.04994568e+03 1.02714697e+03 1.00457727e+03 9.68399780e+02 9.37340576e+02 8.84947266e+02 8.69306580e+02 8.96940186e+02 8.83618408e+02 8.10665161e+02 7.64174561e+02 7.77844299e+02 7.83087280e+02 7.54053101e+02 7.06583862e+02 6.62848572e+02 6.73280273e+02 6.72697266e+02 6.30030762e+02 6.21912109e+02 5.98384216e+02 5.55759521e+02 5.50265991e+02 5.51573120e+02 5.28241821e+02 4.86996948e+02 4.60541016e+02 4.69432251e+02 4.63270508e+02 4.31840363e+02 4.02039978e+02 3.83173340e+02 3.88960052e+02 3.73384430e+02 3.46055939e+02 3.36079834e+02 3.21212128e+02 3.04323700e+02 2.89343353e+02 2.86122375e+02 2.67053955e+02 2.43891373e+02 2.43543335e+02 2.33131393e+02 2.18359512e+02 2.01198959e+02 1.87107666e+02 1.85468124e+02 1.70510208e+02 1.55848999e+02 1.56975067e+02 1.49699661e+02 1.35308212e+02 1.20643875e+02 1.54843231e+02 1.60121399e+02 1.13634979e+02 1.36839859e+02 1.33184235e+02 1.28118835e+02 1.07683601e+02 2.15939621e+02 3.94883209e+02 6.72635950e+06 2.56460575e+06 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. 0. -18616546. 13627983. 13085792. 2.82412415e+02 1.87740784e+02 1.08675659e+02 8.24124832e+01 8.44408112e+01 8.39789886e+01 9.08377228e+01 9.83873672e+01 1.04214134e+02 1.13494316e+02 1.24632538e+02 1.32857254e+02 1.42408997e+02 1.51295731e+02 1.59778290e+02 1.76465271e+02 1.84737595e+02 1.88909424e+02 2.04920822e+02 2.14690033e+02 2.19357117e+02 2.42070724e+02 2.67624054e+02 2.69869049e+02 2.75706970e+02 2.91023254e+02 3.07354919e+02 3.20430054e+02 3.33727234e+02 3.51974060e+02 3.67224854e+02 3.86002441e+02 4.01763397e+02 4.03996246e+02 4.24635742e+02 4.55751251e+02 4.76936584e+02 4.91991547e+02 4.90687836e+02 5.03716156e+02 5.39035767e+02 5.60134277e+02 5.72520996e+02 5.87169617e+02 6.05359009e+02 6.38148254e+02 6.67715942e+02 6.78818481e+02 6.79665955e+02 6.99698792e+02 7.55805237e+02 7.79195740e+02 7.61735352e+02 7.80213074e+02 8.25447693e+02 8.60849304e+02 8.91600403e+02 8.97664612e+02 8.94709045e+02 9.28851868e+02 9.75749634e+02 1.00502148e+03 1.01625159e+03 1.02310236e+03 1.06852356e+03 1.11470093e+03 1.12343018e+03 1.13248413e+03 1.15070190e+03 1.19305347e+03 1.24493298e+03 1.26415125e+03 1.29562927e+03 1.31396875e+03 1.30814722e+03 1.35572998e+03 1.40514722e+03 1.42552881e+03 1.45811584e+03 1.47648059e+03 1.50281958e+03 1.57274744e+03 1.59594434e+03 1.57416309e+03 1.60621997e+03 1.67334802e+03 1.71594788e+03 1.73920496e+03 1.75193835e+03 1.77771899e+03 1.82062354e+03 1.87740027e+03 1.89675574e+03 1.87884351e+03 1.94373950e+03 2.03168225e+03 2.06063867e+03 2.08701562e+03 2.06104443e+03 2.08585645e+03 2.18914795e+03 2.21172852e+03 2.20438696e+03 2.23192651e+03 2.28315381e+03 2.37645264e+03 2.39522632e+03 2.40817139e+03 2.45301318e+03 2.49080713e+03 2.54934668e+03 2.58487915e+03 2.58330347e+03 2.62088257e+03 2.67551270e+03 2.68696216e+03 2.75223291e+03 2.80509326e+03 2.82713135e+03 2.86766479e+03 2.88770898e+03 2.91756201e+03 3.00313672e+03 3.05778687e+03 3.07569385e+03 3.09307373e+03 3.10278467e+03 3.15459668e+03 3.22943335e+03 3.24866431e+03 3.26367676e+03 3.35429492e+03 3.46478955e+03 3.47565063e+03 3.44857520e+03 3.49230420e+03 3.55456934e+03 3.58624731e+03 3.59738037e+03 3.62965088e+03 3.70740820e+03 3.79435620e+03 3.87363965e+03 3.90386279e+03 3.84503833e+03 3.83403149e+03 3.97315479e+03 4.07894800e+03 4.11490039e+03 4.10744092e+03 4.07939697e+03 4.18818408e+03 4.30761230e+03 4.34140332e+03 4.27241797e+03 4.26664502e+03 4.42427002e+03 4.56838281e+03 4.54530615e+03 4.40971582e+03 4.51350488e+03 4.68866113e+03 4.73663672e+03 4.70514404e+03 4.75094678e+03 4.83967188e+03 4.87548340e+03 4.93685938e+03 4.93662500e+03 4.92466650e+03 5.05190967e+03 5.18711279e+03 5.13160645e+03 5.17653369e+03 5.25610986e+03 5.21813037e+03 5.30565771e+03 5.37324023e+03 5.46784082e+03 5.57053320e+03 5.35713721e+03 5.46372705e+03 5.77025977e+03 5.69383350e+03 5.57033984e+03 5.69335742e+03 5.87665625e+03 5.84977881e+03 5.90294580e+03 5.93626953e+03 5.91392676e+03 5.94856885e+03 6.14495361e+03 6.23109326e+03 6.10195459e+03 6.18654834e+03 6.40424561e+03 6.35953662e+03 6.35763574e+03 6.36491748e+03 6.35274561e+03 6.56502539e+03 6.57939355e+03 6.54254297e+03 6.66813184e+03 6.60342773e+03 6.73248193e+03 6.93569971e+03 6.79652979e+03 6.83433447e+03 6.92943262e+03 7.00038916e+03 7.00807178e+03 7.10485059e+03 7.16081982e+03 7.11751270e+03 7.17924023e+03 7.28123730e+03 7.35289355e+03 7.28019580e+03 7.43694531e+03 7.57225488e+03 7.51812061e+03 7.71554297e+03 7.59263037e+03 7.47400049e+03 7.69553027e+03 7.82543945e+03 7.84080420e+03 7.75654736e+03 7.68303516e+03 7.92333936e+03 8.17600830e+03 8.08675195e+03 7.96963623e+03 8.17880664e+03 8.26890625e+03 8.17928711e+03 8.14282715e+03 8.40971094e+03 8.40479883e+03 8.29112305e+03 8.59972949e+03 8.51805176e+03 8.45963867e+03 8.69740234e+03 8.56193457e+03 8.58659375e+03 8.71152734e+03 8.72391504e+03 8.74327930e+03 8.88754492e+03 9.05443457e+03 9.10598730e+03 8.90087598e+03 8.87510059e+03 9.13250879e+03 9.14293359e+03 9.23873047e+03 9.25087598e+03 9.24808203e+03 9.26584961e+03 9.37126953e+03 9.56709668e+03 9.39507812e+03 9.23036426e+03 9.53625684e+03 9.98604590e+03 9.58354980e+03 9.41437695e+03 9.64042188e+03 9.62422754e+03 9.90760938e+03 1.00114775e+04 9.80802930e+03 9.81565918e+03 9.99078906e+03 1.00622334e+04 1.01728896e+04 1.00803330e+04 1.02017490e+04 1.03637588e+04 9.98872852e+03 1.01680010e+04 1.02964492e+04 1.02205957e+04 1.05210615e+04 1.04716914e+04 1.03353857e+04 1.05497627e+04 1.04910166e+04 1.05576211e+04 1.09416367e+04 1.07927344e+04 1.06402295e+04 1.05996270e+04 1.05713066e+04 1.08688535e+04 1.10448975e+04 1.08462236e+04 1.08564570e+04 1.11308301e+04 1.11540820e+04 1.10598193e+04 1.09616455e+04 1.10269033e+04 1.11607676e+04 1.13302539e+04 1.14006963e+04 1.11273477e+04 1.11417334e+04 1.13976982e+04 1.15268545e+04 1.15065098e+04 1.14737344e+04 1.14202412e+04 1.14238789e+04 1.18849805e+04 1.19457129e+04 1.15052705e+04 1.13569756e+04 1.15666904e+04 1.17859502e+04 1.17789688e+04 1.17043760e+04 1.18417773e+04 1.19546865e+04 1.19523203e+04 1.21179092e+04 1.19675508e+04 1.18708564e+04 1.20838525e+04 1.22678906e+04 1.21684541e+04 1.18561504e+04 1.20634775e+04 1.21940488e+04 1.22046963e+04 1.23858408e+04 1.23017227e+04 1.21784883e+04 1.23259980e+04 1.26123447e+04 1.24522285e+04 1.22255547e+04 1.24263574e+04 1.25051816e+04 1.24410107e+04 1.25030068e+04 1.24511523e+04 1.24818691e+04 1.26121787e+04 1.27644561e+04 1.28795840e+04 1.26636660e+04 1.26504502e+04 1.27192002e+04 1.26700049e+04 1.27225254e+04 1.26488262e+04 1.28502227e+04 1.29551162e+04 1.27910312e+04 1.26786787e+04 1.28033379e+04 1.30692891e+04 1.31760801e+04 1.32004844e+04 1.30061543e+04 1.29581162e+04 1.29601934e+04 1.28483438e+04 1.29725068e+04 1.31630156e+04 1.31541152e+04 1.31106650e+04 1.30090723e+04 1.29695879e+04 1.32432383e+04 1.34407139e+04 1.35014062e+04 1.32850996e+04 1.29553867e+04 1.31336572e+04 1.33044580e+04 1.32125938e+04 1.33668066e+04 1.35453838e+04 1.32909951e+04 1.31607695e+04 1.31772227e+04 1.32212842e+04 1.36682139e+04 1.37482637e+04 1.34315283e+04 1.35001162e+04 1.33396846e+04 1.31159160e+04 1.35538096e+04 1.36915254e+04 1.33672861e+04 1.33835342e+04 1.33620400e+04 1.32406582e+04 1.36058877e+04 1.39634404e+04 1.36199932e+04 1.34476211e+04 1.35626484e+04 1.35433018e+04 1.36248486e+04 1.35934902e+04 1.35875469e+04 1.36044150e+04 1.35709141e+04 1.36768906e+04 1.36547422e+04 1.35200469e+04 1.37424609e+04 1.38910137e+04 1.36053428e+04 1.33922520e+04 1.34657139e+04 1.37381504e+04 1.39085000e+04 1.39595811e+04 1.35470527e+04 1.31774404e+04 1.35443418e+04 1.38606572e+04 1.40437148e+04 1.37945957e+04 1.34177832e+04 1.35873838e+04 1.37110732e+04 1.36658525e+04 1.37663926e+04 1.37225146e+04 1.35527285e+04 1.38275410e+04 1.36414453e+04 1.31841953e+04 1.36507715e+04 1.41452734e+04 1.37398428e+04 1.33824238e+04 1.34847910e+04 1.35974873e+04 1.37690840e+04 1.38232500e+04 1.36809883e+04 1.33496094e+04 1.34451035e+04 1.36797168e+04 1.35804248e+04 1.37216709e+04 1.37148057e+04 1.35560234e+04 1.34762041e+04 1.36298086e+04 1.36837803e+04 1.35460879e+04 1.36427910e+04 1.37056191e+04 1.34915449e+04 1.32471191e+04 1.32832637e+04 1.34370703e+04 1.37274961e+04 1.37025947e+04 1.32913828e+04 1.32465674e+04 1.33182227e+04 1.34434697e+04 1.36054668e+04 1.34020820e+04 1.31542344e+04 1.34619941e+04 1.34813955e+04 1.32048320e+04 1.35632666e+04 1.34993447e+04 1.31398291e+04 1.31794688e+04 1.30510527e+04 1.30313799e+04 1.34349404e+04 1.34070977e+04 1.31480820e+04 1.33188887e+04 1.31883887e+04 1.27672119e+04 1.28644111e+04 1.31432822e+04 1.31410059e+04 1.30920986e+04 1.29078154e+04 1.28956289e+04 1.30776953e+04 1.31048613e+04 1.33856426e+04 1.30955352e+04 1.25489756e+04 1.26086787e+04 1.27724092e+04 1.29508955e+04 1.30720850e+04 1.27747344e+04 1.24373643e+04 1.27170781e+04 1.28849668e+04 1.26968174e+04 1.27100645e+04 1.26612529e+04 1.24822871e+04 1.26346650e+04 1.26328203e+04 1.23237148e+04 1.26780508e+04 1.28155752e+04 1.24779141e+04 1.23639785e+04 1.20344951e+04 1.20504443e+04 1.24181113e+04 1.27662949e+04 1.25869316e+04 1.18763662e+04 1.19379756e+04 1.23165020e+04 1.21982148e+04 1.21636357e+04 1.21119678e+04 1.19489863e+04 1.20472969e+04 1.20805156e+04 1.20362529e+04 1.19885029e+04 1.19249160e+04 1.20586465e+04 1.19075879e+04 1.16795068e+04 1.16101748e+04 1.16713867e+04 1.18149375e+04 1.19950508e+04 1.17069141e+04 1.13240078e+04 1.15068447e+04 1.16336641e+04 1.18126611e+04 1.17012080e+04 1.12354121e+04 1.12917617e+04 1.13779092e+04 1.14522783e+04 1.16199922e+04 1.13600371e+04 1.11229404e+04 1.12020439e+04 1.10210508e+04 1.08788340e+04 1.12086357e+04 1.13625068e+04 1.10660693e+04 1.07976631e+04 1.07254883e+04 1.07632754e+04 1.10296348e+04 1.10443330e+04 1.09229434e+04 1.07006260e+04 1.04100107e+04 1.05270107e+04 1.05986396e+04 1.08239932e+04 1.08231768e+04 1.03642529e+04 1.02939629e+04 1.03613740e+04 1.04285820e+04 1.04174873e+04 1.04248906e+04 1.03827432e+04 1.00914453e+04 1.01119805e+04 1.01156348e+04 1.00382344e+04 1.00624912e+04 1.00951270e+04 1.00116465e+04 9.90475098e+03 9.73576270e+03 9.82273438e+03 1.00143379e+04 9.83621582e+03 9.57862012e+03 9.63776660e+03 9.55290332e+03 9.52362207e+03 9.84144141e+03 9.68729395e+03 9.29483496e+03 9.45714941e+03 9.49177344e+03 9.52121973e+03 9.49717188e+03 9.22404785e+03 9.38398340e+03 1.03687109e+04 1.23582510e+04 9.15380078e+03 1.24229531e+04 1.16048730e+04 1.59889814e+04 1.18991084e+04 1.95131035e+04 1.81418609e+05 -4.81705650e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 148295872. -4064524. 6.54952950e+06 -17205846. 1.92852891e+04 1.78573613e+04 9.25863867e+03 6.08893408e+03 6.64723291e+03 6.73177100e+03 6.50962012e+03 6.22602148e+03 6.04587402e+03 6.04311328e+03 6.14741650e+03 6.25020459e+03 6.09259912e+03 5.85687549e+03 5.79501807e+03 5.82720312e+03 5.91503418e+03 5.82159912e+03 5.52103809e+03 5.57445361e+03 5.68407422e+03 5.59389307e+03 5.43972754e+03 5.29783398e+03 5.38679492e+03 5.60138330e+03 5.53164893e+03 5.19535986e+03 4.94987891e+03 5.05545117e+03 5.24038379e+03 5.30118799e+03 5.13806836e+03 4.88426025e+03 4.89679639e+03 4.94165723e+03 5.00522656e+03 4.88858252e+03 4.58515771e+03 4.61645508e+03 4.80851660e+03 4.70058398e+03 4.53046631e+03 4.53410889e+03 4.49440479e+03 4.50027832e+03 4.49382422e+03 4.25013330e+03 4.15831836e+03 4.32339160e+03 4.38653760e+03 4.27289648e+03 4.07822754e+03 3.93907788e+03 4.11145361e+03 4.19474902e+03 4.04443726e+03 3.86020947e+03 3.70893335e+03 3.73308789e+03 3.86597998e+03 3.89494702e+03 3.77311719e+03 3.66864941e+03 3.62747021e+03 3.55224780e+03 3.53243433e+03 3.52118506e+03 3.37438623e+03 3.39348291e+03 3.47200488e+03 3.37367480e+03 3.19627026e+03 3.13224756e+03 3.24653345e+03 3.30186792e+03 3.22277124e+03 3.06522534e+03 2.95726318e+03 2.92627173e+03 2.96907324e+03 3.06139990e+03 2.97506445e+03 2.76911255e+03 2.76906006e+03 2.77687988e+03 2.76801318e+03 2.78335083e+03 2.64327710e+03 2.59109131e+03 2.62266748e+03 2.57163843e+03 2.51393286e+03 2.43563916e+03 2.42236475e+03 2.45286572e+03 2.40210840e+03 2.29070312e+03 2.24508984e+03 2.27967773e+03 2.26994312e+03 2.22927344e+03 2.16649927e+03 2.07085376e+03 2.06393726e+03 2.09384644e+03 2.06189331e+03 1.98689832e+03 1.87961609e+03 1.85890906e+03 1.91838623e+03 1.93419934e+03 1.85536194e+03 1.73867188e+03 1.72082861e+03 1.74839343e+03 1.71338586e+03 1.64061890e+03 1.59254590e+03 1.61302637e+03 1.60699072e+03 1.53944653e+03 1.48643176e+03 1.43721924e+03 1.45429688e+03 1.49030200e+03 1.41850110e+03 1.35320557e+03 1.31060840e+03 1.28483472e+03 1.28222620e+03 1.28034778e+03 1.24036340e+03 1.15954150e+03 1.13884131e+03 1.16521802e+03 1.15363696e+03 1.09616943e+03 1.04482251e+03 1.03553906e+03 1.03314441e+03 1.00723145e+03 9.67729980e+02 9.08853455e+02 8.95819397e+02 9.06657043e+02 8.86915771e+02 8.50846741e+02 8.06062378e+02 7.90965820e+02 7.84854370e+02 7.80812683e+02 7.52666992e+02 6.95691406e+02 6.82305054e+02 6.75735901e+02 6.54254517e+02 6.36615723e+02 6.08065613e+02 5.90662415e+02 5.76563721e+02 5.53458679e+02 5.30307983e+02 5.08557556e+02 5.04013763e+02 4.95141418e+02 4.71523651e+02 4.39212982e+02 4.15379852e+02 4.15988922e+02 4.13576538e+02 3.93780579e+02 3.66463470e+02 3.39829132e+02 3.22789154e+02 3.20986694e+02 3.19520569e+02 2.97788971e+02 2.70009064e+02 2.60346130e+02 2.56240967e+02 2.45157455e+02 2.32037689e+02 2.15426636e+02 2.03828445e+02 1.94156647e+02 1.81277603e+02 1.69052826e+02 1.59638062e+02 1.51582413e+02 1.42169464e+02 1.31717300e+02 1.21460526e+02 1.11966721e+02 1.05584801e+02 9.95032043e+01 9.14017334e+01 8.08920212e+01 7.24698944e+01 6.90022736e+01 6.35571747e+01 5.63583145e+01 4.95688171e+01 4.26090393e+01 3.78783379e+01 3.48108978e+01 3.09064598e+01 2.60191517e+01 2.10942764e+01 1.76202564e+01 1.51097898e+01 1.25817738e+01 9.91862965e+00 7.60006094e+00 5.79583740e+00 4.28400278e+00 3.09748936e+00 2.25283265e+00 1.76301312e+00 1.61467242e+00 1.80732656e+00 2.34784961e+00 3.18809032e+00 4.23056459e+00 5.69331121e+00 7.62825823e+00 9.81101990e+00 1.24965525e+01 1.51391878e+01 1.87092113e+01 2.23571815e+01 2.50365238e+01 2.87853737e+01 3.39450378e+01 4.02543678e+01 4.67444229e+01 5.14376755e+01 5.43666382e+01 5.84972458e+01 6.65815887e+01 7.75036926e+01 8.67036285e+01 9.22870636e+01 9.46266022e+01 1.02131454e+02 1.18571190e+02 1.27042984e+02 1.28416321e+02 1.38737274e+02 1.50816711e+02 1.60865295e+02 1.76840576e+02 1.83265015e+02 1.87972839e+02 2.04451172e+02 2.11756577e+02 2.29340500e+02 2.47942261e+02 2.46911224e+02 2.66418274e+02 2.88548706e+02 2.94717224e+02 3.08694489e+02 3.21676788e+02 3.36867340e+02 3.53742584e+02 3.67504883e+02 3.73600006e+02 3.88637878e+02 4.24608673e+02 4.52955933e+02 4.59428558e+02 4.54241241e+02 4.62715179e+02 4.88310394e+02 5.29592407e+02 5.65037598e+02 5.67919250e+02 5.61277344e+02 5.81584534e+02 6.19064270e+02 6.37563538e+02 6.47214233e+02 6.70089172e+02 6.90004517e+02 7.08506531e+02 7.62319458e+02 7.70189331e+02 7.61719360e+02 8.03298401e+02 8.08149475e+02 8.51125854e+02 8.90967896e+02 8.85672607e+02 9.45631104e+02 9.51717590e+02 9.35183105e+02 9.89724060e+02 9.94151917e+02 1.03002002e+03 1.12867798e+03 1.10193250e+03 1.06539929e+03 1.11228003e+03 1.19457275e+03 1.26690002e+03 1.26615283e+03 1.21810522e+03 1.21178369e+03 1.27533386e+03 1.36556689e+03 1.44321985e+03 1.43998975e+03 1.38416284e+03 1.40401770e+03 1.48918628e+03 1.54630493e+03 1.53516162e+03 1.55018237e+03 1.59910095e+03 1.62830786e+03 1.71493713e+03 1.74621375e+03 1.68865039e+03 1.72243835e+03 1.77761682e+03 1.81961719e+03 1.87125842e+03 1.89171216e+03 1.96877161e+03 1.97161572e+03 1.93400146e+03 2.00216138e+03 1.99654309e+03 2.08566504e+03 2.26727319e+03 2.17879419e+03 2.05980151e+03 2.16351123e+03 2.29831372e+03 2.39838257e+03 2.44604980e+03 2.35119995e+03 2.29022217e+03 2.36577075e+03 2.52726147e+03 2.66497656e+03 2.63290186e+03 2.51112842e+03 2.52811475e+03 2.66436133e+03 2.73401685e+03 2.83102466e+03 2.88068994e+03 2.75042700e+03 2.78000220e+03 2.92706445e+03 2.99349341e+03 2.98609937e+03 2.99253687e+03 3.02324634e+03 3.04286816e+03 3.22432031e+03 3.27956909e+03 3.16312524e+03 3.19713940e+03 3.26914526e+03 3.32760156e+03 3.39501245e+03 3.38993555e+03 3.52501343e+03 3.61268359e+03 3.53197827e+03 3.50065405e+03 3.46674390e+03 3.64943970e+03 3.93286182e+03 3.87254468e+03 3.69206470e+03 3.66322314e+03 3.85600244e+03 4.11558887e+03 4.02618628e+03 3.84631055e+03 3.94621899e+03 4.10248730e+03 4.28586914e+03 4.42258740e+03 4.37186377e+03 4.15377881e+03 4.13076465e+03 4.30362988e+03 4.49106885e+03 4.53632129e+03 4.52163818e+03 4.54746338e+03 4.56686670e+03 4.72048047e+03 4.71990625e+03 4.64803271e+03 4.67952051e+03 4.70982520e+03 4.94573145e+03 5.06494971e+03 4.93715137e+03 5.02721094e+03 5.10090381e+03 5.18967529e+03 5.13532275e+03 4.94518506e+03 5.21434180e+03 5.55976611e+03 5.43571387e+03 5.19914062e+03 5.29684424e+03 5.63105371e+03 5.66251367e+03 5.58533545e+03 5.64312402e+03 5.52839062e+03 5.54525488e+03 5.92377588e+03 5.97843604e+03 5.73031787e+03 5.65928223e+03 5.70483252e+03 6.02613232e+03 6.35797998e+03 6.10589111e+03 5.98602539e+03 6.21262939e+03 6.23444482e+03 6.44984521e+03 6.46374756e+03 6.13743945e+03 6.23971680e+03 6.47970557e+03 6.51926270e+03 6.59631006e+03 6.58467432e+03 6.76455127e+03 7.00718896e+03 6.38509131e+03 6.98225635e+03 6.75781104e+03 8.40241309e+03 1.01781748e+04 1.07260039e+04 1.05410684e+04 1.07586982e+04 1.15768057e+04 1.09325576e+04 1.07868740e+04 1.36017334e+04 2.43222539e+04 3.27031230e+04 4487981. -100529800. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -275219936. -7.83601950e+06 8503334. 3.24175391e+04 1.92442910e+04 1.09252090e+04 9.83320312e+03 1.14136523e+04 1.03279893e+04 9.62184082e+03 9.84233691e+03 9.92133691e+03 9.76221289e+03 9.82466797e+03 9.87846094e+03 1.00539121e+04 1.02628730e+04 9.94067871e+03 9.66016309e+03 9.93833105e+03 9.98299805e+03 9.56757715e+03 1.01970811e+04 1.04865723e+04 9.65109570e+03 1.03198232e+04 1.08803193e+04 1.04344609e+04 1.02590420e+04 1.05558555e+04 1.08186162e+04 1.06109961e+04 1.06131758e+04 1.06721006e+04 1.06576309e+04 1.05847871e+04 1.06042969e+04 1.09294043e+04 1.10284053e+04 1.08584033e+04 1.08652783e+04 1.09428340e+04 1.10044678e+04 1.09857871e+04 1.10220361e+04 1.11068418e+04 1.08477373e+04 1.08206807e+04 1.11329980e+04 1.11442471e+04 1.16336416e+04 1.16965625e+04 1.13186885e+04 1.10580547e+04 1.10434795e+04 1.18002393e+04 1.19125361e+04 1.14939961e+04 1.12904658e+04 1.13809736e+04 1.16112803e+04 1.15759990e+04 1.20005645e+04 1.20327871e+04 1.13574893e+04 1.12734717e+04 1.19195645e+04 1.24438467e+04 1.21507725e+04 1.18786973e+04 1.19952627e+04 1.19426504e+04 1.18498037e+04 1.19842617e+04 1.20385586e+04 1.19991953e+04 1.20242119e+04 1.20609600e+04 1.22119814e+04 1.22331875e+04 1.25075986e+04 1.24779883e+04 1.21559297e+04 1.23815312e+04 1.24294092e+04 1.24701309e+04 1.25656104e+04 1.24979990e+04 1.25108809e+04 1.22536094e+04 1.19945352e+04 1.26262129e+04 1.28177617e+04 1.22054111e+04 1.23092646e+04 1.30399189e+04 1.33898018e+04 1.30334619e+04 1.27413672e+04 1.26795625e+04 1.26732158e+04 1.26183125e+04 1.26104463e+04 1.28953945e+04 1.28651973e+04 1.31690781e+04 1.31514619e+04 1.27819062e+04 1.30214443e+04 1.27217822e+04 1.27481533e+04 1.34642148e+04 1.33772051e+04 1.31125361e+04 1.28231201e+04 1.26284814e+04 1.32999492e+04 1.36380059e+04 1.32632549e+04 1.28490635e+04 1.28675830e+04 1.32167607e+04 1.31781895e+04 1.36145771e+04 1.37379111e+04 1.32817715e+04 1.30347910e+04 1.30643398e+04 1.36109482e+04 1.36468076e+04 1.33388320e+04 1.32177793e+04 1.32125225e+04 1.33916738e+04 1.30813193e+04 1.31434697e+04 1.39337920e+04 1.38619043e+04 1.34684658e+04 1.31122012e+04 1.30763770e+04 1.38872070e+04 1.39386807e+04 1.35419365e+04 1.31983730e+04 1.31265479e+04 1.35670977e+04 1.35718271e+04 1.35732686e+04 1.32101055e+04 1.34951035e+04 1.42486152e+04 1.38604111e+04 1.37233164e+04 1.37867646e+04 1.36760938e+04 1.34887236e+04 1.34915830e+04 1.36650713e+04 1.36528643e+04 1.35922070e+04 1.31847666e+04 1.34282383e+04 1.42801475e+04 1.37199932e+04 1.32540869e+04 1.36435215e+04 1.36411543e+04 1.40498701e+04 1.38096963e+04 1.32752607e+04 1.39723096e+04 1.41118604e+04 1.37021279e+04 1.36072969e+04 1.35724766e+04 1.35364004e+04 1.35935830e+04 1.36076348e+04 1.32092295e+04 1.35765205e+04 1.43696045e+04 1.40663203e+04 1.36035479e+04 1.31628301e+04 1.33055703e+04 1.41901973e+04 1.40929355e+04 1.36999980e+04 1.33600635e+04 1.32474355e+04 1.36552461e+04 1.36508496e+04 1.39250684e+04 1.36362227e+04 1.32201045e+04 1.36189229e+04 1.36373965e+04 1.39010410e+04 1.38352451e+04 1.34317695e+04 1.34299580e+04 1.34522461e+04 1.36093447e+04 1.32138242e+04 1.33554697e+04 1.40958848e+04 1.38501387e+04 1.35076143e+04 1.31587158e+04 1.30562666e+04 1.37862266e+04 1.38580244e+04 1.34376377e+04 1.30764756e+04 1.30335840e+04 1.34482598e+04 1.34631055e+04 1.37202402e+04 1.35574316e+04 1.32237236e+04 1.30681182e+04 1.29882734e+04 1.36368867e+04 1.35917881e+04 1.31535605e+04 1.30433125e+04 1.30461768e+04 1.34271309e+04 1.34457588e+04 1.28833311e+04 1.27969922e+04 1.34509268e+04 1.34448779e+04 1.27899219e+04 1.27213086e+04 1.33494443e+04 1.33987793e+04 1.29746143e+04 1.26325713e+04 1.26055137e+04 1.33266611e+04 1.32130371e+04 1.27548135e+04 1.28323193e+04 1.27799775e+04 1.27543232e+04 1.27387305e+04 1.26960059e+04 1.23287500e+04 1.26287568e+04 1.33410664e+04 1.29357354e+04 1.27308770e+04 1.27558926e+04 1.26767803e+04 1.26636064e+04 1.25776816e+04 1.25059316e+04 1.22138857e+04 1.19868086e+04 1.22834463e+04 1.25570137e+04 1.29117432e+04 1.24227012e+04 1.19334365e+04 1.22705273e+04 1.23945322e+04 1.26896592e+04 1.24471523e+04 1.20870547e+04 1.19998604e+04 1.18876055e+04 1.21192139e+04 1.21058242e+04 1.23416865e+04 1.22720303e+04 1.19246494e+04 1.17198652e+04 1.13941318e+04 1.18498398e+04 1.25181309e+04 1.22223135e+04 1.18096338e+04 1.15059170e+04 1.12912119e+04 1.18124941e+04 1.21369844e+04 1.17925938e+04 1.12877793e+04 1.12391641e+04 1.15140850e+04 1.14561650e+04 1.17411074e+04 1.16517324e+04 1.12947021e+04 1.13067119e+04 1.12586367e+04 1.14705371e+04 1.13782998e+04 1.08778008e+04 1.08970342e+04 1.14580732e+04 1.12035625e+04 1.05782666e+04 1.09033457e+04 1.14782041e+04 1.12114795e+04 1.08967441e+04 1.06199170e+04 1.05609980e+04 1.11049648e+04 1.10569961e+04 1.06888867e+04 1.03710732e+04 1.03226035e+04 1.06186465e+04 1.05631855e+04 1.04543584e+04 1.02219961e+04 1.03748379e+04 1.07634795e+04 1.04269141e+04 1.04496797e+04 1.03534883e+04 1.01446836e+04 1.01840469e+04 1.01733174e+04 1.01433262e+04 9.99425391e+03 9.85718457e+03 9.62691699e+03 9.82322461e+03 1.03317559e+04 9.89562598e+03 9.42393359e+03 9.67665039e+03 9.78755469e+03 9.98228809e+03 9.84081641e+03 9.49828809e+03 9.67516309e+03 9.66110547e+03 9.21346387e+03 9.04243848e+03 9.58016504e+03 9.53287598e+03 9.24570312e+03 9.03532715e+03 8.69862402e+03 9.08123926e+03 9.57286328e+03 9.31987012e+03 8.95707129e+03 8.71346387e+03 8.58651172e+03 9.01028223e+03 9.23764551e+03 8.96092285e+03 8.50767188e+03 8.38411133e+03 8.54952637e+03 8.62768262e+03 8.81802734e+03 8.60255859e+03 8.31058691e+03 8.43656152e+03 8.35561523e+03 8.47779492e+03 8.36061035e+03 8.13230664e+03 8.18032422e+03 8.17046338e+03 8.04332861e+03 7.75474609e+03 7.81551660e+03 8.29858008e+03 8.11993359e+03 7.74149268e+03 7.53182666e+03 7.58901807e+03 7.97981299e+03 7.89751953e+03 7.60986426e+03 7.39931934e+03 7.29584961e+03 7.47590576e+03 7.40970117e+03 7.33949121e+03 7.14656543e+03 7.26645801e+03 7.53319971e+03 7.19224805e+03 7.21664941e+03 7.19401123e+03 7.04457275e+03 6.94774658e+03 6.85321631e+03 6.81146582e+03 6.76841797e+03 6.74662842e+03 6.68488721e+03 6.84105762e+03 6.78836621e+03 6.44448535e+03 6.29000342e+03 6.41672461e+03 6.52997949e+03 6.71013965e+03 6.44183350e+03 6.08490869e+03 6.34931152e+03 6.41651172e+03 6.22797559e+03 6.05259033e+03 5.94794043e+03 6.04020264e+03 6.00774023e+03 5.87614941e+03 5.66925146e+03 5.83705322e+03 6.06694824e+03 5.84097168e+03 5.72677783e+03 5.53357422e+03 5.45429150e+03 5.74289258e+03 5.68009521e+03 5.46874414e+03 5.26341650e+03 5.14210889e+03 5.23588965e+03 5.36740137e+03 5.51370654e+03 5.18904346e+03 4.93906250e+03 5.06198438e+03 5.06003125e+03 5.14473193e+03 5.03737793e+03 4.81556592e+03 4.88730420e+03 4.86137695e+03 4.69188525e+03 4.53444531e+03 4.67248926e+03 4.86693652e+03 4.67836914e+03 4.55424609e+03 4.41776904e+03 4.33123193e+03 4.53176758e+03 4.49335352e+03 4.33015674e+03 4.15888916e+03 4.09593188e+03 4.17465332e+03 4.15004590e+03 4.22051758e+03 4.16930811e+03 3.97961646e+03 3.87778027e+03 3.88969238e+03 4.01237207e+03 3.87453662e+03 3.75257642e+03 3.76930664e+03 3.71222681e+03 3.61998877e+03 3.53217896e+03 3.62534985e+03 3.59305908e+03 3.44810596e+03 3.53953857e+03 3.52829272e+03 3.39165039e+03 3.34183960e+03 3.32207129e+03 3.25459155e+03 3.13647534e+03 3.06893530e+03 3.17588062e+03 3.18696167e+03 2.98395337e+03 2.85292554e+03 2.96008643e+03 3.08899805e+03 2.99602759e+03 2.81073633e+03 2.71900952e+03 2.82662134e+03 2.83048389e+03 2.70385840e+03 2.68626953e+03 2.58091943e+03 2.46550757e+03 2.53722021e+03 2.61332788e+03 2.56591553e+03 2.41395068e+03 2.30838843e+03 2.39748120e+03 2.44539331e+03 2.34012451e+03 2.19834155e+03 2.13563062e+03 2.17272998e+03 2.16018896e+03 2.18114282e+03 2.13870947e+03 2.02792798e+03 2.01143750e+03 1.99114368e+03 1.98908569e+03 1.90730908e+03 1.83442883e+03 1.87909363e+03 1.84393237e+03 1.79806384e+03 1.71393823e+03 1.69744458e+03 1.76362646e+03 1.66344153e+03 1.56998816e+03 1.58062842e+03 1.58388293e+03 1.56146008e+03 1.51140662e+03 1.51322620e+03 1.49587561e+03 1.42424048e+03 1.35003015e+03 1.32427576e+03 1.36839038e+03 1.31296289e+03 1.24545605e+03 1.26637476e+03 1.24414978e+03 1.18664551e+03 1.14825500e+03 1.16441150e+03 1.12969482e+03 1.06852185e+03 1.07304480e+03 1.04928076e+03 1.02845801e+03 1.00468140e+03 9.68654236e+02 9.36908875e+02 8.85810669e+02 8.58292603e+02 8.81911560e+02 8.90240234e+02 8.21110657e+02 7.58482300e+02 7.69364197e+02 7.93069397e+02 7.65619751e+02 7.05743408e+02 6.60701050e+02 6.73869629e+02 6.73688049e+02 6.31062256e+02 6.20561035e+02 6.00114868e+02 5.59552063e+02 5.46438232e+02 5.48680237e+02 5.31705017e+02 4.92294128e+02 4.60699371e+02 4.65022003e+02 4.66929932e+02 4.36997345e+02 4.04271606e+02 3.82310822e+02 3.85156708e+02 3.79792023e+02 3.52423462e+02 3.30093567e+02 3.16443237e+02 3.07232788e+02 2.92506836e+02 2.87327728e+02 2.67892395e+02 2.45044037e+02 2.41803360e+02 2.31236008e+02 2.20202255e+02 2.02685226e+02 1.88007782e+02 1.85494156e+02 1.70436905e+02 1.56896317e+02 1.51703583e+02 1.43172470e+02 1.35151291e+02 1.25394226e+02 1.17986214e+02 1.09568253e+02 1.01034294e+02 9.08079300e+01 7.67647552e+01 8.03284225e+01 6.10457535e+01 1.13360168e+02 2.43566757e+02 6.72635950e+06 2.56460575e+06 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. 55036552. 12985292. 3.13667450e+02 1.84834442e+02 9.69159851e+01 8.72068176e+01 8.70638580e+01 7.26325073e+01 7.51535263e+01 7.77072449e+01 8.29205322e+01 9.12018280e+01 1.01465164e+02 1.09887260e+02 1.15181458e+02 1.22404594e+02 1.33901703e+02 1.43705078e+02 1.52214493e+02 1.62756363e+02 1.74860001e+02 1.82715607e+02 1.93491608e+02 2.08738373e+02 2.12527008e+02 2.17255463e+02 2.40231110e+02 2.66192596e+02 2.76677704e+02 2.78913849e+02 2.85196564e+02 3.07533508e+02 3.25778778e+02 3.36866364e+02 3.48717377e+02 3.63460266e+02 3.86916687e+02 4.05003143e+02 4.16738831e+02 4.28859528e+02 4.44861847e+02 4.76380371e+02 4.95856964e+02 4.89473999e+02 5.06629517e+02 5.36962646e+02 5.56801086e+02 5.85726746e+02 5.99828491e+02 6.04244812e+02 6.33162354e+02 6.59984009e+02 6.77262390e+02 7.00401794e+02 7.12644531e+02 7.36954163e+02 7.67670776e+02 7.78769226e+02 7.96144165e+02 8.16691467e+02 8.45552979e+02 8.82395996e+02 9.11165405e+02 9.29419373e+02 9.35444702e+02 9.52286194e+02 1.00303778e+03 1.02658301e+03 1.02657190e+03 1.06426697e+03 1.09424426e+03 1.12288013e+03 1.16880005e+03 1.18855627e+03 1.18591272e+03 1.21163269e+03 1.27065820e+03 1.30776941e+03 1.30498877e+03 1.31011340e+03 1.35030835e+03 1.39624121e+03 1.46160950e+03 1.48258948e+03 1.46029724e+03 1.49185022e+03 1.56805957e+03 1.59965479e+03 1.61932129e+03 1.60859998e+03 1.62994922e+03 1.71571570e+03 1.75475269e+03 1.74854736e+03 1.78289893e+03 1.82413196e+03 1.85954126e+03 1.89551685e+03 1.91676733e+03 1.96767371e+03 2.00066699e+03 2.06326489e+03 2.10081128e+03 2.04784912e+03 2.09219702e+03 2.17795947e+03 2.20044385e+03 2.22995361e+03 2.25244360e+03 2.29693384e+03 2.38519824e+03 2.38878784e+03 2.38985669e+03 2.47786963e+03 2.51922876e+03 2.51252173e+03 2.53850732e+03 2.60235156e+03 2.64703076e+03 2.67708032e+03 2.67928687e+03 2.72835205e+03 2.78756323e+03 2.88870850e+03 2.90002002e+03 2.84275830e+03 2.90710620e+03 3.01856152e+03 3.05697461e+03 3.06879053e+03 3.06938306e+03 3.07970142e+03 3.19241699e+03 3.29768237e+03 3.28169189e+03 3.24467334e+03 3.30929810e+03 3.43095679e+03 3.49119897e+03 3.54859106e+03 3.49967798e+03 3.44773438e+03 3.56233057e+03 3.61474829e+03 3.65656860e+03 3.72672168e+03 3.73000977e+03 3.82166577e+03 3.94539111e+03 3.92871509e+03 3.81367383e+03 3.90205347e+03 4.03528687e+03 4.11442920e+03 4.18340186e+03 4.14277393e+03 4.12737988e+03 4.21339404e+03 4.38190430e+03 4.35044971e+03 4.24260352e+03 4.36011963e+03 4.53082324e+03 4.54243506e+03 4.55201416e+03 4.51065967e+03 4.56365967e+03 4.68454492e+03 4.72854443e+03 4.76408740e+03 4.85606348e+03 4.83025586e+03 4.87822656e+03 5.04771289e+03 5.02674805e+03 4.96321436e+03 5.05348975e+03 5.19404004e+03 5.21384717e+03 5.28598486e+03 5.22429736e+03 5.19787061e+03 5.36612109e+03 5.62151172e+03 5.68837451e+03 5.36021875e+03 5.42934082e+03 5.77060156e+03 5.72620605e+03 5.64384766e+03 5.67897559e+03 5.69287207e+03 5.86705029e+03 5.99182520e+03 5.96607715e+03 5.89859766e+03 5.91739209e+03 6.06779980e+03 6.25866650e+03 6.29670459e+03 6.23140674e+03 6.21537988e+03 6.31498438e+03 6.39539844e+03 6.35112061e+03 6.37660938e+03 6.51554199e+03 6.51764453e+03 6.71085400e+03 6.81594043e+03 6.52116504e+03 6.61867627e+03 6.87111621e+03 6.93409863e+03 6.94545410e+03 6.82339893e+03 6.90690430e+03 7.13205615e+03 7.20064209e+03 7.16507812e+03 7.01435693e+03 7.02122803e+03 7.28120020e+03 7.48234082e+03 7.38694775e+03 7.37348682e+03 7.53066309e+03 7.50274316e+03 7.67856055e+03 7.70579883e+03 7.53827002e+03 7.55839355e+03 7.68785498e+03 7.93647119e+03 7.84229834e+03 7.79919775e+03 7.87411670e+03 8.05979102e+03 8.12372656e+03 8.07093359e+03 8.08149463e+03 8.13325195e+03 8.30335352e+03 8.23987988e+03 8.46063770e+03 8.36795703e+03 8.29656348e+03 8.54568066e+03 8.36539648e+03 8.46297559e+03 8.74515625e+03 8.60453223e+03 8.60675977e+03 8.71904980e+03 8.81032031e+03 8.80784668e+03 8.71356250e+03 9.01851172e+03 9.33975391e+03 8.90230273e+03 8.85477441e+03 9.03645020e+03 9.10357520e+03 9.35839160e+03 9.30629199e+03 9.13400488e+03 9.21359277e+03 9.48917285e+03 9.56155371e+03 9.47457227e+03 9.46216309e+03 9.51172559e+03 9.65300879e+03 9.53024219e+03 9.60538379e+03 9.58350000e+03 9.65725098e+03 9.83009375e+03 1.00300879e+04 9.95827051e+03 9.83873730e+03 9.81556934e+03 1.01131836e+04 1.03591318e+04 1.00394268e+04 1.01824023e+04 1.02579629e+04 9.96739258e+03 1.02851553e+04 1.03367158e+04 1.01621855e+04 1.04714902e+04 1.04882305e+04 1.04171562e+04 1.07297090e+04 1.06214775e+04 1.04709717e+04 1.06003281e+04 1.07512393e+04 1.08551504e+04 1.06288721e+04 1.06265479e+04 1.08601572e+04 1.10032197e+04 1.09922373e+04 1.09228564e+04 1.08336172e+04 1.11168330e+04 1.14163379e+04 1.11169941e+04 1.09733984e+04 1.09880176e+04 1.13756680e+04 1.15583936e+04 1.12157334e+04 1.11774639e+04 1.13323486e+04 1.14190186e+04 1.14118037e+04 1.15538770e+04 1.15208818e+04 1.13532402e+04 1.16153057e+04 1.19362061e+04 1.16476465e+04 1.12856406e+04 1.15111035e+04 1.18494912e+04 1.18570322e+04 1.18720791e+04 1.18501875e+04 1.16866230e+04 1.20715176e+04 1.23304697e+04 1.19704980e+04 1.18536123e+04 1.19578350e+04 1.23645615e+04 1.22992490e+04 1.18112891e+04 1.18992832e+04 1.21429287e+04 1.22455527e+04 1.23458125e+04 1.24142090e+04 1.22771230e+04 1.23460869e+04 1.23556543e+04 1.21651592e+04 1.22399834e+04 1.22855342e+04 1.24992256e+04 1.26762256e+04 1.24869092e+04 1.23079609e+04 1.24539678e+04 1.27201445e+04 1.31042285e+04 1.30066777e+04 1.24686816e+04 1.24821123e+04 1.27917324e+04 1.27767422e+04 1.26566475e+04 1.27455850e+04 1.28211113e+04 1.29061279e+04 1.28169111e+04 1.25729922e+04 1.28448916e+04 1.31828896e+04 1.32263818e+04 1.30114355e+04 1.27575879e+04 1.29481328e+04 1.28975928e+04 1.28293994e+04 1.32844824e+04 1.32971260e+04 1.28696514e+04 1.29202500e+04 1.31775947e+04 1.34182021e+04 1.34487393e+04 1.31693066e+04 1.31872568e+04 1.32535576e+04 1.31038740e+04 1.30601494e+04 1.32987041e+04 1.33622207e+04 1.35099951e+04 1.35141494e+04 1.29851064e+04 1.31705713e+04 1.33544434e+04 1.33662041e+04 1.37086533e+04 13358. 1.31698740e+04 1.36417080e+04 1.37296846e+04 1.34694561e+04 1.34274668e+04 1.32986768e+04 1.32388066e+04 1.33928037e+04 1.35093232e+04 1.34652627e+04 1.37124492e+04 1.38648760e+04 1.36409258e+04 1.34657178e+04 1.33106602e+04 1.35895674e+04 1.38622207e+04 1.37049434e+04 1.33748662e+04 1.33443242e+04 1.35771182e+04 1.37955928e+04 1.40355889e+04 1.37023486e+04 1.34222920e+04 1.36158906e+04 1.36176035e+04 1.34983818e+04 1.38483320e+04 1.37949453e+04 1.34381924e+04 1.37574111e+04 1.37276152e+04 1.36462764e+04 1.37936436e+04 1.37247080e+04 1.36651104e+04 1.36165977e+04 1.35940225e+04 1.34658193e+04 1.36919756e+04 1.37976895e+04 1.37677812e+04 1.37687646e+04 1.34249326e+04 1.35815215e+04 1.36692344e+04 1.35476328e+04 1.37859297e+04 1.37530762e+04 1.35415391e+04 1.35369512e+04 1.36250762e+04 1.39195420e+04 1.39785557e+04 1.36516172e+04 1.34822402e+04 1.33952764e+04 1.34853857e+04 1.35998340e+04 1.36707178e+04 1.37032559e+04 1.36223857e+04 1.35184736e+04 1.33971260e+04 1.34936807e+04 1.38983145e+04 1.38602031e+04 1.33988779e+04 1.33813027e+04 1.33999463e+04 1.33589512e+04 1.36070898e+04 1.37020518e+04 1.34879482e+04 1.34006826e+04 1.33266445e+04 1.33563428e+04 1.35917988e+04 1.34980771e+04 1.34538223e+04 1.34324219e+04 1.32864014e+04 1.34397891e+04 1.32305469e+04 1.32262773e+04 1.35748848e+04 1.33168037e+04 1.31141074e+04 1.32164189e+04 1.31854658e+04 1.31301602e+04 1.35620361e+04 1.35656191e+04 1.29111455e+04 1.29853438e+04 1.31411895e+04 1.29870811e+04 1.32890635e+04 1.32068076e+04 1.28129434e+04 1.29284502e+04 1.29479629e+04 1.32251602e+04 1.33405059e+04 1.30107803e+04 1.30378359e+04 1.28734219e+04 1.25584854e+04 1.26882822e+04 1.30261855e+04 1.29439170e+04 1.29586387e+04 1.28877803e+04 1.23364395e+04 1.25778447e+04 1.30867803e+04 1.30200830e+04 1.26678408e+04 1.22883145e+04 1.24344912e+04 1.28399102e+04 1.27217266e+04 1.25185547e+04 1.26428438e+04 1.24567080e+04 1.24793887e+04 1.25183965e+04 1.21054932e+04 1.21738750e+04 1.25054658e+04 1.25820361e+04 1.23594375e+04 1.19384023e+04 1.19929814e+04 1.23004639e+04 1.23622998e+04 1.23242471e+04 1.19537295e+04 1.17580801e+04 1.19652432e+04 1.21966211e+04 1.23522520e+04 1.20792559e+04 1.17840967e+04 1.18627881e+04 1.18011025e+04 1.17466387e+04 1.18516748e+04 1.17417871e+04 1.17731602e+04 1.19204893e+04 1.16795967e+04 1.15283613e+04 1.16587568e+04 1.16642871e+04 1.16350391e+04 1.14546553e+04 1.12599111e+04 1.12894004e+04 1.14853223e+04 1.15731357e+04 1.15980518e+04 1.12646426e+04 1.09990205e+04 1.11799609e+04 1.10884668e+04 1.11275703e+04 1.12744678e+04 1.10391309e+04 1.08905635e+04 1.07829707e+04 1.08545869e+04 1.10620967e+04 1.11655430e+04 1.09215898e+04 1.07938545e+04 1.06411982e+04 1.03920811e+04 1.05156973e+04 1.07232422e+04 1.08100254e+04 1.07394873e+04 1.03722051e+04 1.02314688e+04 1.04203848e+04 1.04853516e+04 1.04173955e+04 1.03672402e+04 1.02267559e+04 1.00219141e+04 1.01952666e+04 1.03925195e+04 1.01706836e+04 9.89298340e+03 9.94951660e+03 9.98106152e+03 9.98759180e+03 9.98414355e+03 9.90016602e+03 9.89273340e+03 9.73464160e+03 9.57860840e+03 9.83804492e+03 9.72369531e+03 9.53117676e+03 9.76719922e+03 9.46820312e+03 9.28004395e+03 9.63408301e+03 9.63926367e+03 9.11683203e+03 9.72620703e+03 9.59538965e+03 8.50189941e+03 8.32965820e+03 1.49906465e+04 1.40928623e+04 2.46043809e+04 2.81470801e+04 44367552. -2.02906388e+06 -50382604. 43009116. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -21149680. -21854842. 2.96802441e+04 1.52566797e+04 9.07873340e+03 1.07431504e+04 8.33940625e+03 9.00145508e+03 7.13847656e+03 6.15920703e+03 6.31903516e+03 6.54847852e+03 6.42284814e+03 6.24945264e+03 6.11662305e+03 6.00346875e+03 6.19548340e+03 6.33203418e+03 6.04096143e+03 5.72949561e+03 5.75911572e+03 5.81748291e+03 5.88485400e+03 5.92950098e+03 5.67343848e+03 5.52501025e+03 5.57914941e+03 5.50447949e+03 5.53747363e+03 5.40882324e+03 5.31106689e+03 5.42509912e+03 5.54108691e+03 5.37101465e+03 5.04510693e+03 5.03548486e+03 5.19269629e+03 5.19180273e+03 5.03522803e+03 4.86579688e+03 4.88329736e+03 5.00603223e+03 5.07491650e+03 4.86181592e+03 4.60027881e+03 4.62451611e+03 4.80163672e+03 4.71545312e+03 4.65830225e+03 4.53315576e+03 4.34854053e+03 4.42162354e+03 4.53189502e+03 4.36365137e+03 4.25065332e+03 4.35268262e+03 4.32795654e+03 4.22688184e+03 4.11122266e+03 3.98746289e+03 4.02887891e+03 4.16548486e+03 4.04763306e+03 3.87941528e+03 3.79072778e+03 3.74726343e+03 3.86279736e+03 3.92246265e+03 3.75870142e+03 3.61714087e+03 3.56526489e+03 3.50330396e+03 3.57197070e+03 3.62823071e+03 3.45205444e+03 3.35669336e+03 3.40257007e+03 3.33652197e+03 3.24527393e+03 3.22550488e+03 3.22640649e+03 3.23517480e+03 3.18602051e+03 3.13303467e+03 2.98506519e+03 2.90447974e+03 3.02093579e+03 3.05658887e+03 2.86753589e+03 2.75253833e+03 2.77988232e+03 2.80091113e+03 2.80427710e+03 2.80414233e+03 2.65514087e+03 2.57184741e+03 2.59577197e+03 2.56061475e+03 2.55398364e+03 2.47945532e+03 2.38754150e+03 2.38192554e+03 2.39250879e+03 2.36216187e+03 2.31095288e+03 2.28031787e+03 2.23545874e+03 2.20070068e+03 2.18187012e+03 2.08143213e+03 2.03339001e+03 2.11494165e+03 2.08561768e+03 1.95279126e+03 1.88594800e+03 1.88630469e+03 1.92989160e+03 1.95404675e+03 1.85214771e+03 1.73961194e+03 1.70766821e+03 1.70675220e+03 1.70365698e+03 1.68385205e+03 1.63412476e+03 1.60169800e+03 1.56669690e+03 1.53712512e+03 1.51217847e+03 1.45345203e+03 1.44608789e+03 1.46613232e+03 1.41207153e+03 1.36338977e+03 1.32076489e+03 1.27055493e+03 1.29429541e+03 1.30060132e+03 1.21451514e+03 1.15880505e+03 1.15550537e+03 1.17199158e+03 1.16445374e+03 1.10120752e+03 1.04412354e+03 1.02135486e+03 1.00887134e+03 1.00662653e+03 9.93234497e+02 9.29433716e+02 8.85588074e+02 8.90656189e+02 8.94261292e+02 8.64069824e+02 8.22332336e+02 8.00255310e+02 7.74715149e+02 7.64188416e+02 7.48938232e+02 7.03721436e+02 6.79810120e+02 6.76702576e+02 6.60940369e+02 6.36546509e+02 6.04416565e+02 5.86530518e+02 5.77134705e+02 5.59542236e+02 5.42531494e+02 5.11821289e+02 4.96236816e+02 4.89258789e+02 4.68255493e+02 4.47141876e+02 4.23572296e+02 4.08292175e+02 4.02502472e+02 3.96910248e+02 3.75232330e+02 3.42391113e+02 3.25326691e+02 3.25673676e+02 3.19447205e+02 2.99831512e+02 2.74888489e+02 2.58381744e+02 2.53211304e+02 2.45035797e+02 2.33521561e+02 2.16818253e+02 2.01944916e+02 1.93650620e+02 1.85828949e+02 1.76104279e+02 1.62808670e+02 1.50445419e+02 1.42104355e+02 1.33170593e+02 1.23930267e+02 1.14875191e+02 1.05631386e+02 9.78971100e+01 9.02571259e+01 8.19020462e+01 7.44642029e+01 6.99264832e+01 6.55225601e+01 5.84646759e+01 5.06060600e+01 4.37054939e+01 3.90519600e+01 3.62373047e+01 3.22530098e+01 2.72203083e+01 2.25790424e+01 1.87952900e+01 1.61044369e+01 1.37779589e+01 1.11777935e+01 8.84571457e+00 6.95767403e+00 5.45392799e+00 4.25559044e+00 3.38412976e+00 2.90879059e+00 2.77624178e+00 2.96851158e+00 3.49613285e+00 4.29450274e+00 5.29992533e+00 6.86288595e+00 8.98941040e+00 1.12398758e+01 1.37023230e+01 1.62978725e+01 1.98921127e+01 2.36516476e+01 2.63273640e+01 2.96496506e+01 3.46801987e+01 4.13072395e+01 4.78811760e+01 5.27312660e+01 5.57641716e+01 6.00119553e+01 6.78673706e+01 7.82300415e+01 8.75805588e+01 9.36783066e+01 9.64497604e+01 1.03905396e+02 1.19132935e+02 1.27655975e+02 1.30218491e+02 1.40261200e+02 1.51477875e+02 1.61237137e+02 1.78407059e+02 1.85229675e+02 1.88682739e+02 2.05518906e+02 2.13540451e+02 2.30823517e+02 2.49167786e+02 2.49006805e+02 2.67420746e+02 2.88472015e+02 2.95445679e+02 3.11155945e+02 3.23093842e+02 3.37688629e+02 3.57054596e+02 3.68504883e+02 3.72906830e+02 3.90281189e+02 4.27731628e+02 4.54745789e+02 4.59891388e+02 4.56043854e+02 4.63386871e+02 4.89133667e+02 5.30561157e+02 5.66731323e+02 5.68301941e+02 5.60163452e+02 5.83194580e+02 6.19892151e+02 6.35481384e+02 6.48878906e+02 6.71629333e+02 6.92713989e+02 7.14841919e+02 7.63937073e+02 7.67210022e+02 7.62315369e+02 8.05554016e+02 8.02955566e+02 8.51635986e+02 8.94555664e+02 8.88035767e+02 9.49087891e+02 9.54523132e+02 9.31222168e+02 9.85018677e+02 9.96934937e+02 1.03716943e+03 1.12941174e+03 1.10173889e+03 1.06592188e+03 1.11320142e+03 1.19570190e+03 1.27186853e+03 1.26817639e+03 1.23061450e+03 1.23020691e+03 1.26559216e+03 1.35199902e+03 1.43445203e+03 1.44332764e+03 1.39930225e+03 1.41120325e+03 1.48921582e+03 1.53427209e+03 1.53487292e+03 1.55785291e+03 1.59549194e+03 1.62583923e+03 1.71528760e+03 1.74700195e+03 1.68831677e+03 1.71752820e+03 1.77906348e+03 1.81693970e+03 1.86688489e+03 1.89350012e+03 1.98417773e+03 1.96106677e+03 1.92328577e+03 2.02740881e+03 1.99853369e+03 2.07579004e+03 2.27528955e+03 2.17608716e+03 2.06083911e+03 2.17735352e+03 2.31231934e+03 2.40480225e+03 2.43590039e+03 2.33707373e+03 2.28242578e+03 2.36889233e+03 2.54407349e+03 2.67289111e+03 2.62914722e+03 2.51128394e+03 2.53818799e+03 2.65830103e+03 2.73420312e+03 2.85005713e+03 2.88783057e+03 2.75875537e+03 2.77331738e+03 2.91747656e+03 3.00761914e+03 2.97144238e+03 2.97945703e+03 3.04212573e+03 3.06209033e+03 3.21090381e+03 3.26683423e+03 3.17648706e+03 3.21170850e+03 3.27353345e+03 3.30936157e+03 3.39375488e+03 3.41400146e+03 3.51002417e+03 3.62314771e+03 3.55095728e+03 3.50850342e+03 3.47835840e+03 3.66453906e+03 3.92172998e+03 3.89289941e+03 3.71630420e+03 3.66214575e+03 3.83975317e+03 4.10562598e+03 4.01584668e+03 3.84804150e+03 3.97854272e+03 4.11688379e+03 4.25851904e+03 4.42327100e+03 4.38514209e+03 4.16715625e+03 4.13227930e+03 4.32791113e+03 4.48711133e+03 4.54160059e+03 4.49706738e+03 4.56293018e+03 4.57173486e+03 4.70836865e+03 4.67877051e+03 4.62507373e+03 4.71841162e+03 4.71988818e+03 4.91528320e+03 5.08925293e+03 4.95822070e+03 5.04753223e+03 5.10914502e+03 5.10851855e+03 5.03340186e+03 4.98582520e+03 5.27578076e+03 5.55821289e+03 5.42823096e+03 5.21788477e+03 5.25387695e+03 5.59358545e+03 5.73459131e+03 5.65782715e+03 5.64577539e+03 5.47499170e+03 5.51993848e+03 5.84364307e+03 5.89678369e+03 5.83682764e+03 5.73267529e+03 5.68500977e+03 6.03272119e+03 6.36884180e+03 6.08324756e+03 5.98554688e+03 6.17073535e+03 6.22693555e+03 6.45520850e+03 6.54060596e+03 6.17103613e+03 6.19311182e+03 6.42465039e+03 6.47719922e+03 6.57521240e+03 6.62581494e+03 7.03463281e+03 7.13961475e+03 6.47063818e+03 6.80168115e+03 6.44205811e+03 7.80708350e+03 9.48884668e+03 1.09970605e+04 1.00249131e+04 1.18922158e+04 1.99891621e+04 2.27134668e+04 -5227272. -1.85258175e+06 -2749438. 44000568. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -40309564. 4.78427150e+06 3.90826133e+04 2.46700625e+04 1.57193730e+04 1.51785977e+04 1.28865713e+04 1.18748867e+04 9.49227930e+03 1.03357676e+04 9.94794141e+03 9.61342480e+03 9.82486230e+03 9.85739941e+03 9.72894727e+03 9.81947656e+03 9.91632520e+03 1.00531182e+04 1.02520107e+04 1.00161572e+04 9.68728027e+03 9.93000781e+03 9.95609961e+03 9.59387012e+03 1.02203867e+04 1.04584668e+04 9.66820020e+03 1.03326416e+04 1.09108330e+04 1.04394756e+04 1.02946514e+04 1.05094893e+04 1.07748105e+04 1.06284492e+04 1.06357393e+04 1.06597363e+04 1.06834121e+04 1.04633359e+04 1.04803916e+04 1.10751289e+04 1.11019463e+04 1.08219355e+04 1.08382178e+04 1.09402021e+04 1.10289248e+04 1.09736484e+04 1.10061211e+04 1.11118701e+04 1.09714004e+04 1.09240410e+04 1.10994629e+04 1.11276729e+04 1.15792754e+04 1.16936523e+04 1.13558213e+04 1.11132070e+04 1.10372520e+04 1.17477422e+04 1.18727266e+04 1.14896133e+04 1.13244932e+04 1.14283096e+04 1.16509961e+04 1.15549902e+04 1.19487578e+04 1.20350596e+04 1.13985801e+04 1.13007129e+04 1.18923701e+04 1.24169277e+04 1.21471631e+04 1.18633281e+04 1.19271953e+04 1.19325312e+04 1.19584082e+04 1.20292158e+04 1.21552773e+04 1.21402314e+04 1.19829834e+04 1.20342607e+04 1.21310137e+04 1.21227305e+04 1.25466904e+04 1.25258369e+04 1.21812168e+04 1.23009473e+04 1.23021836e+04 1.26377988e+04 1.27260264e+04 1.24345195e+04 1.24580381e+04 1.22696250e+04 1.21245059e+04 1.27135781e+04 1.27387871e+04 1.20775811e+04 1.22772354e+04 1.30174033e+04 1.34472549e+04 1.30761289e+04 1.27246523e+04 1.26474043e+04 1.26381533e+04 1.27310254e+04 1.27522119e+04 1.27993438e+04 1.27746650e+04 1.31557842e+04 1.31493770e+04 1.28017031e+04 1.29157246e+04 1.25742744e+04 1.28497666e+04 1.36388271e+04 1.34215791e+04 1.31325898e+04 1.27756455e+04 1.26889521e+04 1.34415254e+04 1.35629502e+04 1.31697725e+04 1.28724375e+04 1.28165801e+04 1.31634043e+04 1.31858496e+04 1.36177979e+04 1.37176758e+04 1.32574590e+04 1.31948975e+04 1.32280684e+04 1.34682832e+04 1.35244766e+04 1.33665234e+04 1.32287021e+04 1.32649082e+04 1.33035127e+04 1.29211992e+04 1.32433174e+04 1.40849834e+04 1.38799785e+04 1.34765195e+04 1.31242354e+04 1.30990645e+04 1.39033350e+04 1.39206514e+04 1.35343691e+04 1.32046719e+04 1.31376660e+04 1.36227705e+04 1.35727373e+04 1.35342510e+04 1.32447119e+04 1.35258857e+04 1.42220479e+04 1.38428262e+04 1.37156904e+04 1.38072803e+04 1.36972393e+04 1.34661582e+04 1.34657432e+04 1.35694805e+04 1.35258467e+04 1.36894053e+04 1.33112100e+04 1.34375400e+04 1.43585439e+04 1.37792744e+04 1.32132852e+04 1.36065117e+04 1.36661113e+04 1.40282900e+04 1.38910645e+04 1.34063662e+04 1.38527441e+04 1.39895439e+04 1.37158281e+04 1.36105928e+04 1.36061875e+04 1.35567773e+04 1.35441338e+04 1.35923193e+04 1.32567529e+04 1.36085186e+04 1.43550811e+04 1.40721455e+04 1.35951221e+04 1.31473379e+04 1.33479932e+04 1.42209512e+04 1.40784355e+04 1.36418564e+04 1.33697520e+04 1.32794678e+04 1.36203906e+04 1.36615098e+04 1.39297520e+04 1.37705977e+04 1.33873379e+04 1.34815498e+04 1.34883857e+04 1.39164824e+04 1.38338662e+04 1.34082607e+04 1.34564697e+04 1.35018633e+04 1.34652549e+04 1.30713691e+04 1.34522168e+04 1.42725234e+04 1.39053828e+04 1.34880293e+04 1.31445381e+04 1.30061582e+04 1.37699863e+04 1.39096211e+04 13468. 1.30795156e+04 1.30231230e+04 1.34380723e+04 1.34090527e+04 1.36987930e+04 1.37069951e+04 1.33309990e+04 1.29464219e+04 1.28918672e+04 1.36426514e+04 1.35823008e+04 1.31726279e+04 1.29602969e+04 1.28875430e+04 1.35891416e+04 1.36275674e+04 1.28232852e+04 1.27498613e+04 1.34799531e+04 1.34508018e+04 1.27520693e+04 1.27336436e+04 1.33519941e+04 1.34373262e+04 1.29814736e+04 1.26462930e+04 1.26325244e+04 1.33070527e+04 1.31467646e+04 1.26621572e+04 1.28968477e+04 1.28535068e+04 1.27701504e+04 1.27578047e+04 1.27107383e+04 1.23947979e+04 1.26636094e+04 1.31911221e+04 1.28556553e+04 1.28568604e+04 1.28941748e+04 1.26430840e+04 1.26449219e+04 1.25746797e+04 1.24953037e+04 1.22378447e+04 1.21662617e+04 1.24084365e+04 1.24421445e+04 1.27957158e+04 1.23743242e+04 1.19226670e+04 1.22926602e+04 1.23503076e+04 1.27003506e+04 1.25137959e+04 1.20957256e+04 1.20018643e+04 1.19060215e+04 1.21003447e+04 1.20768994e+04 1.23167422e+04 1.22605186e+04 1.19261699e+04 1.18334697e+04 1.14874912e+04 1.17591455e+04 1.24428682e+04 1.22070801e+04 1.18026914e+04 1.14986055e+04 1.12944590e+04 1.17889248e+04 1.21520049e+04 1.18179033e+04 1.12983965e+04 1.12804238e+04 1.15053291e+04 1.14715059e+04 1.17330947e+04 1.16029814e+04 1.12906211e+04 1.12218477e+04 1.11868252e+04 1.15585947e+04 1.15215186e+04 1.09000430e+04 1.08458252e+04 1.14179111e+04 1.12689062e+04 1.06628408e+04 1.08338525e+04 1.13633867e+04 1.12370488e+04 1.09162285e+04 1.06212969e+04 1.05167666e+04 1.10321211e+04 1.10519131e+04 1.07294326e+04 1.04273125e+04 1.02750146e+04 1.05716758e+04 1.06039043e+04 1.05184072e+04 1.01872256e+04 1.03924238e+04 1.07518750e+04 1.04524922e+04 1.04921064e+04 1.03801670e+04 1.01019902e+04 1.01914824e+04 1.01880469e+04 1.01474248e+04 1.00135869e+04 9.82513672e+03 9.63339062e+03 9.83491016e+03 1.03561055e+04 9.78696777e+03 9.38743457e+03 9.59051855e+03 9.90270410e+03 1.00921914e+04 9.81699414e+03 9.47498340e+03 9.69873242e+03 9.61800684e+03 9.30453125e+03 9.16016309e+03 9.42982520e+03 9.43454980e+03 9.18632422e+03 9.04174902e+03 8.75045215e+03 9.08285059e+03 9.58452441e+03 9.30527246e+03 8.98804297e+03 8.71233594e+03 8.53818164e+03 8.96191992e+03 9.25690625e+03 8.95342285e+03 8.56238672e+03 8.50645117e+03 8.55816309e+03 8.50208398e+03 8.75290430e+03 8.54546680e+03 8.27921582e+03 8.37829199e+03 8.31116016e+03 8.50024902e+03 8.45072754e+03 8.12994971e+03 8.14121240e+03 8.08937354e+03 8.10654297e+03 7.90652881e+03 7.81161719e+03 8.17189844e+03 8.04999170e+03 7.85357373e+03 7.56371143e+03 7.58490039e+03 8.02869580e+03 7.90166895e+03 7.60254590e+03 7.43329492e+03 7.34597363e+03 7.39901953e+03 7.36425537e+03 7.33582031e+03 7.12684082e+03 7.23430615e+03 7.45660254e+03 7.15358447e+03 7.22455176e+03 7.28036035e+03 7.04976318e+03 6.97452441e+03 6.88239697e+03 6.87722705e+03 6.83443848e+03 6.71325293e+03 6.67682031e+03 6.81164014e+03 6.79071973e+03 6.42919922e+03 6.33228271e+03 6.43648682e+03 6.52195703e+03 6.72563184e+03 6.47943408e+03 6.12963867e+03 6.29910303e+03 6.33099854e+03 6.18053516e+03 6.09763232e+03 6.04507129e+03 5.93533643e+03 5.87999023e+03 5.97125342e+03 5.80865186e+03 5.79109473e+03 5.98141211e+03 5.83223145e+03 5.68833691e+03 5.52749756e+03 5.50181592e+03 5.71094629e+03 5.61382812e+03 5.47044873e+03 5.30613770e+03 5.13353418e+03 5.20684424e+03 5.38864551e+03 5.48644141e+03 5.22070264e+03 5.01629883e+03 5.01768457e+03 5.00881201e+03 5.17288330e+03 5.07206689e+03 4.87375928e+03 4.79293604e+03 4.74234326e+03 4.74696729e+03 4.63481592e+03 4.63815381e+03 4.80746826e+03 4.65830273e+03 4.58143652e+03 4.43000586e+03 4.34751953e+03 4.54498340e+03 4.52133887e+03 4.32566553e+03 4.19200537e+03 4.10233936e+03 4.15656396e+03 4.14428174e+03 4.21241895e+03 4.16690283e+03 3.99015137e+03 3.86583423e+03 3.87784717e+03 4.00871533e+03 3.92359888e+03 3.81193799e+03 3.73625684e+03 3.66640088e+03 3.63131299e+03 3.55990088e+03 3.60780835e+03 3.55834766e+03 3.44388281e+03 3.53751172e+03 3.52902881e+03 3.40239990e+03 3.34465771e+03 3.29688159e+03 3.26019312e+03 3.12488062e+03 3.05803882e+03 3.19210352e+03 3.18855054e+03 2.97679883e+03 2.87941479e+03 2.98548486e+03 3.06586987e+03 2.98182275e+03 2.82590112e+03 2.73657690e+03 2.79939722e+03 2.81144092e+03 2.70715015e+03 2.68897583e+03 2.57944141e+03 2.44706299e+03 2.51505884e+03 2.63041455e+03 2.59536572e+03 2.41441089e+03 2.30079346e+03 2.40361890e+03 2.44405298e+03 2.33074316e+03 2.21643286e+03 2.15547974e+03 2.15128760e+03 2.14427441e+03 2.18821436e+03 2.15372388e+03 2.04774939e+03 1.98654028e+03 1.94989368e+03 2.00014734e+03 1.92597925e+03 1.84071460e+03 1.89102869e+03 1.85448853e+03 1.79933704e+03 1.72891394e+03 1.68254089e+03 1.74844409e+03 1.66976440e+03 1.57210107e+03 1.58853528e+03 1.58607520e+03 1.56075952e+03 1.50866431e+03 1.51757617e+03 1.49637012e+03 1.42426257e+03 1.35385852e+03 1.32036292e+03 1.37187500e+03 1.32388733e+03 1.25898682e+03 1.24507617e+03 1.21297229e+03 1.20385645e+03 1.17393750e+03 1.15719666e+03 1.12182227e+03 1.06791028e+03 1.08307922e+03 1.06405396e+03 1.02115149e+03 9.97475586e+02 9.71987976e+02 9.35576111e+02 8.85284912e+02 8.57442566e+02 8.81493103e+02 8.93676086e+02 8.22700806e+02 7.64770203e+02 7.74280212e+02 7.86871094e+02 7.57485779e+02 7.05310059e+02 6.67649292e+02 6.82204041e+02 6.65863220e+02 6.21539917e+02 6.27152222e+02 6.02942505e+02 5.52468628e+02 5.41655273e+02 5.51947632e+02 5.36840698e+02 4.92548065e+02 4.60341949e+02 4.66255615e+02 4.67545898e+02 4.38398285e+02 4.05142639e+02 3.82257660e+02 3.85521423e+02 3.75489441e+02 3.49683533e+02 3.37387756e+02 3.24314697e+02 3.06033478e+02 2.90048553e+02 2.87290009e+02 2.69680176e+02 2.47645416e+02 2.43049057e+02 2.32076157e+02 2.21429642e+02 2.04203186e+02 1.88611435e+02 1.86338226e+02 1.71463760e+02 1.56613373e+02 1.52216431e+02 1.45906540e+02 1.40026031e+02 1.27727997e+02 1.23286697e+02 1.06320435e+02 1.21398560e+02 9.30063324e+01 1.04381805e+02 9.28829498e+01 6.05128822e+01 1.38649246e+02 2.78063904e+02 6.72635950e+06 2.56460575e+06 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. 55036552. 12985292. 3.13667450e+02 1.84834442e+02 9.69159851e+01 6.09285545e+01 6.74176636e+01 6.31653366e+01 7.31705017e+01 7.51337967e+01 8.27201385e+01 9.92634735e+01 8.77761307e+01 1.34325119e+02 1.82731155e+02 1.92322754e+02 1.61612961e+02 1.78717896e+02 1.50890457e+02 1.66171814e+02 1.81992828e+02 1.82353027e+02 1.97149841e+02 2.09128723e+02 2.13534943e+02 2.26638412e+02 2.45726303e+02 2.59893799e+02 2.72653992e+02 2.79781677e+02 2.88146790e+02 3.08780792e+02 3.27748352e+02 3.39003204e+02 3.47623535e+02 3.61134827e+02 3.87250488e+02 4.05056671e+02 4.13827667e+02 4.26654816e+02 4.44332336e+02 4.76919708e+02 4.98209686e+02 4.91671936e+02 5.06087189e+02 5.36667725e+02 5.56309631e+02 5.84911133e+02 6.00797485e+02 6.05244568e+02 6.34882690e+02 6.60214050e+02 6.75519287e+02 6.97815308e+02 7.11384949e+02 7.36823303e+02 7.67017151e+02 7.80200806e+02 7.98131165e+02 8.17806458e+02 8.45452576e+02 8.85515198e+02 9.10432678e+02 9.27216675e+02 9.33649658e+02 9.50192505e+02 1.00435718e+03 1.02937024e+03 1.02577844e+03 1.06281372e+03 1.09420691e+03 1.12095886e+03 1.17090930e+03 1.18868457e+03 1.18659070e+03 1.21103125e+03 1.26992993e+03 1.30684827e+03 1.30226550e+03 1.30655164e+03 1.34485754e+03 1.39718335e+03 1.46384314e+03 1.48680017e+03 1.45995630e+03 1.49425122e+03 1.56830237e+03 1.59599231e+03 1.61498376e+03 1.60417957e+03 1.62885632e+03 1.72089893e+03 1.76131152e+03 1.75087109e+03 1.78067639e+03 1.82317249e+03 1.85471741e+03 1.88907837e+03 1.91789441e+03 1.96546558e+03 2.00246863e+03 2.06281177e+03 2.09145923e+03 2.05146826e+03 2.09797900e+03 2.18199414e+03 2.19895435e+03 2.22138086e+03 2.25491943e+03 2.30058105e+03 2.38110669e+03 2.39270337e+03 2.39345801e+03 2.47295874e+03 2.52084326e+03 2.50149780e+03 2.53908789e+03 2.59750757e+03 2.64981665e+03 2.67247266e+03 2.68179028e+03 2.72630225e+03 2.78537793e+03 2.88350513e+03 2.91159448e+03 2.84484058e+03 2.91061011e+03 3.02074072e+03 3.05368701e+03 3.06985620e+03 3.06169409e+03 3.06749487e+03 3.18471191e+03 3.30531494e+03 3.28399536e+03 3.23912158e+03 3.30139404e+03 3.42370850e+03 3.48741260e+03 3.54296045e+03 3.49720874e+03 3.44658862e+03 3.56410767e+03 3.62880933e+03 3.66428564e+03 3.74430054e+03 3.74794312e+03 3.81465381e+03 3.94961499e+03 3.91918359e+03 3.82255957e+03 3.92726196e+03 4.06421802e+03 4.10946826e+03 4.17328760e+03 4.15235010e+03 4.13992188e+03 4.20858643e+03 4.38485156e+03 4.34917578e+03 4.23128711e+03 4.37524414e+03 4.54483301e+03 4.54009131e+03 4.53732715e+03 4.52878174e+03 4.56904883e+03 4.69822803e+03 4.71877979e+03 4.76837012e+03 4.87679492e+03 4.83345752e+03 4.89789209e+03 5.06158984e+03 5.03589453e+03 4.94936523e+03 5.02475391e+03 5.16272705e+03 5.25937402e+03 5.27067627e+03 5.23131885e+03 5.19842529e+03 5.32236133e+03 5.63141309e+03 5.69795557e+03 5.37782910e+03 5.48082471e+03 5.71679541e+03 5.72213086e+03 5.69198193e+03 5.65165186e+03 5.71245996e+03 5.88339258e+03 5.97707812e+03 5.94678369e+03 5.91987158e+03 5.92041113e+03 6.06686768e+03 6.23110791e+03 6.27188135e+03 6.21012695e+03 6.22219922e+03 6.33605273e+03 6.38304980e+03 6.33997461e+03 6.40659326e+03 6.49413379e+03 6.54602441e+03 6.69970654e+03 6.85120264e+03 6.57322412e+03 6.64489746e+03 6.84336621e+03 6.93595654e+03 6.99103076e+03 6.83887598e+03 6.91159473e+03 7.16901318e+03 7.20979346e+03 7.18810059e+03 7.03993604e+03 7.04921533e+03 7.32061133e+03 7.50289209e+03 7.41660547e+03 7.41581299e+03 7.53831641e+03 7.52128369e+03 7.69520508e+03 7.70905957e+03 7.55124414e+03 7.57249951e+03 7.68259277e+03 7.94896631e+03 7.87302539e+03 7.78772607e+03 7.90864551e+03 8.08779639e+03 8.13700586e+03 8.08522461e+03 8.06724512e+03 8.12251025e+03 8.30648340e+03 8.24362207e+03 8.44625586e+03 8.37962305e+03 8.27438379e+03 8.58519531e+03 8.36444824e+03 8.50096582e+03 8.75088770e+03 8.60982910e+03 8.56746191e+03 8.75673242e+03 8.78627441e+03 8.78610547e+03 8.67324316e+03 9.03089453e+03 9.33030566e+03 8.90798535e+03 8.83419141e+03 9.07552832e+03 9.12070508e+03 9.38701660e+03 9.32907910e+03 9.10339648e+03 9.24229492e+03 9.47928906e+03 9.51462109e+03 9.46526367e+03 9.45446191e+03 9.53011523e+03 9.66966113e+03 9.51026562e+03 9.62305371e+03 9.63904590e+03 9.63850488e+03 9.80030859e+03 9.95820312e+03 1.00129746e+04 9.87641504e+03 9.81156934e+03 1.01279404e+04 1.03806152e+04 1.00412422e+04 1.01643281e+04 1.02439600e+04 9.99427832e+03 1.02709111e+04 1.03755322e+04 1.01888799e+04 1.04610439e+04 1.05126621e+04 1.04383711e+04 1.07475078e+04 1.05919424e+04 1.04626641e+04 1.05798057e+04 1.07513057e+04 1.08818174e+04 1.06388584e+04 1.06166045e+04 1.08781523e+04 1.10018369e+04 1.09888086e+04 1.09388447e+04 1.08650479e+04 1.10883867e+04 1.14293379e+04 1.11053535e+04 1.09424180e+04 1.09722090e+04 1.13903086e+04 1.15463223e+04 1.11794951e+04 1.11716641e+04 1.13213926e+04 1.14336123e+04 1.14092568e+04 1.15568271e+04 1.15419404e+04 1.13672314e+04 1.16238379e+04 1.19339561e+04 1.16595635e+04 1.12548301e+04 1.15080547e+04 1.18412109e+04 1.18342227e+04 1.19016641e+04 1.18302900e+04 1.16978535e+04 1.20764043e+04 1.23304229e+04 1.19549375e+04 1.18492510e+04 1.19627490e+04 1.23592568e+04 1.23211660e+04 1.18214043e+04 1.18928262e+04 1.21654453e+04 1.22902617e+04 1.23078203e+04 1.24122363e+04 1.22786973e+04 1.23395811e+04 1.23675000e+04 1.21772803e+04 1.22487588e+04 1.22937617e+04 1.24823857e+04 1.26868652e+04 1.24990039e+04 1.22818916e+04 1.24525820e+04 1.27198994e+04 1.31000732e+04 1.30145488e+04 1.24522490e+04 1.24775674e+04 1.27920508e+04 1.28008008e+04 1.26907295e+04 1.27283496e+04 1.28225156e+04 1.29533955e+04 1.28185781e+04 1.25673623e+04 1.28525303e+04 1.31569541e+04 1.32277559e+04 1.30351758e+04 1.27757588e+04 1.29474082e+04 1.28881738e+04 1.28544053e+04 1.32934619e+04 1.32824873e+04 1.28703203e+04 1.29415225e+04 1.31719688e+04 1.34352969e+04 1.34440381e+04 1.31824219e+04 1.31539023e+04 1.32172197e+04 1.31496074e+04 1.30834707e+04 1.33138662e+04 1.33565781e+04 1.34896387e+04 1.35171768e+04 1.30042871e+04 1.31958027e+04 1.33705410e+04 1.33659004e+04 1.37164219e+04 1.33662021e+04 13171. 1.36508809e+04 1.37266289e+04 1.34699453e+04 1.34234463e+04 1.33013633e+04 1.32625088e+04 1.33960957e+04 1.35143770e+04 1.34621426e+04 1.37389199e+04 1.38810615e+04 1.36262090e+04 1.34634512e+04 1.33148643e+04 1.36021074e+04 1.38631631e+04 1.37081260e+04 1.33694883e+04 1.33416221e+04 1.35871924e+04 1.38210332e+04 1.40763379e+04 1.37231729e+04 1.34143271e+04 1.35994053e+04 1.36078887e+04 1.35157861e+04 1.38749971e+04 1.38027080e+04 1.34393447e+04 1.37549658e+04 1.37264863e+04 1.36703506e+04 1.37733438e+04 1.37122764e+04 1.37112461e+04 1.36156963e+04 1.36032715e+04 1.34828418e+04 1.36907441e+04 1.38070215e+04 1.37684932e+04 1.37508184e+04 1.34115693e+04 1.35822471e+04 1.37024189e+04 1.36016074e+04 1.37801514e+04 1.37219648e+04 1.35410674e+04 1.35472900e+04 1.36289482e+04 1.39429863e+04 1.39687432e+04 1.36055029e+04 1.35066934e+04 1.34471465e+04 1.34668838e+04 1.35816934e+04 1.37078994e+04 1.37580898e+04 1.36020918e+04 1.34896025e+04 1.34431230e+04 1.34882637e+04 1.38841641e+04 1.38664365e+04 1.34013447e+04 1.33780596e+04 1.34040557e+04 1.33678320e+04 1.36459287e+04 1.37217168e+04 1.34646348e+04 1.33847275e+04 1.33398320e+04 1.33763984e+04 1.35978418e+04 1.35008223e+04 1.34584131e+04 1.34480586e+04 1.32944971e+04 1.34445430e+04 1.32283887e+04 1.32358135e+04 1.36094570e+04 1.33089570e+04 1.31233711e+04 1.32386680e+04 1.31429863e+04 1.31252129e+04 1.35985586e+04 1.35771387e+04 1.28970049e+04 1.29863936e+04 1.31533682e+04 1.29886260e+04 1.32959102e+04 1.32257891e+04 1.28130078e+04 1.29525371e+04 1.29688828e+04 1.31558770e+04 1.33154258e+04 1.30475000e+04 1.30494844e+04 1.28601035e+04 1.25596201e+04 1.27336191e+04 1.30355830e+04 1.29290332e+04 1.29536689e+04 1.28906289e+04 1.23783730e+04 1.25892988e+04 1.31217422e+04 1.30292637e+04 1.26663223e+04 1.22946621e+04 1.24084404e+04 1.28397188e+04 1.27098809e+04 1.25286230e+04 1.27117598e+04 1.24605303e+04 1.24662275e+04 1.25555312e+04 1.20905518e+04 1.21918916e+04 1.25444121e+04 1.25786289e+04 1.23419678e+04 1.19232490e+04 1.19963906e+04 1.22832686e+04 1.24221045e+04 1.23009658e+04 1.19538477e+04 1.18021338e+04 1.19545674e+04 1.22049697e+04 1.23609248e+04 1.21048057e+04 1.17989492e+04 1.18578711e+04 1.18135635e+04 1.17760566e+04 1.18704570e+04 1.17744600e+04 1.17531318e+04 1.19188584e+04 1.16594248e+04 1.15380244e+04 1.16586787e+04 1.16660283e+04 1.16359258e+04 1.14518770e+04 1.12584072e+04 1.13029785e+04 1.14970742e+04 1.15981318e+04 1.16480166e+04 1.13059541e+04 1.09576152e+04 1.11481611e+04 1.10998682e+04 1.11518857e+04 1.12818535e+04 1.10079395e+04 1.08609932e+04 1.08205420e+04 1.08526396e+04 1.10629375e+04 1.11868301e+04 1.09476230e+04 1.07862383e+04 1.06499043e+04 1.04070811e+04 1.05225547e+04 1.07544092e+04 1.08192754e+04 1.07294014e+04 1.03745859e+04 1.02408467e+04 1.04144463e+04 1.05006201e+04 1.04607061e+04 1.03483223e+04 1.01899170e+04 1.00263164e+04 1.02039961e+04 1.04024199e+04 1.02010361e+04 9.87964844e+03 9.94147656e+03 9.98152246e+03 9.96916309e+03 9.98610254e+03 9.89429590e+03 9.93334570e+03 9.72077246e+03 9.56818262e+03 9.86549512e+03 9.74044434e+03 9.55530957e+03 9.77651172e+03 9.43268555e+03 9.28203516e+03 9.66382910e+03 9.61288672e+03 9.13898633e+03 9.74649023e+03 9.59504395e+03 8.51976953e+03 8.39371289e+03 1.75354141e+04 1.36653320e+04 2.74136484e+04 2.65736855e+04 2222158. -3.27102975e+06 2.60875275e+06 141720576. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -21149680. -21854842. 2.96802441e+04 1.52566797e+04 9.07873340e+03 1.07431504e+04 9.62670117e+03 9.78697949e+03 9.22167773e+03 5.14262305e+03 5.76520898e+03 7.51497168e+03 6.27094043e+03 5.79529150e+03 5.35611279e+03 5.83926074e+03 6.32336670e+03 6.20045410e+03 5.93009717e+03 5.84829932e+03 5.97742969e+03 5.89816943e+03 5.94978857e+03 5.94978369e+03 5.69712988e+03 5.56798047e+03 5.58287207e+03 5.52899170e+03 5.54944092e+03 5.40958643e+03 5.29415869e+03 5.42143555e+03 5.55422168e+03 5.37652832e+03 5.05172070e+03 5.03193994e+03 5.20041553e+03 5.21277441e+03 5.02492285e+03 4.85580469e+03 4.87809326e+03 5.00687354e+03 5.07204297e+03 4.87372754e+03 4.59807275e+03 4.61413867e+03 4.81278320e+03 4.69937646e+03 4.66875830e+03 4.54993555e+03 4.34387109e+03 4.39842627e+03 4.50478369e+03 4.36479932e+03 4.24113623e+03 4.35199707e+03 4.32721826e+03 4.22605713e+03 4.10736816e+03 3.98650244e+03 4.02780469e+03 4.16531787e+03 4.03829224e+03 3.87674854e+03 3.78591675e+03 3.73939038e+03 3.89081177e+03 3.91369727e+03 3.74451538e+03 3.61801758e+03 3.56020264e+03 3.49916943e+03 3.55396509e+03 3.61637646e+03 3.46021265e+03 3.35071973e+03 3.40051880e+03 3.33592529e+03 3.24363647e+03 3.21987378e+03 3.23286719e+03 3.23737964e+03 3.18490674e+03 3.11934351e+03 2.99334229e+03 2.90848120e+03 3.02334790e+03 3.05426123e+03 2.86658594e+03 2.73784204e+03 2.77249756e+03 2.79774829e+03 2.81066577e+03 2.80607056e+03 2.64745679e+03 2.57320435e+03 2.59976758e+03 2.55996899e+03 2.54843726e+03 2.47654712e+03 2.38319141e+03 2.37941113e+03 2.39635303e+03 2.36154907e+03 2.31016577e+03 2.28167676e+03 2.23440161e+03 2.20444678e+03 2.17748584e+03 2.07745288e+03 2.03805627e+03 2.11322632e+03 2.08648901e+03 1.95076965e+03 1.88192847e+03 1.88253259e+03 1.93369470e+03 1.94926160e+03 1.85077966e+03 1.74234326e+03 1.71058032e+03 1.70737598e+03 1.70318909e+03 1.68176111e+03 1.64150452e+03 1.60236194e+03 1.56812817e+03 1.53811194e+03 1.51308862e+03 1.45621948e+03 1.45069910e+03 1.46542456e+03 1.40732678e+03 1.36070801e+03 1.32426440e+03 1.27311926e+03 1.29536377e+03 1.30191174e+03 1.21279980e+03 1.16084875e+03 1.15656018e+03 1.17174158e+03 1.16475146e+03 1.10266821e+03 1.04499634e+03 1.01898187e+03 1.00744373e+03 1.00446613e+03 9.91013550e+02 9.27764099e+02 8.85375305e+02 8.91094910e+02 8.92015503e+02 8.62615967e+02 8.22215942e+02 8.02512085e+02 7.77930237e+02 7.64401611e+02 7.47830688e+02 7.01605103e+02 6.79607910e+02 6.78839844e+02 6.61220520e+02 6.32201355e+02 6.00850098e+02 5.85801941e+02 5.76907288e+02 5.58882507e+02 5.42240479e+02 5.15007812e+02 4.97497375e+02 4.88214874e+02 4.67648987e+02 4.46198242e+02 4.24996307e+02 4.09868774e+02 4.02318268e+02 3.94868317e+02 3.73836884e+02 3.42140076e+02 3.25257935e+02 3.25596252e+02 3.19346558e+02 2.99072327e+02 2.74596344e+02 2.58194000e+02 2.51984955e+02 2.44523376e+02 2.32441925e+02 2.14338699e+02 1.99271957e+02 1.90822845e+02 1.84233795e+02 1.75007782e+02 1.62359268e+02 1.50072723e+02 1.40919250e+02 1.32336105e+02 1.23324860e+02 1.14928322e+02 1.06391106e+02 9.75885315e+01 8.88738785e+01 8.03267288e+01 7.30877914e+01 6.88274307e+01 6.45298843e+01 5.75254974e+01 4.95962296e+01 4.25783424e+01 3.80420837e+01 3.53580894e+01 3.17301922e+01 2.65863762e+01 2.19035912e+01 1.80769138e+01 1.52917271e+01 1.28550720e+01 1.03587379e+01 8.14955139e+00 6.27215052e+00 4.77590084e+00 3.63427448e+00 2.78944492e+00 2.30811667e+00 2.14243937e+00 2.31493282e+00 2.85217261e+00 3.73650169e+00 4.77041674e+00 6.26914263e+00 8.27972794e+00 1.04934349e+01 1.30252132e+01 1.57407455e+01 1.93237972e+01 2.29949398e+01 2.57475090e+01 2.90073986e+01 3.40829659e+01 4.07521553e+01 4.73219795e+01 5.21761589e+01 5.51170197e+01 5.93552399e+01 6.71012802e+01 7.73363800e+01 8.68197479e+01 9.32003326e+01 9.57017975e+01 1.03277954e+02 1.18497368e+02 1.26766708e+02 1.30238983e+02 1.40060944e+02 1.51301788e+02 1.61246033e+02 1.77954315e+02 1.84647232e+02 1.88321533e+02 2.05094299e+02 2.12901291e+02 2.30341827e+02 2.49103546e+02 2.48917511e+02 2.66217957e+02 2.87585144e+02 2.94969543e+02 3.09447144e+02 3.22652283e+02 3.37917053e+02 3.55192169e+02 3.67327606e+02 3.73536377e+02 3.88343811e+02 4.25703278e+02 4.54484711e+02 4.58878998e+02 4.55367615e+02 4.62541046e+02 4.88626709e+02 5.30160645e+02 5.65697144e+02 5.67542419e+02 5.58480103e+02 5.83332275e+02 6.20401794e+02 6.32914185e+02 6.48478577e+02 6.71195190e+02 6.91509033e+02 7.16515869e+02 7.63156006e+02 7.65219238e+02 7.61696411e+02 8.03368774e+02 8.01603516e+02 8.52657349e+02 8.95994141e+02 8.89232544e+02 9.48348816e+02 9.52886841e+02 9.30195068e+02 9.83400452e+02 9.99299500e+02 1.03819165e+03 1.13236646e+03 1.10143335e+03 1.06647083e+03 1.11488611e+03 1.19220618e+03 1.26895496e+03 1.26888684e+03 1.23096619e+03 1.22668958e+03 1.26733032e+03 1.35147729e+03 1.43603259e+03 1.44268127e+03 1.40075818e+03 1.41321399e+03 1.48772913e+03 1.53506775e+03 1.53398853e+03 1.55603284e+03 1.59484460e+03 1.62321606e+03 1.71888806e+03 1.75437146e+03 1.68782910e+03 1.71436304e+03 1.77886853e+03 1.81427380e+03 1.86559424e+03 1.89552295e+03 1.98203198e+03 1.96424585e+03 1.92359338e+03 2.02455725e+03 1.99972375e+03 2.08071021e+03 2.27238794e+03 2.17182202e+03 2.06479419e+03 2.16985474e+03 2.31100732e+03 2.40628320e+03 2.44210376e+03 2.33916846e+03 2.28019287e+03 2.37435645e+03 2.54161499e+03 2.67774854e+03 2.63631787e+03 2.51152905e+03 2.53247852e+03 2.66366992e+03 2.72915503e+03 2.84599634e+03 2.88171045e+03 2.75949536e+03 2.78429199e+03 2.92620972e+03 3.00879761e+03 2.96159766e+03 2.97134961e+03 3.04589673e+03 3.05718896e+03 3.21339893e+03 3.27092480e+03 3.18699243e+03 3.21893726e+03 3.26402319e+03 3.30323584e+03 3.38907007e+03 3.40991089e+03 3.52745312e+03 3.60087476e+03 3.54487524e+03 3.51360181e+03 3.47410522e+03 3.66745850e+03 3.90941943e+03 3.88221436e+03 3.73919092e+03 3.66187012e+03 3.84069849e+03 4.10214160e+03 4.00954175e+03 3.84251953e+03 3.98244165e+03 4.13344678e+03 4.26127002e+03 4.41079248e+03 4.38575781e+03 4.16831641e+03 4.12864404e+03 4.29816211e+03 4.48219238e+03 4.53166748e+03 4.50439941e+03 4.54630762e+03 4.58404883e+03 4.72757129e+03 4.70402002e+03 4.60885156e+03 4.72376953e+03 4.72435254e+03 4.94684375e+03 5.09309961e+03 4.96100879e+03 5.05056396e+03 5.11522266e+03 5.14445654e+03 5.05714746e+03 4.99693311e+03 5.27646680e+03 5.55325391e+03 5.45253662e+03 5.19814551e+03 5.29904785e+03 5.60969922e+03 5.74679395e+03 5.67674951e+03 5.64836475e+03 5.48488867e+03 5.54532910e+03 5.87586084e+03 5.89570850e+03 5.84350781e+03 5.73641064e+03 5704. 6.03648584e+03 6.34065381e+03 6.10264600e+03 5.98862158e+03 6.18521729e+03 6.21045801e+03 6.41822021e+03 6.53883154e+03 6.19374072e+03 6.20555566e+03 6.44137646e+03 6.53839502e+03 6.62743311e+03 6.65210400e+03 7.04458105e+03 7.18286426e+03 6.45151123e+03 6.78853711e+03 6.41581104e+03 8.15503955e+03 1.00802041e+04 1.09568193e+04 9.96304688e+03 1.14256201e+04 1.82571152e+04 2.14013320e+04 4.65648650e+06 1.23328338e+06 2220527. -49502404. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -40309564. 4.78427150e+06 3.90826133e+04 2.46700625e+04 1.57193730e+04 1.51785977e+04 1.43306006e+04 1.40407656e+04 1.38116211e+04 1.45674209e+04 1.47285850e+04 1.43870254e+04 1.47129551e+04 1.48112627e+04 1.46063037e+04 1.47854004e+04 1.48621533e+04 1.48851777e+04 1.36242930e+04 1.36363477e+04 1.09007734e+04 1.00334902e+04 9.99771289e+03 1.02965996e+04 1.04090488e+04 9.97429980e+03 1.00323096e+04 1.06228574e+04 1.06169980e+04 1.04343486e+04 1.04760938e+04 1.04808984e+04 1.05014766e+04 1.05491592e+04 1.05631416e+04 1.06499775e+04 1.06515146e+04 1.04261523e+04 1.04582871e+04 1.10545771e+04 1.11264824e+04 1.08059863e+04 1.08676035e+04 1.09414863e+04 1.10330146e+04 1.10182646e+04 1.10350361e+04 1.10997969e+04 1.09764775e+04 1.09354121e+04 1.10933545e+04 1.11048105e+04 1.15940439e+04 1.16947490e+04 1.13395146e+04 1.11123389e+04 1.10318535e+04 1.17463076e+04 1.18679004e+04 1.15120146e+04 1.13388408e+04 1.14603906e+04 1.16597646e+04 1.15655205e+04 1.19225869e+04 1.19976299e+04 1.14055156e+04 1.12917773e+04 1.19065605e+04 1.24475586e+04 1.21500176e+04 1.18927705e+04 1.19546572e+04 1.19330039e+04 1.19544229e+04 1.20210752e+04 1.21714023e+04 1.21894170e+04 1.20069287e+04 1.20371865e+04 1.21146934e+04 1.21290527e+04 1.25798799e+04 1.25242832e+04 1.21677930e+04 1.22648613e+04 1.22881240e+04 1.26575732e+04 1.27495166e+04 1.24542490e+04 1.24542402e+04 1.22649033e+04 1.21417305e+04 1.27183447e+04 1.27330176e+04 1.20654521e+04 1.22874795e+04 1.30393418e+04 1.34472549e+04 1.30874238e+04 1.27434375e+04 1.26203066e+04 1.26332900e+04 1.27762402e+04 1.27711973e+04 1.27996172e+04 1.27741494e+04 1.31693301e+04 1.31880303e+04 1.28215283e+04 1.29005156e+04 1.25490342e+04 1.28787480e+04 1.36710020e+04 1.34043486e+04 1.31277178e+04 1.27917324e+04 1.27052422e+04 1.34561299e+04 1.35507529e+04 1.31713047e+04 1.28440029e+04 1.28396221e+04 1.31775107e+04 1.31667803e+04 1.36291689e+04 1.37433877e+04 1.32911934e+04 1.31826406e+04 1.32196865e+04 1.34799648e+04 1.35354512e+04 1.33795264e+04 1.32195908e+04 1.32717295e+04 1.33289434e+04 1.29064375e+04 1.32307236e+04 1.41103877e+04 1.38856445e+04 1.34670068e+04 1.31403457e+04 1.31143340e+04 1.39144873e+04 1.39470723e+04 1.35340547e+04 1.31879385e+04 1.31281377e+04 1.36306074e+04 1.35899531e+04 1.35184854e+04 1.32576934e+04 1.35692871e+04 1.42225400e+04 1.38294971e+04 1.37230049e+04 1.38163789e+04 1.37024229e+04 1.34721816e+04 1.34771641e+04 1.35490928e+04 1.35176270e+04 1.37216738e+04 1.33199893e+04 1.34573730e+04 1.43717402e+04 1.37667949e+04 1.32334902e+04 1.36175850e+04 1.36585664e+04 1.40555312e+04 1.39102881e+04 1.33926338e+04 1.38630352e+04 1.40051064e+04 1.37230605e+04 1.36143613e+04 1.36090215e+04 1.35731426e+04 1.35436797e+04 1.35856846e+04 1.32661113e+04 1.36048994e+04 1.43564141e+04 1.40875557e+04 1.36030322e+04 1.31616025e+04 1.33518574e+04 1.42204209e+04 1.40893027e+04 1.36447520e+04 1.33695537e+04 1.32793623e+04 1.36417793e+04 1.36827842e+04 1.39242539e+04 1.37596738e+04 1.33972637e+04 1.35048887e+04 1.34930967e+04 1.39145195e+04 1.38284307e+04 1.34251377e+04 1.34777549e+04 1.34949287e+04 1.34699297e+04 1.30821895e+04 1.34670654e+04 1.42860771e+04 1.38935439e+04 1.34854219e+04 1.31479014e+04 1.30191250e+04 1.37843135e+04 1.39118428e+04 1.34772549e+04 1.30750361e+04 1.30324258e+04 1.34308457e+04 1.34095273e+04 1.37175615e+04 13704. 1.33413877e+04 1.29567383e+04 1.28826494e+04 1.36539482e+04 1.35893828e+04 1.31910986e+04 1.29664189e+04 1.28649004e+04 1.35807354e+04 1.36507021e+04 1.28379258e+04 1.27623018e+04 1.34805596e+04 1.34685654e+04 1.27688906e+04 1.27209004e+04 1.33847705e+04 1.34537656e+04 1.29680977e+04 1.26365645e+04 1.26385381e+04 1.33175615e+04 1.31538564e+04 1.26725479e+04 1.28950771e+04 1.28690879e+04 1.27564922e+04 1.27707188e+04 1.27212832e+04 1.23997344e+04 1.26890615e+04 1.32021689e+04 1.28666699e+04 1.28710889e+04 1.29040264e+04 1.26421641e+04 1.26341055e+04 1.25766611e+04 1.25074902e+04 1.22417217e+04 1.21778799e+04 1.24176787e+04 1.24606875e+04 1.27961094e+04 1.23841406e+04 1.19258340e+04 1.22890029e+04 1.23598945e+04 1.27141562e+04 1.25297852e+04 1.21240410e+04 1.19834150e+04 1.19018613e+04 1.21134961e+04 1.21227168e+04 1.23024736e+04 1.22665742e+04 1.19574473e+04 1.18651475e+04 1.14458955e+04 1.17688037e+04 1.24232178e+04 1.22058584e+04 1.18395283e+04 1.14828926e+04 1.12838223e+04 1.18238174e+04 1.21342471e+04 1.18252812e+04 1.13191670e+04 1.12762324e+04 1.15194434e+04 1.14466143e+04 1.17037100e+04 1.16301377e+04 1.13004053e+04 1.12187695e+04 1.12000957e+04 1.15725762e+04 1.15437314e+04 1.09244092e+04 1.08423564e+04 1.13895781e+04 1.12916924e+04 1.06738477e+04 1.08281201e+04 1.13870283e+04 1.12811611e+04 1.09406660e+04 1.05971074e+04 1.05231465e+04 1.10608965e+04 1.10693184e+04 1.07182988e+04 1.04255244e+04 1.03181514e+04 1.05759277e+04 1.06192969e+04 1.04892314e+04 1.01761992e+04 1.04224980e+04 1.07805225e+04 1.04481191e+04 1.05241846e+04 1.03985342e+04 1.01367998e+04 1.01823408e+04 1.01456562e+04 1.01234258e+04 1.00406465e+04 9.82602051e+03 9.61079688e+03 9.86331836e+03 1.03605166e+04 9.78245801e+03 9.35691895e+03 9.64627246e+03 9.88951855e+03 1.00485225e+04 9.83410059e+03 9.49419336e+03 9.64969141e+03 9.62614648e+03 9.31749609e+03 9.14097363e+03 9.45863086e+03 9.46640918e+03 9.19086816e+03 9.10269727e+03 8.79801855e+03 9.11933203e+03 9.61097266e+03 9.30647754e+03 8.95074902e+03 8.75139844e+03 8.56153027e+03 8.99042676e+03 9.28085352e+03 8.96661035e+03 8.57434277e+03 8.51265527e+03 8.55682520e+03 8.49004688e+03 8.75249219e+03 8.56664160e+03 8.29915137e+03 8.35187793e+03 8.26069531e+03 8.53471387e+03 8.44334082e+03 8.12852783e+03 8.12475586e+03 8.08646924e+03 8.08486523e+03 7.87937109e+03 7.82695459e+03 8.12980664e+03 8.07529199e+03 7.87825293e+03 7.56990332e+03 7.58266162e+03 7.98765137e+03 7.88853174e+03 7.60269824e+03 7.42551172e+03 7.33037646e+03 7.37927979e+03 7.37129639e+03 7.38667139e+03 7.15034082e+03 7.23377588e+03 7.49157080e+03 7.15102100e+03 7.25087061e+03 7.28858252e+03 7.07133691e+03 6.98814404e+03 6.89924805e+03 6.90050342e+03 6.83500293e+03 6.71940186e+03 6.68433154e+03 6.80418311e+03 6.81560059e+03 6.41473926e+03 6.30572119e+03 6.42051416e+03 6.52461670e+03 6.67077441e+03 6.45597607e+03 6.13935156e+03 6.29334424e+03 6.33870410e+03 6.19217920e+03 6.10230908e+03 6.04146191e+03 5.94916553e+03 5.88536914e+03 5.96192871e+03 5.77422461e+03 5.78080176e+03 6.01524023e+03 5.85888135e+03 5.71017676e+03 5.53920557e+03 5.50670410e+03 5.73898828e+03 5.61684082e+03 5.48588086e+03 5.29941309e+03 5.10899756e+03 5.23063232e+03 5.37136133e+03 5.49611865e+03 5.23701367e+03 5.01024609e+03 5.03251465e+03 5.02886768e+03 5.16658691e+03 5.07743555e+03 4.87301318e+03 4.81389258e+03 4.75128467e+03 4.74829834e+03 4.63945996e+03 4.65087891e+03 4.80475635e+03 4.66768848e+03 4.57534961e+03 4.40691943e+03 4.33691797e+03 4.54472803e+03 4.50341260e+03 4.33145410e+03 4.18769580e+03 4.11586963e+03 4.15910107e+03 4.14790723e+03 4.24216406e+03 4.18711523e+03 3.99703638e+03 3.87057031e+03 3.87906030e+03 4.02652539e+03 3.94584814e+03 3.80155054e+03 3.73729810e+03 3.67315015e+03 3.63147437e+03 3.56529175e+03 3.61967261e+03 3.56671045e+03 3.44635547e+03 3.53341943e+03 3.53054395e+03 3.41887598e+03 3.35579565e+03 3.29765747e+03 3.26786011e+03 3.14095093e+03 3.06685010e+03 3.19826050e+03 3.18703247e+03 2.98704834e+03 2.88748511e+03 2.98423608e+03 3.06323145e+03 2.98645605e+03 2.82754077e+03 2.72963110e+03 2.80700098e+03 2.81531616e+03 2.71437207e+03 2.68508789e+03 2.57755078e+03 2.44182666e+03 2.50935010e+03 2.62750415e+03 2.58972778e+03 2.40890845e+03 2.29992993e+03 2.40510229e+03 2.44871289e+03 2.32746631e+03 2.21431079e+03 2.15991357e+03 2.15392334e+03 2.14843164e+03 2.18834888e+03 2.15342993e+03 2.05014746e+03 1.98437500e+03 1.95364526e+03 2.00373315e+03 1.92514966e+03 1.83641846e+03 1.88850574e+03 1.85657568e+03 1.79692017e+03 1.72576428e+03 1.68664575e+03 1.74936182e+03 1.66676941e+03 1.57526038e+03 1.58946643e+03 1.59133960e+03 1.56285583e+03 1.50878979e+03 1.51972949e+03 1.49707922e+03 1.42527185e+03 1.35573120e+03 1.31743774e+03 1.37482300e+03 1.32704358e+03 1.26047815e+03 1.24650281e+03 1.21266492e+03 1.20569299e+03 1.17572900e+03 1.15965405e+03 1.12349866e+03 1.06999951e+03 1.08338745e+03 1.06599609e+03 1.02233771e+03 9.99033081e+02 9.72775940e+02 9.36016968e+02 8.87215271e+02 8.59356812e+02 8.82689148e+02 8.93326111e+02 8.24534912e+02 7.64367371e+02 7.74762451e+02 7.87864258e+02 7.58660034e+02 7.06822754e+02 6.68221436e+02 6.82779175e+02 6.66102295e+02 6.23246887e+02 6.27923340e+02 6.04006287e+02 5.53218201e+02 5.42168762e+02 5.52422058e+02 5.36529358e+02 4.92328888e+02 4.61104584e+02 4.67792694e+02 4.68816772e+02 4.39602783e+02 4.04975220e+02 3.82247101e+02 3.86811340e+02 3.76615540e+02 3.50366577e+02 3.37859375e+02 3.25341736e+02 3.06090210e+02 2.89795715e+02 2.86707581e+02 2.68691498e+02 2.47408722e+02 2.43049515e+02 2.32304779e+02 2.21552307e+02 2.04085068e+02 1.88389328e+02 1.85503586e+02 1.71106155e+02 1.56498779e+02 1.52251968e+02 1.46696304e+02 1.41408768e+02 1.29218903e+02 1.25120537e+02 1.07899445e+02 1.27200981e+02 9.06721802e+01 9.64564056e+01 1.01004929e+02 6.39464531e+01 1.22304169e+02 1.91374741e+02 -5111925. -8914302. 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. 2533516. 2.75529358e+02 7.00815048e+01 6.91853714e+01 6.86182556e+01 6.05145454e+01 6.87946320e+01 6.30199623e+01 7.29236984e+01 7.52061920e+01 8.16238708e+01 9.73419571e+01 8.73682175e+01 1.18393486e+02 1.51294189e+02 1.79537109e+02 1.48030411e+02 1.68643082e+02 1.53817261e+02 1.68636551e+02 1.82688492e+02 1.81797302e+02 1.96471603e+02 2.08626999e+02 2.12834503e+02 2.25586166e+02 2.45142441e+02 2.60540680e+02 2.74132874e+02 2.79244934e+02 2.87074371e+02 3.07500732e+02 3.25239777e+02 3.37816345e+02 3.48217834e+02 3.61472321e+02 3.88002502e+02 4.05422424e+02 4.12986755e+02 4.26641815e+02 4.43762451e+02 4.75636200e+02 4.97660767e+02 4.93492676e+02 5.07407410e+02 5.35894165e+02 5.55122375e+02 5.84150024e+02 6.00103821e+02 6.05516113e+02 6.35800476e+02 6.60498657e+02 6.75949402e+02 7.00140747e+02 7.10201233e+02 7.34976379e+02 7.64605469e+02 7.78001221e+02 7.98581299e+02 8.16911499e+02 8.45215088e+02 8.87589478e+02 9.09715332e+02 9.25854736e+02 9.34751953e+02 9.49306519e+02 1.00299158e+03 1.03048291e+03 1.02848230e+03 1.06534497e+03 1.09751831e+03 1.12326538e+03 1.16850708e+03 1.18920117e+03 1.18556763e+03 1.20709644e+03 1.27185461e+03 1.31432300e+03 1.30418762e+03 1.30617065e+03 1.34755591e+03 1.39898486e+03 1.45668311e+03 1.48258191e+03 1.45889819e+03 1.49497839e+03 1.57046753e+03 1.59801453e+03 1.61886755e+03 1.60704895e+03 1.62876343e+03 1.71595251e+03 1.76142664e+03 1.75077686e+03 1.77982373e+03 1.82320044e+03 1.85873511e+03 1.89745801e+03 1.91964636e+03 1.96149597e+03 2.00473242e+03 2.06113940e+03 2.09485132e+03 2.05616602e+03 2.09674048e+03 2.18143042e+03 2.20126074e+03 2.21656885e+03 2.25003931e+03 2.30499707e+03 2.38178296e+03 2.39489600e+03 2.39279834e+03 2.46757520e+03 2.52690381e+03 2.50209766e+03 2.53233447e+03 2.60397754e+03 2.64935010e+03 2.67681226e+03 2.68670068e+03 2.73533081e+03 2.78492407e+03 2.88175391e+03 2.91176758e+03 2.84631738e+03 2.90909790e+03 3.02347778e+03 3.06623291e+03 3.07304712e+03 3.07002344e+03 3.07672461e+03 3.18679932e+03 3.29416284e+03 3.28403882e+03 3.24491211e+03 3.31213428e+03 3.44058496e+03 3.49647266e+03 3.54962354e+03 3.49789722e+03 3.44428296e+03 3.56465894e+03 3.62978809e+03 3.66320923e+03 3.72785571e+03 3.72936548e+03 3.82346240e+03 3.98200806e+03 3.94549268e+03 3.82346924e+03 3.91139307e+03 4.05027246e+03 4.10285449e+03 4.19205322e+03 4.16680469e+03 4.14351270e+03 4.21325928e+03 4.37269385e+03 4.36218750e+03 4.23855371e+03 4.35575049e+03 4.53219482e+03 4.53522949e+03 4.52099512e+03 4.53416797e+03 4.58490234e+03 4.68236377e+03 4.72390869e+03 4.76523486e+03 4.88139453e+03 4.84340771e+03 4.90933594e+03 5.03742188e+03 5.03471729e+03 4.98624951e+03 5.03244629e+03 5.16699854e+03 5.28815527e+03 5.26469971e+03 5.21276123e+03 5.19720410e+03 5.36429736e+03 5.62658594e+03 5.68747119e+03 5.39272314e+03 5.48045703e+03 5.74417676e+03 5.71230029e+03 5.68245654e+03 5.68832129e+03 5.69804883e+03 5.88267041e+03 5.98540137e+03 5.91188721e+03 5.92433350e+03 5.94856250e+03 6.07707764e+03 6.26056787e+03 6.24954639e+03 6.18707764e+03 6.22486816e+03 6.38355957e+03 6.39485498e+03 6.37590674e+03 6.42707520e+03 6.53090771e+03 6.47730273e+03 6.72201074e+03 6.81979150e+03 6.52870166e+03 6.59925391e+03 6.84224902e+03 6.93599414e+03 6.96190186e+03 6.77812598e+03 6.92635938e+03 7.21379150e+03 7.17870947e+03 7.20902979e+03 7.06410498e+03 7.02486865e+03 7.30869678e+03 7.49703418e+03 7.44531445e+03 7.40876953e+03 7.51597949e+03 7.50839844e+03 7.70958301e+03 7.70769092e+03 7.55831543e+03 7.52641309e+03 7.67505469e+03 7.95538525e+03 7.90863574e+03 7.82810498e+03 7.87991113e+03 8.07753711e+03 8.16971387e+03 8.09259863e+03 8.11311963e+03 8.14536084e+03 8.28435938e+03 8.26731836e+03 8.44726562e+03 8.36929883e+03 8.30613477e+03 8.56675293e+03 8.38450977e+03 8.51756445e+03 8.73365918e+03 8.60952051e+03 8.59405957e+03 8.71560938e+03 8.82019629e+03 8.78520703e+03 8.67692969e+03 9.03759375e+03 9.33117480e+03 8.91289551e+03 8.86270801e+03 9.08213672e+03 9.14206152e+03 9.36802539e+03 9.31998926e+03 9.12577832e+03 9.26621387e+03 9.50331641e+03 9.57529590e+03 9.52313770e+03 9.44366992e+03 9.54944141e+03 9.64677148e+03 9.56274609e+03 9.62557812e+03 9.60737988e+03 9.65068457e+03 9.87628027e+03 9.95813379e+03 1.00027539e+04 9.85694043e+03 9.80065430e+03 1.01392881e+04 1.03679111e+04 1.00258652e+04 1.01612344e+04 1.02519014e+04 1.00206875e+04 1.02922988e+04 1.03509941e+04 1.02121963e+04 1.04823418e+04 1.04909893e+04 1.04557246e+04 1.07731982e+04 1.05942637e+04 1.04468818e+04 1.05624404e+04 1.07277549e+04 1.08867227e+04 1.06313730e+04 1.06203076e+04 1.08707646e+04 1.09867510e+04 1.10171660e+04 1.09935352e+04 1.08523740e+04 1.11035586e+04 1.14775723e+04 1.11424385e+04 1.09836289e+04 1.09837451e+04 1.13481074e+04 1.15464648e+04 1.11809941e+04 1.11777305e+04 1.13265645e+04 1.14217051e+04 1.14214619e+04 1.15236309e+04 1.15262725e+04 1.14039834e+04 1.16792256e+04 1.19501025e+04 1.16855527e+04 1.12826816e+04 1.15210928e+04 1.18047617e+04 1.18320654e+04 1.19188281e+04 1.18715078e+04 1.17444619e+04 1.20879980e+04 1.23151260e+04 1.19618018e+04 1.18809561e+04 1.19544004e+04 1.23447031e+04 1.23243428e+04 1.18876924e+04 1.18917998e+04 1.21642021e+04 1.23622803e+04 1.23275898e+04 1.24078525e+04 1.23022998e+04 1.23184287e+04 1.23914248e+04 1.21969893e+04 1.23071709e+04 1.22986328e+04 1.24908516e+04 1.27118037e+04 1.24846826e+04 1.23060430e+04 1.24674814e+04 1.27306631e+04 1.31234385e+04 1.30411777e+04 1.25074756e+04 1.25035430e+04 1.27781934e+04 1.28147559e+04 1.27024043e+04 1.27043242e+04 1.28276768e+04 1.29702051e+04 1.28289531e+04 1.25683037e+04 1.28727705e+04 1.31773760e+04 1.32455986e+04 1.30558174e+04 1.27821201e+04 1.29449844e+04 1.28932686e+04 1.28562500e+04 1.33338730e+04 1.33029590e+04 1.28618730e+04 1.29478330e+04 1.31565166e+04 1.34500889e+04 1.34588389e+04 1.32300850e+04 1.31584961e+04 1.32193545e+04 1.32066260e+04 1.30765127e+04 1.33128535e+04 1.33855811e+04 1.35237734e+04 1.35252520e+04 1.29939756e+04 1.31865781e+04 1.33818379e+04 1.34101670e+04 1.37353252e+04 1.33658193e+04 1.31758828e+04 1.36880986e+04 1.37443252e+04 1.34693262e+04 1.34111992e+04 1.33413330e+04 1.33045596e+04 1.33877217e+04 1.35194482e+04 1.34736260e+04 1.37387090e+04 1.38962822e+04 1.36563799e+04 1.34787334e+04 1.33102686e+04 1.36153867e+04 1.38672432e+04 1.37539600e+04 1.33934727e+04 1.33069141e+04 1.35871973e+04 1.38239824e+04 1.41269639e+04 1.37570293e+04 1.33962637e+04 1.35886143e+04 1.36164131e+04 1.35467646e+04 1.38949727e+04 1.38491660e+04 1.34520781e+04 1.37412529e+04 1.37320742e+04 1.37016230e+04 1.37847812e+04 1.36953936e+04 1.37296035e+04 1.36166279e+04 1.36363096e+04 1.35116387e+04 1.36813271e+04 1.38383350e+04 1.38129072e+04 1.37600498e+04 1.33995928e+04 1.35726943e+04 1.37229805e+04 1.35976074e+04 1.37952607e+04 1.37660947e+04 1.35305859e+04 1.35531797e+04 1.36389648e+04 1.39616279e+04 1.39990654e+04 1.35871758e+04 1.35242900e+04 1.34882441e+04 1.34706914e+04 1.35941621e+04 1.37333125e+04 1.37775488e+04 1.36144014e+04 1.35172500e+04 1.34467539e+04 1.34896533e+04 1.39137988e+04 1.38473213e+04 1.34046816e+04 1.34270127e+04 1.34227354e+04 1.33604170e+04 1.36300430e+04 1.37539834e+04 1.34944346e+04 1.33768994e+04 1.33580039e+04 1.34007773e+04 1.36212500e+04 1.35041182e+04 1.34646074e+04 1.34675215e+04 1.33146855e+04 1.34510771e+04 1.32114395e+04 1.32578477e+04 1.36517070e+04 1.33025801e+04 1.31242520e+04 1.32846211e+04 1.31540977e+04 1.31149834e+04 1.36126445e+04 1.36188066e+04 1.29159805e+04 1.29540430e+04 1.31421230e+04 1.30267002e+04 1.33236602e+04 1.32239639e+04 1.28341934e+04 1.29902354e+04 1.30079980e+04 1.31606904e+04 1.33274238e+04 1.30340957e+04 1.30560010e+04 1.29043652e+04 1.25552969e+04 1.27423809e+04 1.30435420e+04 1.29384746e+04 1.29802568e+04 1.29114863e+04 1.23666035e+04 1.25916143e+04 1.30843184e+04 1.30179473e+04 1.26824072e+04 1.22709023e+04 1.24240059e+04 1.28738467e+04 1.27288066e+04 1.25374912e+04 1.27092129e+04 1.24524316e+04 1.24684150e+04 1.25683066e+04 1.21057812e+04 1.22140781e+04 1.25735801e+04 1.25764590e+04 1.23571787e+04 1.19441084e+04 1.20238311e+04 1.23064814e+04 1.24197910e+04 1.22868301e+04 1.20025459e+04 1.18426934e+04 1.19605400e+04 1.21883789e+04 1.23452773e+04 1.21058838e+04 1.18145879e+04 1.18653242e+04 1.18105781e+04 1.17929990e+04 1.18888359e+04 1.17626943e+04 1.17646729e+04 1.19194277e+04 1.16788760e+04 1.15690439e+04 1.16710498e+04 1.16615010e+04 1.16715762e+04 1.14987549e+04 1.12290215e+04 1.13195996e+04 1.15125361e+04 1.15833604e+04 1.16586611e+04 1.12992012e+04 1.09722080e+04 1.11746777e+04 1.10984346e+04 1.11721240e+04 1.12786084e+04 1.09842383e+04 1.08885098e+04 1.08561953e+04 1.08801123e+04 1.10648105e+04 1.11790791e+04 1.09703174e+04 1.08121152e+04 1.06955117e+04 1.04334434e+04 1.05691094e+04 1.07336416e+04 1.08092705e+04 1.07178828e+04 1.03990684e+04 1.02709297e+04 1.04329912e+04 1.04856475e+04 1.04370244e+04 1.03180049e+04 1.02046162e+04 1.00535176e+04 1.02207373e+04 1.04083184e+04 1.01872988e+04 9.90580176e+03 9.96583984e+03 9.98967188e+03 9.99157422e+03 1.00102783e+04 9.89079102e+03 9.91621094e+03 9.73280176e+03 9.62708887e+03 9.83362012e+03 9.71967773e+03 9.55420508e+03 9.74455859e+03 9.45004199e+03 9.27725781e+03 9.56476172e+03 9.43382422e+03 8.98035059e+03 1.00010977e+04 9.87403906e+03 8.38050879e+03 7.69977002e+03 1.17664248e+04 1.50871318e+04 2.36332617e+04 2.56256035e+04 2222158. -3.27102975e+06 2.60875275e+06 141720576. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -21149680. -21854842. 3.07941699e+04 1.92369648e+04 1.14484814e+04 1.07090283e+04 9.63456055e+03 8.92597852e+03 9.14672461e+03 5.14239844e+03 5.75402686e+03 7.53606543e+03 6.24965430e+03 5.74383838e+03 5.37709473e+03 5.82548828e+03 6.29475928e+03 6.17905957e+03 5.89538770e+03 5.86919873e+03 5.96081592e+03 5.92863916e+03 5.92961182e+03 5.91430713e+03 5.69500684e+03 5.58331934e+03 5.58306934e+03 5.53315527e+03 5.57165723e+03 5.42011963e+03 5.30498389e+03 5.42236914e+03 5.54673828e+03 5.36381104e+03 5.05596094e+03 5.04618115e+03 5.19711279e+03 5.21298584e+03 5.02216943e+03 4.85889795e+03 4.86376025e+03 5.01439453e+03 5.05944238e+03 4.88538184e+03 4.62413086e+03 4.60730811e+03 4.77323584e+03 4.69372021e+03 4.67695654e+03 4.56579395e+03 4.35867139e+03 4.39848242e+03 4.50322168e+03 4.37012744e+03 4.25946729e+03 4.34929834e+03 4.32532129e+03 4.21324316e+03 4.10534229e+03 3.97606104e+03 4.03995850e+03 4.15151270e+03 4.01937354e+03 3.87287158e+03 3.79776514e+03 3.74446704e+03 3.88789722e+03 3.92809521e+03 3.74688452e+03 3.63566089e+03 3.57173145e+03 3.49905981e+03 3.54904346e+03 3.63319751e+03 3.45808057e+03 3.35161865e+03 3.41208813e+03 3.34783105e+03 3.24432690e+03 3.22114624e+03 3.22423340e+03 3.23569360e+03 3.18635840e+03 3.13515552e+03 2.99287427e+03 2.92363281e+03 3.03389941e+03 3.05722729e+03 2.86604541e+03 2.74336743e+03 2.77851196e+03 2.80948755e+03 2.81670947e+03 2.80032593e+03 2.65135156e+03 2.57531982e+03 2.60398999e+03 2.56914600e+03 2.55387476e+03 2.48490503e+03 2.38780127e+03 2.37668628e+03 2.39570239e+03 2.36693091e+03 2.31398267e+03 2.27849390e+03 2.23692773e+03 2.20931934e+03 2.18500854e+03 2.08110864e+03 2.04003748e+03 2.12110986e+03 2.08572876e+03 1.94852441e+03 1.88801245e+03 1.88386121e+03 1.93880225e+03 1.95508655e+03 1.84839783e+03 1.74289954e+03 1.71302295e+03 1.71100208e+03 1.70264966e+03 1.68206958e+03 1.63984387e+03 1.60286096e+03 1.56788220e+03 1.53881946e+03 1.51827808e+03 1.46093359e+03 1.44896106e+03 1.46570349e+03 1.40839832e+03 1.36119153e+03 1.32307898e+03 1.27621912e+03 1.29443677e+03 1.30242017e+03 1.21507349e+03 1.16011414e+03 1.16003174e+03 1.17392017e+03 1.16255676e+03 1.10463647e+03 1.04899133e+03 1.02084332e+03 1.00750769e+03 1.00244800e+03 9.91528015e+02 9.31465088e+02 8.85466553e+02 8.92885132e+02 8.97981506e+02 8.63164795e+02 8.23415283e+02 7.99691162e+02 7.75836975e+02 7.65799438e+02 7.47849548e+02 7.01105530e+02 6.80446838e+02 6.81920715e+02 6.63087646e+02 6.33161743e+02 6.01838074e+02 5.88351440e+02 5.78102661e+02 5.60128845e+02 5.44027344e+02 5.13727478e+02 4.96680573e+02 4.88786407e+02 4.65862183e+02 4.47092010e+02 4.25706879e+02 4.08941803e+02 4.01658447e+02 3.94602264e+02 3.74373352e+02 3.42365204e+02 3.25954407e+02 3.25540741e+02 3.19150360e+02 2.98913544e+02 2.74787567e+02 2.59045746e+02 2.52078125e+02 2.44321075e+02 2.33295380e+02 2.15029388e+02 1.99501007e+02 1.91504257e+02 1.84240311e+02 1.74717758e+02 1.61867081e+02 1.49487106e+02 1.40610687e+02 1.32130890e+02 1.23194649e+02 1.14425446e+02 1.05645889e+02 9.73576202e+01 8.88262863e+01 8.00079803e+01 7.26800232e+01 6.86388550e+01 6.44774628e+01 5.74114494e+01 4.93431625e+01 4.22908134e+01 3.77877808e+01 3.50214157e+01 3.12408524e+01 2.60863228e+01 2.11904812e+01 1.73867416e+01 1.47711105e+01 1.24205008e+01 9.94062805e+00 7.62134647e+00 5.64582491e+00 4.16121531e+00 3.00183654e+00 2.15757036e+00 1.67692626e+00 1.52664137e+00 1.70998216e+00 2.24417138e+00 3.08140421e+00 4.10324430e+00 5.65542889e+00 7.70463943e+00 9.90283012e+00 1.23990774e+01 1.51279202e+01 1.87295589e+01 2.23614655e+01 2.52034245e+01 2.84538994e+01 3.35443039e+01 4.01858368e+01 4.66701736e+01 5.15701637e+01 5.45730057e+01 5.88511429e+01 6.66592789e+01 7.68654938e+01 8.63247910e+01 9.26434631e+01 9.51016846e+01 1.02789604e+02 1.17951714e+02 1.26475624e+02 1.29716187e+02 1.39105652e+02 1.50336578e+02 1.60596008e+02 1.77468231e+02 1.84270828e+02 1.87972763e+02 2.04333969e+02 2.12436462e+02 2.29654678e+02 2.48552109e+02 2.48635239e+02 2.65557343e+02 2.87152283e+02 2.94828552e+02 3.09613770e+02 3.22010162e+02 3.36301880e+02 3.56582611e+02 3.68020538e+02 3.71929260e+02 3.87852905e+02 4.25492035e+02 4.54414124e+02 4.58691925e+02 4.56118408e+02 4.62905365e+02 4.89107849e+02 5.29561890e+02 5.64095093e+02 5.67989136e+02 5.58624023e+02 5.83778931e+02 6.22748169e+02 6.33633240e+02 6.49101807e+02 6.72056030e+02 6.92491089e+02 7.16384033e+02 7.62959656e+02 7.64909729e+02 7.59648560e+02 8.02494202e+02 8.02158569e+02 8.54501038e+02 8.99662170e+02 8.89452881e+02 9.49135193e+02 9.57021973e+02 9.31059692e+02 9.83412659e+02 9.98011780e+02 1.03907495e+03 1.13552991e+03 1.10356482e+03 1.06647327e+03 1.11696545e+03 1.19493677e+03 1.26890955e+03 1.26977783e+03 1.22970032e+03 1.22599805e+03 1.27216675e+03 1.35300171e+03 1.43087646e+03 1.44474780e+03 1.40406860e+03 1.41438416e+03 1.48715845e+03 1.53541016e+03 1.53435278e+03 1.56241443e+03 1.59602075e+03 1.62440186e+03 1.72135242e+03 1.75317554e+03 1.69155957e+03 1.71683740e+03 1.78044385e+03 1.82079858e+03 1.86850659e+03 1.89400732e+03 1.97936426e+03 1.96680298e+03 1.92388708e+03 2.02101465e+03 2.00310815e+03 2.08229272e+03 2.27847900e+03 2.17850537e+03 2.06338354e+03 2.17109180e+03 2.31395264e+03 2.40070044e+03 2.45166528e+03 2.34222095e+03 2.27634961e+03 2.37655469e+03 2.54872607e+03 2.67002783e+03 2.63789404e+03 2.51735840e+03 2.53350708e+03 2.65777368e+03 2.74112036e+03 2.85740430e+03 2.88880981e+03 2.75669019e+03 2.78663159e+03 2.93171997e+03 3.01265674e+03 2.97245190e+03 2.97714648e+03 3.04667651e+03 3.06266260e+03 3.21575098e+03 3.27718945e+03 3.17679443e+03 3.20943018e+03 3.26528857e+03 3.31044775e+03 3.40217358e+03 3.41552612e+03 3.52383496e+03 3.61095703e+03 3.53488647e+03 3.51468677e+03 3.48449023e+03 3.67284839e+03 3.90284131e+03 3.88208057e+03 3.73063306e+03 3.66929736e+03 3.84152466e+03 4.09585864e+03 4.02165991e+03 3.82536890e+03 3.99726807e+03 4.15439062e+03 4.25576074e+03 4.40639209e+03 4.38836865e+03 4.17532959e+03 4.13418799e+03 4.31010449e+03 4.50820801e+03 4.54345459e+03 4.51219727e+03 4.54579590e+03 4.57862891e+03 4.73379248e+03 4.71746094e+03 4.63124268e+03 4.71001367e+03 4.73734570e+03 4.91982227e+03 5.09748730e+03 4.97102783e+03 5.03803564e+03 5.11093945e+03 5.12330127e+03 5.06045898e+03 4.97259229e+03 5.27293604e+03 5.58523389e+03 5.44265723e+03 5.20750781e+03 5.29695898e+03 5.62945166e+03 5.74765723e+03 5.66057275e+03 5.64324414e+03 5.48432373e+03 5.51987842e+03 5.87391162e+03 5.93785547e+03 5.83987842e+03 5.73915283e+03 5.72191309e+03 6.04273145e+03 6.37552051e+03 6.11343848e+03 5.99667676e+03 6.14473193e+03 6.20038770e+03 6.45367627e+03 6.54641895e+03 6.21685938e+03 6.18756250e+03 6.45501514e+03 6.49975049e+03 6.63358789e+03 6.64018359e+03 6.97854492e+03 6.88504053e+03 6.66560303e+03 6.59783203e+03 6.45835547e+03 7.00205713e+03 7.58203125e+03 7.38122852e+03 6.66848096e+03 7.44879932e+03 1.03471973e+04 1.16498008e+04 2.61634609e+04 1.23328338e+06 2220527. -49502404. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -40309564. 1.81641016e+05 2.58857148e+04 1.43547295e+04 1.56877295e+04 1.43514814e+04 1.41817480e+04 1.39891797e+04 1.37542529e+04 1.45509893e+04 1.48062031e+04 1.44038604e+04 1.46818555e+04 1.47718057e+04 1.46578428e+04 1.48094922e+04 1.49114434e+04 1.48403027e+04 1.08609932e+04 1.20162471e+04 1.08297158e+04 1.00443975e+04 9.99006348e+03 1.02574121e+04 1.04088311e+04 1.00081064e+04 1.00672148e+04 1.05669131e+04 1.06870342e+04 1.04543418e+04 1.04499941e+04 1.04642744e+04 1.04985244e+04 1.05667656e+04 1.05833467e+04 1.06305576e+04 1.06617676e+04 1.04758613e+04 1.05207324e+04 1.10514697e+04 1.11384336e+04 1.08313574e+04 1.08896016e+04 1.09711855e+04 1.10133691e+04 1.10127207e+04 1.10212979e+04 1.11064316e+04 1.10207080e+04 1.09622686e+04 1.10938965e+04 1.11232139e+04 1.15665977e+04 1.17029678e+04 1.13477197e+04 1.10870820e+04 1.10494639e+04 1.17556221e+04 1.19083574e+04 1.15228838e+04 1.13473936e+04 1.14552393e+04 1.16509824e+04 1.15768496e+04 1.19314014e+04 1.20397314e+04 1.14165459e+04 1.13019697e+04 1.19352461e+04 1.24688418e+04 1.21632998e+04 1.18905303e+04 1.19624150e+04 1.19193623e+04 1.19599570e+04 1.20283506e+04 1.21448965e+04 1.21498301e+04 1.20507461e+04 1.20804531e+04 1.21404453e+04 1.21239102e+04 1.25772656e+04 1.25515127e+04 1.21908770e+04 1.22941963e+04 1.22552568e+04 1.26682080e+04 1.27873984e+04 1.24646787e+04 1.24693740e+04 1.23081279e+04 1.21551768e+04 1.27191787e+04 1.27218730e+04 1.20716094e+04 1.22925879e+04 1.30403525e+04 1.34682363e+04 1.31184961e+04 1.27567158e+04 1.26143691e+04 1.26362734e+04 1.27891221e+04 1.27592695e+04 1.28126514e+04 1.28007939e+04 1.31641113e+04 1.31873232e+04 1.28351162e+04 1.28958887e+04 1.25644424e+04 1.29069102e+04 1.37146963e+04 1.34325967e+04 1.31214688e+04 1.27899248e+04 1.26930244e+04 1.34766006e+04 1.35936631e+04 1.32029561e+04 1.28451191e+04 1.28466406e+04 1.31883311e+04 1.31723916e+04 1.36466553e+04 1.37627803e+04 1.33117764e+04 1.32009785e+04 1.32225156e+04 1.34827998e+04 1.35736719e+04 1.33996641e+04 1.31887549e+04 1.32559561e+04 1.33552158e+04 1.29515049e+04 1.32399131e+04 1.41169229e+04 1.38959443e+04 1.34876807e+04 1.31634961e+04 1.31182285e+04 1.39259902e+04 1.39600166e+04 1.35467148e+04 1.32128799e+04 1.31394258e+04 1.36281787e+04 1.36103281e+04 1.35548125e+04 1.32706836e+04 1.35656797e+04 1.42202598e+04 1.38522285e+04 1.37246465e+04 1.38035098e+04 1.37289512e+04 1.35106074e+04 1.34785723e+04 1.35496670e+04 1.35231572e+04 1.37192432e+04 1.33402734e+04 1.34787080e+04 1.44066631e+04 1.37756123e+04 1.32449277e+04 1.36403594e+04 1.36674922e+04 1.40758213e+04 1.39254932e+04 1.33995078e+04 1.38868594e+04 1.40011875e+04 1.37248867e+04 1.36511865e+04 1.36199004e+04 1.35723906e+04 1.35558301e+04 1.36105215e+04 1.32763857e+04 1.36175010e+04 1.43761475e+04 1.41113467e+04 1.36176494e+04 1.31694668e+04 1.33774180e+04 1.42168604e+04 1.40994307e+04 1.36692334e+04 1.33680078e+04 1.32908984e+04 1.36565146e+04 1.36979111e+04 1.39541494e+04 1.37702324e+04 1.33930312e+04 1.35158281e+04 1.34896680e+04 1.39308105e+04 1.38522393e+04 1.34395527e+04 1.34919463e+04 1.35111338e+04 1.34823779e+04 1.30963340e+04 1.34864541e+04 1.43150166e+04 1.39085947e+04 1.34950967e+04 1.31548662e+04 1.30265400e+04 1.38092842e+04 1.39281084e+04 1.34925352e+04 1.30640928e+04 1.30416953e+04 1.34608799e+04 1.34147021e+04 1.37377549e+04 1.37157607e+04 1.33473662e+04 1.29791094e+04 1.28981084e+04 1.36482344e+04 1.35832881e+04 1.32019102e+04 1.30057305e+04 1.28981631e+04 1.35867744e+04 1.36534883e+04 1.28433740e+04 1.27721123e+04 1.35013486e+04 1.35037158e+04 1.27703936e+04 1.27179951e+04 1.34060938e+04 1.34725459e+04 1.29675713e+04 1.26440117e+04 1.26585459e+04 1.33321973e+04 1.31854785e+04 1.26853174e+04 1.28946953e+04 1.28832490e+04 1.27830654e+04 1.27615615e+04 1.27348174e+04 1.24097432e+04 1.27231709e+04 1.31981709e+04 1.28232373e+04 1.29145918e+04 1.29149873e+04 1.26444170e+04 1.26432383e+04 1.25603477e+04 1.25090967e+04 1.22331582e+04 1.21552207e+04 1.24349756e+04 1.24738633e+04 1.27898896e+04 1.23801260e+04 1.19388945e+04 1.22909453e+04 1.23984844e+04 1.26990947e+04 1.25864717e+04 1.21301387e+04 1.19857891e+04 1.18788096e+04 1.21325303e+04 1.21376992e+04 1.23517305e+04 1.22417568e+04 1.19510166e+04 1.18717422e+04 1.14811416e+04 1.17885674e+04 1.24251201e+04 1.22163887e+04 1.18525332e+04 1.14713721e+04 1.13046982e+04 1.18364258e+04 1.21336787e+04 1.18197305e+04 1.13068926e+04 1.12758496e+04 1.15719629e+04 1.14601201e+04 1.17178281e+04 1.16528535e+04 1.12770547e+04 1.12271807e+04 1.11944492e+04 1.15835098e+04 1.15844971e+04 1.09215635e+04 1.08766289e+04 1.14446074e+04 1.12943506e+04 1.06780605e+04 1.08387305e+04 1.13773535e+04 1.12967490e+04 1.09889971e+04 1.06388623e+04 1.05509775e+04 1.10876299e+04 1.10746816e+04 1.07486436e+04 1.04580439e+04 1.02948193e+04 1.05830508e+04 1.06303086e+04 1.05210186e+04 1.01666582e+04 1.04165156e+04 1.08004717e+04 1.04294463e+04 1.05205850e+04 1.04026807e+04 1.01476787e+04 1.02052842e+04 1.01632705e+04 1.01205889e+04 1.00249805e+04 9.85377930e+03 9.61066406e+03 9.89054199e+03 1.03601592e+04 9.79550977e+03 9.35794531e+03 9.66278027e+03 9.89761328e+03 1.00725215e+04 9.79534082e+03 9.51293555e+03 9.68916406e+03 9.64767480e+03 9.32062305e+03 9.13990918e+03 9.47707910e+03 9.43137891e+03 9.19058203e+03 9.09711328e+03 8.78239160e+03 9.06184180e+03 9.62326660e+03 9.30331641e+03 8.98157520e+03 8.76540820e+03 8.54628516e+03 9.00941016e+03 9.29897363e+03 8.93501758e+03 8.58669629e+03 8.48982910e+03 8.58340332e+03 8.54151855e+03 8.78615039e+03 8.60916016e+03 8.31582812e+03 8.34220996e+03 8.29186133e+03 8.55603516e+03 8.46545508e+03 8.13774854e+03 8.12676660e+03 8.08194678e+03 8.12828955e+03 7.85880469e+03 7.84037354e+03 8.12220117e+03 8.05570215e+03 7.90925293e+03 7.60441650e+03 7.58961816e+03 8.03223535e+03 7.85079150e+03 7.62661035e+03 7.43076855e+03 7.31745898e+03 7.39812598e+03 7.40031055e+03 7.41407617e+03 7.15756006e+03 7.24126562e+03 7.49673193e+03 7.14297168e+03 7.29345557e+03 7.30840088e+03 7.07437793e+03 7.01079932e+03 6.89795410e+03 6.88589209e+03 6.85552832e+03 6.71985059e+03 6.69719482e+03 6.84185059e+03 6.79037744e+03 6.41503857e+03 6.30744287e+03 6.44952832e+03 6.54360596e+03 6.74194873e+03 6.49103125e+03 6.15907373e+03 6.30585352e+03 6.37671973e+03 6.22537744e+03 6.08209473e+03 6.05246875e+03 5.95489014e+03 5.90744678e+03 5.99391260e+03 5.79250293e+03 5.80654932e+03 6.01081885e+03 5.84902441e+03 5.71332178e+03 5.55364600e+03 5.51748926e+03 5.74742480e+03 5.65165869e+03 5.49939160e+03 5.29176025e+03 5.12519238e+03 5.24020166e+03 5.35960352e+03 5.48470215e+03 5.26020361e+03 5.02793896e+03 5.03673779e+03 5.00950195e+03 5.17359570e+03 5.06609131e+03 4.87543213e+03 4.81619336e+03 4.76717725e+03 4.75483447e+03 4.63100781e+03 4.66512891e+03 4.81044580e+03 4.68518164e+03 4.55870996e+03 4.44029199e+03 4.36542920e+03 4.55506055e+03 4.50721191e+03 4.31789844e+03 4.17765088e+03 4.10850977e+03 4.18828857e+03 4.13785938e+03 4.24296338e+03 4.20845898e+03 4.01112817e+03 3.86801392e+03 3.89366992e+03 4.02138354e+03 3.93658887e+03 3.79436792e+03 3.73079272e+03 3.67880786e+03 3.63056396e+03 3.56247119e+03 3.61243677e+03 3.56445312e+03 3.45412695e+03 3.53146240e+03 3.52424927e+03 3.42001221e+03 3.34821240e+03 3.30166895e+03 3.25911499e+03 3.13982031e+03 3.07642676e+03 3.18912231e+03 3.18348584e+03 3.00033228e+03 2.88751611e+03 2.98591333e+03 3.06708643e+03 2.98477661e+03 2.83229395e+03 2.73117773e+03 2.80968140e+03 2.81007227e+03 2.71525317e+03 2.69725757e+03 2.57717651e+03 2.44601758e+03 2.51476953e+03 2.63284888e+03 2.58965454e+03 2.41886865e+03 2.30011255e+03 2.40833594e+03 2.45151318e+03 2.32647168e+03 2.21891895e+03 2.15998145e+03 2.15271826e+03 2.14829321e+03 2.18570044e+03 2.15621729e+03 2.05290845e+03 1.99267786e+03 1.95917737e+03 2.00638623e+03 1.93012219e+03 1.83719238e+03 1.89021936e+03 1.85940234e+03 1.79644214e+03 1.73305933e+03 1.69055847e+03 1.74887463e+03 1.66940027e+03 1.57340979e+03 1.58916479e+03 1.59356409e+03 1.56175085e+03 1.50863171e+03 1.52252393e+03 1.50016956e+03 1.42583850e+03 1.35268848e+03 1.31953516e+03 1.37369373e+03 1.32863928e+03 1.26057739e+03 1.24604211e+03 1.21191382e+03 1.20573901e+03 1.17789856e+03 1.15886023e+03 1.12096521e+03 1.07285095e+03 1.08240955e+03 1.06301843e+03 1.02007739e+03 1.00009064e+03 9.73747192e+02 9.33787720e+02 8.85466797e+02 8.57660950e+02 8.81986206e+02 8.96726440e+02 8.26581055e+02 7.66382629e+02 7.76742371e+02 7.87060364e+02 7.57452698e+02 7.07517029e+02 6.70262207e+02 6.82457275e+02 6.63811462e+02 6.21534058e+02 6.28661133e+02 6.04321289e+02 5.53550110e+02 5.41868347e+02 5.51909546e+02 5.37486694e+02 4.93049866e+02 4.60601379e+02 4.67240601e+02 4.68618195e+02 4.39146729e+02 4.03910675e+02 3.82171478e+02 3.86393921e+02 3.75692169e+02 3.49583679e+02 3.36810120e+02 3.24606079e+02 3.05975922e+02 2.89300934e+02 2.86348114e+02 2.68329285e+02 2.46896729e+02 2.42546082e+02 2.31620438e+02 2.21122803e+02 2.04563553e+02 1.88344421e+02 1.84663528e+02 1.70464859e+02 1.56327591e+02 1.52532700e+02 1.45254868e+02 1.37857880e+02 1.24551811e+02 1.23069809e+02 1.05255821e+02 1.24477867e+02 8.88094711e+01 1.08647255e+02 1.21211670e+02 1.07615318e+02 1.29918518e+02 1.23298866e+02 -5111925. -8914302. 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. -18104674. 4.18322876e+02 9.97521973e+01 8.39477692e+01 8.25496368e+01 8.13088531e+01 8.17951660e+01 6.34755630e+01 7.08609314e+01 7.40206909e+01 8.15311890e+01 9.67553101e+01 8.70535202e+01 1.17045456e+02 1.49577591e+02 1.90416641e+02 1.90198593e+02 1.95283417e+02 1.55971558e+02 1.68998672e+02 1.85989746e+02 1.88799683e+02 1.99998642e+02 2.06583755e+02 2.11912231e+02 2.28677307e+02 2.48595764e+02 2.57411530e+02 2.69363007e+02 2.80074921e+02 2.92227753e+02 3.15271912e+02 3.23269562e+02 3.27959076e+02 3.47459106e+02 3.62794281e+02 3.85454834e+02 4.05666138e+02 4.09017029e+02 4.26324188e+02 4.57112305e+02 4.93059723e+02 4.99847076e+02 4.83411957e+02 4.98351959e+02 5.31342773e+02 5.61233643e+02 5.90458191e+02 6.02794617e+02 6.04484680e+02 6.39783142e+02 6.68328247e+02 6.67638977e+02 6.82981995e+02 7.05101440e+02 7.50872437e+02 7.96435852e+02 7.80331848e+02 7.75193420e+02 8.16617615e+02 8.61580994e+02 8.99518188e+02 9.04162354e+02 9.08258301e+02 9.25354858e+02 9.69172852e+02 1.03995129e+03 1.03544604e+03 1.00581012e+03 1.05626208e+03 1.10680078e+03 1.12996204e+03 1.16611511e+03 1.17520447e+03 1.17482581e+03 1.22847583e+03 1.28836426e+03 1.29166895e+03 1.29558179e+03 1.31300745e+03 1.35118335e+03 1.42272852e+03 1.48262329e+03 1.46980554e+03 1.44749390e+03 1.50645764e+03 1.57857007e+03 1.57648767e+03 1.58670850e+03 1.62163257e+03 1.67590869e+03 1.76652405e+03 1.76699109e+03 1.72291785e+03 1.74766833e+03 1.79870020e+03 1.87240845e+03 1.92382959e+03 1.92433362e+03 1.95245691e+03 2.03073999e+03 2.12240625e+03 2.10914624e+03 2.02947888e+03 2.07058447e+03 2.18450757e+03 2.22779736e+03 2.25156982e+03 2.25743237e+03 2.28060840e+03 2.38266455e+03 2.41958398e+03 2.38831665e+03 2.44041943e+03 2.49382935e+03 2.51953247e+03 2.61231396e+03 2.64019043e+03 2.61299072e+03 2.65139258e+03 2.69008350e+03 2.73464355e+03 2.83703784e+03 2.93862427e+03 2.89017603e+03 2.82000513e+03 2.94423291e+03 3.07369531e+03 3.04644409e+03 3.02172290e+03 3.05119238e+03 3.10664502e+03 3.24503247e+03 3.30736816e+03 3.22968652e+03 3.24513623e+03 3.33542285e+03 3.43970728e+03 3.49402051e+03 3.49428198e+03 3.50153467e+03 3.56641626e+03 3.67085376e+03 3.61599634e+03 3.58535254e+03 3.68564355e+03 3.76749365e+03 3.86436914e+03 3.97530933e+03 3.94064380e+03 3.83745728e+03 3.96347241e+03 4.12564160e+03 4.09713477e+03 4.11706250e+03 4.07715918e+03 4.11673682e+03 4.35953223e+03 4.43584814e+03 4.28230713e+03 4.24772705e+03 4.43263623e+03 4.60575977e+03 4.50091943e+03 4.43600781e+03 4.52226074e+03 4.72320605e+03 4.84443262e+03 4.72526758e+03 4.68695312e+03 4.78663525e+03 4.81907227e+03 4.93874463e+03 5.02988623e+03 4.98388672e+03 5.06887598e+03 5.17956689e+03 5.22470166e+03 5.20160938e+03 5.16492285e+03 5.21116602e+03 5.26154932e+03 5.38633203e+03 5.70308154e+03 5.68534131e+03 5.36699268e+03 5.54734912e+03 5.78783594e+03 5.64428271e+03 5.54734521e+03 5.64113135e+03 5.76839746e+03 6.06196680e+03 6.03813867e+03 5.82052393e+03 5.85951172e+03 5.95131299e+03 6.13332471e+03 6.22493262e+03 6.18271045e+03 6.17917480e+03 6.41361035e+03 6.52798779e+03 6.34274512e+03 6.29275928e+03 6.39734863e+03 6.46282617e+03 6.58679834e+03 6.78845410e+03 6.87125195e+03 6.57563281e+03 6.65981836e+03 6.87986035e+03 6.86664111e+03 6.90357910e+03 6.83636133e+03 6.99168018e+03 7.23698828e+03 7.24420215e+03 7.10402441e+03 7.07625635e+03 7.15540430e+03 7.24412793e+03 7.40895020e+03 7.35342676e+03 7.43687207e+03 7.56511133e+03 7.64397217e+03 7.79954004e+03 7.56024365e+03 7.48363477e+03 7.70887207e+03 7.76185645e+03 7.96807715e+03 7.96644385e+03 7.66227539e+03 7.94468408e+03 8.25327930e+03 8.03786670e+03 7.98308350e+03 8.13820215e+03 8.24910547e+03 8.31490527e+03 8.19644922e+03 8.49242578e+03 8.53367285e+03 8.33804883e+03 8.51534961e+03 8.39555664e+03 8.58149121e+03 8.83494141e+03 8.53516797e+03 8.63695605e+03 8.87064355e+03 8.80972754e+03 8.66627051e+03 8.68987988e+03 9.13443359e+03 9.36586621e+03 8.87496875e+03 8.84776562e+03 9.22723535e+03 9.22622461e+03 9.34415234e+03 9.10484473e+03 9.09353320e+03 9.39849609e+03 9.64158691e+03 9.56812598e+03 9.39890918e+03 9.42563965e+03 9.59713477e+03 9.81696875e+03 9.54584668e+03 9.47192676e+03 9.58737598e+03 9.60148926e+03 9.91044141e+03 1.02232266e+04 1.00753926e+04 9.74722168e+03 9.74686133e+03 1.02196338e+04 1.04383740e+04 9.96147754e+03 1.01579111e+04 1.05361680e+04 1.01229102e+04 1.01852812e+04 1.01523457e+04 1.02778467e+04 1.07389287e+04 1.05923008e+04 1.03173086e+04 1.06939121e+04 1.07215029e+04 1.04499844e+04 1.06569150e+04 1.08197021e+04 1.08446641e+04 1.05830547e+04 1.05494170e+04 1.09511396e+04 1.11546025e+04 1.10167090e+04 1.08240918e+04 1.08364189e+04 1.12188779e+04 1.13971738e+04 1.09696924e+04 1.09841953e+04 1.11348350e+04 1.14287666e+04 1.14799395e+04 1.11136377e+04 1.11904395e+04 1.15685498e+04 1.16354072e+04 1.13924785e+04 1.15374502e+04 1.16268584e+04 1.14440137e+04 1.18743535e+04 1.20636504e+04 1.15604023e+04 1.12359893e+04 1.15548770e+04 1.18272803e+04 1.18883281e+04 1.18943623e+04 1.17279053e+04 1.17490039e+04 1.21841973e+04 1.23040811e+04 1.18231934e+04 1.18208076e+04 1.21670957e+04 1.25099336e+04 1.22654023e+04 1.18919111e+04 1.21288359e+04 1.22340625e+04 1.22703271e+04 1.22697412e+04 1.24085635e+04 1.23651338e+04 1.21926523e+04 1.23994033e+04 1.25539473e+04 1.24899131e+04 1.22182695e+04 1.22891348e+04 1.26120332e+04 1.26431270e+04 1.25054150e+04 1.24717344e+04 1.26025244e+04 1.29915420e+04 1.30297412e+04 1.25356680e+04 1.26985332e+04 1.28899512e+04 1.28764365e+04 1.27720596e+04 1.26469971e+04 1.29454453e+04 1.30477910e+04 1.27264805e+04 1.24632119e+04 1.29179990e+04 1.33218730e+04 1.31491973e+04 1.31405225e+04 1.30522773e+04 1.31865645e+04 1.28911104e+04 1.25061621e+04 1.30034395e+04 1.33126240e+04 1.32864551e+04 1.32673359e+04 1.29040625e+04 1.30446592e+04 1.33200254e+04 1.35344854e+04 1.36161514e+04 1.32674316e+04 1.30895293e+04 1.29410801e+04 1.33326221e+04 1.37249043e+04 1.35835186e+04 1.34346279e+04 1.28740518e+04 1.31748740e+04 1.37272656e+04 1.34313252e+04 1.35854062e+04 1.33874033e+04 1.33033848e+04 1.37070059e+04 1.34059502e+04 1.32759502e+04 1.37526348e+04 1.38665479e+04 1.33928496e+04 1.30480537e+04 1.33046914e+04 1.35251133e+04 1.39056885e+04 1.42032510e+04 1.36996113e+04 1.33673496e+04 1.32184951e+04 1.36032363e+04 1.41065342e+04 1.38071953e+04 1.34254043e+04 1.31844902e+04 1.33760967e+04 1.38609697e+04 1.41379922e+04 1.38926514e+04 1.36545713e+04 1.38577158e+04 1.36176689e+04 1.32042754e+04 1.35655781e+04 1.38453506e+04 1.38988818e+04 1.42167168e+04 1.36101396e+04 1.31542607e+04 1.35902695e+04 1.40565605e+04 1.41416172e+04 1.36230898e+04 1.35077783e+04 1.34815205e+04 1.36886279e+04 1.41113916e+04 1.40064160e+04 1.37654121e+04 1.34219014e+04 1.36849570e+04 1.37647695e+04 1.33289893e+04 1.35462510e+04 1.38870176e+04 1.38590322e+04 1.37153486e+04 1.34240879e+04 1.36166191e+04 1.39296484e+04 1.38853994e+04 1.39297188e+04 1.33954814e+04 1.31972832e+04 1.35663486e+04 1.38941162e+04 1.40778408e+04 1.37627363e+04 1.35571660e+04 1.32642158e+04 1.35094766e+04 1.40491367e+04 1.37094180e+04 1.35547080e+04 1.35967490e+04 1.34474551e+04 1.32961309e+04 1.34085420e+04 1.36504619e+04 1.37313086e+04 1.37401064e+04 1.34268682e+04 1.31177617e+04 1.33539102e+04 1.35143643e+04 1.35813525e+04 1.37023135e+04 1.33904463e+04 1.33609873e+04 1.32321494e+04 1.33664180e+04 1.38205215e+04 1.34015391e+04 1.32588828e+04 1.32036494e+04 1.28318662e+04 1.30976494e+04 1.37907344e+04 1.36201855e+04 1.30794043e+04 1.32208516e+04 1.30925078e+04 1.27267217e+04 1.30451875e+04 1.32670303e+04 1.32191982e+04 1.32705039e+04 1.28192998e+04 1.27967852e+04 1.31657803e+04 1.32648906e+04 1.35860938e+04 1.31826367e+04 1.25112314e+04 1.24586943e+04 1.29417539e+04 1.31442822e+04 1.30687090e+04 1.28856357e+04 1.23399512e+04 1.25994668e+04 1.31547002e+04 1.28523086e+04 1.26959062e+04 1.24606211e+04 1.25182588e+04 1.28607422e+04 1.24118193e+04 1.23885615e+04 1.29877002e+04 1.29260371e+04 1.26241201e+04 1.22945645e+04 1.18571582e+04 1.21781406e+04 1.26860938e+04 1.29335420e+04 1.25996748e+04 1.19406855e+04 1.17897432e+04 1.21967705e+04 1.24532803e+04 1.22427236e+04 1.21440781e+04 1.18535107e+04 1.18677129e+04 1.21569893e+04 1.22700479e+04 1.22287314e+04 1.19864658e+04 1.20669131e+04 1.18754141e+04 1.14935840e+04 1.17242227e+04 1.19151240e+04 1.19327168e+04 1.21207998e+04 1.16138428e+04 1.13151045e+04 1.16212939e+04 1.17514102e+04 1.19856426e+04 1.17301670e+04 1.12109766e+04 1.11055117e+04 1.14160977e+04 1.17633311e+04 1.18107500e+04 1.14075859e+04 1.10510801e+04 1.10622695e+04 1.10281689e+04 1.10602461e+04 1.12817832e+04 1.13257041e+04 1.11202412e+04 1.08177666e+04 1.06968604e+04 1.09026270e+04 1.11621045e+04 1.11124365e+04 1.11097832e+04 1.07052402e+04 1.03265439e+04 1.05157646e+04 1.08117373e+04 1.09629756e+04 1.08158320e+04 1.03119736e+04 1.01252412e+04 1.03580254e+04 1.07104248e+04 1.05404785e+04 1.04139004e+04 1.02553242e+04 9.97882031e+03 1.02078750e+04 1.03162930e+04 1.01416143e+04 1.00393477e+04 1.01335352e+04 1.00919873e+04 9.85059570e+03 9.89069336e+03 9.88757617e+03 1.00404961e+04 9.94471875e+03 9.56811426e+03 9.58934961e+03 9.51363965e+03 9.59931055e+03 1.00510410e+04 9.71942285e+03 9.25389551e+03 9.16727051e+03 9.25250586e+03 9.54725977e+03 9.86041309e+03 9.45143750e+03 9.07857812e+03 9.26345996e+03 9.57503027e+03 9.85148828e+03 1.07941826e+04 9.44728906e+03 1.33772275e+04 1.20354092e+04 3.98494219e+04 -20669136. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -14942883. 2.15965925e+06 2.54820762e+04 2.02270898e+04 1.24018916e+04 1.02315713e+04 9.15821094e+03 5.13256250e+03 5.82143799e+03 7.71492627e+03 6.48729199e+03 5.84601270e+03 5.28792480e+03 5.76601953e+03 6.29558252e+03 6.28566895e+03 6.01119824e+03 5.97529834e+03 5.91296680e+03 5.80085449e+03 6.04598730e+03 5.95229346e+03 5.64566699e+03 5.58378613e+03 5.61822266e+03 5.55875391e+03 5.40550879e+03 5.36593555e+03 5.47446875e+03 5.60151562e+03 5.56115771e+03 5.25705859e+03 4.95018945e+03 5.04891748e+03 5.29000391e+03 5.37112207e+03 5.11582812e+03 4.82287646e+03 4.77229248e+03 4.94111084e+03 5.16603613e+03 4.94648926e+03 4.64660742e+03 4.58152490e+03 4.78533887e+03 4.73374023e+03 4.59774463e+03 4.56356885e+03 4.46460156e+03 4.51091211e+03 4.48679688e+03 4.23804932e+03 4.19905176e+03 4.37485596e+03 4.45220801e+03 4.30262891e+03 4.05523706e+03 3.90066968e+03 4.08046948e+03 4.27168457e+03 4.12177881e+03 3.87256665e+03 3.72450146e+03 3.65899243e+03 3.82643970e+03 3.98345264e+03 3.83554224e+03 3.71982056e+03 3.62193677e+03 3.49817822e+03 3.52426074e+03 3.57540991e+03 3.43608716e+03 3.35210986e+03 3.45012256e+03 3.35203320e+03 3.17061646e+03 3.17721826e+03 3.30284839e+03 3.31415381e+03 3.20557227e+03 3.09287549e+03 2.97069458e+03 2.90861450e+03 3.01059961e+03 3.11805664e+03 2.95821631e+03 2.74859131e+03 2.71703101e+03 2.79306958e+03 2.87158154e+03 2.82423657e+03 2.64130542e+03 2.57496631e+03 2.62052783e+03 2.56782886e+03 2.51152441e+03 2.48884790e+03 2.43742529e+03 2.42689844e+03 2.38826294e+03 2.28320386e+03 2.27226929e+03 2.29966821e+03 2.29380713e+03 2.26403320e+03 2.17573730e+03 2.06355078e+03 2.04379260e+03 2.12732324e+03 2.10411230e+03 1.98276123e+03 1.89067432e+03 1.84177075e+03 1.89592163e+03 1.97526746e+03 1.87963000e+03 1.74529333e+03 1.71969031e+03 1.73098792e+03 1.70048206e+03 1.63052368e+03 1.61627991e+03 1.63615625e+03 1.62352246e+03 1.54405029e+03 1.46871692e+03 1.44252319e+03 1.48003235e+03 1.50233655e+03 1.43449731e+03 1.35770508e+03 1.30819458e+03 1.26015637e+03 1.28001123e+03 1.32272986e+03 1.25350012e+03 1.16243872e+03 1.13237427e+03 1.15413379e+03 1.17427466e+03 1.11560229e+03 1.05650916e+03 1.03247681e+03 1.01856042e+03 1.00243750e+03 9.77260742e+02 9.26919006e+02 8.91309998e+02 9.09229858e+02 9.01322754e+02 8.41237671e+02 8.03758484e+02 7.96083740e+02 7.93055542e+02 7.93230957e+02 7.54446838e+02 6.89557617e+02 6.74780518e+02 6.86286743e+02 6.68471252e+02 6.33362610e+02 6.04723999e+02 5.86884949e+02 5.72331909e+02 5.61682861e+02 5.36702393e+02 5.08074097e+02 5.05608978e+02 4.97147217e+02 4.66503082e+02 4.39027344e+02 4.21411163e+02 4.18366394e+02 4.13589508e+02 3.95312836e+02 3.68064392e+02 3.40738922e+02 3.24104553e+02 3.24612915e+02 3.25641663e+02 2.99908203e+02 2.71477356e+02 2.57586884e+02 2.53001251e+02 2.49385452e+02 2.35372742e+02 2.16480545e+02 2.02219162e+02 1.92535126e+02 1.81009552e+02 1.70429916e+02 1.62491806e+02 1.51140854e+02 1.41734650e+02 1.32698425e+02 1.20204781e+02 1.12145782e+02 1.06855095e+02 9.99108963e+01 9.15040970e+01 8.03204346e+01 7.15246658e+01 6.83233337e+01 6.45784302e+01 5.72941628e+01 4.97002831e+01 4.28697319e+01 3.72496872e+01 3.43346939e+01 3.15500736e+01 2.64673901e+01 2.12336922e+01 1.75990448e+01 1.49882622e+01 1.23286991e+01 9.84671593e+00 7.65054560e+00 5.72405243e+00 4.20473671e+00 3.02016878e+00 2.17426682e+00 1.70124745e+00 1.55161738e+00 1.73668158e+00 2.27589154e+00 3.11687875e+00 4.13836479e+00 5.58806992e+00 7.63246679e+00 1.01061077e+01 1.26029520e+01 1.51267910e+01 1.86986065e+01 2.24352646e+01 2.52872276e+01 2.84652596e+01 3.36296692e+01 4.03036079e+01 4.66661873e+01 5.17338028e+01 5.46626015e+01 5.88205070e+01 6.65470352e+01 7.72087708e+01 8.72305374e+01 9.28576736e+01 9.50058289e+01 1.03118973e+02 1.19000107e+02 1.26800056e+02 1.30203232e+02 1.40041336e+02 1.49990112e+02 1.60583664e+02 1.77550415e+02 1.84365082e+02 1.89117371e+02 2.04434036e+02 2.11346176e+02 2.30798477e+02 2.49963852e+02 2.48194046e+02 2.66002045e+02 2.88336609e+02 2.95486176e+02 3.09403931e+02 3.22627960e+02 3.36919250e+02 3.56653748e+02 3.69453125e+02 3.74220734e+02 3.89074188e+02 4.24718475e+02 4.55344452e+02 4.61010651e+02 4.56227814e+02 4.62904175e+02 4.92450073e+02 5.32930237e+02 5.64028687e+02 5.66610291e+02 5.59544250e+02 5.87022278e+02 6.22835022e+02 6.33221313e+02 6.53630493e+02 6.76786804e+02 6.92329590e+02 7.14145996e+02 7.65967163e+02 7.67547668e+02 7.59080139e+02 8.02187195e+02 8.08678772e+02 8.62381958e+02 8.97029480e+02 8.88813965e+02 9.52260681e+02 9.57780090e+02 9.28060852e+02 9.86726196e+02 1.00275854e+03 1.03628638e+03 1.13627856e+03 1.10992554e+03 1.06915125e+03 1.11435742e+03 1.19027271e+03 1.27131116e+03 1.27724536e+03 1.22147339e+03 1.21688904e+03 1.28475537e+03 1.36615332e+03 1.43560559e+03 1.44888086e+03 1.40616199e+03 1.41946301e+03 1.48728040e+03 1.54046411e+03 1.54054541e+03 1.56013208e+03 1.60075134e+03 1.63294434e+03 1.71820984e+03 1.74803845e+03 1.69591113e+03 1.72618982e+03 1.77453320e+03 1.81824316e+03 1.88139758e+03 1.90033606e+03 1.97808191e+03 1.97460132e+03 1.93177869e+03 2.01183301e+03 2.00688733e+03 2.09733789e+03 2.27400073e+03 2.18516650e+03 2.07226489e+03 2.17545850e+03 2.30057764e+03 2.40091992e+03 2.47023291e+03 2.35795508e+03 2.28235107e+03 2.37296362e+03 2.53843042e+03 2.66917285e+03 2.64350830e+03 2.52055249e+03 2.53642700e+03 2.66165015e+03 2.75392407e+03 2.87380420e+03 2.88927173e+03 2.75984082e+03 2.78330713e+03 2.94350244e+03 3.02283691e+03 2.95504102e+03 2.96243042e+03 3.06493628e+03 3.07266528e+03 3.23595239e+03 3.28660840e+03 3.14916797e+03 3.19752539e+03 3.31364844e+03 3.35481982e+03 3.40784521e+03 3.39645459e+03 3.51322266e+03 3.61589526e+03 3.56950317e+03 3.53123364e+03 3.48681641e+03 3.65913892e+03 3.91698853e+03 3.90530811e+03 3.74149463e+03 3.66215918e+03 3.83167749e+03 4.11109082e+03 4.04573145e+03 3.88328271e+03 3.98339355e+03 4.14506738e+03 4.26501270e+03 4.43718066e+03 4.39597998e+03 4.18991113e+03 4.12006348e+03 4.27850391e+03 4.58409473e+03 4.61024805e+03 4.50899414e+03 4.54198535e+03 4.57031641e+03 4.73769141e+03 4.76177539e+03 4.64860693e+03 4.71485596e+03 4.66467285e+03 4.92690430e+03 5.12581152e+03 4.93989551e+03 4.99960303e+03 5.11728857e+03 5.25447852e+03 5.14109082e+03 4.96339209e+03 5.22175781e+03 5.57075342e+03 5.47052051e+03 5.20408984e+03 5.34284668e+03 5.65878320e+03 5.68427002e+03 5.62879053e+03 5.65349756e+03 5.49290918e+03 5.52446387e+03 5.95432715e+03 6.00405225e+03 5.79638428e+03 5.69011328e+03 5.72906885e+03 6.03503174e+03 6.34075195e+03 6.12646533e+03 6.06550781e+03 6.16668994e+03 6.19319727e+03 6.47903857e+03 6.52577881e+03 6.25553613e+03 6.26030029e+03 6.43212109e+03 6.53939990e+03 6.61627197e+03 6.63527344e+03 6.80220850e+03 6.78648096e+03 6.54827490e+03 6.77458936e+03 6.77995117e+03 7.00734473e+03 7.51767822e+03 7.31630811e+03 6.86850977e+03 6.91509277e+03 7.66468848e+03 8.61581836e+03 8.60516016e+03 1.29735879e+04 2.06257891e+04 2.29181133e+04 11029614. 16265572. 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. 0. 0. 0. 0. 0. 0. 0. 0. 25327272. -3.24093775e+06 9.15333375e+05 1.22494488e+06 2.85477109e+04 2.44435586e+04 1.59446738e+04 1.44118154e+04 1.48329980e+04 1.48051123e+04 1.43945283e+04 1.47392988e+04 1.47832100e+04 1.46996387e+04 1.48984678e+04 1.49006777e+04 1.50052715e+04 1.25759141e+04 1.32570889e+04 1.09221279e+04 1.00088193e+04 9.98213281e+03 1.03621045e+04 1.04734404e+04 1.00428496e+04 1.00718867e+04 1.06488398e+04 1.07292559e+04 1.04873887e+04 1.04568486e+04 1.04692520e+04 1.05841973e+04 1.05647139e+04 1.05904453e+04 1.07275449e+04 1.06637305e+04 1.05161455e+04 1.05616191e+04 1.10413516e+04 1.11012197e+04 1.08863555e+04 1.09138896e+04 1.09790791e+04 1.10553398e+04 1.10329912e+04 1.10407695e+04 1.10852949e+04 1.08873262e+04 1.09452627e+04 1.11568438e+04 1.11563535e+04 1.16355176e+04 1.17851934e+04 1.14031787e+04 1.10941133e+04 1.10409805e+04 1.17855137e+04 1.20130098e+04 1.15660928e+04 1.13693203e+04 1.15222803e+04 1.16355947e+04 1.14912754e+04 1.20082227e+04 1.20355996e+04 1.13687383e+04 1.13675752e+04 1.19783955e+04 1.24845693e+04 1.21795205e+04 1.19519141e+04 1.20726152e+04 1.19679775e+04 1.18980166e+04 1.20329121e+04 1.22154346e+04 1.21927988e+04 1.19911816e+04 1.19886162e+04 1.22450391e+04 1.22428877e+04 1.25471484e+04 1.24235527e+04 1.20962109e+04 1.23599004e+04 1.23970127e+04 1.26554619e+04 1.27994287e+04 1.25486396e+04 1.25176807e+04 1.22845801e+04 1.20755195e+04 1.26940479e+04 1.28546885e+04 1.22129688e+04 1.23707334e+04 1.30993438e+04 1.34602627e+04 1.31268926e+04 1.27610283e+04 1.27048369e+04 1.27547705e+04 1.26957334e+04 1.26584795e+04 1.29617627e+04 1.29131914e+04 1.31308828e+04 1.30704189e+04 1.27930811e+04 1.30236982e+04 1.27048047e+04 1.29634580e+04 1.37427959e+04 1.34514658e+04 1.31125547e+04 1.27777998e+04 1.27219736e+04 1.35111953e+04 1.36208750e+04 1.32042910e+04 1.28290938e+04 1.29084414e+04 1.32541494e+04 1.31789014e+04 1.36341719e+04 1.37882217e+04 1.33601943e+04 1.30921680e+04 1.31229248e+04 1.36603984e+04 1.37038672e+04 1.33754648e+04 1.30901689e+04 1.31498398e+04 1.34997441e+04 13105. 1.32615928e+04 1.41644873e+04 1.39574248e+04 1.35376514e+04 1.31747422e+04 1.31088564e+04 1.39756357e+04 1.40495859e+04 1.35965195e+04 1.32011201e+04 1.31073838e+04 1.36345938e+04 1.36695693e+04 1.35771924e+04 1.32659707e+04 1.35504961e+04 1.41366211e+04 1.37654092e+04 1.38688047e+04 1.39860576e+04 1.37411533e+04 1.34016660e+04 1.33904238e+04 1.37169893e+04 1.37115498e+04 1.37793604e+04 1.33300859e+04 1.34845518e+04 1.44410176e+04 1.37898359e+04 1.32802480e+04 1.36739678e+04 1.36975332e+04 1.41059121e+04 1.38613896e+04 1.33267617e+04 1.39808633e+04 1.41212031e+04 1.37842451e+04 1.37129434e+04 1.36198975e+04 1.34731709e+04 1.34883818e+04 1.37434404e+04 1.33804092e+04 1.36239443e+04 1.44581602e+04 1.41873418e+04 1.35186904e+04 1.30341670e+04 1.34832314e+04 1.43696748e+04 1.41013271e+04 1.37037607e+04 1.34269502e+04 1.33112256e+04 1.36907461e+04 1.37049258e+04 1.39689346e+04 1.37051963e+04 1.32829502e+04 1.36628223e+04 1.36679795e+04 1.39068027e+04 1.38395303e+04 1.35265840e+04 1.34344502e+04 1.33842822e+04 1.36459717e+04 1.32982988e+04 1.35238398e+04 1.42738164e+04 1.39117480e+04 1.35495762e+04 1.31828135e+04 1.31062344e+04 1.38350986e+04 1.39051826e+04 1.35365479e+04 1.30896396e+04 1.30735947e+04 1.35040146e+04 1.34819121e+04 1.38166279e+04 1.37282529e+04 1.33821553e+04 1.29744346e+04 1.28996113e+04 1.37173252e+04 1.35943271e+04 1.32063457e+04 1.30164854e+04 1.29400938e+04 1.35889561e+04 1.36533457e+04 1.29466914e+04 1.28148066e+04 1.34650176e+04 1.35363408e+04 1.28134912e+04 1.27402393e+04 1.34289932e+04 1.34369785e+04 1.29825557e+04 1.26645781e+04 1.26361338e+04 1.33915918e+04 1.32947012e+04 1.27924648e+04 1.27655332e+04 1.27104600e+04 1.28590176e+04 1.29041816e+04 1.27673652e+04 1.24225459e+04 1.26969219e+04 1.32081064e+04 1.28408848e+04 1.29624834e+04 1.29567754e+04 1.26807090e+04 1.26891162e+04 1.26086846e+04 1.25019658e+04 1.22589746e+04 1.21845156e+04 1.24291738e+04 1.25016055e+04 1.28504209e+04 1.23886367e+04 1.19844746e+04 1.23873633e+04 1.23934199e+04 1.26759902e+04 1.24994434e+04 1.20968682e+04 1.20553438e+04 1.19692881e+04 1.21387266e+04 1.21997588e+04 1.24033643e+04 1.22093203e+04 1.18632061e+04 1.19246924e+04 1.15286621e+04 1.19024883e+04 1.25773203e+04 1.22466553e+04 1.18351230e+04 1.15061768e+04 1.13241445e+04 1.18589229e+04 1.21860303e+04 1.18461787e+04 1.13279873e+04 1.12673711e+04 1.16019229e+04 1.14946533e+04 1.17223115e+04 1.15784365e+04 1.11892480e+04 1.14005791e+04 1.13225068e+04 1.15628359e+04 1.15487207e+04 1.09472080e+04 1.09099229e+04 1.14559336e+04 1.12186924e+04 1.06152012e+04 1.09728770e+04 1.15093320e+04 1.12806562e+04 1.09587832e+04 1.06446387e+04 1.06022393e+04 1.11291963e+04 1.10567021e+04 1.07262910e+04 1.04415029e+04 1.03185898e+04 1.06531455e+04 1.06305225e+04 1.05050146e+04 1.02416240e+04 1.04863193e+04 1.07076846e+04 1.04305234e+04 1.05896768e+04 1.03645098e+04 1.00592480e+04 1.02139375e+04 1.02235430e+04 1.01420186e+04 1.00500439e+04 9.91517871e+03 9.65960254e+03 9.97403027e+03 1.05186865e+04 9.86771777e+03 9.37114453e+03 9.65007129e+03 9.90703711e+03 1.01057139e+04 9.82119238e+03 9.50206152e+03 9.72204102e+03 9.64784766e+03 9.23487109e+03 9.07860840e+03 9.59975684e+03 9.54062207e+03 9.20573730e+03 9.13808691e+03 8.80846387e+03 9.09429883e+03 9.64348047e+03 9.28953320e+03 8.97736426e+03 8.66817090e+03 8.53938867e+03 8.98441406e+03 9.38383398e+03 9.06574902e+03 8.54935352e+03 8.47105371e+03 8.57544336e+03 8.60644922e+03 8.81917383e+03 8.53154102e+03 8.21250000e+03 8.41696777e+03 8.32890039e+03 8.53238379e+03 8.42412988e+03 8.07829541e+03 8.23819043e+03 8.19631641e+03 8.11154150e+03 7.82004102e+03 7.87044141e+03 8.30689551e+03 8.14115869e+03 7.78030908e+03 7.52816064e+03 7.65758008e+03 8.05388867e+03 7.85765674e+03 7.63656494e+03 7.39705273e+03 7.28437305e+03 7.50712158e+03 7.50732471e+03 7.40636523e+03 7.19025098e+03 7.25601660e+03 7.48874121e+03 7.20288867e+03 7.28820898e+03 7.28059912e+03 7.04833838e+03 7.01763574e+03 6.92794189e+03 6.86709326e+03 6.81243115e+03 6.70807520e+03 6.64883301e+03 6.86717627e+03 6.84053467e+03 6.39818408e+03 6.35125732e+03 6.43322314e+03 6.55741797e+03 6.76494580e+03 6.49116602e+03 6.05775879e+03 6.30083643e+03 6.53716260e+03 6.31564844e+03 6.00402100e+03 5.94389404e+03 6.00229785e+03 5.97979834e+03 5.99108691e+03 5.73953174e+03 5.83821631e+03 6.09150049e+03 5.88467627e+03 5.67824951e+03 5.52439160e+03 5.53691943e+03 5.74866797e+03 5.68130225e+03 5.46939502e+03 5.34016162e+03 5.11674658e+03 5.19312939e+03 5.42785791e+03 5.54911475e+03 5.21186475e+03 4.96340918e+03 5.06359766e+03 5.10925781e+03 5.23816895e+03 5.05916553e+03 4.82252051e+03 4.91044336e+03 4.85553564e+03 4.71447021e+03 4.58769678e+03 4.67266309e+03 4.84772119e+03 4.70471777e+03 4.55846094e+03 4.44494092e+03 4.37761670e+03 4.55811328e+03 4.50776221e+03 4.34797021e+03 4.19039355e+03 4.10847803e+03 4.16819385e+03 4.12778516e+03 4.23410303e+03 4.23702881e+03 3.97528491e+03 3.85711426e+03 3.94048950e+03 4.06495947e+03 3.92108936e+03 3.79806982e+03 3.72776953e+03 3.69577759e+03 3.62366357e+03 3.51968774e+03 3.61793384e+03 3.63698169e+03 3.49611328e+03 3.52617065e+03 3.50927173e+03 3.43561646e+03 3.38515234e+03 3.31152368e+03 3.26425610e+03 3.15703564e+03 3.08706079e+03 3.17541235e+03 3.20285522e+03 3.02591699e+03 2.87999487e+03 2.94476660e+03 3.06999585e+03 3.03546655e+03 2.84352539e+03 2.69586694e+03 2.81101978e+03 2.86890723e+03 2.76383374e+03 2.69930640e+03 2.57586914e+03 2.45006860e+03 2.51506763e+03 2.62966187e+03 2.60160547e+03 2.42049268e+03 2.29378638e+03 2.40364551e+03 2.46934985e+03 2.35295630e+03 2.20361304e+03 2.11959741e+03 2.16498730e+03 2.16069531e+03 2.18462109e+03 2.17911963e+03 2.07258350e+03 1.98781445e+03 1.96098401e+03 2.01435669e+03 1.93195361e+03 1.83610669e+03 1.89023425e+03 1.85771448e+03 1.80276733e+03 1.73058594e+03 1.69684595e+03 1.75908472e+03 1.67166418e+03 1.55874170e+03 1.57821887e+03 1.60814294e+03 1.58037939e+03 1.51216125e+03 1.52107629e+03 1.50453638e+03 1.43083398e+03 1.35608606e+03 1.32429871e+03 1.37627307e+03 1.31991406e+03 1.25163599e+03 1.26033191e+03 1.23033032e+03 1.19679248e+03 1.15653455e+03 1.15847766e+03 1.14383179e+03 1.08565930e+03 1.07766089e+03 1.05428540e+03 1.03277014e+03 1.01136975e+03 9.73416992e+02 9.28636414e+02 8.80362793e+02 8.59889893e+02 8.83722290e+02 9.03558228e+02 8.32771912e+02 7.57999084e+02 7.64551208e+02 7.89706299e+02 7.74050598e+02 7.14666138e+02 6.63521851e+02 6.75649780e+02 6.70018005e+02 6.27310303e+02 6.30637451e+02 6.02681946e+02 5.49016602e+02 5.44078735e+02 5.56779541e+02 5.38591248e+02 4.94134552e+02 4.58374695e+02 4.62070648e+02 4.73381287e+02 4.44120209e+02 4.05470001e+02 3.80389404e+02 3.83243530e+02 3.80223724e+02 3.53830353e+02 3.35095093e+02 3.21586945e+02 3.08683228e+02 2.93333221e+02 2.87392090e+02 2.69328705e+02 2.47047348e+02 2.40473251e+02 2.29743057e+02 2.22141220e+02 2.05521103e+02 1.89097366e+02 1.85856689e+02 1.69637482e+02 1.55071487e+02 1.52047241e+02 1.45450272e+02 1.34712433e+02 1.22724960e+02 1.17843964e+02 1.09263535e+02 9.63646393e+01 8.72152939e+01 8.09472809e+01 8.30273132e+01 7.67785416e+01 7.18419037e+01 6.42101669e+01 1.60023773e+02 9.50668152e+02 8916332. 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. 18121824. 5.52762024e+02 9.13901520e+01 5.35913048e+01 4.97058678e+01 5.03963852e+01 5.23369637e+01 5.73541756e+01 6.29450188e+01 6.95289688e+01 7.54500427e+01 8.05671387e+01 9.03700104e+01 1.01049156e+02 1.06156822e+02 1.13365135e+02 1.24793777e+02 1.35657379e+02 1.45499161e+02 1.50951187e+02 1.56575500e+02 1.69769791e+02 1.85586151e+02 1.97910904e+02 2.07761063e+02 2.15050018e+02 2.26963150e+02 2.48133682e+02 2.66410675e+02 2.70856903e+02 2.72741913e+02 2.90048126e+02 3.13739441e+02 3.23978302e+02 3.37824371e+02 3.56425964e+02 3.62256927e+02 3.84656616e+02 4.09263489e+02 4.08678406e+02 4.24456818e+02 4.54929138e+02 4.89217102e+02 5.10785522e+02 4.94038055e+02 4.94829498e+02 5.27025635e+02 5.67642700e+02 5.95435425e+02 5.93034790e+02 6.10985352e+02 6.50802673e+02 6.65686890e+02 6.83306274e+02 6.93822449e+02 6.93965332e+02 7.41258911e+02 7.85623352e+02 7.81155823e+02 8.00053345e+02 8.38930786e+02 8.51728943e+02 8.87651184e+02 9.15871643e+02 9.12000061e+02 9.31718872e+02 9.71529175e+02 1.03115283e+03 1.05020874e+03 1.03250293e+03 1.06789026e+03 1.09254187e+03 1.12824463e+03 1.18108350e+03 1.16511755e+03 1.18014709e+03 1.24062012e+03 1.29055640e+03 1.32557544e+03 1.31153638e+03 1.29872046e+03 1.34275317e+03 1.41370618e+03 1.46490747e+03 1.49033789e+03 1.48896948e+03 1.50544409e+03 1.56961560e+03 1.62410706e+03 1.61686548e+03 1.59744922e+03 1.65387573e+03 1.74613782e+03 1.79758813e+03 1.78627124e+03 1.76930920e+03 1.78264734e+03 1.87748572e+03 1.95118140e+03 1.91301147e+03 1.94483411e+03 2.03821631e+03 2.11221729e+03 2.14663623e+03 2.06942896e+03 2.04726978e+03 2.15631665e+03 2.23600269e+03 2.25231787e+03 2.27738599e+03 2.33948633e+03 2.41129834e+03 2.39147241e+03 2.41036133e+03 2.49317017e+03 2.48474634e+03 2.49911719e+03 2.59828833e+03 2.66157935e+03 2.70519727e+03 2.69700342e+03 2.64728882e+03 2.72186621e+03 2.83356982e+03 2.91068555e+03 2.91376099e+03 2.87809473e+03 2.95501025e+03 3.07673071e+03 3.13843579e+03 3.06493799e+03 3.01566797e+03 3.10344238e+03 3.22941479e+03 3.28844556e+03 3.27790234e+03 3.28988184e+03 3.34127515e+03 3.46601929e+03 3.52709106e+03 3.51541968e+03 3.52942163e+03 3.52221240e+03 3.61074365e+03 3.65363086e+03 3.65138892e+03 3.71286768e+03 3.77062891e+03 3.91693384e+03 4.01964111e+03 3.91144141e+03 3.86364429e+03 3.97321045e+03 4.08136011e+03 4.17845654e+03 4.19654199e+03 4.06112646e+03 4.10895801e+03 4.35294189e+03 4.51120752e+03 4.38821240e+03 4.25587402e+03 4.37530566e+03 4.59415332e+03 4.62801025e+03 4.42899805e+03 4.49953467e+03 4.68969238e+03 4.76892090e+03 4.79374902e+03 4.87179736e+03 4.92003760e+03 4.78122070e+03 4.95106689e+03 5.12028418e+03 4.94946289e+03 5.02116504e+03 5.14962988e+03 5.21479883e+03 5.37188574e+03 5.26507129e+03 5.13637744e+03 5.23332959e+03 5.40353418e+03 5.70039697e+03 5.69349756e+03 5.39661963e+03 5.49575244e+03 5.83228174e+03 5.75227832e+03 5.54208301e+03 5.62252783e+03 5.81592236e+03 6.03077832e+03 6.06238965e+03 6.05505566e+03 5.95276367e+03 5.89565527e+03 6.12283301e+03 6.29332812e+03 6.14609668e+03 6.17459717e+03 6.39606885e+03 6.52083105e+03 6.56272656e+03 6.40441846e+03 6.30706738e+03 6.43088232e+03 6.57327441e+03 6.85100342e+03 6.88668359e+03 6.59924561e+03 6.64971191e+03 6.92031152e+03 7.00511328e+03 7.01021533e+03 6.81987207e+03 6.94075928e+03 7.15475635e+03 7.28737061e+03 7.28434814e+03 7.13803369e+03 7.10711035e+03 7.29362451e+03 7.50268457e+03 7.34512109e+03 7.46760986e+03 7.63875049e+03 7.62153467e+03 7.84734814e+03 7.61633398e+03 7.49340234e+03 7.73892285e+03 7.80715967e+03 7.96708057e+03 7.82977539e+03 7.66156299e+03 7.98372656e+03 8.34346680e+03 8.21276367e+03 8.11059863e+03 8.19249609e+03 8.14218848e+03 8.12699316e+03 8.41046289e+03 8.70360059e+03 8.53637012e+03 8.29588770e+03 8.57916602e+03 8.54713379e+03 8.66373340e+03 8.69166016e+03 8.44938184e+03 8.72351172e+03 8.99434766e+03 8.73618848e+03 8.68954590e+03 8.84729297e+03 9.17730859e+03 9.39819531e+03 8.87025684e+03 8.87407324e+03 9.23608496e+03 9.34445508e+03 9.51289941e+03 9.23895801e+03 9.23244531e+03 9.25731738e+03 9.36643262e+03 9.77295996e+03 9.64064453e+03 9.31983008e+03 9.60925879e+03 9.91600684e+03 9.63375391e+03 9.58012207e+03 9.56473340e+03 9.57118262e+03 1.00101084e+04 1.02248574e+04 9.95313770e+03 9.81443945e+03 9.96416992e+03 1.01819346e+04 1.04158818e+04 1.01065400e+04 1.03372178e+04 1.04416152e+04 1.00342539e+04 1.01351104e+04 1.02853643e+04 1.03958037e+04 1.06594082e+04 1.05164336e+04 1.05062695e+04 1.08274180e+04 1.06073682e+04 1.04465000e+04 1.07113301e+04 1.09407080e+04 1.09282246e+04 1.05788682e+04 1.06019033e+04 1.11813496e+04 1.13122002e+04 1.08787852e+04 1.08102939e+04 1.09710449e+04 1.13056230e+04 1.14658799e+04 1.10989775e+04 1.10846943e+04 1.11140752e+04 1.13713350e+04 1.15543730e+04 1.12623037e+04 1.13268809e+04 1.14123896e+04 1.14147373e+04 1.16222490e+04 1.17939141e+04 1.15498643e+04 1.13434170e+04 1.18764170e+04 1.22883311e+04 1.17044043e+04 1.12825566e+04 1.16299619e+04 1.19653516e+04 1.19932656e+04 1.18322100e+04 1.17330020e+04 1.18702783e+04 1.22328408e+04 1.22981582e+04 1.19884512e+04 1.20166758e+04 1.20296152e+04 1.22898994e+04 1.23911348e+04 1.20442158e+04 1.21471816e+04 1.21920283e+04 1.22390078e+04 1.25031748e+04 1.25333389e+04 1.23064004e+04 1.22233623e+04 1.25303975e+04 1.26718213e+04 1.25026465e+04 1.23042080e+04 1.24225732e+04 1.27532588e+04 1.27916416e+04 1.23745938e+04 1.24289902e+04 1.26679971e+04 1.30665039e+04 1.31556963e+04 1.26697764e+04 1.30045039e+04 1.28895020e+04 1.24354951e+04 1.26061611e+04 1.28037549e+04 1.32024717e+04 1.31630928e+04 1.26320361e+04 1.25283955e+04 1.29728926e+04 1.33972988e+04 1.33573008e+04 1.31676465e+04 1.30926504e+04 1.30073027e+04 1.28715283e+04 1.28410459e+04 1.33255166e+04 1.35009385e+04 1.30330986e+04 1.30665469e+04 1.31675283e+04 1.33277441e+04 1.34778906e+04 1.34552402e+04 1.36870010e+04 1.33413535e+04 1.29186484e+04 1.29769492e+04 1.33809326e+04 1.38090156e+04 1.39132393e+04 1.35122295e+04 1.27952646e+04 1.30685859e+04 1.36222422e+04 1.35101270e+04 1.38191592e+04 1.37480547e+04 1.32352773e+04 1.36552822e+04 1.37421113e+04 1.34256123e+04 1.36255947e+04 1.35444326e+04 1.33443193e+04 1.33137822e+04 1.35067383e+04 1.36000938e+04 1.39462744e+04 1.43812891e+04 1.37470117e+04 1.31806924e+04 1.32923184e+04 1.36357363e+04 1.41075674e+04 1.40387520e+04 1.33962871e+04 1.32762812e+04 1.35928184e+04 1.40087451e+04 1.42030205e+04 1.38221865e+04 1.36784248e+04 1.36669844e+04 1.35887373e+04 1.35361279e+04 1.38787158e+04 1.40587959e+04 1.38550127e+04 1.39754414e+04 1.35366660e+04 1.34816650e+04 1.39081543e+04 1.39547998e+04 1.41393213e+04 1.37428828e+04 1.33526777e+04 1.35298701e+04 1.38519170e+04 1.41737051e+04 1.42655723e+04 1.38299414e+04 1.32559648e+04 1.35276592e+04 1.37486123e+04 1.35391533e+04 1.38692676e+04 1.40831846e+04 1.36608721e+04 1.35441377e+04 1.36249971e+04 1.38988057e+04 1.41025918e+04 1.38539707e+04 1.38524092e+04 1.34195703e+04 1.33024795e+04 1.36907793e+04 1.38281367e+04 1.40557471e+04 1.39672676e+04 1.35661201e+04 1.32934883e+04 1.36075156e+04 1.40649004e+04 1.38609316e+04 1.36459795e+04 1.36651191e+04 1.33872070e+04 1.34494062e+04 1.37159053e+04 1.36674453e+04 1.37134775e+04 1.35130859e+04 1.33397803e+04 1.33323252e+04 1.36793809e+04 1.37332607e+04 1.35398828e+04 1.36451865e+04 1.32944629e+04 1.34111982e+04 1.35803623e+04 1.34320869e+04 1.38056240e+04 1.34878926e+04 1.30188955e+04 1.31008330e+04 1.31043262e+04 1.34339512e+04 1.39685303e+04 1.36607803e+04 1.30787041e+04 1.29707354e+04 1.29874131e+04 1.29831172e+04 1.33360410e+04 1.34928193e+04 1.30579639e+04 1.30236396e+04 1.29213467e+04 1.30688760e+04 1.34124971e+04 1.32268730e+04 1.34727031e+04 1.31679072e+04 1.24363457e+04 1.25856855e+04 1.30689316e+04 1.32466309e+04 1.33256504e+04 1.29108311e+04 1.22120059e+04 1.26049570e+04 1.32647500e+04 1.29951279e+04 1.27352598e+04 1.26817617e+04 1.24860869e+04 1.27106006e+04 1.27251592e+04 1.25271855e+04 1.29365986e+04 1.27404082e+04 1.25343994e+04 1.25449932e+04 1.21588857e+04 1.23073779e+04 1.26039482e+04 1.29166377e+04 1.25382227e+04 1.18313818e+04 1.19411748e+04 1.23495068e+04 1.25160879e+04 1.23991143e+04 1.20549121e+04 1.18683174e+04 1.21054258e+04 1.23046367e+04 1.23165186e+04 1.22323262e+04 1.20354287e+04 1.19232725e+04 1.19339697e+04 1.18445674e+04 1.18934531e+04 1.19570576e+04 1.18728516e+04 1.19559902e+04 1.15992754e+04 1.15571748e+04 1.18452666e+04 1.17011582e+04 1.19844717e+04 1.17251514e+04 1.11271016e+04 1.12026016e+04 1.14771055e+04 1.17501533e+04 1.18973936e+04 1.13961562e+04 1.09737695e+04 1.11004199e+04 1.12780654e+04 1.13087266e+04 1.12931895e+04 1.12965029e+04 1.09802246e+04 1.07804365e+04 1.09091367e+04 1.11412109e+04 1.12570107e+04 1.09944580e+04 1.10440693e+04 1.08210029e+04 1.03639287e+04 1.05971602e+04 1.07738184e+04 1.09053115e+04 1.09074111e+04 1.03207793e+04 1.01800723e+04 1.04672100e+04 1.08062080e+04 1.06779229e+04 1.04149492e+04 1.03328135e+04 9.98220312e+03 1.02445859e+04 1.04717324e+04 1.02204482e+04 1.01019316e+04 1.00848057e+04 1.00805342e+04 1.00279043e+04 9.91339062e+03 9.96861230e+03 9.96788770e+03 9.93731543e+03 9.60912988e+03 9.68091602e+03 9.77254395e+03 9.70005176e+03 9.99659473e+03 9.62391406e+03 9.26367773e+03 9.38306836e+03 9.21380859e+03 9.44727930e+03 9.94194824e+03 9.70159863e+03 9.09170020e+03 9.07376758e+03 9.53004785e+03 1.03218105e+04 1.18132363e+04 1.13401064e+04 1.59116553e+04 2.59126680e+04 1.23087531e+05 43184328. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -40570804. 31519886. 3.14808223e+04 1.98248926e+04 7.91094922e+03 8.25809375e+03 7.45561621e+03 7.07720459e+03 6.78169287e+03 6.34453418e+03 6.38765479e+03 6.66389160e+03 6.57436084e+03 6.24489941e+03 5.97689355e+03 5.95180957e+03 6.25883984e+03 6.41925928e+03 6.12015479e+03 5.86440674e+03 5.76906299e+03 5.81118066e+03 6.00602783e+03 5.99566748e+03 5.73219775e+03 5.59592480e+03 5.54187061e+03 5.56674463e+03 5.56191211e+03 5.41446973e+03 5.37780273e+03 5.56054785e+03 5.63058350e+03 5.30263818e+03 5.00430469e+03 5.07911572e+03 5.28522754e+03 5.40929785e+03 5.13667725e+03 4.81421924e+03 4.81947314e+03 4.99649658e+03 5.18501660e+03 4.92783740e+03 4.60463379e+03 4.58553320e+03 4.74754492e+03 4.79845459e+03 4.75091064e+03 4.63200049e+03 4.45492480e+03 4.43050586e+03 4.51793506e+03 4.34946631e+03 4.21833740e+03 4.40322803e+03 4.39222607e+03 4.29256787e+03 4.11636426e+03 3.91941211e+03 4.10764062e+03 4.27859033e+03 4.13337500e+03 3.84926074e+03 3.69230103e+03 3.71619336e+03 3.90840942e+03 3.99251758e+03 3.83994604e+03 3.71978906e+03 3.60651855e+03 3.48139380e+03 3.54233545e+03 3.61525342e+03 3.46805298e+03 3.40178760e+03 3.41093335e+03 3.38895020e+03 3.26967310e+03 3.20184644e+03 3.28090894e+03 3.27336523e+03 3.24526709e+03 3.10484497e+03 2.95041797e+03 2.92709692e+03 3.05081982e+03 3.13457153e+03 2.94911914e+03 2.74061182e+03 2.74125635e+03 2.80438770e+03 2.85402344e+03 2.82580249e+03 2.67703540e+03 2.61572046e+03 2.58799097e+03 2.57256250e+03 2.57674585e+03 2.50029761e+03 2.44581787e+03 2.40132495e+03 2.38656274e+03 2.36290894e+03 2.29982080e+03 2.28652930e+03 2.27395190e+03 2.26624609e+03 2.18068457e+03 2.04950049e+03 2.05334424e+03 2.13197168e+03 2.13433179e+03 1.99674121e+03 1.87796460e+03 1.85592419e+03 1.92437927e+03 1.98951306e+03 1.87357947e+03 1.75328809e+03 1.74890491e+03 1.71344043e+03 1.69663538e+03 1.68333154e+03 1.63497815e+03 1.63058496e+03 1.58523340e+03 1.54857336e+03 1.52261462e+03 1.45720972e+03 1.46703284e+03 1.48565540e+03 1.44481433e+03 1.37046948e+03 1.30206543e+03 1.27677258e+03 1.29930627e+03 1.32480603e+03 1.24657178e+03 1.15386975e+03 1.14871606e+03 1.17599023e+03 1.18078052e+03 1.11139148e+03 1.05736804e+03 1.04219714e+03 1.01238593e+03 1.00327844e+03 9.89255066e+02 9.25759216e+02 8.97816101e+02 9.07749390e+02 8.98589355e+02 8.59504639e+02 8.21536560e+02 8.00812195e+02 7.88838684e+02 7.92045410e+02 7.53742249e+02 6.87480591e+02 6.78623535e+02 6.83079651e+02 6.69164978e+02 6.45621765e+02 6.05925171e+02 5.83190002e+02 5.75954041e+02 5.69020142e+02 5.48050781e+02 5.15536072e+02 5.03518433e+02 4.87309784e+02 4.68627686e+02 4.50688873e+02 4.23166992e+02 4.15839996e+02 4.11658905e+02 3.98621735e+02 3.70196381e+02 3.38290161e+02 3.27365997e+02 3.28875763e+02 3.26084259e+02 2.98490051e+02 2.70349548e+02 2.61116943e+02 2.54582886e+02 2.46773315e+02 2.35480118e+02 2.15750015e+02 2.02174637e+02 1.93943100e+02 1.84742004e+02 1.73658722e+02 1.61798615e+02 1.52013580e+02 1.40352371e+02 1.32516449e+02 1.23850578e+02 1.13196983e+02 1.05988495e+02 9.83944244e+01 9.09818878e+01 8.04470901e+01 7.18908081e+01 6.82055969e+01 6.40181580e+01 5.78769836e+01 4.98363457e+01 4.23841591e+01 3.73896561e+01 3.45371819e+01 3.15345078e+01 2.63747730e+01 2.12581329e+01 1.74463425e+01 1.44144430e+01 1.20597334e+01 9.81616211e+00 7.48552132e+00 5.50766993e+00 3.97707319e+00 2.80404997e+00 1.94982529e+00 1.46663547e+00 1.31761968e+00 1.50169051e+00 2.03386927e+00 2.88360500e+00 3.91372108e+00 5.45922947e+00 7.50746107e+00 9.76308250e+00 1.23372335e+01 1.50360994e+01 1.85294952e+01 2.22782116e+01 2.52388077e+01 2.84318314e+01 3.34864960e+01 4.01734772e+01 4.66183205e+01 5.15890045e+01 5.47112045e+01 5.91078300e+01 6.68986664e+01 7.72630463e+01 8.67682114e+01 9.28950653e+01 9.55106201e+01 1.03415558e+02 1.18839638e+02 1.27191475e+02 1.29617630e+02 1.39129547e+02 1.52014664e+02 1.62157761e+02 1.78110016e+02 1.84844620e+02 1.89208832e+02 2.05270493e+02 2.12052216e+02 2.30061447e+02 2.51588181e+02 2.50647064e+02 2.66380249e+02 2.89032410e+02 2.97425781e+02 3.12162750e+02 3.22960693e+02 3.37821564e+02 3.59650757e+02 3.70377930e+02 3.73879303e+02 3.92281952e+02 4.26711395e+02 4.54379089e+02 4.61710571e+02 4.59986908e+02 4.65922424e+02 4.92386993e+02 5.33638489e+02 5.66444946e+02 5.73605469e+02 5.62664124e+02 5.84509827e+02 6.28964355e+02 6.39921875e+02 6.51659607e+02 6.75400879e+02 6.96321045e+02 7.17727661e+02 7.69523315e+02 7.70182983e+02 7.62131653e+02 8.03822693e+02 8.06636353e+02 8.61921692e+02 9.07620667e+02 8.97366272e+02 9.55102539e+02 9.60163330e+02 9.37246094e+02 9.90057434e+02 1.00082892e+03 1.04410632e+03 1.13923706e+03 1.10896667e+03 1.07821252e+03 1.12877515e+03 1.19768689e+03 1.26989111e+03 1.27705371e+03 1.22965833e+03 1.21741589e+03 1.28192004e+03 1.37892920e+03 1.44900208e+03 1.45541296e+03 1.40881519e+03 1.41673950e+03 1.50061780e+03 1.56115967e+03 1.54002954e+03 1.55361304e+03 1.60892676e+03 1.63848853e+03 1.72494910e+03 1.75879517e+03 1.72302368e+03 1.74940796e+03 1.77139844e+03 1.81343213e+03 1.89423364e+03 1.90933264e+03 1.98108398e+03 1.98718298e+03 1.93949622e+03 2.01845068e+03 2.01711743e+03 2.10506226e+03 2.28889258e+03 2.19717090e+03 2.07092822e+03 2.16895508e+03 2.31469092e+03 2.40235693e+03 2.48025708e+03 2.38509375e+03 2.29493896e+03 2.37987793e+03 2.54624463e+03 2.70440771e+03 2.65505200e+03 2.52590308e+03 2.54412842e+03 2.66645630e+03 2.76674609e+03 2.88921387e+03 2.90485205e+03 2.77084912e+03 2.79306787e+03 2.93223633e+03 3.01356396e+03 3.04211670e+03 3.04068091e+03 3.03076709e+03 3.05669238e+03 3.24901025e+03 3.29958154e+03 3.16436572e+03 3.20936035e+03 3.32086646e+03 3.37004858e+03 3.42508032e+03 3.42979443e+03 3.54808130e+03 3.62646143e+03 3.54427075e+03 3.54496021e+03 3.54884741e+03 3.69633594e+03 3.91968823e+03 3.92477344e+03 3.75598486e+03 3.69058228e+03 3.87608618e+03 4.14551758e+03 4.05027124e+03 3.86362793e+03 3.98549194e+03 4.16165479e+03 4.28684277e+03 4.42251074e+03 4.39367236e+03 4.20974951e+03 4.12513330e+03 4.30622949e+03 4.62201514e+03 4.66415088e+03 4.50836816e+03 4.53376758e+03 4.60717480e+03 4.75582520e+03 4.73988623e+03 4.63678076e+03 4.71340479e+03 4.73862744e+03 4.96647461e+03 5.15216064e+03 5.00598193e+03 5.01866602e+03 5.12411133e+03 5.28423633e+03 5.19270508e+03 4.95965625e+03 5.27573340e+03 5.62457227e+03 5.41634473e+03 5.18969629e+03 5.39835010e+03 5.74712451e+03 5.71884717e+03 5.61211133e+03 5.69666406e+03 5.52735938e+03 5.55957861e+03 5.96613184e+03 6.01530176e+03 5.81134961e+03 5.73539795e+03 5.73088525e+03 6.06357178e+03 6.38261865e+03 6.17694141e+03 6.03649414e+03 6.17745508e+03 6.25247314e+03 6.52323242e+03 6.58379053e+03 6.25183887e+03 6.26023926e+03 6.45086719e+03 6.53256543e+03 6.66632666e+03 6.69063770e+03 6.89564307e+03 6.86379443e+03 6.63470752e+03 6.74456006e+03 6.73611230e+03 7.01016650e+03 7.49799463e+03 7.35767676e+03 6.87600439e+03 6.98407666e+03 7.86605762e+03 9.40208789e+03 9.63861426e+03 1.34795713e+04 1.14475215e+04 1.76997695e+04 8.77917500e+04 16265572. 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. 0. 0. 0. 0. 0. 0. 0. -160775776. 4.02238555e+04 1.44145840e+04 1.55692432e+04 1.60853525e+04 1.08054365e+04 1.15763027e+04 1.01438389e+04 9.50721582e+03 9.83508887e+03 9.97504883e+03 9.69157520e+03 9.84495508e+03 9.89690820e+03 9.85280273e+03 9.95540039e+03 9.95119629e+03 9.98375879e+03 1.00386074e+04 1.00646201e+04 1.00676650e+04 9.89297852e+03 9.88110156e+03 1.04117656e+04 1.05181152e+04 1.00172783e+04 1.00610430e+04 1.06888750e+04 1.07764697e+04 1.05394297e+04 1.05351416e+04 1.05335918e+04 1.06103018e+04 1.06061777e+04 1.06167490e+04 1.07365127e+04 1.07173242e+04 1.05844443e+04 1.05951846e+04 1.10674463e+04 1.12113857e+04 1.09548096e+04 1.09616133e+04 1.10162637e+04 1.10664893e+04 1.10901689e+04 1.10942666e+04 1.11587344e+04 1.09261670e+04 1.08864131e+04 1.12736582e+04 1.12719639e+04 1.16747744e+04 1.18072920e+04 1.14241924e+04 1.11485371e+04 1.11160039e+04 1.18552295e+04 1.20190215e+04 1.16015283e+04 1.14642852e+04 1.16281934e+04 1.17694023e+04 1.16515166e+04 1.19870635e+04 1.20537461e+04 1.14923848e+04 1.14067734e+04 1.20908809e+04 1.24331553e+04 1.20926064e+04 1.19845908e+04 1.20740205e+04 1.20318398e+04 1.19042539e+04 1.19842139e+04 1.22703223e+04 1.22672812e+04 1.20978027e+04 1.21399941e+04 1.22990117e+04 1.23080146e+04 1.26301953e+04 1.25749443e+04 1.22235869e+04 1.24830928e+04 1.24969648e+04 1.26239375e+04 1.27605820e+04 1.25868037e+04 1.25714111e+04 1.23792148e+04 1.22318281e+04 1.27805996e+04 1.28091895e+04 1.21946875e+04 1.24059492e+04 1.31786689e+04 1.35793262e+04 1.31937900e+04 1.28516924e+04 1.26381045e+04 1.26416914e+04 1.28302607e+04 1.28042588e+04 1.30203262e+04 1.29766055e+04 1.31982256e+04 1.32076885e+04 1.28951846e+04 1.31199717e+04 1.27652666e+04 1.28648457e+04 1.36596230e+04 1.34850146e+04 1.31716113e+04 1.29057031e+04 1.28168652e+04 1.35546562e+04 1.36256406e+04 1.32273682e+04 1.29346719e+04 1.29764668e+04 1.33405469e+04 1.32889639e+04 1.36869570e+04 1.38365186e+04 1.34228115e+04 1.32923154e+04 1.33231309e+04 1.36143486e+04 1.36230752e+04 1.34258145e+04 1.32071416e+04 1.32584580e+04 1.36253809e+04 1.32398643e+04 1.32211465e+04 1.40298633e+04 1.39915713e+04 1.36374785e+04 1.31978291e+04 1.31700576e+04 1.40402334e+04 1.40497373e+04 1.36577305e+04 1.33075381e+04 1.32106328e+04 1.36799277e+04 1.36668945e+04 1.36764297e+04 1.33857217e+04 1.36112549e+04 1.43093096e+04 1.39586328e+04 1.38325527e+04 1.38727744e+04 1.37912451e+04 1.36002852e+04 1.35365684e+04 1.37670215e+04 1.38184609e+04 1.38766396e+04 1.33828594e+04 1.34143330e+04 1.43959971e+04 1.38513496e+04 1.33004951e+04 1.37037861e+04 1.37482725e+04 1.42331338e+04 1.39217480e+04 1.33453506e+04 1.40744492e+04 1.42060732e+04 1.37964473e+04 1.35863594e+04 1.35607764e+04 1.36740156e+04 1.37021416e+04 1.38306621e+04 1.34678496e+04 1.37007471e+04 1.44286377e+04 1.41829932e+04 1.37103340e+04 1.32502500e+04 1.34430996e+04 1.42692139e+04 1.41956123e+04 1.37981631e+04 1.34897285e+04 1.33915732e+04 1.37140566e+04 1.37536338e+04 1.40789961e+04 1.37911699e+04 1.33446689e+04 1.36956084e+04 1.37264033e+04 1.39640322e+04 1.37979912e+04 1.34667881e+04 1.35933359e+04 1.35588750e+04 1.36774668e+04 1.33065869e+04 1.35756318e+04 1.44193271e+04 1.39687471e+04 1.35772051e+04 1.32568965e+04 1.31345879e+04 1.38867471e+04 1.40118613e+04 1.36111816e+04 1.31160420e+04 1.31166904e+04 1.35787979e+04 1.35236445e+04 1.38618516e+04 1.37809170e+04 1.34265244e+04 1.30457139e+04 1.29565342e+04 1.37593779e+04 1.36024707e+04 1.32149111e+04 1.31195703e+04 1.30629658e+04 1.36661582e+04 1.36791807e+04 1.29978496e+04 1.28618379e+04 1.34680381e+04 1.36139473e+04 1.29018184e+04 1.28023809e+04 1.34550420e+04 1.34765049e+04 1.30947236e+04 1.27911025e+04 1.27191768e+04 1.34035830e+04 1.32208652e+04 1.27718281e+04 1.28556738e+04 1.28459414e+04 1.31314600e+04 1.31178594e+04 1.26874043e+04 1.23603896e+04 1.27329150e+04 1.34106787e+04 1.30293926e+04 1.28466572e+04 1.28832090e+04 1.27843545e+04 1.27548906e+04 1.26774082e+04 1.25890908e+04 1.23232842e+04 1.21932002e+04 1.24411074e+04 1.25740635e+04 1.29417822e+04 1.24842900e+04 1.19500029e+04 1.23655352e+04 1.25173105e+04 1.28123477e+04 1.25498457e+04 1.21487275e+04 1.21259668e+04 1.20400615e+04 1.21725010e+04 1.22125625e+04 1.24677598e+04 1.23177100e+04 1.19597178e+04 1.18479326e+04 1.14904424e+04 1.19398516e+04 1.26894023e+04 1.22988428e+04 1.18909307e+04 1.15806953e+04 1.12850137e+04 1.18088633e+04 1.23460957e+04 1.19883145e+04 1.13794941e+04 1.12843096e+04 1.16219473e+04 1.15930947e+04 1.17757949e+04 1.17179648e+04 1.13572900e+04 1.13376406e+04 1.12596455e+04 1.16168525e+04 1.15889189e+04 1.09866465e+04 1.09775195e+04 1.15422188e+04 1.13392061e+04 1.07628193e+04 1.09396738e+04 1.14836514e+04 1.12952959e+04 1.09782080e+04 1.07106875e+04 1.06342354e+04 1.11818408e+04 1.11199385e+04 1.08562549e+04 1.04683047e+04 1.03292412e+04 1.06303311e+04 1.06948125e+04 1.05798330e+04 1.02536201e+04 1.05060518e+04 1.08190840e+04 1.04608145e+04 1.06180400e+04 1.04929756e+04 1.01843076e+04 1.02738535e+04 1.02890742e+04 1.01972881e+04 1.00740039e+04 9.85419629e+03 9.65787695e+03 1.00090352e+04 1.05652520e+04 9.90789062e+03 9.47297754e+03 9.75669727e+03 9.81922949e+03 1.00724199e+04 9.83318066e+03 9.42359375e+03 9.87106250e+03 9.77638770e+03 9.22678906e+03 9.14151367e+03 9.63332910e+03 9.64241113e+03 9.33270312e+03 9.11230469e+03 8.76423926e+03 9.12051270e+03 9.74772949e+03 9.40332129e+03 8.98638574e+03 8.71138867e+03 8.55697852e+03 8.95780371e+03 9.45057227e+03 9.09722070e+03 8.61084570e+03 8.47218848e+03 8.62238184e+03 8.67651270e+03 8.82415137e+03 8.58841406e+03 8.29870996e+03 8.48408594e+03 8.37851270e+03 8.62491895e+03 8.55300781e+03 8.18845264e+03 8.17437695e+03 8.09979199e+03 8.26297754e+03 7.99678467e+03 7.84149463e+03 8.29141406e+03 8.18925244e+03 7.86697217e+03 7.60675635e+03 7.62679053e+03 8.01764258e+03 7.91604688e+03 7.69148047e+03 7.44801172e+03 7.36036133e+03 7.48859570e+03 7.50053760e+03 7.42626074e+03 7.18431104e+03 7.26887158e+03 7.51309326e+03 7.26196777e+03 7.30258643e+03 7.35385742e+03 7.07389355e+03 6.89750439e+03 6.85629932e+03 7.04901025e+03 6.96934180e+03 6.69441797e+03 6.58897314e+03 6.93622705e+03 6.88146484e+03 6.45332275e+03 6.30827686e+03 6.41421777e+03 6.58004932e+03 6.79968896e+03 6.50601074e+03 6.12950635e+03 6.41208203e+03 6.48746631e+03 6.29431543e+03 6.09332568e+03 6.07151758e+03 5.95950342e+03 5.96050928e+03 5.98575000e+03 5.76418213e+03 5.84032129e+03 6.07896777e+03 5.85622461e+03 5.79696338e+03 5.63690674e+03 5.53241895e+03 5.74174463e+03 5.70033887e+03 5.51766455e+03 5.36961328e+03 5.13207812e+03 5.21598242e+03 5.44965723e+03 5.55109570e+03 5.23282861e+03 5.01895459e+03 5.10657373e+03 5.07872754e+03 5.22944824e+03 5.14326172e+03 4.91198584e+03 4.83331934e+03 4.77739355e+03 4.73519824e+03 4.61410645e+03 4.71076465e+03 4.85279492e+03 4.66642969e+03 4.64591211e+03 4.50673535e+03 4.38460742e+03 4.58252393e+03 4.54402490e+03 4.33515381e+03 4.20906934e+03 4.13427441e+03 4.21900195e+03 4.16175244e+03 4.23866748e+03 4.25980225e+03 4.04522461e+03 3.87697461e+03 3.91370483e+03 4.06129297e+03 3.95257983e+03 3.82199658e+03 3.71889209e+03 3.68012305e+03 3.67487427e+03 3.60782837e+03 3.67510669e+03 3.63063843e+03 3.48389722e+03 3.56178613e+03 3.54506299e+03 3.43083276e+03 3.36549121e+03 3.32888525e+03 3.29335156e+03 3.16745239e+03 3.08541284e+03 3.20869214e+03 3.19987646e+03 3.01060571e+03 2.88439258e+03 2.98579077e+03 3.11281519e+03 3.03062744e+03 2.82632446e+03 2.73767480e+03 2.85851538e+03 2.82904370e+03 2.69938110e+03 2.72569775e+03 2.61326367e+03 2.46778271e+03 2.51301953e+03 2.61461035e+03 2.62702271e+03 2.45536890e+03 2.30058423e+03 2.39573120e+03 2.48163794e+03 2.36003516e+03 2.22118701e+03 2.15756616e+03 2.19232104e+03 2.16732324e+03 2.19180396e+03 2.15330713e+03 2.04794641e+03 2.01732812e+03 1.98186670e+03 2.01672046e+03 1.94102051e+03 1.85122888e+03 1.88338879e+03 1.84477551e+03 1.83092896e+03 1.76229321e+03 1.69685144e+03 1.76251953e+03 1.68970178e+03 1.58331104e+03 1.59153394e+03 1.59732690e+03 1.57352319e+03 1.52142896e+03 1.52114587e+03 1.50519812e+03 1.43937231e+03 1.37091760e+03 1.33254419e+03 1.37496448e+03 1.32077527e+03 1.25639368e+03 1.26492993e+03 1.23652161e+03 1.20507910e+03 1.17237207e+03 1.17503040e+03 1.13793115e+03 1.07989197e+03 1.09064441e+03 1.06790918e+03 1.02637170e+03 1.00593176e+03 9.79321960e+02 9.41616028e+02 8.92133606e+02 8.54985168e+02 8.75258057e+02 9.06142761e+02 8.37050720e+02 7.63053040e+02 7.75763428e+02 8.00528992e+02 7.71488403e+02 7.09921021e+02 6.72035156e+02 6.87061279e+02 6.66317871e+02 6.24315308e+02 6.31167297e+02 6.08295410e+02 5.59432495e+02 5.39118347e+02 5.47949158e+02 5.44175720e+02 5.00778717e+02 4.62519531e+02 4.64133392e+02 4.73339417e+02 4.45505890e+02 4.08003357e+02 3.82096130e+02 3.83532837e+02 3.85522858e+02 3.57868256e+02 3.32152679e+02 3.20637329e+02 3.09617920e+02 2.94261047e+02 2.88771881e+02 2.70150635e+02 2.48017883e+02 2.40724854e+02 2.30256699e+02 2.22892227e+02 2.06075638e+02 1.89377319e+02 1.84314865e+02 1.69123901e+02 1.58830536e+02 1.55039261e+02 1.43717484e+02 1.33201813e+02 1.23267334e+02 1.18590919e+02 1.09484131e+02 9.65215073e+01 8.71835022e+01 8.08374329e+01 8.27547760e+01 7.68458862e+01 8.34959717e+01 8.72118378e+01 1.44615280e+02 7.12704468e+02 8916332. 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. 18121824. 3.87429138e+02 6.01019669e+01 5.41417580e+01 4.82113342e+01 4.97383842e+01 5.31464615e+01 5.92054634e+01 6.30424614e+01 6.75017700e+01 7.53615646e+01 8.26688843e+01 9.09288406e+01 1.01766502e+02 1.09265938e+02 1.13957680e+02 1.25199982e+02 1.37465775e+02 1.43182968e+02 1.50727905e+02 1.61253098e+02 1.74421967e+02 1.89947952e+02 2.01470276e+02 2.08055405e+02 2.13503220e+02 2.30804688e+02 2.52059006e+02 2.60008026e+02 2.72241180e+02 2.83683258e+02 2.95444794e+02 3.19941498e+02 3.28092255e+02 3.32426025e+02 3.52267822e+02 3.68509521e+02 3.90003479e+02 4.09385590e+02 4.15296600e+02 4.31397583e+02 4.63028290e+02 5.02454346e+02 5.07167969e+02 4.87633636e+02 5.05358093e+02 5.38535706e+02 5.66859985e+02 6.00029236e+02 6.10020874e+02 6.12975891e+02 6.47455505e+02 6.76630371e+02 6.79990784e+02 6.92001587e+02 7.12115234e+02 7.60882507e+02 8.09971069e+02 7.91332825e+02 7.85980225e+02 8.31153015e+02 8.70954956e+02 9.08566284e+02 9.19242432e+02 9.20278564e+02 9.36363708e+02 9.80419617e+02 1.05618823e+03 1.05494446e+03 1.02085925e+03 1.06925659e+03 1.11826819e+03 1.14610364e+03 1.18960645e+03 1.19363477e+03 1.18726599e+03 1.24702417e+03 1.30975085e+03 1.30538770e+03 1.31095056e+03 1.33656799e+03 1.37173352e+03 1.43875195e+03 1.50418018e+03 1.49606482e+03 1.46851501e+03 1.52926318e+03 1.59628369e+03 1.59950623e+03 1.61622864e+03 1.64180652e+03 1.70340051e+03 1.78744470e+03 1.79031702e+03 1.74636218e+03 1.77143811e+03 1.82613770e+03 1.89485486e+03 1.94907300e+03 1.94765381e+03 1.97847839e+03 2.06166724e+03 2.15820581e+03 2.13549927e+03 2.05697485e+03 2.09829199e+03 2.20524072e+03 2.26786230e+03 2.29647852e+03 2.29259131e+03 2.30695410e+03 2.41067603e+03 2.45101343e+03 2.42732373e+03 2.48176587e+03 2.53492749e+03 2.55538257e+03 2.65411646e+03 2.68354028e+03 2.65027246e+03 2.68503198e+03 2.72072559e+03 2.76351147e+03 2.88689087e+03 2.98417310e+03 2.93065845e+03 2.86666504e+03 2.98096997e+03 3.11424414e+03 3.09533545e+03 3.06682349e+03 3.09457227e+03 3.15025928e+03 3.28628687e+03 3.35574072e+03 3.28947559e+03 3.29828882e+03 3.38516821e+03 3.48668677e+03 3.52259790e+03 3.53845850e+03 3.55482202e+03 3.62213672e+03 3.71695972e+03 3.67765723e+03 3.64332690e+03 3.74216187e+03 3.81380664e+03 3.90342139e+03 4.04407812e+03 3.97686523e+03 3.88201123e+03 4.01356152e+03 4.16720898e+03 4.15275439e+03 4.16391748e+03 4.14850342e+03 4.17017236e+03 4.42925977e+03 4.51919922e+03 4.33820020e+03 4.30885791e+03 4.50788135e+03 4.67304883e+03 4.59894434e+03 4.47782080e+03 4.57506836e+03 4.78732812e+03 4.91154932e+03 4.78378369e+03 4.75883936e+03 4.89004639e+03 4.89774756e+03 4.99246875e+03 5.14954053e+03 5.07122461e+03 5.08174365e+03 5.26412402e+03 5.35701172e+03 5.21742529e+03 5.23490332e+03 5.27042383e+03 5.34191064e+03 5.47962305e+03 5.77186621e+03 5.74789355e+03 5.45470410e+03 5.59463477e+03 5.87183887e+03 5.72633057e+03 5.65543896e+03 5.73724707e+03 5.87301270e+03 6.14941992e+03 6.11231934e+03 5.89963477e+03 5.93109033e+03 6.02995508e+03 6.18721973e+03 6.32516895e+03 6.27677393e+03 6.31972119e+03 6.48514014e+03 6.60450732e+03 6.45650879e+03 6.37661279e+03 6.46872119e+03 6.54434375e+03 6.65601660e+03 6.90569580e+03 6.97887939e+03 6.68019824e+03 6.73478516e+03 6.99670898e+03 7.00386133e+03 6.93975195e+03 6.96649023e+03 7.08291406e+03 7.34536963e+03 7.37277490e+03 7.17352295e+03 7.14736475e+03 7.25859814e+03 7.35221924e+03 7.54081543e+03 7.45316943e+03 7.51534033e+03 7.66567920e+03 7.78110254e+03 7.91139209e+03 7.66825098e+03 7.62220947e+03 7.84186230e+03 7.85451904e+03 8.06639600e+03 8.02100293e+03 7.78366846e+03 8.08497607e+03 8.34602246e+03 8.16313037e+03 8.12531445e+03 8.23107031e+03 8.36320996e+03 8.41994727e+03 8.28299121e+03 8.58174219e+03 8.65216113e+03 8.47485938e+03 8.72863184e+03 8.55519922e+03 8.65856250e+03 8.92594434e+03 8.67394043e+03 8.80169336e+03 8.97122070e+03 8.88780371e+03 8.70029590e+03 8.81715723e+03 9.34104883e+03 9.53843555e+03 9.00292773e+03 9.00305762e+03 9.38520215e+03 9.38471680e+03 9.45243262e+03 9.28748828e+03 9.26726367e+03 9.48903125e+03 9.69087207e+03 9.72227246e+03 9.51918457e+03 9.53334863e+03 9.74402148e+03 9.95849902e+03 9.73864746e+03 9.57077832e+03 9.71038379e+03 9.76552148e+03 1.00102236e+04 1.03690479e+04 1.01902051e+04 9.83254395e+03 9.92586426e+03 1.03676816e+04 1.05813652e+04 1.00999170e+04 1.03320596e+04 1.06296465e+04 1.02452822e+04 1.03901992e+04 1.02779600e+04 1.04182793e+04 1.09168252e+04 1.07051113e+04 1.04279570e+04 1.08736699e+04 1.09106016e+04 1.05813867e+04 1.08332910e+04 1.10149150e+04 1.10217080e+04 1.07210078e+04 1.06744365e+04 1.11132393e+04 1.13415762e+04 1.11619639e+04 1.09615986e+04 1.10258613e+04 1.13806211e+04 1.15766475e+04 1.11400332e+04 1.11009453e+04 1.13162324e+04 1.16142178e+04 1.16152129e+04 1.12419502e+04 1.13705488e+04 1.17312725e+04 1.17998643e+04 1.15576318e+04 1.17298721e+04 1.18038516e+04 1.15541729e+04 1.20426484e+04 1.22466357e+04 1.16818164e+04 1.13933135e+04 1.16595312e+04 1.20466855e+04 1.21496934e+04 1.20574902e+04 1.18509092e+04 1.19027793e+04 1.23820557e+04 1.24762109e+04 1.20308555e+04 1.19892793e+04 1.23027979e+04 1.27120371e+04 1.24177031e+04 1.20593652e+04 1.23271885e+04 1.24126445e+04 1.24189893e+04 1.24271514e+04 1.25566367e+04 1.25386387e+04 1.23513252e+04 1.25511797e+04 1.27552822e+04 1.26825850e+04 1.23880352e+04 1.24481621e+04 1.27561299e+04 1.28173350e+04 1.26703125e+04 1.26595898e+04 1.27844512e+04 1.31802764e+04 1.32121680e+04 1.26931309e+04 1.29426543e+04 1.31128320e+04 1.30524150e+04 1.28897305e+04 1.28270674e+04 1.31987344e+04 1.31916729e+04 1.29098955e+04 1.26439033e+04 1.30552246e+04 1.34967598e+04 1.33459365e+04 1.33337568e+04 1.32323252e+04 1.33488770e+04 1.31209775e+04 1.27194746e+04 1.31863691e+04 1.35003438e+04 1.34245430e+04 1.34371104e+04 1.31225537e+04 1.31859365e+04 1.35344062e+04 1.37188711e+04 1.38597383e+04 1.35103086e+04 1.32535557e+04 1.31175684e+04 1.34908262e+04 1.39331670e+04 1.37518174e+04 1.36246475e+04 1.30883535e+04 1.33746572e+04 1.38876973e+04 1.35950254e+04 1.37683477e+04 1.36011562e+04 1.34805605e+04 1.39175566e+04 1.35859434e+04 1.34710469e+04 1.39924170e+04 1.40531445e+04 1.35562129e+04 1.32417041e+04 1.35137529e+04 1.36898711e+04 1.41239961e+04 1.44109209e+04 1.38881660e+04 1.35577578e+04 1.34142969e+04 1.37895732e+04 1.42964512e+04 1.40077959e+04 1.35953623e+04 1.34171494e+04 1.36050898e+04 1.39827500e+04 1.42479844e+04 1.41244570e+04 1.38705488e+04 1.40148809e+04 1.38613018e+04 1.34341055e+04 1.37408779e+04 1.39988301e+04 1.41487148e+04 1.44208799e+04 1.37540928e+04 1.33551895e+04 1.38119053e+04 1.42810078e+04 1.43007344e+04 1.38189346e+04 1.36976201e+04 1.36771582e+04 1.39598281e+04 1.42724883e+04 1.41341982e+04 1.39677939e+04 1.36153857e+04 1.39501738e+04 1.39464912e+04 1.34696152e+04 1.37631289e+04 1.40478281e+04 1.40517510e+04 1.39637021e+04 1.36436104e+04 1.38002266e+04 1.41103711e+04 1.41489512e+04 1.41146406e+04 1.34990977e+04 1.33935459e+04 1.37826826e+04 1.41106309e+04 1.42369746e+04 1.39517852e+04 1.37929053e+04 1.34147803e+04 1.37139834e+04 1.42587373e+04 1.39073047e+04 1.37552188e+04 1.37751016e+04 1.36479316e+04 1.34841475e+04 1.35978984e+04 1.38100459e+04 1.39100908e+04 1.39830703e+04 1.36352930e+04 1.32820840e+04 1.35420381e+04 1.37248916e+04 1.37979033e+04 1.38925449e+04 1.35314932e+04 1.35450527e+04 1.34812109e+04 1.35378115e+04 1.39422520e+04 1.36332988e+04 1.34683223e+04 1.33601094e+04 1.30398662e+04 1.33135771e+04 1.40073574e+04 1.37723643e+04 1.32563789e+04 1.34584775e+04 1.32789443e+04 1.29005654e+04 1.32454238e+04 1.34878721e+04 13393. 1.34066221e+04 1.29800029e+04 1.29849092e+04 1.33819512e+04 1.34789707e+04 1.37623584e+04 1.33526611e+04 1.27088359e+04 1.26416465e+04 1.30993867e+04 1.33324229e+04 1.32490820e+04 1.30717441e+04 1.25239014e+04 1.27965312e+04 1.33311553e+04 1.29853047e+04 1.28611865e+04 1.27234561e+04 1.27044404e+04 1.29872500e+04 1.26379473e+04 1.25392861e+04 1.31627783e+04 1.31348809e+04 1.27582637e+04 1.24448604e+04 1.20675273e+04 1.23332334e+04 1.28007236e+04 1.31087031e+04 1.27908447e+04 1.21262744e+04 1.19642578e+04 1.23521602e+04 1.26565576e+04 1.24240254e+04 1.22653252e+04 1.20151221e+04 1.20437256e+04 1.23447568e+04 1.24471309e+04 1.23958232e+04 1.21874590e+04 1.22306641e+04 1.20641885e+04 1.16788545e+04 1.18696191e+04 1.20713711e+04 1.20810996e+04 1.22749873e+04 1.17893848e+04 1.14472607e+04 1.17568223e+04 1.19162168e+04 1.21205205e+04 1.19187793e+04 1.13916182e+04 1.12606572e+04 1.15729307e+04 1.19429561e+04 1.19086328e+04 1.14944033e+04 1.12781572e+04 1.12739688e+04 1.11805469e+04 1.12232256e+04 1.14538428e+04 1.15214053e+04 1.12317969e+04 1.09426201e+04 1.08536143e+04 1.10325029e+04 1.13074092e+04 1.13323262e+04 1.12356299e+04 1.08133750e+04 1.04520928e+04 1.06852412e+04 1.09457686e+04 1.11349355e+04 1.09744531e+04 1.04764912e+04 1.02147256e+04 1.05140439e+04 1.09252568e+04 1.06397979e+04 1.06243848e+04 1.04241943e+04 1.01029844e+04 1.03887178e+04 1.04354551e+04 1.02935977e+04 1.01945410e+04 1.03034834e+04 1.02218467e+04 9.98428516e+03 1.00231211e+04 1.00398301e+04 1.01629307e+04 1.00645039e+04 9.70302441e+03 9.76246387e+03 9.56812012e+03 9.75835840e+03 1.01715801e+04 9.89750684e+03 9.41835352e+03 9.32630371e+03 9.35374512e+03 9.61112598e+03 9.84504102e+03 9.50266211e+03 9.12297168e+03 9.29905664e+03 9.39121777e+03 9.25404688e+03 9.32185645e+03 9.56994336e+03 1.03473604e+04 1.19163555e+04 1.94329043e+04 2.80320898e+04 -10163533. -87414224. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -40570804. 31519886. -77912752. 2.56825059e+04 1.01855293e+04 8.91494629e+03 7.89122119e+03 7.25602100e+03 6.71920947e+03 6.35842773e+03 6.49456104e+03 6.73199707e+03 6.61405518e+03 6.36558203e+03 6.04358252e+03 5.94828516e+03 6.23635010e+03 6.53540430e+03 6.24097559e+03 5.96997363e+03 5.82567627e+03 5.83291455e+03 6.06634326e+03 5.99801318e+03 5.70701172e+03 5.60626123e+03 5.72426416e+03 5.63806689e+03 5.48117969e+03 5.43631152e+03 5.59099463e+03 5.70995703e+03 5.62684473e+03 5.29862793e+03 5.03628906e+03 5.12977002e+03 5.36138867e+03 5.42038721e+03 5.21507910e+03 4.93430225e+03 4.86029492e+03 5.02331348e+03 5.21049707e+03 5.00734668e+03 4.68378320e+03 4.64755469e+03 4.85992627e+03 4.81301221e+03 4.67413770e+03 4.63921484e+03 4.52372754e+03 4.56554541e+03 4.53250537e+03 4.29585791e+03 4.26289111e+03 4.44279004e+03 4.48450635e+03 4.36209033e+03 4.13100586e+03 3.95461841e+03 4.15028076e+03 4.35471533e+03 4.17444141e+03 3.93799023e+03 3.77836670e+03 3.69475171e+03 3.88120972e+03 4.05295215e+03 3.88214771e+03 3.77062646e+03 3.68438037e+03 3.56140576e+03 3.56514233e+03 3.61283252e+03 3.47965918e+03 3.39571948e+03 3.48444019e+03 3.39393872e+03 3.21587451e+03 3.23066504e+03 3.34577319e+03 3.36906689e+03 3.26253564e+03 3.12714673e+03 3.00557886e+03 2.93353027e+03 3.05770312e+03 3.16797266e+03 3.00419678e+03 2.79365210e+03 2.75274341e+03 2.83253687e+03 2.91049683e+03 2.86107446e+03 2.68514258e+03 2.61192944e+03 2.65635303e+03 2.60735498e+03 2.54954907e+03 2.52255469e+03 2.47270679e+03 2.46890552e+03 2.42227539e+03 2.31839795e+03 2.29600122e+03 2.32850659e+03 2.33686572e+03 2.29928735e+03 2.19789111e+03 2.09139282e+03 2.07200342e+03 2.15018726e+03 2.13863452e+03 2.01422961e+03 1.91534241e+03 1.86627844e+03 1.92590710e+03 2.00536047e+03 1.90120044e+03 1.76594299e+03 1.74496130e+03 1.75461377e+03 1.72315564e+03 1.65853430e+03 1.63392419e+03 1.65861853e+03 1.64345447e+03 1.57009009e+03 1.48907812e+03 1.45861694e+03 1.50339722e+03 1.51908618e+03 1.45666333e+03 1.37961719e+03 1.32397864e+03 1.27814038e+03 1.29571375e+03 1.33939038e+03 1.27361487e+03 1.18114575e+03 1.14676135e+03 1.17341833e+03 1.19550256e+03 1.13242761e+03 1.07211804e+03 1.04408972e+03 1.03275073e+03 1.02040759e+03 9.91645508e+02 9.40800415e+02 9.04785950e+02 9.18994507e+02 9.11449402e+02 8.55228882e+02 8.15033752e+02 8.06016541e+02 8.05678040e+02 8.02256653e+02 7.65200684e+02 6.98968445e+02 6.84150269e+02 6.94460327e+02 6.76767090e+02 6.44902161e+02 6.13892822e+02 5.91918396e+02 5.78669861e+02 5.71003113e+02 5.43729797e+02 5.14286438e+02 5.11988464e+02 5.04942352e+02 4.75285187e+02 4.44260010e+02 4.27728699e+02 4.22424744e+02 4.18599182e+02 4.02309143e+02 3.73256653e+02 3.45181976e+02 3.27565430e+02 3.28278442e+02 3.29995758e+02 3.04778290e+02 2.74399109e+02 2.60541718e+02 2.57082581e+02 2.52219101e+02 2.38226410e+02 2.19762589e+02 2.05088120e+02 1.94764206e+02 1.82781906e+02 1.72819916e+02 1.64441025e+02 1.53223099e+02 1.43911758e+02 1.33959229e+02 1.21669075e+02 1.13527405e+02 1.08056595e+02 1.00904526e+02 9.24309235e+01 8.10186996e+01 7.21310654e+01 6.90358734e+01 6.51109390e+01 5.75801964e+01 5.00556412e+01 4.31892128e+01 3.74422836e+01 3.44638252e+01 3.15335751e+01 2.64382401e+01 2.12271862e+01 1.74827461e+01 1.48276749e+01 1.21667767e+01 9.58723545e+00 7.36474895e+00 5.44202089e+00 3.89072347e+00 2.69277525e+00 1.84137464e+00 1.36214066e+00 1.20985711e+00 1.39690781e+00 1.94563115e+00 2.79866314e+00 3.84551430e+00 5.31033707e+00 7.37147999e+00 9.88281345e+00 1.23838129e+01 1.49636841e+01 1.85645657e+01 2.24147110e+01 2.53509560e+01 2.85600262e+01 3.36673164e+01 4.04241257e+01 4.70932808e+01 5.19526482e+01 5.50779076e+01 5.92192001e+01 6.70207367e+01 7.81707535e+01 8.83182297e+01 9.37635422e+01 9.60809479e+01 1.04212784e+02 1.19970444e+02 1.28374771e+02 1.31508453e+02 1.41229385e+02 1.52405624e+02 1.62735825e+02 1.79307907e+02 1.86590027e+02 1.91317383e+02 2.06936432e+02 2.14286774e+02 2.33193771e+02 2.52815414e+02 2.51478928e+02 2.69821472e+02 2.92339996e+02 2.99788116e+02 3.12681396e+02 3.27080261e+02 3.43327911e+02 3.60826202e+02 3.74102600e+02 3.78498993e+02 3.94707123e+02 4.31242249e+02 4.59957581e+02 4.66720276e+02 4.62757782e+02 4.69692932e+02 4.99526886e+02 5.40340088e+02 5.69203125e+02 5.77065247e+02 5.68657349e+02 5.91603943e+02 6.29273926e+02 6.42155579e+02 6.64822205e+02 6.86194763e+02 7.01913025e+02 7.24294250e+02 7.75845398e+02 7.77422546e+02 7.70479797e+02 8.13135071e+02 8.17400024e+02 8.74961365e+02 9.08061768e+02 9.00450012e+02 9.71441895e+02 9.63587158e+02 9.45589355e+02 1.00598120e+03 1.01242786e+03 1.05243347e+03 1.15199817e+03 1.12414148e+03 1.08495068e+03 1.12896667e+03 1.20720312e+03 1.29392334e+03 1.28906055e+03 1.24324463e+03 1.23868884e+03 1.29189783e+03 1.38543774e+03 1.46266003e+03 1.46598743e+03 1.42567529e+03 1.43810535e+03 1.50606348e+03 1.56083667e+03 1.56797168e+03 1.57940881e+03 1.62314905e+03 1.66326672e+03 1.73982104e+03 1.77306091e+03 1.72650134e+03 1.74906213e+03 1.79778613e+03 1.84238257e+03 1.90615320e+03 1.92341711e+03 2.00630774e+03 2.01042957e+03 1.95964185e+03 2.03933496e+03 2.03458960e+03 2.12281226e+03 2.29986426e+03 2.21787622e+03 2.11780298e+03 2.20173169e+03 2.34766357e+03 2.44138623e+03 2.48852759e+03 2.38976636e+03 2.32198120e+03 2.41298853e+03 2.56968140e+03 2.71428442e+03 2.67316626e+03 2.55187354e+03 2.58271387e+03 2.70199707e+03 2.78744824e+03 2.91494238e+03 2.94380273e+03 2.80116943e+03 2.81251074e+03 2.98681860e+03 3.06360815e+03 2.99958838e+03 3.00869116e+03 3.11163892e+03 3.12357642e+03 3.26005664e+03 3.33395459e+03 3.19093311e+03 3.22752344e+03 3.36812451e+03 3.39930518e+03 3.44404150e+03 3.44037598e+03 3.56174561e+03 3.68405737e+03 3.63053125e+03 3.57212256e+03 3.54098120e+03 3.72551978e+03 3.96116821e+03 3.95134668e+03 3.78783154e+03 3.72028931e+03 3.90239087e+03 4.17494092e+03 4.10535449e+03 3.93669922e+03 4.02834595e+03 4.18550000e+03 4.33195068e+03 4.49167578e+03 4.43625244e+03 4.23940186e+03 4.16503320e+03 4.33947363e+03 4.63569824e+03 4.68173291e+03 4.55289551e+03 4.61010059e+03 4.65787354e+03 4.82981641e+03 4.81792627e+03 4.75432373e+03 4.78995215e+03 4.72406006e+03 4.99497461e+03 5.19832861e+03 5.02200537e+03 5.09172119e+03 5.17354980e+03 5.30612695e+03 5.23163623e+03 5.04766699e+03 5.30865088e+03 5.61385645e+03 5.53525000e+03 5.28809668e+03 5.40582666e+03 5.76201221e+03 5.76828271e+03 5.68782568e+03 5.75593945e+03 5.57516016e+03 5.62930713e+03 6.04239795e+03 6.06157520e+03 5.86529248e+03 5.77642090e+03 5.81024756e+03 6.12875391e+03 6.43609131e+03 6.21579639e+03 6.13582959e+03 6.30669336e+03 6.29521875e+03 6.60252051e+03 6.66566846e+03 6.30441748e+03 6.33443750e+03 6.52848145e+03 6.59190137e+03 6.66782275e+03 6.70457129e+03 6.95525098e+03 6.87193018e+03 6.70592383e+03 6.80655566e+03 6.76241357e+03 7.06069873e+03 7.53347900e+03 7.35084668e+03 6.95915771e+03 6.96588525e+03 7.24633252e+03 7.42266797e+03 8.07191211e+03 8.48520215e+03 7.95393896e+03 9.21502246e+03 1.79160625e+04 1.75283969e+05 1.48897375e+06 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. 0. 0. 0. 0. 0. 0. -160775776. 1.84202275e+06 1.72953320e+04 2.79424023e+04 1.56173555e+04 1.27165088e+04 1.28854736e+04 1.02806162e+04 9.69084668e+03 9.96996484e+03 9.92739355e+03 9.73926855e+03 1.00080938e+04 1.00076611e+04 9.92164062e+03 1.00055693e+04 1.00256934e+04 1.00678057e+04 1.01035928e+04 1.01932725e+04 1.01858018e+04 1.00095049e+04 1.00583516e+04 1.05174131e+04 1.05423770e+04 1.01583135e+04 1.02030361e+04 1.08214072e+04 1.08635908e+04 1.05833574e+04 1.06105508e+04 1.06149072e+04 1.07161855e+04 1.07427676e+04 1.07610439e+04 1.08272783e+04 1.07723301e+04 1.06656260e+04 1.07190791e+04 1.11935225e+04 1.12713672e+04 1.10087871e+04 1.10912764e+04 1.11588232e+04 1.12315713e+04 1.12009531e+04 1.12271318e+04 1.12730176e+04 1.10312441e+04 1.10646445e+04 1.13051035e+04 1.13354844e+04 1.18001934e+04 1.19004697e+04 1.15987832e+04 1.12650439e+04 1.11740322e+04 1.20078457e+04 1.21599668e+04 1.17106035e+04 1.15422236e+04 1.17173721e+04 1.17526924e+04 1.16242988e+04 1.22434766e+04 1.22187031e+04 1.15161973e+04 1.15042676e+04 1.21605986e+04 1.26368447e+04 1.23349336e+04 1.21524033e+04 1.22567598e+04 1.21366123e+04 1.20838223e+04 1.22385488e+04 1.23728799e+04 1.23596484e+04 1.21511670e+04 1.21316885e+04 1.24144766e+04 1.24444219e+04 1.27451855e+04 1.26373389e+04 1.22512773e+04 1.25171895e+04 1.25941367e+04 1.28704307e+04 1.29630029e+04 1.27133770e+04 1.26912188e+04 1.24828672e+04 1.22191914e+04 1.28531748e+04 1.30825869e+04 1.24110723e+04 1.25471406e+04 1.33003369e+04 1.36258418e+04 1.32768799e+04 1.29215596e+04 1.28989854e+04 1.29714648e+04 1.28498408e+04 1.28522207e+04 1.31307480e+04 1.30932178e+04 1.33405518e+04 1.32366777e+04 1.29757256e+04 1.32342598e+04 1.29059980e+04 1.31472822e+04 1.38978135e+04 1.36429883e+04 1.33022725e+04 1.29742139e+04 1.29377598e+04 1.37231104e+04 1.38043945e+04 1.33524346e+04 1.30318262e+04 1.30684355e+04 1.34477207e+04 1.34063662e+04 1.37979980e+04 1.39644541e+04 1.35148418e+04 1.32796357e+04 1.33519092e+04 1.38814492e+04 1.38547188e+04 1.35373613e+04 1.33084033e+04 1.33321689e+04 1.36873145e+04 1.33191064e+04 1.34768721e+04 1.43461768e+04 1.41392041e+04 1.37582803e+04 1.33444932e+04 1.32953271e+04 1.41818818e+04 1.42262129e+04 1.38023877e+04 1.33993867e+04 1.33098828e+04 1.38254932e+04 1.38293584e+04 1.37809092e+04 1.34837334e+04 1.37229053e+04 1.43330078e+04 1.39699561e+04 1.41013623e+04 1.42014883e+04 1.38998486e+04 1.35677393e+04 1.35668486e+04 1.39292344e+04 1.39264219e+04 1.39817305e+04 1.35276729e+04 1.36818994e+04 1.46351777e+04 1.39785967e+04 1.34605508e+04 1.38682881e+04 1.38994375e+04 1.42922666e+04 1.40578672e+04 1.35293857e+04 1.41563701e+04 1.43235273e+04 1.39921182e+04 1.38896025e+04 1.38076553e+04 1.36761904e+04 1.36963857e+04 1.39367100e+04 1.35759668e+04 1.38349023e+04 1.46362324e+04 1.43812881e+04 1.37235479e+04 1.32243574e+04 1.36861855e+04 1.45743506e+04 1.42799395e+04 1.39003525e+04 1.36477207e+04 1.35097686e+04 1.38593447e+04 1.38723906e+04 1.41797500e+04 1.39353760e+04 1.34711660e+04 1.38288262e+04 1.38962002e+04 1.41127383e+04 1.40088389e+04 1.37224951e+04 1.36441602e+04 1.35595576e+04 1.38287227e+04 1.34986240e+04 1.36965566e+04 1.44648398e+04 1.41067197e+04 1.37440059e+04 1.33832344e+04 1.32872734e+04 1.40180498e+04 1.41102236e+04 1.37458779e+04 1.32872900e+04 1.32488232e+04 1.36873574e+04 1.36805146e+04 1.40025107e+04 1.39244473e+04 1.35724268e+04 1.31431416e+04 1.30951572e+04 1.39165244e+04 1.38041123e+04 1.34203369e+04 1.31875439e+04 1.31171484e+04 1.37814355e+04 1.38445059e+04 1.31304189e+04 1.30010977e+04 1.36628350e+04 1.36983574e+04 1.29966836e+04 1.29440654e+04 1.35956484e+04 1.35993779e+04 1.31890107e+04 1.28829238e+04 1.28160840e+04 1.35686895e+04 1.34679785e+04 1.29995117e+04 1.29491250e+04 1.28545791e+04 1.30526543e+04 1.31088730e+04 1.29806094e+04 1.26052510e+04 1.28540439e+04 1.33886953e+04 1.30446973e+04 1.30895967e+04 1.31804043e+04 1.29203252e+04 1.28966807e+04 1.27990820e+04 1.26923506e+04 1.24208408e+04 1.23624541e+04 1.26005898e+04 1.26573574e+04 1.30179482e+04 1.25846992e+04 1.21776055e+04 1.25450928e+04 1.25870547e+04 1.28468809e+04 1.26007178e+04 1.22666758e+04 1.23120088e+04 1.21562725e+04 1.23135020e+04 1.23403027e+04 1.25605273e+04 1.24063984e+04 1.20253496e+04 1.20565312e+04 1.17022041e+04 1.20813320e+04 1.27699355e+04 1.23940479e+04 1.19907627e+04 1.16888584e+04 1.14802441e+04 1.20166885e+04 1.23771270e+04 1.20265996e+04 1.15064375e+04 1.14322197e+04 1.17540547e+04 1.16656309e+04 1.18838525e+04 1.17261504e+04 1.13927119e+04 1.15212793e+04 1.14707725e+04 1.17643271e+04 1.16975361e+04 1.10612549e+04 1.10898691e+04 1.16320273e+04 1.13760908e+04 1.07711279e+04 1.11379189e+04 1.16623799e+04 1.14099658e+04 1.10801191e+04 1.08063506e+04 1.07586465e+04 1.12832490e+04 1.12214150e+04 1.09071709e+04 1.05816162e+04 1.04741973e+04 1.07805322e+04 1.08148271e+04 1.06864395e+04 1.03855098e+04 1.05964922e+04 1.08781895e+04 1.05500586e+04 1.06823711e+04 1.04997236e+04 1.01635371e+04 1.03581152e+04 1.03454648e+04 1.03388008e+04 1.02158975e+04 1.00462207e+04 9.78764258e+03 1.00594775e+04 1.06526807e+04 1.00249551e+04 9.50618945e+03 9.73847754e+03 1.00649961e+04 1.02876377e+04 9.98351367e+03 9.61646582e+03 9.82987305e+03 9.76897852e+03 9.37142383e+03 9.18952734e+03 9.72316113e+03 9.66124023e+03 9.31747266e+03 9.30188770e+03 8.91026953e+03 9.19984668e+03 9.75073535e+03 9.39072949e+03 9.12969629e+03 8.82983984e+03 8.65241016e+03 9.12080762e+03 9.52687793e+03 9.23598242e+03 8.68836328e+03 8.58906445e+03 8.71509082e+03 8.77821484e+03 8.92706836e+03 8.66123535e+03 8.33461328e+03 8.60492188e+03 8.47727930e+03 8.63849219e+03 8.51806445e+03 8.18863184e+03 8.37435645e+03 8.33252344e+03 8.20404199e+03 7.92893408e+03 8.01727881e+03 8.38261719e+03 8.27223633e+03 7.86752881e+03 7.63250586e+03 7.77592188e+03 8.14870117e+03 8.05175342e+03 7.71686816e+03 7.47762598e+03 7.40527148e+03 7.56404346e+03 7.60291406e+03 7.50712939e+03 7.24435547e+03 7.36808643e+03 7.55692969e+03 7.30189111e+03 7.39374316e+03 7.35738330e+03 7.09200488e+03 7.07154736e+03 7.03060547e+03 6.98255957e+03 6.94746240e+03 6.83660791e+03 6.73509668e+03 6.99759717e+03 6.92441602e+03 6.52169629e+03 6.46784424e+03 6.55374561e+03 6.63114258e+03 6.86662744e+03 6.56729297e+03 6.15411182e+03 6.38596973e+03 6.63453857e+03 6.41758789e+03 6.07798242e+03 6.04090723e+03 6.06165479e+03 6.08485254e+03 6.04137891e+03 5.83254541e+03 5.91903760e+03 6.15773975e+03 5.97239160e+03 5.79455469e+03 5.60325879e+03 5.58912744e+03 5.87435693e+03 5.74673584e+03 5.54904346e+03 5.42308936e+03 5.16847363e+03 5.24601904e+03 5.49816895e+03 5.66156641e+03 5.29208887e+03 5.01224414e+03 5.11378906e+03 5.14976074e+03 5.28952197e+03 5.15078076e+03 4.90378516e+03 4.97329346e+03 4.91604395e+03 4.79541650e+03 4.67697510e+03 4.72955029e+03 4.87603418e+03 4.75178125e+03 4.62933008e+03 4.51905615e+03 4.44834424e+03 4.61427686e+03 4.57630469e+03 4.42105664e+03 4.25574023e+03 4.16006494e+03 4.23676807e+03 4.19718799e+03 4.29936426e+03 4.29188721e+03 4.04628101e+03 3.90099756e+03 4.00334546e+03 4.12749365e+03 3.96211157e+03 3.83225806e+03 3.78974731e+03 3.75492383e+03 3.68990210e+03 3.56890918e+03 3.67549805e+03 3.68500244e+03 3.53431128e+03 3.57786914e+03 3.57312891e+03 3.47919116e+03 3.43498071e+03 3.36493970e+03 3.31692993e+03 3.19965625e+03 3.11762158e+03 3.21581567e+03 3.24820142e+03 3.08466650e+03 2.91793115e+03 2.97675269e+03 3.11431250e+03 3.08433472e+03 2.87573267e+03 2.73632935e+03 2.85018213e+03 2.91031665e+03 2.79784033e+03 2.74101392e+03 2.62075806e+03 2.48383643e+03 2.55090063e+03 2.66462231e+03 2.63567578e+03 2.45303394e+03 2.32649707e+03 2.43580518e+03 2.49995312e+03 2.38806396e+03 2.23479688e+03 2.14975049e+03 2.18959277e+03 2.19120605e+03 2.21162817e+03 2.20776074e+03 2.09763940e+03 2.01863306e+03 1.98744482e+03 2.03587793e+03 1.96168677e+03 1.87158228e+03 1.91399792e+03 1.87741589e+03 1.83132568e+03 1.75383618e+03 1.71743274e+03 1.78492639e+03 1.70002563e+03 1.58598035e+03 1.59248926e+03 1.62963257e+03 1.60332507e+03 1.53651294e+03 1.53865283e+03 1.51845947e+03 1.45126221e+03 1.38303552e+03 1.34416748e+03 1.39015112e+03 1.33676611e+03 1.26824976e+03 1.28127539e+03 1.24997205e+03 1.21260144e+03 1.17356152e+03 1.17186255e+03 1.15668945e+03 1.10092200e+03 1.08982373e+03 1.06924207e+03 1.04861609e+03 1.02132257e+03 9.85495850e+02 9.43378174e+02 8.92951599e+02 8.73999451e+02 8.96994385e+02 9.15667603e+02 8.42723694e+02 7.67951660e+02 7.77387634e+02 8.00978882e+02 7.85537231e+02 7.22499512e+02 6.70443665e+02 6.85417358e+02 6.78013245e+02 6.36633728e+02 6.41413574e+02 6.08335083e+02 5.55622559e+02 5.52195923e+02 5.64380737e+02 5.46779114e+02 5.00544769e+02 4.64117828e+02 4.67985443e+02 4.80027710e+02 4.50609741e+02 4.10709900e+02 3.84602966e+02 3.87658997e+02 3.85974152e+02 3.58852448e+02 3.38874878e+02 3.25345612e+02 3.13349121e+02 2.98100616e+02 2.91056580e+02 2.72834381e+02 2.49942871e+02 2.42817383e+02 2.32739914e+02 2.25367828e+02 2.07647964e+02 1.90880722e+02 1.88184280e+02 1.71826447e+02 1.57094559e+02 1.53658264e+02 1.46346664e+02 1.36204269e+02 1.24612617e+02 1.18862137e+02 1.10585022e+02 9.76400299e+01 8.74158401e+01 8.03757172e+01 7.87282028e+01 6.97834396e+01 6.01684227e+01 6.42119904e+01 8.24386063e+01 2.82815887e+02 15631226. 0. 0. 0. 0. 0. 0. 0. 0. 7232941. -3.75658375e+06 -3.75658375e+06 27873022. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -28123714. -21700862. 1.26443047e+02 6.69024506e+01 4.26791039e+01 3.91073608e+01 4.22736473e+01 4.54721985e+01 5.27214317e+01 5.91449928e+01 6.47256851e+01 7.16033173e+01 7.78269653e+01 8.26761856e+01 9.27072067e+01 1.04273743e+02 1.09432999e+02 1.16771561e+02 1.28268234e+02 1.39314636e+02 1.50099960e+02 1.55661743e+02 1.61472183e+02 1.75558655e+02 1.91619217e+02 2.03700745e+02 2.13334457e+02 2.21182816e+02 2.34773987e+02 2.56032898e+02 2.74019165e+02 2.79522888e+02 2.81271362e+02 2.98555634e+02 3.23234741e+02 3.35018860e+02 3.49365173e+02 3.67121857e+02 3.72289612e+02 3.95417511e+02 4.22053864e+02 4.22335663e+02 4.36770416e+02 4.68518555e+02 5.05394165e+02 5.26832581e+02 5.08477966e+02 5.09703156e+02 5.43498840e+02 5.85576660e+02 6.15835449e+02 6.10582825e+02 6.28486572e+02 6.70513428e+02 6.84246521e+02 7.04485107e+02 7.16163208e+02 7.15624756e+02 7.63581848e+02 8.11976868e+02 8.06587280e+02 8.26011719e+02 8.66872375e+02 8.74030396e+02 9.14344421e+02 9.47916443e+02 9.39226685e+02 9.55743958e+02 1.00210822e+03 1.06272412e+03 1.08333032e+03 1.06523645e+03 1.10032227e+03 1.12436926e+03 1.16394824e+03 1.22126233e+03 1.20169714e+03 1.21661511e+03 1.27811169e+03 1.33594263e+03 1.36869849e+03 1.35109021e+03 1.33873853e+03 1.38532898e+03 1.45796301e+03 1.50634619e+03 1.53767725e+03 1.53934290e+03 1.55237329e+03 1.61765454e+03 1.67978284e+03 1.66696460e+03 1.64281213e+03 1.70452380e+03 1.79502112e+03 1.84544568e+03 1.84232788e+03 1.82567065e+03 1.84065723e+03 1.93899658e+03 2.00571545e+03 1.97389404e+03 2.00426025e+03 2.09917896e+03 2.18178247e+03 2.21188477e+03 2.12821045e+03 2.11161816e+03 2.22810693e+03 2.30210010e+03 2.33092944e+03 2.34471826e+03 2.40024438e+03 2.48002295e+03 2.45931836e+03 2.48706104e+03 2.57342285e+03 2.56401514e+03 2.57238794e+03 2.68294800e+03 2.74364917e+03 2.78281104e+03 2.77918579e+03 2.73814746e+03 2.79393579e+03 2.92518823e+03 3.00085864e+03 2.98770435e+03 2.97717432e+03 3.03916504e+03 3.16267871e+03 3.23487329e+03 3.16978564e+03 3.10246558e+03 3.18987646e+03 3.33352368e+03 3.38805127e+03 3.38648608e+03 3.39847632e+03 3.44805371e+03 3.56210889e+03 3.63600488e+03 3.61652271e+03 3.64034180e+03 3.64045630e+03 3.72603882e+03 3.75561084e+03 3.75713574e+03 3.84245020e+03 3.90715967e+03 4.02226660e+03 4.12617871e+03 4.01995386e+03 3.97618384e+03 4.08324805e+03 4.20703760e+03 4.31147217e+03 4.32326270e+03 4.17881641e+03 4.23809863e+03 4.47867041e+03 4.63414844e+03 4.49819971e+03 4.39624951e+03 4.51107031e+03 4.72619531e+03 4.76054688e+03 4.57188867e+03 4.62817920e+03 4.85238721e+03 4.92067285e+03 4.88499414e+03 5.01251025e+03 5.06382275e+03 4.91379102e+03 5.09572705e+03 5.29150586e+03 5.11549512e+03 5.14504541e+03 5.28557031e+03 5.41551709e+03 5.50477393e+03 5.43980127e+03 5.27692236e+03 5.37493164e+03 5.63390576e+03 5.86096729e+03 5.87662061e+03 5.60697119e+03 5.69196680e+03 5.97746729e+03 5.93801416e+03 5.74296338e+03 5.81350928e+03 5.98034229e+03 6.18113916e+03 6.28930566e+03 6.29091553e+03 6.14772852e+03 6.04661816e+03 6.29426807e+03 6.48833936e+03 6.34140088e+03 6.40641406e+03 6.58715234e+03 6.69357617e+03 6.79179150e+03 6.61292139e+03 6.47091699e+03 6.64006396e+03 6.77434912e+03 7.05251416e+03 7.10321777e+03 6.82693701e+03 6.85465479e+03 7.10151904e+03 7.24805811e+03 7.26670312e+03 7.05837354e+03 7.12691016e+03 7.39093066e+03 7.48402734e+03 7.48191699e+03 7.34880273e+03 7.31649707e+03 7.54051074e+03 7.78951904e+03 7.61180225e+03 7.68428125e+03 7.84812354e+03 7.90740088e+03 8.05615234e+03 7.85829443e+03 7.72751562e+03 7.94251367e+03 8.05386279e+03 8.20543164e+03 8.03752393e+03 7.91540332e+03 8.26747266e+03 8.56257324e+03 8.46665625e+03 8.34349316e+03 8.43101660e+03 8.34972363e+03 8.43211035e+03 8.67864941e+03 9.01541699e+03 8.76483496e+03 8.55548828e+03 8.85415723e+03 8.79747754e+03 8.94063184e+03 8.93961816e+03 8.74848047e+03 8.99378711e+03 9.26080762e+03 8.95215625e+03 8.93132812e+03 9.14519531e+03 9.47290918e+03 9.60689941e+03 9.17589160e+03 9.14698242e+03 9.44964062e+03 9.58133691e+03 9.77525781e+03 9.49594141e+03 9.55122559e+03 9.51002734e+03 9.61951367e+03 9.99797949e+03 9.92003711e+03 9.62850586e+03 9.86378516e+03 1.02472900e+04 9.95952930e+03 9.90015820e+03 9.89369043e+03 9.92901855e+03 1.03525312e+04 1.05379873e+04 1.02632139e+04 1.01046748e+04 1.02997539e+04 1.05316289e+04 1.07184453e+04 1.04345879e+04 1.06425234e+04 1.07636836e+04 1.03248789e+04 1.04808379e+04 1.06332764e+04 1.06921660e+04 1.09397803e+04 1.08371094e+04 1.08528818e+04 1.11636201e+04 1.09540420e+04 1.07704902e+04 1.10490381e+04 1.12857148e+04 1.12929355e+04 1.09499775e+04 1.09111748e+04 1.14762480e+04 1.16853867e+04 1.12340039e+04 1.10970488e+04 1.13180459e+04 1.16458457e+04 1.18126123e+04 1.14134854e+04 1.14481650e+04 1.14527959e+04 1.17154570e+04 1.19493750e+04 1.15623379e+04 1.16540176e+04 1.17832275e+04 1.17590547e+04 1.19665742e+04 1.22116172e+04 1.19194229e+04 1.16344570e+04 1.22737402e+04 1.26880254e+04 1.20259258e+04 1.16086172e+04 1.19105186e+04 1.23992959e+04 1.24246523e+04 1.21788877e+04 1.20867832e+04 1.22441367e+04 1.26200713e+04 1.26782363e+04 1.23522627e+04 1.23504658e+04 1.24047783e+04 1.26913545e+04 1.27400273e+04 1.23935254e+04 1.25793213e+04 1.25982812e+04 1.26078672e+04 1.28593066e+04 1.28929658e+04 1.26668369e+04 1.25936172e+04 1.29553672e+04 1.30444189e+04 1.28445615e+04 1.27217285e+04 1.28321465e+04 1.31449766e+04 1.31834961e+04 1.27596348e+04 1.28071641e+04 1.30640508e+04 1.34781465e+04 1.35438135e+04 1.30573564e+04 1.33916836e+04 1.32827061e+04 1.28304062e+04 1.29716357e+04 1.31855254e+04 1.36773535e+04 1.35969297e+04 1.30135352e+04 1.29142090e+04 1.33572812e+04 1.38029502e+04 1.37670371e+04 1.36008799e+04 1.34895723e+04 1.33772646e+04 1.32817305e+04 1.32644629e+04 1.37313965e+04 1.39153604e+04 1.34241787e+04 1.34655479e+04 1.35852979e+04 1.37152080e+04 1.39465107e+04 1.38550381e+04 1.40809043e+04 1.37782441e+04 1.32775156e+04 1.33988838e+04 1.38486953e+04 1.42234365e+04 1.42804951e+04 1.39202256e+04 1.32952432e+04 1.35410459e+04 1.39002676e+04 1.38606621e+04 1.42779141e+04 1.41886611e+04 1.36365020e+04 1.40838486e+04 1.41537773e+04 1.38592207e+04 1.40797578e+04 1.39417783e+04 1.37544023e+04 1.37382812e+04 1.39049697e+04 1.40188145e+04 1.44271680e+04 1.48053633e+04 1.41579668e+04 1.35995859e+04 1.36917217e+04 1.40507744e+04 1.45056846e+04 1.44618086e+04 1.38278047e+04 1.36784248e+04 1.40387178e+04 1.44644873e+04 1.46068975e+04 1.42181504e+04 1.41141738e+04 1.41175859e+04 1.40352998e+04 1.39509453e+04 1.42529141e+04 1.44640322e+04 1.43191846e+04 1.44005557e+04 1.39344004e+04 1.39229004e+04 1.43710879e+04 1.43977207e+04 1.45414141e+04 1.41793545e+04 1.37763447e+04 1.39176562e+04 1.43064834e+04 1.45884102e+04 1.46665879e+04 1.42661982e+04 1.36542031e+04 1.39822812e+04 1.41954785e+04 1.39541016e+04 1.43039395e+04 1.45099219e+04 1.40713848e+04 1.39497598e+04 1.40940576e+04 1.43599336e+04 1.44800254e+04 1.43046064e+04 1.43050713e+04 1.37859980e+04 1.37066533e+04 1.41318242e+04 14277. 1.44774629e+04 1.43874072e+04 1.40147383e+04 1.37216172e+04 1.40042959e+04 1.44543184e+04 1.43092246e+04 1.40867246e+04 1.40475059e+04 1.37917314e+04 1.38768838e+04 1.41471592e+04 1.40680098e+04 1.41224600e+04 1.39395303e+04 1.37429678e+04 1.37709316e+04 1.41091953e+04 1.41310889e+04 1.39798633e+04 1.41187949e+04 1.36898154e+04 1.37939004e+04 1.40046689e+04 1.38318145e+04 1.41872822e+04 1.39454102e+04 1.34630957e+04 1.34885107e+04 1.34973535e+04 1.38470225e+04 1.44532725e+04 1.40911025e+04 1.34392139e+04 1.33897256e+04 1.34001240e+04 1.33516016e+04 1.37578330e+04 1.39163984e+04 1.34706396e+04 1.33787490e+04 1.33053799e+04 1.34999014e+04 1.38322383e+04 1.36148047e+04 1.39346699e+04 1.35743555e+04 1.28162295e+04 1.30252617e+04 1.34607637e+04 1.36421055e+04 1.37600928e+04 1.32961094e+04 1.26156123e+04 1.30345488e+04 1.36412988e+04 1.33758320e+04 1.31781182e+04 1.31054570e+04 1.28407969e+04 1.30980137e+04 1.31521641e+04 1.29234902e+04 1.33531084e+04 1.31206484e+04 1.28499453e+04 1.29113926e+04 1.25726494e+04 1.26775664e+04 1.29879541e+04 1.33038340e+04 1.29264404e+04 1.22004502e+04 1.23342725e+04 1.27551289e+04 1.29360303e+04 1.27960420e+04 1.23997471e+04 1.22283799e+04 1.24388955e+04 1.26725068e+04 1.27115566e+04 1.25950869e+04 1.24472607e+04 1.23121230e+04 1.22812256e+04 1.22307822e+04 1.22016953e+04 1.23076328e+04 1.22774355e+04 1.23261035e+04 1.19958242e+04 1.18550654e+04 1.21846719e+04 1.20961709e+04 1.23420449e+04 1.20815977e+04 1.14819141e+04 1.15540449e+04 1.18195479e+04 1.21330537e+04 1.22466162e+04 1.17198975e+04 1.13457480e+04 1.14648066e+04 1.16276279e+04 1.16330771e+04 1.16292734e+04 1.15964580e+04 1.12830234e+04 1.10968936e+04 1.12505801e+04 1.14521963e+04 1.15913789e+04 1.13813037e+04 1.14095107e+04 1.10839990e+04 1.06768213e+04 1.09079336e+04 1.10925713e+04 1.13090420e+04 1.12515283e+04 1.06635957e+04 1.04512402e+04 1.07559102e+04 1.11776211e+04 1.09628857e+04 1.07610918e+04 1.06213281e+04 1.02950527e+04 1.05549053e+04 1.07719951e+04 1.04968135e+04 1.04389365e+04 1.03869336e+04 1.03681846e+04 1.03208135e+04 1.02832715e+04 1.03299785e+04 1.02776035e+04 1.01659199e+04 9.89812109e+03 9.96756445e+03 1.00152822e+04 9.97473242e+03 1.02979258e+04 9.96828809e+03 9.56189355e+03 9.65411328e+03 9.47082324e+03 9.76608594e+03 1.01423203e+04 9.88540332e+03 9.30006934e+03 9.17592773e+03 9.51750586e+03 9.62564160e+03 9.38266992e+03 9.86176367e+03 1.02562910e+04 1.25682627e+04 1.40535645e+04 2.37996758e+04 9.21666562e+04 -87414224. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 161005664. 1.01525992e+05 2.03256074e+04 1.35867354e+04 9.33947754e+03 8.46236719e+03 7.19831055e+03 7.03507520e+03 6.95400146e+03 6.85159033e+03 6.45451025e+03 6.55711035e+03 6.85954297e+03 6.79149902e+03 6.39538672e+03 6.09927246e+03 6.15454834e+03 6.46422900e+03 6.60352197e+03 6.31331934e+03 6.05351758e+03 5.92149805e+03 5.96836035e+03 6.22837842e+03 6.17049414e+03 5.86421680e+03 5.73890576e+03 5.71391650e+03 5.75203223e+03 5.72163428e+03 5.57902246e+03 5.57650000e+03 5.71889355e+03 5.77554346e+03 5.46313916e+03 5.14841846e+03 5.23703076e+03 5.44867822e+03 5.57571436e+03 5.30443555e+03 4.99629834e+03 4.94841992e+03 5.17759229e+03 5.31352393e+03 5.09251709e+03 4.73861133e+03 4.71712256e+03 4.87845557e+03 4.96135010e+03 4.92320850e+03 4.77284180e+03 4.59939307e+03 4.54348096e+03 4.65591748e+03 4.46243848e+03 4.36070166e+03 4.54132715e+03 4.50545361e+03 4.43664990e+03 4.22972852e+03 4.04403198e+03 4.22426514e+03 4.42368164e+03 4.25936816e+03 3.96292505e+03 3.80898267e+03 3.83908154e+03 4.02884399e+03 4.11504102e+03 3.94952368e+03 3.82998975e+03 3.73053125e+03 3.59114746e+03 3.64841089e+03 3.72690723e+03 3.56835767e+03 3.51532031e+03 3.50140015e+03 3.49685620e+03 3.38019751e+03 3.29950854e+03 3.36692993e+03 3.39074121e+03 3.34228809e+03 3.20729175e+03 3.03346704e+03 3.00893311e+03 3.14080347e+03 3.23524121e+03 3.05801001e+03 2.83085278e+03 2.82822778e+03 2.89221948e+03 2.93186963e+03 2.90803784e+03 2.76248315e+03 2.69559473e+03 2.66304272e+03 2.66138843e+03 2.66049634e+03 2.57562939e+03 2.52300439e+03 2.47910181e+03 2.46795166e+03 2.43786011e+03 2.36666455e+03 2.36138330e+03 2.35018677e+03 2.34079248e+03 2.24085278e+03 2.10859790e+03 2.11767163e+03 2.18993091e+03 2.20224609e+03 2.06853198e+03 1.93293225e+03 1.90785107e+03 1.98727771e+03 2.05850244e+03 1.93047290e+03 1.79737695e+03 1.80180139e+03 1.76923279e+03 1.75089539e+03 1.73810339e+03 1.68162622e+03 1.67988550e+03 1.63470813e+03 1.59525085e+03 1.56758447e+03 1.50018420e+03 1.50845361e+03 1.53391418e+03 1.49378809e+03 1.41022070e+03 1.34103198e+03 1.31547534e+03 1.33935474e+03 1.36722083e+03 1.28431030e+03 1.18811304e+03 1.18091785e+03 1.21247375e+03 1.21965503e+03 1.14658435e+03 1.08929895e+03 1.07069006e+03 1.04119666e+03 1.03648425e+03 1.02183813e+03 9.55150452e+02 9.27037354e+02 9.34569519e+02 9.24486328e+02 8.89276306e+02 8.44726868e+02 8.26707886e+02 8.15786804e+02 8.14074280e+02 7.74862793e+02 7.10153503e+02 7.00261780e+02 7.02567566e+02 6.90500183e+02 6.66948181e+02 6.25271912e+02 6.01251343e+02 5.91402832e+02 5.86452637e+02 5.64817688e+02 5.30688110e+02 5.18218872e+02 5.03136108e+02 4.84429352e+02 4.62683838e+02 4.37356720e+02 4.27885590e+02 4.23956696e+02 4.12734131e+02 3.81770813e+02 3.48764130e+02 3.37543365e+02 3.38147003e+02 3.35138367e+02 3.07930298e+02 2.78499969e+02 2.68460022e+02 2.62131195e+02 2.54856598e+02 2.43256088e+02 2.22357834e+02 2.07973816e+02 1.99646576e+02 1.90086578e+02 1.79112930e+02 1.66898193e+02 1.56571030e+02 1.44782272e+02 1.36562332e+02 1.27645615e+02 1.16847694e+02 1.09100266e+02 1.01249771e+02 9.39965668e+01 8.29332733e+01 7.39475250e+01 7.01556320e+01 6.58399506e+01 5.96301193e+01 5.12700272e+01 4.36016541e+01 3.85656776e+01 3.55933418e+01 3.23297005e+01 2.70320625e+01 2.19315510e+01 1.79346504e+01 1.47971048e+01 1.23940477e+01 1.00403204e+01 7.63005495e+00 5.61322641e+00 4.02958298e+00 2.81647658e+00 1.94587839e+00 1.45076180e+00 1.29435158e+00 1.48390782e+00 2.03275037e+00 2.90797687e+00 3.96714544e+00 5.55835342e+00 7.67197561e+00 9.97941589e+00 1.26279144e+01 1.54469604e+01 1.90253239e+01 2.28502922e+01 2.59247665e+01 2.92390347e+01 3.43794975e+01 4.13258591e+01 4.81964264e+01 5.31214790e+01 5.62788353e+01 6.08111763e+01 6.87435837e+01 7.97004623e+01 8.95393829e+01 9.56892166e+01 9.84263153e+01 1.06470894e+02 1.22194633e+02 1.31140533e+02 1.33925903e+02 1.43215347e+02 1.56734451e+02 1.67271164e+02 1.83274734e+02 1.90350449e+02 1.94924561e+02 2.11604965e+02 2.19068115e+02 2.37173096e+02 2.58267670e+02 2.57974976e+02 2.75118988e+02 2.98621307e+02 3.06682068e+02 3.19916473e+02 3.32637451e+02 3.50278412e+02 3.70858459e+02 3.81535461e+02 3.84313049e+02 4.04736847e+02 4.41671021e+02 4.66776520e+02 4.74778748e+02 4.75065399e+02 4.81497437e+02 5.08107819e+02 5.50242859e+02 5.82523743e+02 5.92717346e+02 5.80920532e+02 6.00341553e+02 6.45619690e+02 6.60622681e+02 6.74315247e+02 6.96799438e+02 7.17997437e+02 7.39560364e+02 7.89607361e+02 7.96021301e+02 7.87521973e+02 8.25254150e+02 8.29852661e+02 8.89057861e+02 9.37028564e+02 9.24613403e+02 9.83931030e+02 9.87188354e+02 9.68992493e+02 1.02461572e+03 1.03264856e+03 1.07846094e+03 1.17474365e+03 1.14351831e+03 1.11080090e+03 1.16030420e+03 1.23261108e+03 1.31182874e+03 1.30876367e+03 1.27142456e+03 1.26303845e+03 1.31109851e+03 1.41775830e+03 1.50329480e+03 1.49674219e+03 1.44966101e+03 1.46340222e+03 1.55051685e+03 1.60470764e+03 1.58523584e+03 1.59893604e+03 1.66004211e+03 1.69930579e+03 1.77463208e+03 1.81173389e+03 1.77571985e+03 1.80259546e+03 1.82470642e+03 1.86833740e+03 1.94517529e+03 1.96380286e+03 2.05060205e+03 2.04991675e+03 2.00117285e+03 2.08681372e+03 2.07562573e+03 2.16963354e+03 2.34816260e+03 2.26239087e+03 2.14989233e+03 2.23346558e+03 2.39921802e+03 2.49295093e+03 2.53514014e+03 2.45404810e+03 2.38018701e+03 2.45600244e+03 2.62626318e+03 2.79845752e+03 2.73618359e+03 2.60537866e+03 2.61472461e+03 2.74859326e+03 2.85820117e+03 2.97169263e+03 2.99432886e+03 2.86589429e+03 2.87180737e+03 3.01891455e+03 3.11481201e+03 3.11735767e+03 3.13995068e+03 3.13390747e+03 3.15917773e+03 3.33567725e+03 3.39994873e+03 3.26820239e+03 3.30270312e+03 3.43448633e+03 3.46592822e+03 3.52787231e+03 3.53579053e+03 3.65846729e+03 3.73255396e+03 3.65707373e+03 3.63484204e+03 3.64711450e+03 3.81860693e+03 4.05409180e+03 4.02517651e+03 3.87156836e+03 3.80211646e+03 4.00862061e+03 4.27603662e+03 4.15012646e+03 3.99485791e+03 4.11803760e+03 4.26709668e+03 4.40664844e+03 4.57859082e+03 4.56280859e+03 4.33746289e+03 4.26177637e+03 4.45504688e+03 4.74802295e+03 4.79709131e+03 4.68029785e+03 4.67157520e+03 4.74970361e+03 4.88713037e+03 4.87541504e+03 4.81018066e+03 4.86441895e+03 4.86643994e+03 5.10774072e+03 5.31585547e+03 5.13505811e+03 5.18632764e+03 5.28133691e+03 5.44695605e+03 5.35090527e+03 5.14484473e+03 5.45778857e+03 5.80517285e+03 5.60887158e+03 5.37144775e+03 5.55617285e+03 5.91658350e+03 5.90784570e+03 5.80226709e+03 5.87638623e+03 5.71391602e+03 5.75186426e+03 6.14078467e+03 6.16588623e+03 5.98929492e+03 5.90157617e+03 5.93572705e+03 6.26870850e+03 6.58604492e+03 6.39507812e+03 6.25579297e+03 6.39736865e+03 6.45684082e+03 6.76270459e+03 6.80820166e+03 6.45983008e+03 6.47231787e+03 6.64719141e+03 6.75989893e+03 6.86856689e+03 6.90016943e+03 7.08734277e+03 7.07344482e+03 6.89395996e+03 6.90494141e+03 6.84852148e+03 7.16621045e+03 7.66313818e+03 7.51297461e+03 7.13251807e+03 7.12399609e+03 7.41881738e+03 7.52781836e+03 8.35547559e+03 8.69312598e+03 7.93791064e+03 9.79955566e+03 1.60752324e+04 1.71673500e+05 1.48897375e+06 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. 0. 0. 0. 0. 0. 0. 29878270. 3.21532305e+04 9.51794824e+03 1.33314736e+04 1.04507363e+04 1.02135088e+04 1.00134717e+04 9.70537305e+03 9.66279395e+03 1.00941436e+04 1.01993828e+04 1.00213418e+04 1.01623809e+04 1.01759980e+04 1.01479863e+04 1.02619717e+04 1.02667051e+04 1.02524961e+04 1.03348389e+04 1.04310029e+04 1.03906855e+04 1.01850107e+04 1.01799912e+04 1.07678457e+04 1.08408896e+04 1.03275039e+04 1.03452148e+04 1.09880381e+04 1.11027490e+04 1.08337705e+04 1.08439854e+04 1.08907803e+04 1.09130166e+04 1.09463760e+04 1.09815205e+04 1.10222988e+04 1.10508691e+04 1.08937285e+04 1.08893408e+04 1.14473008e+04 1.15326025e+04 1.12498936e+04 1.13081025e+04 1.13409297e+04 1.14081064e+04 1.14372441e+04 1.14087061e+04 1.15416592e+04 1.12514795e+04 1.12159043e+04 1.16273916e+04 1.16272998e+04 1.20213359e+04 1.21837354e+04 1.17865283e+04 1.14884482e+04 1.14862139e+04 1.22561377e+04 1.24276875e+04 1.19572334e+04 1.18189111e+04 1.19867344e+04 1.20922842e+04 1.20059980e+04 1.23854160e+04 1.24106348e+04 1.18177324e+04 1.17669834e+04 1.24347393e+04 1.27977627e+04 1.24918193e+04 1.23768643e+04 1.24650293e+04 1.24400391e+04 1.22677734e+04 1.23283291e+04 1.26408467e+04 1.26728984e+04 1.24583447e+04 1.24932051e+04 1.26763262e+04 1.26599932e+04 1.30363721e+04 1.30129004e+04 1.26178027e+04 1.28584883e+04 1.28726709e+04 1.30371748e+04 1.31559990e+04 1.29406641e+04 1.29576592e+04 1.27833613e+04 1.26140186e+04 1.31658271e+04 1.32157422e+04 1.25855469e+04 1.28003096e+04 1.35941934e+04 1.39858994e+04 1.35531260e+04 1.32490986e+04 1.30346152e+04 1.30311807e+04 1.31956270e+04 1.31960508e+04 1.34022275e+04 1.33957109e+04 1.36365078e+04 1.35816758e+04 1.32814521e+04 1.35435781e+04 1.31977607e+04 1.32516279e+04 1.40530928e+04 1.39251025e+04 1.35851172e+04 1.32932754e+04 1.32380352e+04 1.40013662e+04 1.40829834e+04 1.36209043e+04 1.33023994e+04 1.33411211e+04 1.37436279e+04 1.37205537e+04 1.41018252e+04 1.42453721e+04 1.38283057e+04 1.36780039e+04 1.37394287e+04 1.40674336e+04 1.40246836e+04 1.38319414e+04 1.36499219e+04 1.36933125e+04 1.40374619e+04 1.36450244e+04 1.36526787e+04 1.44536094e+04 1.43997578e+04 1.40546816e+04 1.36027891e+04 1.35828594e+04 1.44736582e+04 1.44626660e+04 1.40947266e+04 1.37149932e+04 1.36279346e+04 1.41236846e+04 1.40778330e+04 1.40783701e+04 1.38138418e+04 1.40590996e+04 1.47404541e+04 1.43718672e+04 1.42662578e+04 1.43226562e+04 1.42066123e+04 1.40053867e+04 1.39461094e+04 1.41977402e+04 1.42559561e+04 1.42975605e+04 1.37971895e+04 1.38475850e+04 1.48150020e+04 1.42627822e+04 1.37170645e+04 1.41348584e+04 1.41965479e+04 1.46570771e+04 1.43478076e+04 1.37596562e+04 1.45082148e+04 1.46745264e+04 1.42203359e+04 1.39769414e+04 1.39643096e+04 1.41052881e+04 1.41653809e+04 1.42476094e+04 1.38627305e+04 1.41379111e+04 1.48594912e+04 1.46237246e+04 1.41437520e+04 1.36646211e+04 1.38570049e+04 1.47381494e+04 1.46111514e+04 1.42145977e+04 1.39325596e+04 1.38043115e+04 1.41130742e+04 1.41454883e+04 1.45283359e+04 1.42173643e+04 1.37503340e+04 1.41154268e+04 1.41769961e+04 1.44279043e+04 1.42049395e+04 1.38592314e+04 1.40225410e+04 1.39676631e+04 1.41042402e+04 1.37408984e+04 1.39933525e+04 1.48393828e+04 1.43741416e+04 1.40229326e+04 1.36806426e+04 1.35144170e+04 1.43263525e+04 1.44681025e+04 1.40347783e+04 1.35452598e+04 1.35085146e+04 1.39713535e+04 1.39437568e+04 1.42841621e+04 1.41996582e+04 1.38578164e+04 1.34677324e+04 1.33544736e+04 1.41853066e+04 1.40397988e+04 1.36217705e+04 1.35210371e+04 1.34689609e+04 1.40635312e+04 1.40916533e+04 1.34051133e+04 1.32774355e+04 1.38903174e+04 1.40110566e+04 1.33016875e+04 1.32042090e+04 1.38635771e+04 1.38872549e+04 1.34887354e+04 1.32070703e+04 1.31271455e+04 1.38018945e+04 1.36260967e+04 1.31652480e+04 1.32724912e+04 1.32333271e+04 1.35347676e+04 1.34916582e+04 1.30971084e+04 1.27268037e+04 1.31287510e+04 1.38680557e+04 1.34269404e+04 1.31922734e+04 1.33258662e+04 1.31867197e+04 1.31568184e+04 1.30845117e+04 1.29725840e+04 1.26730859e+04 1.25716670e+04 1.28605420e+04 1.29837041e+04 1.32969414e+04 1.28888037e+04 1.23900469e+04 1.26987959e+04 1.29265723e+04 1.32004658e+04 1.28872637e+04 1.25022109e+04 1.25425225e+04 1.24176895e+04 1.25447344e+04 1.25638193e+04 1.28161699e+04 1.27391055e+04 1.23763809e+04 1.22181055e+04 1.18689814e+04 1.22917139e+04 1.30326445e+04 1.26767295e+04 1.22886982e+04 1.19579580e+04 1.16312148e+04 1.21781895e+04 1.27144727e+04 1.23401895e+04 1.17486240e+04 1.16390938e+04 1.19421816e+04 1.19470244e+04 1.22002588e+04 1.21110430e+04 1.17423623e+04 1.16283408e+04 1.15761572e+04 1.20097500e+04 1.19466631e+04 1.13047109e+04 1.12940293e+04 1.18832920e+04 1.16621787e+04 1.10973857e+04 1.12755508e+04 1.18601543e+04 1.16385967e+04 1.12987529e+04 1.10258145e+04 1.09799453e+04 1.15188086e+04 1.14897607e+04 1.11782715e+04 1.08253555e+04 1.06740195e+04 1.09980430e+04 1.10194697e+04 1.08973682e+04 1.05887979e+04 1.07984072e+04 1.11628643e+04 1.07713428e+04 1.09500674e+04 1.08333184e+04 1.04459131e+04 1.05795439e+04 1.05950088e+04 1.05131211e+04 1.04126553e+04 1.01721064e+04 9.92831445e+03 1.02968340e+04 1.08860957e+04 1.02902383e+04 9.72446094e+03 1.00145469e+04 1.01506680e+04 1.04095049e+04 1.01268271e+04 9.74631543e+03 1.01088350e+04 1.00600645e+04 9.55798633e+03 9.39292578e+03 9.90267480e+03 9.92355078e+03 9.60844238e+03 9.39673926e+03 8.98555762e+03 9.40741016e+03 1.00461494e+04 9.63579590e+03 9.30493262e+03 9.02761914e+03 8.77821582e+03 9.24767188e+03 9.69018164e+03 9.39802246e+03 8.86487793e+03 8.74170508e+03 8.91049121e+03 8.94666699e+03 9.16008887e+03 8.84627148e+03 8.54952148e+03 8.75784668e+03 8.61624316e+03 8.88233398e+03 8.79942676e+03 8.41677246e+03 8.41674023e+03 8.41686816e+03 8.51373242e+03 8.23353809e+03 8.11701270e+03 8.47803906e+03 8.39793555e+03 8.07525586e+03 7.84953467e+03 7.89358643e+03 8.27241895e+03 8.21952051e+03 7.90117773e+03 7.68136084e+03 7.55530273e+03 7.71931689e+03 7.69832129e+03 7.66208447e+03 7.41842041e+03 7.49798828e+03 7.76680176e+03 7.45979736e+03 7.56158154e+03 7.58158643e+03 7.27639160e+03 7.16269824e+03 7.07855078e+03 7.21673145e+03 7.20863037e+03 6.88294922e+03 6.82031396e+03 7.17475439e+03 7.17047363e+03 6.67345996e+03 6.51032178e+03 6.62939160e+03 6.81460156e+03 6.99418555e+03 6.69446533e+03 6.33658936e+03 6.57655029e+03 6.72057617e+03 6.47355420e+03 6.28535352e+03 6.25765576e+03 6.14845703e+03 6.14391943e+03 6.16105029e+03 5.92446680e+03 6.06068066e+03 6.30174170e+03 6.03305469e+03 6.00066357e+03 5.82867432e+03 5.69771924e+03 5.91969092e+03 5.85622998e+03 5.68953857e+03 5.53385254e+03 5.31038135e+03 5.37709229e+03 5.59694678e+03 5.77439502e+03 5.39530176e+03 5.16702295e+03 5.24214355e+03 5.26425732e+03 5.35875537e+03 5.30937061e+03 5.07200635e+03 5.01457910e+03 4.93158154e+03 4.91362451e+03 4.76374316e+03 4.82649609e+03 4.96984131e+03 4.80082910e+03 4.80666699e+03 4.65515625e+03 4.51827246e+03 4.72275049e+03 4.69144678e+03 4.47616064e+03 4.32494141e+03 4.25806396e+03 4.32803076e+03 4.28828320e+03 4.36923291e+03 4.38142871e+03 4.15937109e+03 4.02240796e+03 4.03182764e+03 4.16740820e+03 4.06855884e+03 3.94264429e+03 3.84052393e+03 3.79178809e+03 3.80764404e+03 3.71771362e+03 3.78222437e+03 3.75086255e+03 3.58664355e+03 3.65910938e+03 3.66463477e+03 3.52947925e+03 3.48095410e+03 3.43709863e+03 3.39430835e+03 3.25483911e+03 3.17708716e+03 3.31349219e+03 3.31373853e+03 3.11155859e+03 2.96282202e+03 3.07362573e+03 3.22589136e+03 3.12204810e+03 2.90730493e+03 2.80973535e+03 2.93811060e+03 2.92096948e+03 2.78482031e+03 2.81680908e+03 2.71214941e+03 2.54691504e+03 2.58844775e+03 2.69173120e+03 2.70715210e+03 2.52790356e+03 2.36614307e+03 2.46950122e+03 2.55830615e+03 2.44450537e+03 2.29570776e+03 2.23035571e+03 2.25593677e+03 2.23346362e+03 2.26255981e+03 2.21428931e+03 2.10710791e+03 2.08023608e+03 2.04909253e+03 2.07363574e+03 2.00471777e+03 1.90966199e+03 1.93999231e+03 1.90055237e+03 1.88258398e+03 1.81729871e+03 1.75148743e+03 1.82065125e+03 1.74272559e+03 1.63118835e+03 1.63376050e+03 1.64560583e+03 1.62527771e+03 1.56810522e+03 1.56679956e+03 1.54835608e+03 1.48509460e+03 1.41724683e+03 1.37227917e+03 1.41570557e+03 1.36177698e+03 1.29731763e+03 1.30551086e+03 1.27400964e+03 1.24431104e+03 1.21002686e+03 1.21044287e+03 1.17232520e+03 1.11098450e+03 1.12241223e+03 1.10257544e+03 1.06251038e+03 1.03543396e+03 1.00434216e+03 9.69224426e+02 9.20880859e+02 8.83456970e+02 9.05822632e+02 9.33500916e+02 8.58712341e+02 7.86467773e+02 7.99396179e+02 8.25498169e+02 7.95139771e+02 7.30433228e+02 6.91747620e+02 7.07686951e+02 6.85851624e+02 6.45034485e+02 6.52120850e+02 6.24754272e+02 5.76453674e+02 5.56917175e+02 5.64905579e+02 5.61339417e+02 5.15253235e+02 4.75670959e+02 4.77915375e+02 4.88832062e+02 4.60497498e+02 4.21042480e+02 3.93749695e+02 3.95007477e+02 3.96746429e+02 3.68628815e+02 3.41904388e+02 3.30559174e+02 3.20124298e+02 3.03797668e+02 2.97638977e+02 2.78002014e+02 2.55195740e+02 2.48341248e+02 2.37518570e+02 2.29405487e+02 2.12201569e+02 1.95092819e+02 1.89392746e+02 1.74431290e+02 1.63954025e+02 1.59304504e+02 1.47765137e+02 1.37345062e+02 1.26971001e+02 1.21537239e+02 1.13062332e+02 1.00361397e+02 8.96565933e+01 8.23970184e+01 8.01543121e+01 7.10227509e+01 6.43486404e+01 7.26426010e+01 1.26145340e+02 4.52139404e+02 -39430612. 0. 0. 0. 0. 30754988. -11310162. 24337942. 4365517. 1.51789503e+01 1.89133091e+01 5.64857330e+01 27873022. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -28123714. -21700862. -15973612. 1.28146820e+02 8.35186920e+01 4.28814125e+01 4.89135284e+01 4.86626091e+01 5.53010216e+01 6.24902802e+01 6.61798553e+01 7.15171356e+01 8.01452942e+01 8.71939545e+01 9.56491318e+01 1.07268982e+02 1.14462341e+02 1.18799484e+02 1.30039429e+02 1.43009262e+02 1.49977280e+02 1.58324127e+02 1.68629730e+02 1.81546783e+02 1.96929596e+02 2.08122803e+02 2.14008347e+02 2.20248444e+02 2.39112473e+02 2.60091339e+02 2.68504303e+02 2.82804260e+02 2.94779327e+02 3.04629089e+02 3.28416382e+02 3.38072449e+02 3.42807953e+02 3.63475861e+02 3.79710358e+02 4.02365417e+02 4.24134186e+02 4.29793976e+02 4.44544403e+02 4.75839813e+02 5.17236084e+02 5.22592346e+02 5.02211914e+02 5.20269653e+02 5.55183899e+02 5.85586487e+02 6.19132019e+02 6.26342957e+02 6.29344299e+02 6.67262085e+02 6.95368469e+02 6.99296692e+02 7.16774963e+02 7.36241516e+02 7.82032471e+02 8.33313965e+02 8.13415649e+02 8.09752075e+02 8.55564453e+02 8.96203064e+02 9.35751648e+02 9.46866577e+02 9.45217957e+02 9.64733643e+02 1.01290295e+03 1.08464673e+03 1.08368396e+03 1.05036597e+03 1.10076282e+03 1.15290222e+03 1.17703674e+03 1.22214612e+03 1.22872058e+03 1.22295276e+03 1.27787976e+03 1.35154480e+03 1.35082275e+03 1.34910413e+03 1.37305774e+03 1.41157996e+03 1.47870007e+03 1.53928271e+03 1.53417993e+03 1.51522180e+03 1.57002100e+03 1.64234167e+03 1.65047278e+03 1.65975415e+03 1.68546570e+03 1.74833411e+03 1.83678027e+03 1.83376868e+03 1.79948792e+03 1.82834424e+03 1.88397144e+03 1.95198950e+03 2.00203271e+03 2.00645947e+03 2.03369800e+03 2.11782397e+03 2.21301685e+03 2.19749463e+03 2.11231323e+03 2.16335889e+03 2.27237451e+03 2.32474902e+03 2.36385742e+03 2.35270825e+03 2.36138232e+03 2.47554932e+03 2.52568896e+03 2.49485059e+03 2.55605981e+03 2.60457397e+03 2.62147974e+03 2.72693262e+03 2.75838257e+03 2.70504199e+03 2.76858154e+03 2.81866431e+03 2.83182983e+03 2.96910425e+03 3.06702832e+03 3.00032837e+03 2.94279370e+03 3.05818188e+03 3.18942114e+03 3.18388623e+03 3.16969629e+03 3.18128491e+03 3.23544238e+03 3.37764355e+03 3.45362720e+03 3.38057715e+03 3.39432422e+03 3.47163428e+03 3.56822852e+03 3.63435205e+03 3.63703271e+03 3.65857520e+03 3.73693481e+03 3.82014673e+03 3.75839917e+03 3.72779395e+03 3.86887573e+03 3.92725098e+03 4.01507861e+03 4.15506982e+03 4.08827368e+03 3.99805249e+03 4.13661426e+03 4.29416846e+03 4.28676953e+03 4.28193018e+03 4.25028369e+03 4.30635791e+03 4.55927197e+03 4.63136914e+03 4.44154639e+03 4.44675049e+03 4.64316260e+03 4.78386035e+03 4.69703369e+03 4.59993945e+03 4.71456299e+03 4.90646289e+03 5.05157812e+03 4.91241943e+03 4.87644922e+03 5.00414893e+03 5.03155127e+03 5.12979492e+03 5.28180273e+03 5.21928271e+03 5.20806885e+03 5.36797705e+03 5.49962158e+03 5.37123047e+03 5.37673193e+03 5.43375244e+03 5.49450879e+03 5.64423193e+03 5.90328076e+03 5.88679688e+03 5.62585352e+03 5.73542334e+03 6.00091455e+03 5.84355518e+03 5.80581934e+03 5.88513477e+03 6.00396875e+03 6.27624951e+03 6.30711621e+03 6.11535742e+03 6.07805225e+03 6.20692139e+03 6384. 6.47602979e+03 6.39813184e+03 6.48870410e+03 6.66426660e+03 6.73780908e+03 6.64311035e+03 6.60652002e+03 6.67025879e+03 6.73466406e+03 6.86920312e+03 7.08701611e+03 7.13133203e+03 6.85330322e+03 6.96970605e+03 7.18212939e+03 7.12339209e+03 7.21310547e+03 7.17241309e+03 7.27003760e+03 7.58119824e+03 7.53657715e+03 7.37913330e+03 7.36685840e+03 7.44345361e+03 7.62224072e+03 7.76920166e+03 7.70188428e+03 7.68274512e+03 7.84995703e+03 8.01377881e+03 8.10648926e+03 7.87790723e+03 7.76222656e+03 8.01445801e+03 8.08429688e+03 8.30508105e+03 8.24220117e+03 8.01184277e+03 8.26676367e+03 8.55517676e+03 8.39595605e+03 8.36123242e+03 8.49910352e+03 8.54810938e+03 8.67943262e+03 8.53994629e+03 8.83701855e+03 8.86708301e+03 8.70094727e+03 8.96193945e+03 8.81156250e+03 8.87520215e+03 9.18783496e+03 8.93318750e+03 9.03769141e+03 9.24095605e+03 9.12190527e+03 8.93795801e+03 9.08719629e+03 9.56760156e+03 9.68518555e+03 9.27950781e+03 9.26829883e+03 9.54891797e+03 9.61950195e+03 9.70866699e+03 9.49375098e+03 9.57640430e+03 9.72912012e+03 9.95137012e+03 9.91656543e+03 9.79654102e+03 9.86570898e+03 9.94648926e+03 1.01832031e+04 9.99371875e+03 9.83152051e+03 1.00119629e+04 1.00530029e+04 1.02704971e+04 1.06172754e+04 1.04745781e+04 1.00891650e+04 1.01855547e+04 1.07133525e+04 1.08760195e+04 1.03462734e+04 1.06029443e+04 1.09355127e+04 1.05231885e+04 1.06299316e+04 1.05685742e+04 1.06661699e+04 1.11789424e+04 1.09782988e+04 1.07237061e+04 1.11497793e+04 1.12281211e+04 1.08614141e+04 1.10763818e+04 1.13213477e+04 1.13579150e+04 1.10628330e+04 1.09638047e+04 1.13587100e+04 1.16952490e+04 1.15022002e+04 1.11977988e+04 1.13049473e+04 1.17073887e+04 1.18871143e+04 1.14185518e+04 1.14162715e+04 1.16286885e+04 1.19073057e+04 1.19494521e+04 1.15386738e+04 1.16685234e+04 1.20751104e+04 1.20914902e+04 1.18735049e+04 1.20725605e+04 1.20891807e+04 1.18038643e+04 1.24091641e+04 1.26182637e+04 1.20089092e+04 1.16752803e+04 1.19565488e+04 1.24068350e+04 1.25405840e+04 1.24022588e+04 1.21887568e+04 1.22405703e+04 1.26860889e+04 1.28253271e+04 1.23644248e+04 1.22515625e+04 1.26401406e+04 1.30787129e+04 1.27544229e+04 1.23579072e+04 1.26967080e+04 1.27938330e+04 1.27764551e+04 1.27544785e+04 1.28714854e+04 1.28688516e+04 1.27191504e+04 1.29694609e+04 1.30544766e+04 1.29649004e+04 1.27539502e+04 1.28417949e+04 1.31154814e+04 1.31740762e+04 1.30526738e+04 1.30075693e+04 1.30948779e+04 1.35486084e+04 1.35539160e+04 1.30698115e+04 1.32547070e+04 1.34616826e+04 1.34364932e+04 1.32327412e+04 1.31445742e+04 1.36251533e+04 1.35799385e+04 1.31887422e+04 1.29784902e+04 1.34203398e+04 1.38996455e+04 1.37281836e+04 1.37227373e+04 1.35940635e+04 1.36951240e+04 1.34638145e+04 1.30659482e+04 1.35416270e+04 1.38710371e+04 1.38219072e+04 1.37994756e+04 1.34503320e+04 1.35326211e+04 1.39754434e+04 1.40582998e+04 1.41840557e+04 1.39191797e+04 1.35573887e+04 1.35081152e+04 1.39455586e+04 1.42620420e+04 1.40693096e+04 1.39502627e+04 1.35679570e+04 1.38500371e+04 1.41217354e+04 1.39224844e+04 1.41787480e+04 1.39213145e+04 1.38369414e+04 1.43135225e+04 1.39504248e+04 1.38488184e+04 1.43647812e+04 1.44295479e+04 1.39662930e+04 1.36144824e+04 1.38405508e+04 1.40865303e+04 1.45487715e+04 1.47604385e+04 1.42737520e+04 1.39460361e+04 1.37456016e+04 1.41767939e+04 1.46542881e+04 1.43677881e+04 1.40081768e+04 1.37343027e+04 1.39765801e+04 1.44176875e+04 1.46309941e+04 1.44581855e+04 1.42669883e+04 1.44713096e+04 1.42190898e+04 1.37583877e+04 1.40696729e+04 1.43946592e+04 1.45527881e+04 1.47954990e+04 1.41254775e+04 1.37280449e+04 1.42142305e+04 1.46696172e+04 1.46672021e+04 1.42077627e+04 1.40976064e+04 1.39966602e+04 1.43139561e+04 1.46660020e+04 1.45221104e+04 1.43627461e+04 1.39674736e+04 1.43211455e+04 1.43593213e+04 1.38468926e+04 1.41285615e+04 1.44731416e+04 1.44199121e+04 1.42944883e+04 1.40444160e+04 1.41968340e+04 1.44664717e+04 1.45479746e+04 1.45174668e+04 1.38200566e+04 1.37656953e+04 1.41971738e+04 1.44958467e+04 1.46105518e+04 1.43042783e+04 1.41990674e+04 1.38045557e+04 1.40638086e+04 1.45943418e+04 1.42691846e+04 1.41687500e+04 1.41424141e+04 1.40218945e+04 1.38405488e+04 1.39350977e+04 1.41939111e+04 1.42894971e+04 1.43521895e+04 1.39902588e+04 1.36848252e+04 1.39135029e+04 1.40400137e+04 1.41912617e+04 1.43439023e+04 1.38915439e+04 1.38738496e+04 1.38210732e+04 1.39075342e+04 1.43243096e+04 1.40398740e+04 1.38443721e+04 1.37115430e+04 1.34263662e+04 1.36415635e+04 1.44198184e+04 1.41822070e+04 1.35922041e+04 1.38107451e+04 1.36372422e+04 1.32517568e+04 1.35772793e+04 1.38246621e+04 1.38086094e+04 1.37405645e+04 1.33238750e+04 1.34016367e+04 1.37144971e+04 1.37878096e+04 1.41595186e+04 1.37347607e+04 1.30173643e+04 1.30266016e+04 1.34499316e+04 1.37069502e+04 1.35895967e+04 1.34114980e+04 1.28845449e+04 1.31627578e+04 1.36477852e+04 1.33416504e+04 1.32807471e+04 1.30480371e+04 1.30463613e+04 1.33545039e+04 1.30026680e+04 1.29084258e+04 1.35394775e+04 1.34720098e+04 1.30908203e+04 1.27899717e+04 1.23935586e+04 1.26651162e+04 1.31770908e+04 1.34692617e+04 1.31290439e+04 1.24740596e+04 1.23093994e+04 1.27173086e+04 1.29919404e+04 1.27509375e+04 1.26170869e+04 1.23595879e+04 1.23327910e+04 1.26748721e+04 1.27689277e+04 1.27173789e+04 1.25857666e+04 1.25871260e+04 1.23700312e+04 1.19978848e+04 1.21471836e+04 1.23933770e+04 1.24676016e+04 1.26277764e+04 1.21410410e+04 1.17160020e+04 1.20464590e+04 1.23013203e+04 1.24256934e+04 1.22293438e+04 1.17200371e+04 1.15404238e+04 1.18769453e+04 1.22736836e+04 1.22170596e+04 1.18346416e+04 1.16145029e+04 1.15882314e+04 1.15090869e+04 1.15006924e+04 1.16874873e+04 1.18201396e+04 1.15778613e+04 1.12582285e+04 1.11512891e+04 1.13087490e+04 1.15593906e+04 1.16844619e+04 1.15757285e+04 1.10690820e+04 1.07213779e+04 1.09409219e+04 1.12714375e+04 1.14928105e+04 1.13003594e+04 1.07429414e+04 1.04646191e+04 1.08257773e+04 1.12554668e+04 1.09286055e+04 1.08811211e+04 1.06836299e+04 1.03624736e+04 1.06648682e+04 1.06918760e+04 1.05739131e+04 1.05371055e+04 1.05638672e+04 1.05000361e+04 1.02104561e+04 1.03243281e+04 1.03743311e+04 1.04746475e+04 1.02867578e+04 1.00167021e+04 1.00421904e+04 9.81095508e+03 9.95825391e+03 1.04592041e+04 1.02073076e+04 9.65165332e+03 9.53840723e+03 9.61572266e+03 9.92004004e+03 1.01054893e+04 9.67784766e+03 9.40594629e+03 9.47195215e+03 9.54368945e+03 9.45507812e+03 9.52287109e+03 9.61496582e+03 9.77475586e+03 9.68838086e+03 1.07211328e+04 1.27913457e+04 4.63707852e+04 -43707112. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 161005664. -13986770. 1.74760888e+06 3.83147025e+06 2.30162598e+04 1.46850059e+04 7.54718359e+03 7.50767773e+03 7.16225781e+03 6.76709180e+03 6.46019482e+03 6.60790186e+03 6.96501953e+03 6.83543555e+03 6.45258545e+03 6.20280957e+03 6.11901904e+03 6.42052881e+03 6.69082178e+03 6.37602686e+03 6.12661816e+03 5.98791650e+03 6.00009570e+03 6.25798389e+03 6.17706787e+03 5.83594678e+03 5.78538184e+03 5.92038574e+03 5.81444727e+03 5.59070020e+03 5.63081885e+03 5.75127930e+03 5.85064404e+03 5.77516797e+03 5.47081152e+03 5.14227051e+03 5.27549365e+03 5.53657568e+03 5.58464697e+03 5.35559912e+03 5.07708594e+03 4.97594385e+03 5.16800977e+03 5.36240771e+03 5.14727930e+03 4.79665820e+03 4.76786670e+03 4.96370898e+03 4.93650586e+03 4.79309912e+03 4.73928662e+03 4.64872754e+03 4.69355615e+03 4.67307617e+03 4.40583838e+03 4.37491455e+03 4.57384814e+03 4.59941602e+03 4.47114404e+03 4.22145264e+03 4.04915576e+03 4.24083594e+03 4.46475586e+03 4.29868750e+03 4.04973193e+03 3.88901025e+03 3.81757007e+03 3.98161377e+03 4.16237207e+03 3.99223120e+03 3.87239624e+03 3.77789355e+03 3.67068262e+03 3.68623584e+03 3.72193506e+03 3.58385498e+03 3.50104761e+03 3.58552588e+03 3.48626392e+03 3.30591431e+03 3.31511035e+03 3.43040210e+03 3.46300513e+03 3.35230347e+03 3.22526929e+03 3.08868188e+03 3.01926270e+03 3.13838477e+03 3.24991528e+03 3.09708472e+03 2.86852588e+03 2.83269849e+03 2.91094360e+03 2.98248730e+03 2.93153467e+03 2.76011841e+03 2.68544092e+03 2.72533643e+03 2.68967896e+03 2.62312354e+03 2.59350610e+03 2.53936157e+03 2.53736646e+03 2.49739331e+03 2.38292236e+03 2.35835962e+03 2.39643359e+03 2.40451611e+03 2.36023413e+03 2.26007324e+03 2.15010303e+03 2.12895215e+03 2.20590503e+03 2.20162476e+03 2.08424072e+03 1.97393555e+03 1.91378699e+03 1.98247766e+03 2.06776392e+03 1.94835095e+03 1.81316956e+03 1.78972852e+03 1.80915942e+03 1.76991626e+03 1.70344519e+03 1.67920923e+03 1.70511389e+03 1.69022632e+03 1.61328015e+03 1.53102393e+03 1.49920642e+03 1.54086877e+03 1.56808875e+03 1.49940491e+03 1.41928210e+03 1.36349756e+03 1.31512061e+03 1.33599927e+03 1.38062158e+03 1.30414697e+03 1.21157178e+03 1.17898743e+03 1.20717224e+03 1.23257507e+03 1.16698926e+03 1.10133813e+03 1.07302869e+03 1.06104321e+03 1.05028418e+03 1.02087451e+03 9.71058167e+02 9.34786133e+02 9.46991333e+02 9.38468079e+02 8.81715942e+02 8.37987976e+02 8.28809937e+02 8.29765564e+02 8.25615234e+02 7.86344604e+02 7.21595459e+02 7.06363159e+02 7.15049194e+02 6.97696533e+02 6.66090576e+02 6.35485901e+02 6.12357605e+02 5.95228088e+02 5.89531860e+02 5.60041565e+02 5.28018677e+02 5.26411499e+02 5.21137024e+02 4.90219147e+02 4.56938812e+02 4.42406250e+02 4.35321381e+02 4.32262390e+02 4.16633728e+02 3.85693146e+02 3.57326416e+02 3.39418854e+02 3.38580597e+02 3.40275726e+02 3.15369537e+02 2.84505920e+02 2.69379883e+02 2.65599274e+02 2.62721893e+02 2.48610840e+02 2.28469223e+02 2.13762436e+02 2.03789612e+02 1.90371704e+02 1.79590454e+02 1.70845535e+02 1.59225433e+02 1.50553452e+02 1.40098068e+02 1.26867279e+02 1.18258858e+02 1.12512581e+02 1.05646194e+02 9.76851730e+01 8.59198380e+01 7.63895569e+01 7.32563171e+01 6.93886261e+01 6.17285004e+01 5.37964211e+01 4.66777649e+01 4.09395981e+01 3.78377686e+01 3.44747086e+01 2.91935635e+01 2.38066483e+01 2.00060883e+01 1.74500198e+01 1.48477478e+01 1.21186037e+01 9.69815731e+00 7.67993927e+00 6.09013891e+00 4.81368637e+00 3.93100333e+00 3.44279742e+00 3.30927181e+00 3.51871657e+00 4.07476234e+00 4.89038897e+00 5.94116974e+00 7.49769974e+00 9.69736767e+00 1.22850065e+01 1.47868004e+01 1.74212036e+01 2.11436901e+01 2.50052624e+01 2.80621490e+01 3.13861580e+01 3.66154785e+01 4.36608086e+01 5.06686440e+01 5.54150391e+01 5.85605965e+01 6.29511108e+01 7.09637222e+01 8.26726303e+01 9.28542023e+01 9.82060394e+01 1.00789932e+02 1.09276596e+02 1.24941460e+02 1.33996857e+02 1.37410507e+02 1.46843597e+02 1.58183136e+02 1.69059662e+02 1.86118622e+02 1.93689758e+02 1.98525055e+02 2.14563385e+02 2.22579681e+02 2.41777435e+02 2.60334869e+02 2.59591003e+02 2.80022644e+02 3.03510742e+02 3.09769653e+02 3.20958374e+02 3.37819031e+02 3.57259186e+02 3.72940948e+02 3.86158356e+02 3.90327820e+02 4.07842865e+02 4.46736176e+02 4.73654724e+02 4.80107849e+02 4.78358429e+02 4.85797791e+02 5.15627991e+02 5.56479919e+02 5.86463928e+02 5.94529297e+02 5.87970520e+02 6.09434753e+02 6.46174438e+02 6.64700317e+02 6.87830933e+02 7.06349976e+02 7.23640320e+02 7.43823730e+02 7.95779114e+02 8.03581299e+02 7.93803040e+02 8.32136047e+02 8.42352295e+02 9.00609558e+02 9.35613464e+02 9.25838257e+02 9.98684875e+02 9.92151367e+02 9.76249695e+02 1.03883972e+03 1.04099597e+03 1.08370410e+03 1.18690344e+03 1.16131750e+03 1.11633777e+03 1.15855701e+03 1.24169873e+03 1.33154871e+03 1.32268347e+03 1.27837122e+03 1.28008386e+03 1.32133069e+03 1.41998218e+03 1.51420056e+03 1.50385120e+03 1.46025354e+03 1.48243079e+03 1.55665491e+03 1.60325842e+03 1.61042212e+03 1.62246350e+03 1.66447144e+03 1.71785718e+03 1.78788342e+03 1.81675220e+03 1.77137524e+03 1.80002454e+03 1.85119897e+03 1.89688257e+03 1.95351099e+03 1.98133887e+03 2.06909229e+03 2.05726123e+03 2.01399036e+03 2.10187598e+03 2.08724658e+03 2.18843994e+03 2.35450244e+03 2.27612207e+03 2.18300391e+03 2.26602954e+03 2.40947046e+03 2.52809106e+03 2.54605688e+03 2.44327979e+03 2.39990137e+03 2.47871387e+03 2.64028394e+03 2.79794629e+03 2.74468091e+03 2.61518799e+03 2.65000928e+03 2.76968213e+03 2.87117065e+03 2.99441113e+03 3.02106470e+03 2.88745337e+03 2.87039355e+03 3.07690356e+03 3.16422070e+03 3.06776489e+03 3.09937305e+03 3.21110913e+03 3.22047534e+03 3.35056274e+03 3.42398633e+03 3.27429199e+03 3.31571802e+03 3.45773340e+03 3.49835449e+03 3.55348608e+03 3.53699878e+03 3.64782935e+03 3.78779810e+03 3.73691455e+03 3.65025781e+03 3.61209717e+03 3.82343677e+03 4.09926074e+03 4.04779199e+03 3.89298828e+03 3.82192432e+03 4.00150171e+03 4.29843896e+03 4.23237646e+03 4.04640332e+03 4.13152539e+03 4.28085156e+03 4.43539600e+03 4.61487891e+03 4.57174219e+03 4.35820361e+03 4.30231885e+03 4.48953564e+03 4.73733252e+03 4.78848877e+03 4.68826123e+03 4.72305225e+03 4.77493408e+03 4.93448828e+03 4.96693457e+03 4.90276221e+03 4.92365430e+03 4.82255371e+03 5.09677246e+03 5.33352832e+03 5.15367773e+03 5.26465381e+03 5.33788574e+03 5.43498877e+03 5.34374561e+03 5.18682373e+03 5.46498682e+03 5.78717480e+03 5.69037061e+03 5.43200244e+03 5.52242969e+03 5.88204736e+03 5.94904980e+03 5.85002100e+03 5.91749072e+03 5.72276172e+03 5.76629639e+03 6.19740723e+03 6.21099805e+03 6.01277100e+03 5.93697852e+03 5.97598633e+03 6.31136914e+03 6.58184863e+03 6.40541162e+03 6.28668701e+03 6.45965918e+03 6.47657080e+03 6.76170654e+03 6.79976758e+03 6.49178076e+03 6.55160547e+03 6.72785645e+03 6.76551709e+03 6.86056592e+03 6.88316602e+03 7.14037500e+03 7.08696924e+03 6.90907275e+03 7.02513623e+03 6.91742529e+03 7.21420947e+03 7.71510498e+03 7.53770410e+03 7.21690234e+03 7.15221924e+03 7.32686572e+03 7.60658984e+03 8.00670117e+03 8.18682031e+03 8.72927344e+03 8.03774854e+03 1.18860293e+04 8.60365938e+04 7.44486875e+05 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. 0. 0. 0. 0. 0. 0. -114649008. -20285250. 3.60067773e+04 2.17486289e+04 1.07350479e+04 1.06292041e+04 1.02347812e+04 9.79476172e+03 9.82054492e+03 1.01118359e+04 1.01432842e+04 1.00155273e+04 1.03200254e+04 1.03021240e+04 1.02233662e+04 1.03072090e+04 1.03367930e+04 1.03161230e+04 1.04050752e+04 1.05386641e+04 1.04696953e+04 1.02994844e+04 1.03439893e+04 1.08459727e+04 1.08739326e+04 1.03999648e+04 1.04969775e+04 1.10771055e+04 1.11791943e+04 1.08648867e+04 1.09215127e+04 1.09163701e+04 1.09934463e+04 1.10317510e+04 1.11128682e+04 1.11227500e+04 1.10639521e+04 1.09556289e+04 1.10159316e+04 1.15039609e+04 1.15608389e+04 1.12985723e+04 1.13846787e+04 1.14501396e+04 1.15376934e+04 1.14957236e+04 1.14931426e+04 1.15886855e+04 1.13398066e+04 1.13577852e+04 1.16281104e+04 1.16400156e+04 1.21067051e+04 1.22212354e+04 1.19086074e+04 1.15478760e+04 1.14905352e+04 1.23351113e+04 1.25064697e+04 1.19993154e+04 1.18673643e+04 1.20855342e+04 1.20451396e+04 1.19445840e+04 1.25836504e+04 1.25469844e+04 1.18418428e+04 1.18191641e+04 1.24862754e+04 1.29807354e+04 1.27187314e+04 1.24915068e+04 1.25534775e+04 1.24877393e+04 1.24075781e+04 1.25321709e+04 1.27219893e+04 1.27016875e+04 1.24686924e+04 1.24461777e+04 1.27230332e+04 1.27481562e+04 1.30985107e+04 1.29848311e+04 1.26057129e+04 1.28864639e+04 1.29214785e+04 1.32315059e+04 1.33216787e+04 1.30264502e+04 1.30406963e+04 1.28102676e+04 1.25751006e+04 1.31939473e+04 1.34171143e+04 1.27522900e+04 1.29094951e+04 1.37019414e+04 1.39944609e+04 1.36345244e+04 1.32922988e+04 1.32528828e+04 1.33174033e+04 1.31943574e+04 1.31873262e+04 1.34931436e+04 1.34895020e+04 1.37080449e+04 1.35537910e+04 1.33110371e+04 1.35862764e+04 1.32899893e+04 1.35121670e+04 1.42505312e+04 1.40222275e+04 1.36624053e+04 1.33221689e+04 1.33053867e+04 1.41032607e+04 1.42294316e+04 1.37182744e+04 1.33387266e+04 1.33794209e+04 1.37834004e+04 1.37903574e+04 1.41983174e+04 1.43492197e+04 1.38774404e+04 1.36132988e+04 1.36938643e+04 1.42896543e+04 1.42400225e+04 1.39123467e+04 1.36954033e+04 1.37188125e+04 1.40261699e+04 1.36700488e+04 1.38706152e+04 1.47298760e+04 1.45168105e+04 1.40962178e+04 1.37100127e+04 1.36773555e+04 1.45534521e+04 1.45923711e+04 1.41903086e+04 1.37580293e+04 1.36768086e+04 1.42155400e+04 1.41995430e+04 1.41397852e+04 1.38627139e+04 1.41333164e+04 1.46911250e+04 1.43181250e+04 1.44912920e+04 1.45987109e+04 1.42689248e+04 1.39340039e+04 1.39408799e+04 1.43181016e+04 1.43128398e+04 1.43398027e+04 1.38983184e+04 1.40817090e+04 1.50232666e+04 1.43419102e+04 1.38244990e+04 1.42577520e+04 1.43015479e+04 1.46621855e+04 1.44308691e+04 1.38955166e+04 1.45477744e+04 1.47340352e+04 1.43584521e+04 1.42527988e+04 1.41790117e+04 1.40411465e+04 1.40945020e+04 1.43213965e+04 1.39194756e+04 1.42115762e+04 1.50361436e+04 1.47857939e+04 1.41017705e+04 1.35743301e+04 1.40489844e+04 1.50090635e+04 1.46491416e+04 1.42608672e+04 1.40367002e+04 1.38723594e+04 1.42119287e+04 1.42142500e+04 1.45850137e+04 1.43061777e+04 1.38314170e+04 1.42037344e+04 1.42685029e+04 1.45381436e+04 1.43933906e+04 1.40625430e+04 1.40031553e+04 1.39246436e+04 1.42334912e+04 1.38884688e+04 1.40597539e+04 1.48264609e+04 1.44690234e+04 1.41603672e+04 1.37434609e+04 1.36092314e+04 1.44154951e+04 1.45060234e+04 1.41293184e+04 1.36504609e+04 1.35970967e+04 1.40387002e+04 1.40439951e+04 1.43818184e+04 1.43125947e+04 1.39584395e+04 1.35206660e+04 1.34487363e+04 1.42705889e+04 1.41800791e+04 1.37785996e+04 1.35463545e+04 1.34905742e+04 1.41298809e+04 1.42100752e+04 1.34919004e+04 1.33761465e+04 1.40522764e+04 1.40553076e+04 1.33467520e+04 1.32806016e+04 1.39692627e+04 1.39839346e+04 1.35188438e+04 1.32294385e+04 1.31796865e+04 1.39289775e+04 1.38369912e+04 1.33276641e+04 1.33220830e+04 1.32163145e+04 1.33800225e+04 1.34267256e+04 1.33321953e+04 1.29588730e+04 1.31683955e+04 1.37637764e+04 1.34092266e+04 1.34419033e+04 1.35341426e+04 1.32469297e+04 1.32378691e+04 1.31739316e+04 1.30037861e+04 1.27120645e+04 1.27068086e+04 1.29586211e+04 1.30156484e+04 1.33383193e+04 1.29647686e+04 1.25329072e+04 1.28868418e+04 1.29120156e+04 1.31945811e+04 1.29572168e+04 1.25728193e+04 1.26267871e+04 1.24638643e+04 1.26466963e+04 1.26532549e+04 1.28573584e+04 1.27262910e+04 1.23727773e+04 1.23836963e+04 1.20385938e+04 1.23995225e+04 1.30880996e+04 1.27491719e+04 1.23393369e+04 1.19950137e+04 1.18101611e+04 1.23654727e+04 1.27332998e+04 1.23223369e+04 1.18207061e+04 1.17371650e+04 1.20177227e+04 1.19971562e+04 1.22420166e+04 1.20544658e+04 1.16690303e+04 1.18231758e+04 1.17825020e+04 1.20773271e+04 1.20500254e+04 1.13526865e+04 1.13628506e+04 1.19353271e+04 1.16976309e+04 1.10766260e+04 1.13973457e+04 1.19867959e+04 1.17173682e+04 1.13947490e+04 1.11228330e+04 1.10742295e+04 1.15709521e+04 1.15348037e+04 1.12176309e+04 1.08903809e+04 1.08075234e+04 1.11398477e+04 1.10440898e+04 1.09576260e+04 1.06898750e+04 1.08517803e+04 1.12264629e+04 1.08581543e+04 1.09851143e+04 1.07733594e+04 1.04135645e+04 1.06441387e+04 1.06555684e+04 1.05881436e+04 1.04828301e+04 1.03120762e+04 1.00627686e+04 1.03095566e+04 1.09752012e+04 1.03077129e+04 9.72639355e+03 9.97160840e+03 1.03073799e+04 1.05445625e+04 1.02366660e+04 9.93092383e+03 1.01214824e+04 1.00322891e+04 9.62622754e+03 9.42241895e+03 9.91417480e+03 9.92370703e+03 9.54708398e+03 9.54502930e+03 9.19698047e+03 9.48564355e+03 9.99704785e+03 9.65098242e+03 9.38405078e+03 9.04186230e+03 8.89859570e+03 9.39812598e+03 9.75546289e+03 9.47086816e+03 8.94916992e+03 8.79320410e+03 8.95505273e+03 8.96585449e+03 9.18909082e+03 8.87157910e+03 8.59657129e+03 8.84833789e+03 8.67804395e+03 8.85505371e+03 8.77067578e+03 8.39038574e+03 8.63273828e+03 8.57929199e+03 8.41227148e+03 8.14923193e+03 8.18549609e+03 8.58411621e+03 8.48189355e+03 8.04096973e+03 7.84658105e+03 8.01705615e+03 8.38824121e+03 8.22147559e+03 7.94592432e+03 7.71491602e+03 7.63800146e+03 7.79526172e+03 7.81087061e+03 7.73101025e+03 7.48752246e+03 7.52823828e+03 7.76968506e+03 7.51246875e+03 7.63946436e+03 7.56616357e+03 7.27988818e+03 7.30171826e+03 7.27894043e+03 7.14738672e+03 7.13614697e+03 6.99823877e+03 6.94971191e+03 7.18490039e+03 7.09910645e+03 6.70242432e+03 6.61072803e+03 6.70339941e+03 6.82370996e+03 7.02968262e+03 6.74349805e+03 6.32313672e+03 6.52479883e+03 6.83369922e+03 6.59921045e+03 6.25518359e+03 6.20131104e+03 6.23883984e+03 6.23193408e+03 6.22548438e+03 5.98854053e+03 6.08957324e+03 6.33696289e+03 6.11443506e+03 5.93562158e+03 5.75117090e+03 5.72792578e+03 6.01888623e+03 5.89950635e+03 5.72537891e+03 5.57868066e+03 5.29847021e+03 5.40293506e+03 5.68363037e+03 5.81099170e+03 5.44137354e+03 5.14320850e+03 5.25719482e+03 5.31372998e+03 5.45234229e+03 5.25501367e+03 5.05136523e+03 5.10102930e+03 5.05985107e+03 4.94426465e+03 4.78655713e+03 4.83599072e+03 5.00236182e+03 4.88160791e+03 4.77068408e+03 4.64230664e+03 4.56804541e+03 4.72738818e+03 4.71553076e+03 4.53607764e+03 4.38894482e+03 4.28854102e+03 4.35051465e+03 4.31925098e+03 4.40815186e+03 4.39471533e+03 4.13410596e+03 4.02763062e+03 4.10820166e+03 4.22287402e+03 4.06910938e+03 3.94117871e+03 3.88251562e+03 3.84638403e+03 3.80150366e+03 3.66730566e+03 3.76577271e+03 3.78609229e+03 3.63029590e+03 3.67649805e+03 3.67727637e+03 3.56735229e+03 3.53666187e+03 3.48025757e+03 3.38816431e+03 3.26284351e+03 3.20317944e+03 3.31191406e+03 3.34876733e+03 3.16835986e+03 2.99527197e+03 3.06731152e+03 3.21132153e+03 3.16143164e+03 2.95096680e+03 2.79998071e+03 2.90782520e+03 2.99400635e+03 2.88126611e+03 2.83418530e+03 2.71025562e+03 2.55508716e+03 2.62245142e+03 2.74131079e+03 2.71690649e+03 2.52448755e+03 2.39023315e+03 2.50475732e+03 2.58238696e+03 2.46220752e+03 2.30853442e+03 2.21282104e+03 2.24468628e+03 2.25166113e+03 2.27612842e+03 2.26838354e+03 2.15228125e+03 2.07905371e+03 2.04597766e+03 2.09708691e+03 2.01688562e+03 1.92171399e+03 1.97532959e+03 1.93822400e+03 1.87926465e+03 1.80540466e+03 1.77213574e+03 1.83817542e+03 1.74575378e+03 1.62518689e+03 1.63431116e+03 1.67037988e+03 1.64694556e+03 1.58048364e+03 1.57959167e+03 1.55680371e+03 1.49244531e+03 1.42183240e+03 1.37718127e+03 1.42870032e+03 1.37456580e+03 1.30770178e+03 1.31827234e+03 1.28579993e+03 1.24765332e+03 1.20860291e+03 1.20562000e+03 1.18680896e+03 1.13080481e+03 1.11796997e+03 1.10059265e+03 1.08463000e+03 1.05251221e+03 1.00740057e+03 9.69886169e+02 9.19070618e+02 8.99185120e+02 9.24726990e+02 9.44307251e+02 8.68270630e+02 7.91931763e+02 8.00133057e+02 8.24853638e+02 8.06109436e+02 7.43637939e+02 6.90539734e+02 7.04316406e+02 6.97177185e+02 6.56486206e+02 6.60860474e+02 6.24805359e+02 5.72359375e+02 5.70428589e+02 5.82054138e+02 5.63941162e+02 5.14945496e+02 4.77468048e+02 4.82277374e+02 4.95222900e+02 4.65866669e+02 4.23548798e+02 3.96902679e+02 3.99664337e+02 3.96247620e+02 3.68972015e+02 3.48869293e+02 3.35917908e+02 3.24773499e+02 3.07839172e+02 3.00701508e+02 2.81930481e+02 2.58442230e+02 2.51518036e+02 2.40767868e+02 2.32858231e+02 2.15908340e+02 1.98432571e+02 1.95043640e+02 1.79152298e+02 1.63722626e+02 1.59041138e+02 1.51671982e+02 1.41936752e+02 1.29831039e+02 1.23970573e+02 1.16079803e+02 1.03159790e+02 9.22288818e+01 8.44463425e+01 8.21773987e+01 7.35668869e+01 6.53643417e+01 6.60135574e+01 8.85675888e+01 4.61749786e+02 -19715306. 0. 0. 0. 0. 30754988. -11310162. 24337942. 4365517. 1.01216755e+01 1.28753185e+01 3.06714458e+01 13936511. 0. 0.
================================================ FILE: config/m2dgr/ring32_M_1.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 71192800. 1436088. 1.36346594e+03 1.12033386e+03 8.55616150e+02 8.55051880e+02 8.95150635e+02 9.99455017e+02 1.03132410e+03 1.08163525e+03 1.11647998e+03 1.13358618e+03 1.22156946e+03 1.31960352e+03 1.32863208e+03 1.36615100e+03 1.44740039e+03 1.51549792e+03 1.57756702e+03 1.58153540e+03 1.58283850e+03 1.66557800e+03 1.76566406e+03 1.83586279e+03 1.87330469e+03 1.88255859e+03 1.93338110e+03 2.04935156e+03 2.15255811e+03 2.13172314e+03 2.09050562e+03 2.17418896e+03 2.29387134e+03 2.32662744e+03 2.37034692e+03 2.43887500e+03 2.41941309e+03 2.51118970e+03 2.62660962e+03 2.56846143e+03 2.60698120e+03 2.74077295e+03 2.89518896e+03 2.96870850e+03 2.81697900e+03 2.76557837e+03 2.90053442e+03 3.07788306e+03 3.16255811e+03 3.08850537e+03 3.12973706e+03 3.28006396e+03 3.29152954e+03 3.34052197e+03 3.34395752e+03 3.27585962e+03 3.43656592e+03 3.60644556e+03 3.54033789e+03 3.56961597e+03 3.68816284e+03 3.66437402e+03 3.77901978e+03 3.86961084e+03 3.76595068e+03 3.77955249e+03 3.91187500e+03 4.09260742e+03 4.10493896e+03 4.01391382e+03 4.08608936e+03 4.10810645e+03 4.19189600e+03 4.33383398e+03 4.22301953e+03 4.23568311e+03 4.41235693e+03 4.51511816e+03 4.57531445e+03 4.50401709e+03 4.37239648e+03 4.46999023e+03 4.65530811e+03 4.77861719e+03 4.81255225e+03 4.76194922e+03 4.73633447e+03 4.89635400e+03 5.02630762e+03 4.89931885e+03 4.80241992e+03 4.92676758e+03 5.13943604e+03 5.22235449e+03 5.19421436e+03 5.10410693e+03 5.04889453e+03 5.25895312e+03 5.42605127e+03 5.25580469e+03 5.29536133e+03 5.49198828e+03 5.62618066e+03 5.64617773e+03 5.42417188e+03 5.30796094e+03 5.52112891e+03 5.68810400e+03 5.70215771e+03 5.69724854e+03 5.75286426e+03 5.87746045e+03 5.79376074e+03 5.79848389e+03 5.96214551e+03 5.84431494e+03 5.83575879e+03 6.01701611e+03 6.10819873e+03 6.15230469e+03 6.07605127e+03 5.93825537e+03 6.01661230e+03 6.20103076e+03 6.34346973e+03 6.30419385e+03 6.29055615e+03 6.77970459e+03 8.75354004e+03 9.74331445e+03 -8.66385500e+05 1.03574431e+06 1.46907425e+06 -2.19784850e+06 9.30510645e+03 8.96751758e+03 7.67704541e+03 7.26778857e+03 6.95975928e+03 8.94347852e+03 9.76652441e+03 7.59844650e+06 -34227304. 1028188. 16951284. 8.06068812e+05 -1.03928362e+06 3.21023375e+06 -2.14830350e+06 -9.95933688e+05 1.25265075e+06 9.67970996e+03 9.12331934e+03 7.75619287e+03 7.70525977e+03 7.19188037e+03 6.79497656e+03 6.78057031e+03 7.28665039e+03 7.44639014e+03 7.15853662e+03 6.91860156e+03 7.06972168e+03 7.33784375e+03 7.32789648e+03 7.00591602e+03 7.03834326e+03 7.29414648e+03 7.33657959e+03 7.31779980e+03 7.40624463e+03 7.43707178e+03 7.14975928e+03 7.34269189e+03 7.56992480e+03 7.23425781e+03 7.22283643e+03 7.43883008e+03 7.50705420e+03 7.57312891e+03 7.44433691e+03 7.18203320e+03 7.26327588e+03 7.48867627e+03 7.78560107e+03 7.76761523e+03 7.33985498e+03 7.39225244e+03 7.78517041e+03 7.62948389e+03 7.30313379e+03 7.35150000e+03 7.57428955e+03 7.69210938e+03 7.78816748e+03 7.76327783e+03 7.55054541e+03 7.35740234e+03 7.60133350e+03 7.78604248e+03 7.54287207e+03 7.52568750e+03 7.71305127e+03 7.83196875e+03 7.82101221e+03 7.61832129e+03 7.41010547e+03 7.49502051e+03 7.68266895e+03 7.91234082e+03 7.87696045e+03 7.47959424e+03 7.51376074e+03 7.70327295e+03 7.74559180e+03 7.68565527e+03 7.52692432e+03 7.51726172e+03 7.74231641e+03 7.85264307e+03 7.75747705e+03 7.56869385e+03 7.45656250e+03 7.64063037e+03 7.77492285e+03 7.57251025e+03 7.62062939e+03 7.75905811e+03 7.71908252e+03 7.85863477e+03 7.56578662e+03 7.37635303e+03 7.56465186e+03 7.59474902e+03 7.70386230e+03 7.47873242e+03 7.28853125e+03 7.59499023e+03 7.81606445e+03 7.68137598e+03 7.47866211e+03 7.54712646e+03 7.39921729e+03 7.37916260e+03 7.55771875e+03 7.77891162e+03 7.53093994e+03 7.32597363e+03 7.54747461e+03 7.41037988e+03 7.45917383e+03 7.45017432e+03 7.18900781e+03 7.39477051e+03 7.53246289e+03 7.26158252e+03 7.10944580e+03 7.25737158e+03 7.51197021e+03 7.54104297e+03 7.13476904e+03 7.06158545e+03 7.22974268e+03 7.31139453e+03 7.38512354e+03 7.15033008e+03 7.10181836e+03 7.02967627e+03 7.03097900e+03 7.31059473e+03 7.17714648e+03 6.85552979e+03 6.99207080e+03 7.24012109e+03 6.95924268e+03 6.89113037e+03 6.79516602e+03 6.74218506e+03 7.02776562e+03 7.12211084e+03 6.84058838e+03 6.71310938e+03 6.76952344e+03 6.87848193e+03 6.94327002e+03 6.71314844e+03 6.78663770e+03 6.80562598e+03 6.47995166e+03 6.52208643e+03 6.56718799e+03 6.55661035e+03 6.63541943e+03 6.55483447e+03 6.49426318e+03 6.59766943e+03 6.43412256e+03 6.27700879e+03 6.38150098e+03 6.47321875e+03 6.41700781e+03 6.15791211e+03 6.12061230e+03 6.35595703e+03 6.40622314e+03 6.10538135e+03 5.98135840e+03 6.03112500e+03 6.17034473e+03 6.21243701e+03 5.96561084e+03 5.92026709e+03 5.85387256e+03 5.93138135e+03 6.01413232e+03 5.78975049e+03 5.75947852e+03 5.75999902e+03 5.69733447e+03 5.74297607e+03 5.82050488e+03 5.63478174e+03 5.43237256e+03 5.64451855e+03 5.79047998e+03 5.44268799e+03 5.20799658e+03 5.34044092e+03 5.42821582e+03 5.37760938e+03 5.24769238e+03 5.15746826e+03 5.16806396e+03 5.25754883e+03 5.25604834e+03 5.07475586e+03 5.01493799e+03 4.97398438e+03 5.05650195e+03 5.00503223e+03 4.81087256e+03 4.82447412e+03 4.78062598e+03 4.71307617e+03 4.76620801e+03 4.73833545e+03 4.58964600e+03 4.53566846e+03 4.60248438e+03 4.56434912e+03 4.40975146e+03 4.34546826e+03 4.35404980e+03 4.40305225e+03 4.33907861e+03 4.14804736e+03 4.11866016e+03 4.14764014e+03 4.21392773e+03 4.19009229e+03 4.00375684e+03 4.03911377e+03 3.94417505e+03 3.74035449e+03 3.74889966e+03 3.76311328e+03 3.83308594e+03 3.76567529e+03 3.54614502e+03 3.47197437e+03 3.53756616e+03 3.60627734e+03 3.53705151e+03 3.42088647e+03 3.35296851e+03 3.27271387e+03 3.19556885e+03 3.14239307e+03 3.19103271e+03 3.19276221e+03 3.04236157e+03 2.98387842e+03 2.94241577e+03 2.92868555e+03 2.91366553e+03 2.84608862e+03 2.85314062e+03 2.71895459e+03 2.56061523e+03 2.54829370e+03 2.57577856e+03 2.58849365e+03 2.56388013e+03 2.42957764e+03 2.25528247e+03 2.25196045e+03 2.27563550e+03 2.20791162e+03 2.21147534e+03 2.14395215e+03 2.01046753e+03 2.02002637e+03 1.98923767e+03 1.89373730e+03 1.86098071e+03 1.78466101e+03 1.70940295e+03 1.66233911e+03 1.62178674e+03 1.58700989e+03 1.57942212e+03 1.56594751e+03 1.44165723e+03 1.32778845e+03 1.28755664e+03 1.26687549e+03 1.25542151e+03 1.19419641e+03 1.08822559e+03 1.02516174e+03 1.00325958e+03 9.82850098e+02 9.32961975e+02 8.54137451e+02 7.96375732e+02 7.40143433e+02 6.79119568e+02 6.24313965e+02 5.88835083e+02 5.44080750e+02 4.83090759e+02 4.32169495e+02 3.64600311e+02 3.11247498e+02 2.68916901e+02 2.16112411e+02 1.64531174e+02 1.05841812e+02 4.95632629e+01 -3.41827607e+00 -5.82850304e+01 -1.13104500e+02 -1.67700165e+02 -2.14959290e+02 -2.58250824e+02 -3.19364777e+02 -3.79435089e+02 -4.26811157e+02 -4.89822906e+02 -5.51549316e+02 -5.85064209e+02 -6.33075623e+02 -6.95470642e+02 -7.60745667e+02 -8.22257324e+02 -8.62963684e+02 -9.16153137e+02 -9.41380127e+02 -9.87688049e+02 -1.07247253e+03 -1.13298950e+03 -1.20299805e+03 -1.25552295e+03 -1.26944617e+03 -1.29303552e+03 -1.37951013e+03 -1.48079321e+03 -1.51954236e+03 -1.54607336e+03 -1.59459949e+03 -1.61861536e+03 -1.68471094e+03 -1.77232397e+03 -1.81056079e+03 -1.86903735e+03 -1.90397351e+03 -1.93047400e+03 -1.98299817e+03 -2.08851685e+03 -2.15219287e+03 -2.17319800e+03 -2.24111328e+03 -2.23155420e+03 -2.30908057e+03 -2.40058813e+03 -2.42335059e+03 -2.53699219e+03 -2.53487524e+03 -2.49738037e+03 -2.57483496e+03 -2.63262402e+03 -2.74394629e+03 -2.91156860e+03 -2.89754858e+03 -2.82117261e+03 -2.85652344e+03 -2.91515430e+03 -2.96400879e+03 -3.10242285e+03 -3.19463477e+03 -3.13861279e+03 -3.16652661e+03 -3.22458716e+03 -3.33760547e+03 -3.44434204e+03 -3.44414258e+03 -3.58203271e+03 -3.54412012e+03 -3.38639648e+03 -3.49552417e+03 -3.67667017e+03 -3.78476587e+03 -3.87270459e+03 -3.77868823e+03 -3.64117920e+03 -3.81461646e+03 -4.05835083e+03 -4.04799243e+03 -4.03006885e+03 -4.03650854e+03 -4.02720654e+03 -4.15606201e+03 -4.22821533e+03 -4.21234668e+03 -4.37680566e+03 -4.36734375e+03 -4.35615234e+03 -4.42873438e+03 -4.36851514e+03 -4.45403418e+03 -4.59002148e+03 -4.76476318e+03 -4.68778027e+03 -4.48358496e+03 -4.59384131e+03 -4.78253564e+03 -4.91312354e+03 -4.93861035e+03 -4.82642334e+03 -4.78292236e+03 -4.93571289e+03 -5.08176807e+03 -5.16527295e+03 -5.16484277e+03 -5.15092676e+03 -5.14036230e+03 -5.20709375e+03 -5.24256885e+03 -5.25846143e+03 -5.36381641e+03 -5.40740479e+03 -5.48774365e+03 -5.35575049e+03 -5.39750781e+03 -5.59938086e+03 -5.58691846e+03 -5.74229980e+03 -5.68759131e+03 -5.47544775e+03 -5.54107959e+03 -5.70508203e+03 -5.92553711e+03 -6.07621533e+03 -5.87320264e+03 -5.71131689e+03 -5.81920068e+03 -5.95122266e+03 -6.00698242e+03 -6.06166113e+03 -6.11476367e+03 -6.01307910e+03 -5.96594922e+03 -6.09989893e+03 -6.23619873e+03 -6.34785547e+03 -6.31786377e+03 -6.35475049e+03 -6.25400049e+03 -6.08955908e+03 -6.24839600e+03 -6.39098535e+03 -6.58025146e+03 -6.61479199e+03 -6.29337451e+03 -6.25897705e+03 -6.50354053e+03 -6.78964844e+03 -6.72740723e+03 -6.63948242e+03 -6.63830811e+03 -6.48401025e+03 -6.65956543e+03 -6.87572412e+03 -6.77589160e+03 -6.76448145e+03 -6.75490137e+03 -6.82422900e+03 -6.87119189e+03 -6.85613037e+03 -6.91679297e+03 -6.96403223e+03 -6.96549658e+03 -6.83582715e+03 -6.92934961e+03 -7.06546338e+03 -7.03201611e+03 -7.30733984e+03 -7.12177881e+03 -6.88284619e+03 -7.01479102e+03 -6.95604297e+03 -7.21389258e+03 -7.55876807e+03 -7.37401611e+03 -6.99124756e+03 -6.94058789e+03 -7.23154150e+03 -7.31875830e+03 -7.52905176e+03 -7.33268262e+03 -8.32786914e+03 -8.01519531e+03 -1.37978164e+04 -2.30682734e+04 4.53441750e+06 66448264. 2.31867550e+06 1.55539738e+06 -84543384. 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. 0. 0. 0. 0. 0. 0. 0. -209539664. -8.04047500e+04 -1.39668887e+04 -9.18071973e+03 -8.06825977e+03 -7.58370508e+03 -7.83836816e+03 -7.80261133e+03 -7.76184082e+03 -7.39706201e+03 -7.54184766e+03 -7.98897217e+03 -7.94098096e+03 -7.55913574e+03 -7.29216553e+03 -7.38028516e+03 -7.75401074e+03 -8.01567383e+03 -7.72564160e+03 -7.43198779e+03 -7.40132227e+03 -7.43323486e+03 -7.75880029e+03 -7.82044531e+03 -7.52999365e+03 -7.38440381e+03 -7.37225586e+03 -7.49977393e+03 -7.55352344e+03 -7.42611963e+03 -7.41814941e+03 -7.69463574e+03 -7.82959912e+03 -7.44018457e+03 -7.06528467e+03 -7.21420557e+03 -7.59448193e+03 -7.84405078e+03 -7.47754541e+03 -7.07486621e+03 -7.12820654e+03 -7.44499805e+03 -7.74466602e+03 -7.47252441e+03 -6.98149268e+03 -7.03266406e+03 -7.29906348e+03 -7.45231152e+03 -7.45586084e+03 -7.31682568e+03 -7.05433447e+03 -7.03787402e+03 -7.28394678e+03 -7.02700879e+03 -6.90400635e+03 -7.24222412e+03 -7.29848389e+03 -7.19274756e+03 -6.93039355e+03 -6.63554688e+03 -6.97749170e+03 -7.42618799e+03 -7.22687598e+03 -6.76603467e+03 -6.49518408e+03 -6.61299756e+03 -6.99981250e+03 -7.24200146e+03 -6.99385889e+03 -6.80758398e+03 -6.67421045e+03 -6.46387012e+03 -6.66668896e+03 -6.88801514e+03 -6.63374951e+03 -6.55633057e+03 -6.59319971e+03 -6.62364062e+03 -6.49902832e+03 -6.40473145e+03 -6.57374463e+03 -6.58550391e+03 -6.58730518e+03 -6.40867041e+03 -6.10930176e+03 -6.10770166e+03 -6.42124658e+03 -6.67255811e+03 -6.35536621e+03 -5.93913672e+03 -5.99814697e+03 -6.16319775e+03 -6.29244775e+03 -6.31423975e+03 -6.05666064e+03 -5.96808447e+03 -5.92681543e+03 -5.97627148e+03 -6.05739209e+03 -5.90466748e+03 -5.82840723e+03 -5.76277539e+03 -5.79637451e+03 -5.80045898e+03 -5.69797217e+03 -5.71748535e+03 -5.72296045e+03 -5.77478906e+03 -5.58598242e+03 -5.30622656e+03 -5.37530225e+03 -5.63887646e+03 -5.71522607e+03 -5.40043408e+03 -5.09863330e+03 -5.09779053e+03 -5.36341943e+03 -5.59375586e+03 -5.29479346e+03 -5.01088281e+03 -5.06855859e+03 -5.01743115e+03 -5.00796191e+03 -5.03885986e+03 -4.93825732e+03 -4.98692871e+03 -4.88525098e+03 -4.81940381e+03 -4.81252832e+03 -4.65546045e+03 -4.70030859e+03 -4.84462109e+03 -4.80133008e+03 -4.58225439e+03 -4.37884229e+03 -4.35766699e+03 -4.50513135e+03 -4.64961426e+03 -4.41875195e+03 -4.13377881e+03 -4.16072168e+03 -4.32692236e+03 -4.40189404e+03 -4.18834814e+03 -4.02888428e+03 -4.02238745e+03 -3.96601685e+03 -4.00524121e+03 -3.99427393e+03 -3.78085571e+03 -3.73000879e+03 -3.82186157e+03 -3.82559424e+03 -3.72966016e+03 -3.60568384e+03 -3.56837646e+03 -3.57049341e+03 -3.62358179e+03 -3.50282544e+03 -3.26969458e+03 -3.27347827e+03 -3.31365186e+03 -3.31725293e+03 -3.26964014e+03 -3.10962573e+03 -3.04851807e+03 -3.05484058e+03 -3.06836646e+03 -3.01695361e+03 -2.89542236e+03 -2.88081055e+03 -2.82725024e+03 -2.77910474e+03 -2.72419897e+03 -2.60620264e+03 -2.60876562e+03 -2.65160938e+03 -2.61787231e+03 -2.46718530e+03 -2.31769019e+03 -2.29027612e+03 -2.35010986e+03 -2.38962622e+03 -2.24130640e+03 -2.07281421e+03 -2.04858252e+03 -2.05991553e+03 -2.05665747e+03 -2.00772546e+03 -1.87748145e+03 -1.81039978e+03 -1.79466003e+03 -1.76034961e+03 -1.71131396e+03 -1.64408484e+03 -1.59974072e+03 -1.52432556e+03 -1.48372607e+03 -1.44529590e+03 -1.37635840e+03 -1.33266284e+03 -1.28413989e+03 -1.23750830e+03 -1.14309717e+03 -1.07052490e+03 -1.06146350e+03 -1.04697375e+03 -1.00015710e+03 -9.05074768e+02 -8.13152283e+02 -7.67217957e+02 -7.57313110e+02 -7.37660767e+02 -6.61448059e+02 -5.79976624e+02 -5.15286011e+02 -4.60685608e+02 -4.27099365e+02 -3.87286041e+02 -3.25582153e+02 -2.66109558e+02 -2.12023254e+02 -1.58826416e+02 -1.03657570e+02 -5.24063148e+01 -3.19622785e-01 5.46031418e+01 1.12050087e+02 1.66045776e+02 2.07653885e+02 2.63382599e+02 3.25549988e+02 3.78211548e+02 4.34535858e+02 4.84703278e+02 5.48238403e+02 6.06078796e+02 6.31315002e+02 6.61600891e+02 7.27885986e+02 8.21438354e+02 9.02583008e+02 9.40456116e+02 9.39603394e+02 9.66572571e+02 1.04150867e+03 1.14339185e+03 1.22951208e+03 1.26152295e+03 1.25177307e+03 1.29589465e+03 1.42281226e+03 1.47985144e+03 1.46038281e+03 1.50753674e+03 1.59351477e+03 1.64574280e+03 1.74790161e+03 1.75824854e+03 1.75485144e+03 1.85258960e+03 1.85414185e+03 1.95515845e+03 2.07409375e+03 2.01754138e+03 2.10008691e+03 2.22787695e+03 2.22564673e+03 2.26582837e+03 2.31254175e+03 2.37285767e+03 2.45503931e+03 2.47277417e+03 2.44190503e+03 2.51367871e+03 2.68900903e+03 2.79765405e+03 2.77931860e+03 2.71930322e+03 2.70605859e+03 2.80678955e+03 2.98972021e+03 3.11953491e+03 3.10748877e+03 2.99145776e+03 3.03472876e+03 3.20413892e+03 3.24040942e+03 3.24277490e+03 3.28839819e+03 3.34700366e+03 3.39228906e+03 3.57422412e+03 3.54283569e+03 3.44910742e+03 3.56682251e+03 3.53170117e+03 3.71369727e+03 3.85490283e+03 3.77492993e+03 3.95749683e+03 3.90962207e+03 3.79194604e+03 3.95649414e+03 3.92707886e+03 4.05027222e+03 4.36186768e+03 4.18346973e+03 4.00480151e+03 4.13891455e+03 4.35030078e+03 4.54775635e+03 4.52232031e+03 4.32575049e+03 4.21062207e+03 4.35592822e+03 4.67429053e+03 4.85777686e+03 4.79746777e+03 4.58448682e+03 4.57205811e+03 4.81054297e+03 4.93547314e+03 4.80651953e+03 4.77840479e+03 4.91117041e+03 4.96749414e+03 5.13672656e+03 5.16295020e+03 5.01164062e+03 5.09608105e+03 5.10460498e+03 5.13799902e+03 5.29140137e+03 5.29800098e+03 5.45340381e+03 5.38674463e+03 5.22327100e+03 5.40384326e+03 5.32192725e+03 5.48120361e+03 5.91050049e+03 5.65402783e+03 5.30732031e+03 5.44454834e+03 5.77338818e+03 5.97393896e+03 6.04699316e+03 5.78367725e+03 5.54557520e+03 5.66365820e+03 6.00403516e+03 6.32872070e+03 6.15154834e+03 5.81715479e+03 5.80142627e+03 6.00866455e+03 6.20390186e+03 6.41659863e+03 6.39593555e+03 6.05078857e+03 6.00205029e+03 6.29710986e+03 6.41862695e+03 6.37970410e+03 6.36207422e+03 6.30025244e+03 6.26804443e+03 6.59097656e+03 6.66983740e+03 6.36511670e+03 6.35691162e+03 6.56252783e+03 6.59782080e+03 6.62877930e+03 6.59223096e+03 6.76242188e+03 6.82556934e+03 6.64422363e+03 6.63362988e+03 6.55545312e+03 6.80914990e+03 7.13823828e+03 7.06214697e+03 6.73358691e+03 6.56996582e+03 6.85493115e+03 7.25518262e+03 7.00749756e+03 6.67740527e+03 6.83170996e+03 7.03484229e+03 7.21096680e+03 7.43414453e+03 7.33147168e+03 6.93340771e+03 6.74729346e+03 7.02838184e+03 7.38083105e+03 7.37157422e+03 7.17735742e+03 7.18239111e+03 7.21584570e+03 7.35908838e+03 7.26572266e+03 7.11356152e+03 7.19077344e+03 7.16815918e+03 7.43770312e+03 7.64891895e+03 7.38096533e+03 7.37420361e+03 7.40499170e+03 7.60818701e+03 7.45235303e+03 7.07592529e+03 7.39913623e+03 7.82978271e+03 7.56241992e+03 7.18078955e+03 7.38549805e+03 7.80105518e+03 7.72449561e+03 7.56472803e+03 7.60963037e+03 7.38011133e+03 7.33880518e+03 7.75585693e+03 7.84876660e+03 7.53335547e+03 7.32156982e+03 7.23927930e+03 7.63029443e+03 8.02491357e+03 7.68415527e+03 7.45820410e+03 7.62886133e+03 7.62937207e+03 7.86797363e+03 7.91996973e+03 7.45806006e+03 7.39609424e+03 7.58296338e+03 7.64058105e+03 7.69963525e+03 7.70962207e+03 7.87922363e+03 7.82902393e+03 7.49352783e+03 7.48434082e+03 7.37376709e+03 7.68214258e+03 8.13507715e+03 7.90778076e+03 7.46269971e+03 7.39822021e+03 7647. 8.14888721e+03 8.67473828e+03 9.51443750e+03 8.34812012e+03 1.57556475e+04 1.09856141e+05 -6.41029350e+06 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. 0. 0. 0. 0. 0. 0. -7.64077450e+06 46421. 1.02059482e+04 8.25738379e+03 7.27982959e+03 7.16063428e+03 7.28557129e+03 7.15850488e+03 6.91777588e+03 6.88072021e+03 7.16109229e+03 7.20809961e+03 6.99307861e+03 7.03995166e+03 7.03695898e+03 6.93519092e+03 6.94541699e+03 6.89865527e+03 6.86637109e+03 6.86163184e+03 6.82452539e+03 6.78749658e+03 6.62986719e+03 6.54095264e+03 6.87593457e+03 6.87720654e+03 6.51265234e+03 6.44771533e+03 6.77783691e+03 6.80471729e+03 6.58308984e+03 6.56202637e+03 6.50513281e+03 6.46513135e+03 6.44292578e+03 6.39369238e+03 6.37687109e+03 6.32468018e+03 6.15580713e+03 6.10406934e+03 6.40986230e+03 6.40861816e+03 6.20650098e+03 6.15379736e+03 6.13463037e+03 6.12079443e+03 6.06125049e+03 6.00726221e+03 6.02366016e+03 5.82041943e+03 5.72626562e+03 5.90571924e+03 5.87976562e+03 6.00948047e+03 6.01271924e+03 5.76549463e+03 5.56830469e+03 5.50417627e+03 5.82265088e+03 5.84327441e+03 5.57487842e+03 5.47752002e+03 5.47729492e+03 5.47881250e+03 5.38470996e+03 5.49759766e+03 5.44919141e+03 5.14545410e+03 5.07942969e+03 5.32185596e+03 5.40569434e+03 5.22571143e+03 5.12462598e+03 5.08818311e+03 5.03430225e+03 4.92524170e+03 4.89021289e+03 4.96246777e+03 4.91466113e+03 4.76986621e+03 4.74270117e+03 4.77063379e+03 4.70760449e+03 4.77655518e+03 4.71387549e+03 4.53015381e+03 4.55819775e+03 4.50932422e+03 4.49548340e+03 4.49513281e+03 4.38009863e+03 4.32382031e+03 4.20420459e+03 4.10776514e+03 4.23700537e+03 4.18554199e+03 3.94406421e+03 3.95613770e+03 4.12670410e+03 4.22466260e+03 4.03682471e+03 3.87873022e+03 3.77289697e+03 3.70749927e+03 3.70465869e+03 3.65992505e+03 3.66197144e+03 3.59718408e+03 3.60862280e+03 3.54196753e+03 3.40842236e+03 3.43829980e+03 3.28830518e+03 3.23468799e+03 3.37923413e+03 3.30261743e+03 3.17169702e+03 3.04363525e+03 2.97227344e+03 3.09177026e+03 3.05647412e+03 2.91333154e+03 2.79235254e+03 2.74332739e+03 2.77035669e+03 2.71749487e+03 2.74099805e+03 2.70649878e+03 2.57426099e+03 2.50077783e+03 2.45489990e+03 2.44909106e+03 2.39823364e+03 2.31315088e+03 2.23113989e+03 2.18547949e+03 2.17433594e+03 2.06407568e+03 2.01390710e+03 2.07583203e+03 2.01532471e+03 1.90985938e+03 1.80095056e+03 1.74857971e+03 1.80271094e+03 1.74667029e+03 1.64862573e+03 1.55416101e+03 1.49175964e+03 1.49218311e+03 1.43371301e+03 1.37790857e+03 1.30032544e+03 1.27110571e+03 1.27910315e+03 1.19611694e+03 1.12805054e+03 1.07737708e+03 1.01873413e+03 9.53127747e+02 8.96508911e+02 8.56782837e+02 8.06526917e+02 7.56588806e+02 6.78154724e+02 6.25857605e+02 6.13134583e+02 5.36563293e+02 4.64695404e+02 4.24534180e+02 3.71111176e+02 3.29825897e+02 2.69367676e+02 2.06450500e+02 1.63019043e+02 1.09837639e+02 5.33181763e+01 -1.76700675e+00 -5.58978539e+01 -1.09954987e+02 -1.62358765e+02 -2.16379456e+02 -2.62434418e+02 -3.20359833e+02 -3.94429901e+02 -4.41855469e+02 -4.79658966e+02 -5.15150146e+02 -5.74036987e+02 -6.66659790e+02 -7.17909912e+02 -7.49838074e+02 -7.87010376e+02 -8.33328064e+02 -9.06200684e+02 -9.61088196e+02 -1.03964514e+03 -1.07281763e+03 -1.09217676e+03 -1.17510608e+03 -1.22745776e+03 -1.30589404e+03 -1.34387915e+03 -1.35948425e+03 -1.43026709e+03 -1.48162573e+03 -1.54798315e+03 -1.55787488e+03 -1.64045508e+03 -1.79956006e+03 -1.79678467e+03 -1.80156287e+03 -1.81020349e+03 -1.84390100e+03 -2.00916687e+03 -2.08003027e+03 -2.06772241e+03 -2.05132910e+03 -2.10220166e+03 -2.22880225e+03 -2.27718115e+03 -2.38615210e+03 -2.42673853e+03 -2.42045068e+03 -2.40562085e+03 -2.43730249e+03 -2.64581079e+03 -2.66922119e+03 -2.63609717e+03 -2.68166895e+03 -2.72388647e+03 -2.89605908e+03 -2.95782520e+03 -2.86431274e+03 -2.88884424e+03 -3.07763452e+03 -3.16111816e+03 -3.04848047e+03 -3.07782593e+03 -3.29222388e+03 -3.35292456e+03 -3.30706494e+03 -3.28642065e+03 -3.31841821e+03 -3.55041626e+03 -3.56111987e+03 -3.48613110e+03 -3.56416943e+03 -3.62082739e+03 -3.76518872e+03 -3.79734717e+03 -3.71635791e+03 -3.67911157e+03 -3.84968311e+03 -4.11668652e+03 -4.04596533e+03 -4.02844360e+03 -4.12034961e+03 -4.12578076e+03 -4.16869824e+03 -4.20085254e+03 -4.22963818e+03 -4.17392188e+03 -4.19932275e+03 -4.35499609e+03 -4.43053369e+03 -4.61567969e+03 -4.51780908e+03 -4.37210889e+03 -4.53853027e+03 -4.69097754e+03 -4.86426953e+03 -4.79654785e+03 -4.70289355e+03 -4.74743994e+03 -4.75947900e+03 -4.90435986e+03 -4.94487158e+03 -5.06514062e+03 -5.10255957e+03 -5.02916797e+03 -5.00222510e+03 -4.90035742e+03 -5.15072070e+03 -5.51892773e+03 -5.43175098e+03 -5.30035645e+03 -5.18606494e+03 -5.12172217e+03 -5.41529346e+03 -5.73237598e+03 -5.60035938e+03 -5.36601758e+03 -5.38107422e+03 -5.57609082e+03 -5.65392383e+03 -5.79324658e+03 -5.79872412e+03 -5.70430420e+03 -5.70949072e+03 -5.71382910e+03 -5.96260107e+03 -6.01056982e+03 -5.73681885e+03 -5.76845068e+03 -6.13722754e+03 -6.12046533e+03 -5.84446143e+03 -5.97480127e+03 -6.32519434e+03 -6.30963184e+03 -6.16563867e+03 -6.05121973e+03 -6.08238232e+03 -6.44848535e+03 -6.49782861e+03 -6.34983984e+03 -6.21312842e+03 -6.18492969e+03 -6.39351514e+03 -6.46476855e+03 -6.45267969e+03 -6.32356592e+03 -6.50950684e+03 -6.77874365e+03 -6.60284131e+03 -6.75681396e+03 -6.75606299e+03 -6.57410596e+03 -6.70719287e+03 -6.75880225e+03 -6.76794531e+03 -6.69623682e+03 -6.61013867e+03 -6.55494189e+03 -6.87648535e+03 -7.26802881e+03 -6.92118408e+03 -6.63689844e+03 -6.86943994e+03 -7.00705469e+03 -7.26363525e+03 -7.08435010e+03 -6.86251611e+03 -7.20404590e+03 -7.23310010e+03 -6.87288525e+03 -6.84322607e+03 -7.30215527e+03 -7.38051318e+03 -7.14971191e+03 -7.05694678e+03 -6.78626855e+03 -7.15267676e+03 -7.69470020e+03 -7.45696094e+03 -7.24430420e+03 -7.06899414e+03 -6.97716113e+03 -7.35727197e+03 -7.76171045e+03 -7.57224951e+03 -7.19922998e+03 -7.16440283e+03 -7.36846387e+03 -7.43092188e+03 -7.64411816e+03 -7.48116650e+03 -7.27886523e+03 -7.45905518e+03 -7.46985645e+03 -7.70112744e+03 -7.67564404e+03 -7.43457861e+03 -7.46997998e+03 -7.45052783e+03 -7.62169629e+03 -7.47106104e+03 -7.40593506e+03 -7.82613281e+03 -7.78424121e+03 -7.51682422e+03 -7.35125635e+03 -7.41500830e+03 -7.89174072e+03 -7.82406934e+03 -7.62006641e+03 -7.44322656e+03 -7.38575488e+03 -7.60046143e+03 -7.63072998e+03 -7.64138672e+03 -7.46337988e+03 -7.61229004e+03 -7.90383252e+03 -7.66907959e+03 -7.86760791e+03 -7.87281689e+03 -7.66467773e+03 -7.56536719e+03 -7.49411426e+03 -7.77657129e+03 -7.79789355e+03 -7.49452051e+03 -7.42857080e+03 -7.85516504e+03 -7.95765967e+03 -7.46854834e+03 -7.28773047e+03 -7.47882031e+03 -7.78223242e+03 -8.04017041e+03 -7.74523193e+03 -7.36615430e+03 -7.71757031e+03 -7.89754443e+03 -7.70321387e+03 -7.54912793e+03 -7.54484131e+03 -7.46528223e+03 -7.47930371e+03 -7.61442188e+03 -7.37919141e+03 -7.55783350e+03 -7.91777197e+03 -7.63782520e+03 -7.62039551e+03 -7.46019238e+03 -7.36062695e+03 -7.72354346e+03 -7.69607715e+03 -7.52069482e+03 -7.32005127e+03 -7.11004053e+03 -7.26301025e+03 -7.62216846e+03 -7.87239209e+03 -7.46636230e+03 -7.20253662e+03 -7.34745947e+03 -7.39806348e+03 -7.61565039e+03 -7.57844092e+03 -7.32998486e+03 -7.26793262e+03 -7.22282031e+03 -7.21299414e+03 -7.05027344e+03 -7.24426221e+03 -7.51618750e+03 -7.26640625e+03 -7.31096143e+03 -7.19532422e+03 -6.98767627e+03 -7.38409033e+03 -7.40170752e+03 -7.12482910e+03 -6.94826074e+03 -6.82625049e+03 -7.04020654e+03 -7.01051025e+03 -7.21319434e+03 -7.26446582e+03 -6.96906885e+03 -6.78797803e+03 -6.84758398e+03 -7.14742920e+03 -7.01183691e+03 -6.84727148e+03 -6.71177441e+03 -6.67607227e+03 -6.75323389e+03 -6.70013818e+03 -6.84376318e+03 -6.84191895e+03 -6.59674072e+03 -6.77785791e+03 -6.84111230e+03 -6.64711670e+03 -6.59023584e+03 -6.57265381e+03 -6.55141162e+03 -6.35459326e+03 -6.24822266e+03 -6.55219238e+03 -6.59766162e+03 -6.22124658e+03 -6.00438574e+03 -6.29670703e+03 -6.65774023e+03 -6.51073340e+03 -6.09185303e+03 -5.96999902e+03 -6.29357129e+03 -6.26659326e+03 -6.03214307e+03 -6.15681201e+03 -5.97356396e+03 -5.66393945e+03 -5.82420898e+03 -6.11796875e+03 -6.20956885e+03 -5.84479492e+03 -5.52676611e+03 -5.82204443e+03 -6.06946631e+03 -5.86163477e+03 -5.55054053e+03 -5.43369385e+03 -5.56555469e+03 -5.58380664e+03 -5.68231250e+03 -5.62670215e+03 -5.39597266e+03 -5.39010254e+03 -5.35271191e+03 -5.48347510e+03 -5.33899902e+03 -5.15381055e+03 -5.30194873e+03 -5.23683545e+03 -5.23998193e+03 -5.11244141e+03 -4.97101465e+03 -5.20969043e+03 -5.04818799e+03 -4.78895312e+03 -4.86836035e+03 -4.92202295e+03 -4.90791748e+03 -4.79821973e+03 -4.86175439e+03 -4.86354834e+03 -4.70641455e+03 -4.52039648e+03 -4.45560303e+03 -4.64313965e+03 -4.51289502e+03 -4.35021191e+03 -4.43070898e+03 -4.38368896e+03 -4.32648975e+03 -4.26418848e+03 -4.33761035e+03 -4.24881738e+03 -4.07061304e+03 -4.17293262e+03 -4.14872021e+03 -4.03368799e+03 -3.99496704e+03 -3.93549512e+03 -3.85342017e+03 -3.70952881e+03 -3.59974561e+03 -3.73546167e+03 -3.90912793e+03 -3.66583691e+03 -3.39909082e+03 -3.50991187e+03 -3.68943311e+03 -3.59570752e+03 -3.35335254e+03 -3.22767944e+03 -3.36311743e+03 -3.31791895e+03 -3.15156616e+03 -3.23628760e+03 -3.18104761e+03 -2.97148926e+03 -2.91637695e+03 -3.01620264e+03 -3.04724146e+03 -2.85816724e+03 -2.69321558e+03 -2.75030908e+03 -2.85776807e+03 -2.75058325e+03 -2.57155151e+03 -2.45693701e+03 -2.51324365e+03 -2.58119702e+03 -2.45296606e+03 -2.32687427e+03 -2.29700049e+03 -2.27162280e+03 -2.20865112e+03 -2.21902759e+03 -2.11921143e+03 -2.00429968e+03 -2.00577271e+03 -1.96119214e+03 -1.94969092e+03 -1.85652502e+03 -1.75526624e+03 -1.75653333e+03 -1.66041467e+03 -1.61522949e+03 -1.62483118e+03 -1.55459729e+03 -1.49126001e+03 -1.42715808e+03 -1.42260120e+03 -1.37621399e+03 -1.27313293e+03 -1.19066821e+03 -1.14183459e+03 -1.15577063e+03 -1.06885876e+03 -9.69127136e+02 -9.56986816e+02 -9.93905151e+02 -1.02760217e+03 -7.30321960e+02 -7.46192200e+02 -1.91975110e+03 -2.58951733e+03 1.44595953e+05 -46060172. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 142385600. 2872176. 2.72696216e+03 1.44082776e+03 1.17387915e+03 8.70118286e+02 9.26905396e+02 1.06156445e+03 1.01987866e+03 1.02780969e+03 1.09212671e+03 1.14281519e+03 1.20797253e+03 1.30196985e+03 1.34176111e+03 1.34407971e+03 1.42068909e+03 1.50836414e+03 1.51947595e+03 1.54765454e+03 1.60015881e+03 1.67215381e+03 1.76500891e+03 1.82796497e+03 1.83281091e+03 1.82434131e+03 1.91849487e+03 2.03629761e+03 2.05732178e+03 2.09958325e+03 2.12679858e+03 2.16392578e+03 2.28652441e+03 2.29271167e+03 2.26979736e+03 2.35856885e+03 2.40979541e+03 2.49260132e+03 2.57093970e+03 2.54952612e+03 2.59413672e+03 2.72953467e+03 2.89836865e+03 2.87088794e+03 2.72330884e+03 2.76863965e+03 2.90137134e+03 3.00995996e+03 3.11306201e+03 3.10547729e+03 3.06742383e+03 3.19172095e+03 3.28515649e+03 3.23970117e+03 3.25710938e+03 3.29941602e+03 3.45426978e+03 3.62550415e+03 3.49660132e+03 3.41924829e+03 3.55419580e+03 3.68076538e+03 3.79186865e+03 3.78402759e+03 3.73118530e+03 3.73341650e+03 3.86941748e+03 4.09071753e+03 4.02268164e+03 3.87851782e+03 3.99931274e+03 4.11992529e+03 4.16101416e+03 4.25859863e+03 4.23907812e+03 4.17726367e+03 4.32574268e+03 4.45981982e+03 4.41911963e+03 4.39576660e+03 4.39760156e+03 4.46487988e+03 4.64052100e+03 4.79919092e+03 4.71786475e+03 4.57983789e+03 4.70409375e+03 4.87189307e+03 4.82245605e+03 4.79145117e+03 4.83612158e+03 4.96405127e+03 5.15330273e+03 5.11166553e+03 4.96135889e+03 4.98207324e+03 5.04950195e+03 5.20646973e+03 5.28686816e+03 5.23686816e+03 5.26610986e+03 5.44429248e+03 5.61240186e+03 5.51120654e+03 5.25744336e+03 5.31374316e+03 5.53605420e+03 5.63158740e+03 5.66908838e+03 5.59517969e+03 5.54741016e+03 5.76695020e+03 5.83236084e+03 5.69871729e+03 5.76779443e+03 5.83617529e+03 5.84962305e+03 6.00967236e+03 6.01452686e+03 5.89511523e+03 5.92445459e+03 5.96281201e+03 6.01036816e+03 6.17981982e+03 6.34797168e+03 6.21646240e+03 6.11627490e+03 6.68497852e+03 8.48620508e+03 8.69638770e+03 8.97321094e+03 8.83764844e+03 8.99012305e+03 9.28076367e+03 8.64380859e+03 8.49270508e+03 7.47936230e+03 7.18942822e+03 6.84373047e+03 8.57116895e+03 9.11416211e+03 9.45480664e+03 9.45334961e+03 9.63584961e+03 9.57175000e+03 9.42481738e+03 9.59107031e+03 9.71520898e+03 9.87562012e+03 1.00439414e+04 9.77731055e+03 8.89238477e+03 8.85263867e+03 7.72267676e+03 7.43958643e+03 7.00528662e+03 6.76782764e+03 6.75173096e+03 7.22053125e+03 7.26092432e+03 6.93180322e+03 6.84743652e+03 7.14086914e+03 7.28693506e+03 7.10612842e+03 6.91435742e+03 6.99089404e+03 7.24675000e+03 7.40623389e+03 7.15794824e+03 7.07525391e+03 7.16176123e+03 7.14232080e+03 7.29743945e+03 7.38123730e+03 7.20822607e+03 7.25409326e+03 7.42352588e+03 7.45489600e+03 7.28497949e+03 7.20998389e+03 7.22336426e+03 7.25657568e+03 7.42651465e+03 7.67164697e+03 7.70410352e+03 7.21553076e+03 7.33288281e+03 7.69435791e+03 7.42195312e+03 7.26473291e+03 7.35547217e+03 7.40816797e+03 7.64103857e+03 7.68779639e+03 7.40798096e+03 7.31002246e+03 7.39329004e+03 7.55341309e+03 7.61752393e+03 7.45538330e+03 7.47675928e+03 7.69396436e+03 7.75886426e+03 7.47944629e+03 7.40214453e+03 7.39848926e+03 7.51113281e+03 7.61650586e+03 7.77575195e+03 7.80460449e+03 7.42113916e+03 7.45510205e+03 7.65483838e+03 7.54867578e+03 7.49698389e+03 7.51579102e+03 7.52234424e+03 7.72035254e+03 7.74476221e+03 7.47212109e+03 7.44644238e+03 7.44272949e+03 7.51247949e+03 7.64233105e+03 7.51038721e+03 7.50797998e+03 7.59190918e+03 7.69415039e+03 7.73914014e+03 7.38847949e+03 7.27672168e+03 7.47218555e+03 7.51636523e+03 7.61122510e+03 7.50965771e+03 7.27045947e+03 7.45965234e+03 7.70802148e+03 7.44857324e+03 7.33366650e+03 7.44625977e+03 7.42080127e+03 7.42341846e+03 7.34686133e+03 7.51617578e+03 7.49491699e+03 7.28433008e+03 7.45481445e+03 7.26702686e+03 7.27756348e+03 7.45525488e+03 7.20062305e+03 7.24227734e+03 7.37316504e+03 7.25454980e+03 7.01461621e+03 7.05997266e+03 7.41758936e+03 7.51955811e+03 7.07371191e+03 6.98654150e+03 7.22243750e+03 7.16205420e+03 7.19743604e+03 6.98507031e+03 6.92998193e+03 7.06000830e+03 7.19047705e+03 7.11030029e+03 6.95608301e+03 6.87177100e+03 6.95174756e+03 7.07079150e+03 6.86900195e+03 6.73194482e+03 6.73968750e+03 6.72019580e+03 6.86478662e+03 7.02979639e+03 6.86231885e+03 6.59053711e+03 6.55668213e+03 6.85065430e+03 6.87854053e+03 6.50542969e+03 6.65358203e+03 6.82628662e+03 6.47025146e+03 6.46556738e+03 6.42139062e+03 6.40433154e+03 6.65223193e+03 6.51849316e+03 6.29932568e+03 6.45657275e+03 6.45107666e+03 6.24577539e+03 6.31527490e+03 6.34317773e+03 6.29246143e+03 6.10529346e+03 6.03239746e+03 6.18995312e+03 6.26837549e+03 6.14769678e+03 5.93083008e+03 5.90637256e+03 6.08741113e+03 6.12295605e+03 5.86991309e+03 5.80011670e+03 5.83078906e+03 5.90511865e+03 5.93945654e+03 5.66373779e+03 5.64356396e+03 5.78814551e+03 5.76733545e+03 5.57924072e+03 5.64160449e+03 5.61779541e+03 5.43681348e+03 5.59088721e+03 5.62526709e+03 5.33332129e+03 5.14426074e+03 5.22910840e+03 5.33913965e+03 5.32519629e+03 5.24181982e+03 5.10801660e+03 5.07434570e+03 5.21229834e+03 5.21019580e+03 4.97491553e+03 4.89011426e+03 4.99251562e+03 5.09248584e+03 4.90046875e+03 4.71909326e+03 4.78796729e+03 4.74579297e+03 4.67689111e+03 4.65541992e+03 4.64798779e+03 4.59579150e+03 4.49499219e+03 4.50225195e+03 4.47721289e+03 4.39824951e+03 4.28027490e+03 4.25916357e+03 4.30049658e+03 4.26718164e+03 4.15570850e+03 4.10850732e+03 4.09473755e+03 4.15551270e+03 4.11529395e+03 3.91929614e+03 3.91731592e+03 3.91180640e+03 3.84194849e+03 3.75880859e+03 3.68420142e+03 3.73537036e+03 3.69148022e+03 3.55185278e+03 3.42751514e+03 3.49281152e+03 3.55710449e+03 3.45836279e+03 3.38815796e+03 3.31746313e+03 3.30064966e+03 3.18469385e+03 3.03561670e+03 3.08817773e+03 3.11361597e+03 3.07344800e+03 3.00559155e+03 2.86097339e+03 2.84197510e+03 2.85324341e+03 2.83738306e+03 2.82305835e+03 2.68740894e+03 2.57838550e+03 2.51533545e+03 2.53617212e+03 2.55939404e+03 2.48562256e+03 2.39812988e+03 2.24807178e+03 2.24963257e+03 2.27674658e+03 2.18015259e+03 2.15387109e+03 2.07140674e+03 2.00598608e+03 2.01595447e+03 1.92187598e+03 1.84928674e+03 1.86205981e+03 1.82199512e+03 1.70724500e+03 1.61264136e+03 1.58752649e+03 1.56473035e+03 1.55934363e+03 1.53178918e+03 1.42454626e+03 1.33955371e+03 1.27067322e+03 1.25486682e+03 1.24790466e+03 1.16860852e+03 1.08590796e+03 1.01417773e+03 9.79685913e+02 9.57182983e+02 9.16799194e+02 8.54953979e+02 7.88264709e+02 7.44833801e+02 6.79748291e+02 6.07247620e+02 5.70968018e+02 5.29066895e+02 4.79615295e+02 4.36477722e+02 3.65064270e+02 3.01655243e+02 2.59226990e+02 2.14673782e+02 1.61482635e+02 1.03000702e+02 4.97038116e+01 -2.84390545e+00 -5.58534126e+01 -1.11269310e+02 -1.63447525e+02 -2.13741684e+02 -2.60398560e+02 -3.19106415e+02 -3.72411591e+02 -4.12198853e+02 -4.74218689e+02 -5.39399414e+02 -5.89076416e+02 -6.37482422e+02 -6.77044373e+02 -7.35765137e+02 -8.07373596e+02 -8.62017334e+02 -9.12678223e+02 -9.27686951e+02 -9.73493042e+02 -1.05342236e+03 -1.12646228e+03 -1.19266833e+03 -1.22361670e+03 -1.26202588e+03 -1.27762415e+03 -1.35669055e+03 -1.46939417e+03 -1.48250244e+03 -1.52177954e+03 -1.57504749e+03 -1.61195068e+03 -1.65289856e+03 -1.71414868e+03 -1.78917273e+03 -1.86283252e+03 -1.92760767e+03 -1.92409290e+03 -1.92537109e+03 -2.01720374e+03 -2.10250806e+03 -2.16741895e+03 -2.23234399e+03 -2.22363599e+03 -2.28031396e+03 -2.32396069e+03 -2.38978052e+03 -2.51037158e+03 -2.50371875e+03 -2.53291382e+03 -2.56838770e+03 -2.55165796e+03 -2.65539526e+03 -2.85148193e+03 -2.86478687e+03 -2.80528491e+03 -2.89126904e+03 -2.90590771e+03 -2.87815430e+03 -3.00929272e+03 -3.11721680e+03 -3.15121606e+03 -3.20197437e+03 -3.16680347e+03 -3.23852148e+03 -3.35675024e+03 -3.42522900e+03 -3.57729688e+03 -3.52707593e+03 -3.38101392e+03 -3.42273267e+03 -3.60329224e+03 -3.73345898e+03 -3.75918481e+03 -3.75058105e+03 -3.64428833e+03 -3.77953003e+03 -3.98814380e+03 -3.95134692e+03 -3.97607202e+03 -3.96295093e+03 -4.00942798e+03 -4.15765869e+03 -4.09424023e+03 -4.11721631e+03 -4.37034180e+03 -4.41375732e+03 -4.35293066e+03 -4.28641064e+03 -4.21847461e+03 -4.36741357e+03 -4.58331738e+03 -4.74344238e+03 -4.68356689e+03 -4.48111768e+03 -4.49138916e+03 -4.69435889e+03 -4.85713867e+03 -4.81943555e+03 -4.80626904e+03 -4.74531396e+03 -4.81357178e+03 -4.99160449e+03 -5.09846729e+03 -5.12124414e+03 -5.08616553e+03 -5.16359766e+03 -5.14609766e+03 -5.03068750e+03 -5.16504639e+03 -5.31086182e+03 -5.38188770e+03 -5.49827637e+03 -5.34161035e+03 -5.23437305e+03 -5.43299756e+03 -5.55029785e+03 -5.70950830e+03 -5.66412109e+03 -5.46641064e+03 -5.43569287e+03 -5.64030469e+03 -5.89667236e+03 -5.95334717e+03 -5.78984375e+03 -5.72068555e+03 -5.77248291e+03 -5.77282471e+03 -5.84977881e+03 -6.00398828e+03 -6.11749805e+03 -6.02174951e+03 -5.90917334e+03 -5.90746387e+03 -6.05457178e+03 -6.25076221e+03 -6.34141553e+03 -6.32261084e+03 -6.13011035e+03 -5.99651611e+03 -6.15595996e+03 -6.36826367e+03 -6.55976709e+03 -6.50160205e+03 -6.26634521e+03 -6.15998535e+03 -6.39875879e+03 -6.69019189e+03 -6.56239893e+03 -6.60763379e+03 -6.54706250e+03 -6.41161768e+03 -6.59166162e+03 -6.70107812e+03 -6.70063574e+03 -6.65860693e+03 -6.74406006e+03 -6.78031299e+03 -6.69258691e+03 -6.74839648e+03 -6.79021777e+03 -6.95937891e+03 -6.95439404e+03 -6.78005811e+03 -6.80547949e+03 -6.76692627e+03 -6.89744873e+03 -7.29161621e+03 -7.13024805e+03 -6.83255762e+03 -6.81345117e+03 -6.94047656e+03 -7.20888428e+03 -7.37666064e+03 -7.16546240e+03 -6.94914990e+03 -7.05109619e+03 -7.21008789e+03 -7.11380029e+03 -7.28179443e+03 -7.25583691e+03 -8.19205078e+03 -7.83824561e+03 -8.81948730e+03 -1.66526973e+04 -2.41260371e+04 66448264. 2.31867550e+06 1.55539738e+06 -84543384. 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. 0. 0. 0. 0. 0. 0. 0. -419079328. -1.61748641e+05 -2.53477012e+04 -1.08691543e+04 -1.04096426e+04 -8.42958301e+03 -7.92454102e+03 -7.73463770e+03 -7.74262695e+03 -7.22370557e+03 -7.42778760e+03 -7.87316895e+03 -7.79529688e+03 -7.47251172e+03 -7.27279541e+03 -7.24124756e+03 -7.57874316e+03 -7.94757568e+03 -7.65761328e+03 -7.37372949e+03 -7.29854785e+03 -7.36188086e+03 -7.69392578e+03 -7.66372217e+03 -7.38303955e+03 -7.29477441e+03 -7.47679883e+03 -7.40497314e+03 -7.22391602e+03 -7.28165869e+03 -7.47810645e+03 -7.69095215e+03 -7.67129443e+03 -7.27153467e+03 -6.94239648e+03 -7.13487793e+03 -7.55355664e+03 -7.70557715e+03 -7.39488281e+03 -7.06314795e+03 -6.97556104e+03 -7.28372754e+03 -7.65846484e+03 -7.41475342e+03 -6.95880859e+03 -6.97864795e+03 -7.33744482e+03 -7.29509766e+03 -7.11561426e+03 -7.13213281e+03 -7.03966504e+03 -7.15747852e+03 -7.17385596e+03 -6.81966846e+03 -6.81720752e+03 -7.16816162e+03 -7.33716455e+03 -7.14565723e+03 -6.76978418e+03 -6.53487207e+03 -6.90875195e+03 -7.32813525e+03 -7.13636426e+03 -6.75149609e+03 -6.50248779e+03 -6.43148828e+03 -6.82298877e+03 -7.17091992e+03 -6.94784961e+03 -6.72541748e+03 -6.64629297e+03 -6.46488477e+03 -6.55367627e+03 -6.74913525e+03 -6.51236572e+03 -6.39548730e+03 -6.59771582e+03 -6.48615430e+03 -6.20819873e+03 -6.29306104e+03 -6.55999268e+03 -6.62374902e+03 -6.51791455e+03 -6.33587500e+03 -6.09884131e+03 -5.98982178e+03 -6.28342480e+03 -6.60419922e+03 -6.30443115e+03 -5.90827051e+03 -5.85640674e+03 -6.08478613e+03 -6.31492041e+03 -6.25774561e+03 -5.94032568e+03 -5.82236133e+03 -5.95589014e+03 -5.91096387e+03 -5.85193213e+03 -5.84229639e+03 -5.77278906e+03 -5.79275000e+03 -5.74880029e+03 -5.54761572e+03 -5.57571631e+03 -5.68545557e+03 -5.74714697e+03 -5.69933643e+03 -5.52998047e+03 -5.29160205e+03 -5.29192920e+03 -5.55720264e+03 -5.60103027e+03 -5.31849072e+03 -5.10587988e+03 -5.00940234e+03 -5.24260547e+03 -5.50138477e+03 -5.26097217e+03 -4.95824609e+03 -4.94342773e+03 -5.03185938e+03 -4.98745117e+03 -4.85652686e+03 -4.83063721e+03 -4.96618555e+03 -4.95802100e+03 -4.77965381e+03 -4.60798779e+03 -4.55827734e+03 -4.72152197e+03 -4.85841650e+03 -4.72832764e+03 -4.50861768e+03 -4.36351807e+03 -4.26198145e+03 -4.40437109e+03 -4.59254297e+03 -4.38655078e+03 -4.13967969e+03 -4.08086230e+03 -4.21736328e+03 -4.34502246e+03 -4.17275781e+03 -3.99536426e+03 -3.95458960e+03 -3.96243066e+03 -3.97792261e+03 -3.91082227e+03 -3.75054785e+03 -3.67078809e+03 -3.78354370e+03 -3.79988770e+03 -3.61934033e+03 -3.49889160e+03 -3.51241724e+03 -3.56123730e+03 -3.59773071e+03 -3.48359985e+03 -3.25181421e+03 -3.22550684e+03 -3.30349683e+03 -3.28403125e+03 -3.18472095e+03 -3.09185596e+03 -3.03386157e+03 -2.99956079e+03 -3.01142480e+03 -2.92574829e+03 -2.82443945e+03 -2.86536353e+03 -2.86475171e+03 -2.75029126e+03 -2.62576611e+03 -2.57390967e+03 -2.60266455e+03 -2.63508423e+03 -2.57288574e+03 -2.44013721e+03 -2.31145215e+03 -2.24404419e+03 -2.29901636e+03 -2.36568140e+03 -2.23321362e+03 -2.05948120e+03 -2.00561267e+03 -2.03747607e+03 -2.05734619e+03 -1.98298962e+03 -1.87512939e+03 -1.80903687e+03 -1.76547705e+03 -1.70492358e+03 -1.66596008e+03 -1.63090308e+03 -1.57507178e+03 -1.53140881e+03 -1.47085059e+03 -1.38772876e+03 -1.34568347e+03 -1.32758911e+03 -1.28969812e+03 -1.23440771e+03 -1.13141724e+03 -1.05319519e+03 -1.05536133e+03 -1.04906628e+03 -9.77607727e+02 -8.92359680e+02 -8.15375610e+02 -7.53405334e+02 -7.41020264e+02 -7.28403625e+02 -6.53677490e+02 -5.66329163e+02 -5.07858582e+02 -4.72212677e+02 -4.29894714e+02 -3.75609009e+02 -3.19077911e+02 -2.63677032e+02 -2.10295502e+02 -1.55157898e+02 -9.98056335e+01 -4.93501968e+01 2.47986841e+00 5.61476974e+01 1.12877480e+02 1.63619629e+02 2.04245300e+02 2.54170792e+02 3.17096527e+02 3.81297119e+02 4.32930542e+02 4.75460846e+02 5.40722595e+02 5.99111328e+02 6.22565308e+02 6.52570496e+02 7.19839233e+02 8.12286438e+02 8.91830139e+02 9.29116577e+02 9.26675110e+02 9.50407288e+02 1.02378137e+03 1.13047559e+03 1.22366138e+03 1.24926489e+03 1.23239807e+03 1.27735303e+03 1.41014807e+03 1.46333289e+03 1.45034875e+03 1.49968689e+03 1.55740649e+03 1.61074121e+03 1.72312744e+03 1.74063757e+03 1.73855566e+03 1.82512842e+03 1.83025854e+03 1.93977893e+03 2.04226221e+03 1.98321863e+03 2.08013647e+03 2.19659570e+03 2.18826538e+03 2.23284155e+03 2.29208154e+03 2.34869067e+03 2.41096948e+03 2.44228882e+03 2.42174243e+03 2.47776929e+03 2.65256030e+03 2.77267627e+03 2.75029297e+03 2.67470361e+03 2.66505566e+03 2.78366479e+03 2.95981812e+03 3.07320459e+03 3.05588208e+03 2.95019995e+03 3.00834229e+03 3.15944116e+03 3.18259790e+03 3.21266895e+03 3.26746851e+03 3.30274390e+03 3.35007251e+03 3.53707349e+03 3.49088232e+03 3.40302783e+03 3.53715234e+03 3.50551489e+03 3.67217700e+03 3.79920190e+03 3.71604492e+03 3.90984351e+03 3.85270410e+03 3.74148975e+03 3.91465039e+03 3.87201147e+03 3.98972656e+03 4.30951807e+03 4.13836572e+03 3.93820703e+03 4.05780566e+03 4.28297900e+03 4.51418457e+03 4.48431689e+03 4.27679932e+03 4.17248682e+03 4.30537402e+03 4.58930176e+03 4.77243115e+03 4.73301367e+03 4.53261182e+03 4.53012158e+03 4.71454883e+03 4.81983252e+03 4.78210498e+03 4.75209229e+03 4.84470361e+03 4.91513867e+03 5.08008057e+03 5.10633203e+03 4.91337598e+03 4.97498828e+03 5.06030273e+03 5.11212842e+03 5.21347119e+03 5.24446338e+03 5.40753760e+03 5.32602979e+03 5.16392236e+03 5.34653027e+03 5.25160645e+03 5.40928320e+03 5.81686963e+03 5.57890918e+03 5.27420850e+03 5.39441650e+03 5.69458545e+03 5.91872168e+03 5.93417529e+03 5.67941260e+03 5.48438867e+03 5.61143994e+03 5.94187158e+03 6.18462988e+03 6.03631885e+03 5.75326318e+03 5.75218018e+03 5.95402246e+03 6.10260400e+03 6.30263525e+03 6.33238281e+03 5.96643164e+03 5.92999658e+03 6.27426465e+03 6.38570557e+03 6.16532812e+03 6.17728174e+03 6.28957520e+03 6.25952051e+03 6.49916064e+03 6.60266455e+03 6.26118994e+03 6.29216846e+03 6.49101562e+03 6.52275928e+03 6.54163721e+03 6.48175000e+03 6.63055762e+03 6.78788721e+03 6.66525879e+03 6.52128809e+03 6.39266797e+03 6.68973438e+03 7.06687549e+03 6.97504980e+03 6.65068115e+03 6.48859912e+03 6.70504150e+03 7.15224902e+03 7.00061328e+03 6.62375488e+03 6.70003906e+03 6.91847021e+03 7.12964258e+03 7.39487988e+03 7.19888818e+03 6.83532812e+03 6.70648535e+03 6.94317871e+03 7.28465381e+03 7.27693750e+03 7.13573340e+03 7.09541553e+03 7.12810059e+03 7.29824121e+03 7.26187891e+03 7.09754736e+03 7.10063867e+03 6.97995166e+03 7.31439062e+03 7.56867578e+03 7.28497607e+03 7.27977686e+03 7.34373340e+03 7.49188965e+03 7.31322070e+03 7.01440283e+03 7.32170947e+03 7.71748438e+03 7.53239062e+03 7.17747705e+03 7.23885938e+03 7.64852686e+03 7.63101514e+03 7.48111475e+03 7.49701318e+03 7.22873242e+03 7.21120947e+03 7.72772266e+03 7.70589941e+03 7.42875049e+03 7.23490479e+03 7.20227490e+03 7.54055615e+03 7.90114209e+03 7.57436084e+03 7.39489844e+03 7.53758936e+03 7.51478271e+03 7.79914990e+03 7.77602197e+03 7.36207080e+03 7.33062256e+03 7.54999365e+03 7.57190430e+03 7.57576514e+03 7.57057129e+03 7.75872021e+03 7.63403711e+03 7.37035400e+03 7.48356543e+03 7.32319141e+03 7.61853174e+03 8.04719385e+03 7.82931592e+03 7.33753662e+03 7.32999854e+03 7.63656689e+03 7.83985254e+03 7.99723926e+03 8.88833398e+03 8.47221777e+03 1.00521514e+04 4.54912578e+04 -16867494. 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. 0. 0. 0. 0. 0. 0. -15821683. 7.22483359e+04 1.15796025e+04 1.00061348e+04 8.00272119e+03 7.74201074e+03 7.13068213e+03 7.01655859e+03 7.01639258e+03 6.80318896e+03 7.04798584e+03 7.02289551e+03 6.83748096e+03 6.98538965e+03 6.98273926e+03 6.85717529e+03 6.84724805e+03 6.80463818e+03 6.78465967e+03 6.78410107e+03 6.74745361e+03 6.68789209e+03 6.55171875e+03 6.52030615e+03 6.76103711e+03 6.77678711e+03 6.43583496e+03 6.37901318e+03 6.70262256e+03 6.69349219e+03 6.50488135e+03 6.47456152e+03 6.40991504e+03 6.41075635e+03 6.37345947e+03 6.32922070e+03 6.29643896e+03 6.24097119e+03 6.09275830e+03 6.05788281e+03 6.31250000e+03 6.29641016e+03 6.11470117e+03 6.08950342e+03 6.06948877e+03 6.05707373e+03 5.99721094e+03 5.94255762e+03 5.93580078e+03 5.74023779e+03 5.69634131e+03 5.80934375e+03 5.76267139e+03 5.93421729e+03 5.94077490e+03 5.71510303e+03 5.48083594e+03 5.40285840e+03 5.75719434e+03 5.77430518e+03 5.51043018e+03 5.39635303e+03 5.40816504e+03 5.35747266e+03 5.26594727e+03 5.47429688e+03 5.41069678e+03 5.05478662e+03 5.01273975e+03 5.24002930e+03 5.38511816e+03 5.20094189e+03 5.05909277e+03 5.04592432e+03 4.97762158e+03 4.89618750e+03 4.88340088e+03 4.89680908e+03 4.83995801e+03 4.68715869e+03 4.64317139e+03 4.70141406e+03 4.64683984e+03 4.72272070e+03 4.61207129e+03 4.44541943e+03 4.47795898e+03 4.43469678e+03 4.48013477e+03 4.47231689e+03 4.33460889e+03 4.26973340e+03 4.13308740e+03 4.00788647e+03 4.16791504e+03 4.17468262e+03 3.91654932e+03 3.90305664e+03 4.08187671e+03 4.14863232e+03 3.98331519e+03 3.82594360e+03 3.75955811e+03 3.71455078e+03 3.63873877e+03 3.58935156e+03 3.61458862e+03 3.55160449e+03 3.56191235e+03 3.47588721e+03 3.35333569e+03 3.38073682e+03 3.24036182e+03 3.23896313e+03 3.37208838e+03 3.26616772e+03 3.13512573e+03 2.99301660e+03 2.92951440e+03 3.05533545e+03 3.02744775e+03 2.87868652e+03 2.75356519e+03 2.70327173e+03 2.72922437e+03 2.67892651e+03 2.70696216e+03 2.67401416e+03 2.53427051e+03 2.44156787e+03 2.40102515e+03 2.43744116e+03 2.38465283e+03 2.28232812e+03 2.19179834e+03 2.13953662e+03 2.13794165e+03 2.03259265e+03 2.00403967e+03 2.07619653e+03 1.99428027e+03 1.88524475e+03 1.78213635e+03 1.72394946e+03 1.77896118e+03 1.73094470e+03 1.62979431e+03 1.53105286e+03 1.46992004e+03 1.47286011e+03 1.41942346e+03 1.36002625e+03 1.27992725e+03 1.25198608e+03 1.25110547e+03 1.16705261e+03 1.12051782e+03 1.07693982e+03 1.00514154e+03 9.29445435e+02 8.76157471e+02 8.44532715e+02 7.92726746e+02 7.42278870e+02 6.66417786e+02 6.21013367e+02 6.08175415e+02 5.29505920e+02 4.59658386e+02 4.19767487e+02 3.66734680e+02 3.23830780e+02 2.65286438e+02 2.04112808e+02 1.60252106e+02 1.07601151e+02 5.24304085e+01 -7.51788557e-01 -5.34225578e+01 -1.05086670e+02 -1.57487274e+02 -2.13485260e+02 -2.59174835e+02 -3.16735046e+02 -3.91602203e+02 -4.37435089e+02 -4.69137146e+02 -5.03663727e+02 -5.72437744e+02 -6.66471375e+02 -7.07135742e+02 -7.37934875e+02 -7.77146423e+02 -8.23023132e+02 -8.97261536e+02 -9.49159729e+02 -1.02373828e+03 -1.06095154e+03 -1.07865588e+03 -1.15991528e+03 -1.21435315e+03 -1.29031580e+03 -1.33683362e+03 -1.35509985e+03 -1.39953210e+03 -1.45001038e+03 -1.53229602e+03 -1.54208118e+03 -1.61822632e+03 -1.76760510e+03 -1.77685181e+03 -1.78086121e+03 -1.78559448e+03 -1.82632507e+03 -1.98365601e+03 -2.04704004e+03 -2.04149255e+03 -2.03035498e+03 -2.07932031e+03 -2.19909717e+03 -2.25084814e+03 -2.35663623e+03 -2.39743262e+03 -2.39144482e+03 -2.36729834e+03 -2.40794214e+03 -2.62084497e+03 -2.64768164e+03 -2.61505176e+03 -2.63626367e+03 -2.67536719e+03 -2.85654517e+03 -2.92377686e+03 -2.82712573e+03 -2.85301294e+03 -3.05292627e+03 -3.11170166e+03 -3.00177954e+03 -3.04025000e+03 -3.25802368e+03 -3.31377637e+03 -3.25335376e+03 -3.23016040e+03 -3.27090308e+03 -3.51019727e+03 -3.54562012e+03 -3.46809253e+03 -3.51046973e+03 -3.53958936e+03 -3.65139966e+03 -3.71599805e+03 -3.72100635e+03 -3.67327612e+03 -3.80542407e+03 -4.02223486e+03 -3.94832080e+03 -4.01851636e+03 -4.11290283e+03 -4.07010376e+03 -4.11626465e+03 -4.15917676e+03 -4.16662939e+03 -4.12860498e+03 -4.15735498e+03 -4.30335645e+03 -4.36605029e+03 -4.54169824e+03 -4.44926953e+03 -4.35217334e+03 -4.51403369e+03 -4.58883691e+03 -4.76881982e+03 -4.73962256e+03 -4.64620459e+03 -4.68945947e+03 -4.71056104e+03 -4.82407324e+03 -4.86919727e+03 -5.00832324e+03 -5.00550732e+03 -4.91513379e+03 -4.98602393e+03 -4.88525000e+03 -5.08931592e+03 -5.44050635e+03 -5.32497070e+03 -5.21760107e+03 -5.13080859e+03 -5.08431934e+03 -5.39752002e+03 -5.61108496e+03 -5.48081104e+03 -5.30992676e+03 -5.31494482e+03 -5.51471484e+03 -5.54752393e+03 -5.70912012e+03 -5.69050391e+03 -5.57128613e+03 -5.68577246e+03 -5.71067090e+03 -5.89747412e+03 -5.94376904e+03 -5.65383301e+03 -5.70248779e+03 -6.04965527e+03 -5.98905713e+03 -5.71318750e+03 -5.93301270e+03 -6.29407422e+03 -6.22836133e+03 -6.09113916e+03 -5.96302637e+03 -6.01116260e+03 -6.37859863e+03 -6.40336133e+03 -6.25265039e+03 -6.10862451e+03 -6.09584424e+03 -6.35854688e+03 -6.37203076e+03 -6.38677783e+03 -6.26950244e+03 -6.44390625e+03 -6.68472070e+03 -6.51800635e+03 -6.65932617e+03 -6.57840674e+03 -6.43137646e+03 -6.59189453e+03 -6.66938672e+03 -6.68896143e+03 -6.64739404e+03 -6.59062158e+03 -6.52803076e+03 -6.74141211e+03 -7.17683057e+03 -6.82416309e+03 -6.50022119e+03 -6.74129346e+03 -6.98203711e+03 -7.18596143e+03 -7.03040723e+03 -6.86258203e+03 -7.04777490e+03 -7.08835059e+03 -6.83369531e+03 -6.75385596e+03 -7.15509424e+03 -7.22312939e+03 -6.98761670e+03 -7.02417139e+03 -6.79252246e+03 -7.06795166e+03 -7.51449756e+03 -7.31018945e+03 -7.18530371e+03 -6.97538184e+03 -6.89862500e+03 -7.32487500e+03 -7.68343652e+03 -7.46579102e+03 -7.08552002e+03 -7.07684277e+03 -7.26960059e+03 -7.30539600e+03 -7.54667969e+03 -7.35088330e+03 -7.17196143e+03 -7.40718311e+03 -7.37492676e+03 -7.56836523e+03 -7.52020703e+03 -7.27062695e+03 -7.48089014e+03 -7.50474512e+03 -7.44018701e+03 -7.23515332e+03 -7.34364111e+03 -7.79322998e+03 -7.68012695e+03 -7.38461084e+03 -7.24163037e+03 -7.40398486e+03 -7.84487158e+03 -7.74571143e+03 -7.48987207e+03 -7.32937598e+03 -7.32718994e+03 -7.52369287e+03 -7.62289453e+03 -7.56901904e+03 -7.39215918e+03 -7.52263867e+03 -7.81767236e+03 -7.55957764e+03 -7.71478613e+03 -7.75465137e+03 -7.54404004e+03 -7.51933154e+03 -7.56065479e+03 -7.55692432e+03 -7.54688135e+03 -7.46451904e+03 -7.45031787e+03 -7.75857031e+03 -7.81408252e+03 -7.36356104e+03 -7.28933203e+03 -7.43343848e+03 -7.61998242e+03 -7.88185059e+03 -7.68197656e+03 -7.23272803e+03 -7.51943359e+03 -7.84568750e+03 -7.69704980e+03 -7.35741553e+03 -7.33575000e+03 -7.39693848e+03 -7.46336182e+03 -7.49515576e+03 -7.27441650e+03 -7.43582422e+03 -7.79546973e+03 -7.62684229e+03 -7.41403857e+03 -7.28166699e+03 -7.29053857e+03 -7.67208154e+03 -7.61628564e+03 -7.41728027e+03 -7.26864355e+03 -7.02514941e+03 -7.14128125e+03 -7.56943994e+03 -7.81087451e+03 -7.34684131e+03 -7.02581055e+03 -7.22202002e+03 -7.35411816e+03 -7.58744873e+03 -7.42676416e+03 -7.14210254e+03 -7.27041504e+03 -7.24402051e+03 -7.15190576e+03 -6.97596680e+03 -7.11675391e+03 -7.41173096e+03 -7.26991309e+03 -7.15808643e+03 -6.99130957e+03 -6.96475000e+03 -7.30652148e+03 -7.28558936e+03 -7.08428662e+03 -6.86104492e+03 -6.76051807e+03 -6.95165918e+03 -6.91191748e+03 -7.11363721e+03 -7.16814209e+03 -6.80200195e+03 -6.63893066e+03 -6.86040283e+03 -7.07936230e+03 -6.86901807e+03 -6.73835938e+03 -6.68477686e+03 -6.64966016e+03 -6.60531982e+03 -6.46625293e+03 -6.69263428e+03 -6.79622412e+03 -6.54998682e+03 -6.69323340e+03 -6.71603760e+03 -6.61682715e+03 -6.55474561e+03 -6.48016650e+03 -6.43420801e+03 -6.27153271e+03 -6.16933398e+03 -6.41519189e+03 -6.55013037e+03 -6.21137158e+03 -5.94438965e+03 -6.17347656e+03 -6.49681396e+03 -6.45548242e+03 -6.08627588e+03 -5.83606494e+03 -6.12283887e+03 -6.31791699e+03 -6.12540527e+03 -6.05805566e+03 -5.84081104e+03 -5.58397998e+03 -5.79184668e+03 -6.11109961e+03 -6.09993262e+03 -5.72305371e+03 -5.47820410e+03 -5.77217725e+03 -5.97967725e+03 -5.77326904e+03 -5.46606299e+03 -5.28486865e+03 -5.44953418e+03 -5.52480811e+03 -5.62109424e+03 -5.64645166e+03 -5.42562891e+03 -5.27226611e+03 -5.23336133e+03 -5.43212549e+03 -5.26557471e+03 -5.08213281e+03 -5.27767725e+03 -5.21704443e+03 -5.12023633e+03 -4.96571143e+03 -4.92258643e+03 -5.15434521e+03 -4.96449805e+03 -4.67987158e+03 -4.77014355e+03 -4.91381299e+03 -4.88179297e+03 -4.74331006e+03 -4.80111035e+03 -4.80204492e+03 -4.63521533e+03 -4.45551807e+03 -4.39042334e+03 -4.60174121e+03 -4.47377637e+03 -4.29678369e+03 -4.37947021e+03 -4.32773828e+03 -4.26819287e+03 -4.16877197e+03 -4.22427588e+03 -4.21469678e+03 -4.06514478e+03 -4.08708350e+03 -4.04575586e+03 -4.02934888e+03 -3.97773926e+03 -3.87626123e+03 -3.76720288e+03 -3.62320459e+03 -3.58890356e+03 -3.73822241e+03 -3.87503955e+03 -3.61828394e+03 -3.34892529e+03 -3.43732568e+03 -3.60514722e+03 -3.57446729e+03 -3.34326050e+03 -3.15410840e+03 -3.27560034e+03 -3.30145874e+03 -3.14124097e+03 -3.20965356e+03 -3.11394507e+03 -2.88518701e+03 -2.91770679e+03 -3.04113721e+03 -2.99194312e+03 -2.79718677e+03 -2.64742529e+03 -2.71419800e+03 -2.83348145e+03 -2.71851196e+03 -2.53064478e+03 -2.41810864e+03 -2.48355371e+03 -2.52329346e+03 -2.40119531e+03 -2.32517725e+03 -2.28204785e+03 -2.24303174e+03 -2.18427368e+03 -2.18767114e+03 -2.09516919e+03 -1.97803064e+03 -1.98062500e+03 -1.93737268e+03 -1.92609790e+03 -1.83461670e+03 -1.73501099e+03 -1.75647424e+03 -1.65164734e+03 -1.56210889e+03 -1.57524670e+03 -1.54908655e+03 -1.48846680e+03 -1.41249207e+03 -1.40448792e+03 -1.35777075e+03 -1.25792053e+03 -1.17807227e+03 -1.12312390e+03 -1.13673181e+03 -1.06382605e+03 -9.51649597e+02 -9.42843262e+02 -9.78059326e+02 -9.32817078e+02 -8.23333618e+02 -8.11798279e+02 -1.69367725e+03 -2.45293604e+03 1.44595953e+05 -46060172. 0. 0. 0. 0. 0. 1355850624. -8.61302031e+04 1.62657861e+04 -4.36760586e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 142385600. 2872176. 3.66754565e+03 1.84445703e+03 9.75788086e+02 8.59637512e+02 9.15331482e+02 9.63731995e+02 9.71127380e+02 1.00905957e+03 1.04672559e+03 1.06305566e+03 1.14226782e+03 1.23362500e+03 1.24374512e+03 1.27568311e+03 1.35177551e+03 1.41809265e+03 1.47233093e+03 1.47699792e+03 1.48363904e+03 1.55990405e+03 1.64872510e+03 1.71020813e+03 1.74323413e+03 1.75312354e+03 1.80666284e+03 1.91790918e+03 2.00332153e+03 1.98936792e+03 1.95844263e+03 2.02922681e+03 2.13934375e+03 2.16907812e+03 2.20486499e+03 2.27271118e+03 2.26296362e+03 2.34610303e+03 2.45015845e+03 2.39865112e+03 2.43865601e+03 2.56185205e+03 2.70370972e+03 2.76404175e+03 2.62655957e+03 2.58676782e+03 2.71127197e+03 2.87389062e+03 2.95581689e+03 2.88611987e+03 2.91531934e+03 3.06007056e+03 3.08110400e+03 3.11471729e+03 3.11901416e+03 3.06604297e+03 3.21285327e+03 3.37052124e+03 3.30107935e+03 3.31766577e+03 3.44160571e+03 3.43134595e+03 3.53154395e+03 3.60206445e+03 3.52129761e+03 3.54107202e+03 3.65419653e+03 3.81762158e+03 3.83247925e+03 3.74120728e+03 3.81144629e+03 3.83996143e+03 3.91915088e+03 4.05386670e+03 3.95834863e+03 3.95671387e+03 4.11011475e+03 4.20921973e+03 4.27621338e+03 4.20384961e+03 4.09467725e+03 4.17447754e+03 4.35479199e+03 4.47298096e+03 4.48718115e+03 4.43877930e+03 4.42325684e+03 4.56560303e+03 4.69404199e+03 4.58515625e+03 4.49167432e+03 4.61454102e+03 4.81999219e+03 4.87098145e+03 4.83377441e+03 4.74721094e+03 4.72221875e+03 4.92390674e+03 5.05111816e+03 4.90692969e+03 4.93907227e+03 5.11636963e+03 5.26542139e+03 5.28602441e+03 5.06481836e+03 4.96659766e+03 5.17227393e+03 5.28588965e+03 5.30411133e+03 5.30297363e+03 5.37474365e+03 5.50077197e+03 5.43247949e+03 5.41357617e+03 5.55789795e+03 5.46713623e+03 5.46083350e+03 5.65112793e+03 5.68550977e+03 5.73509131e+03 5.67005713e+03 5.54762061e+03 5.65159863e+03 5.79445312e+03 5.92617871e+03 5.88236182e+03 5.77587305e+03 5.86514453e+03 6.04138770e+03 6.09958643e+03 5.93184717e+03 5.79134473e+03 5.91248535e+03 6.09739990e+03 6.14710254e+03 6.09363965e+03 6.07528271e+03 6.08622998e+03 6.27059473e+03 6.36632324e+03 6.27237305e+03 6.23252148e+03 6.16632764e+03 6.25587891e+03 6.31812744e+03 6.23919824e+03 6.32276758e+03 6.39266797e+03 6.53938330e+03 6.65940332e+03 6.43386963e+03 6.30137061e+03 6.43920215e+03 6.57855029e+03 6.68529004e+03 6.64271533e+03 6.39105322e+03 6.42561377e+03 6.76207422e+03 6.94428467e+03 6.66426270e+03 6.48117236e+03 6.60979736e+03 6.86957373e+03 6.81093506e+03 6.54066748e+03 6.59184082e+03 6.82789160e+03 6.85249707e+03 6.82978223e+03 6.88288525e+03 6.93051709e+03 6.68843066e+03 6.87457568e+03 7.03940234e+03 6.74259570e+03 6.79224072e+03 6.96527002e+03 6.99682617e+03 7.06396631e+03 6.93960400e+03 6.72545410e+03 6.77047559e+03 7.00479736e+03 7.24934717e+03 7.27176172e+03 6.84333203e+03 6.89009619e+03 7.28343652e+03 7.09871777e+03 6.84606250e+03 6.89015723e+03 7.03559131e+03 7.15721582e+03 7.30979980e+03 7.24229004e+03 7.03151904e+03 6.85474219e+03 7.12406006e+03 7.25501025e+03 7.06100244e+03 7.04602148e+03 7.18308789e+03 7.31356836e+03 7.30031250e+03 7.09476611e+03 6.90497217e+03 6.98439502e+03 7.16254102e+03 7.33314355e+03 7.38094092e+03 6.99785547e+03 7.02155469e+03 7.26821045e+03 7.28718555e+03 7.16318604e+03 7.05095654e+03 7.07848145e+03 7.26926562e+03 7.31544385e+03 7.23636768e+03 7.06339648e+03 6.95281348e+03 7.08679150e+03 7.23360303e+03 7.06960645e+03 7.13422510e+03 7.19592871e+03 7.23193506e+03 7.34620361e+03 7.04668066e+03 6.87723633e+03 7.08907764e+03 7.08936279e+03 7.18587695e+03 6.96554248e+03 6.83283887e+03 7.09566748e+03 7.28209375e+03 7.16940088e+03 6.96549512e+03 7.02829834e+03 6.90701367e+03 6.88358838e+03 7.06048096e+03 7.25473730e+03 7.07227002e+03 6.80169922e+03 7.03087109e+03 6.93353662e+03 6.92896484e+03 6.95474854e+03 6.71738428e+03 6.90797217e+03 7.04328320e+03 6.80001172e+03 6.62140625e+03 6.75899512e+03 7.01603125e+03 7.04788525e+03 6.66862646e+03 6.58036035e+03 6.75963770e+03 6.82970850e+03 6.86273779e+03 6.66235254e+03 6.64560596e+03 6.56406738e+03 6.56662012e+03 6.80422021e+03 6.69642139e+03 6.41296875e+03 6.55548242e+03 6.75105908e+03 6.51307080e+03 6.44210303e+03 6.35960547e+03 6.29735547e+03 6.56076367e+03 6.66291406e+03 6.38491797e+03 6.26305371e+03 6.31611475e+03 6.43880615e+03 6.47836230e+03 6.24726904e+03 6.35490918e+03 6.35799902e+03 6.04041113e+03 6.07569287e+03 6.12464697e+03 6.10600684e+03 6.20720654e+03 6.13130078e+03 6.05708447e+03 6.16820459e+03 6.01757520e+03 5.87507715e+03 5.98189062e+03 6.02860742e+03 5.96690869e+03 5.74902588e+03 5.70192725e+03 5.92590625e+03 5.98735791e+03 5.71681494e+03 5.57731299e+03 5.63188086e+03 5.76091064e+03 5.79278809e+03 5.57937061e+03 5.51327002e+03 5.47758496e+03 5.54246240e+03 5.61445068e+03 5.40509668e+03 5.36547998e+03 5.36454053e+03 5.32504785e+03 5.35944092e+03 5.42484521e+03 5.27238330e+03 5.07972656e+03 5.26182080e+03 5.38744287e+03 5.11257471e+03 4.87500684e+03 4.96751172e+03 5.06815186e+03 5.03389697e+03 4.90643311e+03 4.82957178e+03 4.82834473e+03 4.90219678e+03 4.89248242e+03 4.72460791e+03 4.67456787e+03 4.66614502e+03 4.73218701e+03 4.64013428e+03 4.49149268e+03 4.52565234e+03 4.45878955e+03 4.40880029e+03 4.46174805e+03 4.42426270e+03 4.28570898e+03 4.23443506e+03 4.29016846e+03 4.26905029e+03 4.13047314e+03 4.05603906e+03 4.06023486e+03 4.11355322e+03 4.05599976e+03 3.87111670e+03 3.84399268e+03 3.87551270e+03 3.94004126e+03 3.91603027e+03 3.72822632e+03 3.76126831e+03 3.68223901e+03 3.50869263e+03 3.50779541e+03 3.51687183e+03 3.56821338e+03 3.51365405e+03 3.32537842e+03 3.24623438e+03 3.30293921e+03 3.37078540e+03 3.30553662e+03 3.19473413e+03 3.12882202e+03 3.05996729e+03 2.98709521e+03 2.93438232e+03 2.98065283e+03 2.97690308e+03 2.84786719e+03 2.79313550e+03 2.74432056e+03 2.73295483e+03 2.71409033e+03 2.65923193e+03 2.66701538e+03 2.53639941e+03 2.39560938e+03 2.37913843e+03 2.40349951e+03 2.41963721e+03 2.39185718e+03 2.27070801e+03 2.10877173e+03 2.10851562e+03 2.12907788e+03 2.06135083e+03 2.06075024e+03 2.00260120e+03 1.88241931e+03 1.88768848e+03 1.85620959e+03 1.76539270e+03 1.73627454e+03 1.67057263e+03 1.60116931e+03 1.55330896e+03 1.51472009e+03 1.48280933e+03 1.47560791e+03 1.46060437e+03 1.34665833e+03 1.24262366e+03 1.20284265e+03 1.18755566e+03 1.17582751e+03 1.11689246e+03 1.01924011e+03 9.57835815e+02 9.37116272e+02 9.16410461e+02 8.69881531e+02 7.99336609e+02 7.44475403e+02 6.93627930e+02 6.37624817e+02 5.85205933e+02 5.49404541e+02 5.06203827e+02 4.49648407e+02 4.04660767e+02 3.42915497e+02 2.90939514e+02 2.49360641e+02 2.00656967e+02 1.52267990e+02 9.75844269e+01 4.63816605e+01 -2.50952363e+00 -5.26627998e+01 -1.05147308e+02 -1.57030457e+02 -2.02228622e+02 -2.42172287e+02 -2.96125946e+02 -3.51017700e+02 -3.95035706e+02 -4.55790070e+02 -5.15449097e+02 -5.47596924e+02 -5.90112366e+02 -6.45147949e+02 -7.09084900e+02 -7.70223083e+02 -8.08164490e+02 -8.56181641e+02 -8.77062073e+02 -9.20453796e+02 -1.00249762e+03 -1.05593262e+03 -1.12136145e+03 -1.17352222e+03 -1.18638025e+03 -1.20517969e+03 -1.28358093e+03 -1.38355505e+03 -1.41657715e+03 -1.44153406e+03 -1.48823633e+03 -1.51186865e+03 -1.57321472e+03 -1.65085449e+03 -1.69202930e+03 -1.75079688e+03 -1.78224988e+03 -1.80010925e+03 -1.84425415e+03 -1.94672986e+03 -2.00958240e+03 -2.03245093e+03 -2.09852881e+03 -2.08705078e+03 -2.15302271e+03 -2.23835400e+03 -2.26578003e+03 -2.37264478e+03 -2.36779297e+03 -2.33803027e+03 -2.40503857e+03 -2.45284229e+03 -2.55814941e+03 -2.71727148e+03 -2.70866309e+03 -2.63686353e+03 -2.67205298e+03 -2.72087036e+03 -2.76206470e+03 -2.89415503e+03 -2.97991675e+03 -2.93656152e+03 -2.96088623e+03 -3.00872949e+03 -3.12000952e+03 -3.20666870e+03 -3.21240601e+03 -3.35377637e+03 -3.31358667e+03 -3.15614502e+03 -3.26247632e+03 -3.43708691e+03 -3.53489624e+03 -3.60805859e+03 -3.52889673e+03 -3.40500171e+03 -3.55541309e+03 -3.78226343e+03 -3.79165991e+03 -3.76138623e+03 -3.77922705e+03 -3.75796582e+03 -3.87560962e+03 -3.95881616e+03 -3.91880566e+03 -4.09467212e+03 -4.08542261e+03 -4.07197437e+03 -4.14180176e+03 -4.06628247e+03 -4.16616357e+03 -4.29843896e+03 -4.44886230e+03 -4.39055957e+03 -4.18586035e+03 -4.28103760e+03 -4.46154248e+03 -4.59078320e+03 -4.60514893e+03 -4.49773730e+03 -4.47428027e+03 -4.60958203e+03 -4.74695557e+03 -4.81899463e+03 -4.82592236e+03 -4.81042480e+03 -4.80157227e+03 -4.85799023e+03 -4.89088672e+03 -4.92340527e+03 -5.00687207e+03 -5.06329346e+03 -5.13566211e+03 -5.01194141e+03 -5.02399512e+03 -5.21335498e+03 -5.21476758e+03 -5.37078906e+03 -5.31696436e+03 -5.11925244e+03 -5.17943457e+03 -5.33072217e+03 -5.53030127e+03 -5.68205811e+03 -5.47882520e+03 -5.33616406e+03 -5.44143994e+03 -5.55564746e+03 -5.61234082e+03 -5.65775342e+03 -5.72252686e+03 -5.61586523e+03 -5.55314502e+03 -5.67942139e+03 -5.81439697e+03 -5.94610107e+03 -5.92302148e+03 -5.95249170e+03 -5.82334863e+03 -5.67614014e+03 -5.83261230e+03 -5.98053516e+03 -6.15984961e+03 -6.17828271e+03 -5.87113770e+03 -5.85404346e+03 -6.08291797e+03 -6.33284570e+03 -6.26123047e+03 -6.20095947e+03 -6.21417627e+03 -6.03035547e+03 -6.21234180e+03 -6.42312598e+03 -6.32606152e+03 -6.29948389e+03 -6.30070752e+03 -6.38689795e+03 -6.41490283e+03 -6.38509375e+03 -6.46987598e+03 -6.52966699e+03 -6.50691553e+03 -6.38214893e+03 -6.46287891e+03 -6.57041064e+03 -6.58135010e+03 -6.80766943e+03 -6.64875928e+03 -6.43999170e+03 -6.55049365e+03 -6.49503223e+03 -6.77927393e+03 -7.04884521e+03 -6.83067920e+03 -6.56879102e+03 -6.51658691e+03 -6.80821875e+03 -7.11399316e+03 -6.92510596e+03 -6.68756201e+03 -1.02340293e+04 -1.02513164e+04 -1.71651816e+04 -1.11026047e+05 15265469. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -419079328. -1.65937156e+05 -2.42262031e+04 -9.24829883e+03 -8.88943066e+03 -7.82492822e+03 -7.30154980e+03 -7281. -7.45069678e+03 -6.88572656e+03 -7.03068018e+03 -7.42029053e+03 -7.37417334e+03 -7.08762354e+03 -6.81518311e+03 -6.90909521e+03 -7.26255615e+03 -7.51399072e+03 -7.23657861e+03 -6.93570850e+03 -6.90852686e+03 -6.95294385e+03 -7.25741406e+03 -7.31326123e+03 -7.01793994e+03 -6.92384814e+03 -6.88985693e+03 -6.99495166e+03 -7.01827002e+03 -6.89141504e+03 -6.92237891e+03 -7.18085352e+03 -7.30616895e+03 -6.95116699e+03 -6.58520166e+03 -6.76582275e+03 -7.09513281e+03 -7.29370850e+03 -6.97384961e+03 -6.61867334e+03 -6.64858301e+03 -6.92815039e+03 -7.25916455e+03 -6.96443457e+03 -6.52127051e+03 -6.57562695e+03 -6.85573779e+03 -6.97922314e+03 -6.94934521e+03 -6.82403076e+03 -6.57484473e+03 -6.62737012e+03 -6.81134912e+03 -6.54136230e+03 -6.45548438e+03 -6.77098779e+03 -6.81661230e+03 -6.72757178e+03 -6.45428906e+03 -6.20988623e+03 -6.53894287e+03 -6.91916895e+03 -6.75157471e+03 -6.30110156e+03 -6.06335254e+03 -6.16711670e+03 -6.55679004e+03 -6.77076807e+03 -6.53361963e+03 -6.36128125e+03 -6.21305176e+03 -6.03110010e+03 -6.21002295e+03 -6.43222852e+03 -6.21692822e+03 -6.12500244e+03 -6.17226172e+03 -6.18198438e+03 -6.03629004e+03 -5.96594678e+03 -6.12337988e+03 -6.17331982e+03 -6.17324658e+03 -6.00592432e+03 -5.72406494e+03 -5.70098291e+03 -5.99411475e+03 -6.24125635e+03 -5.91237451e+03 -5.54207373e+03 -5.58704639e+03 -5.76127490e+03 -5.87661670e+03 -5.89906543e+03 -5.66475977e+03 -5.57275000e+03 -5.54178711e+03 -5.57364111e+03 -5.64603027e+03 -5.51907227e+03 -5.45132422e+03 -5.39460107e+03 -5.40695166e+03 -5.40090820e+03 -5.31099121e+03 -5.33426416e+03 -5.35291309e+03 -5.38555518e+03 -5.21969775e+03 -4.96678857e+03 -5.02551709e+03 -5.25729492e+03 -5.32959131e+03 -5.04105273e+03 -4.76739844e+03 -4.75425635e+03 -5.00459326e+03 -5.20701709e+03 -4.96017773e+03 -4.67935400e+03 -4.72248877e+03 -4.68111865e+03 -4.69530762e+03 -4.70649902e+03 -4.59978418e+03 -4.65679541e+03 -4.58295215e+03 -4.50208643e+03 -4.48979297e+03 -4.34044385e+03 -4.40427441e+03 -4.53594922e+03 -4.47704492e+03 -4.27592090e+03 -4.10351367e+03 -4.07658447e+03 -4.19910059e+03 -4.34053613e+03 -4.12091211e+03 -3.86565991e+03 -3.88951538e+03 -4.03472974e+03 -4.11248535e+03 -3.91899268e+03 -3.75998462e+03 -3.75588989e+03 -3.70820361e+03 -3.74329272e+03 -3.73075244e+03 -3.53257373e+03 -3.48323560e+03 -3.56997217e+03 -3.57558838e+03 -3.48275122e+03 -3.36144482e+03 -3.33118042e+03 -3.33326270e+03 -3.38604126e+03 -3.27219189e+03 -3.05965527e+03 -3.05485645e+03 -3.09751367e+03 -3.10657227e+03 -3.05350415e+03 -2.90573828e+03 -2.84746265e+03 -2.85263770e+03 -2.86868677e+03 -2.81509253e+03 -2.69830249e+03 -2.68893970e+03 -2.64831470e+03 -2.59625928e+03 -2.54065894e+03 -2.43466260e+03 -2.43682544e+03 -2.47762012e+03 -2.44358813e+03 -2.30822510e+03 -2.16953125e+03 -2.13968823e+03 -2.19352466e+03 -2.23073657e+03 -2.09409888e+03 -1.93682788e+03 -1.91310046e+03 -1.92690503e+03 -1.92609802e+03 -1.87705615e+03 -1.75727686e+03 -1.69477380e+03 -1.68085620e+03 -1.64624536e+03 -1.59546472e+03 -1.53503467e+03 -1.49338135e+03 -1.42596252e+03 -1.38804346e+03 -1.34772839e+03 -1.28216431e+03 -1.24260657e+03 -1.20058215e+03 -1.15873059e+03 -1.07028210e+03 -1.00173444e+03 -9.94189941e+02 -9.81969421e+02 -9.36138794e+02 -8.47118774e+02 -7.62037720e+02 -7.17886475e+02 -7.08402832e+02 -6.89546204e+02 -6.18928528e+02 -5.41072754e+02 -4.80738831e+02 -4.33133240e+02 -4.02702179e+02 -3.64368561e+02 -3.05167236e+02 -2.48889648e+02 -1.98764557e+02 -1.47918747e+02 -9.51947632e+01 -4.63831367e+01 2.70923066e+00 5.27361984e+01 1.05330391e+02 1.53544189e+02 1.91883072e+02 2.44807968e+02 3.04504028e+02 3.55349060e+02 4.06695801e+02 4.51893829e+02 5.11158661e+02 5.65644836e+02 5.90078979e+02 6.18345947e+02 6.79954956e+02 7.67273315e+02 8.43233826e+02 8.78130920e+02 8.76966309e+02 9.02349609e+02 9.73150452e+02 1.06945972e+03 1.14995056e+03 1.17899109e+03 1.16797925e+03 1.20984326e+03 1.32992908e+03 1.38303076e+03 1.36389185e+03 1.40731238e+03 1.48616846e+03 1.53499548e+03 1.63215491e+03 1.64318274e+03 1.63939331e+03 1.72957190e+03 1.73082202e+03 1.82504297e+03 1.93623352e+03 1.88404492e+03 1.96291956e+03 2.08076685e+03 2.07728296e+03 2.11388745e+03 2.16195068e+03 2.21916626e+03 2.29239746e+03 2.31060669e+03 2.27988208e+03 2.34743750e+03 2.51184521e+03 2.61210205e+03 2.59671509e+03 2.54164575e+03 2.52599292e+03 2.62118188e+03 2.79374438e+03 2.91297852e+03 2.90063330e+03 2.79469238e+03 2.83467065e+03 2.99678418e+03 3.03040747e+03 3.02742505e+03 3.07130713e+03 3.12552197e+03 3.17022827e+03 3.33719263e+03 3.30434326e+03 3.22409448e+03 3.33280005e+03 3.29343872e+03 3.46366064e+03 3.60741797e+03 3.53132837e+03 3.69369287e+03 3.65156665e+03 3.53875537e+03 3.69327002e+03 3.66432104e+03 3.78284692e+03 4.07210034e+03 3.90745044e+03 3.74038257e+03 3.86120166e+03 4.06151172e+03 4.24310986e+03 4.22853076e+03 4.04437891e+03 3.93482056e+03 4.06625708e+03 4.35476758e+03 4.53549316e+03 4.47338184e+03 4.28775977e+03 4.27560449e+03 4.49119775e+03 4.60493945e+03 4.48260107e+03 4.45806494e+03 4.57694434e+03 4.64319580e+03 4.80583447e+03 4.84833838e+03 4.68689990e+03 4.73843604e+03 4.76585645e+03 4.79007373e+03 4.94396484e+03 4.96188916e+03 5.10527637e+03 5.03069580e+03 4.88165820e+03 5.05799219e+03 4.97111768e+03 5.11462891e+03 5.51883398e+03 5.29030664e+03 4.95834326e+03 5.08625977e+03 5.38693994e+03 5.58319189e+03 5.64377686e+03 5.40082764e+03 5.17487012e+03 5.29004346e+03 5.61062207e+03 5.90351611e+03 5.74093457e+03 5.43617432e+03 5.40565967e+03 5.59302588e+03 5.78638477e+03 5.99880518e+03 5.96545361e+03 5.65645508e+03 5.61375684e+03 5.88759766e+03 6.00110352e+03 5.94630615e+03 5.95015283e+03 5.89098730e+03 5.86329932e+03 6.16523975e+03 6.23160156e+03 5.93534961e+03 5.95594238e+03 6.11456250e+03 6.16536328e+03 6.20167969e+03 6.16262646e+03 6.30196143e+03 6.39396484e+03 6.22895166e+03 6.15384814e+03 6.09804883e+03 6.34980713e+03 6.69212598e+03 6.60757031e+03 6.28277002e+03 6.14604297e+03 6.40230664e+03 6.75623242e+03 6.55206055e+03 6.24889697e+03 6.37133691e+03 6.57660645e+03 6.73663867e+03 6.93906250e+03 6.84181543e+03 6.48805859e+03 6.31950928e+03 6.55251025e+03 6.90632324e+03 6.89576172e+03 6.69285449e+03 6.69833252e+03 6.72199219e+03 6.86817627e+03 6.82362158e+03 6.64493750e+03 6.69716797e+03 6.65843359e+03 6.98723486e+03 7.14054492e+03 6.87820654e+03 6.85484131e+03 6.90875146e+03 7.08940039e+03 6.93629199e+03 6.63200146e+03 6.90696533e+03 7.33296924e+03 7.08026709e+03 6.73110791e+03 6.88343555e+03 7.28387744e+03 7.20605225e+03 7.10383496e+03 7.07526660e+03 6.88129883e+03 6.84115723e+03 7.27108008e+03 7.28755859e+03 6.99710986e+03 6.82662793e+03 6.81129492e+03 7.15486523e+03 7.48658936e+03 7.18124658e+03 6.95801514e+03 7.10199951e+03 7.10161572e+03 7.37001611e+03 7.35658105e+03 6.94924072e+03 6.93178564e+03 7.07734961e+03 7.14683789e+03 7.21219482e+03 7.17060400e+03 7.32914209e+03 7.26308643e+03 6.98206494e+03 7.01685449e+03 6.93499512e+03 7.22452197e+03 7.53988379e+03 7.35491650e+03 7.01458545e+03 6.93896582e+03 7.46092773e+03 7.56942676e+03 7.51499023e+03 8.42544141e+03 9.70180566e+03 1.27297061e+04 1.07363242e+05 67072368. 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. 0. 0. 0. 0. 0. 0. -151458048. 1.34417141e+05 1.68280078e+04 9.05071191e+03 7.50391064e+03 7.38228271e+03 7.00137256e+03 6.66210889e+03 6.60839941e+03 6.43254053e+03 6.69277246e+03 6.70297363e+03 6.53755664e+03 6.56304639e+03 6.55450244e+03 6.49541748e+03 6.50181055e+03 6.44681152e+03 6.41571143e+03 6.41413867e+03 6.36692822e+03 6.34645068e+03 6.19316748e+03 6.11401904e+03 6.39748340e+03 6.42122607e+03 6.05918652e+03 6.03083447e+03 6.31187695e+03 6.34544873e+03 6.16020117e+03 6.13220801e+03 6.06196289e+03 6.04775879e+03 6.01586719e+03 5.97554980e+03 5.97687207e+03 5.92599365e+03 5.77084717e+03 5.72429248e+03 5.96820410e+03 5.97365039e+03 5.79350830e+03 5.75082275e+03 5.74140918e+03 5.73538965e+03 5.66133643e+03 5.60084912e+03 5.61616260e+03 5.42728467e+03 5.33904590e+03 5.52751318e+03 5.48488721e+03 5.60186377e+03 5.60967578e+03 5.39164600e+03 5.19391211e+03 5.13136719e+03 5.43592578e+03 5.45154297e+03 5.20636426e+03 5.10699170e+03 5.11220068e+03 5.10670801e+03 5.03384717e+03 5.14694385e+03 5.09576270e+03 4.80823145e+03 4.75362012e+03 4.97346484e+03 5.05800049e+03 4.87975342e+03 4.77969385e+03 4.75465771e+03 4.70713086e+03 4.60493799e+03 4.56778662e+03 4.62391260e+03 4.58746631e+03 4.46031543e+03 4.44035254e+03 4.44947168e+03 4.39710107e+03 4.46991260e+03 4.40372266e+03 4.23985303e+03 4.25273682e+03 4.19800830e+03 4.20389844e+03 4.20201123e+03 4.09347974e+03 4.03645093e+03 3.92539087e+03 3.83529761e+03 3.95980713e+03 3.90575195e+03 3.68177954e+03 3.68921265e+03 3.86061304e+03 3.94180859e+03 3.76574878e+03 3.61725049e+03 3.52833130e+03 3.46942383e+03 3.46053296e+03 3.41445288e+03 3.42013550e+03 3.35824048e+03 3.36929224e+03 3.30944946e+03 3.18614038e+03 3.20363623e+03 3.06488062e+03 3.02660083e+03 3.16120093e+03 3.08731250e+03 2.96539941e+03 2.84445850e+03 2.77683618e+03 2.88865259e+03 2.85901074e+03 2.72333130e+03 2.61021240e+03 2.56220557e+03 2.58462598e+03 2.53475024e+03 2.55777075e+03 2.52973242e+03 2.40225708e+03 2.33221240e+03 2.29136670e+03 2.28504785e+03 2.23622339e+03 2.15946680e+03 2.08040356e+03 2.03500391e+03 2.03121814e+03 1.92570129e+03 1.87977905e+03 1.94215076e+03 1.88519800e+03 1.78208020e+03 1.68103088e+03 1.63191882e+03 1.68331006e+03 1.63262195e+03 1.54074036e+03 1.45207495e+03 1.39384680e+03 1.39427295e+03 1.33951880e+03 1.28698291e+03 1.21394031e+03 1.18635193e+03 1.19187915e+03 1.11356799e+03 1.05145776e+03 1.00669598e+03 9.50559875e+02 8.87858276e+02 8.34595276e+02 7.96736816e+02 7.51079956e+02 7.03730774e+02 6.29570862e+02 5.81930176e+02 5.70446045e+02 5.00287262e+02 4.33789520e+02 3.96512329e+02 3.46611603e+02 3.07583405e+02 2.50909561e+02 1.92418869e+02 1.51868698e+02 1.01783531e+02 4.93168373e+01 -6.71405494e-01 -4.99059944e+01 -1.00308990e+02 -1.50357498e+02 -2.01988693e+02 -2.45713211e+02 -2.99991760e+02 -3.68879089e+02 -4.12142975e+02 -4.47308350e+02 -4.82103455e+02 -5.37815063e+02 -6.23726196e+02 -6.70059875e+02 -7.00138794e+02 -7.34892273e+02 -7.78116272e+02 -8.47596191e+02 -8.97686707e+02 -9.70890625e+02 -1.00312695e+03 -1.01970990e+03 -1.09761267e+03 -1.14809167e+03 -1.22112549e+03 -1.25562756e+03 -1.26922095e+03 -1.33414355e+03 -1.38329102e+03 -1.44705396e+03 -1.45464270e+03 -1.53173657e+03 -1.67942456e+03 -1.67742920e+03 -1.68318494e+03 -1.69222070e+03 -1.72266125e+03 -1.87328040e+03 -1.94252307e+03 -1.93218848e+03 -1.91463928e+03 -1.96506409e+03 -2.08302490e+03 -2.12768042e+03 -2.22681665e+03 -2.26503491e+03 -2.26382129e+03 -2.24632178e+03 -2.27462988e+03 -2.47326221e+03 -2.49198730e+03 -2.46201929e+03 -2.50372461e+03 -2.54275464e+03 -2.70120532e+03 -2.75887744e+03 -2.67428735e+03 -2.69780615e+03 -2.87816187e+03 -2.95021484e+03 -2.84363281e+03 -2.87395337e+03 -3.07864209e+03 -3.12937500e+03 -3.08439819e+03 -3.06638574e+03 -3.09880664e+03 -3.31792993e+03 -3.32530981e+03 -3.25544775e+03 -3.33294458e+03 -3.37234766e+03 -3.50608691e+03 -3.54666235e+03 -3.47527954e+03 -3.43975806e+03 -3.59939160e+03 -3.85158691e+03 -3.76545435e+03 -3.75375269e+03 -3.85153735e+03 -3.85604248e+03 -3.89211011e+03 -3.92993408e+03 -3.95187036e+03 -3.90394556e+03 -3.92463257e+03 -4.05883008e+03 -4.14663330e+03 -4.30584521e+03 -4.22300537e+03 -4.08950464e+03 -4.24637646e+03 -4.36807373e+03 -4.54352539e+03 -4.48649023e+03 -4.39364160e+03 -4.43710156e+03 -4.45890479e+03 -4.57668115e+03 -4.60887988e+03 -4.73662451e+03 -4.76744092e+03 -4.68668750e+03 -4.66918408e+03 -4.58049512e+03 -4.80901562e+03 -5.14881885e+03 -5.05717676e+03 -4.95586670e+03 -4.84880615e+03 -4.77839355e+03 -5.05570752e+03 -5.33907910e+03 -5.21904541e+03 -5.00491992e+03 -5.02458350e+03 -5.21214111e+03 -5.24908643e+03 -5.40700342e+03 -5.43238672e+03 -5.31152832e+03 -5.33352002e+03 -5.35905322e+03 -5.56823193e+03 -5.62600146e+03 -5.36786084e+03 -5.38517871e+03 -5.73205957e+03 -5.70400684e+03 -5.45699902e+03 -5.59020654e+03 -5.91936475e+03 -5.87415576e+03 -5.74958105e+03 -5.64511914e+03 -5.67440625e+03 -6.02161963e+03 -6.05436182e+03 -5.92828027e+03 -5.78997168e+03 -5.76428467e+03 -5.97709180e+03 -6.03229199e+03 -6.03539600e+03 -5.91048584e+03 -6.08619727e+03 -6.31727734e+03 -6.16327686e+03 -6.30114990e+03 -6.31378369e+03 -6.13836621e+03 -6.24867627e+03 -6.30326562e+03 -6.30980713e+03 -6.28179395e+03 -6.17607422e+03 -6.12621826e+03 -6.39667871e+03 -6.76820947e+03 -6.45741162e+03 -6.19877148e+03 -6.42995215e+03 -6.55386523e+03 -6.75903174e+03 -6.61496045e+03 -6.41684424e+03 -6.71115674e+03 -6.75875586e+03 -6.42950195e+03 -6.39819531e+03 -6.82450244e+03 -6.83653369e+03 -6.66124365e+03 -6.56617725e+03 -6.36990723e+03 -6.67962744e+03 -7.17090234e+03 -7.00290332e+03 -6.77050928e+03 -6.58765234e+03 -6.50253955e+03 -6.85985449e+03 -7.28633447e+03 -7.08490723e+03 -6.71787061e+03 -6.68106396e+03 -6.88216113e+03 -6.93907812e+03 -7.10302832e+03 -6.96459961e+03 -6.79820898e+03 -7.00981104e+03 -6.96133154e+03 -7.18297119e+03 -7.14878711e+03 -6.94074170e+03 -6.97908350e+03 -6.95552051e+03 -7.12677783e+03 -6.98250586e+03 -6.91281592e+03 -7.25811133e+03 -7.29595361e+03 -7.05217725e+03 -6.86407227e+03 -6.92460205e+03 -7.34065527e+03 -7.31993604e+03 -7.13120312e+03 -6.93050146e+03 -6.93490234e+03 -7.14092236e+03 -7.16455615e+03 -7.19159961e+03 -6.94843604e+03 -7.12996143e+03 -7.41540479e+03 -7.14382568e+03 -7.33860889e+03 -7.37837109e+03 -7.12673486e+03 -7.02783984e+03 -7.02041895e+03 -7.24818896e+03 -7.25796533e+03 -7.00655859e+03 -6.99005957e+03 -7.36547656e+03 -7.42875684e+03 -6.99618799e+03 -6.81420459e+03 -6.96635693e+03 -7.26881152e+03 -7.55311084e+03 -7.26015381e+03 -6.90933545e+03 -7.19078174e+03 -7.36686523e+03 -7.16551807e+03 -7.05013330e+03 -7.02901660e+03 -6.96971289e+03 -7.01296777e+03 -7.11794385e+03 -6.91405420e+03 -7.05563477e+03 -7.38114307e+03 -7.10423438e+03 -7.11100244e+03 -6.97109131e+03 -6.84687402e+03 -7.18603418e+03 -7.19910254e+03 -7.00547949e+03 -6.84557617e+03 -6.64452295e+03 -6.77961133e+03 -7.14650293e+03 -7.37255566e+03 -6.98841455e+03 -6.67255322e+03 -6.88632959e+03 -6.92959619e+03 -7.14198340e+03 -7.08470850e+03 -6.83353809e+03 -6.75328320e+03 -6.74918896e+03 -6.76815771e+03 -6.61760498e+03 -6.75794531e+03 -7.03783594e+03 -6.83294531e+03 -6.80648193e+03 -6.66844824e+03 -6.51242334e+03 -6.91499756e+03 -6.87608594e+03 -6.63063916e+03 -6.47433008e+03 -6.39816797e+03 -6.57793359e+03 -6.56355322e+03 -6.71804248e+03 -6.76611426e+03 -6.49938086e+03 -6.32054053e+03 -6.40805469e+03 -6.68207910e+03 -6.57798193e+03 -6.39936377e+03 -6.28847754e+03 -6.24680615e+03 -6.28787744e+03 -6.23698486e+03 -6.39467578e+03 -6.38950879e+03 -6.14951221e+03 -6.33026465e+03 -6.38162500e+03 -6.20320020e+03 -6.17422852e+03 -6.12716602e+03 -6.11539062e+03 -5.92362939e+03 -5.82863965e+03 -6.11867236e+03 -6.16665186e+03 -5.79876074e+03 -5.60528711e+03 -5.88579004e+03 -6.20682275e+03 -6.06381738e+03 -5.69122900e+03 -5.55974316e+03 -5.85077930e+03 -5.86606250e+03 -5.64290283e+03 -5.76963428e+03 -5.57579785e+03 -5.29910742e+03 -5.43985498e+03 -5.72167188e+03 -5.79996533e+03 -5.45683691e+03 -5.16394922e+03 -5.43769678e+03 -5.66862549e+03 -5.47777979e+03 -5.18739844e+03 -5.07119824e+03 -5.19265625e+03 -5.20438477e+03 -5.31965186e+03 -5.26234863e+03 -5.04821484e+03 -5.02788867e+03 -4.99157422e+03 -5.12421338e+03 -4.98461279e+03 -4.81003662e+03 -4.95485791e+03 -4.89484717e+03 -4.88360596e+03 -4.76204639e+03 -4.63856787e+03 -4.86279785e+03 -4.70411816e+03 -4.47284229e+03 -4.54095459e+03 -4.60042236e+03 -4.58794922e+03 -4.48693799e+03 -4.54223145e+03 -4.54125391e+03 -4.39386719e+03 -4.22010449e+03 -4.15954590e+03 -4.34606543e+03 -4.21384961e+03 -4.06763306e+03 -4.14576416e+03 -4.09818115e+03 -4.04403125e+03 -3.97537427e+03 -4.03606421e+03 -3.96313281e+03 -3.79726514e+03 -3.89267896e+03 -3.86699854e+03 -3.77643066e+03 -3.73073706e+03 -3.67540430e+03 -3.58813794e+03 -3.46035669e+03 -3.36456030e+03 -3.49445679e+03 -3.65468677e+03 -3.41907129e+03 -3.17141357e+03 -3.27407983e+03 -3.44342798e+03 -3.35740674e+03 -3.13131494e+03 -3.00976343e+03 -3.13340820e+03 -3.09590967e+03 -2.94636353e+03 -3.02197021e+03 -2.96731714e+03 -2.77029321e+03 -2.72419629e+03 -2.81955591e+03 -2.84493896e+03 -2.66980566e+03 -2.51467773e+03 -2.56610278e+03 -2.67081445e+03 -2.57244653e+03 -2.40001489e+03 -2.29013257e+03 -2.34513257e+03 -2.40917896e+03 -2.28594238e+03 -2.17523438e+03 -2.14638184e+03 -2.11715308e+03 -2.05999097e+03 -2.07323804e+03 -1.98073767e+03 -1.87137183e+03 -1.87330103e+03 -1.83055640e+03 -1.82175378e+03 -1.73359668e+03 -1.63761462e+03 -1.64563635e+03 -1.55350293e+03 -1.50463098e+03 -1.51887317e+03 -1.45629236e+03 -1.39340540e+03 -1.32574988e+03 -1.32674634e+03 -1.29046021e+03 -1.19124194e+03 -1.11321179e+03 -1.07339307e+03 -1.09234912e+03 -1.00510559e+03 -9.16429565e+02 -1.00014044e+03 -1.30495874e+03 -1.18628259e+03 -1.20490332e+03 -1.13096423e+03 -4.58549512e+03 -102366048. 0. 0. 0. 0. 0. -3.15935667e+09 -3.15935667e+09 120488216. -8.61302031e+04 1.62657861e+04 -4.36760586e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -438734144. 4.98015723e+03 1.52368591e+03 9.08891174e+02 8.92662964e+02 1.01095392e+03 9.68202209e+02 9.69680115e+02 1.01592078e+03 1.06004211e+03 1.12189575e+03 1.20780310e+03 1.24410132e+03 1.24687744e+03 1.31832214e+03 1.40012561e+03 1.40891443e+03 1.43256494e+03 1.48304065e+03 1.55369690e+03 1.63725378e+03 1.69539636e+03 1.70110535e+03 1.69054517e+03 1.78064148e+03 1.89369604e+03 1.90298181e+03 1.94333069e+03 1.97625757e+03 2.00792126e+03 2.12184399e+03 2.12845898e+03 2.10392603e+03 2.18291162e+03 2.23694897e+03 2.31054175e+03 2.37962109e+03 2.36292334e+03 2.40911841e+03 2.53671338e+03 2.69015088e+03 2.66082642e+03 2.52294556e+03 2.56853442e+03 2.69000391e+03 2.78863525e+03 2.88674341e+03 2.87997070e+03 2.84208691e+03 2.96219971e+03 3.05212817e+03 3.00221191e+03 3.01691089e+03 3.05937573e+03 3.20181323e+03 3.36798975e+03 3.24037012e+03 3.16933765e+03 3.29811328e+03 3.41388208e+03 3.51588916e+03 3.49801636e+03 3.46103223e+03 3.46633301e+03 3.59456909e+03 3.79180664e+03 3.73175293e+03 3.59333228e+03 3.71115552e+03 3.81948877e+03 3.86748511e+03 3.95116943e+03 3.93976245e+03 3.87521240e+03 4.00546704e+03 4.13629639e+03 4.10520508e+03 4.07431494e+03 4.07708203e+03 4.13554688e+03 4.30284473e+03 4.45791455e+03 4.37040967e+03 4.25044482e+03 4.35647266e+03 4.52206641e+03 4.47305371e+03 4.45165381e+03 4.49127246e+03 4.61256494e+03 4.79782471e+03 4.74710059e+03 4.58206592e+03 4.59453955e+03 4.68570605e+03 4.82463379e+03 4.89605762e+03 4.84679004e+03 4.87447363e+03 5.03908203e+03 5.21489990e+03 5.11532617e+03 4.87350098e+03 4.92973584e+03 5.13918506e+03 5.21018262e+03 5.23593555e+03 5.18262158e+03 5.15695654e+03 5.35278174e+03 5.41418604e+03 5.28556201e+03 5.36863770e+03 5.42641895e+03 5.41561328e+03 5.57441650e+03 5.58560693e+03 5.46546924e+03 5.49530518e+03 5.53343896e+03 5.57202588e+03 5.74127637e+03 5.89494043e+03 5.75680713e+03 5.58832568e+03 5.73906055e+03 5.92690967e+03 5.84134619e+03 5.76895801e+03 5.76756543e+03 5.82958105e+03 6.02794092e+03 6.09291895e+03 5.91854297e+03 5.88814600e+03 5.98096875e+03 6.13600781e+03 6.19803467e+03 6.12005518e+03 6.10054932e+03 6.17037549e+03 6.28783740e+03 6.17159619e+03 6.05266211e+03 6.18420264e+03 6.26760400e+03 6.35977197e+03 6.50745557e+03 6.38315039e+03 6.14867773e+03 6.32319775e+03 6.50738135e+03 6.46486914e+03 6.40042432e+03 6.30075146e+03 6.36293896e+03 6.66022949e+03 6.75177832e+03 6.42765820e+03 6.32150830e+03 6.62052734e+03 6.75948779e+03 6.61567383e+03 6.42920410e+03 6.49747559e+03 6.74848633e+03 6.86274707e+03 6.64786670e+03 6.56948145e+03 6.66338232e+03 6.63319336e+03 6.77983838e+03 6.86628906e+03 6.70029785e+03 6.73743066e+03 6.88746240e+03 6.88081055e+03 6.77336719e+03 6.70707959e+03 6.71758398e+03 6.74129248e+03 6.90224707e+03 7.14041064e+03 7.13679297e+03 6.70640137e+03 6.79493506e+03 7.13634180e+03 6.85806689e+03 6.75740820e+03 6.83842090e+03 6.89104541e+03 7.10753760e+03 7.13402734e+03 6.82332520e+03 6.76072461e+03 6.84674463e+03 6.98906982e+03 7.06387061e+03 6.93159863e+03 6.94556934e+03 7.17976514e+03 7.13951172e+03 6.95034668e+03 6.85324658e+03 6.90617432e+03 6.93285791e+03 7.09867822e+03 7.17821094e+03 7.18467285e+03 6.86323926e+03 6.92601953e+03 7.12552490e+03 6.99252246e+03 6.92647607e+03 6.98096240e+03 6.99161865e+03 7.20298486e+03 7.21885986e+03 6.93250830e+03 6.90980273e+03 6.89840381e+03 6.98770264e+03 7.09264453e+03 6.96370410e+03 6.99866260e+03 7.02431396e+03 7.13253906e+03 7.21641895e+03 6.82823047e+03 6.76387061e+03 6.95781982e+03 6.97118164e+03 7.05875732e+03 6.95116162e+03 6.74714600e+03 6.92760107e+03 7.14806299e+03 6.89290039e+03 6.81536084e+03 6.90556592e+03 6.89603320e+03 6.89727344e+03 6.83972656e+03 7.01343896e+03 6.95999463e+03 6.76077051e+03 6.90884326e+03 6.72346484e+03 6.74712207e+03 6.90030908e+03 6.69432812e+03 6.70586816e+03 6.82077930e+03 6.69017871e+03 6.49836328e+03 6.54248340e+03 6.85819775e+03 6.97637842e+03 6.55048193e+03 6.47931055e+03 6.68087061e+03 6.67675635e+03 6.66701611e+03 6.45881348e+03 6.44918701e+03 6.57881836e+03 6.66972803e+03 6.56575879e+03 6.44532861e+03 6.41923193e+03 6.44021387e+03 6.56484326e+03 6.35950293e+03 6.25501562e+03 6.24482178e+03 6.22516504e+03 6.35102930e+03 6.52665137e+03 6377. 6.07231641e+03 6.08861084e+03 6.36197461e+03 6.39825000e+03 6.05249219e+03 6.17256494e+03 6.30414795e+03 6.00466846e+03 6.02989844e+03 5.96401123e+03 5.94009131e+03 6.16704004e+03 6.06009277e+03 5.82858105e+03 6.00790527e+03 6.01041846e+03 5.79634131e+03 5.88257617e+03 5.88522900e+03 5.80495361e+03 5.65386914e+03 5.59765234e+03 5.73570947e+03 5.82872949e+03 5.70552979e+03 5.51251416e+03 5.47632178e+03 5.64972217e+03 5.67555615e+03 5.43585254e+03 5.36349512e+03 5.38344531e+03 5.49358350e+03 5.49193652e+03 5.24187500e+03 5.22171436e+03 5.35365039e+03 5.32229590e+03 5.17967676e+03 5.24004199e+03 5.21266211e+03 5.04489648e+03 5.17464209e+03 5.22776562e+03 4.96970947e+03 4.78027148e+03 4.83601904e+03 4.93457422e+03 4.94414893e+03 4.86331299e+03 4.74697510e+03 4.70771973e+03 4.81773438e+03 4.82564990e+03 4.60997852e+03 4.53984326e+03 4.64164258e+03 4.72051465e+03 4.51705371e+03 4.38500879e+03 4.46859521e+03 4.40260059e+03 4.33673779e+03 4.31438477e+03 4.32009766e+03 4.25303857e+03 4.15982178e+03 4.17123096e+03 4.15832324e+03 4.08274414e+03 3.96857227e+03 3.95229810e+03 3.99871997e+03 3.96679248e+03 3.85371899e+03 3.79744849e+03 3.78767798e+03 3.86223706e+03 3.81256543e+03 3.62709326e+03 3.63279370e+03 3.63561060e+03 3.57105518e+03 3.49000220e+03 3.42636792e+03 3.44949634e+03 3.41702783e+03 3.29990527e+03 3.17914941e+03 3.23555493e+03 3.30286548e+03 3.20395239e+03 3.14100146e+03 3.07342139e+03 3.05534399e+03 2.95438501e+03 2.81224658e+03 2.86425708e+03 2.89510449e+03 2.85552734e+03 2.78488843e+03 2.64852197e+03 2.63329810e+03 2.64559448e+03 2.63663989e+03 2.62490942e+03 2.48302075e+03 2.38872217e+03 2.33494849e+03 2.35191748e+03 2.37695483e+03 2.29978857e+03 2.22248242e+03 2.08706226e+03 2.08886450e+03 2.11334619e+03 2.01878918e+03 1.99568201e+03 1.92410889e+03 1.86178027e+03 1.86626978e+03 1.78202722e+03 1.71541187e+03 1.72444360e+03 1.68915369e+03 1.58411926e+03 1.49610864e+03 1.47304175e+03 1.45002734e+03 1.44504846e+03 1.42152307e+03 1.32142908e+03 1.24076416e+03 1.17842053e+03 1.16518408e+03 1.15905664e+03 1.08345178e+03 1.00506403e+03 9.38916138e+02 9.07682800e+02 8.88360657e+02 8.51491882e+02 7.93056335e+02 7.29632080e+02 6.90154114e+02 6.30874390e+02 5.63270569e+02 5.29083191e+02 4.90797089e+02 4.45714111e+02 4.04893036e+02 3.38091309e+02 2.79019592e+02 2.40204575e+02 1.99078247e+02 1.49695267e+02 9.53342743e+01 4.63260155e+01 -2.37451839e+00 -5.15887299e+01 -1.02844467e+02 -1.51043045e+02 -1.97838654e+02 -2.41309692e+02 -2.96127502e+02 -3.45880432e+02 -3.82219238e+02 -4.39855652e+02 -5.00443024e+02 -5.46618713e+02 -5.90376404e+02 -6.26509949e+02 -6.83564026e+02 -7.49591248e+02 -7.99716003e+02 -8.46155334e+02 -8.60005371e+02 -9.02480225e+02 -9.77252502e+02 -1.04421411e+03 -1.10573035e+03 -1.13695715e+03 -1.16923840e+03 -1.18554626e+03 -1.26132605e+03 -1.36041956e+03 -1.37388367e+03 -1.41309460e+03 -1.45969958e+03 -1.49340173e+03 -1.53197827e+03 -1.58767749e+03 -1.65907666e+03 -1.73130298e+03 -1.78968237e+03 -1.78502454e+03 -1.78442993e+03 -1.86897083e+03 -1.94706653e+03 -2.00916479e+03 -2.07394019e+03 -2.06585522e+03 -2.11614819e+03 -2.15354370e+03 -2.21635889e+03 -2.33034448e+03 -2.31825781e+03 -2.35205054e+03 -2.38428003e+03 -2.37125269e+03 -2.46102173e+03 -2.63738477e+03 -2.66017090e+03 -2.59950317e+03 -2.68242261e+03 -2.69616357e+03 -2.66633838e+03 -2.78865796e+03 -2.88918555e+03 -2.92292554e+03 -2.96745947e+03 -2.93884277e+03 -3.00036890e+03 -3.10553296e+03 -3.17467334e+03 -3.32005713e+03 -3.27151929e+03 -3.12999121e+03 -3.17520435e+03 -3.34561475e+03 -3.46436646e+03 -3.48625293e+03 -3.47480078e+03 -3.38242554e+03 -3.49889331e+03 -3.70011475e+03 -3.67774072e+03 -3.69294458e+03 -3.68011035e+03 -3.71330200e+03 -3.85163892e+03 -3.80939185e+03 -3.81915381e+03 -4.05070703e+03 -4.10556006e+03 -4.05462524e+03 -3.98179346e+03 -3.90662305e+03 -4.04845386e+03 -4.24736572e+03 -4.39963086e+03 -4.34846338e+03 -4.15788721e+03 -4.14880518e+03 -4.34461084e+03 -4.50569385e+03 -4.46902344e+03 -4.45303271e+03 -4.39495752e+03 -4.47221973e+03 -4.62657031e+03 -4.71613525e+03 -4.76077734e+03 -4.71730713e+03 -4.78500537e+03 -4.76272656e+03 -4.66701221e+03 -4.78131299e+03 -4.91601904e+03 -4.99249658e+03 -5.12080957e+03 -4.95268457e+03 -4.84603662e+03 -5.02514209e+03 -5.15048535e+03 -5.29587549e+03 -5.25793262e+03 -5.06330859e+03 -5.05336865e+03 -5.23311865e+03 -5.46292334e+03 -5.51367529e+03 -5.36826709e+03 -5.30705371e+03 -5.34425977e+03 -5.35008203e+03 -5.42334766e+03 -5.58248682e+03 -5.67002148e+03 -5.58702686e+03 -5.47951123e+03 -5.46597754e+03 -5.61549072e+03 -5.80858740e+03 -5.88181885e+03 -5.86080225e+03 -5.69020410e+03 -5.55060938e+03 -5.70154883e+03 -5.92774756e+03 -6.06671436e+03 -6.03521631e+03 -5.79585059e+03 -5.70214502e+03 -5.95608350e+03 -6.22582080e+03 -6.06993750e+03 -6.09585107e+03 -6.07341650e+03 -5.92729639e+03 -6.11313428e+03 -6.24709912e+03 -6.19127393e+03 -6.15163428e+03 -6.25191895e+03 -6.30168701e+03 -6.18979590e+03 -6.25302734e+03 -6.30955859e+03 -6.47232178e+03 -6.45801221e+03 -6.26656885e+03 -6.31591357e+03 -6.27685742e+03 -6.41205664e+03 -6.73184521e+03 -6.61492334e+03 -6.31918408e+03 -6.34421973e+03 -6.43021436e+03 -6.75127197e+03 -6.84447998e+03 -6.55135205e+03 -6.44048730e+03 -6.54391602e+03 -6.70455762e+03 -6.85707227e+03 -6.79066797e+03 -6.65935107e+03 -9.21666504e+03 -8.94625586e+03 -1.72696289e+04 -1.12885312e+05 15265469. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 25050002. -2.44711675e+06 -2.60119180e+04 -1.92686797e+04 -1.22524102e+04 -9.32965332e+03 -9.32975098e+03 -7.58692969e+03 -6.89345996e+03 -6.98110986e+03 -7.33747559e+03 -7.22985498e+03 -6.94682715e+03 -6.80779053e+03 -6.68736133e+03 -7.03028516e+03 -7.41252002e+03 -7.15629102e+03 -6.88353613e+03 -6.78549072e+03 -6.82188184e+03 -7.12698535e+03 -7.12705811e+03 -6.82360303e+03 -6.75333301e+03 -6.89224756e+03 -6.87913672e+03 -6.72077588e+03 -6.75362891e+03 -6.91127979e+03 -7.09687402e+03 -7.12095850e+03 -6.73427100e+03 -6.41115820e+03 -6.62856738e+03 -7.00166748e+03 -7.17154004e+03 -6.87876709e+03 -6.55458984e+03 -6.44829395e+03 -6.73769092e+03 -7.09922314e+03 -6.83783105e+03 -6.44846484e+03 -6.48018311e+03 -6.79289697e+03 -6.73549902e+03 -6.59659033e+03 -6.62301465e+03 -6.53044727e+03 -6.63469775e+03 -6.66748340e+03 -6.31330469e+03 -6.33397803e+03 -6.63236035e+03 -6.77637354e+03 -6.63986719e+03 -6.29823926e+03 -6.07963770e+03 -6.38935254e+03 -6.80051416e+03 -6.61083740e+03 -6.26164014e+03 -6.02077197e+03 -5.95936914e+03 -6.32172021e+03 -6.64601709e+03 -6.41476855e+03 -6.25121045e+03 -6.16240381e+03 -6.00134961e+03 -6.08527148e+03 -6.24398047e+03 -6.05331689e+03 -5.92754541e+03 -6.14753369e+03 -6.01479199e+03 -5.74158936e+03 -5.82007227e+03 -6.07965869e+03 -6.13879004e+03 -6.04568750e+03 -5.86799023e+03 -5.65644873e+03 -5.55930518e+03 -5.81603467e+03 -6.11289014e+03 -5.84830371e+03 -5.46342822e+03 -5.44607471e+03 -5.64063379e+03 -5.82305127e+03 -5.79438281e+03 -5.51236279e+03 -5.40400049e+03 -5.52882471e+03 -5.48003857e+03 -5.40668799e+03 -5.41034814e+03 -5.35477539e+03 -5.39131592e+03 -5.33221094e+03 -5.14660693e+03 -5.15775439e+03 -5.28904248e+03 -5.33549463e+03 -5.28920654e+03 -5.12462402e+03 -4.91224609e+03 -4.91338184e+03 -5.15256641e+03 -5.19259521e+03 -4.93125781e+03 -4.73306250e+03 -4.65088916e+03 -4.84645801e+03 -5.10293945e+03 -4.90343311e+03 -4.59218994e+03 -4.57877100e+03 -4.66241602e+03 -4.62975635e+03 -4.49497900e+03 -4.46809570e+03 -4.61401221e+03 -4.60617090e+03 -4.42784619e+03 -4.26819238e+03 -4.22589502e+03 -4.37082422e+03 -4.50828662e+03 -4.37565820e+03 -4.17953467e+03 -4.05540161e+03 -3.95476685e+03 -4.08242871e+03 -4.25909619e+03 -4.07266089e+03 -3.84176489e+03 -3.78575244e+03 -3.90711499e+03 -4.03335962e+03 -3.87048999e+03 -3.70557446e+03 -3.66876294e+03 -3.67901929e+03 -3.68739502e+03 -3.61977417e+03 -3.48559204e+03 -3.40779712e+03 -3.51252881e+03 -3.52217017e+03 -3.35733447e+03 -3.24412476e+03 -3.25988428e+03 -3.30335522e+03 -3.33745752e+03 -3.22793311e+03 -3.01612524e+03 -2.98878394e+03 -3.06237280e+03 -3.04087793e+03 -2.95704150e+03 -2.87137378e+03 -2.80795093e+03 -2.78120752e+03 -2.79357910e+03 -2.71351367e+03 -2.61811987e+03 -2.65696826e+03 -2.65934741e+03 -2.55063867e+03 -2.43464014e+03 -2.38563745e+03 -2.41462256e+03 -2.44362476e+03 -2.38464087e+03 -2.26573926e+03 -2.14597729e+03 -2.08260913e+03 -2.13137769e+03 -2.19115161e+03 -2.07192749e+03 -1.90938904e+03 -1.86129590e+03 -1.89048035e+03 -1.90816431e+03 -1.83883740e+03 -1.73877478e+03 -1.67668054e+03 -1.63792712e+03 -1.58415491e+03 -1.54249304e+03 -1.51124304e+03 -1.46011841e+03 -1.41925696e+03 -1.36427380e+03 -1.28696045e+03 -1.24661365e+03 -1.23151782e+03 -1.19801843e+03 -1.14526575e+03 -1.04905762e+03 -9.76929077e+02 -9.78489807e+02 -9.72813232e+02 -9.06556702e+02 -8.26809204e+02 -7.56049622e+02 -6.98455627e+02 -6.86981384e+02 -6.75734741e+02 -6.06730957e+02 -5.25250488e+02 -4.70925079e+02 -4.38038483e+02 -3.98312042e+02 -3.48087067e+02 -2.95911377e+02 -2.44764069e+02 -1.95098999e+02 -1.43685669e+02 -9.23610229e+01 -4.56951294e+01 2.33003211e+00 5.20278053e+01 1.04621872e+02 1.51567734e+02 1.89484482e+02 2.35491409e+02 2.93818207e+02 3.53861298e+02 4.02263031e+02 4.40970612e+02 5.00538879e+02 5.54951965e+02 5.77723267e+02 6.05810181e+02 6.67920776e+02 7.52649658e+02 8.26705322e+02 8.61645325e+02 8.59505432e+02 8.81216003e+02 9.48661987e+02 1.04800293e+03 1.13616724e+03 1.15985205e+03 1.14234985e+03 1.18417273e+03 1.30799976e+03 1.35748059e+03 1.34517029e+03 1.39091748e+03 1.44563086e+03 1.49395093e+03 1.59728064e+03 1.61408875e+03 1.61150476e+03 1.69151624e+03 1.69838232e+03 1.79486121e+03 1.89382202e+03 1.84278442e+03 1.92950513e+03 2.03596826e+03 2.02716772e+03 2.07080664e+03 2.12887622e+03 2.17865308e+03 2.23412451e+03 2.26645825e+03 2.24830884e+03 2.29835034e+03 2.45613184e+03 2.56872363e+03 2.55286743e+03 2.48199976e+03 2.47158276e+03 2.57698633e+03 2.74365747e+03 2.84898071e+03 2.83890332e+03 2.73049438e+03 2.78615234e+03 2.93922510e+03 2.95746533e+03 2.97793359e+03 3.02864673e+03 3.06457593e+03 3.10610522e+03 3.27422534e+03 3.23566113e+03 3.15647656e+03 3.27840259e+03 3.25085034e+03 3.40353711e+03 3.51818970e+03 3.44745581e+03 3.62543237e+03 3.57341357e+03 3.46824487e+03 3.62773584e+03 3.59513794e+03 3.69565845e+03 3.99267236e+03 3.83761060e+03 3.65906396e+03 3.76505469e+03 3.97441943e+03 4.18130078e+03 4.15185498e+03 3.96929810e+03 3.86447705e+03 3.99964453e+03 4.25722119e+03 4.42732422e+03 4.38193115e+03 4.20759521e+03 4.21183936e+03 4.38317139e+03 4.46373975e+03 4.42313574e+03 4.41189941e+03 4.48482520e+03 4.55835986e+03 4.71316455e+03 4.75376953e+03 4.55812451e+03 4.59798730e+03 4.68593115e+03 4.73782959e+03 4.84414111e+03 4.85729590e+03 5.02733984e+03 4.94030322e+03 4.79173193e+03 4.96276709e+03 4.86521582e+03 5.01911719e+03 5.39781885e+03 5.17880518e+03 4.88680664e+03 4.99495605e+03 5.28670068e+03 5.48226172e+03 5.52165820e+03 5.26418213e+03 5.07549316e+03 5.20125195e+03 5.50483008e+03 5.73502637e+03 5.61131934e+03 5.32743848e+03 5.31310010e+03 5.51117090e+03 5.66156396e+03 5.86241016e+03 5.87738574e+03 5.53725684e+03 5.50532129e+03 5.84717920e+03 5.92438428e+03 5.70177051e+03 5.73513135e+03 5.83740918e+03 5.81732861e+03 6.04157373e+03 6.10755957e+03 5.81313965e+03 5.82432764e+03 6.00876758e+03 6.02738379e+03 6.07184814e+03 6.00237988e+03 6.15941455e+03 6.31885986e+03 6.20302002e+03 6.03997949e+03 5.93407275e+03 6.18901270e+03 6.55801074e+03 6.46524072e+03 6.16420898e+03 6.00397803e+03 6.22910156e+03 6.61589453e+03 6.47833984e+03 6.15147021e+03 6.21659473e+03 6.41777197e+03 6.59861719e+03 6.84744092e+03 6.69590527e+03 6.35596094e+03 6.20115283e+03 6.42037256e+03 6.74658594e+03 6.77322070e+03 6.60033105e+03 6.56712842e+03 6.58336133e+03 6.75671387e+03 6.74009180e+03 6.61196094e+03 6.54962695e+03 6.44914648e+03 6.79139746e+03 7.03568848e+03 6.74277686e+03 6.77032764e+03 6.81631445e+03 6.95679248e+03 6.81199268e+03 6.49915918e+03 6.75669434e+03 7.17427441e+03 7.00147803e+03 6.65821143e+03 6.70262256e+03 7.09252002e+03 7.10271924e+03 6.90749023e+03 6.92067334e+03 6.70992432e+03 6.68200049e+03 7.13970459e+03 7.16436230e+03 6.88434180e+03 6.70002051e+03 6.68774463e+03 6.98630518e+03 7.29175537e+03 7.01396777e+03 6.85823193e+03 7.00206934e+03 6.99722607e+03 7.19939941e+03 7.19066650e+03 6.81545020e+03 6.80866797e+03 7.00245996e+03 7.01041406e+03 7.05440234e+03 6.99948877e+03 7.18336377e+03 7.11280322e+03 6.84512549e+03 6.95727686e+03 6.88758203e+03 7.06422607e+03 7.37098877e+03 7.20193164e+03 6.93086426e+03 6.87010254e+03 7.26202100e+03 7.33921191e+03 7.23924561e+03 7.68417529e+03 8.85075391e+03 9.49718652e+03 5.73875117e+04 -8565182. 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. 0. 0. 0. 0. 0. 0. 0. 41193472. 1.10661867e+05 2.03885840e+04 1.20247461e+04 1.15107266e+04 1.03603867e+04 8.17232422e+03 8.29335938e+03 6.78318701e+03 6.80130029e+03 6.56662695e+03 6.35833057e+03 6.51876660e+03 6.52761035e+03 6.33413965e+03 6.34239648e+03 6.32551709e+03 6.28736523e+03 6.28711768e+03 6.25328857e+03 6.19703174e+03 6.07916455e+03 6.05118604e+03 6.26539258e+03 6.27429688e+03 5.96849170e+03 5.91595215e+03 6.20442627e+03 6.22429150e+03 6.04801611e+03 6.00393506e+03 5.92623291e+03 5.92728906e+03 5.90868018e+03 5.86186719e+03 5.84317871e+03 5.78841699e+03 5.66246875e+03 5.63541113e+03 5.83618018e+03 5.82330176e+03 5.66412793e+03 5.63825488e+03 5.64016553e+03 5.62112646e+03 5.55814062e+03 5.50027246e+03 5.48355322e+03 5.32450098e+03 5.29276660e+03 5.38107666e+03 5.32387598e+03 5.48414160e+03 5.51297998e+03 5.29372852e+03 5.08269922e+03 5.01435205e+03 5.33210693e+03 5.33639307e+03 5.09157324e+03 5.00206787e+03 5.00546289e+03 4.96625830e+03 4.88539893e+03 5.07503027e+03 5.01964355e+03 4.68905615e+03 4.64555957e+03 4.85811230e+03 4.99605273e+03 4.83270068e+03 4.68256934e+03 4.68522217e+03 4.62028418e+03 4.53643994e+03 4.51501855e+03 4.53859814e+03 4.47599805e+03 4.35063379e+03 4.32268506e+03 4.36980664e+03 4.30608398e+03 4.37539697e+03 4.29228662e+03 4.11768213e+03 4.14795947e+03 4.11207227e+03 4.15515918e+03 4.14702734e+03 4.02844604e+03 3.95773267e+03 3.83109106e+03 3.72652319e+03 3.87007520e+03 3.87838794e+03 3.63370679e+03 3.61814062e+03 3.79305371e+03 3.84929443e+03 3.68894409e+03 3.54281079e+03 3.49249561e+03 3.45071021e+03 3.37269702e+03 3.32260913e+03 3.34967407e+03 3.29848633e+03 3.29716821e+03 3.22406494e+03 3.11635327e+03 3.13411768e+03 3.00133276e+03 3.00581079e+03 3.12867261e+03 3.02117603e+03 2.90528760e+03 2.77758057e+03 2.71599023e+03 2.83476392e+03 2.81108276e+03 2.66723779e+03 2.55171509e+03 2.51227905e+03 2.52931396e+03 2.48007935e+03 2.50663550e+03 2.47898486e+03 2.35355957e+03 2.26540015e+03 2.22681104e+03 2.26077759e+03 2.21197144e+03 2.11923999e+03 2.02885681e+03 1.98074268e+03 1.98565515e+03 1.88492053e+03 1.85869519e+03 1.92887366e+03 1.85124829e+03 1.74656812e+03 1.65159875e+03 1.59815808e+03 1.64901038e+03 1.60631604e+03 1.51120764e+03 1.41974280e+03 1.36528564e+03 1.36688586e+03 1.31577466e+03 1.26095349e+03 1.18703040e+03 1.15952576e+03 1.15854578e+03 1.08227759e+03 1.03914441e+03 9.99824524e+02 9.32582214e+02 8.60427368e+02 8.12278320e+02 7.82809021e+02 7.35683289e+02 6.89155334e+02 6.17602478e+02 5.75334656e+02 5.63174072e+02 4.91219147e+02 4.26393158e+02 3.89460114e+02 3.40278717e+02 3.00354156e+02 2.45959503e+02 1.89257095e+02 1.48830139e+02 9.99331894e+01 4.87184982e+01 -7.40290701e-01 -4.97636261e+01 -9.76807480e+01 -1.46065338e+02 -1.97975510e+02 -2.40551712e+02 -2.93937531e+02 -3.63945496e+02 -4.06314728e+02 -4.34577911e+02 -4.67206543e+02 -5.31092651e+02 -6.16874084e+02 -6.56047424e+02 -6.85426941e+02 -7.20264771e+02 -7.62515991e+02 -8.31755493e+02 -8.79841370e+02 -9.50463257e+02 -9.84621643e+02 -9.98080261e+02 -1.07452881e+03 -1.12795642e+03 -1.19745068e+03 -1.23848975e+03 -1.25659607e+03 -1.29886963e+03 -1.34604272e+03 -1.42164197e+03 -1.43113562e+03 -1.50143567e+03 -1.63618860e+03 -1.64644666e+03 -1.65339160e+03 -1.65763354e+03 -1.69326453e+03 -1.83569958e+03 -1.89991821e+03 -1.89471838e+03 -1.88115918e+03 -1.93093311e+03 -2.03937854e+03 -2.08410571e+03 -2.18581396e+03 -2.22393262e+03 -2.21843115e+03 -2.19522388e+03 -2.23289941e+03 -2.43106934e+03 -2.45379175e+03 -2.42383008e+03 -2.44681494e+03 -2.48292676e+03 -2.64545093e+03 -2.71118896e+03 -2.61950073e+03 -2.64480249e+03 -2.83566919e+03 -2.88487134e+03 -2.78393408e+03 -2.81894604e+03 -3.02232251e+03 -3.07381177e+03 -3.01814746e+03 -2.99469873e+03 -3.02678247e+03 -3.26259912e+03 -3.28486865e+03 -3.21048706e+03 -3.26436792e+03 -3.27665381e+03 -3.37517773e+03 -3.44451733e+03 -3.44888208e+03 -3.40719556e+03 -3.53224438e+03 -3.73635938e+03 -3.65851074e+03 -3.72633887e+03 -3.81247754e+03 -3.76847144e+03 -3.82221924e+03 -3.85563477e+03 -3.86545728e+03 -3.83404419e+03 -3.85859033e+03 -3.98623242e+03 -4.05191504e+03 -4.21492676e+03 -4.13048389e+03 -4.03954736e+03 -4.18722705e+03 -4.25221191e+03 -4.42712207e+03 -4.39172021e+03 -4.30048193e+03 -4.35530127e+03 -4.37802686e+03 -4.48742529e+03 -4.51616406e+03 -4.65900586e+03 -4.65070361e+03 -4.55606445e+03 -4.62899805e+03 -4.52279395e+03 -4.71353613e+03 -5.04066016e+03 -4.95320459e+03 -4.83649951e+03 -4.74105713e+03 -4.72856006e+03 -4.99972168e+03 -5.18928662e+03 -5.07627393e+03 -4.91605615e+03 -4.94628418e+03 -5.12923975e+03 -5.13539844e+03 -5.28226416e+03 -5.28079004e+03 -5.15988428e+03 -5.27658203e+03 -5.29460059e+03 -5.48263037e+03 -5.52827051e+03 -5.25465967e+03 -5.28436182e+03 -5.62159814e+03 -5.55308105e+03 -5.30115332e+03 -5.50859375e+03 -5.84785840e+03 -5.76386035e+03 -5.63265820e+03 -5.53324561e+03 -5.57488428e+03 -5.90933105e+03 -5.92416211e+03 -5.80217383e+03 -5.68792236e+03 -5.66961768e+03 -5.87723096e+03 -5.92184814e+03 -5.91551758e+03 -5.82002881e+03 -5.97667969e+03 -6.18854346e+03 -6.06054346e+03 -6.17386182e+03 -6.10458203e+03 -5.96203125e+03 -6.11872363e+03 -6.18272070e+03 -6.21054004e+03 -6.16364062e+03 -6.13665039e+03 -6.04569873e+03 -6.23238086e+03 -6.65650293e+03 -6.32009570e+03 -6.04336084e+03 -6.24055469e+03 -6.48480322e+03 -6.67014990e+03 -6.49820898e+03 -6.35961279e+03 -6.52767627e+03 -6.57708594e+03 -6.32745361e+03 -6.27554590e+03 -6.65890039e+03 -6.65773340e+03 -6.45709180e+03 -6.51253027e+03 -6.31611523e+03 -6.54825684e+03 -6.99567627e+03 -6.82566650e+03 -6.65196094e+03 -6.47560449e+03 -6.41307861e+03 -6.78512988e+03 -7.16098535e+03 -6.91983984e+03 -6.57981982e+03 -6.56073877e+03 -6.73579492e+03 -6.77447119e+03 -6.99241357e+03 -6.82356445e+03 -6.64440869e+03 -6.87037842e+03 -6.82592822e+03 -7.03180469e+03 -6.98538770e+03 -6.70817871e+03 -6.96108105e+03 -6.96407861e+03 -6.88988037e+03 -6.71007861e+03 -6.80677832e+03 -7.19555664e+03 -7.11336279e+03 -6.82538086e+03 -6.69812598e+03 -6.88468115e+03 -7.26800391e+03 -7.19069043e+03 -6.97880273e+03 -6.77469727e+03 -6.75642529e+03 -6.97938916e+03 -7.01818945e+03 -7.03155225e+03 -6.82365967e+03 -6.98213916e+03 -7.21287207e+03 -7.00942578e+03 -7.18709521e+03 -7.15562012e+03 -6.97532520e+03 -7.01009424e+03 -7.02229199e+03 -6.98665771e+03 -6.96899609e+03 -6.90234229e+03 -6.90610303e+03 -7.18214648e+03 -7.17866650e+03 -6.85421582e+03 -6.75112305e+03 -6.89537549e+03 -7.10817236e+03 -7.33623047e+03 -7.08946240e+03 -6.71209814e+03 -6.98186377e+03 -7.29002197e+03 -7.14526025e+03 -6.82491064e+03 -6.83370703e+03 -6.92506641e+03 -6.94870312e+03 -6.96682959e+03 -6.78762891e+03 -6.92955762e+03 -7.22866748e+03 -7.05589355e+03 -6.91899512e+03 -6.75719629e+03 -6.79675000e+03 -7.09448096e+03 -7.05623926e+03 -6.91190234e+03 -6.73414062e+03 -6.52656152e+03 -6.64794482e+03 -7.01253955e+03 -7.25516016e+03 -6.82502734e+03 -6.52056641e+03 -6.69121143e+03 -6.82544287e+03 -7.06884717e+03 -6.89984473e+03 -6.61583350e+03 -6.72783447e+03 -6.69010986e+03 -6.65701514e+03 -6.49493018e+03 -6.57800146e+03 -6.88354150e+03 -6.76420605e+03 -6.64392480e+03 -6.47452393e+03 -6.44275830e+03 -6.77679883e+03 -6.77302051e+03 -6.55340967e+03 -6.36053760e+03 -6.29206299e+03 -6.46168604e+03 -6.43330371e+03 -6.60528613e+03 -6.65679248e+03 -6.30872559e+03 -6.14816016e+03 -6.35781836e+03 -6.58874023e+03 -6.36986572e+03 -6.25291406e+03 -6.20825146e+03 -6.18152393e+03 -6.11843262e+03 -5.97382666e+03 -6.20109326e+03 -6.29356250e+03 -6.08088477e+03 -6.18627051e+03 -6.21010352e+03 -6.12116748e+03 -6.09591504e+03 -6.01753418e+03 -5.99416992e+03 -5.83112988e+03 -5.72911914e+03 -5.96293213e+03 -6.06920459e+03 -5.77145898e+03 -5.50547754e+03 -5.72389453e+03 -6.03749268e+03 -5.97892041e+03 -5.64774756e+03 -5.41502490e+03 -5.66345703e+03 -5.84618506e+03 -5.68268262e+03 -5.62663281e+03 -5.40404883e+03 -5.18467773e+03 -5.36343115e+03 -5.67193555e+03 -5.63942871e+03 -5.28847510e+03 -5.09185156e+03 -5.37148145e+03 -5.53741553e+03 -5.33965625e+03 -5.06891357e+03 -4.91660352e+03 -5.05275391e+03 -5.11211523e+03 -5.20395312e+03 -5.25009326e+03 -5.03702686e+03 -4.87627148e+03 -4.85950146e+03 -5.03295605e+03 -4.87108105e+03 -4.71170508e+03 -4.88701123e+03 -4.84105371e+03 -4.75131592e+03 -4.60380078e+03 -4.56351562e+03 -4.78743896e+03 -4.60219873e+03 -4.34088965e+03 -4.42203125e+03 -4.55183691e+03 -4.53431641e+03 -4.39013232e+03 -4.45199609e+03 -4.45547266e+03 -4.29772656e+03 -4.12915332e+03 -4.06695068e+03 -4.27354785e+03 -4.15569531e+03 -3.98425293e+03 -4.07413867e+03 -4.01547339e+03 -3.94963086e+03 -3.86685889e+03 -3.91545874e+03 -3.91066968e+03 -3.77203101e+03 -3.78148779e+03 -3.75284375e+03 -3.73653320e+03 -3.69411157e+03 -3.60058716e+03 -3.49859937e+03 -3.35652344e+03 -3.33142676e+03 -3.47022461e+03 -3.59281079e+03 -3.35442773e+03 -3.10646411e+03 -3.18520850e+03 -3.33653003e+03 -3.31325854e+03 -3.09949219e+03 -2.92111768e+03 -3.03735620e+03 -3.06342358e+03 -2.91593628e+03 -2.97378833e+03 -2.88678882e+03 -2.68081567e+03 -2.70432275e+03 -2.81892041e+03 -2.77745044e+03 -2.59706641e+03 -2.45302393e+03 -2.51243774e+03 -2.63106665e+03 -2.52277148e+03 -2.34491626e+03 -2.24083960e+03 -2.30639868e+03 -2.33994531e+03 -2.22111401e+03 -2.15883984e+03 -2.11920435e+03 -2.07786572e+03 -2.02500415e+03 -2.02744336e+03 -1.94530383e+03 -1.83640015e+03 -1.83417114e+03 -1.79639563e+03 -1.78692627e+03 -1.69988501e+03 -1.60952161e+03 -1.63272583e+03 -1.53206030e+03 -1.44589600e+03 -1.46349805e+03 -1.44238245e+03 -1.38073547e+03 -1.30151453e+03 -1.30008130e+03 -1.26432080e+03 -1.17041138e+03 -1.09606519e+03 -1.04869373e+03 -1.06719885e+03 -9.86979309e+02 -8.86701355e+02 -9.58494812e+02 -1.14567749e+03 -1.05769348e+03 -2.65820068e+03 -3.05015674e+03 -1.89622422e+05 -2.80026650e+06 0. 0. 0. 0. 0. -3.15935667e+09 -14147680. -1.60170081e+03 -1.92591602e+04 1.62657861e+04 -4.36760586e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1261755264. 2.18308574e+04 1.28036255e+03 9.27579834e+02 9.23900330e+02 8.65357849e+02 9.41869507e+02 9.53082275e+02 9.96841431e+02 1.01909991e+03 1.03172375e+03 1.11249329e+03 1.19902661e+03 1.20781775e+03 1.24184570e+03 1.31286694e+03 1.37629773e+03 1.43214111e+03 1.43398340e+03 1.43784766e+03 1.51580310e+03 1.60148938e+03 1.66220496e+03 1.69471802e+03 1.70035779e+03 1.75571252e+03 1.86681702e+03 1.94261597e+03 1.93072412e+03 1.90555627e+03 1.97278027e+03 2.07860938e+03 2.10475195e+03 2.14485254e+03 2.21045679e+03 2.19579419e+03 2.27831616e+03 2.37808765e+03 2.32847681e+03 2.37032397e+03 2.49172876e+03 2.62886011e+03 2.68439111e+03 2.55125146e+03 2.51066016e+03 2.63184521e+03 2.78697095e+03 2.87109766e+03 2.80241650e+03 2.83664282e+03 2.97572656e+03 2.99463672e+03 3.02984326e+03 3.03040967e+03 2.97836865e+03 3.12165381e+03 3.27247412e+03 3.20403809e+03 3.23175488e+03 3.33960986e+03 3.33150415e+03 3.42950635e+03 3.49948120e+03 3.42313867e+03 3.43572046e+03 3.55354053e+03 3.70763599e+03 3.72469580e+03 3.62903784e+03 3.70334131e+03 3.73223267e+03 3.81294531e+03 3.93523877e+03 3.83904370e+03 3.84904590e+03 3.98400049e+03 4.08678467e+03 4.15575293e+03 4.08656836e+03 3.97355103e+03 4.05078540e+03 4.23531934e+03 4.34652734e+03 4.36148096e+03 4.31105225e+03 4.29334619e+03 4.43796777e+03 4.55296240e+03 4.45209521e+03 4.35779980e+03 4.48558301e+03 4.68229883e+03 4.74301270e+03 4.67856348e+03 4.60727490e+03 4.59430957e+03 4.77771729e+03 4.90002734e+03 4.77773975e+03 4.79107031e+03 4.95915869e+03 5.11670264e+03 5.14229102e+03 4.92308789e+03 4.82139893e+03 5.01095654e+03 5.15314307e+03 5.15888672e+03 5.16528320e+03 5.22580859e+03 5.34687256e+03 5.25992188e+03 5.25865381e+03 5.40875391e+03 5.31554736e+03 5.30204199e+03 5.46761914e+03 5.54265234e+03 5.59113428e+03 5.50859814e+03 5.38882471e+03 5.46899902e+03 5.62835254e+03 5.76112158e+03 5.73280811e+03 5.62162354e+03 5.68893555e+03 5.86644629e+03 5.93896387e+03 5.76342188e+03 5.63169434e+03 5.73050879e+03 5.91510107e+03 5.98180420e+03 5.93881152e+03 5.89967529e+03 5.91978516e+03 6.08627783e+03 6.17015381e+03 6.07839795e+03 6.07072705e+03 6.00244092e+03 6.08904150e+03 6.13055762e+03 6.07385059e+03 6.14225586e+03 6.19972998e+03 6.35404980e+03 6.48388916e+03 6.25138672e+03 6.09872949e+03 6.23098486e+03 6.38466846e+03 6.51313037e+03 6.45067432e+03 6.21151270e+03 6.25421289e+03 6.57480273e+03 6.72522803e+03 6.49272852e+03 6.26827734e+03 6.41280469e+03 6.67517773e+03 6.63720557e+03 6.34524951e+03 6.38892578e+03 6.59651270e+03 6.66486621e+03 6.62667285e+03 6.71457666e+03 6.68520557e+03 6.45779590e+03 6.68733008e+03 6.81188330e+03 6.54229443e+03 6.59188086e+03 6.77675098e+03 6.79229346e+03 6.86724951e+03 6.74575488e+03 6.52994531e+03 6.58007471e+03 6.82052588e+03 7.07271387e+03 7.09992920e+03 6.63454199e+03 6.68837939e+03 7.06600928e+03 6.90221875e+03 6.62770557e+03 6.67722070e+03 6.83500537e+03 6.99915576e+03 7.07713721e+03 7.01620410e+03 6.80193701e+03 6.65338379e+03 6.90827686e+03 7.03409961e+03 6.81660596e+03 6.85117480e+03 7.01646094e+03 7.08290967e+03 7.12096191e+03 6.88454785e+03 6.69623877e+03 6.82528906e+03 6.95065283e+03 7.14555615e+03 7.14052930e+03 6.82100684e+03 6.83143896e+03 7.01619482e+03 7.04011865e+03 6.98853027e+03 6.81993066e+03 6.82218408e+03 7.05487402e+03 7.12609766e+03 6.99128662e+03 6.89306494e+03 6.75710645e+03 6.93611621e+03 7.03427295e+03 6.83657471e+03 6.93120312e+03 6.98131787e+03 7.02188037e+03 7.19135107e+03 6.83614990e+03 6.70071289e+03 6.87500684e+03 6.90469922e+03 7.00556201e+03 6.77491260e+03 6.64449268e+03 6.88803076e+03 7.03900928e+03 6.98752979e+03 6.77046191e+03 6.82721484e+03 6.74314062e+03 6.68067432e+03 6.85040137e+03 7.05426221e+03 6.86833887e+03 6.58910449e+03 6.80029980e+03 6.71369092e+03 6.75744775e+03 6.74898828e+03 6.52476611e+03 6.69650146e+03 6.83307422e+03 6.55679932e+03 6.48163379e+03 6.59038428e+03 6.76152295e+03 6.84758789e+03 6.45611572e+03 6.39135010e+03 6.60941016e+03 6.64550049e+03 6.69607959e+03 6.44892822e+03 6.41230664e+03 6.39429541e+03 6.39336816e+03 6.57634033e+03 6.50934766e+03 6.25796924e+03 6.36308301e+03 6.53218408e+03 6.30135400e+03 6.23018945e+03 6.18555225e+03 6.14105078e+03 6.35918555e+03 6.47559521e+03 6.22267236e+03 6.08984766e+03 6.15089795e+03 6.21873828e+03 6.28758545e+03 6.10003613e+03 6.16146729e+03 6.16819434e+03 5.86147168e+03 5.91193311e+03 5.94983936e+03 5.93557031e+03 6.01874170e+03 5.96767285e+03 5.86753564e+03 5.99212695e+03 5.85608936e+03 5.69785156e+03 5.81751807e+03 5.87380078e+03 5.79435400e+03 5.59471826e+03 5.54465234e+03 5.76334180e+03 5.82476514e+03 5.58194189e+03 5.40930615e+03 5.48177930e+03 5.61084717e+03 5.64068750e+03 5.41235498e+03 5.36689893e+03 5.29992334e+03 5.37269775e+03 5.44367285e+03 5.25681396e+03 5.23084180e+03 5.21819336e+03 5.16576074e+03 5.20897021e+03 5.27172021e+03 5.11252686e+03 4.91664844e+03 5.11439697e+03 5.25582080e+03 4.97417578e+03 4.74616553e+03 4.81150781e+03 4.89815039e+03 4.89576562e+03 4.75513184e+03 4.69994189e+03 4.69759619e+03 4.76674365e+03 4.74302734e+03 4.60296338e+03 4.53792725e+03 4.52958545e+03 4.59812109e+03 4.49520361e+03 4.36834961e+03 4.40619775e+03 4.33972217e+03 4.27154639e+03 4.33101660e+03 4.31220459e+03 4.17040381e+03 4.10502832e+03 4.17212451e+03 4.14394678e+03 4.01104102e+03 3.93728345e+03 3.94399927e+03 3.99522119e+03 3.94261719e+03 3.76043652e+03 3.72884302e+03 3.75598022e+03 3.83125879e+03 3.80133887e+03 3.62474121e+03 3.65431909e+03 3.57635327e+03 3.41058862e+03 3.41700488e+03 3.43059790e+03 3.46026685e+03 3.40498657e+03 3.22451099e+03 3.15205835e+03 3.20831763e+03 3.27629370e+03 3.21074878e+03 3.10415698e+03 3.04686548e+03 2.96821265e+03 2.89663062e+03 2.84787964e+03 2.89470337e+03 2.90092822e+03 2.76538306e+03 2.70632227e+03 2.66180737e+03 2.65231323e+03 2.64142822e+03 2.58908643e+03 2.59667944e+03 2.45456885e+03 2.32410718e+03 2.31823413e+03 2.33788843e+03 2.35271631e+03 2.31631079e+03 2.20343750e+03 2.05100317e+03 2.04630115e+03 2.07092651e+03 2.00167944e+03 2.00244543e+03 1.95075891e+03 1.82589954e+03 1.82844104e+03 1.80434912e+03 1.71581274e+03 1.68368555e+03 1.62397974e+03 1.55517017e+03 1.50967712e+03 1.47497900e+03 1.43853687e+03 1.43117786e+03 1.42144299e+03 1.30888184e+03 1.20493127e+03 1.16979944e+03 1.15302612e+03 1.14377966e+03 1.08661487e+03 9.88702332e+02 9.30823730e+02 9.10695312e+02 8.91288940e+02 8.46450745e+02 7.74845154e+02 7.22109558e+02 6.74779541e+02 6.20578857e+02 5.69396301e+02 5.33438293e+02 4.91481110e+02 4.38028198e+02 3.92105469e+02 3.32370026e+02 2.82779022e+02 2.42559433e+02 1.95052185e+02 1.47778412e+02 9.46960449e+01 4.47294083e+01 -2.50449991e+00 -5.13965836e+01 -1.01990799e+02 -1.52571732e+02 -1.96315506e+02 -2.35046417e+02 -2.87815887e+02 -3.41021820e+02 -3.83325134e+02 -4.43454803e+02 -5.01771484e+02 -5.31722473e+02 -5.73559448e+02 -6.26928223e+02 -6.88843872e+02 -7.47899536e+02 -7.84283997e+02 -8.31466919e+02 -8.53109924e+02 -8.93909302e+02 -9.71089294e+02 -1.02724048e+03 -1.09185730e+03 -1.13993213e+03 -1.14800171e+03 -1.17333472e+03 -1.25502124e+03 -1.33869324e+03 -1.37233337e+03 -1.40483606e+03 -1.44650647e+03 -1.46574805e+03 -1.52473376e+03 -1.60353613e+03 -1.64696570e+03 -1.70150793e+03 -1.72825720e+03 -1.74737732e+03 -1.79281189e+03 -1.89266479e+03 -1.95009534e+03 -1.97087012e+03 -2.03866003e+03 -2.02762415e+03 -2.09557935e+03 -2.17597632e+03 -2.19972070e+03 -2.30824683e+03 -2.29335938e+03 -2.26972852e+03 -2.33843433e+03 -2.38566479e+03 -2.48695825e+03 -2.63355542e+03 -2.63214893e+03 -2.56078027e+03 -2.59504517e+03 -2.64230835e+03 -2.68293823e+03 -2.80994531e+03 -2.89798511e+03 -2.85381860e+03 -2.87036792e+03 -2.92414453e+03 -3.02882202e+03 -3.10896582e+03 -3.12179272e+03 -3.25975244e+03 -3.21551367e+03 -3.06260645e+03 -3.17067432e+03 -3.34401758e+03 -3.43625708e+03 -3.50135767e+03 -3.43395996e+03 -3.30690210e+03 -3.44921631e+03 -3.67926538e+03 -3.68740381e+03 -3.65056616e+03 -3.66555835e+03 -3.64621875e+03 -3.77196558e+03 -3.84888550e+03 -3.81238184e+03 -3.97887402e+03 -3.98222852e+03 -3.95674121e+03 -4.01421411e+03 -3.94201172e+03 -4.03921436e+03 -4.18089893e+03 -4.32516357e+03 -4.25841113e+03 -4.06842969e+03 -4.15056055e+03 -4.33314941e+03 -4.46767578e+03 -4.47160254e+03 -4.36226318e+03 -4.34292529e+03 -4.47569434e+03 -4.61728174e+03 -4.66796777e+03 -4.68068359e+03 -4.68204541e+03 -4.66430811e+03 -4.70853369e+03 -4.74524756e+03 -4.79653076e+03 -4.86611279e+03 -4.90576270e+03 -5.00144775e+03 -4.86368604e+03 -4.88034570e+03 -5.06248438e+03 -5.06119971e+03 -5.22540527e+03 -5.17600830e+03 -4.95495117e+03 -5.03616406e+03 -5.17980469e+03 -5.36904590e+03 -5.50564502e+03 -5.32380078e+03 -5.19209570e+03 -5.26351416e+03 -5.38154736e+03 -5.46687695e+03 -5.50540820e+03 -5.54957275e+03 -5.44687939e+03 -5.41520703e+03 -5.49889014e+03 -5.65101660e+03 -5.78944873e+03 -5.73375098e+03 -5.75868994e+03 -5.67899854e+03 -5.52286377e+03 -5.67171045e+03 -5.82177441e+03 -5.98355225e+03 -5.98303906e+03 -5.70673975e+03 -5.67210205e+03 -5.91871582e+03 -6.17407910e+03 -6.09442676e+03 -6.01798877e+03 -6.02716455e+03 -5.85628271e+03 -6.04238818e+03 -6.23082812e+03 -6.14350977e+03 -6.11539453e+03 -6.09803320e+03 -6.20630078e+03 -6.22422510e+03 -6.21314551e+03 -6.29596826e+03 -6.36184033e+03 -6.34900684e+03 -6.17730127e+03 -6.27794189e+03 -6.39083105e+03 -6.38303369e+03 -6.60406396e+03 -6.46483594e+03 -6.23848779e+03 -6.36345264e+03 -6.35710986e+03 -6.63034424e+03 -6.89029150e+03 -6.60484766e+03 -6.39154688e+03 -6.34911621e+03 -6.64011426e+03 -7.09094922e+03 -6.97147705e+03 -6.43709033e+03 -1.18582842e+04 -1.34821279e+04 1.39985525e+06 314489440. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 12928603. -6.19341680e+04 -1.31654883e+04 -1.14451533e+04 -1.06301992e+04 -7.96314307e+03 -8.72070703e+03 -7.47048877e+03 -6.90203906e+03 -6.96636279e+03 -7.24449707e+03 -7.15752490e+03 -6.88268799e+03 -6.67287695e+03 -6.69357812e+03 -7.03028125e+03 -7.28095068e+03 -7.02548730e+03 -6.78253906e+03 -6.73357178e+03 -6.76171826e+03 -7.04035352e+03 -7.07813037e+03 -6.83877002e+03 -6.69433740e+03 -6.70915820e+03 -6.82700977e+03 -6.83955811e+03 -6.70304590e+03 -6.74596777e+03 -6.95306494e+03 -7.10352002e+03 -6.76213672e+03 -6.37745361e+03 -6.56188379e+03 -6.91052148e+03 -7.09466504e+03 -6.78109619e+03 -6.39136914e+03 -6.45958789e+03 -6.75726416e+03 -7.04508105e+03 -6.74084717e+03 -6.31379932e+03 -6.38159912e+03 -6.67480176e+03 -6.74899219e+03 -6.72225977e+03 -6.58172705e+03 -6.40192236e+03 -6.42874072e+03 -6.61871631e+03 -6.37237842e+03 -6.28592383e+03 -6.56698291e+03 -6.61023145e+03 -6.55677100e+03 -6.27585791e+03 -6.00937256e+03 -6.33895020e+03 -6.72790381e+03 -6.52176270e+03 -6.12866846e+03 -5.88908496e+03 -5.98773096e+03 -6.36593701e+03 -6.56546533e+03 -6.33393213e+03 -6.17383691e+03 -6.03404443e+03 -5.86122803e+03 -6.06806445e+03 -6.22669971e+03 -6.01607422e+03 -5.92867969e+03 -6.00114307e+03 -6.00656445e+03 -5.84705518e+03 -5.78021729e+03 -5.93537451e+03 -6.00007861e+03 -6.01016309e+03 -5.82972021e+03 -5.54842725e+03 -5.53381982e+03 -5.82701709e+03 -6.07061572e+03 -5.76368115e+03 -5.38501611e+03 -5.43095264e+03 -5.57766748e+03 -5.71195068e+03 -5.73292871e+03 -5.50883936e+03 -5.41453516e+03 -5.38193115e+03 -5.42504395e+03 -5.48305029e+03 -5.36877783e+03 -5.29995850e+03 -5.24097803e+03 -5.25782324e+03 -5.25050146e+03 -5.15113330e+03 -5.18365088e+03 -5.21350879e+03 -5.23157422e+03 -5.08454395e+03 -4.81681006e+03 -4.88235254e+03 -5.11690283e+03 -5.16496484e+03 -4.89742578e+03 -4.62882080e+03 -4.63711377e+03 -4.85998340e+03 -5.06248828e+03 -4.83233105e+03 -4.54030908e+03 -4.58983496e+03 -4.55489160e+03 -4.55031689e+03 -4.56032471e+03 -4.46804248e+03 -4.52782227e+03 -4.44438818e+03 -4.37755127e+03 -4.36116650e+03 -4.21757861e+03 -4.27664844e+03 -4.40407324e+03 -4.34602246e+03 -4.15345020e+03 -3.97874365e+03 -3.96342505e+03 -4.09290942e+03 -4.21338916e+03 -4.01860547e+03 -3.76558325e+03 -3.76838086e+03 -3.91622803e+03 -3.99487646e+03 -3.79460596e+03 -3.65499170e+03 -3.65127173e+03 -3.60838281e+03 -3.63913843e+03 -3.62023438e+03 -3.43138086e+03 -3.39004053e+03 -3.47625439e+03 -3.47254248e+03 -3.37856616e+03 -3.26585522e+03 -3.23539771e+03 -3.24312695e+03 -3.29107861e+03 -3.17633398e+03 -2.97118799e+03 -2.96931689e+03 -3.00662622e+03 -3.00973413e+03 -2.96747021e+03 -2.82591504e+03 -2.76651562e+03 -2.77141895e+03 -2.78503394e+03 -2.73592603e+03 -2.62181909e+03 -2.61149658e+03 -2.57304834e+03 -2.52202734e+03 -2.46663062e+03 -2.36278027e+03 -2.36734229e+03 -2.40606470e+03 -2.37132886e+03 -2.24249341e+03 -2.10811768e+03 -2.08034619e+03 -2.13253491e+03 -2.16398413e+03 -2.03430542e+03 -1.88113232e+03 -1.85885815e+03 -1.87303857e+03 -1.87099951e+03 -1.82299170e+03 -1.70468225e+03 -1.64612036e+03 -1.63451831e+03 -1.60101318e+03 -1.55013086e+03 -1.49101880e+03 -1.44957739e+03 -1.38515784e+03 -1.34865112e+03 -1.31079553e+03 -1.24572839e+03 -1.20643628e+03 -1.16600574e+03 -1.12600659e+03 -1.04092639e+03 -9.72740967e+02 -9.65037109e+02 -9.53069702e+02 -9.09168335e+02 -8.22531494e+02 -7.40122742e+02 -6.97616333e+02 -6.89120422e+02 -6.70337402e+02 -6.01304688e+02 -5.25248779e+02 -4.66957214e+02 -4.20577515e+02 -3.90677582e+02 -3.54220428e+02 -2.96066101e+02 -2.41484268e+02 -1.92798676e+02 -1.43304352e+02 -9.24827499e+01 -4.51550560e+01 2.51131868e+00 5.13092461e+01 1.02409660e+02 1.49202148e+02 1.86562714e+02 2.37859100e+02 2.95954712e+02 3.45071625e+02 3.94991577e+02 4.39328094e+02 4.96627533e+02 5.49233398e+02 5.72953552e+02 6.00805237e+02 6.61179199e+02 7.45277283e+02 8.17637329e+02 8.52316589e+02 8.51914917e+02 8.76531067e+02 9.45603638e+02 1.03636792e+03 1.11685474e+03 1.14930957e+03 1.13542798e+03 1.17428979e+03 1.29127246e+03 1.34380566e+03 1.32501147e+03 1.36641968e+03 1.44419434e+03 1.49264417e+03 1.58658508e+03 1.59612439e+03 1.58917566e+03 1.67944702e+03 1.68294934e+03 1.77011548e+03 1.88110291e+03 1.83248840e+03 1.90699792e+03 2.01594519e+03 2.01705225e+03 2.06116211e+03 2.09983569e+03 2.15359253e+03 2.22640308e+03 2.24590576e+03 2.21777197e+03 2.28078979e+03 2.43738501e+03 2.53588770e+03 2.52797070e+03 2.47349365e+03 2.45232373e+03 2.53975024e+03 2.70995142e+03 2.83061035e+03 2.82501733e+03 2.70316260e+03 2.74875220e+03 2.92386401e+03 2.94676416e+03 2.93850586e+03 2.98410352e+03 3.04032349e+03 3.08048047e+03 3.23968188e+03 3.20505127e+03 3.13017334e+03 3.23943457e+03 3.20702368e+03 3.36883105e+03 3.49534839e+03 3.43574170e+03 3.58632544e+03 3.53906250e+03 3.44794873e+03 3.58246655e+03 3.55363745e+03 3.67041187e+03 3.95587744e+03 3.79605469e+03 3.63202124e+03 3.76111987e+03 3.94721753e+03 4.12446191e+03 4.10803467e+03 3.93244214e+03 3.82124390e+03 3.94092725e+03 4.23206641e+03 4.40393164e+03 4.34622314e+03 4.15434375e+03 4.15573486e+03 4.37051904e+03 4.45941357e+03 4.34881201e+03 4.33425977e+03 4.43967871e+03 4.49952295e+03 4.67964258e+03 4.71267480e+03 4.56218750e+03 4.58928662e+03 4.61639258e+03 4.66259521e+03 4.79865186e+03 4.81932617e+03 4.95680420e+03 4.89014502e+03 4.74279004e+03 4.91814014e+03 4.83120557e+03 4.96667676e+03 5.34790283e+03 5.13836719e+03 4.81821875e+03 4.93875830e+03 5.23314551e+03 5.39719336e+03 5.47828369e+03 5.25156934e+03 5.03761426e+03 5.14453662e+03 5.45086572e+03 5.73549805e+03 5.59379834e+03 5.27034619e+03 5.25614893e+03 5.43611572e+03 5.63013037e+03 5.83472803e+03 5.78761523e+03 5.47583154e+03 5.45108740e+03 5.73629736e+03 5.81758789e+03 5.75802002e+03 5.77942725e+03 5.71758447e+03 5.68698193e+03 5.98066406e+03 6.05630713e+03 5.77804639e+03 5.77014795e+03 5.92287109e+03 5.98876074e+03 6.01263428e+03 5.98223438e+03 6.12437305e+03 6.24394531e+03 6.07864648e+03 5.98747070e+03 5.91893066e+03 6.16282178e+03 6.50918799e+03 6.39650635e+03 6.10347559e+03 5.96579150e+03 6.21325879e+03 6.57461426e+03 6.36705225e+03 6.04820410e+03 6.17749414e+03 6.38606396e+03 6.54607959e+03 6.76178271e+03 6.64870068e+03 6.28010498e+03 6.14222949e+03 6.35020361e+03 6.70938281e+03 6.70191260e+03 6.54430469e+03 6.49213574e+03 6.53292041e+03 6.72213916e+03 6.65590723e+03 6.44636719e+03 6.45870117e+03 6.46604541e+03 6.77447656e+03 6.94380420e+03 6.71590234e+03 6.67132080e+03 6.71663477e+03 6.90912939e+03 6.77542480e+03 6.42536084e+03 6.71387500e+03 7.12260205e+03 6.86329248e+03 6.55694385e+03 6.69493799e+03 7.06912305e+03 7.05444629e+03 6.87327686e+03 6.86306494e+03 6.65822656e+03 6.67347803e+03 7.06877197e+03 7.06747119e+03 6.81444385e+03 6.62255029e+03 6.63943994e+03 6.92452393e+03 7.28677588e+03 6.98569629e+03 6.79822314e+03 6.92595752e+03 6.91366748e+03 7.13863525e+03 7.11906396e+03 6.74390186e+03 6.71841162e+03 6.88085693e+03 6.93352295e+03 6.98926074e+03 6.98062207e+03 7.16907031e+03 7.08638867e+03 6.78750586e+03 6.78856885e+03 6.75292676e+03 7.02777979e+03 7.28085303e+03 7.13972266e+03 6.88587988e+03 6.78597314e+03 7.23916748e+03 7.36957178e+03 7.51447070e+03 7.98748193e+03 9.41653125e+03 1.28844590e+04 1.21028555e+05 -17152160. 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. 0. 0. 0. 0. 0. 0. 0. 41193472. 1.06774414e+05 2.03173262e+04 1.15811357e+04 1.05034355e+04 1.02411055e+04 7.31936279e+03 7.44216064e+03 6.71979688e+03 6.78184619e+03 6.61209473e+03 6.32134082e+03 6.40069775e+03 6.41375684e+03 6.29007617e+03 6.31388965e+03 6.25598535e+03 6.24020215e+03 6.23565088e+03 6.19494238e+03 6.13943799e+03 6.01262549e+03 5.94442920e+03 6.22026318e+03 6.22124121e+03 5.87262354e+03 5.84483398e+03 6.14753906e+03 6.15393311e+03 5.98639502e+03 5.95687354e+03 5.88477979e+03 5.88911963e+03 5.83306885e+03 5.80264941e+03 5.80119141e+03 5.76792920e+03 5.61818701e+03 5.55201465e+03 5.80006885e+03 5.80388281e+03 5.61909570e+03 5.57805713e+03 5.55810938e+03 5.55620801e+03 5.50006055e+03 5.44281006e+03 5.44071729e+03 5.27218213e+03 5.20801367e+03 5.34744336e+03 5.29317139e+03 5.43652002e+03 5.46448047e+03 5.23864209e+03 5.04978955e+03 4.97849756e+03 5.28816455e+03 5.29712402e+03 5.05714844e+03 4.95651025e+03 4.96959766e+03 4.96186719e+03 4.88528174e+03 4.99639160e+03 4.95337842e+03 4.66870264e+03 4.61101221e+03 4.81752393e+03 4.90477441e+03 4.73947607e+03 4.63882715e+03 4.62485254e+03 4.57366650e+03 4.46684521e+03 4.43316406e+03 4.48468262e+03 4.44666406e+03 4.33709570e+03 4.31204102e+03 4.33129053e+03 4.26461621e+03 4.33811328e+03 4.27646582e+03 4.10764648e+03 4.13412842e+03 4.09095044e+03 4.07893896e+03 4.06833569e+03 3.98084546e+03 3.91207422e+03 3.80999170e+03 3.72537915e+03 3.84605835e+03 3.79769580e+03 3.57169409e+03 3.58337671e+03 3.75328076e+03 3.83609155e+03 3.65980542e+03 3.51203394e+03 3.42123511e+03 3.37159253e+03 3.36060522e+03 3.31962769e+03 3.32606592e+03 3.26586963e+03 3.26930347e+03 3.21792114e+03 3.09346753e+03 3.11114355e+03 2.97413599e+03 2.94212256e+03 3.07035889e+03 2.98955371e+03 2.87737061e+03 2.76568188e+03 2.69506226e+03 2.80694751e+03 2.78185352e+03 2.63905078e+03 2.53257080e+03 2.49359082e+03 2.51366992e+03 2.46174023e+03 2.48419604e+03 2.45466724e+03 2.33791772e+03 2.26832861e+03 2.22310596e+03 2.22088550e+03 2.17472437e+03 2.10055420e+03 2.01738232e+03 1.97463269e+03 1.97311316e+03 1.86856543e+03 1.82732312e+03 1.88845996e+03 1.82992139e+03 1.73034973e+03 1.63348291e+03 1.58610632e+03 1.63588074e+03 1.58705493e+03 1.49503223e+03 1.41053845e+03 1.35626843e+03 1.35391467e+03 1.30092554e+03 1.25022412e+03 1.17883899e+03 1.15171680e+03 1.15744934e+03 1.08128552e+03 1.02160840e+03 9.77795776e+02 9.23564087e+02 8.61518250e+02 8.10571411e+02 7.74521973e+02 7.29370544e+02 6.83637207e+02 6.11312012e+02 5.64797119e+02 5.53602417e+02 4.86605774e+02 4.21478424e+02 3.85262360e+02 3.36949127e+02 2.98707275e+02 2.43665085e+02 1.86511520e+02 1.47496811e+02 9.88200989e+01 4.79282532e+01 -5.99164903e-01 -4.83829193e+01 -9.75011368e+01 -1.46008591e+02 -1.96274689e+02 -2.38564240e+02 -2.91055847e+02 -3.58746674e+02 -4.01229767e+02 -4.34212769e+02 -4.68185394e+02 -5.22218262e+02 -6.03989929e+02 -6.51687073e+02 -6.81305237e+02 -7.13882629e+02 -7.55864319e+02 -8.21842468e+02 -8.71767029e+02 -9.45166626e+02 -9.75235779e+02 -9.89075684e+02 -1.06456921e+03 -1.11534058e+03 -1.18653003e+03 -1.21785510e+03 -1.23218237e+03 -1.29750439e+03 -1.34502612e+03 -1.40575745e+03 -1.41455139e+03 -1.48839050e+03 -1.62879614e+03 -1.63030029e+03 -1.63664563e+03 -1.64312500e+03 -1.67346582e+03 -1.81880591e+03 -1.88638806e+03 -1.87874268e+03 -1.86180237e+03 -1.90952502e+03 -2.02161987e+03 -2.06483618e+03 -2.16482275e+03 -2.20128027e+03 -2.19726562e+03 -2.18073413e+03 -2.21065088e+03 -2.40480078e+03 -2.41905347e+03 -2.38979712e+03 -2.43389478e+03 -2.46969287e+03 -2.62276562e+03 -2.68102808e+03 -2.59649976e+03 -2.61852856e+03 -2.79744409e+03 -2.86684741e+03 -2.76310645e+03 -2.79078076e+03 -2.99120190e+03 -3.04506787e+03 -2.99835693e+03 -2.97871753e+03 -3.00718896e+03 -3.22647192e+03 -3.22778174e+03 -3.16153345e+03 -3.24588794e+03 -3.28028833e+03 -3.39475806e+03 -3.44495728e+03 -3.37557178e+03 -3.34147827e+03 -3.49559595e+03 -3.73479443e+03 -3.66937842e+03 -3.65103638e+03 -3.73231396e+03 -3.73713086e+03 -3.78608447e+03 -3.81926050e+03 -3.83956128e+03 -3.79705322e+03 -3.81410571e+03 -3.93234790e+03 -4.02951514e+03 -4.19112988e+03 -4.10733789e+03 -3.97444702e+03 -4.12335449e+03 -4.24591992e+03 -4.41944336e+03 -4.36151660e+03 -4.25855566e+03 -4.29552588e+03 -4.33214502e+03 -4.44615332e+03 -4.46381738e+03 -4.60823975e+03 -4.63830859e+03 -4.55269580e+03 -4.54114795e+03 -4.44253320e+03 -4.67838037e+03 -5.00482422e+03 -4.92187549e+03 -4.80221729e+03 -4.69739160e+03 -4.64232715e+03 -4.91178467e+03 -5.19311133e+03 -5.06994971e+03 -4.86935791e+03 -4.89334229e+03 -5.06468457e+03 -5.09079150e+03 -5.25054053e+03 -5.26098584e+03 -5.15330029e+03 -5.17739014e+03 -5.19803369e+03 -5.41994824e+03 -5.47791504e+03 -5.21670605e+03 -5.22420898e+03 -5.55143555e+03 -5.54330371e+03 -5.29043604e+03 -5.43373633e+03 -5.74827734e+03 -5.71988721e+03 -5.58682422e+03 -5.48313330e+03 -5.50212988e+03 -5.86060645e+03 -5.87326270e+03 -5.75578467e+03 -5.65255273e+03 -5.60782422e+03 -5.79867578e+03 -5.88258643e+03 -5.84892578e+03 -5.72877051e+03 -5.91706885e+03 -6.13178564e+03 -5.98870850e+03 -6.11797803e+03 -6.09860254e+03 -5.97491846e+03 -6.07105420e+03 -6.12728271e+03 -6.16031396e+03 -6.11974707e+03 -6.01309229e+03 -5.94831445e+03 -6.21359766e+03 -6.61281982e+03 -6.28808887e+03 -6.00810156e+03 -6.22199756e+03 -6.38551758e+03 -6.58029932e+03 -6.41798730e+03 -6.22016699e+03 -6.53346436e+03 -6.59355518e+03 -6.25453955e+03 -6.22945068e+03 -6.62214111e+03 -6.64889453e+03 -6.44554541e+03 -6.38531787e+03 -6.16154980e+03 -6.47519336e+03 -6.94540039e+03 -6.78269678e+03 -6.57304004e+03 -6.40618457e+03 -6.32239648e+03 -6.66163086e+03 -7.08846191e+03 -6.86038330e+03 -6.52510645e+03 -6.49127295e+03 -6.71013037e+03 -6.75474268e+03 -6.93953711e+03 -6.77970166e+03 -6.60473926e+03 -6.78270068e+03 -6.77248730e+03 -7.00838916e+03 -6.96276221e+03 -6.74094580e+03 -6.77252197e+03 -6.74804150e+03 -6.92063330e+03 -6.72612305e+03 -6.66279053e+03 -7.09466992e+03 -7.06852832e+03 -6.80426709e+03 -6.65116650e+03 -6.76308594e+03 -7.13691602e+03 -7.13117578e+03 -6.93203418e+03 -6.74459473e+03 -6.71072119e+03 -6.92860498e+03 -6.90363525e+03 -6.95295312e+03 -6.77049561e+03 -6.92111475e+03 -7.20568896e+03 -6.92296484e+03 -7.11050781e+03 -7.14050195e+03 -6.96765430e+03 -6.83889111e+03 -6.77894385e+03 -7.05585010e+03 -7.06085352e+03 -6.77816650e+03 -6.74412744e+03 -7.11241357e+03 -7.17447070e+03 -6.78867822e+03 -6.60341113e+03 -6.78545654e+03 -7.04310840e+03 -7.32079883e+03 -6.99992627e+03 -6.69998975e+03 -6.96827832e+03 -7.12265332e+03 -6.98420703e+03 -6.84255566e+03 -6.81355615e+03 -6.79497070e+03 -6.79843457e+03 -6.90230469e+03 -6.68389209e+03 -6.85151562e+03 -7.16915479e+03 -6.96874805e+03 -6.91085303e+03 -6.76411572e+03 -6.66153027e+03 -6.98582715e+03 -6.97247217e+03 -6.82076025e+03 -6.65507275e+03 -6.44299414e+03 -6.56825928e+03 -6.90949170e+03 -7.13102295e+03 -6.77613330e+03 -6.50814404e+03 -6.66552100e+03 -6.71275439e+03 -6.96728125e+03 -6.88001465e+03 -6.63843701e+03 -6.58986816e+03 -6.55520264e+03 -6.54067334e+03 -6.39492383e+03 -6.57124951e+03 -6.82032129e+03 -6.61387354e+03 -6.63472314e+03 -6.49937842e+03 -6.33147656e+03 -6.70854053e+03 -6.67485938e+03 -6.45533936e+03 -6.29907227e+03 -6.21090527e+03 -6.40007373e+03 -6.37729346e+03 -6.53902832e+03 -6.58330957e+03 -6.30844678e+03 -6.16293604e+03 -6.22654053e+03 -6.50213428e+03 -6.37059326e+03 -6.21471631e+03 -6.11813867e+03 -6.07610059e+03 -6.10591846e+03 -6.06259180e+03 -6.20061230e+03 -6.19301660e+03 -5.99823926e+03 -6.15583203e+03 -6.18997070e+03 -6.03794141e+03 -5.98863623e+03 -5.97171631e+03 -5.94235254e+03 -5.76975098e+03 -5.66687451e+03 -5.95421387e+03 -5.98851855e+03 -5.62910742e+03 -5.44489893e+03 -5.70087207e+03 -6.03951123e+03 -5.89302979e+03 -5.52673340e+03 -5.39743018e+03 -5.68912256e+03 -5.70331494e+03 -5.49834521e+03 -5.60657031e+03 -5.41219678e+03 -5.14912061e+03 -5.27161523e+03 -5.55034326e+03 -5.62551074e+03 -5.29796338e+03 -5.02858008e+03 -5.29721875e+03 -5.49874512e+03 -5.29676660e+03 -5.04022656e+03 -4.93397510e+03 -5.06378174e+03 -5.05700977e+03 -5.15839355e+03 -5.10487451e+03 -4.91031592e+03 -4.88274268e+03 -4.84769629e+03 -4.97645459e+03 -4.82606396e+03 -4.66071826e+03 -4.80891016e+03 -4.74563037e+03 -4.74369922e+03 -4.61803418e+03 -4.50912256e+03 -4.73153613e+03 -4.56165527e+03 -4.34678271e+03 -4.41801074e+03 -4.45839014e+03 -4452. -4.35464893e+03 -4.40576904e+03 -4.40640039e+03 -4.25883643e+03 -4.10396973e+03 -4.03474219e+03 -4.21517383e+03 -4.10116162e+03 -3.94768921e+03 -4.02586597e+03 -3.97446655e+03 -3.92251978e+03 -3.86234619e+03 -3.91849390e+03 -3.85436353e+03 -3.70284399e+03 -3.77754004e+03 -3.75330884e+03 -3.66440674e+03 -3.63062183e+03 -3.57453564e+03 -3.48938989e+03 -3.35381274e+03 -3.26490430e+03 -3.38874072e+03 -3.54995752e+03 -3.32276172e+03 -3.08384717e+03 -3.18041113e+03 -3.33513892e+03 -3.25759814e+03 -3.04737646e+03 -2.92049829e+03 -3.04361450e+03 -3.01122217e+03 -2.86719946e+03 -2.93139282e+03 -2.87787256e+03 -2.69343530e+03 -2.64311499e+03 -2.73945142e+03 -2.76775928e+03 -2.59668921e+03 -2.44066943e+03 -2.48842163e+03 -2.59366211e+03 -2.49675000e+03 -2.33012915e+03 -2.22752490e+03 -2.28070557e+03 -2.34076514e+03 -2.21688135e+03 -2.11021436e+03 -2.08395703e+03 -2.05809204e+03 -2.00351257e+03 -2.01298877e+03 -1.92596802e+03 -1.82091492e+03 -1.81504810e+03 -1.77830591e+03 -1.76798083e+03 -1.68019629e+03 -1.59265942e+03 -1.60229565e+03 -1.51011523e+03 -1.46175842e+03 -1.47450146e+03 -1.41112830e+03 -1.34987830e+03 -1.28843042e+03 -1.28921179e+03 -1.25839771e+03 -1.16024878e+03 -1.07994690e+03 -1.04033679e+03 -1.06645593e+03 -1.01422363e+03 -9.36395203e+02 -8.12256653e+02 -9.22370117e+02 -1.53687366e+03 -1.19643584e+04 160289632. 0. 0. 0. 0. 0. 2.20249702e+09 -7.46532062e+05 -1.23679163e+03 -1.12045837e+03 -2.25595386e+03 -462779840. 0. 0. 1.05506458e+10 1.05506458e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1261755264. 3885088. 1.26736938e+03 1.28865381e+03 1.27105786e+03 8.46152588e+02 9.01689270e+02 9.67615356e+02 1.03626282e+03 1.02945129e+03 1.05897461e+03 1.11220276e+03 1.16267981e+03 1.18652161e+03 1.24009497e+03 1.31327417e+03 1.35042004e+03 1.39398450e+03 1.43137927e+03 1.46083008e+03 1.54184534e+03 1.59131140e+03 1.61752979e+03 1.66992834e+03 1.69897791e+03 1.75879065e+03 1.86729578e+03 1.91300098e+03 1.89855969e+03 1.93161902e+03 2.00593970e+03 2.05298413e+03 2.07954590e+03 2.12548901e+03 2.18567334e+03 2.22110938e+03 2.30053369e+03 2.33961841e+03 2.29841992e+03 2.37464648e+03 2.50412524e+03 2.56907764e+03 2.60010693e+03 2.54596606e+03 2.56018872e+03 2.69035840e+03 2.75130566e+03 2.76142676e+03 2.78238062e+03 2.82908594e+03 2.92749268e+03 3.00925977e+03 3.01495093e+03 2.96274414e+03 3.00002661e+03 3.20263257e+03 3.25261768e+03 3.12092261e+03 3.17026782e+03 3.30172559e+03 3.38050220e+03 3.45707251e+03 3.43077246e+03 3.35832349e+03 3.43778564e+03 3.57168457e+03 3.63588916e+03 3.62922021e+03 3.60628809e+03 3.71641089e+03 3.81492700e+03 3.79663403e+03 3.79546558e+03 3.81935254e+03 3.89150928e+03 3.99249927e+03 4.01622559e+03 4.08741528e+03 4.07704614e+03 4.00575024e+03 4.10647412e+03 4.21605469e+03 4.23159961e+03 4.27544873e+03 4.27122363e+03 4.31925684e+03 4.47129102e+03 4.47684424e+03 4.35885498e+03 4.40832812e+03 4.54475830e+03 4.62295264e+03 4.63083154e+03 4.59527588e+03 4.62360645e+03 4.70350049e+03 4.80044287e+03 4.78198389e+03 4.70545850e+03 4.80358838e+03 4.97148096e+03 5.00081543e+03 4.99556592e+03 4.91258936e+03 4.92220117e+03 5.10037646e+03 5.12354199e+03 5.04276807e+03 5.07097461e+03 5.13422412e+03 5.27411865e+03 5.30577295e+03 5.26854102e+03 5.30762061e+03 5.31699170e+03 5.40798633e+03 5.45722607e+03 5.39685449e+03 5.44432422e+03 5.47778223e+03 5.46598633e+03 5.56013770e+03 5.60676172e+03 5.61833105e+03 5.67837842e+03 5.64476465e+03 5.63290869e+03 5.73777930e+03 5.80927051e+03 5.79297656e+03 5.77002930e+03 5.74184961e+03 5.78386768e+03 5.90205811e+03 5.89480322e+03 5.85745361e+03 5.93292188e+03 6.09765479e+03 6.12698047e+03 5.96139307e+03 6.02925244e+03 6.09601172e+03 6.06672656e+03 6.06482275e+03 6.04631592e+03 6.10852881e+03 6.21121826e+03 6.33779932e+03 6.32545898e+03 6.17846631e+03 6.12606445e+03 6.22200879e+03 6.39298486e+03 6.38170850e+03 6.35141748e+03 6.29465771e+03 6.40106152e+03 6.50563135e+03 6.47529785e+03 6.38906299e+03 6.31933643e+03 6.41356104e+03 6.66712354e+03 6.57243848e+03 6.30601953e+03 6.41070166e+03 6.63881152e+03 6.60096680e+03 6.51993457e+03 6.59113428e+03 6.59589355e+03 6.56698975e+03 6.70684082e+03 6.61345898e+03 6.54879834e+03 6.72027783e+03 6.80406396e+03 6.69770166e+03 6.70090332e+03 6.74823828e+03 6.59822168e+03 6.74215771e+03 6.74151123e+03 6.76927881e+03 6.91577539e+03 6.61904932e+03 6.67854590e+03 6.96365967e+03 6.82908594e+03 6.68543262e+03 6.78424121e+03 6.87397559e+03 6.86322461e+03 6.88246777e+03 6.86661035e+03 6.73023682e+03 6.75159521e+03 6.97756445e+03 7.05192334e+03 6.75560156e+03 6842. 7.03478906e+03 6.92564648e+03 6.89080762e+03 6.82222754e+03 6.77773096e+03 6.96624707e+03 6.94916064e+03 6.90275293e+03 6.91239990e+03 6.83277393e+03 6.89722168e+03 7.05978516e+03 6.90007129e+03 6.88569922e+03 6.92088574e+03 6.89709814e+03 6.93918311e+03 6.94867432e+03 6.86960449e+03 6.86382178e+03 6.88562305e+03 6.92351270e+03 6.92825684e+03 6.82068066e+03 6.94331787e+03 6.98597168e+03 6.91581348e+03 7.01797559e+03 6.87650244e+03 6.68355273e+03 6.85963232e+03 6.90458887e+03 6.84771289e+03 6.75373682e+03 6.71877686e+03 6.83833057e+03 6.94369824e+03 6.86941602e+03 6.76212988e+03 6.85604932e+03 6.89149072e+03 6.71672754e+03 6.65067236e+03 6.83769092e+03 6.79523486e+03 6.64258447e+03 6.86160645e+03 6.76716357e+03 6.61160400e+03 6.72033691e+03 6.63456250e+03 6.58839014e+03 6.66190381e+03 6.61279834e+03 6.54614990e+03 6.62999219e+03 6.65909082e+03 6.69591748e+03 6.49160205e+03 6.41060205e+03 6.59705273e+03 6.51545215e+03 6.52884229e+03 6.49851904e+03 6.41931006e+03 6.43439258e+03 6.43568457e+03 6.52285107e+03 6.38116602e+03 6.21569287e+03 6.38196582e+03 6.54438330e+03 6.27219092e+03 6.13765723e+03 6.20670312e+03 6.18234082e+03 6.28951123e+03 6.30890479e+03 6.15471143e+03 6.09617432e+03 6.17815332e+03 6.15075293e+03 6.16879395e+03 6.09595068e+03 6.11026904e+03 6.12221484e+03 5.86299707e+03 5.91552441e+03 5.98991309e+03 5.88469434e+03 5.97508740e+03 5.90354492e+03 5.79508887e+03 5.88367090e+03 5.78360693e+03 5.74597559e+03 5.91554688e+03 5.80874854e+03 5.65788574e+03 5.60840967e+03 5.51840723e+03 5.62419678e+03 5.69357227e+03 5.55853662e+03 5.48479199e+03 5.56174365e+03 5.55513232e+03 5.49942383e+03 5.37692480e+03 5.32233008e+03 5.31883008e+03 5.37593750e+03 5.37378271e+03 5.18160303e+03 5.15709570e+03 5.22225781e+03 5.22132666e+03 5.17889355e+03 5.14929395e+03 5.05771680e+03 4.98630029e+03 5.12400586e+03 5.12417383e+03 4.89990332e+03 4.80665332e+03 4.79880176e+03 4.84007959e+03 4.81781787e+03 4.72463232e+03 4.73945654e+03 4.74163379e+03 4.68024854e+03 4.68215430e+03 4.60053223e+03 4.52520264e+03 4.54948096e+03 4.55543652e+03 4.42637061e+03 4.33201123e+03 4.36451270e+03 4.32410059e+03 4.28339355e+03 4.29812109e+03 4.22952344e+03 4.13289111e+03 4.13573242e+03 4.19722119e+03 4.09473657e+03 3.97241895e+03 3.98076416e+03 3.96839062e+03 3.91267554e+03 3.85612695e+03 3.78162305e+03 3.75744922e+03 3.74416162e+03 3.75575708e+03 3.73938086e+03 3.62516602e+03 3.58756860e+03 3.53892847e+03 3.47070874e+03 3.44587671e+03 3.38117334e+03 3.37753320e+03 3.35183472e+03 3.26833813e+03 3.20132227e+03 3.16876855e+03 3.19505713e+03 3.17940601e+03 3.12958325e+03 3.04207764e+03 2.96775146e+03 2.92823315e+03 2.85854077e+03 2.84117944e+03 2.83868726e+03 2.78307910e+03 2.72405811e+03 2.63770703e+03 2.59049097e+03 2.61713062e+03 2.60122925e+03 2.56247437e+03 2.44976099e+03 2.35782520e+03 2.35740625e+03 2.32471729e+03 2.26733643e+03 2.23278296e+03 2.20627612e+03 2.13005688e+03 2.06136206e+03 2.01714124e+03 1.97028271e+03 1.98513721e+03 1.95787036e+03 1.85376685e+03 1.82325061e+03 1.76091406e+03 1.67900769e+03 1.68825793e+03 1.65318506e+03 1.55903650e+03 1.51680298e+03 1.47062634e+03 1.40577234e+03 1.39736414e+03 1.38491895e+03 1.29680396e+03 1.23051172e+03 1.19808215e+03 1.14942383e+03 1.10722278e+03 1.05460071e+03 1.00141760e+03 9.57759277e+02 9.18366638e+02 8.75965454e+02 8.21377747e+02 7.63326599e+02 7.22606567e+02 6.81948181e+02 6.23017639e+02 5.67413818e+02 5.23276611e+02 4.88473083e+02 4.45791626e+02 3.93066711e+02 3.32239227e+02 2.78557678e+02 2.38159470e+02 1.93592682e+02 1.45929291e+02 9.41233597e+01 4.58217850e+01 1.36260200e+00 -4.73413124e+01 -9.59686508e+01 -1.50008606e+02 -1.98716904e+02 -2.43041962e+02 -2.96686829e+02 -3.39316467e+02 -3.74640625e+02 -4.36428467e+02 -4.99178558e+02 -5.29043701e+02 -5.68786621e+02 -6.23789368e+02 -6.73191101e+02 -7.29685669e+02 -7.83812378e+02 -8.24894653e+02 -8.56935852e+02 -9.06367432e+02 -9.64938721e+02 -1.01286676e+03 -1.07525317e+03 -1.12657996e+03 -1.15228821e+03 -1.18966797e+03 -1.26439160e+03 -1.30752209e+03 -1.33973022e+03 -1.40954663e+03 -1.46028687e+03 -1.48023474e+03 -1.50075500e+03 -1.55298376e+03 -1.62411206e+03 -1.70706897e+03 -1.75238684e+03 -1.75092065e+03 -1.78615515e+03 -1.84709265e+03 -1.90854346e+03 -1.98420630e+03 -2.01487732e+03 -2.01214624e+03 -2.10514331e+03 -2.16848242e+03 -2.16724023e+03 -2.27053857e+03 -2.31123340e+03 -2.29624463e+03 -2.36084253e+03 -2.38033374e+03 -2.40968823e+03 -2.54276489e+03 -2.59112109e+03 -2.58957007e+03 -2.66489990e+03 -2.68062866e+03 -2.64913599e+03 -2.72265308e+03 -2.83060645e+03 -2.87175659e+03 -2.91900879e+03 -2.93232422e+03 -2.95808203e+03 -3.03900977e+03 -3.09998145e+03 -3.23583594e+03 -3.21429395e+03 -3.11220605e+03 -3.19118018e+03 -3.27892871e+03 -3.35136255e+03 -3.44871582e+03 -3.42007593e+03 -3.37679419e+03 -3.49286304e+03 -3.59124707e+03 -3.60199585e+03 -3.64889404e+03 -3.67298071e+03 -3.65469458e+03 -3.76098047e+03 -3.81761572e+03 -3.77318359e+03 -3.94300928e+03 -4.01466406e+03 -3.95694531e+03 -3.97229761e+03 -3.90280615e+03 -3.96203979e+03 -4.13826270e+03 -4.29512451e+03 -4.28498975e+03 -4.10474658e+03 -4.15985107e+03 -4.35636035e+03 -4.36491748e+03 -4.36700586e+03 -4.40952246e+03 -4.41405029e+03 -4.48012256e+03 -4.54857666e+03 -4.58922607e+03 -4.60200391e+03 -4.64066309e+03 -4.73857715e+03 -4.70082812e+03 -4.68186523e+03 -4.72109668e+03 -4.76630029e+03 -4.86835840e+03 -5.01898389e+03 -4.95053076e+03 -4.82241260e+03 -4.93463428e+03 -5.03605811e+03 -5.19136523e+03 -5.18525439e+03 -5.00846289e+03 -5.09638135e+03 -5178. -5.26281006e+03 -5.37666357e+03 -5.30486865e+03 -5.28710400e+03 -5.30423926e+03 -5.27971094e+03 -5.32296387e+03 -5.47594434e+03 -5.59311035e+03 -5.49004102e+03 -5.46045410e+03 -5.43341406e+03 -5.48840430e+03 -5.70001514e+03 -5.74709229e+03 -5.70295801e+03 -5.67683936e+03 -5.58362939e+03 -5.66620557e+03 -5.75986572e+03 -5.89984131e+03 -5.96592236e+03 -5.74794385e+03 -5.73326025e+03 -5.87683105e+03 -5.94772607e+03 -5.96186328e+03 -6.03655127e+03 -6.09077783e+03 -5.95422803e+03 -6.00390479e+03 -6.04623193e+03 -6.06636475e+03 -6.12872559e+03 -6.17401318e+03 -6.19072168e+03 -6.14836279e+03 -6.11976611e+03 -6.21302295e+03 -6.38886133e+03 -6.33825732e+03 -6.21302002e+03 -6.24295459e+03 -6.28520654e+03 -6.27753613e+03 -6.52333008e+03 -6.51369922e+03 -6.26537793e+03 -6.44279053e+03 -6.37278711e+03 -6.49817188e+03 -6.69001270e+03 -6.51730615e+03 -6.45681836e+03 -6.50610400e+03 -6.61024121e+03 -6.65084424e+03 -6.78808105e+03 -6.60269189e+03 -8.37922852e+03 -8.68771680e+03 -1.66537090e+04 -2.98714336e+04 3.28185375e+06 128801400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -15632281. 3.74871525e+06 -22097878. 4087152. -4.40459930e+09 -1.10397178e+04 -1.23309600e+04 -7.89150879e+03 -7.05616992e+03 -6.92922559e+03 -7.21109717e+03 -7.06482129e+03 -6.90439648e+03 -6.71858936e+03 -6.76278906e+03 -6.95556982e+03 -7.07097168e+03 -6.97599756e+03 -6.79993262e+03 -6.78287793e+03 -6.80791113e+03 -6.95418408e+03 -6.90777197e+03 -6.63817236e+03 -6.69761670e+03 -6.88240283e+03 -6.85305713e+03 -6.67685303e+03 -6.53436670e+03 -6.75452832e+03 -7.05055615e+03 -7.01130518e+03 -6.63745312e+03 -6.32730518e+03 -6.52951123e+03 -6.83555127e+03 -6.96206982e+03 -6.80550830e+03 -6.50929736e+03 -6.54573242e+03 -6.66922217e+03 -6.81495312e+03 -6.68856299e+03 -6.34394336e+03 -6.44857227e+03 -6.78957422e+03 -6.63482227e+03 -6.42869971e+03 -6.47603662e+03 -6.47388330e+03 -6.59311670e+03 -6.56373486e+03 -6.29869238e+03 -6.18556592e+03 -6.47557275e+03 -6.60210840e+03 -6.51075049e+03 -6.26351904e+03 -6.09561133e+03 -6.37628906e+03 -6.56413867e+03 -6.36969238e+03 -6.16322705e+03 -5.91065674e+03 -6.01542383e+03 -6.31221191e+03 -6.38555273e+03 -6.27033105e+03 -6.15809131e+03 -6.11586475e+03 -5.98149170e+03 -6.04497852e+03 -6.07904102e+03 -5.85922754e+03 -5.90295898e+03 -6.11530225e+03 -5.99774756e+03 -5.71843604e+03 -5.66024805e+03 -5.92327002e+03 -6.07823535e+03 -5.96592139e+03 -5.74293555e+03 -5.55407178e+03 -5.56251758e+03 -5.68754395e+03 -5.91525586e+03 -5.78790381e+03 -5.44882812e+03 -5.49869824e+03 -5.54897656e+03 -5.56424658e+03 -5.64403516e+03 -5.44017969e+03 -5.36979492e+03 -5.48632324e+03 -5.45399219e+03 -5.33110205e+03 -5.23558984e+03 -5.27296338e+03 -5.35762598e+03 -5.29439209e+03 -5.12796631e+03 -5.00921143e+03 -5.13927490e+03 -5.26130615e+03 -5.17817725e+03 -5.04134326e+03 -4.87832959e+03 -4.92558008e+03 -5.03675146e+03 -4.99877930e+03 -4.87365869e+03 -4.65736035e+03 -4.65296387e+03 -4.83882080e+03 -4.92753223e+03 -4.79310107e+03 -4.53141699e+03 -4.53480518e+03 -4.65445557e+03 -4.59122656e+03 -4.45525342e+03 -4.36227686e+03 -4.49618604e+03 -4.52418555e+03 -4.36310400e+03 -4.28368408e+03 -4.17918164e+03 -4.26619238e+03 -4.39824609e+03 -4.26641748e+03 -4.11765527e+03 -4.00858350e+03 -4.00286963e+03 -4.03946973e+03 -4.07825488e+03 -3.99459668e+03 -3.79375879e+03 -3.76506543e+03 -3.88828223e+03 -3.90161670e+03 -3.76729150e+03 -3.63227051e+03 -3.63747388e+03 -3.68619824e+03 -3.64644775e+03 -3.54001025e+03 -3.37683179e+03 -3.38295410e+03 -3.48183813e+03 -3.43251270e+03 -3.33438477e+03 -3.21351294e+03 -3.19070435e+03 -3.23167505e+03 -3.26524341e+03 -3.18224683e+03 -3.00342529e+03 -2.98478076e+03 -2.99735376e+03 -2.96049683e+03 -2.92588159e+03 -2.82817896e+03 -2.80715674e+03 -2.77869263e+03 -2.70863672e+03 -2.65302246e+03 -2.59819580e+03 -2.62427832e+03 -2.61651343e+03 -2.53334644e+03 -2.41465869e+03 -2.33104980e+03 -2.37121875e+03 -2.41280737e+03 -2.33747510e+03 -2.23169092e+03 -2.12323462e+03 -2.05103516e+03 -2.08372510e+03 -2.13428076e+03 -2.02670642e+03 -1.87834009e+03 -1.86296912e+03 -1.88231116e+03 -1.85101514e+03 -1.79208191e+03 -1.70227380e+03 -1.65985645e+03 -1.63649548e+03 -1.56695105e+03 -1.50532642e+03 -1.47026953e+03 -1.44667273e+03 -1.40037573e+03 -1.34112646e+03 -1.28687598e+03 -1.23127808e+03 -1.20406995e+03 -1.18061877e+03 -1.12899988e+03 -1.04008228e+03 -9.72533752e+02 -9.67699219e+02 -9.38950562e+02 -8.77492065e+02 -8.12604919e+02 -7.40204529e+02 -6.98375305e+02 -6.84794250e+02 -6.52753601e+02 -5.89541748e+02 -5.15112183e+02 -4.65415680e+02 -4.33505890e+02 -3.91044037e+02 -3.39112823e+02 -2.87560242e+02 -2.41674927e+02 -1.93153961e+02 -1.44733353e+02 -9.62896957e+01 -4.90272255e+01 -1.28637516e+00 5.06186256e+01 1.03164749e+02 1.52533157e+02 1.90496582e+02 2.36876480e+02 2.86630310e+02 3.33975586e+02 3.89759216e+02 4.36074066e+02 4.94152344e+02 5.42800354e+02 5.63425110e+02 6.03158020e+02 6.65895691e+02 7.43843872e+02 8.16022278e+02 8.45609558e+02 8.43768433e+02 8.66329773e+02 9.39031494e+02 1.03675024e+03 1.11511914e+03 1.14002856e+03 1.12370447e+03 1.16504932e+03 1.28863513e+03 1.33973792e+03 1.31858643e+03 1.35973767e+03 1.43430188e+03 1.48560938e+03 1.57830518e+03 1.58785669e+03 1.57898547e+03 1.67216199e+03 1.68058154e+03 1.76382874e+03 1.86720862e+03 1.81676416e+03 1.90522339e+03 2.01069922e+03 2.00290137e+03 2.04882275e+03 2.09008594e+03 2.14394849e+03 2.20169043e+03 2.23659326e+03 2.22355884e+03 2.26191260e+03 2.40806958e+03 2.53058643e+03 2.52603516e+03 2.45144897e+03 2.43848706e+03 2.52770264e+03 2.69495410e+03 2.82198706e+03 2.81387939e+03 2.68929126e+03 2.73576147e+03 2.90240039e+03 2.92273315e+03 2.92617090e+03 2.96965186e+03 3.02437329e+03 3.06943945e+03 3.21566699e+03 3.18280322e+03 3.12031494e+03 3.23874072e+03 3.20813281e+03 3.35191260e+03 3.45511792e+03 3.42055615e+03 3.57020605e+03 3.50171851e+03 3.43764355e+03 3.57379321e+03 3.53399609e+03 3.64479858e+03 3.93780005e+03 3.77515576e+03 3.60360962e+03 3.72745068e+03 3.93444482e+03 4.12690186e+03 4.08324658e+03 3.89348071e+03 3.80548657e+03 3.94756299e+03 4.21213232e+03 4.38038281e+03 4.31699902e+03 4.11850195e+03 4.12249414e+03 4.31728662e+03 4.42475830e+03 4.35416211e+03 4.33409912e+03 4.43544385e+03 4.49391895e+03 4.66072656e+03 4.68403418e+03 4.49967773e+03 4.53784033e+03 4.61746582e+03 4.67533447e+03 4.76530078e+03 4.79059375e+03 4.92909277e+03 4.86802393e+03 4.73931543e+03 4.87500586e+03 4.79887256e+03 4.96776709e+03 5.32337305e+03 5.06804980e+03 4.79759424e+03 4.92635498e+03 5.21149121e+03 5.41125195e+03 5.43018359e+03 5.17607666e+03 4.99667090e+03 5.12925049e+03 5.43631982e+03 5.68690137e+03 5.54448926e+03 5.28265723e+03 5.25708301e+03 5.43758643e+03 5.56036523e+03 5.74340674e+03 5.73738037e+03 5.44685986e+03 5.45758496e+03 5.77139795e+03 5.83666650e+03 5.65390674e+03 5.66785742e+03 5.70438965e+03 5.70481543e+03 5.97735303e+03 6.03567334e+03 5.76144482e+03 5.75026367e+03 5.83965283e+03 5.92364502e+03 5.98412988e+03 5.94095898e+03 6.11608643e+03 6.21558691e+03 6.04957568e+03 5.94098242e+03 5.86037256e+03 6.09885986e+03 6.46913574e+03 6.37174268e+03 6.06172607e+03 5.90763477e+03 6.19349658e+03 6.55569287e+03 6.33800879e+03 6.01426367e+03 6.11803955e+03 6.32998633e+03 6.52041504e+03 6.71584668e+03 6.59143066e+03 6.24252637e+03 6.15508643e+03 6.36643750e+03 6.59737109e+03 6.63911230e+03 6.52996826e+03 6.46590332e+03 6.50448438e+03 6.67479395e+03 6.62910107e+03 6.44455127e+03 6.42616309e+03 6.42741553e+03 6.74790283e+03 6.83967529e+03 6.62499707e+03 6.65785498e+03 6.71879541e+03 6.86641553e+03 6.70639014e+03 6.37253271e+03 6.70654004e+03 7.07640186e+03 6.90650928e+03 6.56275195e+03 6.63647656e+03 6.96197949e+03 6.98549023e+03 6.83995703e+03 6.83105322e+03 6.65475586e+03 6.62617871e+03 6.98882715e+03 7.03256152e+03 6.69091553e+03 6.56542725e+03 6.58819629e+03 6.95246484e+03 7.23834668e+03 6.93675684e+03 6.70190430e+03 6.88128125e+03 6.89476465e+03 7.12956201e+03 7.05861719e+03 6.65677539e+03 6.76513135e+03 6.96971533e+03 6.89569629e+03 6.93527490e+03 6.86401172e+03 7.01455176e+03 7.03539307e+03 6.80317432e+03 6.83487988e+03 6.77389893e+03 6.92526904e+03 7.20306787e+03 7.07908936e+03 6.75396826e+03 6.75875488e+03 7.02367725e+03 7.27910986e+03 7.61957227e+03 7.72003662e+03 6.95976221e+03 8.34192773e+03 1.51797861e+04 1.17348469e+05 53426952. 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. 0. 0. 0. 0. 0. 0. 0. -48947436. 6.41627950e+06 1.56498862e+06 4.90040650e+06 1.92910371e+04 1.05036660e+04 8.76500879e+03 6.97105273e+03 6.76098047e+03 6.58782080e+03 6.23900928e+03 6.43736279e+03 6.49090967e+03 6.27231201e+03 6.25910547e+03 6.22589600e+03 6.18984082e+03 6.19411279e+03 6.13442871e+03 6.06351953e+03 6.04906885e+03 6.02154150e+03 6.11992285e+03 6.12274707e+03 5.86172412e+03 5.84015527e+03 6.10132129e+03 6.10710791e+03 5.93102295e+03 5.90854932e+03 5.86212549e+03 5.85687500e+03 5.80327148e+03 5.77169092e+03 5.75046875e+03 5.72264355e+03 5.64346240e+03 5.60518457e+03 5.72293799e+03 5.72036377e+03 5.60287158e+03 5.57057617e+03 5.55686621e+03 5.52149756e+03 5.47465869e+03 5.43720312e+03 5.42220312e+03 5.23557373e+03 5.19886963e+03 5.29239502e+03 5.26450586e+03 5.42768945e+03 5.42044043e+03 5.19853857e+03 5.01278955e+03 4.96284082e+03 5.26774512e+03 5.27605371e+03 5.03648486e+03 4.91355762e+03 4.88694971e+03 4.90697119e+03 4.85507568e+03 4.99454297e+03 4.96978906e+03 4.64416650e+03 4.55514258e+03 4.77199316e+03 4.93444678e+03 4.75737891e+03 4.61424121e+03 4.60952344e+03 4.55510010e+03 4.46651025e+03 4.45598779e+03 4.41029199e+03 4.35002686e+03 4.33586816e+03 4.29176758e+03 4.30925879e+03 4.25381738e+03 4.29984082e+03 4.26218750e+03 4.10214258e+03 4.10798242e+03 4.08461353e+03 4.05302539e+03 4.03385278e+03 3.96174268e+03 3.90992725e+03 3.78440698e+03 3.66965576e+03 3.80366357e+03 3.81542847e+03 3.57788989e+03 3.56774805e+03 3.73210425e+03 3.78345483e+03 3.62708032e+03 3.49061743e+03 3.43206641e+03 3.38893604e+03 3.32169360e+03 3.26953809e+03 3.29429517e+03 3.23808032e+03 3.26969800e+03 3.21184473e+03 3.08428101e+03 3.09154297e+03 2.97080127e+03 2.93668579e+03 3.04342847e+03 2.96733911e+03 2.85804663e+03 2.75430103e+03 2.66408936e+03 2.77010815e+03 2.78210254e+03 2.64261914e+03 2.51977124e+03 2.48509424e+03 2.50160547e+03 2.44908447e+03 2.47907153e+03 2.44566089e+03 2.32188550e+03 2.23312744e+03 2.18708472e+03 2.23031738e+03 2.18661255e+03 2.09045435e+03 2.01921082e+03 1.97679993e+03 1.95929077e+03 1.86118420e+03 1.82488831e+03 1.88367993e+03 1.81720386e+03 1.72086707e+03 1.62954089e+03 1.57405725e+03 1.62343848e+03 1.58079004e+03 1.48603796e+03 1.40338599e+03 1.34900830e+03 1.34110913e+03 1.29426538e+03 1.24532471e+03 1.16703625e+03 1.14462292e+03 1.15674219e+03 1.08033240e+03 1.02174762e+03 9.77336914e+02 9.18772766e+02 8.59680237e+02 8.13531799e+02 7.77105164e+02 7.27632385e+02 6.74718323e+02 6.06676270e+02 5.67968933e+02 5.53226318e+02 4.83257996e+02 4.19988892e+02 3.83504700e+02 3.34592163e+02 2.96180878e+02 2.42119431e+02 1.85566513e+02 1.46609070e+02 9.85096359e+01 4.78993874e+01 -1.02956986e+00 -4.94654045e+01 -9.63484344e+01 -1.42902405e+02 -1.91151062e+02 -2.33692291e+02 -2.89156311e+02 -3.57980804e+02 -4.00452087e+02 -4.31947754e+02 -4.64486755e+02 -5.16723694e+02 -5.99009644e+02 -6.48297852e+02 -6.78356873e+02 -7.07408020e+02 -7.49878113e+02 -8.20750916e+02 -8.67315063e+02 -9.37412476e+02 -9.67285583e+02 -9.81774353e+02 -1.06098315e+03 -1.11081799e+03 -1.18154907e+03 -1.22353662e+03 -1.23696924e+03 -1.28448096e+03 -1.33132690e+03 -1.39504431e+03 -1.40545752e+03 -1.46885510e+03 -1.59932910e+03 -1.62022913e+03 -1.62892810e+03 -1.63313477e+03 -1.66923621e+03 -1.81275146e+03 -1.86978369e+03 -1.86400452e+03 -1.85729175e+03 -1.90103711e+03 -2.00999048e+03 -2.05702368e+03 -2.15273999e+03 -2.17437549e+03 -2.16771631e+03 -2.19103662e+03 -2.22350830e+03 -2.38898389e+03 -2.42130933e+03 -2.39091724e+03 -2.42706030e+03 -2.47105688e+03 -2.58875317e+03 -2.64311304e+03 -2.57951782e+03 -2.61332031e+03 -2.79789233e+03 -2.84205151e+03 -2.74544629e+03 -2.77295508e+03 -2.97635718e+03 -3.03177466e+03 -2.97566968e+03 -2.95064795e+03 -2.99060449e+03 -3.21525708e+03 -3.23096997e+03 -3.17329736e+03 -3.24217383e+03 -3.26908105e+03 -3.30644971e+03 -3.34922266e+03 -3.39158203e+03 -3.35235181e+03 -3.47848975e+03 -3.71504517e+03 -3.64367578e+03 -3.63413062e+03 -3.70591016e+03 -3.71678394e+03 -3.75863965e+03 -3.79607568e+03 -3.82615527e+03 -3.77446777e+03 -3.75247925e+03 -3.88456567e+03 -4.03136816e+03 -4.20159814e+03 -4.08644629e+03 -3.97701807e+03 -4.12030664e+03 -4.20782520e+03 -4.37164600e+03 -4.35161328e+03 -4.25998828e+03 -4.26950781e+03 -4.28889844e+03 -4.41563623e+03 -4.44544971e+03 -4.58966357e+03 -4.61111182e+03 -4.52611377e+03 -4.51268115e+03 -4.42557910e+03 -4.65526416e+03 -4.96498291e+03 -4.89638086e+03 -4.78694434e+03 -4.68733008e+03 -4.66470557e+03 -4.93508398e+03 -5.12104004e+03 -4.99700879e+03 -4.84174512e+03 -4.87537500e+03 -5.05892676e+03 -5.06270508e+03 -5.23206055e+03 -5.24606934e+03 -5.12469189e+03 -5.17448438e+03 -5.19690137e+03 -5.34636523e+03 -5.39814111e+03 -5.18977148e+03 -5.21718066e+03 -5.54066846e+03 -5.46823486e+03 -5.21818896e+03 -5.41944189e+03 -5.75568652e+03 -5.69950244e+03 -5.55289355e+03 -5.46081348e+03 -5.49437793e+03 -5.84084814e+03 -5.85658447e+03 -5.68824170e+03 -5.60736670e+03 -5.58912158e+03 -5.77781299e+03 -5.80703418e+03 -5.83252686e+03 -5.72868408e+03 -5.87624658e+03 -6.15256055e+03 -6.02540039e+03 -6.05894434e+03 -6.04298584e+03 -5.95674854e+03 -6.03373096e+03 -6.07976318e+03 -6.10358984e+03 -6.10843994e+03 -6.05452930e+03 -5.95777832e+03 -6.11869434e+03 -6.49340332e+03 -6.25338477e+03 -6.00511719e+03 -6.21820557e+03 -6.33292676e+03 -6.54736084e+03 -6.46955273e+03 -6.26837842e+03 -6.44203076e+03 -6.46257422e+03 -6.21323535e+03 -6.20279932e+03 -6.61522314e+03 -6.61293555e+03 -6.43420264e+03 -6.36834326e+03 -6.18062061e+03 -6.46986182e+03 -6.90609619e+03 -6.69800928e+03 -6.55971094e+03 -6.38764062e+03 -6.37432910e+03 -6.69336963e+03 -6.93827637e+03 -6.77401709e+03 -6.45724414e+03 -6.41829883e+03 -6.62265820e+03 -6.74243066e+03 -6.93764209e+03 -6.82494434e+03 -6.61354248e+03 -6.76998486e+03 -6.74024658e+03 -6.89913721e+03 -6.85860645e+03 -6.70338281e+03 -6.80177686e+03 -6.78029736e+03 -6.79071924e+03 -6.57142920e+03 -6.68302002e+03 -7.14675635e+03 -7.00060498e+03 -6.75133691e+03 -6.63013770e+03 -6.71468750e+03 -7.09166748e+03 -7.08960938e+03 -6.89652051e+03 -6.71786914e+03 -6.69052490e+03 -6.87953564e+03 -6.86811816e+03 -6.91367188e+03 -6.73323730e+03 -6.87555664e+03 -7.20220752e+03 -6.96756885e+03 -7.02960205e+03 -7.04531152e+03 -6.87117480e+03 -6.87872168e+03 -6.88227832e+03 -6.88786621e+03 -6.87666162e+03 -6.90982178e+03 -6.87570996e+03 -7.02711768e+03 -7.06820898e+03 -6.73933594e+03 -6.61806396e+03 -6.79276367e+03 -6.98084863e+03 -7.16155469e+03 -6.96571924e+03 -6.66775098e+03 -6.94169629e+03 -7.10933154e+03 -6.94163281e+03 -6.76801904e+03 -6.75076514e+03 -6.84483984e+03 -6.89609961e+03 -6.83739258e+03 -6.63901465e+03 -6.83331201e+03 -7.16865430e+03 -6.98322266e+03 -6.85181299e+03 -6.66542676e+03 -6.64034229e+03 -6.99962744e+03 -6.98953516e+03 -6.79190186e+03 -6.61296973e+03 -6.45308496e+03 -6.61745996e+03 -6.85097852e+03 -7.02966162e+03 -6.74586523e+03 -6.42850000e+03 -6.61154443e+03 -6.70131885e+03 -6.89151025e+03 -6.74921826e+03 -6.49245508e+03 -6.67516748e+03 -6.64756250e+03 -6.48175146e+03 -6.30170850e+03 -6.53117090e+03 -6.86126270e+03 -6.66071729e+03 -6.54239697e+03 -6.35824170e+03 -6.31142480e+03 -6.66060010e+03 -6.64072510e+03 -6.43570312e+03 -6.25048633e+03 -6.17297021e+03 -6.36585059e+03 -6.34499365e+03 -6.50878223e+03 -6.52475879e+03 -6.24512695e+03 -6.12539893e+03 -6.17319141e+03 -6.43925684e+03 -6.27476416e+03 -6.09367383e+03 -6.17855078e+03 -6.17331445e+03 -6.03925781e+03 -5.94147266e+03 -6.17975342e+03 -6.14099756e+03 -5.93714648e+03 -6.15086963e+03 -6.17086572e+03 -6.00877637e+03 -5.95219287e+03 -5.91552588e+03 -5.91209375e+03 -5.74694775e+03 -5.63923730e+03 -5.91086865e+03 -5.95369678e+03 -5.63116406e+03 -5.41765430e+03 -5.66610498e+03 -5.99293604e+03 -5.85354395e+03 -5.52788770e+03 -5.39392285e+03 -5.65141748e+03 -5.71069678e+03 -5.52544678e+03 -5.53272852e+03 -5.34205859e+03 -5.16098584e+03 -5.34580273e+03 -5.54139990e+03 -5.49924707e+03 -5.24477930e+03 -5.06671729e+03 -5.30232178e+03 -5.42854004e+03 -5.23449072e+03 -5.00499121e+03 -4.91704150e+03 -5.03297412e+03 -5.04543701e+03 -5.13839990e+03 -5.09121826e+03 -4.85692480e+03 -4.88901465e+03 -4.89413184e+03 -4.94266309e+03 -4.75330762e+03 -4.62261865e+03 -4.79706348e+03 -4.76150244e+03 -4.66436523e+03 -4.51756250e+03 -4.52851660e+03 -4.75720459e+03 -4.52954688e+03 -4.31319482e+03 -4.40060498e+03 -4.45524756e+03 -4.41913135e+03 -4.33126172e+03 -4.39588379e+03 -4.39147314e+03 -4.22978076e+03 -4.06941138e+03 -4.01453638e+03 -4.20122119e+03 -4.08838452e+03 -3.92544360e+03 -4.03450562e+03 -3.99555469e+03 -3.87471484e+03 -3.80194653e+03 -3.89544775e+03 -3.83489258e+03 -3.68477368e+03 -3.72927734e+03 -3.68925928e+03 -3.67033765e+03 -3.63744824e+03 -3.55885376e+03 -3.47755054e+03 -3.34259644e+03 -3.29232520e+03 -3.42403052e+03 -3.49883447e+03 -3.27280273e+03 -3.07656689e+03 -3.16618677e+03 -3.30066772e+03 -3.23911011e+03 -3.04424292e+03 -2.88938354e+03 -2.99144727e+03 -3.03812061e+03 -2.90905005e+03 -2.90651953e+03 -2.84575195e+03 -2.70506201e+03 -2.67990918e+03 -2.73866016e+03 -2.71100806e+03 -2.55451025e+03 -2.44164502e+03 -2.50511841e+03 -2.57003784e+03 -2.45799023e+03 -2.31008130e+03 -2.22792969e+03 -2.29531543e+03 -2.32064819e+03 -2.19531079e+03 -2.09843945e+03 -2.06192554e+03 -2.04913623e+03 -1.99676111e+03 -2.00159277e+03 -1.91256995e+03 -1.80625818e+03 -1.82373718e+03 -1.78491211e+03 -1.74854529e+03 -1.66212122e+03 -1.58558569e+03 -1.60078406e+03 -1.51508972e+03 -1.44962769e+03 -1.44898730e+03 -1.39900391e+03 -1.34835339e+03 -1.29546558e+03 -1.28324231e+03 -1.24265332e+03 -1.15512488e+03 -1.07618091e+03 -1.02916016e+03 -1.04747473e+03 -1.00591284e+03 -9.19670593e+02 -7.73296753e+02 -7.96229309e+02 -1.24485718e+03 -6.45872852e+03 -1.48200391e+05 0. 0. 0. 0. 0. 2.20249702e+09 -7.46532062e+05 1.32763438e+05 -6.59330994e+02 -4.88326996e+02 -9.51549835e+01 -2.55462148e+04 3.49749632e+09 1.05506458e+10 1.05506458e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1261755264. 3885088. -4.42376031e+05 3.01446338e+03 2.53770020e+03 1.08055212e+03 7.63668518e+02 1.01706030e+03 1.01639758e+03 1.03738391e+03 1.07460559e+03 1.11946130e+03 1.16767334e+03 1.18654883e+03 1.23481006e+03 1.30708313e+03 1.34664575e+03 1.39324902e+03 1.43372058e+03 1.46611462e+03 1.54228003e+03 1.58560950e+03 1.60544409e+03 1.65941406e+03 1.68607959e+03 1.73587708e+03 1.85075195e+03 1.91204553e+03 1.89471545e+03 1.92271118e+03 1.98825183e+03 2.04424487e+03 2.06012646e+03 2.09190723e+03 2.17749194e+03 2.22413721e+03 2.30681299e+03 2.34197705e+03 2.29850049e+03 2.36716772e+03 2.49545410e+03 2.55895679e+03 2.58193140e+03 2.53599854e+03 2.55393384e+03 2.68199316e+03 2.74777490e+03 2.75346973e+03 2773. 2.81742041e+03 2.91978467e+03 2.99901001e+03 3.00271265e+03 2.95743921e+03 3.00181372e+03 3.19564331e+03 3.23753125e+03 3.11024707e+03 3.14937305e+03 3.28943115e+03 3.37054321e+03 3.44961450e+03 3.41954712e+03 3.35130566e+03 3.42711328e+03 3.55551709e+03 3.61958496e+03 3.60949048e+03 3.58958838e+03 3.70405225e+03 3.80298999e+03 3.78464844e+03 3.78782959e+03 3.80543140e+03 3.87509814e+03 3.98315161e+03 4.00387378e+03 4.06194897e+03 4.07168652e+03 4.00908008e+03 4.10023438e+03 4.19228516e+03 4.21623340e+03 4.25558545e+03 4.25617188e+03 4.30587012e+03 4.44672559e+03 4.46549268e+03 4.34888037e+03 4.40778809e+03 4.52219531e+03 4.60498682e+03 4.60922314e+03 4.57281738e+03 4.60667139e+03 4.69784229e+03 4.78764062e+03 4.78570020e+03 4.69689453e+03 4.79351465e+03 4.95440674e+03 4.98917871e+03 4.98366113e+03 4.89266309e+03 4.90830615e+03 5.08911816e+03 5.10363379e+03 5.01571143e+03 5.05483545e+03 5.12802295e+03 5.25731982e+03 5.28211084e+03 5.25328271e+03 5.28768701e+03 5.31337354e+03 5.41274707e+03 5.43928320e+03 5.36928809e+03 5.41785742e+03 5.46370605e+03 5.45370557e+03 5.53684766e+03 5.58297510e+03 5.59957227e+03 5.65751953e+03 5.62138965e+03 5.60307617e+03 5.71956592e+03 5.79667871e+03 5.75749316e+03 5.76099072e+03 5.73411230e+03 5.75434033e+03 5.88666260e+03 5.86269531e+03 5.84940576e+03 5.91711816e+03 6.08426025e+03 6.10361719e+03 5.94481689e+03 6.01035059e+03 6.08612061e+03 6.04892969e+03 6.00849561e+03 6.04382715e+03 6.11480762e+03 6.19380811e+03 6.31506885e+03 6.26961816e+03 6.17914258e+03 6.11937451e+03 6.21645801e+03 6.35554736e+03 6.37457422e+03 6.33885742e+03 6.26891748e+03 6.35599512e+03 6.49091162e+03 6.45150586e+03 6.35897656e+03 6.30285107e+03 6.42819434e+03 6.58596436e+03 6.52812939e+03 6.30467578e+03 6.39450195e+03 6.61012354e+03 6.60781689e+03 6.50958984e+03 6.52397559e+03 6.58199658e+03 6.58587695e+03 6.65525098e+03 6.61303174e+03 6.48147070e+03 6.65786719e+03 6.82149805e+03 6.70622949e+03 6.68274072e+03 6.69706689e+03 6.60532959e+03 6.72584424e+03 6.72819287e+03 6.76358789e+03 6.88640576e+03 6.63010059e+03 6.64573145e+03 6.94008594e+03 6.80113574e+03 6.63983398e+03 6.75830908e+03 6.89020801e+03 6.86836719e+03 6.85429150e+03 6.83507471e+03 6.73028174e+03 6.69467773e+03 6.94859473e+03 7.02811035e+03 6.73162158e+03 6.77177881e+03 6.98850684e+03 6.89646826e+03 6.91056641e+03 6.79253223e+03 6.76224512e+03 6.92175146e+03 6.89609277e+03 6.89512988e+03 6.91901074e+03 6.81065771e+03 6.86055908e+03 6.98187695e+03 6.90033545e+03 6.85464062e+03 6.87004053e+03 6.91613428e+03 6.89371436e+03 6.87519434e+03 6.85512744e+03 6.84199365e+03 6.82763086e+03 6.91311426e+03 6.89956299e+03 6.82362939e+03 6.90475391e+03 6.98277002e+03 6.87500977e+03 7.03932910e+03 6.86950586e+03 6.65562256e+03 6.80565381e+03 6.87672852e+03 6.84285938e+03 6.72716211e+03 6.67530078e+03 6.80611914e+03 6.93994385e+03 6.84273633e+03 6.71802393e+03 6.82714941e+03 6.90109570e+03 6.69576123e+03 6.64476416e+03 6.81533301e+03 6.76745752e+03 6.59924365e+03 6.81217090e+03 6.70699121e+03 6.59892188e+03 6.68512402e+03 6.63112109e+03 6.57767725e+03 6.60808154e+03 6.59224121e+03 6.52340820e+03 6.60270996e+03 6.67367139e+03 6.68535059e+03 6.44603027e+03 6.39560791e+03 6.57956641e+03 6.49456689e+03 6.50601221e+03 6.47238867e+03 6.37373975e+03 6.38528369e+03 6.44381006e+03 6.49654395e+03 6.34769287e+03 6.18708691e+03 6.33649268e+03 6.53101953e+03 6.26088867e+03 6.11356787e+03 6.21128174e+03 6.17227588e+03 6.24919824e+03 6.29005322e+03 6.13471289e+03 6.10166797e+03 6.14032764e+03 6.12260498e+03 6.14665674e+03 6.09098389e+03 6.08465088e+03 6.12737695e+03 5.84668604e+03 5.91006104e+03 5.97133594e+03 5.84970117e+03 5.95651465e+03 5.89548438e+03 5.77048926e+03 5.84851514e+03 5.76650391e+03 5.72931250e+03 5.89009424e+03 5.79625244e+03 5.65356201e+03 5.57935596e+03 5.52242969e+03 5.60843799e+03 5.66423975e+03 5.51844482e+03 5.47005713e+03 5.56446631e+03 5.54382910e+03 5.46114404e+03 5.35372559e+03 5.32917285e+03 5.30046094e+03 5.33511279e+03 5.35092725e+03 5.16624023e+03 5.13983740e+03 5.21543652e+03 5.20276758e+03 5162. 5.12998047e+03 5.03662256e+03 4.96874658e+03 5.10857178e+03 5.11121045e+03 4.89069434e+03 4.78793213e+03 4.78525293e+03 4.81947559e+03 4.79471484e+03 4.70798340e+03 4.73183740e+03 4.71619775e+03 4.66443945e+03 4.66638037e+03 4.58687988e+03 4.49548535e+03 4.52415918e+03 4.54895703e+03 4.42940186e+03 4.30894482e+03 4.34357324e+03 4.31304932e+03 4.28371875e+03 4.30259570e+03 4.21336035e+03 4.12362549e+03 4.12914258e+03 4.18693701e+03 4.08131006e+03 3.95833838e+03 3.96386499e+03 3.94463403e+03 3.89491650e+03 3.83966577e+03 3.76096216e+03 3.75218604e+03 3.74820581e+03 3.73901099e+03 3.72478784e+03 3.60551270e+03 3.57099487e+03 3.52726074e+03 3.46370312e+03 3.42794775e+03 3.37324219e+03 3.38311475e+03 3.34320288e+03 3.26551953e+03 3.19817529e+03 3.16461011e+03 3.18811646e+03 3.17383545e+03 3.12595459e+03 3.03160547e+03 2.96550562e+03 2.92809082e+03 2.85112158e+03 2.82781055e+03 2.82048779e+03 2.76689868e+03 2.71612793e+03 2.63237793e+03 2.58125708e+03 2.60046313e+03 2.58725464e+03 2.54572241e+03 2.44422461e+03 2.35165747e+03 2.34521997e+03 2.31902930e+03 2.25811450e+03 2.23260547e+03 2.20362622e+03 2.11620654e+03 2.05163013e+03 2.01415210e+03 1.97246948e+03 1.98789624e+03 1.95150415e+03 1.84054517e+03 1.81043396e+03 1.75247815e+03 1.66614722e+03 1.67605823e+03 1.65299133e+03 1.56226270e+03 1.51477502e+03 1.46322327e+03 1.39965625e+03 1.39211865e+03 1.37976746e+03 1.29776904e+03 1.23140869e+03 1.19332605e+03 1.14787036e+03 1.10814624e+03 1.05553503e+03 1.00564734e+03 9.56876770e+02 9.08493225e+02 8.64069031e+02 8.17242065e+02 7.60908386e+02 7.21423340e+02 6.86523193e+02 6.27070374e+02 5.69068298e+02 5.19208435e+02 4.79477692e+02 4.37063965e+02 3.90104797e+02 3.34808563e+02 2.78661804e+02 2.33426575e+02 1.89401688e+02 1.43612457e+02 9.34110107e+01 4.59417496e+01 -5.28638363e-01 -4.75260429e+01 -9.71285095e+01 -1.48638351e+02 -1.97346054e+02 -2.40787552e+02 -2.90111938e+02 -3.32522675e+02 -3.67688782e+02 -4.33949158e+02 -5.03169769e+02 -5.30898254e+02 -5.66728577e+02 -6.18400757e+02 -6.70954163e+02 -7.31509460e+02 -7.81976257e+02 -8.21228699e+02 -8.48830811e+02 -8.99296997e+02 -9.63564758e+02 -1.00816168e+03 -1.06895239e+03 -1.12017310e+03 -1.14579578e+03 -1.18458459e+03 -1.25315784e+03 -1.29917712e+03 -1.33489697e+03 -1.40167139e+03 -1.45546851e+03 -1.47639465e+03 -1.49876550e+03 -1.55059900e+03 -1.62630151e+03 -1.70197632e+03 -1.73985522e+03 -1.74300867e+03 -1.77724451e+03 -1.83923743e+03 -1.90566858e+03 -1.98267346e+03 -2.01349207e+03 -2.00265662e+03 -2.08833862e+03 -2.16072070e+03 -2.16516162e+03 -2.27201562e+03 -2.30508862e+03 -2.28552393e+03 -2.35555811e+03 -2.36046069e+03 -2.39655859e+03 -2.54329785e+03 -2.58944214e+03 -2.58450342e+03 -2.65094238e+03 -2.66828931e+03 -2.64307495e+03 -2.71443091e+03 -2.82957227e+03 -2.86308911e+03 -2.90591064e+03 -2.92075879e+03 -2.94894360e+03 -3.02887476e+03 -3.09478589e+03 -3.22534131e+03 -3.19899707e+03 -3.09795557e+03 -3.17772583e+03 -3.25803784e+03 -3.34268604e+03 -3.43826611e+03 -3.40832397e+03 -3.36373340e+03 -3.47911182e+03 -3.57479565e+03 -3.58397412e+03 -3.63903198e+03 -3.65610815e+03 -3.64294946e+03 -3.76163037e+03 -3.79395288e+03 -3.76550000e+03 -3.94817505e+03 -3.99312451e+03 -3.92724756e+03 -3.95448291e+03 -3.89073096e+03 -3.95342334e+03 -4.11953174e+03 -4.28107227e+03 -4.27511865e+03 -4.07674097e+03 -4.13370312e+03 -4.33771875e+03 -4.35028857e+03 -4.34532178e+03 -4.39205322e+03 -4.39298193e+03 -4.46550146e+03 -4.53729395e+03 -4.58056641e+03 -4.57758252e+03 -4.62766992e+03 -4.71922949e+03 -4.68441895e+03 -4.66066455e+03 -4.71502051e+03 -4.76740186e+03 -4.85386572e+03 -4.98413770e+03 -4.91298047e+03 -4.82147412e+03 -4.93310840e+03 -5.02470947e+03 -5.16307471e+03 -5.15639551e+03 -4.99201904e+03 -5.08306445e+03 -5.16300391e+03 -5.23504492e+03 -5.36134277e+03 -5.29178174e+03 -5.25458398e+03 -5.28462305e+03 -5.25755469e+03 -5.27863037e+03 -5.45747559e+03 -5.58665674e+03 -5.48297314e+03 -5.43207520e+03 -5.41109521e+03 -5.47510498e+03 -5.68937305e+03 -5.71484424e+03 -5.68246289e+03 -5.64540869e+03 -5.54376904e+03 -5.63343701e+03 -5.74516113e+03 -5.88487939e+03 -5.94006201e+03 -5.73319336e+03 -5.73521045e+03 -5.86096289e+03 -5.92508643e+03 -5.95297363e+03 -6.01632275e+03 -6.05675586e+03 -5.94361768e+03 -5.95313867e+03 -6.00408496e+03 -6.04766406e+03 -6.12454395e+03 -6.16656836e+03 -6.16613965e+03 -6.13170898e+03 -6.12413184e+03 -6.17907227e+03 -6.34763574e+03 -6.31038672e+03 -6.18193945e+03 -6.20202832e+03 -6.24833447e+03 -6.24471533e+03 -6.51949756e+03 -6.47659326e+03 -6.25792285e+03 -6.41721631e+03 -6.34307764e+03 -6.44596631e+03 -6.66747119e+03 -6.48884326e+03 -6.43992822e+03 -6.47361816e+03 -6.61548438e+03 -6.67438184e+03 -6.76278369e+03 -6.54875879e+03 -8.93071680e+03 -9.48420215e+03 -1.58292822e+04 -2.94189531e+04 3.28185375e+06 128801400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -15632281. 3.74871525e+06 -2.66100762e+04 -1.81376094e+04 -9.50637500e+03 -7.41654053e+03 -9.41682520e+03 -7.87305078e+03 -6.91479492e+03 -6.90980713e+03 -7.15135400e+03 -7.07995068e+03 -6.86555518e+03 -6.70073584e+03 -6.76783350e+03 -6.96062695e+03 -7.04732275e+03 -6.96105859e+03 -6.78345947e+03 -6.75242383e+03 -6.75902979e+03 -6.91393701e+03 -6.89783301e+03 -6.58592578e+03 -6.69535791e+03 -6.88375439e+03 -6.83823877e+03 -6.68134814e+03 -6.56534180e+03 -6.74034131e+03 -6.99101807e+03 -6.99975684e+03 -6.57629053e+03 -6.30495068e+03 -6.52175000e+03 -6.79844141e+03 -6.93795068e+03 -6.78091113e+03 -6.48593896e+03 -6.54056299e+03 -6.65053027e+03 -6.76706299e+03 -6.69893848e+03 -6.33149072e+03 -6.42576807e+03 -6.74610107e+03 -6.64607129e+03 -6.42620361e+03 -6.47916748e+03 -6.48537256e+03 -6.57518848e+03 -6.54735889e+03 -6.27926318e+03 -6.16967139e+03 -6.45923682e+03 -6.59137939e+03 -6.51467090e+03 -6.23741064e+03 -6.06421338e+03 -6.33332227e+03 -6.53837402e+03 -6.37412891e+03 -6.15772754e+03 -5.92808008e+03 -6.01282617e+03 -6.30346436e+03 -6.35858057e+03 -6.25807227e+03 -6.13026172e+03 -6.10612939e+03 -5.99552832e+03 -6.00042676e+03 -6.05955420e+03 -5.84778564e+03 -5.91600391e+03 -6.12653223e+03 -6.00108301e+03 -5.69811426e+03 -5.63439209e+03 -5.89971777e+03 -6.05577783e+03 -5.95320703e+03 -5.72806934e+03 -5.54558057e+03 -5.55185840e+03 -5.67384229e+03 -5.88481055e+03 -5.77530713e+03 -5.43469043e+03 -5.47120459e+03 -5.54208740e+03 -5.55695508e+03 -5.63204053e+03 -5.41050635e+03 -5.35647217e+03 -5.46993896e+03 -5.43203809e+03 -5.32261816e+03 -5.21456396e+03 -5.25557031e+03 -5.33547217e+03 -5.28945264e+03 -5.12455615e+03 -4.99512598e+03 -5.11288232e+03 -5.25031299e+03 -5.17253760e+03 -5.03149023e+03 -4.84910449e+03 -4.92635254e+03 -5.02970508e+03 -4.99570264e+03 -4.86237402e+03 -4.63682617e+03 -4.64280225e+03 -4.83482373e+03 -4.91362793e+03 -4.75833594e+03 -4.51545312e+03 -4.53163281e+03 -4.63777979e+03 -4.57648975e+03 -4.44476807e+03 -4.35197803e+03 -4.47683691e+03 -4.51672559e+03 -4.35613037e+03 -4.26100879e+03 -4.16056006e+03 -4.25238525e+03 -4.39174316e+03 -4.26319287e+03 -4.09791455e+03 -3.99871289e+03 -3.99033301e+03 -4.02006714e+03 -4.06125146e+03 -3.99059985e+03 -3.77826880e+03 -3.75322632e+03 -3.87743628e+03 -3.88288770e+03 -3.75466382e+03 -3.62942334e+03 -3.62802930e+03 -3.67304028e+03 -3.64107593e+03 -3.53635889e+03 -3.37094556e+03 -3.37581299e+03 -3.47228296e+03 -3.42304932e+03 -3.32559204e+03 -3.21266943e+03 -3.17709473e+03 -3.22085205e+03 -3.25731006e+03 -3.17558447e+03 -2.99974438e+03 -2.97441895e+03 -2.99119946e+03 -2.96036328e+03 -2.91370923e+03 -2.82181885e+03 -2.81369995e+03 -2.77286230e+03 -2.69864624e+03 -2.64716235e+03 -2.58696875e+03 -2.61511401e+03 -2.60899341e+03 -2.52217358e+03 -2.40743091e+03 -2.32350244e+03 -2.36211060e+03 -2.40334009e+03 -2.33164575e+03 -2.22631860e+03 -2.12000269e+03 -2.04815771e+03 -2.07586841e+03 -2.13041626e+03 -2.02458044e+03 -1.87872632e+03 -1.86037671e+03 -1.87805896e+03 -1.84805103e+03 -1.79394031e+03 -1.70835339e+03 -1.66505078e+03 -1.64589917e+03 -1.56916980e+03 -1.50302917e+03 -1.46737622e+03 -1.44387000e+03 -1.40099377e+03 -1.34020776e+03 -1.28127698e+03 -1.22400525e+03 -1.19782422e+03 -1.17653479e+03 -1.12678052e+03 -1.04064587e+03 -9.72938660e+02 -9.67369690e+02 -9.41874939e+02 -8.81250366e+02 -8.18603333e+02 -7.46456055e+02 -7.02519836e+02 -6.87049255e+02 -6.52587158e+02 -5.90956360e+02 -5.15642639e+02 -4.64513855e+02 -4.36404846e+02 -3.97808258e+02 -3.45991760e+02 -2.91031342e+02 -2.42732620e+02 -1.94346405e+02 -1.42016388e+02 -9.02218628e+01 -4.08647652e+01 6.89427710e+00 5.37111282e+01 1.02579018e+02 1.46004059e+02 1.83970398e+02 2.37043900e+02 2.92211151e+02 3.39572052e+02 3.89787659e+02 4.33216034e+02 4.93660919e+02 5.41105286e+02 5.60182312e+02 5.99503662e+02 6.62145874e+02 7.41844116e+02 8.14542358e+02 8.42931396e+02 8.41494873e+02 8.63910461e+02 9.37672180e+02 1.03621838e+03 1.11232825e+03 1.13638025e+03 1.12184448e+03 1.15992847e+03 1.28269263e+03 1.33956641e+03 1.31326575e+03 1.35181860e+03 1.42579333e+03 1.47693604e+03 1.57439453e+03 1.58370825e+03 1.57157312e+03 1.66418506e+03 1.67457849e+03 1.75818860e+03 1.85984314e+03 1.80827625e+03 1.89567029e+03 2.00382800e+03 1.99904968e+03 2.04441943e+03 2.08158374e+03 2.13323145e+03 2.19465161e+03 2.23323022e+03 2.21561938e+03 2.25462158e+03 2.40490015e+03 2.52098315e+03 2.51758130e+03 2.44538037e+03 2.43138354e+03 2.51894531e+03 2.68500684e+03 2.81161279e+03 2.80270581e+03 2.68713428e+03 2.73383545e+03 2.88832104e+03 2.91445166e+03 2.92072192e+03 2.95859058e+03 3.01271631e+03 3.06058350e+03 3.20530908e+03 3.17497070e+03 3.11505029e+03 3.22920142e+03 3.19896362e+03 3.33252881e+03 3.44550317e+03 3.40922510e+03 3.55074951e+03 3.48816016e+03 3.42273218e+03 3.56986475e+03 3.51937524e+03 3.63370776e+03 3.92894189e+03 3.76827734e+03 3.58894067e+03 3.71028809e+03 3.92558203e+03 4.11764258e+03 4.06257251e+03 3.87729395e+03 3.80118628e+03 3.93469189e+03 4.18667920e+03 4.36368164e+03 4.29799023e+03 4.11031689e+03 4.11502783e+03 4.30491797e+03 4.40909375e+03 4.34499756e+03 4.31231104e+03 4.42104297e+03 4.47770020e+03 4.62707373e+03 4.66736963e+03 4.48669189e+03 4.51603418e+03 4.60541553e+03 4.66585498e+03 4.76036523e+03 4.77290918e+03 4.90865088e+03 4.85625146e+03 4.72756787e+03 4.85932373e+03 4.78764404e+03 4.95886865e+03 5.30510107e+03 5.06212598e+03 4.77363281e+03 4.91785254e+03 5.20802832e+03 5.40039502e+03 5.41704297e+03 5.15407471e+03 4.98010498e+03 5.10033447e+03 5.40648730e+03 5.66933350e+03 5.53825049e+03 5.25422168e+03 5.24709863e+03 5.42882812e+03 5.53189746e+03 5.72391650e+03 5.71662695e+03 5.43774463e+03 5.42783545e+03 5.74729297e+03 5.81380078e+03 5.63727832e+03 5.64398242e+03 5.69227783e+03 5.67500537e+03 5.94656738e+03 6.02772998e+03 5.74995312e+03 5.73440771e+03 5.82335254e+03 5.90619678e+03 5.97228613e+03 5.93481934e+03 6.10813330e+03 6.21914502e+03 6.02909570e+03 5.93035205e+03 5.82339014e+03 6.08532324e+03 6.45595996e+03 6.33736279e+03 6.04134668e+03 5.90568896e+03 6.15846582e+03 6.51826562e+03 6.33708691e+03 6.00553027e+03 6.13867871e+03 6.30251514e+03 6.52181152e+03 6.70413379e+03 6.58540137e+03 6.21761035e+03 6.12403467e+03 6.34057812e+03 6.57685400e+03 6.58808350e+03 6.51398193e+03 6.50469043e+03 6.48673877e+03 6.63435156e+03 6.61098047e+03 6.42650928e+03 6.38308643e+03 6.43216748e+03 6.75583057e+03 6.81428223e+03 6.63480469e+03 6.65989404e+03 6.70885156e+03 6.80566309e+03 6.70116943e+03 6.36219092e+03 6.67527490e+03 7.06419189e+03 6.87766992e+03 6.53407324e+03 6.56548975e+03 6.92545947e+03 6.96678369e+03 6.84216943e+03 6.80555420e+03 6.62902148e+03 6.64322852e+03 6.98944043e+03 7.00515527e+03 6.69944385e+03 6.57072998e+03 6.60517285e+03 6.91728564e+03 7.19693066e+03 6.88048193e+03 6.68300195e+03 6.83227295e+03 6.87688232e+03 7.08737061e+03 7.05171582e+03 6.61074805e+03 6.72941406e+03 6.94830225e+03 6.90371924e+03 6.92031982e+03 6.85690186e+03 7.02578467e+03 7.00021484e+03 6.79031055e+03 6.81620996e+03 6.68658594e+03 6.93014453e+03 7.24873828e+03 7.05553369e+03 6.75715723e+03 6.66570557e+03 7.01108301e+03 7.24745215e+03 7.60682959e+03 8.03729199e+03 7.15133301e+03 8.56967578e+03 1.32397559e+04 1.19849859e+05 53426952. 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. 0. 0. 0. 0. 0. 0. 0. -48947436. 6.41627950e+06 1.56498862e+06 4.90040650e+06 1.92910371e+04 1.53019355e+04 8.66125488e+03 8.46806445e+03 6.90060010e+03 6.72663428e+03 6.41188330e+03 6.51815625e+03 6.39643652e+03 6.14645996e+03 6.27146777e+03 6.24667383e+03 6.41727246e+03 6.43754883e+03 5.85914014e+03 5.75315869e+03 5.86863428e+03 5.99127588e+03 5.88471436e+03 5.75664502e+03 6.15458105e+03 5.97217969e+03 5.78709473e+03 6.02981104e+03 5.98255713e+03 5.75518018e+03 5.92323730e+03 6.09380322e+03 5.90373975e+03 5.78961182e+03 5.75099023e+03 5.69738281e+03 5.62289502e+03 5.61119531e+03 5.73767969e+03 5.71433154e+03 5.59654492e+03 5.55311963e+03 5.52675488e+03 5.50255713e+03 5.45745410e+03 5.41869727e+03 5.40454590e+03 5.22205518e+03 5.16840625e+03 5.28549756e+03 5.25634521e+03 5.41289209e+03 5.39763818e+03 5.17917334e+03 4.99698047e+03 4.95307910e+03 5.23962207e+03 5.25858838e+03 5.02268701e+03 4.88744336e+03 4.87178613e+03 4.90190479e+03 4.84285693e+03 4.97621680e+03 4.94194873e+03 4.62985156e+03 4.54452490e+03 4.75350146e+03 4.90382910e+03 4.74132324e+03 4.59328711e+03 4.58504688e+03 4.53757617e+03 4.44656543e+03 4.43962842e+03 4.41406250e+03 4.34931641e+03 4.31693018e+03 4.27473047e+03 4.29232227e+03 4.23691748e+03 4.29480518e+03 4.24164062e+03 4.07079590e+03 4.09478174e+03 4.06173145e+03 4.03928711e+03 4.01593384e+03 3.94826782e+03 3.90425195e+03 3.77638525e+03 3.64450293e+03 3.78371045e+03 3.79741553e+03 3.56439746e+03 3.55216479e+03 3.71512695e+03 3.77798340e+03 3.61903687e+03 3.47514868e+03 3.42088062e+03 3.38069141e+03 3.31872705e+03 3.26392456e+03 3.28255591e+03 3.22932349e+03 3.26270679e+03 3.20013501e+03 3.06779761e+03 3.07665820e+03 2.95141577e+03 2.91994141e+03 3.03417700e+03 2.96518115e+03 2.85511865e+03 2.74490381e+03 2.65718701e+03 2.76808521e+03 2.77500244e+03 2.63203638e+03 2.51516724e+03 2.48028271e+03 2.49792310e+03 2.43857227e+03 2.46747900e+03 2.44070776e+03 2.30869238e+03 2.21787622e+03 2.17482373e+03 2.21834033e+03 2.17679419e+03 2.07825171e+03 2.00958276e+03 1.96714636e+03 1.94150342e+03 1.84556104e+03 1.81254614e+03 1.87226379e+03 1.81070752e+03 1.71605762e+03 1.62627527e+03 1.56804712e+03 1.61651465e+03 1.57741394e+03 1.48356445e+03 1.40077954e+03 1.34451758e+03 1.33566858e+03 1.29109277e+03 1.24262939e+03 1.16304517e+03 1.14040369e+03 1.14945081e+03 1.06947314e+03 1.01205444e+03 9.69723267e+02 9.14067200e+02 8.52904846e+02 8.03597534e+02 7.65299133e+02 7.15807800e+02 6.63194824e+02 5.97099182e+02 5.62021667e+02 5.48697876e+02 4.80702484e+02 4.18255829e+02 3.82216156e+02 3.33876190e+02 2.94861053e+02 2.40975937e+02 1.84768860e+02 1.46118912e+02 9.76220398e+01 4.71730652e+01 1.36062384e+00 -4.44985046e+01 -9.23673325e+01 -1.42525772e+02 -1.92947144e+02 -2.34944275e+02 -2.89503174e+02 -3.56835266e+02 -3.96818634e+02 -4.31436401e+02 -4.67397858e+02 -5.20148560e+02 -6.01268677e+02 -6.46402100e+02 -6.75995728e+02 -7.05237793e+02 -7.48034729e+02 -8.19254578e+02 -8.65624451e+02 -9.33838684e+02 -9.64538208e+02 -9.80041504e+02 -1.05895813e+03 -1.10809436e+03 -1.17927881e+03 -1.21933142e+03 -1.23205530e+03 -1.27957373e+03 -1.32648035e+03 -1.39475049e+03 -1.40355103e+03 -1.46451575e+03 -1.59594055e+03 -1.61512146e+03 -1.62393127e+03 -1.62890857e+03 -1.66333301e+03 -1.80671265e+03 -1.86281921e+03 -1.85780554e+03 -1.85168726e+03 -1.89288525e+03 -2.00428625e+03 -2.05333643e+03 -2.14301001e+03 -2.16297852e+03 -2.16139062e+03 -2.18254858e+03 -2.21364893e+03 -2.38230249e+03 -2.41203174e+03 -2.38038696e+03 -2.41642261e+03 -2.46319458e+03 -2.58420825e+03 -2.63509253e+03 -2.57111328e+03 -2.60304248e+03 -2.78478687e+03 -2.83062280e+03 -2.73700537e+03 -2.76711230e+03 -2.96457324e+03 -3.02327563e+03 -2.96364526e+03 -2.94090869e+03 -2.98444336e+03 -3.20458691e+03 -3.21841748e+03 -3.16499048e+03 -3.22064502e+03 -3.25326660e+03 -3.30608423e+03 -3.34452002e+03 -3.38534424e+03 -3.34064038e+03 -3.46943237e+03 -3.71019263e+03 -3.64026660e+03 -3.62994800e+03 -3.70134863e+03 -3.71300146e+03 -3.75091016e+03 -3.78247559e+03 -3.81637573e+03 -3.76158057e+03 -3.74055029e+03 -3.86831665e+03 -4.01010156e+03 -4.17899072e+03 -4.06876611e+03 -3.96130225e+03 -4.10580762e+03 -4.19510400e+03 -4.36059131e+03 -4.34019629e+03 -4.25045947e+03 -4.25569873e+03 -4.26452930e+03 -4.39700635e+03 -4.43634814e+03 -4.56349121e+03 -4.59320166e+03 -4.52133008e+03 -4.50721143e+03 -4.41492090e+03 -4.63541406e+03 -4.93875342e+03 -4.87765332e+03 -4.76475977e+03 -4.66664502e+03 -4.64910449e+03 -4.92363184e+03 -5.08751807e+03 -4.97808252e+03 -4.83092725e+03 -4.86621582e+03 -5.02977148e+03 -5.05415918e+03 -5.22974902e+03 -5.23895703e+03 -5.11090283e+03 -5.17248877e+03 -5.18987451e+03 -5.31858545e+03 -5.37456738e+03 -5.18058008e+03 -5.20276807e+03 -5.53359668e+03 -5.45187549e+03 -5.20002539e+03 -5.41184961e+03 -5.72960840e+03 -5.66299609e+03 -5.54435449e+03 -5.43760449e+03 -5.47874121e+03 -5.82972803e+03 -5.82033984e+03 -5.67993066e+03 -5.57606055e+03 -5.57130225e+03 -5.77102734e+03 -5.79529102e+03 -5.79906738e+03 -5.70735938e+03 -5.86140088e+03 -6.13743799e+03 -5.98994727e+03 -6.02149414e+03 -6.02464062e+03 -5.93059912e+03 -6.01420020e+03 -6.04452930e+03 -6.09085547e+03 -6.07745459e+03 -6.04415527e+03 -5.94606689e+03 -6.10868750e+03 -6.48695215e+03 -6.21558350e+03 -5.95303369e+03 -6.16473193e+03 -6.33971436e+03 -6.53827051e+03 -6.41682129e+03 -6.24334766e+03 -6.41948633e+03 -6.45139453e+03 -6.20464600e+03 -6.15486133e+03 -6.54541895e+03 -6.59395264e+03 -6.42434619e+03 -6.32931348e+03 -6.15594434e+03 -6.43372754e+03 -6.86962451e+03 -6.69620068e+03 -6.53507373e+03 -6.37457959e+03 -6.33054590e+03 -6.68945947e+03 -6.92591846e+03 -6.74513818e+03 -6.43831934e+03 -6.42490479e+03 -6.61212354e+03 -6.72952148e+03 -6.88585205e+03 -6.77989355e+03 -6.59758936e+03 -6.73392773e+03 -6.71689893e+03 -6.83985254e+03 -6.79814648e+03 -6.70311084e+03 -6.76800732e+03 -6.75430273e+03 -6.73309131e+03 -6.55522021e+03 -6.70084033e+03 -7.12591602e+03 -6.97781934e+03 -6.73275049e+03 -6.61138623e+03 -6.70501709e+03 -7.10074951e+03 -7.06687842e+03 -6.87600244e+03 -6.70070947e+03 -6.67958838e+03 -6.84351172e+03 -6.86480273e+03 -6.86342529e+03 -6.70518799e+03 -6.84227148e+03 -7.15340723e+03 -6.92889160e+03 -6.98829053e+03 -7.02172119e+03 -6.85325830e+03 -6.85316162e+03 -6.85130908e+03 -6.82494922e+03 -6.83114160e+03 -6.85348340e+03 -6.84643652e+03 -7.01664160e+03 -7.04815283e+03 -6.69203223e+03 -6.61891943e+03 -6.80828174e+03 -6.98275439e+03 -7.16652002e+03 -6.92446143e+03 -6.63072559e+03 -6.93992139e+03 -7.08886719e+03 -6.90390771e+03 -6.73929395e+03 -6.70970801e+03 -6.85708789e+03 -6.87459717e+03 -6.80075781e+03 -6.61046045e+03 -6.80955957e+03 -7.13632715e+03 -6.97265430e+03 -6.83316504e+03 -6.67276318e+03 -6.57701074e+03 -6.96663135e+03 -6.93111523e+03 -6.75445264e+03 -6.60471338e+03 -6.40298389e+03 -6.58070020e+03 -6.84020996e+03 -7.03294873e+03 -6.72353760e+03 -6.41168896e+03 -6.58558105e+03 -6.68460986e+03 -6.86178613e+03 -6.71457959e+03 -6.48975342e+03 -6.66162939e+03 -6.62623047e+03 -6.48321436e+03 -6.29062939e+03 -6.48930371e+03 -6.82745654e+03 -6.65411084e+03 -6.54957227e+03 -6.35018750e+03 -6.30992871e+03 -6.62203857e+03 -6.62758447e+03 -6.39781982e+03 -6.22115576e+03 -6.16907715e+03 -6.36141650e+03 -6.33242529e+03 -6.49452832e+03 -6.47281738e+03 -6.22791650e+03 -6.09879980e+03 -6.15678857e+03 -6.40599219e+03 -6.24207617e+03 -6.08847168e+03 -6.15808154e+03 -6.16031445e+03 -6.01204541e+03 -5.91630127e+03 -6.14535547e+03 -6.10226514e+03 -5.90535107e+03 -6.12829443e+03 -6.14669873e+03 -6.00095752e+03 -5.95221826e+03 -5.90367334e+03 -5.88136523e+03 -5.70543213e+03 -5.62083154e+03 -5.88330957e+03 -5.95297998e+03 -5.61179492e+03 -5.41334375e+03 -5.64176123e+03 -5.94607861e+03 -5.83606592e+03 -5.51952100e+03 -5.37701270e+03 -5.62481934e+03 -5.69231934e+03 -5.49919336e+03 -5.51849707e+03 -5.33048145e+03 -5.14964844e+03 -5.32625635e+03 -5.53088965e+03 -5.48993652e+03 -5.23838281e+03 -5.04941260e+03 -5.27666846e+03 -5.41394336e+03 -5.22262793e+03 -4.98934375e+03 -4.88850732e+03 -5.01394922e+03 -5.01347070e+03 -5.10439844e+03 -5.06012549e+03 -4.83938867e+03 -4.87968799e+03 -4.87983496e+03 -4.91946289e+03 -4.74344043e+03 -4.60566992e+03 -4.78806641e+03 -4.76182666e+03 -4.66230078e+03 -4.50977148e+03 -4.50940039e+03 -4.73577979e+03 -4.51996924e+03 -4.29129297e+03 -4.36904541e+03 -4.43272705e+03 -4.40463867e+03 -4.31558984e+03 -4.37517480e+03 -4.37098047e+03 -4.20318213e+03 -4.05023901e+03 -4.00541968e+03 -4.18333740e+03 -4.07179785e+03 -3.91646704e+03 -4.01760791e+03 -3.97912549e+03 -3.86790137e+03 -3.78884741e+03 -3.87565869e+03 -3.81054834e+03 -3.66446899e+03 -3.72079785e+03 -3.68001538e+03 -3.65534888e+03 -3.62204370e+03 -3.53824731e+03 -3.47015381e+03 -3.33441821e+03 -3.27215674e+03 -3.39858569e+03 -3.48889209e+03 -3.26796899e+03 -3.06326978e+03 -3.14941577e+03 -3.29410962e+03 -3.22690576e+03 -3.02822290e+03 -2.88248999e+03 -2.97931396e+03 -3.02703003e+03 -2.88986133e+03 -2.89549756e+03 -2.83779199e+03 -2.68407300e+03 -2.66546313e+03 -2.72452979e+03 -2.69926758e+03 -2.54544434e+03 -2.43081494e+03 -2.49448413e+03 -2.55667969e+03 -2.44743384e+03 -2.30215601e+03 -2.21878149e+03 -2.27926636e+03 -2.30634155e+03 -2.18332617e+03 -2.08335254e+03 -2.04956592e+03 -2.04343335e+03 -1.99011145e+03 -1.99545459e+03 -1.90724719e+03 -1.79838599e+03 -1.81865198e+03 -1.77777625e+03 -1.73981738e+03 -1.65537280e+03 -1.57887183e+03 -1.59922217e+03 -1.51707031e+03 -1.44673218e+03 -1.44118726e+03 -1.38959412e+03 -1.34245984e+03 -1.29180664e+03 -1.28192542e+03 -1.24162378e+03 -1.14884070e+03 -1.06803711e+03 -1.02474768e+03 -1.04171594e+03 -9.92979065e+02 -8.98501770e+02 -7.73571777e+02 -8.26482300e+02 -1.33441602e+03 -7.05908447e+03 -2.66911188e+05 0. 0. 0. 0. 0. 2.20249702e+09 -7.46532062e+05 1.32763438e+05 2.37324927e+03 2.97410205e+03 -3.87646523e+04 -2.55462148e+04 3.49749632e+09 1.05506458e+10 1.05506458e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 199508688. 4.52900188e+05 2.67558719e+05 1.59048169e+03 1.63518970e+03 1.01414044e+03 7.54132935e+02 9.87938721e+02 9.93640137e+02 1.02003461e+03 1.06499170e+03 1.11753979e+03 1.16847485e+03 1.18598547e+03 1.23143274e+03 1.30595276e+03 1.34141577e+03 1.37989294e+03 1.42061816e+03 1.45669165e+03 1.54027417e+03 1.58877686e+03 1.61081226e+03 1.66769421e+03 1.68971069e+03 1.73408630e+03 1.84518933e+03 1.90826331e+03 1.88510095e+03 1.91505273e+03 1.99314587e+03 2.04764709e+03 2.06059155e+03 2.09171948e+03 2.16576343e+03 2.21380200e+03 2.30337012e+03 2.34006567e+03 2.29639722e+03 2.36551245e+03 2.50293848e+03 2.56340210e+03 2.57503076e+03 2.52437256e+03 2.54599487e+03 2.68230298e+03 2.75387061e+03 2.75100122e+03 2.77077441e+03 2.81644092e+03 2.91458984e+03 2.99203589e+03 2.99511035e+03 2.94875537e+03 2.98766406e+03 3.19296338e+03 3.24910425e+03 3.11956079e+03 3.15016260e+03 3.27868726e+03 3.36728223e+03 3.44598633e+03 3.42293140e+03 3.34631934e+03 3.42393555e+03 3.55813794e+03 3.61138965e+03 3.60447925e+03 3.58966455e+03 3.68899316e+03 3.77838916e+03 3.78793677e+03 3.78712842e+03 3.78957129e+03 3.86469580e+03 3.97854053e+03 3.99598291e+03 4.05226709e+03 4.06504761e+03 3.99650146e+03 4.10410059e+03 4.18794092e+03 4.21442676e+03 4.25515283e+03 4.24589893e+03 4.28919238e+03 4.44514111e+03 4.45480420e+03 4.33235498e+03 4.38833203e+03 4.51590869e+03 4.60423438e+03 4.60381396e+03 4.54869629e+03 4.58652979e+03 4.68349902e+03 4.76904395e+03 4.77429590e+03 4.68925586e+03 4.78656250e+03 4.96262598e+03 4.96920557e+03 4.96209229e+03 4.86605420e+03 4.87876514e+03 5.09759375e+03 5.08695215e+03 5.02513281e+03 5.05029297e+03 5.11446240e+03 5.24652881e+03 5.26803418e+03 5.22495947e+03 5.25474121e+03 5.29055566e+03 5.40069092e+03 5.43758789e+03 5.36747705e+03 5.40559668e+03 5.44053027e+03 5.43289404e+03 5.53031104e+03 5.57474609e+03 5.58087451e+03 5.62389746e+03 5.60423877e+03 5.58892383e+03 5.70272510e+03 5.79813818e+03 5.74070996e+03 5.73718359e+03 5.70152539e+03 5.75105908e+03 5.87639014e+03 5.85162061e+03 5.84881592e+03 5.88877783e+03 6.03875732e+03 6.07873047e+03 5.95792822e+03 6.01168066e+03 6.05918945e+03 6.03890137e+03 5.99035840e+03 6.02175635e+03 6.09328906e+03 6.19352197e+03 6.27657764e+03 6.28105469e+03 6.16442871e+03 6.09283936e+03 6.24428369e+03 6.32422314e+03 6.32075879e+03 6.33324316e+03 6.26769092e+03 6.35305615e+03 6.46304053e+03 6.44082129e+03 6.34122656e+03 6.26171777e+03 6.42876270e+03 6.59723145e+03 6.54407617e+03 6.30760010e+03 6.37859229e+03 6.60242236e+03 6.60904590e+03 6.50053320e+03 6.53507080e+03 6.57410742e+03 6.53872314e+03 6.63930225e+03 6.58377539e+03 6.45613574e+03 6.63601465e+03 6.77882373e+03 6.67971191e+03 6.67941846e+03 6.70230566e+03 6.58938184e+03 6.66330273e+03 6.72636475e+03 6.78718213e+03 6.88376562e+03 6.59838379e+03 6.63800293e+03 6.90677148e+03 6.79284473e+03 6.62059180e+03 6.74015479e+03 6.87935205e+03 6.84182568e+03 6.84968115e+03 6.82995166e+03 6.74780469e+03 6.72485938e+03 6.93656934e+03 7.03711816e+03 6.75655859e+03 6.78592920e+03 7.00504102e+03 6.90209131e+03 6.86034619e+03 6.79717334e+03 6.71376221e+03 6.90913721e+03 6.87111523e+03 6.84621387e+03 6.90463477e+03 6.77918164e+03 6.82746045e+03 6.97830322e+03 6.83366650e+03 6.82504150e+03 6.89357764e+03 6.88567871e+03 6.84624756e+03 6.89239307e+03 6.87514160e+03 6.82340771e+03 6.82818115e+03 6.92354785e+03 6.89181592e+03 6.78699854e+03 6.89051416e+03 6.96795020e+03 6.86437646e+03 6.97367920e+03 6.84653418e+03 6.67640576e+03 6.82417627e+03 6.83264355e+03 6.83181201e+03 6.73524365e+03 6.68113184e+03 6.83772363e+03 6.95971045e+03 6.81921680e+03 6.70365918e+03 6.78626025e+03 6.85015283e+03 6.69772559e+03 6.62006641e+03 6.82339502e+03 6.77318213e+03 6.58596289e+03 6.76544873e+03 6.69104492e+03 6.63440869e+03 6.68852588e+03 6.57144287e+03 6.56757666e+03 6.62181299e+03 6.57662451e+03 6.54369092e+03 6.59797363e+03 6.63605615e+03 6.65322314e+03 6.42053613e+03 6.36607373e+03 6.53058740e+03 6.48783301e+03 6.50322070e+03 6.46003711e+03 6.35849707e+03 6.39904541e+03 6.42572266e+03 6.52272412e+03 6.35846924e+03 6.15317725e+03 6.30446143e+03 6.56006543e+03 6.26617725e+03 6.10594434e+03 6.17587451e+03 6.15416943e+03 6.22929053e+03 6.28093115e+03 6.10770264e+03 6.08164600e+03 6.12155078e+03 6.11369580e+03 6.16509033e+03 6.05005127e+03 6.06845020e+03 6.11980664e+03 5.84085986e+03 5.89194385e+03 5.95137793e+03 5.84413477e+03 5.95302393e+03 5.88431641e+03 5.76598145e+03 5.84109619e+03 5.73991943e+03 5.72483740e+03 5.88810742e+03 5.77635986e+03 5.63030273e+03 5.56643164e+03 5.50183252e+03 5.60564893e+03 5.65314551e+03 5.54013135e+03 5.48158057e+03 5.54255273e+03 5.53354932e+03 5.46528564e+03 5.34068896e+03 5.29323633e+03 5.31447461e+03 5.34323438e+03 5.34474512e+03 5.17150732e+03 5.13079004e+03 5.19485596e+03 5.19155225e+03 5.15048535e+03 5.12422119e+03 5.03777002e+03 4.95847607e+03 5.07591016e+03 5.10543115e+03 4.90164111e+03 4.76683496e+03 4.76952637e+03 4.82562793e+03 4.79088916e+03 4.70366162e+03 4.73465576e+03 4.71188232e+03 4.65046924e+03 4.66580615e+03 4.58088477e+03 4.49832715e+03 4.51906494e+03 4.54541162e+03 4.41432910e+03 4.29572119e+03 4.34047266e+03 4.30696191e+03 4.27980811e+03 4.29404883e+03 4.21050391e+03 4.11093945e+03 4.12111768e+03 4.17366846e+03 4.07853345e+03 3.95471558e+03 3.94608350e+03 3.92696240e+03 3.88487646e+03 3.83447461e+03 3.76078857e+03 3.75028979e+03 3.73416626e+03 3.73200513e+03 3.71981958e+03 3.60356079e+03 3.56484180e+03 3.52062671e+03 3.45880493e+03 3.42050244e+03 3.34983374e+03 3.36638745e+03 3.34622510e+03 3.25848682e+03 3.18180566e+03 3.14780566e+03 3.17121973e+03 3.16390259e+03 3.12087598e+03 3.01995532e+03 2.95294312e+03 2.91257544e+03 2.82805103e+03 2.81535840e+03 2.81664673e+03 2.75891772e+03 2.69579443e+03 2.61947510e+03 2.58150659e+03 2.59535498e+03 2.58197534e+03 2.54134253e+03 2.43805371e+03 2.34313623e+03 2.33043335e+03 2.30046875e+03 2.25028735e+03 2.23201196e+03 2.19894751e+03 2.10886548e+03 2.04372083e+03 1.99424780e+03 1.95777869e+03 1.98379822e+03 1.94029114e+03 1.83256848e+03 1.80136255e+03 1.74317517e+03 1.66423914e+03 1.67721204e+03 1.64665979e+03 1.54806213e+03 1.49692297e+03 1.44775000e+03 1.38922620e+03 1.38637231e+03 1.38181934e+03 1.30071948e+03 1.22706946e+03 1.18373975e+03 1.13371130e+03 1.09674084e+03 1.04896313e+03 9.99672546e+02 9.47031189e+02 8.94096619e+02 8.54846680e+02 8.14373535e+02 7.61766357e+02 7.19366089e+02 6.79011230e+02 6.16749084e+02 5.56359314e+02 5.14115173e+02 4.80000519e+02 4.38519958e+02 3.86171356e+02 3.26894348e+02 2.74972870e+02 2.35870819e+02 1.95793732e+02 1.49662003e+02 9.71243515e+01 4.50046387e+01 -6.91148567e+00 -5.65237160e+01 -1.00729240e+02 -1.43290329e+02 -1.87710358e+02 -2.35252213e+02 -2.95651611e+02 -3.43255737e+02 -3.76669739e+02 -4.36757629e+02 -5.01863373e+02 -5.33133972e+02 -5.72193848e+02 -6.26679077e+02 -6.73051697e+02 -7.28644287e+02 -7.77769836e+02 -8.17669434e+02 -8.46461609e+02 -9.00882019e+02 -9.66598572e+02 -1.00908954e+03 -1.06756177e+03 -1.11783374e+03 -1.14633875e+03 -1.18397412e+03 -1.25596741e+03 -1.30234827e+03 -1.33393481e+03 -1.39777600e+03 -1.45288293e+03 -1.48049438e+03 -1.50360791e+03 -1.54839099e+03 -1.61344604e+03 -1.69269067e+03 -1.74055322e+03 -1.74890088e+03 -1.78304102e+03 -1.83309692e+03 -1.89917188e+03 -1.97439355e+03 -2.00830347e+03 -2.00708215e+03 -2.08323267e+03 -2.14676050e+03 -2.15301343e+03 -2.26068408e+03 -2.30411182e+03 -2.28059058e+03 -2.35723779e+03 -2.36909595e+03 -2.39250977e+03 -2.53043384e+03 -2.57534595e+03 -2.57324561e+03 -2.64405298e+03 -2.67186279e+03 -2.64698413e+03 -2.71056006e+03 -2.81647876e+03 -2.85481543e+03 -2.90329004e+03 -2.91855542e+03 -2.94759302e+03 -3.02779639e+03 -3.07673389e+03 -3.20927466e+03 -3.19480078e+03 -3.09791504e+03 -3.17960376e+03 -3.25389917e+03 -3.33613940e+03 -3.42219971e+03 -3.39487158e+03 -3.35677856e+03 -3.47973413e+03 -3.56251123e+03 -3.57343066e+03 -3.63225146e+03 -3.64337842e+03 -3.62932349e+03 -3.74593774e+03 -3.79269482e+03 -3.75011768e+03 -3.93506812e+03 -3.98379150e+03 -3.91853467e+03 -3.95845801e+03 -3.88931787e+03 -3.94334473e+03 -4.11097412e+03 -4.27925977e+03 -4.26823682e+03 -4.06392065e+03 -4.12433252e+03 -4.33045068e+03 -4.33750830e+03 -4.33496533e+03 -4.38824658e+03 -4.38499170e+03 -4.46311035e+03 -4.52476172e+03 -4.57005469e+03 -4.58620020e+03 -4.62087891e+03 -4.70895605e+03 -4.66742188e+03 -4.65569238e+03 -4.69599756e+03 -4.74375244e+03 -4.83552002e+03 -4.96862842e+03 -4.90880908e+03 -4.80375049e+03 -4.92429248e+03 -5.01503613e+03 -5.14833496e+03 -5.14492969e+03 -4.97390332e+03 -5.06355859e+03 -5.15717139e+03 -5.23167773e+03 -5.34972070e+03 -5.27859424e+03 -5.22914844e+03 -5.28471094e+03 -5.26381641e+03 -5.24399463e+03 -5.44614355e+03 -5.58045752e+03 -5.45280713e+03 -5.41546191e+03 -5.41112305e+03 -5.47039453e+03 -5.67523340e+03 -5.70468652e+03 -5.66828369e+03 -5.64424756e+03 -5.53232910e+03 -5.64560010e+03 -5.72491846e+03 -5.86708789e+03 -5.93008105e+03 -5.73053662e+03 -5.73631055e+03 -5.85416260e+03 -5.91211768e+03 -5.93971631e+03 -6.00708984e+03 -6.04117920e+03 -5.92184229e+03 -5.95697168e+03 -6.00788965e+03 -6.03567480e+03 -6.09989453e+03 -6.15566016e+03 -6.14959375e+03 -6.13739062e+03 -6.11331250e+03 -6.18512549e+03 -6.33712207e+03 -6.28531055e+03 -6.17224414e+03 -6.19564941e+03 -6.24995166e+03 -6.26004004e+03 -6.51545898e+03 -6.54937207e+03 -6.27547070e+03 -6.33638037e+03 -6.30312744e+03 -6.39486963e+03 -6.65643750e+03 -6.71633105e+03 -6.35345752e+03 -5.92522852e+03 -8.09447754e+03 -8.96909473e+03 -9.91778125e+03 -1.01831260e+04 -1.07391045e+04 -1.00669082e+04 -1.58292822e+04 -2.94189531e+04 3.28185375e+06 128801400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 28359492. -3.05143301e+04 -1.12721230e+04 -1.03541162e+04 -9.03706348e+03 -1.06004727e+04 -7.91824902e+03 -6.83040137e+03 -6.84746240e+03 -7.16657666e+03 -7.05884375e+03 -6.83958350e+03 -6.68755078e+03 -6.71520898e+03 -6.93267480e+03 -7.02325684e+03 -6.94967822e+03 -6.75902686e+03 -6.70187402e+03 -6.72126074e+03 -6.90649951e+03 -6.84894043e+03 -6.59796191e+03 -6.68250049e+03 -6.87820264e+03 -6.80444385e+03 -6.64979199e+03 -6.53960352e+03 -6.74024121e+03 -7.03493213e+03 -6.98844287e+03 -6.55492090e+03 -6.29250537e+03 -6.49599072e+03 -6.78443066e+03 -6.91127881e+03 -6.79459863e+03 -6.45500293e+03 -6.50532031e+03 -6.60517188e+03 -6.77737402e+03 -6.66714551e+03 -6.31276465e+03 -6.38924756e+03 -6.71505029e+03 -6.59826660e+03 -6.43109570e+03 -6.46514355e+03 -6.48420020e+03 -6.52242920e+03 -6.50881104e+03 -6.26998291e+03 -6.18147754e+03 -6.43443799e+03 -6.61795801e+03 -6.47737695e+03 -6.24075439e+03 -6.03447607e+03 -6.30238867e+03 -6.52458740e+03 -6.37399854e+03 -6.12889844e+03 -5.89468945e+03 -5.98354639e+03 -6.30293066e+03 -6.35627295e+03 -6.25021191e+03 -6.10839209e+03 -6.07938477e+03 -5.97889551e+03 -6.00205957e+03 -6.03216016e+03 -5.83526953e+03 -5.91289941e+03 -6.09869141e+03 -5.98549854e+03 -5.67658643e+03 -5.62877783e+03 -5.89826660e+03 -6.06616748e+03 -5.92536035e+03 -5.71701416e+03 -5.54416211e+03 -5.51747070e+03 -5.64905371e+03 -5.87208691e+03 -5.75885498e+03 -5.42085840e+03 -5.45932471e+03 -5.53145703e+03 -5.54462939e+03 -5.61471729e+03 -5.39229590e+03 -5.34332324e+03 -5.47053027e+03 -5.42828223e+03 -5.29018945e+03 -5.19472754e+03 -5.25967969e+03 -5.32604395e+03 -5.26643750e+03 -5.10057031e+03 -4.98874414e+03 -5.11076465e+03 -5.23519922e+03 -5.15631250e+03 -5.00903662e+03 -4.84197266e+03 -4.90034863e+03 -5.01667578e+03 -4.98287793e+03 -4.84085107e+03 -4.63126172e+03 -4.63411621e+03 -4.81677002e+03 -4.89258691e+03 -4.75914160e+03 -4.50269531e+03 -4.52922314e+03 -4.63892383e+03 -4.56242041e+03 -4.42972070e+03 -4.33696045e+03 -4.47145508e+03 -4.51690332e+03 -4.33777051e+03 -4.24008203e+03 -4.15993359e+03 -4.24360596e+03 -4.37510059e+03 -4.25724902e+03 -4.08634937e+03 -3.99111499e+03 -3.98219653e+03 -4.00495654e+03 -4.05561108e+03 -3.98260767e+03 -3.76806226e+03 -3.74178809e+03 -3.86701514e+03 -3.87792725e+03 -3.75220947e+03 -3.62969067e+03 -3.62708252e+03 -3.66407007e+03 -3.62004248e+03 -3.52093774e+03 -3.36456323e+03 -3.36248389e+03 -3.45787744e+03 -3.41282666e+03 -3.31607104e+03 -3.20143799e+03 -3.18037744e+03 -3.22347241e+03 -3.25932861e+03 -3.17550220e+03 -2.99223511e+03 -2.95742920e+03 -2.97522607e+03 -2.95032202e+03 -2.90438525e+03 -2.81026123e+03 -2.80318164e+03 -2.75716064e+03 -2.68419727e+03 -2.64339746e+03 -2.58613159e+03 -2.61581494e+03 -2.60322729e+03 -2.50855835e+03 -2.39899072e+03 -2.31947388e+03 -2.35629321e+03 -2.39298682e+03 -2.32459399e+03 -2.22215259e+03 -2.11107935e+03 -2.03714539e+03 -2.07026831e+03 -2.13126782e+03 -2.02931934e+03 -1.87526001e+03 -1.85269714e+03 -1.87236328e+03 -1.83836096e+03 -1.78275989e+03 -1.70136462e+03 -1.65098706e+03 -1.62308618e+03 -1.55676160e+03 -1.49759460e+03 -1.46858167e+03 -1.44700659e+03 -1.39483313e+03 -1.33459448e+03 -1.27644104e+03 -1.22611853e+03 -1.20263208e+03 -1.17588208e+03 -1.11693530e+03 -1.02687781e+03 -9.63596558e+02 -9.55656311e+02 -9.28325317e+02 -8.71901306e+02 -8.12767761e+02 -7.40762268e+02 -6.94209839e+02 -6.79315186e+02 -6.49019836e+02 -5.91204895e+02 -5.21356323e+02 -4.67680511e+02 -4.30811035e+02 -3.84835052e+02 -3.34123352e+02 -2.88895630e+02 -2.43882156e+02 -1.92058960e+02 -1.40372452e+02 -9.04024277e+01 -4.45314560e+01 1.01839566e+00 4.83605003e+01 9.92887650e+01 1.47086517e+02 1.87977539e+02 2.42032455e+02 2.95030884e+02 3.40756561e+02 3.90976471e+02 4.34184753e+02 4.93778961e+02 5.40031128e+02 5.56869141e+02 5.95765259e+02 6.58255493e+02 7.39974121e+02 8.13837402e+02 8.43396606e+02 8.42336975e+02 8.61829407e+02 9.31880615e+02 1.03385535e+03 1.11145435e+03 1.13151404e+03 1.11934155e+03 1.15799548e+03 1.27947144e+03 1.33671936e+03 1.31053027e+03 1.35391919e+03 1.42645605e+03 1.47192188e+03 1.56884692e+03 1.57880908e+03 1.56800671e+03 1.66010339e+03 1.67069482e+03 1.75566492e+03 1.85484473e+03 1.80542920e+03 1.89163867e+03 1.99939392e+03 1.99429346e+03 2.03480359e+03 2.07861987e+03 2.13263306e+03 2.18687671e+03 2.22019263e+03 2.20809692e+03 2.24859863e+03 2.39522314e+03 2.51479199e+03 2.50926465e+03 2.43887329e+03 2.42577563e+03 2.51198193e+03 2.67901904e+03 2.80335327e+03 2.79001294e+03 2.68538525e+03 2.72853906e+03 2.87751611e+03 2.90697949e+03 2.91447388e+03 2.94907251e+03 2.99595752e+03 3.05082593e+03 3.19880396e+03 3.16218115e+03 3.10792480e+03 3.22879834e+03 3.18935181e+03 3.32828003e+03 3.44019458e+03 3.39320654e+03 3.54926318e+03 3.48683081e+03 3.40813184e+03 3.56148169e+03 3.51781055e+03 3.62866113e+03 3.91473291e+03 3.74825122e+03 3.58718604e+03 3.70220312e+03 3.91444043e+03 4.10825635e+03 4.05716187e+03 3.85290356e+03 3.79771680e+03 3.94351782e+03 4.17177393e+03 4.36051074e+03 4.29235352e+03 4.09636377e+03 4.10605273e+03 4.29302344e+03 4.39065723e+03 4.32367139e+03 4.30139014e+03 4.41286133e+03 4.48056592e+03 4.62132471e+03 4.66634082e+03 4.46733740e+03 4.50381396e+03 4.60120947e+03 4.65769287e+03 4.74934521e+03 4.75881104e+03 4.88543408e+03 4.85433691e+03 4.72885889e+03 4.84295605e+03 4.77339502e+03 4.95338574e+03 5.29870117e+03 5.04122656e+03 4.75848633e+03 4.91389600e+03 5.19954004e+03 5.39034375e+03 5.40077881e+03 5.15576709e+03 4.97313770e+03 5.09124121e+03 5.39889697e+03 5.64875879e+03 5.52912695e+03 5.24866016e+03 5.22237793e+03 5.39452002e+03 5.54670654e+03 5.71102100e+03 5.70876611e+03 5.43699805e+03 5.42069385e+03 5.72864941e+03 5.81898340e+03 5.63578955e+03 5.64132275e+03 5.65294873e+03 5.66186230e+03 5.95208008e+03 6.01029297e+03 5.73415967e+03 5.71712207e+03 5.82737451e+03 5.87821924e+03 5.95876758e+03 5.92992285e+03 6.11021826e+03 6.19055225e+03 6.00294678e+03 5.90757422e+03 5.81176074e+03 6.06945605e+03 6.45438281e+03 6.33964746e+03 6.00806738e+03 5.89084082e+03 6.15389600e+03 6.52715283e+03 6.32498730e+03 5.97219434e+03 6.11305518e+03 6.28114111e+03 6.46722803e+03 6.69303906e+03 6.54490527e+03 6.21118359e+03 6.08117920e+03 6.33523828e+03 6.57760986e+03 6.59027734e+03 6.48326025e+03 6.45272852e+03 6.45863818e+03 6.61931592e+03 6.57789648e+03 6.39839355e+03 6.36519971e+03 6.39535156e+03 6.71739307e+03 6.82477100e+03 6.59222363e+03 6.63441699e+03 6.67751465e+03 6.79641895e+03 6.68298730e+03 6.35953467e+03 6.63852295e+03 6.99354248e+03 6.85171387e+03 6.51921387e+03 6.56113867e+03 6.93885303e+03 6.97212354e+03 6.77795117e+03 6.78580518e+03 6.60508984e+03 6.63161035e+03 6.98499170e+03 6.97391357e+03 6.66794775e+03 6.54324854e+03 6.56038330e+03 6.89465576e+03 7.20333887e+03 6.88817871e+03 6.69116064e+03 6.83737109e+03 6.85352246e+03 7.07180127e+03 7.02650293e+03 6.59513428e+03 6.73178906e+03 6.92094287e+03 6.86812549e+03 6.90556934e+03 6.86154541e+03 7.09210889e+03 7.20494824e+03 6.97961963e+03 6.88171191e+03 6.32804688e+03 8.59198242e+03 9.93623828e+03 1.05838945e+04 1.00679443e+04 9.92029199e+03 1.03343535e+04 1.07467012e+04 1.12658340e+04 1.16009365e+04 1.03171621e+04 1.01761475e+04 1.95611426e+04 1.19849859e+05 53426952. 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. 0. 0. 0. 0. 0. 0. 0. 0. -51509072. -3.08721825e+06 -1.97736375e+06 2.18576973e+04 1.59871445e+04 7.19728223e+03 7.57354150e+03 6.86420410e+03 6.71597607e+03 6.42571973e+03 6.54215137e+03 6.35075928e+03 6.12813818e+03 6.27410840e+03 6.23687988e+03 6.38409521e+03 6.43097559e+03 5.84711328e+03 5.74666797e+03 5.84296289e+03 5.96731934e+03 5.87101709e+03 5.74545850e+03 6.11827246e+03 5.95969629e+03 5.76986279e+03 6.01129492e+03 5.94764941e+03 5.73749658e+03 5.89843506e+03 6.07117725e+03 5.89069629e+03 5.80733643e+03 5.73686719e+03 5.70011816e+03 5.62002783e+03 5.60206445e+03 5.70195557e+03 5.69414795e+03 5.57456396e+03 5.53680859e+03 5.52557764e+03 5.49495996e+03 5.43928711e+03 5.41105420e+03 5.39139990e+03 5.21128857e+03 5.16108936e+03 5.26968213e+03 5.23440479e+03 5.39810547e+03 5.38173145e+03 5.16425244e+03 4.98254980e+03 4.93564355e+03 5.23239941e+03 5.24358838e+03 5.01462402e+03 4.87154004e+03 4.85543359e+03 4.91103320e+03 4.83522510e+03 4.96347021e+03 4.93055322e+03 4.61599268e+03 4.53461475e+03 4.75433887e+03 4.89697119e+03 4.73325146e+03 4.59273877e+03 4.57665430e+03 4.53062891e+03 4.43017871e+03 4.42020459e+03 4.39426758e+03 4.32267871e+03 4.30987646e+03 4.27420117e+03 4.27615039e+03 4.23204150e+03 4.28422412e+03 4.23018604e+03 4.06393237e+03 4.07913672e+03 4.05629614e+03 4.04828613e+03 4.00940454e+03 3.93514111e+03 3.89511499e+03 3.77024756e+03 3.63955591e+03 3.78719580e+03 3.79729077e+03 3.55897754e+03 3.55123364e+03 3.71049951e+03 3.76697070e+03 3.60686353e+03 3.46874731e+03 3.42010962e+03 3.37660132e+03 3.30332837e+03 3.24988843e+03 3.27834277e+03 3.22412671e+03 3.25913623e+03 3.19402271e+03 3.06912109e+03 3.07463501e+03 2.94983911e+03 2.91020288e+03 3.02750073e+03 2.95687256e+03 2.84574170e+03 2.73904883e+03 2.65254590e+03 2.76051196e+03 2.76778369e+03 2.63152393e+03 2.50972974e+03 2.47129126e+03 2.48902539e+03 2.42969214e+03 2.46153906e+03 2.43774512e+03 2.30335376e+03 2.21381104e+03 2.17605029e+03 2.22154712e+03 2.17675488e+03 2.07290796e+03 2.00384839e+03 1.96222876e+03 1.94454700e+03 1.85004541e+03 1.80910938e+03 1.86475000e+03 1.80519543e+03 1.71325964e+03 1.62155017e+03 1.56285437e+03 1.61241040e+03 1.57469519e+03 1.48034741e+03 1.39602747e+03 1.34028784e+03 1.33344800e+03 1.28903589e+03 1.23926660e+03 1.16116589e+03 1.13957947e+03 1.14976221e+03 1.07242883e+03 1.01335339e+03 9.68155701e+02 9.13412170e+02 8.52416992e+02 8.02827026e+02 7.67219360e+02 7.19515442e+02 6.68714661e+02 6.04539551e+02 5.68737000e+02 5.52818481e+02 4.82063202e+02 4.19981506e+02 3.82639832e+02 3.33750885e+02 2.95930969e+02 2.42242233e+02 1.85943939e+02 1.46807068e+02 9.84202423e+01 4.76380997e+01 -2.31138206e+00 -5.14471321e+01 -1.00219109e+02 -1.47623825e+02 -1.94663971e+02 -2.34664108e+02 -2.87543915e+02 -3.55003418e+02 -3.95521820e+02 -4.30016907e+02 -4.63443024e+02 -5.16469421e+02 -5.99299683e+02 -6.45537720e+02 -6.74544495e+02 -7.03118042e+02 -7.45690857e+02 -8.17904785e+02 -8.64341187e+02 -9.30910400e+02 -9.60815918e+02 -9.76349670e+02 -1.05439624e+03 -1.10458411e+03 -1.17415613e+03 -1.21847351e+03 -1.23602832e+03 -1.28396436e+03 -1.32967615e+03 -1.39394543e+03 -1.40531140e+03 -1.46546838e+03 -1.59214648e+03 -1.60891357e+03 -1.61914868e+03 -1.62576416e+03 -1.65924536e+03 -1.79960339e+03 -1.85963367e+03 -1.85197656e+03 -1.84323816e+03 -1.88799023e+03 -1.99866748e+03 -2.04768311e+03 -2.13944751e+03 -2.15965112e+03 -2.15312524e+03 -2.17444775e+03 -2.20827344e+03 -2.37539526e+03 -2.40855737e+03 -2.37872290e+03 -2.41371362e+03 -2.46152905e+03 -2.58384619e+03 -2.62957690e+03 -2.56844043e+03 -2.60434717e+03 -2.77718237e+03 -2.81734644e+03 -2.73691870e+03 -2.76809131e+03 -2.95988477e+03 -3.01830054e+03 -2.96031641e+03 -2.93589551e+03 -2.97590649e+03 -3.19555640e+03 -3.21542798e+03 -3.16078589e+03 -3.22362305e+03 -3.25483521e+03 -3.30394751e+03 -3.33607935e+03 -3.37239429e+03 -3.33221484e+03 -3.46277246e+03 -3.69518921e+03 -3.62579443e+03 -3.62249097e+03 -3.69418774e+03 -3.70493774e+03 -3.74387427e+03 -3.77467896e+03 -3.80170435e+03 -3.74594922e+03 -3.73765845e+03 -3.86943921e+03 -3.99530029e+03 -4.17138037e+03 -4.06555591e+03 -3.95772754e+03 -4.09834521e+03 -4.18728662e+03 -4.34882861e+03 -4.31469238e+03 -4.24537402e+03 -4.25347900e+03 -4.24888916e+03 -4.37956982e+03 -4.43544727e+03 -4.55367725e+03 -4.58122021e+03 -4.51446533e+03 -4.49279297e+03 -4.39877686e+03 -4.62072803e+03 -4.91811523e+03 -4.86009863e+03 -4.74895850e+03 -4.66221436e+03 -4.62889502e+03 -4.90447363e+03 -5.08745801e+03 -4.97855518e+03 -4.81362305e+03 -4.84996777e+03 -5.01021973e+03 -5.03753027e+03 -5.21786816e+03 -5.21646387e+03 -5.09372217e+03 -5.15158740e+03 -5.17652344e+03 -5.30832422e+03 -5.36518115e+03 -5.16261719e+03 -5.20052197e+03 -5.52905420e+03 -5.43217822e+03 -5.18372705e+03 -5.40140576e+03 -5.73561816e+03 -5.65388086e+03 -5.52094385e+03 -5.42123047e+03 -5.46161719e+03 -5.79893896e+03 -5.82170605e+03 -5.67133105e+03 -5.56779297e+03 -5.55998242e+03 -5.75007910e+03 -5.79006445e+03 -5.81169775e+03 -5.69487939e+03 -5.84856934e+03 -6.14077441e+03 -5.99006006e+03 -6.01146240e+03 -6.02555615e+03 -5.91259814e+03 -6.00469043e+03 -6.05622754e+03 -6.05981445e+03 -6.04284717e+03 -6.01881982e+03 -5.93227051e+03 -6.10226807e+03 -6.46779053e+03 -6.18246387e+03 -5.96680518e+03 -6.15994775e+03 -6.28856152e+03 -6.51597266e+03 -6.40026025e+03 -6.23553760e+03 -6.42465625e+03 -6.47226074e+03 -6.17000293e+03 -6.16450049e+03 -6.51469727e+03 -6.59658301e+03 -6.42455273e+03 -6.30488232e+03 -6.14208691e+03 -6.44894580e+03 -6.84416553e+03 -6.70523389e+03 -6.49894482e+03 -6.35164648e+03 -6.34263916e+03 -6.65132959e+03 -6.93119092e+03 -6.70429443e+03 -6.43889258e+03 -6.39349365e+03 -6.57747168e+03 -6.68533398e+03 -6.88947412e+03 -6.73296582e+03 -6.56540674e+03 -6.73527148e+03 -6.72144971e+03 -6.84024756e+03 -6.80625488e+03 -6.69760449e+03 -6.75417871e+03 -6.73182666e+03 -6.72540479e+03 -6.54235107e+03 -6.65988281e+03 -7.11716846e+03 -6.97469873e+03 -6.73025684e+03 -6.59375830e+03 -6.65496826e+03 -7.07405713e+03 -7.03010352e+03 -6.82933887e+03 -6.68621436e+03 -6.61573438e+03 -6.87322168e+03 -6.85992578e+03 -6.88413379e+03 -6.72124561e+03 -6.83715869e+03 -7.12439355e+03 -6.96080859e+03 -6.97983691e+03 -6.99206250e+03 -6.84740625e+03 -6.82554834e+03 -6.81483887e+03 -6.82451318e+03 -6.83180469e+03 -6.85915967e+03 -6.85645166e+03 -6.99876855e+03 -7.02549854e+03 -6.72180176e+03 -6.59633838e+03 -6.81860645e+03 -6.96575635e+03 -7.09863916e+03 -6.95254150e+03 -6.58917480e+03 -6.91550488e+03 -7.09405371e+03 -6.87735449e+03 -6.72998145e+03 -6.69590381e+03 -6.82030664e+03 -6.86486768e+03 -6.78398389e+03 -6.56172363e+03 -6.74759521e+03 -7.11443408e+03 -6.93596289e+03 -6.82732324e+03 -6.64325928e+03 -6.59461914e+03 -6.97101221e+03 -6.91686426e+03 -6.73170166e+03 -6.57559424e+03 -6.41527100e+03 -6.59661670e+03 -6.80125830e+03 -7.03823242e+03 -6.70084180e+03 -6.40270264e+03 -6.61219482e+03 -6.67516797e+03 -6.85312061e+03 -6.72521924e+03 -6.45456299e+03 -6.63060059e+03 -6.61841943e+03 -6.45906250e+03 -6.29266650e+03 -6.50217090e+03 -6.78661768e+03 -6.61545508e+03 -6.52159814e+03 -6.36278516e+03 -6.27751172e+03 -6.61217285e+03 -6.61705908e+03 -6.38911084e+03 -6.23175928e+03 -6.17399609e+03 -6.33849170e+03 -6.30893750e+03 -6.43132031e+03 -6.45721631e+03 -6.21860107e+03 -6.09267334e+03 -6.14864258e+03 -6.44322754e+03 -6.25414844e+03 -6.05932812e+03 -6.16183301e+03 -6.14474268e+03 -6.01641455e+03 -5.90742773e+03 -6.13015479e+03 -6.09976416e+03 -5.90970117e+03 -6.12767285e+03 -6.14734277e+03 -5.97862793e+03 -5.92124268e+03 -5.88822314e+03 -5.86356689e+03 -5.70500293e+03 -5.60842920e+03 -5.88084424e+03 -5.94924463e+03 -5.59484863e+03 -5.40083008e+03 -5.63221094e+03 -5.93965234e+03 -5.83648242e+03 -5.51885254e+03 -5.36180371e+03 -5.61407031e+03 -5.67018213e+03 -5.48299170e+03 -5.49302393e+03 -5.31863232e+03 -5.12399072e+03 -5.31753271e+03 -5.51544629e+03 -5.45903418e+03 -5.21737842e+03 -5.03597803e+03 -5.26105762e+03 -5.40498877e+03 -5.20740771e+03 -4.95981787e+03 -4.87602002e+03 -5.00744873e+03 -4.99982520e+03 -5.09794531e+03 -5.05387061e+03 -4.82720850e+03 -4.85411572e+03 -4.86668115e+03 -4.90521533e+03 -4.72925781e+03 -4.60237109e+03 -4.77276465e+03 -4.73178320e+03 -4.65279834e+03 -4.49816748e+03 -4.50566455e+03 -4.72429297e+03 -4.50564502e+03 -4.29227246e+03 -4.36296484e+03 -4.42800244e+03 -4.39638867e+03 -4.30583984e+03 -4.36348486e+03 -4.36343652e+03 -4.20176074e+03 -4.04606372e+03 -3.99988574e+03 -4.17940771e+03 -4.07013965e+03 -3.90523438e+03 -4.00699268e+03 -3.97370166e+03 -3.86260376e+03 -3.78019067e+03 -3.86923267e+03 -3.80263574e+03 -3.65629419e+03 -3.71566968e+03 -3.68070459e+03 -3.66227295e+03 -3.62252661e+03 -3.53080713e+03 -3.45958325e+03 -3.33249854e+03 -3.27276855e+03 -3.38918677e+03 -3.47387671e+03 -3.26488525e+03 -3.06318018e+03 -3.14441724e+03 -3.28977002e+03 -3.22243970e+03 -3.02141089e+03 -2.87771191e+03 -2.97773291e+03 -3.02620337e+03 -2.88526343e+03 -2.88842676e+03 -2.82976880e+03 -2.67651587e+03 -2.65796240e+03 -2.71183203e+03 -2.68776978e+03 -2.53165601e+03 -2.42588794e+03 -2.49222290e+03 -2.55224219e+03 -2.44248389e+03 -2.29960986e+03 -2.21220679e+03 -2.27636279e+03 -2.30346289e+03 -2.17900415e+03 -2.08411035e+03 -2.05083960e+03 -2.04355786e+03 -1.98621484e+03 -1.99117163e+03 -1.90818237e+03 -1.79725757e+03 -1.81673328e+03 -1.77575562e+03 -1.73647278e+03 -1.65254565e+03 -1.57560950e+03 -1.59598682e+03 -1.55476135e+03 -1.55148108e+03 -1.43798413e+03 -1.41135693e+03 -1.91924707e+03 -1.92235437e+03 -1.91819617e+03 -1.85325940e+03 -1.34299341e+03 -1.10170227e+03 -9.79655090e+02 -1.11882874e+03 -1.36593665e+03 -1.37143469e+03 -1.33258215e+03 -1.44030066e+03 -1.69976855e+03 -7.92323779e+03 -141366320. 0. 0. 0. 0. 0. 0. 0. 0. -1.66598246e+10 6.77701250e+04 -3.87646523e+04 -2.55462148e+04 3.49749632e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.26456832e+09 -1.45109719e+05 1.04390778e+02 8.45376160e+02 1.08499231e+03 1.03082068e+03 9.54782410e+02 8.97944031e+02 7.84528320e+02 9.70905823e+02 9.58661926e+02 1.00396747e+03 1.03812268e+03 1.09413574e+03 1.17945374e+03 1.23152112e+03 1.22861523e+03 1.26159729e+03 1.34185559e+03 1.38990625e+03 1.42578442e+03 1.47141431e+03 1.50872791e+03 1.54877161e+03 1.63900903e+03 1.70391724e+03 1.67663647e+03 1.72006018e+03 1.83061804e+03 1.89148059e+03 1.92969202e+03 1.92998938e+03 1.94054626e+03 2.04609924e+03 2.10200854e+03 2.11285132e+03 2.14269360e+03 2.18546143e+03 2.29147510e+03 2.33213452e+03 2.33618066e+03 2.36281836e+03 2.42063647e+03 2.56392798e+03 2.60049976e+03 2.52178345e+03 2.56080347e+03 2.64934106e+03 2.70882837e+03 2.79334521e+03 2.81811011e+03 2.80413647e+03 2.89169360e+03 2.95052026e+03 2.98132471e+03 3.02995093e+03 3.01454590e+03 3.08297144e+03 3.17308228e+03 3.17486377e+03 3.20463306e+03 3.23128516e+03 3.29186694e+03 3.39642725e+03 3.44930322e+03 3.46553149e+03 3.43404102e+03 3.43995337e+03 3.58613403e+03 3.64731982e+03 3.59933252e+03 3.65595166e+03 3.70776904e+03 3.77752539e+03 3.88930273e+03 3.89295020e+03 3.82414771e+03 3.86038623e+03 4.01002856e+03 4.08040063e+03 4.00878760e+03 3.97463501e+03 4.06113745e+03 4.15528564e+03 4.29647412e+03 4.32036963e+03 4.19375488e+03 4.24980859e+03 4.40962988e+03 4.43607471e+03 4.43419238e+03 4.37968311e+03 4.39128711e+03 4.57941406e+03 4.64468311e+03 4.55300195e+03 4.59645215e+03 4.66937695e+03 4.70316748e+03 4.73094482e+03 4.75433398e+03 4.83544385e+03 4.86736084e+03 4.95872559e+03 4.99777490e+03 4.85139062e+03 4.87918506e+03 5.03763672e+03 5.02666455e+03 5.06139502e+03 5.09234570e+03 5.12953955e+03 5.24589990e+03 5.22078662e+03 5.18779297e+03 5.29724902e+03 5.38121631e+03 5.29667236e+03 5.30849756e+03 5.39303223e+03 5.44075049e+03 5.43273389e+03 5.40311133e+03 5.46345996e+03 5.52963232e+03 5.68708496e+03 5.68586621e+03 5.49741602e+03 5.55990723e+03 5.74171729e+03 5.75948047e+03 5.71921143e+03 5.68469580e+03 5.64556885e+03 5.80155273e+03 5.96557666e+03 5.88942480e+03 5.80012354e+03 5.81777295e+03 5.98782520e+03 6.06063525e+03 6.10098828e+03 5.98546729e+03 5.86130225e+03 5.99759082e+03 6.03954541e+03 6.05522510e+03 6.14553027e+03 6.07597168e+03 6.16169092e+03 6.35804688e+03 6.27375000e+03 6.04639014e+03 6.10104004e+03 6.25893604e+03 6.33876270e+03 6.40988428e+03 6.34310840e+03 6.22170898e+03 6.29606494e+03 6.52230664e+03 6.38934033e+03 6.20751758e+03 6.35543115e+03 6.54236768e+03 6.54168945e+03 6.44334033e+03 6.37616797e+03 6.39704883e+03 6.49390479e+03 6.50581055e+03 6.55312158e+03 6.64963867e+03 6.51832910e+03 6.57789893e+03 6.72811963e+03 6.59608643e+03 6.51635400e+03 6.60500049e+03 6.72561865e+03 6.72522754e+03 6.71085840e+03 6.59335840e+03 6.54455664e+03 6.66816797e+03 6.97376367e+03 6.98030225e+03 6.57244922e+03 6.59477881e+03 6.89516699e+03 6.86954883e+03 6.72575439e+03 6.69684375e+03 6.67968604e+03 6.81416699e+03 6.92232910e+03 6.81196289e+03 6.74877197e+03 6.67580859e+03 6.80598584e+03 6.96642822e+03 6.95819336e+03 6.80561572e+03 6.78134766e+03 6.87529492e+03 6.89209277e+03 6.83485596e+03 6.78588184e+03 6.81989062e+03 6.82136768e+03 6.98294873e+03 7.05272705e+03 6.72045654e+03 6.73579395e+03 6.91836816e+03 6.94921777e+03 6.93632178e+03 6.75959619e+03 6.84096777e+03 7.02646240e+03 6.88294580e+03 6.89540576e+03 6.75296777e+03 6.65626416e+03 6.85289893e+03 7.00126904e+03 6.87049170e+03 6.84952246e+03 6.89866016e+03 6.83049512e+03 6.94422607e+03 6.92324756e+03 6.71414648e+03 6.66376660e+03 6.70460596e+03 6.88765137e+03 6.85242627e+03 6.73627930e+03 6.73098193e+03 6.85591064e+03 6.87016748e+03 6.73448145e+03 6.65387158e+03 6.68283301e+03 6.77704150e+03 6.72552490e+03 6.89353418e+03 6.70886182e+03 6.57741406e+03 6.73337842e+03 6.58135889e+03 6.63200684e+03 6.71319336e+03 6.58275195e+03 6.56020801e+03 6.54110596e+03 6.58421631e+03 6.58796631e+03 6.42410107e+03 6.66334033e+03 6.76477637e+03 6.43410498e+03 6.37874365e+03 6.45828467e+03 6.46982568e+03 6.57798584e+03 6.48031787e+03 6.30652490e+03 6.35213574e+03 6.49871094e+03 6.43108643e+03 6.36797461e+03 6.27981885e+03 6.27046094e+03 6.34550879e+03 6.24594727e+03 6.20341699e+03 6.17031641e+03 6.13605957e+03 6.17808008e+03 6.26486768e+03 6.19210742e+03 6.06713867e+03 6.00510059e+03 6.13654932e+03 6.23836719e+03 5.98044141e+03 6.02464697e+03 6.04996045e+03 5.82439697e+03 5.95085645e+03 5.97970801e+03 5.84659521e+03 5.88854443e+03 5.88066260e+03 5.80507129e+03 5.89691406e+03 5.79038232e+03 5.66560352e+03 5.69710156e+03 5.73609521e+03 5.74247021e+03 5.54638525e+03 5.52739453e+03 5.59676562e+03 5.61689014e+03 5.58617920e+03 5.47707764e+03 5.38304932e+03 5.49848047e+03 5.59314111e+03 5.39846631e+03 5.26591895e+03 5.23694531e+03 5.34764795e+03 5.39689941e+03 5.20684131e+03 5.13206494e+03 5.15221680e+03 5.15094141e+03 5.09437793e+03 5.13606250e+03 5.04916260e+03 4.91269141e+03 4.99960498e+03 5.07794434e+03 4.93326416e+03 4.71737109e+03 4.73977100e+03 4.84507617e+03 4.82411670e+03 4.78411865e+03 4.70228760e+03 4.61129590e+03 4.69720801e+03 4.74555469e+03 4.57735303e+03 4.48607129e+03 4.47396387e+03 4.56095264e+03 4.47213037e+03 4.28270557e+03 4.26233154e+03 4.29139502e+03 4.28361279e+03 4.25281982e+03 4.23861719e+03 4.14532666e+03 4.12291748e+03 4.09058472e+03 3.97743555e+03 3.94237231e+03 3.89458301e+03 3.92844043e+03 3.95586108e+03 3.81680127e+03 3.71914697e+03 3.73221460e+03 3.76189600e+03 3.81557178e+03 3.74403540e+03 3.54165674e+03 3.50890210e+03 3.52332910e+03 3.47666455e+03 3.40200562e+03 3.36457446e+03 3.35481079e+03 3.32762842e+03 3.25600928e+03 3.14358789e+03 3.15664014e+03 3.19902441e+03 3.16433423e+03 3.07252783e+03 2.94966895e+03 2.93647778e+03 2.88057397e+03 2.81641602e+03 2.89097314e+03 2.84767163e+03 2.69751978e+03 2.64681152e+03 2.64444751e+03 2.67456201e+03 2.63840308e+03 2.54010107e+03 2.47281836e+03 2.42498096e+03 2.37235107e+03 2.31194922e+03 2.29965039e+03 2.26931519e+03 2.24396582e+03 2.18880566e+03 2.05639844e+03 2.04264355e+03 2.02315466e+03 1.97434985e+03 1.98406567e+03 1.88288489e+03 1.79571350e+03 1.81905310e+03 1.79773413e+03 1.71259253e+03 1.65531824e+03 1.59234827e+03 1.52716101e+03 1.49745105e+03 1.47097510e+03 1.42260828e+03 1.39832495e+03 1.36449304e+03 1.28910376e+03 1.21801306e+03 1.16449744e+03 1.14119360e+03 1.11871924e+03 1.05457068e+03 9.79670898e+02 9.30564514e+02 8.99589050e+02 8.74911804e+02 8.42321045e+02 7.69081604e+02 6.98871460e+02 6.60536194e+02 6.12491028e+02 5.61193604e+02 5.34856506e+02 4.90169952e+02 4.28158722e+02 3.79917694e+02 3.27855682e+02 2.84730103e+02 2.47287109e+02 1.98095413e+02 1.42544235e+02 9.09373779e+01 4.34180527e+01 -1.28038836e+00 -4.95254860e+01 -9.95598221e+01 -1.49826294e+02 -1.99145126e+02 -2.41652222e+02 -2.95347595e+02 -3.44777313e+02 -3.85566071e+02 -4.36863312e+02 -4.82401093e+02 -5.24970581e+02 -5.78026672e+02 -6.27471191e+02 -6.84308411e+02 -7.34045227e+02 -7.64220215e+02 -8.07979370e+02 -8.50025208e+02 -9.01326233e+02 -9.53706299e+02 -1.00919446e+03 -1.06297913e+03 -1.10778955e+03 -1.15069409e+03 -1.18168787e+03 -1.24158594e+03 -1.31791455e+03 -1.36153760e+03 -1.37666125e+03 -1.41798865e+03 -1.46942065e+03 -1.51554651e+03 -1.58080603e+03 -1.63689087e+03 -1.66274207e+03 -1.70386975e+03 -1.75007153e+03 -1.79470215e+03 -1.86327893e+03 -1.90147852e+03 -1.95042615e+03 -2.00425366e+03 -2.02253540e+03 -2.08423535e+03 -2.09999072e+03 -2.15079614e+03 -2.26887427e+03 -2.26849609e+03 -2.28067383e+03 -2.36655200e+03 -2.37986328e+03 -2.40397852e+03 -2.55384546e+03 -2.60454053e+03 -2.53445703e+03 -2.58124268e+03 -2.65925586e+03 -2.68355151e+03 -2.78344751e+03 -2.81979175e+03 -2.78032861e+03 -2.85600317e+03 -2.92716162e+03 -3.01161865e+03 -3.06711548e+03 -3.05060083e+03 -3.13196826e+03 -3.14148682e+03 -3.10316724e+03 -3.18909863e+03 -3.31675830e+03 -3.33366504e+03 -3.38799365e+03 -3.42643286e+03 -3.33216821e+03 -3.43109009e+03 -3.60766309e+03 -3.64720264e+03 -3.62328760e+03 -3.53113013e+03 -3.61024512e+03 -3.80578564e+03 -3.80990283e+03 -3.79705322e+03 -3.89410547e+03 -3.87894019e+03 -3.91493628e+03 -3.99426123e+03 -3.90431860e+03 -3.96581226e+03 -4.12401660e+03 -4.20906738e+03 -4.18925244e+03 -4.09654395e+03 -4.13998730e+03 -4.29181738e+03 -4.39696777e+03 -4.38778906e+03 -4.32536914e+03 -4.31171875e+03 -4.41640527e+03 -4.54329346e+03 -4.65344824e+03 -4.62242773e+03 -4.53916748e+03 -4.61803760e+03 -4.64010010e+03 -4.67532568e+03 -4.77016064e+03 -4.75369629e+03 -4.81692432e+03 -4.92241016e+03 -4.87116211e+03 -4.87820605e+03 -4.97116064e+03 -4.98753320e+03 -5.05635254e+03 -5.05000732e+03 -4.99255371e+03 -5.04409814e+03 -5.16390723e+03 -5.27975342e+03 -5.32064453e+03 -5.23391797e+03 -5.16362207e+03 -5.26514551e+03 -5.28027637e+03 -5.33664844e+03 -5.47935986e+03 -5.40381885e+03 -5.35413477e+03 -5.40843457e+03 -5.47701416e+03 -5.58526904e+03 -5.71036963e+03 -5.67730908e+03 -5.62780371e+03 -5.59172119e+03 -5.50792432e+03 -5.62819629e+03 -5.77986523e+03 -5.84890869e+03 -5.85963330e+03 -5.72187207e+03 -5.71846973e+03 -5.85446045e+03 -5.94836816e+03 -5.93313818e+03 -5.95933154e+03 -5.92739648e+03 -5.85362695e+03 -5.99491162e+03 -6.14261523e+03 -6.10507129e+03 -5.98999756e+03 -6.05067676e+03 -6.10501807e+03 -6.17523486e+03 -6.22520752e+03 -6.16617969e+03 -6.29105957e+03 -6.19739551e+03 -6.16024951e+03 -6.32221777e+03 -6.32609961e+03 -6.29712695e+03 -6.45934326e+03 -6.39922314e+03 -6.26294824e+03 -6.38721729e+03 -6.49367090e+03 -6.51567773e+03 -7.20593164e+03 -7.14987598e+03 -7.56816064e+03 -6.88743115e+03 -1.42250107e+04 -1.89101973e+04 -6.08099950e+06 -2534636. -1.44473775e+06 -1.63376012e+06 -8694040. -3.98597750e+05 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6806928. 2.10658975e+06 -2.72596367e+04 -1.30791250e+04 -7.43235156e+03 -6.80496387e+03 -6.52766650e+03 -7.53331885e+03 -7.40609326e+03 -6.74847559e+03 -6.82033887e+03 -7.08126758e+03 -6.97278271e+03 -6.81261523e+03 -6.74034814e+03 -6.63236963e+03 -6.95597363e+03 -7.15379150e+03 -6.85460889e+03 -6.58036865e+03 -6.62597168e+03 -6.77015137e+03 -6.85708545e+03 -6.95974512e+03 -6.71435254e+03 -6.59191895e+03 -6.76557666e+03 -6.77276514e+03 -6.76401904e+03 -6.64390918e+03 -6.58270117e+03 -6.81759375e+03 -6.95644824e+03 -6.77521631e+03 -6.41832861e+03 -6.47411816e+03 -6.71121045e+03 -6.75932861e+03 -6.62934912e+03 -6.43934766e+03 -6.48212549e+03 -6.67865771e+03 -6.81305371e+03 -6.64725635e+03 -6.30444971e+03 -6.40830469e+03 -6.68134961e+03 -6.57794092e+03 -6.60901514e+03 -6.48983105e+03 -6.22516650e+03 -6.36828711e+03 -6.51014746e+03 -6.40491016e+03 -6.32324121e+03 -6.45328418e+03 -6.45139160e+03 -6.40722119e+03 -6.28062354e+03 -6.03217139e+03 -6.17493555e+03 -6.51777002e+03 -6.33809863e+03 -6.09189307e+03 -6.00163330e+03 -5.99713525e+03 -6.28754688e+03 -6.40251074e+03 -6.16839893e+03 -5.99434619e+03 -5.96021680e+03 -5.91086621e+03 -6.03688379e+03 -6.20187109e+03 -5.95643408e+03 -5.83858691e+03 -5.97610547e+03 -5.90000146e+03 -5.77366309e+03 -5.77766797e+03 -5.86082031e+03 -5.93279004e+03 -5.83520947e+03 -5.80123633e+03 -5.62537354e+03 -5.46063330e+03 -5.73748047e+03 -5.87712695e+03 -5.55436816e+03 -5.34490869e+03 -5.47803027e+03 -5.59115332e+03 -5.61410889e+03 -5.64453320e+03 -5.41954932e+03 -5.29612744e+03 -5.40606787e+03 -5.38048389e+03 -5.35269336e+03 -5.28735693e+03 -5.16295410e+03 -5.15147266e+03 -5.23327295e+03 -5.24447168e+03 -5.14489111e+03 -5.13191211e+03 -5.12878027e+03 -5.06428467e+03 -5.02601465e+03 -4.86278174e+03 -4.82319971e+03 -5.05280176e+03 -5.04048389e+03 -4.73964893e+03 -4.62306104e+03 -4.66674512e+03 -4.85793164e+03 -4.93732227e+03 -4.72459766e+03 -4.49644092e+03 -4.47807227e+03 -4.51652100e+03 -4.53429004e+03 -4.53241455e+03 -4.45495605e+03 -4.42677637e+03 -4.37127344e+03 -4.32493555e+03 -4.31407178e+03 -4.19994775e+03 -4.21143359e+03 -4.31377930e+03 -4.22241553e+03 -4.09015234e+03 -4.00626709e+03 -3.93331812e+03 -4.05533350e+03 -4.11726416e+03 -3.89209985e+03 -3.75543091e+03 -3.77754517e+03 -3.89143335e+03 -3.91546802e+03 -3.74936743e+03 -3.61345190e+03 -3.56685376e+03 -3.55764258e+03 -3.60433325e+03 -3.60415796e+03 -3.43384009e+03 -3.30856372e+03 -3.37340332e+03 -3.43263550e+03 -3.36096094e+03 -3.26336206e+03 -3.21859399e+03 -3.18128784e+03 -3.16782544e+03 -3.12244604e+03 -3.00528369e+03 -2.94325684e+03 -2.97448462e+03 -2.97333154e+03 -2.89211670e+03 -2.77598755e+03 -2.76635767e+03 -2.76417920e+03 -2.71919458e+03 -2.70607129e+03 -2.59571045e+03 -2.56749902e+03 -2.56612451e+03 -2.48515088e+03 -2.43783057e+03 -2.36059351e+03 -2.31415430e+03 -2.32273413e+03 -2.32875806e+03 -2.26371948e+03 -2.11146143e+03 -2.04765442e+03 -2.09346265e+03 -2.10897852e+03 -2.02770447e+03 -1.88855933e+03 -1.83223865e+03 -1.84085059e+03 -1.82760400e+03 -1.78471985e+03 -1.68284656e+03 -1.60830359e+03 -1.59253247e+03 -1.57736389e+03 -1.54735364e+03 -1.48040356e+03 -1.41636829e+03 -1.37439197e+03 -1.33045190e+03 -1.29166272e+03 -1.24772290e+03 -1.20558203e+03 -1.14526123e+03 -1.07578809e+03 -1.01707831e+03 -9.72457947e+02 -9.59595947e+02 -9.45630005e+02 -8.84042175e+02 -7.98615295e+02 -7.26655579e+02 -6.91003784e+02 -6.86701355e+02 -6.54710266e+02 -5.84323364e+02 -5.14372437e+02 -4.56109528e+02 -4.19307556e+02 -3.86298798e+02 -3.38154358e+02 -2.87095947e+02 -2.37891693e+02 -1.89074112e+02 -1.42216995e+02 -9.46948318e+01 -5.00596657e+01 -3.61094499e+00 4.75256805e+01 1.00661453e+02 1.51241150e+02 1.89220215e+02 2.38117844e+02 2.91182343e+02 3.37492035e+02 3.87860504e+02 4.32876190e+02 4.91367767e+02 5.43274170e+02 5.65016785e+02 5.94613464e+02 6.53123718e+02 7.35177856e+02 8.10423157e+02 8.42812744e+02 8.44785034e+02 8.66074829e+02 9.28106628e+02 1.02236475e+03 1.10254846e+03 1.12857373e+03 1.12006580e+03 1.15804797e+03 1.27102429e+03 1.32904431e+03 1.31257434e+03 1.35700964e+03 1.42412976e+03 1.46527124e+03 1.56546484e+03 1.58413611e+03 1.57043750e+03 1.65745728e+03 1.66887708e+03 1.75117017e+03 1.85040332e+03 1.81312708e+03 1.88697778e+03 1.98466748e+03 1.99039636e+03 2.03310657e+03 2.08125342e+03 2.13429297e+03 2.18799316e+03 2.20801611e+03 2.18822705e+03 2.24323657e+03 2.40980103e+03 2.51629468e+03 2.50062524e+03 2.43842554e+03 2.41513306e+03 2.50383130e+03 2.67263770e+03 2.79215820e+03 2.77940747e+03 2.68041064e+03 2.72301367e+03 2.86461523e+03 2.89362402e+03 2.91553687e+03 2.95205981e+03 2.99502686e+03 3.05236475e+03 3.19878223e+03 3.15295044e+03 3.10454346e+03 3.21965039e+03 3.16304028e+03 3.31420703e+03 3.46388184e+03 3.38800024e+03 3.53284912e+03 3.48905786e+03 3.39342285e+03 3.55048340e+03 3.52362817e+03 3.62361182e+03 3.90674658e+03 3.74820776e+03 3.58012915e+03 3.69014233e+03 3.90931396e+03 4.10332275e+03 4.05799292e+03 3.88009058e+03 3.82529175e+03 3.90695776e+03 4.12273096e+03 4.32635596e+03 4.27966602e+03 4.11859961e+03 4.10842822e+03 4.28408984e+03 4.35835791e+03 4.32170508e+03 4.33328174e+03 4.38637598e+03 4.44941455e+03 4.62464551e+03 4.67612598e+03 4.46281738e+03 4.46725928e+03 4.59620605e+03 4.64061328e+03 4.71947949e+03 4.73927002e+03 4.90778564e+03 4.82300732e+03 4.69160596e+03 4.89301367e+03 4.78328516e+03 4.91646680e+03 5.28170361e+03 5.04390723e+03 4.75997607e+03 4.92420605e+03 5.20041602e+03 5.36861328e+03 5.36542773e+03 5.11831006e+03 4.96058301e+03 5.10209961e+03 5.40151318e+03 5.62929053e+03 5.50958105e+03 5.22122559e+03 5.21799902e+03 5.42663623e+03 5.53723389e+03 5.70149414e+03 5.72999268e+03 5.42430566e+03 5.39228027e+03 5.68130566e+03 5.77798975e+03 5.61984082e+03 5.62043213e+03 5.69013916e+03 5.67471094e+03 5.92369922e+03 5.99091748e+03 5.72953223e+03 5.74748193e+03 5.84409277e+03 5.84777979e+03 5.92509570e+03 5.91967480e+03 6.07966406e+03 6.15246729e+03 6.00614307e+03 5.89271045e+03 5.80718701e+03 6.09025586e+03 6.42151953e+03 6.31376660e+03 6.02849707e+03 5.90211182e+03 6.13643408e+03 6.47444189e+03 6.29730811e+03 5.96131543e+03 6.10847998e+03 6.32057178e+03 6.45911426e+03 6.70660107e+03 6.57412402e+03 6.21670752e+03 6.09383838e+03 6.29931201e+03 6.53025000e+03 6.55086670e+03 6.46262354e+03 6.43792822e+03 6.47471436e+03 6.61120508e+03 6.54910156e+03 6.37319971e+03 6.44607568e+03 6.40715967e+03 6.68880762e+03 6.84866064e+03 6.61453760e+03 6.63960889e+03 6.68583057e+03 6.67490820e+03 6.58603320e+03 6.39706201e+03 6.70908105e+03 7.02795605e+03 6.84048193e+03 6.51999414e+03 6.52575000e+03 6.88633594e+03 6.99170703e+03 6.85054443e+03 6.79148242e+03 6.57711621e+03 6.56134619e+03 6.90211914e+03 6.92415869e+03 6.74992285e+03 6.59559082e+03 6.53183936e+03 6.93699414e+03 7.17158545e+03 6.79507178e+03 6.66063867e+03 6.81511426e+03 6.84304785e+03 7.02613330e+03 7.05996924e+03 6.67280908e+03 6.64732910e+03 6.79768506e+03 6.86059277e+03 7.00538379e+03 7.13834082e+03 7.22035889e+03 6.97805615e+03 6.78423730e+03 6.78779834e+03 8.13154346e+03 1.53236055e+04 2.18090742e+04 -5.83206950e+06 1.61249675e+06 -2.18745225e+06 -9317552. -10302088. -29288174. -1705541. 2.71037375e+06 -3.11176925e+06 3000966. -50659216. 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. 0. 0. 0. 0. 0. 0. 0. 50713344. -4564874. 2.49077188e+04 1.79988711e+04 1.13084893e+04 1.01870723e+04 9.80600098e+03 8.72073730e+03 8.34929004e+03 6.93969141e+03 6.64865625e+03 6.41987061e+03 6.52384766e+03 6.32834473e+03 6.13545654e+03 6.27633301e+03 6.26969727e+03 6.37425684e+03 6.40684326e+03 5.84975293e+03 5.75860498e+03 5.84183105e+03 5.95054980e+03 5.92953809e+03 5.78179736e+03 6.13394727e+03 5.97416211e+03 5.80780469e+03 6.04403223e+03 5.99890771e+03 5.74981104e+03 5.89432031e+03 6.04883936e+03 5.87862207e+03 5.79772070e+03 5.73913525e+03 5.69170508e+03 5.54017236e+03 5.51052393e+03 5.73945264e+03 5.74613574e+03 5.54064258e+03 5.52311963e+03 5.50091553e+03 5.49263574e+03 5.43166309e+03 5.38405078e+03 5.39441748e+03 5.26005078e+03 5.20843115e+03 5.24178174e+03 5.19664209e+03 5.36418262e+03 5.36574023e+03 5.17636670e+03 4.98906982e+03 4.92999170e+03 5.19707715e+03 5.21630469e+03 5.00512500e+03 4.86814941e+03 4.86873877e+03 4.90724023e+03 4.84040625e+03 4.95727393e+03 4.91854004e+03 4.61615430e+03 4.52716357e+03 4.74195020e+03 4.88670801e+03 4.72310889e+03 4.58523438e+03 4.55170410e+03 4.49611865e+03 4.46675830e+03 4.43744043e+03 4.43840869e+03 4.38832617e+03 4.28827197e+03 4.25292871e+03 4.24488037e+03 4.19314648e+03 4.29372412e+03 4.24562939e+03 4.07826074e+03 4.03845239e+03 3.99628125e+03 4.08798535e+03 4.06438037e+03 3.91371875e+03 3.88244482e+03 3.76403345e+03 3.66958862e+03 3.80781421e+03 3.75592847e+03 3.52012427e+03 3.52988672e+03 3.69722900e+03 3.78022168e+03 3.62554907e+03 3.45976367e+03 3.39041821e+03 3.35453516e+03 3.32914307e+03 3.28694946e+03 3.25629419e+03 3.19424292e+03 3.24166162e+03 3.19246558e+03 3.06896899e+03 3.04233423e+03 2.90680591e+03 2.92611206e+03 3.06169604e+03 2.95682910e+03 2.84209302e+03 2.71881421e+03 2.65967700e+03 2.78115649e+03 2.74293384e+03 2.60849268e+03 2.51061011e+03 2.45943555e+03 2.47371118e+03 2.42265894e+03 2.45518628e+03 2.43337329e+03 2.30277295e+03 2.23723486e+03 2.19853076e+03 2.19310693e+03 2.14974072e+03 2.07486475e+03 2.00336047e+03 1.96740930e+03 1.93218420e+03 1.83008997e+03 1.82480640e+03 1.88085315e+03 1.80479041e+03 1.71275183e+03 1.62294336e+03 1.56640869e+03 1.60923926e+03 1.56781409e+03 1.47402930e+03 1.39065344e+03 1.34059985e+03 1.34018164e+03 1.28527417e+03 1.23414404e+03 1.16284961e+03 1.13903394e+03 1.14923096e+03 1.07617175e+03 1.01612805e+03 9.70674255e+02 9.14900818e+02 8.53328247e+02 8.05966248e+02 7.65270325e+02 7.15219177e+02 6.72694275e+02 6.06595398e+02 5.66372131e+02 5.53176880e+02 4.82072845e+02 4.18704803e+02 3.81215271e+02 3.33000366e+02 2.94340729e+02 2.44018753e+02 1.89264282e+02 1.46711517e+02 9.81163483e+01 4.74696503e+01 -1.28041339e+00 -4.95866356e+01 -9.55831299e+01 -1.40713684e+02 -1.88802307e+02 -2.32301132e+02 -2.88110626e+02 -3.54423218e+02 -3.95212067e+02 -4.27472168e+02 -4.58523376e+02 -5.11962219e+02 -5.95435791e+02 -6.42612671e+02 -6.70833252e+02 -7.02387695e+02 -7.44661804e+02 -8.14208130e+02 -8.62746155e+02 -9.28031311e+02 -9.66812378e+02 -9.83892456e+02 -1.03824377e+03 -1.08698059e+03 -1.17057678e+03 -1.21500220e+03 -1.22760962e+03 -1.27782007e+03 -1.32417029e+03 -1.36970496e+03 -1.38281824e+03 -1.46793616e+03 -1.60588928e+03 -1.61449988e+03 -1.61442004e+03 -1.62036938e+03 -1.65354407e+03 -1.79487830e+03 -1.85994495e+03 -1.85268030e+03 -1.84373120e+03 -1.88449939e+03 -1.99351685e+03 -2.03889661e+03 -2.13046777e+03 -2.18381934e+03 -2.17406250e+03 -2.15048975e+03 -2.18745435e+03 -2.37426318e+03 -2.41039087e+03 -2.38081934e+03 -2.39042480e+03 -2.42646899e+03 -2.60138696e+03 -2.65487402e+03 -2.55401440e+03 -2.59230078e+03 -2.77573853e+03 -2.82113306e+03 -2.72998120e+03 -2.76853540e+03 -2.95241504e+03 -3.01368604e+03 -2.95904395e+03 -2.93067822e+03 -2.98108276e+03 -3.17882642e+03 -3.18863550e+03 -3.13665112e+03 -3.22798755e+03 -3.25605200e+03 -3.29543018e+03 -3.34032471e+03 -3.36843457e+03 -3.33374707e+03 -3.45498633e+03 -3.65325122e+03 -3.59767334e+03 -3.65468628e+03 -3.71218896e+03 -3.68945068e+03 -3.73182617e+03 -3.75510498e+03 -3.77613062e+03 -3.75521924e+03 -3.78809888e+03 -3.90490698e+03 -3.95623779e+03 -4.11199658e+03 -4.03248071e+03 -3.94255322e+03 -4.09522363e+03 -4.17786670e+03 -4.34773975e+03 -4.31789648e+03 -4.22422607e+03 -4.23138232e+03 -4.24997461e+03 -4.38295654e+03 -4.41956152e+03 -4.54058203e+03 -4.57329883e+03 -4.49954492e+03 -4.51620459e+03 -4.42546338e+03 -4.59162256e+03 -4.88957764e+03 -4.85184033e+03 -4.76133301e+03 -4.65712256e+03 -4.61919873e+03 -4.88025000e+03 -5.06743799e+03 -4.97472314e+03 -4.81876270e+03 -4.84566943e+03 -4.97878027e+03 -5.03493457e+03 -5.19636768e+03 -5.19066650e+03 -5.10231885e+03 -5.10729053e+03 -5.11938037e+03 -5.37569531e+03 -5.41582617e+03 -5.14476367e+03 -5.17072510e+03 -5.50169531e+03 -5.46936670e+03 -5.21299512e+03 -5.34538574e+03 -5.65554541e+03 -5.64974902e+03 -5.54445410e+03 -5.41620947e+03 -5.44485205e+03 -5.77190674e+03 -5.80859424e+03 -5.68168457e+03 -5.59274023e+03 -5.53806055e+03 -5.68903711e+03 -5.81921875e+03 -5.81983545e+03 -5.65910449e+03 -5.82003418e+03 -6.11533740e+03 -5.96142236e+03 -5.99550635e+03 -6.01454248e+03 -5.91818164e+03 -5.98529688e+03 -6.04785742e+03 -6.06922754e+03 -6.04259570e+03 -5.97993848e+03 -5.87936816e+03 -6.11509668e+03 -6.44677002e+03 -6.12686963e+03 -5.90141113e+03 -6.14644043e+03 -6.34117139e+03 -6.54191895e+03 -6.40412207e+03 -6.23796582e+03 -6.38704150e+03 -6.41983301e+03 -6.23686768e+03 -6.18076758e+03 -6.46759424e+03 -6.50570508e+03 -6.35531055e+03 -6.32335742e+03 -6.16150537e+03 -6.40281592e+03 -6.83851416e+03 -6.67341455e+03 -6.48669727e+03 -6.35081299e+03 -6.30544141e+03 -6.63601709e+03 -6.91139307e+03 -6.72846924e+03 -6.48022852e+03 -6.47532227e+03 -6.56743262e+03 -6.60706201e+03 -6.78698779e+03 -6.73859912e+03 -6.55117480e+03 -6.65375732e+03 -6.60904590e+03 -6.89456152e+03 -6.85513037e+03 -6.67541406e+03 -6.70324463e+03 -6.71445166e+03 -6.77183838e+03 -6.62273193e+03 -6.63709229e+03 -6.94789404e+03 -6.93596533e+03 -6.80600781e+03 -6.62276709e+03 -6.66395703e+03 -7.07725928e+03 -7.04334668e+03 -6.83299756e+03 -6.70722266e+03 -6.69130225e+03 -6.77517383e+03 -6.78919922e+03 -6.88877588e+03 -6.73043604e+03 -6.81332959e+03 -7.05689795e+03 -6.87556738e+03 -7.01905566e+03 -7.05514258e+03 -6.86735840e+03 -6.85336084e+03 -6.77722168e+03 -6.87588428e+03 -6.85108887e+03 -6.79474756e+03 -6.75781885e+03 -7.01079297e+03 -7.02962354e+03 -6.67474365e+03 -6.59207715e+03 -6.78360156e+03 -6.90400391e+03 -7.09180225e+03 -6.97755420e+03 -6.68977979e+03 -6.85820459e+03 -7.00783691e+03 -6.87262793e+03 -6.78134668e+03 -6.76683740e+03 -6.73215039e+03 -6.67969873e+03 -6.83277734e+03 -6.69394824e+03 -6.73320654e+03 -7.05341113e+03 -6.93369580e+03 -6.78848828e+03 -6.62490967e+03 -6.61190479e+03 -6.91369482e+03 -6.87441895e+03 -6.77320557e+03 -6.60863281e+03 -6.41816357e+03 -6.56325830e+03 -6.80153711e+03 -7.02117480e+03 -6.76086279e+03 -6.50970947e+03 -6.55616650e+03 -6.60348291e+03 -6.83843896e+03 -6.77960498e+03 -6.53084326e+03 -6.49214697e+03 -6.43958789e+03 -6.52456299e+03 -6.42069824e+03 -6.44414160e+03 -6.71294971e+03 -6.59342920e+03 -6.50726660e+03 -6.35063281e+03 -6.26569824e+03 -6.63163281e+03 -6.60436182e+03 -6.38274609e+03 -6.22595068e+03 -6.16237891e+03 -6.30699219e+03 -6.29021777e+03 -6.49086768e+03 -6.49029688e+03 -6.23806494e+03 -6.02633789e+03 -6.12634863e+03 -6.44599854e+03 -6.31479053e+03 -6.12229834e+03 -6.08071045e+03 -6.03261133e+03 -6.03059668e+03 -5.94581543e+03 -6.07472754e+03 -6.04185596e+03 -5.89930859e+03 -6.10233838e+03 -6.14565674e+03 -5.99471436e+03 -5.91445557e+03 -5.85744873e+03 -5.85343018e+03 -5.67847803e+03 -5.59928027e+03 -5.87926318e+03 -5.92977686e+03 -5.56918457e+03 -5.43856836e+03 -5.68904395e+03 -5.87112695e+03 -5.76745459e+03 -5.51639404e+03 -5.36452539e+03 -5.56657568e+03 -5.64726270e+03 -5.50691162e+03 -5.48677100e+03 -5.30718652e+03 -5.06513916e+03 -5.26385840e+03 -5.56027539e+03 -5.51004883e+03 -5.18619971e+03 -5.00079053e+03 -5.26345752e+03 -5.39647998e+03 -5.19281787e+03 -4.99795898e+03 -4.91393945e+03 -4.96249219e+03 -4.97720850e+03 -5.11593164e+03 -5.08834326e+03 -4.88620020e+03 -4.79067334e+03 -4.76745850e+03 -4.91809131e+03 -4.78289551e+03 -4.61989062e+03 -4.79096826e+03 -4.74821777e+03 -4.65056494e+03 -4.52313281e+03 -4.44651660e+03 -4.65765186e+03 -4.49756738e+03 -4.30125049e+03 -4.37695703e+03 -4.41942334e+03 -4.39549707e+03 -4.30287500e+03 -4.36137256e+03 -4.35455957e+03 -4.19531152e+03 -4.03720874e+03 -3.98564307e+03 -4.18056055e+03 -4.09366235e+03 -3.94157104e+03 -3.93199805e+03 -3.88214233e+03 -3.91537866e+03 -3.86138599e+03 -3.84268311e+03 -3.77268213e+03 -3.65007935e+03 -3.73616724e+03 -3.71155298e+03 -3.62642554e+03 -3.58619971e+03 -3.52303613e+03 -3.45408643e+03 -3.32349219e+03 -3.27006812e+03 -3.39673120e+03 -3.47612842e+03 -3.26621313e+03 -3.07669873e+03 -3.17555518e+03 -3.27006055e+03 -3.18765771e+03 -3.01192090e+03 -2.90200195e+03 -3.01002515e+03 -2.98057275e+03 -2.83548242e+03 -2.90721655e+03 -2.84195117e+03 -2.65052344e+03 -2.64362842e+03 -2.73786279e+03 -2.71805347e+03 -2.53278760e+03 -2.41970215e+03 -2.50432129e+03 -2.55672559e+03 -2.44087769e+03 -2.29479468e+03 -2.20957861e+03 -2.28390552e+03 -2.28096631e+03 -2.15682666e+03 -2.12722559e+03 -2.10003174e+03 -2.02318530e+03 -1.95742310e+03 -1.98136182e+03 -1.90580127e+03 -1.79395776e+03 -1.81222290e+03 -1.78184949e+03 -1.74011597e+03 -1.65629614e+03 -1.57616614e+03 -1.64067200e+03 -1.64949487e+03 -1.51986707e+03 -1.48610376e+03 -2.04819702e+03 -4.02246191e+03 -5.01722314e+03 2.50389469e+05 -3.54541531e+05 -2.32719751e+03 -1.70169580e+03 -1.42297595e+03 -1.74614392e+03 -2.72689014e+03 -3.48958911e+03 1.97084156e+05 -1.57085412e+06 1.12451875e+06 -3.92171844e+05 -107829184. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.26456832e+09 -1.45109719e+05 1.04390778e+02 8.45376160e+02 1.08499231e+03 1.24765161e+03 1.24231726e+03 8.92421875e+02 6.86639465e+02 9.30568298e+02 1.08135767e+03 1.03844067e+03 1.06251831e+03 1.09811340e+03 1.14494824e+03 1.19125500e+03 1.23915430e+03 1.27837671e+03 1.31732642e+03 1.39306812e+03 1.45089941e+03 1.48152686e+03 1.52476782e+03 1.51996912e+03 1.57066699e+03 1.67372412e+03 1.69967297e+03 1.72436707e+03 1.82399573e+03 1.91969666e+03 1.91226184e+03 1.91401807e+03 1.95704822e+03 1.98345728e+03 2.06672632e+03 2.16825415e+03 2.17604956e+03 2.20604077e+03 2.30068701e+03 2.31448901e+03 2.29915527e+03 2.36498047e+03 2.41588623e+03 2.47006128e+03 2.56575244e+03 2.56347461e+03 2.58706738e+03 2.68129956e+03 2.69344482e+03 2.71331104e+03 2.74824561e+03 2.81406812e+03 2.89523828e+03 2.94742993e+03 3.03498535e+03 3.01990942e+03 2.99961719e+03 3.11956226e+03 3.09738843e+03 3.09156860e+03 3.23487231e+03 3.27665015e+03 3.29487549e+03 3.39097192e+03 3.42237305e+03 3.40112866e+03 3.44139819e+03 3.46429565e+03 3.48467529e+03 3.58935864e+03 3.66466089e+03 3.71014575e+03 3.75167896e+03 3.76303589e+03 3.77334570e+03 3.80782788e+03 3.89018091e+03 3.90665405e+03 3.94812549e+03 4.11698340e+03 4.06954736e+03 3.94857837e+03 4.09184375e+03 4.13276758e+03 4.12837891e+03 4.26970459e+03 4.27737061e+03 4.26500977e+03 4.42014209e+03 4.49854590e+03 4.41356494e+03 4.35756104e+03 4.39013672e+03 4.46936914e+03 4.57663574e+03 4.62852979e+03 4.69104492e+03 4.74538477e+03 4.74451514e+03 4.68222949e+03 4.66650488e+03 4.82022510e+03 4.86555469e+03 4.81328955e+03 4.95069824e+03 4.94811230e+03 4.94108984e+03 5.07747852e+03 5.00874561e+03 4.92551514e+03 5.01937646e+03 5.18777393e+03 5.24705127e+03 5.18411377e+03 5.25051318e+03 5.33158350e+03 5.35733398e+03 5.36456445e+03 5.26858301e+03 5.27485742e+03 5.47718457e+03 5.50898145e+03 5.44006738e+03 5.52571094e+03 5.47734375e+03 5.47608496e+03 5.63599902e+03 5.63014111e+03 5.53379883e+03 5.62458447e+03 5.80112158e+03 5.83785498e+03 5.76967139e+03 5.65436035e+03 5.65181689e+03 5.84033789e+03 5.94348779e+03 5.83693945e+03 5.83242188e+03 6.03412695e+03 6.07452783e+03 6.01169629e+03 5.99189746e+03 5.85566162e+03 5.85818359e+03 5.99100049e+03 6.12866846e+03 6.13438086e+03 6.12480469e+03 6.23711426e+03 6.24822119e+03 6.15172412e+03 6.08694092e+03 6.11533643e+03 6.22906689e+03 6.36175293e+03 6.46560938e+03 6.41063477e+03 6.34465771e+03 6.22356396e+03 6.34224707e+03 6.42517529e+03 6.24566113e+03 6.29466748e+03 6.49657764e+03 6.60138818e+03 6.45801758e+03 6.40673340e+03 6.42373535e+03 6.36094336e+03 6.50713916e+03 6.67846436e+03 6.65880078e+03 6.56536719e+03 6.56902441e+03 6.61650049e+03 6.53770068e+03 6.52848877e+03 6.57535693e+03 6.58902832e+03 6.81338916e+03 6.87202930e+03 6.59310791e+03 6.56058301e+03 6.63887744e+03 6.75725537e+03 6.84488232e+03 6.57941748e+03 6.55156250e+03 6.82238428e+03 6.89510303e+03 6.74874756e+03 6.75872803e+03 6.72670361e+03 6.64985938e+03 6.80020947e+03 6.94649512e+03 6.78152832e+03 6.69758105e+03 6.88422900e+03 7.01089648e+03 6.86592285e+03 6.79904443e+03 6.77323389e+03 6.76235205e+03 6.95139160e+03 6.87423389e+03 6.78789062e+03 6.90993506e+03 6.85191650e+03 6.75158252e+03 6.85565576e+03 6.75403125e+03 6.78707520e+03 6.93717432e+03 6.92081445e+03 6.93647949e+03 6.83396680e+03 6.84933057e+03 6.80751562e+03 6.76159668e+03 6.90772021e+03 6.84359229e+03 6.70858740e+03 6.89504834e+03 6.91083398e+03 6.81092627e+03 6.83367969e+03 6.90666016e+03 6.79027148e+03 6.86875391e+03 6.98074512e+03 6.80084326e+03 6.68897217e+03 6.75487207e+03 6.71316846e+03 6.73966211e+03 6.76077197e+03 6.75355762e+03 6.79216992e+03 6.85181055e+03 6.78769287e+03 6.71676807e+03 6.74659424e+03 6.69334961e+03 6.69792041e+03 6.82320752e+03 6.61813574e+03 6.54837646e+03 6.74433496e+03 6.68748682e+03 6.59316846e+03 6.63408838e+03 6.62715820e+03 6.53583252e+03 6.51513086e+03 6.57288672e+03 6.67808545e+03 6.57658545e+03 6.59024365e+03 6.61221631e+03 6.39939355e+03 6.41407178e+03 6.43569238e+03 6.37242529e+03 6.53590527e+03 6.56597754e+03 6.40129883e+03 6.29709521e+03 6.35087012e+03 6.45560645e+03 6.40723828e+03 6.10280811e+03 6.25433398e+03 6.46157373e+03 6.27266797e+03 6.20391357e+03 6.17149365e+03 6.16666602e+03 6.17864648e+03 6.14082861e+03 6.04816699e+03 6.16028516e+03 6.16768604e+03 6.06350293e+03 6.10582861e+03 6.08743555e+03 6.02909619e+03 5.96381641e+03 5.77696533e+03 5.93815723e+03 6.08864404e+03 5.84359033e+03 5.81478271e+03 5.81363135e+03 5.84490625e+03 5.87080713e+03 5.66117139e+03 5.72599561e+03 5.82231152e+03 5.73780811e+03 5.65942041e+03 5.55131934e+03 5.52736426e+03 5.59019824e+03 5.54996191e+03 5.50126270e+03 5.53472363e+03 5.51542041e+03 5.47356348e+03 5.49064648e+03 5.42117578e+03 5.29303271e+03 5.23759912e+03 5.30479443e+03 5.34637842e+03 5.19131396e+03 5.11528320e+03 5.08544336e+03 5.09167188e+03 5.16541064e+03 5.09914941e+03 4.96003418e+03 4.93166260e+03 5.01365527e+03 5.03930420e+03 4.92457422e+03 4.74815479e+03 4.77235010e+03 4.82772412e+03 4.73771143e+03 4.70221680e+03 4.75623535e+03 4.69417578e+03 4.62340576e+03 4.65177197e+03 4.62153906e+03 4.52047314e+03 4.43304590e+03 4.45507471e+03 4.43681396e+03 4.28708984e+03 4.22012598e+03 4.26124219e+03 4.30177441e+03 4.29387012e+03 4.19624268e+03 4.07975806e+03 4.14740820e+03 4.15577979e+03 3.97338550e+03 3.90057251e+03 3.96585083e+03 4.01410913e+03 3.92354395e+03 3.76594189e+03 3.70972485e+03 3.73175732e+03 3.76274121e+03 3.76826685e+03 3.71538770e+03 3.58283350e+03 3.49338086e+03 3.47518994e+03 3.42531519e+03 3.40481079e+03 3.36693774e+03 3.32568091e+03 3.31572314e+03 3.27268237e+03 3.21171948e+03 3.14742456e+03 3.13981348e+03 3.18377466e+03 3.09810767e+03 2.95371265e+03 2.89760449e+03 2.91561401e+03 2.92334473e+03 2.91209033e+03 2.81776587e+03 2.66484131e+03 2.63592285e+03 2.68597461e+03 2.66772119e+03 2.62250977e+03 2.52774048e+03 2.44421851e+03 2.42409985e+03 2.37871997e+03 2.36682837e+03 2.30566382e+03 2.20106836e+03 2.21801685e+03 2.20811255e+03 2.12420557e+03 2.05273315e+03 1.96580237e+03 1.96102075e+03 2.00494006e+03 1.94257605e+03 1.82718555e+03 1.81174182e+03 1.80043201e+03 1.68870325e+03 1.62772192e+03 1.57877148e+03 1.54142163e+03 1.55823181e+03 1.49360437e+03 1.39996277e+03 1.37575134e+03 1.34653857e+03 1.27587158e+03 1.22524219e+03 1.20819055e+03 1.15596948e+03 1.08912476e+03 1.04694434e+03 9.95790955e+02 9.66329834e+02 9.32076294e+02 8.74301270e+02 8.18283386e+02 7.47942383e+02 7.03416687e+02 6.69153320e+02 6.25848083e+02 5.86408386e+02 5.36288086e+02 4.85014496e+02 4.25439301e+02 3.79472473e+02 3.38718842e+02 2.89609863e+02 2.37778687e+02 1.82130539e+02 1.35237961e+02 9.04125748e+01 4.60846672e+01 5.58225822e+00 -4.01061058e+01 -9.09290009e+01 -1.50445999e+02 -2.04142487e+02 -2.45832916e+02 -2.88370209e+02 -3.26139038e+02 -3.71609924e+02 -4.36300598e+02 -4.89911438e+02 -5.14135010e+02 -5.53616821e+02 -6.17701660e+02 -6.82013062e+02 -7.31312073e+02 -7.63417603e+02 -8.01488464e+02 -8.55242065e+02 -9.14798645e+02 -9.60521667e+02 -9.91016113e+02 -1.04063135e+03 -1.10449670e+03 -1.14383936e+03 -1.19743457e+03 -1.24213171e+03 -1.28313367e+03 -1.34815503e+03 -1.38455286e+03 -1.43241101e+03 -1.46697571e+03 -1.49900269e+03 -1.56416553e+03 -1.62390173e+03 -1.67137659e+03 -1.69268201e+03 -1.72577832e+03 -1.80425745e+03 -1.85863733e+03 -1.89986987e+03 -1.96138196e+03 -1.96118896e+03 -1.99543787e+03 -2.11009644e+03 -2.13746411e+03 -2.13090869e+03 -2.23938623e+03 -2.28920630e+03 -2.25168286e+03 -2.34976367e+03 -2.41505396e+03 -2.39432178e+03 -2.49782104e+03 -2.58042114e+03 -2.56187646e+03 -2.59438550e+03 -2.66677881e+03 -2.68502686e+03 -2.74890283e+03 -2.80196729e+03 -2.76923022e+03 -2.84589062e+03 -2.95491089e+03 -3.01425757e+03 -3.05578076e+03 -3.03457959e+03 -3.09233057e+03 -3.11776904e+03 -3.10501514e+03 -3.23122559e+03 -3.29286548e+03 -3.27410059e+03 -3.38702100e+03 -3.40982275e+03 -3.37485498e+03 -3.46380469e+03 -3.53082568e+03 -3.61371924e+03 -3.62491772e+03 -3.59282446e+03 -3.60235107e+03 -3.74315845e+03 -3.87595728e+03 -3.80059351e+03 -3.82734766e+03 -3.81557153e+03 -3.88353613e+03 -4.04313037e+03 -3.94722266e+03 -3.95239697e+03 -4.07632251e+03 -4.16539502e+03 -4.17129785e+03 -4.09247192e+03 -4.20689111e+03 -4.33317236e+03 -4.30688184e+03 -4.35319580e+03 -4.33570020e+03 -4.37177930e+03 -4.48008105e+03 -4.52522656e+03 -4.58744434e+03 -4.54243262e+03 -4.53561084e+03 -4.62447314e+03 -4.66233252e+03 -4.75670166e+03 -4.74436328e+03 -4.69029053e+03 -4.76380859e+03 -4.87802100e+03 -4.92041699e+03 -4.91745508e+03 -4.94184229e+03 -4.96498877e+03 -5.04903564e+03 -5.04670020e+03 -5.01521191e+03 -5.14582031e+03 -5.17096191e+03 -5.13930420e+03 -5.27797314e+03 -5.23223828e+03 -5.19370117e+03 -5.30408594e+03 -5.27758984e+03 -5.29454980e+03 -5.44276904e+03 -5.42492383e+03 -5.33822021e+03 -5.42377246e+03 -5.51518506e+03 -5.52557080e+03 -5.66197852e+03 -5.61818848e+03 -5.56210596e+03 -5.61904736e+03 -5.57577246e+03 -5.67356152e+03 -5.69049512e+03 -5.75721533e+03 -5.87027979e+03 -5.73344775e+03 -5.82147461e+03 -5.86212988e+03 -5.76271631e+03 -5.84875732e+03 -5.96401416e+03 -6.02582031e+03 -5.96292188e+03 -5.94449561e+03 -6.05977588e+03 -6.05763721e+03 -6.03245508e+03 -6.05518408e+03 -6.09140576e+03 -6.20641992e+03 -6.14946143e+03 -6.20553711e+03 -6.28351562e+03 -6.14084180e+03 -6.15640723e+03 -6.37223193e+03 -6.39454346e+03 -6.23679736e+03 -6.30933789e+03 -6.37381494e+03 -6.32451025e+03 -6.51506348e+03 -6.51779102e+03 -6.39299023e+03 -7.13010254e+03 -7.07324219e+03 -6.96645703e+03 -6.39051660e+03 -1.44464072e+04 -1.93686914e+04 -9395441. -29051356. -2.35885625e+06 -9067950. 27270078. -1.42323562e+06 -9259576. 11414557. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6806928. 2.10658975e+06 -2.72596367e+04 -1.31879873e+04 -7.06265723e+03 -8.92518848e+03 -7.31188916e+03 -7.75188672e+03 -7.32764844e+03 -6.84069727e+03 -6.89925293e+03 -7.03330029e+03 -6.87378711e+03 -6.77096045e+03 -6.79596191e+03 -6.86538184e+03 -6.93918457e+03 -6.90156055e+03 -6.79194580e+03 -6.63315137e+03 -6.82250391e+03 -6.87110693e+03 -6.82670166e+03 -6.83601025e+03 -6.64507861e+03 -6.61054004e+03 -6.75605566e+03 -6.77627051e+03 -6.78197363e+03 -6.54208496e+03 -6.53678662e+03 -6.84338623e+03 -6.98304736e+03 -6.72248877e+03 -6.42499121e+03 -6.43903809e+03 -6.64218311e+03 -6.68716797e+03 -6.63871631e+03 -6.46781592e+03 -6.64125977e+03 -6.66970459e+03 -6.61762158e+03 -6.59487646e+03 -6.31652246e+03 -6.44873486e+03 -6.74202246e+03 -6.57959863e+03 -6.53257471e+03 -6.41479688e+03 -6.26709717e+03 -6.36013818e+03 -6.52044727e+03 -6.47058789e+03 -6.24278418e+03 -6.39338037e+03 -6.39127539e+03 -6.34099512e+03 -6.32950830e+03 -6.15754150e+03 -6.23467090e+03 -6.36831787e+03 -6.17469434e+03 -6.08387793e+03 -6.03644189e+03 -6.16178174e+03 -6.36174756e+03 -6.26219092e+03 -6.07485791e+03 -5.96735205e+03 -6.02211475e+03 -5.97274707e+03 -6.04675635e+03 -6.10287646e+03 -5.87455762e+03 -5.87623730e+03 -6.04625586e+03 -5.96018896e+03 -5.84649365e+03 -5.66649805e+03 -5.75499316e+03 -5.93288428e+03 -5.85921387e+03 -5.76165674e+03 -5.60365234e+03 -5.54956494e+03 -5.68971436e+03 -5.77208643e+03 -5.56300879e+03 -5.40510059e+03 -5.60720850e+03 -5.55970117e+03 -5.41981641e+03 -5.57441455e+03 -5.41307764e+03 -5.34264355e+03 -5.43956543e+03 -5.40874805e+03 -5.36675830e+03 -5.18840967e+03 -5.16856836e+03 -5.21591943e+03 -5.28694141e+03 -5.27481885e+03 -5.06567920e+03 -5.08189014e+03 -5.07112354e+03 -5.00470117e+03 -5.02272021e+03 -4.89782227e+03 -4.88761816e+03 -5.00166553e+03 -4.94454248e+03 -4.75624072e+03 -4.60783984e+03 -4.73732617e+03 -4.89986475e+03 -4.83454297e+03 -4.68842236e+03 -4.49166943e+03 -4.47513623e+03 -4.56178809e+03 -4.57418213e+03 -4.56246826e+03 -4.39393652e+03 -4.36642773e+03 -4.34065186e+03 -4.30880518e+03 -4.39150293e+03 -4.21416455e+03 -4.16465723e+03 -4.25780762e+03 -4.16942725e+03 -4.09771631e+03 -4.03007349e+03 -4.03179761e+03 -4.06097632e+03 -3.98806421e+03 -3.86705957e+03 -3.74595947e+03 -3.82594165e+03 -3.91860840e+03 -3.83399731e+03 -3.70455396e+03 -3.58463574e+03 -3.57655469e+03 -3.61381396e+03 -3.61584741e+03 -3.56591187e+03 -3.37574512e+03 -3.31885400e+03 -3.38632251e+03 -3.40034741e+03 -3.39190991e+03 -3.26245996e+03 -3.18314453e+03 -3.14071313e+03 -3.13302734e+03 -3.13311182e+03 -3.01899561e+03 -2.98405322e+03 -2.96261011e+03 -2.93316089e+03 -2.90657324e+03 -2.77676709e+03 -2.79066382e+03 -2.80574731e+03 -2.69137671e+03 -2.67570093e+03 -2.59776343e+03 -2.55057422e+03 -2.55822217e+03 -2.51358447e+03 -2.44181519e+03 -2.32705005e+03 -2.30072095e+03 -2.32347388e+03 -2.32628442e+03 -2.26854590e+03 -2.11063892e+03 -2.03960217e+03 -2.07326660e+03 -2.07427661e+03 -2.00953662e+03 -1.88300085e+03 -1.85634607e+03 -1.85453369e+03 -1.80067920e+03 -1.77482129e+03 -1.68160632e+03 -1.62757349e+03 -1.62834473e+03 -1.59580518e+03 -1.53359448e+03 -1.45576941e+03 -1.41816919e+03 -1.37586877e+03 -1.33265356e+03 -1.31016003e+03 -1.23410522e+03 -1.18372571e+03 -1.14443628e+03 -1.08284558e+03 -1.03495630e+03 -9.93506775e+02 -9.74421753e+02 -9.37094482e+02 -8.76136230e+02 -8.02624207e+02 -7.29029480e+02 -7.10100586e+02 -6.98465088e+02 -6.41603943e+02 -5.76520386e+02 -5.09893372e+02 -4.56503723e+02 -4.27630951e+02 -4.00192657e+02 -3.47004211e+02 -2.87205994e+02 -2.39810104e+02 -1.93845474e+02 -1.46393219e+02 -9.62735977e+01 -4.48738174e+01 3.94737363e+00 5.43541107e+01 1.04137527e+02 1.50159973e+02 1.84911987e+02 2.37747559e+02 2.87649872e+02 3.25450378e+02 3.81798004e+02 4.30776215e+02 4.88644531e+02 5.36887390e+02 5.60213623e+02 6.01634216e+02 6.60068604e+02 7.34770569e+02 8.10223206e+02 8.36450745e+02 8.38957825e+02 8.64436462e+02 9.32799500e+02 1.03091663e+03 1.10405225e+03 1.12277551e+03 1.11425256e+03 1.15917175e+03 1.27506372e+03 1.32661230e+03 1.29677856e+03 1.33831140e+03 1.42674963e+03 1.47355396e+03 1.56469116e+03 1.57757117e+03 1.56252417e+03 1.65834644e+03 1.67379883e+03 1.74114417e+03 1.84394104e+03 1.81102258e+03 1.88809656e+03 1.98667139e+03 1.98809167e+03 2.03070935e+03 2.07411938e+03 2.13733545e+03 2.18858057e+03 2.21325391e+03 2.19226660e+03 2.23617261e+03 2.39960083e+03 2.51022095e+03 2.50008350e+03 2.44018335e+03 2.41892993e+03 2.49669336e+03 2.66394458e+03 2.79697705e+03 2.78984033e+03 2.68223242e+03 2.71288013e+03 2.86617969e+03 2.91334790e+03 2.89561792e+03 2.92846021e+03 2.99931299e+03 3.04956909e+03 3.18193506e+03 3.15431372e+03 3.10645728e+03 3.21642920e+03 3.16217725e+03 3.29584961e+03 3.43888525e+03 3.39276685e+03 3.53218311e+03 3.49099463e+03 3.39194702e+03 3.54386963e+03 3.51160547e+03 3.61182275e+03 3.89668311e+03 3.74348730e+03 3.57003760e+03 3.69999829e+03 3.92216992e+03 4.08674561e+03 4.03995190e+03 3.85999048e+03 3.81838477e+03 3.91192554e+03 4.12187842e+03 4.33771875e+03 4.27136182e+03 4.08245361e+03 4.08845312e+03 4.29473291e+03 4.38093604e+03 4.28904688e+03 4.31119189e+03 4.39755322e+03 4.43644971e+03 4.62336279e+03 4.66611572e+03 4.44284814e+03 4.47652881e+03 4.59771045e+03 4.64248584e+03 4.70602979e+03 4.73120557e+03 4.87369189e+03 4.81837842e+03 4.69689551e+03 4.86003564e+03 4.77512158e+03 4.91973975e+03 5.28024658e+03 5.00525537e+03 4.72716553e+03 4.91177979e+03 5.20882568e+03 5.37297266e+03 5.36404395e+03 5.11468213e+03 4.93631836e+03 5.09472705e+03 5.41005957e+03 5.64161182e+03 5.49819922e+03 5.24627441e+03 5.22132471e+03 5.39841211e+03 5.51719531e+03 5.66124805e+03 5.66906299e+03 5.42014355e+03 5.41775342e+03 5.66885840e+03 5.74092920e+03 5.65973877e+03 5.65533643e+03 5.63462061e+03 5.65486377e+03 5.90362061e+03 5.98417285e+03 5.78742969e+03 5.74850195e+03 5.74755957e+03 5.79496729e+03 5.93700391e+03 5.95871436e+03 6.11220361e+03 6.13968555e+03 5.93396045e+03 5.88022656e+03 5.80727539e+03 6.09598047e+03 6.42140967e+03 6.30454785e+03 5.98905273e+03 5.87805518e+03 6.15278711e+03 6.50717139e+03 6.25510352e+03 5.94987500e+03 6.11620703e+03 6.32705371e+03 6.44185547e+03 6.67024219e+03 6.50756006e+03 6.18178662e+03 6.10655029e+03 6.35252930e+03 6.46056006e+03 6.49500977e+03 6.47952441e+03 6.46266113e+03 6.43524951e+03 6.56895068e+03 6.52805420e+03 6.31495508e+03 6.41925879e+03 6.45969092e+03 6.73175244e+03 6.75009375e+03 6.56979932e+03 6.66922412e+03 6.63841699e+03 6.65456982e+03 6.56954785e+03 6.36846289e+03 6.70716260e+03 6.99458545e+03 6.77804590e+03 6.48660449e+03 6.53819434e+03 6.86423291e+03 6.96852002e+03 6.87990674e+03 6.75279297e+03 6.57243311e+03 6.62195654e+03 6.84496338e+03 6.85091309e+03 6.73342773e+03 6.58292871e+03 6.55246484e+03 6.96151123e+03 7.22586670e+03 6.81546240e+03 6.60048486e+03 6.81236914e+03 6.82819678e+03 7.01210791e+03 7.01884033e+03 6.59626172e+03 6.67062598e+03 6.84807959e+03 6.87690820e+03 6.99014893e+03 7.06102783e+03 7.18118604e+03 6.99222949e+03 6.80294336e+03 6.83085498e+03 7.85215723e+03 1.32007363e+04 2.17063594e+04 -3.74247450e+06 -1.92411225e+06 -10643127. -1.67169725e+06 -21806334. 21553496. 3627887. -2.40186875e+06 1.51527612e+06 3.78810925e+06 7.84434350e+06 -26928992. 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. 0. 0. 0. 0. 0. 0. 50713344. -4564874. 2.49077188e+04 1.79988711e+04 1.13084893e+04 8.24545117e+03 8.33322852e+03 6.77592529e+03 6.43435156e+03 6.63475000e+03 6.45355469e+03 6.19554688e+03 6.38842578e+03 6.34372168e+03 6.24223828e+03 6.22009033e+03 6.20471680e+03 6.14593457e+03 6.11177881e+03 6.06333838e+03 6.01876025e+03 6.01980762e+03 5.96247412e+03 6.03505566e+03 6.05143750e+03 5.79208545e+03 5.78165332e+03 6.07945020e+03 6.06202197e+03 5.86889062e+03 5.83027686e+03 5.79931836e+03 5.78184766e+03 5.77508740e+03 5.74144873e+03 5.70318262e+03 5.68058105e+03 5.58677051e+03 5.53456299e+03 5.69091455e+03 5.70435352e+03 5.53683936e+03 5.50761279e+03 5.51082666e+03 5.49175439e+03 5.41744629e+03 5.38094678e+03 5.39878857e+03 5.25318408e+03 5.18021826e+03 5.22508789e+03 5.20922705e+03 5.37061865e+03 5.36261768e+03 5.14113184e+03 4.99604199e+03 4.93902002e+03 5.20169629e+03 5.21871973e+03 4.98762305e+03 4.85549121e+03 4.81660449e+03 4.91520654e+03 4.87802441e+03 4.93788086e+03 4.91528320e+03 4.62563232e+03 4.48901660e+03 4.70875586e+03 4.87881201e+03 4.70835303e+03 4.57839014e+03 4.53374219e+03 4.48553271e+03 4.45595117e+03 4.43483887e+03 4.37436377e+03 4.32161914e+03 4.32243701e+03 4.30247363e+03 4.23212012e+03 4.18794385e+03 4.27839600e+03 4.26173340e+03 4.11052344e+03 4.03044629e+03 3.99415747e+03 4.04924512e+03 4.00745239e+03 3.90867749e+03 3.88451270e+03 3.75386694e+03 3.65028589e+03 3.78326782e+03 3.73545312e+03 3.51929199e+03 3.52719092e+03 3.68087231e+03 3.77087158e+03 3.60685645e+03 3.44597192e+03 3.38188013e+03 3.34689746e+03 3.32414185e+03 3.27580688e+03 3.24179541e+03 3.18678223e+03 3.25513965e+03 3.21750806e+03 3.07318970e+03 3.03133936e+03 2.90683472e+03 2.89536865e+03 3.02066821e+03 2.94378784e+03 2.83554443e+03 2.73414014e+03 2.64553101e+03 2.74156396e+03 2.75243604e+03 2.62878662e+03 2.51270728e+03 2.46138867e+03 2.47385889e+03 2.42360791e+03 2.45942212e+03 2.43528271e+03 2.30284033e+03 2.22825928e+03 2.18163501e+03 2.18238916e+03 2.14418799e+03 2.07245508e+03 2.01888879e+03 1.97922253e+03 1.92397229e+03 1.82895032e+03 1.80842126e+03 1.85590906e+03 1.79788855e+03 1.70865417e+03 1.61672351e+03 1.56432056e+03 1.60641223e+03 1.56221631e+03 1.47293774e+03 1.39138562e+03 1.34049072e+03 1.33562170e+03 1.27995764e+03 1.23302966e+03 1.15885376e+03 1.13595190e+03 1.15491150e+03 1.07905139e+03 1.00117065e+03 9.55104126e+02 9.13662964e+02 8.59547607e+02 8.09727905e+02 7.59174927e+02 7.09245605e+02 6.60567932e+02 5.95173706e+02 5.57986755e+02 5.43659424e+02 4.76231720e+02 4.14320648e+02 3.78136292e+02 3.30185974e+02 2.92444031e+02 2.39881348e+02 1.83714294e+02 1.42750885e+02 9.57952118e+01 4.67554207e+01 1.71812987e+00 -4.37180786e+01 -9.02589340e+01 -1.38159348e+02 -1.85999664e+02 -2.30338531e+02 -2.89560577e+02 -3.55201080e+02 -3.94812622e+02 -4.32791534e+02 -4.67871368e+02 -5.11866150e+02 -5.90286865e+02 -6.42892334e+02 -6.72688721e+02 -7.00202454e+02 -7.42638123e+02 -8.14219788e+02 -8.62481262e+02 -9.28927856e+02 -9.66059937e+02 -9.85745056e+02 -1.04504224e+03 -1.08885510e+03 -1.17072510e+03 -1.21465784e+03 -1.22173181e+03 -1.27971460e+03 -1.32753369e+03 -1.36407190e+03 -1.37333704e+03 -1.45133069e+03 -1.58917847e+03 -1.61185474e+03 -1.61384998e+03 -1.61872290e+03 -1.65061023e+03 -1.79432275e+03 -1.85480249e+03 -1.84817334e+03 -1.84517944e+03 -1.88094543e+03 -1.99321326e+03 -2.03590906e+03 -2.12217920e+03 -2.16355981e+03 -2.15038477e+03 -2.17794263e+03 -2.21178955e+03 -2.35601050e+03 -2.40041162e+03 -2.37589185e+03 -2.40105542e+03 -2.43736108e+03 -2.56952710e+03 -2.61931055e+03 -2.54210107e+03 -2.58844897e+03 -2.77116187e+03 -2.81386523e+03 -2.72530835e+03 -2.75332104e+03 -2.93554565e+03 -3.00872485e+03 -2.95654712e+03 -2.92393848e+03 -2.97346606e+03 -3.17826123e+03 -3.17679224e+03 -3.12559399e+03 -3.23913208e+03 -3.27561108e+03 -3.26915771e+03 -3.30147607e+03 -3.35921021e+03 -3.32621094e+03 -3.45356543e+03 -3.68938013e+03 -3.62428809e+03 -3.61120874e+03 -3.65771899e+03 -3.68133716e+03 -3.72211792e+03 -3.74337646e+03 -3.78545483e+03 -3.75653955e+03 -3.73633765e+03 -3.86997485e+03 -3.99890283e+03 -4.14316699e+03 -4.03874194e+03 -3.92988403e+03 -4.08447754e+03 -4.17494678e+03 -4.34705811e+03 -4.33744727e+03 -4.24913818e+03 -4.20589062e+03 -4.19882129e+03 -4.37049707e+03 -4.41688477e+03 -4.53058984e+03 -4.60736279e+03 -4.52266748e+03 -4.46304053e+03 -4.38866553e+03 -4.58064209e+03 -4.87510059e+03 -4.85205811e+03 -4.75747314e+03 -4.65791016e+03 -4.61915820e+03 -4.87635645e+03 -5.04463232e+03 -4.96057178e+03 -4.81813574e+03 -4.83570264e+03 -4.97390820e+03 -5.03135107e+03 -5.20791357e+03 -5.23800195e+03 -5.12688916e+03 -5.08930322e+03 -5.08553662e+03 -5.30043652e+03 -5.35709473e+03 -5.14930322e+03 -5.16692090e+03 -5.48695557e+03 -5.46869824e+03 -5.21494043e+03 -5.33669824e+03 -5.64936768e+03 -5.63482471e+03 -5.53293799e+03 -5.40460205e+03 -5.43328467e+03 -5.77077881e+03 -5.80319971e+03 -5.67145850e+03 -5.55758447e+03 -5.51989062e+03 -5.67892236e+03 -5.76374707e+03 -5.82624854e+03 -5.65802246e+03 -5.82124121e+03 -6.14281836e+03 -6.00114307e+03 -5.95916992e+03 -6.01772949e+03 -5.97595947e+03 -5.98757764e+03 -6.00519189e+03 -6.05177002e+03 -6.02530859e+03 -5.95603125e+03 -5.86918555e+03 -6.07045312e+03 -6.36610303e+03 -6.15074707e+03 -5.96315137e+03 -6.18629639e+03 -6.25693359e+03 -6.46447949e+03 -6.42473096e+03 -6.22033154e+03 -6.38177637e+03 -6.39181396e+03 -6.20531348e+03 -6.22544580e+03 -6.50910107e+03 -6.50732861e+03 -6.38462500e+03 -6.27208789e+03 -6.09804688e+03 -6.40157373e+03 -6.86627930e+03 -6.67718799e+03 -6.46542188e+03 -6.35715771e+03 -6.34386426e+03 -6.70308008e+03 -6.80368604e+03 -6.64920020e+03 -6.45872607e+03 -6.44400195e+03 -6.56751562e+03 -6.59379199e+03 -6.81181055e+03 -6.81547314e+03 -6.60342188e+03 -6.60809619e+03 -6.62470557e+03 -6.79122656e+03 -6.84011426e+03 -6.71539160e+03 -6.67329102e+03 -6.64748242e+03 -6.72518311e+03 -6.57410254e+03 -6.64385449e+03 -6.98632910e+03 -6.89621582e+03 -6.83636426e+03 -6.67534912e+03 -6.58808594e+03 -7.04598389e+03 -7.01220264e+03 -6.80170361e+03 -6.71537891e+03 -6.67134863e+03 -6.76103564e+03 -6.73976660e+03 -6.84763232e+03 -6.70002100e+03 -6.84792822e+03 -7.13306152e+03 -6.88013623e+03 -6.93637158e+03 -7.02462549e+03 -6.87616064e+03 -6.78551709e+03 -6.76990771e+03 -6.82161230e+03 -6.84793506e+03 -6.82932178e+03 -6.82358887e+03 -6.89800781e+03 -6.96491113e+03 -6.67973535e+03 -6.56509424e+03 -6.77071094e+03 -6.90925146e+03 -7.08020361e+03 -6.94290332e+03 -6.70721289e+03 -6.93936426e+03 -6.88087988e+03 -6.75994434e+03 -6.83339502e+03 -6.81412549e+03 -6.75661670e+03 -6.69113086e+03 -6.76300293e+03 -6.66064062e+03 -6.71889697e+03 -7.00961279e+03 -6.92573730e+03 -6.81772852e+03 -6.64462061e+03 -6.52308301e+03 -6.89717432e+03 -6.91108252e+03 -6.73512939e+03 -6.54522998e+03 -6.43655957e+03 -6.62721875e+03 -6.70991895e+03 -6.94180664e+03 -6.72237500e+03 -6.49401758e+03 -6.60544678e+03 -6.55985303e+03 -6.74086523e+03 -6.70889502e+03 -6.50370850e+03 -6.48966162e+03 -6.49863672e+03 -6.50431738e+03 -6.34680762e+03 -6.45445947e+03 -6.78102979e+03 -6.63033984e+03 -6.52398340e+03 -6.32599365e+03 -6.20973389e+03 -6.59496387e+03 -6.56187500e+03 -6.34880615e+03 -6.21494141e+03 -6.15655322e+03 -6.28821875e+03 -6.29851123e+03 -6.47985156e+03 -6.44161572e+03 -6.23501758e+03 -6.09816992e+03 -6.03881543e+03 -6.38370068e+03 -6.31279150e+03 -6.07748340e+03 -6.12683936e+03 -6.10777783e+03 -6.02096631e+03 -5.96848242e+03 -6.13454590e+03 -5.95372461e+03 -5.80081445e+03 -6.12813574e+03 -6.15963818e+03 -5.91142773e+03 -5.86026123e+03 -5.83945264e+03 -5.86543359e+03 -5.66287354e+03 -5.58634814e+03 -5.91300635e+03 -5.90124121e+03 -5.52251807e+03 -5.41482715e+03 -5.69942334e+03 -5.90505078e+03 -5.72475635e+03 -5.49279590e+03 -5.43592822e+03 -5.62034033e+03 -5.56722607e+03 -5.41522217e+03 -5.47225830e+03 -5.29904980e+03 -5.12201562e+03 -5.34039062e+03 -5.52073779e+03 -5.44925537e+03 -5.20151318e+03 -5.04577734e+03 -5.27963574e+03 -5.37316895e+03 -5.16173730e+03 -4.99565820e+03 -4.97831787e+03 -4.99268262e+03 -4.95978320e+03 -5.10452881e+03 -4.98476318e+03 -4.78930078e+03 -4.86485547e+03 -4.84156006e+03 -4.88039551e+03 -4.73050293e+03 -4.60222314e+03 -4.76054199e+03 -4.73289209e+03 -4.63331689e+03 -4.48772754e+03 -4.46510986e+03 -4.69827686e+03 -4.50110400e+03 -4.32225830e+03 -4.40051318e+03 -4.35920996e+03 -4.33683350e+03 -4.30076611e+03 -4.36079883e+03 -4.35031641e+03 -4.18658936e+03 -4.03122534e+03 -3.98434155e+03 -4.17025830e+03 -4.07728442e+03 -3.91957690e+03 -3.94384058e+03 -3.91811841e+03 -3.88881372e+03 -3.83721606e+03 -3.86421582e+03 -3.72455029e+03 -3.59739038e+03 -3.72672144e+03 -3.69671118e+03 -3.60622754e+03 -3.58118872e+03 -3.52081128e+03 -3.47283203e+03 -3.34369897e+03 -3.26557300e+03 -3.39491455e+03 -3.42594360e+03 -3.22792188e+03 -3.09103247e+03 -3.19240771e+03 -3.27413013e+03 -3.14400293e+03 -2.98366187e+03 -2.90244922e+03 -2.99174365e+03 -2.97849146e+03 -2.85599023e+03 -2.87700732e+03 -2.83740601e+03 -2.70856201e+03 -2.65461670e+03 -2.69207373e+03 -2.69203662e+03 -2.52329175e+03 -2.43427124e+03 -2.52571704e+03 -2.53259741e+03 -2.40807861e+03 -2.28010498e+03 -2.21834790e+03 -2.29718433e+03 -2.28483228e+03 -2.15075220e+03 -2.08791699e+03 -2.06341333e+03 -2.00948401e+03 -1.94815002e+03 -1.98064868e+03 -1.89377966e+03 -1.78102771e+03 -1.82358655e+03 -1.79389697e+03 -1.72415906e+03 -1.63976672e+03 -1.56809265e+03 -1.62440637e+03 -1.62691187e+03 -1.49240869e+03 -1.42562183e+03 -1.67828564e+03 -2.27819531e+03 -3.03817114e+03 3.31793938e+05 2.59283484e+05 -4.23522607e+03 -2.59360913e+03 -1.58686768e+03 -1.92127588e+03 -2.11044482e+03 -2.10051978e+03 1.61169172e+05 1.73862425e+06 3.16963156e+05 -263028352. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.28936320e+09 -4.28936320e+09 -2144681600. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.26456832e+09 -1.45109719e+05 -1.87298219e+05 6.80387812e+05 3.00344580e+03 1.66427832e+03 1.13292175e+03 1.23405432e+03 6.99323486e+02 9.96587036e+02 1.01678400e+03 1.01974744e+03 1.08853101e+03 1.11032617e+03 1.15189343e+03 1.21571399e+03 1.23476379e+03 1.27737549e+03 1.32816870e+03 1.35184326e+03 1.42801270e+03 1.51638062e+03 1.55939929e+03 1.55430481e+03 1.58694336e+03 1.65311548e+03 1.66096411e+03 1.72381104e+03 1.82759045e+03 1.85215417e+03 1.90143994e+03 1.96218005e+03 1.96302405e+03 1.99714172e+03 2.06175098e+03 2.09343042e+03 2.12435767e+03 2.22837036e+03 2.31905347e+03 2.30034277e+03 2.32110645e+03 2.38928369e+03 2.44423267e+03 2.50166699e+03 2.51534546e+03 2.50196265e+03 2.61645361e+03 2.72455029e+03 2.68226416e+03 2.71328491e+03 2.79722778e+03 2.78816992e+03 2.84643237e+03 2.96880347e+03 2.97780859e+03 2.98089355e+03 3.06785840e+03 3.19084082e+03 3.15991333e+03 3.09885156e+03 3.14121509e+03 3.20437549e+03 3.35118506e+03 3.44673169e+03 3.39613599e+03 3.40356519e+03 3.44056030e+03 3.47916406e+03 3.52919067e+03 3.56270923e+03 3.57414453e+03 3.66970239e+03 3.81552759e+03 3.78384351e+03 3.74835645e+03 3.85483081e+03 3.88896362e+03 3.89937793e+03 3.96955713e+03 4.01595972e+03 4.01940942e+03 4.02161523e+03 4.13956885e+03 4.16332812e+03 4.19717090e+03 4.24476367e+03 4.17017334e+03 4.28919287e+03 4.44297119e+03 4.37529346e+03 4.37184619e+03 4.44845361e+03 4.46481689e+03 4.51981982e+03 4.53926465e+03 4.50912598e+03 4.63826172e+03 4.79981055e+03 4.74876953e+03 4.64275195e+03 4.69656934e+03 4.85668262e+03 4.87722461e+03 4.85071045e+03 4.87301123e+03 4.86673926e+03 5.01791602e+03 5.17852490e+03 5.03445068e+03 4.95834229e+03 4.99826562e+03 5.07306299e+03 5.18670068e+03 5.26883838e+03 5.22262549e+03 5.23192041e+03 5.41577246e+03 5.43514600e+03 5.32821777e+03 5.25731055e+03 5.29199951e+03 5.43895947e+03 5.54381152e+03 5.57988916e+03 5.52602295e+03 5.56654248e+03 5.63440430e+03 5.53842676e+03 5.53828223e+03 5.62548340e+03 5.64294971e+03 5.76620312e+03 5.87159131e+03 5.69820312e+03 5.69372900e+03 5.88339355e+03 5.87285010e+03 5.74654590e+03 5.84964795e+03 6.03736426e+03 6.03060107e+03 5.99423682e+03 5.98703516e+03 5.97435840e+03 6.00948291e+03 5.96802539e+03 6.03470166e+03 6.11169141e+03 6.12143457e+03 6.16738525e+03 6.22042773e+03 6.23140576e+03 6.03559131e+03 6.14609961e+03 6.32455371e+03 6.26947510e+03 6.35587158e+03 6.46995996e+03 6.41212451e+03 6.27674023e+03 6.31163916e+03 6.28431982e+03 6.26263818e+03 6.39820752e+03 6.50592822e+03 6.47546826e+03 6.44459229e+03 6.43787012e+03 6.41654883e+03 6.44638184e+03 6.45171631e+03 6.46068311e+03 6.55475586e+03 6.64247119e+03 6.56424512e+03 6.54509521e+03 6.58163623e+03 6.63254443e+03 6.63069873e+03 6.62004590e+03 6.63136963e+03 6.70113721e+03 6.68285449e+03 6.67305615e+03 6.66293652e+03 6.74269434e+03 6.82749561e+03 6.58089551e+03 6.60631641e+03 6.84591064e+03 6.74963672e+03 6.78175146e+03 6.80767383e+03 6.68909717e+03 6.69192285e+03 6.75657373e+03 6.69937451e+03 6.69027295e+03 6.79175879e+03 6.91859180e+03 6.97879980e+03 6.88295166e+03 6.82397754e+03 6.81918359e+03 6.74587109e+03 6.74476123e+03 6.77051123e+03 6.88198584e+03 7.03351807e+03 6.82457568e+03 6.71313281e+03 6.87744727e+03 6.74003516e+03 6.83311768e+03 6.97205957e+03 6.80846680e+03 6.82592725e+03 6.85261914e+03 6.90538135e+03 6.88559082e+03 6.80181201e+03 6.75304785e+03 6.72191064e+03 6.79523584e+03 6.87575684e+03 6.88452832e+03 6.86059570e+03 6.86496777e+03 6.87173828e+03 6.82898926e+03 6.87927051e+03 6.88968018e+03 6.75621826e+03 6.67506006e+03 6.75613818e+03 6.80699756e+03 6.81487256e+03 6.76079834e+03 6.74567383e+03 6.75633057e+03 6.72169336e+03 6.77229932e+03 6.77058740e+03 6.84612012e+03 6.80637744e+03 6.55663965e+03 6.65505371e+03 6.66666357e+03 6.65281543e+03 6.73519971e+03 6.58224658e+03 6.51621582e+03 6.74198340e+03 6.73911084e+03 6.46924561e+03 6.44585400e+03 6.63902783e+03 6.64764160e+03 6.48573340e+03 6.53925146e+03 6.64574561e+03 6.44846045e+03 6.42960400e+03 6.47271826e+03 6.35674707e+03 6.43606885e+03 6.50487793e+03 6.31810596e+03 6.41477490e+03 6.51114404e+03 6.40702197e+03 6.27859033e+03 6.16605029e+03 6.31172803e+03 6.40289355e+03 6.22005225e+03 6.14956934e+03 6.22536621e+03 6.21042822e+03 6.14307959e+03 6.13746582e+03 6.15651562e+03 6.12390088e+03 6.04763086e+03 6.08502002e+03 6.15792920e+03 6.01871387e+03 5.96385254e+03 6.00725000e+03 5.84319678e+03 5.97937109e+03 6.02223877e+03 5.78966064e+03 5.87841748e+03 5.85299805e+03 5.73048242e+03 5.81004053e+03 5.75994189e+03 5.74982812e+03 5.82877490e+03 5.68963379e+03 5.63568115e+03 5.57922119e+03 5.51014795e+03 5.52365479e+03 5.51814648e+03 5.55531934e+03 5.56473730e+03 5.49033447e+03 5.45847217e+03 5.48315820e+03 5.38904053e+03 5.26556885e+03 5.24738086e+03 5.32925830e+03 5.35705908e+03 5.14551562e+03 5.04486035e+03 5.15263135e+03 5.21118555e+03 5.09541846e+03 5.01891992e+03 5.01056982e+03 4.98921973e+03 5.04598682e+03 4.97758838e+03 4.87462451e+03 4.75327588e+03 4.75642676e+03 4.80543115e+03 4.74148828e+03 4.75453857e+03 4.76003857e+03 4.66163525e+03 4.62727930e+03 4.68712500e+03 4.58581250e+03 4.46949658e+03 4.48854248e+03 4.51770166e+03 4.42475293e+03 4.26883350e+03 4.22251660e+03 4.29042529e+03 4.32325488e+03 4.24887061e+03 4.16040674e+03 4.12005176e+03 4.15815918e+03 4.10606836e+03 3.94761865e+03 3.93743823e+03 3.95044214e+03 3.96978687e+03 3.88124829e+03 3.73395703e+03 3.75449878e+03 3.75946729e+03 3.75494092e+03 3.75512891e+03 3.68175684e+03 3.55241382e+03 3.44456201e+03 3.49886108e+03 3.56558984e+03 3.45127783e+03 3.34294189e+03 3.28938550e+03 3.29557764e+03 3.32480786e+03 3.20532959e+03 3.13859961e+03 3.13181714e+03 3.14047485e+03 3.11229224e+03 2.94845532e+03 2.95428369e+03 2.95033130e+03 2.85222583e+03 2.84072925e+03 2.77030005e+03 2.71474927e+03 2.68612061e+03 2.63831445e+03 2.61056226e+03 2.59210400e+03 2.54670215e+03 2.44878833e+03 2.42722559e+03 2.41988965e+03 2.35321899e+03 2.28766797e+03 2.19174121e+03 2.18527344e+03 2.21996167e+03 2.14124121e+03 2.05976099e+03 1.98173267e+03 1.96234985e+03 1.98286743e+03 1.89869800e+03 1.83586548e+03 1.81857007e+03 1.75360437e+03 1.66490283e+03 1.64061121e+03 1.62523914e+03 1.56092151e+03 1.52802527e+03 1.46396729e+03 1.37942493e+03 1.37192468e+03 1.34478345e+03 1.28829993e+03 1.25771753e+03 1.19822717e+03 1.14637476e+03 1.08545312e+03 1.03405444e+03 1.00968414e+03 9.60201538e+02 9.00271179e+02 8.44970032e+02 8.08372803e+02 7.54407166e+02 7.06690979e+02 6.84999817e+02 6.32177917e+02 5.70511414e+02 5.17715515e+02 4.65826965e+02 4.21628052e+02 3.87264587e+02 3.41847229e+02 2.79496796e+02 2.25316223e+02 1.80747131e+02 1.40373154e+02 9.67607880e+01 4.92750130e+01 -4.00399351e+00 -5.15594635e+01 -9.52132034e+01 -1.38810715e+02 -1.86922729e+02 -2.37034470e+02 -2.88128052e+02 -3.28196014e+02 -3.68972046e+02 -4.31550110e+02 -4.88213593e+02 -5.29595520e+02 -5.66849731e+02 -6.13647095e+02 -6.77591492e+02 -7.34172485e+02 -7.70296753e+02 -8.03769104e+02 -8.50095398e+02 -9.09778931e+02 -9.64915039e+02 -1.00758759e+03 -1.04973096e+03 -1.08018823e+03 -1.13570654e+03 -1.20288293e+03 -1.23895081e+03 -1.28823120e+03 -1.33338232e+03 -1.37708496e+03 -1.42843689e+03 -1.47317029e+03 -1.49103638e+03 -1.54073938e+03 -1.62278662e+03 -1.67876013e+03 -1.72862598e+03 -1.74080444e+03 -1.78499951e+03 -1.82541003e+03 -1.88279321e+03 -1.97630298e+03 -1.97040063e+03 -2.01017419e+03 -2.10712476e+03 -2.09708350e+03 -2.12935205e+03 -2.23474365e+03 -2.27401782e+03 -2.30193726e+03 -2.37566846e+03 -2.37075439e+03 -2.35504053e+03 -2.48393994e+03 -2.56980078e+03 -2.55917456e+03 -2.65156665e+03 -2.69743237e+03 -2.64348218e+03 -2.71051733e+03 -2.77811499e+03 -2.80786890e+03 -2.90649976e+03 -2.94574731e+03 -2.96438403e+03 -3.02378833e+03 -3.06287183e+03 -3.12131104e+03 -3.12238135e+03 -3.12905176e+03 -3.21399219e+03 -3.27241821e+03 -3.27258618e+03 -3.32815747e+03 -3.40563452e+03 -3.40021069e+03 -3.48117212e+03 -3.53823730e+03 -3.56285669e+03 -3.62728857e+03 -3.56399316e+03 -3.63174536e+03 -3.79478149e+03 -3.79062231e+03 -3.79017627e+03 -3.85930566e+03 -3.89148755e+03 -3.92420728e+03 -3.97219116e+03 -3.87947827e+03 -3.91901807e+03 -4.11057422e+03 -4.19552588e+03 -4.20725537e+03 -4.12831738e+03 -4.14984570e+03 -4.31123682e+03 -4.31700342e+03 -4.30083496e+03 -4.36891797e+03 -4.39135107e+03 -4.43812158e+03 -4.50496387e+03 -4.58729248e+03 -4.56643555e+03 -4.52267871e+03 -4.69363135e+03 -4.67208838e+03 -4.63888232e+03 -4.70390674e+03 -4.68883057e+03 -4.79950098e+03 -4.94401758e+03 -4.94012891e+03 -4.83811377e+03 -4.86597949e+03 -4.99448242e+03 -5.05574268e+03 -5.07274316e+03 -5.03632861e+03 -5.12468799e+03 -5.17551367e+03 -5.17735303e+03 -5.23926562e+03 -5.24107715e+03 -5.26898340e+03 -5.33438916e+03 -5.17650439e+03 -5.20919189e+03 -5.47999365e+03 -5.46731982e+03 -5.42429346e+03 -5.43860791e+03 -5.41405664e+03 -5.43589307e+03 -5.63949609e+03 -5.70712354e+03 -5.59722949e+03 -5.56847803e+03 -5.56317285e+03 -5.64367627e+03 -5.76011133e+03 -5.79279980e+03 -5.82419775e+03 -5.76677637e+03 -5.83193701e+03 -5.83628906e+03 -5.74922363e+03 -5.81257227e+03 -5.97911377e+03 -6.01953125e+03 -5.94620508e+03 -5.95793066e+03 -6.00136279e+03 -6.02810352e+03 -5.98097559e+03 -6.09817139e+03 -6.12591553e+03 -6.11032471e+03 -6.12369824e+03 -6.12748096e+03 -6.33448096e+03 -6.18764160e+03 -6.15534717e+03 -6.33699414e+03 -6.21943213e+03 -6.19356982e+03 -6.33515869e+03 -6.39074609e+03 -6.30925000e+03 -6.52120215e+03 -6.60744287e+03 -6.47785889e+03 -6.97938770e+03 -6.77784814e+03 -8.05205713e+03 -8.72277148e+03 -9.67110449e+03 -9.56609668e+03 -9.76712207e+03 -1.01217881e+04 -1.08767119e+04 -9.59608789e+03 -1.72946758e+04 -2.92452227e+04 -9259576. 11414557. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6806928. 2.10658975e+06 -12905183. 3.29227225e+06 -2.20531191e+04 -1.58378467e+04 -1.03262588e+04 -8.43916992e+03 -7.44614844e+03 -6.96457520e+03 -6.97831787e+03 -7.06025146e+03 -6.84805371e+03 -6.78578906e+03 -6.85272705e+03 -6.80123047e+03 -6.91838574e+03 -6.90949512e+03 -6.74985791e+03 -6.66934570e+03 -6.82517871e+03 -6.86624463e+03 -6.81750342e+03 -6.82843848e+03 -6.61194336e+03 -6.60713477e+03 -6.92670020e+03 -6.76576025e+03 -6.58624023e+03 -6.50583154e+03 -6.64112012e+03 -6.89313477e+03 -6.93958398e+03 -6.69873096e+03 -6.43377539e+03 -6.47602881e+03 -6.65868164e+03 -6.67000293e+03 -6.63284521e+03 -6.54991748e+03 -6.58098682e+03 -6.62402539e+03 -6.62929980e+03 -6.60275830e+03 -6.36010986e+03 -6.44059668e+03 -6.84789453e+03 -6.51241064e+03 -6.32206641e+03 -6.37051660e+03 -6.31665430e+03 -6.57240869e+03 -6.56846484e+03 -6.32477783e+03 -6.24931348e+03 -6.40283398e+03 -6.52952783e+03 -6.34053369e+03 -6.25926172e+03 -6.12982666e+03 -6.25656787e+03 -6.40681641e+03 -6.18067480e+03 -6.19025977e+03 -6.12020508e+03 -6.06284717e+03 -6.23892334e+03 -6.24226758e+03 -6.10534375e+03 -5.98591699e+03 -6.07389209e+03 -6.09610791e+03 -6.02884229e+03 -6.05345410e+03 -5.81264111e+03 -5.81721680e+03 -6.11708496e+03 -5.91895215e+03 -5.66922607e+03 -5.61722949e+03 -5.84586865e+03 -6.03067188e+03 -5.82038525e+03 -5.74501025e+03 -5.64107568e+03 -5.50654150e+03 -5.62987207e+03 -5.75473828e+03 -5.60223584e+03 -5.43828711e+03 -5.56481152e+03 -5.54272070e+03 -5.47370215e+03 -5.59206006e+03 -5.35920312e+03 -5.30398145e+03 -5.53273096e+03 -5.38891406e+03 -5.24392871e+03 -5.19050732e+03 -5.14749268e+03 -5.30072607e+03 -5.30270654e+03 -5.10245361e+03 -5.02439844e+03 -5.13018408e+03 -5.13580762e+03 -5.02207812e+03 -5.03491357e+03 -4.94401123e+03 -4.86275244e+03 -4.98737744e+03 -4.91487109e+03 -4.74146191e+03 -4.66779736e+03 -4.71426758e+03 -4.84104346e+03 -4.82831934e+03 -4.69383691e+03 -4.49852246e+03 -4.42913574e+03 -4.62888379e+03 -4.60063281e+03 -4.44211377e+03 -4.35296826e+03 -4.38243115e+03 -4.43677100e+03 -4.31603418e+03 -4.26441699e+03 -4.17363818e+03 -4.20995410e+03 -4.30880908e+03 -4.15801953e+03 -4.09363525e+03 -4.06653149e+03 -3.97250391e+03 -4.01127075e+03 -3.98118213e+03 -3.88789429e+03 -3.80855103e+03 -3.80134277e+03 -3.87134741e+03 -3.81698291e+03 -3.74017993e+03 -3.61473267e+03 -3.55669360e+03 -3.65135449e+03 -3.63692822e+03 -3.53214966e+03 -3.39332788e+03 -3.32106787e+03 -3.39888110e+03 -3.41899609e+03 -3.32939819e+03 -3.21133423e+03 -3.17246362e+03 -3.16273730e+03 -3.15528760e+03 -3.15967651e+03 -3.03348169e+03 -2.96816016e+03 -2.99442725e+03 -2.93125854e+03 -2.85717065e+03 -2.79788354e+03 -2.79991821e+03 -2.77419556e+03 -2.67803369e+03 -2.62265015e+03 -2.56243970e+03 -2.56698096e+03 -2.61319604e+03 -2.51442529e+03 -2.37584277e+03 -2.32163330e+03 -2.32544678e+03 -2.34042334e+03 -2.31591699e+03 -2.26934473e+03 -2.13162793e+03 -2.01662231e+03 -2.05172363e+03 -2.08385352e+03 -2.02726257e+03 -1.90115381e+03 -1.84247681e+03 -1.84584119e+03 -1.81617859e+03 -1.78465784e+03 -1.70741003e+03 -1.64937439e+03 -1.62573267e+03 -1.56836670e+03 -1.51346643e+03 -1.46150159e+03 -1.41677515e+03 -1.40018530e+03 -1.33743213e+03 -1.27275171e+03 -1.22011755e+03 -1.18861145e+03 -1.15865186e+03 -1.09119910e+03 -1.04015393e+03 -9.88468262e+02 -9.69221863e+02 -9.40543884e+02 -8.65147583e+02 -8.04494446e+02 -7.46227600e+02 -7.04826782e+02 -6.87088562e+02 -6.39105408e+02 -5.80478088e+02 -5.14886230e+02 -4.65103973e+02 -4.44749023e+02 -4.00958527e+02 -3.36307007e+02 -2.87115143e+02 -2.45058502e+02 -1.94987457e+02 -1.41559967e+02 -8.84474869e+01 -3.91951599e+01 8.20446110e+00 5.35243645e+01 1.01755135e+02 1.43806030e+02 1.80741074e+02 2.36822479e+02 2.92997009e+02 3.40376221e+02 3.88139923e+02 4.28286621e+02 4.89454193e+02 5.36475830e+02 5.54824951e+02 5.96217224e+02 6.57164612e+02 7.35535889e+02 8.12223328e+02 8.38451965e+02 8.38963379e+02 8.62230713e+02 9.28910217e+02 1.03025403e+03 1.11482483e+03 1.13007410e+03 1.11177515e+03 1.15561633e+03 1.28223572e+03 1.32511536e+03 1.30540039e+03 1.34812341e+03 1.41188574e+03 1.46116394e+03 1.55696472e+03 1.58131763e+03 1.56422778e+03 1.64960730e+03 1.67530457e+03 1.75499646e+03 1.84029675e+03 1.80136572e+03 1.88796497e+03 1.98444373e+03 1.98333301e+03 2.02431482e+03 2.07614600e+03 2.13326587e+03 2.17978809e+03 2.21011133e+03 2.19974365e+03 2.23897095e+03 2.39647656e+03 2.51653101e+03 2.50281421e+03 2.42949951e+03 2.41483179e+03 2.50641797e+03 2.66622803e+03 2.79151685e+03 2.77300781e+03 2.67355005e+03 2.72798242e+03 2.85629395e+03 2.88904980e+03 2.90176147e+03 2.94837354e+03 3.00354956e+03 3.03885278e+03 3.17712231e+03 3.15187671e+03 3.10993408e+03 3.22231006e+03 3.18286011e+03 3.30491919e+03 3.42676270e+03 3.37465894e+03 3.53337109e+03 3.48874438e+03 3.38275293e+03 3.55009741e+03 3.51197412e+03 3.60336255e+03 3.90040942e+03 3.75401831e+03 3.55662305e+03 3.66363428e+03 3.90649243e+03 4.10819238e+03 4.04292017e+03 3.87124512e+03 3.82351685e+03 3.91708716e+03 4.12103809e+03 4.31555420e+03 4.25972510e+03 4.08023486e+03 4.11259521e+03 4.27282910e+03 4.32290186e+03 4.31422559e+03 4.33486572e+03 4.39490918e+03 4.43472021e+03 4.61710059e+03 4.66087207e+03 4.40399316e+03 4.43413428e+03 4.63784473e+03 4.66956982e+03 4.70108740e+03 4.73703516e+03 4.89323242e+03 4.81793066e+03 4.69115967e+03 4.85408740e+03 4.74944238e+03 4.92251172e+03 5.26149072e+03 4.99604932e+03 4.75462939e+03 4.92905957e+03 5.20725391e+03 5.39978564e+03 5.36465088e+03 5.08053467e+03 4.94234521e+03 5.10878564e+03 5.40485547e+03 5.59556104e+03 5.47480762e+03 5.21586816e+03 5.25281592e+03 5.44641846e+03 5.50742383e+03 5.62291797e+03 5.67841406e+03 5.41934473e+03 5.41198486e+03 5.71752881e+03 5.78112012e+03 5.54414355e+03 5.53051074e+03 5.70297314e+03 5.71176221e+03 5.89036133e+03 5.98162646e+03 5.76233105e+03 5.75651416e+03 5.77065381e+03 5.79168652e+03 5.92320020e+03 5.91345508e+03 6.09054785e+03 6.20602832e+03 6.01832324e+03 5.85808398e+03 5.77599023e+03 6.06721680e+03 6.42459424e+03 6.27623145e+03 6.01024951e+03 5.84497705e+03 6.09370410e+03 6.47134180e+03 6.30619385e+03 5.97491797e+03 6.06206152e+03 6.27884521e+03 6.47561475e+03 6.71559668e+03 6.53543896e+03 6.16402393e+03 6.14455078e+03 6.36001074e+03 6.43546240e+03 6.50252002e+03 6.48114062e+03 6.47607178e+03 6.42538281e+03 6.58660352e+03 6.57884375e+03 6.39951465e+03 6.42222461e+03 6.38454688e+03 6.65577441e+03 6.76671973e+03 6.55536914e+03 6.68839453e+03 6.67486475e+03 6.62956445e+03 6.52575537e+03 6.42036768e+03 6.67918262e+03 7.01343066e+03 6.86977490e+03 6.57002637e+03 6.48408789e+03 6.80282080e+03 6.98557666e+03 6.87660254e+03 6.78716895e+03 6.56079590e+03 6.57763623e+03 6.84480273e+03 6.87471826e+03 6.68179883e+03 6.57841162e+03 6.55171338e+03 6.94917871e+03 7.18111377e+03 6.79905615e+03 6.62734229e+03 6.85406104e+03 6.86293506e+03 7.03665869e+03 6.99315967e+03 6.61302246e+03 6.67844971e+03 6.89776953e+03 6.87583643e+03 6.94680762e+03 7.03772900e+03 7.00350000e+03 6.72372754e+03 6.51572510e+03 6.81254590e+03 8.82628223e+03 9.39485938e+03 1.08743096e+04 1.05714658e+04 1.00459355e+04 9.99489844e+03 1.03720049e+04 1.12669785e+04 1.08908496e+04 1.08230840e+04 1.07158145e+04 1.72102969e+04 2.59632656e+04 7.84434350e+06 -26928992. 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. 0. 0. 0. 0. 0. 0. 50713344. -4564874. 1.91930650e+06 1671625. 33559880. 1.82845879e+04 1.61365039e+04 9.78323535e+03 7.05129004e+03 6.71452588e+03 6.33305957e+03 6.10796436e+03 6.41408545e+03 6.39524365e+03 6.20949658e+03 6.21388916e+03 6.17318604e+03 6.13648193e+03 6.13092432e+03 6.08494971e+03 6.02669727e+03 6.04992871e+03 5.98799170e+03 6.02618994e+03 6.02551904e+03 5.81105615e+03 5.80323584e+03 6.06837012e+03 6.04048340e+03 5.87587451e+03 5.81656006e+03 5.80263965e+03 5.78826074e+03 5.80451660e+03 5.75805420e+03 5.68446533e+03 5.65573389e+03 5.57145654e+03 5.53575488e+03 5.69354297e+03 5.67783496e+03 5.54479932e+03 5.51482568e+03 5.50818359e+03 5.49259033e+03 5.41881445e+03 5.38306787e+03 5.37458496e+03 5.27049463e+03 5.22099268e+03 5.20612744e+03 5.16498682e+03 5.37654785e+03 5.37076758e+03 5.16488135e+03 4.96762158e+03 4.92270312e+03 5.20389551e+03 5.20097412e+03 4.98334863e+03 4.84095605e+03 4.81738037e+03 4.88022559e+03 4.82410547e+03 4.97031494e+03 4.92646973e+03 4.59331055e+03 4.48426855e+03 4.68756152e+03 4.92335010e+03 4.74854590e+03 4.58023975e+03 4546. 4.47187012e+03 4.47655518e+03 4.47472363e+03 4.37592529e+03 4.30942480e+03 4.29267676e+03 4.25503564e+03 4.23200684e+03 4.18617383e+03 4.26713525e+03 4.22895459e+03 4.07597754e+03 4.00511426e+03 3.97912964e+03 4.06518213e+03 4.03246924e+03 3.90890430e+03 3.88248193e+03 3.74006934e+03 3.61077124e+03 3.75992676e+03 3.77542529e+03 3.53799707e+03 3.52434521e+03 3.68839868e+03 3.75173779e+03 3.60064673e+03 3.44627979e+03 3.41596338e+03 3.39360645e+03 3.30622900e+03 3.25024756e+03 3.24199854e+03 3.18320215e+03 3.25238599e+03 3.19696680e+03 3.06118872e+03 3.01422559e+03 2.90381177e+03 2.93550757e+03 3.05081152e+03 2.95339819e+03 2.83714819e+03 2.72145801e+03 2.64214624e+03 2.75345752e+03 2.76087451e+03 2.62613672e+03 2.50548169e+03 2.45430884e+03 2.46691968e+03 2.42157861e+03 2.45595020e+03 2.43201025e+03 2.29567334e+03 2.20231909e+03 2.15916113e+03 2.20034204e+03 2.16073682e+03 2.07093384e+03 2.01089062e+03 1.95840417e+03 1.90514270e+03 1.81569495e+03 1.82111267e+03 1.87671155e+03 1.79881689e+03 1.70501758e+03 1.61573804e+03 1.56107483e+03 1.60543250e+03 1.56651013e+03 1.47478638e+03 1.38752502e+03 1.33646887e+03 1.33354785e+03 1.28190308e+03 1.23314441e+03 1.15543445e+03 1.13359143e+03 1.14289587e+03 1.06163293e+03 1.00126160e+03 9.61681519e+02 9.10656311e+02 8.43493591e+02 7.95380981e+02 7.51033020e+02 7.01898193e+02 6.61087646e+02 5.99775269e+02 5.67632690e+02 5.50669006e+02 4.77946686e+02 4.15644440e+02 3.78874329e+02 3.30820343e+02 2.91835114e+02 2.39029373e+02 1.82306839e+02 1.40362442e+02 9.50325851e+01 4.76190567e+01 -1.86541781e-01 -4.80589943e+01 -9.67408829e+01 -1.45923904e+02 -1.92906219e+02 -2.32609467e+02 -2.88388367e+02 -3.56502869e+02 -3.95351685e+02 -4.29274689e+02 -4.66070496e+02 -5.21036621e+02 -5.99914124e+02 -6.42330627e+02 -6.71955444e+02 -7.01828552e+02 -7.43127075e+02 -8.14286743e+02 -8.62474304e+02 -9.28420166e+02 -9.67851196e+02 -9.88828613e+02 -1.05053552e+03 -1.09204431e+03 -1.17199976e+03 -1.22668103e+03 -1.23924365e+03 -1.27931653e+03 -1.32619336e+03 -1.37643860e+03 -1.38503723e+03 -1.45471826e+03 -1.58331824e+03 -1.61040417e+03 -1.61301501e+03 -1.61578870e+03 -1.65342346e+03 -1.79573877e+03 -1.84718652e+03 -1.84225269e+03 -1.84816650e+03 -1.88160522e+03 -1.98911462e+03 -2.03378613e+03 -2.11902100e+03 -2.15775122e+03 -2.14072656e+03 -2.16574438e+03 -2.20929980e+03 -2.35594482e+03 -2.40904199e+03 -2.38650269e+03 -2.39574731e+03 -2.43271094e+03 -2.56920410e+03 -2.62360718e+03 -2.53874365e+03 -2.58434888e+03 -2.78817480e+03 -2.81424609e+03 -2.71520142e+03 -2.74900830e+03 -2.93760034e+03 -3.01076221e+03 -2.94703589e+03 -2.91317310e+03 -2.97010376e+03 -3.18548828e+03 -3.20344043e+03 -3.15573584e+03 -3.23482837e+03 -3.25458740e+03 -3.22218652e+03 -3.26981689e+03 -3.39743042e+03 -3.35957788e+03 -3.45174805e+03 -3.63692578e+03 -3.59753296e+03 -3.66148901e+03 -3.69381689e+03 -3.66981909e+03 -3.71992163e+03 -3.74269214e+03 -3.78205469e+03 -3.75024634e+03 -3.74341357e+03 -3.85991479e+03 -3.98042676e+03 -4.13518164e+03 -4.02628491e+03 -3.95578589e+03 -4.11457471e+03 -4.14618604e+03 -4.30351465e+03 -4.32943262e+03 -4.24804492e+03 -4.20712402e+03 -4.21379639e+03 -4.37260107e+03 -4.40796045e+03 -4.53032080e+03 -4.57258643e+03 -4.49334912e+03 -4.50536328e+03 -4.42934082e+03 -4.58885400e+03 -4.86699756e+03 -4.83147510e+03 -4.73523682e+03 -4.65507568e+03 -4.67270264e+03 -4.92243945e+03 -4.99539307e+03 -4.91936133e+03 -4.82421631e+03 -4.83189160e+03 -4.97291504e+03 -5.02513037e+03 -5.19232568e+03 -5.19632520e+03 -5.09690869e+03 -5.12915430e+03 -5.13358203e+03 -5.30142676e+03 -5.36313818e+03 -5.13838965e+03 -5.16276074e+03 -5.50115479e+03 -5.42173291e+03 -5.16489600e+03 -5.36408447e+03 -5.68058643e+03 -5.65837891e+03 -5.53997949e+03 -5.39111230e+03 -5.43911377e+03 -5.77815771e+03 -5.78243213e+03 -5.64517139e+03 -5.55674414e+03 -5.53397217e+03 -5.69126855e+03 -5.76744775e+03 -5.80744092e+03 -5.68422266e+03 -5.81313916e+03 -6.13307812e+03 -6.01262793e+03 -5.94754395e+03 -5.94933350e+03 -5.92044482e+03 -5.98093408e+03 -6.00491553e+03 -6.05963037e+03 -6.04727002e+03 -6.04591064e+03 -5.93036621e+03 -6.01322217e+03 -6.36807227e+03 -6.12798291e+03 -5.93673779e+03 -6.11170605e+03 -6.33016895e+03 -6.51271777e+03 -6.42453467e+03 -6.28394873e+03 -6.34408545e+03 -6.31216016e+03 -6.21240234e+03 -6.21528711e+03 -6.44626270e+03 -6.48475244e+03 -6.33765674e+03 -6.31811719e+03 -6.17893262e+03 -6.39631152e+03 -6.80970508e+03 -6.62236719e+03 -6.49030762e+03 -6.34965039e+03 -6.35512256e+03 -6.72032178e+03 -6.82804688e+03 -6.62324414e+03 -6.46759814e+03 -6.44858545e+03 -6.55834229e+03 -6.59645068e+03 -6.81422510e+03 -6.77623486e+03 -6.59104736e+03 -6.61855078e+03 -6.62863818e+03 -6.78819287e+03 -6.80647119e+03 -6.63550049e+03 -6.76814355e+03 -6.77948486e+03 -6.65491504e+03 -6.47938330e+03 -6.69338477e+03 -7.03464893e+03 -6.93553955e+03 -6.79019434e+03 -6.62136182e+03 -6.63171875e+03 -7.03876172e+03 -7.04508252e+03 -6.79216406e+03 -6.68084717e+03 -6.63885791e+03 -6.74823682e+03 -6.74144922e+03 -6.83269434e+03 -6.71832178e+03 -6.84301367e+03 -7.11669678e+03 -6.87305322e+03 -6.94229688e+03 -6.99461914e+03 -6.83217578e+03 -6.89319043e+03 -6.85920068e+03 -6.67735352e+03 -6.69716992e+03 -6.89490332e+03 -6.94339160e+03 -6.93962695e+03 -6.91828760e+03 -6.68497266e+03 -6.62981982e+03 -6.85077686e+03 -6.87266455e+03 -7.04007715e+03 -6.94446533e+03 -6.68925439e+03 -6.83688135e+03 -6.94245801e+03 -6.87594141e+03 -6.75253906e+03 -6.70151025e+03 -6.82444141e+03 -6.80585205e+03 -6.73511621e+03 -6.63420410e+03 -6.72018848e+03 -7.03516113e+03 -6.97952246e+03 -6.74962256e+03 -6.54479150e+03 -6.59709814e+03 -6.90113379e+03 -6.88724023e+03 -6.73259180e+03 -6.54975928e+03 -6.41858789e+03 -6.61831055e+03 -6.75103125e+03 -6.97014258e+03 -6.72070361e+03 -6.41996191e+03 -6.53556982e+03 -6.60041846e+03 -6.78401611e+03 -6.64052783e+03 -6.43597998e+03 -6.60466260e+03 -6.58090918e+03 -6.54196533e+03 -6.36961426e+03 -6.39345703e+03 -6.74697412e+03 -6.67635498e+03 -6.45106006e+03 -6.26153906e+03 -6.29339600e+03 -6.61716309e+03 -6.56560693e+03 -6.38808740e+03 -6.21661328e+03 -6.15175537e+03 -6.31154688e+03 -6.29051172e+03 -6.50121973e+03 -6.42870264e+03 -6.16798535e+03 -6.03125391e+03 -6.08778027e+03 -6.39756592e+03 -6.24140381e+03 -6.06604053e+03 -6.16126758e+03 -6.17312646e+03 -5.95470703e+03 -5.84156250e+03 -6.06306250e+03 -5.98965820e+03 -5.83150977e+03 -6.10720020e+03 -6.15332959e+03 -5.94872803e+03 -5.88575879e+03 -5.84201465e+03 -5.84013037e+03 -5.67660352e+03 -5.61338135e+03 -5.85348535e+03 -5.90691064e+03 -5.58151611e+03 -5.43763623e+03 -5.65324463e+03 -5.83843652e+03 -5.76308789e+03 -5.54874658e+03 -5.38048291e+03 -5.53533789e+03 -5.65760254e+03 -5.54139453e+03 -5.43886914e+03 -5.25526562e+03 -5.09845459e+03 -5.34595361e+03 -5.57138574e+03 -5.41172754e+03 -5.15306445e+03 -5.06505615e+03 -5.30382666e+03 -5.34310254e+03 -5.13289697e+03 -4.96331885e+03 -4.89810693e+03 -4.93511816e+03 -4.95211621e+03 -5.10594824e+03 -5.06174219e+03 -4.85615186e+03 -4.82450781e+03 -4.78606348e+03 -4.86444629e+03 -4.73064209e+03 -4.60191992e+03 -4.78819482e+03 -4.77624658e+03 -4.58940332e+03 -4.41152832e+03 -4.46979297e+03 -4.70379102e+03 -4.48427100e+03 -4.26424268e+03 -4.35860010e+03 -4.40842432e+03 -4.37313818e+03 -4.29058301e+03 -4.36136182e+03 -4.36564893e+03 -4.18035205e+03 -4.01243091e+03 -3.98539771e+03 -4.17427832e+03 -4.07944922e+03 -3.91895654e+03 -3.94107886e+03 -3.91166455e+03 -3.85904785e+03 -3.78816357e+03 -3.81684082e+03 -3.74186304e+03 -3.63963159e+03 -3.70149731e+03 -3.66285938e+03 -3.64193335e+03 -3.60611230e+03 -3.51827417e+03 -3.44462646e+03 -3.30335156e+03 -3.29490283e+03 -3.42858496e+03 -3.42452344e+03 -3.21740039e+03 -3.08055566e+03 -3.15532471e+03 -3.23386426e+03 -3.16028369e+03 -3.00738989e+03 -2.87348926e+03 -2.95886035e+03 -2.99754370e+03 -2.86862939e+03 -2.88544482e+03 -2.80934082e+03 -2.65833643e+03 -2.67471265e+03 -2.72992310e+03 -2.66233813e+03 -2.49762134e+03 -2.41592065e+03 -2.50719458e+03 -2.52899878e+03 -2.39933740e+03 -2.26910474e+03 -2.20992529e+03 -2.29470532e+03 -2.25448340e+03 -2.13014062e+03 -2.10929468e+03 -2.07245996e+03 -2.00854822e+03 -1.95094080e+03 -1.98052441e+03 -1.89771045e+03 -1.78215564e+03 -1.82445105e+03 -1.79083508e+03 -1.71463171e+03 -1.63545044e+03 -1.56887610e+03 -1.62927612e+03 -1.58028259e+03 -1.37233447e+03 -1.41075427e+03 -1.68390649e+03 -1.48979895e+03 -1.94737268e+03 -1.90088684e+03 -1.83326099e+03 -1.72296509e+03 -1.60394470e+03 -1.51890796e+03 -1.57673633e+03 -1.51268274e+03 -1.43054565e+03 -1.50675854e+03 -1.11621619e+03 -1.21971826e+03 -1.11638008e+04 -3.44552986e+09 0. 0. 0. 0. 0. 0. 0. -257262672. 6.40989188e+05 -3.54991016e+04 -1.90519080e+03 -3.10861230e+03 -637180544. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1331396224. -2.41632969e+05 3.95746307e+02 9.62290955e+02 1.00892035e+03 1.10082861e+03 6.99709839e+02 9.63120361e+02 1.00717181e+03 1.00523920e+03 1.06563086e+03 1.11893933e+03 1.16110608e+03 1.17546399e+03 1.22106067e+03 1.30391174e+03 1.34132373e+03 1.37280957e+03 1.41352344e+03 1.44829895e+03 1.53500342e+03 1.58996582e+03 1.60420007e+03 1.65034656e+03 1.67754382e+03 1.73167285e+03 1.84040833e+03 1.89237903e+03 1.87924780e+03 1.90875476e+03 1.98310596e+03 2.03522363e+03 2.05538477e+03 2.09563477e+03 2.15838159e+03 2.20667236e+03 2.28252417e+03 2.32156958e+03 2.28792090e+03 2.36108936e+03 2.49076489e+03 2.55137427e+03 2.57890332e+03 2.51731055e+03 2.53321606e+03 2.66406714e+03 2.74287598e+03 2.75971704e+03 2.75309814e+03 2.80050317e+03 2.89760229e+03 2.96953784e+03 2.98879248e+03 2.94264380e+03 2.97175049e+03 3.17610229e+03 3.23241748e+03 3.10724902e+03 3.13082617e+03 3.26060278e+03 3.35373584e+03 3.44775122e+03 3.40652148e+03 3.32797119e+03 3.40492505e+03 3.53626587e+03 3.60705737e+03 3.60604102e+03 3.57481470e+03 3.65642358e+03 3.75816553e+03 3.77589380e+03 3.77001538e+03 3.75276807e+03 3.84793115e+03 3.97173950e+03 3.98969458e+03 4.03173633e+03 4.02897192e+03 3.97200977e+03 4.08929883e+03 4.18161523e+03 4.20095312e+03 4.25036914e+03 4.23584570e+03 4.26073633e+03 4.40552979e+03 4.42778906e+03 4.32501172e+03 4.37421191e+03 4.49983301e+03 4.56555908e+03 4.59044092e+03 4.55015820e+03 4.57476611e+03 4.66159375e+03 4.73983105e+03 4.74949756e+03 4.66525830e+03 4.76696631e+03 4.92288916e+03 4.92049170e+03 4.91866113e+03 4.85789648e+03 4.89145068e+03 5.08256836e+03 5.07049170e+03 4.99527979e+03 5.02457227e+03 5.09607373e+03 5.22300342e+03 5.23521826e+03 5.19965039e+03 5.25671338e+03 5.28580469e+03 5.36301123e+03 5.40929980e+03 5.33702881e+03 5.37848975e+03 5.43533008e+03 5.40652344e+03 5.51306055e+03 5.54752588e+03 5.56394189e+03 5.58164307e+03 5.55875830e+03 5.59335693e+03 5.67997705e+03 5.72531738e+03 5.73199121e+03 5.71290918e+03 5.69135547e+03 5.72700684e+03 5.83620508e+03 5.83378320e+03 5.79479199e+03 5.84741357e+03 6.02396533e+03 6.05586914e+03 5.90743164e+03 5.97034424e+03 6.02802588e+03 6.02838965e+03 6.00022314e+03 5.99413525e+03 6.03901562e+03 6.15110156e+03 6.26264941e+03 6.25710254e+03 6.15761865e+03 6.05490283e+03 6.17178613e+03 6.29136816e+03 6.31607617e+03 6.28917871e+03 6.22909326e+03 6.30160059e+03 6.41632031e+03 6.43770801e+03 6.28269922e+03 6.22683936e+03 6.36212598e+03 6.56629980e+03 6.53287158e+03 6.29318701e+03 6.32938428e+03 6.55113477e+03 6.56876807e+03 6.50290332e+03 6.53064014e+03 6.58270508e+03 6.54089893e+03 6.59174463e+03 6.56259814e+03 6.45837891e+03 6.62713965e+03 6.71111475e+03 6.64294482e+03 6.67637939e+03 6.67085059e+03 6.58819336e+03 6.61304688e+03 6.71938477e+03 6.78053125e+03 6.82042236e+03 6.59713623e+03 6.59290820e+03 6.91898389e+03 6.75034473e+03 6.58931152e+03 6.73812695e+03 6.80043652e+03 6.82097217e+03 6.79906885e+03 6.79521191e+03 6.70965430e+03 6.66802344e+03 6.88357617e+03 6.98894336e+03 6.67996631e+03 6.76658594e+03 6.95459961e+03 6.85523438e+03 6.84749902e+03 6.75268164e+03 6.69636719e+03 6.87163965e+03 6.92709863e+03 6.78490723e+03 6.84912109e+03 6.74086816e+03 6.82628418e+03 6.96085059e+03 6.83105322e+03 6.82192822e+03 6.85313477e+03 6.89554883e+03 6.82078418e+03 6.83031445e+03 6.83038428e+03 6.76246191e+03 6.77152295e+03 6.88567041e+03 6.84652930e+03 6.77287646e+03 6.89943115e+03 6.92631885e+03 6.87024268e+03 6.95089648e+03 6.75521387e+03 6.64118945e+03 6.80529980e+03 6.83075098e+03 6.77448145e+03 6.67737842e+03 6.60666504e+03 6.76367090e+03 6.91433008e+03 6.74838818e+03 6.68081055e+03 6.80284863e+03 6.76134473e+03 6.65437598e+03 6.59008643e+03 6.78208301e+03 6.73212793e+03 6.58335352e+03 6.75180273e+03 6.67251025e+03 6.59511182e+03 6.66346143e+03 6.58314648e+03 6.52259961e+03 6.59977197e+03 6.54482471e+03 6.50340527e+03 6.61223584e+03 6.60464502e+03 6.58803174e+03 6.43164502e+03 6.36217920e+03 6.49885596e+03 6.43812061e+03 6.47620752e+03 6.42820215e+03 6.36013184e+03 6.34159424e+03 6.36886670e+03 6.49081250e+03 6.33331055e+03 6.06380127e+03 6.30775244e+03 6.55815918e+03 6.24960107e+03 6.08126465e+03 6.15423389e+03 6.12964209e+03 6.24470654e+03 6.23791699e+03 6.07082373e+03 6.02724512e+03 6.11678662e+03 6.10966064e+03 6.13444922e+03 6.03938184e+03 6.02637598e+03 6.07793750e+03 5.80834619e+03 5.86709717e+03 5.96755713e+03 5.82136670e+03 5.93418799e+03 5.86804932e+03 5.72075781e+03 5.81114941e+03 5.73533154e+03 5.73176904e+03 5.86382227e+03 5.74331934e+03 5.62158691e+03 5.54122607e+03 5.46034473e+03 5.60268164e+03 5.66188965e+03 5.48241553e+03 5.44542188e+03 5.52949658e+03 5.48496875e+03 5.43930127e+03 5.32662988e+03 5.29425684e+03 5.28412451e+03 5.30705859e+03 5.32995410e+03 5.15384521e+03 5.08294238e+03 5.17241748e+03 5.17498145e+03 5.12371729e+03 5.09916211e+03 5.01286768e+03 4.93374072e+03 5.07150000e+03 5.09573486e+03 4.88115039e+03 4.70314307e+03 4.75709717e+03 4.81925684e+03 4.76108447e+03 4.69881934e+03 4.70384668e+03 4.68914258e+03 4.64840039e+03 4.64950244e+03 4.55781836e+03 4.48255859e+03 4.50936475e+03 4.50054980e+03 4.40238818e+03 4.29493799e+03 4.31459668e+03 4.28249268e+03 4.26187402e+03 4.27699561e+03 4.18354248e+03 4.09408154e+03 4.10491357e+03 4.13912793e+03 4.06309595e+03 3.96343311e+03 3.93400171e+03 3.90292334e+03 3.86901855e+03 3.82193408e+03 3.74274512e+03 3.71705640e+03 3.72455127e+03 3.71319580e+03 3.69867676e+03 3.59725684e+03 3.54223926e+03 3.50523193e+03 3.44585205e+03 3.40596704e+03 3.34120337e+03 3.35212280e+03 3.33188184e+03 3.23938550e+03 3.16034692e+03 3.13708813e+03 3.15048755e+03 3.14527075e+03 3.11458887e+03 3.00197217e+03 2.94049390e+03 2.90478516e+03 2.81523193e+03 2.79946313e+03 2.79672729e+03 2.74589380e+03 2.68363696e+03 2.60375415e+03 2.57154028e+03 2.57778027e+03 2.57521143e+03 2.52743677e+03 2.42431738e+03 2.34101636e+03 2.32636572e+03 2.28899878e+03 2.22395215e+03 2.22226099e+03 2.20325781e+03 2.09923975e+03 2.02532666e+03 1.98561499e+03 1.95603247e+03 1.97619666e+03 1.93249402e+03 1.82098560e+03 1.78840405e+03 1.73551721e+03 1.65798193e+03 1.66197742e+03 1.63067053e+03 1.54485205e+03 1.49250061e+03 1.43527734e+03 1.37709387e+03 1.38677051e+03 1.38347852e+03 1.29244275e+03 1.22086011e+03 1.17663562e+03 1.13219983e+03 1.08981445e+03 1.04049707e+03 9.99547241e+02 9.43144775e+02 8.83486755e+02 8.48905884e+02 8.13174377e+02 7.55251953e+02 7.16956787e+02 6.77921265e+02 6.10068481e+02 5.50785828e+02 5.12277466e+02 4.77068390e+02 4.35471344e+02 3.84140106e+02 3.24803589e+02 2.72151093e+02 2.34826828e+02 1.96936295e+02 1.50642319e+02 9.67970734e+01 4.43575211e+01 -8.97770119e+00 -5.86255608e+01 -1.02122314e+02 -1.42374466e+02 -1.85149002e+02 -2.34532333e+02 -2.96866547e+02 -3.44885406e+02 -3.77832428e+02 -4.34792084e+02 -4.96613861e+02 -5.37577820e+02 -5.75047363e+02 -6.19989563e+02 -6.73288574e+02 -7.26297729e+02 -7.67021545e+02 -8.16859375e+02 -8.44441223e+02 -8.92651855e+02 -9.64718262e+02 -1.00751508e+03 -1.06955627e+03 -1.10503381e+03 -1.13606775e+03 -1.19065051e+03 -1.24668140e+03 -1.29672229e+03 -1.33072339e+03 -1.39215869e+03 -1.44881445e+03 -1.46998792e+03 -1.50055115e+03 -1.55052649e+03 -1.60141650e+03 -1.68641248e+03 -1.73119849e+03 -1.73924170e+03 -1.78530957e+03 -1.82224561e+03 -1.89596179e+03 -1.96463855e+03 -1.97470154e+03 -2.00196118e+03 -2.08809082e+03 -2.12912646e+03 -2.14520068e+03 -2.24861157e+03 -2.28596899e+03 -2.27805542e+03 -2.34697754e+03 -2.34950928e+03 -2.39657471e+03 -2.52906934e+03 -2.55386182e+03 -2.56025488e+03 -2.63442773e+03 -2.66638867e+03 -2.63316724e+03 -2.69367456e+03 -2.80217480e+03 -2.83457666e+03 -2.89482300e+03 -2.91311304e+03 -2.92756128e+03 -3.01417188e+03 -3.08666626e+03 -3.19066162e+03 -3.16032080e+03 -3.08231030e+03 -3.17158228e+03 -3.25377612e+03 -3.32806470e+03 -3.40023315e+03 -3.37237378e+03 -3.33221411e+03 -3.48076074e+03 -3.57472485e+03 -3.52037256e+03 -3.60961255e+03 -3.64980835e+03 -3.62687207e+03 -3.72526758e+03 -3.77191943e+03 -3.74394385e+03 -3.90291382e+03 -3.94377979e+03 -3.90450366e+03 -3.93905103e+03 -3.86362549e+03 -3.92640137e+03 -4.10308545e+03 -4.25932764e+03 -4.23259131e+03 -4.04901440e+03 -4.11074658e+03 -4.30993799e+03 -4.31958984e+03 -4.30875830e+03 -4.35501514e+03 -4.36317871e+03 -4.44537256e+03 -4.50286963e+03 -4.55097461e+03 -4.54771289e+03 -4.58117822e+03 -4.69320947e+03 -4.66750146e+03 -4.63314258e+03 -4.67536914e+03 -4.72516602e+03 -4.81680957e+03 -4.92363281e+03 -4.87169092e+03 -4.77857373e+03 -4.90186230e+03 -4.99271533e+03 -5.13342188e+03 -5.11977930e+03 -4.93425293e+03 -5.04850488e+03 -5.13934766e+03 -5.20852588e+03 -5.32024658e+03 -5.27844971e+03 -5.19295605e+03 -5.24167432e+03 -5.23537549e+03 -5.22363281e+03 -5.44698193e+03 -5.56525098e+03 -5.44863916e+03 -5.38400732e+03 -5.38655420e+03 -5.44587061e+03 -5.65276514e+03 -5.68232324e+03 -5.63843945e+03 -5.59895898e+03 -5.50352832e+03 -5.61016504e+03 -5.71197314e+03 -5.84875879e+03 -5.88177100e+03 -5.70742822e+03 -5.76386035e+03 -5.79108643e+03 -5.85683545e+03 -5.94734570e+03 -5.97301074e+03 -6.04166455e+03 -5.90133008e+03 -5.90569580e+03 -5.99544092e+03 -5.99889209e+03 -6.04092871e+03 -6.12707520e+03 -6.16013770e+03 -6.13589648e+03 -6.07363281e+03 -6.15053906e+03 -6.31010742e+03 -6.27280127e+03 -6.14663916e+03 -6.18541748e+03 -6.22480811e+03 -6.19813232e+03 -6.45563379e+03 -6.43088525e+03 -6.23512988e+03 -6.39504102e+03 -6.31068115e+03 -6.31313330e+03 -6.60402881e+03 -6.48399268e+03 -6.50806299e+03 -6.62666797e+03 -6.59817920e+03 -6.97266650e+03 -8.57433789e+03 -8.70354395e+03 -1.08767119e+04 -9.59608789e+03 -1.72946758e+04 -2.92452227e+04 -9259576. 11414557. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70624112. -1.05716977e+05 -1.44007520e+04 -9.60143652e+03 -8.70701953e+03 -7.40422217e+03 -6.88731152e+03 -6.99745850e+03 -7.14441064e+03 -6.95593701e+03 -6.83719727e+03 -6.66962061e+03 -6.69961914e+03 -6.89580518e+03 -7.01274658e+03 -6.86707520e+03 -6.75839160e+03 -6.72035498e+03 -6.74433984e+03 -6.90140479e+03 -6.81267773e+03 -6.57999561e+03 -6.63072900e+03 -6.80874121e+03 -6.77953125e+03 -6.59906006e+03 -6.50191895e+03 -6.70622461e+03 -6.98350293e+03 -6.94457471e+03 -6.57445459e+03 -6.31230078e+03 -6.47727734e+03 -6.74204248e+03 -6.89728760e+03 -6.74566357e+03 -6.45960352e+03 -6.46961035e+03 -6.57631934e+03 -6.76819336e+03 -6.65133008e+03 -6.30749463e+03 -6.38617090e+03 -6.71267432e+03 -6.56753467e+03 -6.34661816e+03 -6.41598584e+03 -6.43136572e+03 -6.51162793e+03 -6.50652979e+03 -6.21430518e+03 -6.12199609e+03 -6.43784912e+03 -6.60053760e+03 -6.47329590e+03 -6.18242334e+03 -6.01032422e+03 -6.32413086e+03 -6.50707373e+03 -6.30144385e+03 -6.11518408e+03 -5.90233301e+03 -5.97203516e+03 -6.24913867e+03 -6.32013330e+03 -6.20084375e+03 -6.07919678e+03 -6.06949512e+03 -5.98564355e+03 -5.96590527e+03 -6.00310889e+03 -5.79166504e+03 -5.84943311e+03 -6.06686279e+03 -5.94620557e+03 -5.67293848e+03 -5.59566504e+03 -5.86749316e+03 -6.03560254e+03 -5.86896680e+03 -5.68414795e+03 -5.51714648e+03 -5.49406982e+03 -5.64563281e+03 -5.86388574e+03 -5.73359912e+03 -5.39876562e+03 -5.43028711e+03 -5.47726807e+03 -5.50402881e+03 -5.59060742e+03 -5.35529980e+03 -5.35826855e+03 -5.48593652e+03 -5.37003906e+03 -5.26342139e+03 -5.19499902e+03 -5.21367529e+03 -5.31903369e+03 -5.24324414e+03 -5.05156348e+03 -4.98340039e+03 -5.12137744e+03 -5.17408594e+03 -5.12168018e+03 -5.00825928e+03 -4.82482617e+03 -4.85004297e+03 -5.00909082e+03 -4.97172754e+03 -4.83367627e+03 -4.61842188e+03 -4.60433496e+03 -4.79018555e+03 -4.88344287e+03 -4.72218945e+03 -4.49227295e+03 -4.49288770e+03 -4.61312256e+03 -4.54964893e+03 -4.41340479e+03 -4.33095020e+03 -4.43550781e+03 -4.47880762e+03 -4.30111328e+03 -4.24311035e+03 -4.16716455e+03 -4.22580713e+03 -4.34987793e+03 -4.23027734e+03 -4.08349878e+03 -3.97092017e+03 -3.95214038e+03 -3.99541675e+03 -4.03596973e+03 -3967. -3.75616382e+03 -3.72902466e+03 -3.86139893e+03 -3.86284204e+03 -3.74087817e+03 -3.61367480e+03 -3.60229858e+03 -3.64266187e+03 -3.61071069e+03 -3.50946118e+03 -3.34409082e+03 -3.35153125e+03 -3.44148926e+03 -3.40043677e+03 -3.29765723e+03 -3.19390991e+03 -3.17776929e+03 -3.20375806e+03 -3.24505957e+03 -3.17144214e+03 -2.95508447e+03 -2.94087769e+03 -2.98777539e+03 -2.93058081e+03 -2.88614746e+03 -2.80998462e+03 -2.76682178e+03 -2.73027637e+03 -2.69958423e+03 -2.63438086e+03 -2.57221167e+03 -2.60096680e+03 -2.58959570e+03 -2.50961890e+03 -2.37354297e+03 -2.30294971e+03 -2.36051514e+03 -2.39137451e+03 -2.31796729e+03 -2.20908716e+03 -2.09658618e+03 -2.02830176e+03 -2.06935840e+03 -2.11829688e+03 -2.01659705e+03 -1.87263464e+03 -1.84933801e+03 -1.85134131e+03 -1.82699731e+03 -1.78838330e+03 -1.70030750e+03 -1.64031299e+03 -1.60675500e+03 -1.55268811e+03 -1.49208838e+03 -1.45937183e+03 -1.44314050e+03 -1.38675012e+03 -1.33118127e+03 -1.27312317e+03 -1.21515698e+03 -1.19863745e+03 -1.17200134e+03 -1.10771497e+03 -1.02553040e+03 -9.60376587e+02 -9.45805603e+02 -9.19791443e+02 -8.67065735e+02 -8.10445679e+02 -7.37618164e+02 -6.89261536e+02 -6.75450745e+02 -6.47705139e+02 -5.89385193e+02 -5.20208984e+02 -4.67142731e+02 -4.28391541e+02 -3.80853821e+02 -3.30991608e+02 -2.87880219e+02 -2.44006882e+02 -1.90482132e+02 -1.38545212e+02 -8.92886200e+01 -4.49118652e+01 -5.66429943e-02 4.66658058e+01 9.80036240e+01 1.46552017e+02 1.87351685e+02 2.42097351e+02 2.95377899e+02 3.40741913e+02 3.90604492e+02 4.32386566e+02 4.91321259e+02 5.36632996e+02 5.53387573e+02 5.92791443e+02 6.54200378e+02 7.36318237e+02 8.11395081e+02 8.38747803e+02 8.37282593e+02 8.60010071e+02 9.24224609e+02 1.02568811e+03 1.11011902e+03 1.13080383e+03 1.11126965e+03 1.15334314e+03 1.28590247e+03 1.32226843e+03 1.30239331e+03 1.34856970e+03 1.41778296e+03 1.46764026e+03 1.55861536e+03 1.57676379e+03 1.56209290e+03 1.64678052e+03 1.66586011e+03 1.75555798e+03 1.84649695e+03 1.79658081e+03 1.87873730e+03 1.98699414e+03 1.99005750e+03 2.02532349e+03 2.06245166e+03 2.12160400e+03 2.18353711e+03 2.20175684e+03 2.19418945e+03 2.25035132e+03 2.39576855e+03 2.49837915e+03 2.48911035e+03 2.42974780e+03 2.41951465e+03 2.50480981e+03 2.66487451e+03 2.79291284e+03 2.76517993e+03 2.67191357e+03 2.73093994e+03 2.86660864e+03 2.88937036e+03 2.89149243e+03 2.94542407e+03 2.98515210e+03 3.02525732e+03 3.18439941e+03 3.15559937e+03 3.10150757e+03 3.20762378e+03 3.17543042e+03 3.32341064e+03 3.43526538e+03 3.36740771e+03 3.52376196e+03 3.49357593e+03 3.38887573e+03 3.54937573e+03 3.50525830e+03 3.59972046e+03 3.89702100e+03 3.75131006e+03 3.57572925e+03 3.67996533e+03 3.89673291e+03 4.09254980e+03 4.03582642e+03 3.84841895e+03 3.77965381e+03 3.92229590e+03 4.15983789e+03 4.33815869e+03 4.26786523e+03 4.06357715e+03 4.09739111e+03 4.28350537e+03 4.37289893e+03 4.29779834e+03 4.27689893e+03 4.40110889e+03 4.44054834e+03 4.59899658e+03 4.65427832e+03 4.45294385e+03 4.47715332e+03 4.57998486e+03 4.63145996e+03 4.71328662e+03 4.72872705e+03 4.87558545e+03 4.84161035e+03 4.69934570e+03 4.81520947e+03 4.74189893e+03 4.93255566e+03 5.27380713e+03 5.01145410e+03 4.74069043e+03 4.89933398e+03 5.17624512e+03 5.35909961e+03 5.39446533e+03 5.14371924e+03 4.95294775e+03 5.08354102e+03 5.38160742e+03 5.63351953e+03 5.49654492e+03 5.21477881e+03 5.21402490e+03 5.39533105e+03 5.52673096e+03 5.65552100e+03 5.66544434e+03 5.40548291e+03 5.40615283e+03 5.67280859e+03 5.77833447e+03 5.64485645e+03 5.62566895e+03 5.64600684e+03 5.64380908e+03 5.88784961e+03 5.98956006e+03 5.73787109e+03 5.70248633e+03 5.78626514e+03 5.84064551e+03 5.92813184e+03 5.89248535e+03 6.07371875e+03 6.18889844e+03 5.96434082e+03 5.86525635e+03 5.79973340e+03 6.06487061e+03 6.43741260e+03 6.29810596e+03 5.97914209e+03 5.86545215e+03 6.10145996e+03 6.47228369e+03 6.30486133e+03 5.97983545e+03 6.09248975e+03 6.24527295e+03 6.45188965e+03 6.68894287e+03 6.51424268e+03 6.16773779e+03 6.07445459e+03 6.32662402e+03 6.52562451e+03 6.56024512e+03 6.47780664e+03 6.44527588e+03 6.41867627e+03 6.58448193e+03 6.58486719e+03 6.39767676e+03 6.38913037e+03 6.38545459e+03 6.69081104e+03 6.79985596e+03 6.55847559e+03 6.60688477e+03 6.65659814e+03 6.78936133e+03 6.63093604e+03 6.31431055e+03 6.63778711e+03 6.99940625e+03 6.81264600e+03 6.48311963e+03 6.54366016e+03 6.88146143e+03 6.91717480e+03 6.79709082e+03 6.76414600e+03 6.54949121e+03 6.57846875e+03 6.93476270e+03 6.95293359e+03 6.66086475e+03 6.51013818e+03 6.54879736e+03 6.85804492e+03 7.16151855e+03 6.86260742e+03 6.62164111e+03 6.84093604e+03 6.83838281e+03 7.03104785e+03 7.02295801e+03 6.63063135e+03 6.66340918e+03 6.87218994e+03 6.83954248e+03 6.90626514e+03 6.82855225e+03 6.98391162e+03 7.08940381e+03 6.77884961e+03 6.97160889e+03 6.61860303e+03 6.89072803e+03 9.66840137e+03 7.56782666e+03 9.94727930e+03 8.49793359e+03 1.03720049e+04 1.12669785e+04 1.08908496e+04 1.08230840e+04 1.07158145e+04 1.72102969e+04 2.59632656e+04 7.84434350e+06 -26928992. 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. 0. 0. 0. 0. 0. 0. 0. 0. -14108127. -3.58977750e+06 1975401. 2.26907148e+04 1.35470273e+04 8.84856836e+03 7.11187012e+03 6.76605322e+03 6.40966748e+03 6.17714014e+03 6.37605029e+03 6.35314648e+03 6.19597656e+03 6.23107910e+03 6.18109082e+03 6.11276904e+03 6.15247363e+03 6.09135742e+03 6.02371631e+03 5.99728760e+03 5.92669678e+03 6.07205371e+03 6.10084717e+03 5.81014697e+03 5.78108545e+03 6.03525098e+03 6.05238916e+03 5.90269727e+03 5.85000195e+03 5.81237256e+03 5.78634570e+03 5.76163867e+03 5.74134424e+03 5.70253711e+03 5.67467188e+03 5.58792139e+03 5.54203320e+03 5.68283545e+03 5.67718213e+03 5.54283447e+03 5.51721338e+03 5.49582471e+03 5.47509766e+03 5.41251953e+03 5.37561816e+03 5.36368506e+03 5.21118457e+03 5.14494873e+03 5.24661816e+03 5.21281494e+03 5.38226416e+03 5.35283154e+03 5.13719482e+03 4.94629541e+03 4.91255078e+03 5.21749561e+03 5.21890234e+03 4.98292480e+03 4.86239746e+03 4.84619727e+03 4.89440479e+03 4.82248828e+03 4.94255566e+03 4.90299170e+03 4.58772949e+03 4.51499268e+03 4.73340674e+03 4.87236768e+03 4.71589746e+03 4.58397021e+03 4.56083545e+03 4.49250635e+03 4.40581396e+03 4.40431299e+03 4.37819873e+03 4.31696680e+03 4.29094629e+03 4.24835498e+03 4.26033350e+03 4.21688623e+03 4.26194287e+03 4.20519531e+03 4.05438477e+03 4.06524536e+03 4.04087842e+03 4.01641187e+03 3.99357520e+03 3.91905908e+03 3.88619165e+03 3.75974048e+03 3.62053784e+03 3.77004419e+03 3.77961230e+03 3.54679761e+03 3.53197998e+03 3.69261426e+03 3.75467017e+03 3.59036401e+03 3.45662329e+03 3.40976978e+03 3.36082104e+03 3.28411621e+03 3.24091211e+03 3.27235767e+03 3.21472778e+03 3.24466016e+03 3.17923022e+03 3.04642456e+03 3.05412354e+03 2.93888013e+03 2.90161011e+03 3.01452710e+03 2.94423340e+03 2.83080981e+03 2.72718872e+03 2.64313916e+03 2.74828223e+03 2.75321265e+03 2.62011646e+03 2.49895923e+03 2.45520679e+03 2.47279004e+03 2.42365259e+03 2.45350610e+03 2.42786157e+03 2.29527856e+03 2.20131836e+03 2.16582959e+03 2.21609692e+03 2.16681006e+03 2.06403760e+03 2.00130005e+03 1.95036243e+03 1.92975537e+03 1.84202063e+03 1.80074341e+03 1.85467578e+03 1.79707202e+03 1.70349060e+03 1.60872986e+03 1.55877124e+03 1.61293140e+03 1.56677832e+03 1.47534729e+03 1.38555054e+03 1.33027844e+03 1.33225134e+03 1.28232715e+03 1.23529065e+03 1.15796008e+03 1.13369543e+03 1.14599524e+03 1.06810938e+03 1.00646362e+03 9.64826721e+02 9.12270264e+02 8.47465881e+02 7.98679199e+02 7.62887573e+02 7.13750732e+02 6.65629883e+02 6.04330383e+02 5.67674805e+02 5.50318848e+02 4.80323639e+02 4.17360199e+02 3.81250549e+02 3.32754974e+02 2.94635376e+02 2.40859238e+02 1.84952759e+02 1.46608490e+02 9.89862137e+01 4.83539543e+01 -1.98234582e+00 -5.20176620e+01 -1.01127167e+02 -1.48674652e+02 -1.94846985e+02 -2.33252350e+02 -2.85449188e+02 -3.52847412e+02 -3.94119995e+02 -4.27397308e+02 -4.61108032e+02 -5.14708496e+02 -5.96421204e+02 -6.42534180e+02 -6.71286804e+02 -7.01824402e+02 -7.43854370e+02 -8.10909058e+02 -8.59890564e+02 -9.29608887e+02 -9.54444824e+02 -9.71519714e+02 -1.05284985e+03 -1.10008472e+03 -1.16953540e+03 -1.21258643e+03 -1.23059875e+03 -1.27987585e+03 -1.32375720e+03 -1.38787280e+03 -1.40001111e+03 -1.46173242e+03 -1.58974829e+03 -1.60011035e+03 -1.60554382e+03 -1.61874390e+03 -1.65417773e+03 -1.79597424e+03 -1.84726172e+03 -1.84142664e+03 -1.84409241e+03 -1.88096155e+03 -1.98848206e+03 -2.03512500e+03 -2.12928833e+03 -2.15348096e+03 -2.13696289e+03 -2.16420068e+03 -2.20306519e+03 -2.35840112e+03 -2.39330322e+03 -2.37321484e+03 -2.41135742e+03 -2.45108276e+03 -2.56902759e+03 -2.62286938e+03 -2.55816870e+03 -2.58944556e+03 -2.76801904e+03 -2.81716699e+03 -2.72240259e+03 -2.74819580e+03 -2.93826416e+03 -3.00559863e+03 -2.95516431e+03 -2.92289551e+03 -2.96084326e+03 -3.18160107e+03 -3.20111499e+03 -3.15316333e+03 -3.21997266e+03 -3.23984106e+03 -3.27448828e+03 -3.31847485e+03 -3.35646484e+03 -3.31582788e+03 -3.44688184e+03 -3.67453857e+03 -3.61820752e+03 -3.60631396e+03 -3.67254321e+03 -3.67533765e+03 -3.72485669e+03 -3.75663867e+03 -3.78708130e+03 -3.73584839e+03 -3.71990527e+03 -3.85686401e+03 -3.98261865e+03 -4.13627197e+03 -4.04049365e+03 -3.93609082e+03 -4.09214575e+03 -4.16435742e+03 -4.32625000e+03 -4.31216553e+03 -4.21645410e+03 -4.22380908e+03 -4.23500537e+03 -4.36396436e+03 -4.41775293e+03 -4.53861475e+03 -4.56795508e+03 -4.49178125e+03 -4.46637451e+03 -4.38099951e+03 -4.60243457e+03 -4.91878223e+03 -4.84479199e+03 -4.73641211e+03 -4.64765967e+03 -4.62251074e+03 -4.89252148e+03 -5.05479053e+03 -4.96242627e+03 -4.80397266e+03 -4.80987842e+03 -4.98334814e+03 -5.02291650e+03 -5.19266895e+03 -5.20502002e+03 -5.08709131e+03 -5.13738623e+03 -5.14547363e+03 -5.29287158e+03 -5.33464648e+03 -5.13303564e+03 -5.17560156e+03 -5.48173828e+03 -5.41337354e+03 -5.17225537e+03 -5.36790332e+03 -5.70728613e+03 -5.63856152e+03 -5.50251660e+03 -5.39744629e+03 -5.45151611e+03 -5.79579346e+03 -5.78557764e+03 -5.65845801e+03 -5.54071387e+03 -5.52580518e+03 -5.73045703e+03 -5.73314746e+03 -5.78637061e+03 -5.66527051e+03 -5.81542480e+03 -6.08703662e+03 -5.96359180e+03 -5.99132764e+03 -5.98135205e+03 -5.89185547e+03 -5.96643359e+03 -6.01039990e+03 -6.05495557e+03 -6.03661816e+03 -5.99561279e+03 -5.89584180e+03 -6.03833740e+03 -6.45243018e+03 -6.18957227e+03 -5.93894287e+03 -6.13935645e+03 -6.25613135e+03 -6.48792188e+03 -6.39202148e+03 -6.20174463e+03 -6.37624707e+03 -6.40002930e+03 -6.16489160e+03 -6.14165430e+03 -6.54150439e+03 -6.54299316e+03 -6.36706152e+03 -6.28991748e+03 -6.11947559e+03 -6.39521533e+03 -6.81317041e+03 -6.65419727e+03 -6.49279834e+03 -6.36310742e+03 -6.29062158e+03 -6.63653809e+03 -6.88650586e+03 -6.70823682e+03 -6.39741846e+03 -6.37004395e+03 -6.57920898e+03 -6.65770361e+03 -6.86564062e+03 -6.72030176e+03 -6.53670068e+03 -6.70784082e+03 -6.69470215e+03 -6.80107520e+03 -6.79153516e+03 -6.66363623e+03 -6.70331543e+03 -6.73914648e+03 -6.72732617e+03 -6.51923242e+03 -6.66979150e+03 -7.09231006e+03 -6.96372656e+03 -6.68594189e+03 -6.54502734e+03 -6.63785107e+03 -7.04595508e+03 -6.98682080e+03 -6.80726367e+03 -6.63350293e+03 -6.63734912e+03 -6.84031201e+03 -6.83020508e+03 -6.84759717e+03 -6.65713770e+03 -6.84611133e+03 -7.12551074e+03 -6.89923242e+03 -6.95331689e+03 -6.96368945e+03 -6.86504395e+03 -6.81489258e+03 -6.75703955e+03 -6.80975977e+03 -6.78488770e+03 -6.82527490e+03 -6.79621094e+03 -6.97037744e+03 -6.98748877e+03 -6.69873242e+03 -6.58436523e+03 -6.74417090e+03 -6.88745312e+03 -7.12814014e+03 -6.89495801e+03 -6.60214990e+03 -6.89630371e+03 -7.06199512e+03 -6.87559326e+03 -6.69383350e+03 -6.67284814e+03 -6.76566162e+03 -6.77820215e+03 -6.72506104e+03 -6.54452588e+03 -6.75617871e+03 -7.08646680e+03 -6.90796387e+03 -6.76188428e+03 -6.63138086e+03 -6.55648877e+03 -6.90893311e+03 -6.92306348e+03 -6.70318994e+03 -6.52482275e+03 -6.36756152e+03 -6.54587402e+03 -6.78311572e+03 -6.99433105e+03 -6.69295605e+03 -6.38524072e+03 -6.57701953e+03 -6.62480615e+03 -6.83760791e+03 -6.66944580e+03 -6.45324072e+03 -6.61188037e+03 -6.58528809e+03 -6.41891016e+03 -6.28554639e+03 -6.47982666e+03 -6.78927881e+03 -6.63050049e+03 -6.49188721e+03 -6.31026318e+03 -6.25542334e+03 -6.57221484e+03 -6.57578564e+03 -6.37719580e+03 -6.19121191e+03 -6.11319336e+03 -6.28980615e+03 -6.32058203e+03 -6.43563818e+03 -6.44745898e+03 -6.20733838e+03 -6.05919482e+03 -6.10353760e+03 -6.40039355e+03 -6.24632324e+03 -6.05520312e+03 -6.12981494e+03 -6.12687549e+03 -5.97320020e+03 -5.86865283e+03 -6.11288037e+03 -6.06469629e+03 -5.86972705e+03 -6.09917090e+03 -6.11740381e+03 -5.95499268e+03 -5.89947705e+03 -5.86377783e+03 -5.83400928e+03 -5.68106104e+03 -5.60945996e+03 -5.85945215e+03 -5.88502197e+03 -5.56147266e+03 -5.36956885e+03 -5.62499707e+03 -5.91434180e+03 -5.81624268e+03 -5.49392676e+03 -5.34026904e+03 -5.59737158e+03 -5.65540820e+03 -5.45121826e+03 -5.46951367e+03 -5.30531543e+03 -5.11748340e+03 -5.28127148e+03 -5.48733447e+03 -5.43121729e+03 -5.18375488e+03 -5.01053857e+03 -5.24907324e+03 -5.37177344e+03 -5.17541357e+03 -4.93738672e+03 -4.85029736e+03 -4.99163818e+03 -4.98721191e+03 -5.07828027e+03 -5.03553613e+03 -4.81483008e+03 -4.85593066e+03 -4.82201123e+03 -4.86322852e+03 -4.72747998e+03 -4.58306299e+03 -4.74828271e+03 -4.72321826e+03 -4.61746875e+03 -4.46291748e+03 -4.47712744e+03 -4.71115820e+03 -4.49594141e+03 -4.26748926e+03 -4.33376416e+03 -4.39671387e+03 -4.37143604e+03 -4.28476660e+03 -4.35110303e+03 -4.35684082e+03 -4.18829443e+03 -4.01736133e+03 -3.99015527e+03 -4.16321436e+03 -4.04414844e+03 -3.87946924e+03 -3.97662720e+03 -3.96411670e+03 -3.84239600e+03 -3.75728662e+03 -3.86456421e+03 -3.78520703e+03 -3.63690625e+03 -3.69634546e+03 -3.66873560e+03 -3.64682617e+03 -3.59959326e+03 -3.51996606e+03 -3.45230542e+03 -3.30847363e+03 -3.25960840e+03 -3.37971313e+03 -3.44880688e+03 -3.24801440e+03 -3.04531006e+03 -3.13059351e+03 -3.27247363e+03 -3.20833203e+03 -3.01151343e+03 -2.86475928e+03 -2.96394580e+03 -3.00788232e+03 -2.86576855e+03 -2.87869702e+03 -2.81834863e+03 -2.66959961e+03 -2.65328931e+03 -2.69637622e+03 -2.66372974e+03 -2.52636279e+03 -2.42057910e+03 -2.47464209e+03 -2.54001294e+03 -2.43067505e+03 -2.28373657e+03 -2.20313916e+03 -2.27157861e+03 -2.29497778e+03 -2.16836401e+03 -2.06902881e+03 -2.04116162e+03 -2.03658472e+03 -1.98003088e+03 -1.98778149e+03 -1.89734509e+03 -1.78675708e+03 -1.81058276e+03 -1.77315845e+03 -1.72497717e+03 -1.64287927e+03 -1.57032983e+03 -1.58634375e+03 -1.50072852e+03 -1.43077332e+03 -1.43894495e+03 -1.41818481e+03 -1.40989246e+03 -1.34045435e+03 -1.30965405e+03 -1.25624817e+03 -1.01283734e+03 -9.87587830e+02 -1.04415454e+03 -1.08369629e+03 -1.05135828e+03 -8.98627136e+02 -8.46124084e+02 -1.08466125e+03 -1.44732483e+03 -1.11638008e+04 -3.44552986e+09 0. 0. 0. 0. 1381557632. 1381557632. 8.02582875e+05 -231494368. -4.65549170e+03 -3.54991016e+04 -1.90519080e+03 -3.10861230e+03 -637180544. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 469363232. 1.79326781e+05 1.31527771e+03 1.47304993e+03 6.42729797e+02 9.16528381e+02 7.63691345e+02 9.08724487e+02 8.27546509e+02 9.81135010e+02 9.65397095e+02 9.95626770e+02 1.03136926e+03 1.09747668e+03 1.17703687e+03 1.22062756e+03 1.22247656e+03 1.25673010e+03 1.33985876e+03 1.38895117e+03 1.42791907e+03 1.46872327e+03 1.49878809e+03 1.54901978e+03 1.63458960e+03 1.68581812e+03 1.66998865e+03 1.71931604e+03 1.82667383e+03 1.88483789e+03 1.93137207e+03 1.92529309e+03 1.93024023e+03 2.02975061e+03 2.10021973e+03 2.12616357e+03 2.13839941e+03 2.17942480e+03 2.26980029e+03 2.31145483e+03 2.33753857e+03 2.35755396e+03 2.40429688e+03 2.54714258e+03 2.61046021e+03 2.52704053e+03 2.53931079e+03 2.63423047e+03 2.70570703e+03 2.79427319e+03 2.81078589e+03 2.78817188e+03 2.86726465e+03 2.94028613e+03 2.97998999e+03 3.03211353e+03 3.01682007e+03 3.06615088e+03 3.14677856e+03 3.16296826e+03 3.19787573e+03 3.22254419e+03 3.28296826e+03 3.40674561e+03 3.43839795e+03 3.43271484e+03 3.40923047e+03 3.44290625e+03 3.59849731e+03 3.64687378e+03 3.58040576e+03 3.64203589e+03 3.69290308e+03 3.76560376e+03 3.89230225e+03 3.87062109e+03 3.80770679e+03 3.85990186e+03 4.00563037e+03 4.05535864e+03 3.99700659e+03 3.95932202e+03 4.03970703e+03 4.14392236e+03 4.28940283e+03 4.32483984e+03 4.18929883e+03 4.22594580e+03 4.38667334e+03 4.41980127e+03 4.42396338e+03 4.36456543e+03 4.36631201e+03 4.56319043e+03 4.63960596e+03 4.56047021e+03 4.59835449e+03 4.65192920e+03 4.67746289e+03 4.71822510e+03 4.73908447e+03 4.80658838e+03 4.83749414e+03 4.93064502e+03 4.96738184e+03 4.84700586e+03 4.89479736e+03 5.02236816e+03 4.99977246e+03 5.05659814e+03 5.07325049e+03 5.10671924e+03 5.22852637e+03 5.21369629e+03 5.16476318e+03 5.30367627e+03 5.35252832e+03 5.26754590e+03 5.29017920e+03 5.37111670e+03 5.44123779e+03 5.42947314e+03 5.38252002e+03 5.42691113e+03 5.51526367e+03 5.69493604e+03 5.65989648e+03 5.48084668e+03 5.58165771e+03 5.70983350e+03 5.72685400e+03 5.72076953e+03 5.67218945e+03 5.65268994e+03 5.78468066e+03 5.93071143e+03 5.88449072e+03 5.75505664e+03 5.78325098e+03 5.95987061e+03 6.05088916e+03 6.08473730e+03 5.96796631e+03 5.84171240e+03 5.98073145e+03 6.02364746e+03 6.04936963e+03 6.11046387e+03 6.06403955e+03 6.13383057e+03 6.34398535e+03 6.22657178e+03 6.02963281e+03 6.11340527e+03 6.26030518e+03 6.30430713e+03 6.39465869e+03 6.30345264e+03 6.20795752e+03 6.28386230e+03 6.51061719e+03 6.40031689e+03 6.19905859e+03 6.30720801e+03 6.52989990e+03 6.50273633e+03 6.44536035e+03 6.32308350e+03 6.38233984e+03 6.49154834e+03 6.54088037e+03 6.54254883e+03 6.60934668e+03 6.48837012e+03 6.52027979e+03 6.73235889e+03 6.60462500e+03 6.47232324e+03 6.56432617e+03 6.68587109e+03 6.74725293e+03 6.69743896e+03 6.55685010e+03 6.54735107e+03 6.67916162e+03 6.92374414e+03 6.95183789e+03 6.56209131e+03 6.57051221e+03 6.90245752e+03 6.81127637e+03 6.67814600e+03 6.64869141e+03 6.63538330e+03 6.79750098e+03 6.88491260e+03 6.80391455e+03 6.77011572e+03 6.62429932e+03 6.77687939e+03 6.93442285e+03 6.89706836e+03 6.79345459e+03 6.75953174e+03 6.85388574e+03 6.89521289e+03 6.79893701e+03 6.76543994e+03 6.79479834e+03 6.83945703e+03 6.97115137e+03 7.02445801e+03 6.69890967e+03 6.73228760e+03 6.89760254e+03 6.90313916e+03 6.91624463e+03 6.74225391e+03 6.78870459e+03 6.98958252e+03 6.91586230e+03 6.88905420e+03 6.71265234e+03 6.65059668e+03 6.88284619e+03 6.94621436e+03 6.87463428e+03 6.81488037e+03 6.83893848e+03 6.82978320e+03 6.93387891e+03 6.87394873e+03 6.71816943e+03 6.63211133e+03 6.69861621e+03 6.88661670e+03 6.80199121e+03 6.67055518e+03 6.72156152e+03 6.85132520e+03 6.82729102e+03 6.76132031e+03 6.69864062e+03 6.63491309e+03 6.69801807e+03 6.71581885e+03 6.81278369e+03 6.69386230e+03 6.58673877e+03 6.75049658e+03 6.56194238e+03 6.57484082e+03 6.71773340e+03 6.51268311e+03 6.52165723e+03 6.58652148e+03 6.57716943e+03 6.48914893e+03 6.42878955e+03 6.63924609e+03 6.70903223e+03 6.41041943e+03 6.37989941e+03 6.44578662e+03 6.44214307e+03 6.53942676e+03 6.45242041e+03 6.30814746e+03 6.31477832e+03 6.45260645e+03 6.45354541e+03 6.34479688e+03 6.22854932e+03 6.29505615e+03 6.35675439e+03 6.21608008e+03 6.20062598e+03 6.13841406e+03 6.11929199e+03 6.17792627e+03 6.23871875e+03 6.19556787e+03 6.06660889e+03 6.00207617e+03 6.15193213e+03 6.22896240e+03 6.00912061e+03 5.99185791e+03 6.01786182e+03 5.78980127e+03 5.92307471e+03 6.00685303e+03 5.80031689e+03 5.84948096e+03 5.89521875e+03 5.78415332e+03 5.87344434e+03 5.79192432e+03 5.68284033e+03 5.69111865e+03 5.71306592e+03 5.73535205e+03 5.57144824e+03 5.47495947e+03 5.56093359e+03 5.64489551e+03 5.57014600e+03 5.46487256e+03 5.37824609e+03 5.45170020e+03 5.59120312e+03 5.40683984e+03 5.25784863e+03 5.22214404e+03 5.33923926e+03 5.40914990e+03 5.20769336e+03 5.08534668e+03 5.14687842e+03 5.14748926e+03 5.07136914e+03 5.12081006e+03 5.04990820e+03 4.90141943e+03 4.97486328e+03 5.07757520e+03 4.92741455e+03 4.67312256e+03 4.73767188e+03 4.85924268e+03 4.80683545e+03 4.75963281e+03 4.67784277e+03 4.60289893e+03 4.67643896e+03 4.73114307e+03 4.55668701e+03 4.47048584e+03 4.46841455e+03 4.51619775e+03 4.45482715e+03 4.28093506e+03 4.24766064e+03 4.28629004e+03 4.27449805e+03 4.25464697e+03 4.22198877e+03 4.12822656e+03 4.11698535e+03 4.05795703e+03 3.96359985e+03 3.94256592e+03 3.88419702e+03 3.91112109e+03 3.94673218e+03 3.81739771e+03 3.70307593e+03 3.70282690e+03 3.75506055e+03 3.80719360e+03 3.72846973e+03 3.54286670e+03 3.48612646e+03 3.51464014e+03 3.47143677e+03 3.38964551e+03 3.36561377e+03 3.34485620e+03 3.31430713e+03 3.23629517e+03 3.13080371e+03 3.16364038e+03 3.18579932e+03 3.15089160e+03 3.06797314e+03 2.93669873e+03 2.93144263e+03 2.88516650e+03 2.80912305e+03 2.87311426e+03 2.84093652e+03 2.69938818e+03 2.64278003e+03 2.62827759e+03 2.66846729e+03 2.62944946e+03 2.52796460e+03 2.46511060e+03 2.41783691e+03 2.37277173e+03 2.30374634e+03 2.29058350e+03 2.26047119e+03 2.23139990e+03 2.18610278e+03 2.05383154e+03 2.03138831e+03 2.01519214e+03 1.97654724e+03 1.98487366e+03 1.87701929e+03 1.78639526e+03 1.80910400e+03 1.79438770e+03 1.70964136e+03 1.64837830e+03 1.58034863e+03 1.52532715e+03 1.49906372e+03 1.46493823e+03 1.41219568e+03 1.39892773e+03 1.36768530e+03 1.28432800e+03 1.21591138e+03 1.15668677e+03 1.14058496e+03 1.11750171e+03 1.05129565e+03 9.78241211e+02 9.28146179e+02 8.97129761e+02 8.71545898e+02 8.42057922e+02 7.64656555e+02 6.97728210e+02 6.60399475e+02 6.07790222e+02 5.59630676e+02 5.34495667e+02 4.87900513e+02 4.26799774e+02 3.77861694e+02 3.26695831e+02 2.84148010e+02 2.46812683e+02 1.97883194e+02 1.40948944e+02 8.97397308e+01 4.27791481e+01 -8.86555314e-01 -4.90073776e+01 -9.97565231e+01 -1.50674713e+02 -1.99751526e+02 -2.42661591e+02 -2.95130493e+02 -3.43998688e+02 -3.85280701e+02 -4.35192444e+02 -4.77537048e+02 -5.24536499e+02 -5.78941101e+02 -6.22130615e+02 -6.83107239e+02 -7.30575439e+02 -7.55401978e+02 -8.08731873e+02 -8.49232422e+02 -8.95502808e+02 -9.49622375e+02 -1.00476697e+03 -1.06615649e+03 -1.10072827e+03 -1.14136633e+03 -1.18203174e+03 -1.23816125e+03 -1.31520093e+03 -1.35616724e+03 -1.37757153e+03 -1.41143958e+03 -1.45277368e+03 -1.51602832e+03 -1.58840186e+03 -1.63088818e+03 -1.66200159e+03 -1.70049011e+03 -1.73829224e+03 -1.79390833e+03 -1.86034607e+03 -1.89285950e+03 -1.93464526e+03 -1.98617224e+03 -2.02855420e+03 -2.08594824e+03 -2.08680957e+03 -2.14574561e+03 -2.25665332e+03 -2.26087451e+03 -2.28299707e+03 -2.36010522e+03 -2.36645435e+03 -2.40456104e+03 -2.55679883e+03 -2.59092529e+03 -2.51750708e+03 -2.57492993e+03 -2.65487500e+03 -2.67441943e+03 -2.77685156e+03 -2.80904077e+03 -2.77430493e+03 -2.85118481e+03 -2.91570898e+03 -2.99814771e+03 -3.05623218e+03 -3.05435425e+03 -3.12192407e+03 -3.11569849e+03 -3.09356104e+03 -3.19166455e+03 -3.30625806e+03 -3.32674219e+03 -3.37104297e+03 -3.41117896e+03 -3.31341675e+03 -3.42992627e+03 -3.62282422e+03 -3.61462793e+03 -3.59768750e+03 -3.53831836e+03 -3.60693896e+03 -3.77829565e+03 -3.79623730e+03 -3.78560693e+03 -3.87423877e+03 -3.87089111e+03 -3.91120947e+03 -3.97678247e+03 -3.90960962e+03 -3.95961450e+03 -4.11873340e+03 -4.19264209e+03 -4.15276367e+03 -4.08290161e+03 -4.12576318e+03 -4.27978271e+03 -4.38786816e+03 -4.37155518e+03 -4.30680078e+03 -4.29261035e+03 -4.41256152e+03 -4.54155957e+03 -4.65632324e+03 -4.59768848e+03 -4.51759961e+03 -4.60308008e+03 -4.63469678e+03 -4.65909814e+03 -4.75822607e+03 -4.75348975e+03 -4.80254443e+03 -4.91247559e+03 -4.84187939e+03 -4.85677881e+03 -4.95501318e+03 -4.98425537e+03 -5.04504053e+03 -5.01420264e+03 -4.93801416e+03 -5.03232959e+03 -5.16330859e+03 -5.25975684e+03 -5.32034961e+03 -5.23778369e+03 -5.14321436e+03 -5.24225391e+03 -5.25133008e+03 -5.31925684e+03 -5.48384814e+03 -5.39423193e+03 -5.36096387e+03 -5.37272949e+03 -5.42696924e+03 -5.58622021e+03 -5.70990723e+03 -5.65217188e+03 -5.59449609e+03 -5.57425293e+03 -5.48268213e+03 -5.60788721e+03 -5.78166748e+03 -5.85709473e+03 -5.82475537e+03 -5.69631543e+03 -5.70773340e+03 -5.80908545e+03 -5.90853564e+03 -5.92384473e+03 -5.95134961e+03 -5.92180029e+03 -5.84786328e+03 -5.98029980e+03 -6.12968066e+03 -6.09930371e+03 -5.94269043e+03 -6.03238281e+03 -6.11265283e+03 -6.15633154e+03 -6.18562354e+03 -6.15930615e+03 -6.25265479e+03 -6.20968555e+03 -6.13179639e+03 -6.30310791e+03 -6.30404932e+03 -6.24089551e+03 -6.39507129e+03 -6.30326416e+03 -6.17512744e+03 -6.39740479e+03 -6.39110205e+03 -6.41975000e+03 -6.70806885e+03 -6.62244043e+03 -6.33907715e+03 -6.48394971e+03 -8.76624805e+03 -1.03136396e+04 -1.71165684e+04 -2.01644434e+04 -11914131. -2.91965150e+06 5.01341750e+06 -35914360. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7938896. -17083144. 1.68124838e+06 7235108. 4.09605475e+06 -2.18553047e+04 -1.77106465e+04 -9.57482715e+03 -9.03665234e+03 -7.70607129e+03 -7.30382031e+03 -6.76672852e+03 -6.83577344e+03 -7.04058936e+03 -6.91332666e+03 -6.76958984e+03 -6.67670850e+03 -6.63035791e+03 -6.96771875e+03 -7.07661475e+03 -6.76601123e+03 -6.56383838e+03 -6.65735352e+03 -6.77797803e+03 -6.87202295e+03 -6.94647754e+03 -6.73093262e+03 -6.57083936e+03 -6.66182959e+03 -6.70245459e+03 -6.74015283e+03 -6.60068213e+03 -6.52247412e+03 -6.79333398e+03 -6.96916016e+03 -6.76453174e+03 -6.45754199e+03 -6.44338037e+03 -6.70777881e+03 -6.75657812e+03 -6.58147461e+03 -6.42407764e+03 -6.44665625e+03 -6.68029736e+03 -6.80989795e+03 -6.59614209e+03 -6.27128564e+03 -6.37602930e+03 -6.68290088e+03 -6.56875928e+03 -6.53628223e+03 -6.48124707e+03 -6.23253857e+03 -6.35375195e+03 -6.56062939e+03 -6.39257373e+03 -6.27917578e+03 -6.41845166e+03 -6.47270508e+03 -6.37684961e+03 -6.28661963e+03 -6.06180762e+03 -6.17220117e+03 -6.44579004e+03 -6.31102881e+03 -6.10497314e+03 -6.00437354e+03 -6.00011719e+03 -6.25468311e+03 -6.39729834e+03 -6.16483008e+03 -5.97581885e+03 -5.93259570e+03 -5.89812646e+03 -6.01964795e+03 -6.15248682e+03 -5.90152246e+03 -5.80032617e+03 -5.94099023e+03 -5.87753564e+03 -5.77680176e+03 -5.73504004e+03 -5.82229248e+03 -5.90695654e+03 -5.82809131e+03 -5.77655078e+03 -5.58577637e+03 -5.46795752e+03 -5.73613867e+03 -5.84588477e+03 -5.54184619e+03 -5.34905469e+03 -5.43811035e+03 -5.55780762e+03 -5.61616064e+03 -5.60934229e+03 -5.38113086e+03 -5.30884375e+03 -5.40290674e+03 -5.33539355e+03 -5.35224121e+03 -5.30144287e+03 -5.10543994e+03 -5.13992627e+03 -5.21727979e+03 -5.20882666e+03 -5.16449414e+03 -5.12526611e+03 -5.08889893e+03 -5.06029834e+03 -5.01815820e+03 -4.83238623e+03 -4.80232275e+03 -5.05324121e+03 -5.01881543e+03 -4.73672998e+03 -4.61317920e+03 -4.65795215e+03 -4.83676758e+03 -4.92074805e+03 -4.70320459e+03 -4.49765576e+03 -4.46246631e+03 -4.50655469e+03 -4.52020996e+03 -4.53288867e+03 -4.44731152e+03 -4.38595215e+03 -4.34942725e+03 -4.31563477e+03 -4.32184033e+03 -4.18972314e+03 -4.19990137e+03 -4.30457373e+03 -4.20315234e+03 -4.08810205e+03 -3.99467944e+03 -3.91280127e+03 -4.03587695e+03 -4.10300391e+03 -3.88049292e+03 -3.74811841e+03 -3.76149414e+03 -3.88693188e+03 -3.91273608e+03 -3.74833496e+03 -3.60662817e+03 -3.54210767e+03 -3.54648584e+03 -3.59168359e+03 -3.59314795e+03 -3.42125684e+03 -3.30215601e+03 -3.36769824e+03 -3.42427222e+03 -3.34305005e+03 -3.25265503e+03 -3.21609058e+03 -3.15859033e+03 -3.15428442e+03 -3.12638843e+03 -2.98143774e+03 -2.93635791e+03 -2.99834961e+03 -2.95637183e+03 -2.87346509e+03 -2.78139136e+03 -2.74448047e+03 -2.74437598e+03 -2.72966553e+03 -2.69892529e+03 -2.58841089e+03 -2.56252051e+03 -2.55212891e+03 -2.47991260e+03 -2.42476660e+03 -2.34996631e+03 -2.31815527e+03 -2.32969775e+03 -2.32041870e+03 -2.24423535e+03 -2.10477710e+03 -2.04594287e+03 -2.09137744e+03 -2.09682935e+03 -2.01415637e+03 -1.88548022e+03 -1.83106787e+03 -1.83005664e+03 -1.82491406e+03 -1.79023352e+03 -1.68179468e+03 -1.60353137e+03 -1.58505713e+03 -1.57343445e+03 -1.54423413e+03 -1.47276379e+03 -1.41215417e+03 -1.36833105e+03 -1.32668945e+03 -1.29243054e+03 -1.24037866e+03 -1.19595190e+03 -1.14031628e+03 -1.07538306e+03 -1.01912476e+03 -9.71229797e+02 -9.55628113e+02 -9.39991516e+02 -8.81106384e+02 -7.98495972e+02 -7.24103455e+02 -6.89531555e+02 -6.86676819e+02 -6.55071411e+02 -5.83263489e+02 -5.11429352e+02 -4.53918762e+02 -4.18359802e+02 -3.85737793e+02 -3.38471802e+02 -2.87705475e+02 -2.37485245e+02 -1.88132172e+02 -1.41224091e+02 -9.43746567e+01 -4.89322701e+01 -2.73105049e+00 4.74032249e+01 9.94260864e+01 1.50205002e+02 1.88314575e+02 2.37397232e+02 2.90653229e+02 3.37719330e+02 3.87276794e+02 4.31393890e+02 4.90384796e+02 5.42390747e+02 5.62624756e+02 5.92141479e+02 6.49821106e+02 7.32681824e+02 8.07871338e+02 8.39027527e+02 8.40731018e+02 8.64839233e+02 9.23732483e+02 1.01574060e+03 1.09993481e+03 1.13500867e+03 1.11386072e+03 1.15030103e+03 1.27694946e+03 1.31761255e+03 1.31037244e+03 1.35410107e+03 1.41734949e+03 1.46552026e+03 1.55849866e+03 1.58084106e+03 1.56700171e+03 1.64631885e+03 1.66572925e+03 1.75637891e+03 1.84546716e+03 1.80488416e+03 1.87123706e+03 1.97331226e+03 1.99279004e+03 2.02788416e+03 2.06746899e+03 2.12156519e+03 2.18936914e+03 2.19037598e+03 2.17380957e+03 2.25239624e+03 2.40763306e+03 2.50372925e+03 2.48927319e+03 2.43114087e+03 2.41203564e+03 2.50322974e+03 2.66244849e+03 2.78768774e+03 2.75582275e+03 2.66403125e+03 2.73250195e+03 2.85885034e+03 2.88219312e+03 2.89645142e+03 2.94687964e+03 2.99154126e+03 3.04243701e+03 3.18806592e+03 3.14554028e+03 3.10191089e+03 3.21037329e+03 3.16083423e+03 3.30422021e+03 3.45754883e+03 3.36666235e+03 3.51020728e+03 3.50297803e+03 3.37901953e+03 3.53617651e+03 3.51090430e+03 3.60184399e+03 3.88641919e+03 3.74585645e+03 3.57555737e+03 3.68166992e+03 3.90775879e+03 4.08165771e+03 4.02901636e+03 3.88130322e+03 3.81790771e+03 3.90126831e+03 4.11593896e+03 4.30412842e+03 4.27467578e+03 4.09278906e+03 4.10789502e+03 4.28235498e+03 4.34452100e+03 4.30231543e+03 4.30728223e+03 4.38152930e+03 4.41987646e+03 4.60520068e+03 4.66515332e+03 4.45334619e+03 4.45642432e+03 4.58558643e+03 4.63415869e+03 4.70970264e+03 4.73638916e+03 4.88742773e+03 4.81026611e+03 4.65555078e+03 4.86227002e+03 4.75588867e+03 4.90142871e+03 5.27873145e+03 5.01869336e+03 4.76587207e+03 4.90209473e+03 5.18470410e+03 5.35687793e+03 5.36451562e+03 5.10987646e+03 4.96160400e+03 5.09587598e+03 5.37339648e+03 5.60724707e+03 5.48426318e+03 5.19732666e+03 5.21004785e+03 5.40850684e+03 5.52128711e+03 5.66599707e+03 5.67913184e+03 5.40890430e+03 5.37047266e+03 5.65342188e+03 5.76379688e+03 5.63176660e+03 5.61659424e+03 5.67805176e+03 5.64548242e+03 5.89758936e+03 5.98480859e+03 5.72864551e+03 5.73951953e+03 5.82841504e+03 5.81506299e+03 5.90215918e+03 5.90125439e+03 6.06771045e+03 6.15926562e+03 5.98472119e+03 5.87567676e+03 5.81098242e+03 6.07762988e+03 6.39399219e+03 6.29516016e+03 6.02662256e+03 5.87514307e+03 6.10368408e+03 6.45375488e+03 6.27160645e+03 5.96941504e+03 6.08908252e+03 6.28027490e+03 6.42900439e+03 6.64892871e+03 6.51559424e+03 6.18665625e+03 6.09109033e+03 6.32563965e+03 6.53434229e+03 6.52826172e+03 6.44837500e+03 6.43416846e+03 6.44299512e+03 6.59962842e+03 6.52890674e+03 6.35466309e+03 6.45332471e+03 6.37097168e+03 6.64603857e+03 6.84969385e+03 6.57792871e+03 6.65186426e+03 6.64079883e+03 6.66252686e+03 6.52906299e+03 6.38738037e+03 6.68343457e+03 7.02378369e+03 6.83616553e+03 6.49693945e+03 6.50736475e+03 6.89391162e+03 6.95865576e+03 6.80565430e+03 6.78054541e+03 6.56366113e+03 6.52791846e+03 6.87730664e+03 6.86995996e+03 6.71734814e+03 6.60713086e+03 6.52208203e+03 6.84948926e+03 7.17757373e+03 6.84194238e+03 6.60094336e+03 6.80221094e+03 6.83465479e+03 7.02444189e+03 7.06087256e+03 6.64353418e+03 6.62167041e+03 6.84054053e+03 6.82355762e+03 6.89242090e+03 7.00805127e+03 6.84768945e+03 7.38764795e+03 7.29839648e+03 6.80935352e+03 8.54031152e+03 9.58301172e+03 1.86273848e+04 1.19021191e+04 2.00692344e+04 1.99386016e+04 -3.03897675e+06 -6.12702950e+06 2.78608075e+06 -3586535. 6.41523750e+06 2244814. 7399735. 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. 0. 0. -249400496. -249400496. -249400496. 0. 0. 3318850. 4221781. 2.21180575e+06 2.00392910e+04 1.63375947e+04 1.07579980e+04 1.03559424e+04 8.56783984e+03 8.22499316e+03 6.66815918e+03 6.60705615e+03 6.38557178e+03 6.18226270e+03 6.37912012e+03 6.31888428e+03 6.18282031e+03 6.21514844e+03 6.19100391e+03 6.13387744e+03 6.13942236e+03 6.10910645e+03 6.03801025e+03 5.96079932e+03 5.91579395e+03 6.08400928e+03 6.10212451e+03 5.79050244e+03 5.77510156e+03 6.03262207e+03 6.04557666e+03 5.90709033e+03 5.85275586e+03 5.81078613e+03 5.76301465e+03 5.75812891e+03 5.75184277e+03 5.71473438e+03 5.66913281e+03 5.51195557e+03 5.45549902e+03 5.72467334e+03 5.72494336e+03 5.51083984e+03 5.48910156e+03 5.47940137e+03 5.48570361e+03 5.41932666e+03 5.36419531e+03 5.35910840e+03 5.25938965e+03 5.22064990e+03 5.22036084e+03 5.17560303e+03 5.34771143e+03 5.35463867e+03 5.14726416e+03 4.97001318e+03 4.91175928e+03 5.18594141e+03 5.18466260e+03 4.98197119e+03 4.87035303e+03 4.86277832e+03 4.90217969e+03 4.82173340e+03 4.92252002e+03 4.89947168e+03 4.60027881e+03 4.51881396e+03 4.72102637e+03 4.86793066e+03 4.71581299e+03 4.58298340e+03 4.53455127e+03 4.47590723e+03 4.44245850e+03 4.42605908e+03 4.43916602e+03 4.38201562e+03 4.26986328e+03 4.24018066e+03 4.21971631e+03 4.18840332e+03 4.26879883e+03 4.21899707e+03 4.06725488e+03 4.03256128e+03 3.98829199e+03 4.06707910e+03 4.05002808e+03 3.91106909e+03 3.86801685e+03 3.75693457e+03 3.65676685e+03 3.80062671e+03 3.74196924e+03 3.50893506e+03 3.52516333e+03 3.68360815e+03 3.77228394e+03 3.59925659e+03 3.45901807e+03 3.39481128e+03 3.34376538e+03 3.32211890e+03 3.27955737e+03 3.24153735e+03 3.18411499e+03 3.23133618e+03 3.17787231e+03 3.05407104e+03 3.03202100e+03 2.90253027e+03 2.91592993e+03 3.05560181e+03 2.95328906e+03 2.83265112e+03 2.71053882e+03 2.65192261e+03 2.77013599e+03 2.73746851e+03 2.60403784e+03 2.50150781e+03 2.44799463e+03 2.46388623e+03 2.42290479e+03 2.45033862e+03 2.42089771e+03 2.29498877e+03 2.22593262e+03 2.18937012e+03 2.19317871e+03 2.14531860e+03 2.06630835e+03 2.00436304e+03 1.95874963e+03 1.92265356e+03 1.82438403e+03 1.81872546e+03 1.87622375e+03 1.79422437e+03 1.70406946e+03 1.61422583e+03 1.56464526e+03 1.61187549e+03 1.56317456e+03 1.46928735e+03 1.38290173e+03 1.33366357e+03 1.33830640e+03 1.28283057e+03 1.23474976e+03 1.15978833e+03 1.13373279e+03 1.14864319e+03 1.07187207e+03 1.00905969e+03 9.70107971e+02 9.12797363e+02 8.47514587e+02 8.03347717e+02 7.62526550e+02 7.10998718e+02 6.70457031e+02 6.05790283e+02 5.63924255e+02 5.50359314e+02 4.80561096e+02 4.16498749e+02 3.80626556e+02 3.32908783e+02 2.93240753e+02 2.43149002e+02 1.88642548e+02 1.47089966e+02 9.84341354e+01 4.74286194e+01 -6.49889231e-01 -4.84326744e+01 -9.43556976e+01 -1.40244110e+02 -1.88671112e+02 -2.31426483e+02 -2.86235870e+02 -3.52745819e+02 -3.95367920e+02 -4.26413147e+02 -4.57873535e+02 -5.10828857e+02 -5.92262390e+02 -6.40873718e+02 -6.68887146e+02 -7.00708801e+02 -7.42783752e+02 -8.09281677e+02 -8.60195862e+02 -9.25698853e+02 -9.60864380e+02 -9.80545166e+02 -1.03594873e+03 -1.08423108e+03 -1.16950684e+03 -1.21103101e+03 -1.22165051e+03 -1.27096375e+03 -1.31809204e+03 -1.36358374e+03 -1.37671985e+03 -1.46996790e+03 -1.60775598e+03 -1.60301428e+03 -1.60342029e+03 -1.61611963e+03 -1.64865735e+03 -1.79611780e+03 -1.85215515e+03 -1.84611133e+03 -1.84852039e+03 -1.88000903e+03 -1.98442566e+03 -2.02818335e+03 -2.12498413e+03 -2.17828784e+03 -2.16485522e+03 -2.14707080e+03 -2.18329419e+03 -2.36426807e+03 -2.39713550e+03 -2.37344702e+03 -2.38454517e+03 -2.41655786e+03 -2.59630981e+03 -2.65260254e+03 -2.54600122e+03 -2.58243799e+03 -2.77516919e+03 -2.81488306e+03 -2.71628247e+03 -2.75263501e+03 -2.93762451e+03 -3.00287329e+03 -2.95124487e+03 -2.92345288e+03 -2.96902710e+03 -3.16687109e+03 -3.18147437e+03 -3.12964722e+03 -3.21991846e+03 -3.25451855e+03 -3.27724731e+03 -3.32313647e+03 -3.36553003e+03 -3.32584302e+03 -3.44308105e+03 -3.63011670e+03 -3.59292139e+03 -3.65091992e+03 -3.70786523e+03 -3.66623462e+03 -3.71019824e+03 -3.75530737e+03 -3.77416040e+03 -3.73828198e+03 -3.77502832e+03 -3.89766895e+03 -3.94726392e+03 -4.09075317e+03 -4.02830420e+03 -3.93880908e+03 -4.09564258e+03 -4.16590186e+03 -4.31534863e+03 -4.30815479e+03 -4.20573535e+03 -4.22553809e+03 -4.23579639e+03 -4.36220264e+03 -4.40422363e+03 -4.53081006e+03 -4.56156299e+03 -4.49316895e+03 -4.50132178e+03 -4.41085254e+03 -4.58344531e+03 -4.86986963e+03 -4.85038232e+03 -4.73598975e+03 -4.63585010e+03 -4.60465820e+03 -4.87314648e+03 -5.04757471e+03 -4.96119434e+03 -4.80697168e+03 -4.82902734e+03 -4.98102930e+03 -5.03196289e+03 -5.16597510e+03 -5.17751172e+03 -5.08262158e+03 -5.09447705e+03 -5.11474219e+03 -5.34279248e+03 -5.40545264e+03 -5.13132617e+03 -5.15680908e+03 -5.46465186e+03 -5.46797461e+03 -5.20502344e+03 -5.31004590e+03 -5.64385596e+03 -5.63796289e+03 -5.53567139e+03 -5.40528369e+03 -5.41981445e+03 -5.77045752e+03 -5.78492383e+03 -5.65499219e+03 -5.54916211e+03 -5.51477051e+03 -5.68088232e+03 -5.76219580e+03 -5.82730664e+03 -5.65959277e+03 -5.81177393e+03 -6.08896875e+03 -5.95869971e+03 -6.00084424e+03 -5.97233105e+03 -5.88521045e+03 -5.98329980e+03 -6.02918213e+03 -6.05948486e+03 -6.02522070e+03 -5.95826514e+03 -5.87338916e+03 -6.06252881e+03 -6.39793115e+03 -6.13700928e+03 -5.89913770e+03 -6.12240186e+03 -6.29909473e+03 -6.55063428e+03 -6.38895850e+03 -6.20858496e+03 -6.37143799e+03 -6.38144629e+03 -6.22656982e+03 -6.18731787e+03 -6.45120459e+03 -6.44335889e+03 -6.35273975e+03 -6.33223193e+03 -6.16369629e+03 -6.38199561e+03 -6.81939795e+03 -6.64352588e+03 -6.46817822e+03 -6.32597803e+03 -6.26749268e+03 -6.61757373e+03 -6.93202686e+03 -6.70889551e+03 -6.44487158e+03 -6.46571582e+03 -6.54351904e+03 -6.58018652e+03 -6.80547998e+03 -6.71727832e+03 -6.53557666e+03 -6.61903174e+03 -6.60977295e+03 -6.84545557e+03 -6.83785498e+03 -6.63722705e+03 -6.66012549e+03 -6.68767090e+03 -6.78378711e+03 -6.62502588e+03 -6.62747607e+03 -6.93244678e+03 -6.88551562e+03 -6.77469824e+03 -6.59645654e+03 -6.61916797e+03 -7.08847363e+03 -7.04498828e+03 -6.80469824e+03 -6.67833789e+03 -6.64258398e+03 -6.73458740e+03 -6.78749268e+03 -6.85141113e+03 -6.70303516e+03 -6.79397363e+03 -7.08299414e+03 -6.83834912e+03 -6.96953076e+03 -7.02744531e+03 -6.83618262e+03 -6.79840576e+03 -6.76011084e+03 -6.84620752e+03 -6.85107568e+03 -6.76265723e+03 -6.77021045e+03 -6.93987451e+03 -7.02219141e+03 -6.67236621e+03 -6.60000684e+03 -6.77338477e+03 -6.92400146e+03 -7.13742236e+03 -6.95728906e+03 -6.66770947e+03 -6.83752100e+03 -6.99008008e+03 -6.87326562e+03 -6.78145068e+03 -6.74883594e+03 -6.67063525e+03 -6.66266211e+03 -6.78337793e+03 -6.65684277e+03 -6.71770947e+03 -7.00664453e+03 -6.90792139e+03 -6.73216211e+03 -6.63689551e+03 -6.62383057e+03 -6.90551416e+03 -6.89056250e+03 -6.71447803e+03 -6.54107324e+03 -6.39040674e+03 -6.52444189e+03 -6.80648828e+03 -6.97557666e+03 -6.72269824e+03 -6.46824756e+03 -6.51639453e+03 -6.54569580e+03 -6.81689893e+03 -6.74072021e+03 -6.51630420e+03 -6.47407178e+03 -6.42531885e+03 -6.53321582e+03 -6.42319922e+03 -6.41235791e+03 -6.67890576e+03 -6.59195850e+03 -6.46884619e+03 -6.30543408e+03 -6.25951562e+03 -6.61172070e+03 -6.58791406e+03 -6.34714746e+03 -6.21690967e+03 -6.13580957e+03 -6.27541016e+03 -6.32097412e+03 -6.48950391e+03 -6.43282959e+03 -6.20926025e+03 -6.01076855e+03 -6.09918408e+03 -6.42033301e+03 -6.29230225e+03 -6.11618018e+03 -6.05516260e+03 -6.03676416e+03 -6.00193701e+03 -5.92967529e+03 -6.06675684e+03 -6.02897803e+03 -5.87950098e+03 -6.06874805e+03 -6.11792285e+03 -5.97072070e+03 -5.88528027e+03 -5.83506104e+03 -5.83608838e+03 -5.66864990e+03 -5.59133740e+03 -5.85887451e+03 -5.87611523e+03 -5.53642920e+03 -5.41650342e+03 -5.68762842e+03 -5.87374561e+03 -5.75489941e+03 -5.51145605e+03 -5.37071631e+03 -5.54961084e+03 -5.59755566e+03 -5.46833350e+03 -5.46039795e+03 -5.30982324e+03 -5.07412891e+03 -5.24111621e+03 -5.53512158e+03 -5.49236475e+03 -5.16020605e+03 -4.99014844e+03 -5.26328418e+03 -5.38427930e+03 -5.17897363e+03 -4.97698975e+03 -4.88270801e+03 -4.94014844e+03 -4.94880273e+03 -5.10169531e+03 -5.07935400e+03 -4.86945752e+03 -4.78458496e+03 -4.74412988e+03 -4.88932471e+03 -4.77609473e+03 -4.60934229e+03 -4.76785596e+03 -4.73420996e+03 -4.62829541e+03 -4.50169775e+03 -4.44071143e+03 -4.65785986e+03 -4.49892090e+03 -4.27527979e+03 -4.35055566e+03 -4.40839307e+03 -4.37655615e+03 -4.28378516e+03 -4.35280664e+03 -4.33999902e+03 -4.18533447e+03 -4.02625317e+03 -3.97858594e+03 -4.16647070e+03 -4.08012427e+03 -3.93433618e+03 -3.91977295e+03 -3.87353662e+03 -3.89437769e+03 -3.83505249e+03 -3.84111597e+03 -3.75667700e+03 -3.64051025e+03 -3.72248389e+03 -3.70803760e+03 -3.61220532e+03 -3.55864795e+03 -3.51910718e+03 -3.44964014e+03 -3.30809082e+03 -3.26285352e+03 -3.39264307e+03 -3.46879565e+03 -3.25382153e+03 -3.07258130e+03 -3.16124146e+03 -3.25418750e+03 -3.17076440e+03 -3.01250293e+03 -2.89427856e+03 -3.00161475e+03 -2.96607642e+03 -2.82156934e+03 -2.90843506e+03 -2.83794165e+03 -2.64745508e+03 -2.63878442e+03 -2.72579395e+03 -2.69939771e+03 -2.53407739e+03 -2.42260986e+03 -2.48912744e+03 -2.54521680e+03 -2.43818384e+03 -2.28226465e+03 -2.20049243e+03 -2.28325293e+03 -2.27201050e+03 -2.14765381e+03 -2.11878247e+03 -2.09229639e+03 -2.01573718e+03 -1.95233350e+03 -1.97937317e+03 -1.89485974e+03 -1.78676001e+03 -1.81181189e+03 -1.77645996e+03 -1.73430371e+03 -1.64908875e+03 -1.56595374e+03 -1.58812915e+03 -1.50820422e+03 -1.42573853e+03 -1.44420312e+03 -1.48441113e+03 -1.46165710e+03 -1.26577405e+03 -1.32018884e+03 -1.37178711e+03 -1.02860022e+03 -1.01851617e+03 -1.00777637e+03 -1.04962207e+03 -1.58134924e+03 -1.39553113e+03 -1.16980615e+03 -1.85431360e+03 -3.10797974e+03 -8.61803750e+05 -3.44552986e+09 0. 0. 0. 0. 1381557632. 1381557632. 8.02582875e+05 -231494368. -4.65549170e+03 -3.54991016e+04 -5.51520508e+04 -1.22436906e+05 1129844736. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 469363232. 1.79326781e+05 1.31527771e+03 1.47304993e+03 1.02846533e+03 9.17847290e+02 1.07899292e+03 1.31368164e+03 1.17492212e+03 9.69030457e+02 1.11005408e+03 1.03423889e+03 1.05474866e+03 1.10661804e+03 1.14860608e+03 1.18521460e+03 1.24145007e+03 1.27328186e+03 1.30897717e+03 1.39327783e+03 1.44876819e+03 1.47910645e+03 1.51789246e+03 1.52306238e+03 1.57596082e+03 1.66724878e+03 1.69779993e+03 1.72218408e+03 1.81802551e+03 1.91544727e+03 1.91213928e+03 1.90599304e+03 1.94598157e+03 1.98184241e+03 2.07094067e+03 2.16564868e+03 2.17195166e+03 2.20956592e+03 2.29106909e+03 2.29970093e+03 2.30526733e+03 2.36382056e+03 2.40502197e+03 2.46126270e+03 2.57381812e+03 2.57629370e+03 2.57544507e+03 2.68080322e+03 2.69710571e+03 2.70543457e+03 2.75707324e+03 2.80465576e+03 2.87950244e+03 2.95029736e+03 3.02840918e+03 3.02366943e+03 3.00617651e+03 3.10362280e+03 3.08213623e+03 3.08784253e+03 3.24314331e+03 3.26997925e+03 3.28779785e+03 3.38849048e+03 3.41884985e+03 3.39313159e+03 3.43085400e+03 3.46164648e+03 3.50015039e+03 3.59381665e+03 3.64523364e+03 3.69178931e+03 3.73874756e+03 3.75414014e+03 3.78888330e+03 3.81890332e+03 3.88062769e+03 3.90537231e+03 3.95250342e+03 4.10255029e+03 4.05592993e+03 3.93669116e+03 4.06392017e+03 4.11690039e+03 4.13128369e+03 4.28101465e+03 4.25963232e+03 4.24776562e+03 4.40461621e+03 4.50341162e+03 4.42114160e+03 4.34049219e+03 4.37750439e+03 4.45956348e+03 4.57343994e+03 4.62209033e+03 4.67268701e+03 4.72957178e+03 4.73678027e+03 4.69722754e+03 4.65631152e+03 4.80130664e+03 4.85870215e+03 4.79470361e+03 4.92281885e+03 4.95096729e+03 4.94221387e+03 5.04984033e+03 5.00480908e+03 4.94793018e+03 5.02515674e+03 5.16450049e+03 5.23412500e+03 5.19852734e+03 5.23629688e+03 5.30731934e+03 5.34552783e+03 5.34894824e+03 5.26221533e+03 5.24599268e+03 5.47898145e+03 5.51185645e+03 5.39555957e+03 5.49943408e+03 5.47677344e+03 5.46618945e+03 5.61908936e+03 5.62747461e+03 5.54802002e+03 5.62568701e+03 5.79391797e+03 5.82820410e+03 5.77295605e+03 5.62496533e+03 5.64159473e+03 5.85438379e+03 5.92543848e+03 5.79931592e+03 5.85728613e+03 6.04241357e+03 6.04137354e+03 6.01114258e+03 5.97824072e+03 5.85599609e+03 5.85932910e+03 5.97869629e+03 6.12938818e+03 6.12990967e+03 6.09865039e+03 6.22310156e+03 6.22554395e+03 6.12710791e+03 6.09916113e+03 6.13958936e+03 6.19544238e+03 6.30791748e+03 6.43709766e+03 6.39330322e+03 6.33808252e+03 6.24125146e+03 6.37910742e+03 6.41998682e+03 6.21561377e+03 6.23892188e+03 6.46775586e+03 6.60512695e+03 6.40787256e+03 6.36773730e+03 6.37714844e+03 6.37878223e+03 6.52394043e+03 6.66255469e+03 6.63115186e+03 6.54237402e+03 6.56960059e+03 6.61757568e+03 6.52387109e+03 6.52575342e+03 6.56974805e+03 6.56969531e+03 6.76962988e+03 6.84662793e+03 6.57759619e+03 6.57944482e+03 6.65325488e+03 6.69468945e+03 6.82065527e+03 6.56277393e+03 6.51764307e+03 6.83185107e+03 6.88610254e+03 6.73696436e+03 6.69415967e+03 6.71619287e+03 6.67858008e+03 6.73914307e+03 6.88001562e+03 6.85147363e+03 6.70094678e+03 6.81089160e+03 6.99510986e+03 6.84072021e+03 6.77690137e+03 6.76024707e+03 6.75594629e+03 6.95810645e+03 6.84964209e+03 6.77619580e+03 6.96617383e+03 6.76224121e+03 6.73566602e+03 6.88871338e+03 6.74060059e+03 6.75574072e+03 6.93128516e+03 6.92622705e+03 6.91152295e+03 6.79849854e+03 6.86700391e+03 6.79424854e+03 6.75961133e+03 6.94223975e+03 6.75220996e+03 6.69753564e+03 6.88569238e+03 6.92360010e+03 6.80819873e+03 6.87067529e+03 6.93767969e+03 6.74031445e+03 6.85018457e+03 7.03573486e+03 6.75670947e+03 6.66653223e+03 6.74882324e+03 6.77129541e+03 6.68771875e+03 6.67691895e+03 6.72054883e+03 6.78013574e+03 6.84926660e+03 6.81885645e+03 6.71025000e+03 6.70842285e+03 6.68488721e+03 6.63540967e+03 6.77216846e+03 6.61868799e+03 6.60541309e+03 6.79363281e+03 6.63680322e+03 6.55005078e+03 6.61397510e+03 6.60330029e+03 6.51044922e+03 6.52942676e+03 6.58835449e+03 6.63650586e+03 6.59118945e+03 6.52562061e+03 6.57387646e+03 6.41329834e+03 6.39243311e+03 6.43061084e+03 6.33306104e+03 6.50671875e+03 6.60287500e+03 6.37383252e+03 6.27070068e+03 6.31867334e+03 6.50505273e+03 6.40814355e+03 6.10480713e+03 6.26913135e+03 6.44229736e+03 6.25463721e+03 6.18199023e+03 6.16044238e+03 6.16211035e+03 6.16372803e+03 6.12278906e+03 6.03825732e+03 6.19145947e+03 6.16879688e+03 6.04068115e+03 6.10852148e+03 6.08641895e+03 6.00242969e+03 5.96956299e+03 5.76678320e+03 5.93033301e+03 6.10633691e+03 5.82773975e+03 5.75680566e+03 5.80482373e+03 5.83160254e+03 5.82934668e+03 5.66702051e+03 5.73481250e+03 5.81688135e+03 5.71731104e+03 5.67760645e+03 5.59224756e+03 5.51016064e+03 5.54250488e+03 5.56757861e+03 5.49302002e+03 5.52139990e+03 5.52539258e+03 5.42574268e+03 5.45990332e+03 5.41972412e+03 5.28644043e+03 5.24368994e+03 5.30492285e+03 5.33189453e+03 5.18497021e+03 5.09850586e+03 5.07540625e+03 5.10725684e+03 5.15276318e+03 5.08834424e+03 4.95322021e+03 4.93261328e+03 4.99773486e+03 5.05927344e+03 4.92661914e+03 4.74065430e+03 4.78848438e+03 4.82300732e+03 4.72577539e+03 4.70286084e+03 4.72664355e+03 4.68881006e+03 4.61394873e+03 4.63846191e+03 4.61897852e+03 4.49904785e+03 4.44236865e+03 4.42816455e+03 4.42994141e+03 4.29033545e+03 4.20111182e+03 4.26945850e+03 4.28858545e+03 4.28736865e+03 4.19831494e+03 4.08049585e+03 4.14190820e+03 4.14315479e+03 3.96989258e+03 3.90980469e+03 3.95561255e+03 3.98293628e+03 3.91622778e+03 3.77626831e+03 3.69912451e+03 3.70514502e+03 3.75563916e+03 3.75673364e+03 3.71935815e+03 3.58533813e+03 3.47931104e+03 3.47512207e+03 3.41953149e+03 3.39024512e+03 3.37554785e+03 3.32880493e+03 3.31046387e+03 3.25710767e+03 3.20360815e+03 3.15041431e+03 3.12892700e+03 3.17166406e+03 3.09013306e+03 2.94530811e+03 2.90188721e+03 2.91571851e+03 2.91040259e+03 2.89037329e+03 2.81431714e+03 2.67284937e+03 2.62915479e+03 2.66964429e+03 2.66284839e+03 2.61696167e+03 2.52521289e+03 2.43256104e+03 2.42045166e+03 2.38493652e+03 2.35602832e+03 2.29770508e+03 2.19425830e+03 2.20945337e+03 2.20570215e+03 2.11765625e+03 2.04125940e+03 1.96394885e+03 1.96019507e+03 2.00580542e+03 1.93750305e+03 1.81381360e+03 1.79856360e+03 1.79788770e+03 1.69196313e+03 1.62635071e+03 1.56959949e+03 1.53582239e+03 1.55413208e+03 1.49083154e+03 1.39539807e+03 1.37009070e+03 1.34591284e+03 1.27825415e+03 1.22953076e+03 1.19894006e+03 1.14677368e+03 1.08660693e+03 1.04652026e+03 9.92157532e+02 9.60292358e+02 9.24846436e+02 8.68824890e+02 8.17283386e+02 7.44989319e+02 7.03078796e+02 6.67825867e+02 6.19569092e+02 5.81161743e+02 5.34782593e+02 4.84956787e+02 4.24599548e+02 3.76266022e+02 3.35878357e+02 2.88899750e+02 2.37138275e+02 1.83619797e+02 1.36481857e+02 9.18036728e+01 4.66326714e+01 3.51872826e+00 -4.33503799e+01 -9.30369873e+01 -1.48426651e+02 -2.00600769e+02 -2.42849518e+02 -2.87816803e+02 -3.29787750e+02 -3.74876526e+02 -4.38010010e+02 -4.89078522e+02 -5.16528870e+02 -5.57286621e+02 -6.18853699e+02 -6.83847656e+02 -7.30542786e+02 -7.58298828e+02 -7.99178406e+02 -8.54376160e+02 -9.09917542e+02 -9.53669434e+02 -9.89319458e+02 -1.04544507e+03 -1.10217041e+03 -1.13930981e+03 -1.19681995e+03 -1.24128809e+03 -1.28248425e+03 -1.34572131e+03 -1.38454309e+03 -1.42565649e+03 -1.45972131e+03 -1.50330347e+03 -1.56747729e+03 -1.62083777e+03 -1.67224231e+03 -1.69281140e+03 -1.72050916e+03 -1.80478052e+03 -1.86020996e+03 -1.89887207e+03 -1.94839966e+03 -1.95114026e+03 -2.00358057e+03 -2.10417798e+03 -2.12728369e+03 -2.12759448e+03 -2.23105737e+03 -2.28149023e+03 -2.25199170e+03 -2.35788281e+03 -2.40543408e+03 -2.38778979e+03 -2.50589038e+03 -2.57230200e+03 -2.54506494e+03 -2.58773560e+03 -2.66834619e+03 -2.69337671e+03 -2.75148022e+03 -2.79134229e+03 -2.76582349e+03 -2.84017407e+03 -2.95172437e+03 -3.00011377e+03 -3.03913501e+03 -3.04012158e+03 -3.08771948e+03 -3.11469482e+03 -3.10795679e+03 -3.22907935e+03 -3.28805859e+03 -3.26110840e+03 -3.37185767e+03 -3.41639160e+03 -3.37057690e+03 -3.47637134e+03 -3.55049146e+03 -3.57708936e+03 -3.61034106e+03 -3.58771265e+03 -3.58962256e+03 -3.74833984e+03 -3.87050464e+03 -3.79396704e+03 -3.82020337e+03 -3.82214990e+03 -3.87409448e+03 -4.03101440e+03 -3.97052808e+03 -3.94314111e+03 -4.07377368e+03 -4.16485840e+03 -4.15765381e+03 -4.07278687e+03 -4.20897217e+03 -4.32709766e+03 -4.28535596e+03 -4.34965576e+03 -4.32554785e+03 -4.36365918e+03 -4.49382275e+03 -4.51037354e+03 -4.58258789e+03 -4.52191846e+03 -4.51426416e+03 -4.61742383e+03 -4.63907959e+03 -4.74407373e+03 -4.73922070e+03 -4.67768018e+03 -4.77188672e+03 -4.89042432e+03 -4.90617285e+03 -4.89098193e+03 -4.92860693e+03 -4.96632959e+03 -5.02327441e+03 -5.02744336e+03 -4.97743262e+03 -5.14785254e+03 -5.16728418e+03 -5.14091895e+03 -5.27689160e+03 -5.22636719e+03 -5.16912598e+03 -5.32250293e+03 -5.26463965e+03 -5.27431250e+03 -5.44451514e+03 -5.39991162e+03 -5.36019629e+03 -5.41752002e+03 -5.49235254e+03 -5.53029248e+03 -5.65365430e+03 -5.60644629e+03 -5.55450293e+03 -5.61495850e+03 -5.56787988e+03 -5.64159033e+03 -5.68812939e+03 -5.76305518e+03 -5.85805420e+03 -5.71403223e+03 -5.82483789e+03 -5.85586133e+03 -5.75732861e+03 -5.86355469e+03 -5.93002393e+03 -6.02142627e+03 -5.96606396e+03 -5.91167578e+03 -6.04312793e+03 -6.04016064e+03 -6.02543213e+03 -6.03766504e+03 -6.08351074e+03 -6.22078516e+03 -6.14861426e+03 -6.13873096e+03 -6.24234521e+03 -6.14377002e+03 -6.12552539e+03 -6.32053125e+03 -6.37206201e+03 -6.20562256e+03 -6.28544238e+03 -6.27448633e+03 -6.21524951e+03 -6.55924170e+03 -6.45454736e+03 -6.30336963e+03 -6.66839941e+03 -6.59553662e+03 -6.42825342e+03 -6.47548926e+03 -8.30529297e+03 -8.98740039e+03 -1.66407773e+04 -2.00054824e+04 1.40079388e+06 -7004084. 4.11939175e+06 -5.13831350e+06 7554618. 49093276. 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. 0. 0. 0. 0. 0. 0. 0. 0. 7938896. -17083144. 1.68124838e+06 7235108. 4.09605475e+06 -2.18553047e+04 -1.77106465e+04 -1.09506572e+04 -8.75546191e+03 -9.17402051e+03 -7.57031787e+03 -6.88159229e+03 -6.78432129e+03 -6.94882373e+03 -6.86839551e+03 -6.79453662e+03 -6.76366846e+03 -6.83448682e+03 -6.91951074e+03 -6.91490186e+03 -6.75738379e+03 -6.60192822e+03 -6.81466064e+03 -6.89747852e+03 -6.80179346e+03 -6.84163623e+03 -6.66145557e+03 -6.64291943e+03 -6.73573682e+03 -6.77505225e+03 -6.80337598e+03 -6.56190674e+03 -6.46857422e+03 -6.80300391e+03 -6.95274902e+03 -6.75617822e+03 -6.42327197e+03 -6.43303809e+03 -6.67192236e+03 -6.71490527e+03 -6.58702441e+03 -6.44660010e+03 -6.60273584e+03 -6.72163965e+03 -6.62960742e+03 -6.57822998e+03 -6.29443848e+03 -6.41169434e+03 -6.70378076e+03 -6.55430322e+03 -6.49171387e+03 -6.43203174e+03 -6.25945312e+03 -6.38090771e+03 -6.57782324e+03 -6.46382031e+03 -6.21768457e+03 -6.36021924e+03 -6.40852930e+03 -6.30401709e+03 -6.32297314e+03 -6.14637158e+03 -6.28426611e+03 -6.32931396e+03 -6.18867676e+03 -6.09452686e+03 -6.00846387e+03 -6.15037109e+03 -6.31809277e+03 -6.23673438e+03 -6.09247754e+03 -5.94693604e+03 -5.99155518e+03 -5.98940479e+03 -6.04903760e+03 -6.07045020e+03 -5.84411963e+03 -5.88872461e+03 -6.00545117e+03 -5.93574609e+03 -5.86364014e+03 -5.67802148e+03 -5.74193896e+03 -5.90228418e+03 -5.85107227e+03 -5.73597266e+03 -5.57284619e+03 -5.56663818e+03 -5.68844385e+03 -5.74698828e+03 -5.57509961e+03 -5.42036963e+03 -5.58700342e+03 -5.53984619e+03 -5.44057959e+03 -5.55663867e+03 -5.38431396e+03 -5.35773926e+03 -5.44098145e+03 -5.36312109e+03 -5.36434570e+03 -5.21203271e+03 -5.08250537e+03 -5.20514502e+03 -5.27950977e+03 -5.24382422e+03 -5.09352979e+03 -5.05405518e+03 -5.05684766e+03 -5.04149365e+03 -5.01413623e+03 -4.85549707e+03 -4.88471631e+03 -5.01320996e+03 -4.93669678e+03 -4.75781934e+03 -4.61846582e+03 -4.71671729e+03 -4.90461963e+03 -4.81816943e+03 -4.65425488e+03 -4.49860986e+03 -4.48506592e+03 -4.55142334e+03 -4.57334180e+03 -4.57517725e+03 -4.39483740e+03 -4.34098584e+03 -4.33657080e+03 -4.32334375e+03 -4.38806689e+03 -4.20310156e+03 -4.15442578e+03 -4.25520215e+03 -4.15333838e+03 -4.07539966e+03 -4.02836987e+03 -4.01512451e+03 -4.04499292e+03 -3.98450000e+03 -3.85494775e+03 -3.74003076e+03 -3.81743701e+03 -3.92956030e+03 -3.83086475e+03 -3.69367627e+03 -3.57992676e+03 -3.57436743e+03 -3.60910059e+03 -3.59731860e+03 -3.55257056e+03 -3.37359033e+03 -3.32273926e+03 -3.37518091e+03 -3.40192432e+03 -3.38548438e+03 -3.27441772e+03 -3.18749902e+03 -3.11828735e+03 -3.12101196e+03 -3.13245850e+03 -3.02517529e+03 -2.98109106e+03 -2.96791919e+03 -2.91875439e+03 -2.89681470e+03 -2.78729614e+03 -2.76926343e+03 -2.78441089e+03 -2.69116260e+03 -2.67333569e+03 -2.59876831e+03 -2.55228418e+03 -2.54581079e+03 -2.50045972e+03 -2.44049634e+03 -2.31977026e+03 -2.29948218e+03 -2.33247363e+03 -2.32284277e+03 -2.25010278e+03 -2.10340723e+03 -2.04752637e+03 -2.07422388e+03 -2.06737476e+03 -2.00572876e+03 -1.88563147e+03 -1.85580371e+03 -1.84851074e+03 -1.79925232e+03 -1.77721533e+03 -1.67873596e+03 -1.62481396e+03 -1.62630139e+03 -1.58979944e+03 -1.52816284e+03 -1.45336548e+03 -1.41926868e+03 -1.37036609e+03 -1.32785608e+03 -1.31265259e+03 -1.23192969e+03 -1.17546863e+03 -1.14194910e+03 -1.08550159e+03 -1.03309009e+03 -9.90593201e+02 -9.69205383e+02 -9.29329834e+02 -8.70427307e+02 -8.02182861e+02 -7.28383667e+02 -7.08298645e+02 -6.98129456e+02 -6.41079712e+02 -5.76928345e+02 -5.09848267e+02 -4.56942505e+02 -4.26781097e+02 -3.96331055e+02 -3.44482697e+02 -2.87181793e+02 -2.39493607e+02 -1.92624420e+02 -1.44565399e+02 -9.50214386e+01 -4.48266411e+01 3.21829438e+00 5.19872208e+01 1.01183472e+02 1.47471283e+02 1.85214828e+02 2.39717270e+02 2.90490173e+02 3.27712830e+02 3.82185089e+02 4.31152191e+02 4.89147278e+02 5.37359070e+02 5.58108154e+02 5.98585022e+02 6.56534119e+02 7.34054260e+02 8.09839355e+02 8.36119690e+02 8.38182617e+02 8.63083862e+02 9.30731018e+02 1.02631921e+03 1.09848621e+03 1.13059839e+03 1.10971484e+03 1.14895728e+03 1.27751208e+03 1.32373083e+03 1.30235217e+03 1.33717102e+03 1.41964392e+03 1.47266724e+03 1.56247253e+03 1.57600403e+03 1.56037341e+03 1.65646936e+03 1.67319507e+03 1.74606689e+03 1.84334448e+03 1.80526746e+03 1.87452539e+03 1.97983020e+03 1.99264246e+03 2.02817004e+03 2.06672827e+03 2.12221118e+03 2.19192285e+03 2.20383203e+03 2.18159839e+03 2.24635767e+03 2.39830786e+03 2.50590771e+03 2.49160815e+03 2.43081812e+03 2.41448413e+03 2.49863892e+03 2.65655469e+03 2.79403320e+03 2.77038574e+03 2.67854321e+03 2.72457349e+03 2.85993457e+03 2.89665918e+03 2.88033423e+03 2.93192017e+03 2.99836743e+03 3.04909546e+03 3.17559961e+03 3.14829565e+03 3.11197119e+03 3216. 3.15435425e+03 3.28222314e+03 3.44716650e+03 3.37542188e+03 3.49959106e+03 3.50730347e+03 3.39899805e+03 3.54179028e+03 3.50416162e+03 3.58648267e+03 3.89186694e+03 3.73780811e+03 3.57258643e+03 3.70748877e+03 3.91589819e+03 4.07800854e+03 4.01960181e+03 3.86489355e+03 3.82030396e+03 3.91064038e+03 4.11708984e+03 4.30433398e+03 4.26431152e+03 4.08128809e+03 4.08108374e+03 4.28364551e+03 4.36990674e+03 4.29192627e+03 4.29240479e+03 4.39199512e+03 4.42455908e+03 4.61299805e+03 4.66724707e+03 4.44561914e+03 4.47559473e+03 4.59480615e+03 4.63663818e+03 4.71480713e+03 4733. 4.86087500e+03 4.80138135e+03 4.67357373e+03 4.84943750e+03 4.74891699e+03 4.91538428e+03 5.26887207e+03 4.98829932e+03 4.72842090e+03 4.92026953e+03 5.19739697e+03 5.35128369e+03 5.38802295e+03 5.10787158e+03 4.93075391e+03 5.09659766e+03 5.39226855e+03 5.62278516e+03 5.51459229e+03 5.22082666e+03 5.20317871e+03 5.40387207e+03 5.50896094e+03 5.62381787e+03 5.64581836e+03 5.39789111e+03 5.41472314e+03 5.66844922e+03 5.74352832e+03 5.64429834e+03 5.63987207e+03 5.62106934e+03 5.63288037e+03 5.89552051e+03 6.00380957e+03 5.77944922e+03 5.73536133e+03 5.74458887e+03 5.76040332e+03 5.91430029e+03 5.92828467e+03 6.12948096e+03 6.14036816e+03 5.92962988e+03 5.84658984e+03 5.80605469e+03 6.08059961e+03 6.40437354e+03 6.28747559e+03 6.01686816e+03 5.85151318e+03 6.13722363e+03 6.51324121e+03 6.21006348e+03 5.93023633e+03 6.10557275e+03 6.28911621e+03 6.45193213e+03 6.61796484e+03 6.52686426e+03 6.15705371e+03 6.08476904e+03 6.38046875e+03 6.49120264e+03 6.49027539e+03 6.45635693e+03 6.44597412e+03 6.40867920e+03 6.58061865e+03 6.47625049e+03 6.33408740e+03 6.39420557e+03 6.47594727e+03 6.73344434e+03 6.74200098e+03 6.55731201e+03 6.67382568e+03 6.64161475e+03 6.64758496e+03 6.53912939e+03 6.35185156e+03 6.71988477e+03 7.04907080e+03 6.77049023e+03 6.48266699e+03 6.51117822e+03 6.87340527e+03 6.96055811e+03 6.85679541e+03 6.72984082e+03 6.55602686e+03 6.57691504e+03 6.84341064e+03 6.86100781e+03 6.72834961e+03 6.57176172e+03 6.52565332e+03 6.87223047e+03 7.23404834e+03 6.85893750e+03 6.61288330e+03 6.80042139e+03 6.82526025e+03 7.02094336e+03 7.00133887e+03 6.56207812e+03 6.64476270e+03 6.88800586e+03 6.84960205e+03 6.86981445e+03 7.00377246e+03 6.76637695e+03 7.37720850e+03 7.37275342e+03 6.80276465e+03 7.78620215e+03 8.17316797e+03 1.83622168e+04 1.18735859e+04 2.00422695e+04 2.00373320e+04 -2.86640450e+06 -2804770. 11531426. -2.06619912e+06 -4.54671750e+06 1.76137875e+06 17449876. 34538408. 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. 0. -249400496. -249400496. -249400496. 0. 0. 3318850. 4221781. 2.21180575e+06 2.00392910e+04 1.63375947e+04 1.07579980e+04 1.03559424e+04 8.23293848e+03 8.06710010e+03 6.64842725e+03 6.59546826e+03 6.41953271e+03 6.20726221e+03 6.34447412e+03 6.36095459e+03 6.17901807e+03 6.19991064e+03 6.21614355e+03 6.13538574e+03 6.12250098e+03 6.05314648e+03 6.00232031e+03 6.00592188e+03 5.98451807e+03 6.02979590e+03 6.04000244e+03 5.79578516e+03 5.78224219e+03 6.02518848e+03 6.00750879e+03 5.88180420e+03 5.84891504e+03 5.80189746e+03 5.78990137e+03 5.74419482e+03 5.73763525e+03 5.69769531e+03 5.66164111e+03 5.57338232e+03 5.51398926e+03 5.68627490e+03 5.70363818e+03 5.54148828e+03 5.48507520e+03 5.47741748e+03 5.47892432e+03 5.41932080e+03 5.39159424e+03 5.37055420e+03 5.24319238e+03 5.18614600e+03 5.22927441e+03 5.18498877e+03 5.36319727e+03 5.33973145e+03 5.13000879e+03 4.97964941e+03 4.92582471e+03 5.18680908e+03 5.19750635e+03 5.00615820e+03 4.85510791e+03 4.82623242e+03 4.89689746e+03 4.85226953e+03 4.92831592e+03 4.91622607e+03 4.60978027e+03 4.49718701e+03 4.70900879e+03 4.88475635e+03 4.69996777e+03 4.57362500e+03 4.53034912e+03 4.47418311e+03 4.43847852e+03 4.42704883e+03 4.38178955e+03 4.31192676e+03 4.31250342e+03 4.28607178e+03 4.23166553e+03 4.18248584e+03 4.27368164e+03 4.24983008e+03 4.09926025e+03 4.03147021e+03 3.99645972e+03 4.03529858e+03 4.00308325e+03 3.89850635e+03 3.87419458e+03 3.74833691e+03 3.65736157e+03 3.78921802e+03 3.73186230e+03 3.51095288e+03 3.51816089e+03 3.67805371e+03 3.76146655e+03 3.59794922e+03 3.44697339e+03 3.37766504e+03 3.33683984e+03 3.32237085e+03 3.27636914e+03 3.23148901e+03 3.18567065e+03 3.24461133e+03 3.20899487e+03 3.07228516e+03 3.02859888e+03 2.90437378e+03 2.88662231e+03 3.01712720e+03 2.94519287e+03 2.83656689e+03 2.73171265e+03 2.64268188e+03 2.73856641e+03 2.74843286e+03 2.62431470e+03 2.50420654e+03 2.45435059e+03 2.46909985e+03 2.42102271e+03 2.45491113e+03 2.42709497e+03 2.29719824e+03 2.22194287e+03 2.17800342e+03 2.18682617e+03 2.14694385e+03 2.06843579e+03 2.01721143e+03 1.97253223e+03 1.91871704e+03 1.82524292e+03 1.80576013e+03 1.85573083e+03 1.78698254e+03 1.70211890e+03 1.61675830e+03 1.56433960e+03 1.60708337e+03 1.55715051e+03 1.46813733e+03 1.38801001e+03 1.33767786e+03 1.33483264e+03 1.27825134e+03 1.23533301e+03 1.16092920e+03 1.13034033e+03 1.15339355e+03 1.07829468e+03 9.97283508e+02 9.54961487e+02 9.09623657e+02 8.56387146e+02 8.09182800e+02 7.56983276e+02 7.08419800e+02 6.62127808e+02 5.97182678e+02 5.59546631e+02 5.44506714e+02 4.77064056e+02 4.14843231e+02 3.79156281e+02 3.31488220e+02 2.92317596e+02 2.40186462e+02 1.84434464e+02 1.43955414e+02 9.64206543e+01 4.67912292e+01 8.04359376e-01 -4.48352470e+01 -9.15287018e+01 -1.39865524e+02 -1.87416214e+02 -2.30644440e+02 -2.87673431e+02 -3.53132324e+02 -3.94555725e+02 -4.31450500e+02 -4.66787506e+02 -5.10443390e+02 -5.88236267e+02 -6.42380432e+02 -6.72956482e+02 -6.99241821e+02 -7.40406799e+02 -8.12543823e+02 -8.62704712e+02 -9.27691406e+02 -9.62716248e+02 -9.82855530e+02 -1.04003540e+03 -1.08626111e+03 -1.17371375e+03 -1.21612012e+03 -1.21972180e+03 -1.27661853e+03 -1.32831946e+03 -1.36389258e+03 -1.36983984e+03 -1.45462170e+03 -1.59309802e+03 -1.59813391e+03 -1.60595312e+03 -1.61953174e+03 -1.65079077e+03 -1.79676123e+03 -1.84819104e+03 -1.84557397e+03 -1.84796204e+03 -1.87812036e+03 -1.98668787e+03 -2.02715308e+03 -2.11971924e+03 -2.15803931e+03 -2.14471265e+03 -2.17447119e+03 -2.20485645e+03 -2.35345752e+03 -2.39466455e+03 -2.37451343e+03 -2.40283594e+03 -2.43466870e+03 -2.56920044e+03 -2.62144043e+03 -2.54421069e+03 -2.58271240e+03 -2.76821997e+03 -2.81688867e+03 -2.71820825e+03 -2.74545630e+03 -2.93412573e+03 -3.00520508e+03 -2.94916138e+03 -2.91645801e+03 -2.96857007e+03 -3.17204785e+03 -3.17181885e+03 -3.12551367e+03 -3.23150195e+03 -3.27566650e+03 -3.27693896e+03 -3.29371582e+03 -3.35324146e+03 -3.31627075e+03 -3.44669604e+03 -3.68488184e+03 -3.61731396e+03 -3.60340479e+03 -3.66161035e+03 -3.67130591e+03 -3.70907642e+03 -3.75469971e+03 -3.79358691e+03 -3.73229614e+03 -3.72406836e+03 -3.86302612e+03 -3.98060669e+03 -4.12439111e+03 -4.03659375e+03 -3.93406250e+03 -4.08646411e+03 -4.17027783e+03 -4.33118408e+03 -4.33208691e+03 -4.24021484e+03 -4.20136621e+03 -4.20367578e+03 -4.35916504e+03 -4.41364502e+03 -4.52735010e+03 -4.58339648e+03 -4.52468701e+03 -4.45859326e+03 -4.37518457e+03 -4.58029248e+03 -4.85192969e+03 -4.84024023e+03 -4.74079346e+03 -4.64334180e+03 -4.60761963e+03 -4.87786572e+03 -5.05049658e+03 -4.93852832e+03 -4.79423682e+03 -4.83107861e+03 -4.98913965e+03 -5.02374365e+03 -5.17587500e+03 -5.22524463e+03 -5.13231201e+03 -5.08474512e+03 -5.08567969e+03 -5.30223145e+03 -5.36004053e+03 -5.14140820e+03 -5.16295654e+03 -5.47369922e+03 -5.46047266e+03 -5.20960693e+03 -5.32411084e+03 -5.62752441e+03 -5.61842725e+03 -5.52638623e+03 -5.40633789e+03 -5.40540771e+03 -5.76682178e+03 -5.80261719e+03 -5.66250732e+03 -5.52835498e+03 -5.51538184e+03 -5.69222510e+03 -5.75840576e+03 -5.79324023e+03 -5.65656445e+03 -5.82049023e+03 -6.11987598e+03 -5.98152588e+03 -5.98138379e+03 -5.99389648e+03 -5.95922217e+03 -5.98647998e+03 -6.01033691e+03 -6.03825049e+03 -6.02504736e+03 -5.98502637e+03 -5.88914600e+03 -6.05226855e+03 -6.33229102e+03 -6.12905420e+03 -5.96262939e+03 -6.16549414e+03 -6.26620166e+03 -6.47707373e+03 -6.38707178e+03 -6.22219141e+03 -6.36769287e+03 -6.35099951e+03 -6.19641748e+03 -6.20597461e+03 -6.47718750e+03 -6.48206299e+03 -6.35999121e+03 -6.27859863e+03 -6.12203369e+03 -6.38116064e+03 -6.82826465e+03 -6.69604492e+03 -6.45373242e+03 -6.36283545e+03 -6.32063916e+03 -6.64822461e+03 -6.82132568e+03 -6.62744580e+03 -6.45426709e+03 -6.42986719e+03 -6.54516113e+03 -6.57213086e+03 -6.80571973e+03 -6.78895508e+03 -6.59708350e+03 -6.63876807e+03 -6.62620850e+03 -6.80112402e+03 -6.82275391e+03 -6.73580811e+03 -6.63629248e+03 -6.65687061e+03 -6.71778320e+03 -6.58976123e+03 -6.61743896e+03 -6.96309668e+03 -6.86745996e+03 -6.79313721e+03 -6.62934570e+03 -6.57998926e+03 -6.99934082e+03 -7.02421484e+03 -6.79411816e+03 -6.68168994e+03 -6.68157324e+03 -6.72549268e+03 -6.73941602e+03 -6.80752197e+03 -6.67371729e+03 -6.83872803e+03 -7.11640039e+03 -6.88359033e+03 -6.93932910e+03 -6.97414795e+03 -6.87491113e+03 -6.82772900e+03 -6.73580908e+03 -6.81134717e+03 -6.85408984e+03 -6.84370166e+03 -6.83080859e+03 -6.90550488e+03 -6.98639209e+03 -6.65600537e+03 -6.56513916e+03 -6.78326611e+03 -6.90119824e+03 -7.08471045e+03 -6.92749902e+03 -6.71504102e+03 -6.92542773e+03 -6.90187891e+03 -6.72208740e+03 -6.81402539e+03 -6.78014062e+03 -6.72903418e+03 -6.69370801e+03 -6.78722412e+03 -6.62709619e+03 -6.76778418e+03 -7.01851660e+03 -6.86691553e+03 -6.78126807e+03 -6.66253223e+03 -6.56233740e+03 -6.83753467e+03 -6.90517725e+03 -6.72736914e+03 -6.54202051e+03 -6.40324414e+03 -6.59854297e+03 -6.73426807e+03 -6.88950928e+03 -6.70583350e+03 -6.47369971e+03 -6.58446582e+03 -6.54412158e+03 -6.79198291e+03 -6.74812598e+03 -6.49668066e+03 -6.48703662e+03 -6.43461816e+03 -6.51876074e+03 -6.36397754e+03 -6.44669385e+03 -6.74567578e+03 -6.59448242e+03 -6.49780615e+03 -6.31007324e+03 -6.20704541e+03 -6.60304541e+03 -6.55019922e+03 -6.31710449e+03 -6.20133154e+03 -6.14775635e+03 -6.30043945e+03 -6.30845654e+03 -6.43928906e+03 -6.41109570e+03 -6.22566943e+03 -6.05993359e+03 -6.02971680e+03 -6.36206006e+03 -6.26428955e+03 -6.07225244e+03 -6.11494043e+03 -6.09533740e+03 -6.02318994e+03 -5.95910303e+03 -6.11215771e+03 -5.97389746e+03 -5.82757861e+03 -6.11404834e+03 -6.14537598e+03 -5.92953369e+03 -5.84289502e+03 -5.85100488e+03 -5.85277148e+03 -5.64286572e+03 -5.57387207e+03 -5.88143701e+03 -5.86861914e+03 -5.49709863e+03 -5.40205225e+03 -5.71099805e+03 -5.91865674e+03 -5.70205615e+03 -5.46848145e+03 -5.43008887e+03 -5.60181738e+03 -5.54259375e+03 -5.39689502e+03 -5.46536279e+03 -5.31950146e+03 -5.11516943e+03 -5.30005957e+03 -5.50972998e+03 -5.44413477e+03 -5.17785742e+03 -5.02069287e+03 -5.27844873e+03 -5.37420361e+03 -5.14880859e+03 -4.98549561e+03 -4.95581055e+03 -4.99063379e+03 -4.94942139e+03 -5.09250098e+03 -5.00372705e+03 -4.77067334e+03 -4.85759961e+03 -4.83061426e+03 -4.86703516e+03 -4.72939551e+03 -4.58019287e+03 -4.74692139e+03 -4.73206787e+03 -4.60868799e+03 -4.47988330e+03 -4.47114258e+03 -4.68369971e+03 -4.50715967e+03 -4.31983057e+03 -4.38024512e+03 -4.35031787e+03 -4.32724170e+03 -4.28624121e+03 -4.35275439e+03 -4.33935645e+03 -4.18370459e+03 -4.02185156e+03 -3.98434473e+03 -4.15796777e+03 -4.07738232e+03 -3.92089038e+03 -3.93398413e+03 -3.91024121e+03 -3.87738062e+03 -3.82247217e+03 -3.85858643e+03 -3.72849292e+03 -3.59925562e+03 -3.72467310e+03 -3.69065918e+03 -3.60521973e+03 -3.56492773e+03 -3.51740967e+03 -3.46718628e+03 -3.33810791e+03 -3.25908594e+03 -3.39364917e+03 -3.42842847e+03 -3.21970752e+03 -3.08374976e+03 -3.17797021e+03 -3.25853540e+03 -3.14209839e+03 -2.98937695e+03 -2.90041260e+03 -2.99284961e+03 -2.97411694e+03 -2.84528564e+03 -2.87698877e+03 -2.83918701e+03 -2.70516992e+03 -2.64692505e+03 -2.68036377e+03 -2.67619141e+03 -2.52691724e+03 -2.43852637e+03 -2.51549194e+03 -2.51532983e+03 -2.40662524e+03 -2.27407202e+03 -2.21191382e+03 -2.29926807e+03 -2.27081519e+03 -2.14585034e+03 -2.09246045e+03 -2.05888989e+03 -2.00233826e+03 -1.94834009e+03 -1.98145471e+03 -1.88881470e+03 -1.77870996e+03 -1.82572742e+03 -1.78802100e+03 -1.72006738e+03 -1.63698413e+03 -1.56186267e+03 -1.58130676e+03 -1.51145886e+03 -1.44328247e+03 -1.44770105e+03 -1.45371912e+03 -1.42039490e+03 -1.23918811e+03 -1.28523926e+03 -1.31399622e+03 -9.88848999e+02 -1.00641980e+03 -1.04727063e+03 -1.04616418e+03 -1.43698340e+03 -1.05126318e+03 -1.02084668e+03 -1.69305591e+03 -2.76005786e+03 1.47612953e+05 940005440. 0. 0. 0. 0. 1381557632. 1381557632. 8.02582875e+05 838171904. 89105472. 5.56289648e+04 5.56289648e+04 833382336. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 469363232. 1.79326781e+05 2.65901406e+05 -9.74267750e+05 1.48940516e+05 3.04350391e+03 2.34339844e+03 1.29185352e+03 1.02443726e+03 1.43161658e+03 1.15092969e+03 1.02772278e+03 1.07634167e+03 1.10845703e+03 1.15132202e+03 1.21540942e+03 1.23899548e+03 1.26931592e+03 1.32042957e+03 1.35507947e+03 1.42412317e+03 1.51419714e+03 1.55636121e+03 1.54935559e+03 1.58650928e+03 1.64951990e+03 1.66401233e+03 1.72742578e+03 1.82307483e+03 1.85460449e+03 1.90162195e+03 1.95373096e+03 1.95865234e+03 1.99948462e+03 2.06603516e+03 2.09641260e+03 2.12764209e+03 2.22653540e+03 2.30556372e+03 2.29133765e+03 2.32289209e+03 2.38504395e+03 2.43155591e+03 2.49744751e+03 2.52151147e+03 2.50824634e+03 2.60606592e+03 2.72917139e+03 2.67731177e+03 2.69341309e+03 2.80637012e+03 2.78264404e+03 2.84020898e+03 2.97938989e+03 2.96822876e+03 2.97363062e+03 3.06688135e+03 3.18093262e+03 3.14178809e+03 3.09904688e+03 3.14868311e+03 3.19610742e+03 3.33994116e+03 3.43796191e+03 3.40029492e+03 3.40081421e+03 3.43718628e+03 3.46827417e+03 3.53877710e+03 3.56144336e+03 3.55174902e+03 3.66998413e+03 3.81128223e+03 3.77920435e+03 3.76261084e+03 3.86599951e+03 3.86647559e+03 3.87923047e+03 3.96853198e+03 4.01471704e+03 4.00654541e+03 4.01172998e+03 4.12994775e+03 4.16006104e+03 4.18414404e+03 4.23134521e+03 4.15209521e+03 4.28250684e+03 4.44932715e+03 4.37446924e+03 4.36600488e+03 4.42301807e+03 4.46415771e+03 4.54107471e+03 4.53010303e+03 4.46919238e+03 4.63994971e+03 4.79268750e+03 4.74015234e+03 4.65287256e+03 4.69612598e+03 4.84549023e+03 4.86929150e+03 4.83863281e+03 4.85949902e+03 4.85254248e+03 5.00144678e+03 5.14201367e+03 5.02021338e+03 4.96755957e+03 4.99542188e+03 5.05328467e+03 5.17387207e+03 5.26658301e+03 5.21423584e+03 5.23131250e+03 5.39732764e+03 5.43485352e+03 5.30837891e+03 5.24024023e+03 5.31352393e+03 5.44402783e+03 5.51839697e+03 5.54932471e+03 5.52695703e+03 5.55447168e+03 5.60147510e+03 5.53524854e+03 5.54159570e+03 5.63102197e+03 5.63554150e+03 5.74993213e+03 5.86191699e+03 5.66028369e+03 5.67295801e+03 5.91933643e+03 5.87211816e+03 5.72142383e+03 5.86745459e+03 6.04096729e+03 6.00477490e+03 5.97307666e+03 5.97334180e+03 5.97227734e+03 5.97587256e+03 5.94635059e+03 6.06167871e+03 6.09925977e+03 6.08598242e+03 6.15554932e+03 6.21435889e+03 6.20459619e+03 6.08221191e+03 6.16661328e+03 6.30442285e+03 6.20234180e+03 6.33180127e+03 6.44762109e+03 6.40671436e+03 6.28095654e+03 6.29919434e+03 6.33670117e+03 6.24621143e+03 6.38123291e+03 6.52651855e+03 6.48525488e+03 6.44483545e+03 6.42195557e+03 6.43068506e+03 6.48772412e+03 6.47569678e+03 6.42697314e+03 6.51009131e+03 6.60708545e+03 6.58041602e+03 6.56772949e+03 6.59372119e+03 6.58145215e+03 6.62738232e+03 6.61797070e+03 6.58398926e+03 6.72257275e+03 6.68152441e+03 6.62143896e+03 6.68576270e+03 6.73509570e+03 6.84146729e+03 6.53333057e+03 6.58850732e+03 6.83816113e+03 6.70712451e+03 6.81965869e+03 6.79435742e+03 6.67968457e+03 6.76095312e+03 6.73432910e+03 6.66275586e+03 6.74444482e+03 6.79777051e+03 6.85700195e+03 6.95921191e+03 6.91506055e+03 6.82099658e+03 6.82987061e+03 6.75796191e+03 6.74554443e+03 6.78024805e+03 6.86789990e+03 7.01304395e+03 6.79537158e+03 6.72644629e+03 6.87012744e+03 6.70816650e+03 6.83961816e+03 6.98638281e+03 6.81287598e+03 6.78310352e+03 6.84923193e+03 6.91690918e+03 6.89099316e+03 6.79249023e+03 6.76063672e+03 6.73197119e+03 6.81037842e+03 6.92066553e+03 6.89869531e+03 6.84219971e+03 6.83946045e+03 6.88786377e+03 6.76919043e+03 6.83635791e+03 6.97161035e+03 6.73591992e+03 6.69537793e+03 6.75663916e+03 6.78721729e+03 6.80352930e+03 6.76758398e+03 6.72502734e+03 6.74231201e+03 6.74689795e+03 6.73241553e+03 6.74564600e+03 6.88917432e+03 6.82595459e+03 6.53665479e+03 6.63308301e+03 6.65114746e+03 6.65921240e+03 6.79390479e+03 6.59164502e+03 6.49394287e+03 6.70352686e+03 6.66940137e+03 6.50518945e+03 6.48942236e+03 6.61312012e+03 6.64070557e+03 6.48474268e+03 6.52949170e+03 6.61961475e+03 6.45727490e+03 6.42270264e+03 6.47721191e+03 6.33530029e+03 6.43711670e+03 6.54506689e+03 6.31314795e+03 6.39785938e+03 6.52019727e+03 6.39364600e+03 6.26195605e+03 6.18094189e+03 6.27097559e+03 6.39859912e+03 6.25219189e+03 6.11904639e+03 6.20280322e+03 6.18530273e+03 6.13056494e+03 6.10889209e+03 6.14036865e+03 6.11959814e+03 6.04592334e+03 6.06311816e+03 6.13032617e+03 6.00762109e+03 5.97394873e+03 6.02073291e+03 5.86008691e+03 5.99865088e+03 6.02442627e+03 5.76856201e+03 5.85303906e+03 5.84139111e+03 5.71873584e+03 5.79296680e+03 5.73566455e+03 5.74877246e+03 5.80653516e+03 5.68467090e+03 5.63085596e+03 5.60147510e+03 5.51117627e+03 5.47858252e+03 5.50919971e+03 5.57527441e+03 5.54376611e+03 5.47381885e+03 5.43955322e+03 5.44888721e+03 5.38146045e+03 5.25316650e+03 5.28459521e+03 5.34405518e+03 5.30746094e+03 5.14537207e+03 5.05959277e+03 5.14227344e+03 5.22228711e+03 5.07627734e+03 4.98679834e+03 5.01626123e+03 4.99110986e+03 5.02202686e+03 4.98877295e+03 4.88603662e+03 4.75795557e+03 4.75829053e+03 4.79036328e+03 4.72486963e+03 4.74276172e+03 4.72746777e+03 4.66534277e+03 4.61389160e+03 4.65549170e+03 4.57956787e+03 4.45871533e+03 4.50075098e+03 4.50594043e+03 4.40889697e+03 4.26323926e+03 4.21414355e+03 4.29364795e+03 4.30914258e+03 4.23709277e+03 4.16408545e+03 4.11930029e+03 4.15191016e+03 4.10952930e+03 3.94360986e+03 3.92530347e+03 3.94998877e+03 3.96060620e+03 3.87543384e+03 3.75061670e+03 3.74942432e+03 3.74703101e+03 3.75391162e+03 3.74568701e+03 3.68648950e+03 3.54626172e+03 3.43539062e+03 3.50146118e+03 3.55502441e+03 3.43892700e+03 3.34936377e+03 3.29226440e+03 3.28893115e+03 3.29711133e+03 3.19871484e+03 3.14382153e+03 3.12740454e+03 3.13783813e+03 3.10028882e+03 2.94884668e+03 2.95715796e+03 2.94207861e+03 2.83727246e+03 2.82646118e+03 2.77777759e+03 2.72089648e+03 2.68276904e+03 2.62903271e+03 2.60459399e+03 2.58877783e+03 2.54246753e+03 2.44425659e+03 2.41957031e+03 2.42363477e+03 2.34711865e+03 2.28428955e+03 2.19697559e+03 2.17272607e+03 2.20732373e+03 2.13662231e+03 2.06215527e+03 1.97670215e+03 1.95837634e+03 1.98611877e+03 1.89469470e+03 1.82701978e+03 1.81056299e+03 1.75386902e+03 1.67220300e+03 1.64648523e+03 1.61838684e+03 1.54937610e+03 1.52220276e+03 1.46872302e+03 1.38215540e+03 1.36254712e+03 1.33650427e+03 1.28667212e+03 1.26041455e+03 1.19572754e+03 1.13927490e+03 1.08676306e+03 1.03602600e+03 1.00006720e+03 9.56253113e+02 9.04985107e+02 8.45772766e+02 8.07196228e+02 7.52289429e+02 7.05292603e+02 6.82527405e+02 6.26511719e+02 5.68032715e+02 5.19241821e+02 4.69645996e+02 4.23141113e+02 3.84462952e+02 3.39243805e+02 2.80468140e+02 2.27839615e+02 1.83905029e+02 1.40507172e+02 9.55381927e+01 4.83159981e+01 -2.81363297e+00 -5.00002747e+01 -9.48689804e+01 -1.39415466e+02 -1.89372406e+02 -2.40002579e+02 -2.90333618e+02 -3.31424530e+02 -3.70933685e+02 -4.32496979e+02 -4.88953613e+02 -5.28811462e+02 -5.68247131e+02 -6.16412903e+02 -6.76651917e+02 -7.30433838e+02 -7.68410522e+02 -8.02211853e+02 -8.51989441e+02 -9.11444763e+02 -9.54570435e+02 -1.00331934e+03 -1.05289941e+03 -1.08162354e+03 -1.13724500e+03 -1.19730591e+03 -1.23980566e+03 -1.29123474e+03 -1.33150659e+03 -1.37839880e+03 -1.42494348e+03 -1.47220312e+03 -1.48974414e+03 -1.53457153e+03 -1.61895251e+03 -1.68265454e+03 -1.73670911e+03 -1.73958215e+03 -1.77753235e+03 -1.82575940e+03 -1.87835413e+03 -1.97174329e+03 -1.97064246e+03 -2.01062549e+03 -2.11367944e+03 -2.09331421e+03 -2.10973853e+03 -2.22787183e+03 -2.28317041e+03 -2.30104932e+03 -2.37489233e+03 -2.37097729e+03 -2.34725000e+03 -2.48292358e+03 -2.56944629e+03 -2.54976855e+03 -2.64630200e+03 -2.70034009e+03 -2.64601611e+03 -2.70736914e+03 -2.76976074e+03 -2.80112793e+03 -2.90482446e+03 -2.93557202e+03 -2.95013208e+03 -3.01069141e+03 -3.05845581e+03 -3.11816406e+03 -3.12331396e+03 -3.13596362e+03 -3.21446973e+03 -3.27109888e+03 -3.25597168e+03 -3.31662012e+03 -3.40863721e+03 -3.41433887e+03 -3.48056396e+03 -3.53470288e+03 -3.55674805e+03 -3.60818481e+03 -3.56556543e+03 -3.61503711e+03 -3.78637939e+03 -3.80497998e+03 -3.77608838e+03 -3.84437646e+03 -3.90958862e+03 -3.92343237e+03 -3.95181323e+03 -3.88059692e+03 -3.91483203e+03 -4.10517920e+03 -4.18168213e+03 -4.19696924e+03 -4.12084717e+03 -4.17258594e+03 -4.29755566e+03 -4.29861328e+03 -4.31076123e+03 -4.36273682e+03 -4.38307422e+03 -4.45923242e+03 -4.49243311e+03 -4.56923926e+03 -4.55696045e+03 -4.52335742e+03 -4.69231543e+03 -4.63947510e+03 -4.61438184e+03 -4.70002588e+03 -4.68985205e+03 -4.79462744e+03 -4.96285010e+03 -4.95350781e+03 -4.81107471e+03 -4.85465137e+03 -4.99588477e+03 -5.04945166e+03 -5.04604736e+03 -5.03336719e+03 -5.10756348e+03 -5.17754053e+03 -5.18336670e+03 -5.23545996e+03 -5.21575391e+03 -5.23923389e+03 -5.34208740e+03 -5.16802490e+03 -5.17513965e+03 -5.45195557e+03 -5.46152051e+03 -5.44956787e+03 -5.46047021e+03 -5.40480127e+03 -5.43940625e+03 -5.64022949e+03 -5.70098340e+03 -5.58656055e+03 -5.56282959e+03 -5.55659473e+03 -5.63416260e+03 -5.75559277e+03 -5.80182471e+03 -5.82454053e+03 -5.75945312e+03 -5.79592041e+03 -5.84224951e+03 -5.75543213e+03 -5.79804639e+03 -5.96376709e+03 -5.98610059e+03 -5.95112695e+03 -5.95685205e+03 -5.98658203e+03 -6.03618896e+03 -5.97623926e+03 -6.11708398e+03 -6.10706006e+03 -6.11834277e+03 -6.13436572e+03 -6.14184717e+03 -6.31775195e+03 -6.20731885e+03 -6.15241943e+03 -6.31458057e+03 -6.24316113e+03 -6.15074121e+03 -6.32036963e+03 -6.34104199e+03 -6.28270117e+03 -6.41285596e+03 -6.46533594e+03 -6.42963232e+03 -6.55140039e+03 -6.45925342e+03 -6.32550391e+03 -6.55205225e+03 -8.53295117e+03 -8.86862305e+03 -9.94960254e+03 -9.94640039e+03 -1.07276689e+04 -9.40586719e+03 -1.91186914e+04 -2.88367031e+04 7554618. 49093276. 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. 0. 0. 0. 0. 0. 0. 0. 0. 7938896. -17083144. 1.68124838e+06 7235108. 4.09605475e+06 -6.14514050e+06 -13922853. -2.00655156e+04 -1.36336973e+04 -9.78537988e+03 -7.83336621e+03 -6.96088770e+03 -6.83350195e+03 -6.98257617e+03 -6.82703857e+03 -6.82531055e+03 -6.83629639e+03 -6.85347656e+03 -6.91509570e+03 -6.88756250e+03 -6.79908203e+03 -6.64035010e+03 -6.81308789e+03 -6.85495508e+03 -6.79468018e+03 -6.80094531e+03 -6.62067041e+03 -6.62057031e+03 -6.91526904e+03 -6.75507959e+03 -6.61139258e+03 -6.51552002e+03 -6.63999023e+03 -6.89208350e+03 -6.91693799e+03 -6.71252344e+03 -6.42754688e+03 -6.44655762e+03 -6.69244482e+03 -6.67908545e+03 -6.65618555e+03 -6542. -6.56462988e+03 -6.64919824e+03 -6.62889209e+03 -6.60461035e+03 -6.35639551e+03 -6.44359277e+03 -6.80331006e+03 -6.51250684e+03 -6.30848926e+03 -6.36163721e+03 -6.31703418e+03 -6.52496924e+03 -6.54875732e+03 -6.34418896e+03 -6.19530420e+03 -6.35996533e+03 -6.46950391e+03 -6.33804883e+03 -6.24299414e+03 -6.14464697e+03 -6.25683057e+03 -6.37356885e+03 -6.18902246e+03 -6.18115479e+03 -6.09766748e+03 -6.02502637e+03 -6.20932227e+03 -6.25371484e+03 -6.10329492e+03 -5.98372607e+03 -6.03750244e+03 -6.05874219e+03 -6.02914111e+03 -6.04043457e+03 -5.82121240e+03 -5.84055762e+03 -6.06840039e+03 -5.91522363e+03 -5.67490771e+03 -5.64972656e+03 -5.82005713e+03 -6.01136816e+03 -5.84645215e+03 -5.72238867e+03 -5.62441943e+03 -5.51964209e+03 -5.61053271e+03 -5.74377100e+03 -5.62884863e+03 -5.45959180e+03 -5.51951514e+03 -5.53024219e+03 -5.51013232e+03 -5.57477295e+03 -5.34372607e+03 -5.27332471e+03 -5.52476660e+03 -5.38453320e+03 -5.25140625e+03 -5.20931445e+03 -5.10642725e+03 -5.29028223e+03 -5.30199512e+03 -5.08711133e+03 -5.04279980e+03 -5.10508691e+03 -5.14200781e+03 -5.04389453e+03 -5.01040479e+03 -4.91516406e+03 -4.87312500e+03 -4.98884521e+03 -4.88475586e+03 -4.73824414e+03 -4.66380957e+03 -4.70688477e+03 -4.85413232e+03 -4.79501123e+03 -4.67358008e+03 -4.50613135e+03 -4.45213135e+03 -4.62856250e+03 -4.59742969e+03 -4.43530518e+03 -4.34657227e+03 -4.36818994e+03 -4.43780420e+03 -4.34304053e+03 -4.24349805e+03 -4.15356885e+03 -4.20690186e+03 -4.32333691e+03 -4.13895264e+03 -4.05982642e+03 -4.06665283e+03 -3.97490405e+03 -4.00960547e+03 -3.99312280e+03 -3.89167847e+03 -3.78571045e+03 -3.78211621e+03 -3.87643457e+03 -3.83593237e+03 -3.73111182e+03 -3.59167407e+03 -3.55160571e+03 -3.65649292e+03 -3.62191382e+03 -3.52076270e+03 -3.39245044e+03 -3.31187402e+03 -3.38754199e+03 -3.41745093e+03 -3.32581738e+03 -3.21529395e+03 -3.17566235e+03 -3.15628760e+03 -3.14405591e+03 -3.14864697e+03 -3.03749609e+03 -2.96787671e+03 -2.99123730e+03 -2.92454932e+03 -2.85606055e+03 -2.80256201e+03 -2.79324512e+03 -2.76140405e+03 -2.66940869e+03 -2.62843506e+03 -2.56857422e+03 -2.56527026e+03 -2.61084009e+03 -2.50502881e+03 -2.37926685e+03 -2.32310645e+03 -2.31767505e+03 -2.33802490e+03 -2.31657788e+03 -2.25525586e+03 -2.12369824e+03 -2.02961816e+03 -2.05249609e+03 -2.07704980e+03 -2.02704565e+03 -1.89536938e+03 -1.83994629e+03 -1.84912134e+03 -1.81492273e+03 -1.77649377e+03 -1.69528577e+03 -1.64415820e+03 -1.62384167e+03 -1.55593713e+03 -1.50715076e+03 -1.46425317e+03 -1.41692175e+03 -1.39452039e+03 -1.33193945e+03 -1.27572095e+03 -1.22399902e+03 -1.18349390e+03 -1.15753125e+03 -1.09559961e+03 -1.03405859e+03 -9.83090942e+02 -9.69995178e+02 -9.37192688e+02 -8.59296021e+02 -8.02890320e+02 -7.43244568e+02 -7.04082397e+02 -6.87477783e+02 -6.37136047e+02 -5.79035339e+02 -5.11591187e+02 -4.62097107e+02 -4.43272675e+02 -3.98530426e+02 -3.34769165e+02 -2.86309937e+02 -2.42898468e+02 -1.93287506e+02 -1.41469208e+02 -8.96045380e+01 -4.15300751e+01 5.95234632e+00 5.27398491e+01 1.02338821e+02 1.44784592e+02 1.82719971e+02 2.36161774e+02 2.91838867e+02 3.38792755e+02 3.87733734e+02 4.29058105e+02 4.88889038e+02 5.36393372e+02 5.56080627e+02 5.95519897e+02 6.54855591e+02 7.34104919e+02 8.10647339e+02 8.38447754e+02 8.38683350e+02 8.59949951e+02 9.25156128e+02 1.02674976e+03 1.11029089e+03 1.13506738e+03 1.10769556e+03 1.14326404e+03 1.27988159e+03 1.32581226e+03 1.31051001e+03 1.35083435e+03 1.40498621e+03 1.45899878e+03 1.55758374e+03 1.57662061e+03 1.56230530e+03 1.65289771e+03 1.67320215e+03 1.75064868e+03 1.83830103e+03 1.80014014e+03 1.88064844e+03 1.97944446e+03 1.98234497e+03 2.02108423e+03 2.07361572e+03 2.12918604e+03 2.17861768e+03 2.19816260e+03 2.19480688e+03 2.24115698e+03 2.39266553e+03 2.51509253e+03 2.49953906e+03 2.41956372e+03 2.40586792e+03 2.50973975e+03 2.66605566e+03 2.78325244e+03 2.76628345e+03 2.66746729e+03 2.72289990e+03 2.85324683e+03 2.88742578e+03 2.89774854e+03 2.93999097e+03 2.99242798e+03 3.04724658e+03 3.17894800e+03 3.13925391e+03 3.11137598e+03 3.22115161e+03 3.16929492e+03 3.29539966e+03 3.43746094e+03 3.36022705e+03 3.49541675e+03 3.49545312e+03 3.38957715e+03 3.54432837e+03 3.50073535e+03 3.58327979e+03 3.88865088e+03 3.75207983e+03 3.56303442e+03 3.67672119e+03 3.91005664e+03 4.09940430e+03 4.02786206e+03 3.86927783e+03 3.82639868e+03 3.94007910e+03 4.10753027e+03 4.28260205e+03 4.26334131e+03 4.07846240e+03 4.08969727e+03 4.23717285e+03 4.34203809e+03 4.31430469e+03 4.31774609e+03 4.39618262e+03 4.42727930e+03 4.62701611e+03 4.64380957e+03 4.41276465e+03 4.42524463e+03 4.61874707e+03 4.68089209e+03 4.72110596e+03 4.73008496e+03 4.86645459e+03 4.80700830e+03 4.67968652e+03 4.84229980e+03 4.74455225e+03 4.91266602e+03 5.26641553e+03 4.97968604e+03 4.75038477e+03 4.93281494e+03 5.20124658e+03 5.37873389e+03 5.36114697e+03 5.09374463e+03 4.94259424e+03 5.11116406e+03 5.37703125e+03 5.57167725e+03 5.47772461e+03 5.21785498e+03 5.22524219e+03 5.45143262e+03 5.50294727e+03 5.59919189e+03 5.64837402e+03 5.39915186e+03 5.40852344e+03 5.72591943e+03 5.77854980e+03 5.54023438e+03 5.55341016e+03 5.70674609e+03 5.67640918e+03 5.91516699e+03 5.98507080e+03 5.76207178e+03 5.74686084e+03 5.77402832e+03 5.80329785e+03 5.89996826e+03 5.90792529e+03 6.09816650e+03 6.20007324e+03 6.01507520e+03 5.84484570e+03 5.74301611e+03 6.05604883e+03 6.39505566e+03 6.30240186e+03 6.02082910e+03 5.83543506e+03 6.11638184e+03 6.48543848e+03 6.28632129e+03 5.93367725e+03 6.09288721e+03 6.30975635e+03 6.45705713e+03 6.63933105e+03 6.52816699e+03 6.13187402e+03 6.12911377e+03 6.35975977e+03 6.43736279e+03 6.46982471e+03 6.45285889e+03 6.50185547e+03 6.44594092e+03 6.56490820e+03 6.54263818e+03 6.39731055e+03 6.41985205e+03 6.38662451e+03 6.62338574e+03 6.73292432e+03 6.57255273e+03 6.63866064e+03 6.67586328e+03 6.65788867e+03 6.52526611e+03 6.39908496e+03 6.66420508e+03 6.99154297e+03 6.84776611e+03 6.51975977e+03 6.48570947e+03 6.79019385e+03 6.94351465e+03 6.82390918e+03 6.74769482e+03 6.55047607e+03 6.57530518e+03 6.85302490e+03 6.86186133e+03 6.69114062e+03 6.55774951e+03 6.52654443e+03 6.89721875e+03 7.20332959e+03 6.80758350e+03 6.62266211e+03 6.80540234e+03 6.83431348e+03 7.04683008e+03 7.01021777e+03 6.59762939e+03 6.68185791e+03 6.89345801e+03 6.86779932e+03 6.89898438e+03 6.96785791e+03 6.73526611e+03 7.20099268e+03 7.27347852e+03 6.69390479e+03 8.52317383e+03 9.11187598e+03 1.09429941e+04 1.06131855e+04 1.01484854e+04 1.04615938e+04 1.03239414e+04 1.08707217e+04 1.14286650e+04 1.06556650e+04 1.84976406e+04 2.84773809e+04 17449876. 34538408. 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. 0. -249400496. -249400496. -249400496. 0. 0. 3318850. 4221781. 2.21180575e+06 2.52339075e+06 -11740239. 4.62016750e+06 2.84509275e+06 1.65851914e+04 1.32200254e+04 7.50664404e+03 6.85979248e+03 6.37655225e+03 6.15638672e+03 6.39952783e+03 6.41092188e+03 6.17728369e+03 6.17980957e+03 6.20985498e+03 6.13868164e+03 6.10939600e+03 6.07878125e+03 5.99291748e+03 6.03381152e+03 6.02416406e+03 6.01991797e+03 6.02092090e+03 5.79094141e+03 5.80665479e+03 6.04706738e+03 6.01439014e+03 5.89411426e+03 5.83882031e+03 5.81372461e+03 5.80734326e+03 5.75299609e+03 5.74033398e+03 5.69686182e+03 5.64206494e+03 5.56493945e+03 5.54403223e+03 5.67585498e+03 5.65747461e+03 5.52350488e+03 5.48615723e+03 5.50315576e+03 5.50018701e+03 5.42346582e+03 5.38643945e+03 5.36628467e+03 5.26433936e+03 5.22534766e+03 5.17065967e+03 5.13825391e+03 5.37381348e+03 5.36739551e+03 5.14861084e+03 4.97731592e+03 4.91389844e+03 5.17866992e+03 5.19441357e+03 4.99429102e+03 4.84273975e+03 4.81344580e+03 4.85126221e+03 4.80960303e+03 4.97069678e+03 4.92250830e+03 4.58873340e+03 4.48748584e+03 4.68892676e+03 4.90393213e+03 4.74795361e+03 4.58884326e+03 4.53973291e+03 4.47877197e+03 4.46975049e+03 4.46110742e+03 4.37304248e+03 4.29414355e+03 4.28765430e+03 4.25209131e+03 4.22015771e+03 4.17574658e+03 4.26469434e+03 4.22388574e+03 4.06504004e+03 4.00555591e+03 3.97786108e+03 4.05992236e+03 4.03416187e+03 3.90604785e+03 3.87223145e+03 3.73944287e+03 3.62257861e+03 3.76310840e+03 3.76787891e+03 3.53323706e+03 3.51811938e+03 3.67868701e+03 3.73763306e+03 3.59412720e+03 3.45211279e+03 3.39965039e+03 3.37736548e+03 3.30666870e+03 3.24345312e+03 3.23168140e+03 3.18718921e+03 3.24585693e+03 3.18559619e+03 3.06601074e+03 3.01864526e+03 2.89691333e+03 2.92311743e+03 3.05017139e+03 2.95459131e+03 2.83401709e+03 2.71692749e+03 2.63575903e+03 2.74626074e+03 2.75993994e+03 2.62706079e+03 2.49603247e+03 2.44911353e+03 2.46150293e+03 2.41431323e+03 2.45135205e+03 2.42701465e+03 2.29079468e+03 2.19683765e+03 2.15909521e+03 2.20332886e+03 2.16319971e+03 2.07050415e+03 2.00677466e+03 1.95438269e+03 1.90597510e+03 1.81392285e+03 1.81909985e+03 1.87751428e+03 1.79005200e+03 1.70254346e+03 1.61698132e+03 1.55777380e+03 1.60420520e+03 1.56197412e+03 1.46842847e+03 1.38630396e+03 1.33706470e+03 1.33249146e+03 1.27949243e+03 1.23401331e+03 1.15727832e+03 1.12869824e+03 1.14006189e+03 1.06386157e+03 1.00114960e+03 9.62293823e+02 9.08401428e+02 8.44824280e+02 7.98171936e+02 7.52658203e+02 7.04118469e+02 6.61285278e+02 5.98666809e+02 5.66423767e+02 5.50578918e+02 4.77656158e+02 4.15432739e+02 3.78085449e+02 3.30413910e+02 2.91213470e+02 2.39398911e+02 1.83519882e+02 1.42071716e+02 9.54900818e+01 4.73031349e+01 -4.42062646e-01 -4.81394844e+01 -9.57441788e+01 -1.44632355e+02 -1.91636871e+02 -2.32462738e+02 -2.87302277e+02 -3.54778748e+02 -3.95645935e+02 -4.28519196e+02 -4.63205688e+02 -5.17550842e+02 -5.97095642e+02 -6.40822937e+02 -6.72544922e+02 -7.01069641e+02 -7.39592407e+02 -8.14042297e+02 -8.62938049e+02 -9.25659912e+02 -9.66967407e+02 -9.86901306e+02 -1.04184338e+03 -1.08758716e+03 -1.17506946e+03 -1.22700378e+03 -1.23466321e+03 -1.27341382e+03 -1.32459448e+03 -1.37298535e+03 -1.37774939e+03 -1.45529944e+03 -1.58309924e+03 -1.60127136e+03 -1.60997498e+03 -1.61506921e+03 -1.65157910e+03 -1.79278394e+03 -1.84414026e+03 -1.84419849e+03 -1.84852368e+03 -1.87886365e+03 -1.98568542e+03 -2.02782361e+03 -2.11659570e+03 -2.15165649e+03 -2.13885669e+03 -2.16558594e+03 -2.20495532e+03 -2.35534766e+03 -2.40561694e+03 -2.38862183e+03 -2.39387622e+03 -2.42528613e+03 -2.56937646e+03 -2.62230273e+03 -2.53456934e+03 -2.58626611e+03 -2.78130664e+03 -2.80888184e+03 -2.71550977e+03 -2.74450952e+03 -2.93480835e+03 -3.00758789e+03 -2.94034644e+03 -2.90421289e+03 -2.96344141e+03 -3.17998193e+03 -3.19860229e+03 -3.15293701e+03 -3.21493091e+03 -3.24208496e+03 -3.23292969e+03 -3.26441064e+03 -3.39500928e+03 -3.34451416e+03 -3.44701099e+03 -3.65598218e+03 -3.59173071e+03 -3.64570435e+03 -3.69301050e+03 -3.66900928e+03 -3.71452954e+03 -3.75314087e+03 -3.78042065e+03 -3.72413062e+03 -3.72525684e+03 -3.86069287e+03 -3.96588354e+03 -4.12535449e+03 -4.02512549e+03 -3.95506396e+03 -4.12038916e+03 -4.14600391e+03 -4.29975244e+03 -4.31811621e+03 -4.23723340e+03 -4.20915381e+03 -4.21597852e+03 -4.36094971e+03 -4.40253223e+03 -4.52805029e+03 -4.57632471e+03 -4.50063477e+03 -4.49789746e+03 -4.42504150e+03 -4.58291992e+03 -4.85250537e+03 -4.82845264e+03 -4.71440088e+03 -4.64133301e+03 -4.64329736e+03 -4.91667676e+03 -5.03036475e+03 -4.90787988e+03 -4.79381055e+03 -4.84002344e+03 -5.00724365e+03 -5.01236426e+03 -5.16837695e+03 -5.17375830e+03 -5.08169727e+03 -5.12536328e+03 -5.12895361e+03 -5.30517334e+03 -5.35705469e+03 -5.13254297e+03 -5.15539014e+03 -5.48896289e+03 -5.41979980e+03 -5.15314209e+03 -5.35361572e+03 -5.66001318e+03 -5.63093701e+03 -5.52226562e+03 -5.38379980e+03 -5.42356006e+03 -5.77004443e+03 -5.77179199e+03 -5.64864551e+03 -5.54099170e+03 -5.52643311e+03 -5.70871582e+03 -5.74855615e+03 -5.80475293e+03 -5.66478564e+03 -5.79962695e+03 -6.09661768e+03 -5.98513135e+03 -5.97960889e+03 -5.94893848e+03 -5.90496533e+03 -5.95974707e+03 -5.99937842e+03 -6.05272168e+03 -6.04519482e+03 -6.04164111e+03 -5.92006055e+03 -6.01714648e+03 -6.36186426e+03 -6.09033691e+03 -5.93105957e+03 -6.14151953e+03 -6.29788672e+03 -6.50987988e+03 -6.42021289e+03 -6.27588477e+03 -6.34599023e+03 -6.30472314e+03 -6.21771094e+03 -6.19775000e+03 -6.49694482e+03 -6.44017188e+03 -6.31816602e+03 -6.33892432e+03 -6.18207959e+03 -6.40498291e+03 -6.79874072e+03 -6.61959180e+03 -6.46851807e+03 -6.31801270e+03 -6.32132275e+03 -6.70310645e+03 -6.84650781e+03 -6.61530615e+03 -6.45287891e+03 -6.43494141e+03 -6.54247217e+03 -6.59010107e+03 -6.82793359e+03 -6.75658545e+03 -6.58917676e+03 -6.60706836e+03 -6.61826807e+03 -6.76019727e+03 -6.75254980e+03 -6.65894336e+03 -6.74589209e+03 -6.75227441e+03 -6.65208838e+03 -6.48807373e+03 -6.65038672e+03 -7.01363232e+03 -6.89319482e+03 -6.73730225e+03 -6.61586475e+03 -6.63614746e+03 -7.05604883e+03 -7.00919824e+03 -6.78427637e+03 -6.68535352e+03 -6.66201709e+03 -6.72823047e+03 -6.74395068e+03 -6.85146875e+03 -6.65998145e+03 -6.79245850e+03 -7.04996191e+03 -6.87107617e+03 -6.93176367e+03 -6.92597607e+03 -6.83523682e+03 -6.89727441e+03 -6.86840332e+03 -6.68934473e+03 -6.70251953e+03 -6.91948975e+03 -6.90570020e+03 -6.91767139e+03 -6.88059033e+03 -6.65719385e+03 -6.60931641e+03 -6.83512451e+03 -6.85847266e+03 -7.03560840e+03 -6.94176172e+03 -6.65790723e+03 -6.84254053e+03 -6.92389844e+03 -6.83193848e+03 -6.72506201e+03 -6.69934180e+03 -6.79842188e+03 -6.76648584e+03 -6.78122363e+03 -6.61175098e+03 -6.75390234e+03 -7.07482227e+03 -6.93850732e+03 -6.74224170e+03 -6.54229492e+03 -6.52824854e+03 -6.92109326e+03 -6.88835254e+03 -6.71200146e+03 -6.51726270e+03 -6.40393994e+03 -6.62249365e+03 -6.75069043e+03 -6.93978076e+03 -6.68281250e+03 -6.41214746e+03 -6.51168066e+03 -6.60422949e+03 -6.80602246e+03 -6.63897070e+03 -6.41360889e+03 -6.56919873e+03 -6.57049365e+03 -6.49492236e+03 -6.33368066e+03 -6.42833789e+03 -6.76469141e+03 -6.67360498e+03 -6.42704199e+03 -6.21980322e+03 -6.26198828e+03 -6.61716309e+03 -6.57595752e+03 -6.37850635e+03 -6.20546924e+03 -6.14105664e+03 -6.31874951e+03 -6.29924121e+03 -6.45346094e+03 -6.42162012e+03 -6.15886816e+03 -6.01749609e+03 -6.09608447e+03 -6.40747998e+03 -6.24455322e+03 -6.04946094e+03 -6.18362451e+03 -6.14284521e+03 -5.96218604e+03 -5.85063574e+03 -6.02607471e+03 -5.98782373e+03 -5.85258154e+03 -6.09972803e+03 -6.11234131e+03 -5.94740332e+03 -5.88102197e+03 -5.83881689e+03 -5.83115186e+03 -5.66637891e+03 -5.57315381e+03 -5.82995605e+03 -5.90530371e+03 -5.59421924e+03 -5.42084814e+03 -5.64455957e+03 -5.83460938e+03 -5.74053516e+03 -5.52920215e+03 -5.38213281e+03 -5.52983838e+03 -5.64111328e+03 -5.51539844e+03 -5.43300293e+03 -5.24867676e+03 -5.11442236e+03 -5.33214502e+03 -5.54885596e+03 -5.40851904e+03 -5.12666699e+03 -5.04158252e+03 -5.29192871e+03 -5.34423584e+03 -5.13294775e+03 -4.97624463e+03 -4.90075830e+03 -4.92173242e+03 -4.94881396e+03 -5.08342285e+03 -5.06758594e+03 -4.84223730e+03 -4.78827783e+03 -4.78563721e+03 -4.87988232e+03 -4.73228564e+03 -4.58593262e+03 -4.77442578e+03 -4.75983691e+03 -4.56466309e+03 -4.41783887e+03 -4.47452539e+03 -4.68221484e+03 -4.47874609e+03 -4.27652930e+03 -4.35196533e+03 -4.39017041e+03 -4.37206055e+03 -4.28315186e+03 -4.35571240e+03 -4.34700635e+03 -4.16922998e+03 -4.00842383e+03 -3.98585620e+03 -4.16858154e+03 -4.07214526e+03 -3.91587891e+03 -3.93244702e+03 -3.91041309e+03 -3.86303882e+03 -3.78903003e+03 -3.80582202e+03 -3.74828760e+03 -3.63710645e+03 -3.68796997e+03 -3.65326709e+03 -3.64572339e+03 -3.60503198e+03 -3.50230225e+03 -3.43577319e+03 -3.30321118e+03 -3.28395337e+03 -3.42729980e+03 -3.43581055e+03 -3.21359668e+03 -3.07478149e+03 -3.14422437e+03 -3.22712842e+03 -3.16422876e+03 -3.00922266e+03 -2.87481763e+03 -2.95952051e+03 -2.99565674e+03 -2.86894873e+03 -2.88277905e+03 -2.81082886e+03 -2.65611060e+03 -2.67100391e+03 -2.72673877e+03 -2.65536597e+03 -2.49560010e+03 -2.41974146e+03 -2.51131616e+03 -2.52295239e+03 -2.39696240e+03 -2.26338110e+03 -2.21121606e+03 -2.29790747e+03 -2.24260278e+03 -2.12916309e+03 -2.12000635e+03 -2.07047192e+03 -2.00218042e+03 -1.94839441e+03 -1.97707422e+03 -1.89555359e+03 -1.78181909e+03 -1.82554980e+03 -1.78748474e+03 -1.71696216e+03 -1.63594885e+03 -1.56328247e+03 -1.59604126e+03 -1.52141284e+03 -1.41267188e+03 -1.41640356e+03 -1.44006604e+03 -1.37579138e+03 -1.21950659e+03 -1.28015210e+03 -1.32893250e+03 -1.14610254e+03 -1.08186597e+03 -9.67339722e+02 -1.01838519e+03 -1.27411365e+03 -9.38010376e+02 -8.74695557e+02 -1.01579028e+03 -1.32305225e+03 -5.27330762e+03 -115786944. 0. 0. 0. 0. 0. 0. -219605696. -219605696. -1.33163477e+03 -3.50749146e+03 -3.50749146e+03 833382336. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 273463104. 7.61380811e+03 1.73774585e+03 1.03364136e+03 1.17995288e+03 1.13745203e+03 1.02586218e+03 1.06075854e+03 1.10947278e+03 1.15443555e+03 1.17840491e+03 1.22895850e+03 1.30020068e+03 1.33719031e+03 1.37540649e+03 1.40810095e+03 1.45303235e+03 1.54066101e+03 1.58132788e+03 1.59821228e+03 1.64389990e+03 1.67781628e+03 1.73893103e+03 1.83992346e+03 1.89394873e+03 1.87552905e+03 1.89817407e+03 1.97587524e+03 2.03316223e+03 2.05871680e+03 2.09310767e+03 2.16282642e+03 2.20571362e+03 2.27769971e+03 2.31754468e+03 2.28001709e+03 2.35344043e+03 2.47849097e+03 2.54685815e+03 2.56991797e+03 2.50842554e+03 2.53051245e+03 2.67628687e+03 2.73268726e+03 2.72905859e+03 2.75531421e+03 2.80101587e+03 2.89911963e+03 2.98381519e+03 2.97765161e+03 2.91998877e+03 2.97105859e+03 3.17804321e+03 3.21908154e+03 3.10961548e+03 3.14077051e+03 3.26019897e+03 3.33379932e+03 3.41547241e+03 3.39345728e+03 3.33984131e+03 3.41121533e+03 3.52482007e+03 3.59391406e+03 3.60592139e+03 3.55538037e+03 3.64963623e+03 3.77442041e+03 3.77686060e+03 3.77383618e+03 3.76475317e+03 3.83187256e+03 3.95026587e+03 3.99790063e+03 4.03941284e+03 4.00851343e+03 3.95953955e+03 4.09377173e+03 4.17324756e+03 4.17936572e+03 4.22255420e+03 4.21141260e+03 4.28039941e+03 4.41774609e+03 4.42146680e+03 4.30225928e+03 4.34337158e+03 4.50848291e+03 4.58477002e+03 4.57530469e+03 4.52065186e+03 4.58711133e+03 4.65444043e+03 4.72862012e+03 4.74316455e+03 4.65803369e+03 4.77148145e+03 4.90843652e+03 4.92634521e+03 4.93226367e+03 4.84938184e+03 4.87530273e+03 5.05717041e+03 5.06439795e+03 4.97298047e+03 4.99728076e+03 5.08031348e+03 5.20864160e+03 5.24058691e+03 5.21749805e+03 5.24171680e+03 5.26738232e+03 5.38003174e+03 5.39788428e+03 5.30812451e+03 5.37197900e+03 5.43457520e+03 5.39797900e+03 5.48978516e+03 5.55344287e+03 5.53707568e+03 5.56043652e+03 5.56741113e+03 5.59346289e+03 5.69530176e+03 5.72492334e+03 5.71510693e+03 5.72507861e+03 5.67906787e+03 5.72838232e+03 5.86831641e+03 5.82569385e+03 5.78397949e+03 5.89737695e+03 6.06286914e+03 6.02764111e+03 5.90107227e+03 5.96340186e+03 6.04898877e+03 5.97534229e+03 5.95141455e+03 5.99545850e+03 6.01913232e+03 6.15392090e+03 6.25859668e+03 6.20879736e+03 6.14047510e+03 6.09425781e+03 6.19815576e+03 6.31184424e+03 6.30320654e+03 6.27444531e+03 6.22903027e+03 6.31867285e+03 6.43622949e+03 6.40768311e+03 6.29348193e+03 6.20664258e+03 6.35238037e+03 6.54192969e+03 6.50337598e+03 6.24487256e+03 6.32400146e+03 6.55529883e+03 6.54505176e+03 6.46264258e+03 6.49609424e+03 6.53163379e+03 6.50764111e+03 6.61360498e+03 6.57724658e+03 6.46993994e+03 6.62389404e+03 6.72073193e+03 6.62839062e+03 6.68691602e+03 6.65256689e+03 6.55058057e+03 6.59946240e+03 6.67057861e+03 6.75500537e+03 6.84592334e+03 6.59377393e+03 6.58516797e+03 6.85241553e+03 6.73316211e+03 6.58243652e+03 6.69149512e+03 6.78123193e+03 6.83446338e+03 6.82192773e+03 6.76626318e+03 6.70362500e+03 6.68707910e+03 6.85872900e+03 6.91303076e+03 6.71872412e+03 6.77676221e+03 6.97597070e+03 6.86994531e+03 6.86364160e+03 6.76319385e+03 6.68534961e+03 6.88969092e+03 6.83389746e+03 6.79312451e+03 6.88282764e+03 6.74990527e+03 6.81378223e+03 7.02105273e+03 6.81295410e+03 6.77981006e+03 6.84351855e+03 6.86199072e+03 6.82611475e+03 6.84250928e+03 6.80554053e+03 6.79457812e+03 6.77780273e+03 6.85343506e+03 6.83000195e+03 6.73449512e+03 6.82184521e+03 6.93636963e+03 6.80555615e+03 6.93830273e+03 6.85530566e+03 6.60552490e+03 6.76800049e+03 6.82818408e+03 6.78195117e+03 6.67616016e+03 6.57212695e+03 6.79341211e+03 6.94497803e+03 6.73515576e+03 6.62437207e+03 6.77993164e+03 6.86009424e+03 6.67464697e+03 6.54385303e+03 6.74693018e+03 6.70586426e+03 6.58793311e+03 6.77434082e+03 6.63571045e+03 6.56045361e+03 6.62425244e+03 6.56207471e+03 6.56112158e+03 6.61849414e+03 6.50349463e+03 6.49793408e+03 6.57059131e+03 6.62469238e+03 6.60696924e+03 6.38131396e+03 6.36056445e+03 6.53268896e+03 6.43837158e+03 6.46824805e+03 6.42427686e+03 6.35689990e+03 6.36210303e+03 6.37358887e+03 6.45943164e+03 6.33073682e+03 6.10293311e+03 6.26625684e+03 6.49821094e+03 6.22370117e+03 6.05866699e+03 6.15092676e+03 6.11915820e+03 6.19644189e+03 6.25210449e+03 6.06850928e+03 6.06393066e+03 6.09464795e+03 6.06272998e+03 6.10048682e+03 6.03074072e+03 6.05700439e+03 6.07084717e+03 5.79935742e+03 5.87794287e+03 5.92932812e+03 5.79259180e+03 5.93647754e+03 5.83947803e+03 5.72805762e+03 5.78756689e+03 5.69455566e+03 5.71917334e+03 5.86057910e+03 5.72075391e+03 5.61175439e+03 5.55731250e+03 5.47897119e+03 5.57736182e+03 5.62282422e+03 5.49271826e+03 5.42789746e+03 5.51613672e+03 5.49045850e+03 5.41645459e+03 5.30053809e+03 5.28916943e+03 5.32713037e+03 5.30833936e+03 5.28687744e+03 5.13921289e+03 5.10613672e+03 5.16877686e+03 5.19581055e+03 5.13254639e+03 5.07408838e+03 4.98632373e+03 4.89833252e+03 5.09091943e+03 5.10079639e+03 4.84524805e+03 4.73502246e+03 4.75527490e+03 4.77662988e+03 4.75853223e+03 4.68343701e+03 4.67526758e+03 4.69916064e+03 4.64417529e+03 4.61858887e+03 4.55166406e+03 4.48405518e+03 4.50187695e+03 4.49533008e+03 4.40951904e+03 4.28530957e+03 4.29839648e+03 4.27959961e+03 4.24465918e+03 4.26739502e+03 4.18040674e+03 4.08927612e+03 4.08984155e+03 4.14230908e+03 4.05867993e+03 3.95038940e+03 3.92669702e+03 3.90535474e+03 3.85883252e+03 3.82304297e+03 3.74832153e+03 3.71480493e+03 3.72025415e+03 3.71083008e+03 3.68986377e+03 3.57495996e+03 3.53842969e+03 3.51120874e+03 3.43222998e+03 3.39203564e+03 3.33734570e+03 3.36160571e+03 3.31658667e+03 3.22731665e+03 3.16356421e+03 3.13073462e+03 3.15406641e+03 3.13999658e+03 3.10800220e+03 3.00641040e+03 2.93982690e+03 2.89990894e+03 2.81079468e+03 2.79509570e+03 2.79872266e+03 2.74489844e+03 2.68573535e+03 2.60335840e+03 2.56969263e+03 2.57829077e+03 2.57307690e+03 2.51751978e+03 2.41751904e+03 2.34324487e+03 2.32699976e+03 2.29702344e+03 2.22563550e+03 2.20832593e+03 2.19610132e+03 2.09766602e+03 2.02945056e+03 1.98801440e+03 1.95606921e+03 1.97622791e+03 1.92501917e+03 1.82142480e+03 1.79427417e+03 1.73844788e+03 1.66046326e+03 1.66372949e+03 1.62455396e+03 1.54052783e+03 1.49293958e+03 1.44456506e+03 1.38559937e+03 1.37432922e+03 1.37178540e+03 1.29081799e+03 1.22207275e+03 1.18425354e+03 1.13087634e+03 1.08733911e+03 1.04057581e+03 9.97143982e+02 9.44844666e+02 8.89204651e+02 8.53120544e+02 8.12848633e+02 7.52494507e+02 7.16339478e+02 6.79328125e+02 6.12288635e+02 5.55576111e+02 5.13660156e+02 4.76970306e+02 4.33119934e+02 3.84689789e+02 3.27578735e+02 2.73324036e+02 2.33543411e+02 1.94645462e+02 1.48904694e+02 9.53211746e+01 4.46961250e+01 -5.94789934e+00 -5.42728119e+01 -9.97399216e+01 -1.42958466e+02 -1.88140320e+02 -2.36626068e+02 -2.93176727e+02 -3.39219208e+02 -3.73893219e+02 -4.31667053e+02 -4.97633209e+02 -5.34272522e+02 -5.68068298e+02 -6.17444275e+02 -6.70715820e+02 -7.24717773e+02 -7.71995361e+02 -8.15747009e+02 -8.47606812e+02 -8.96147400e+02 -9.55144531e+02 -1.00260431e+03 -1.06954834e+03 -1.10202417e+03 -1.13616907e+03 -1.18639038e+03 -1.24191992e+03 -1.29653894e+03 -1.32697607e+03 -1.38866052e+03 -1.44672632e+03 -1.47186938e+03 -1.49014868e+03 -1.53534326e+03 -1.60185583e+03 -1.69327002e+03 -1.73991907e+03 -1.73376257e+03 -1.76950256e+03 -1.81889026e+03 -1.89421265e+03 -1.97236157e+03 -1.98018970e+03 -1.99200073e+03 -2.10062817e+03 -2.13751880e+03 -2.11916309e+03 -2.24130371e+03 -2.30080786e+03 -2.27366040e+03 -2.33964917e+03 -2.34501123e+03 -2.38250317e+03 -2.53141333e+03 -2.55860791e+03 -2.54892969e+03 -2.63478223e+03 -2.66973901e+03 -2.62730469e+03 -2.69070264e+03 -2.79611719e+03 -2.83898608e+03 -2.90252539e+03 -2.89316650e+03 -2.91442822e+03 -3.01411353e+03 -3.07285864e+03 -3.19411328e+03 -3.16831567e+03 -3.07477808e+03 -3.16278149e+03 -3.26221558e+03 -3.31276392e+03 -3.38547119e+03 -3.37574609e+03 -3.34316382e+03 -3.46949072e+03 -3.56401196e+03 -3.53744043e+03 -3.58433618e+03 -3.64224951e+03 -3.60716992e+03 -3.71893457e+03 -3.79080249e+03 -3.73814014e+03 -3.89251392e+03 -3.96180127e+03 -3.90506616e+03 -3.93150098e+03 -3.86298584e+03 -3.91661938e+03 -4.09846387e+03 -4.26080176e+03 -4.22460449e+03 -4.03858398e+03 -4.12590625e+03 -4.29906885e+03 -4.31002051e+03 -4.31739697e+03 -4.35098535e+03 -4.36817236e+03 -4.46429150e+03 -4.49758643e+03 -4.52738281e+03 -4.54612061e+03 -4.58205469e+03 -4.70274219e+03 -4.64996777e+03 -4.60298730e+03 -4.65915283e+03 -4.73201318e+03 -4.82478857e+03 -4.94625244e+03 -4.87914893e+03 -4.77597266e+03 -4.88265088e+03 -4.98541699e+03 -5.12819580e+03 -5.11510400e+03 -4.96420068e+03 -5.02226514e+03 -5.11749023e+03 -5.21282422e+03 -5.32377393e+03 -5.25554395e+03 -5.17148779e+03 -5.25012793e+03 -5.23963330e+03 -5.21229834e+03 -5.41180762e+03 -5.53810107e+03 -5.46945361e+03 -5.39690283e+03 -5.37955273e+03 -5.42217676e+03 -5.64918262e+03 -5.69501660e+03 -5.63818945e+03 -5.58903906e+03 -5.49838428e+03 -5.58907324e+03 -5.71385742e+03 -5.86262842e+03 -5.86171680e+03 -5.68511670e+03 -5.72856055e+03 -5.77638281e+03 -5.85001855e+03 -5.92218164e+03 -5.95709082e+03 -6.01346826e+03 -5.90010938e+03 -5.92647510e+03 -6.00346387e+03 -6.00353809e+03 -6.05053809e+03 -6.11749072e+03 -6.11958643e+03 -6.10505420e+03 -6.06587256e+03 -6.15043359e+03 -6.28955371e+03 -6.26592383e+03 -6.13674219e+03 -6.17473047e+03 -6.21470020e+03 -6.22997461e+03 -6.44089160e+03 -6.42194189e+03 -6.28389893e+03 -6.39107178e+03 -6.32084766e+03 -6.35431299e+03 -6.55909961e+03 -6.55362939e+03 -6.49835742e+03 -6.51957666e+03 -6.23852393e+03 -6.39493506e+03 -6.60656250e+03 -6.39648877e+03 -9.22077344e+03 -8.71612207e+03 -1.91186914e+04 -2.88367031e+04 7554618. 49093276. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -13710447. 2.95389075e+06 3.39485750e+06 -3429949. -2.92355137e+04 -1.99715410e+04 -1.11983955e+04 -7.71975879e+03 -6.89574268e+03 -6.93465869e+03 -7.12446777e+03 -7.00858252e+03 -6.85033496e+03 -6.62774707e+03 -6.71542725e+03 -6.89063818e+03 -6.92417090e+03 -6.88140381e+03 -6.73862988e+03 -6.73247803e+03 -6.74350049e+03 -6.85022510e+03 -6.83003955e+03 -6.60602881e+03 -6.65535742e+03 -6.79900244e+03 -6.77643799e+03 -6.62400732e+03 -6.50321729e+03 -6.70361230e+03 -6.97838281e+03 -6.93308350e+03 -6.56932520e+03 -6.27891553e+03 -6.45490918e+03 -6.73270264e+03 -6.87722168e+03 -6.71566846e+03 -6.45574365e+03 -6.45517578e+03 -6.62527393e+03 -6.75258447e+03 -6.63211719e+03 -6.29846436e+03 -6.30688477e+03 -6.64328223e+03 -6.59636377e+03 -6.35677295e+03 -6.41091602e+03 -6.45630664e+03 -6.49567725e+03 -6.50947363e+03 -6.23232422e+03 -6.10965186e+03 -6.44299365e+03 -6.58523047e+03 -6.41108398e+03 -6.17801904e+03 -5.99524658e+03 -6.29925049e+03 -6.47928955e+03 -6.33277930e+03 -6.11078809e+03 -5.88950977e+03 -5.93455420e+03 -6.23625293e+03 -6.32190723e+03 -6.20810547e+03 -6.05991846e+03 -6.03854932e+03 -5.96691406e+03 -5.96387842e+03 -5.98736719e+03 -5.81093604e+03 -5.85735547e+03 -6.05930859e+03 -5.94521387e+03 -5.66720898e+03 -5.58770605e+03 -5.85964648e+03 -6.01763525e+03 -5.89860205e+03 -5.66417871e+03 -5.50805176e+03 -5.50603613e+03 -5.61731201e+03 -5.86060352e+03 -5.74475781e+03 -5.39743701e+03 -5.41344189e+03 -5.46911475e+03 -5.53425830e+03 -5.59212695e+03 -5.35495898e+03 -5.31097314e+03 -5.44528809e+03 -5.36426660e+03 -5.27009814e+03 -5.20272461e+03 -5.19828418e+03 -5.28429785e+03 -5.24004492e+03 -5.04007959e+03 -4.99211816e+03 -5.12178564e+03 -5.17973242e+03 -5.10724609e+03 -4.98245508e+03 -4.82746777e+03 -4.86353467e+03 -4.98252295e+03 -4.96376367e+03 -4.83169336e+03 -4.59659424e+03 -4.59668164e+03 -4.80743311e+03 -4.85602930e+03 -4.71488232e+03 -4.49727148e+03 -4.49836572e+03 -4.60670947e+03 -4.55391650e+03 -4.41447705e+03 -4.32291406e+03 -4.43428418e+03 -4.46547803e+03 -4.31285352e+03 -4.22464551e+03 -4.13854834e+03 -4.21194824e+03 -4.37381006e+03 -4.22321094e+03 -4.05154150e+03 -3.97103442e+03 -3.95696704e+03 -4.00391138e+03 -4.04104126e+03 -3.94959473e+03 -3.73747168e+03 -3.72296875e+03 -3.87221582e+03 -3.86968848e+03 -3.72125635e+03 -3.59568774e+03 -3.60965869e+03 -3.65157788e+03 -3.60137036e+03 -3.48993359e+03 -3.35058301e+03 -3.34915112e+03 -3.43078003e+03 -3.40590088e+03 -3.29889331e+03 -3.18316797e+03 -3.17254541e+03 -3.20468555e+03 -3.22529419e+03 -3.16121094e+03 -2.96598267e+03 -2.93603271e+03 -2.97805249e+03 -2.94376221e+03 -2.88780469e+03 -2.80984546e+03 -2.76389868e+03 -2.72285376e+03 -2.69094336e+03 -2.63741626e+03 -2.56699854e+03 -2.58761182e+03 -2.60116675e+03 -2.50711401e+03 -2.37499829e+03 -2.31056055e+03 -2.34796411e+03 -2.37668945e+03 -2.32455933e+03 -2.20537817e+03 -2.09049243e+03 -2.03467358e+03 -2.06653809e+03 -2.11318652e+03 -2.01458838e+03 -1.86353967e+03 -1.84810974e+03 -1.85648560e+03 -1.82163818e+03 -1.77926843e+03 -1.69274866e+03 -1.64403931e+03 -1.61298572e+03 -1.54843347e+03 -1.48983289e+03 -1.46119067e+03 -1.43712280e+03 -1.38187622e+03 -1.32785242e+03 -1.27474084e+03 -1.21848901e+03 -1.19257886e+03 -1.16791443e+03 -1.11401941e+03 -1.02507251e+03 -9.57835571e+02 -9.51350647e+02 -9.25436584e+02 -8.66003662e+02 -8.08171570e+02 -7.38168640e+02 -6.91226135e+02 -6.76944641e+02 -6.46154663e+02 -5.86625366e+02 -5.16711792e+02 -4.65464661e+02 -4.30133423e+02 -3.83018463e+02 -3.32498383e+02 -2.87982605e+02 -2.42549118e+02 -1.91195129e+02 -1.39843063e+02 -9.01027069e+01 -4.43741188e+01 1.35992455e+00 4.87838631e+01 9.95202408e+01 1.47415543e+02 1.87206055e+02 2.38884720e+02 2.92367981e+02 3.38329620e+02 3.90205414e+02 4.32485077e+02 4.89963409e+02 5.35349304e+02 5.55319946e+02 5.93222473e+02 6.53629944e+02 7.35591064e+02 8.07964111e+02 8.37924316e+02 8.36997803e+02 8.58746155e+02 9.22951050e+02 1.02728357e+03 1.11101172e+03 1.13048145e+03 1.10646045e+03 1.14370862e+03 1.28345850e+03 1.32257141e+03 1.30478296e+03 1.35517957e+03 1.41234937e+03 1.46313708e+03 1.55881531e+03 1.57122681e+03 1.55864270e+03 1.65053601e+03 1.66602100e+03 1.74892505e+03 1.84315491e+03 1.79122070e+03 1.88211243e+03 1.99245020e+03 1.98410522e+03 2.02010742e+03 2.05705640e+03 2.12724341e+03 2.18349658e+03 2.18582617e+03 2.19537524e+03 2.24833643e+03 2.39533789e+03 2.50528076e+03 2.48516846e+03 2.42183179e+03 2.41654590e+03 2.50566797e+03 2.66435889e+03 2.78563647e+03 2.76117603e+03 2.66562939e+03 2.72307812e+03 2.86297388e+03 2.88446753e+03 2.89353247e+03 2.94839966e+03 2.96644141e+03 3.02869531e+03 3.19587256e+03 3.15067261e+03 3.10149170e+03 3.20005542e+03 3.15936475e+03 3.30804443e+03 3.44674438e+03 3.35735059e+03 3.49409155e+03 3.49424292e+03 3.38765210e+03 3.54783691e+03 3.49963696e+03 3.58799121e+03 3.89109644e+03 3.74403149e+03 3.57601123e+03 3.69276416e+03 3.89580688e+03 4.07621973e+03 4.03180469e+03 3.82660107e+03 3.77513794e+03 3.95772754e+03 4.14298193e+03 4.31155762e+03 4.28025146e+03 4.05563208e+03 4.07769629e+03 4.26918018e+03 4.40030615e+03 4.28490039e+03 4.24511670e+03 4.39721289e+03 4.44211963e+03 4.60317480e+03 4.63260840e+03 4.45742822e+03 4.48343262e+03 4.57618701e+03 4.63638379e+03 4.73592529e+03 4.71863721e+03 4.86401855e+03 4.82890283e+03 4.69510400e+03 4.81061816e+03 4.73993652e+03 4.92301270e+03 5.25755371e+03 5.00802295e+03 4.74073535e+03 4.89514404e+03 5.16831152e+03 5.33864014e+03 5.40272217e+03 5.14233301e+03 4.95957324e+03 5.10343896e+03 5.34082959e+03 5.60870752e+03 5.50780664e+03 5.19559326e+03 5.19663770e+03 5.41965820e+03 5.52772461e+03 5.64933594e+03 5.65838525e+03 5.39015137e+03 5.41600732e+03 5.68970605e+03 5.74760352e+03 5.63044287e+03 5.62109863e+03 5.64224609e+03 5.61745703e+03 5.90996777e+03 5.98039941e+03 5.69483350e+03 5.69851025e+03 5.79512109e+03 5.87299707e+03 5.91239893e+03 5.89207715e+03 6.06939600e+03 6.17651221e+03 5.97585986e+03 5.87297607e+03 5.77694971e+03 6.02123633e+03 6.40080615e+03 6.30798926e+03 5.97143408e+03 5.86928760e+03 6.11534375e+03 6.46735352e+03 6.28635156e+03 5.96978516e+03 6.08430273e+03 6.28550928e+03 6.42522070e+03 6.64423779e+03 6.54041260e+03 6.17636670e+03 6.07140430e+03 6.29711572e+03 6.55479834e+03 6.53429883e+03 6.46178955e+03 6.45121143e+03 6.42091455e+03 6.57141602e+03 6.53232812e+03 6.38801172e+03 6.35703467e+03 6.39969043e+03 6.65349902e+03 6.75217236e+03 6.57054395e+03 6.61806396e+03 6.65419580e+03 6.78147314e+03 6.61516797e+03 6.28883350e+03 6.61021631e+03 7.00365186e+03 6.81631445e+03 6.46935840e+03 6.56080713e+03 6.87376367e+03 6.88820361e+03 6.78221240e+03 6.72593896e+03 6.55401074e+03 6.57210742e+03 6.94807031e+03 6.96607520e+03 6.65768604e+03 6.48246484e+03 6.53746436e+03 6.86102051e+03 7.15991992e+03 6.83632910e+03 6.65576514e+03 6.79722998e+03 6.81166943e+03 7.03920215e+03 7.03141113e+03 6.61937695e+03 6.65385303e+03 6.84567578e+03 6.85509961e+03 6.87898389e+03 6.78013428e+03 6.96747803e+03 7.13179346e+03 7.09669678e+03 7.17377148e+03 8.60697949e+03 8.84256348e+03 1.09429941e+04 1.06131855e+04 1.01484854e+04 1.04615938e+04 1.03239414e+04 1.08707217e+04 1.14286650e+04 1.06556650e+04 1.84976406e+04 2.84773809e+04 17449876. 34538408. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 22249762. -2.53423725e+06 -6.80806950e+06 1.90120195e+04 1.33684854e+04 7.55563184e+03 6.87034961e+03 6.44094629e+03 6.18177344e+03 6.36673340e+03 6.33247803e+03 6.18378516e+03 6.19534619e+03 6.19940088e+03 6.13224902e+03 6.13222070e+03 6.09203809e+03 6.01387354e+03 5.98699121e+03 5.94461182e+03 6.05994775e+03 6.09583057e+03 5.79957324e+03 5.76802051e+03 6.06554785e+03 6.04165430e+03 5.88596436e+03 5.83889404e+03 5.81144336e+03 5.80707764e+03 5.72550146e+03 5.72321826e+03 5.71922998e+03 5.62297900e+03 5.58627881e+03 5.55818408e+03 5.65489990e+03 5.65323145e+03 5.52892969e+03 5.49519922e+03 5.49123340e+03 5.47280273e+03 5.41667627e+03 5.36918848e+03 5.35257031e+03 5.20264111e+03 5.14740674e+03 5.21291943e+03 5.17690771e+03 5.39191895e+03 5.37920850e+03 5.12899854e+03 4.95868701e+03 4.90611475e+03 5.18503467e+03 5.21673828e+03 5.00088623e+03 4.85872998e+03 4.83670801e+03 4.87153955e+03 4.81072070e+03 4.94805811e+03 4.89191016e+03 4.57622754e+03 4.51760400e+03 4.72542725e+03 4.87508643e+03 4.71161768e+03 4.58022070e+03 4.55341357e+03 4.49329395e+03 4.40746973e+03 4.40288672e+03 4.37765918e+03 4.29742578e+03 4.28288086e+03 4.25506836e+03 4.25729590e+03 4.20170557e+03 4.25133789e+03 4.22135840e+03 4.05789795e+03 4.06233032e+03 4.03558740e+03 4.01151196e+03 3.99895825e+03 3.91032861e+03 3.86460669e+03 3.74453589e+03 3.62013257e+03 3.76368774e+03 3.75763550e+03 3.54837109e+03 3.52784839e+03 3.68585693e+03 3.74987964e+03 3.59721948e+03 3.45983325e+03 3.39014404e+03 3.34613159e+03 3.29012793e+03 3.23744849e+03 3.26479053e+03 3.21446045e+03 3.23996069e+03 3.17276318e+03 3.05325781e+03 3.05444287e+03 2.92593799e+03 2.89328247e+03 3.01340356e+03 2.94773999e+03 2.82850342e+03 2.72230029e+03 2.64265430e+03 2.73913184e+03 2.75083984e+03 2.62669702e+03 2.49439111e+03 2.44933203e+03 2.46387329e+03 2.41848340e+03 2.45144434e+03 2.42369287e+03 2.29627759e+03 2.19831641e+03 2.15742529e+03 2.21027222e+03 2.16853735e+03 2.07042603e+03 1.99117786e+03 1.94272900e+03 1.93364880e+03 1.83882251e+03 1.80061621e+03 1.85658569e+03 1.79747766e+03 1.70777649e+03 1.60598889e+03 1.55078040e+03 1.60982654e+03 1.56240393e+03 1.46936646e+03 1.38831421e+03 1.33297375e+03 1.32877271e+03 1.27885071e+03 1.23376221e+03 1.16090637e+03 1.13029407e+03 1.13798914e+03 1.06794763e+03 1.00544781e+03 9.62246216e+02 9.10185791e+02 8.49141724e+02 8.00065125e+02 7.61239929e+02 7.14250793e+02 6.64165955e+02 6.00443848e+02 5.64285522e+02 5.48826294e+02 4.78470642e+02 4.15925720e+02 3.78742188e+02 3.31226776e+02 2.93207458e+02 2.39595947e+02 1.84325104e+02 1.45930374e+02 9.76267548e+01 4.71264915e+01 -2.04108000e+00 -5.07384758e+01 -9.86248322e+01 -1.46150101e+02 -1.93059204e+02 -2.33018051e+02 -2.85442200e+02 -3.52889740e+02 -3.94900879e+02 -4.28487122e+02 -4.59675018e+02 -5.13258972e+02 -5.96591492e+02 -6.41372314e+02 -6.71654663e+02 -7.01345764e+02 -7.39866394e+02 -8.10704468e+02 -8.60005737e+02 -9.28828003e+02 -9.57791321e+02 -9.72487000e+02 -1.04639856e+03 -1.09521521e+03 -1.17137463e+03 -1.21378223e+03 -1.22554211e+03 -1.27528809e+03 -1.32340955e+03 -1.38582581e+03 -1.39253882e+03 -1.45774316e+03 -1.58673413e+03 -1.59783740e+03 -1.60576819e+03 -1.61673975e+03 -1.65231580e+03 -1.79225793e+03 -1.84775000e+03 -1.84189417e+03 -1.83986230e+03 -1.87886475e+03 -1.98355762e+03 -2.03356641e+03 -2.13091724e+03 -2.14422974e+03 -2.13477393e+03 -2.16767017e+03 -2.19965552e+03 -2.35855298e+03 -2.39152466e+03 -2.37078369e+03 -2.41035425e+03 -2.44122876e+03 -2.56362012e+03 -2.61753198e+03 -2.54883130e+03 -2.59040088e+03 -2.75960352e+03 -2.80934082e+03 -2.72351270e+03 -2.74362646e+03 -2.94092480e+03 -3.00080029e+03 -2.94406201e+03 -2.91314771e+03 -2.96230933e+03 -3.18641968e+03 -3.19561865e+03 -3.14950098e+03 -3.20029688e+03 -3.22210815e+03 -3.28819385e+03 -3.31708911e+03 -3.35300171e+03 -3.30557959e+03 -3.44553687e+03 -3.68607959e+03 -3.61069458e+03 -3.59778418e+03 -3.66162378e+03 -3.67333398e+03 -3.72426001e+03 -3.75533618e+03 -3.78317529e+03 -3.72240576e+03 -3.71145044e+03 -3.84591309e+03 -3.97305737e+03 -4.14133838e+03 -4.03934863e+03 -3.93433203e+03 -4.09279663e+03 -4.16755029e+03 -4.31406738e+03 -4.30100928e+03 -4.21459912e+03 -4.21106104e+03 -4.22888721e+03 -4.36814355e+03 -4.41142041e+03 -4.53455566e+03 -4.56093701e+03 -4.50656738e+03 -4.47098193e+03 -4.37574365e+03 -4.59362207e+03 -4.90661768e+03 -4.83744727e+03 -4.71584961e+03 -4.62916211e+03 -4.60201807e+03 -4.88409668e+03 -5.07435693e+03 -4.94728174e+03 -4.78112793e+03 -4.81583691e+03 -4.99189648e+03 -5.02196338e+03 -5.18821973e+03 -5.18183252e+03 -5.06640430e+03 -5.13154980e+03 -5.14404248e+03 -5.29063428e+03 -5.32388672e+03 -5.13235938e+03 -5.17059277e+03 -5.49264453e+03 -5.42112451e+03 -5.15789502e+03 -5.36812646e+03 -5.68658154e+03 -5.61843115e+03 -5.49413232e+03 -5.37797607e+03 -5.43499268e+03 -5.77198828e+03 -5.78494629e+03 -5.64728516e+03 -5.52467676e+03 -5.52592627e+03 -5.74638574e+03 -5.75017627e+03 -5.76778955e+03 -5.66141162e+03 -5.80650928e+03 -6.07335693e+03 -5.92834180e+03 -6.00832178e+03 -5.99285254e+03 -5.88338037e+03 -5.95112646e+03 -6.01708203e+03 -6.05158789e+03 -6.02298193e+03 -5.98594336e+03 -5.90490967e+03 -6.08957520e+03 -6.43366455e+03 -6.15160840e+03 -5.90539209e+03 -6.13125098e+03 -6.26880908e+03 -6.46124561e+03 -6.35422021e+03 -6.22016846e+03 -6.36942920e+03 -6.37384912e+03 -6.13053369e+03 -6.11560156e+03 -6.54530078e+03 -6.55549609e+03 -6.33440088e+03 -6.28755273e+03 -6.10510547e+03 -6.40754199e+03 -6.84635986e+03 -6.65146387e+03 -6.49493457e+03 -6.32795752e+03 -6.26800244e+03 -6.60830469e+03 -6.87997705e+03 -6.70650195e+03 -6.40290381e+03 -6.37615186e+03 -6.56367529e+03 -6.63167480e+03 -6.84939941e+03 -6.73805029e+03 -6.51025439e+03 -6.66384717e+03 -6.68931836e+03 -6.78580371e+03 -6.77254248e+03 -6.63780957e+03 -6.71276562e+03 -6.71857031e+03 -6.70882080e+03 -6.53513037e+03 -6.62774951e+03 -7.05655762e+03 -6.94942822e+03 -6.69363379e+03 -6.53718799e+03 -6.63171875e+03 -7.00502148e+03 -7.02346045e+03 -6.82972070e+03 -6.64149121e+03 -6.60381543e+03 -6.79263672e+03 -6.83104639e+03 -6.87112012e+03 -6.68562158e+03 -6.80934912e+03 -7.07619482e+03 -6.87742188e+03 -6.96455029e+03 -6.95719922e+03 -6.78273779e+03 -6.81537256e+03 -6.77481934e+03 -6.77918945e+03 -6.81172168e+03 -6.81171680e+03 -6.78561230e+03 -6.96096094e+03 -6.95875391e+03 -6.68483203e+03 -6.58618750e+03 -6.76929639e+03 -6.92449902e+03 -7.12894189e+03 -6.91733691e+03 -6.58249170e+03 -6.91200195e+03 -7.03083691e+03 -6.85265381e+03 -6.67707471e+03 -6.64514258e+03 -6.78757666e+03 -6.77573584e+03 -6.77497363e+03 -6.53761914e+03 -6.75940674e+03 -7.05294141e+03 -6.88100146e+03 -6.78958838e+03 -6.64392383e+03 -6.55292383e+03 -6.88558203e+03 -6.93395166e+03 -6.69092725e+03 -6.52192383e+03 -6.38779688e+03 -6.56318750e+03 -6.79392432e+03 -6.97987744e+03 -6.64741211e+03 -6.36277148e+03 -6.56712207e+03 -6.63915283e+03 -6.81800684e+03 -6.67059668e+03 -6.39750830e+03 -6.57772949e+03 -6.59854346e+03 -6.42269385e+03 -6.28487061e+03 -6.45865381e+03 -6.76866064e+03 -6.59714453e+03 -6.47720166e+03 -6.27068848e+03 -6.25066943e+03 -6.60270312e+03 -6.56144238e+03 -6.34555420e+03 -6.17776025e+03 -6.12153418e+03 -6.28558887e+03 -6.26639258e+03 -6.41362988e+03 -6.42788477e+03 -6.18831250e+03 -6.06634082e+03 -6.13851904e+03 -6.35358594e+03 -6.21527686e+03 -6.05517773e+03 -6.10987109e+03 -6.09906250e+03 -5.96477686e+03 -5.86826416e+03 -6.09410791e+03 -6.04534814e+03 -5.88314404e+03 -6.08876367e+03 -6.08376807e+03 -5.94632520e+03 -5.88973389e+03 -5.86510840e+03 -5.82995020e+03 -5.65876172e+03 -5.58832129e+03 -5.81895166e+03 -5.91341357e+03 -5.58114062e+03 -5.36203955e+03 -5.60586182e+03 -5.89906543e+03 -5.79172070e+03 -5.47611621e+03 -5.34811133e+03 -5.58757910e+03 -5.64259717e+03 -5.45030029e+03 -5.46695215e+03 -5.29233154e+03 -5.11064648e+03 -5.27249561e+03 -5.47736719e+03 -5.46216016e+03 -5.16697461e+03 -4.98511084e+03 -5.24959131e+03 -5.38593262e+03 -5.17052051e+03 -4.94557227e+03 -4.85065381e+03 -4.96647656e+03 -4.98042529e+03 -5.06523340e+03 -5.02779785e+03 -4.81077148e+03 -4.82431104e+03 -4.84045068e+03 -4.87098779e+03 -4.72011523e+03 -4.58469629e+03 -4.74034570e+03 -4.70568066e+03 -4.61033643e+03 -4.45999365e+03 -4.48538525e+03 -4.69254004e+03 -4.48335645e+03 -4.28056543e+03 -4.33453320e+03 -4.38202246e+03 -4.37334180e+03 -4.29353613e+03 -4.34103711e+03 -4.33830518e+03 -4.17634180e+03 -4.01744971e+03 -3.99641138e+03 -4.15285986e+03 -4.02297900e+03 -3.88570557e+03 -3.97205273e+03 -3.95155298e+03 -3.84339771e+03 -3.75826660e+03 -3.84215381e+03 -3.78732349e+03 -3.63436768e+03 -3.68639624e+03 -3.65508740e+03 -3.65254297e+03 -3.60836060e+03 -3.50631592e+03 -3.43957617e+03 -3.30865527e+03 -3.24745190e+03 -3.38612207e+03 -3.46429199e+03 -3.24006250e+03 -3.04174438e+03 -3.12227466e+03 -3.26970898e+03 -3.21467505e+03 -3.00530200e+03 -2.86339185e+03 -2.96238599e+03 -2.99853442e+03 -2.87108130e+03 -2.87363867e+03 -2.80955884e+03 -2.66605273e+03 -2.65099707e+03 -2.70169287e+03 -2.66702026e+03 -2.51949219e+03 -2.41872461e+03 -2.48482593e+03 -2.53612573e+03 -2.42343237e+03 -2.27518115e+03 -2.20866943e+03 -2.27276245e+03 -2.28053564e+03 -2.16832422e+03 -2.07840112e+03 -2.03936255e+03 -2.02487158e+03 -1.97238098e+03 -1.98169067e+03 -1.89681323e+03 -1.78531738e+03 -1.80604797e+03 -1.77092297e+03 -1.72594275e+03 -1.64602014e+03 -1.57287280e+03 -1.58530005e+03 -1.50196301e+03 -1.43696924e+03 -1.49216797e+03 -1.43482166e+03 -1.33167102e+03 -1.74361792e+03 -1.86776147e+03 -1.86552222e+03 -1.82656152e+03 -1.72866541e+03 -1.37216797e+03 -1.37789258e+03 -1.35919092e+03 -1.12098840e+03 -8.74695557e+02 -1.01579028e+03 -1.32305225e+03 -5.27330762e+03 -115786944. 0. 0. 0. 0. 0. 0. -219605696. -219605696. -1.33163477e+03 -3.50749146e+03 -3.50749146e+03 833382336. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 391148160. 1.60673500e+05 -1.16610180e+05 2.09380835e+03 1.74053174e+03 1.25825330e+03 8.53561523e+02 1.15941907e+03 1.03147229e+03 1.00982758e+03 1.03317700e+03 1.08781299e+03 1.17193530e+03 1.22777417e+03 1.22816260e+03 1.25579700e+03 1.33548730e+03 1.38869226e+03 1.41968054e+03 1.46819202e+03 1.51021790e+03 1.54913843e+03 1.62810950e+03 1.67673926e+03 1.66632422e+03 1.72188586e+03 1.82705798e+03 1.88174658e+03 1.91639417e+03 1.91820618e+03 1.93059717e+03 2.02592493e+03 2.09570605e+03 2.11656104e+03 2.13878540e+03 2.17774927e+03 2.26936035e+03 2.31800537e+03 2.33411084e+03 2.35964526e+03 2.40125391e+03 2.54166919e+03 2.60140649e+03 2.50965918e+03 2.53542261e+03 2.64930469e+03 2.70075220e+03 2.77671289e+03 2.80913354e+03 2.78760059e+03 2.87744678e+03 2.94176074e+03 2.96196118e+03 3.00884424e+03 3.01274927e+03 3.07887524e+03 3.15440137e+03 3.16119238e+03 3.19114868e+03 3.21799048e+03 3.27555249e+03 3.38470508e+03 3.43355908e+03 3.43883960e+03 3.42156030e+03 3.44016504e+03 3.57903955e+03 3.63286011e+03 3.56617310e+03 3.64236353e+03 3.70378320e+03 3.75563013e+03 3.88240161e+03 3.87846655e+03 3.79089990e+03 3.83982104e+03 4.00623975e+03 4.08436035e+03 3.97699243e+03 3.94369312e+03 4.07212549e+03 4.14887500e+03 4.26839844e+03 4.28750488e+03 4.17833398e+03 4.25760791e+03 4.39835107e+03 4.40761035e+03 4.39221973e+03 4.35216797e+03 4.38094580e+03 4.57582422e+03 4.62907666e+03 4.53950977e+03 4.60310840e+03 4.66361523e+03 4.67536670e+03 4.70050098e+03 4.73866504e+03 4.83165381e+03 4.83015039e+03 4.92360889e+03 4.96793604e+03 4.82461084e+03 4.87480566e+03 5.02052393e+03 5.02500146e+03 5.01521631e+03 5.05718311e+03 5.11347510e+03 5.21515088e+03 5.21037158e+03 5.18066016e+03 5.29106152e+03 5.35668896e+03 5.27478613e+03 5.28910498e+03 5.35091650e+03 5.41348975e+03 5.43463037e+03 5.37715918e+03 5.40956787e+03 5.51180762e+03 5.66510449e+03 5.65185791e+03 5.46487305e+03 5.57019238e+03 5.73540332e+03 5.71186670e+03 5.71517383e+03 5.65318115e+03 5.63588672e+03 5.78823926e+03 5.94804248e+03 5.89311914e+03 5.75465918e+03 5.79314697e+03 5.99424854e+03 6.01824951e+03 6.05774609e+03 5.96409277e+03 5.85661816e+03 5.96278662e+03 6.00878369e+03 6.03355469e+03 6.08108838e+03 6.05024316e+03 6.13428564e+03 6.32968457e+03 6.22805127e+03 6.02358984e+03 6.11271631e+03 6.27801611e+03 6.28433496e+03 6.38667236e+03 6.33027002e+03 6.17804541e+03 6.29098389e+03 6.48952881e+03 6.42652002e+03 6.15454932e+03 6.28594482e+03 6.50011963e+03 6.48419922e+03 6.43437891e+03 6.35943262e+03 6.34512207e+03 6.47906055e+03 6.50218701e+03 6.53779932e+03 6.59318164e+03 6.43993555e+03 6.56618408e+03 6.70456104e+03 6.59764404e+03 6.46861914e+03 6.55081885e+03 6.67207178e+03 6.72309180e+03 6.67828564e+03 6.55296191e+03 6.48813672e+03 6.63358691e+03 6.92359961e+03 6.93957324e+03 6.53923047e+03 6.56158740e+03 6.83542041e+03 6.79715771e+03 6.75045752e+03 6.68293164e+03 6.59248096e+03 6.77910010e+03 6.91989355e+03 6.82926025e+03 6.68925684e+03 6.67209521e+03 6.75153906e+03 6.89743555e+03 6.96185498e+03 6.82770068e+03 6.75225781e+03 6.82688867e+03 6.84009424e+03 6.82211670e+03 6.79291309e+03 6.81152832e+03 6.74155420e+03 6.92741113e+03 7.03817432e+03 6.66240820e+03 6.69848340e+03 6.94192969e+03 6.88376855e+03 6.89528223e+03 6.72032324e+03 6.75633594e+03 7.00218018e+03 6.90565039e+03 6.82191602e+03 6.70502344e+03 6.64686426e+03 6.82365479e+03 6.97526514e+03 6.83967188e+03 6.77952930e+03 6.90580811e+03 6.82107666e+03 6.93420605e+03 6.88848535e+03 6.66705957e+03 6.65713770e+03 6.67289307e+03 6.88525293e+03 6.82946924e+03 6.67807373e+03 6.71531006e+03 6.82097998e+03 6.81184473e+03 6.73030957e+03 6.70234521e+03 6.70166748e+03 6.74074707e+03 6.68237988e+03 6.79974512e+03 6.68732178e+03 6.54329248e+03 6.74180127e+03 6.55732080e+03 6.58666650e+03 6.71931836e+03 6.54983545e+03 6.55229883e+03 6.58906689e+03 6.55570801e+03 6.50884229e+03 6.40255078e+03 6.63981738e+03 6.76710059e+03 6.38633936e+03 6.36718701e+03 6.44539062e+03 6.43913916e+03 6.55143408e+03 6.47428516e+03 6.30373096e+03 6.31349072e+03 6.43413330e+03 6.43063623e+03 6.35486035e+03 6.21968799e+03 6.25079639e+03 6.28700098e+03 6.20891260e+03 6.19827051e+03 6.13430859e+03 6.10804834e+03 6.17019092e+03 6.23617920e+03 6.19896436e+03 6.06070264e+03 5.98786768e+03 6.11919678e+03 6.20861670e+03 5.99556738e+03 6.03229199e+03 5.99722363e+03 5.78688721e+03 5.95052393e+03 5.93385986e+03 5.79334717e+03 5.86101465e+03 5.85328320e+03 5.78014258e+03 5.87732959e+03 5.74591406e+03 5.67033398e+03 5.68787891e+03 5.70989893e+03 5.70508350e+03 5.55159570e+03 5.49349951e+03 5.56496094e+03 5.60212207e+03 5.56308203e+03 5.46852393e+03 5.36767773e+03 5.47605566e+03 5.58352393e+03 5.39164893e+03 5.25036182e+03 5.22621436e+03 5.32541162e+03 5.35439844e+03 5.18787842e+03 5.11734570e+03 5.13521338e+03 5.13481836e+03 5.08257910e+03 5.10594727e+03 5.04306201e+03 4.87169873e+03 4.97414014e+03 5.07827832e+03 4.90841455e+03 4.70106006e+03 4.72456641e+03 4.79825342e+03 4.81740967e+03 4.76151953e+03 4.65646826e+03 4.59874268e+03 4.67191064e+03 4.72110693e+03 4.55018262e+03 4.45192334e+03 4.45580811e+03 4.54114404e+03 4.46606738e+03 4.27066309e+03 4.23504102e+03 4.26662646e+03 4.24790771e+03 4.25096631e+03 4.23079248e+03 4.12529883e+03 4.10172949e+03 4.06668311e+03 3.95361450e+03 3.92843091e+03 3.89015308e+03 3.92300806e+03 3.93015308e+03 3.81051953e+03 3.70774561e+03 3.70688965e+03 3.76053687e+03 3.81239551e+03 3.70664136e+03 3.50954370e+03 3.50437646e+03 3.52601392e+03 3.45282104e+03 3.38554053e+03 3.36570459e+03 3.34066724e+03 3.30418945e+03 3.23732715e+03 3.13578003e+03 3.15035034e+03 3.17475537e+03 3.14687793e+03 3.06454614e+03 2.94027026e+03 2.92831396e+03 2.88965430e+03 2.81774780e+03 2.86621094e+03 2.81951611e+03 2.69012476e+03 2.65539233e+03 2.62791064e+03 2.66147778e+03 2.62267456e+03 2.51564697e+03 2.46528467e+03 2.42306689e+03 2.36761328e+03 2.30170142e+03 2.29551880e+03 2.25624219e+03 2.22770825e+03 2.18650464e+03 2.05559302e+03 2.03401917e+03 2.01329651e+03 1.97197363e+03 1.98274194e+03 1.87461475e+03 1.78334497e+03 1.81158289e+03 1.79117175e+03 1.70840515e+03 1.64681067e+03 1.57772070e+03 1.52770227e+03 1.49621130e+03 1.46758411e+03 1.41470752e+03 1.38506946e+03 1.35943433e+03 1.28459900e+03 1.21969714e+03 1.16707471e+03 1.13809644e+03 1.11182434e+03 1.04691907e+03 9.77832214e+02 9.32192078e+02 8.97329468e+02 8.66537048e+02 8.36075989e+02 7.64545471e+02 6.98771790e+02 6.64333191e+02 6.11337158e+02 5.62512451e+02 5.32088562e+02 4.81578888e+02 4.23666626e+02 3.79745422e+02 3.30008148e+02 2.83843658e+02 2.43030151e+02 1.94160965e+02 1.41521271e+02 9.13286133e+01 4.44989433e+01 -1.68217468e+00 -4.93836517e+01 -9.95679092e+01 -1.47841431e+02 -1.96019943e+02 -2.40218155e+02 -2.90626038e+02 -3.39197205e+02 -3.83341827e+02 -4.35203827e+02 -4.81133667e+02 -5.23367310e+02 -5.73807007e+02 -6.21247192e+02 -6.81209778e+02 -7.31948975e+02 -7.62898254e+02 -8.04724609e+02 -8.47812683e+02 -9.00201294e+02 -9.48530212e+02 -1.00595294e+03 -1.06477271e+03 -1.09631067e+03 -1.13760156e+03 -1.17808093e+03 -1.23840649e+03 -1.31471753e+03 -1.34801416e+03 -1.37162427e+03 -1.41228748e+03 -1.45985461e+03 -1.50374475e+03 -1.57131812e+03 -1.63220264e+03 -1.66501746e+03 -1.70386011e+03 -1.73742053e+03 -1.78420825e+03 -1.85257007e+03 -1.88957935e+03 -1.94933740e+03 -1.99285388e+03 -2.00615613e+03 -2.09996680e+03 -2.10321533e+03 -2.11700635e+03 -2.24230005e+03 -2.26793335e+03 -2.27603296e+03 -2.34744482e+03 -2.37110986e+03 -2.39784131e+03 -2.54750781e+03 -2.59300220e+03 -2.50746338e+03 -2.57923901e+03 -2.66089600e+03 -2.67018311e+03 -2.77247144e+03 -2.80159399e+03 -2.77027759e+03 -2.85050000e+03 -2.89510645e+03 -2.99043921e+03 -3.07241113e+03 -3.05599536e+03 -3.12190454e+03 -3.10785498e+03 -3.06762085e+03 -3.17991260e+03 -3.31681885e+03 -3.31736035e+03 -3.36530493e+03 -3.39313086e+03 -3.31907129e+03 -3.42139282e+03 -3.62822314e+03 -3.62764990e+03 -3.56595312e+03 -3.55098706e+03 -3.58716235e+03 -3.75577124e+03 -3.82509692e+03 -3.77469409e+03 -3.86035938e+03 -3.85894604e+03 -3.90893384e+03 -3.98084229e+03 -3.88015039e+03 -3.96271753e+03 -4.13227490e+03 -4.19436475e+03 -4.14601318e+03 -4.07818921e+03 -4.12422119e+03 -4.26009277e+03 -4.37951807e+03 -4.38870117e+03 -4.30401807e+03 -4.28409033e+03 -4.43189551e+03 -4.53921240e+03 -4.63921875e+03 -4.60320361e+03 -4.50301318e+03 -4.61718896e+03 -4.62392432e+03 -4.63156201e+03 -4.74959814e+03 -4.75507617e+03 -4.78497607e+03 -4.92118799e+03 -4.85886035e+03 -4.84331494e+03 -4.93889355e+03 -4.98049512e+03 -5.05707617e+03 -5.00212842e+03 -4.96218750e+03 -5.02044580e+03 -5.14806445e+03 -5.26586377e+03 -5.29915576e+03 -5.23774121e+03 -5.14711523e+03 -5.21641406e+03 -5.25870605e+03 -5.33958643e+03 -5.43396826e+03 -5.37497119e+03 -5.36960303e+03 -5.40504346e+03 -5.43929248e+03 -5.55320850e+03 -5.72263232e+03 -5.65662256e+03 -5.54636621e+03 -5.56266455e+03 -5.48800635e+03 -5.58899316e+03 -5.77626953e+03 -5.84868604e+03 -5.81806836e+03 -5.70164990e+03 -5.70494971e+03 -5.78203906e+03 -5.90260889e+03 -5.92443652e+03 -5.95592383e+03 -5.92233740e+03 -5.82366016e+03 -5.97364209e+03 -6.15277100e+03 -6.12096338e+03 -5.93042090e+03 -6.02361670e+03 -6.08652783e+03 -6.14437598e+03 -6.18454639e+03 -6.16384863e+03 -6.24680469e+03 -6.16804688e+03 -6.11283105e+03 -6.31083252e+03 -6.29914600e+03 -6.28933203e+03 -6.38387646e+03 -6.23685156e+03 -6.19099316e+03 -6.39335254e+03 -6.39712744e+03 -6.45508838e+03 -6.68471533e+03 -6.64274805e+03 -6.44525439e+03 -6.31905225e+03 -6.44986084e+03 -6.81421045e+03 -8.45103809e+03 -8.21455078e+03 -1.64016699e+04 -1.70681152e+04 -2.72666625e+06 72470784. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -181644528. -4717116. -2.69870801e+04 -1.47211025e+04 -7.33157178e+03 -9.31232715e+03 -1.08827061e+04 -9.48917871e+03 -7.75185645e+03 -7.37528125e+03 -6.81142480e+03 -6.79946191e+03 -7.03434082e+03 -6.90576465e+03 -6.81674219e+03 -6.67664648e+03 -6.64706787e+03 -6.93127979e+03 -7.08086035e+03 -6.81889209e+03 -6.61614307e+03 -6.66987939e+03 -6.77203711e+03 -6.88383789e+03 -6.95888086e+03 -6.70600049e+03 -6.59131738e+03 -6.68188428e+03 -6.71362549e+03 -6.70168555e+03 -6.59464355e+03 -6.55793750e+03 -6.79898877e+03 -6.92048730e+03 -6.76029688e+03 -6.43122217e+03 -6.41069922e+03 -6.68077539e+03 -6.73116553e+03 -6.58882959e+03 -6.39146777e+03 -6.44439258e+03 -6.72629443e+03 -6.82349072e+03 -6.63076758e+03 -6.26047119e+03 -6.35064502e+03 -6.64897900e+03 -6.58578320e+03 -6.55816602e+03 -6.40937158e+03 -6.21253320e+03 -6.31968506e+03 -6.53432861e+03 -6.37757080e+03 -6.23848535e+03 -6.44616699e+03 -6.45132227e+03 -6.34745264e+03 -6.26603174e+03 -6.02233643e+03 -6.18126758e+03 -6.48567041e+03 -6.30705518e+03 -6.07690918e+03 -5.99681348e+03 -5.96460400e+03 -6.22566602e+03 -6.39803027e+03 -6.15957861e+03 -5.96157422e+03 -5.90397607e+03 -5.87517139e+03 -6.01070068e+03 -6.16517578e+03 -5.94270996e+03 -5.78182861e+03 -5.93198975e+03 -5.89053711e+03 -5.74861719e+03 -5.72804492e+03 -5.81735254e+03 -5.90236768e+03 -5.83047070e+03 -5.77718457e+03 -5.60268066e+03 -5.44362988e+03 -5.71941553e+03 -5.89520947e+03 -5.54881055e+03 -5.33451904e+03 -5.41643115e+03 -5.55147998e+03 -5.60541260e+03 -5.62213232e+03 -5.39100439e+03 -5.27075684e+03 -5.37971826e+03 -5.35287305e+03 -5.36183057e+03 -5.28314258e+03 -5.11086914e+03 -5.12098877e+03 -5.23015186e+03 -5.20001367e+03 -5.14465283e+03 -5.14065332e+03 -5.09357666e+03 -5.01925781e+03 -5.00398340e+03 -4.85573633e+03 -4.78802490e+03 -5.01867920e+03 -5.03013184e+03 -4.73022559e+03 -4.59015234e+03 -4.64908203e+03 -4.84598291e+03 -4.89200098e+03 -4.69315820e+03 -4.50316699e+03 -4.46022314e+03 -4.49440625e+03 -4.53004785e+03 -4.50839453e+03 -4.44265088e+03 -4.39909473e+03 -4.34565967e+03 -4.31478223e+03 -4.29687988e+03 -4.16746191e+03 -4.19414844e+03 -4.32362549e+03 -4.18404004e+03 -4.05565723e+03 -4.00473486e+03 -3.91252368e+03 -4.04198804e+03 -4.09090991e+03 -3.86930225e+03 -3.74271533e+03 -3.76351636e+03 -3.89357324e+03 -3.91479419e+03 -3.73891431e+03 -3.58802686e+03 -3.54164917e+03 -3.54371704e+03 -3.59191553e+03 -3.58250293e+03 -3.41576172e+03 -3.29662842e+03 -3.36690503e+03 -3.43236572e+03 -3.35259448e+03 -3.22937817e+03 -3.20208398e+03 -3.17939429e+03 -3.13954419e+03 -3.12591431e+03 -2.97452734e+03 -2.92658154e+03 -3.00465942e+03 -2.95248608e+03 -2.86595215e+03 -2.78321240e+03 -2.74480029e+03 -2.73431396e+03 -2.72004297e+03 -2.69734473e+03 -2.58226416e+03 -2.54568970e+03 -2.56524780e+03 -2.49038501e+03 -2.40811743e+03 -2.35502661e+03 -2.31212036e+03 -2.31492603e+03 -2.33034937e+03 -2.23934692e+03 -2.09723047e+03 -2.04720435e+03 -2.09214648e+03 -2.09687061e+03 -2.01367053e+03 -1.87538062e+03 -1.83137805e+03 -1.83744727e+03 -1.81836987e+03 -1.77777588e+03 -1.67924097e+03 -1.61412781e+03 -1.58898108e+03 -1.57129614e+03 -1.54623315e+03 -1.47612598e+03 -1.41132776e+03 -1.36846631e+03 -1.32480627e+03 -1.28815308e+03 -1.24077124e+03 -1.19345251e+03 -1.13597705e+03 -1.07815088e+03 -1.02014050e+03 -9.69876404e+02 -9.57751953e+02 -9.45349243e+02 -8.82689697e+02 -7.96655945e+02 -7.26368652e+02 -6.90928284e+02 -6.84640198e+02 -6.53085327e+02 -5.83547791e+02 -5.12411560e+02 -4.55242065e+02 -4.21132141e+02 -3.87451904e+02 -3.38868011e+02 -2.88923035e+02 -2.39277115e+02 -1.88294098e+02 -1.40849930e+02 -9.27668076e+01 -4.71017075e+01 -6.32442474e-01 4.83511658e+01 9.95668869e+01 1.49632034e+02 1.86421967e+02 2.34419769e+02 2.91312256e+02 3.39272949e+02 3.87373474e+02 4.31637634e+02 4.90706665e+02 5.39602722e+02 5.63265991e+02 5.92773438e+02 6.50653931e+02 7.32154602e+02 8.03707520e+02 8.38142334e+02 8.42229675e+02 8.65313354e+02 9.20387817e+02 1.01643005e+03 1.10380042e+03 1.13099841e+03 1.11198193e+03 1.14718079e+03 1.27888733e+03 1.31250208e+03 1.30392847e+03 1.36263196e+03 1.41449329e+03 1.46159045e+03 1.55998145e+03 1.57685571e+03 1.56178088e+03 1.64878015e+03 1.66650488e+03 1.74664050e+03 1.83996948e+03 1.80172363e+03 1.88454102e+03 1.98182666e+03 1.98293579e+03 2.02704504e+03 2.05934717e+03 2.13635938e+03 2.18054761e+03 2.17167212e+03 2.18183105e+03 2.24582227e+03 2.41081396e+03 2.51165381e+03 2.48367725e+03 2.42314893e+03 2.41326074e+03 2.50293018e+03 2.65770728e+03 2.78567871e+03 2.75911304e+03 2.64937915e+03 2.72361060e+03 2.87373535e+03 2.87531519e+03 2.90758911e+03 2.96173340e+03 2.95549487e+03 3.02734155e+03 3.20507764e+03 3.14010278e+03 3.09907104e+03 3.20856812e+03 3.15164355e+03 3.30405859e+03 3.46522778e+03 3.35443311e+03 3.48747827e+03 3.49302246e+03 3.38956934e+03 3.53923022e+03 3.49151343e+03 3.61379980e+03 3.90161084e+03 3.72207520e+03 3.57596167e+03 3.68637134e+03 3.89722412e+03 4.07229883e+03 4.05214062e+03 3.86104956e+03 3.79425195e+03 3.92248511e+03 4.09502783e+03 4.31174512e+03 4.27191406e+03 4.07476318e+03 4.11323047e+03 4.26190137e+03 4.37425488e+03 4.28783496e+03 4.28060107e+03 4.37407568e+03 4.41338721e+03 4.60610498e+03 4.66131396e+03 4.45854736e+03 4.44015771e+03 4.57828369e+03 4.63586768e+03 4.71613477e+03 4.71494775e+03 4.88284229e+03 4.82211523e+03 4.66353809e+03 4.84162500e+03 4.75490625e+03 4.89720215e+03 5.26057129e+03 5.02037598e+03 4.74103076e+03 4.89256348e+03 5.19537451e+03 5.34921533e+03 5.34897266e+03 5.10938232e+03 4.97775977e+03 5.11273096e+03 5.32870996e+03 5.59969336e+03 5.48892627e+03 5.18671729e+03 5.19591895e+03 5.42065576e+03 5.50318359e+03 5.66248877e+03 5.71136768e+03 5.38480957e+03 5.39613477e+03 5.64325977e+03 5.72662061e+03 5.63445850e+03 5.63780566e+03 5.67268213e+03 5.60636816e+03 5.92601611e+03 5.94792969e+03 5.69525244e+03 5.71573340e+03 5.79814209e+03 5.83920996e+03 5.87965088e+03 5.89717041e+03 6.08299219e+03 6.15563818e+03 6.00020752e+03 5.88986621e+03 5.78181055e+03 6.05786426e+03 6.37990869e+03 6.27504736e+03 5.97012158e+03 5.87594629e+03 6.09159131e+03 6.43233203e+03 6.28581592e+03 5.94597412e+03 6.11195312e+03 6.34451611e+03 6.38847852e+03 6.64504736e+03 6.53557422e+03 6.16802881e+03 6.07105664e+03 6.27551270e+03 6.51588037e+03 6.55577881e+03 6.44606055e+03 6.43711182e+03 6.44269824e+03 6.58087158e+03 6.52780859e+03 6.39618652e+03 6.43913184e+03 6.35619678e+03 6.62685938e+03 6.82296973e+03 6.57229150e+03 6.62228564e+03 6.67464648e+03 6.67825244e+03 6.51973340e+03 6.41759912e+03 6.68261621e+03 6.97594629e+03 6.78529736e+03 6.48065088e+03 6.54269238e+03 6.85719238e+03 6.95437744e+03 6.84099951e+03 6.78811963e+03 6.55273828e+03 6.54917090e+03 6.84934473e+03 6.88176270e+03 6.74648828e+03 6.60530322e+03 6.52474414e+03 6.85690137e+03 7.12741992e+03 6.81172803e+03 6.64242969e+03 6.82810156e+03 6.75948633e+03 7.02145850e+03 7.03685303e+03 6.68754443e+03 6.58982324e+03 6.78808057e+03 6.82309521e+03 6.88912402e+03 6.82315039e+03 7.00219482e+03 7.13820410e+03 7.06363184e+03 7.31520264e+03 7.85027100e+03 7.25496582e+03 1.08961064e+04 1.03265195e+04 1.56588018e+04 2.18159062e+04 5619526. 2.75342275e+06 2.75369775e+06 -5.51757950e+06 9313138. 1.02738431e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 28241116. 2.45838250e+06 2.74274414e+04 1.73062715e+04 1.13054805e+04 9.22666016e+03 8.39049805e+03 6.85155420e+03 6.69844385e+03 6.40760938e+03 6.17881055e+03 6.32258887e+03 6.30294678e+03 6.18604736e+03 6.21631836e+03 6.16689209e+03 6.12869629e+03 6.10838525e+03 6.09164893e+03 6.03528125e+03 5.96188965e+03 5.92147852e+03 6.08006738e+03 6.09906445e+03 5.77908301e+03 5.75262695e+03 6.06052734e+03 6.06560400e+03 5.87717822e+03 5.82660156e+03 5.82780176e+03 5.78416211e+03 5.69865381e+03 5.74402197e+03 5.71050342e+03 5.63287061e+03 5.51766211e+03 5.49409180e+03 5.70600928e+03 5.71368652e+03 5.50368896e+03 5.48810645e+03 5.48597949e+03 5.46927930e+03 5.39253711e+03 5.34961670e+03 5.36707275e+03 5.27598584e+03 5.20232715e+03 5.19774023e+03 5.15020312e+03 5.35997900e+03 5.35675635e+03 5.13180029e+03 4.96559473e+03 4.91469482e+03 5.18931201e+03 5.19206445e+03 4.97694482e+03 4.86529932e+03 4.85475586e+03 4.88948535e+03 4.80283496e+03 4.93124658e+03 4.89299463e+03 4.59102686e+03 4.51638770e+03 4.70879834e+03 4.86640723e+03 4.71269531e+03 4.56742871e+03 4.53653125e+03 4.48537451e+03 4.44555615e+03 4.40798828e+03 4.41744629e+03 4.37544531e+03 4.26945264e+03 4.23391260e+03 4.21831836e+03 4.16562598e+03 4.27367529e+03 4.21994043e+03 4.06597949e+03 4.01854346e+03 3.98881030e+03 4.05646289e+03 4.04235522e+03 3.89731055e+03 3.85394873e+03 3.75035864e+03 3.65098682e+03 3.79005371e+03 3.73162207e+03 3.50763892e+03 3.52649878e+03 3.67999512e+03 3.75384106e+03 3.60180811e+03 3.46297900e+03 3.37769653e+03 3.33144019e+03 3.31460815e+03 3.27693774e+03 3.24256714e+03 3.18751416e+03 3.22830396e+03 3.17780908e+03 3.05634497e+03 3.02675391e+03 2.89159814e+03 2.91701831e+03 3.05855713e+03 2.94783960e+03 2.82130176e+03 2.71230835e+03 2.65811816e+03 2.76329785e+03 2.72835986e+03 2.60618091e+03 2.50011987e+03 2.44402954e+03 2.45273950e+03 2.41965356e+03 2.45095728e+03 2.41930469e+03 2.29538940e+03 2.22103027e+03 2.18246997e+03 2.18383398e+03 2.14636084e+03 2.07441943e+03 1.99260449e+03 1.95171570e+03 1.92448059e+03 1.81749609e+03 1.81494055e+03 1.87690479e+03 1.79816931e+03 1.70732385e+03 1.60774438e+03 1.55419714e+03 1.60933167e+03 1.56213367e+03 1.46521936e+03 1.38750867e+03 1.33734424e+03 1.33332788e+03 1.27727319e+03 1.23096301e+03 1.16166248e+03 1.13188171e+03 1.14156250e+03 1.06893579e+03 1.00583789e+03 9.65814636e+02 9.11617615e+02 8.47467529e+02 8.01484009e+02 7.59006897e+02 7.07522888e+02 6.67848328e+02 6.03907715e+02 5.62780884e+02 5.49968079e+02 4.79246552e+02 4.14870026e+02 3.78252380e+02 3.31435028e+02 2.93301453e+02 2.42258667e+02 1.87353165e+02 1.45552429e+02 9.72902908e+01 4.70738068e+01 -8.29565942e-01 -4.84331589e+01 -9.49606934e+01 -1.41218979e+02 -1.89359039e+02 -2.32301773e+02 -2.86693054e+02 -3.52222778e+02 -3.94404633e+02 -4.27568176e+02 -4.58296875e+02 -5.11799316e+02 -5.94171692e+02 -6.39849854e+02 -6.68925415e+02 -7.00909180e+02 -7.40331055e+02 -8.07571289e+02 -8.59764221e+02 -9.26877991e+02 -9.65140747e+02 -9.84064331e+02 -1.03588269e+03 -1.08169714e+03 -1.16999207e+03 -1.21262903e+03 -1.22068616e+03 -1.27177673e+03 -1.32043188e+03 -1.36653699e+03 -1.37547156e+03 -1.46510352e+03 -1.60504456e+03 -1.60621362e+03 -1.60437195e+03 -1.61255359e+03 -1.64426013e+03 -1.79136304e+03 -1.85379419e+03 -1.84243689e+03 -1.84027344e+03 -1.88005042e+03 -1.98134192e+03 -2.02810107e+03 -2.12456665e+03 -2.16948364e+03 -2.16255786e+03 -2.14716235e+03 -2.18187109e+03 -2.36057300e+03 -2.39566553e+03 -2.37374902e+03 -2.38342896e+03 -2.40919946e+03 -2.59400366e+03 -2.65158130e+03 -2.53630371e+03 -2.57583374e+03 -2.76604761e+03 -2.81055688e+03 -2.71280591e+03 -2.75335571e+03 -2.93859546e+03 -2.99990625e+03 -2.94720190e+03 -2.91789648e+03 -2.96962402e+03 -3.17303369e+03 -3.17258203e+03 -3.11671411e+03 -3.20906787e+03 -3.24323535e+03 -3.28216504e+03 -3.32853101e+03 -3.36940942e+03 -3.31210400e+03 -3.43592285e+03 -3.64843091e+03 -3.58436011e+03 -3.64439648e+03 -3.70155347e+03 -3.67260742e+03 -3.71586011e+03 -3.75104565e+03 -3.77551929e+03 -3.73284204e+03 -3.76719189e+03 -3.88985156e+03 -3.93033032e+03 -4.10576611e+03 -4.03349414e+03 -3.92430859e+03 -4.08045825e+03 -4.15441406e+03 -4.32639697e+03 -4.30341895e+03 -4.20822461e+03 -4.20580518e+03 -4.23645996e+03 -4.35701465e+03 -4.38929492e+03 -4.53888330e+03 -4.55454834e+03 -4.48577100e+03 -4.50702490e+03 -4.40482324e+03 -4.56932275e+03 -4.87269385e+03 -4.85256104e+03 -4.72716602e+03 -4.62665869e+03 -4.59857080e+03 -4.86538525e+03 -5.06564600e+03 -4.96373682e+03 -4.78604736e+03 -4.82771826e+03 -4.99256494e+03 -5.01830322e+03 -5.16576465e+03 -5.18233008e+03 -5.06278760e+03 -5.09370459e+03 -5.12352051e+03 -5.32877295e+03 -5.38340625e+03 -5.12911914e+03 -5.14584326e+03 -5.47693115e+03 -5.46560889e+03 -5.20652100e+03 -5.32526465e+03 -5.61771631e+03 -5.62630615e+03 -5.54015137e+03 -5.40242578e+03 -5.40245850e+03 -5.73790967e+03 -5.78589355e+03 -5.65730811e+03 -5.53444434e+03 -5.50529150e+03 -5.70071826e+03 -5.77634229e+03 -5.79562695e+03 -5.64792041e+03 -5.79157080e+03 -6.07796143e+03 -5.95577783e+03 -6.00677734e+03 -5.97609229e+03 -5.88735791e+03 -5.95316992e+03 -5.99488965e+03 -6.06487891e+03 -6.04871240e+03 -5.95329980e+03 -5.85691064e+03 -6.06364111e+03 -6.39702246e+03 -6.08870312e+03 -5.89629834e+03 -6.12720312e+03 -6.29791016e+03 -6.52754443e+03 -6.36203174e+03 -6.18186865e+03 -6.35509668e+03 -6.41561230e+03 -6.22894385e+03 -6.16840186e+03 -6.46457861e+03 -6.45868506e+03 -6.30295410e+03 -6.34158008e+03 -6.14202197e+03 -6.40612549e+03 -6.81828418e+03 -6.66101611e+03 -6.49185547e+03 -6.32550049e+03 -6.26126709e+03 -6.60595068e+03 -6.89343506e+03 -6.69826221e+03 -6.42651416e+03 -6.46183740e+03 -6.54343994e+03 -6.53884229e+03 -6.77376416e+03 -6.71602148e+03 -6.53073389e+03 -6.60635596e+03 -6.61047217e+03 -6.82784521e+03 -6.87042480e+03 -6.62987549e+03 -6.66655859e+03 -6.70288232e+03 -6.76728027e+03 -6.64389990e+03 -6.63269043e+03 -6.90436914e+03 -6.86712256e+03 -6.80316455e+03 -6.61515137e+03 -6.63767871e+03 -7.05629834e+03 -7.01532715e+03 -6.81836865e+03 -6.67730225e+03 -6.61356250e+03 -6.69355615e+03 -6.73232373e+03 -6.84989746e+03 -6.70915332e+03 -6.77833984e+03 -7.02326855e+03 -6.80446533e+03 -6.98083936e+03 -7.03583301e+03 -6.83096973e+03 -6.80010986e+03 -6.81098828e+03 -6.81063281e+03 -6.85473926e+03 -6.78338330e+03 -6.77804150e+03 -6.96468799e+03 -6.97055225e+03 -6.64597314e+03 -6.62443994e+03 -6.75936670e+03 -6.87935840e+03 -7.13027588e+03 -6.93845361e+03 -6.61145459e+03 -6.85544678e+03 -6.99189404e+03 -6.80695508e+03 -6.78619482e+03 -6.75554443e+03 -6.67186719e+03 -6.68081787e+03 -6.83202539e+03 -6.65023193e+03 -6.70116797e+03 -7.04518262e+03 -6.86148340e+03 -6.75439941e+03 -6.63329932e+03 -6.57465283e+03 -6.88370020e+03 -6.87274512e+03 -6.70151318e+03 -6.52245947e+03 -6.35771875e+03 -6.55954688e+03 -6.77335254e+03 -6.95918994e+03 -6.71325684e+03 -6.49099512e+03 -6.48736133e+03 -6.55930713e+03 -6.79570312e+03 -6.73598730e+03 -6.49860791e+03 -6.46613818e+03 -6.43303613e+03 -6.52032666e+03 -6.38999854e+03 -6.43557764e+03 -6.71073242e+03 -6.58208447e+03 -6.47240527e+03 -6.30942188e+03 -6.24139160e+03 -6.60477441e+03 -6.57195215e+03 -6.33347070e+03 -6.20246191e+03 -6.16953955e+03 -6.27779395e+03 -6.23023682e+03 -6.45566699e+03 -6.48021533e+03 -6.20273047e+03 -6.03643506e+03 -6.07217139e+03 -6.41060596e+03 -6.30051807e+03 -6.10142236e+03 -6.02766260e+03 -6.00898926e+03 -5.98629688e+03 -5.92785742e+03 -6.06199902e+03 -5.99604590e+03 -5.86566309e+03 -6.05917578e+03 -6.10465137e+03 -5.94237451e+03 -5.90521338e+03 -5.82236768e+03 -5.82069385e+03 -5.65313818e+03 -5.58832812e+03 -5.82528027e+03 -5.88941309e+03 -5.58172559e+03 -5.41890039e+03 -5.65508838e+03 -5.84795605e+03 -5.76439600e+03 -5.49986670e+03 -5.33762646e+03 -5.53815283e+03 -5.61054883e+03 -5.45825439e+03 -5.46876416e+03 -5.27779053e+03 -5.06473975e+03 -5.23648535e+03 -5.54373486e+03 -5.49407812e+03 -5.14033057e+03 -4.97595557e+03 -5.24586719e+03 -5.38599072e+03 -5.18185498e+03 -4.96651270e+03 -4.87980469e+03 -4.92735742e+03 -4.95881543e+03 -5.08202637e+03 -5.07495508e+03 -4.88042920e+03 -4.76462988e+03 -4.73248145e+03 -4.89157080e+03 -4.75779736e+03 -4.60874023e+03 -4.77165967e+03 -4.72135938e+03 -4.62308350e+03 -4.47934229e+03 -4.43820312e+03 -4.65748779e+03 -4.48117676e+03 -4.27993115e+03 -4.36355713e+03 -4.38007129e+03 -4.37557129e+03 -4.29478320e+03 -4.34589502e+03 -4.32831641e+03 -4.18516504e+03 -4.01337231e+03 -3.98414966e+03 -4.16745752e+03 -4.05172217e+03 -3.91993970e+03 -3.91560571e+03 -3.86640723e+03 -3.89892407e+03 -3.83641748e+03 -3.81264819e+03 -3.76018384e+03 -3.63468652e+03 -3.70672095e+03 -3.68968286e+03 -3.62564941e+03 -3.57598242e+03 -3.50070288e+03 -3.43863110e+03 -3.30311450e+03 -3.24169580e+03 -3.39820190e+03 -3.47825488e+03 -3.23995703e+03 -3.06538062e+03 -3.15649756e+03 -3.25273633e+03 -3.17879102e+03 -3.00427222e+03 -2.89330664e+03 -2.99150488e+03 -2.95315332e+03 -2.82789575e+03 -2.90334985e+03 -2.82211597e+03 -2.63352832e+03 -2.63426538e+03 -2.72717676e+03 -2.69839893e+03 -2.52603882e+03 -2.41665405e+03 -2.49015283e+03 -2.54026733e+03 -2.42818457e+03 -2.27728857e+03 -2.20543774e+03 -2.27665967e+03 -2.25842017e+03 -2.14635669e+03 -2.12125049e+03 -2.08976196e+03 -2.00926526e+03 -1.94424048e+03 -1.97162524e+03 -1.89814673e+03 -1.79008545e+03 -1.80414404e+03 -1.77407288e+03 -1.73468689e+03 -1.64463550e+03 -1.56507275e+03 -1.58462854e+03 -1.50426697e+03 -1.43043347e+03 -1.48254309e+03 -1.43198352e+03 -1.39633997e+03 -1.66113928e+03 -1.49052258e+03 -1.74712634e+03 -1.83428809e+03 -1.87897437e+03 -1.32573071e+03 -1.36636646e+03 -1.97811353e+03 -2.16246167e+03 -6.29304750e+05 -2.64252625e+05 -1.97808844e+05 4.81136375e+05 951473920. 0. 0. 0. 0. 0. 0. -219605696. -219605696. -3.08545406e+05 -1175630720. -1175630720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 391148160. 1.60673500e+05 -1.16610180e+05 2.14819971e+03 2.01208521e+03 1.35746497e+03 1.21469116e+03 1.25843103e+03 1.07407800e+03 1.10970630e+03 1.10624097e+03 1.10194739e+03 1.14601843e+03 1.19075537e+03 1.24357703e+03 1.27400073e+03 1.30912866e+03 1.39066809e+03 1.43946252e+03 1.47682898e+03 1.52533118e+03 1.52500403e+03 1.57196045e+03 1.66210022e+03 1.69710278e+03 1.72166626e+03 1.81971875e+03 1.92083228e+03 1.90261206e+03 1.89973303e+03 1.94897839e+03 1.98050708e+03 2.07225806e+03 2.15669580e+03 2.16795410e+03 2.20718921e+03 2.29528491e+03 2.31157349e+03 2.30369116e+03 2.36072290e+03 2.40207861e+03 2.45953442e+03 2.57327686e+03 2.56679663e+03 2.57334912e+03 2.69239526e+03 2.69624316e+03 2.70135645e+03 2.75019751e+03 2.80138965e+03 2.88469897e+03 2.95151733e+03 3.01727271e+03 3.00938672e+03 3.00724048e+03 3.11281909e+03 3.10225098e+03 3.08288330e+03 3.22336597e+03 3.26689917e+03 3.28594800e+03 3.38861133e+03 3.42377759e+03 3.39356787e+03 3.43783643e+03 3.47954688e+03 3.48509204e+03 3.57155884e+03 3.63840161e+03 3.70142383e+03 3.75079102e+03 3.73535132e+03 3.78272485e+03 3.81103149e+03 3.86836255e+03 3.90163818e+03 3.95206934e+03 4.11590967e+03 4.03976978e+03 3.92710205e+03 4.09847656e+03 4.13310010e+03 4.11615039e+03 4.25096436e+03 4.25533887e+03 4.26976465e+03 4.41358936e+03 4.47898340e+03 4.37216406e+03 4.32830078e+03 4.38983252e+03 4.46676123e+03 4.57944873e+03 4.62948438e+03 4.68384131e+03 4.73515430e+03 4.72770898e+03 4.67311572e+03 4.66290039e+03 4.80785596e+03 4.82989551e+03 4.79819629e+03 4.93043896e+03 4.94238525e+03 4.92574268e+03 5.05210498e+03 5.03180078e+03 4.90309180e+03 4.99256689e+03 5.18356641e+03 5.21723047e+03 5.18396631e+03 5.24151318e+03 5.30959717e+03 5.35579883e+03 5.36735400e+03 5.24958301e+03 5.23414258e+03 5.45260205e+03 5.50667188e+03 5.41469385e+03 5.49874805e+03 5.47728564e+03 5.47689648e+03 5.61392822e+03 5.59581787e+03 5.54076465e+03 5.62580322e+03 5.76101172e+03 5.80204492e+03 5.75768164e+03 5.65378223e+03 5.63145703e+03 5.81101953e+03 5.93554492e+03 5.79324512e+03 5.83365137e+03 6.06698877e+03 6.04768213e+03 5.98738232e+03 5.95526611e+03 5.86903223e+03 5.84631592e+03 5.94934424e+03 6.12437354e+03 6.12888379e+03 6.10751562e+03 6.18590967e+03 6.22348438e+03 6.14848584e+03 6.03773096e+03 6.10397705e+03 6.26647412e+03 6.34633594e+03 6.42477002e+03 6.38532666e+03 6.31190430e+03 6.24374707e+03 6.35420459e+03 6.43029395e+03 6.22327734e+03 6.24251807e+03 6.47537061e+03 6.57123828e+03 6.43717773e+03 6.39159424e+03 6.37833740e+03 6.34238135e+03 6.48955615e+03 6.66965137e+03 6.65554883e+03 6.54221045e+03 6.55767529e+03 6.59523242e+03 6.53503174e+03 6.52386377e+03 6.59220410e+03 6.56245850e+03 6.75209570e+03 6.84361279e+03 6.54302734e+03 6.58976221e+03 6.63129102e+03 6.67127197e+03 6.80259033e+03 6.62134277e+03 6.54882666e+03 6.74902246e+03 6.83548242e+03 6.79044434e+03 6.74321924e+03 6.68722949e+03 6.65230762e+03 6.74688428e+03 6.84926465e+03 6.83962598e+03 6.68428125e+03 6.82457324e+03 6.95464893e+03 6.83331396e+03 6.80015771e+03 6.75444189e+03 6.76921191e+03 6.91679688e+03 6.82773779e+03 6.79235498e+03 6.95842529e+03 6.74699365e+03 6.70740137e+03 6.89842578e+03 6.72335889e+03 6.77585693e+03 6.96134033e+03 6.90642529e+03 6.91529590e+03 6.79466650e+03 6.81801172e+03 6.80264111e+03 6.80691357e+03 6.92696973e+03 6.78211475e+03 6.66639062e+03 6.89123828e+03 6.94896436e+03 6.77310352e+03 6.85295166e+03 6.93894922e+03 6.70446826e+03 6.82713379e+03 6.96684912e+03 6.74642725e+03 6.69493701e+03 6.77522998e+03 6.77079492e+03 6.71437500e+03 6.73034277e+03 6.70367529e+03 6.75659473e+03 6.83141113e+03 6.78096924e+03 6.75348145e+03 6.73051758e+03 6.67808398e+03 6.65809863e+03 6.78620508e+03 6.60711426e+03 6.56482373e+03 6.77310742e+03 6.66019434e+03 6.51506836e+03 6.60856543e+03 6.56992236e+03 6.51194336e+03 6.53909863e+03 6.57216699e+03 6.62874121e+03 6.57927881e+03 6.56496289e+03 6.58363330e+03 6.40106104e+03 6.43191455e+03 6.46144287e+03 6.36787793e+03 6.49640967e+03 6.58157764e+03 6.37270312e+03 6.26385986e+03 6.30648682e+03 6.47034326e+03 6.37493945e+03 6.12549219e+03 6.26858301e+03 6.40961084e+03 6.24827197e+03 6.22692188e+03 6.18454883e+03 6.12696191e+03 6.18147705e+03 6.09740918e+03 6.05238330e+03 6.18132275e+03 6.19265967e+03 6.06618799e+03 6.08825732e+03 6.06422510e+03 6.07848096e+03 5.92813037e+03 5.76341943e+03 5.92961523e+03 6.04630762e+03 5.82483740e+03 5.76807080e+03 5.79355078e+03 5.85839795e+03 5.82788428e+03 5.61060352e+03 5.73243750e+03 5.81260547e+03 5.69462012e+03 5.65646631e+03 5.59055811e+03 5.50593018e+03 5.54440674e+03 5.54885010e+03 5.46936475e+03 5.56308301e+03 5.52830713e+03 5.44207129e+03 5.46661182e+03 5.39575293e+03 5.27084619e+03 5.23814990e+03 5.30179102e+03 5.31914355e+03 5.19477930e+03 5.10926660e+03 5.07062012e+03 5.08217432e+03 5.14604443e+03 5.10762744e+03 4.96868799e+03 4.90780566e+03 5.00592383e+03 5.04326416e+03 4.88968604e+03 4.77593750e+03 4.74757227e+03 4.78672754e+03 4.75593701e+03 4.68594482e+03 4.73971533e+03 4.69018750e+03 4.61034326e+03 4.66801562e+03 4.60995410e+03 4.47852197e+03 4.43711035e+03 4.45426123e+03 4.43015381e+03 4.26621240e+03 4.18705811e+03 4.26086963e+03 4.27873633e+03 4.29315625e+03 4.20359814e+03 4.06422363e+03 4.13894775e+03 4.14758643e+03 3.96384888e+03 3.89043628e+03 3.95975122e+03 3.99336890e+03 3.89138818e+03 3.76176978e+03 3.70323120e+03 3.71270581e+03 3.74977441e+03 3.75971191e+03 3.69845215e+03 3.56148657e+03 3.49477759e+03 3.48738989e+03 3.42295435e+03 3.39330762e+03 3.35973169e+03 3.30608545e+03 3.29404370e+03 3.26819141e+03 3.21064990e+03 3.13492554e+03 3.12110278e+03 3.17389990e+03 3.09547388e+03 2.94141479e+03 2.89154370e+03 2.91320630e+03 2.91147241e+03 2.89001587e+03 2.79333691e+03 2.65722266e+03 2.63684424e+03 2.66823413e+03 2.66091113e+03 2.61416211e+03 2.50940356e+03 2.44039282e+03 2.43144629e+03 2.37251782e+03 2.34776099e+03 2.29509521e+03 2.18922900e+03 2.20540918e+03 2.20584570e+03 2.12325269e+03 2.04232349e+03 1.95562695e+03 1.94837793e+03 1.99922229e+03 1.93589453e+03 1.81075964e+03 1.79870288e+03 1.78950537e+03 1.68790295e+03 1.62653821e+03 1.56760083e+03 1.53455896e+03 1.54417822e+03 1.48613440e+03 1.39427698e+03 1.36212158e+03 1.34373901e+03 1.27990527e+03 1.22909705e+03 1.20421497e+03 1.14099084e+03 1.07757935e+03 1.04129297e+03 9.94385437e+02 9.63072632e+02 9.16256104e+02 8.60266174e+02 8.13621033e+02 7.48390015e+02 7.04072266e+02 6.64856873e+02 6.16700195e+02 5.79798706e+02 5.30852417e+02 4.79540192e+02 4.25151978e+02 3.75400604e+02 3.33098541e+02 2.87443115e+02 2.38291000e+02 1.85780655e+02 1.38715775e+02 9.27909088e+01 4.58236580e+01 3.84470403e-01 -4.72328072e+01 -9.48117905e+01 -1.46348251e+02 -1.96114319e+02 -2.41253174e+02 -2.89316711e+02 -3.32131073e+02 -3.77029724e+02 -4.38296875e+02 -4.92012878e+02 -5.17405273e+02 -5.57399963e+02 -6.22650330e+02 -6.80910400e+02 -7.27455750e+02 -7.59930359e+02 -7.96549622e+02 -8.54523315e+02 -9.15312134e+02 -9.57636230e+02 -9.90158875e+02 -1.04243994e+03 -1.09833179e+03 -1.14000232e+03 -1.19672290e+03 -1.24826514e+03 -1.28301672e+03 -1.33440454e+03 -1.38397278e+03 -1.43180859e+03 -1.46590308e+03 -1.49716211e+03 -1.55859021e+03 -1.61805347e+03 -1.66796936e+03 -1.69302258e+03 -1.72621350e+03 -1.80831189e+03 -1.85749036e+03 -1.88894104e+03 -1.95165625e+03 -1.95500659e+03 -1.98345374e+03 -2.11361353e+03 -2.14627246e+03 -2.11460376e+03 -2.21866382e+03 -2.28104712e+03 -2.25295703e+03 -2.35257153e+03 -2.41351343e+03 -2.39017261e+03 -2.49342261e+03 -2.56162207e+03 -2.52916870e+03 -2.59896094e+03 -2.67424756e+03 -2.69340112e+03 -2.75115894e+03 -2.77594727e+03 -2.76183716e+03 -2.83972925e+03 -2.93346045e+03 -3.00048511e+03 -3.05708374e+03 -3.03090747e+03 -3.08405225e+03 -3.11152441e+03 -3.08917139e+03 -3.22572754e+03 -3.29068677e+03 -3.26947412e+03 -3.37276392e+03 -3.38921655e+03 -3.36370142e+03 -3.46982568e+03 -3.55558057e+03 -3.59793750e+03 -3.58705908e+03 -3.60043335e+03 -3.59100391e+03 -3.73209326e+03 -3.88935254e+03 -3.77182349e+03 -3.80726636e+03 -3.82428247e+03 -3.87261230e+03 -4.02778979e+03 -3.95298145e+03 -3.94172803e+03 -4.07112451e+03 -4.15932568e+03 -4.14805908e+03 -4.07262427e+03 -4.18701123e+03 -4.31850781e+03 -4.29970557e+03 -4.34850879e+03 -4.32271143e+03 -4.36323926e+03 -4.49599707e+03 -4.51258398e+03 -4.57708154e+03 -4.51612695e+03 -4.49603955e+03 -4.60777637e+03 -4.65581641e+03 -4.73275439e+03 -4.73942188e+03 -4.67943164e+03 -4.75326270e+03 -4.87517920e+03 -4.91485645e+03 -4.90140771e+03 -4.92180811e+03 -4.94386475e+03 -5.03371777e+03 -5.02458838e+03 -4.97815918e+03 -5.13322559e+03 -5.18336084e+03 -5.13167480e+03 -5.25206055e+03 -5.24097900e+03 -5.17909668e+03 -5.25462207e+03 -5.25238916e+03 -5.31467285e+03 -5.42026709e+03 -5.38529102e+03 -5.34213477e+03 -5.42518750e+03 -5.48081885e+03 -5.51158740e+03 -5.68167480e+03 -5.59905518e+03 -5.49564502e+03 -5.61445801e+03 -5.58078271e+03 -5.63000830e+03 -5.68906006e+03 -5.74573389e+03 -5.84766553e+03 -5.74336377e+03 -5.82958057e+03 -5.82286914e+03 -5.74046289e+03 -5.83750586e+03 -5.97796045e+03 -6.01419287e+03 -5.92769775e+03 -5.93239795e+03 -6.05219629e+03 -6.03187109e+03 -6.00672070e+03 -6.04343896e+03 -6.07024561e+03 -6.20847754e+03 -6.15594482e+03 -6.14544287e+03 -6.22153418e+03 -6.13222998e+03 -6.12974219e+03 -6.34276611e+03 -6.37190039e+03 -6.25979932e+03 -6.26715527e+03 -6.20187256e+03 -6.25803564e+03 -6.54935156e+03 -6.44096826e+03 -6.30762842e+03 -6.58569629e+03 -6.63717139e+03 -6.56763086e+03 -6.37797998e+03 -6.45991357e+03 -6.79737061e+03 -7.46445654e+03 -7.30922412e+03 -1.61196387e+04 -2.11617266e+04 3559672. 3.86196375e+06 20270600. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -181644528. -4717116. -2.69870801e+04 -1.47211025e+04 -7.33157178e+03 -9.31232715e+03 -1.19626475e+04 -1.05661094e+04 -9.33731152e+03 -9.08968750e+03 -6.77585791e+03 -6.87963818e+03 -7.12008594e+03 -6.96239502e+03 -6.82595605e+03 -6.75370117e+03 -6.81221387e+03 -6.97044385e+03 -6.91163672e+03 -6.75066846e+03 -6.59863965e+03 -6.79789160e+03 -6.83713086e+03 -6.78408691e+03 -6.83499170e+03 -6.66323535e+03 -6.63762451e+03 -6.77084180e+03 -6.77528271e+03 -6.74440479e+03 -6.52993213e+03 -6.49695947e+03 -6.81567285e+03 -6.94769189e+03 -6.74481348e+03 -6.42777344e+03 -6.41597314e+03 -6.65204150e+03 -6.68724609e+03 -6.60674170e+03 -6.46735693e+03 -6.62080078e+03 -6.69631299e+03 -6.62611816e+03 -6.56377686e+03 -6.30947559e+03 -6.38608887e+03 -6.73151611e+03 -6.56988477e+03 -6.51284033e+03 -6.42132275e+03 -6.28475488e+03 -6.35284473e+03 -6.56198438e+03 -6.47626562e+03 -6.21128955e+03 -6.36127002e+03 -6.39123535e+03 -6.31266211e+03 -6.30495654e+03 -6.13068604e+03 -6.23837012e+03 -6.35399756e+03 -6.18213477e+03 -6.10892773e+03 -6.01835791e+03 -6.12211377e+03 -6.32633252e+03 -6.25353809e+03 -6.09647119e+03 -5.93853760e+03 -5.97518115e+03 -5.95359424e+03 -6.02947559e+03 -6.08215918e+03 -5.84834326e+03 -5.87253174e+03 -6.02936670e+03 -5.95866943e+03 -5.82773730e+03 -5.64006543e+03 -5.72243994e+03 -5.91025537e+03 -5.86001660e+03 -5.73795166e+03 -5.56732422e+03 -5.54783154e+03 -5.66701807e+03 -5.76018213e+03 -5.55789404e+03 -5.38874512e+03 -5.56880420e+03 -5.54209082e+03 -5.42751221e+03 -5.56552002e+03 -5.39790820e+03 -5.31664990e+03 -5.40204004e+03 -5.36389355e+03 -5.36412793e+03 -5.19532227e+03 -5.11134668e+03 -5.17508398e+03 -5.26787891e+03 -5.25923730e+03 -5.07816748e+03 -5.09104932e+03 -5.07012891e+03 -4.99149463e+03 -5.01597656e+03 -4.89314893e+03 -4.86460986e+03 -4.97580273e+03 -4.94107910e+03 -4.75046777e+03 -4.58607178e+03 -4.71145654e+03 -4.90929590e+03 -4.81370264e+03 -4.65687500e+03 -4.49590674e+03 -4.48072559e+03 -4.55652686e+03 -4.57215869e+03 -4.54118945e+03 -4.38636328e+03 -4.34937109e+03 -4.32398682e+03 -4.31918359e+03 -4.38691650e+03 -4.18825195e+03 -4.14352197e+03 -4.27976123e+03 -4.14515625e+03 -4.06870288e+03 -4.03065991e+03 -4.01050610e+03 -4.05509497e+03 -3.97425195e+03 -3.83156079e+03 -3.73177734e+03 -3.81417310e+03 -3.93614893e+03 -3.83869702e+03 -3.69515918e+03 -3.58121118e+03 -3.57436792e+03 -3.59861865e+03 -3.59999609e+03 -3.54864893e+03 -3.36842236e+03 -3.31580884e+03 -3.39557129e+03 -3.40059863e+03 -3.38823315e+03 -3.24756152e+03 -3.17608301e+03 -3.15117139e+03 -3.11958130e+03 -3.14037915e+03 -3.01059741e+03 -2.96837231e+03 -2.97777026e+03 -2.90895728e+03 -2.88324365e+03 -2.78102734e+03 -2.77344287e+03 -2.78283130e+03 -2.68549756e+03 -2.66451050e+03 -2.59522290e+03 -2.54798560e+03 -2.55351294e+03 -2.50558618e+03 -2.42496973e+03 -2.33379370e+03 -2.30041382e+03 -2.31923608e+03 -2.32669165e+03 -2.24290210e+03 -2.09851953e+03 -2.04132178e+03 -2.07687329e+03 -2.07404395e+03 -2.00606201e+03 -1.87716760e+03 -1.85841174e+03 -1.85581543e+03 -1.79434680e+03 -1.76094116e+03 -1.67641541e+03 -1.63415906e+03 -1.61413049e+03 -1.57582776e+03 -1.53390845e+03 -1.45933704e+03 -1.41715405e+03 -1.37170447e+03 -1.32780994e+03 -1.30700964e+03 -1.23612073e+03 -1.18141809e+03 -1.13685754e+03 -1.07953284e+03 -1.02749487e+03 -9.84699768e+02 -9.67180298e+02 -9.30479736e+02 -8.71147156e+02 -7.99459290e+02 -7.27396057e+02 -7.04479309e+02 -6.91911926e+02 -6.41555603e+02 -5.77325195e+02 -5.11619415e+02 -4.59483276e+02 -4.26204590e+02 -3.92109070e+02 -3.40574158e+02 -2.87440552e+02 -2.41129547e+02 -1.90866638e+02 -1.42494202e+02 -9.37626266e+01 -4.49429779e+01 2.17676497e+00 5.05672493e+01 9.97771072e+01 1.48399170e+02 1.85576416e+02 2.38814224e+02 2.92252289e+02 3.30162231e+02 3.82419739e+02 4.31090149e+02 4.91054657e+02 5.36288208e+02 5.57074280e+02 5.97413940e+02 6.57091064e+02 7.34477478e+02 8.05827881e+02 8.34736206e+02 8.39250488e+02 8.62250000e+02 9.25494446e+02 1.02589673e+03 1.10147400e+03 1.12602588e+03 1.10945581e+03 1.14718750e+03 1.27976562e+03 1.31808142e+03 1.29240723e+03 1.34390674e+03 1.42451208e+03 1.47332104e+03 1.56216248e+03 1.57310083e+03 1.55270361e+03 1.64992554e+03 1.67242773e+03 1.74275232e+03 1.83894641e+03 1.80252783e+03 1.88395276e+03 1.98821777e+03 1.99020215e+03 2.02506787e+03 2.05617407e+03 2.13539136e+03 2.17605420e+03 2.18385059e+03 2.19004883e+03 2.24023755e+03 2.39784399e+03 2.51043848e+03 2.48779468e+03 2.42443188e+03 2.42232471e+03 2.49341772e+03 2.64674365e+03 2.79581616e+03 2.76258643e+03 2.66009204e+03 2.73119067e+03 2.87540601e+03 2.88586060e+03 2.89039478e+03 2.94455981e+03 2.95797754e+03 3.02859888e+03 3.19803687e+03 3.15048682e+03 3.10762500e+03 3.21006323e+03 3.15816870e+03 3.28993848e+03 3.44480786e+03 3.36172632e+03 3.48159204e+03 3.50653149e+03 3.40574731e+03 3.53006909e+03 3.47974512e+03 3.60618457e+03 3.89826660e+03 3.72440942e+03 3.57181006e+03 3.70550391e+03 3.91256494e+03 4.07222241e+03 4.03612183e+03 3.84780762e+03 3.79594287e+03 3.92665894e+03 4.10336035e+03 4.33388525e+03 4.27207568e+03 4.03930884e+03 4.09429346e+03 4.27685840e+03 4.37380469e+03 4.27812061e+03 4.28221094e+03 4.37001172e+03 4.41621533e+03 4.62695264e+03 4.67272998e+03 4.44584033e+03 4.45744531e+03 4.58956885e+03 4.63734766e+03 4.69572705e+03 4.71782617e+03 4.87838916e+03 4.82366406e+03 4.67553516e+03 4.83126660e+03 4.75040283e+03 4.92576318e+03 5.26160400e+03 4.99212012e+03 4.72641211e+03 4.90552295e+03 5.20974365e+03 5.36717139e+03 5.35582324e+03 5.08671777e+03 4.95742676e+03 5.09804297e+03 5.34864355e+03 5.60251953e+03 5.50695850e+03 5.20321631e+03 5.19247070e+03 5.42574023e+03 5.48064893e+03 5.62673486e+03 5.68396924e+03 5.38066553e+03 5.41854688e+03 5.66046387e+03 5.73391113e+03 5.66552246e+03 5.64649170e+03 5.62963330e+03 5.57893311e+03 5.93832617e+03 5.96810547e+03 5.73899316e+03 5.74176562e+03 5.73618994e+03 5.79445020e+03 5.88785938e+03 5.89466992e+03 6.13281494e+03 6.15685791e+03 5.92693213e+03 5.86866846e+03 5.79341748e+03 6.05345801e+03 6.41493408e+03 6.27446533e+03 5.96073242e+03 5.89392285e+03 6.15190430e+03 6.44713525e+03 6.23522266e+03 5.92047314e+03 6.11462598e+03 6.30491357e+03 6.42542627e+03 6.64986865e+03 6.48393701e+03 6.16097070e+03 6.13609912e+03 6.33564697e+03 6.46597705e+03 6.51080713e+03 6.43927588e+03 6.43493066e+03 6.44171826e+03 6.57695508e+03 6.49586377e+03 6.33663672e+03 6.40087158e+03 6.43326904e+03 6.72160254e+03 6.77200391e+03 6.57987939e+03 6.61393457e+03 6.63241162e+03 6.67384375e+03 6.49940430e+03 6.39845459e+03 6.69070215e+03 6.98948828e+03 6.78391846e+03 6.46989160e+03 6.54374121e+03 6.86443359e+03 6.95778271e+03 6.84063086e+03 6.71404443e+03 6.56470898e+03 6.61836768e+03 6.84188184e+03 6.82524365e+03 6.69719238e+03 6.56403955e+03 6.54814893e+03 6.88286230e+03 7.17506445e+03 6.79790137e+03 6.61077734e+03 6.80671680e+03 6.79269678e+03 7.01556299e+03 6.97675293e+03 6.59742090e+03 6.65084863e+03 6.87857861e+03 6.82663721e+03 6.84628418e+03 6.80644287e+03 6.94326172e+03 7.20379297e+03 7.12059082e+03 7.36071387e+03 8.89917188e+03 8.44074023e+03 1.07013555e+04 1.03452393e+04 1.56207451e+04 2.04756777e+04 7.16612050e+06 24705494. 29251180. 3860606. 6.60897950e+06 47075812. 2126702. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 28241116. 2.45838250e+06 2.74274414e+04 1.73062715e+04 1.13054805e+04 1.04599023e+04 8.16789648e+03 7.74105713e+03 6.70285840e+03 6.80478564e+03 6.25902930e+03 6.38321240e+03 6.37096582e+03 6.20773926e+03 6.19655664e+03 6.18896094e+03 6.13172949e+03 6.10474805e+03 6.05147021e+03 5.99126270e+03 6.02975293e+03 5.97685938e+03 6.00635791e+03 6.04624609e+03 5.78549512e+03 5.75919482e+03 6.07995166e+03 6.04264551e+03 5.85042676e+03 5.81567969e+03 5.83521680e+03 5.78320215e+03 5.72708447e+03 5.72145752e+03 5.69473096e+03 5.65712988e+03 5.55623535e+03 5.52974219e+03 5.68269336e+03 5.67967627e+03 5.52799854e+03 5.48879541e+03 5.47625537e+03 5.45746973e+03 5.39991797e+03 5.36033838e+03 5.39007861e+03 5.25920557e+03 5.17787891e+03 5.19771826e+03 5.18186523e+03 5.36826855e+03 5.34631055e+03 5.11729053e+03 4.96691797e+03 4.93408984e+03 5.18740576e+03 5.19686182e+03 4.98533350e+03 4.84963135e+03 4.81039453e+03 4.89406299e+03 4.86072754e+03 4.92392627e+03 4.91285889e+03 4.62118994e+03 4.49662842e+03 4.69871826e+03 4.86116260e+03 4.70777979e+03 4.56403711e+03 4.52707129e+03 4.47569336e+03 4.43388086e+03 4.41890576e+03 4.36620947e+03 4.31025342e+03 4.31171582e+03 4.28219043e+03 4.22692920e+03 4.17422168e+03 4.27229443e+03 4.25085742e+03 4.10251904e+03 4.01797852e+03 3.99820801e+03 4.02174805e+03 3.99328540e+03 3.90419775e+03 3.86656274e+03 3.75655249e+03 3.65219971e+03 3.77807275e+03 3.72620239e+03 3.50651294e+03 3.52231738e+03 3.67219727e+03 3.75260669e+03 3.59647241e+03 3.46189648e+03 3.37548169e+03 3.32917725e+03 3.31844043e+03 3.27692261e+03 3.23617603e+03 3.17598364e+03 3.24565430e+03 3.21210205e+03 3.06414746e+03 3.01600806e+03 2.89903833e+03 2.89538525e+03 3.02005713e+03 2.93730176e+03 2.82439185e+03 2.72643628e+03 2.64977393e+03 2.73163647e+03 2.73666357e+03 2.63099976e+03 2.51059326e+03 2.45320947e+03 2.45693042e+03 2.41850952e+03 2.45585620e+03 2.42667383e+03 2.29807373e+03 2.22123462e+03 2.17254248e+03 2.17799731e+03 2.14803857e+03 2.07372266e+03 2.01091357e+03 1.96951917e+03 1.92330969e+03 1.81874695e+03 1.80013684e+03 1.85871045e+03 1.79194385e+03 1.70058850e+03 1.61006238e+03 1.55826135e+03 1.60497229e+03 1.56014404e+03 1.46481140e+03 1.38858350e+03 1.34005981e+03 1.32935046e+03 1.27374963e+03 1.23287769e+03 1.16050195e+03 1.13300452e+03 1.15319788e+03 1.07645520e+03 9.98299316e+02 9.54480042e+02 9.07686279e+02 8.55865662e+02 8.09505371e+02 7.56179626e+02 7.05118774e+02 6.61219116e+02 5.98514221e+02 5.60809570e+02 5.45922363e+02 4.77090973e+02 4.14829895e+02 3.78250397e+02 3.30407684e+02 2.92830261e+02 2.41101425e+02 1.85270813e+02 1.44194946e+02 9.62876587e+01 4.70006981e+01 1.21247582e-02 -4.68698807e+01 -9.45552826e+01 -1.42514847e+02 -1.88341248e+02 -2.30851196e+02 -2.87617584e+02 -3.51992950e+02 -3.93569427e+02 -4.32529297e+02 -4.65815765e+02 -5.08654938e+02 -5.87506531e+02 -6.42502075e+02 -6.73805847e+02 -6.99356445e+02 -7.38783142e+02 -8.09250916e+02 -8.61100159e+02 -9.28414978e+02 -9.63116699e+02 -9.84198059e+02 -1.04072192e+03 -1.08289270e+03 -1.17041467e+03 -1.21622400e+03 -1.22176514e+03 -1.27828064e+03 -1.32784521e+03 -1.36678882e+03 -1.37257324e+03 -1.45226892e+03 -1.59133496e+03 -1.60401245e+03 -1.60732520e+03 -1.61311304e+03 -1.64513257e+03 -1.79403223e+03 -1.85170898e+03 -1.83959619e+03 -1.84333557e+03 -1.88006738e+03 -1.98030225e+03 -2.02874988e+03 -2.11882764e+03 -2.15042310e+03 -2.14373608e+03 -2.17062329e+03 -2.20416553e+03 -2.35212646e+03 -2.39707251e+03 -2.37186914e+03 -2.39742529e+03 -2.43414966e+03 -2.57290210e+03 -2.62453125e+03 -2.53287598e+03 -2.57624268e+03 -2.76931372e+03 -2.80762354e+03 -2.71329102e+03 -2.75041333e+03 -2.93599072e+03 -3.00386938e+03 -2.94651782e+03 -2.92031445e+03 -2.97187280e+03 -3.17389038e+03 -3.16735986e+03 -3.11931079e+03 -3.23290430e+03 -3.27507739e+03 -3.27927026e+03 -3.29129150e+03 -3.35166382e+03 -3.30544800e+03 -3.43825171e+03 -3.68264331e+03 -3.61104395e+03 -3.59878320e+03 -3.65985620e+03 -3.67326050e+03 -3.71039575e+03 -3.74137183e+03 -3.78674805e+03 -3.73805054e+03 -3.71880737e+03 -3.85590112e+03 -3.98575684e+03 -4.13592578e+03 -4.03572485e+03 -3.92205151e+03 -4.07277466e+03 -4.16112256e+03 -4.34193604e+03 -4.32983154e+03 -4.22899609e+03 -4.18530127e+03 -4.19178516e+03 -4.35774707e+03 -4.40583984e+03 -4.53456396e+03 -4.57680615e+03 -4.51909473e+03 -4.47429688e+03 -4.37665967e+03 -4.56062305e+03 -4.85429590e+03 -4.84441504e+03 -4.74475342e+03 -4.63642334e+03 -4.60843457e+03 -4.87389014e+03 -5.04854541e+03 -4.94051709e+03 -4.80102002e+03 -4.83292578e+03 -4.98299023e+03 -5.02118652e+03 -5.19472412e+03 -5.23054736e+03 -5.10655371e+03 -5.07914502e+03 -5.09355127e+03 -5.28225684e+03 -5.33839697e+03 -5.13986182e+03 -5.16563184e+03 -5.48007617e+03 -5.45732959e+03 -5.20598828e+03 -5.31323877e+03 -5.61749365e+03 -5.61552100e+03 -5.53127734e+03 -5.40806006e+03 -5.39197705e+03 -5.73522852e+03 -5.79636719e+03 -5.66366309e+03 -5.53218750e+03 -5.52538477e+03 -5.69151416e+03 -5.75618799e+03 -5.79673682e+03 -5.64182080e+03 -5.78517090e+03 -6.13004541e+03 -6.00327490e+03 -5.95798145e+03 -5.99900391e+03 -5.95672217e+03 -5955. -5.98871289e+03 -6.03389795e+03 -6.03112109e+03 -5.98235400e+03 -5.84825537e+03 -6.04604492e+03 -6.35565674e+03 -6.09913623e+03 -5.95610547e+03 -6.17392432e+03 -6.26119336e+03 -6.48272510e+03 -6.39578027e+03 -6.18957471e+03 -6.35994824e+03 -6.38873975e+03 -6.20340381e+03 -6.17576025e+03 -6.51482568e+03 -6.47885986e+03 -6.32892236e+03 -6.23918457e+03 -6.12159717e+03 -6.41287549e+03 -6.82547803e+03 -6.67991455e+03 -6.45348389e+03 -6.33218945e+03 -6.29635596e+03 -6.65324854e+03 -6.81617920e+03 -6.64734082e+03 -6.43620068e+03 -6.42985010e+03 -6.51341602e+03 -6.60745459e+03 -6.80024951e+03 -6.76762646e+03 -6.60828711e+03 -6.61835205e+03 -6.60895947e+03 -6.77862842e+03 -6.84362012e+03 -6.72452246e+03 -6.66000830e+03 -6.63261230e+03 -6.74846924e+03 -6.60746729e+03 -6.63244434e+03 -6.93819971e+03 -6.88986377e+03 -6.79522900e+03 -6.66214209e+03 -6.57524414e+03 -7.01066895e+03 -7.00708350e+03 -6.80674219e+03 -6.68104639e+03 -6.63675781e+03 -6.72571826e+03 -6.76473047e+03 -6.80850879e+03 -6.70766992e+03 -6.81968994e+03 -7.07730664e+03 -6.87233350e+03 -6.93373584e+03 -6.98256543e+03 -6.86334814e+03 -6.83404883e+03 -6.74140039e+03 -6.78202783e+03 -6.83468262e+03 -6.83931104e+03 -6.81835889e+03 -6.90323047e+03 -6.94886328e+03 -6.68724170e+03 -6.59448096e+03 -6.75645801e+03 -6.87228174e+03 -7.07043164e+03 -6.89464062e+03 -6.70954053e+03 -6.92949463e+03 -6.88511719e+03 -6.78050488e+03 -6.79912451e+03 -6.77259912e+03 -6.70895752e+03 -6.69710107e+03 -6.77652539e+03 -6.59190234e+03 -6.69982861e+03 -7.00846143e+03 -6.86364844e+03 -6.78618555e+03 -6.67467188e+03 -6.53371094e+03 -6.87503467e+03 -6.87355615e+03 -6.72669873e+03 -6.54362256e+03 -6.40823096e+03 -6.60134814e+03 -6.70421826e+03 -6.90299609e+03 -6.68159326e+03 -6.47859277e+03 -6.56908838e+03 -6.53841162e+03 -6.74766455e+03 -6.70785791e+03 -6.47846436e+03 -6.50717334e+03 -6.46309082e+03 -6.51065332e+03 -6.34260986e+03 -6.43315723e+03 -6.75003613e+03 -6.62798730e+03 -6.50138086e+03 -6.31402783e+03 -6.19787598e+03 -6.56663525e+03 -6.57938721e+03 -6.34231982e+03 -6.17198975e+03 -6.16151904e+03 -6.32556201e+03 -6.29695361e+03 -6.42334863e+03 -6.42235010e+03 -6.23339355e+03 -6.09233447e+03 -6.02343408e+03 -6.34869385e+03 -6.30871338e+03 -6.07896387e+03 -6.09544141e+03 -6.09535205e+03 -5.99432178e+03 -5.97422852e+03 -6.12004102e+03 -5.93685449e+03 -5.79596680e+03 -6.11387158e+03 -6.11733545e+03 -5.92744531e+03 -5.86108154e+03 -5.83072949e+03 -5.83622559e+03 -5.64074072e+03 -5.57880029e+03 -5.86778223e+03 -5.87139551e+03 -5.53391650e+03 -5.42375635e+03 -5.68070068e+03 -5.87568555e+03 -5.72354102e+03 -5.47057666e+03 -5.39977441e+03 -5.59341650e+03 -5.54074805e+03 -5.39581885e+03 -5.45837207e+03 -5.30658203e+03 -5.11547510e+03 -5.29453662e+03 -5.52339893e+03 -5.42472314e+03 -5.15244043e+03 -5.04453711e+03 -5.26249121e+03 -5.35196484e+03 -5.15827197e+03 -4.98408057e+03 -4.94052686e+03 -4.97828662e+03 -4.95404688e+03 -5.08850439e+03 -4.98998486e+03 -4.77353467e+03 -4.84386035e+03 -4.84702344e+03 -4.85501660e+03 -4.71416602e+03 -4.58939551e+03 -4.74665479e+03 -4.72155225e+03 -4.60396436e+03 -4.44822168e+03 -4.47076074e+03 -4.68750684e+03 -4.47495703e+03 -4.32097412e+03 -4.39356543e+03 -4.33659717e+03 -4.33397754e+03 -4.29796680e+03 -4.33822119e+03 -4.33427588e+03 -4.18162305e+03 -4.00834058e+03 -3.98599634e+03 -4.17243018e+03 -4.05131201e+03 -3.90294971e+03 -3.94057397e+03 -3.90028833e+03 -3.87632788e+03 -3.83059741e+03 -3.84564502e+03 -3.73010498e+03 -3.59782812e+03 -3.70909351e+03 -3.67996069e+03 -3.60492285e+03 -3.57235254e+03 -3.50944141e+03 -3.46993945e+03 -3.33291602e+03 -3.25025195e+03 -3.39524390e+03 -3.42512183e+03 -3.20692383e+03 -3.07127271e+03 -3.17973511e+03 -3.26429956e+03 -3.14732812e+03 -2.98939990e+03 -2.90512524e+03 -2.98484937e+03 -2.96035303e+03 -2.84844653e+03 -2.87627295e+03 -2.82595898e+03 -2.69329248e+03 -2.64473926e+03 -2.67986353e+03 -2.67764282e+03 -2.51898462e+03 -2.43179980e+03 -2.51754102e+03 -2.51302222e+03 -2.40000122e+03 -2.26992554e+03 -2.21611890e+03 -2.29728589e+03 -2.26778418e+03 -2.14429810e+03 -2.09026343e+03 -2.06014746e+03 -2.00093933e+03 -1.94598889e+03 -1.97843201e+03 -1.89324402e+03 -1.78213306e+03 -1.81960107e+03 -1.78994873e+03 -1.72262317e+03 -1.63472510e+03 -1.56102368e+03 -1.57344556e+03 -1.50819482e+03 -1.45118542e+03 -1.49007129e+03 -1.41334937e+03 -1.36980408e+03 -1.73552893e+03 -1.60998828e+03 -1.70578394e+03 -1.81845813e+03 -1.94994031e+03 -1.54032568e+03 -1.12939856e+03 -1.29820361e+03 -5.94285938e+03 112373816. 546353984. -18419674. -18419674. 5.39781350e+06 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. 391148160. 1.60673500e+05 -1.16610180e+05 -8.25295625e+04 -1.60373812e+05 -2.17510422e+05 2.02303101e+03 1.57223242e+03 9.56342468e+02 1.02881934e+03 1.03751624e+03 1.05559058e+03 1.18124585e+03 1.39046448e+03 1.21082983e+03 1.21786377e+03 1.35360388e+03 1.28825818e+03 1.37095764e+03 1.59979248e+03 1.62566956e+03 1.55501440e+03 1.59671594e+03 1.65278882e+03 1.67480994e+03 1.73489954e+03 1.82711609e+03 1.86088953e+03 1.89560901e+03 1.95612659e+03 1.96935999e+03 2.00184387e+03 2.06594434e+03 2.09057886e+03 2.11917505e+03 2.22622876e+03 2.31352832e+03 2.29495068e+03 2.31606079e+03 2.38186475e+03 2.42801001e+03 2.49346484e+03 2.52381543e+03 2.51462549e+03 2.61172974e+03 2.72345508e+03 2.67292993e+03 2.69781860e+03 2.80183545e+03 2.77398389e+03 2.84053247e+03 2.97579834e+03 2.96627002e+03 2.98120483e+03 3.06407104e+03 3.16307080e+03 3.15768652e+03 3.10400659e+03 3.13205298e+03 3.18714600e+03 3.33661328e+03 3.44302148e+03 3.40021069e+03 3.39275098e+03 3.42270386e+03 3.48479199e+03 3.53507373e+03 3.54257056e+03 3.55531958e+03 3.67192383e+03 3.81623242e+03 3.75495630e+03 3.74821143e+03 3.86504492e+03 3.87919507e+03 3.88907031e+03 3.94340381e+03 4.01744092e+03 4.00979956e+03 4.00272607e+03 4.13205762e+03 4.15436963e+03 4.18310156e+03 4.22371289e+03 4.16448535e+03 4.28003223e+03 4.44360352e+03 4.36717822e+03 4.33713184e+03 4.41438086e+03 4.46114990e+03 4.53318115e+03 4.54356494e+03 4.48620508e+03 4.62276465e+03 4.79153271e+03 4.73733936e+03 4.63835938e+03 4.68910938e+03 4.83839795e+03 4.86652246e+03 4.85946973e+03 4.85526904e+03 4.85254150e+03 4.99142383e+03 5.14935107e+03 5.03733691e+03 4.93897119e+03 4.99149609e+03 5.05615723e+03 5.17110059e+03 5.26741406e+03 5.21890088e+03 5.21866846e+03 5.40990039e+03 5.43404492e+03 5.27899951e+03 5.23063232e+03 5.30355664e+03 5.43914893e+03 5.51121973e+03 5.53533252e+03 5.52962695e+03 5.55479785e+03 5.61530762e+03 5.50614551e+03 5.51619043e+03 5.63138770e+03 5.64026855e+03 5.74399414e+03 5.83737695e+03 5.69011182e+03 5.69673291e+03 5.86867383e+03 5.85970752e+03 5.74023340e+03 5.86991016e+03 6.04280127e+03 6.00846289e+03 5.96627197e+03 5.94909570e+03 5.97385791e+03 5.98846582e+03 5.93724854e+03 6.03804297e+03 6.11025391e+03 6.11725684e+03 6.14378174e+03 6.18318652e+03 6.20254346e+03 6.02509082e+03 6.15611865e+03 6.28876807e+03 6.25858154e+03 6.32436670e+03 6.43876318e+03 6.39990918e+03 6.25829590e+03 6.26196387e+03 6.31748926e+03 6.24035693e+03 6.35769678e+03 6.50806836e+03 6.44158057e+03 6.45241602e+03 6.46034033e+03 6.42044629e+03 6.43603125e+03 6.44173096e+03 6.45253857e+03 6.52600146e+03 6.60585791e+03 6.59187500e+03 6.50568359e+03 6.62432959e+03 6.60419580e+03 6.61268945e+03 6.58420166e+03 6.57512891e+03 6.70760107e+03 6.62974707e+03 6.64633154e+03 6.67197803e+03 6.69716553e+03 6.78568945e+03 6.55745410e+03 6.62002539e+03 6.81764746e+03 6.73779346e+03 6.82463477e+03 6.82941650e+03 6.70040625e+03 6.71862354e+03 6.64599951e+03 6.65693701e+03 6.72603613e+03 6.81631689e+03 6.86363330e+03 6.87118066e+03 6.88099902e+03 6.86284424e+03 6.80768018e+03 6.75477295e+03 6.67317383e+03 6.71617480e+03 6.91216309e+03 7.02642383e+03 6.77279248e+03 6.70414990e+03 6.92361621e+03 6.72028223e+03 6.82371143e+03 6.97172803e+03 6.79322217e+03 6.76653467e+03 6.85365234e+03 6.90053174e+03 6.88544482e+03 6.81516064e+03 6.78547021e+03 6.66504248e+03 6.73767725e+03 6.87367773e+03 6.85601514e+03 6.80857764e+03 6.80280322e+03 6.87623535e+03 6.75784521e+03 6.82009570e+03 6.87988086e+03 6.73180420e+03 6.66935205e+03 6.74012109e+03 6.76895850e+03 6.80378174e+03 6.76669922e+03 6.70284277e+03 6.75533203e+03 6.73271338e+03 6.72829150e+03 6.70180811e+03 6.84541846e+03 6.83190479e+03 6.53593262e+03 6.65230371e+03 6.67691064e+03 6.62643555e+03 6.76756104e+03 6.56002734e+03 6.47045410e+03 6.73480078e+03 6.70105176e+03 6.47461523e+03 6.48013525e+03 6.60253955e+03 6.63380615e+03 6.47332080e+03 6.55403857e+03 6.62918652e+03 6.42159814e+03 6.40765869e+03 6.50588330e+03 6.30905762e+03 6.41137305e+03 6.51242627e+03 6.30126611e+03 6.39940723e+03 6.50907812e+03 6.38550000e+03 6.26308545e+03 6.23365039e+03 6.29230469e+03 6.36332715e+03 6.24264990e+03 6.13743604e+03 6.18718994e+03 6.18228809e+03 6.12584033e+03 6.09040674e+03 6.12840137e+03 6.10307227e+03 6.06648535e+03 6.09975391e+03 6.11083643e+03 5.98883691e+03 5.99721484e+03 5.99297656e+03 5.83749854e+03 5.98191699e+03 5.99719336e+03 5.77124316e+03 5.84534570e+03 5.85183740e+03 5.74401611e+03 5.80420020e+03 5.70412207e+03 5.74860938e+03 5.80916016e+03 5.68934570e+03 5.61784814e+03 5.59098828e+03 5.51975439e+03 5.47747998e+03 5.48782178e+03 5.57258008e+03 5.59342969e+03 5.47555127e+03 5.41870703e+03 5.46896289e+03 5.36296973e+03 5.23775342e+03 5.27055371e+03 5.34601367e+03 5.33127881e+03 5.16061133e+03 5.06037354e+03 5.15333301e+03 5.18990576e+03 5.07531104e+03 5.01262988e+03 5.00288525e+03 4.98829639e+03 5.02762793e+03 4.95648438e+03 4.86463281e+03 4.77871045e+03 4.73886133e+03 4.77071240e+03 4.73390967e+03 4.71461328e+03 4.75353613e+03 4.65583252e+03 4.61092822e+03 4.69213721e+03 4.57674707e+03 4.43643213e+03 4.48868213e+03 4.53776758e+03 4.40316602e+03 4.24163379e+03 4.21260400e+03 4.29633203e+03 4.31506006e+03 4.24436816e+03 4.17393604e+03 4.09477148e+03 4.14430518e+03 4.11818896e+03 3.93206128e+03 3.90374316e+03 3.95854858e+03 3.95981641e+03 3.85348877e+03 3.74423804e+03 3.74810815e+03 3.75324951e+03 3.75330713e+03 3.74602515e+03 3.68174023e+03 3.54764624e+03 3.44403638e+03 3.50940845e+03 3.56420581e+03 3.43478589e+03 3.33393750e+03 3.26637646e+03 3.27539160e+03 3.31123608e+03 3.20419873e+03 3.13562158e+03 3.11897778e+03 3.13647827e+03 3.09921289e+03 2.94303247e+03 2.94967627e+03 2.93883887e+03 2.84031079e+03 2.83158813e+03 2.75716968e+03 2.71052783e+03 2.69409204e+03 2.63200098e+03 2.60477466e+03 2.58604150e+03 2.53702881e+03 2.45502124e+03 2.42954712e+03 2.40682861e+03 2.34431177e+03 2.28440259e+03 2.19131616e+03 2.17380615e+03 2.19797534e+03 2.13738501e+03 2.06802075e+03 1.97312451e+03 1.94465686e+03 1.97641614e+03 1.89617444e+03 1.82177039e+03 1.80847888e+03 1.75384814e+03 1.67358826e+03 1.64661816e+03 1.62012341e+03 1.54818237e+03 1.51502856e+03 1.46819312e+03 1.38469690e+03 1.36055701e+03 1.33058911e+03 1.28480200e+03 1.26011340e+03 1.20078638e+03 1.14089563e+03 1.08178589e+03 1.02988110e+03 9.99085327e+02 9.62339233e+02 9.02940918e+02 8.42127869e+02 8.08626282e+02 7.59570374e+02 7.05864746e+02 6.75734619e+02 6.22846436e+02 5.67502075e+02 5.19882812e+02 4.70544830e+02 4.27254852e+02 3.83879730e+02 3.35374603e+02 2.80452942e+02 2.31933044e+02 1.87233917e+02 1.40465622e+02 9.43363724e+01 4.70492935e+01 -2.10209513e+00 -4.96782417e+01 -9.56054916e+01 -1.41882309e+02 -1.92295654e+02 -2.42460327e+02 -2.93372253e+02 -3.33624908e+02 -3.72907990e+02 -4.32650665e+02 -4.87941956e+02 -5.27642761e+02 -5.68853577e+02 -6.17536865e+02 -6.69588562e+02 -7.24474854e+02 -7.68663696e+02 -8.00139832e+02 -8.53427612e+02 -9.15278625e+02 -9.55099915e+02 -1.00040186e+03 -1.04508069e+03 -1.08545764e+03 -1.14464331e+03 -1.19396069e+03 -1.24721802e+03 -1.29065002e+03 -1.32264551e+03 -1.38098950e+03 -1.43100549e+03 -1.47733008e+03 -1.48945508e+03 -1.53075610e+03 -1.61819019e+03 -1.68021375e+03 -1.73273633e+03 -1.74343152e+03 -1.78199133e+03 -1.82224438e+03 -1.87228003e+03 -1.96666797e+03 -1.97114172e+03 -2.00313562e+03 -2.10830322e+03 -2.10479785e+03 -2.11559375e+03 -2.22788013e+03 -2.28045435e+03 -2.30358252e+03 -2.37335645e+03 -2.38151294e+03 -2.34742065e+03 -2.46550049e+03 -2.55968359e+03 -2.54389233e+03 -2.66112988e+03 -2.69959814e+03 -2.65530054e+03 -2.70974805e+03 -2.74466846e+03 -2.79730566e+03 -2.90389282e+03 -2.92510815e+03 -2.94728882e+03 -3.01954492e+03 -3.06252295e+03 -3.12073828e+03 -3.12413599e+03 -3.12338574e+03 -3.19996167e+03 -3.26162451e+03 -3.26489526e+03 -3.32572217e+03 -3.39854199e+03 -3.39754370e+03 -3.48160352e+03 -3.54063745e+03 -3.56046753e+03 -3.59497217e+03 -3.57275830e+03 -3.62521655e+03 -3.78005078e+03 -3.81658765e+03 -3.75613330e+03 -3.84009985e+03 -3.90642676e+03 -3.91859082e+03 -3.95317627e+03 -3.87913989e+03 -3.91324341e+03 -4.09978906e+03 -4.19321777e+03 -4.18982715e+03 -4.12190234e+03 -4.14919580e+03 -4.29159180e+03 -4.29260010e+03 -4.30015820e+03 -4.36289551e+03 -4.38162256e+03 -4.44982666e+03 -4.49510938e+03 -4.57496729e+03 -4.54102393e+03 -4.50443506e+03 -4.68268506e+03 -4.64989062e+03 -4.61921680e+03 -4.69857031e+03 -4.67863965e+03 -4.77061670e+03 -4.94972314e+03 -4.95462549e+03 -4.82024756e+03 -4.84848438e+03 -4.98020312e+03 -5.04457324e+03 -5.05580811e+03 -5.02964795e+03 -5.08767578e+03 -5.18390820e+03 -5.19207715e+03 -5.22953467e+03 -5.23791504e+03 -5.25912500e+03 -5.29023877e+03 -5.17059180e+03 -5.22237158e+03 -5.43464355e+03 -5.45380957e+03 -5.42776514e+03 -5.45015332e+03 -5.40969141e+03 -5.42769922e+03 -5.64972461e+03 -5.67166260e+03 -5.54253906e+03 -5.57212695e+03 -5.56306055e+03 -5.64929346e+03 -5.71695264e+03 -5.76659814e+03 -5.84975586e+03 -5.79726221e+03 -5.79551221e+03 -5.80815674e+03 -5.74527734e+03 -5.76659229e+03 -5.98635840e+03 -6.02700537e+03 -5.92220801e+03 -5.94252295e+03 -5.98266016e+03 -6.01422119e+03 -5.99826953e+03 -6.10631934e+03 -6.07531641e+03 -6.09749951e+03 -6.14224854e+03 -6.15334424e+03 -6.28154834e+03 -6.18497754e+03 -6.15104541e+03 -6.32199023e+03 -6.22205566e+03 -6.19521924e+03 -6.30987354e+03 -6.28080957e+03 -6.28711572e+03 -6.42376465e+03 -6.48979736e+03 -6.39175586e+03 -6.46883887e+03 -6.45944434e+03 -6.45127344e+03 -6.45674707e+03 -6.81094873e+03 -6.86757178e+03 -8.23881250e+03 -8.84862305e+03 -1.06168643e+04 -8.99137988e+03 -1.48310088e+04 -8.74486641e+04 20270600. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -181644528. -4717116. 2.81008050e+06 -7779535. 8937507. -3.13485375e+06 -11670611. -5.63130850e+06 -2.03439102e+04 -1.72137949e+04 -9.08920215e+03 -7.24067773e+03 -7.09668115e+03 -8.85985449e+03 -7.26350244e+03 -9.19760840e+03 -6.52477490e+03 -6.32506787e+03 -6.89558838e+03 -6.74795850e+03 -6.56358594e+03 -6.87140918e+03 -7.02807422e+03 -6.92248486e+03 -6.80119434e+03 -6.58790039e+03 -6.65591797e+03 -6.95741650e+03 -6.71465576e+03 -6.57974268e+03 -6.50855664e+03 -6.62994775e+03 -6.92185156e+03 -6.87227051e+03 -6.66510156e+03 -6.39227344e+03 -6.41992773e+03 -6.66952490e+03 -6.67495215e+03 -6.62222168e+03 -6.55562012e+03 -6.57334863e+03 -6.62389453e+03 -6.60003223e+03 -6.62033643e+03 -6.35302148e+03 -6.43661182e+03 -6.78547217e+03 -6.47938330e+03 -6.28839697e+03 -6.34789258e+03 -6.34273828e+03 -6.54588574e+03 -6.55123828e+03 -6.35747217e+03 -6.22056396e+03 -6.36033691e+03 -6.44347168e+03 -6.33163184e+03 -6.24781738e+03 -6.11565723e+03 -6.26481836e+03 -6.39310498e+03 -6.17013672e+03 -6.12724609e+03 -6.09569336e+03 -6.04689453e+03 -6.24175488e+03 -6.26429688e+03 -6.11280078e+03 -5.96015039e+03 -6.03308203e+03 -6.05406982e+03 -6.03025098e+03 -6.01860986e+03 -5.81794287e+03 -5.81620508e+03 -6.07974170e+03 -5.88351025e+03 -5.68153955e+03 -5.63831689e+03 -5.78715820e+03 -6.01419141e+03 -5.86207861e+03 -5.72380176e+03 -5.61987939e+03 -5.51513037e+03 -5.61942822e+03 -5.74352539e+03 -5.59146289e+03 -5.42345947e+03 -5.54050488e+03 -5.55671533e+03 -5.49351270e+03 -5.56050439e+03 -5.35003174e+03 -5.27151709e+03 -5.49357910e+03 -5.39109277e+03 -5.26600293e+03 -5.17691016e+03 -5.11091260e+03 -5.27632080e+03 -5.29226904e+03 -5.09592578e+03 -5.02939551e+03 -5.12024609e+03 -5.13117480e+03 -5.01941211e+03 -5.03375439e+03 -4.93209375e+03 -4.84662842e+03 -4.98534766e+03 -4.90600146e+03 -4.74142480e+03 -4.64612988e+03 -4.68887207e+03 -4.85133545e+03 -4.80824854e+03 -4.69557178e+03 -4.50678271e+03 -4.42278271e+03 -4.61357617e+03 -4.60319775e+03 -4.41259912e+03 -4.35650977e+03 -4.38876123e+03 -4.42507666e+03 -4.32607715e+03 -4.25483887e+03 -4.14886914e+03 -4.19655859e+03 -4.33820801e+03 -4.13595947e+03 -4.05478638e+03 -4.06535693e+03 -3.97239966e+03 -4.00190063e+03 -3.96694653e+03 -3.87218481e+03 -3.78644897e+03 -3.78566309e+03 -3.87084839e+03 -3.83539673e+03 -3.72115991e+03 -3.59662012e+03 -3.55434106e+03 -3.63669556e+03 -3.61636304e+03 -3.52183325e+03 -3.39314771e+03 -3.30140332e+03 -3.39366724e+03 -3.42043750e+03 -3.32727515e+03 -3.19867407e+03 -3.16757300e+03 -3.16999341e+03 -3.13599780e+03 -3.16552197e+03 -3.03001855e+03 -2.96344409e+03 -3.00186597e+03 -2.90744873e+03 -2.84267969e+03 -2.80373096e+03 -2.79686597e+03 -2.76896094e+03 -2.66912671e+03 -2.61362305e+03 -2.56522925e+03 -2.57088281e+03 -2.61097241e+03 -2.50873120e+03 -2.37617236e+03 -2.32949829e+03 -2.31778882e+03 -2.33906689e+03 -2.31936426e+03 -2.24083130e+03 -2.11854053e+03 -2.02847522e+03 -2.05718359e+03 -2.07362524e+03 -2.02538391e+03 -1.89671399e+03 -1.83880884e+03 -1.85388684e+03 -1.81286230e+03 -1.76363586e+03 -1.69529260e+03 -1.64763464e+03 -1.60659558e+03 -1.54510535e+03 -1.51188074e+03 -1.46915076e+03 -1.41498999e+03 -1.39369202e+03 -1.33142407e+03 -1.27178491e+03 -1.22514880e+03 -1.19086829e+03 -1.15605920e+03 -1.08694788e+03 -1.02755164e+03 -9.80553589e+02 -9.69037354e+02 -9.37684509e+02 -8.60338867e+02 -7.98895325e+02 -7.38707581e+02 -7.00416260e+02 -6.84067017e+02 -6.38374207e+02 -5.77569092e+02 -5.09713287e+02 -4.61515411e+02 -4.40588165e+02 -3.96001556e+02 -3.32651947e+02 -2.84855896e+02 -2.42619308e+02 -1.91238007e+02 -1.40545929e+02 -9.13970184e+01 -4.33458328e+01 3.51150966e+00 5.10608177e+01 1.00468285e+02 1.47001236e+02 1.85177429e+02 2.35752106e+02 2.90461273e+02 3.37709351e+02 3.86240753e+02 4.28148315e+02 4.90308441e+02 5.37125549e+02 5.55072449e+02 5.95420410e+02 6.57466675e+02 7.35238586e+02 8.07227539e+02 8.36102417e+02 8.38625793e+02 8.59097900e+02 9.22485657e+02 1.02581750e+03 1.10674023e+03 1.13023389e+03 1.10698633e+03 1.14429199e+03 1.28537769e+03 1.32232312e+03 1.29861475e+03 1.35477063e+03 1.41197644e+03 1.45966467e+03 1.55950720e+03 1.57432178e+03 1.55728235e+03 1.64744958e+03 1.67075671e+03 1.74700549e+03 1.83725134e+03 1.80143860e+03 1.88430750e+03 1.98150330e+03 1.98486890e+03 2.01962561e+03 2.06420630e+03 2.13409155e+03 2.16496924e+03 2.18954028e+03 2.19253442e+03 2.23711841e+03 2.39839917e+03 2.51631055e+03 2.49679199e+03 2.41356543e+03 2.41166064e+03 2.50254761e+03 2.65167139e+03 2.78609839e+03 2.75411426e+03 2.65926416e+03 2.73698096e+03 2.86902344e+03 2.87131836e+03 2.89017456e+03 2.95982202e+03 2.96931372e+03 3.01675439e+03 3.18891064e+03 3.16174756e+03 3.09773975e+03 3.21105420e+03 3.18046069e+03 3.30499170e+03 3.43221606e+03 3.34663745e+03 3.48223047e+03 3.50627979e+03 3.40834839e+03 3.53283716e+03 3.48215601e+03 3.59979199e+03 3.88751587e+03 3.72982983e+03 3.56070679e+03 3.66135767e+03 3.90104932e+03 4.10041211e+03 4.04021167e+03 3.85543066e+03 3.81301172e+03 3.92039771e+03 4.09841846e+03 4.31933252e+03 4.26289551e+03 4.05214014e+03 4.09245068e+03 4.24012744e+03 4.33093799e+03 4.32492578e+03 4.33853711e+03 4.37084521e+03 4.40209229e+03 4.62495508e+03 4.66617969e+03 4.39823926e+03 4.40571143e+03 4.63555713e+03 4.68039697e+03 4.68316455e+03 4.72464844e+03 4.89395605e+03 4.82992822e+03 4.67249561e+03 4.82714697e+03 4.73887842e+03 4.92147314e+03 5.27737012e+03 4.99032471e+03 4.74076514e+03 4.93991699e+03 5.21589404e+03 5.39207910e+03 5.36161230e+03 5.04045459e+03 4.95194775e+03 5.11677246e+03 5.34717773e+03 5.56073389e+03 5.50908984e+03 5.19708545e+03 5.19640674e+03 5.44683936e+03 5.47497510e+03 5.61169385e+03 5.69335156e+03 5.39602051e+03 5.38604492e+03 5.70703760e+03 5.78953613e+03 5.55302393e+03 5.54497314e+03 5.71881152e+03 5.65599365e+03 5.88330176e+03 5.95868457e+03 5.75309424e+03 5.74127441e+03 5.75477295e+03 5.80263916e+03 5.86156152e+03 5.86114502e+03 6.09528027e+03 6.19652246e+03 6.02519092e+03 5.86623047e+03 5.73502588e+03 6.01633887e+03 6.39218555e+03 6.27154639e+03 5.95765430e+03 5.86357568e+03 6.09672021e+03 6.44539209e+03 6.28495996e+03 5.93874072e+03 6.09399902e+03 6.30045996e+03 6.43502441e+03 6.68413916e+03 6.48546533e+03 6.10064355e+03 6.14520459e+03 6.31951123e+03 6.43765088e+03 6.51612939e+03 6.46497021e+03 6.47338721e+03 6.45284229e+03 6.56552881e+03 6.54938330e+03 6.38899561e+03 6.41011768e+03 6.38762012e+03 6.69013623e+03 6.76492383e+03 6.53114551e+03 6.66338428e+03 6.67272412e+03 6.65173633e+03 6.48045166e+03 6.38781006e+03 6.71341992e+03 6.97669727e+03 6.86166162e+03 6.53876465e+03 6.49386572e+03 6.81868750e+03 6.95366016e+03 6.83923633e+03 6.71327197e+03 6.54112061e+03 6.58650342e+03 6.85314941e+03 6.85516797e+03 6.70594775e+03 6.55843604e+03 6.52074561e+03 6.85644287e+03 7.16814795e+03 6.82445166e+03 6.62730127e+03 6.80423047e+03 6.79516211e+03 7.01159326e+03 6.96064795e+03 6.61335938e+03 6.67843750e+03 6.88529443e+03 6.89923584e+03 6.85068457e+03 6.79021338e+03 6.92609619e+03 6.95883643e+03 6.69721875e+03 7.00159033e+03 6.79535205e+03 6.51994531e+03 7.23033105e+03 7.16422656e+03 8.71377832e+03 8.90109277e+03 1.01931445e+04 1.18359209e+04 1.75669570e+04 2.00014980e+04 6.60897950e+06 47075812. 2126702. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 28241116. 2.45838250e+06 5940163. 9734758. 3.73960925e+06 -9.85152750e+05 1.83632715e+04 1.44833916e+04 1.03254697e+04 1.04312842e+04 9.38225391e+03 9.63622559e+03 9.64802930e+03 9.31961914e+03 9.27968359e+03 9.24586816e+03 7.84888867e+03 8.01292432e+03 6.56704443e+03 6.18660205e+03 6.13003418e+03 6.01607324e+03 6.03543262e+03 6.03206006e+03 5.82814795e+03 5.81015820e+03 6.06416553e+03 6.04884131e+03 5.86230811e+03 5.79310938e+03 5.82286133e+03 5.80911377e+03 5.74610156e+03 5.72720117e+03 5.68553418e+03 5.64112305e+03 5.55898633e+03 5.53168506e+03 5.69308447e+03 5.66145703e+03 5.51225635e+03 5.48743213e+03 5.48569385e+03 5.49127490e+03 5.39805371e+03 5.37926953e+03 5.36959082e+03 5.27489404e+03 5.21083447e+03 5.18725098e+03 5.15160352e+03 5.35523389e+03 5.35058057e+03 5.13307227e+03 4.97160791e+03 4.91491016e+03 5.19498242e+03 5.19361963e+03 4.97577002e+03 4.83733545e+03 4.81820264e+03 4.84436670e+03 4.79368555e+03 4.97255176e+03 4.92989941e+03 4.59329736e+03 4.49797021e+03 4.69131982e+03 4.89296045e+03 4.75820166e+03 4.57675098e+03 4.52591504e+03 4.47337354e+03 4.46632959e+03 4.46227832e+03 4.35963672e+03 4.30144287e+03 4.28322021e+03 4.24607764e+03 4.21847266e+03 4.17765479e+03 4.27321582e+03 4.21825439e+03 4.05198730e+03 4.00769189e+03 3.98759741e+03 4.04775952e+03 4.01647974e+03 3.91120630e+03 3.85647363e+03 3.74099902e+03 3.61450635e+03 3.76077393e+03 3.77036084e+03 3.53161182e+03 3.51517017e+03 3.67400659e+03 3.73128125e+03 3.58177783e+03 3.44985205e+03 3.41389453e+03 3.38334912e+03 3.29470435e+03 3.24676562e+03 3.23657031e+03 3.17837134e+03 3.24323242e+03 3.18485303e+03 3.05311597e+03 3.01089087e+03 2.89800293e+03 2.93573804e+03 3.05092407e+03 2.93880591e+03 2.82529761e+03 2.71653418e+03 2.63927002e+03 2.73958130e+03 2.74881079e+03 2.62524829e+03 2.50183813e+03 2.44729761e+03 2.45828638e+03 2.41477271e+03 2.45342554e+03 2.42652686e+03 2.28952930e+03 2.19993311e+03 2.15518872e+03 2.19343750e+03 2.16551636e+03 2.07445020e+03 2.00352625e+03 1.95956653e+03 1.91130078e+03 1.80695044e+03 1.81235815e+03 1.88168298e+03 1.79148315e+03 1.69753015e+03 1.61622754e+03 1.55885059e+03 1.60207861e+03 1.56432666e+03 1.46667590e+03 1.38346692e+03 1.33645801e+03 1.33126831e+03 1.27710645e+03 1.23165967e+03 1.15552832e+03 1.13010742e+03 1.14407703e+03 1.06360583e+03 1.00442645e+03 9.65947754e+02 9.07238892e+02 8.44093872e+02 7.99890991e+02 7.56298157e+02 7.03868835e+02 6.59494446e+02 5.97569946e+02 5.66611816e+02 5.51660645e+02 4.77747772e+02 4.15653442e+02 3.78600586e+02 3.31051727e+02 2.91873444e+02 2.40421173e+02 1.85244217e+02 1.43218094e+02 9.59723587e+01 4.72998810e+01 -4.09079969e-01 -4.81746597e+01 -9.52918777e+01 -1.43436218e+02 -1.89556839e+02 -2.30714310e+02 -2.87418793e+02 -3.53968445e+02 -3.94827209e+02 -4.28326508e+02 -4.61273560e+02 -5.14579773e+02 -5.94789673e+02 -6.40499573e+02 -6.72155212e+02 -6.99901123e+02 -7.39152893e+02 -8.11236633e+02 -8.60968689e+02 -9.25087769e+02 -9.61525330e+02 -9.84348083e+02 -1.04446606e+03 -1.08493616e+03 -1.16943201e+03 -1.22433252e+03 -1.23438782e+03 -1.27083508e+03 -1.31866711e+03 -1.37155383e+03 -1.37960706e+03 -1.45242590e+03 -1.58221448e+03 -1.60541760e+03 -1.61015405e+03 -1.61166260e+03 -1.64878137e+03 -1.79139197e+03 -1.84583667e+03 -1.83910205e+03 -1.84359143e+03 -1.88161438e+03 -1.98075110e+03 -2.03242810e+03 -2.11751880e+03 -2.15001294e+03 -2.14244727e+03 -2.16076196e+03 -2.20025879e+03 -2.35432983e+03 -2.41188794e+03 -2.38502222e+03 -2.38662915e+03 -2.42648462e+03 -2.57436035e+03 -2.62421509e+03 -2.52961548e+03 -2.57576489e+03 -2.78400244e+03 -2.80578052e+03 -2.70674146e+03 -2.74989502e+03 -2.93425635e+03 -3.00615210e+03 -2.93994214e+03 -2.91014404e+03 -2.96341235e+03 -3.17690088e+03 -3.19718701e+03 -3.14017139e+03 -3.22107349e+03 -3.24934351e+03 -3.22535376e+03 -3.25670508e+03 -3.38801123e+03 -3.34381274e+03 -3.43586743e+03 -3.64427100e+03 -3.58348218e+03 -3.64136865e+03 -3.69947949e+03 -3.66639209e+03 -3.70724634e+03 -3.74678442e+03 -3.78677612e+03 -3.73067188e+03 -3.72510010e+03 -3.86150659e+03 -3.97548828e+03 -4.12125146e+03 -4.02361670e+03 -3.94985889e+03 -4.09870947e+03 -4.13114941e+03 -4.30915283e+03 -4.33027783e+03 -4.22858008e+03 -4.19864795e+03 -4.20871631e+03 -4.35062012e+03 -4.40065967e+03 -4.53579688e+03 -4.55190283e+03 -4.48595166e+03 -4.51682764e+03 -4.41781006e+03 -4.56579688e+03 -4.84538818e+03 -4.83764014e+03 -4.73137305e+03 -4.64206201e+03 -4.65140137e+03 -4.91762207e+03 -5.00134326e+03 -4.90998730e+03 -4.79956104e+03 -4.83894287e+03 -4.98904932e+03 -5.00740918e+03 -5.17425732e+03 -5.19094092e+03 -5.07108154e+03 -5.12116162e+03 -5.12985840e+03 -5.28809961e+03 -5.32536523e+03 -5.12247705e+03 -5.16296045e+03 -5.48614062e+03 -5.42646191e+03 -5.15598047e+03 -5.34868311e+03 -5.66124805e+03 -5.63571533e+03 -5.53695410e+03 -5.41523193e+03 -5.40845508e+03 -5.74828955e+03 -5.79021436e+03 -5.65133447e+03 -5.52697949e+03 -5.53176074e+03 -5.70409961e+03 -5.75827734e+03 -5.80488477e+03 -5.67295898e+03 -5.79848584e+03 -6.11984961e+03 -5.98734424e+03 -5.95512158e+03 -5.93852295e+03 -5.90160400e+03 -5.96220654e+03 -5.97884570e+03 -6.04843848e+03 -6.05059326e+03 -6.03815088e+03 -5.89646387e+03 -6.00638330e+03 -6.34295557e+03 -6.11466211e+03 -5.87293457e+03 -6.11892725e+03 -6.31034375e+03 -6.50362695e+03 -6.40862500e+03 -6.25282617e+03 -6.31050488e+03 -6.34031494e+03 -6.21846680e+03 -6.20557080e+03 -6.46216211e+03 -6.44843457e+03 -6.33586768e+03 -6.30514990e+03 -6.15421289e+03 -6.41832227e+03 -6.78162646e+03 -6.63248096e+03 -6.50039795e+03 -6.34408789e+03 -6.31792188e+03 -6.69189258e+03 -6.83092480e+03 -6.64073535e+03 -6.43392480e+03 -6.41353906e+03 -6.52725342e+03 -6.55636035e+03 -6.82430566e+03 -6.76001123e+03 -6.57800146e+03 -6.61527881e+03 -6.59309668e+03 -6.77013525e+03 -6.79149951e+03 -6.64322656e+03 -6.72916260e+03 -6.73751953e+03 -6.62137109e+03 -6.47956543e+03 -6.63305420e+03 -6.98891797e+03 -6.87286768e+03 -6.74433936e+03 -6.60528076e+03 -6.65731885e+03 -7.04905713e+03 -7.02941895e+03 -6.81227344e+03 -6.64233057e+03 -6.61324561e+03 -6.73043750e+03 -6.74474854e+03 -6.85807861e+03 -6.67404688e+03 -6.80630078e+03 -7.04313330e+03 -6.86843848e+03 -6.92596777e+03 -6.97663281e+03 -6.82221045e+03 -6.89167822e+03 -6.89670410e+03 -6.68208350e+03 -6.66236670e+03 -6.91391846e+03 -6.92952832e+03 -6.91252148e+03 -6.88158008e+03 -6.67829785e+03 -6.62736572e+03 -6.84212207e+03 -6.84730859e+03 -7.04015967e+03 -6.95241943e+03 -6.64818652e+03 -6.80612646e+03 -6.95685254e+03 -6.87162061e+03 -6.75001855e+03 -6.66935645e+03 -6.81178857e+03 -6.80649512e+03 -6.75519092e+03 -6.60379102e+03 -6.70711963e+03 -7.08312158e+03 -6.92362744e+03 -6.72280225e+03 -6.57060303e+03 -6.55580029e+03 -6.90543066e+03 -6.87464844e+03 -6.71076514e+03 -6.50956641e+03 -6.41657910e+03 -6.59926123e+03 -6.75120703e+03 -6.91472803e+03 -6.73341455e+03 -6.42150000e+03 -6.49189453e+03 -6.54584473e+03 -6.78568750e+03 -6.63606250e+03 -6.42998340e+03 -6.59608838e+03 -6.59201367e+03 -6.50617041e+03 -6.32969922e+03 -6.42017822e+03 -6.73295459e+03 -6.66650195e+03 -6.41571387e+03 -6.24802539e+03 -6.25717920e+03 -6.56408740e+03 -6.58557373e+03 -6.38675586e+03 -6.18253760e+03 -6.15563330e+03 -6.29819678e+03 -6.26833398e+03 -6.43802002e+03 -6.43030176e+03 -6.18708105e+03 -6.02921680e+03 -6.08210352e+03 -6.41045312e+03 -6.28054443e+03 -6.03610596e+03 -6.15849854e+03 -6.15949658e+03 -5.93986670e+03 -5.85213232e+03 -6.04628223e+03 -5.99253320e+03 -5.82944385e+03 -6.10431494e+03 -6.11029688e+03 -5.94908789e+03 -5.89532715e+03 -5.83223242e+03 -5.81210596e+03 -5.65624121e+03 -5.56940674e+03 -5.83889111e+03 -5.87439795e+03 -5.59752588e+03 -5.43817578e+03 -5.62497949e+03 -5.82682617e+03 -5.76388281e+03 -5.51950391e+03 -5.34823291e+03 -5.52886523e+03 -5.65554297e+03 -5.53439600e+03 -5.40738232e+03 -5.24129443e+03 -5.10471924e+03 -5.31820654e+03 -5.56729541e+03 -5.38843896e+03 -5.11389795e+03 -5.06045654e+03 -5.27900293e+03 -5.33753320e+03 -5.15017090e+03 -4.95470605e+03 -4.87827393e+03 -4.93996973e+03 -4.96289893e+03 -5.08748926e+03 -5.05871387e+03 -4.85942090e+03 -4.79503906e+03 -4.80125635e+03 -4.86386182e+03 -4.69575391e+03 -4.59143018e+03 -4.78528467e+03 -4.75447217e+03 -4.56596680e+03 -4.40127344e+03 -4.48294824e+03 -4.70261475e+03 -4.45049658e+03 -4.26679297e+03 -4.35967139e+03 -4.39066309e+03 -4.37983789e+03 -4.29285840e+03 -4.34675537e+03 -4.34692383e+03 -4.16521924e+03 -3.99818213e+03 -3.96996729e+03 -4.17625146e+03 -4.07138232e+03 -3.91422705e+03 -3.94502368e+03 -3.90447852e+03 -3.86730713e+03 -3.80285864e+03 -3.80596118e+03 -3.75303931e+03 -3.63628101e+03 -3.68923730e+03 -3.65542358e+03 -3.63007666e+03 -3.60334326e+03 -3.50301465e+03 -3.44339990e+03 -3.30733521e+03 -3.28514600e+03 -3.43454443e+03 -3.43728979e+03 -3.20904907e+03 -3.06910571e+03 -3.14849561e+03 -3.22743335e+03 -3.16686987e+03 -3.02142188e+03 -2.87241846e+03 -2.94594238e+03 -2.98700977e+03 -2.86353394e+03 -2.88706104e+03 -2.81107690e+03 -2.65101831e+03 -2.67241260e+03 -2.73105762e+03 -2.66113794e+03 -2.49575488e+03 -2.41408594e+03 -2.50802417e+03 -2.52067651e+03 -2.39846851e+03 -2.26866626e+03 -2.21036035e+03 -2.29515503e+03 -2.24634106e+03 -2.12661621e+03 -2.11661963e+03 -2.07500366e+03 -1.99896240e+03 -1.94823022e+03 -1.97694946e+03 -1.89991467e+03 -1.78298608e+03 -1.81763171e+03 -1.78657336e+03 -1.72049939e+03 -1.63501733e+03 -1.55870166e+03 -1.58742981e+03 -1.51830762e+03 -1.42134204e+03 -1.41716870e+03 -1.39885583e+03 -1.41638049e+03 -1.34066516e+03 -1.22424133e+03 -1.19993665e+03 -1.19657007e+03 -1.21271289e+03 -1.06442285e+03 -9.02391174e+02 -1.02918457e+03 -3.22572095e+03 -1.78577576e+03 -522877888. -1.22315000e+04 -18419674. 5.39781350e+06 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. 0. 0. 0. 2.57731494e+03 1.77520544e+03 9.83858032e+02 1.02794922e+03 1.01481793e+03 1.03339209e+03 1.16814514e+03 1.33284644e+03 1.19727747e+03 1.24580859e+03 1.37238245e+03 1.29976770e+03 1.34379175e+03 1.52035901e+03 1.60314307e+03 1.58132373e+03 1.59977344e+03 1.64633142e+03 1.68841101e+03 1.74367517e+03 1.83727161e+03 1.90018811e+03 1.88198254e+03 1.90146252e+03 1.97992883e+03 2.02959485e+03 2.04836426e+03 2.08671875e+03 2.15886133e+03 2.20302783e+03 2.28064819e+03 2.31553052e+03 2.27418896e+03 2.35189819e+03 2.47611548e+03 2.54079419e+03 2.57552319e+03 2.51974292e+03 2.53496558e+03 2.66105078e+03 2.72321191e+03 2.72967188e+03 2.75007617e+03 2.78922339e+03 2.88557495e+03 2.97619092e+03 2.98442847e+03 2.94072656e+03 2.97301660e+03 3.16424194e+03 3.22254297e+03 3.10115845e+03 3.12924097e+03 3.25621997e+03 3.32960059e+03 3.41589502e+03 3.40809229e+03 3.33192896e+03 3.39265479e+03 3.53434741e+03 3.59782690e+03 3.58100220e+03 3.56373218e+03 3.66409717e+03 3.78143359e+03 3.75397778e+03 3.74305493e+03 3.75837085e+03 3.84997046e+03 3.96287134e+03 3.97731592e+03 4.03501929e+03 4.02800903e+03 3.96857886e+03 4.07225146e+03 4.16821094e+03 4.17106396e+03 4.22933252e+03 4.22633105e+03 4.25643018e+03 4.40533008e+03 4.43501270e+03 4.30991309e+03 4.34152637e+03 4.49312646e+03 4.56513672e+03 4.58987402e+03 4.54498193e+03 4.57429346e+03 4.64803125e+03 4.73122998e+03 4.75209961e+03 4.65743750e+03 4.74040576e+03 4.90618701e+03 4.94916895e+03 4.93269434e+03 4.84036230e+03 4.86177539e+03 5.06239551e+03 5.06598486e+03 4.98390186e+03 5.01614258e+03 5.08172119e+03 5.21463379e+03 5.22681348e+03 5.21677490e+03 5.24792529e+03 5.27983154e+03 5.36552930e+03 5.37404004e+03 5.31012988e+03 5.35979102e+03 5.42669238e+03 5.41812646e+03 5.49152783e+03 5.55712207e+03 5.55003320e+03 5.57592627e+03 5.54882764e+03 5.56958447e+03 5.66828711e+03 5.73831934e+03 5.70723340e+03 5.70846582e+03 5.70826562e+03 5.73346631e+03 5.81332666e+03 5.81170850e+03 5.79168408e+03 5.88845068e+03 6.04976953e+03 6.04065674e+03 5.88761963e+03 5.93274707e+03 6.04715039e+03 5.98512988e+03 5.96061426e+03 5.95679150e+03 6.05579199e+03 6.15078906e+03 6.24199414e+03 6.19654492e+03 6.10157861e+03 6.06962305e+03 6.21097656e+03 6.28761621e+03 6.29102734e+03 6.29073975e+03 6.20892578e+03 6.32525586e+03 6.43608789e+03 6.41837402e+03 6.27266260e+03 6.21137549e+03 6.38238525e+03 6.56913086e+03 6.49044092e+03 6.24627051e+03 6.36639502e+03 6.58998438e+03 6.53728516e+03 6.45734619e+03 6.46461084e+03 6.53371387e+03 6.54091943e+03 6.57488574e+03 6.57767920e+03 6.46056885e+03 6.65911621e+03 6.71148047e+03 6.62886426e+03 6.64483789e+03 6.68643262e+03 6.50816846e+03 6.61520605e+03 6.68619629e+03 6.73815723e+03 6.82362402e+03 6.54730371e+03 6.58239795e+03 6.84440918e+03 6.72095361e+03 6.59041943e+03 6.71483203e+03 6.82233398e+03 6.76089844e+03 6.74180957e+03 6.75036377e+03 6.69404395e+03 6.73402637e+03 6.84068848e+03 6.86993262e+03 6.67327246e+03 6.78564990e+03 6.92138867e+03 6.92676172e+03 6.80373389e+03 6.69517480e+03 6.76451514e+03 6.93228955e+03 6.80498145e+03 6.75433740e+03 6.88300439e+03 6.74321582e+03 6.82088623e+03 6.98956592e+03 6.83766211e+03 6.78003662e+03 6.83600391e+03 6.85284326e+03 6.81497705e+03 6.88025049e+03 6.85313672e+03 6.72791748e+03 6.76571729e+03 6.85525586e+03 6.84481445e+03 6.72017822e+03 6.83004932e+03 6.94917139e+03 6.85540820e+03 6.95004004e+03 6.81102588e+03 6.63909668e+03 6.78375049e+03 6.83529053e+03 6.79112939e+03 6.66845020e+03 6.57765381e+03 6.78350635e+03 6.87158203e+03 6.77648828e+03 6.64366895e+03 6.79028564e+03 6.81175244e+03 6.67672998e+03 6.57459277e+03 6.76706152e+03 6.71745996e+03 6.55992871e+03 6.73121387e+03 6.63192188e+03 6.55764551e+03 6.65360498e+03 6.56326562e+03 6.52888574e+03 6.59234033e+03 6.51876904e+03 6.46372021e+03 6.57444385e+03 6.62567432e+03 6.60871191e+03 6.36741699e+03 6.36169336e+03 6.47896826e+03 6.41418213e+03 6.45964111e+03 6.41306641e+03 6.35666162e+03 6.34989502e+03 6.38862793e+03 6.47020166e+03 6.32414062e+03 6.13739307e+03 6.28771045e+03 6.49938184e+03 6.22436768e+03 6.09014795e+03 6.16516406e+03 6.13061133e+03 6.21838379e+03 6.20095801e+03 6.07308838e+03 6.06258789e+03 6.10586475e+03 6.10924121e+03 6.07712061e+03 5.97353174e+03 6.05165527e+03 6.08066357e+03 5.82851465e+03 5.84728418e+03 5.90352979e+03 5.83178418e+03 5.91927832e+03 5.83878467e+03 5.75454980e+03 5.82047510e+03 5.68596045e+03 5.69696680e+03 5.87207568e+03 5.73595898e+03 5.59736035e+03 5.52922021e+03 5.46605859e+03 5.58160498e+03 5.62634082e+03 5.48268945e+03 5.46539844e+03 5.51458447e+03 5.47903369e+03 5.41423584e+03 5.29047119e+03 5.25275732e+03 5.29731396e+03 5.32084863e+03 5.31951172e+03 5.14435254e+03 5.08681006e+03 5.15869922e+03 5.14614600e+03 5.11962549e+03 5.09854834e+03 4.98212988e+03 4.92991992e+03 5.08290869e+03 5.06458398e+03 4.86576221e+03 4.73467920e+03 4.73678076e+03 4.80112061e+03 4.74805908e+03 4.64857471e+03 4.68336328e+03 4.68385889e+03 4.64522168e+03 4.64667578e+03 4.54862305e+03 4.46808057e+03 4.50418066e+03 4.50311963e+03 4.38562598e+03 4.27080664e+03 4.30324365e+03 4.30356348e+03 4.25477344e+03 4.27368115e+03 4.18170361e+03 4.07684277e+03 4.07041748e+03 4.14325293e+03 4.05104517e+03 3.93153369e+03 3.95456836e+03 3.91167139e+03 3.83550903e+03 3.83084521e+03 3.74703223e+03 3.70607251e+03 3.71055981e+03 3.70000708e+03 3.70304053e+03 3.58738794e+03 3.53484570e+03 3.50833911e+03 3.44720801e+03 3.39723218e+03 3.32833472e+03 3.34183008e+03 3.31248682e+03 3.23524438e+03 3.16556396e+03 3.13474414e+03 3.15859692e+03 3.14275757e+03 3.10153003e+03 3.00354126e+03 2.94107568e+03 2.89789380e+03 2.81573218e+03 2.80753198e+03 2.78964453e+03 2.74029688e+03 2.69635962e+03 2.61642773e+03 2.56647217e+03 2.56711743e+03 2.56915503e+03 2.52811523e+03 2.42041260e+03 2.33604419e+03 2.32674878e+03 2.29391284e+03 2.23548022e+03 2.21248975e+03 2.18251514e+03 2.09895654e+03 2.04098669e+03 1.98703894e+03 1.94779150e+03 1.97342126e+03 1.93070117e+03 1.82701624e+03 1.79665735e+03 1.73872510e+03 1.65504407e+03 1.66433679e+03 1.63240613e+03 1.53947485e+03 1.49640552e+03 1.44828308e+03 1.38854224e+03 1.37804468e+03 1.36433398e+03 1.28793848e+03 1.22613403e+03 1.18457104e+03 1.13435547e+03 1.09091724e+03 1.04078210e+03 9.94590454e+02 9.50380737e+02 8.95273621e+02 8.52782715e+02 8.14349121e+02 7.55001160e+02 7.15041199e+02 6.76957703e+02 6.13918640e+02 5.59562866e+02 5.15414124e+02 4.77106598e+02 4.36341248e+02 3.87095734e+02 3.28335541e+02 2.74055969e+02 2.33126053e+02 1.91860123e+02 1.45837646e+02 9.44249420e+01 4.50626564e+01 -2.87130213e+00 -5.08166122e+01 -9.78537598e+01 -1.45810013e+02 -1.92663132e+02 -2.38206894e+02 -2.91922150e+02 -3.35771698e+02 -3.71198456e+02 -4.32198639e+02 -4.97336548e+02 -5.29744263e+02 -5.63756775e+02 -6.15758728e+02 -6.67287537e+02 -7.23865479e+02 -7.71904236e+02 -8.12799377e+02 -8.46105530e+02 -8.98056030e+02 -9.58431580e+02 -9.99313232e+02 -1.06020789e+03 -1.10629016e+03 -1.14024158e+03 -1.18139868e+03 -1.24448804e+03 -1.29455261e+03 -1.32295728e+03 -1.39221606e+03 -1.44809058e+03 -1.46351196e+03 -1.48715906e+03 -1.53750427e+03 -1.60226514e+03 -1.69077832e+03 -1.73230298e+03 -1.72899622e+03 -1.77230090e+03 -1.82159973e+03 -1.88979724e+03 -1.96604919e+03 -1.98486218e+03 -1.99030151e+03 -2.08710132e+03 -2.14218579e+03 -2.13475830e+03 -2.24579590e+03 -2.29478931e+03 -2.27464185e+03 -2.33202441e+03 -2.34396240e+03 -2.38505200e+03 -2.52030908e+03 -2.54878906e+03 -2.55066333e+03 -2.64361255e+03 -2.66239258e+03 -2.62940210e+03 -2.69428589e+03 -2.78802686e+03 -2.83034570e+03 -2.88703784e+03 -2.89943970e+03 -2.92017480e+03 -3.00800366e+03 -3.07211011e+03 -3.20122388e+03 -3.17572949e+03 -3.08489844e+03 -3.14937476e+03 -3.23314429e+03 -3.32162891e+03 -3.40166797e+03 -3.37365649e+03 -3.33525659e+03 -3.46162695e+03 -3.55657910e+03 -3.54276929e+03 -3.59133032e+03 -3.63461523e+03 -3.62063525e+03 -3.72229199e+03 -3.78170312e+03 -3.73513184e+03 -3.87927197e+03 -3.96407007e+03 -3.90646729e+03 -3.92580444e+03 -3.87117627e+03 -3.92018237e+03 -4.08152319e+03 -4.26095020e+03 -4.23296729e+03 -4.04084302e+03 -4.10187207e+03 -4.29616992e+03 -4.31204834e+03 -4.30288965e+03 -4.35861963e+03 -4.38312109e+03 -4.44531982e+03 -4.48685889e+03 -4.52601221e+03 -4.54700586e+03 -4.57153955e+03 -4.68541406e+03 -4.65701660e+03 -4.61178027e+03 -4.66291406e+03 -4.72027881e+03 -4.81547412e+03 -4.93894678e+03 -4.87040088e+03 -4.79700879e+03 -4.88465820e+03 -4.97021143e+03 -5.13742725e+03 -5.12782764e+03 -4.95155469e+03 -5.00383643e+03 -5.12542432e+03 -5.21990332e+03 -5.33118750e+03 -5.25654492e+03 -5.19119873e+03 -5.22802051e+03 -5.24009961e+03 -5.24319092e+03 -5.40523145e+03 -5.54485693e+03 -5.44947412e+03 -5.38540283e+03 -5.36190088e+03 -5.42828955e+03 -5.66263428e+03 -5.67087207e+03 -5.62339453e+03 -5.58921680e+03 -5.51771094e+03 -5.61385107e+03 -5.68456299e+03 -5.82998242e+03 -5.89104541e+03 -5.70447559e+03 -5.69960986e+03 -5.79517090e+03 -5.87722363e+03 -5.89549170e+03 -5.98118994e+03 -5.99856299e+03 -5.88810449e+03 -5.93616748e+03 -5.98798730e+03 -5.99940918e+03 -6.06033398e+03 -6.13491309e+03 -6.11422119e+03 -6.06546484e+03 -6.05186963e+03 -6.17584033e+03 -6.30016748e+03 -6.21719580e+03 -6.15678760e+03 -6.16220898e+03 -6.23260498e+03 -6.22957861e+03 -6.41979834e+03 -6.41511768e+03 -6.25776709e+03 -6.36121387e+03 -6.36131738e+03 -6.37753369e+03 -6.53522900e+03 -6.50553125e+03 -6.44440283e+03 -6.47917627e+03 -6.53298633e+03 -6.91637305e+03 -6.35920752e+03 -5.94857666e+03 -9.01762109e+03 -8.38649414e+03 -1.48310088e+04 -8.74486641e+04 20270600. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.10336172e+04 -1.32917529e+04 -8.11523193e+03 -7.27760449e+03 -7.19726514e+03 -8.80191211e+03 -7.25979639e+03 -8.58106934e+03 -6.47899072e+03 -6.35531982e+03 -6.91531543e+03 -6.82000879e+03 -6.64598340e+03 -6.79573193e+03 -6.89988086e+03 -6.99310449e+03 -6.83358594e+03 -6.55352197e+03 -6.66538721e+03 -6.83299512e+03 -6.71719434e+03 -6.57149268e+03 -6.50878906e+03 -6.70841797e+03 -7.01972266e+03 -6.91851270e+03 -6.53345361e+03 -6.27288086e+03 -6.44055518e+03 -6.73108887e+03 -6.88424121e+03 -6.74817480e+03 -6.43490088e+03 -6.48043555e+03 -6.56775537e+03 -6.70558398e+03 -6.66021289e+03 -6.29471631e+03 -6.33659863e+03 -6.65249365e+03 -6.56006982e+03 -6.36350635e+03 -6.42370508e+03 -6.44634863e+03 -6.50744482e+03 -6.50573438e+03 -6.25072852e+03 -6.10671582e+03 -6.38687646e+03 -6.55321533e+03 -6.42730615e+03 -6.18227197e+03 -5.99628467e+03 -6.28573535e+03 -6.51996094e+03 -6.31991602e+03 -6.08511816e+03 -5.85372949e+03 -5.96620557e+03 -6.25231543e+03 -6.33857568e+03 -6.21645801e+03 -6.04853760e+03 -6.05720703e+03 -5.95691406e+03 -5.95488184e+03 -5.97124170e+03 -5.80548975e+03 -5.87865430e+03 -6.03370312e+03 -5.93422363e+03 -5.66225391e+03 -5.60150537e+03 -5.84410986e+03 -6.01622559e+03 -5.90346094e+03 -5.67428125e+03 -5.49479785e+03 -5.51758057e+03 -5.62788623e+03 -5.84462109e+03 -5.72461475e+03 -5.36857520e+03 -5.42994141e+03 -5.49948145e+03 -5.52587793e+03 -5.58812549e+03 -5.33880322e+03 -5.32778955e+03 -5.43038379e+03 -5.36431934e+03 -5.27146484e+03 -5.18474609e+03 -5.21730908e+03 -5.28290918e+03 -5.23647217e+03 -5.05906299e+03 -4.98428418e+03 -5.11000732e+03 -5.16798242e+03 -5.12017188e+03 -5.00610400e+03 -4.82895605e+03 -4.85068604e+03 -4.96915967e+03 -4.97404004e+03 -4.82967676e+03 -4.60560791e+03 -4.59911572e+03 -4.79626221e+03 -4.87470117e+03 -4.70766553e+03 -4.49126953e+03 -4.49465820e+03 -4.60523877e+03 -4.53629883e+03 -4.38985498e+03 -4.32545312e+03 -4.44622559e+03 -4.46531299e+03 -4.32249756e+03 -4.22463379e+03 -4.12018701e+03 -4.20764844e+03 -4.36934473e+03 -4.21689746e+03 -4.04884644e+03 -3.97091772e+03 -3.96318018e+03 -3.99780444e+03 -4.02632788e+03 -3.95015991e+03 -3.74082715e+03 -3.72226172e+03 -3.85142749e+03 -3.85268359e+03 -3.72820264e+03 -3.59724829e+03 -3.61205591e+03 -3.64564233e+03 -3.60012866e+03 -3.49765430e+03 -3.34745044e+03 -3.33347852e+03 -3.43920215e+03 -3.40776465e+03 -3.29460156e+03 -3.17337891e+03 -3.16652515e+03 -3.20436548e+03 -3.21973291e+03 -3.16525464e+03 -2.95944189e+03 -2.94238794e+03 -2.97756079e+03 -2.92143970e+03 -2.87950537e+03 -2.80320874e+03 -2.77068286e+03 -2.74827930e+03 -2.68980786e+03 -2.61642334e+03 -2.56570190e+03 -2.58920630e+03 -2.58548340e+03 -2.50888477e+03 -2.38294434e+03 -2.31283984e+03 -2.34618701e+03 -2.37889844e+03 -2.32258130e+03 -2.20158179e+03 -2.08873071e+03 -2.03179968e+03 -2.06991846e+03 -2.10778931e+03 -2.00852417e+03 -1.86512756e+03 -1.84421716e+03 -1.85944836e+03 -1.82426160e+03 -1.77378601e+03 -1.69697729e+03 -1.64855884e+03 -1.60673926e+03 -1.54343579e+03 -1.49352881e+03 -1.46379858e+03 -1.43024426e+03 -1.38093091e+03 -1.33218848e+03 -1.27043542e+03 -1.21483850e+03 -1.19504736e+03 -1.16321228e+03 -1.10871338e+03 -1.02891077e+03 -9.63406494e+02 -9.57798523e+02 -9.29161255e+02 -8.66983643e+02 -8.09072693e+02 -7.37497253e+02 -6.90303406e+02 -6.75312988e+02 -6.47355103e+02 -5.85347107e+02 -5.12331421e+02 -4.64131104e+02 -4.30386749e+02 -3.87005707e+02 -3.35867828e+02 -2.87137390e+02 -2.41392639e+02 -1.90481262e+02 -1.40487518e+02 -9.13859482e+01 -4.44322205e+01 2.04155517e+00 4.99866333e+01 1.00019981e+02 1.48359741e+02 1.86882599e+02 2.35996597e+02 2.89105438e+02 3.37013977e+02 3.88871765e+02 4.30086609e+02 4.89411194e+02 5.36816223e+02 5.55185547e+02 5.94344910e+02 6.56724731e+02 7.36221191e+02 8.07898071e+02 8.35836426e+02 8.34271423e+02 8.58008423e+02 9.22610168e+02 1.02700732e+03 1.10688318e+03 1.12839490e+03 1.11000696e+03 1.14488892e+03 1.28206714e+03 1.32430945e+03 1.29820325e+03 1.35278711e+03 1.41961609e+03 1.46377295e+03 1.55667444e+03 1.56909192e+03 1.55762830e+03 1.64453247e+03 1.66217944e+03 1.74760657e+03 1.84748376e+03 1.80077686e+03 1.87273877e+03 1.98820020e+03 1.99485876e+03 2.01598950e+03 2.06302173e+03 2.12567480e+03 2.16200952e+03 2.20106445e+03 2.19484106e+03 2.23274243e+03 2.39694043e+03 2.51174854e+03 2.49091870e+03 2.41716040e+03 2.41695410e+03 2.50340112e+03 2.65456982e+03 2.78364404e+03 2.75202173e+03 2.66776953e+03 2.73966602e+03 2.87425513e+03 2.87644849e+03 2.88625684e+03 2.95314600e+03 2.96986279e+03 3.00326978e+03 3.18477100e+03 3.18018066e+03 3.09296094e+03 3.18352417e+03 3.17359790e+03 3.31865381e+03 3.44338721e+03 3.34598975e+03 3.48624023e+03 3.50735254e+03 3.40223682e+03 3.54136523e+03 3.48514917e+03 3.59698047e+03 3.88900903e+03 3.71730322e+03 3.57258252e+03 3.68008057e+03 3.89239014e+03 4.08381885e+03 4.04772095e+03 3.83585474e+03 3.76539941e+03 3.93244751e+03 4.14299023e+03 4.33759326e+03 4.26108643e+03 4.04555591e+03 4.08677710e+03 4.27015283e+03 4.36368066e+03 4.30334961e+03 4.29820264e+03 4.38178760e+03 4.43084814e+03 4.61581494e+03 4.63657324e+03 4.43310400e+03 4.46063965e+03 4.58728125e+03 4.63067139e+03 4.71469775e+03 4.73139746e+03 4.87974121e+03 4.83194922e+03 4.68040283e+03 4.80225000e+03 4.73996631e+03 4.92705664e+03 5.28723145e+03 4.99911279e+03 4.72562207e+03 4.89460498e+03 5.18704492e+03 5.37111377e+03 5.38786963e+03 5.11446338e+03 4.96159326e+03 5.08840479e+03 5.32908643e+03 5.59589502e+03 5.52605469e+03 5.20308643e+03 5.16948096e+03 5.41457080e+03 5.48863330e+03 5.64795850e+03 5.67983984e+03 5.36691211e+03 5.39474902e+03 5.67982227e+03 5.76290771e+03 5.62808789e+03 5.62437158e+03 5.65739600e+03 5.62280518e+03 5.90901953e+03 5.93489014e+03 5.70844141e+03 5.67398535e+03 5.78025977e+03 5.86956592e+03 5.88629688e+03 5.85891992e+03 6.07257178e+03 6.15658447e+03 5.98369775e+03 5.87662695e+03 5.75706494e+03 6.01052246e+03 6.41953711e+03 6.30642090e+03 5.97497705e+03 5.85455469e+03 6.11210400e+03 6.48203906e+03 6.27154248e+03 5.94506543e+03 6.06913428e+03 6.26417139e+03 6.43611035e+03 6.68880273e+03 6.48454785e+03 6.17085840e+03 6.08785205e+03 6.28519922e+03 6.49829688e+03 6.55362158e+03 6.48565186e+03 6.40475928e+03 6.38544580e+03 6.57499219e+03 6.55970898e+03 6.37514014e+03 6.36702002e+03 6.38074072e+03 6.73211377e+03 6.76147314e+03 6.54110645e+03 6.59388379e+03 6.66123389e+03 6.79338867e+03 6.58109424e+03 6.28371436e+03 6.64559717e+03 6.99613184e+03 6.80539258e+03 6.48527783e+03 6.56346924e+03 6.91075537e+03 6.88409082e+03 6.75020068e+03 6.76074023e+03 6.55278711e+03 6.59242480e+03 6.93954248e+03 6.89505762e+03 6.64416064e+03 6.48743896e+03 6.50099512e+03 6.83052979e+03 7.16892676e+03 6.83937891e+03 6.63625439e+03 6.84108936e+03 6.78363770e+03 7.03239990e+03 6.97519385e+03 6.62596729e+03 6.61989551e+03 6.82539990e+03 6.84088232e+03 6.86022998e+03 6839. 6.98979102e+03 7.12794629e+03 7.25963477e+03 7.07139746e+03 6.48704395e+03 7.15386572e+03 9.49044922e+03 9.44505859e+03 1.03906250e+04 9.55453418e+03 1.01931445e+04 1.18359209e+04 1.75669570e+04 2.00014980e+04 6.60897950e+06 47075812. 2126702. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.86402012e+04 1.47679941e+04 1.03802920e+04 1.05580664e+04 9.56497559e+03 9.59707910e+03 9.52384668e+03 9.31224414e+03 9.29209473e+03 9.24259180e+03 6.58058838e+03 7.16352637e+03 6.50028320e+03 6.18950000e+03 6.08048486e+03 5.92916064e+03 6.09303760e+03 6.09972607e+03 5.83126221e+03 5.78307129e+03 6.04557275e+03 6.06301855e+03 5.87496045e+03 5.81509863e+03 5.80735254e+03 5.81018555e+03 5.75286670e+03 5.70776904e+03 5.68459717e+03 5.65486523e+03 5.56663867e+03 5.53055664e+03 5.66920264e+03 5.66847363e+03 5.51693213e+03 5.48687695e+03 5.47935254e+03 5.46872217e+03 5.40825146e+03 5.36792285e+03 5.36013721e+03 5.19924805e+03 5.14208252e+03 5.23191064e+03 5.19449463e+03 5.36868311e+03 5.36731250e+03 5.13512695e+03 4.96085986e+03 4.91151270e+03 5.19601660e+03 5.19586865e+03 4.97803027e+03 4.84599316e+03 4.83916455e+03 4.85980127e+03 4.78595264e+03 4.93590039e+03 4.89542676e+03 4.58658789e+03 4.52506006e+03 4.71450195e+03 4.85797949e+03 4.70553564e+03 4.58000098e+03 4.54481934e+03 4.48466309e+03 4.40248633e+03 4.40396973e+03 4.37424316e+03 4.30932080e+03 4.27980518e+03 4.25008838e+03 4.25470068e+03 4.20883203e+03 4.25882715e+03 4.19193311e+03 4.03907129e+03 4.06669580e+03 4.03490625e+03 4.00591772e+03 3.98711719e+03 3.91011548e+03 3.85963940e+03 3.74844165e+03 3.62111768e+03 3.75768652e+03 3.77090405e+03 3.54114307e+03 3.52361133e+03 3.68645068e+03 3.73665063e+03 3.58142529e+03 3.45361963e+03 3.39448096e+03 3.35311011e+03 3.28678564e+03 3.23170996e+03 3.26249683e+03 3.20418188e+03 3.23662378e+03 3.16865991e+03 3.04187158e+03 3.05070483e+03 2.93270215e+03 2.90432349e+03 3.00931348e+03 2.93951709e+03 2.82488110e+03 2.71958350e+03 2.64157568e+03 2.73601074e+03 2.74802148e+03 2.62032812e+03 2.49498877e+03 2.45159424e+03 2.46546094e+03 2.41802930e+03 2.45096533e+03 2.42298145e+03 2.29438940e+03 2.20246045e+03 2.15827539e+03 2.20270874e+03 2.16583789e+03 2.06754126e+03 1.99444275e+03 1.95055603e+03 1.93328174e+03 1.83365942e+03 1.79516345e+03 1.85958276e+03 1.79618250e+03 1.69668750e+03 1.60868665e+03 1.55934961e+03 1.60476904e+03 1.56507715e+03 1.47286194e+03 1.38294641e+03 1.32925500e+03 1.32864014e+03 1.27896326e+03 1.23214502e+03 1.15621692e+03 1.13096533e+03 1.14181702e+03 1.06335022e+03 1.00731494e+03 9.64437805e+02 9.06347534e+02 8.46497314e+02 8.00727173e+02 7.64428955e+02 7.14892212e+02 6.63051147e+02 5.96661255e+02 5.61390930e+02 5.48207703e+02 4.77373108e+02 4.15468323e+02 3.79065521e+02 3.30945801e+02 2.93416138e+02 2.39426575e+02 1.84084702e+02 1.45260666e+02 9.71819153e+01 4.72105446e+01 -8.88646781e-01 -4.85792580e+01 -9.61802673e+01 -1.44260330e+02 -1.91462357e+02 -2.31990250e+02 -2.86332001e+02 -3.52615173e+02 -3.94360046e+02 -4.28280396e+02 -4.60270050e+02 -5.13156067e+02 -5.94377930e+02 -6.40615417e+02 -6.72639893e+02 -7.01460999e+02 -7.39920837e+02 -8.10037354e+02 -8.59074646e+02 -9.26662109e+02 -9.53066162e+02 -9.73184692e+02 -1.05263770e+03 -1.09587378e+03 -1.16734717e+03 -1.21011206e+03 -1.22533655e+03 -1.27218811e+03 -1.31599829e+03 -1.38391528e+03 -1.39356628e+03 -1.45402466e+03 -1.58374585e+03 -1.60462927e+03 -1.60940100e+03 -1.61190454e+03 -1.64963757e+03 -1.79342725e+03 -1.84999854e+03 -1.84095703e+03 -1.83828967e+03 -1.87943774e+03 -1.98249670e+03 -2.03561560e+03 -2.13057983e+03 -2.14529688e+03 -2.13888452e+03 -2.16260767e+03 -2.19543726e+03 -2.35576758e+03 -2.39830396e+03 -2.37105005e+03 -2.39508008e+03 -2.44036279e+03 -2.56567993e+03 -2.61523389e+03 -2.54520093e+03 -2.57896143e+03 -2.76618408e+03 -2.81160669e+03 -2.71492114e+03 -2.74297021e+03 -2.93706860e+03 -2.99751489e+03 -2.94365088e+03 -2.91539404e+03 -2.95869824e+03 -3.18129907e+03 -3.19940967e+03 -3.13979199e+03 -3.19563672e+03 -3.23116333e+03 -3.28745337e+03 -3.31006836e+03 -3.34807153e+03 -3.31343481e+03 -3.43660742e+03 -3.67842505e+03 -3.60233179e+03 -3.59916577e+03 -3.67343335e+03 -3.67584033e+03 -3.71398022e+03 -3.75504565e+03 -3.78620532e+03 -3.72801733e+03 -3.70663892e+03 -3.85589868e+03 -3.99245605e+03 -4.13829395e+03 -4.02933569e+03 -3.92250586e+03 -4.07716479e+03 -4.16277490e+03 -4.33504590e+03 -4.29882715e+03 -4.20080029e+03 -4.22697559e+03 -4.22287500e+03 -4.35249756e+03 -4.41714893e+03 -4.53772705e+03 -4.54400928e+03 -4.48686572e+03 -4.47650342e+03 -4.37392383e+03 -4.58898193e+03 -4.90133789e+03 -4.83455615e+03 -4.72878613e+03 -4.64647559e+03 -4.60542822e+03 -4.87925000e+03 -5.05994727e+03 -4.93777686e+03 -4.79841504e+03 -4.81057080e+03 -4.98746973e+03 -5.01020557e+03 -5.18711133e+03 -5.19301416e+03 -5.06807373e+03 -5.13833252e+03 -5.14979053e+03 -5.28365332e+03 -5.30341406e+03 -5.11722607e+03 -5.17312598e+03 -5.47903320e+03 -5.40537842e+03 -5.17148340e+03 -5.36280908e+03 -5.68921094e+03 -5.62137354e+03 -5.50905127e+03 -5.40315186e+03 -5.42000342e+03 -5.76776318e+03 -5.79414844e+03 -5.64554199e+03 -5.51845557e+03 -5.53487500e+03 -5.72631396e+03 -5.75136084e+03 -5.76950879e+03 -5.66350244e+03 -5.79968262e+03 -6.07803613e+03 -5.93435303e+03 -5.99877197e+03 -5.96415723e+03 -5.87065576e+03 -5.97320068e+03 -6.02385205e+03 -6.03412061e+03 -6.03002148e+03 -6.00020996e+03 -5.88187744e+03 -6.06264746e+03 -6.45107764e+03 -6.16099023e+03 -5.90110645e+03 -6.12545361e+03 -6.25805322e+03 -6.48755811e+03 -6.37623779e+03 -6.21990674e+03 -6.39316309e+03 -6.36961768e+03 -6.16535303e+03 -6.12468018e+03 -6.50611426e+03 -6.54218311e+03 -6.36172119e+03 -6.29895557e+03 -6.08427295e+03 -6.39465283e+03 -6.81678369e+03 -6.62251660e+03 -6.47131885e+03 -6.31564111e+03 -6.26399854e+03 -6.65264111e+03 -6.86136133e+03 -6.68146973e+03 -6.42263770e+03 -6.35797363e+03 -6.52599756e+03 -6.63105029e+03 -6.83128662e+03 -6.71372852e+03 -6.52890039e+03 -6.68329688e+03 -6.65737500e+03 -6.78831250e+03 -6.76036572e+03 -6.63780762e+03 -6.71493896e+03 -6.68838574e+03 -6.67423633e+03 -6.50177686e+03 -6.62513379e+03 -7.08909277e+03 -6.92735205e+03 -6.66437012e+03 -6.53669824e+03 -6.59878809e+03 -7.03433691e+03 -6.98142139e+03 -6.82638672e+03 -6.64336084e+03 -6.62715234e+03 -6.82641016e+03 -6.84123389e+03 -6.82881543e+03 -6.68639795e+03 -6.81182373e+03 -7.06951074e+03 -6.90289844e+03 -6.95539258e+03 -6.96513037e+03 -6.84193018e+03 -6.78181885e+03 -6.79910986e+03 -6.78364258e+03 -6.76982568e+03 -6.83121289e+03 -6.83422656e+03 -6.99770605e+03 -6.95805371e+03 -6.64343750e+03 -6.56957178e+03 -6.75365283e+03 -6.89914111e+03 -7.10938184e+03 -6.86308984e+03 -6.58780078e+03 -6.87361230e+03 -7.03590771e+03 -6.86722803e+03 -6.71225146e+03 -6.67836621e+03 -6.77593604e+03 -6.81120605e+03 -6.74348779e+03 -6.52828271e+03 -6.70566406e+03 -7.11198926e+03 -6.86276709e+03 -6.78864990e+03 -6.60889844e+03 -6.51632373e+03 -6.92899658e+03 -6.87981494e+03 -6.70771387e+03 -6.52704004e+03 -6.36858447e+03 -6.57881201e+03 -6.73984375e+03 -6.95390332e+03 -6.65475977e+03 -6.33179980e+03 -6.56083350e+03 -6.61207959e+03 -6.83061670e+03 -6.68333789e+03 -6.42675000e+03 -6.59802002e+03 -6.59152686e+03 -6.42505518e+03 -6.23980127e+03 -6.46370166e+03 -6.75500732e+03 -6.62204590e+03 -6.45695654e+03 -6.29449512e+03 -6.27462891e+03 -6.57188574e+03 -6.53971875e+03 -6.34813770e+03 -6.20314160e+03 -6.10098047e+03 -6.27616357e+03 -6.29071436e+03 -6.42141406e+03 -6.44222168e+03 -6.20613965e+03 -6.03399854e+03 -6.08308545e+03 -6.38755859e+03 -6.23897607e+03 -6.02570020e+03 -6.13610352e+03 -6.10090137e+03 -5.96941016e+03 -5.88021777e+03 -6.07341309e+03 -6.05935986e+03 -5.86933496e+03 -6.06932764e+03 -6.10286475e+03 -5.93936768e+03 -5.86187354e+03 -5.85347266e+03 -5.84054883e+03 -5.66516943e+03 -5.57201514e+03 -5.83084424e+03 -5.89472363e+03 -5.57363525e+03 -5.36675244e+03 -5.59536670e+03 -5.92244336e+03 -5.80056934e+03 -5.45231934e+03 -5.33095850e+03 -5.59041553e+03 -5.64671680e+03 -5.46822363e+03 -5.45075439e+03 -5.30947168e+03 -5.10492871e+03 -5.27024268e+03 -5.49646631e+03 -5.43127588e+03 -5.18164697e+03 -5.01752686e+03 -5.23283447e+03 -5.36318262e+03 -5.19311035e+03 -4.94216016e+03 -4.84647705e+03 -4.97460059e+03 -4.98027197e+03 -5.06856836e+03 -5.00860449e+03 -4.80763281e+03 -4.83687695e+03 -4.83820898e+03 -4.87436914e+03 -4.69696729e+03 -4.58263574e+03 -4.75216016e+03 -4.69845850e+03 -4.60276709e+03 -4.45800244e+03 -4.47944434e+03 -4.69010840e+03 -4.45707959e+03 -4.26143994e+03 -4.34094189e+03 -4.39176074e+03 -4.36685840e+03 -4.29224951e+03 -4.33996045e+03 -4.35012256e+03 -4.17829932e+03 -4.01744531e+03 -3.98318994e+03 -4.14485156e+03 -4.02866992e+03 -3.87611084e+03 -3.98381250e+03 -3.94798926e+03 -3.84206763e+03 -3.76969263e+03 -3.84456445e+03 -3.78236816e+03 -3.63153638e+03 -3.68720703e+03 -3.65928223e+03 -3.62969604e+03 -3.59093506e+03 -3.51279590e+03 -3.44069336e+03 -3.30869800e+03 -3.25309546e+03 -3.37606348e+03 -3.45917847e+03 -3.23725171e+03 -3.03591626e+03 -3.12947998e+03 -3.26852271e+03 -3.20452686e+03 -3.01349683e+03 -2.86400146e+03 -2.95368335e+03 -2.99053491e+03 -2.86280396e+03 -2.87854077e+03 -2.81910864e+03 -2.66478809e+03 -2.64794507e+03 -2.70040942e+03 -2.67417725e+03 -2.51913354e+03 -2.41134741e+03 -2.48357617e+03 -2.53164941e+03 -2.41653369e+03 -2.28164990e+03 -2.20497827e+03 -2.26880322e+03 -2.28538257e+03 -2.16190918e+03 -2.07394336e+03 -2.03905615e+03 -2.01882153e+03 -1.97058984e+03 -1.98130725e+03 -1.90006848e+03 -1.78407581e+03 -1.80103748e+03 -1.76892700e+03 -1.72742163e+03 -1.64528491e+03 -1.56840820e+03 -1.58109973e+03 -1.50055383e+03 -1.44776233e+03 -1.48911487e+03 -1.41094702e+03 -1.36764136e+03 -1.30919421e+03 -1.67539551e+03 -1.80318469e+03 -1.51271741e+03 -1.56165210e+03 -1.53683411e+03 -9.14234619e+02 -1.28294116e+03 -6.45945312e+03 -1.78577576e+03 -522877888. -1.22315000e+04 -18419674. 5.39781350e+06 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. 61294816. 8.60907617e+03 2.34301807e+03 1.52891809e+03 1.28939417e+03 1.21749109e+03 1.14620386e+03 9.29307922e+02 9.55889648e+02 9.54763428e+02 1.03257007e+03 1.20456848e+03 1.39819055e+03 1.19900037e+03 1.20723926e+03 1.36994983e+03 1.31189197e+03 1.35920837e+03 1.54598010e+03 1.57540881e+03 1.55374695e+03 1.63151172e+03 1.67962085e+03 1.67186975e+03 1.72650366e+03 1.81992407e+03 1.87742163e+03 1.92481067e+03 1.92270654e+03 1.92995984e+03 2.01918628e+03 2.08572461e+03 2.11216968e+03 2.13241943e+03 2.17521045e+03 2.27429761e+03 2.31904028e+03 2.33071899e+03 2.36176636e+03 2.40446631e+03 2.53953613e+03 2.59866675e+03 2.51223096e+03 2.53907031e+03 2.63972095e+03 2.69753516e+03 2.77970581e+03 2.80396851e+03 2.78474878e+03 2.86612427e+03 2.92987256e+03 2.96706885e+03 3.01893872e+03 3.01404199e+03 3.07342285e+03 3.14635205e+03 3.16364697e+03 3.19049438e+03 3.21812573e+03 3.26834131e+03 3.37488940e+03 3.43552344e+03 3.44605737e+03 3.40793628e+03 3.43800684e+03 3.58495386e+03 3.62411572e+03 3.57281909e+03 3.64607715e+03 3.71018921e+03 3.75049194e+03 3.84651050e+03 3.87749878e+03 3.82323608e+03 3.84272168e+03 3.99189478e+03 4.06631274e+03 4.00057349e+03 3.96250610e+03 4.04142676e+03 4.12890332e+03 4.26657324e+03 4.30522754e+03 4.18968018e+03 4.23730176e+03 4.39297266e+03 4.42930469e+03 4.41646875e+03 4.35873193e+03 4.36943701e+03 4.55686768e+03 4.63643066e+03 4.54864551e+03 4.58890479e+03 4.65260400e+03 4.68961621e+03 4.71452588e+03 4.72887988e+03 4.79607227e+03 4.84886426e+03 4.94507275e+03 4.95644922e+03 4.83225781e+03 4.87857715e+03 5.02998682e+03 5.00218066e+03 5.03798926e+03 5.07797949e+03 5.09071338e+03 5.23197070e+03 5.19313379e+03 5.16313281e+03 5.30400586e+03 5.35257471e+03 5.26975928e+03 5.27274414e+03 5.35288281e+03 5.40764258e+03 5.42316699e+03 5.39909961e+03 5.43024756e+03 5.50376123e+03 5.65952588e+03 5.64910254e+03 5.46582861e+03 5.55050977e+03 5.72177686e+03 5.73187744e+03 5.69244336e+03 5.64053223e+03 5.62906396e+03 5.78996680e+03 5.93989014e+03 5.87546875e+03 5.75269189e+03 5.80523340e+03 5.97995312e+03 6.03940723e+03 6.06394873e+03 5.94536230e+03 5.84559082e+03 5.95828223e+03 6.01728760e+03 6.02333789e+03 6.11570801e+03 6.06398389e+03 6.13304688e+03 6.29952246e+03 6.22115283e+03 6.01819238e+03 6.11741553e+03 6.27606738e+03 6.31300488e+03 6.37149072e+03 6.31829688e+03 6.21125098e+03 6.29733496e+03 6.51460107e+03 6.38376611e+03 6.13731445e+03 6.31340234e+03 6.51930762e+03 6.51822021e+03 6.41716406e+03 6.32628271e+03 6.36228174e+03 6.51239258e+03 6.50133252e+03 6.53080713e+03 6.59688477e+03 6.45299268e+03 6.52426318e+03 6.70079199e+03 6.57026270e+03 6.50110498e+03 6.54575195e+03 6.65811035e+03 6.72451514e+03 6.71911719e+03 6.54105908e+03 6.46208008e+03 6.66164551e+03 6.91631250e+03 6.95813135e+03 6.55246680e+03 6.54863135e+03 6.89846582e+03 6.78325684e+03 6.71524268e+03 6.68845166e+03 6.61624902e+03 6.73377979e+03 6.82291260e+03 6.82442041e+03 6.70569287e+03 6.67787695e+03 6.77597314e+03 6.91324756e+03 6.87984717e+03 6.78675098e+03 6.76500537e+03 6.85400049e+03 6.83469531e+03 6.70062598e+03 6.77743896e+03 6.84021729e+03 6.73492236e+03 6.90509229e+03 7.07690039e+03 6.70256348e+03 6.72665527e+03 6.93042041e+03 6.88680762e+03 6.89034229e+03 6.71028223e+03 6.75586084e+03 6.95344482e+03 6.94859229e+03 6.86622705e+03 6.67633203e+03 6.61186816e+03 6.81511670e+03 6.94040527e+03 6.84835498e+03 6.76660693e+03 6.86766260e+03 6.84431982e+03 6.93800537e+03 6.85648438e+03 6.69663086e+03 6.65637256e+03 6.71069189e+03 6.89853223e+03 6.78258008e+03 6.65807812e+03 6.71900537e+03 6.83033984e+03 6.83077734e+03 6.76584961e+03 6.64893896e+03 6.65572217e+03 6.75490430e+03 6.67800586e+03 6.81835010e+03 6.69092578e+03 6.56701660e+03 6.70238574e+03 6.52000635e+03 6.56717529e+03 6.75353760e+03 6.57601025e+03 6.52703662e+03 6.54189355e+03 6.59132227e+03 6.47850000e+03 6.39465479e+03 6.64223340e+03 6.74033252e+03 6.37441846e+03 6.36434766e+03 6.42344385e+03 6.41032861e+03 6.54960449e+03 6.46482275e+03 6.28125977e+03 6.32882666e+03 6.43894092e+03 6.40311865e+03 6.34722656e+03 6.20969922e+03 6.26707324e+03 6.33401904e+03 6.20831445e+03 6.20325098e+03 6.13367090e+03 6.10669775e+03 6.17569043e+03 6.21449121e+03 6.14771924e+03 6.03336914e+03 5.99370117e+03 6.13794727e+03 6.20312891e+03 5.96317383e+03 5.99654199e+03 6.00909717e+03 5.81586328e+03 5.92067725e+03 5.94164600e+03 5.77152783e+03 5.86380664e+03 5.86631348e+03 5.80569873e+03 5.90937793e+03 5.74509570e+03 5.64391406e+03 5.68666650e+03 5.71437451e+03 5.70558154e+03 5.52231348e+03 5.49548291e+03 5.58173682e+03 5.57481055e+03 5.56024170e+03 5.48188135e+03 5.37067871e+03 5.45763672e+03 5.56253516e+03 5.37214404e+03 5.22346631e+03 5.22524707e+03 5.36145605e+03 5.38253662e+03 5.16554932e+03 5.11164551e+03 5.13039844e+03 5.11144531e+03 5.07516992e+03 5.09085547e+03 5.01856641e+03 4.91854443e+03 4.96958398e+03 5.04992822e+03 4.91370898e+03 4.69896484e+03 4.74322119e+03 4.82194287e+03 4.77908008e+03 4.73963330e+03 4.65297461e+03 4.59417822e+03 4.68919824e+03 4.71697705e+03 4.55912012e+03 4.44816309e+03 4.45001758e+03 4.52730518e+03 4.45513086e+03 4.26104297e+03 4.24067773e+03 4.28622266e+03 4.26369043e+03 4.23564844e+03 4.23555859e+03 4.10817041e+03 4.09003052e+03 4.06154712e+03 3.94773120e+03 3.91828882e+03 3.91534399e+03 3.91792676e+03 3.90850537e+03 3.81600684e+03 3.70306055e+03 3.68895874e+03 3.74340845e+03 3.80166089e+03 3.72909766e+03 3.52011255e+03 3.48536523e+03 3.52292944e+03 3.46576782e+03 3.38910938e+03 3.35402661e+03 3.33559155e+03 3.31023999e+03 3.24547998e+03 3.13038623e+03 3.14982788e+03 3.18545435e+03 3.14760229e+03 3.05722388e+03 2.94013208e+03 2.92763184e+03 2.88707764e+03 2.82540771e+03 2.86517627e+03 2.81689478e+03 2.69290039e+03 2.65603296e+03 2.63962085e+03 2.65386255e+03 2.60427246e+03 2.52188184e+03 2.47167603e+03 2.41787354e+03 2.36237793e+03 2.29951733e+03 2.29130103e+03 2.25899121e+03 2.23401685e+03 2.17808862e+03 2.05238086e+03 2.04079749e+03 2.01134375e+03 1.96925940e+03 1.97920117e+03 1.87529504e+03 1.79186353e+03 1.81250146e+03 1.78902271e+03 1.70378430e+03 1.64410229e+03 1.58373450e+03 1.52679553e+03 1.49974597e+03 1.46644153e+03 1.41188586e+03 1.39066882e+03 1.35507434e+03 1.28573181e+03 1.22496680e+03 1.16415540e+03 1.13852429e+03 1.11183215e+03 1.04926868e+03 9.78300903e+02 9.32343933e+02 8.98164062e+02 8.63257690e+02 8.35702820e+02 7.63436157e+02 6.97392883e+02 6.63843994e+02 6.14088745e+02 5.63992249e+02 5.30817139e+02 4.78947266e+02 4.21952911e+02 3.81855591e+02 3.32189362e+02 2.83306488e+02 2.38714920e+02 1.90197845e+02 1.41227463e+02 9.25779114e+01 4.53713875e+01 -2.36771393e+00 -5.00971909e+01 -9.88950882e+01 -1.46408218e+02 -1.93766953e+02 -2.36445435e+02 -2.86975433e+02 -3.35644928e+02 -3.80770538e+02 -4.36884186e+02 -4.83651886e+02 -5.22209167e+02 -5.70245239e+02 -6.20709106e+02 -6.82645203e+02 -7.35519409e+02 -7.63930176e+02 -8.00984131e+02 -8.44483887e+02 -9.00664001e+02 -9.55703125e+02 -1.00572791e+03 -1.05675635e+03 -1.09772449e+03 -1.13654895e+03 -1.17329285e+03 -1.23541516e+03 -1.31384277e+03 -1.35085547e+03 -1.36877612e+03 -1.40948242e+03 -1.45352148e+03 -1.50312500e+03 -1.57535828e+03 -1.63370154e+03 -1.66188428e+03 -1.69643188e+03 -1.73061462e+03 -1.78279749e+03 -1.85714807e+03 -1.89639709e+03 -1.94596521e+03 -1.98973511e+03 -2.00654456e+03 -2.08264697e+03 -2.10052710e+03 -2.13527881e+03 -2.25209155e+03 -2.26150732e+03 -2.26865918e+03 -2.34110791e+03 -2.36425146e+03 -2.40017627e+03 -2.54741553e+03 -2.58338232e+03 -2.50897876e+03 -2.57485205e+03 -2.64370435e+03 -2.67336182e+03 -2.78031689e+03 -2.80782544e+03 -2.76621240e+03 -2.83963525e+03 -2.91394482e+03 -2.99781372e+03 -3.05906934e+03 -3.04801172e+03 -3.12076123e+03 -3.11917407e+03 -3.07977344e+03 -3.17114282e+03 -3.29239551e+03 -3.31811426e+03 -3.37745557e+03 -3.39697119e+03 -3.30355078e+03 -3.41273584e+03 -3.61114185e+03 -3.64033984e+03 -3.58242407e+03 -3.53652661e+03 -3.60294238e+03 -3.76524976e+03 -3.81700024e+03 -3.78800269e+03 -3.85322998e+03 -3.85599512e+03 -3.89875757e+03 -3.97049780e+03 -3.90266968e+03 -3.96514160e+03 -4.11163184e+03 -4.18873242e+03 -4.15555859e+03 -4.07100684e+03 -4.12099707e+03 -4.27670459e+03 -4.38333057e+03 -4.36209375e+03 -4.30710498e+03 -4.29412891e+03 -4.41062744e+03 -4.52981250e+03 -4.64021973e+03 -4.60260107e+03 -4.51007324e+03 -4.60952148e+03 -4.63334131e+03 -4.63798877e+03 -4.74521484e+03 -4.75675195e+03 -4.79883398e+03 -4.90868164e+03 -4.84683984e+03 -4.86414062e+03 -4.95080029e+03 -4.98867822e+03 -5.04475684e+03 -5.01551660e+03 -4.95640283e+03 -5.00883057e+03 -5.15436523e+03 -5.27925195e+03 -5.31028857e+03 -5.21233350e+03 -5.14153076e+03 -5.22806836e+03 -5.24693701e+03 -5.34163721e+03 -5.43665137e+03 -5.39208447e+03 -5.33597412e+03 -5.36959082e+03 -5.42919775e+03 -5.54742725e+03 -5.69258252e+03 -5.65195801e+03 -5.57134473e+03 -5.54972266e+03 -5.47959570e+03 -5.60840332e+03 -5.73780615e+03 -5.81478857e+03 -5.84304248e+03 -5.70511816e+03 -5.66640625e+03 -5.81940479e+03 -5.93300049e+03 -5.87899268e+03 -5.93627734e+03 -5.89675293e+03 -5.81756934e+03 -6.00325732e+03 -6.13858643e+03 -6.08458984e+03 -5.97118799e+03 -6.00965967e+03 -6.09646680e+03 -6.14327734e+03 -6.16408887e+03 -6.16456201e+03 -6.24424756e+03 -6.18474072e+03 -6.11283545e+03 -6.31522754e+03 -6.32661084e+03 -6.24734277e+03 -6.39157617e+03 -6.25329004e+03 -6.17781445e+03 -6.41851660e+03 -6.46687598e+03 -6.43927100e+03 -6.65945410e+03 -6.71139697e+03 -6.11519336e+03 -5.78279297e+03 -6.91359326e+03 -7.97806396e+03 -8.47137012e+03 -7.59697510e+03 -1.61481113e+04 -1.56417324e+04 -39223056. 56004376. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 66855588. 1.62207450e+06 -2.42330430e+04 -1.79677305e+04 -1.16578662e+04 -1.13582129e+04 -1.09664473e+04 -9.97798535e+03 -1.04527500e+04 -9.46057715e+03 -8.83332715e+03 -7.07830957e+03 -6.93380322e+03 -8.89863477e+03 -7.24564893e+03 -8.94785840e+03 -6.41319092e+03 -6.38371387e+03 -7.01829883e+03 -6.80507812e+03 -6.50415332e+03 -6.72833545e+03 -6.92584277e+03 -6.97537451e+03 -6.98141357e+03 -6.71426611e+03 -6.62186426e+03 -6.69792139e+03 -6.68777637e+03 -6.69518896e+03 -6.60268750e+03 -6.57481348e+03 -6.77657324e+03 -6.95555371e+03 -6.75337598e+03 -6.43587646e+03 -6.44696436e+03 -6.70378564e+03 -6.74059277e+03 -6.56581396e+03 -6.38923096e+03 -6.44948096e+03 -6.67143555e+03 -6.77489941e+03 -6.61722559e+03 -6.29430420e+03 -6.38829590e+03 -6.61092578e+03 -6.53509473e+03 -6.55755957e+03 -6.43819531e+03 -6.19096045e+03 -6.31240625e+03 -6.57820020e+03 -6.40711426e+03 -6.24296484e+03 -6.39617139e+03 -6.40568945e+03 -6.33674268e+03 -6.24626416e+03 -6.01828125e+03 -6.17056787e+03 -6.50597070e+03 -6.31734424e+03 -6.07000977e+03 -6.00760547e+03 -5.97956152e+03 -6.24223877e+03 -6.39544580e+03 -6.17604492e+03 -5.95283203e+03 -5.91213965e+03 -5.86523047e+03 -6.00262598e+03 -6.17299951e+03 -5.93276074e+03 -5.81494434e+03 -5.92915234e+03 -5.87579053e+03 -5.76129297e+03 -5.72547754e+03 -5.80262939e+03 -5.87819775e+03 -5.84027197e+03 -5.77290674e+03 -5.57357520e+03 -5.46158203e+03 -5.71704785e+03 -5.86068994e+03 -5.52936475e+03 -5.33033203e+03 -5.44590137e+03 -5.56999219e+03 -5.61808887e+03 -5.61752734e+03 -5.38097803e+03 -5.26866553e+03 -5.35733154e+03 -5.34324805e+03 -5.36738770e+03 -5.27756055e+03 -5.12106445e+03 -5.11704688e+03 -5.21926025e+03 -5.21825586e+03 -5.13762598e+03 -5.09982812e+03 -5.06744434e+03 -5.05443457e+03 -5.03185645e+03 -4.83844238e+03 -4.77816064e+03 -5.01069189e+03 -5.01152490e+03 -4.72408545e+03 -4.61345264e+03 -4.65310547e+03 -4.83451270e+03 -4.90703564e+03 -4.69548682e+03 -4.48761963e+03 -4.45719434e+03 -4.48594482e+03 -4.52335498e+03 -4.51060303e+03 -4.44221533e+03 -4.40716016e+03 -4.34630566e+03 -4.32419922e+03 -4.30468896e+03 -4.15821045e+03 -4.19354248e+03 -4.31558691e+03 -4.19397656e+03 -4.06924976e+03 -4.00203589e+03 -3.91525806e+03 -4.03204053e+03 -4.08699854e+03 -3.87227441e+03 -3.73540479e+03 -3.76856982e+03 -3.88214038e+03 -3.89148438e+03 -3.74290625e+03 -3.60583008e+03 -3.54710254e+03 -3.53894238e+03 -3.59324707e+03 -3.59108105e+03 -3.42076172e+03 -3.29008057e+03 -3.35869824e+03 -3.43559790e+03 -3.35567017e+03 -3.23727588e+03 -3.20125049e+03 -3.16270850e+03 -3.13921631e+03 -3.11883398e+03 -2.98566309e+03 -2.93617065e+03 -2.98532617e+03 -2.94501636e+03 -2.86624731e+03 -2.78082617e+03 -2.74875806e+03 -2.75521118e+03 -2.71512817e+03 -2.67735791e+03 -2.57894312e+03 -2.54286279e+03 -2.55186768e+03 -2.49027905e+03 -2.41998999e+03 -2.35051050e+03 -2.29907861e+03 -2.31902319e+03 -2.33613306e+03 -2.24079590e+03 -2.09303174e+03 -2.04136597e+03 -2.09480835e+03 -2.08588721e+03 -2.01234436e+03 -1.88931885e+03 -1.82452478e+03 -1.83623950e+03 -1.81604871e+03 -1.77934204e+03 -1.68757544e+03 -1.61047107e+03 -1.59321155e+03 -1.57733997e+03 -1.54536267e+03 -1.47549292e+03 -1.40658093e+03 -1.36924744e+03 -1.32931262e+03 -1.28335632e+03 -1.23348291e+03 -1.19264514e+03 -1.13439526e+03 -1.07796570e+03 -1.02621375e+03 -9.73313049e+02 -9.60928101e+02 -9.44274719e+02 -8.81894531e+02 -8.03461426e+02 -7.30316284e+02 -6.91126160e+02 -6.84648743e+02 -6.52032837e+02 -5.83440247e+02 -5.13246277e+02 -4.57338257e+02 -4.21818298e+02 -3.90133423e+02 -3.42477631e+02 -2.88792236e+02 -2.38489517e+02 -1.89224716e+02 -1.41333588e+02 -9.16721115e+01 -4.48099632e+01 2.08375192e+00 4.99719543e+01 1.00434105e+02 1.47403610e+02 1.83879044e+02 2.33552139e+02 2.91210022e+02 3.40952301e+02 3.88042236e+02 4.29831207e+02 4.88673157e+02 5.40340942e+02 5.62772888e+02 5.91768066e+02 6.51958130e+02 7.33296692e+02 8.04399292e+02 8.37171814e+02 8.38140320e+02 8.63431702e+02 9.23698303e+02 1.01894006e+03 1.10168079e+03 1.13011462e+03 1.11756824e+03 1.15031433e+03 1.27304321e+03 1.31460059e+03 1.30079297e+03 1.35961206e+03 1.42017749e+03 1.45847620e+03 1.55472546e+03 1.57274866e+03 1.56118567e+03 1.64573706e+03 1.66453650e+03 1.74918921e+03 1.84230969e+03 1.80399121e+03 1.87755396e+03 1.98192615e+03 1.98912170e+03 2.02201770e+03 2.06877344e+03 2.12177197e+03 2.17305322e+03 2.20491699e+03 2.17384277e+03 2.22444067e+03 2.40948340e+03 2.51900610e+03 2.49213208e+03 2.42331421e+03 2.40842651e+03 2.49994043e+03 2.65747876e+03 2.77271582e+03 2.75827490e+03 2.67270190e+03 2.72455176e+03 2.86267065e+03 2.87650830e+03 2.89101514e+03 2.95820752e+03 2.98636255e+03 3.01067993e+03 3.18384180e+03 3.16674414e+03 3.08740210e+03 3.19240894e+03 3.15973071e+03 3.30488159e+03 3.45201416e+03 3.35249146e+03 3.49751514e+03 3.48988965e+03 3.38677466e+03 3.54687109e+03 3.49946973e+03 3.61034180e+03 3.87919727e+03 3.70820288e+03 3.55675928e+03 3.67623560e+03 3.89503394e+03 4.08895410e+03 4.06059302e+03 3.87757056e+03 3.79865259e+03 3.88455420e+03 4.10397021e+03 4.32061230e+03 4.26103320e+03 4.08694556e+03 4.11465967e+03 4.25393408e+03 4.33680762e+03 4.30541162e+03 4.32299951e+03 4.37281299e+03 4.41083057e+03 4.61085840e+03 4.65752930e+03 4.42077051e+03 4.43508789e+03 4.60015381e+03 4.62919238e+03 4.70457324e+03 4.72116992e+03 4.89960400e+03 4.80916064e+03 4.64797021e+03 4.85115186e+03 4.74725781e+03 4.90018506e+03 5.27981885e+03 5.01179688e+03 4.73071680e+03 4.89852051e+03 5.17438818e+03 5.34900439e+03 5.36592090e+03 5.08456738e+03 4.96147656e+03 5.11698975e+03 5.32717041e+03 5.58265283e+03 5.50744971e+03 5.19927686e+03 5.18636377e+03 5.39646533e+03 5.51201709e+03 5.67985498e+03 5.68223193e+03 5.37599805e+03 5.36270703e+03 5.66986279e+03 5.76511523e+03 5.60194824e+03 5.59651270e+03 5.69207764e+03 5.66102051e+03 5.87246338e+03 5.94058936e+03 5.72604932e+03 5.70537598e+03 5.79520117e+03 5.85499805e+03 5.87934521e+03 5.88906348e+03 6.05927148e+03 6.13830225e+03 6.02405615e+03 5.86609033e+03 5.78342285e+03 6.05267090e+03 6.38623877e+03 6.30483447e+03 6.00774365e+03 5.86581006e+03 6.08263916e+03 6.46376221e+03 6.27229443e+03 5.91611377e+03 6.09068066e+03 6.28201758e+03 6.42563037e+03 6.67033008e+03 6.48613330e+03 6.11929150e+03 6.10706934e+03 6.32075244e+03 6.48237109e+03 6.53246045e+03 6.45976172e+03 6.43866797e+03 6.39897510e+03 6.56140918e+03 6.50054443e+03 6.36669238e+03 6.42940283e+03 6.38008838e+03 6.63561719e+03 6.79517773e+03 6.55120752e+03 6.66938721e+03 6.67875146e+03 6.64859473e+03 6.48354639e+03 6.36812402e+03 6.72629980e+03 6.95195166e+03 6.74751514e+03 6.49330078e+03 6.50542529e+03 6.86932422e+03 6.98821533e+03 6.79026709e+03 6.75377344e+03 6.55479980e+03 6.56833008e+03 6.88783594e+03 6.85194531e+03 6.73070996e+03 6.61740869e+03 6.49750146e+03 6.87290186e+03 7.12225879e+03 6.80048535e+03 6.65675049e+03 6.82089160e+03 6.78437549e+03 7.02083594e+03 7.00500195e+03 6.67710596e+03 6.56732568e+03 6.81124658e+03 6.86561328e+03 6.89566992e+03 6.98662695e+03 7.22014941e+03 7.22459131e+03 7.04433838e+03 6.98716602e+03 6.53672754e+03 7.36217529e+03 7.86972852e+03 7.35234033e+03 9.93486816e+03 1.36135625e+04 1.27680635e+04 2.83094844e+04 1.45392391e+05 45281080. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 50947440. 50947440. -3.28714275e+06 5.60369258e+04 1.62408652e+04 1.27142715e+04 1.08895977e+04 9.65992773e+03 9.30228418e+03 9.11501562e+03 9.62728613e+03 9.63537305e+03 9.29536035e+03 9.49688477e+03 9.42921680e+03 9.28252832e+03 9.32700781e+03 9.31189844e+03 7.81043115e+03 8.00987354e+03 6.58629346e+03 6.22940820e+03 6.06964990e+03 5.91619385e+03 6.08486328e+03 6.09355615e+03 5.81058887e+03 5.80862061e+03 6.04500439e+03 6.05324121e+03 5.87914062e+03 5.80820508e+03 5.80666113e+03 5.79177441e+03 5.76288818e+03 5.73623633e+03 5.68051514e+03 5.63252588e+03 5.51140527e+03 5.46524170e+03 5.71900195e+03 5.72443994e+03 5.49535498e+03 5.47989600e+03 5.48737695e+03 5.46724170e+03 5.39685547e+03 5.34830029e+03 5.36589941e+03 5.25891602e+03 5.21155713e+03 5.20034473e+03 5.15625293e+03 5.35396875e+03 5.34866650e+03 5.13261426e+03 4.96529785e+03 4.92294189e+03 5.20168945e+03 5.17669580e+03 4.97652881e+03 4.86117529e+03 4.85473047e+03 4.89003516e+03 4.78954688e+03 4.91310938e+03 4.89756836e+03 4.59241455e+03 4.51948828e+03 4.71751318e+03 4.86034473e+03 4.69811182e+03 4.56383887e+03 4.52868701e+03 4.47581787e+03 4.44677295e+03 4.41294922e+03 4.41164502e+03 4.37642920e+03 4.27624805e+03 4.23006445e+03 4.20590088e+03 4.17557178e+03 4.28301318e+03 4.20633252e+03 4.04408569e+03 4.02412769e+03 3.99781689e+03 4.05679468e+03 4.03118286e+03 3.89753711e+03 3.84673901e+03 3.75150488e+03 3.65669238e+03 3.78993579e+03 3.74558569e+03 3.50230347e+03 3.51312476e+03 3.68284692e+03 3.75551514e+03 3.59926416e+03 3.44421118e+03 3.37938599e+03 3.33586377e+03 3.31756787e+03 3.27774707e+03 3.23822314e+03 3.17893872e+03 3.23041455e+03 3.17769482e+03 3.04548047e+03 3.02687744e+03 2.89733643e+03 2.92154272e+03 3.05293262e+03 2.95313599e+03 2.82930078e+03 2.71024194e+03 2.65318042e+03 2.76475732e+03 2.73062476e+03 2.60060522e+03 2.49708838e+03 2.44413843e+03 2.45390161e+03 2.41653418e+03 2.45270874e+03 2.41562622e+03 2.29333643e+03 2.22971436e+03 2.18244141e+03 2.17793652e+03 2.14374902e+03 2.07115259e+03 1.99371521e+03 1.95483936e+03 1.91932532e+03 1.81386292e+03 1.81094836e+03 1.87600110e+03 1.80005298e+03 1.69950647e+03 1.60996179e+03 1.56147156e+03 1.60332153e+03 1.56206030e+03 1.47067834e+03 1.38416077e+03 1.33012988e+03 1.33342285e+03 1.28188708e+03 1.22979773e+03 1.15634912e+03 1.13134924e+03 1.14007568e+03 1.06267175e+03 1.00696851e+03 9.65670044e+02 9.07522644e+02 8.44355103e+02 7.98948669e+02 7.58879944e+02 7.07348267e+02 6.67550110e+02 6.02181519e+02 5.61951416e+02 5.50549194e+02 4.78498962e+02 4.13922211e+02 3.78257446e+02 3.31070679e+02 2.92801331e+02 2.40930984e+02 1.85945679e+02 1.44153305e+02 9.63716812e+01 4.72743263e+01 -6.31785095e-01 -4.81419640e+01 -9.56141357e+01 -1.43139038e+02 -1.91096268e+02 -2.32608856e+02 -2.87039734e+02 -3.52867432e+02 -3.93875763e+02 -4.26808258e+02 -4.60275665e+02 -5.15225830e+02 -5.94533020e+02 -6.37999634e+02 -6.69653625e+02 -7.02543945e+02 -7.41630005e+02 -8.09148438e+02 -8.60260071e+02 -9.26196411e+02 -9.63041809e+02 -9.85139771e+02 -1.03916785e+03 -1.08393811e+03 -1.16936987e+03 -1.20992358e+03 -1.22091931e+03 -1.27318335e+03 -1.32135669e+03 -1.36738220e+03 -1.37824304e+03 -1.46412415e+03 -1.60338647e+03 -1.61124890e+03 -1.60568652e+03 -1.60910767e+03 -1.64375195e+03 -1.78985461e+03 -1.85460559e+03 -1.84327002e+03 -1.83737048e+03 -1.87609229e+03 -1.98002026e+03 -2.02926599e+03 -2.12780029e+03 -2.16842871e+03 -2.15842334e+03 -2.14024219e+03 -2.17729346e+03 -2.35771362e+03 -2.39684229e+03 -2.37472900e+03 -2.37657056e+03 -2.40938574e+03 -2.59104077e+03 -2.65078320e+03 -2.53402783e+03 -2.56622217e+03 -2.77289575e+03 -2.82186157e+03 -2.71035962e+03 -2.74797998e+03 -2.93414990e+03 -2.99704956e+03 -2.94736865e+03 -2.91650195e+03 -2.96255981e+03 -3.17041797e+03 -3.18634180e+03 -3.11689160e+03 -3.20503516e+03 -3.24892163e+03 -3.27926489e+03 -3.31825806e+03 -3.36263110e+03 -3.32267285e+03 -3.44208008e+03 -3.63875269e+03 -3.57959717e+03 -3.64884424e+03 -3.70770410e+03 -3.66364771e+03 -3.70813403e+03 -3.74673975e+03 -3.76991089e+03 -3.74174146e+03 -3.76723706e+03 -3.89229663e+03 -3.95027686e+03 -4.09448242e+03 -4.01932642e+03 -3.92812207e+03 -4.07173901e+03 -4.15232324e+03 -4.32410889e+03 -4.31092822e+03 -4.20642920e+03 -4.21349609e+03 -4.22594238e+03 -4.35642480e+03 -4.39253516e+03 -4.53057275e+03 -4.55443164e+03 -4.47827051e+03 -4.51298096e+03 -4.40918506e+03 -4.57126855e+03 -4.86853125e+03 -4.83712939e+03 -4.73577490e+03 -4.63813721e+03 -4.60201855e+03 -4.85786426e+03 -5.05874316e+03 -4.96581494e+03 -4.79824609e+03 -4.82744043e+03 -4.98828662e+03 -5.00720850e+03 -5.16202051e+03 -5.17516162e+03 -5.06975928e+03 -5.09380908e+03 -5.10884961e+03 -5.33797949e+03 -5.38984424e+03 -5.12085303e+03 -5.13656738e+03 -5.46636670e+03 -5.45816602e+03 -5.20758301e+03 -5.31053955e+03 -5.61376904e+03 -5.63647266e+03 -5.52595801e+03 -5.41296924e+03 -5.39710645e+03 -5.72397852e+03 -5.79701025e+03 -5.66499756e+03 -5.54024414e+03 -5.51081641e+03 -5.69484717e+03 -5.76725635e+03 -5.79496387e+03 -5.65014551e+03 -5.81497168e+03 -6.07742773e+03 -5.94743750e+03 -5.99367822e+03 -5.95628516e+03 -5.88280273e+03 -5.97582959e+03 -5.99940283e+03 -6.05654297e+03 -6.02847656e+03 -5.96047217e+03 -5.85352148e+03 -6.09295557e+03 -6.41125146e+03 -6.12498096e+03 -5.86829395e+03 -6.10686621e+03 -6.31543604e+03 -6.53311182e+03 -6.35722998e+03 -6.18710449e+03 -6.38285352e+03 -6.41057520e+03 -6.21812207e+03 -6.15431836e+03 -6.42465674e+03 -6.42676465e+03 -6.35218652e+03 -6.30036279e+03 -6.12287939e+03 -6.40167188e+03 -6.82116016e+03 -6.65405176e+03 -6.48320605e+03 -6.32099902e+03 -6.25950146e+03 -6.63864502e+03 -6.86469385e+03 -6.67263525e+03 -6.46472168e+03 -6.47388037e+03 -6.51751270e+03 -6.53853369e+03 -6.77255762e+03 -6.70652881e+03 -6.54200635e+03 -6.62761572e+03 -6.58616504e+03 -6.83525684e+03 -6.86884277e+03 -6.64619775e+03 -6.67236182e+03 -6.67341309e+03 -6.73295996e+03 -6.60164844e+03 -6.62850684e+03 -6.95194678e+03 -6.89224121e+03 -6.77506592e+03 -6.58149414e+03 -6.62327588e+03 -7.04818945e+03 -7.02533545e+03 -6.81875049e+03 -6.69778467e+03 -6.63450098e+03 -6.72072217e+03 -6.76179004e+03 -6.84328809e+03 -6.68816455e+03 -6.75677783e+03 -7.05319238e+03 -6.82896973e+03 -6.99654395e+03 -7.00078516e+03 -6.82011328e+03 -6.78907520e+03 -6.78853857e+03 -6.81112988e+03 -6.81236328e+03 -6.76501758e+03 -6.79677539e+03 -6.93378125e+03 -6.97814844e+03 -6.65839844e+03 -6.62824414e+03 -6.74898975e+03 -6.86996484e+03 -7.09164258e+03 -6.96526367e+03 -6628. -6.82909277e+03 -6.96201758e+03 -6.85612402e+03 -6.76832275e+03 -6.72643262e+03 -6.67285742e+03 -6.67818457e+03 -6.85740527e+03 -6.62266016e+03 -6.70748291e+03 -7.03387988e+03 -6.88934375e+03 -6.72580078e+03 -6.61783838e+03 -6.57031787e+03 -6.91601074e+03 -6.86551025e+03 -6.69739746e+03 -6.57313330e+03 -6.36840137e+03 -6.50859131e+03 -6.79232715e+03 -6.97541846e+03 -6.70404004e+03 -6.48508545e+03 -6.51980371e+03 -6.54345703e+03 -6.79076221e+03 -6.73727490e+03 -6.49669141e+03 -6.48804785e+03 -6.46240625e+03 -6.49122266e+03 -6.36515771e+03 -6.41515723e+03 -6.66591064e+03 -6.57275830e+03 -6.46572705e+03 -6.33371533e+03 -6.25464697e+03 -6.59360645e+03 -6.57193652e+03 -6.36421045e+03 -6.18897998e+03 -6.14834473e+03 -6.25767334e+03 -6.28714160e+03 -6.42665527e+03 -6.44123291e+03 -6.18089355e+03 -6.01852734e+03 -6.06990674e+03 -6.37892920e+03 -6.28805566e+03 -6.12322998e+03 -6.07257568e+03 -6.01687695e+03 -5.99378467e+03 -5.93077539e+03 -6.05880811e+03 -6.01532373e+03 -5.87228027e+03 -6.05065967e+03 -6.09652441e+03 -5.95120068e+03 -5.87082764e+03 -5.83583594e+03 -5.83018799e+03 -5.67285693e+03 -5.57817529e+03 -5.84554492e+03 -5.88396631e+03 -5.56357178e+03 -5.40460400e+03 -5.66262939e+03 -5.86972266e+03 -5.74430225e+03 -5.49506641e+03 -5.34120654e+03 -5.54025049e+03 -5.60100928e+03 -5.47134326e+03 -5.44018994e+03 -5.29376221e+03 -5.05647510e+03 -5.22260596e+03 -5.52687012e+03 -5.50229639e+03 -5.17858936e+03 -5.00107129e+03 -5.23650830e+03 -5.36873340e+03 -5.17317334e+03 -4.98070068e+03 -4.90112061e+03 -4.92453613e+03 -4.94746240e+03 -5.08070752e+03 -5.06094775e+03 -4.86684473e+03 -4.76737598e+03 -4.72617383e+03 -4.88766309e+03 -4.75999268e+03 -4.60536719e+03 -4.76568311e+03 -4.70800635e+03 -4.61897559e+03 -4.49665723e+03 -4.44235742e+03 -4.64269727e+03 -4.47380762e+03 -4.27304736e+03 -4.34274512e+03 -4.40020117e+03 -4.37253564e+03 -4.28409180e+03 -4.33555176e+03 -4.33801025e+03 -4.18482617e+03 -4.01765259e+03 -3.96937305e+03 -4.17069531e+03 -4.06417236e+03 -3.91579102e+03 -3.92182812e+03 -3.86906860e+03 -3.89823706e+03 -3.84087305e+03 -3.82139404e+03 -3.75094531e+03 -3.62574243e+03 -3.71123315e+03 -3.69501929e+03 -3.60456714e+03 -3.56135229e+03 -3.51115869e+03 -3.43288428e+03 -3.30442236e+03 -3.25646704e+03 -3.38546069e+03 -3.46492017e+03 -3.23392944e+03 -3.05522705e+03 -3.16475122e+03 -3.24278613e+03 -3.16125146e+03 -3.00867383e+03 -2.88894507e+03 -2.99166309e+03 -2.95942432e+03 -2.81543506e+03 -2.89862793e+03 -2.83458447e+03 -2.63235278e+03 -2.62394702e+03 -2.72132104e+03 -2.70245166e+03 -2.52364087e+03 -2.40885596e+03 -2.48645630e+03 -2.53052466e+03 -2.42198975e+03 -2.28582275e+03 -2.20146045e+03 -2.27029443e+03 -2.26079199e+03 -2.14384766e+03 -2.11740039e+03 -2.08404248e+03 -2.00452380e+03 -1.94564624e+03 -1.97527454e+03 -1.90158936e+03 -1.78658716e+03 -1.80055334e+03 -1.76945630e+03 -1.73191016e+03 -1.64528137e+03 -1.56589648e+03 -1.58498315e+03 -1.50068555e+03 -1.44991882e+03 -1.55116760e+03 -1.47720898e+03 -1.38873267e+03 -1.28004919e+03 -2.39839966e+03 -3.69486816e+03 -3.07921826e+03 -2.77122412e+03 -2.92925928e+03 -1.57506555e+03 -4.47582861e+03 -2.74513242e+04 -1.18801138e+06 520358368. 520358368. 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. 61294816. 8.60907617e+03 2.34301807e+03 1.52891809e+03 1.28939417e+03 1.09089758e+03 1.15780029e+03 1.05645288e+03 1.09927393e+03 1.05327441e+03 1.10181140e+03 1.15798352e+03 1.18692664e+03 1.23759753e+03 1.27522864e+03 1.31105774e+03 1.39001428e+03 1.43726697e+03 1.47044324e+03 1.52741626e+03 1.52763049e+03 1.56686108e+03 1.66796252e+03 1.69473303e+03 1.72164734e+03 1.81818945e+03 1.91325024e+03 1.91023474e+03 1.90261377e+03 1.94490479e+03 1.97569971e+03 2.06953247e+03 2.16158740e+03 2.16324048e+03 2.20125195e+03 2.29850635e+03 2.31444238e+03 2.30032983e+03 2.36539844e+03 2.40983838e+03 2.46264795e+03 2.57767749e+03 2.56682056e+03 2.57393848e+03 2.69259180e+03 2.70209009e+03 2.70268311e+03 2.74879688e+03 2.80861475e+03 2.88638940e+03 2.93394824e+03 3.02044458e+03 3.00952466e+03 3.00778979e+03 3.12063550e+03 3.09505469e+03 3.09321460e+03 3.23039526e+03 3.27093774e+03 3.28168823e+03 3.38449829e+03 3.41567456e+03 3.39709570e+03 3.44713965e+03 3.47224878e+03 3.48180737e+03 3.58018066e+03 3.63939502e+03 3.69520190e+03 3.75469482e+03 3.74308203e+03 3.75653125e+03 3.81266650e+03 3.88477490e+03 3.88879126e+03 3.93261963e+03 4.10197314e+03 4.05790283e+03 3.94468872e+03 4.07227271e+03 4.11702002e+03 4.12130908e+03 4.26204541e+03 4.27254785e+03 4.25290088e+03 4.40686621e+03 4.48929395e+03 4.40294971e+03 4.34353857e+03 4.37112842e+03 4.45217773e+03 4.58346436e+03 4.63016064e+03 4.65597656e+03 4.73679346e+03 4.73710645e+03 4.67810645e+03 4.65108057e+03 4.78243994e+03 4.83771875e+03 4.81612549e+03 4.91949805e+03 4.93727490e+03 4.92350928e+03 5.06125195e+03 5.00565576e+03 4.93510400e+03 5.02901318e+03 5.15551611e+03 5.22179004e+03 5.16341846e+03 5.21112305e+03 5.32523193e+03 5.36212891e+03 5.33152393e+03 5.23999658e+03 5.26521240e+03 5.44271777e+03 5.49316455e+03 5.42684424e+03 5.49387598e+03 5.47126953e+03 5.45463574e+03 5.62102930e+03 5.61121924e+03 5.53235840e+03 5.61505176e+03 5.76872412e+03 5.82184766e+03 5.76622559e+03 5.63844922e+03 5.64045459e+03 5.81056348e+03 5.92658789e+03 5.78728271e+03 5.84283545e+03 6.06783594e+03 6.02894629e+03 5.96989844e+03 5.96079541e+03 5.84897559e+03 5.87477100e+03 5.96971924e+03 6.08962256e+03 6.11822803e+03 6.12374072e+03 6.21300293e+03 6.20363086e+03 6.11191504e+03 6.07944434e+03 6.11066943e+03 6.22368994e+03 6.30776660e+03 6.40144678e+03 6.38094971e+03 6.31308789e+03 6.27056689e+03 6.33597314e+03 6.41991602e+03 6.20696094e+03 6.26961719e+03 6.50169238e+03 6.56463721e+03 6.42255957e+03 6.39687646e+03 6.39303125e+03 6.36942822e+03 6.48012891e+03 6.64450830e+03 6.65859717e+03 6.54720068e+03 6.54555713e+03 6.58950732e+03 6.51423193e+03 6.53715869e+03 6.57791504e+03 6.54804443e+03 6.77093066e+03 6.86336670e+03 6.53523047e+03 6.57680908e+03 6.62959912e+03 6.69005371e+03 6.82122217e+03 6.58378271e+03 6.55309619e+03 6.83295752e+03 6.84802100e+03 6.77612695e+03 6.73143506e+03 6.67996094e+03 6.63506689e+03 6.77717432e+03 6.91824902e+03 6.79766748e+03 6.67204980e+03 6.84713867e+03 7.01049072e+03 6.79238525e+03 6.72850879e+03 6.77215234e+03 6.72559570e+03 6.90102979e+03 6.80644482e+03 6.79408105e+03 6.94741309e+03 6.75175977e+03 6.75249951e+03 6.85732471e+03 6.70729736e+03 6.75945508e+03 6.88671289e+03 6.90931641e+03 6.90737939e+03 6.81585059e+03 6.81627295e+03 6.77802832e+03 6.82791650e+03 6.93680127e+03 6.75259131e+03 6.67232422e+03 6.84100830e+03 6.93998682e+03 6.79269482e+03 6.86248291e+03 6.90560156e+03 6.70701514e+03 6.83363330e+03 6.96765723e+03 6.76222607e+03 6.64523193e+03 6.77246484e+03 6.74792871e+03 6.71582617e+03 6.68658936e+03 6.70409033e+03 6.75408838e+03 6.83451367e+03 6.81238818e+03 6.72917725e+03 6.71422266e+03 6.70042871e+03 6.63478418e+03 6.78786475e+03 6.57046680e+03 6.54655469e+03 6.78452100e+03 6.63445459e+03 6.55607861e+03 6.60773242e+03 6.61910742e+03 6.50121533e+03 6.51583936e+03 6.56266846e+03 6.64390625e+03 6.55290430e+03 6.53630811e+03 6.56233301e+03 6.40102002e+03 6.38243066e+03 6.41387207e+03 6.35160938e+03 6.49271240e+03 6.59222070e+03 6.39682861e+03 6.27505469e+03 6.32194678e+03 6.46640039e+03 6.39539648e+03 6.10805957e+03 6.26664307e+03 6.42710107e+03 6.27607324e+03 6.23093359e+03 6.16711133e+03 6.12140625e+03 6.18156689e+03 6.10652588e+03 6.03337158e+03 6.17588037e+03 6.14871729e+03 6.03456494e+03 6.09362158e+03 6.06095557e+03 6.02723242e+03 5.94275293e+03 5.77881104e+03 5.92133643e+03 6.01410254e+03 5.79966357e+03 5.77697412e+03 5.80112207e+03 5.84965576e+03 5.86205371e+03 5.64501855e+03 5.70837402e+03 5.82296436e+03 5.70411670e+03 5.63244971e+03 5.58187109e+03 5.51412158e+03 5.56023389e+03 5.53077344e+03 5.46032227e+03 5.53002588e+03 5.52674023e+03 5.45883984e+03 5.45698975e+03 5.39868018e+03 5.27549072e+03 5.23981494e+03 5.32158789e+03 5.32776807e+03 5.18043652e+03 5.11533105e+03 5.07506641e+03 5.06932275e+03 5.15051318e+03 5.07752393e+03 4.95711621e+03 4.95155615e+03 5.01136328e+03 5.02448389e+03 4.91156445e+03 4.77919971e+03 4.76840234e+03 4.79902246e+03 4.72696582e+03 4.68441357e+03 4.70950146e+03 4.68155322e+03 4.63064014e+03 4.66231006e+03 4.60543896e+03 4.47849805e+03 4.42473096e+03 4.45523730e+03 4.43862988e+03 4.27724609e+03 4.19647559e+03 4.27139844e+03 4.28851562e+03 4.27731494e+03 4.20788428e+03 4.07751465e+03 4.12665430e+03 4.14469824e+03 3.95694531e+03 3.88072876e+03 3.96927515e+03 3.99300073e+03 3.88178223e+03 3.77392236e+03 3.69888623e+03 3.69427808e+03 3.74645605e+03 3.76033008e+03 3.70913696e+03 3.56458862e+03 3.48783594e+03 3.47773853e+03 3.42216846e+03 3.39903198e+03 3.36153833e+03 3.31603906e+03 3.31036157e+03 3.27035107e+03 3.19711353e+03 3.13489819e+03 3.12744604e+03 3.16709717e+03 3.09030078e+03 2.94597925e+03 2.88043921e+03 2.90037646e+03 2.91751123e+03 2.88150977e+03 2.79845728e+03 2.66569507e+03 2.63073486e+03 2.67049097e+03 2.64957983e+03 2.60339941e+03 2.51863794e+03 2.44475513e+03 2.42944873e+03 2.36609473e+03 2.34095532e+03 2.28788110e+03 2.18512158e+03 2.20735547e+03 2.20703149e+03 2.12318872e+03 2.03830750e+03 1.94568994e+03 1.94777856e+03 1.99487866e+03 1.93170837e+03 1.81823462e+03 1.79678040e+03 1.78051746e+03 1.68435303e+03 1.62698938e+03 1.56805261e+03 1.52969421e+03 1.54350049e+03 1.47877124e+03 1.38694775e+03 1.36864075e+03 1.34223633e+03 1.28051184e+03 1.23266931e+03 1.19702454e+03 1.13540881e+03 1.07753491e+03 1.04313037e+03 9.92083191e+02 9.57547302e+02 9.14500427e+02 8.58422180e+02 8.11097900e+02 7.47480103e+02 7.04242249e+02 6.64181824e+02 6.13483521e+02 5.74449890e+02 5.30683472e+02 4.79359863e+02 4.23843140e+02 3.74346497e+02 3.30681305e+02 2.85905762e+02 2.38861221e+02 1.88211227e+02 1.41305832e+02 9.40608444e+01 4.52525063e+01 -2.81993580e+00 -5.08366432e+01 -9.65677567e+01 -1.44578949e+02 -1.92544937e+02 -2.38238312e+02 -2.91481506e+02 -3.36475464e+02 -3.79187622e+02 -4.40465210e+02 -4.94315460e+02 -5.18499451e+02 -5.58988403e+02 -6.26992371e+02 -6.85221558e+02 -7.29726135e+02 -7.58732788e+02 -7.93053772e+02 -8.48049011e+02 -9.15248047e+02 -9.66122620e+02 -9.91710083e+02 -1.03839954e+03 -1.09708276e+03 -1.13762244e+03 -1.19680859e+03 -1.25055823e+03 -1.28472388e+03 -1.33903308e+03 -1.37937622e+03 -1.42926538e+03 -1.46586523e+03 -1.50059534e+03 -1.56954077e+03 -1.61721570e+03 -1.65925586e+03 -1.68837451e+03 -1.72673535e+03 -1.81396362e+03 -1.86193811e+03 -1.89158752e+03 -1.95446765e+03 -1.95364111e+03 -1.98109619e+03 -2.10406543e+03 -2.14090552e+03 -2.12380103e+03 -2.22410669e+03 -2.27538574e+03 -2.25118579e+03 -2.35433984e+03 -2.41083838e+03 -2.39760913e+03 -2.49478735e+03 -2.55417310e+03 -2.53158618e+03 -2.59452612e+03 -2.66515210e+03 -2.69379980e+03 -2.75345581e+03 -2.79430688e+03 -2.75693384e+03 -2.81989722e+03 -2.96058813e+03 -3.01834131e+03 -3.04262598e+03 -3.02375464e+03 -3.07828662e+03 -3.11228418e+03 -3.09987646e+03 -3.21947778e+03 -3.27265186e+03 -3.27445947e+03 -3.38654468e+03 -3.39208911e+03 -3.35435376e+03 -3.45659033e+03 -3.53959814e+03 -3.60221338e+03 -3.60165625e+03 -3.59191919e+03 -3.60112329e+03 -3.72590210e+03 -3.88251855e+03 -3.78799243e+03 -3.79517310e+03 -3.81732446e+03 -3.87370996e+03 -4.02640576e+03 -3.96993091e+03 -3.94055566e+03 -4.04675391e+03 -4.14684521e+03 -4.15750488e+03 -4.07901782e+03 -4.18836182e+03 -4.32351904e+03 -4.29933008e+03 -4.34534326e+03 -4.32066211e+03 -4.36649512e+03 -4.48941846e+03 -4.51092969e+03 -4.57004150e+03 -4.52530615e+03 -4.51480176e+03 -4.61747070e+03 -4.66332520e+03 -4.73300098e+03 -4.72943799e+03 -4.68030078e+03 -4.74801855e+03 -4.87777295e+03 -4.90410596e+03 -4.89698340e+03 -4.92529004e+03 -4.94840918e+03 -5.01065283e+03 -5.01660889e+03 -4.98434180e+03 -5.12168457e+03 -5.16548145e+03 -5.13486377e+03 -5.27580029e+03 -5.22355420e+03 -5.17689209e+03 -5.28600635e+03 -5.25135938e+03 -5.30066455e+03 -5.41632910e+03 -5.40579541e+03 -5.34017139e+03 -5.39550000e+03 -5.48484424e+03 -5.51270752e+03 -5.65225830e+03 -5.62479639e+03 -5.54200830e+03 -5.59873291e+03 -5.56562305e+03 -5.64705518e+03 -5.68320605e+03 -5.75693750e+03 -5.85642529e+03 -5.71780664e+03 -5.79621924e+03 -5.85833789e+03 -5.79204932e+03 -5.85044678e+03 -5.94637402e+03 -5.98773291e+03 -5.92206494e+03 -5.96416895e+03 -6.05071240e+03 -6.04253418e+03 -6.00656982e+03 -6.03883838e+03 -6.06388525e+03 -6.17482764e+03 -6.12834863e+03 -6.14141895e+03 -6.24401221e+03 -6.13039502e+03 -6.13263867e+03 -6.35521973e+03 -6.38248828e+03 -6.21515820e+03 -6.24022119e+03 -6.24403467e+03 -6.21925586e+03 -6.57692432e+03 -6.46926953e+03 -6.28108594e+03 -6.61743115e+03 -6.72018555e+03 -6.22252539e+03 -5.79196191e+03 -6.82560107e+03 -8.00324512e+03 -7.48636768e+03 -6.55883105e+03 -1.67870234e+04 -1.65432871e+04 6.08102250e+06 3.71097275e+06 43397152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 66855588. 1.62207450e+06 -2.42330430e+04 -1.79677305e+04 -1.16578662e+04 -1.13582129e+04 -1.09664473e+04 -9.97798535e+03 -9.46809766e+03 -9.02652246e+03 -6.73670703e+03 -6.96975879e+03 -7.07810547e+03 -6.88873926e+03 -6.81996191e+03 -6.72895410e+03 -6.86062158e+03 -6.95241992e+03 -6.89183789e+03 -6.74685547e+03 -6.59684375e+03 -6.78712158e+03 -6.85917578e+03 -6.82002588e+03 -6.83919775e+03 -6.62029492e+03 -6.63717432e+03 -6.76841504e+03 -6.72332910e+03 -6.75697461e+03 -6.55176123e+03 -6.45828516e+03 -6.84316211e+03 -6.96468359e+03 -6.70343066e+03 -6.43720605e+03 -6.45845752e+03 -6.62603320e+03 -6.68710449e+03 -6.58918066e+03 -6.45405078e+03 -6.64648779e+03 -6.65594873e+03 -6.58498926e+03 -6.55485156e+03 -6.29108203e+03 -6.41200635e+03 -6.71092969e+03 -6.55460645e+03 -6.51922168e+03 -6.39568994e+03 -6.27195996e+03 -6.35721533e+03 -6.56517139e+03 -6.47139697e+03 -6.22596582e+03 -6.35196924e+03 -6.34119531e+03 -6.28842822e+03 -6.29031982e+03 -6.14818506e+03 -6.22974316e+03 -6.35958545e+03 -6.17434424e+03 -6.09245361e+03 -5.99431055e+03 -6.11975488e+03 -6.30077734e+03 -6.21633838e+03 -6.07765723e+03 -5.95721582e+03 -5.95846582e+03 -5.95109863e+03 -6.01726123e+03 -6.09040479e+03 -5.84291016e+03 -5.86769482e+03 -6.00551953e+03 -5.95485449e+03 -5.81873633e+03 -5.65093994e+03 -5.72025684e+03 -5.90649072e+03 -5.85476709e+03 -5.72651904e+03 -5.57707080e+03 -5.54299463e+03 -5.65590723e+03 -5.75621777e+03 -5.56998682e+03 -5.39347363e+03 -5.57247607e+03 -5.55060156e+03 -5.42790332e+03 -5.55769482e+03 -5.39244873e+03 -5.31686133e+03 -5.37916504e+03 -5.36569922e+03 -5.36737158e+03 -5.17458350e+03 -5.10878125e+03 -5.18417236e+03 -5.26826025e+03 -5.26378662e+03 -5.09027393e+03 -5.05940186e+03 -5.04116309e+03 -4.99602588e+03 -5.03423193e+03 -4.88518652e+03 -4.85387158e+03 -4.97695898e+03 -4.92552686e+03 -4.73958643e+03 -4.60176807e+03 -4.73084961e+03 -4.89837207e+03 -4.82076074e+03 -4.64109961e+03 -4.49370752e+03 -4.49185107e+03 -4.54737402e+03 -4.55732812e+03 -4.52791064e+03 -4.38752832e+03 -4.34949268e+03 -4.33116455e+03 -4.32275781e+03 -4.37650146e+03 -4.18218164e+03 -4.14923926e+03 -4.26797510e+03 -4.14313086e+03 -4.07058838e+03 -4.03268359e+03 -4.01012695e+03 -4.03858276e+03 -3.97160474e+03 -3.85630591e+03 -3.73432886e+03 -3.81228076e+03 -3.92815356e+03 -3.82729834e+03 -3.69582739e+03 -3.59451587e+03 -3.57232837e+03 -3.59449365e+03 -3.59928052e+03 -3.55548022e+03 -3.36351245e+03 -3.31118921e+03 -3.37383740e+03 -3.39120532e+03 -3.40116089e+03 -3.26155884e+03 -3.17896069e+03 -3.14252441e+03 -3.12399121e+03 -3.12333032e+03 -3.00994556e+03 -2.98239990e+03 -2.95842432e+03 -2.90074902e+03 -2.88340405e+03 -2.77538916e+03 -2.77616162e+03 -2.79533765e+03 -2.68097583e+03 -2.65761328e+03 -2.60417041e+03 -2.54925464e+03 -2.54101392e+03 -2.50945581e+03 -2.43076953e+03 -2.32502197e+03 -2.29754590e+03 -2.32258081e+03 -2.32372192e+03 -2.24569897e+03 -2.09479883e+03 -2.03095923e+03 -2.07936108e+03 -2.06990747e+03 -2.00533057e+03 -1.88657764e+03 -1.85596985e+03 -1.85721594e+03 -1.79072302e+03 -1.76406506e+03 -1.67644165e+03 -1.62026038e+03 -1.61427710e+03 -1.58114941e+03 -1.53134155e+03 -1.45713062e+03 -1.41791235e+03 -1.37393408e+03 -1.32697266e+03 -1.30091614e+03 -1.23531042e+03 -1.18811133e+03 -1.13629138e+03 -1.07667688e+03 -1.02751611e+03 -9.80986023e+02 -9.64491211e+02 -9.24474121e+02 -8.67846497e+02 -8.05396606e+02 -7.28649963e+02 -7.01374146e+02 -6.89994751e+02 -6.40113098e+02 -5.80444458e+02 -5.14785461e+02 -4.60530548e+02 -4.24638275e+02 -3.89848999e+02 -3.40098755e+02 -2.86939850e+02 -2.40247787e+02 -1.90365479e+02 -1.42336060e+02 -9.28555374e+01 -4.48652611e+01 1.54924488e+00 4.92487640e+01 9.91205215e+01 1.47616837e+02 1.86097549e+02 2.40732086e+02 2.94366608e+02 3.32429779e+02 3.83978912e+02 4.31864075e+02 4.89525085e+02 5.35758484e+02 5.55874695e+02 5.95403259e+02 6.57488037e+02 7.34579773e+02 8.07178772e+02 8.36672607e+02 8.36999634e+02 8.60513306e+02 9.26380249e+02 1.02507373e+03 1.10121655e+03 1.12657458e+03 1.11581653e+03 1.15044043e+03 1.27104871e+03 1.31840588e+03 1.29201831e+03 1.34392786e+03 1.43111145e+03 1.47115881e+03 1.55399658e+03 1.56917371e+03 1.55778394e+03 1.64968164e+03 1.67092444e+03 1.74502039e+03 1.83608252e+03 1.80254614e+03 1.87844141e+03 1.98607715e+03 1.99238391e+03 2.02054614e+03 2.07089331e+03 2.12695386e+03 2.16354321e+03 2.21319067e+03 2.18520972e+03 2.21247290e+03 2.39560791e+03 2.51894824e+03 2.49472925e+03 2.42642041e+03 2.41562769e+03 2.48946118e+03 2.64909595e+03 2.77711011e+03 2.77501196e+03 2.68177075e+03 2.71466675e+03 2.85855786e+03 2.89397534e+03 2.89141919e+03 2.93350171e+03 2.98142432e+03 3.01979053e+03 3.16921997e+03 3.16553027e+03 3.09605493e+03 3.21003394e+03 3.16919946e+03 3.28793945e+03 3.43633838e+03 3.35676709e+03 3.49584009e+03 3.48793408e+03 3.40851318e+03 3.55370923e+03 3.48209399e+03 3.60282910e+03 3.89247974e+03 3.70714722e+03 3.55869507e+03 3.69535889e+03 3.90298877e+03 4.07302075e+03 4.05302905e+03 3.85784155e+03 3.78590869e+03 3.89941382e+03 4.11240967e+03 4.34301953e+03 4.25274951e+03 4.05047778e+03 4.10246484e+03 4.25731885e+03 4.35334766e+03 4.29880420e+03 4.30961279e+03 4.38748486e+03 4.40149414e+03 4.61864453e+03 4.68525635e+03 4.43064795e+03 4.44976807e+03 4.59798242e+03 4.62976025e+03 4.70344141e+03 4.71306250e+03 4.87341357e+03 4.81275586e+03 4.67391455e+03 4.83123633e+03 4.75665723e+03 4.91666797e+03 5.28314746e+03 4.99652295e+03 4.70765918e+03 4.87902344e+03 5.19261914e+03 5.36317090e+03 5.38071875e+03 5.11228467e+03 4.96276025e+03 5.09823242e+03 5.34147607e+03 5.59223242e+03 5.50650391e+03 5.20971191e+03 5.19428564e+03 5.42614697e+03 5.49391748e+03 5.63161084e+03 5.66698926e+03 5.37304932e+03 5.40523779e+03 5.65745361e+03 5.73571875e+03 5.65309766e+03 5.64731592e+03 5.63971484e+03 5.59647656e+03 5.89025049e+03 5.95888428e+03 5.76270459e+03 5.73764551e+03 5.73110059e+03 5.82059814e+03 5.88675879e+03 5.90461182e+03 6.11780664e+03 6.11904590e+03 5.95459326e+03 5.87260010e+03 5.78284326e+03 6.06472266e+03 6.40757227e+03 6.26205420e+03 5.98040430e+03 5.88563867e+03 6.11590234e+03 6.46425488e+03 6.22450049e+03 5.91691992e+03 6.09002002e+03 6.33652148e+03 6.45731396e+03 6.65488232e+03 6.48904590e+03 6.17743164e+03 6.13129199e+03 6.30989551e+03 6.43801172e+03 6.49777734e+03 6.47159082e+03 6.45282861e+03 6.41982910e+03 6.53981641e+03 6.47989453e+03 6.35182520e+03 6.41074854e+03 6.44206006e+03 6.69730518e+03 6.76704639e+03 6.56280176e+03 6.62997656e+03 6.63945557e+03 6.65560059e+03 6.51148633e+03 6.38711670e+03 6.73103906e+03 6.99916992e+03 6.76775635e+03 6.47431885e+03 6.54206592e+03 6.89303369e+03 6.96315039e+03 6.78691943e+03 6.76681787e+03 6.59450879e+03 6.58810010e+03 6.85567285e+03 6.79812646e+03 6.71036426e+03 6.56749805e+03 6.55460107e+03 6.93098047e+03 7.14948877e+03 6.77875977e+03 6.62618262e+03 6.78609424e+03 6.81237451e+03 7.01509473e+03 6.96902734e+03 6.61756982e+03 6.65174658e+03 6.86457568e+03 6.86487646e+03 6.86553564e+03 6.93352246e+03 7.18148682e+03 7.26907373e+03 7.12913916e+03 7.09160449e+03 6.63316357e+03 7.49093750e+03 8.80780859e+03 8.44457324e+03 9.78197266e+03 1.51126201e+04 1.42303359e+04 2.03465586e+04 1.82923164e+04 -2.98607775e+06 -6801838. -2.43777750e+06 -4466672. -49551468. 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. 0. 0. 0. 0. 0. 0. 50947440. 50947440. -3.28714275e+06 5.60369258e+04 1.62408652e+04 1.27142715e+04 9.21920508e+03 8.18072217e+03 6.08438379e+03 6.26822119e+03 7.00401465e+03 6.63268848e+03 6.18499561e+03 6.35013818e+03 6.35820361e+03 6.18522852e+03 6.15770459e+03 6.17319580e+03 6.13850000e+03 6.09042578e+03 6.05039600e+03 6.01646533e+03 6.01723535e+03 5.97536377e+03 6.03683838e+03 6.05375830e+03 5.79893213e+03 5.76293506e+03 6.02514697e+03 6.03437842e+03 5.84859326e+03 5.81885596e+03 5.80543115e+03 5.77969434e+03 5.76795605e+03 5.72644678e+03 5.66936963e+03 5.65924365e+03 5.56043945e+03 5.51330908e+03 5.67639404e+03 5.68205176e+03 5.53366943e+03 5.48333594e+03 5.48467188e+03 5.45151660e+03 5.40592236e+03 5.37903320e+03 5.37646338e+03 5.25852344e+03 5.17558496e+03 5.18599951e+03 5.16628516e+03 5.37596289e+03 5.36300684e+03 5.11563818e+03 4.97127832e+03 4.93371973e+03 5.19479639e+03 5.18677246e+03 4.97467725e+03 4.84443945e+03 4.80537012e+03 4.91038477e+03 4.84321729e+03 4.91405322e+03 4.92516943e+03 4.61887793e+03 4.48757178e+03 4.71026758e+03 4.88378174e+03 4.70137354e+03 4.55776221e+03 4.52673779e+03 4.48170312e+03 4.44389795e+03 4.41964258e+03 4.35740039e+03 4.31178516e+03 4.31616211e+03 4.27175244e+03 4.21779492e+03 4.18493555e+03 4.26623535e+03 4.24192871e+03 4.09267603e+03 4.02869849e+03 3.99874756e+03 4.02251318e+03 3.98686768e+03 3.90206104e+03 3.86467993e+03 3.75110010e+03 3.64708447e+03 3.77891724e+03 3.74152466e+03 3.50797974e+03 3.51506641e+03 3.67743091e+03 3.74462134e+03 3.60075171e+03 3.45447876e+03 3.37180518e+03 3.32431079e+03 3.31878149e+03 3.27442944e+03 3.22765698e+03 3.18022510e+03 3.24610156e+03 3.21015552e+03 3.06269604e+03 3.02437891e+03 2.89902783e+03 2.88880200e+03 3.01875537e+03 2.94974219e+03 2.83137524e+03 2.72626099e+03 2.64419482e+03 2.73390649e+03 2.74232617e+03 2.62348975e+03 2.50541113e+03 2.45268921e+03 2.45782520e+03 2.41815552e+03 2.45440820e+03 2.41692676e+03 2.29581885e+03 2.22989819e+03 2.17940771e+03 2.17833374e+03 2.14343359e+03 2.06943433e+03 2.01347388e+03 1.97014490e+03 1.91552563e+03 1.82089209e+03 1.79964709e+03 1.85347266e+03 1.79455347e+03 1.69606311e+03 1.61175000e+03 1.56403638e+03 1.59945654e+03 1.55850745e+03 1.46974707e+03 1.38839795e+03 1.33460864e+03 1.32724255e+03 1.27909753e+03 1.23391479e+03 1.15573511e+03 1.13326965e+03 1.15311499e+03 1.07507227e+03 1.00082935e+03 9.53576233e+02 9.05623779e+02 8.55686951e+02 8.09235779e+02 7.55958435e+02 7.05268127e+02 6.62698914e+02 5.99760681e+02 5.62904358e+02 5.47331421e+02 4.76987244e+02 4.15593231e+02 3.79629974e+02 3.29994476e+02 2.93311890e+02 2.41630920e+02 1.85584778e+02 1.44510513e+02 9.66297913e+01 4.72378654e+01 -9.12220776e-01 -4.86174965e+01 -9.70130005e+01 -1.44805222e+02 -1.89810135e+02 -2.30957962e+02 -2.86735962e+02 -3.51878204e+02 -3.92570404e+02 -4.30976532e+02 -4.66381866e+02 -5.10548187e+02 -5.87470459e+02 -6.40071594e+02 -6.73030029e+02 -7.00276611e+02 -7.39924316e+02 -8.11812378e+02 -8.61471680e+02 -9.26596436e+02 -9.61812927e+02 -9.82350159e+02 -1.03821484e+03 -1.08365027e+03 -1.17208716e+03 -1.21473120e+03 -1.22009705e+03 -1.28021326e+03 -1.33121692e+03 -1.36691418e+03 -1.37515442e+03 -1.45318860e+03 -1.59076526e+03 -1.60736755e+03 -1.60582312e+03 -1.60943213e+03 -1.64451465e+03 -1.79319165e+03 -1.85335925e+03 -1.83888574e+03 -1.83701367e+03 -1.87574670e+03 -1.98235522e+03 -2.02913977e+03 -2.12034790e+03 -2.15127344e+03 -2.14114062e+03 -2.16578589e+03 -2.20107593e+03 -2.35101392e+03 -2.39868994e+03 -2.37677148e+03 -2.39492871e+03 -2.43223560e+03 -2.56875610e+03 -2.62547510e+03 -2.53525049e+03 -2.57058301e+03 -2.77606689e+03 -2.82331128e+03 -2.71456030e+03 -2.74662427e+03 -2.93156470e+03 -3.00219263e+03 -2.95192578e+03 -2.91306494e+03 -2.96593262e+03 -3.17249561e+03 -3.17931152e+03 -3.12248340e+03 -3.23219897e+03 -3.28010767e+03 -3.27522705e+03 -3.29196582e+03 -3.35151929e+03 -3.31148706e+03 -3.43981323e+03 -3.68080396e+03 -3.60356128e+03 -3.60311499e+03 -3.66641064e+03 -3.67186841e+03 -3.71175977e+03 -3.73312671e+03 -3.78605127e+03 -3.74117969e+03 -3.71285718e+03 -3.84539917e+03 -3.98587842e+03 -4.12734863e+03 -4.03431201e+03 -3.92188403e+03 -4.06705151e+03 -4.16392969e+03 -4.32931689e+03 -4.32823584e+03 -4.23854297e+03 -4.20023096e+03 -4.20015283e+03 -4.35209570e+03 -4.40348975e+03 -4.53763965e+03 -4.58353027e+03 -4.49634082e+03 -4.45264648e+03 -4.39008154e+03 -4.56889258e+03 -4.86447168e+03 -4.83629736e+03 -4.74186230e+03 -4.65035352e+03 -4.60120166e+03 -4.87088428e+03 -5.04209961e+03 -4.94079688e+03 -4.81411523e+03 -4.83310010e+03 -4.97824463e+03 -5.01187109e+03 -5.17638330e+03 -5.23255322e+03 -5.11797607e+03 -5.07626904e+03 -5.08595068e+03 -5.30615088e+03 -5.32855469e+03 -5.13140283e+03 -5.14259473e+03 -5.48365576e+03 -5.46024414e+03 -5.20260059e+03 -5.30944873e+03 -5.59811914e+03 -5.61639551e+03 -5.53848389e+03 -5.39897119e+03 -5.39158301e+03 -5.72153760e+03 -5.80168213e+03 -5.65020459e+03 -5.52300244e+03 -5.51605957e+03 -5.69710156e+03 -5.78124951e+03 -5.79090088e+03 -5.64186377e+03 -5.78685742e+03 -6.13938916e+03 -5.99483008e+03 -5.96372852e+03 -5.99921191e+03 -5.95634814e+03 -5.96250195e+03 -6.00351465e+03 -6.02546436e+03 -6.01709424e+03 -5.96701221e+03 -5.85966602e+03 -6.03656592e+03 -6.36149805e+03 -6.15394580e+03 -5.93409424e+03 -6.14926221e+03 -6.27174756e+03 -6.45739355e+03 -6.38402881e+03 -6.18809961e+03 -6.34906445e+03 -6.41381055e+03 -6.19537354e+03 -6.20505029e+03 -6.46607178e+03 -6.47234912e+03 -6.36873389e+03 -6.26303369e+03 -6.10448096e+03 -6.41112695e+03 -6.82773047e+03 -6.68337109e+03 -6.46275586e+03 -6.33369629e+03 -6.31690283e+03 -6.63833154e+03 -6.80783643e+03 -6.59971094e+03 -6.45228320e+03 -6.43678076e+03 -6.52142480e+03 -6.59011572e+03 -6.78565088e+03 -6.76679395e+03 -6.62524268e+03 -6.65085889e+03 -6.60716211e+03 -6.79868896e+03 -6.83204248e+03 -6.72263428e+03 -6.61422754e+03 -6.59376074e+03 -6.70492334e+03 -6.58273633e+03 -6.62814258e+03 -6.95562891e+03 -6.92063330e+03 -6.82455029e+03 -6.63296338e+03 -6.56033252e+03 -6.98163818e+03 -7.00472754e+03 -6.82898193e+03 -6.70898438e+03 -6.62720703e+03 -6.75751904e+03 -6.72835840e+03 -6.83555518e+03 -6.69365137e+03 -6.83416943e+03 -7.10584814e+03 -6.89984961e+03 -6.96052881e+03 -6.96200781e+03 -6.83619336e+03 -6.78563916e+03 -6.71679736e+03 -6.74687158e+03 -6.81409131e+03 -6.86102197e+03 -6.84678076e+03 -6.88760986e+03 -6.92806201e+03 -6.68400391e+03 -6.57047803e+03 -6.76841064e+03 -6.86789258e+03 -7.07497461e+03 -6.93191064e+03 -6.71205029e+03 -6.91578857e+03 -6.88141602e+03 -6.74486035e+03 -6.77815576e+03 -6.78040723e+03 -6.70701465e+03 -6.70536621e+03 -6.75317627e+03 -6.62022998e+03 -6.72011426e+03 -7.02364307e+03 -6.90689893e+03 -6.77411523e+03 -6.65640820e+03 -6.52586914e+03 -6.91215625e+03 -6.89089795e+03 -6.71703027e+03 -6.51854248e+03 -6.39645557e+03 -6.61943408e+03 -6.72332715e+03 -6.89605127e+03 -6.68517432e+03 -6.48857129e+03 -6.59157715e+03 -6.50518359e+03 -6.72372266e+03 -6.69000146e+03 -6.46949609e+03 -6.48057471e+03 -6.44459473e+03 -6.52045801e+03 -6.31403613e+03 -6.44673633e+03 -6.76262256e+03 -6.57885986e+03 -6.49840381e+03 -6.35015332e+03 -6.21524512e+03 -6.54881689e+03 -6.56827295e+03 -6.33841699e+03 -6.19383838e+03 -6.16426074e+03 -6.27851709e+03 -6.30859326e+03 -6.44807275e+03 -6.42114795e+03 -6.23528760e+03 -6.06778809e+03 -6.01454297e+03 -6.37812061e+03 -6.30904297e+03 -6.07221729e+03 -6.13547607e+03 -6.09464795e+03 -5.99438672e+03 -5.97370752e+03 -6.09539795e+03 -5.95256641e+03 -5.81391211e+03 -6.09419580e+03 -6.14608350e+03 -5.91366260e+03 -5.83639746e+03 -5.84975684e+03 -5.84501318e+03 -5.64855176e+03 -5.58914551e+03 -5.87481299e+03 -5.86594482e+03 -5.49900488e+03 -5.40208691e+03 -5.70505762e+03 -5.90335400e+03 -5.71683643e+03 -5.48145068e+03 -5.41205127e+03 -5.61471729e+03 -5.53931152e+03 -5.38190674e+03 -5.44573389e+03 -5.29998486e+03 -5.11021826e+03 -5.29075049e+03 -5.49239502e+03 -5.42787500e+03 -5.18990137e+03 -5.02734375e+03 -5.26367090e+03 -5.33593164e+03 -5.14162256e+03 -5.00020947e+03 -4.94874951e+03 -4.96330811e+03 -4.95156348e+03 -5.08671289e+03 -4.97712109e+03 -4.76871289e+03 -4.84795605e+03 -4.82418262e+03 -4.84878906e+03 -4.71911426e+03 -4.58497754e+03 -4.74033301e+03 -4.69998096e+03 -4.62383545e+03 -4.46880664e+03 -4.46309912e+03 -4.68763965e+03 -4.47775049e+03 -4.30908936e+03 -4.38497900e+03 -4.35540527e+03 -4.32549316e+03 -4.28961328e+03 -4.34540576e+03 -4.33377881e+03 -4.18161328e+03 -4.01821240e+03 -3.97233105e+03 -4.16173145e+03 -4.05999707e+03 -3.89947412e+03 -3.94268188e+03 -3.90539893e+03 -3.86482104e+03 -3.83177368e+03 -3.85558984e+03 -3.71844141e+03 -3.60325366e+03 -3.71879443e+03 -3.69006885e+03 -3.59875391e+03 -3.56743921e+03 -3.52183301e+03 -3.47110376e+03 -3.33112036e+03 -3.25246753e+03 -3.38652588e+03 -3.41965405e+03 -3.20066895e+03 -3.06993677e+03 -3.19447998e+03 -3.25930005e+03 -3.13251392e+03 -2.98318481e+03 -2.90292725e+03 -2.99577490e+03 -2.97298950e+03 -2.84005957e+03 -2.86777661e+03 -2.82874023e+03 -2.69501611e+03 -2.64018188e+03 -2.67550537e+03 -2.67308789e+03 -2.52132593e+03 -2.42837891e+03 -2.51232568e+03 -2.50248975e+03 -2.39236108e+03 -2.28121094e+03 -2.21691479e+03 -2.29277319e+03 -2.27002002e+03 -2.14545483e+03 -2.09206177e+03 -2.05814551e+03 -2.00229016e+03 -1.94899438e+03 -1.98090918e+03 -1.89355554e+03 -1.77999988e+03 -1.81981189e+03 -1.78764868e+03 -1.71989807e+03 -1.63044885e+03 -1.56482532e+03 -1.58051099e+03 -1.50504663e+03 -1.46722363e+03 -1.55954651e+03 -1.45916016e+03 -1.37008765e+03 -1.27417493e+03 -2.34497021e+03 -3.50586304e+03 -2.69119824e+03 -3.11258789e+03 -3.21375098e+03 -1.69030566e+03 -2.88404736e+03 -9.02785742e+03 -95812040. 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. 0. 0. 61294816. 1.34376325e+06 -8.15503188e+05 -2.48378016e+05 2.23532739e+03 1.64756763e+03 1.19596289e+03 1.08086145e+03 1.10162512e+03 1.07809741e+03 1.10488501e+03 1.15350781e+03 1.20866418e+03 1.23362158e+03 1.26754419e+03 1.31865918e+03 1.35888660e+03 1.42936267e+03 1.50600854e+03 1.57558936e+03 1.55964709e+03 1.56993188e+03 1.67142578e+03 1.67274622e+03 1.66647705e+03 1.78894299e+03 1.89918567e+03 1.93307727e+03 1.95086084e+03 1.94801355e+03 1.99765869e+03 2.07669409e+03 2.10266455e+03 2.12237378e+03 2.22344751e+03 2.30550830e+03 2.29446729e+03 2.31755103e+03 2.38252881e+03 2.43234717e+03 2.49474658e+03 2.52228662e+03 2.51318481e+03 2.61697900e+03 2.72841675e+03 2.67432617e+03 2.69767407e+03 2.79930811e+03 2.78520142e+03 2.84712744e+03 2.96912476e+03 2.97132471e+03 2.97472705e+03 3.06177539e+03 3.16634497e+03 3.14604199e+03 3.09866504e+03 3.13796997e+03 3.19025757e+03 3.34388379e+03 3.44485254e+03 3.39024731e+03 3.40556592e+03 3.43791064e+03 3.47049268e+03 3.52695239e+03 3.54400586e+03 3.56306323e+03 3.67025952e+03 3.81651562e+03 3.76909668e+03 3.73853003e+03 3.85467261e+03 3.87923535e+03 3.88223730e+03 3.94488770e+03 4.01188940e+03 4.01585278e+03 4.01689453e+03 4.12606250e+03 4.15696826e+03 4.18948877e+03 4.22999561e+03 4.16731641e+03 4.27401514e+03 4.43444580e+03 4.38860693e+03 4.35183594e+03 4.42339844e+03 4.44913379e+03 4.51043359e+03 4.53518848e+03 4.49701709e+03 4.61250342e+03 4.78831055e+03 4.73579346e+03 4.62964014e+03 4.69257031e+03 4.82511963e+03 4.86196973e+03 4.85548975e+03 4.87852441e+03 4.84983057e+03 4.98726025e+03 5.13191992e+03 5.01394043e+03 4.95995654e+03 5.00177197e+03 5.04591797e+03 5.18565967e+03 5.24897803e+03 5.19980420e+03 5.25561816e+03 5.40950488e+03 5.40977148e+03 5.30102930e+03 5.27314111e+03 5.30878955e+03 5.40931445e+03 5.51097168e+03 5.55365137e+03 5.50353369e+03 5.55536963e+03 5.61172266e+03 5.51924951e+03 5.53438232e+03 5.64736328e+03 5.64586035e+03 5.75895850e+03 5.85990234e+03 5.67623486e+03 5.70562500e+03 5.87851025e+03 5.83568994e+03 5.74001904e+03 5.84739258e+03 6.04628711e+03 6.01679883e+03 5.97743213e+03 5.95709326e+03 5.95888281e+03 5.99284570e+03 5.96382520e+03 6.03523730e+03 6.12026562e+03 6.11665186e+03 6.12509668e+03 6.22892822e+03 6.20394141e+03 6.03411328e+03 6.14859473e+03 6.31664404e+03 6.23516064e+03 6.31616309e+03 6.41667529e+03 6.40999854e+03 6.26702539e+03 6.27431934e+03 6.32000732e+03 6.24857812e+03 6.39311670e+03 6.53110205e+03 6.47890381e+03 6.42934375e+03 6.41188867e+03 6.43917334e+03 6.49006982e+03 6.45840625e+03 6.40737305e+03 6.50987158e+03 6.62634619e+03 6.54911865e+03 6.52345703e+03 6.62030176e+03 6.57597559e+03 6.66687012e+03 6.58959717e+03 6.57665771e+03 6.69592725e+03 6.66510400e+03 6.67504199e+03 6.64302588e+03 6.69665967e+03 6.81166016e+03 6.55582666e+03 6.60456494e+03 6.84326660e+03 6.73318945e+03 6.80096680e+03 6.77119141e+03 6.70990039e+03 6.70702637e+03 6.68356885e+03 6.67140771e+03 6.69582861e+03 6.80092871e+03 6.89794727e+03 6.99193848e+03 6.88411719e+03 6.82252441e+03 6.81142871e+03 6.71771094e+03 6.68915137e+03 6.74187402e+03 6.89004395e+03 7.01772412e+03 6.78305713e+03 6.73256348e+03 6.87477539e+03 6.69667090e+03 6.81120166e+03 6.94783740e+03 6.81732568e+03 6.79674414e+03 6.86306787e+03 6.91592578e+03 6.88050146e+03 6.77992041e+03 6.80323340e+03 6.69850781e+03 6.77377344e+03 6.86496484e+03 6.91061865e+03 6.83758740e+03 6.85794775e+03 6.87406055e+03 6.76200781e+03 6.82202295e+03 6.91398779e+03 6.76123877e+03 6.64093652e+03 6.77497510e+03 6.78574609e+03 6.82062695e+03 6.74984424e+03 6.65954199e+03 6.77371484e+03 6.71947119e+03 6.76215088e+03 6.73064746e+03 6.81539307e+03 6.79378809e+03 6.54334375e+03 6.63924707e+03 6.66363086e+03 6.60756836e+03 6.77584521e+03 6.60005908e+03 6.49061230e+03 6.73832471e+03 6.73014355e+03 6.45434082e+03 6.42864844e+03 6.63592383e+03 6.62593848e+03 6.46721289e+03 6.53135547e+03 6.66252490e+03 6.45388330e+03 6.40976611e+03 6.44397900e+03 6.31149463e+03 6.43334424e+03 6.50854688e+03 6.34266650e+03 6.41079102e+03 6.48992578e+03 6.35834814e+03 6.26349121e+03 6.22273389e+03 6.28651367e+03 6.38955371e+03 6.22529004e+03 6.14183496e+03 6.18297021e+03 6.20566943e+03 6.12617871e+03 6.10012158e+03 6.12313428e+03 6.11551611e+03 6.05194678e+03 6.09474463e+03 6.14327979e+03 5.98640137e+03 5.97416992e+03 6.00843359e+03 5.84921045e+03 5.99655078e+03 5.97899902e+03 5.74954639e+03 5.87095166e+03 5.83745996e+03 5.73787061e+03 5.82049951e+03 5.73760352e+03 5.72759229e+03 5.80993555e+03 5.66686572e+03 5.62166943e+03 5.59705420e+03 5.50638184e+03 5.49014160e+03 5.48391748e+03 5.54898682e+03 5.56376904e+03 5.49970264e+03 5.43588525e+03 5.44263281e+03 5.36968359e+03 5.24805762e+03 5.27025244e+03 5.38439160e+03 5.32403760e+03 5.14616064e+03 5.08050000e+03 5.16051123e+03 5.19801270e+03 5.07801758e+03 4.98798584e+03 5.00319580e+03 5.01620898e+03 5.04061768e+03 4.95735986e+03 4.84643701e+03 4.77147363e+03 4.75255420e+03 4.77583105e+03 4.72604492e+03 4.73506885e+03 4.74292041e+03 4.64502148e+03 4.63272852e+03 4.68874072e+03 4.58954785e+03 4.43754248e+03 4.47693604e+03 4.55230957e+03 4.43554639e+03 4.24830566e+03 4.20744092e+03 4.29005078e+03 4.31189014e+03 4.22702441e+03 4.17477881e+03 4.13094873e+03 4.15405566e+03 4.11433545e+03 3.93074951e+03 3.90180176e+03 3.95574219e+03 3.96282739e+03 3.85576538e+03 3.74500391e+03 3.76110352e+03 3.73845654e+03 3.73934106e+03 3.75032544e+03 3.68666699e+03 3.54604126e+03 3.43470386e+03 3.50133521e+03 3.55951440e+03 3.44283252e+03 3.33577612e+03 3.27171655e+03 3.28474072e+03 3.31790991e+03 3.19424341e+03 3.13770752e+03 3.13199683e+03 3.13173364e+03 3.09230444e+03 2.94702734e+03 2.93739526e+03 2.92584375e+03 2.84913452e+03 2.82716162e+03 2.76991602e+03 2.71924121e+03 2.68282031e+03 2.63350879e+03 2.59870166e+03 2.58607910e+03 2.54548364e+03 2.45515527e+03 2.43231958e+03 2.40541211e+03 2.33393213e+03 2.28384619e+03 2.18752710e+03 2.16863403e+03 2.20723511e+03 2.14215283e+03 2.05748877e+03 1.97177686e+03 1.94748315e+03 1.96792261e+03 1.89163745e+03 1.83433911e+03 1.81247424e+03 1.74369092e+03 1.67436499e+03 1.65061694e+03 1.61430737e+03 1.54272522e+03 1.51633691e+03 1.46692151e+03 1.38547461e+03 1.36774207e+03 1.33202747e+03 1.28101880e+03 1.25385388e+03 1.19646191e+03 1.13882581e+03 1.08319482e+03 1.03298999e+03 9.98789429e+02 9.57254700e+02 9.05260559e+02 8.50229797e+02 8.08301514e+02 7.57170044e+02 7.06525269e+02 6.73427979e+02 6.20103088e+02 5.65135071e+02 5.21414795e+02 4.75333954e+02 4.27929077e+02 3.82220978e+02 3.33185638e+02 2.80275665e+02 2.36502609e+02 1.91081192e+02 1.40881027e+02 9.28155899e+01 4.55476189e+01 -1.70364511e+00 -4.91051369e+01 -9.61079254e+01 -1.43877792e+02 -1.95372543e+02 -2.44709763e+02 -2.97826538e+02 -3.38044983e+02 -3.73563904e+02 -4.32106995e+02 -4.88180084e+02 -5.28050537e+02 -5.70177673e+02 -6.20246887e+02 -6.71424500e+02 -7.22006897e+02 -7.66918701e+02 -8.01867249e+02 -8.48615112e+02 -9.11878052e+02 -9.59045044e+02 -9.99742920e+02 -1.04137842e+03 -1.08819885e+03 -1.14844360e+03 -1.19514417e+03 -1.24547290e+03 -1.29344690e+03 -1.33235815e+03 -1.37536670e+03 -1.42999365e+03 -1.48178333e+03 -1.49036462e+03 -1.53585327e+03 -1.62060107e+03 -1.67242322e+03 -1.72988037e+03 -1.74672693e+03 -1.78640161e+03 -1.82840100e+03 -1.87184863e+03 -1.96694873e+03 -1.96510449e+03 -2.00249902e+03 -2.10889941e+03 -2.09683398e+03 -2.12300854e+03 -2.23050000e+03 -2.27169141e+03 -2.30964453e+03 -2.37638428e+03 -2.37997852e+03 -2.35476953e+03 -2.46942261e+03 -2.56429663e+03 -2.55034351e+03 -2.65655933e+03 -2.69979980e+03 -2.64902710e+03 -2.70762671e+03 -2.75674561e+03 -2.79888281e+03 -2.89165137e+03 -2.93526221e+03 -2.96788306e+03 -3.01188525e+03 -3.04657056e+03 -3.11317188e+03 -3.13135449e+03 -3.13306616e+03 -3.19581250e+03 -3.25612231e+03 -3.26858594e+03 -3.34063428e+03 -3.40582471e+03 -3.39461499e+03 -3.46630542e+03 -3.53007886e+03 -3.57376074e+03 -3.60998657e+03 -3.55859277e+03 -3.62992822e+03 -3.77891846e+03 -3.80218701e+03 -3.75664087e+03 -3.82991235e+03 -3.90766309e+03 -3.92665674e+03 -3.95742017e+03 -3.88206030e+03 -3.90652051e+03 -4.08019897e+03 -4.17374951e+03 -4.20508740e+03 -4.12877637e+03 -4.16387158e+03 -4.28957959e+03 -4.29471191e+03 -4.31739795e+03 -4.36224023e+03 -4.37115625e+03 -4.43475537e+03 -4.48782324e+03 -4.57437793e+03 -4.54784131e+03 -4.51326660e+03 -4.68375879e+03 -4.66102100e+03 -4.63890186e+03 -4.68049609e+03 -4.67169580e+03 -4.78848242e+03 -4.94578760e+03 -4.94725098e+03 -4.80249316e+03 -4.84301172e+03 -4.99962109e+03 -5.02387500e+03 -5.04703662e+03 -5.04279736e+03 -5.12025439e+03 -5.16687354e+03 -5.16828564e+03 -5.23814453e+03 -5.20220605e+03 -5.25354443e+03 -5.35455469e+03 -5.15752686e+03 -5.19228467e+03 -5.43243506e+03 -5.47271875e+03 -5.42851514e+03 -5.42887061e+03 -5.39995898e+03 -5.44146094e+03 -5.61060889e+03 -5.69562158e+03 -5.59884229e+03 -5.54622998e+03 -5.54233057e+03 -5.63929102e+03 -5.73419287e+03 -5.79825732e+03 -5.83964014e+03 -5.75440967e+03 -5.79005176e+03 -5.85239990e+03 -5.77260059e+03 -5.78857666e+03 -5.97135596e+03 -5.99676660e+03 -5.94648096e+03 -5.96208887e+03 -5.97666699e+03 -6.02635303e+03 -5.99722119e+03 -6.10158887e+03 -6.07862061e+03 -6.12706641e+03 -6.13033350e+03 -6.09687695e+03 -6.34354834e+03 -6.18624561e+03 -6.15127100e+03 -6.35120947e+03 -6.21140918e+03 -6.19086133e+03 -6.31334082e+03 -6.34426611e+03 -6.25535889e+03 -6.42593604e+03 -6.50572754e+03 -6.37828564e+03 -6.56627539e+03 -6.64139355e+03 -6.16783398e+03 -5.86286084e+03 -6.97774365e+03 -7.54365723e+03 -7.99564648e+03 -8.76127832e+03 -1.16990225e+04 -8.78295020e+03 -1.46073623e+04 -1.36412594e+05 43397152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 66855588. 1.62207450e+06 -2.20699225e+06 5557439. 51155096. -1.04991338e+06 -2.68851950e+06 -1.97057441e+04 -1.56897344e+04 -9.15435840e+03 -6.55859570e+03 -7.05949023e+03 -7.15754395e+03 -6.92442139e+03 -6.85365771e+03 -6.85188232e+03 -6.79158447e+03 -6.91357764e+03 -6.96202002e+03 -6.79890820e+03 -6.61245605e+03 -6.74504004e+03 -6.84136865e+03 -6.81530518e+03 -6.79288818e+03 -6.52357520e+03 -6.58550293e+03 -6.90487793e+03 -6.73968213e+03 -6.59183008e+03 -6.52720459e+03 -6.57154736e+03 -6.86049951e+03 -6.89632715e+03 -6.67328027e+03 -6.38685156e+03 -6.48336230e+03 -6.68155615e+03 -6.68658838e+03 -6.60364893e+03 -6.52173193e+03 -6.59704443e+03 -6.62261377e+03 -6.58974121e+03 -6.62252344e+03 -6.34074512e+03 -6.45285303e+03 -6.78483350e+03 -6.49184619e+03 -6.34082715e+03 -6.34406641e+03 -6.31063184e+03 -6.52335059e+03 -6.52088379e+03 -6.31167480e+03 -6.20058105e+03 -6.38284033e+03 -6.47301514e+03 -6.33555762e+03 -6.24431836e+03 -6.12363721e+03 -6.24770068e+03 -6.39200146e+03 -6.16580908e+03 -6.15942334e+03 -6.09531641e+03 -6.03017578e+03 -6.20746240e+03 -6.24215430e+03 -6.10691602e+03 -5.96069873e+03 -6.02173682e+03 -6.03338623e+03 -6.03045068e+03 -6.04155664e+03 -5.81269287e+03 -5.80621875e+03 -6.09406299e+03 -5.90257520e+03 -5.65798389e+03 -5.63933447e+03 -5.82468066e+03 -5.97763770e+03 -5.84744922e+03 -5.73351074e+03 -5.61393604e+03 -5.51966016e+03 -5.62225146e+03 -5.74304346e+03 -5.60599414e+03 -5.43597168e+03 -5.54486621e+03 -5.54267480e+03 -5.48664111e+03 -5.58222803e+03 -5.34647803e+03 -5.26572949e+03 -5.47140039e+03 -5.39917822e+03 -5.25447412e+03 -5.18538281e+03 -5.12369238e+03 -5.27116895e+03 -5.27968945e+03 -5.10239795e+03 -5.04711914e+03 -5.12386572e+03 -5.10753027e+03 -5.01280664e+03 -5.04750000e+03 -4.92666064e+03 -4.83478906e+03 -4.97962939e+03 -4.89373486e+03 -4.71831104e+03 -4.65718262e+03 -4.69792383e+03 -4.84389111e+03 -4.81895361e+03 -4.68701514e+03 -4.49054834e+03 -4.42648145e+03 -4.60783594e+03 -4.59245996e+03 -4.42650879e+03 -4.35287598e+03 -4.38596289e+03 -4.42682861e+03 -4.33314502e+03 -4.25129492e+03 -4.15363037e+03 -4.20347803e+03 -4.32475977e+03 -4.14595654e+03 -4.06822144e+03 -4.06100269e+03 -3.96852393e+03 -4.00038428e+03 -3.98065649e+03 -3.88537280e+03 -3.77561108e+03 -3.77601392e+03 -3.87978198e+03 -3.83394092e+03 -3.73155981e+03 -3.60440601e+03 -3.55318530e+03 -3.63325537e+03 -3.60470166e+03 -3.53244678e+03 -3.39199951e+03 -3.30798486e+03 -3.38117896e+03 -3.40928906e+03 -3.34081274e+03 -3.21296313e+03 -3.17650684e+03 -3.16787012e+03 -3.14344141e+03 -3.13844678e+03 -3.03238745e+03 -2.97258447e+03 -2.97927588e+03 -2.90916772e+03 -2.85247754e+03 -2.79264453e+03 -2.80205542e+03 -2.77778687e+03 -2.66239233e+03 -2.62231396e+03 -2.56718701e+03 -2.57009766e+03 -2.61474072e+03 -2.50566504e+03 -2.38262036e+03 -2.32721680e+03 -2.31445996e+03 -2.33993921e+03 -2.31662158e+03 -2.24421924e+03 -2.11593555e+03 -2.01970007e+03 -2.05752686e+03 -2.07063623e+03 -2.02654858e+03 -1.90137366e+03 -1.83770862e+03 -1.85803589e+03 -1.81026416e+03 -1.76418384e+03 -1.69263074e+03 -1.63085730e+03 -1.60621729e+03 -1.55111707e+03 -1.51070679e+03 -1.46619971e+03 -1.41291150e+03 -1.39476953e+03 -1.32938953e+03 -1.26937720e+03 -1.22914001e+03 -1.19399890e+03 -1.15885034e+03 -1.08959595e+03 -1.02223779e+03 -9.74680847e+02 -9.68573486e+02 -9.34149536e+02 -8.59284241e+02 -8.01693909e+02 -7.35100769e+02 -6.97952759e+02 -6.86028625e+02 -6.37234497e+02 -5.77815735e+02 -5.09847687e+02 -4.59214752e+02 -4.37418427e+02 -3.94151825e+02 -3.33025543e+02 -2.84135071e+02 -2.40458054e+02 -1.90941055e+02 -1.41440475e+02 -9.24877319e+01 -4.58003654e+01 7.52172887e-01 4.98887787e+01 1.01168556e+02 1.48286316e+02 1.87089661e+02 2.36612350e+02 2.89108093e+02 3.35687225e+02 3.86977997e+02 4.28762604e+02 4.88729919e+02 5.37950623e+02 5.55706848e+02 5.95117737e+02 6.58345947e+02 7.34423157e+02 8.05195740e+02 8.38158630e+02 8.39973877e+02 8.55611206e+02 9.22726562e+02 1.02722717e+03 1.10734985e+03 1.12812659e+03 1.10965381e+03 1.14622913e+03 1.27788513e+03 1.32373462e+03 1.29760254e+03 1.35485278e+03 1.41672571e+03 1.46052588e+03 1.55554700e+03 1.57163623e+03 1.56087695e+03 1.64934656e+03 1.67008801e+03 1.75399597e+03 1.83055005e+03 1.78816907e+03 1.88733765e+03 1.98647778e+03 1.98157178e+03 2.02481140e+03 2.06900146e+03 2.11603516e+03 2.17149731e+03 2.21306641e+03 2.18527026e+03 2.22032837e+03 2.39445605e+03 2.52117163e+03 2.50145215e+03 2.41663306e+03 2.40646558e+03 2.49889429e+03 2.65967212e+03 2.77715527e+03 2.75806396e+03 2.68298779e+03 2.72094141e+03 2.83832422e+03 2.88238135e+03 2.89963232e+03 2.94814062e+03 2.98493188e+03 3.02209351e+03 3.18575244e+03 3.16048242e+03 3.09782178e+03 3.22661987e+03 3.18987378e+03 3.30447656e+03 3.40614551e+03 3.33942749e+03 3.51543872e+03 3.49385962e+03 3.38523755e+03 3.54886450e+03 3.49836426e+03 3.57854077e+03 3.88299585e+03 3.73320483e+03 3.54843799e+03 3.66213257e+03 3.91217358e+03 4.10314209e+03 4.04024707e+03 3.85161304e+03 3.81386719e+03 3.90380640e+03 4.10536768e+03 4.31242090e+03 4.26354150e+03 4.06147681e+03 4.08373242e+03 4.24831201e+03 4.32181836e+03 4.32920703e+03 4.35898389e+03 4.39149023e+03 4.40261475e+03 4.60743945e+03 4.65333887e+03 4.39763379e+03 4.42538037e+03 4.62873633e+03 4.67293311e+03 4.70247070e+03 4.71980322e+03 4.88104639e+03 4.81722559e+03 4.66515234e+03 4.83810303e+03 4.74970996e+03 4.90712451e+03 5.27853223e+03 4.99738623e+03 4.72340137e+03 4.91559912e+03 5.19821582e+03 5.36744678e+03 5.36916162e+03 5.07094971e+03 4.94203809e+03 5.11291504e+03 5.36474902e+03 5.55496973e+03 5.48359521e+03 5.20298730e+03 5.20954248e+03 5.44476465e+03 5.50558350e+03 5.62530664e+03 5.67803174e+03 5.39978955e+03 5.38295508e+03 5.69883545e+03 5.75874805e+03 5.54814746e+03 5.55580957e+03 5.70830225e+03 5.65976953e+03 5.88695264e+03 5.95435059e+03 5.74296338e+03 5.73964990e+03 5.74662549e+03 5.82478027e+03 5.89620557e+03 5.85654053e+03 6.06542578e+03 6.19074805e+03 6.01500928e+03 5.85505078e+03 5.73389062e+03 6.04081348e+03 6.44085645e+03 6.28953760e+03 5.94268555e+03 5.85374121e+03 6.08807324e+03 6.46757764e+03 6.31760938e+03 5.95168896e+03 6.07556250e+03 6.27626025e+03 6.48222949e+03 6.64918799e+03 6.47637842e+03 6.13267090e+03 6.15788721e+03 6.33824414e+03 6.43218701e+03 6.46964111e+03 6.46228711e+03 6.47261426e+03 6.44179883e+03 6.53706689e+03 6.49226416e+03 6.41004932e+03 6.43083447e+03 6.36479980e+03 6.63595898e+03 6.71524707e+03 6.54525879e+03 6.68171143e+03 6.70010254e+03 6.62681885e+03 6.50188428e+03 6.36547021e+03 6.69320117e+03 6.99163379e+03 6.84083008e+03 6.54770850e+03 6.46650195e+03 6.83706787e+03 6.97677490e+03 6.78673535e+03 6.73606299e+03 6.55314648e+03 6.54628809e+03 6.87636523e+03 6.83712256e+03 6.70486426e+03 6.57148584e+03 6.50829736e+03 6.90125928e+03 7.15413086e+03 6.74581396e+03 6.62242432e+03 6.82973535e+03 6.83524365e+03 7.04123730e+03 6.96459375e+03 6.57546875e+03 6.66780176e+03 6.91661719e+03 6.82936914e+03 6.85744922e+03 6.90044775e+03 7.15204443e+03 7.02022852e+03 6.51155762e+03 6.78443896e+03 6.82086670e+03 7.13025195e+03 6.82035303e+03 6.62331689e+03 6.61457373e+03 8.66384375e+03 8.55835742e+03 1.03190195e+04 8.60672070e+03 1.27230771e+04 2.24452520e+04 2.97645762e+04 -4466672. -49551468. 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. 0. 0. 0. 0. 0. 0. 50947440. 50947440. -3.28714275e+06 -5.08869550e+06 -4127077. -1.70640425e+06 2.00020371e+04 1.53695664e+04 7.97463574e+03 6.42759570e+03 7.49706689e+03 6.69499219e+03 6.14615039e+03 6.38590918e+03 6.38619922e+03 6.18846631e+03 6.17663428e+03 6.17854736e+03 6.24371875e+03 6.29121777e+03 6.06318555e+03 5.83500732e+03 6.03104785e+03 6.00215479e+03 5.59515967e+03 5.91234961e+03 6.09317139e+03 5.60090283e+03 5.91707520e+03 6.16809961e+03 5.85794189e+03 5.69952393e+03 5.81596436e+03 5.93166113e+03 5.81392578e+03 5.76307275e+03 5.69734521e+03 5.66200098e+03 5.55215137e+03 5.53350439e+03 5.66774707e+03 5.66200049e+03 5.53581445e+03 5.48653955e+03 5.48555127e+03 5.47697266e+03 5.40203223e+03 5.37274707e+03 5.35734277e+03 5.26195508e+03 5.22157666e+03 5.17232080e+03 5.14248584e+03 5.37275000e+03 5.35283398e+03 5.13017871e+03 4.96256592e+03 4.92250684e+03 5.20053516e+03 5.19765283e+03 4.97564893e+03 4.81641357e+03 4.80653369e+03 4.85751709e+03 4.80351904e+03 4.96048877e+03 4.94269629e+03 4.59397705e+03 4.48445508e+03 4.68484814e+03 4.90958154e+03 4.74593799e+03 4.56092529e+03 4.53016553e+03 4.47861182e+03 4.47439111e+03 4.47344141e+03 4.36888232e+03 4.29707861e+03 4.29107959e+03 4.24549805e+03 4.21112939e+03 4.18098535e+03 4.26681494e+03 4.21092090e+03 4.06247144e+03 4.01541724e+03 3.97507764e+03 4.04705469e+03 4.01927075e+03 3.90801538e+03 3.87514331e+03 3.74075732e+03 3.61574316e+03 3.75883252e+03 3.78050854e+03 3.53692383e+03 3.51403271e+03 3.67268872e+03 3.73857104e+03 3.59151855e+03 3.44769189e+03 3.40943311e+03 3.37169653e+03 3.29415894e+03 3.24514038e+03 3.23615820e+03 3.18165967e+03 3.24629077e+03 3.18504956e+03 3.04965210e+03 3.01877490e+03 2.89960303e+03 2.92070142e+03 3.04712305e+03 2.95651465e+03 2.83551001e+03 2.71226123e+03 2.63213086e+03 2.73308862e+03 2.75101489e+03 2.62880273e+03 2.50265112e+03 2.44975488e+03 2.45939648e+03 2.41300928e+03 2.45213916e+03 2.41928467e+03 2.28824316e+03 2.20844360e+03 2.15913257e+03 2.19461768e+03 2.16298706e+03 2.06941284e+03 2.00533582e+03 1.95979309e+03 1.90918420e+03 1.81452991e+03 1.81506909e+03 1.87824597e+03 1.79578809e+03 1.69760718e+03 1.61647083e+03 1.55924890e+03 1.60047986e+03 1.56215784e+03 1.46783386e+03 1.38611255e+03 1.33390100e+03 1.32893591e+03 1.28326672e+03 1.23361792e+03 1.15076782e+03 1.12986072e+03 1.14579797e+03 1.06777625e+03 1.00826721e+03 9.65756775e+02 9.07317688e+02 8.47460205e+02 8.03164917e+02 7.57827576e+02 7.04028625e+02 6.59534119e+02 5.99445740e+02 5.67040710e+02 5.51190613e+02 4.78134918e+02 4.16031219e+02 3.79945312e+02 3.31041534e+02 2.91477905e+02 2.41561096e+02 1.87048828e+02 1.44682495e+02 9.69049530e+01 4.74345894e+01 -5.07889748e-01 -4.82236557e+01 -9.45008240e+01 -1.41703125e+02 -1.88486404e+02 -2.30035461e+02 -2.86789368e+02 -3.54032135e+02 -3.94149597e+02 -4.26587219e+02 -4.59994019e+02 -5.13827698e+02 -5.94014832e+02 -6.38178711e+02 -6.70530640e+02 -6.99764099e+02 -7.40419861e+02 -8.13626221e+02 -8.61369324e+02 -9.24039978e+02 -9.61383240e+02 -9.80194153e+02 -1.03681226e+03 -1.08552429e+03 -1.17155261e+03 -1.22329309e+03 -1.22997900e+03 -1.26890503e+03 -1.32067212e+03 -1.36712708e+03 -1.37698877e+03 -1.45226685e+03 -1.58206494e+03 -1.60754834e+03 -1.60801147e+03 -1.61107874e+03 -1.64952930e+03 -1.79108105e+03 -1.84743542e+03 -1.83768323e+03 -1.84306250e+03 -1.87944312e+03 -1.98225073e+03 -2.03421509e+03 -2.11903198e+03 -2.15268042e+03 -2.14250952e+03 -2.16238647e+03 -2.20364551e+03 -2.35335327e+03 -2.40872656e+03 -2.38606226e+03 -2.38729614e+03 -2.42637329e+03 -2.56732544e+03 -2.62551367e+03 -2.53655200e+03 -2.57326978e+03 -2.78674292e+03 -2.81163037e+03 -2.70856885e+03 -2.75362378e+03 -2.93179858e+03 -3.00250269e+03 -2.94364868e+03 -2.90552563e+03 -2.95927588e+03 -3.17523926e+03 -3.20463843e+03 -3.14156934e+03 -3.22062646e+03 -3.25068213e+03 -3.22152246e+03 -3.26046411e+03 -3.39187280e+03 -3.34401172e+03 -3.44414673e+03 -3.63998584e+03 -3.58004956e+03 -3.65318677e+03 -3.68865820e+03 -3.66792114e+03 -3.71941016e+03 -3.74164502e+03 -3.77393921e+03 -3.74863110e+03 -3.72742749e+03 -3.84713477e+03 -3.96754614e+03 -4.12364453e+03 -4.03103052e+03 -3.94750781e+03 -4.10211963e+03 -4.14381104e+03 -4.29583203e+03 -4.32184326e+03 -4.23338086e+03 -4.20735205e+03 -4.21400781e+03 -4.35383838e+03 -4.39418506e+03 -4.54175000e+03 -4.56677686e+03 -4.46960889e+03 -4.49753906e+03 -4.41971484e+03 -4.57110547e+03 -4.85713818e+03 -4.82430859e+03 -4.73001025e+03 -4.64977637e+03 -4.63925537e+03 -4.89380225e+03 -5.00244287e+03 -4.91229199e+03 -4.81000488e+03 -4.83639600e+03 -4.99608789e+03 -4.99062402e+03 -5.17139404e+03 -5.18014014e+03 -5.06807617e+03 -5.11158936e+03 -5.14185938e+03 -5.31446729e+03 -5.33001221e+03 -5.12000439e+03 -5.16095020e+03 -5.48827295e+03 -5.42205566e+03 -5.15275732e+03 -5.33564893e+03 -5.65286182e+03 -5.63802881e+03 -5.53904932e+03 -5.40486670e+03 -5.40927441e+03 -5.73440967e+03 -5.78632080e+03 -5.64114453e+03 -5.53027344e+03 -5.52726074e+03 -5.70913525e+03 -5.75071680e+03 -5.78294434e+03 -5.67980273e+03 -5.81866602e+03 -6.10288525e+03 -5.99764014e+03 -5.94577979e+03 -5.94232080e+03 -5.93025195e+03 -5.96703320e+03 -6.01904248e+03 -6.03752148e+03 -6.04568457e+03 -6.03491602e+03 -5.90733643e+03 -6.00610986e+03 -6.34731738e+03 -6.14010791e+03 -5.89800293e+03 -6.10419336e+03 -6.30637988e+03 -6.50248779e+03 -6.42358594e+03 -6.27552246e+03 -6.31439551e+03 -6.35210254e+03 -6.20958496e+03 -6.19731348e+03 -6.43668213e+03 -6.45615625e+03 -6.33346484e+03 -6.30680664e+03 -6.14417676e+03 -6.42299219e+03 -6.78767773e+03 -6.60865625e+03 -6.46776465e+03 -6.33758008e+03 -6.35287451e+03 -6.68821777e+03 -6.81340430e+03 -6.63254688e+03 -6.47295605e+03 -6.43798975e+03 -6.48962500e+03 -6.58979297e+03 -6.81149707e+03 -6.75115918e+03 -6.60271338e+03 -6.63307568e+03 -6.62537402e+03 -6.73718604e+03 -6.75819824e+03 -6.63649316e+03 -6.71706934e+03 -6.75379932e+03 -6.64118018e+03 -6.48618018e+03 -6.67260986e+03 -6.99078320e+03 -6.92712402e+03 -6.74940479e+03 -6.61081641e+03 -6.64333203e+03 -7.04946240e+03 -7.01915723e+03 -6.77967334e+03 -6.68349121e+03 -6.63780469e+03 -6.72508008e+03 -6.76859326e+03 -6.81979541e+03 -6.67257568e+03 -6.80330518e+03 -7.12179785e+03 -6.85445312e+03 -6.93297266e+03 -6.96210449e+03 -6.85122852e+03 -6.84158105e+03 -6.86189648e+03 -6.66156592e+03 -6.68420361e+03 -6.91125732e+03 -6.95390820e+03 -6.91797461e+03 -6.91333838e+03 -6.66826514e+03 -6.60064941e+03 -6.81583545e+03 -6.84612012e+03 -7.04852344e+03 -6.96841406e+03 -6.64068652e+03 -6.82618115e+03 -6.92317969e+03 -6.82989746e+03 -6.73480029e+03 -6.70085742e+03 -6.78601611e+03 -6.82003369e+03 -6.75534766e+03 -6.58597021e+03 -6.71358203e+03 -7.06287109e+03 -6.92493115e+03 -6.71168896e+03 -6.55291016e+03 -6.54190869e+03 -6.94934766e+03 -6.85859180e+03 -6.73097949e+03 -6.50852588e+03 -6.38931006e+03 -6.62973389e+03 -6.76356299e+03 -6.92008545e+03 -6.69150195e+03 -6.40765771e+03 -6.51470850e+03 -6.55007422e+03 -6.80137402e+03 -6.62678906e+03 -6.43543506e+03 -6.57960156e+03 -6.57258545e+03 -6.47994141e+03 -6.33221582e+03 -6.41175439e+03 -6.76663037e+03 -6.63071143e+03 -6.41834717e+03 -6.23965381e+03 -6.25670312e+03 -6.56561475e+03 -6.56116895e+03 -6.36651562e+03 -6.21552441e+03 -6.13113184e+03 -6.28433350e+03 -6.30386035e+03 -6.44916455e+03 -6.43671924e+03 -6.16947998e+03 -6.02516211e+03 -6.12512158e+03 -6.37485400e+03 -6.22975293e+03 -6.07665381e+03 -6.17857080e+03 -6.12256445e+03 -5.94609668e+03 -5.84989990e+03 -6.04933252e+03 -5.99635010e+03 -5.86790186e+03 -6.09813916e+03 -6.11950977e+03 -5.93388965e+03 -5.88657910e+03 -5.86271191e+03 -5.80458203e+03 -5.63205029e+03 -5.58520117e+03 -5.82087744e+03 -5.89481152e+03 -5.57222900e+03 -5.41154150e+03 -5.64698096e+03 -5.84729297e+03 -5.75710303e+03 -5.53352490e+03 -5.38009717e+03 -5.53970508e+03 -5.63968555e+03 -5.50904688e+03 -5.41808057e+03 -5.23499121e+03 -5.10158398e+03 -5.33094580e+03 -5.54457715e+03 -5.40337109e+03 -5.14958447e+03 -5.04995166e+03 -5.28425879e+03 -5.32902100e+03 -5.14356055e+03 -4.96654150e+03 -4.88382129e+03 -4.93169775e+03 -4.95258447e+03 -5.09095508e+03 -5.05614746e+03 -4.84515869e+03 -4.79854004e+03 -4.78036816e+03 -4.85210059e+03 -4.71205615e+03 -4.59640039e+03 -4.78807227e+03 -4.74852441e+03 -4.58704395e+03 -4.42115332e+03 -4.46650586e+03 -4.68448438e+03 -4.46654834e+03 -4.26125146e+03 -4.36818311e+03 -4.40026221e+03 -4.37270312e+03 -4.28559033e+03 -4.34628418e+03 -4.34203760e+03 -4.16419678e+03 -3.99532910e+03 -3.97760645e+03 -4.18569189e+03 -4.06859619e+03 -3.91076538e+03 -3.95078076e+03 -3.91710327e+03 -3.84906152e+03 -3.79045190e+03 -3.81771851e+03 -3.75150000e+03 -3.63649707e+03 -3.69265967e+03 -3.65971460e+03 -3.62757007e+03 -3.59584399e+03 -3.51365747e+03 -3.44748975e+03 -3.30021973e+03 -3.28783594e+03 -3.44095386e+03 -3.43876367e+03 -3.20118994e+03 -3.06282202e+03 -3.16422974e+03 -3.23364331e+03 -3.16178979e+03 -3.00982935e+03 -2.86868994e+03 -2.96064282e+03 -3.00639062e+03 -2.86231494e+03 -2.87326465e+03 -2.81154932e+03 -2.65634375e+03 -2.67685986e+03 -2.73175269e+03 -2.66381982e+03 -2.50156982e+03 -2.41048071e+03 -2.50429102e+03 -2.51964209e+03 -2.39525562e+03 -2.27619824e+03 -2.21457837e+03 -2.29562012e+03 -2.25093457e+03 -2.13205371e+03 -2.11745166e+03 -2.06989331e+03 -2.00725806e+03 -1.95502112e+03 -1.98137500e+03 -1.89592419e+03 -1.77612976e+03 -1.82056653e+03 -1.78940186e+03 -1.72186755e+03 -1.63233411e+03 -1.56329211e+03 -1.59729468e+03 -1.51417822e+03 -1.42772522e+03 -1.48353430e+03 -1.46025928e+03 -1.36347290e+03 -1.26078198e+03 -1.64297107e+03 -1.73755017e+03 -1.41150464e+03 -1.70336865e+03 -1.65322144e+03 -1.65091382e+03 -1.43439014e+03 -2.86981714e+03 -5.24811035e+03 4.23644188e+05 128359992. 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. 0. -217353520. -7.14308750e+05 -7.31227875e+05 3.36780713e+03 2.54110791e+03 1.48797119e+03 1.12973792e+03 1.11384985e+03 1.06692932e+03 1.10822620e+03 1.15206799e+03 1.17110010e+03 1.22715149e+03 1.29968616e+03 1.33636084e+03 1.38262439e+03 1.41952625e+03 1.45256262e+03 1.55857800e+03 1.58382007e+03 1.57108728e+03 1.65423279e+03 1.68408533e+03 1.67390479e+03 1.79941699e+03 1.93908386e+03 1.90592712e+03 1.89991711e+03 1.95867456e+03 2.02077051e+03 2.05792188e+03 2.09396606e+03 2.15980859e+03 2.20595776e+03 2.27179932e+03 2.31646387e+03 2.28090137e+03 2.34963330e+03 2.47376831e+03 2.53931641e+03 2.56874829e+03 2.51289160e+03 2.53363013e+03 2.66576733e+03 2.72224951e+03 2.73288525e+03 2.75309375e+03 2.78979126e+03 2.89244556e+03 2.97778223e+03 2.97889917e+03 2.93479712e+03 2.97397437e+03 3.16535376e+03 3.21541357e+03 3.09545801e+03 3.12126367e+03 3.25270605e+03 3.34434497e+03 3.41620044e+03 3.39169287e+03 3.33203442e+03 3.41100293e+03 3.53509790e+03 3.59212134e+03 3.58280884e+03 3.55809424e+03 3.66806128e+03 3.77980859e+03 3.76186011e+03 3.74384375e+03 3.75489429e+03 3.84540625e+03 3.96513892e+03 3.97758545e+03 4.02726318e+03 4.03534033e+03 3.97095605e+03 4.06926270e+03 4.16995996e+03 4.18168457e+03 4.22715771e+03 4.23122998e+03 4.25919092e+03 4.40939600e+03 4.42561328e+03 4.31696631e+03 4.35756885e+03 4.49249414e+03 4.55895312e+03 4.57127686e+03 4.55514697e+03 4.57423340e+03 4.63840479e+03 4.73613867e+03 4.73696289e+03 4.64364453e+03 4.75602295e+03 4.92246191e+03 4.94331152e+03 4.95650732e+03 4.84650195e+03 4.85888721e+03 5.05329102e+03 5.05826416e+03 4.99334424e+03 5.00661768e+03 5.07229199e+03 5.22998145e+03 5.22313721e+03 5.20374902e+03 5.25241748e+03 5.28566455e+03 5.36298584e+03 5.39074121e+03 5.33881299e+03 5.36652246e+03 5.42917041e+03 5.40547266e+03 5.49093262e+03 5.54913184e+03 5.54392383e+03 5.57427148e+03 5.56518018e+03 5.57495947e+03 5.68927344e+03 5.74257178e+03 5.72825146e+03 5.71431982e+03 5.68642090e+03 5.73355273e+03 5.82011084e+03 5.80596533e+03 5.78504883e+03 5.89813281e+03 6.04451367e+03 6.01543213e+03 5.91981006e+03 5.94648779e+03 6.00517041e+03 6.01174219e+03 5.98291455e+03 5.98837061e+03 6.06849707e+03 6.16304590e+03 6.24323047e+03 6.24301953e+03 6.10070654e+03 6.03603223e+03 6.20781201e+03 6.32480127e+03 6.33165137e+03 6.27159814e+03 6.18218701e+03 6.30153906e+03 6.43371240e+03 6.43423047e+03 6.28236963e+03 6.22630566e+03 6.40911768e+03 6.56979053e+03 6.48827295e+03 6.24794971e+03 6.34823633e+03 6.54716748e+03 6.56641211e+03 6.47447363e+03 6.48810400e+03 6.55996484e+03 6.56128711e+03 6.59639062e+03 6.54793066e+03 6.48364160e+03 6.60372412e+03 6.73363281e+03 6.61392041e+03 6.62336963e+03 6.67617578e+03 6.58118457e+03 6.64575049e+03 6.68327588e+03 6.75168262e+03 6.82739160e+03 6.51798975e+03 6.60063477e+03 6.92158105e+03 6.78115137e+03 6.58737158e+03 6.68651270e+03 6.85479004e+03 6.77519238e+03 6.78752002e+03 6.77554492e+03 6.70181250e+03 6.69397461e+03 6.86834082e+03 6.91720068e+03 6.72659375e+03 6.77260889e+03 6.96267871e+03 6.86569482e+03 6.81446533e+03 6.77310352e+03 6.71375049e+03 6.89177979e+03 6.86000537e+03 6.77278418e+03 6.85234961e+03 6.73744580e+03 6.82241406e+03 6.98082422e+03 6.79272314e+03 6.78183398e+03 6.82851416e+03 6.85198584e+03 6.81231982e+03 6.85718750e+03 6.86115674e+03 6.77177832e+03 6.78354736e+03 6.83292578e+03 6.85199414e+03 6.73643555e+03 6.83377148e+03 6.91028760e+03 6.81268701e+03 6.94209375e+03 6.78351318e+03 6.63084082e+03 6.78031641e+03 6.84672461e+03 6.81177002e+03 6.69109570e+03 6.58053125e+03 6.73930811e+03 6.90457080e+03 6.78047070e+03 6.63450146e+03 6.76102637e+03 6.78941992e+03 6.66928906e+03 6.59200977e+03 6.75724805e+03 6.70396240e+03 6.56589209e+03 6.76262402e+03 6.65101367e+03 6.55750537e+03 6.69336523e+03 6.54235059e+03 6.51423682e+03 6.56042285e+03 6.52147070e+03 6.48971533e+03 6.55050488e+03 6.62475928e+03 6.61313379e+03 6.41620605e+03 6.35104346e+03 6.48817188e+03 6.44654492e+03 6.46538477e+03 6.42500049e+03 6.37597559e+03 6.34182129e+03 6.36679346e+03 6.45187207e+03 6.28722852e+03 6.12961084e+03 6.28439844e+03 6.53220508e+03 6.22157422e+03 6.06503467e+03 6.16277734e+03 6.10560498e+03 6.23740332e+03 6.25288818e+03 6.07748682e+03 6.03465186e+03 6.09548145e+03 6.09089990e+03 6.10925391e+03 6.00533838e+03 6.02935986e+03 6.07682031e+03 5.80997021e+03 5.86793164e+03 5.89438379e+03 5.80395801e+03 5.92596924e+03 5.84971533e+03 5.72596631e+03 5.79527734e+03 5.71471631e+03 5.70370068e+03 5.86427490e+03 5.73678516e+03 5.60788965e+03 5.53842529e+03 5.47649268e+03 5.58201855e+03 5.62210254e+03 5.47275928e+03 5.43116748e+03 5.52217822e+03 5.48605908e+03 5.39134717e+03 5.29497705e+03 5.27877393e+03 5.29596240e+03 5.32829834e+03 5.31331982e+03 5.13758789e+03 5.09643848e+03 5.16534326e+03 5.17660059e+03 5.11989404e+03 5.05672510e+03 4.98463770e+03 4.93929980e+03 5.09122021e+03 5.06808447e+03 4.83344482e+03 4.72410645e+03 4.76442041e+03 4.80647656e+03 4.75452832e+03 4.67634277e+03 4.68384131e+03 4.68173584e+03 4.63298389e+03 4.64853369e+03 4.54246533e+03 4.45874268e+03 4.49113184e+03 4.51099951e+03 4.42654688e+03 4.26513770e+03 4.29170850e+03 4.29002979e+03 4.24687891e+03 4.26176953e+03 4.18459814e+03 4.09455396e+03 4.09684570e+03 4.14456201e+03 4.04433716e+03 3.92366284e+03 3.94062939e+03 3.91863184e+03 3.85062476e+03 3.82094482e+03 3.75728906e+03 3.71957544e+03 3.71129883e+03 3.70673120e+03 3.69126855e+03 3.58112207e+03 3.52914209e+03 3.50005640e+03 3.43971582e+03 3.40809058e+03 3.34143677e+03 3.34522705e+03 3.32310620e+03 3.23428516e+03 3.16021558e+03 3.14469751e+03 3.16048633e+03 3.13715527e+03 3.09492432e+03 3.00229102e+03 2.94440405e+03 2.89788428e+03 2.82682300e+03 2.80612720e+03 2.79801758e+03 2.74792603e+03 2.69172046e+03 2.62411792e+03 2.56721704e+03 2.57249487e+03 2.56194336e+03 2.52542920e+03 2.43754712e+03 2.33097241e+03 2.31752368e+03 2.29996338e+03 2.23488721e+03 2.21010522e+03 2.19070825e+03 2.10439551e+03 2.03862097e+03 1.99367627e+03 1.95126575e+03 1.96784570e+03 1.93132520e+03 1.84081067e+03 1.80307471e+03 1.73330078e+03 1.65534802e+03 1.66178357e+03 1.63128271e+03 1.54689502e+03 1.50293359e+03 1.45292029e+03 1.39211084e+03 1.38027710e+03 1.36569434e+03 1.28360754e+03 1.22138049e+03 1.18650732e+03 1.13862598e+03 1.09622607e+03 1.04407520e+03 9.96016663e+02 9.51570068e+02 9.03462585e+02 8.61839783e+02 8.10381592e+02 7.53159241e+02 7.17321594e+02 6.78135803e+02 6.17888123e+02 5.62089111e+02 5.16356262e+02 4.78077393e+02 4.35025055e+02 3.89260803e+02 3.31073395e+02 2.74769897e+02 2.33760162e+02 1.89376007e+02 1.43300171e+02 9.34381943e+01 4.52623405e+01 -2.02044491e-02 -4.75031662e+01 -9.63214645e+01 -1.47676727e+02 -1.96505356e+02 -2.40263107e+02 -2.90563965e+02 -3.32800598e+02 -3.68722351e+02 -4.31043945e+02 -4.95824036e+02 -5.28205444e+02 -5.60770325e+02 -6.12559692e+02 -6.66713257e+02 -7.24195068e+02 -7.76225647e+02 -8.16023804e+02 -8.42753845e+02 -8.95297363e+02 -9.58038086e+02 -9.98668701e+02 -1.05812244e+03 -1.10670532e+03 -1.14144507e+03 -1.18097449e+03 -1.24096924e+03 -1.29452466e+03 -1.33037415e+03 -1.38865466e+03 -1.44217224e+03 -1.46545581e+03 -1.48602710e+03 -1.53857520e+03 -1.60603589e+03 -1.68907422e+03 -1.73293140e+03 -1.72679980e+03 -1.76741736e+03 -1.82614697e+03 -1.89182690e+03 -1.96357617e+03 -1.98182544e+03 -1.99216516e+03 -2.08694116e+03 -2.13743726e+03 -2.14131641e+03 -2.24866504e+03 -2.28636157e+03 -2.27137012e+03 -2.32398804e+03 -2.34774365e+03 -2.39244531e+03 -2.51754297e+03 -2.56258594e+03 -2.56023364e+03 -2.63916431e+03 -2.65883936e+03 -2.61971533e+03 -2.68864282e+03 -2.79685156e+03 -2.84481421e+03 -2.88072803e+03 -2.88605493e+03 -2.93116968e+03 -3.02172168e+03 -3.07712573e+03 -3.19192871e+03 -3.17038672e+03 -3.08354785e+03 -3.14436694e+03 -3.23314551e+03 -3.32774927e+03 -3.40899927e+03 -3.37922998e+03 -3.33532959e+03 -3.45641650e+03 -3.55072046e+03 -3.54791968e+03 -3.60034521e+03 -3.63358618e+03 -3.62857397e+03 -3.72037915e+03 -3.76749365e+03 -3.72279224e+03 -3.87853027e+03 -3.96894800e+03 -3.91149731e+03 -3.92256250e+03 -3.86559985e+03 -3.91824609e+03 -4.08712573e+03 -4.25117529e+03 -4.23901318e+03 -4.04510059e+03 -4.11161182e+03 -4.29002148e+03 -4.29735449e+03 -4.33425146e+03 -4.36377979e+03 -4.35087158e+03 -4.43291504e+03 -4.49339258e+03 -4.52566699e+03 -4.55709521e+03 -4.58084668e+03 -4.67978223e+03 -4.66809619e+03 -4.62531592e+03 -4.64626855e+03 -4.71932373e+03 -4.82656934e+03 -4.94837402e+03 -4.87575000e+03 -4.76288037e+03 -4.88787549e+03 -4.99119824e+03 -5.11645459e+03 -5116. -4.95808740e+03 -5.02850781e+03 -5.11411377e+03 -5.19593701e+03 -5.32223975e+03 -5.25161133e+03 -5.18774463e+03 -5.27095850e+03 -5.23288379e+03 -5.21416992e+03 -5.42173730e+03 -5.54443701e+03 -5.44562793e+03 -5.35912549e+03 -5.37026758e+03 -5.43804834e+03 -5.62264697e+03 -5.67889844e+03 -5.66410010e+03 -5.59564160e+03 -5.48970508e+03 -5.59790869e+03 -5.68371143e+03 -5.85349219e+03 -5.90207617e+03 -5.69810596e+03 -5.70526025e+03 -5.78946143e+03 -5.87596240e+03 -5.91949609e+03 -5.97240332e+03 -5.99522900e+03 -5.87210791e+03 -5.93129736e+03 -5.98213281e+03 -5.98558984e+03 -6.04798682e+03 -6.11448730e+03 -6.11106055e+03 -6.09309326e+03 -6.03732764e+03 -6.13916895e+03 -6.30726367e+03 -6.24232227e+03 -6.12485059e+03 -6.21077686e+03 -6.20379346e+03 -6.23372900e+03 -6.49167676e+03 -6.43798975e+03 -6.22310645e+03 -6.37827197e+03 -6.45035840e+03 -6.52046826e+03 -6.55431250e+03 -6.41399365e+03 -6.57354785e+03 -7.32480469e+03 -8.83269434e+03 -6.57474854e+03 -8.98586133e+03 -8.51084473e+03 -1.16990225e+04 -8.78295020e+03 -1.46073623e+04 -1.36412594e+05 43397152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -86350792. -4093179. 6.31776650e+06 -16706702. -2.08284082e+04 -1.90429961e+04 -9.86472363e+03 -6.49233838e+03 -7.13689111e+03 -7.27412842e+03 -7.08147461e+03 -6.81975488e+03 -6.66857764e+03 -6.71066455e+03 -6.87452930e+03 -7.03903906e+03 -6.91108887e+03 -6.69026562e+03 -6.66500049e+03 -6.74821875e+03 -6.89797900e+03 -6.83847021e+03 -6.53363770e+03 -6.64459619e+03 -6.82197510e+03 -6.75955811e+03 -6.62016943e+03 -6.49546045e+03 -6.65223633e+03 -6.96547852e+03 -6.92690771e+03 -6.55294531e+03 -6.28991455e+03 -6.47121875e+03 -6.75698438e+03 -6.88477148e+03 -6.72083105e+03 -6.43404688e+03 -6.49575342e+03 -6.60322217e+03 -6.73803125e+03 -6.63017334e+03 -6.26430713e+03 -6.35256738e+03 -6.66437109e+03 -6.56267871e+03 -6.37380322e+03 -6.42892578e+03 -6.41997168e+03 -6.47375879e+03 -6.51145752e+03 -6.20451855e+03 -6.11800049e+03 -6.40968848e+03 -6.55244531e+03 -6.43059424e+03 -6.18388232e+03 -6.01829688e+03 -6.32858496e+03 -6.50671631e+03 -6.32236426e+03 -6.08147852e+03 -5.88810645e+03 -5.97164307e+03 -6.23290869e+03 -6.32912256e+03 -6.18004297e+03 -6.05669482e+03 -6.03470361e+03 -5.95483057e+03 -5.96746387e+03 -5.99696484e+03 -5.79530127e+03 -5.87623633e+03 -6.05969434e+03 -5.93445508e+03 -5.66844238e+03 -5.60320459e+03 -5.85669092e+03 -6.00502881e+03 -5.90820996e+03 -5.66603271e+03 -5.51266846e+03 -5.50104395e+03 -5.63006104e+03 -5.85541211e+03 -5.73897803e+03 -5.38599170e+03 -5.43083984e+03 -5.49346436e+03 -5.52411768e+03 -5.60499902e+03 -5.37054639e+03 -5.31159033e+03 -5.42310791e+03 -5.36433984e+03 -5.29119385e+03 -5.17507617e+03 -5.19478369e+03 -5.30702979e+03 -5.24338916e+03 -5.04654199e+03 -4.99447949e+03 -5.12023730e+03 -5.14632422e+03 -5.10143555e+03 -5.00475342e+03 -4.82932129e+03 -4.85877734e+03 -4.97752100e+03 -4.95072754e+03 -4.81867578e+03 -4.60429541e+03 -4.59864844e+03 -4.79399512e+03 -4.88309619e+03 -4.73232568e+03 -4.48145312e+03 -4.48181201e+03 -4.60030762e+03 -4.55430225e+03 -4.40712500e+03 -4.32636621e+03 -4.43085889e+03 -4.46162012e+03 -4.32021143e+03 -4.21777246e+03 -4.12533594e+03 -4.22187158e+03 -4.37552783e+03 -4.21250146e+03 -4.06520728e+03 -3.98355786e+03 -3.95022583e+03 -3.99002393e+03 -4.03340332e+03 -3.95583594e+03 -3.74342432e+03 -3.72183545e+03 -3.85654272e+03 -3.86736230e+03 -3.72198901e+03 -3.59445776e+03 -3.60876245e+03 -3.64714795e+03 -3.60200708e+03 -3.50770532e+03 -3.34115625e+03 -3.33989429e+03 -3.42797363e+03 -3.40067993e+03 -3.30947437e+03 -3.18225977e+03 -3.16997705e+03 -3.19351562e+03 -3.22506470e+03 -3.15561548e+03 -2.96124561e+03 -2.94915601e+03 -2.96766016e+03 -2.92041602e+03 -2.88977710e+03 -2.80669727e+03 -2.77179907e+03 -2.75160718e+03 -2.68830127e+03 -2.62401489e+03 -2.56384937e+03 -2.58806396e+03 -2.58843311e+03 -2.51070752e+03 -2.38436304e+03 -2.30135278e+03 -2.35240723e+03 -2.38632349e+03 -2.31926807e+03 -2.20384546e+03 -2.08849268e+03 -2.02889453e+03 -2.06565381e+03 -2.10588354e+03 -2.00877637e+03 -1.86535107e+03 -1.84309949e+03 -1.86054858e+03 -1.82617529e+03 -1.77491223e+03 -1.69319751e+03 -1.64674524e+03 -1.61360925e+03 -1.55233179e+03 -1.49400061e+03 -1.45777222e+03 -1.43014014e+03 -1.38566199e+03 -1.32827295e+03 -1.26917383e+03 -1.21518140e+03 -1.19086621e+03 -1.16695203e+03 -1.11558020e+03 -1.02922693e+03 -9.64138306e+02 -9.62360718e+02 -9.31681824e+02 -8.70169861e+02 -8.08360718e+02 -7.34704285e+02 -6.92650146e+02 -6.79578064e+02 -6.46360901e+02 -5.84064087e+02 -5.10122986e+02 -4.60992950e+02 -4.30625000e+02 -3.91575958e+02 -3.38895782e+02 -2.86379517e+02 -2.40525223e+02 -1.91379333e+02 -1.41557037e+02 -9.18995590e+01 -4.42876625e+01 3.04749012e+00 5.16733894e+01 1.02000290e+02 1.48612411e+02 1.86284149e+02 2.33659073e+02 2.86955994e+02 3.34998627e+02 3.88457184e+02 4.29051727e+02 4.88521240e+02 5.38560608e+02 5.56580627e+02 5.95182495e+02 6.57509705e+02 7.34719971e+02 8.05711853e+02 8.38239258e+02 8.38017395e+02 8.54755859e+02 9.26204651e+02 1.03041199e+03 1.10421252e+03 1.12654639e+03 1.10710730e+03 1.14735278e+03 1.28358191e+03 1.32601172e+03 1.29294202e+03 1.34909998e+03 1.41816846e+03 1.46443445e+03 1.56082117e+03 1.56866101e+03 1.56130664e+03 1.65008484e+03 1.66124316e+03 1.75137329e+03 1.84378052e+03 1.78823743e+03 1.88131360e+03 1.98857983e+03 1.98281384e+03 2.02853796e+03 2.06549805e+03 2.11478760e+03 2.17203296e+03 2.20836035e+03 2.19708496e+03 2.23796875e+03 2.39550220e+03 2.50581250e+03 2.49281567e+03 2.41722729e+03 2.41513550e+03 2.50101758e+03 2.66353979e+03 2.79180859e+03 2.75719360e+03 2.67753613e+03 2.72692969e+03 2.85385156e+03 2.89060278e+03 2.88645679e+03 2.94058740e+03 2.97981616e+03 3.01164111e+03 3.19095947e+03 3.17491504e+03 3.09290601e+03 3.21370117e+03 3.18599097e+03 3.30763550e+03 3.41313843e+03 3.34460767e+03 3.52165503e+03 3.49553052e+03 3.38809937e+03 3.53783813e+03 3.50576245e+03 3.58443188e+03 3.87719336e+03 3.73709595e+03 3.56673706e+03 3.67598730e+03 3.89906079e+03 4.08553003e+03 4.03439404e+03 3.83396313e+03 3.76758325e+03 3.91777734e+03 4.14631543e+03 4.33234521e+03 4.27336084e+03 4.06029712e+03 4.07102930e+03 4.26889990e+03 4.38339746e+03 4.30401953e+03 4.29914941e+03 4.38727734e+03 4.41952100e+03 4.60585156e+03 4.64074268e+03 4.44021143e+03 4.48083447e+03 4.57626367e+03 4.63687402e+03 4.72075439e+03 4.72422217e+03 4.86784180e+03 4.82657520e+03 4.68762012e+03 4.80475537e+03 4.74384033e+03 4.90777686e+03 5.28476855e+03 5.03019824e+03 4.70957666e+03 4.89946387e+03 5.15608008e+03 5.33177441e+03 5.38866846e+03 5.13203711e+03 4.95229932e+03 5.06834277e+03 5.36552002e+03 5.60759863e+03 5.49112012e+03 5.19034668e+03 5.17919189e+03 5.41036084e+03 5.50361182e+03 5.64952002e+03 5.69898730e+03 5.39390771e+03 5.40521240e+03 5.64311768e+03 5.72333252e+03 5.66050195e+03 5.62429639e+03 5.63369482e+03 5.62315527e+03 5.90979053e+03 5.96201953e+03 5.70381836e+03 5.71784570e+03 5.79848047e+03 5.85372070e+03 5.92356055e+03 5.86685059e+03 6.05216406e+03 6.15414355e+03 5.96979102e+03 5.86976904e+03 5.76569629e+03 6.02115527e+03 6.43842236e+03 6.29109375e+03 5.95101953e+03 5.85762549e+03 6.11778418e+03 6.47996924e+03 6.29118799e+03 5.96402148e+03 6.07158008e+03 6.26368555e+03 6.49478027e+03 6.65260547e+03 6.52739062e+03 6.15473242e+03 6.07449072e+03 6.28126367e+03 6.50596533e+03 6.52213330e+03 6.45274561e+03 6.44212402e+03 6.42214990e+03 6.58969287e+03 6.54069141e+03 6.39464697e+03 6.39062549e+03 6.38490674e+03 6.65584424e+03 6.76701172e+03 6.54847070e+03 6.61950049e+03 6.66839795e+03 6.73599365e+03 6.61742773e+03 6.32607764e+03 6.62239258e+03 7.01090674e+03 6.80682568e+03 6.46445557e+03 6.53894092e+03 6.90172217e+03 6.89102686e+03 6.74929492e+03 6.77080615e+03 6.58602051e+03 6.55901465e+03 6.95778955e+03 6.97244629e+03 6.63574414e+03 6.50606641e+03 6.51162500e+03 6.83044482e+03 7.15731934e+03 6.82573389e+03 6.64473291e+03 6.84773877e+03 6.82399854e+03 7.01118799e+03 6.97689795e+03 6.57754297e+03 6.63994287e+03 6.84800391e+03 6.84276416e+03 6.87564502e+03 6.81517041e+03 6.95195459e+03 7.14882324e+03 6.46975342e+03 7.02218945e+03 6.75161035e+03 8.30309180e+03 9.97547949e+03 1.04988096e+04 1.02456367e+04 1.03819980e+04 1.11000459e+04 1.04048232e+04 1.01884561e+04 1.27230771e+04 2.24452520e+04 2.97645762e+04 -4466672. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -142007024. 11945210. -12088190. 2.16294727e+04 1.28170117e+04 7.27734766e+03 6.50962842e+03 7.50645020e+03 6.75023828e+03 6.24410742e+03 6.33899609e+03 6.34215283e+03 6.19353662e+03 6.18522852e+03 6.17107520e+03 6.23220215e+03 6.31281689e+03 6.06654004e+03 5.84849707e+03 5.96973926e+03 5.94977344e+03 5.65648291e+03 5.97986670e+03 6.10006348e+03 5.56898828e+03 5.90689307e+03 6.17729346e+03 5.87666309e+03 5.73043555e+03 5.84789551e+03 5.94445947e+03 5.78314355e+03 5.73671582e+03 5.72081543e+03 5.66502100e+03 5.57955371e+03 5.54300195e+03 5.66476172e+03 5.66717480e+03 5.53179346e+03 5.48774316e+03 5.47927197e+03 5.46234229e+03 5.40565918e+03 5.37593408e+03 5.36954932e+03 5.19736279e+03 5.13766650e+03 5.23758936e+03 5.19491699e+03 5.37400244e+03 5.35431299e+03 5.13417188e+03 4.96877979e+03 4.91544727e+03 5.20308594e+03 5.20379248e+03 4.97387744e+03 4.83851660e+03 4.82929980e+03 4.87816113e+03 4.81531201e+03 4.94373389e+03 4.90870898e+03 4.58739111e+03 4.50639258e+03 4.71586230e+03 4.87390234e+03 4.71170898e+03 4.55949316e+03 4.55630225e+03 4.48854346e+03 4.40672998e+03 4.40966797e+03 4.38130127e+03 4.31832617e+03 4.27887842e+03 4.24453516e+03 4.25038232e+03 4.20978027e+03 4.25609521e+03 4.19759863e+03 4.04250806e+03 4.06938599e+03 4.03707715e+03 4.00201904e+03 3.98442383e+03 3.91516211e+03 3.87180444e+03 3.74496436e+03 3.61881860e+03 3.76017017e+03 3.76872559e+03 3.54285547e+03 3.52667554e+03 3.68664575e+03 3.73564429e+03 3.58764526e+03 3.45956299e+03 3.39577637e+03 3.34737158e+03 3.28559595e+03 3.23591699e+03 3.26008716e+03 3.20481226e+03 3.23235938e+03 3.17993774e+03 3.04372583e+03 3.05245044e+03 2.93506445e+03 2.89408643e+03 3.00762524e+03 2.93976050e+03 2.83417847e+03 2.72450488e+03 2.63606787e+03 2.72703271e+03 2.74717871e+03 2.62468359e+03 2.49655029e+03 2.45327222e+03 2.47179956e+03 2.41695630e+03 2.44850610e+03 2.42173926e+03 2.29414038e+03 2.20358765e+03 2.16051636e+03 2.20201270e+03 2.15990967e+03 2.06449146e+03 1.99866418e+03 1.95056714e+03 1.92908105e+03 1.83712805e+03 1.79875903e+03 1.85772571e+03 1.79928076e+03 1.70083716e+03 1.60888354e+03 1.55779431e+03 1.60518921e+03 1.56228467e+03 1.47046484e+03 1.38630908e+03 1.33194470e+03 1.32831482e+03 1.28089966e+03 1.23337073e+03 1.15334729e+03 1.13050574e+03 1.14377295e+03 1.06495142e+03 1.00689032e+03 9.63412170e+02 9.07830627e+02 8.48138245e+02 8.01053650e+02 7.63419189e+02 7.14689575e+02 6.62843323e+02 5.95700256e+02 5.59410339e+02 5.45644714e+02 4.76814880e+02 4.14398529e+02 3.78911407e+02 3.31282471e+02 2.92462982e+02 2.39203659e+02 1.83678162e+02 1.44685455e+02 9.71717987e+01 4.71625443e+01 2.26903018e-02 -4.67383080e+01 -9.36690750e+01 -1.41827362e+02 -1.90374283e+02 -2.32095367e+02 -2.86873474e+02 -3.53312561e+02 -3.94026031e+02 -4.28007568e+02 -4.60704102e+02 -5.12572937e+02 -5.96355835e+02 -6.40882874e+02 -6.70284241e+02 -7.00771790e+02 -7.41778564e+02 -8.12785889e+02 -8.60260376e+02 -9.25791321e+02 -9.54777466e+02 -9.72238647e+02 -1.04987476e+03 -1.09922021e+03 -1.16858374e+03 -1.21076660e+03 -1.22170227e+03 -1.26871509e+03 -1.31846729e+03 -1.38199670e+03 -1.38864038e+03 -1.45128040e+03 -1.58210144e+03 -1.60354688e+03 -1.61145386e+03 -1.61674023e+03 -1.65072095e+03 -1.79180737e+03 -1.84995374e+03 -1.84145789e+03 -1.83892847e+03 -1.87975269e+03 -1.98769080e+03 -2.03774585e+03 -2.12514355e+03 -2.14869409e+03 -2.14360620e+03 -2.16544189e+03 -2.19846802e+03 -2.35650317e+03 -2.39687012e+03 -2.36622729e+03 -2.39293774e+03 -2.44040674e+03 -2.56050928e+03 -2.61293408e+03 -2.55120410e+03 -2.58058765e+03 -2.76113940e+03 -2.80817407e+03 -2.71803442e+03 -2.75049902e+03 -2.93512769e+03 -2.99459692e+03 -2.94705933e+03 -2.91640747e+03 -2.95727979e+03 -3.17551465e+03 -3.19629248e+03 -3.13153979e+03 -3.19771167e+03 -3.23203540e+03 -3.27442310e+03 -3.31939893e+03 -3.35645435e+03 -3.30550342e+03 -3.43256494e+03 -3.67613354e+03 -3.61225415e+03 -3.60272021e+03 -3.65780347e+03 -3.68287231e+03 -3.72702197e+03 -3.74949951e+03 -3.77562866e+03 -3.73437720e+03 -3.71194092e+03 -3.85223926e+03 -3.98650903e+03 -4.14778662e+03 -4.03781323e+03 -3.92460767e+03 -4.08286450e+03 -4.17220117e+03 -4.32059912e+03 -4.28635840e+03 -4.20887354e+03 -4.22593408e+03 -4.23375098e+03 -4.36464893e+03 -4.40769189e+03 -4.54184521e+03 -4.56456641e+03 -4.48240479e+03 -4.45256934e+03 -4.37497803e+03 -4.59788477e+03 -4.90714355e+03 -4.83978906e+03 -4.72368848e+03 -4.64913721e+03 -4.60819531e+03 -4.86860156e+03 -5.05173242e+03 -4.95672900e+03 -4.79172559e+03 -4.81767139e+03 -4.98342139e+03 -5.00587646e+03 -5.17876514e+03 -5.18759326e+03 -5.07547900e+03 -5.12807324e+03 -5.15361670e+03 -5.29904590e+03 -5.30532617e+03 -5.11897021e+03 -5.17511768e+03 -5.49037939e+03 -5.41677734e+03 -5.16084668e+03 -5.36735791e+03 -5.69972119e+03 -5.61481006e+03 -5.50438818e+03 -5.41145410e+03 -5.42840234e+03 -5.75698145e+03 -5.78058887e+03 -5.63535840e+03 -5.51470898e+03 -5.53565625e+03 -5.74267725e+03 -5.76047754e+03 -5.74854590e+03 -5.66745996e+03 -5.79950342e+03 -6.06551318e+03 -5.92279492e+03 -5.98360400e+03 -5.97679980e+03 -5.90381641e+03 -5.97448438e+03 -6.01610693e+03 -6.04655615e+03 -6.00494727e+03 -5.96898096e+03 -5.87541064e+03 -6.04274951e+03 -6.40589209e+03 -6.18354150e+03 -5.93464160e+03 -6.14143799e+03 -6.25979199e+03 -6.43301611e+03 -6.38960938e+03 -6.21341162e+03 -6.37733740e+03 -6.41697803e+03 -6.16720605e+03 -6.09901172e+03 -6.51056543e+03 -6.52672803e+03 -6.37734277e+03 -6.27939502e+03 -6.09104346e+03 -6.40656836e+03 -6.80312500e+03 -6.67176221e+03 -6.45917090e+03 -6.33012451e+03 -6.28367969e+03 -6.64153613e+03 -6.85847266e+03 -6.70155420e+03 -6.40984473e+03 -6.36350293e+03 -6.53691016e+03 -6.64462695e+03 -6.83971533e+03 -6.71968066e+03 -6.53755908e+03 -6.68400195e+03 -6.66743066e+03 -6.81392285e+03 -6.76840527e+03 -6.63130566e+03 -6.71781689e+03 -6.75711230e+03 -6.69988623e+03 -6.50727148e+03 -6.60599219e+03 -7.06351025e+03 -6.95882910e+03 -6.68115186e+03 -6.54679492e+03 -6.64393555e+03 -7.03540039e+03 -7.01174561e+03 -6.80338770e+03 -6.66221533e+03 -6.61565674e+03 -6.82716260e+03 -6.81433105e+03 -6.79722949e+03 -6.66545117e+03 -6.82473535e+03 -7.12422412e+03 -6.84823926e+03 -6.91933545e+03 -6.94627832e+03 -6.85009277e+03 -6.80262451e+03 -6.75630371e+03 -6.76310693e+03 -6.76910254e+03 -6.79483057e+03 -6.77804297e+03 -6.98376758e+03 -6.97889453e+03 -6.67262793e+03 -6.55845947e+03 -6.73725586e+03 -6.90429346e+03 -7.14442236e+03 -6.90723193e+03 -6.57022900e+03 -6.90400586e+03 -7.02601611e+03 -6.86699414e+03 -6.72126025e+03 -6.65243701e+03 -6.80294141e+03 -6.81290186e+03 -6.71009326e+03 -6.52054785e+03 -6.76190576e+03 -7.07718750e+03 -6.86052686e+03 -6.77350537e+03 -6.59242627e+03 -6.54534277e+03 -6.94087354e+03 -6.91320605e+03 -6.70277783e+03 -6.49801562e+03 -6.39417529e+03 -6.55767090e+03 -6.77052637e+03 -7.00453516e+03 -6.64001318e+03 -6.36618701e+03 -6.57297510e+03 -6.61829932e+03 -6.77743994e+03 -6.68494873e+03 -6.43797217e+03 -6.58151709e+03 -6.59301709e+03 -6.40879346e+03 -6.24011279e+03 -6.47854395e+03 -6.79729834e+03 -6.58077100e+03 -6.45320459e+03 -6.30725098e+03 -6.23088574e+03 -6.56834619e+03 -6.56103271e+03 -6.36986279e+03 -6.16424512e+03 -6.11730859e+03 -6.28249463e+03 -6.29287451e+03 -6.44809375e+03 -6.41840967e+03 -6.17335791e+03 -6.06225000e+03 -6.12828516e+03 -6.37026855e+03 -6.19958057e+03 -6.05177295e+03 -6.12599609e+03 -6.07906299e+03 -5.97405273e+03 -5.87650928e+03 -6.08064355e+03 -6.07517285e+03 -5.87670850e+03 -6.08098096e+03 -6.10998193e+03 -5.92035400e+03 -5.88083105e+03 -5.89354443e+03 -5.82129053e+03 -5.65653613e+03 -5.58128955e+03 -5.82408594e+03 -5.89301611e+03 -5.56356494e+03 -5.36447803e+03 -5.61395068e+03 -5.90843799e+03 -5.77880566e+03 -5.46727832e+03 -5.33455615e+03 -5.59384863e+03 -5.64967188e+03 -5.44303516e+03 -5.45512158e+03 -5.28824365e+03 -5.09730029e+03 -5.29191699e+03 -5.49902002e+03 -5.44792383e+03 -5.17264502e+03 -4.99186182e+03 -5.23196436e+03 -5.38566895e+03 -5.20185400e+03 -4.93327490e+03 -4.83869385e+03 -4.97033008e+03 -4.98920850e+03 -5.08577930e+03 -5.03514258e+03 -4.82089258e+03 -4.82862158e+03 -4.82657715e+03 -4.86913086e+03 -4.71638574e+03 -4.58296289e+03 -4.74278125e+03 -4.70118066e+03 -4.63190039e+03 -4.46241748e+03 -4.46660352e+03 -4.68959668e+03 -4.46960205e+03 -4.26418945e+03 -4.34036475e+03 -4.39709229e+03 -4.38249512e+03 -4.28922021e+03 -4.34226367e+03 -4.34060010e+03 -4.17963330e+03 -4.00798633e+03 -3.97805640e+03 -4.15906934e+03 -4.03761182e+03 -3.87582056e+03 -3.98836597e+03 -3.96547607e+03 -3.82854590e+03 -3.75176929e+03 -3.85362402e+03 -3.78659790e+03 -3.62738721e+03 -3.69079468e+03 -3.65707275e+03 -3.63198340e+03 -3.59500317e+03 -3.51214795e+03 -3.44371387e+03 -3.30154297e+03 -3.24390186e+03 -3.38032495e+03 -3.46097949e+03 -3.23895483e+03 -3.03700391e+03 -3.12761816e+03 -3.27332642e+03 -3.20816382e+03 -3.00299097e+03 -2.85656714e+03 -2.96171362e+03 -3.00914453e+03 -2.86398706e+03 -2.86287402e+03 -2.81612476e+03 -2.67102319e+03 -2.65357056e+03 -2.71172046e+03 -2.67569214e+03 -2.52414575e+03 -2.40728320e+03 -2.47678613e+03 -2.53560205e+03 -2.42008057e+03 -2.28490479e+03 -2.20575586e+03 -2.26902197e+03 -2.28538965e+03 -2.16662744e+03 -2.07525293e+03 -2.03555347e+03 -2.02312549e+03 -1.97236719e+03 -1.98438074e+03 -1.89640161e+03 -1.77893884e+03 -1.80193018e+03 -1.76901941e+03 -1.73064233e+03 -1.63861108e+03 -1.56466931e+03 -1.59054639e+03 -1.50591736e+03 -1.43036780e+03 -1.42951074e+03 -1.39579614e+03 -1.36471741e+03 -1.31428040e+03 -1.28473523e+03 -1.24088696e+03 -1.19284106e+03 -1.11460254e+03 -9.75226013e+02 -1.05873682e+03 -8.28766357e+02 -1.59225427e+03 -3.52343262e+03 4.23644188e+05 128359992. 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. 466285152. -6.38635938e+05 3.99322607e+03 2.57463623e+03 1.41469275e+03 1.19943115e+03 1.21353711e+03 1.02753271e+03 1.02468237e+03 1.01580133e+03 1.03777795e+03 1.09588721e+03 1.17283984e+03 1.22132080e+03 1.23155200e+03 1.26241553e+03 1.33604028e+03 1.38723474e+03 1.42076404e+03 1.46926343e+03 1.53256116e+03 1.55618726e+03 1.60377625e+03 1.68207043e+03 1.66385034e+03 1.65160938e+03 1.77818408e+03 1.92064380e+03 1.94877307e+03 1.91593018e+03 1.91260364e+03 2.01671997e+03 2.08846484e+03 2.10974780e+03 2.13419971e+03 2.17595508e+03 2.26828027e+03 2.32496753e+03 2.34300708e+03 2.36299194e+03 2.40502563e+03 2.53093311e+03 2.58753638e+03 2.50563257e+03 2.54337329e+03 2.64581714e+03 2.69556641e+03 2.78794604e+03 2.80768848e+03 2.78018701e+03 2.86581836e+03 2.93925366e+03 2.96767163e+03 3.01851807e+03 3.02061377e+03 3.07625171e+03 3.15955835e+03 3.15914282e+03 3.18077979e+03 3.21295190e+03 3.27898779e+03 3.37532739e+03 3.43686108e+03 3.45566650e+03 3.42816748e+03 3.44286865e+03 3.58083789e+03 3.61827295e+03 3.56972632e+03 3.65091943e+03 3.70537720e+03 3.75496704e+03 3.85988232e+03 3.87507837e+03 3.81726318e+03 3.85297168e+03 3.99330151e+03 4.06123584e+03 4.00352539e+03 3.97117749e+03 4.04566162e+03 4.13667334e+03 4.28306104e+03 4.29639160e+03 4.18327588e+03 4.22534521e+03 4.39294434e+03 4.43187891e+03 4.43609131e+03 4.35804688e+03 4.37045020e+03 4.55532617e+03 4.61204639e+03 4.54710596e+03 4.58608252e+03 4.64163232e+03 4.68281445e+03 4.72597559e+03 4.73164893e+03 4.80887354e+03 4.84187158e+03 4.94739014e+03 4.99060303e+03 4.81705029e+03 4.87175635e+03 5.02194580e+03 5.02622998e+03 5.04730811e+03 5.05097607e+03 5.10196338e+03 5.24857715e+03 5.20837500e+03 5.16336963e+03 5.30400928e+03 5.34193701e+03 5.27946631e+03 5.28801123e+03 5.37513281e+03 5.41922119e+03 5.43140137e+03 5.38689941e+03 5.43769727e+03 5.50890039e+03 5.66181885e+03 5.63638525e+03 5.47699854e+03 5.55333350e+03 5.71874902e+03 5.74329150e+03 5.71605957e+03 5.66780957e+03 5.63955225e+03 5.79933643e+03 5.94256934e+03 5.86477197e+03 5.75038721e+03 5.81679004e+03 5.98274707e+03 6.03861816e+03 6.08805664e+03 5.95589111e+03 5.82241895e+03 5.97156592e+03 6.01306055e+03 6.03340088e+03 6.09902197e+03 6.05616406e+03 6.15759766e+03 6.30897314e+03 6.23390039e+03 6.00453809e+03 6.09676562e+03 6.25805518e+03 6.33298877e+03 6.38915723e+03 6.27606152e+03 6.20369629e+03 6.28670312e+03 6.49154785e+03 6.39682715e+03 6.19047607e+03 6.31498975e+03 6.51593555e+03 6.48426904e+03 6.44808398e+03 6.33998096e+03 6.36863916e+03 6.49259326e+03 6.50753857e+03 6.50739453e+03 6.58222314e+03 6.49816992e+03 6.51486475e+03 6.69208350e+03 6.61553125e+03 6.48521240e+03 6.55751416e+03 6.69401465e+03 6.67056689e+03 6.71254297e+03 6.58463721e+03 6.50442969e+03 6.66776172e+03 6.93688086e+03 6.97086426e+03 6.52193994e+03 6.55954785e+03 6.92337646e+03 6.82149951e+03 6.67377881e+03 6.66558545e+03 6.63542334e+03 6.79300342e+03 6.89079883e+03 6.81217578e+03 6.68594971e+03 6.65860596e+03 6.78010254e+03 6.94413232e+03 6.93625830e+03 6.81572412e+03 6.75230225e+03 6.81536768e+03 6.85460303e+03 6.75854199e+03 6.73606104e+03 6.83413232e+03 6.78868652e+03 6.94283398e+03 7.00388623e+03 6.65426221e+03 6.70724170e+03 6.91502930e+03 6.92925000e+03 6.89076514e+03 6.72176416e+03 6.75707373e+03 6.93018408e+03 6.94894092e+03 6.86620020e+03 6.67460449e+03 6.63407617e+03 6.83240234e+03 6.97150049e+03 6.83335938e+03 6.77261621e+03 6.86841797e+03 6.79739551e+03 6.90970410e+03 6.88532764e+03 6.68634668e+03 6.65630859e+03 6.72415430e+03 6.89449023e+03 6.76484570e+03 6.67930078e+03 6.69578809e+03 6.80674170e+03 6.81259473e+03 6.71937891e+03 6.67925781e+03 6.67529297e+03 6.76704492e+03 6.66679443e+03 6.79673633e+03 6.67516211e+03 6.57175439e+03 6.72111865e+03 6.53146436e+03 6.56123340e+03 6.73153369e+03 6.57558203e+03 6.52985449e+03 6.56773340e+03 6.58890820e+03 6.53705957e+03 6.41893262e+03 6.59495850e+03 6.78219141e+03 6.41694336e+03 6.33560254e+03 6.41819092e+03 6.41951758e+03 6.55110791e+03 6.46429590e+03 6.29629004e+03 6.30355420e+03 6.44572900e+03 6.44678320e+03 6.33953955e+03 6.28251953e+03 6.26730615e+03 6.31381055e+03 6.18571826e+03 6.18617139e+03 6.12271191e+03 6.12157178e+03 6.18341992e+03 6.26231885e+03 6.17071973e+03 6.04833887e+03 5.98531592e+03 6.11801367e+03 6.21882031e+03 5.97857178e+03 6.01591064e+03 6.01313965e+03 5.79792822e+03 5.93466455e+03 5.91412598e+03 5.76639697e+03 5.89464893e+03 5.85809375e+03 5.77022168e+03 5.89381396e+03 5.78554346e+03 5.65689307e+03 5.67985059e+03 5.71269434e+03 5.72010596e+03 5.55214551e+03 5.50292725e+03 5.57539697e+03 5.60186182e+03 5.54885889e+03 5.46544971e+03 5.37254492e+03 5.46466357e+03 5.56255908e+03 5.36731104e+03 5.24975439e+03 5.20964453e+03 5.34568066e+03 5.38268408e+03 5.17462256e+03 5.10926904e+03 5.13299707e+03 5.12634961e+03 5.07604102e+03 5.09142236e+03 5.02862891e+03 4.90891895e+03 4.97558789e+03 5.06488672e+03 4.89485986e+03 4.69471484e+03 4.74039111e+03 4.83116260e+03 4.78676611e+03 4.74451855e+03 4.68727588e+03 4.57443799e+03 4.67682666e+03 4.72823975e+03 4.54156006e+03 4.44896680e+03 4.44086963e+03 4.54484863e+03 4.47297705e+03 4.24875586e+03 4.23448779e+03 4.27422754e+03 4.26288379e+03 4.24808740e+03 4.22330615e+03 4.12884082e+03 4.10349951e+03 4.05873291e+03 3.94994067e+03 3.92875024e+03 3.89626733e+03 3.91439038e+03 3.91985669e+03 3.81374048e+03 3.71337427e+03 3.71100391e+03 3.74135962e+03 3.80393774e+03 3.72573682e+03 3.52464526e+03 3.48237842e+03 3.52158740e+03 3.47088110e+03 3.39094458e+03 3.36703394e+03 3.33957446e+03 3.31367676e+03 3.24318384e+03 3.13268091e+03 3.15256348e+03 3.18686377e+03 3.14909448e+03 3.05036328e+03 2.94471143e+03 2.94373169e+03 2.88516797e+03 2.82092554e+03 2.86851709e+03 2.82102441e+03 2.68556421e+03 2.65181470e+03 2.65667505e+03 2.65342603e+03 2.60767432e+03 2.50693262e+03 2.46565894e+03 2.43234155e+03 2.35714551e+03 2.29976123e+03 2.29367554e+03 2.25792188e+03 2.23611060e+03 2.18888965e+03 2.05471118e+03 2.03674536e+03 2.01801282e+03 1.97318237e+03 1.97492725e+03 1.87585022e+03 1.80314929e+03 1.81920020e+03 1.78047510e+03 1.69691553e+03 1.64442810e+03 1.58518140e+03 1.53331116e+03 1.50241504e+03 1.46465039e+03 1.41065930e+03 1.38908435e+03 1.35805676e+03 1.28921521e+03 1.22551416e+03 1.16237476e+03 1.13866016e+03 1.11332837e+03 1.05382007e+03 9.82233582e+02 9.31384094e+02 8.98661682e+02 8.63193237e+02 8.29506348e+02 7.62794556e+02 7.01637939e+02 6.66408203e+02 6.19617615e+02 5.65263367e+02 5.27794006e+02 4.75562500e+02 4.18066101e+02 3.83866577e+02 3.36210358e+02 2.83601868e+02 2.34917007e+02 1.85967545e+02 1.40816223e+02 9.42196655e+01 4.63541565e+01 -3.11184740e+00 -5.12162971e+01 -9.86581268e+01 -1.44710342e+02 -1.91396011e+02 -2.33724945e+02 -2.83295135e+02 -3.33261597e+02 -3.79063385e+02 -4.36347900e+02 -4.84042084e+02 -5.22107849e+02 -5.67609680e+02 -6.19657776e+02 -6.84235413e+02 -7.37852905e+02 -7.67245300e+02 -8.02253601e+02 -8.43645447e+02 -8.97929382e+02 -9.55634460e+02 -1.00794415e+03 -1.05671924e+03 -1.09638147e+03 -1.13452148e+03 -1.17296875e+03 -1.22913416e+03 -1.31545361e+03 -1.35987366e+03 -1.36143164e+03 -1.40659192e+03 -1.45505664e+03 -1.49894751e+03 -1.57648059e+03 -1.63763623e+03 -1.65885205e+03 -1.69319775e+03 -1.72956091e+03 -1.78237329e+03 -1.86470764e+03 -1.90140771e+03 -1.94272180e+03 -1.98578601e+03 -2.01087354e+03 -2.08171338e+03 -2.09770752e+03 -2.14378613e+03 -2.24810425e+03 -2.25181299e+03 -2.26355176e+03 -2.32944531e+03 -2.37359180e+03 -2.41291919e+03 -2.54104272e+03 -2.58939014e+03 -2.51004102e+03 -2.57040479e+03 -2.64857739e+03 -2.66663403e+03 -2.78002368e+03 -2.81235229e+03 -2.77326245e+03 -2.84346289e+03 -2.89515552e+03 -3.00808618e+03 -3.08581958e+03 -3.05679468e+03 -3.10767651e+03 -3.11251636e+03 -3.08173633e+03 -3.16326538e+03 -3.29773999e+03 -3.32493115e+03 -3.37563037e+03 -3.40453369e+03 -3.30631860e+03 -3.41856421e+03 -3.60637769e+03 -3.63729077e+03 -3.58658350e+03 -3.52578003e+03 -3.61345264e+03 -3.78018848e+03 -3.79523804e+03 -3.78428687e+03 -3.86959717e+03 -3.85671606e+03 -3.90873682e+03 -3.96987646e+03 -3.88858472e+03 -3.95991602e+03 -4.11619238e+03 -4.18729590e+03 -4.15855957e+03 -4.06234009e+03 -4.12998682e+03 -4.28562793e+03 -4.35654785e+03 -4.39097412e+03 -4.30551123e+03 -4.28193164e+03 -4.40520215e+03 -4.54038672e+03 -4.64786426e+03 -4.59300537e+03 -4.52658984e+03 -4.60201904e+03 -4.62470166e+03 -4.65215039e+03 -4.74413477e+03 -4.74853418e+03 -4.80745947e+03 -4.91359375e+03 -4.86188721e+03 -4.84784863e+03 -4.95309375e+03 -5.00387598e+03 -5.03686328e+03 -5.00392871e+03 -4.96485840e+03 -5.02718262e+03 -5.16439160e+03 -5.25225635e+03 -5.31073584e+03 -5.20401416e+03 -5.12769482e+03 -5.25972803e+03 -5.26516357e+03 -5.33319629e+03 -5.45251172e+03 -5.38452002e+03 -5.35649854e+03 -5.34979150e+03 -5.43448535e+03 -5589. -5.69128320e+03 -5.61367139e+03 -5.59337988e+03 -5.56049463e+03 -5.47751123e+03 -5.59161621e+03 -5.75027637e+03 -5.84410010e+03 -5.85294727e+03 -5.69965479e+03 -5.67092725e+03 -5.82484277e+03 -5.90864600e+03 -5.91676709e+03 -5.93417480e+03 -5.90144482e+03 -5.83010352e+03 -5.97974121e+03 -6.14521875e+03 -6.06237354e+03 -5.94393018e+03 -6.02384961e+03 -6.08980420e+03 -6.14212354e+03 -6.18946729e+03 -6.18656152e+03 -6.22881934e+03 -6.17538330e+03 -6.12249707e+03 -6.33880029e+03 -6.31631104e+03 -6.23998193e+03 -6.44119922e+03 -6.28779785e+03 -6.20865332e+03 -6.49783838e+03 -6.55365820e+03 -6.24137500e+03 -6.70873828e+03 -6.66665283e+03 -5.95083936e+03 -5.85807422e+03 -1.06712275e+04 -1.01477295e+04 -1.79236309e+04 -2.10968477e+04 60721824. -2819905. -67271688. -41445444. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.98316650e+06 -20910288. -3.07884688e+04 -1.58189316e+04 -9.33458008e+03 -1.11550117e+04 -8.83713867e+03 -9.54229883e+03 -7.56193799e+03 -6.56211963e+03 -6.78235791e+03 -7.07486084e+03 -6.98370459e+03 -6.84071875e+03 -6.74262891e+03 -6.66699316e+03 -6.93005371e+03 -7.13165918e+03 -6.84842725e+03 -6.53899414e+03 -6.62026367e+03 -6.73676367e+03 -6.86318506e+03 -6.96387451e+03 -6.71026465e+03 -6.58258887e+03 -6.69383057e+03 -6.65112500e+03 -6.74046338e+03 -6.63260791e+03 -6.55849463e+03 -6.74407227e+03 -6.93546973e+03 -6.77240576e+03 -6.40986963e+03 -6.44608105e+03 -6.69460449e+03 -6.73840088e+03 -6.57974512e+03 -6.40331348e+03 -6.47601953e+03 -6.68914746e+03 -6.83055420e+03 -6.58927148e+03 -6.27944824e+03 -6.36057227e+03 -6.65355664e+03 -6.58306689e+03 -6.55197119e+03 -6.42366602e+03 -6.20701270e+03 -6.35595361e+03 -6.56316309e+03 -6.36914795e+03 -6.25396826e+03 -6.45340771e+03 -6.46239746e+03 -6.35629541e+03 -6.22935205e+03 -6.09023877e+03 -6.20190381e+03 -6.45935889e+03 -6.32115527e+03 -6.10410986e+03 -6.01248438e+03 -5.99378760e+03 -6.22935938e+03 -6.37466553e+03 -6.15363184e+03 -5.96558643e+03 -5.92518945e+03 -5.86811133e+03 -6.03199023e+03 -6.17761475e+03 -5.92612305e+03 -5.80972559e+03 -5.93653027e+03 -5.86886719e+03 -5.75699121e+03 -5.77109961e+03 -5.82023096e+03 -5.88186572e+03 -5.83849707e+03 -5.78950537e+03 -5.56332275e+03 -5.46085400e+03 -5.72928711e+03 -5.84489160e+03 -5.52715820e+03 -5.34960840e+03 -5.45174805e+03 -5.54284033e+03 -5.59753516e+03 -5.64445605e+03 -5.39087158e+03 -5.26855518e+03 -5.36501660e+03 -5.33990576e+03 -5.37500830e+03 -5.26607617e+03 -5.11633301e+03 -5.14873926e+03 -5.21924072e+03 -5.20331201e+03 -5.14132861e+03 -5.12172363e+03 -5.06610254e+03 -5.03190723e+03 -5.03565967e+03 -4.85051562e+03 -4.78591016e+03 -5.02684277e+03 -5.00489209e+03 -4.73051660e+03 -4.61373877e+03 -4.66317725e+03 -4.82213574e+03 -4.93237158e+03 -4.72129785e+03 -4.47896338e+03 -4.44302100e+03 -4.48687939e+03 -4.52636572e+03 -4.52375781e+03 -4.43973291e+03 -4.39869971e+03 -4.34623242e+03 -4.30972900e+03 -4.28898877e+03 -4.17163477e+03 -4.19810107e+03 -4.30207324e+03 -4.18779688e+03 -4.08934521e+03 -4.00924121e+03 -3.90497437e+03 -4.02758398e+03 -4.09525342e+03 -3.86784912e+03 -3.73435571e+03 -3.77235815e+03 -3.87712817e+03 -3.90141309e+03 -3.73524487e+03 -3.58614038e+03 -3.55362476e+03 -3.55583154e+03 -3.59539941e+03 -3.59626221e+03 -3.41218311e+03 -3.29650586e+03 -3.36133203e+03 -3.42225586e+03 -3.35546777e+03 -3.24260693e+03 -3.20471582e+03 -3.14796582e+03 -3.14918604e+03 -3.13148633e+03 -2.98821973e+03 -2.93432886e+03 -2.96894849e+03 -2.94660059e+03 -2.88405835e+03 -2.78349561e+03 -2.74751807e+03 -2.75110278e+03 -2.71485034e+03 -2.68058887e+03 -2.57547974e+03 -2.54342236e+03 -2.55327563e+03 -2.48887231e+03 -2.42410205e+03 -2.34318530e+03 -2.30388647e+03 -2.31539258e+03 -2.32930957e+03 -2.24920435e+03 -2.09784448e+03 -2.03932617e+03 -2.08914087e+03 -2.09605908e+03 -2.01273010e+03 -1.88938391e+03 -1.82166650e+03 -1.83127185e+03 -1.81727759e+03 -1.77625378e+03 -1.69216577e+03 -1.61925281e+03 -1.59745667e+03 -1.58064282e+03 -1.54608972e+03 -1.47511755e+03 -1.40661987e+03 -1.37191187e+03 -1.33002722e+03 -1.28351636e+03 -1.23587939e+03 -1.18071606e+03 -1.13548340e+03 -1.08653601e+03 -1.02632214e+03 -9.75468628e+02 -9.61391174e+02 -9.45771362e+02 -8.85144348e+02 -8.04268250e+02 -7.31008545e+02 -6.92579834e+02 -6.85970886e+02 -6.51169861e+02 -5.83360901e+02 -5.15311401e+02 -4.58644012e+02 -4.24094177e+02 -3.93221985e+02 -3.43238800e+02 -2.89422791e+02 -2.38977020e+02 -1.91224197e+02 -1.41897232e+02 -8.97840576e+01 -4.22898331e+01 5.15615797e+00 5.16778488e+01 1.01256065e+02 1.45620804e+02 1.81455978e+02 2.32974167e+02 2.93024719e+02 3.42405304e+02 3.88910828e+02 4.28908356e+02 4.89027252e+02 5.42424133e+02 5.61399780e+02 5.90438416e+02 6.50240173e+02 7.32706909e+02 8.04879456e+02 8.39828491e+02 8.41422974e+02 8.59981995e+02 9.27596252e+02 1.02383417e+03 1.09961694e+03 1.12861902e+03 1.11421680e+03 1.15368433e+03 1.27661292e+03 1.31981763e+03 1.29960583e+03 1.35330127e+03 1.41430042e+03 1.45774963e+03 1.56446619e+03 1.57573633e+03 1.55799548e+03 1.64963892e+03 1.66605469e+03 1.75350623e+03 1.84419604e+03 1.79514319e+03 1.88039233e+03 1.97986902e+03 1.97992151e+03 2.03699329e+03 2.06687671e+03 2.11193262e+03 2.18460693e+03 2.20636377e+03 2.18560107e+03 2.24034106e+03 2.40697803e+03 2.50953955e+03 2.48906787e+03 2.42035498e+03 2.41227930e+03 2.49897144e+03 2.66280518e+03 2.79498755e+03 2.75361426e+03 2.66652466e+03 2.72878979e+03 2.85231470e+03 2.87564014e+03 2.88841919e+03 2.94226831e+03 2.98659155e+03 3.03370068e+03 3.19302466e+03 3.15832129e+03 3.09125269e+03 3.21797803e+03 3.16042627e+03 3.30472314e+03 3.42250073e+03 3.34940527e+03 3.53081934e+03 3.50234937e+03 3.37024292e+03 3.51731104e+03 3.51210693e+03 3.60598828e+03 3.87620898e+03 3.73273804e+03 3.56482739e+03 3.67556226e+03 3.89893677e+03 4.09779053e+03 4.03696216e+03 3.86960840e+03 3.82041992e+03 3.88324438e+03 4.10055469e+03 4.30204883e+03 4.27973535e+03 4.10172559e+03 4.08939087e+03 4.26713232e+03 4.34794482e+03 4.30198730e+03 4.31859619e+03 4.37513672e+03 4.41049902e+03 4.60447656e+03 4.63958545e+03 4.43642383e+03 4.46588965e+03 4.57812305e+03 4.62753223e+03 4.70658398e+03 4.72572607e+03 4.90327002e+03 4.79796045e+03 4.65919824e+03 4.86293408e+03 4.74605127e+03 4.88150049e+03 5.30049756e+03 5.02135986e+03 4.70989307e+03 4.92860449e+03 5.18447412e+03 5.34230420e+03 5.36207471e+03 5.09800781e+03 4.93272314e+03 5.07253467e+03 5.39808643e+03 5.62113623e+03 5.48009766e+03 5.18760156e+03 5.19603418e+03 5.39371436e+03 5.49932373e+03 5.68388574e+03 5.71062012e+03 5.40839746e+03 5.38962451e+03 5.62122949e+03 5.74608105e+03 5.62913428e+03 5.59658789e+03 5.66640869e+03 5.65603955e+03 5.88282471e+03 5.93618994e+03 5.72358154e+03 5.73829639e+03 5.80111621e+03 5.81821289e+03 5.91967041e+03 5.90639844e+03 6.02359424e+03 6.16820410e+03 5.99802881e+03 5.87966162e+03 5.78204541e+03 6.04312646e+03 6.41731592e+03 6.32140430e+03 5.98762891e+03 5.85341504e+03 6.08920068e+03 6.46133057e+03 6.27251953e+03 5.96478320e+03 6.11965430e+03 6.28346631e+03 6.45081689e+03 6.65102490e+03 6.54531689e+03 6.17277344e+03 6.07397363e+03 6.31291016e+03 6.49696484e+03 6.52832471e+03 6.41740527e+03 6.46323779e+03 6.42771094e+03 6.57162695e+03 6.48310156e+03 6.36265674e+03 6.44330273e+03 6.39703174e+03 6.61250488e+03 6.79683105e+03 6.57394873e+03 6.64372510e+03 6.67631299e+03 6.62898584e+03 6.48573047e+03 6.37814795e+03 6.69937207e+03 7.00710645e+03 6.79503662e+03 6.48522949e+03 6.48344189e+03 6.85427393e+03 6.97755713e+03 6.83554590e+03 6.77201025e+03 6.52017627e+03 6.52665332e+03 6.86178516e+03 6.87718311e+03 6.75994141e+03 6.59155518e+03 6.48890137e+03 6.83676172e+03 7.16704102e+03 6.79794482e+03 6.64260449e+03 6.80067041e+03 6.81507129e+03 7.01623242e+03 7.05981104e+03 6.61457080e+03 6.59153711e+03 6.79004492e+03 6.79767969e+03 6.85257422e+03 6.85696533e+03 7.22784766e+03 7.28331006e+03 6.55117383e+03 6.84123828e+03 6.43514990e+03 7.75617383e+03 9.36034473e+03 1.07624844e+04 9.74575879e+03 1.14755986e+04 1.90584160e+04 2.13672031e+04 5.61971450e+06 2.03219938e+06 3435410. -23206266. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38534712. -6.24706650e+06 2.60444980e+04 1.65947969e+04 1.07022451e+04 1.02780605e+04 8.55183398e+03 7.85540674e+03 6.28653418e+03 6.79945557e+03 6.50271777e+03 6.23836377e+03 6.32765820e+03 6.30039404e+03 6.17072607e+03 6.18027295e+03 6.19302246e+03 6.23171680e+03 6.30950635e+03 6.11894336e+03 5.87054004e+03 5.96871240e+03 5.93491357e+03 5.66848584e+03 5.98821094e+03 6.07889746e+03 5.57463379e+03 5.90890967e+03 6.18741016e+03 5.87552148e+03 5.74495850e+03 5.81780420e+03 5.91698486e+03 5.79198145e+03 5.74894678e+03 5.71461475e+03 5.67976025e+03 5.51602734e+03 5.47814355e+03 5.74001514e+03 5.70479297e+03 5.51326416e+03 5.47388574e+03 5.47771484e+03 5.47440674e+03 5.39947021e+03 5.36794189e+03 5.37106348e+03 5.25488232e+03 5.18418066e+03 5.21944727e+03 5.18549902e+03 5.34768457e+03 5.35173828e+03 5.15012451e+03 4.99268213e+03 4.91159277e+03 5.17878760e+03 5.18538916e+03 4.97123438e+03 4.85244580e+03 4.84991895e+03 4.89563623e+03 4.80741846e+03 4.92231787e+03 4.90910303e+03 4.60286768e+03 4.51662451e+03 4.70491699e+03 4.86323779e+03 4.70932227e+03 4.55205762e+03 4.52954834e+03 4.48418750e+03 4.44622510e+03 4.42406299e+03 4.42228906e+03 4.36906494e+03 4.26472314e+03 4.23449121e+03 4.22083008e+03 4.17078516e+03 4.26854395e+03 4.21161182e+03 4.04758398e+03 4.03953052e+03 3.99305688e+03 4.05416724e+03 4.03379834e+03 3.89386206e+03 3.85381274e+03 3.74806299e+03 3.65640942e+03 3.78487183e+03 3.74428613e+03 3.50496924e+03 3.51692310e+03 3.68024976e+03 3.75194458e+03 3.59995239e+03 3.45557275e+03 3.38761304e+03 3.33831177e+03 3.31469897e+03 3.27171167e+03 3.23596216e+03 3.18292847e+03 3.22998413e+03 3.17869775e+03 3.04669458e+03 3.02620776e+03 2.90063306e+03 2.91779810e+03 3.04723926e+03 2.95021460e+03 2.83896777e+03 2.71474072e+03 2.64927832e+03 2.75742505e+03 2.73356934e+03 2.60699048e+03 2.50092090e+03 2.44308447e+03 2.46132080e+03 2.41796802e+03 2.44832666e+03 2.41728076e+03 2.28885645e+03 2.22966650e+03 2.18668677e+03 2.17826367e+03 2.14002466e+03 2.06816870e+03 1.99836658e+03 1.95521997e+03 1.91318164e+03 1.81249414e+03 1.81122241e+03 1.87676477e+03 1.80106470e+03 1.70175500e+03 1.61025671e+03 1.56014832e+03 1.60669836e+03 1.56012598e+03 1.46991431e+03 1.38694702e+03 1.33287708e+03 1.33338782e+03 1.28085449e+03 1.22975977e+03 1.15626904e+03 1.13271155e+03 1.14034680e+03 1.06095862e+03 1.00368799e+03 9.62894897e+02 9.08477051e+02 8.44990967e+02 7.96752014e+02 7.55224670e+02 7.06464539e+02 6.68230652e+02 6.02680603e+02 5.61126038e+02 5.49481018e+02 4.79585083e+02 4.13643158e+02 3.78007568e+02 3.31875000e+02 2.92140472e+02 2.40377121e+02 1.84555466e+02 1.42320480e+02 9.56868286e+01 4.70759239e+01 -5.80542743e-01 -4.81643753e+01 -9.63437881e+01 -1.44508804e+02 -1.92610123e+02 -2.34116928e+02 -2.87401489e+02 -3.52823608e+02 -3.93791809e+02 -4.28239655e+02 -4.61750366e+02 -5.16195984e+02 -5.98817139e+02 -6.40708923e+02 -6.68000366e+02 -7.01854614e+02 -7.43750732e+02 -8.10938232e+02 -8.61433228e+02 -9.26766785e+02 -9.65219299e+02 -9.86129822e+02 -1.04071619e+03 -1.08783899e+03 -1.17011255e+03 -1.21174158e+03 -1.22143213e+03 -1.27407385e+03 -1.32680005e+03 -1.37066846e+03 -1.37608423e+03 -1.46272400e+03 -1.60230981e+03 -1.60959448e+03 -1.60868066e+03 -1.61426807e+03 -1.64370654e+03 -1.78903882e+03 -1.85632605e+03 -1.84486292e+03 -1.83854846e+03 -1.87730115e+03 -1.98529272e+03 -2.02846204e+03 -2.12039429e+03 -2.17005200e+03 -2.15778516e+03 -2.14263403e+03 -2.18035645e+03 -2.35650098e+03 -2.39449097e+03 -2.36954077e+03 -2.37865576e+03 -2.41205566e+03 -2.59252051e+03 -2.64881421e+03 -2.53878394e+03 -2.57069043e+03 -2.76692676e+03 -2.80987695e+03 -2.71028809e+03 -2.75321069e+03 -2.93560547e+03 -3.00360645e+03 -2.94898608e+03 -2.92003516e+03 -2.96375708e+03 -3.17108447e+03 -3.18050928e+03 -3.10918799e+03 -3.21533521e+03 -3.25370728e+03 -3.28084814e+03 -3.32493262e+03 -3.35934961e+03 -3.32268311e+03 -3.44252319e+03 -3.63560278e+03 -3.59109888e+03 -3.63932202e+03 -3.69811816e+03 -3.67332642e+03 -3.72138037e+03 -3.74814941e+03 -3.77206274e+03 -3.74157983e+03 -3.76679980e+03 -3.88972974e+03 -3.94814575e+03 -4.10907861e+03 -4.02143335e+03 -3.92050464e+03 -4.09022217e+03 -4.15710840e+03 -4.32416943e+03 -4.30992627e+03 -4.21384277e+03 -4.22844189e+03 -4.24093750e+03 -4.35723438e+03 -4.39638770e+03 -4.53202881e+03 -4.56012354e+03 -4.48357422e+03 -4.49668652e+03 -4.41188232e+03 -4.56287451e+03 -4.87725732e+03 -4.83254346e+03 -4.72002051e+03 -4.64550146e+03 -4.60963281e+03 -4.85962842e+03 -5.05860449e+03 -4.96712061e+03 -4.79549463e+03 -4.83503271e+03 -4.97966162e+03 -5.01279688e+03 -5.17555811e+03 -5.16727686e+03 -5.07573340e+03 -5.09208496e+03 -5.12237061e+03 -5.34045312e+03 -5.37221924e+03 -5.12926416e+03 -5.15043604e+03 -5.47087695e+03 -5.44813232e+03 -5.20204785e+03 -5.33279443e+03 -5.64181396e+03 -5.62659375e+03 -5.51353760e+03 -5.41173438e+03 -5.40508398e+03 -5.71803174e+03 -5.77691357e+03 -5.65572412e+03 -5.54385400e+03 -5.50918457e+03 -5.71573975e+03 -5.78112402e+03 -5.78225586e+03 -5.64718408e+03 -5.80814209e+03 -6.05877881e+03 -5.93838037e+03 -6.00910107e+03 -5.99346191e+03 -5.88045020e+03 -5.98128076e+03 -6.02718506e+03 -6.05043799e+03 -6.01821436e+03 -5.95139160e+03 -5.88174658e+03 -6.05141455e+03 -6.42063672e+03 -6.11351270e+03 -5.90951611e+03 -6.08549854e+03 -6.33282812e+03 -6.50320020e+03 -6.37401221e+03 -6.19883789e+03 -6.39360986e+03 -6.38797119e+03 -6.22732422e+03 -6.17876904e+03 -6.40938330e+03 -6.46065527e+03 -6.33672803e+03 -6.28375977e+03 -6.12709229e+03 -6.40709277e+03 -6.81171582e+03 -6.66145557e+03 -6.48201318e+03 -6.32997998e+03 -6.25014014e+03 -6.60950928e+03 -6.87575391e+03 -6.69738477e+03 -6.45097119e+03 -6.45671680e+03 -6.54385889e+03 -6.54793506e+03 -6.78873633e+03 -6.67640039e+03 -6.51574609e+03 -6.64185645e+03 -6.63540820e+03 -6.83401758e+03 -6.84353857e+03 -6.63140137e+03 -6.68802490e+03 -6.69161914e+03 -6.75268457e+03 -6.63408496e+03 -6.60183740e+03 -6.95453711e+03 -6.89764502e+03 -6.77735791e+03 -6.57517969e+03 -6.64128613e+03 -7.07879736e+03 -7.01494971e+03 -6.79642041e+03 -6.69289404e+03 -6.66178418e+03 -6.75727881e+03 -6.77159229e+03 -6.79190771e+03 -6.64521729e+03 -6.79307373e+03 -7.05101123e+03 -6.81119824e+03 -6.92670996e+03 -7.02913330e+03 -6.85435156e+03 -6.82879297e+03 -6.78536035e+03 -6.82748779e+03 -6.83259912e+03 -6.75934863e+03 -6.77054736e+03 -6.95536133e+03 -6.98192139e+03 -6.65571045e+03 -6.60212207e+03 -6.75852832e+03 -6.89626318e+03 -7.16027441e+03 -6.94602490e+03 -6.61834717e+03 -6.85060938e+03 -6.93251025e+03 -6.81297754e+03 -6.76874609e+03 -6.75956494e+03 -6.68465234e+03 -6.66833984e+03 -6.81934521e+03 -6.68153174e+03 -6.70879492e+03 -6.97794043e+03 -6.85085889e+03 -6.72933643e+03 -6.58628662e+03 -6.60284375e+03 -6.90222998e+03 -6.83210742e+03 -6.70462598e+03 -6.55001416e+03 -6.38377100e+03 -6.52278955e+03 -6.79929102e+03 -6.97100391e+03 -6.68060791e+03 -6.46696680e+03 -6.51695361e+03 -6.55226855e+03 -6.81421729e+03 -6.72954834e+03 -6.51364697e+03 -6.45206934e+03 -6.42944385e+03 -6.48264111e+03 -6.37728418e+03 -6.42981738e+03 -6.71363184e+03 -6.55251025e+03 -6.49224609e+03 -6.32466895e+03 -6.25352002e+03 -6.58631055e+03 -6.60033838e+03 -6.36108008e+03 -6.21112061e+03 -6.12493262e+03 -6.25392627e+03 -6.28363477e+03 -6.43548389e+03 -6.41422363e+03 -6.18917334e+03 -6.04300879e+03 -6.10829004e+03 -6.36255273e+03 -6.27555811e+03 -6.14508447e+03 -6.07054785e+03 -6.00384229e+03 -5.99418799e+03 -5.92466846e+03 -6.05291309e+03 -6.01693652e+03 -5.86810986e+03 -6.07561328e+03 -6.10992334e+03 -5.93804639e+03 -5.88378271e+03 -5.84640869e+03 -5.82856592e+03 -5.63272900e+03 -5.55850928e+03 -5.85119629e+03 -5.89325195e+03 -5.54724023e+03 -5.41152832e+03 -5.66045947e+03 -5.86281250e+03 -5.74919287e+03 -5.49414844e+03 -5.36758838e+03 -5.53949902e+03 -5.61095508e+03 -5.44773730e+03 -5.45761816e+03 -5.28205225e+03 -5.05642139e+03 -5.24485449e+03 -5.53499902e+03 -5.50994141e+03 -5.17170996e+03 -4.97428613e+03 -5.24563525e+03 -5.38328906e+03 -5.17979932e+03 -4.97228906e+03 -4.88330518e+03 -4.92212402e+03 -4.95371045e+03 -5.10338037e+03 -5.07050781e+03 -4.86659668e+03 -4.76693262e+03 -4.72591357e+03 -4.89618848e+03 -4.76185498e+03 -4.59671729e+03 -4.77104932e+03 -4.72657715e+03 -4.63304590e+03 -4.49836182e+03 -4.42371973e+03 -4.64598486e+03 -4.48387646e+03 -4.26789160e+03 -4.36107520e+03 -4.40224316e+03 -4.37868115e+03 -4.27863721e+03 -4.35202100e+03 -4.33933105e+03 -4.17678076e+03 -4.01624072e+03 -3.96289185e+03 -4.16636230e+03 -4.06857788e+03 -3.91601147e+03 -3.91953052e+03 -3.86407812e+03 -3.88206274e+03 -3.83456567e+03 -3.82836890e+03 -3.75776562e+03 -3.62127979e+03 -3.72079932e+03 -3.70417798e+03 -3.60146021e+03 -3.56441455e+03 -3.51956348e+03 -3.43504492e+03 -3.29647388e+03 -3.23906348e+03 -3.37815649e+03 -3.47294189e+03 -3.24218188e+03 -3.05861255e+03 -3.14584326e+03 -3.24661523e+03 -3.17140601e+03 -2.99686768e+03 -2.88224536e+03 -2.99443384e+03 -2.97062158e+03 -2.81739917e+03 -2.89002539e+03 -2.82619409e+03 -2.63460059e+03 -2.62952759e+03 -2.72753589e+03 -2.69972437e+03 -2.52133789e+03 -2.40163745e+03 -2.48102905e+03 -2.53683618e+03 -2.42413745e+03 -2.28368701e+03 -2.19990161e+03 -2.26670972e+03 -2.25525635e+03 -2.14454224e+03 -2.11528809e+03 -2.08062427e+03 -2.00862769e+03 -1.94810632e+03 -1.97542749e+03 -1.89990454e+03 -1.78822705e+03 -1.80270618e+03 -1.76849438e+03 -1.73372083e+03 -1.64301562e+03 -1.56024841e+03 -1.58794080e+03 -1.50559265e+03 -1.41852661e+03 -1.42573242e+03 -1.41292664e+03 -1.40511450e+03 -1.32724670e+03 -1.33305762e+03 -1.18629480e+03 -1.45739478e+03 -1.10777771e+03 -1.27825085e+03 -1.27714343e+03 -8.77022156e+02 -1.99630713e+03 -4.34907617e+03 4.23644188e+05 128359992. 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. 466285152. -6.38635938e+05 3.99322607e+03 2.57463623e+03 1.41469275e+03 1.04683398e+03 1.07503296e+03 9.17897644e+02 1.01292010e+03 9.93297058e+02 1.04242212e+03 1.19804041e+03 1.01675677e+03 1.46275916e+03 1.89129150e+03 1.88253027e+03 1.72086462e+03 1.80561414e+03 1.43468945e+03 1.52286560e+03 1.60986255e+03 1.55583472e+03 1.63164954e+03 1.68181958e+03 1.67033557e+03 1.72498608e+03 1.82162122e+03 1.87902563e+03 1.92358215e+03 1.92526318e+03 1.93284766e+03 2.02143311e+03 2.09675610e+03 2.12217188e+03 2.13071216e+03 2.16689502e+03 2.27488843e+03 2.33081421e+03 2.33338086e+03 2.35768994e+03 2.40582666e+03 2.53193237e+03 2.59613159e+03 2.51571411e+03 2.54308276e+03 2.64766602e+03 2.69630933e+03 2.78653857e+03 2.81284985e+03 2.78591724e+03 2.87400073e+03 2.94075220e+03 2.96180640e+03 3.01247168e+03 3.02373364e+03 3.08172998e+03 3.15678589e+03 3.16196606e+03 3.18809497e+03 3.22139258e+03 3.28235425e+03 3.38800146e+03 3.43380713e+03 3.44932568e+03 3.42628857e+03 3.43888843e+03 3.58537378e+03 3.62559961e+03 3.56667334e+03 3.64939404e+03 3.70836304e+03 3.75041431e+03 3.86813086e+03 3.87837109e+03 3.82389087e+03 3.85437061e+03 3.99379419e+03 4.06224487e+03 4.00131641e+03 3.96722461e+03 4.03449658e+03 4.14151953e+03 4.28870947e+03 4.30704834e+03 4.18318652e+03 4.23449609e+03 4.39567090e+03 4.42579492e+03 4.43197705e+03 4.35484424e+03 4.37222363e+03 4.56809082e+03 4.62641016e+03 4.55300488e+03 4.58503857e+03 4.64671338e+03 4.67895605e+03 4.71739941e+03 4.74127100e+03 4.81019385e+03 4.85140771e+03 4.94813574e+03 4.96844727e+03 4.82712793e+03 4.88936719e+03 5.03544678e+03 5.02498633e+03 5.02776123e+03 5.05587793e+03 5.11172412e+03 5.24315283e+03 5.22001123e+03 5.17392969e+03 5.29808398e+03 5.35300732e+03 5.26357275e+03 5.29310938e+03 5.36637354e+03 5.42779492e+03 5.42785449e+03 5.39950684e+03 5.43975732e+03 5.50802979e+03 5.65210791e+03 5.65810449e+03 5.48194434e+03 5.56156104e+03 5.72348242e+03 5.73872119e+03 5.72230371e+03 5.66000049e+03 5.62240674e+03 5.78756689e+03 5.95696338e+03 5.87048926e+03 5.74385303e+03 5.80712891e+03 5.97382959e+03 6.03664502e+03 6.08510449e+03 5.95868213e+03 5.82407617e+03 5.97229053e+03 6.03131299e+03 6.04321729e+03 6.12804541e+03 6.08658447e+03 6.14737891e+03 6.31612061e+03 6.21893164e+03 6.01817139e+03 6.13449316e+03 6.29931299e+03 6.32154443e+03 6.37260791e+03 6.29371045e+03 6.22662842e+03 6.28078857e+03 6.49521582e+03 6.39545264e+03 6.17614795e+03 6.33724609e+03 6.53249902e+03 6.47804736e+03 6.42701562e+03 6.36794727e+03 6.37516016e+03 6.50541162e+03 6.48512744e+03 6.50772461e+03 6.61025000e+03 6.50467139e+03 6.54346582e+03 6.71328320e+03 6.63116211e+03 6.46900049e+03 6.51831348e+03 6.64801758e+03 6.72550391e+03 6.69357959e+03 6.59675928e+03 6.50684326e+03 6.61315088e+03 6.94751904e+03 6.98051904e+03 6.54111084e+03 6.61843018e+03 6.85402051e+03 6.81326123e+03 6.73017432e+03 6.63545312e+03 6.65830957e+03 6.80815527e+03 6.86787988e+03 6.78732471e+03 6.71152686e+03 6.66535010e+03 6.78144824e+03 6.91637158e+03 6.91353467e+03 6.79749170e+03 6.76144434e+03 6.83636572e+03 6.84037158e+03 6.74867188e+03 6.77261914e+03 6.81587012e+03 6.82141504e+03 6.93290283e+03 7.04066113e+03 6.70779102e+03 6.73311768e+03 6.88504004e+03 6.93098242e+03 6.93898633e+03 6.74123145e+03 6.76422607e+03 6.96544775e+03 6.95639844e+03 6.88869580e+03 6.70076221e+03 6.66254102e+03 6.87000732e+03 6.99257227e+03 6.86448633e+03 6.81616553e+03 6.88047363e+03 6.81647510e+03 6.92555859e+03 6.88972168e+03 6.70238672e+03 6.67380078e+03 6.72260596e+03 6.90641650e+03 6.79111572e+03 6.66984863e+03 6.72473584e+03 6.82926611e+03 6.82320752e+03 6.73320703e+03 6.67135449e+03 6.66783350e+03 6.76914453e+03 6.67031934e+03 6.78759570e+03 6.68674023e+03 6.55507715e+03 6.75175537e+03 6.53156836e+03 6.59093018e+03 6.73551074e+03 6.57796143e+03 6.49768652e+03 6.59355078e+03 6.56769043e+03 6.52043555e+03 6.38986133e+03 6.60610254e+03 6.77486865e+03 6.42055957e+03 6.31994971e+03 6.44368213e+03 6.42777588e+03 6.56701025e+03 6.48027539e+03 6.27775049e+03 6.32501758e+03 6.43633936e+03 6.41115381e+03 6.33130225e+03 6.27684521e+03 6.27907080e+03 6.32198828e+03 6.17171582e+03 6.19791504e+03 6.16098584e+03 6.11299072e+03 6.16773584e+03 6.21867236e+03 6.20369580e+03 6.07155029e+03 5.98519775e+03 6.13084814e+03 6.23424902e+03 5.98344727e+03 6.01001367e+03 6.00868457e+03 5.81391162e+03 5.92547900e+03 5.93807764e+03 5.78462109e+03 5.89046973e+03 5.87025586e+03 5.78167432e+03 5.90508105e+03 5.77175244e+03 5.65328320e+03 5.66805908e+03 5.71237061e+03 5.73326465e+03 5.55829639e+03 5.49942041e+03 5.58762012e+03 5.60348438e+03 5.54849463e+03 5.47483838e+03 5.39022412e+03 5.45359326e+03 5.57281055e+03 5.36793799e+03 5.24269189e+03 5.20919922e+03 5.35857227e+03 5.38263086e+03 5.16529785e+03 5.11503711e+03 5.13479248e+03 5.13571436e+03 5.07666260e+03 5.09516602e+03 5.04121924e+03 4.91642529e+03 4.97807715e+03 5.06241797e+03 4.89902539e+03 4.68367676e+03 4.74191895e+03 4.83133545e+03 4.78076318e+03 4.75952783e+03 4.68297949e+03 4.58311377e+03 4.68320752e+03 4.73229688e+03 4.54125635e+03 4.45454785e+03 4.44896436e+03 4.54609570e+03 4.48267578e+03 4.25432910e+03 4.23288184e+03 4.28103711e+03 4.27607422e+03 4.23531885e+03 4.22348779e+03 4.13065869e+03 4.10286279e+03 4.06443481e+03 3.95517871e+03 3.93018726e+03 3.89721069e+03 3.90945776e+03 3.92656030e+03 3.82103882e+03 3.70701221e+03 3.70982739e+03 3.74065332e+03 3.80393042e+03 3.73094507e+03 3.52346289e+03 3.48455835e+03 3.52391260e+03 3.47619751e+03 3.39634204e+03 3.35787988e+03 3.33617090e+03 3.32281006e+03 3.24021851e+03 3.12990356e+03 3.15254443e+03 3.17956665e+03 3.14854932e+03 3.05537183e+03 2.94720093e+03 2.93694971e+03 2.87536401e+03 2.82108813e+03 2.87176685e+03 2.82308984e+03 2.68723535e+03 2.65292261e+03 2.65136523e+03 2.65822998e+03 2.61366968e+03 2.51469946e+03 2.46111768e+03 2.42400488e+03 2.36354126e+03 2.30403955e+03 2.29592944e+03 2.25586621e+03 2.23063354e+03 2.18745337e+03 2.05813770e+03 2.03960938e+03 2.01750586e+03 1.96835010e+03 1.97204358e+03 1.87600598e+03 1.80156641e+03 1.81877454e+03 1.78098071e+03 1.70191101e+03 1.64812476e+03 1.58262415e+03 1.52888660e+03 1.49673645e+03 1.46408069e+03 1.41182959e+03 1.39254834e+03 1.35848169e+03 1.28562195e+03 1.22206665e+03 1.16125708e+03 1.13760876e+03 1.11134106e+03 1.05069226e+03 9.77676025e+02 9.29092529e+02 8.98795532e+02 8.67734680e+02 8.35016785e+02 7.65815308e+02 7.00774597e+02 6.60827271e+02 6.12932129e+02 5.61539490e+02 5.30863159e+02 4.81744537e+02 4.21956421e+02 3.81548126e+02 3.31236847e+02 2.83511993e+02 2.39783188e+02 1.91469238e+02 1.42826553e+02 9.34632568e+01 4.51971512e+01 -2.67693591e+00 -5.11063881e+01 -9.91937103e+01 -1.46196671e+02 -1.93732971e+02 -2.36314072e+02 -2.88955170e+02 -3.40580963e+02 -3.85108612e+02 -4.36146820e+02 -4.80538391e+02 -5.22442139e+02 -5.71858765e+02 -6.23688965e+02 -6.84897400e+02 -7.32827271e+02 -7.61175537e+02 -8.04126160e+02 -8.49057068e+02 -8.97368713e+02 -9.52040039e+02 -1.00933429e+03 -1.06205969e+03 -1.09811719e+03 -1.13673669e+03 -1.17974219e+03 -1.23178223e+03 -1.31612000e+03 -1.36287744e+03 -1.36394360e+03 -1.40854724e+03 -1.45992517e+03 -1.50250159e+03 -1.58122925e+03 -1.63681116e+03 -1.65425562e+03 -1.69400549e+03 -1.73737732e+03 -1.78983960e+03 -1.86546704e+03 -1.89835181e+03 -1.93984253e+03 -1.98729126e+03 -2.01355017e+03 -2.08453076e+03 -2.09747559e+03 -2.14535181e+03 -2.25419482e+03 -2.25282300e+03 -2.27015259e+03 -2.33915454e+03 -2.36957397e+03 -2.41148853e+03 -2.54580078e+03 -2.59011963e+03 -2.50748022e+03 -2.57410718e+03 -2.65653564e+03 -2.67049683e+03 -2.77972070e+03 -2.81150635e+03 -2.77135645e+03 -2.85108716e+03 -2.90359790e+03 -2.99191577e+03 -3.07454126e+03 -3.06005908e+03 -3.10974609e+03 -3.11404663e+03 -3.08910327e+03 -3.17907397e+03 -3.30241333e+03 -3.32231055e+03 -3.37584912e+03 -3.40746338e+03 -3.31876221e+03 -3.42396338e+03 -3.61761084e+03 -3.63978418e+03 -3.58544043e+03 -3.52597827e+03 -3.60709326e+03 -3.78110156e+03 -3.79063086e+03 -3.78264014e+03 -3.88613501e+03 -3.85964795e+03 -3.91038013e+03 -3.98651221e+03 -3.88300732e+03 -3.96121558e+03 -4.12429980e+03 -4.18495068e+03 -4.15545752e+03 -4.06208154e+03 -4.13403125e+03 -4.28059277e+03 -4.37644043e+03 -4.38141455e+03 -4.30546533e+03 -4.29766162e+03 -4.40102246e+03 -4.53989062e+03 -4.64618701e+03 -4.59781055e+03 -4.52930469e+03 -4.60121191e+03 -4.63182666e+03 -4.66390039e+03 -4.74712305e+03 -4.75572070e+03 -4.79543896e+03 -4.91305371e+03 -4.85470166e+03 -4.85052734e+03 -4.94751562e+03 -4.99794092e+03 -5.03378125e+03 -5.00305322e+03 -4.96632715e+03 -5.03332471e+03 -5.16778613e+03 -5.26163672e+03 -5.33320801e+03 -5.22450635e+03 -5.11073682e+03 -5.24819727e+03 -5.27214941e+03 -5.34277588e+03 -5.45246436e+03 -5.36831494e+03 -5.34583643e+03 -5.37432178e+03 -5.43733496e+03 -5.58909570e+03 -5.69874658e+03 -5.62560449e+03 -5.59106982e+03 -5.56873291e+03 -5.48781738e+03 -5.59581982e+03 -5.76806787e+03 -5.85171387e+03 -5.85170508e+03 -5.70535449e+03 -5.67824365e+03 -5.82246680e+03 -5.91828564e+03 -5.94382861e+03 -5.92778955e+03 -5.88418359e+03 -5.83724561e+03 -5.98825732e+03 -6.15305908e+03 -6.08103906e+03 -5.93570166e+03 -6.02166992e+03 -6.09396582e+03 -6.13412646e+03 -6.19129785e+03 -6.18150000e+03 -6.25508643e+03 -6.16936768e+03 -6.12094580e+03 -6.35866553e+03 -6.32435498e+03 -6.24981885e+03 -6.44313672e+03 -6.26620996e+03 -6.21333154e+03 -6.51665430e+03 -6.52825098e+03 -6.25246484e+03 -6.71710254e+03 -6.66162891e+03 -5.95760693e+03 -5.90863330e+03 -1.23183027e+04 -9.69551562e+03 -1.96037480e+04 -1.88124980e+04 2.99202775e+06 -4489850. 3.35797025e+06 -72840128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.98316650e+06 -20910288. -3.07884688e+04 -1.58189316e+04 -9.33458008e+03 -1.11550117e+04 -1.00423184e+04 -1.02091504e+04 -9.73584961e+03 -5.48282764e+03 -6.18943555e+03 -8.12062793e+03 -6.83592334e+03 -6.35648584e+03 -5.90816992e+03 -6.48022559e+03 -7.06349365e+03 -6.97531396e+03 -6.71632568e+03 -6.67270117e+03 -6.87032959e+03 -6.83040186e+03 -6.93908301e+03 -6.98848633e+03 -6.73843555e+03 -6.63261621e+03 -6.69991162e+03 -6.68338330e+03 -6.75500977e+03 -6.63051758e+03 -6.53655029e+03 -6.74397217e+03 -6.95873242e+03 -6.78287500e+03 -6.41771631e+03 -6439. -6.70343896e+03 -6.76842480e+03 -6.57250781e+03 -6.39837061e+03 -6.47460596e+03 -6.69321484e+03 -6.82835449e+03 -6.60974463e+03 -6.28259766e+03 -6.35208594e+03 -6.67542480e+03 -6.56493652e+03 -6.56839893e+03 -6.44671777e+03 -6.20098584e+03 -6.32857764e+03 -6.53045117e+03 -6.37391797e+03 -6.23784521e+03 -6.44910400e+03 -6.46212793e+03 -6.35939648e+03 -6.22821436e+03 -6.09055078e+03 -6.20111035e+03 -6.46259375e+03 -6.31407178e+03 -6.10925293e+03 -6.01342236e+03 -5.98557666e+03 -6.27523291e+03 -6.36010400e+03 -6.13291309e+03 -5.97333838e+03 -5.92609326e+03 -5.87258203e+03 -6.01249707e+03 -6.16642383e+03 -5.94586133e+03 -5.80334033e+03 -5.93826172e+03 -5.87217969e+03 -5.75515527e+03 -5.75777148e+03 -5.82917969e+03 -5.88725684e+03 -5.84057227e+03 -5.76795117e+03 -5.58149316e+03 -5.46922168e+03 -5.73304834e+03 -5.84010498e+03 -5.52838428e+03 -5.32669971e+03 -5.44100830e+03 -5.53834277e+03 -5.61244971e+03 -5.65285059e+03 -5.37966943e+03 -5.27411719e+03 -5.37729053e+03 -5.34229346e+03 -5.36576953e+03 -5.26013672e+03 -5.10797803e+03 -5.14898535e+03 -5.23383105e+03 -5.20435303e+03 -5.13599170e+03 -5.11960400e+03 -5.06250391e+03 -5.04321045e+03 -5.03012012e+03 -4.84556299e+03 -4.80037598e+03 -5.02645752e+03 -5.01057764e+03 -4.73083252e+03 -4.61015820e+03 -4.65866895e+03 -4.83292822e+03 -4.91977686e+03 -4.71873389e+03 -4.48821387e+03 -4.45260498e+03 -4.49257715e+03 -4.52922705e+03 -4.51905029e+03 -4.45587158e+03 -4.39655566e+03 -4.35241699e+03 -4.31711768e+03 -4.29315869e+03 -4.17616406e+03 -4.20739551e+03 -4.30051855e+03 -4.17789062e+03 -4.08667920e+03 -4.02397754e+03 -3.91413916e+03 -4.02938550e+03 -4.09796875e+03 -3.86455078e+03 -3.74620483e+03 -3.77907495e+03 -3.87585107e+03 -3.90002686e+03 -3.73980005e+03 -3.59074268e+03 -3.54827319e+03 -3.55571411e+03 -3.59304785e+03 -3.59304199e+03 -3.40932129e+03 -3.29900708e+03 -3.36876050e+03 -3.42053564e+03 -3.35440601e+03 -3.24148730e+03 -3.20901270e+03 -3.15806470e+03 -3.15146631e+03 -3.13215015e+03 -2.98445239e+03 -2.93711719e+03 -2.98204199e+03 -2.95235352e+03 -2.86886084e+03 -2.77214478e+03 -2.74909302e+03 -2.75513647e+03 -2.71517285e+03 -2.67978589e+03 -2.59004785e+03 -2.54807568e+03 -2.54984619e+03 -2.48952637e+03 -2.42081421e+03 -2.35021045e+03 -2.31315918e+03 -2.31916260e+03 -2.32411841e+03 -2.24709009e+03 -2.10101367e+03 -2.04221753e+03 -2.09127979e+03 -2.09840820e+03 -2.01188208e+03 -1.89247986e+03 -1.82372742e+03 -1.82623486e+03 -1.81921130e+03 -1.77676599e+03 -1.68440613e+03 -1.61090125e+03 -1.58862292e+03 -1.57812598e+03 -1.54367615e+03 -1.47597107e+03 -1.40863757e+03 -1.36890076e+03 -1.33037146e+03 -1.28365088e+03 -1.23903467e+03 -1.19090051e+03 -1.13809033e+03 -1.08117639e+03 -1.02070532e+03 -9.70340698e+02 -9.58110291e+02 -9.43380310e+02 -8.83442810e+02 -8.01343628e+02 -7.26692871e+02 -6.89191223e+02 -6.82881836e+02 -6.53242676e+02 -5.84219910e+02 -5.14560120e+02 -4.57314575e+02 -4.21201324e+02 -3.87693634e+02 -3.39583069e+02 -2.88322662e+02 -2.37332809e+02 -1.89578049e+02 -1.42545654e+02 -9.25213089e+01 -4.69553490e+01 -4.05822486e-01 4.86493797e+01 1.00368347e+02 1.49380844e+02 1.85034485e+02 2.33881332e+02 2.91296661e+02 3.40563812e+02 3.87712585e+02 4.30348755e+02 4.90478119e+02 5.41651855e+02 5.62310547e+02 5.90044678e+02 6.50607849e+02 7.33927979e+02 8.06032227e+02 8.40997192e+02 8.41015564e+02 8.59863647e+02 9.27188110e+02 1.02219397e+03 1.09900854e+03 1.13063330e+03 1.11310046e+03 1.15489014e+03 1.27722302e+03 1.31735034e+03 1.30459875e+03 1.35511523e+03 1.41609375e+03 1.46207910e+03 1.56605652e+03 1.57599243e+03 1.56001172e+03 1.65097729e+03 1.66601086e+03 1.75453979e+03 1.84836121e+03 1.79914490e+03 1.87686548e+03 1.97845703e+03 1.98122827e+03 2.03038501e+03 2.06890186e+03 2.11879102e+03 2.17865918e+03 2.20489185e+03 2.19411597e+03 2.23402734e+03 2.40032983e+03 2.51310327e+03 2.48803174e+03 2.42145337e+03 2.41259009e+03 2.50096777e+03 2.66436646e+03 2.79325464e+03 2.75410034e+03 2.66306616e+03 2.73374902e+03 2.85879956e+03 2.86856885e+03 2.89116113e+03 2.94380835e+03 2.98427905e+03 3.04399609e+03 3.19314990e+03 3.15306519e+03 3.09148608e+03 3.21229150e+03 3.15738916e+03 3.30988379e+03 3.42874561e+03 3.35561255e+03 3.53008472e+03 3.49810083e+03 3.36814404e+03 3.51264062e+03 3.52161279e+03 3.61075781e+03 3.88840063e+03 3.73368604e+03 3.56865356e+03 3.68365796e+03 3.89084863e+03 4.09136304e+03 4.04172046e+03 3.87345654e+03 3.81297729e+03 3.89162891e+03 4.10123340e+03 4.30855811e+03 4.27973535e+03 4.10777002e+03 4.09651709e+03 4.26454590e+03 4.35212939e+03 4.30134717e+03 4.31484473e+03 4.37371631e+03 4.40347217e+03 4.61408252e+03 4.66037793e+03 4.43726270e+03 4.46046094e+03 4.58039111e+03 4.62309326e+03 4.70507129e+03 4.73215430e+03 4.89918848e+03 4.80663574e+03 4.66038574e+03 4.85674463e+03 4.74992529e+03 4.89458057e+03 5.29508691e+03 5.01266357e+03 4.71942676e+03 4.91162109e+03 5.18187061e+03 5.34610889e+03 5.37633008e+03 5.10258203e+03 4.92795996e+03 5.08422852e+03 5.39328906e+03 5.63278320e+03 5.49721289e+03 5.19049805e+03 5.18644385e+03 5.40690332e+03 5.49120410e+03 5.67755420e+03 5.69942773e+03 5.41091602e+03 5.41220996e+03 5.63898047e+03 5.74848584e+03 5.61166553e+03 5.58416943e+03 5.67670264e+03 5.64907812e+03 5.88806348e+03 5.94458838e+03 5.74492871e+03 5.75511768e+03 5.78774365e+03 5.80935596e+03 5.91206006e+03 5.90096924e+03 6.05629883e+03 6.13325879e+03 5.98942383e+03 5.88851465e+03 5.77617432e+03 6.05014941e+03 6.40003613e+03 6.30660840e+03 6.02712646e+03 5.85623242e+03 6.09489844e+03 6.46047803e+03 6.26602686e+03 5.95793359e+03 6.12685645e+03 6.31081006e+03 6.45710498e+03 6.63404834e+03 6.54740479e+03 6.17613086e+03 6.07078125e+03 6.27262061e+03 6.49247266e+03 6.51608398e+03 6.42880859e+03 6.44075488e+03 6.44609961e+03 6.59901953e+03 6.51723877e+03 6.33722852e+03 6.44701514e+03 6.40079248e+03 6.65467139e+03 6.80260645e+03 6.57879297e+03 6.64962354e+03 6.68608203e+03 6.67585547e+03 6.51483643e+03 6.39059180e+03 6.70003369e+03 7.00209277e+03 6.82618213e+03 6.46037207e+03 6.53812598e+03 6.87274951e+03 6.99195703e+03 6.85862549e+03 6.77666357e+03 6.53386963e+03 6.55922070e+03 6.90084766e+03 6.87536670e+03 6.76661230e+03 6.59577783e+03 6.51196240e+03 6.84297949e+03 7.13828955e+03 6.82265381e+03 6.64807764e+03 6.81773730e+03 6.79743213e+03 6.97654932e+03 7.05882422e+03 6.63973438e+03 6.60532324e+03 6.80762158e+03 6.86170068e+03 6.90686084e+03 6.88455908e+03 7.24230811e+03 7.33766211e+03 6.54421045e+03 6.84314648e+03 6.41744434e+03 8.14904492e+03 1.00161426e+04 1.07336680e+04 9.68785449e+03 1.10530586e+04 1.77676152e+04 2.10090410e+04 -4913675. -1.25274312e+06 -2.09654575e+06 -43805204. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38534712. -6.24706650e+06 2.60444980e+04 1.65947969e+04 1.07022451e+04 1.02780605e+04 9.64592383e+03 9.38255762e+03 9.16236914e+03 9.59276758e+03 9.62842090e+03 9.33626562e+03 9.47612988e+03 9.46471680e+03 9.26023047e+03 9.30188770e+03 9.27801465e+03 9.22134473e+03 8.49934473e+03 8.39120801e+03 6.61245801e+03 6.03053467e+03 5.96007227e+03 6.08891455e+03 6.10669434e+03 5.80437842e+03 5.79015820e+03 6.08109180e+03 6.02875635e+03 5.87738867e+03 5.85313428e+03 5.80823047e+03 5.77177197e+03 5.74973486e+03 5.70933740e+03 5.70830713e+03 5.66166455e+03 5.49492871e+03 5.46497119e+03 5.72747119e+03 5.71612354e+03 5.50446582e+03 5.48809717e+03 5.47730566e+03 5.47466455e+03 5.41912207e+03 5.37932617e+03 5.36326660e+03 5.25617090e+03 5.18922461e+03 5.21642188e+03 5.17468213e+03 5.35431396e+03 5.35165869e+03 5.14156836e+03 4.99159961e+03 4.90892090e+03 5.17808643e+03 5.18249854e+03 4.97958984e+03 4.85753223e+03 4.86216992e+03 4.89934326e+03 4.81290869e+03 4.91328125e+03 4.89561035e+03 4.60741064e+03 4.51547607e+03 4.71290723e+03 4.87685205e+03 4.71152344e+03 4.56354150e+03 4.53915527e+03 4.48304395e+03 4.44303662e+03 4.41946582e+03 4.42629932e+03 4.38496484e+03 4.27257959e+03 4.23657227e+03 4.21631543e+03 4.17384375e+03 4.28000977e+03 4.21342920e+03 4.04722583e+03 4.03259082e+03 3.99296655e+03 4.06409473e+03 4.04429468e+03 3.90235376e+03 3.85454980e+03 3.74888257e+03 3.66530054e+03 3.79147241e+03 3.74722461e+03 3.50378247e+03 3.52036743e+03 3.68664575e+03 3.75267041e+03 3.60424219e+03 3.46246191e+03 3.38075171e+03 3.33584302e+03 3.32536475e+03 3.27687549e+03 3.23715869e+03 3.18286646e+03 3.23289307e+03 3.18960474e+03 3.05449292e+03 3.02616895e+03 2.89676880e+03 2.92455127e+03 3.05343848e+03 2.94456543e+03 2.83619824e+03 2.71690552e+03 2.65220093e+03 2.76015503e+03 2.73032031e+03 2.60633447e+03 2.49472900e+03 2.44710962e+03 2.46358716e+03 2.41389722e+03 2.45031689e+03 2.42183179e+03 2.29488916e+03 2.22948413e+03 2.18918652e+03 2.18410425e+03 2.14394604e+03 2.07074829e+03 1.99924768e+03 1.96032239e+03 1.92155432e+03 1.81416003e+03 1.81177673e+03 1.88142627e+03 1.80219214e+03 1.70021472e+03 1.61207861e+03 1.56190979e+03 1.60801196e+03 1.56267896e+03 1.46883887e+03 1.38439160e+03 1.33178479e+03 1.33451550e+03 1.28241235e+03 1.22809778e+03 1.15742419e+03 1.13746521e+03 1.14331995e+03 1.06472949e+03 1.00873871e+03 9.66450256e+02 9.09762329e+02 8.47761841e+02 8.01568970e+02 7.58654663e+02 7.09505371e+02 6.72114563e+02 6.05602966e+02 5.63850098e+02 5.51655762e+02 4.79985474e+02 4.15071960e+02 3.78746124e+02 3.31867615e+02 2.93146851e+02 2.41848801e+02 1.86430328e+02 1.44425018e+02 9.74315186e+01 4.75825462e+01 -1.35831428e+00 -4.98876495e+01 -9.71182632e+01 -1.43283432e+02 -1.90592484e+02 -2.32749252e+02 -2.86402832e+02 -3.52334930e+02 -3.94635132e+02 -4.27757172e+02 -4.59398071e+02 -5.13098206e+02 -5.96750854e+02 -6.40656860e+02 -6.67453491e+02 -7.00973083e+02 -7.43058289e+02 -8.11627075e+02 -8.62026550e+02 -9.25680542e+02 -9.62331055e+02 -9.83578430e+02 -1.03922363e+03 -1.08616650e+03 -1.16894092e+03 -1.21048010e+03 -1.22286035e+03 -1.27523901e+03 -1.32395264e+03 -1.36853784e+03 -1.37632178e+03 -1.46486572e+03 -1.60385608e+03 -1.60781274e+03 -1.60768628e+03 -1.61456006e+03 -1.64552515e+03 -1.79127759e+03 -1.85679114e+03 -1.84586951e+03 -1.83769202e+03 -1.87864795e+03 -1.98436853e+03 -2.02926318e+03 -2.12447510e+03 -2.17125342e+03 -2.16103662e+03 -2.14553882e+03 -2.17996338e+03 -2.35957568e+03 -2.39737598e+03 -2.37456494e+03 -2.38134741e+03 -2.40932275e+03 -2.59194800e+03 -2.65436377e+03 -2.54268115e+03 -2.57478296e+03 -2.76880640e+03 -2.81508960e+03 -2.71515698e+03 -2.75173071e+03 -2.94435254e+03 -3.00837964e+03 -2.94670630e+03 -2.91781128e+03 -2.96491821e+03 -3.17332275e+03 -3.18340942e+03 -3.11442651e+03 -3.21723853e+03 -3.25777881e+03 -3.27509497e+03 -3.32546118e+03 -3.36025415e+03 -3.32304761e+03 -3.44907959e+03 -3.63703149e+03 -3.59171460e+03 -3.64093652e+03 -3.69969751e+03 -3.67284180e+03 -3.71834473e+03 -3.74921216e+03 -3.77611938e+03 -3.74278125e+03 -3.77031934e+03 -3.89267285e+03 -3.95414258e+03 -4.10890625e+03 -4.02394385e+03 -3.92151489e+03 -4.08956421e+03 -4.16142334e+03 -4.32892871e+03 -4.31396631e+03 -4.22088477e+03 -4.21928027e+03 -4.23769922e+03 -4.36133936e+03 -4.41266504e+03 -4.52649219e+03 -4.56113574e+03 -4.49296582e+03 -4.50601709e+03 -4.39375830e+03 -4.56603955e+03 -4.86953857e+03 -4.83271484e+03 -4.73461572e+03 -4.63876709e+03 -4.60534619e+03 -4.87496045e+03 -5.05218408e+03 -4.97096338e+03 -4.80422852e+03 -4.83321875e+03 -4.98560547e+03 -5.00161865e+03 -5.16213428e+03 -5.17711475e+03 -5.07662646e+03 -5.08747021e+03 -5.12707129e+03 -5.34726270e+03 -5.38239258e+03 -5.14004346e+03 -5.14815820e+03 -5.45690283e+03 -5.45770654e+03 -5.20435889e+03 -5.32671533e+03 -5.65148291e+03 -5.64853711e+03 -5.52531543e+03 -5.39867432e+03 -5.40759375e+03 -5.73324121e+03 -5.78625342e+03 -5.64978467e+03 -5.54213818e+03 -5.53203516e+03 -5.71861670e+03 -5.79013574e+03 -5.76657275e+03 -5.64133545e+03 -5.82587061e+03 -6.07536523e+03 -5.93550977e+03 -6.02675293e+03 -6.00242627e+03 -5.89746387e+03 -5.97113623e+03 -5.99705322e+03 -6.03176660e+03 -6.03007812e+03 -5.94908252e+03 -5.86580713e+03 -6.06818701e+03 -6.42381250e+03 -6.11277100e+03 -5.89218066e+03 -6.12155762e+03 -6.32457764e+03 -6.47545068e+03 -6.38643701e+03 -6.21314551e+03 -6.36312109e+03 -6.39537988e+03 -6.23642627e+03 -6.16472119e+03 -6.42691455e+03 -6.48003027e+03 -6.33801123e+03 -6.32489111e+03 -6.16029932e+03 -6.43428076e+03 -6.83081934e+03 -6.66213428e+03 -6.45391260e+03 -6.35709619e+03 -6.26563623e+03 -6.62829443e+03 -6.89265479e+03 -6.70749463e+03 -6.46073730e+03 -6.46117822e+03 -6.54227148e+03 -6.53864990e+03 -6.78943164e+03 -6.69303955e+03 -6.53039160e+03 -6.61925439e+03 -6.59394238e+03 -6.86129199e+03 -6.83534521e+03 -6.62636035e+03 -6.67123145e+03 -6.68878809e+03 -6.73559131e+03 -6.61028320e+03 -6.61242725e+03 -6.91766943e+03 -6.92054492e+03 -6.79834521e+03 -6.57810742e+03 -6.63587793e+03 -7.04037695e+03 -7.00193994e+03 -6.79530859e+03 -6.68367188e+03 -6.64448340e+03 -6.73625098e+03 -6.77705420e+03 -6.83972168e+03 -6.66784619e+03 -6.79296582e+03 -7.08406982e+03 -6.80911865e+03 -6.95197363e+03 -7.03657471e+03 -6.87342334e+03 -6.84099072e+03 -6.80277246e+03 -6.85168555e+03 -6.83303564e+03 -6.76357910e+03 -6.77643994e+03 -6.94675635e+03 -7.00661670e+03 -6.64040186e+03 -6.57436719e+03 -6.74246094e+03 -6.90045996e+03 -7.10366504e+03 -6.92257275e+03 -6.62826709e+03 -6.84162354e+03 -6.93960889e+03 -6.82772412e+03 -6.77622998e+03 -6.75462891e+03 -6.69828857e+03 -6.67431836e+03 -6.81006006e+03 -6.64240186e+03 -6.69683057e+03 -7.01818799e+03 -6.88442285e+03 -6.75645898e+03 -6.59998486e+03 -6.60739111e+03 -6.93578223e+03 -6.83657812e+03 -6.72435889e+03 -6.54241064e+03 -6.35284277e+03 -6.55142773e+03 -6.77634766e+03 -6.98346191e+03 -6.70176172e+03 -6.45683447e+03 -6.53211426e+03 -6.57494727e+03 -6.80441846e+03 -6.73492871e+03 -6.50938477e+03 -6.47819287e+03 -6.44253223e+03 -6.48735742e+03 -6.38556494e+03 -6.44791016e+03 -6.71054492e+03 -6.56710596e+03 -6.48423096e+03 -6.29168701e+03 -6.23768994e+03 -6.58587939e+03 -6.57492627e+03 -6.37115283e+03 -6.20675488e+03 -6.14691455e+03 -6.25892920e+03 -6.28957129e+03 -6.48114746e+03 -6.44554199e+03 -6.19900049e+03 -6.04887891e+03 -6.10964258e+03 -6.39199316e+03 -6.31228760e+03 -6.12779297e+03 -6.07176172e+03 -6.01534473e+03 -5.99411523e+03 -5.93008496e+03 -6.06671387e+03 -6.02556689e+03 -5.86965039e+03 -6.06667969e+03 -6.10999707e+03 -5.96427441e+03 -5.90254785e+03 -5.84817188e+03 -5.84269824e+03 -5.66241064e+03 -5.57506738e+03 -5.86230371e+03 -5.89022314e+03 -5.56738379e+03 -5.42861475e+03 -5.65803662e+03 -5.85600391e+03 -5.75722949e+03 -5.49811719e+03 -5.35362695e+03 -5.55252588e+03 -5.61813721e+03 -5.46585059e+03 -5.45570459e+03 -5.28334277e+03 -5.04938965e+03 -5.23667871e+03 -5.53341943e+03 -5.50243359e+03 -5.16403857e+03 -4.97560938e+03 -5.25195020e+03 -5.39664307e+03 -5.17644922e+03 -4.97036768e+03 -4.89333350e+03 -4.92573730e+03 -4.95991748e+03 -5.10055273e+03 -5.06873438e+03 -4.87357031e+03 -4.76446045e+03 -4.73694531e+03 -4.90642529e+03 -4.76147070e+03 -4.58779688e+03 -4.76684229e+03 -4.73493164e+03 -4.62959766e+03 -4.49221729e+03 -4.43604492e+03 -4.64997314e+03 -4.47735498e+03 -4.27592822e+03 -4.36127441e+03 -4.41457520e+03 -4.38402832e+03 -4.27988379e+03 -4.35896143e+03 -4.34247021e+03 -4.18068896e+03 -4.02248022e+03 -3.95449585e+03 -4.17585400e+03 -4.07850464e+03 -3.91999829e+03 -3.92401758e+03 -3.86452393e+03 -3.88974170e+03 -3.83928223e+03 -3.83278442e+03 -3.76064453e+03 -3.62828369e+03 -3.72210669e+03 -3.70944238e+03 -3.60418555e+03 -3.56987646e+03 -3.52388403e+03 -3.43651172e+03 -3.30209277e+03 -3.24419434e+03 -3.38143555e+03 -3.47273779e+03 -3.25163184e+03 -3.05894287e+03 -3.14687451e+03 -3.24803101e+03 -3.17517993e+03 -3.00490527e+03 -2.88606055e+03 -2.99591748e+03 -2.97005933e+03 -2.82489185e+03 -2.89530518e+03 -2.83174878e+03 -2.63743530e+03 -2.63089624e+03 -2.73026953e+03 -2.70039771e+03 -2.52274463e+03 -2.40644434e+03 -2.48859766e+03 -2.54277490e+03 -2.43099854e+03 -2.28451660e+03 -2.20080811e+03 -2.27472656e+03 -2.26163208e+03 -2.14910107e+03 -2.11886743e+03 -2.08746436e+03 -2.01014514e+03 -1.94867078e+03 -1.97565466e+03 -1.89736279e+03 -1.79121216e+03 -1.80632031e+03 -1.77271313e+03 -1.73677417e+03 -1.64483411e+03 -1.56250867e+03 -1.58631995e+03 -1.50833484e+03 -1.42200012e+03 -1.42840857e+03 -1.42248682e+03 -1.41776282e+03 -1.33864368e+03 -1.33987390e+03 -1.19706958e+03 -1.45063208e+03 -1.08506689e+03 -1.22343298e+03 -1.31732874e+03 -8.77210205e+02 -1.72585999e+03 -2.75376245e+03 -3.23092500e+05 -126757328. 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. 54902536. 5.77535303e+03 1.39893103e+03 1.29662891e+03 1.20078003e+03 9.77478271e+02 1.05320691e+03 9.21328003e+02 1.01686713e+03 9.98769836e+02 1.03812439e+03 1.18900269e+03 1.01964142e+03 1.34355859e+03 1.65502649e+03 1.88091663e+03 1.47448511e+03 1.62273889e+03 1.43794141e+03 1.53108740e+03 1.61141785e+03 1.55676135e+03 1.63315796e+03 1.68496216e+03 1.67062878e+03 1.72256689e+03 1.82194873e+03 1.88606946e+03 1.93535828e+03 1.92434009e+03 1.93195703e+03 2.02085413e+03 2.08857324e+03 2.12090918e+03 2.13719482e+03 2.17057983e+03 2.28132202e+03 2.33549585e+03 2.33167261e+03 2.36132568e+03 2.40829956e+03 2.53073315e+03 2.59655273e+03 2.52615186e+03 2.55100854e+03 2.64797266e+03 2.69487402e+03 2.78621436e+03 2.81357300e+03 2.79139502e+03 2.88196289e+03 2.94403076e+03 2.96402783e+03 3.02256812e+03 3.01946631e+03 3.07815381e+03 3.15338794e+03 3.16002197e+03 3.19503320e+03 3.21947852e+03 3.28231982e+03 3.39757104e+03 3.43436841e+03 3.44796191e+03 3.43401538e+03 3.43986914e+03 3.58420850e+03 3.63238477e+03 3.57701514e+03 3.65681396e+03 3.71950122e+03 3.75860718e+03 3.86182544e+03 3.88304492e+03 3.82446411e+03 3.84638062e+03 4.00254272e+03 4.08595093e+03 4.00607104e+03 3.96528491e+03 4.04409644e+03 4.15043506e+03 4.27299072e+03 4.30006885e+03 4.18343262e+03 4.23896533e+03 4.40367920e+03 4.43211719e+03 4.44165283e+03 4.36222705e+03 4.37450684e+03 4.55959766e+03 4.63046729e+03 4.55346533e+03 4.58110742e+03 4.64615674e+03 4.68952686e+03 4.73826074e+03 4.74519287e+03 4.80113525e+03 4.85911133e+03 4.94620898e+03 4.97667725e+03 4.83676709e+03 4.88582275e+03 5.03622510e+03 5.03475635e+03 5.02138721e+03 5.04876416e+03 5.12325342e+03 5.24453516e+03 5.22518848e+03 5.17283203e+03 5.28639014e+03 5.36584033e+03 5.26662549e+03 5.28286230e+03 5.38258154e+03 5.42643066e+03 5.43386279e+03 5.40682324e+03 5.45794922e+03 5.50923975e+03 5.65210059e+03 5.66232861e+03 5.48767236e+03 5.56030176e+03 5.72913672e+03 5.76036377e+03 5.72493799e+03 5.67239795e+03 5.63833057e+03 5.79209375e+03 5.93864600e+03 5.87287256e+03 5.75530713e+03 5.82636084e+03 6.00277344e+03 6.05173877e+03 6.09532373e+03 5.95883154e+03 5.82049170e+03 5.97532324e+03 6.03615137e+03 6.04437646e+03 6.10349902e+03 6.05843506e+03 6.16199854e+03 6.36735742e+03 6.26107520e+03 6.02082910e+03 6.11191162e+03 6.27965234e+03 6.31233936e+03 6.40093164e+03 6.31599219e+03 6.23484277e+03 6.29158984e+03 6.47891943e+03 6.41383984e+03 6.18523828e+03 6.30919922e+03 6.51575977e+03 6.47212793e+03 6.40529736e+03 6.37770605e+03 6.40163428e+03 6.48845703e+03 6.49706689e+03 6.50501562e+03 6.61437891e+03 6.51547314e+03 6.55642432e+03 6.67943799e+03 6.62833691e+03 6.51737939e+03 6.53026172e+03 6.65553418e+03 6.76249365e+03 6.68441992e+03 6.57187744e+03 6.50631152e+03 6.66761523e+03 6.94386426e+03 6.96948389e+03 6.56118164e+03 6.62056348e+03 6.88914941e+03 6.80252686e+03 6.72055469e+03 6.68145654e+03 6.64592725e+03 6.81172949e+03 6.88071973e+03 6.74738330e+03 6.71326904e+03 6.69370703e+03 6.79091602e+03 6.94791602e+03 6.88882910e+03 6.77362891e+03 6.76751709e+03 6.88983789e+03 6.85203760e+03 6.78304102e+03 6.79055908e+03 6.85399756e+03 6.75120605e+03 6.95731787e+03 7.00886133e+03 6.66285254e+03 6.68787402e+03 6.88583887e+03 6.93168457e+03 6.90925098e+03 6.67982959e+03 6.77895850e+03 7.01174268e+03 6.92941943e+03 6.90966504e+03 6.72215283e+03 6.63752051e+03 6.85737061e+03 6.98605420e+03 6.89068213e+03 6.80943945e+03 6.85985400e+03 6.80368311e+03 6.93672754e+03 6.88683887e+03 6.70697949e+03 6.63149170e+03 6.71392773e+03 6.90971924e+03 6.82238281e+03 6.70675830e+03 6.70396680e+03 6.82219873e+03 6.85036914e+03 6.73792188e+03 6.70689307e+03 6.68678467e+03 6.75345605e+03 6.69268799e+03 6.78871045e+03 6.67667041e+03 6.57913525e+03 6.73735010e+03 6.54631836e+03 6.60129102e+03 6.72027002e+03 6.57852051e+03 6.51964600e+03 6.56279102e+03 6.59320557e+03 6.52030225e+03 6.39321582e+03 6.60998486e+03 6.77487256e+03 6.42487012e+03 6.34230225e+03 6.45112109e+03 6.44479443e+03 6.55477246e+03 6.47315527e+03 6.29106201e+03 6.34082275e+03 6.45527002e+03 6.45597852e+03 6.37248047e+03 6.27162549e+03 6.29467920e+03 6.31001709e+03 6.20675928e+03 6.19959375e+03 6.14130176e+03 6.12219531e+03 6.21656641e+03 6.21876025e+03 6.19808350e+03 6.06086523e+03 5.97912646e+03 6.13695264e+03 6.22608301e+03 5.97358447e+03 6.00566016e+03 6.01017920e+03 5.82756201e+03 5.93887988e+03 5.92600635e+03 5.79945557e+03 5.90410693e+03 5.86021191e+03 5.79290332e+03 5.91987402e+03 5.77407129e+03 5.64715283e+03 5.66176514e+03 5.70195166e+03 5.73741992e+03 5.55607178e+03 5.50344678e+03 5.58427246e+03 5.59404004e+03 5.56122900e+03 5.50256738e+03 5.38539746e+03 5.46144043e+03 5.59600879e+03 5.38542529e+03 5.26157520e+03 5.21414893e+03 5.33897998e+03 5.38399268e+03 5.16662305e+03 5.11727539e+03 5.13773047e+03 5.13307324e+03 5.08481689e+03 5.08137793e+03 5.03412842e+03 4.93390186e+03 5.00445459e+03 5.07035254e+03 4.90943408e+03 4.69357422e+03 4.74550830e+03 4.81365820e+03 4.77652490e+03 4.76419531e+03 4.69823193e+03 4.60102051e+03 4.68692334e+03 4.72609375e+03 4.54366162e+03 4.46552734e+03 4.44538184e+03 4.54225098e+03 4.48672656e+03 4.28076904e+03 4.23361182e+03 4.28241699e+03 4.30387988e+03 4.24409326e+03 4.22327783e+03 4.13953076e+03 4.09854053e+03 4.07458716e+03 3.96217310e+03 3.94876050e+03 3.89787134e+03 3.91186206e+03 3.93253003e+03 3.81425464e+03 3.71205225e+03 3.71314209e+03 3.74453198e+03 3.81162427e+03 3.73957544e+03 3.53883276e+03 3.48813672e+03 3.51602197e+03 3.47906982e+03 3.40336450e+03 3.35718384e+03 3.34019531e+03 3.32847070e+03 3.24461694e+03 3.13322998e+03 3.16188257e+03 3.18714160e+03 3155. 3.06115234e+03 2.94915234e+03 2.93873877e+03 2.87955005e+03 2.82521240e+03 2.88175806e+03 2.82646338e+03 2.68522510e+03 2.65511743e+03 2.65049219e+03 2.66178174e+03 2.61590747e+03 2.52336377e+03 2.46039404e+03 2.42326978e+03 2.37408594e+03 2.30528296e+03 2.29960571e+03 2.26245630e+03 2.23602075e+03 2.18725708e+03 2.05577466e+03 2.04033508e+03 2.02244385e+03 1.97911743e+03 1.97751978e+03 1.87594861e+03 1.80177148e+03 1.82302600e+03 1.78308789e+03 1.70015405e+03 1.64545386e+03 1.58910205e+03 1.53699683e+03 1.49957349e+03 1.46708484e+03 1.41485193e+03 1.39384814e+03 1.35914172e+03 1.28750806e+03 1.22384412e+03 1.16330273e+03 1.14294763e+03 1.11475354e+03 1.05708704e+03 9.81482971e+02 9.28891052e+02 9.01054565e+02 8.68204102e+02 8.37813049e+02 7.67666931e+02 7.00185669e+02 6.62407104e+02 6.15987671e+02 5.66510010e+02 5.33057312e+02 4.82594696e+02 4.20524567e+02 3.80249573e+02 3.32783691e+02 2.85742218e+02 2.40361374e+02 1.90696228e+02 1.41237183e+02 9.19952774e+01 4.49223938e+01 -1.25257814e+00 -4.84436073e+01 -9.89218140e+01 -1.48521576e+02 -1.97340912e+02 -2.38387360e+02 -2.87379578e+02 -3.37693634e+02 -3.81427246e+02 -4.35357239e+02 -4.83342926e+02 -5.22904602e+02 -5.71235840e+02 -6.21472595e+02 -6.84186584e+02 -7.34443054e+02 -7.60550781e+02 -8.05730408e+02 -8.50882751e+02 -8.96852966e+02 -9.51759705e+02 -1.00962970e+03 -1.06202014e+03 -1.09821448e+03 -1.13869763e+03 -1.17952063e+03 -1.23051794e+03 -1.31759619e+03 -1.35990222e+03 -1.36392700e+03 -1.41451343e+03 -1.46182788e+03 -1.50246729e+03 -1.58043140e+03 -1.64328210e+03 -1.65994873e+03 -1.69274426e+03 -1.73796448e+03 -1.78997571e+03 -1.86801721e+03 -1.90001001e+03 -1.94264990e+03 -1.99153687e+03 -2.01571558e+03 -2.08436816e+03 -2.09480347e+03 -2.15073218e+03 -2.26488354e+03 -2.25465820e+03 -2.27109595e+03 -2.34514990e+03 -2.36807495e+03 -2.40916211e+03 -2.55062500e+03 -2.60205981e+03 -2.51467139e+03 -2.56841699e+03 -2.65281665e+03 -2.67540503e+03 -2.78442554e+03 -2.81228857e+03 -2.77712646e+03 -2.85913574e+03 -2.91015991e+03 -2.99148462e+03 -3.07768311e+03 -3.05760815e+03 -3.11241211e+03 -3.12500439e+03 -3.08737793e+03 -3.17952539e+03 -3.30206250e+03 -3.32434717e+03 -3.38451172e+03 -3.41522974e+03 -3.31651440e+03 -3.42297827e+03 -3.60603784e+03 -3.63585059e+03 -3.58998486e+03 -3.52078857e+03 -3.61250488e+03 -3.79176782e+03 -3.79593311e+03 -3.78571436e+03 -3.88646777e+03 -3.85578882e+03 -3.90914453e+03 -3.98818970e+03 -3.88810962e+03 -3.97017822e+03 -4.13573877e+03 -4.18605566e+03 -4.16112744e+03 -4.06867310e+03 -4.14165430e+03 -4.28672168e+03 -4.37450635e+03 -4.37604736e+03 -4.32205127e+03 -4.31164600e+03 -4.40220898e+03 -4.53458447e+03 -4.64110205e+03 -4.59893066e+03 -4.53578027e+03 -4.60350928e+03 -4.63047607e+03 -4.67070410e+03 -4.75687988e+03 -4.75422754e+03 -4.80339795e+03 -4.91540137e+03 -4.86263672e+03 -4.86385303e+03 -4.95454834e+03 -4.99881104e+03 -5.05249707e+03 -5.02597803e+03 -4.95518408e+03 -5.04112256e+03 -5.17386768e+03 -5.25400195e+03 -5.33742285e+03 -5.22154980e+03 -5.11678613e+03 -5.25822949e+03 -5.27002100e+03 -5.35301123e+03 -5.45303662e+03 -5.35826074e+03 -5.35909668e+03 -5.39061133e+03 -5.44935205e+03 -5.59016895e+03 -5.69666211e+03 -5.63804834e+03 -5.60515625e+03 -5.59258203e+03 -5.50272754e+03 -5.62110205e+03 -5.75629102e+03 -5.84534473e+03 -5.84423438e+03 -5.71728125e+03 -5.69294287e+03 -5.82958398e+03 -5.90825488e+03 -5.92986914e+03 -5.91116602e+03 -5.89375879e+03 -5.85302490e+03 -5.99825439e+03 -6.15629346e+03 -6.07347412e+03 -5.95295557e+03 -6.03680322e+03 -6.09984863e+03 -6.14817041e+03 -6.20767578e+03 -6.18069434e+03 -6.24428467e+03 -6.17708838e+03 -6.15661523e+03 -6.33644678e+03 -6.31004785e+03 -6.25019922e+03 -6.42474365e+03 -6.27862695e+03 -6.21063281e+03 -6.44950781e+03 -6.40650781e+03 -6.14665039e+03 -6.89552979e+03 -6.86129199e+03 -5.86867041e+03 -5.44528027e+03 -8.34679004e+03 -1.07721396e+04 -1.72547402e+04 -1.90573281e+04 2.99202775e+06 -4489850. 3.35797025e+06 -72840128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.98316650e+06 -20910288. -3.10481680e+04 -1.95688477e+04 -1.17609004e+04 -1.10829346e+04 -1.00452959e+04 -9.38457520e+03 -9.67686621e+03 -5.47241602e+03 -6.16661182e+03 -8.13636719e+03 -6.79181641e+03 -6.28763037e+03 -5.92965283e+03 -6.47035742e+03 -7.04144141e+03 -6.96020850e+03 -6.68844238e+03 -6.70661328e+03 -6.85926074e+03 -6.86912207e+03 -6.91835645e+03 -6.94887842e+03 -6.73916748e+03 -6.65344629e+03 -6.70035547e+03 -6.68749707e+03 -6.78173193e+03 -6.64497754e+03 -6.55072656e+03 -6.74478809e+03 -6.94938867e+03 -6.76719189e+03 -6.42371973e+03 -6.45697852e+03 -6.69893994e+03 -6.76989014e+03 -6.57045605e+03 -6.40378027e+03 -6.45547852e+03 -6.70322998e+03 -6.81280957e+03 -6.62672510e+03 -6.31893945e+03 -6.34120215e+03 -6.61709375e+03 -6.55437451e+03 -6.57980078e+03 -6.47277002e+03 -6.22614893e+03 -6.33052832e+03 -6.52945605e+03 -6.38254346e+03 -6.26709277e+03 -6.44707227e+03 -6.46034619e+03 -6.34157520e+03 -6.22581299e+03 -6.07554883e+03 -6.22019971e+03 -6.44220166e+03 -6.28661426e+03 -6.10374854e+03 -6.03056836e+03 -5.99051025e+03 -6.26813525e+03 -6.38295654e+03 -6.13687500e+03 -6.00319727e+03 -5.94517432e+03 -5.87049121e+03 -6.00088428e+03 -6.19104785e+03 -5.93951416e+03 -5.80330518e+03 -5.95616650e+03 -5.89241943e+03 -5.75677637e+03 -5.76359131e+03 -5.81635693e+03 -5.88532861e+03 -5.84406738e+03 -5.79707764e+03 -5.57985645e+03 -5.49590283e+03 -5.75184326e+03 -5.84637109e+03 -5.52855273e+03 -5.33828613e+03 -5.45298926e+03 -5.56058154e+03 -5.62299414e+03 -5.63877881e+03 -5.38604834e+03 -5.27843604e+03 -5.38489404e+03 -5.36043408e+03 -5.37577002e+03 -5.27871777e+03 -5.11959814e+03 -5.14334033e+03 -5.23259375e+03 -5.21648486e+03 -5.14669092e+03 -5.11473047e+03 -5.06899658e+03 -5.05512305e+03 -5.04707520e+03 -4.85317480e+03 -4.80286719e+03 -5.04260840e+03 -5.00792725e+03 -4.72552637e+03 -4.62534717e+03 -4.66099658e+03 -4.84413135e+03 -4.93436328e+03 -4.71252686e+03 -4.49022705e+03 -4.46032861e+03 -4.50258936e+03 -4.52814502e+03 -4.51989990e+03 -4.45360303e+03 -4.40054443e+03 -4.35199170e+03 -4.31888916e+03 -4.30830859e+03 -4.19213184e+03 -4.20480371e+03 -4.30241797e+03 -4.18282227e+03 -4.08957739e+03 -4.02123633e+03 -3.92403760e+03 -4.02748340e+03 -4.10234473e+03 -3.87420215e+03 -3.74508643e+03 -3.79115308e+03 -3.88392139e+03 -3.89500684e+03 -3.74781934e+03 -3.60573584e+03 -3.55614380e+03 -3.55729517e+03 -3.58713770e+03 -3.59494849e+03 -3.42290894e+03 -3.29950806e+03 -3.37530127e+03 -3.44361377e+03 -3.35698438e+03 -3.24843359e+03 -3.20109448e+03 -3.15272119e+03 -3.16076685e+03 -3.13487744e+03 -2.98426318e+03 -2.94115674e+03 -2.99449194e+03 -2.95942017e+03 -2.87291992e+03 -2.77757495e+03 -2.76174707e+03 -2.76031616e+03 -2.72165698e+03 -2.69099146e+03 -2.58803394e+03 -2.54861328e+03 -2.55510645e+03 -2.48166602e+03 -2.42760913e+03 -2.35778857e+03 -2.31145312e+03 -2.31843164e+03 -2.32664526e+03 -2.25325562e+03 -2.10440186e+03 -2.04807642e+03 -2.09344385e+03 -2.10143530e+03 -2.01406592e+03 -1.89602771e+03 -1.83171558e+03 -1.82909033e+03 -1.82040039e+03 -1.78507410e+03 -1.69093884e+03 -1.61370569e+03 -1.59512170e+03 -1.58151868e+03 -1.54534802e+03 -1.47675793e+03 -1.40866882e+03 -1.37006873e+03 -1.33330566e+03 -1.28749304e+03 -1.24104602e+03 -1.18989648e+03 -1.14133716e+03 -1.08669580e+03 -1.02234271e+03 -9.71767761e+02 -9.61210632e+02 -9.48042664e+02 -8.88022766e+02 -8.04963013e+02 -7.30347290e+02 -6.93148621e+02 -6.85607178e+02 -6.54744629e+02 -5.86322571e+02 -5.13250427e+02 -4.56382202e+02 -4.23099609e+02 -3.90536591e+02 -3.43815735e+02 -2.91141174e+02 -2.37020554e+02 -1.89463562e+02 -1.41869476e+02 -9.14936142e+01 -4.48239365e+01 2.38152027e+00 5.02643356e+01 1.01089050e+02 1.47473373e+02 1.83173218e+02 2.34344131e+02 2.92458527e+02 3.40849152e+02 3.87608826e+02 4.31019684e+02 4.90918488e+02 5.41148560e+02 5.63749939e+02 5.91141785e+02 6.51854492e+02 7.34829956e+02 8.05508301e+02 8.41477844e+02 8.42535950e+02 8.61658508e+02 9.29027893e+02 1.02308673e+03 1.10001624e+03 1.13142749e+03 1.11362939e+03 1.15622949e+03 1.27800183e+03 1.32075305e+03 1.30680688e+03 1.35368115e+03 1.41472656e+03 1.46260205e+03 1.56705688e+03 1.57810889e+03 1.56230920e+03 1.65007739e+03 1.66764929e+03 1.75502551e+03 1.84968970e+03 1.80235620e+03 1.87672363e+03 1.98024573e+03 1.98436731e+03 2.03541443e+03 2.06844629e+03 2.11239209e+03 2.19079883e+03 2.21266260e+03 2.18816797e+03 2.23419238e+03 2.40175781e+03 2.51535864e+03 2.49047388e+03 2.42859546e+03 2.41732422e+03 2.50617847e+03 2.66449121e+03 2.78852246e+03 2.75873950e+03 2.66577930e+03 2.73795532e+03 2.87136230e+03 2.87289380e+03 2.89485596e+03 2.94916406e+03 2.99086011e+03 3.04590356e+03 3.19470557e+03 3.15417773e+03 3.08539624e+03 3.21152344e+03 3.16279321e+03 3.32099072e+03 3.44607202e+03 3.35903076e+03 3.53479614e+03 3.51551685e+03 3.37309961e+03 3.51473560e+03 3.51892969e+03 3.61609839e+03 3.90145020e+03 3.74329468e+03 3.57072217e+03 3.69161621e+03 3.90015625e+03 4.09196973e+03 4.04586743e+03 3.87146582e+03 3.81361304e+03 3.91001099e+03 4.10906348e+03 4.29488086e+03 4.28710205e+03 4.11886572e+03 4.10219141e+03 4.26454834e+03 4.35352002e+03 4.30244824e+03 4.33366553e+03 4.37936963e+03 4.40918408e+03 4.62315088e+03 4.65957910e+03 4.44795605e+03 4.46619385e+03 4.58332422e+03 4.63964209e+03 4.71329346e+03 4.72929053e+03 4.89372510e+03 4.81422314e+03 4.66241113e+03 4.84955859e+03 4.75932422e+03 4.89984668e+03 5.31029541e+03 5.02898145e+03 4.71745898e+03 4.91668457e+03 5.19201172e+03 5.33790723e+03 5.40169043e+03 5.11219531e+03 4.92157520e+03 5.09069287e+03 5.41082129e+03 5.61831152e+03 5.50176953e+03 5.20319629e+03 5.19038086e+03 5.39691895e+03 5.51786475e+03 5.70211182e+03 5.71535791e+03 5.40675879e+03 5.41837695e+03 5.65218945e+03 5.75992285e+03 5.63429004e+03 5.59449561e+03 5.67666650e+03 5.65951855e+03 5.89417676e+03 5.95750586e+03 5.72841602e+03 5.74028662e+03 5.79236279e+03 5.82388672e+03 5.93620508e+03 5.91135986e+03 6.05065283e+03 6.15166406e+03 5.97517529e+03 5.89382227e+03 5.79606250e+03 6.06073633e+03 6.39003906e+03 6.30728223e+03 6.01396387e+03 5.86852979e+03 6.09577686e+03 6.44954102e+03 6.28425830e+03 5.93163135e+03 6.15041162e+03 6.34351318e+03 6.44957715e+03 6.62858105e+03 6.55253418e+03 6.18747070e+03 6.08039795e+03 6.29153369e+03 6.53162354e+03 6.53280176e+03 6.43933984e+03 6.43959912e+03 6.43868994e+03 6.60864453e+03 6.53726709e+03 6.37123730e+03 6.43213379e+03 6.42226514e+03 6.62106543e+03 6.81038867e+03 6.59370410e+03 6.63514258e+03 6.68321094e+03 6.65057080e+03 6.52011768e+03 6.35998584e+03 6.69655908e+03 7.04379980e+03 6.81606104e+03 6.47536426e+03 6.53888477e+03 6.89913916e+03 6.99421826e+03 6.84052686e+03 6.77212109e+03 6.53431543e+03 6.52957910e+03 6.89856396e+03 6.92383643e+03 6.76180225e+03 6.59832227e+03 6.53259619e+03 6.85077393e+03 7.17848682e+03 6.83532324e+03 6.65739404e+03 6.77338379e+03 6.78678906e+03 7.01506104e+03 7.06664014e+03 6.66382666e+03 6.58570166e+03 6.82232275e+03 6.82206787e+03 6.91431934e+03 6.87320654e+03 7.17588770e+03 7.03214990e+03 6.76355762e+03 6.64563574e+03 6.45707666e+03 6.94839648e+03 7.47289307e+03 7.22611963e+03 6.48199121e+03 7.19500146e+03 9.96975977e+03 1.11256670e+04 2.42268594e+04 -1.25274312e+06 -2.09654575e+06 -43805204. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38534712. 1.26827328e+05 1.80338301e+04 9.90223438e+03 1.07459443e+04 9.75377051e+03 9.56627344e+03 9.36455859e+03 9.13654492e+03 9.59218066e+03 9.68557910e+03 9.35041602e+03 9.45826562e+03 9.44455273e+03 9.30077832e+03 9.32455859e+03 9.31651465e+03 9.20009668e+03 6.66484668e+03 7.31726709e+03 6.55314600e+03 6.03280078e+03 5.95353662e+03 6.06469531e+03 6.10502051e+03 5.82255615e+03 5.81009668e+03 6.04974902e+03 6.06965771e+03 5.88946631e+03 5.83907324e+03 5.79890186e+03 5.76999268e+03 5.75967334e+03 5.72113428e+03 5.69890283e+03 5.66762549e+03 5.52131152e+03 5.49752148e+03 5.72592676e+03 5.72232422e+03 5.51726465e+03 5.49883887e+03 5.49208936e+03 5.46538379e+03 5.41742383e+03 5.37408545e+03 5.36772852e+03 5.27965674e+03 5.20512842e+03 5.21999023e+03 5.18537402e+03 5.34265381e+03 5.35639258e+03 5.14646777e+03 4.98123535e+03 4.91770947e+03 5.18275488e+03 5.20073291e+03 4.98473584e+03 4.86139990e+03 4.85972607e+03 4.89426074e+03 4.81522119e+03 4.91451904e+03 4.91061670e+03 4.61023535e+03 4.51708252e+03 4.72121191e+03 4.88282861e+03 4.71544385e+03 4.56312500e+03 4.54245605e+03 4.47842871e+03 4.44654785e+03 4.42532959e+03 4.42089258e+03 4.37463428e+03 4.29111377e+03 4.25399707e+03 4.22677930e+03 4.17300635e+03 4.28003662e+03 4.22287549e+03 4.05468530e+03 4.04042993e+03 3.97942432e+03 4.06480908e+03 4.05481665e+03 3.90567725e+03 3.85927148e+03 3.76196582e+03 3.66794971e+03 3.78962231e+03 3.74212476e+03 3.50485889e+03 3.52167432e+03 3.68623291e+03 3.75722925e+03 3.61111523e+03 3.46405103e+03 3.37843140e+03 3.33743823e+03 3.33051880e+03 3.27525513e+03 3.24052539e+03 3.18942651e+03 3.23104907e+03 3.18858252e+03 3.05643652e+03 3.02257544e+03 2.89736792e+03 2.92874634e+03 3.06280347e+03 2.95237524e+03 2.83666406e+03 2.71787939e+03 2.65036597e+03 2.76479028e+03 2.73990601e+03 2.61383496e+03 2.49612378e+03 2.44931689e+03 2.46616553e+03 2.41519312e+03 2.45352319e+03 2.42519263e+03 2.29823389e+03 2.23135620e+03 2.18732227e+03 2.18210718e+03 2.14841992e+03 2.07323169e+03 1.99372302e+03 1.95679126e+03 1.92302710e+03 1.81725171e+03 1.81003674e+03 1.88082593e+03 1.80351758e+03 1.70312561e+03 1.61515112e+03 1.56279370e+03 1.60986780e+03 1.56483459e+03 1.47109644e+03 1.38775879e+03 1.33321448e+03 1.33455457e+03 1.28491882e+03 1.23196265e+03 1.15879700e+03 1.13674011e+03 1.14193311e+03 1.06441565e+03 1.00692542e+03 9.64705933e+02 9.11687744e+02 8.49652893e+02 8.00095337e+02 7.55945618e+02 7.06156372e+02 6.67385315e+02 6.01752319e+02 5.61452942e+02 5.50747803e+02 4.79482361e+02 4.14827332e+02 3.79351746e+02 3.32261505e+02 2.93236572e+02 2.41994965e+02 1.86690399e+02 1.45081085e+02 9.71383438e+01 4.72226982e+01 1.71599776e-01 -4.66206589e+01 -9.34848709e+01 -1.41209396e+02 -1.90386444e+02 -2.33240967e+02 -2.87343109e+02 -3.53011505e+02 -3.94798676e+02 -4.28257568e+02 -4.60825623e+02 -5.15265686e+02 -5.96976013e+02 -6.40614685e+02 -6.68542053e+02 -7.01099426e+02 -7.44134155e+02 -8.12697266e+02 -8.63121887e+02 -9.27815247e+02 -9.63320740e+02 -9.83299011e+02 -1.04002124e+03 -1.08613550e+03 -1.17074182e+03 -1.21195410e+03 -1.22223059e+03 -1.27432800e+03 -1.32382263e+03 -1.36937195e+03 -1.37736633e+03 -1.46690259e+03 -1.60714758e+03 -1.60984851e+03 -1.60926855e+03 -1.61574316e+03 -1.64683057e+03 -1.79483691e+03 -1.85940027e+03 -1.84870398e+03 -1.83675415e+03 -1.88047046e+03 -1.98925757e+03 -2.03050037e+03 -2.12819849e+03 -2.17342310e+03 -2.16251758e+03 -2.14963159e+03 -2.18296924e+03 -2.35886084e+03 -2.39571289e+03 -2.37509644e+03 -2.38703418e+03 -2.41465479e+03 -2.59291211e+03 -2.65434302e+03 -2.54339868e+03 -2.57614331e+03 -2.77220410e+03 -2.82133643e+03 -2.71466772e+03 -2.75071802e+03 -2.94847632e+03 -3.01175659e+03 -2.94610107e+03 -2.91942749e+03 -2.97017017e+03 -3.17724854e+03 -3.19064624e+03 -3.11607178e+03 -3.21490015e+03 -3.25948315e+03 -3.28261548e+03 -3.32609766e+03 -3.36732568e+03 -3.32736230e+03 -3.45836255e+03 -3.63742358e+03 -3.58227881e+03 -3.65585181e+03 -3.70364868e+03 -3.67304810e+03 -3.72078296e+03 -3.74426147e+03 -3.77671899e+03 -3.74033862e+03 -3.76307422e+03 -3.89755127e+03 -3.95767310e+03 -4.10705713e+03 -4.02343872e+03 -3.92604663e+03 -4.08953662e+03 -4.17344775e+03 -4.32371729e+03 -4.33414209e+03 -4.22364795e+03 -4.22073096e+03 -4.23035791e+03 -4.36905127e+03 -4.41916504e+03 -4.54555078e+03 -4.55360693e+03 -4.49239941e+03 -4.50955908e+03 -4.40686572e+03 -4.57241504e+03 -4.86962354e+03 -4.83698633e+03 -4.74045850e+03 -4.63481299e+03 -4.61338428e+03 -4.87826660e+03 -5.05006934e+03 -4.96777246e+03 -4.79925830e+03 -4.83260449e+03 -5.00785889e+03 -5.00699951e+03 -5.16843408e+03 -5.18811621e+03 -5.06804834e+03 -5.09309668e+03 -5.12580713e+03 -5.35254883e+03 -5.40147119e+03 -5.13863721e+03 -5.16444971e+03 -5.48337109e+03 -5.45985107e+03 -5.20831006e+03 -5.33423877e+03 -5.64886523e+03 -5.65733398e+03 -5.55057178e+03 -5.42050146e+03 -5.42276758e+03 -5.74788867e+03 -5.78999854e+03 -5.66693115e+03 -5.56067676e+03 -5.52055811e+03 -5.72333740e+03 -5.79701025e+03 -5.78495410e+03 -5.63655469e+03 -5.82276562e+03 -6.08663232e+03 -5.92443164e+03 -6.02439697e+03 -6.00517578e+03 -5.90558398e+03 -5.98710205e+03 -6.01038623e+03 -6.03295508e+03 -6.02324023e+03 -5.96692041e+03 -5.86596680e+03 -6.08484863e+03 -6.42444434e+03 -6.12232373e+03 -5.89524463e+03 -6.13550439e+03 -6.33265625e+03 -6.49299365e+03 -6.36100732e+03 -6.22395947e+03 -6.38762891e+03 -6.40910449e+03 -6.23895898e+03 -6.16383643e+03 -6.43970508e+03 -6.45766553e+03 -6.34090381e+03 -6.32360693e+03 -6.15044287e+03 -6.39314990e+03 -6.83930420e+03 -6.66067334e+03 -6.47751660e+03 -6.36856006e+03 -6.25480469e+03 -6.64165967e+03 -6.90480566e+03 -6.68274512e+03 -6.46936523e+03 -6.44268408e+03 -6.56128564e+03 -6.57718848e+03 -6.81491016e+03 -6.72536572e+03 -6.54231982e+03 -6.61064062e+03 -6.61867871e+03 -6.87899512e+03 -6.85473828e+03 -6.63644824e+03 -6.67450293e+03 -6.68483691e+03 -6.77130273e+03 -6.59424023e+03 -6.62613184e+03 -6.91332129e+03 -6.90530811e+03 -6.82753418e+03 -6.61072656e+03 -6.64436279e+03 -7.08110889e+03 -6.96893457e+03 -6.81706885e+03 -6.68865625e+03 -6.63330469e+03 -6.75425195e+03 -6.80484326e+03 -6.86580225e+03 -6.67508350e+03 -6.80042041e+03 -7.08992627e+03 -6.80259326e+03 -6.99445312e+03 -7.05785742e+03 -6.87940967e+03 -6.86463086e+03 -6.80064014e+03 -6.83662891e+03 -6.85546582e+03 -6.76718311e+03 -6.79066943e+03 -6.98526660e+03 -6.98160254e+03 -6.64284814e+03 -6.57720459e+03 -6.77228320e+03 -6.91895557e+03 -7.17858350e+03 -6.95964844e+03 -6.64955371e+03 -6.85624121e+03 -6.98273682e+03 -6.86530029e+03 -6.75444336e+03 -6.76873535e+03 -6.70643896e+03 -6.70017383e+03 -6.84603320e+03 -6.66249658e+03 -6.72583838e+03 -7.01136621e+03 -6.87030469e+03 -6.75830127e+03 -6.61717139e+03 -6.62186279e+03 -6.94696826e+03 -6.87967578e+03 -6.74174365e+03 -6.53411475e+03 -6.37387500e+03 -6.56405420e+03 -6.76175244e+03 -6.96872754e+03 -6.73110791e+03 -6.47974316e+03 -6.53891309e+03 -6.55151074e+03 -6.81568408e+03 -6.72253760e+03 -6.51671484e+03 -6.48493945e+03 -6.46598486e+03 -6.49589355e+03 -6.37279639e+03 -6.46724609e+03 -6.71788623e+03 -6.59085107e+03 -6.46001758e+03 -6.33996045e+03 -6.28041846e+03 -6.60244922e+03 -6.58128613e+03 -6.35181885e+03 -6.19174609e+03 -6.13556348e+03 -6.30253467e+03 -6.27380908e+03 -6.48170605e+03 -6.47764111e+03 -6.22129492e+03 -6.04640039e+03 -6.13406592e+03 -6.38418945e+03 -6.29734131e+03 -6.11665723e+03 -6.06090186e+03 -6.02300342e+03 -5.99095557e+03 -5.92584619e+03 -6.05782080e+03 -6.02595459e+03 -5.88680078e+03 -6.06702539e+03 -6.10302441e+03 -5.96961328e+03 -5.89181787e+03 -5.85740869e+03 -5.82963184e+03 -5.66293750e+03 -5.59508154e+03 -5.84864453e+03 -5.88670605e+03 -5.59416943e+03 -5.42908057e+03 -5.66163135e+03 -5.86498975e+03 -5.75606445e+03 -5.50858008e+03 -5.35755469e+03 -5.55995703e+03 -5.60908447e+03 -5.46668066e+03 -5.47799512e+03 -5.28131982e+03 -5.05847852e+03 -5.24753320e+03 -5.54272559e+03 -5.50019873e+03 -5.18451611e+03 -4.97552295e+03 -5.25748193e+03 -5.40082959e+03 -5.17317822e+03 -4.98069629e+03 -4.89456348e+03 -4.92537500e+03 -4.96301367e+03 -5.09823242e+03 -5.07686377e+03 -4.87965674e+03 -4.78329541e+03 -4.75031396e+03 -4.91400586e+03 -4.77467285e+03 -4.59071338e+03 -4.77103662e+03 -4.74031201e+03 -4.62686426e+03 -4.51108545e+03 -4.44788477e+03 -4.65028174e+03 -4.48640479e+03 -4.27408838e+03 -4.36437354e+03 -4.42425098e+03 -4.38335840e+03 -4.28130762e+03 -4.36878125e+03 -4.35305908e+03 -4.18396777e+03 -4.01575806e+03 -3.96364673e+03 -4.17509668e+03 -4.08517334e+03 -3.92113452e+03 -3.92336377e+03 -3.86332788e+03 -3.89147852e+03 -3.84856616e+03 -3.83400171e+03 -3.75641113e+03 -3.64202539e+03 -3.72228564e+03 -3.70343457e+03 -3.60056982e+03 -3.57731592e+03 -3.53039844e+03 -3.43226050e+03 -3.30059912e+03 -3.24212329e+03 -3.38118872e+03 -3.48656470e+03 -3.26061963e+03 -3.06809595e+03 -3.15662280e+03 -3.24736621e+03 -3.17344873e+03 -3.01074170e+03 -2.89779395e+03 -2.99847559e+03 -2.96426880e+03 -2.82091724e+03 -2.90099219e+03 -2.83624561e+03 -2.64308130e+03 -2.63329077e+03 -2.72969263e+03 -2.70587817e+03 -2.52837427e+03 -2.40727173e+03 -2.48914502e+03 -2.54515356e+03 -2.43179370e+03 -2.28266064e+03 -2.20472778e+03 -2.27648535e+03 -2.26175293e+03 -2.15111426e+03 -2.11899170e+03 -2.08760718e+03 -2.01306104e+03 -1.94956433e+03 -1.97778857e+03 -1.89982507e+03 -1.79272925e+03 -1.80740027e+03 -1.77176917e+03 -1.73742798e+03 -1.65327869e+03 -1.56700732e+03 -1.58286853e+03 -1.50560840e+03 -1.42508972e+03 -1.43790906e+03 -1.41615576e+03 -1.38804529e+03 -1.29742114e+03 -1.32589014e+03 -1.18043005e+03 -1.40800195e+03 -1.08200244e+03 -1.42084143e+03 -1.55578125e+03 -1.40623047e+03 -2.02842651e+03 -2.16301074e+03 -3.23092500e+05 -126757328. 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. 234322608. 9.33574316e+03 2.06560791e+03 1.49982385e+03 1.37853308e+03 1.22677234e+03 1.20719531e+03 9.25578674e+02 9.89085571e+02 9.85333008e+02 1.04218604e+03 1.18954236e+03 1.01832745e+03 1.35273047e+03 1.66649878e+03 1.94491528e+03 1.80497168e+03 1.82594299e+03 1.44652673e+03 1.52592590e+03 1.63302661e+03 1.61372949e+03 1.66060510e+03 1.66654700e+03 1.66217065e+03 1.74569043e+03 1.84873328e+03 1.86571606e+03 1.90398193e+03 1.93114075e+03 1.96656543e+03 2.07225830e+03 2.07626587e+03 2.05899194e+03 2.13364868e+03 2.17937573e+03 2.26692065e+03 2.33659326e+03 2.30814966e+03 2.35763867e+03 2.47893945e+03 2.62359839e+03 2.61029785e+03 2.47719531e+03 2.50667871e+03 2.62439478e+03 2.72337549e+03 2.81613892e+03 2.82609424e+03 2.78616382e+03 2.90038086e+03 2.98062817e+03 2.92956372e+03 2.94902661e+03 2.99649414e+03 3.14214331e+03 3.28280493e+03 3.16825806e+03 3.10045850e+03 3.21820776e+03 3.34655200e+03 3.44461792e+03 3.41385156e+03 3.38162036e+03 3.39744531e+03 3.50996362e+03 3.71629858e+03 3.65142822e+03 3.49990918e+03 3.62759131e+03 3.75223828e+03 3.78227197e+03 3.85429004e+03 3.83589941e+03 3.78717310e+03 3.91188818e+03 4.05349561e+03 4.01577954e+03 3.98037671e+03 3.98618311e+03 4.05386108e+03 4.21955664e+03 4.34764795e+03 4.26175439e+03 4.14975635e+03 4.27065674e+03 4.42599170e+03 4.37208545e+03 4.35280566e+03 4.40045312e+03 4.49912354e+03 4.69276416e+03 4.64522852e+03 4.48230957e+03 4.49945654e+03 4.58309180e+03 4.72228369e+03 4.80312061e+03 4.75620508e+03 4.77758154e+03 4.92024414e+03 5.09265820e+03 5.01202734e+03 4.77568262e+03 4.82511865e+03 5.04196338e+03 5.09335059e+03 5.09922412e+03 5.06438037e+03 5.06864160e+03 5.24682275e+03 5.27950928e+03 5.16363330e+03 5.22835059e+03 5.29429980e+03 5.30063721e+03 5.44680957e+03 5.45618945e+03 5.35243506e+03 5.38333105e+03 5.41386768e+03 5.45559912e+03 5.61088330e+03 5.76231836e+03 5.61898242e+03 5.43570166e+03 5.62695703e+03 5.82498584e+03 5.72523535e+03 5.63138818e+03 5.63865527e+03 5.69308008e+03 5.89762891e+03 5.96189160e+03 5.77433057e+03 5.75453320e+03 5.86642236e+03 6.00114258e+03 6.04721289e+03 5.99958643e+03 5.96427637e+03 6.02644434e+03 6.15383301e+03 6.01379443e+03 5.91575000e+03 6.03350000e+03 6.11937842e+03 6.22827637e+03 6.35791553e+03 6.25397900e+03 6.04300439e+03 6.19334619e+03 6.39755957e+03 6.30530664e+03 6.28786377e+03 6.17936768e+03 6.19196045e+03 6.50804883e+03 6.57295166e+03 6.29792090e+03 6.20009082e+03 6.42160400e+03 6.62312695e+03 6.42437305e+03 6.28450732e+03 6.35888379e+03 6.59271973e+03 6.71282666e+03 6.49998486e+03 6.40018604e+03 6.48850830e+03 6.48483545e+03 6.59753174e+03 6.67059863e+03 6.56181201e+03 6.62571875e+03 6.72143750e+03 6.73155371e+03 6.65373877e+03 6.55970898e+03 6.57078027e+03 6.58638135e+03 6.69413672e+03 7.03786523e+03 6.96670117e+03 6.53009521e+03 6.70169727e+03 6.94295850e+03 6.72315186e+03 6.56073145e+03 6.62406787e+03 6.72539746e+03 7.01811426e+03 6.94174170e+03 6.64473633e+03 6.64221289e+03 6.69857715e+03 6.85492773e+03 6.90870850e+03 6.81381982e+03 6.76212207e+03 6.96977881e+03 7.04521777e+03 6.79790967e+03 6.69722461e+03 6.76051758e+03 6.78175391e+03 6.86360547e+03 7.02520654e+03 7.06183545e+03 6.71088525e+03 6.74905908e+03 6.92352197e+03 6.86236133e+03 6.85126660e+03 6.73716309e+03 6.84202246e+03 7.03312256e+03 6.99147266e+03 6.80889209e+03 6.73481592e+03 6.76224854e+03 6.79815283e+03 6.90442285e+03 6.80487158e+03 6.83421191e+03 6.90320801e+03 6.92711426e+03 7.01902295e+03 6.75646338e+03 6.64073047e+03 6.79211621e+03 6.79076221e+03 6.92256543e+03 6.87249609e+03 6.56329346e+03 6.75697363e+03 6.97038135e+03 6.74088623e+03 6.64779150e+03 6.72879443e+03 6.77187354e+03 6.77743311e+03 6.63324170e+03 6.82446533e+03 6.80873145e+03 6.60537500e+03 6.69745703e+03 6.55584619e+03 6.65316211e+03 6.80050000e+03 6.52239844e+03 6.55234082e+03 6.68096436e+03 6.58719238e+03 6.43252734e+03 6.40275000e+03 6.68119482e+03 6.80118750e+03 6.39744482e+03 6.33091260e+03 6.55347461e+03 6.50479346e+03 6.53947266e+03 6.32460059e+03 6.26941553e+03 6.43126221e+03 6.54873975e+03 6.45065186e+03 6.28903467e+03 6.25911230e+03 6.32475244e+03 6.42080078e+03 6.19589453e+03 6.10087402e+03 6.12733643e+03 6.08907910e+03 6.23650586e+03 6.38433203e+03 6.24360010e+03 5.99311230e+03 5.94560059e+03 6.18519922e+03 6.26833105e+03 5.93485205e+03 6.00412988e+03 6.17832910e+03 5.88866699e+03 5.87728076e+03 5.81066455e+03 5.83480713e+03 6.04720947e+03 5.91626270e+03 5.71566455e+03 5.87577344e+03 5.84230078e+03 5.64711816e+03 5.71078564e+03 5.74963037e+03 5.71475928e+03 5.52968750e+03 5.46500195e+03 5.62453564e+03 5.68022559e+03 5.56194434e+03 5.41750195e+03 5.37603857e+03 5.51716113e+03 5.55548779e+03 5.29988232e+03 5.25969824e+03 5.28370068e+03 5.37465820e+03 5.35002930e+03 5.13243213e+03 5.12042090e+03 5.24452148e+03 5.22624756e+03 5.06955664e+03 5.08621729e+03 5.07717480e+03 4.94978809e+03 5.08691943e+03 5.11894873e+03 4.85820459e+03 4.67527100e+03 4.76007910e+03 4.82379346e+03 4.80052881e+03 4.75470410e+03 4.64069922e+03 4.60151660e+03 4.72323438e+03 4.72075098e+03 4.48910498e+03 4.44087793e+03 4.52241016e+03 4.60079492e+03 4.46259033e+03 4.27979053e+03 4.31721777e+03 4.30660205e+03 4.27147705e+03 4.22312207e+03 4.22275195e+03 4.15976123e+03 4.05445947e+03 4.07512231e+03 4.07740918e+03 4.00845557e+03 3.87403662e+03 3.84914380e+03 3.90197070e+03 3.86345264e+03 3.77364282e+03 3.71587646e+03 3.70670459e+03 3.77235986e+03 3.73456421e+03 3.54590479e+03 3.54416821e+03 3.54899121e+03 3.49705322e+03 3.42072900e+03 3.33984326e+03 3.37048755e+03 3.34886230e+03 3.21905884e+03 3.10569312e+03 3.17072021e+03 3.22076880e+03 3.13089941e+03 3.08073584e+03 3.01209253e+03 2.99475464e+03 2.88007690e+03 2.74777588e+03 2.80908960e+03 2.82726587e+03 2.77364111e+03 2.72148291e+03 2.59984058e+03 2.58075562e+03 2.58678027e+03 2.58012012e+03 2.54656860e+03 2.43365527e+03 2.35322339e+03 2.27947217e+03 2.30051929e+03 2.31919971e+03 2.24722632e+03 2.17453296e+03 2.03739001e+03 2.03758704e+03 2.07368359e+03 1.98119397e+03 1.95568152e+03 1.87963635e+03 1.82055493e+03 1.82710046e+03 1.73923523e+03 1.67531116e+03 1.68651257e+03 1.65176917e+03 1.54792627e+03 1.46161926e+03 1.44269543e+03 1.41838525e+03 1.40959473e+03 1.39037671e+03 1.29337732e+03 1.21482532e+03 1.15408777e+03 1.13957556e+03 1.13229810e+03 1.06029541e+03 9.83807556e+02 9.19379395e+02 8.85258667e+02 8.68822083e+02 8.37501770e+02 7.74863037e+02 7.13976868e+02 6.75906372e+02 6.16530273e+02 5.51296204e+02 5.18642456e+02 4.80849518e+02 4.34361786e+02 3.95233704e+02 3.30724640e+02 2.73674347e+02 2.34563828e+02 1.93798874e+02 1.46134506e+02 9.35641479e+01 4.54984245e+01 -2.41116452e+00 -5.03740997e+01 -1.01017380e+02 -1.48503937e+02 -1.93680908e+02 -2.36030273e+02 -2.88772980e+02 -3.38866791e+02 -3.74684479e+02 -4.28217957e+02 -4.87459106e+02 -5.34830505e+02 -5.77326172e+02 -6.12331970e+02 -6.68666382e+02 -7.32720154e+02 -7.78763306e+02 -8.29909241e+02 -8.45072449e+02 -8.79144409e+02 -9.51834961e+02 -1.02355237e+03 -1.08577563e+03 -1.10947607e+03 -1.14028345e+03 -1.16272473e+03 -1.23190576e+03 -1.33043298e+03 -1.34627136e+03 -1.37853076e+03 -1.43103235e+03 -1.46299329e+03 -1.49390088e+03 -1.55397668e+03 -1.63032703e+03 -1.68819604e+03 -1.73798169e+03 -1.74599170e+03 -1.75278955e+03 -1.83180884e+03 -1.90199890e+03 -1.95950281e+03 -2.02562476e+03 -2.02710901e+03 -2.07032544e+03 -2.09806763e+03 -2.16708960e+03 -2.28989136e+03 -2.26825122e+03 -2.29152856e+03 -2.32987280e+03 -2.31100195e+03 -2.40657617e+03 -2.58331104e+03 -2.59966895e+03 -2.54366431e+03 -2.61939868e+03 -2.64197778e+03 -2.61476953e+03 -2.72790015e+03 -2.82271143e+03 -2.86048291e+03 -2.92001611e+03 -2.86790234e+03 -2.91001147e+03 -3.04246240e+03 -3.11393188e+03 -3.23852051e+03 -3.19069580e+03 -3.07441455e+03 -3.10837402e+03 -3.27725610e+03 -3.37717627e+03 -3.40597290e+03 -3.40607300e+03 -3.30851294e+03 -3.42568628e+03 -3.62588159e+03 -3.59025903e+03 -3.59402612e+03 -3.57491504e+03 -3.63902222e+03 -3.78745068e+03 -3.70237915e+03 -3.74261353e+03 -3.97284961e+03 -4.00283398e+03 -3.95715967e+03 -3.90131494e+03 -3.80869727e+03 -3.95929712e+03 -4.17355566e+03 -4.30419971e+03 -4.24152930e+03 -4.06638379e+03 -4.06166919e+03 -4.24994922e+03 -4.38781592e+03 -4.36127686e+03 -4.37379541e+03 -4.31632178e+03 -4.36885693e+03 -4.52383643e+03 -4.61450244e+03 -4.64740039e+03 -4.60298682e+03 -4.68204199e+03 -4.65550732e+03 -4.55239746e+03 -4.69140332e+03 -4.81613965e+03 -4.87140430e+03 -4.99709082e+03 -4.83551953e+03 -4.75767773e+03 -4.93470605e+03 -5.03819629e+03 -5.18766455e+03 -5.12530762e+03 -4.94533496e+03 -4.94586523e+03 -5.13240430e+03 -5.33754297e+03 -5.40793994e+03 -5.27099854e+03 -5.15341797e+03 -5.20595117e+03 -5.23736963e+03 -5.29977393e+03 -5.45461426e+03 -5.52442773e+03 -5.47238818e+03 -5.37070410e+03 -5.35772656e+03 -5.50863281e+03 -5.68845801e+03 -5.71147070e+03 -5.75866455e+03 -5.59641211e+03 -5.44485352e+03 -5.59213867e+03 -5.79822119e+03 -5.92827588e+03 -5.89718066e+03 -5.66930420e+03 -5.61311816e+03 -5.79016162e+03 -6.03593896e+03 -5.98834277e+03 -5.96410547e+03 -5.92107617e+03 -5.80833594e+03 -5.98948340e+03 -6.10159180e+03 -6.04581934e+03 -6.03253174e+03 -6.13732617e+03 -6.16049951e+03 -6.06041992e+03 -6.13286035e+03 -6.17875098e+03 -6.32282812e+03 -6.31079590e+03 -6.11872070e+03 -6.17964697e+03 -6.17816357e+03 -6.28149414e+03 -6.62671973e+03 -6.45638281e+03 -6.19367676e+03 -6.18295898e+03 -6.28814893e+03 -6.53706982e+03 -6.80094824e+03 -6.56661133e+03 -6.35413428e+03 -6.53172656e+03 -6.79962109e+03 -7.04498242e+03 -7.76538232e+03 -6.84805566e+03 -9.79502734e+03 -8.90033789e+03 -2.96201680e+04 15462871. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 36997176. 1961652. -2.56472109e+04 -2.06835977e+04 -1.28871973e+04 -1.08009307e+04 -9.70161719e+03 -5.45703955e+03 -6.23422705e+03 -8.32589355e+03 -7.03514355e+03 -6.38991162e+03 -5.82968457e+03 -6.40933447e+03 -7.05040137e+03 -7.08692725e+03 -6.82685254e+03 -6.83278564e+03 -6.80833838e+03 -6.72364209e+03 -7.05647559e+03 -6.99496436e+03 -6.68117334e+03 -6.65461670e+03 -6.74305664e+03 -6.71907129e+03 -6.58064844e+03 -6.57939404e+03 -6.76066748e+03 -6.96675146e+03 -6.96546143e+03 -6.63164014e+03 -6.28989404e+03 -6.46244238e+03 -6.82006982e+03 -6.97382520e+03 -6.68981104e+03 -6.35264941e+03 -6.33280371e+03 -6.60503223e+03 -6.95557666e+03 -6.70786768e+03 -6.34735254e+03 -6.30511035e+03 -6.63447559e+03 -6.61148145e+03 -6.46863965e+03 -6.46822168e+03 -6.37505078e+03 -6.48949121e+03 -6.50306787e+03 -6.18885400e+03 -6.17850781e+03 -6.48601025e+03 -6.64988232e+03 -6.47429395e+03 -6.14850391e+03 -5.96000391e+03 -6.28307568e+03 -6.62756641e+03 -6.44318311e+03 -6.10011621e+03 -5.91314844e+03 -5.85538135e+03 -6.17147607e+03 -6.47443213e+03 -6.28210205e+03 -6.14019922e+03 -6.02600146e+03 -5.86673047e+03 -5.95804053e+03 -6.09317676e+03 -5.90276953e+03 -5.80511914e+03 -6.02337549e+03 -5.89974072e+03 -5.62627051e+03 -5.68482568e+03 -5.95854492e+03 -6.02802002e+03 -5.87827979e+03 -5.71864990e+03 -5.53910840e+03 -5.46986670e+03 -5.71002783e+03 -5.96347754e+03 -5.70539160e+03 -5.34663672e+03 -5.33197168e+03 -5.52942627e+03 -5.73428955e+03 -5.68836035e+03 -5.36656250e+03 -5.27820703e+03 -5.41996533e+03 -5.35835059e+03 -5.28815137e+03 -5.28794043e+03 -5.22608252e+03 -5.25127197e+03 -5.21530957e+03 -5.03221533e+03 -5.05504688e+03 -5.16418652e+03 -5.19947266e+03 -5.18037695e+03 -5.02589502e+03 -4.81292188e+03 -4.81365137e+03 -5.05941943e+03 -5.05280371e+03 -4.80801953e+03 -4.63091797e+03 -4.55726025e+03 -4.73932275e+03 -4.98753613e+03 -4.79405127e+03 -4.49725977e+03 -4.47796875e+03 -4.55504248e+03 -4.52229102e+03 -4.38264941e+03 -4.39146582e+03 -4.49359570e+03 -4.50737988e+03 -4.33379395e+03 -4.16836719e+03 -4.14065332e+03 -4.29686621e+03 -4.41119385e+03 -4.25967969e+03 -4.07812891e+03 -3.97595264e+03 -3.87606567e+03 -3.98462720e+03 -4.16710010e+03 -3.99646362e+03 -3.75177197e+03 -3.70113818e+03 -3.82022925e+03 -3.93610327e+03 -3.78683667e+03 -3.63270605e+03 -3.59702490e+03 -3.59610352e+03 -3.58670996e+03 -3.54405029e+03 -3.40771582e+03 -3.32279663e+03 -3.43793823e+03 -3.45630469e+03 -3.27207422e+03 -3.17206030e+03 -3.18900049e+03 -3.22467285e+03 -3.27428467e+03 -3.16148438e+03 -2.93465576e+03 -2.91779102e+03 -3.01602588e+03 -2.98533179e+03 -2.87531104e+03 -2.79150098e+03 -2.75584009e+03 -2.73433740e+03 -2.73094629e+03 -2.65602734e+03 -2.56008325e+03 -2.59515112e+03 -2.59996313e+03 -2.48621191e+03 -2.38554492e+03 -2.33584058e+03 -2.36628320e+03 -2.38748022e+03 -2.32913916e+03 -2.21469897e+03 -2.09518677e+03 -2.03822974e+03 -2.08877710e+03 -2.14441724e+03 -2.02141125e+03 -1.87407715e+03 -1.82335767e+03 -1.83768872e+03 -1.85941638e+03 -1.80170398e+03 -1.70218140e+03 -1.63522473e+03 -1.60302332e+03 -1.55256433e+03 -1.50719006e+03 -1.48285864e+03 -1.42470874e+03 -1.38151709e+03 -1.33904810e+03 -1.25688525e+03 -1.21700037e+03 -1.20561267e+03 -1.17301758e+03 -1.11928711e+03 -1.02493042e+03 -9.54637024e+02 -9.57210632e+02 -9.50971191e+02 -8.86970032e+02 -8.11033325e+02 -7.39927063e+02 -6.82960571e+02 -6.72391724e+02 -6.62047058e+02 -5.94839966e+02 -5.12435547e+02 -4.60299164e+02 -4.28908691e+02 -3.87315277e+02 -3.40362793e+02 -2.91564148e+02 -2.39187408e+02 -1.90281479e+02 -1.40822876e+02 -9.03983841e+01 -4.47616501e+01 2.31474733e+00 5.08024445e+01 1.02341576e+02 1.48649826e+02 1.84320450e+02 2.29471634e+02 2.87720703e+02 3.47625824e+02 3.93512207e+02 4.30157013e+02 4.89665955e+02 5.42677246e+02 5.65547485e+02 5.90988464e+02 6.53405823e+02 7.36513367e+02 8.04874268e+02 8.43600769e+02 8.43434204e+02 8.60694031e+02 9.26998474e+02 1.02738538e+03 1.11132690e+03 1.13361804e+03 1.11163977e+03 1.15922290e+03 1.28862231e+03 1.32374902e+03 1.31128540e+03 1.36244873e+03 1.41096350e+03 1.46239600e+03 1.56774475e+03 1.57884851e+03 1.57186670e+03 1.65075293e+03 1.65870996e+03 1.76313989e+03 1.85989197e+03 1.79881555e+03 1.87982898e+03 1.98818530e+03 1.98885876e+03 2.03394434e+03 2.07219141e+03 2.11553857e+03 2.19052734e+03 2.22051587e+03 2.20134888e+03 2.24106079e+03 2.39728564e+03 2.52013135e+03 2.50220020e+03 2.42848340e+03 2.41677100e+03 2.52313916e+03 2.68117456e+03 2.78785107e+03 2.75157983e+03 2.66983301e+03 2.75288916e+03 2.87212842e+03 2.87150171e+03 2.91581519e+03 2.97026514e+03 2.99037427e+03 3.03632397e+03 3.20735059e+03 3.16514917e+03 3.08310132e+03 3.20954199e+03 3.18751709e+03 3.35048999e+03 3.43572192e+03 3.35659375e+03 3.54681665e+03 3.51838306e+03 3.36245215e+03 3.52691406e+03 3.53588379e+03 3.60646362e+03 3.90392505e+03 3.76473755e+03 3.57978149e+03 3.68358447e+03 3.88566357e+03 4.10016162e+03 4.06983472e+03 3.84494678e+03 3.78382300e+03 3.94692285e+03 4.14786230e+03 4.30906104e+03 4.29967725e+03 4.12535254e+03 4.11680762e+03 4.26505664e+03 4.36875000e+03 4.32092285e+03 4.32789453e+03 4.39220752e+03 4.43236719e+03 4.61466748e+03 4.64569092e+03 4.45985107e+03 4.49195605e+03 4.56950391e+03 4.63398193e+03 4.74617383e+03 4.74561426e+03 4.89087500e+03 4.83363232e+03 4.68198633e+03 4.82778516e+03 4.76834131e+03 4.93509814e+03 5.30020117e+03 5.04492920e+03 4.73826660e+03 4.92643945e+03 5.16073535e+03 5.33642822e+03 5.44075732e+03 5.14583350e+03 4.93462549e+03 5.08297119e+03 5.38833643e+03 5.61598486e+03 5.51333447e+03 5.21009619e+03 5.19583691e+03 5.40392285e+03 5.54233545e+03 5.73412842e+03 5.71571094e+03 5.41250195e+03 5.41149609e+03 5.67395654e+03 5.77793311e+03 5.60062891e+03 5.56754834e+03 5.71181299e+03 5.67832666e+03 5.93099268e+03 5.97445508e+03 5.67767529e+03 5.71732715e+03 5.87657031e+03 5.90113672e+03 5.94621729e+03 5.87843555e+03 6.03237402e+03 6.15916357e+03 6.03215527e+03 5.91978223e+03 5.79850342e+03 6.03711768e+03 6.41250146e+03 6.34436670e+03 6.03093262e+03 5.85655713e+03 6.07991602e+03 6.47348975e+03 6.32200098e+03 6.02133789e+03 6.12900195e+03 6.32896729e+03 6.46340430e+03 6.67437061e+03 6.56359863e+03 6.20881738e+03 6.05890723e+03 6.24406836e+03 6.64043408e+03 6.62912158e+03 6.43614893e+03 6.43526855e+03 6.42744189e+03 6.61393262e+03 6.59884619e+03 6.39485400e+03 6.43819189e+03 6.32275488e+03 6.62981006e+03 6.84791504e+03 6.55205322e+03 6.58346729e+03 6.68983105e+03 6.82032422e+03 6.62513818e+03 6.34962695e+03 6.63170801e+03 7.02481250e+03 6.84984277e+03 6.46965527e+03 6.59448975e+03 6.93508643e+03 6.91750244e+03 6.80203271e+03 6.78359424e+03 6.54392236e+03 6.53449512e+03 6.99345459e+03 7.00269873e+03 6.71319238e+03 6.54320654e+03 6.54090967e+03 6.84158008e+03 7.13836279e+03 6.84916113e+03 6.73373486e+03 6.79780469e+03 6.77935547e+03 7.04316602e+03 7.04490771e+03 6.70611426e+03 6.66398145e+03 6.79883496e+03 6.86393750e+03 6.89648193e+03 6.86811182e+03 6.99249023e+03 6.92788867e+03 6.63816602e+03 6.81965576e+03 6.77702100e+03 6.95601562e+03 7.41124609e+03 7.16349170e+03 6.67830469e+03 6.67688232e+03 7.35060938e+03 8.21593652e+03 8.15377197e+03 1.21941885e+04 1.93917324e+04 2.15464629e+04 -12068305. -17693968. 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. 0. 0. 0. 0. 0. 0. 0. 0. 12482699. 4.93358550e+06 -1.27353125e+06 -1.73694238e+06 1.98487598e+04 1.66857930e+04 1.06913545e+04 9.57345312e+03 9.77512793e+03 9.68439844e+03 9.34731152e+03 9.49916113e+03 9.45330273e+03 9.32670996e+03 9.38082324e+03 9.31000781e+03 9.30286035e+03 7.64008643e+03 8.02337842e+03 6.60115479e+03 6.00936865e+03 5.94662793e+03 6.12492676e+03 6.14209229e+03 5.84300635e+03 5.81299072e+03 6.09667139e+03 6.09370215e+03 5.90848291e+03 5.84346484e+03 5.80258740e+03 5.81814404e+03 5.75944141e+03 5.72544922e+03 5.75120850e+03 5.66906885e+03 5.54328467e+03 5.51965918e+03 5.72149463e+03 5.70372949e+03 5.54582910e+03 5.51190918e+03 5.49683984e+03 5.48698486e+03 5.42804736e+03 5.38410449e+03 5.35789502e+03 5.21505566e+03 5.19546289e+03 5.24785205e+03 5.19982031e+03 5.37422266e+03 5.39399756e+03 5.17151416e+03 4.98426807e+03 4.91346582e+03 5.19564600e+03 5.24646582e+03 5.00386230e+03 4.87143262e+03 4.88919531e+03 4.88920459e+03 4.78142236e+03 4.94765479e+03 4.90992529e+03 4.59139209e+03 4.54418506e+03 4.73973340e+03 4.89031592e+03 4.72255420e+03 4.58662109e+03 4.58469189e+03 4.49715625e+03 4.42336621e+03 4.42548242e+03 4.44412207e+03 4.38786670e+03 4.26791553e+03 4.21968262e+03 4.26173047e+03 4.21306641e+03 4.26919287e+03 4.17897363e+03 4.02202881e+03 4.06178613e+03 4.02588818e+03 4.06144019e+03 4.05860815e+03 3.93137158e+03 3.87359033e+03 3.75421167e+03 3.64368726e+03 3.78205054e+03 3.78097510e+03 3.54576123e+03 3.54413721e+03 3.70355542e+03 3.75585791e+03 3.61437207e+03 3.46624634e+03 3.40314795e+03 3.36865430e+03 3.30530591e+03 3.24826343e+03 3.27796924e+03 3.21767261e+03 3.22374634e+03 3.16053589e+03 3.04633398e+03 3.05305469e+03 2.93107837e+03 2.94302026e+03 3.06980420e+03 2.95616406e+03 2.83423169e+03 2.71479883e+03 2.65607886e+03 2.77154395e+03 2.74505615e+03 2.61366357e+03 2.49246680e+03 2.46065894e+03 2.47811304e+03 2.41640796e+03 2.45102710e+03 2.42970996e+03 2.30681860e+03 2.21333521e+03 2.17110596e+03 2.21105225e+03 2.16951416e+03 2.07008105e+03 1.97886023e+03 1.94055359e+03 1.94384949e+03 1.83996460e+03 1.81448889e+03 1.88788123e+03 1.81142383e+03 1.70944873e+03 1.61645459e+03 1.56148010e+03 1.61539185e+03 1.57474390e+03 1.47653503e+03 1.38644556e+03 1.32984021e+03 1.33482874e+03 1.29019482e+03 1.23376123e+03 1.15834607e+03 1.13554431e+03 1.13516382e+03 1.05753210e+03 1.01705536e+03 9.76818298e+02 9.11895081e+02 8.42306030e+02 7.94466675e+02 7.65461182e+02 7.17075012e+02 6.72508484e+02 6.03534790e+02 5.63256042e+02 5.52960144e+02 4.80166565e+02 4.15978149e+02 3.80038849e+02 3.32749023e+02 2.93931244e+02 2.40606384e+02 1.84785385e+02 1.45094421e+02 9.75880966e+01 4.77157516e+01 -5.91901124e-01 -4.82649422e+01 -9.51679230e+01 -1.42547806e+02 -1.93430725e+02 -2.35465271e+02 -2.87471924e+02 -3.55233582e+02 -3.97301056e+02 -4.25490479e+02 -4.56409119e+02 -5.19731201e+02 -6.03870117e+02 -6.41221252e+02 -6.70575745e+02 -7.04457764e+02 -7.45390564e+02 -8.14960144e+02 -8.63789307e+02 -9.28921204e+02 -9.59554138e+02 -9.76708374e+02 -1.05292725e+03 -1.10125696e+03 -1.16885681e+03 -1.21177832e+03 -1.23177258e+03 -1.27109546e+03 -1.31363220e+03 -1.38750537e+03 -1.39942590e+03 -1.47085657e+03 -1.60244604e+03 -1.61013892e+03 -1.61574524e+03 -1.61909009e+03 -1.65667737e+03 -1.79791003e+03 -1.85599390e+03 -1.85435352e+03 -1.84012585e+03 -1.88484827e+03 -1.99547693e+03 -2.04025415e+03 -2.13972119e+03 -2.17469214e+03 -2.16729126e+03 -2.14824390e+03 -2.18262183e+03 -2.37038501e+03 -2.39779663e+03 -2.37657227e+03 -2.38975488e+03 -2.42278540e+03 -2.59327490e+03 -2.65458862e+03 -2564. -2.58478125e+03 -2.76496582e+03 -2.82849121e+03 -2.72414600e+03 -2.75555029e+03 -2.95357446e+03 -3.00408569e+03 -2.94967700e+03 -2.92444385e+03 -2.96488232e+03 -3.19141479e+03 -3.21707056e+03 -3.14264185e+03 -3.18352563e+03 -3.21717334e+03 -3.30251782e+03 -3.36226367e+03 -3.37430322e+03 -3.33020874e+03 -3.45145728e+03 -3.63985156e+03 -3.58635327e+03 -3.66872974e+03 -3.71578247e+03 -3.68424878e+03 -3.73469873e+03 -3.75880566e+03 -3.77451855e+03 -3.74845264e+03 -3.77274854e+03 -3.89653687e+03 -3.96709814e+03 -4.12681982e+03 -4.02621362e+03 -3.94128857e+03 -4.12233105e+03 -4.17248242e+03 -4.31631299e+03 -4.30437305e+03 -4.21287207e+03 -4.24605957e+03 -4.26309131e+03 -4.37122266e+03 -4.44133496e+03 -4.56416016e+03 -4.54114014e+03 -4.45922314e+03 -4.53012012e+03 -4.42636621e+03 -4.61805420e+03 -4.93028711e+03 -4.84909766e+03 -4.73348389e+03 -4.64885352e+03 -4.62186035e+03 -4.88881982e+03 -5.07306299e+03 -4.97952344e+03 -4.80844580e+03 -4.82954199e+03 -5.02137256e+03 -5.02280273e+03 -5.17074023e+03 -5.15552002e+03 -5.02881299e+03 -5.17204004e+03 -5.18444482e+03 -5.34303320e+03 -5.38510498e+03 -5.15126709e+03 -5.18077393e+03 -5.48917139e+03 -5.42350439e+03 -5.17771143e+03 -5.40028613e+03 -5.71412402e+03 -5.64895020e+03 -5.53513721e+03 -5.42360596e+03 -5.44917090e+03 -5.76907959e+03 -5.78002246e+03 -5.65454883e+03 -5.55150732e+03 -5.53278369e+03 -5.76048535e+03 -5.79637988e+03 -5.77575244e+03 -5.67825244e+03 -5.86176416e+03 -6.03453125e+03 -5.92582764e+03 -6.06492627e+03 -5.98383643e+03 -5.85434473e+03 -5.99235254e+03 -6.04613867e+03 -6.04562500e+03 -6.03849365e+03 -6.00491064e+03 -5.89700977e+03 -6.13725244e+03 -6.52262012e+03 -6.16622656e+03 -5.90159766e+03 -6.12515186e+03 -6.33695068e+03 -6.51321533e+03 -6.37806689e+03 -6.21771240e+03 -6.41011719e+03 -6.40920996e+03 -6.18164258e+03 -6.12364990e+03 -6.52425635e+03 -6.53262402e+03 -6.35010547e+03 -6.35095850e+03 -6.16830566e+03 -6.41637500e+03 -6.85414014e+03 -6.65054248e+03 -6.47418750e+03 -6.29765283e+03 -6.25060791e+03 -6.62509082e+03 -6.96987305e+03 -6.78185352e+03 -6.44197314e+03 -6.42987891e+03 -6.55679150e+03 -6.62841309e+03 -6.84096094e+03 -6.66557324e+03 -6.46246436e+03 -6.67171289e+03 -6.64955322e+03 -6.86050391e+03 -6.82170215e+03 -6.58813916e+03 -6.76686963e+03 -6.78044873e+03 -6.75808838e+03 -6.56190723e+03 -6.65141504e+03 -7.07002979e+03 -6.97741895e+03 -6.71511035e+03 -6.54409082e+03 -6.70405078e+03 -7.10071777e+03 -6.97595605e+03 -6.82701318e+03 -6.65979590e+03 -6.60490967e+03 -6.85532422e+03 -6.90368848e+03 -6.85848145e+03 -6.70557812e+03 -6.81449512e+03 -7.08243701e+03 -6.85938965e+03 -6.98889014e+03 -7.03037939e+03 -6.85328223e+03 -6.87130225e+03 -6.83093994e+03 -6.81835889e+03 -6.81138184e+03 -6.75430908e+03 -6.74197021e+03 -7.01218457e+03 -7.03342529e+03 -6.62444043e+03 -6.62275635e+03 -6.75615479e+03 -6.93504395e+03 -7.20377881e+03 -6.96024756e+03 -6.54119922e+03 -6.85198633e+03 -7.15863232e+03 -6.96416895e+03 -6.66706641e+03 -6.64717920e+03 -6.76031201e+03 -6.78265625e+03 -6.84351221e+03 -6.60275000e+03 -6.76387842e+03 -7.10717285e+03 -6.91387500e+03 -6.71841064e+03 -6.58321338e+03 -6.64537842e+03 -6.94861279e+03 -6.91562695e+03 -6.70474951e+03 -6.59359033e+03 -6.36380322e+03 -6.50606299e+03 -6.84914502e+03 -7.05172217e+03 -6.67038135e+03 -6.39830176e+03 -6.57532861e+03 -6.68269580e+03 -6.90047168e+03 -6.71265234e+03 -6.44502051e+03 -6.61076123e+03 -6.58481250e+03 -6.44066455e+03 -6.31417627e+03 -6.47870312e+03 -6.77094336e+03 -6.61921338e+03 -6.46081592e+03 -6.34706348e+03 -6.29784961e+03 -6.60648096e+03 -6.58191455e+03 -6.39577539e+03 -6.21093896e+03 -6.13614209e+03 -6.27315137e+03 -6.25965771e+03 -6.46955078e+03 -6.52314893e+03 -6.16670068e+03 -6.02982324e+03 -6.20796924e+03 -6.45350244e+03 -6.27301660e+03 -6.12335010e+03 -6.05732178e+03 -6.05279932e+03 -5.98195703e+03 -5.85679590e+03 -6.06826270e+03 -6.14883545e+03 -5.95762061e+03 -6.05718652e+03 -6.07653809e+03 -5.99671875e+03 -5.95627148e+03 -5.87422705e+03 -5.83792676e+03 -5.69305957e+03 -5.61341553e+03 -5.82239307e+03 -5.92150732e+03 -5.64107520e+03 -5.41495264e+03 -5.58425293e+03 -5.87116553e+03 -5.85370947e+03 -5.53043262e+03 -5.28903760e+03 -5.56336719e+03 -5.72734375e+03 -5.56526904e+03 -5.48283252e+03 -5.27862939e+03 -5.06630518e+03 -5.24835156e+03 -5.53704102e+03 -5.52661768e+03 -5.18832812e+03 -4.96228418e+03 -5.24849023e+03 -5.44174219e+03 -5.23276807e+03 -4.94670312e+03 -4.80378369e+03 -4.95415967e+03 -4.99214795e+03 -5.09578027e+03 -5.13193359e+03 -4.92818115e+03 -4.77323047e+03 -4.75568896e+03 -4.93371533e+03 -4.77925049e+03 -4.58812500e+03 -4.77190576e+03 -4.73791504e+03 -4.64486084e+03 -4.50556445e+03 -4.46424805e+03 -4.67715576e+03 -4.49212158e+03 -4.23393262e+03 -4.33419189e+03 -4.46479199e+03 -4.43583496e+03 -4.29134229e+03 -4.36488037e+03 -4.36589648e+03 -4.19894531e+03 -4.02590796e+03 -3.97792017e+03 -4.18298633e+03 -4.05911987e+03 -3.89502173e+03 -3.97000977e+03 -3.92280176e+03 -3.86288306e+03 -3.77968652e+03 -3.83367480e+03 -3.83332031e+03 -3.68480811e+03 -3.70534253e+03 -3.67253711e+03 -3.64517188e+03 -3.61747583e+03 -3.52888037e+03 -3.41285645e+03 -3.28102637e+03 -3.25091333e+03 -3.38942480e+03 -3.51515308e+03 -3.28623486e+03 -3.03551489e+03 -3.10874902e+03 -3.26031201e+03 -3.24415015e+03 -3.04145361e+03 -2.86876123e+03 -2.96879028e+03 -2.99238086e+03 -2.84763672e+03 -2.91098242e+03 -2.82918481e+03 -2.62179126e+03 -2.64479736e+03 -2.75568140e+03 -2.71361719e+03 -2.53514941e+03 -2.39632227e+03 -2.46281714e+03 -2.57266968e+03 -2.46069531e+03 -2.29166406e+03 -2.19479663e+03 -2.25856519e+03 -2.28909351e+03 -2.17621924e+03 -2.10717407e+03 -2.06860913e+03 -2.03226270e+03 -1.97741882e+03 -1.98475793e+03 -1.90647278e+03 -1.79313733e+03 -1.79204517e+03 -1.75838989e+03 -1.74726062e+03 -1.66221680e+03 -1.57380212e+03 -1.59409766e+03 -1.49993848e+03 -1.41481372e+03 -1.43377844e+03 -1.41811536e+03 -1.35896094e+03 -1.28266052e+03 -1.27828735e+03 -1.23126367e+03 -1.12860486e+03 -1.06453772e+03 -1.03143835e+03 -1.10683594e+03 -1.06934387e+03 -1.04002673e+03 -9.76973938e+02 -2.50667603e+03 -1.54946396e+04 -281374080. 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. 94908496. 1.10996289e+04 1.71637354e+03 1.00691724e+03 8.97523254e+02 8.67064636e+02 8.54788635e+02 8.88082214e+02 9.25685547e+02 9.73343323e+02 1.00709003e+03 1.02728149e+03 1.10396643e+03 1.18512634e+03 1.19629248e+03 1.22910303e+03 1.30403455e+03 1.36799744e+03 1.41784326e+03 1.42213892e+03 1.42732434e+03 1.49943457e+03 1.59013220e+03 1.64667017e+03 1.67971619e+03 1.69003711e+03 1.73519568e+03 1.84751086e+03 1.93326526e+03 1.91628955e+03 1.88200781e+03 1.95360962e+03 2.06413867e+03 2.08254053e+03 2.12265747e+03 2.19008203e+03 2.17746143e+03 2.26365698e+03 2.35897754e+03 2.30764307e+03 2.34884058e+03 2.46842090e+03 2.60460742e+03 2.66904395e+03 2.53339844e+03 2.49030103e+03 2.60422510e+03 2.75571069e+03 2.84102197e+03 2.78134229e+03 2.81721875e+03 2.95151074e+03 2.96979883e+03 2.99958179e+03 2.99705420e+03 2.95027344e+03 3.10297583e+03 3.23913696e+03 3.17252612e+03 3.20092676e+03 3.30708423e+03 3.30901367e+03 3.39991675e+03 3.45889893e+03 3.39617065e+03 3.42156543e+03 3.51932300e+03 3.68580078e+03 3.70447729e+03 3.59391650e+03 3.66861646e+03 3.70486426e+03 3.77763184e+03 3.90503076e+03 3.80420728e+03 3.80551025e+03 3.95163940e+03 4.06125513e+03 4.12207812e+03 4.03004663e+03 3.94335205e+03 4.02923315e+03 4.19350732e+03 4.29640430e+03 4.32196289e+03 4.26938916e+03 4.26840576e+03 4.40155566e+03 4.50495801e+03 4.43625391e+03 4.33541406e+03 4.44054541e+03 4.63912500e+03 4.72627148e+03 4.64769189e+03 4.55552148e+03 4.54219971e+03 4.73530762e+03 4.87180566e+03 4.72875342e+03 4.75954248e+03 4.93890283e+03 5.06872559e+03 5.10176953e+03 4.87058057e+03 4.77147412e+03 4.97735547e+03 5.11235107e+03 5.10133545e+03 5.10966943e+03 5.20015186e+03 5.31040088e+03 5.21849023e+03 5.21162793e+03 5.34155029e+03 5.27518018e+03 5.25791943e+03 5.41799268e+03 5.50088867e+03 5.54188477e+03 5.47629883e+03 5.32802930e+03 5.43032666e+03 5.60432764e+03 5.70795703e+03 5.66532959e+03 5.54827393e+03 5.64805029e+03 5.83136523e+03 5.89873438e+03 5.71227686e+03 5.57328711e+03 5.68764600e+03 5.86994287e+03 5.92838867e+03 5.86123193e+03 5.83443701e+03 5.87718359e+03 6.04759229e+03 6.10501562e+03 6.03644189e+03 6.01212842e+03 5.95212061e+03 6.05362549e+03 6.07717676e+03 6.02545410e+03 6.07843848e+03 6.12459082e+03 6.31303711e+03 6.42908740e+03 6.20796924e+03 6.08465088e+03 6.20898486e+03 6.32930225e+03 6.43088672e+03 6.40965967e+03 6.15544873e+03 6.18054492e+03 6.49848389e+03 6.68493359e+03 6.45432422e+03 6.21257227e+03 6.33907568e+03 6.60689795e+03 6.60643359e+03 6.27530859e+03 6.32772168e+03 6.54648389e+03 6.60859033e+03 6.59469141e+03 6.65328027e+03 6.66981006e+03 6.43402295e+03 6.61419531e+03 6.79082031e+03 6.51685889e+03 6.56350488e+03 6.68307275e+03 6.71928369e+03 6.87217090e+03 6.68694336e+03 6.47639014e+03 6.55114893e+03 6.71610059e+03 7.03535547e+03 6.97753271e+03 6.56660254e+03 6.63958496e+03 6.99654590e+03 6.85222754e+03 6.55487598e+03 6.60234814e+03 6.78085840e+03 6.98244434e+03 6.97021143e+03 6.91304297e+03 6.74804492e+03 6.63604199e+03 6.84348389e+03 6.98497168e+03 6.77386084e+03 6.75761377e+03 6.95126855e+03 7.03782666e+03 7.03392676e+03 6.81639697e+03 6.66565283e+03 6.74887207e+03 6.84989746e+03 7.08978223e+03 7.07751709e+03 6.73481885e+03 6.73909717e+03 6.96441064e+03 7.00114746e+03 6.95752197e+03 6.72123291e+03 6.79258496e+03 6.95331787e+03 7.03356201e+03 6.98189062e+03 6.79406836e+03 6.71703564e+03 6.84508789e+03 6.99201611e+03 6.79743506e+03 6.86263037e+03 6.97100879e+03 6.90704688e+03 7.06249023e+03 6.80666992e+03 6.64965576e+03 6.81908740e+03 6.83077148e+03 6.92189795e+03 6.75470898e+03 6.56285840e+03 6.79058105e+03 7.04692480e+03 6.88780029e+03 6.75393896e+03 6.77373730e+03 6.68440576e+03 6.62461963e+03 6.80664111e+03 6.99420361e+03 6.81116260e+03 6.57219238e+03 6.74790479e+03 6.67422217e+03 6.71699463e+03 6.69026807e+03 6.45703076e+03 6.61831396e+03 6.77446631e+03 6.53242432e+03 6.45000098e+03 6.51885010e+03 6.71274170e+03 6.82461426e+03 6.39414648e+03 6.34981934e+03 6.55998926e+03 6.58827002e+03 6.65775684e+03 6.41796777e+03 6.36552148e+03 6.33479688e+03 6.36179688e+03 6.58870068e+03 6.45093262e+03 6.18918701e+03 6.33304980e+03 6.48573486e+03 6.25318311e+03 6.17078564e+03 6.11322363e+03 6.07002441e+03 6.29935596e+03 6.38521387e+03 6.16775293e+03 6.03440039e+03 6.07816943e+03 6.16239551e+03 6.25497119e+03 6.02146094e+03 6.11028809e+03 6.12295557e+03 5.83729785e+03 5.84840186e+03 5.88680176e+03 5.90163867e+03 6.00236182e+03 5.87385498e+03 5.82034717e+03 5.94912402e+03 5.78025830e+03 5.64537793e+03 5.74004932e+03 5.81380371e+03 5.75859473e+03 5.52714648e+03 5.49195654e+03 5.74261865e+03 5.76056250e+03 5.49237305e+03 5.41040869e+03 5.44253418e+03 5.55958301e+03 5.58911182e+03 5.36270996e+03 5.30787012e+03 5.27404541e+03 5.34772803e+03 5.38490186e+03 5.20097021e+03 5.18270166e+03 5.17366455e+03 5.12711523e+03 5.17175488e+03 5.19903564e+03 5.04322510e+03 4.90606641e+03 5.08775146e+03 5.21421191e+03 4.91860449e+03 4.69469434e+03 4.79130029e+03 4.88036914e+03 4.84324707e+03 4.73017432e+03 4.64306348e+03 4.64921777e+03 4.74220264e+03 4.71858447e+03 4.55195605e+03 4.51455615e+03 4.47149268e+03 4.51993848e+03 4.50850732e+03 4.33467090e+03 4.32348975e+03 4.29137305e+03 4.25997070e+03 4.30339502e+03 4.26520459e+03 4.14017236e+03 4.06466040e+03 4.11803516e+03 4.11575244e+03 4.01265771e+03 3.90138062e+03 3.89093506e+03 3.94561963e+03 3.90879517e+03 3.73416040e+03 3.70302148e+03 3.72593848e+03 3.79393164e+03 3.77057104e+03 3.58377905e+03 3.62950903e+03 3.54889697e+03 3.37739331e+03 3.37644971e+03 3.38135498e+03 3.43744873e+03 3.37835742e+03 3.19495312e+03 3.12165063e+03 3.18407031e+03 3.23902173e+03 3.18075073e+03 3.08733765e+03 3.02179126e+03 2.95436182e+03 2.87601196e+03 2.82146851e+03 2.87873730e+03 2.86736548e+03 2.72095508e+03 2.68041504e+03 2.65293457e+03 2.63664185e+03 2.61741602e+03 2.56481689e+03 2.55984351e+03 2.44742383e+03 2.32298047e+03 2.28638037e+03 2.30904883e+03 2.33370508e+03 2.30186426e+03 2.18732007e+03 2.02488379e+03 2.02101758e+03 2.05778662e+03 1.99303040e+03 1.98959351e+03 1.93024731e+03 1.81103064e+03 1.81989636e+03 1.78283521e+03 1.69405713e+03 1.67092761e+03 1.61310779e+03 1.54216443e+03 1.49112170e+03 1.46453235e+03 1.42633728e+03 1.41380518e+03 1.40794153e+03 1.29791394e+03 1.19803101e+03 1.16072339e+03 1.14257227e+03 1.13274597e+03 1.07849719e+03 9.82078857e+02 9.26033997e+02 8.99838318e+02 8.78176514e+02 8.41330811e+02 7.70751282e+02 7.15181763e+02 6.66794312e+02 6.15311646e+02 5.64981934e+02 5.30379761e+02 4.88257233e+02 4.33151398e+02 3.88620911e+02 3.29008423e+02 2.80386414e+02 2.40102997e+02 1.92385773e+02 1.46075211e+02 9.41583786e+01 4.48211136e+01 -2.47306514e+00 -5.10544319e+01 -1.01561012e+02 -1.51205719e+02 -1.94450989e+02 -2.32895508e+02 -2.85367981e+02 -3.38310089e+02 -3.80809418e+02 -4.38656219e+02 -4.94556305e+02 -5.27140259e+02 -5.69974731e+02 -6.21522827e+02 -6.82755493e+02 -7.41939453e+02 -7.76924561e+02 -8.24905151e+02 -8.46523071e+02 -8.85997192e+02 -9.60436157e+02 -1.01833728e+03 -1.08409351e+03 -1.12593066e+03 -1.14116187e+03 -1.16545813e+03 -1.24100806e+03 -1.33218140e+03 -1.36136047e+03 -1.38814697e+03 -1.43826038e+03 -1.45621350e+03 -1.51085461e+03 -1.58965747e+03 -1.63238086e+03 -1.68616406e+03 -1.70908191e+03 -1.73459985e+03 -1.78126294e+03 -1.87649365e+03 -1.93285645e+03 -1.95362427e+03 -2.01721655e+03 -2.01270020e+03 -2.07827881e+03 -2.15344580e+03 -2.17784229e+03 -2.28749683e+03 -2.28280396e+03 -2.25026514e+03 -2.31197534e+03 -2.36025366e+03 -2.46833105e+03 -2.61669531e+03 -2.60783594e+03 -2.54365625e+03 -2.56992090e+03 -2.62072754e+03 -2.66753320e+03 -2.78886084e+03 -2.87099683e+03 -2.82582617e+03 -2.86588110e+03 -2.89070947e+03 -2.97181274e+03 -3.09927197e+03 -3.10481055e+03 -3.21151514e+03 -3.18702002e+03 -3.05609717e+03 -3.14015283e+03 -3.30954175e+03 -3.40348926e+03 -3.47276929e+03 -3.41271216e+03 -3.27403418e+03 -3.42714087e+03 -3.65637646e+03 -3.63046436e+03 -3.60552612e+03 -3.63859814e+03 -3.62982251e+03 -3.74336743e+03 -3.79587964e+03 -3.78458496e+03 -3.95745459e+03 -3.94575366e+03 -3.92934717e+03 -3.98084814e+03 -3.90559204e+03 -4.00133130e+03 -4.14661865e+03 -4.29856689e+03 -4.22074805e+03 -4.02876147e+03 -4.11352637e+03 -4.30288037e+03 -4.41008545e+03 -4.41724609e+03 -4.34206152e+03 -4.32191943e+03 -4.45652295e+03 -4.57886523e+03 -4.63190820e+03 -4.64865869e+03 -4.62169287e+03 -4.62628760e+03 -4.67844922e+03 -4.69154443e+03 -4.75938379e+03 -4.83341455e+03 -4.84719482e+03 -4.92931348e+03 -4.82970459e+03 -4.85974121e+03 -5.02996045e+03 -5.01682275e+03 -5.18728564e+03 -5.12323926e+03 -4.90829150e+03 -4.98898438e+03 -5.15977393e+03 -5.33171240e+03 -5.44790137e+03 -5.26601416e+03 -5.11727686e+03 -5.22406592e+03 -5.35635547e+03 -5.41955176e+03 -5.46060645e+03 -5.51056787e+03 -5.40352832e+03 -5.35212158e+03 -5.46399268e+03 -5.62927637e+03 -5.73702637e+03 -5.65133301e+03 -5.72502588e+03 -5.65733838e+03 -5.46475537e+03 -5.63576709e+03 -5.77821777e+03 -5.89732129e+03 -5.94721191e+03 -5.67419824e+03 -5.64365576e+03 -5.85131885e+03 -6.09012695e+03 -6.06678076e+03 -5.96491602e+03 -5.96588525e+03 -5.81014453e+03 -6.01112842e+03 -6.19367285e+03 -6.09302148e+03 -6.07022510e+03 -6.10791113e+03 -6.15343945e+03 -6.16940332e+03 -6.14679980e+03 -6.22942578e+03 -6.27724756e+03 -6.30630273e+03 -6.14515234e+03 -6.23896826e+03 -6.34672852e+03 -6.34780664e+03 -6.59121777e+03 -6.39328564e+03 -6.20063037e+03 -6.32871533e+03 -6.26201709e+03 -6.46857764e+03 -6.85686670e+03 -6.73913037e+03 -6.36125781e+03 -6.39509424e+03 -6.76435742e+03 -7.37194092e+03 -8.45338281e+03 -8.15692725e+03 -1.16493408e+04 -1.92436426e+04 -9.16756016e+04 -44345160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -20479820. 31591046. -3.24172637e+04 -2.04293906e+04 -8.17122119e+03 -8.58199121e+03 -7.78544775e+03 -7.43655713e+03 -7.17313379e+03 -6.75743994e+03 -6.85119727e+03 -7.19731641e+03 -7.14942090e+03 -6.83809814e+03 -6.59080029e+03 -6.61013818e+03 -7.00039844e+03 -7.23015820e+03 -6.94123682e+03 -6.69796777e+03 -6.63599268e+03 -6.73212256e+03 -7.00700244e+03 -7.04412939e+03 -6.78208252e+03 -6.66808691e+03 -6.65104590e+03 -6.72873047e+03 -6.77109229e+03 -6.63898242e+03 -6.64131689e+03 -6.91606787e+03 -7.05257910e+03 -6.68922510e+03 -6.35872412e+03 -6.50126758e+03 -6.81415967e+03 -7.02375732e+03 -6.71763379e+03 -6.34180615e+03 -6.39589160e+03 -6.67935889e+03 -6.98129883e+03 -6.68267920e+03 -6.29023926e+03 -6.31103809e+03 -6.58260547e+03 -6.70219824e+03 -6.68449512e+03 -6.56570703e+03 -6.36177295e+03 -6.37426514e+03 -6.54866211e+03 -6.35202441e+03 -6.20726318e+03 -6.52838525e+03 -6.56065527e+03 -6.45962451e+03 -6.24162500e+03 -5.98905664e+03 -6.32530273e+03 -6.63873242e+03 -6.46183301e+03 -6.06384863e+03 -5.86233496e+03 -5.94731299e+03 -6.30426270e+03 -6.48986523e+03 -6.28984375e+03 -6.14042871e+03 -6.00076074e+03 -5.83908447e+03 -5.98922266e+03 -6.16137109e+03 -5.95793555e+03 -5.89139307e+03 -5.95520361e+03 -5.96478760e+03 -5.80206885e+03 -5.72887402e+03 -5.91898779e+03 -5.95391064e+03 -5.95135938e+03 -5.74129639e+03 -5.50183008e+03 -5.50505469e+03 -5.78670166e+03 -5.99563916e+03 -5.68862207e+03 -5.33195508e+03 -5.38021484e+03 -5.55233887e+03 -5.69959375e+03 -5.69192676e+03 -5.43945996e+03 -5.36205518e+03 -5.35274316e+03 -5.36849170e+03 -5.42580859e+03 -5.31249072e+03 -5.24432812e+03 -5.19615625e+03 -5.21212646e+03 -5.20852783e+03 -5.11700830e+03 -5.13525684e+03 -5.15500879e+03 -5.18600488e+03 -5.03763574e+03 -4.78043457e+03 -4.83649219e+03 -5.07098828e+03 -5.12614258e+03 -4.84262891e+03 -4.60033643e+03 -4.59290625e+03 -4.81104688e+03 -5.02408350e+03 -4.77898877e+03 -4.51817529e+03 -4.55456934e+03 -4.50945020e+03 -4.51274121e+03 -4.52547607e+03 -4.44295459e+03 -4.47915137e+03 -4.40183594e+03 -4.34733301e+03 -4.32229395e+03 -4.18353369e+03 -4.25958350e+03 -4.36250244e+03 -4.29077393e+03 -4.11710059e+03 -3.95799683e+03 -3.92790698e+03 -4.04549658e+03 -4.17452148e+03 -3.97531323e+03 -3.72515430e+03 -3.75548828e+03 -3.89351562e+03 -3.95867920e+03 -3.77334204e+03 -3.63637134e+03 -3.63154199e+03 -3.57463062e+03 -3.59021851e+03 -3.58825195e+03 -3.40430957e+03 -3.34791870e+03 -3.43307178e+03 -3.44661377e+03 -3.34408179e+03 -3.24317993e+03 -3.20881421e+03 -3.20839111e+03 -3.27015869e+03 -3.15938818e+03 -2.92665479e+03 -2.93554712e+03 -3.00301440e+03 -2.98970068e+03 -2.93216577e+03 -2.79811914e+03 -2.73939014e+03 -2.75271655e+03 -2.76757617e+03 -2.71336572e+03 -2.59893579e+03 -2.58551367e+03 -2.54948486e+03 -2.49857739e+03 -2.45020386e+03 -2.34663354e+03 -2.35305493e+03 -2.37750952e+03 -2.35011304e+03 -2.22907422e+03 -2.08169067e+03 -2.06048657e+03 -2.11804272e+03 -2.14884155e+03 -2.01319543e+03 -1.86764575e+03 -1.85011157e+03 -1.85081580e+03 -1.84125464e+03 -1.80394751e+03 -1.69817432e+03 -1.63687512e+03 -1.61667249e+03 -1.58658655e+03 -1.53785229e+03 -1.47868909e+03 -1.43530762e+03 -1.37018726e+03 -1.33954980e+03 -1.29796204e+03 -1.23132507e+03 -1.19848425e+03 -1.15776904e+03 -1.11562585e+03 -1.02967786e+03 -9.62863647e+02 -9.58911804e+02 -9.45957336e+02 -9.00015625e+02 -8.17169312e+02 -7.35484436e+02 -6.90103821e+02 -6.81406433e+02 -6.66871643e+02 -5.98166199e+02 -5.19347107e+02 -4.62674805e+02 -4.18134918e+02 -3.85947998e+02 -3.48786041e+02 -2.94962646e+02 -2.40274750e+02 -1.90706924e+02 -1.42565369e+02 -9.19398193e+01 -4.47793007e+01 2.59403276e+00 5.04857140e+01 1.01116905e+02 1.48703491e+02 1.84874481e+02 2.35309525e+02 2.92784729e+02 3.43106415e+02 3.92464935e+02 4.34801086e+02 4.91493073e+02 5.44533691e+02 5.69804993e+02 5.95315918e+02 6.55174744e+02 7.38489502e+02 8.08218811e+02 8.44999451e+02 8.47735168e+02 8.68470459e+02 9.35407104e+02 1.03150696e+03 1.10856042e+03 1.13699109e+03 1.12054602e+03 1.16540039e+03 1.28980652e+03 1.33049670e+03 1.30764172e+03 1.35553052e+03 1.43219885e+03 1.47882385e+03 1.57474915e+03 1.58498547e+03 1.57459790e+03 1.65943994e+03 1.66596533e+03 1.75908679e+03 1.87349292e+03 1.81815955e+03 1.88382495e+03 1.99443799e+03 2.00348462e+03 2.05374756e+03 2.07587988e+03 2.12279761e+03 2.21060254e+03 2.22761743e+03 2.20074805e+03 2.26093066e+03 2.40986206e+03 2.51601855e+03 2.50740186e+03 2.44989771e+03 2.43394849e+03 2.52396265e+03 2.68587964e+03 2.80093433e+03 2.78676294e+03 2.68589819e+03 2.74216870e+03 2.90140112e+03 2.90313013e+03 2.90813013e+03 2.96548169e+03 3.00876196e+03 3.05255347e+03 3.22323193e+03 3.17678906e+03 3.09631030e+03 3.21676294e+03 3.18040405e+03 3.34970337e+03 3.47745166e+03 3.38993872e+03 3.55863037e+03 3.52834888e+03 3.39698047e+03 3.53975610e+03 3.52995874e+03 3.63427271e+03 3.91472607e+03 3.76223755e+03 3.61111426e+03 3.73222021e+03 3.91072266e+03 4.09643945e+03 4.07025342e+03 3.87165161e+03 3.78627100e+03 3.93893286e+03 4.18751611e+03 4.35020264e+03 4.31984814e+03 4.13383447e+03 4.10961621e+03 4.30411035e+03 4.42826660e+03 4.32022266e+03 4.31055469e+03 4.41537158e+03 4.44806006e+03 4.63330811e+03 4.67470557e+03 4.53160107e+03 4.55270410e+03 4.56197998e+03 4.62224854e+03 4.77927734e+03 4.76874561e+03 4.89897217e+03 4.86503467e+03 4.70110352e+03 4.84387793e+03 4.79295312e+03 4.95362354e+03 5.33560449e+03 5.07329395e+03 4.73589014e+03 4.91238818e+03 5.19296973e+03 5.34019189e+03 5.46332617e+03 5.20571631e+03 4.96242480e+03 5.09839111e+03 5.40550244e+03 5.69066064e+03 5.53769336e+03 5.22129102e+03 5.21186816e+03 5.41378955e+03 5.56853369e+03 5.76518311e+03 5.74710352e+03 5.43468555e+03 5.43095947e+03 5.65272021e+03 5.76072070e+03 5.76630859e+03 5.71517188e+03 5.64839990e+03 5.64907422e+03 5.95526270e+03 5.99840430e+03 5.70538232e+03 5.73864697e+03 5.88947266e+03 5.92826562e+03 5.97670215e+03 5.93647852e+03 6.09236377e+03 6.17731885e+03 5.98974072e+03 5.94316064e+03 5.90213281e+03 6.09879346e+03 6.41726025e+03 6.37631787e+03 6.05479639e+03 5.90245068e+03 6.15068750e+03 6.52802344e+03 6.32947705e+03 5.99136865e+03 6.13263037e+03 6.35479980e+03 6.49690869e+03 6.65279150e+03 6.56052002e+03 6.23845850e+03 6.06648145e+03 6.28468457e+03 6.69575977e+03 6.70718701e+03 6.43564844e+03 6.42393652e+03 6.47974512e+03 6.63985791e+03 6.56920117e+03 6.37914795e+03 6.43666553e+03 6.42336865e+03 6.68337939e+03 6.88332861e+03 6.63989014e+03 6.60865137e+03 6.69883496e+03 6.85911035e+03 6.69191357e+03 6.34522754e+03 6.70069971e+03 7.09312207e+03 6.78234619e+03 6.45219824e+03 6.66345020e+03 7.04373828e+03 6.95978271e+03 6.78194434e+03 6.83560889e+03 6.58514111e+03 6.57622119e+03 7.00746045e+03 7.01605664e+03 6.73085742e+03 6.59559717e+03 6.54322217e+03 6.87411475e+03 7.18562744e+03 6.90578125e+03 6.70171436e+03 6.80986914e+03 6.84441504e+03 7.09138330e+03 7.10795654e+03 6.70252002e+03 6.66436035e+03 6.81896045e+03 6.85715381e+03 6.94905176e+03 6.92578809e+03 7.08873779e+03 7.00675635e+03 6.72551611e+03 6.78931885e+03 6.73394238e+03 6.96057227e+03 7.39505322e+03 7.20847998e+03 6.68971826e+03 6.74833643e+03 7.55360693e+03 9.01122363e+03 9.19102246e+03 1.26416436e+04 1.06695186e+04 1.62886494e+04 8.06232344e+04 -17693968. 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. 0. 0. 0. 0. 0. 0. 0. -99286584. 2.78277051e+04 9.92599902e+03 1.07324170e+04 1.10006348e+04 7.32247656e+03 7.78855615e+03 6.78444775e+03 6.31315625e+03 6.48226855e+03 6.52522070e+03 6.29184863e+03 6.34280713e+03 6.32759375e+03 6.25124365e+03 6.26777148e+03 6.21692334e+03 6.18916406e+03 6.17486475e+03 6.14257568e+03 6.09614600e+03 5.94288379e+03 5.88852881e+03 6.15571289e+03 6.16948291e+03 5.82870850e+03 5.80684814e+03 6.11959180e+03 6.12048633e+03 5.93789502e+03 5.88730420e+03 5.83829053e+03 5.83248291e+03 5.78196191e+03 5.73968652e+03 5.75609424e+03 5.69774414e+03 5.57962305e+03 5.53775928e+03 5.73552588e+03 5.76077197e+03 5.58091260e+03 5.53635791e+03 5.51577490e+03 5.49272949e+03 5.45628223e+03 5.41019922e+03 5.39335498e+03 5.23354688e+03 5.16738916e+03 5.30272803e+03 5.25377100e+03 5.39253027e+03 5.40427930e+03 5.18133984e+03 5.00901514e+03 4.94723730e+03 5.22668311e+03 5.24932178e+03 5.01937842e+03 4.91227734e+03 4.93428955e+03 4.94550342e+03 4.84807031e+03 4.93891016e+03 4.91754346e+03 4.64174951e+03 4.56017383e+03 4.78447754e+03 4.87034229e+03 4.68905029e+03 4.59941846e+03 4.58544482e+03 4.52132031e+03 4.42575635e+03 4.40763818e+03 4.46427246e+03 4.41479785e+03 4.30606689e+03 4.27312646e+03 4.28076709e+03 4.23562891e+03 4.29764746e+03 4.22992773e+03 4.06443945e+03 4.10218262e+03 4.05847314e+03 4.05134741e+03 4.04645215e+03 3.94329102e+03 3.89040674e+03 3.78319507e+03 3.69101685e+03 3.80776392e+03 3.76758398e+03 3.54038940e+03 3.55422510e+03 3.72604883e+03 3.78927148e+03 3.63309595e+03 3.49110083e+03 3.38551318e+03 3.33895508e+03 3.34054785e+03 3.28585059e+03 3.29287524e+03 3.23355566e+03 3.24024097e+03 3.19372559e+03 3.07072876e+03 3.07570312e+03 2.94517139e+03 2.92078125e+03 3.05155054e+03 2.96380786e+03 2.84719141e+03 2.74203760e+03 2.67593164e+03 2.78051245e+03 2.74606152e+03 2.61832227e+03 2.51314453e+03 2.47385425e+03 2.49449316e+03 2.43672095e+03 2.46075464e+03 2.43837524e+03 2.31779541e+03 2.24731128e+03 2.20442285e+03 2.20378418e+03 2.15677734e+03 2.07783496e+03 1.99656201e+03 1.95659436e+03 1.96186462e+03 1.85876770e+03 1.80882776e+03 1.86990894e+03 1.81584998e+03 1.72202539e+03 1.61934021e+03 1.56878381e+03 1.62288220e+03 1.57475867e+03 1.48314893e+03 1.39770166e+03 1.34040674e+03 1.33934741e+03 1.28988367e+03 1.24274902e+03 1.16879993e+03 1.14061169e+03 1.14894299e+03 1.07229724e+03 1.01444318e+03 9.68966492e+02 9.15215332e+02 8.54689697e+02 8.03057190e+02 7.68308594e+02 7.22852539e+02 6.77419250e+02 6.06048340e+02 5.60321045e+02 5.51357666e+02 4.82402435e+02 4.16803223e+02 3.81000397e+02 3.34146576e+02 2.96694794e+02 2.41704315e+02 1.85084869e+02 1.46046188e+02 9.80931320e+01 4.76077347e+01 -6.36467874e-01 -4.80242691e+01 -9.65625839e+01 -1.44891525e+02 -1.94714478e+02 -2.37009811e+02 -2.89005219e+02 -3.54366089e+02 -3.96947601e+02 -4.31290985e+02 -4.63870148e+02 -5.18166626e+02 -5.99773376e+02 -6.45554077e+02 -6.75271790e+02 -7.07682007e+02 -7.49877502e+02 -8.16274353e+02 -8.66927795e+02 -9.36238220e+02 -9.65509827e+02 -9.80992920e+02 -1.05531909e+03 -1.10599292e+03 -1.17387036e+03 -1.20820862e+03 -1.22632471e+03 -1.28608606e+03 -1.33081689e+03 -1.39074902e+03 -1.40029480e+03 -1.47649243e+03 -1.61880701e+03 -1.61674255e+03 -1.61895947e+03 -1.62814465e+03 -1.66012329e+03 -1.80457349e+03 -1.87013696e+03 -1.86449036e+03 -1.84380615e+03 -1.89101172e+03 -2.00650037e+03 -2.04649121e+03 -2.14667480e+03 -2.18301709e+03 -2.17444580e+03 -2.16000537e+03 -2.19223291e+03 -2.37760181e+03 -2.39921777e+03 -2.37815381e+03 -2.40871924e+03 -2.44580981e+03 -2.60803906e+03 -2.65966211e+03 -2.57414453e+03 -2.59431201e+03 -2.76553125e+03 -2.84465234e+03 -2.74279810e+03 -2.76887256e+03 -2.95923169e+03 -3.01288867e+03 -2.97515796e+03 -2.95373975e+03 -2.98446191e+03 -3.19437451e+03 -3.19928125e+03 -3.13760059e+03 -3.20622925e+03 -3.25174756e+03 -3.37288892e+03 -3.41824829e+03 -3.35338647e+03 -3.31368530e+03 -3.46138013e+03 -3.69587646e+03 -3.63926318e+03 -3.63606812e+03 -3.69471265e+03 -3.71431396e+03 -3.75401538e+03 -3.77930615e+03 -3.80093262e+03 -3.76809302e+03 -3.77541870e+03 -3.90019873e+03 -3.99022144e+03 -4.15604248e+03 -4.05731006e+03 -3.92994629e+03 -4.11507373e+03 -4.21417090e+03 -4.36279053e+03 -4.32188086e+03 -4.23087305e+03 -4.27084912e+03 -4.28839355e+03 -4.38376660e+03 -4.44637500e+03 -4.58806641e+03 -4.58152539e+03 -4.49577051e+03 -4.50150146e+03 -4.41229688e+03 -4.63300439e+03 -4.97439209e+03 -4.86971826e+03 -4.75574316e+03 -4.67893018e+03 -4.60610107e+03 -4.86842773e+03 -5.13997705e+03 -5.03956250e+03 -4.83054785e+03 -4.83724365e+03 -5.03026221e+03 -5.06597412e+03 -5.19422949e+03 -5.21781934e+03 -5.10467871e+03 -5.14384717e+03 -5.15594922e+03 -5.36820801e+03 -5.40417871e+03 -5.17001709e+03 -5.21307227e+03 -5.53076270e+03 -5.48205371e+03 -5.24990967e+03 -5.38394629e+03 -5.70139746e+03 -5.65648584e+03 -5.54526904e+03 -5.45738525e+03 -5.46564355e+03 -5.79647412e+03 -5.81338623e+03 -5.72338623e+03 -5.56608936e+03 -5.53885840e+03 -5.74855371e+03 -5.83166650e+03 -5.81686621e+03 -5.68460205e+03 -5.87262598e+03 -6.09726611e+03 -5.94318896e+03 -6.08125293e+03 -6.05829053e+03 -5.92728613e+03 -6.02771338e+03 -6.08485107e+03 -6.07882715e+03 -6.05320752e+03 -5.96846973e+03 -5.89629785e+03 -6.15887549e+03 -6.55147900e+03 -6.19140967e+03 -5.96586572e+03 -6.19292676e+03 -6.28077539e+03 -6.49177051e+03 -6.38596094e+03 -6.16655176e+03 -6.50862988e+03 -6.49487207e+03 -6.17646533e+03 -6.16639209e+03 -6.54724561e+03 -6.60254199e+03 -6.43806641e+03 -6.33353125e+03 -6.13781445e+03 -6.43518604e+03 -6.92868750e+03 -6.73236865e+03 -6.48112061e+03 -6.32949219e+03 -6.26389111e+03 -6.60562793e+03 -7.01931836e+03 -6.80523877e+03 -6.48823828e+03 -6.43075781e+03 -6.59284424e+03 -6.68252930e+03 -6.84499951e+03 -6.71019727e+03 -6.53064209e+03 -6.72509180e+03 -6.68928711e+03 -6.93506641e+03 -6.92632324e+03 -6.67826514e+03 -6.71459473e+03 -6.70083496e+03 -6.88443359e+03 -6.71053223e+03 -6.62722998e+03 -7.05712500e+03 -7.01888867e+03 -6.78993896e+03 -6.61247119e+03 -6.67714502e+03 -7.06893018e+03 -7.02797461e+03 -6.87631738e+03 -6.70594531e+03 -6.67410693e+03 -6.83853125e+03 -6.89754883e+03 -6.87708789e+03 -6.70020068e+03 -6.82672119e+03 -7.10554102e+03 -6.91583643e+03 -7.00278418e+03 -7.10116699e+03 -6.87806836e+03 -6.75375928e+03 -6.76054004e+03 -6.99941064e+03 -6.96882568e+03 -6.74102930e+03 -6.68168408e+03 -7.08294922e+03 -7.07600342e+03 -6.68214844e+03 -6.57835889e+03 -6.73643506e+03 -6.95907520e+03 -7.24107568e+03 -6.97642285e+03 -6.61896191e+03 -6.97312256e+03 -7.10439014e+03 -6.94077490e+03 -6.76643115e+03 -6.79003174e+03 -6.71214209e+03 -6.76082031e+03 -6.83747021e+03 -6.63134326e+03 -6.76655762e+03 -7.09295264e+03 -6.88080859e+03 -6.85933594e+03 -6.71763379e+03 -6.64031592e+03 -6.94060156e+03 -6.93917627e+03 -6.76429248e+03 -6.63014404e+03 -6.38307080e+03 -6.53476318e+03 -6.87686572e+03 -7.05448096e+03 -6.69760889e+03 -6.47034766e+03 -6.63152832e+03 -6.64320361e+03 -6.88945801e+03 -6.82481250e+03 -6.56512988e+03 -6.50739355e+03 -6.47921631e+03 -6.46935840e+03 -6.35080029e+03 -6.53199316e+03 -6.77834131e+03 -6.56578027e+03 -6.58509863e+03 -6.43563721e+03 -6.30820654e+03 -6.64220850e+03 -6.63540234e+03 -6.37729297e+03 -6.23890723e+03 -6.17492139e+03 -6.34988184e+03 -6.31162012e+03 -6.47689844e+03 -6.55859082e+03 -6.27549951e+03 -6.06121436e+03 -6.16621484e+03 -6.44821191e+03 -6.32378711e+03 -6.16235547e+03 -6.04327588e+03 -6.02764697e+03 -6.06697412e+03 -6.00406543e+03 -6.16478906e+03 -6.13878809e+03 -5.93745752e+03 -6.11885693e+03 -6.13892578e+03 -5.98872998e+03 -5.92222510e+03 -5.90542920e+03 -5.89049268e+03 -5.71242383e+03 -5.61108594e+03 -5.88398389e+03 -5.91656104e+03 -5.61323535e+03 -5.42375244e+03 -5.66255811e+03 -5.95356836e+03 -5.84515674e+03 -5.49764600e+03 -5.37166504e+03 -5.65790186e+03 -5.64827441e+03 -5.43593359e+03 -5.53701904e+03 -5.35576953e+03 -5.10342773e+03 -5.24449072e+03 -5.50582422e+03 -5.58128418e+03 -5.26373682e+03 -4.97762988e+03 -5.23183154e+03 -5.46945264e+03 -5.24902246e+03 -4.98658057e+03 -4.89032568e+03 -5.01721045e+03 -5.00793799e+03 -5.11293311e+03 -5.07150635e+03 -4.86996631e+03 -4.84460742e+03 -4.80690381e+03 -4.94007812e+03 -4.80236914e+03 -4.62655664e+03 -4.75524414e+03 -4.70548145e+03 -4.71811475e+03 -4.58900391e+03 -4.46509082e+03 -4.68718359e+03 -4.54136865e+03 -4.30147266e+03 -4.37150635e+03 -4.43552637e+03 -4.41732178e+03 -4.31836182e+03 -4.36578564e+03 -4.36864062e+03 -4.22485840e+03 -4.07073730e+03 -4.00334204e+03 -4.17966895e+03 -4.06242920e+03 -3.91061670e+03 -3.98528540e+03 -3.94344507e+03 -3.89067578e+03 -3.83252368e+03 -3.88946680e+03 -3.81446704e+03 -3.66615771e+03 -3.75103711e+03 -3.72108740e+03 -3.62344824e+03 -3.59880981e+03 -3.55095093e+03 -3.46135767e+03 -3.32570020e+03 -3.23303076e+03 -3.35769312e+03 -3.52615552e+03 -3.30417773e+03 -3.05673853e+03 -3.15532324e+03 -3.30598730e+03 -3.23445679e+03 -3.02232373e+03 -2.90677588e+03 -3.02012915e+03 -2.97682544e+03 -2.83507227e+03 -2.91451562e+03 -2.85687427e+03 -2.67288428e+03 -2.62184180e+03 -2.71288892e+03 -2.74293726e+03 -2.57054321e+03 -2.41934399e+03 -2.47517944e+03 -2.57369678e+03 -2.46968481e+03 -2.30731177e+03 -2.20603003e+03 -2.26178369e+03 -2.32265576e+03 -2.20275488e+03 -2.09006543e+03 -2.06409570e+03 -2.03998425e+03 -1.98538501e+03 -1.99599207e+03 -1.91398853e+03 -1.80195129e+03 -1.79568738e+03 -1.76427295e+03 -1.75512402e+03 -1.66857422e+03 -1.57797009e+03 -1.58246350e+03 -1.49732581e+03 -1.45148950e+03 -1.46464868e+03 -1.40352087e+03 -1.34625317e+03 -1.29114771e+03 -1.28893896e+03 -1.23624207e+03 -1.13323767e+03 -1.06728320e+03 -1.03358716e+03 -1.10477979e+03 -1.06783557e+03 -1.17219153e+03 -1.27118604e+03 -2.53193823e+03 -1.33733701e+04 -281374080. 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. 94908496. 9.21878320e+03 1.18080408e+03 9.94295898e+02 8.73475403e+02 8.54785583e+02 8.68706360e+02 9.18965698e+02 9.28751404e+02 9.46060120e+02 1.00729132e+03 1.05597632e+03 1.11227380e+03 1.19494202e+03 1.23274988e+03 1.23664062e+03 1.30947327e+03 1.38779749e+03 1.39633691e+03 1.42109827e+03 1.47119836e+03 1.54175977e+03 1.62874561e+03 1.67734302e+03 1.68289014e+03 1.67851575e+03 1.76547559e+03 1.87767847e+03 1.88748071e+03 1.92706250e+03 1.95856628e+03 1.99064954e+03 2.10561060e+03 2.10968481e+03 2.08925732e+03 2.16506836e+03 2.21604956e+03 2.29607227e+03 2.36052026e+03 2.34563525e+03 2.38787329e+03 2.51297168e+03 2.67586987e+03 2.65066040e+03 2.50103125e+03 2.54405688e+03 2.66185938e+03 2.75245215e+03 2.86338037e+03 2.86161157e+03 2.82691162e+03 2.93672559e+03 3.01918335e+03 2.98558398e+03 2.98975464e+03 3.02817358e+03 3.18568823e+03 3.34022803e+03 3.21426001e+03 3.14484766e+03 3.27670166e+03 3.38420483e+03 3.48055371e+03 3.47205933e+03 3.42752100e+03 3.43905713e+03 3.55184106e+03 3.77565649e+03 3.72138281e+03 3.55368994e+03 3.67354614e+03 3.79239746e+03 3.83768579e+03 3.93357910e+03 3.89787793e+03 3.82890430e+03 3.97258228e+03 4.12225000e+03 4.05965625e+03 4.02848926e+03 4.05877930e+03 4.11675439e+03 4.26821973e+03 4.41201123e+03 4.33900977e+03 4.21130566e+03 4.33666553e+03 4.47684961e+03 4.43693945e+03 4.43468750e+03 4.45622461e+03 4.57406348e+03 4.74940332e+03 4.70763525e+03 4.54433301e+03 4.56153271e+03 4.65351855e+03 4.77942773e+03 4.86680615e+03 4.81467432e+03 4.84215723e+03 4.99603906e+03 5.17954834e+03 5.07574561e+03 4.84169873e+03 4.89083496e+03 5.09061914e+03 5.18544189e+03 5.20153711e+03 5.14392236e+03 5.12795459e+03 5.30921826e+03 5.34861426e+03 5.24836621e+03 5.31716357e+03 5.38183154e+03 5.37658203e+03 5.53456006e+03 5.54645996e+03 5.42959180e+03 5.45242920e+03 5.47639111e+03 5.51371045e+03 5.71017139e+03 5.85234912e+03 5.69839648e+03 5.52634912e+03 5.69784717e+03 5.90276318e+03 5.81797705e+03 5.71613867e+03 5.71938574e+03 5.77371289e+03 5.97352930e+03 6.04994531e+03 5.88200391e+03 5.84940088e+03 5.95462549e+03 6.08397705e+03 6.09764844e+03 6.07635889e+03 6.05563330e+03 6.12113525e+03 6.23185254e+03 6.11729004e+03 6.01239844e+03 6.12663428e+03 6.19503271e+03 6.29148047e+03 6.46843213e+03 6.31220752e+03 6.11413330e+03 6.27249170e+03 6.46274902e+03 6.39143848e+03 6.36010205e+03 6.28826025e+03 6.27287549e+03 6.61237305e+03 6.69661230e+03 6.38058887e+03 6.28978955e+03 6.53085889e+03 6.72010059e+03 6.56489648e+03 6.34454785e+03 6.43401758e+03 6.68283301e+03 6.80629492e+03 6.58098193e+03 6.49886084e+03 6.62925098e+03 6.59098975e+03 6.66976953e+03 6.82993262e+03 6.67742383e+03 6.64291699e+03 6.83168213e+03 6.90268799e+03 6.67459814e+03 6.64892041e+03 6.64580029e+03 6.68744189e+03 6.81074121e+03 7.12368945e+03 7.04430078e+03 6.63773096e+03 6.75936279e+03 7.04432080e+03 6.82128174e+03 6.68901904e+03 6.73714258e+03 6.84778271e+03 7.12030420e+03 7.02809375e+03 6.73612500e+03 6.72395654e+03 6.78770508e+03 6.91565723e+03 7.02050293e+03 6.91810254e+03 6.91670996e+03 7.04839307e+03 7.12832812e+03 6.92025000e+03 6.78657422e+03 6.83637256e+03 6.86776660e+03 6.93636621e+03 7.14673486e+03 7.17277490e+03 6.81798047e+03 6.82571436e+03 7.04147461e+03 6.99986182e+03 6.88771436e+03 6.86592822e+03 6.93206396e+03 7.13875879e+03 7.11599268e+03 6.87536523e+03 6.80262695e+03 6.86018115e+03 6.90014600e+03 7.02775098e+03 6.89744971e+03 6.90650830e+03 6.99569775e+03 7.05180469e+03 7.12031006e+03 6.85294971e+03 6.76391699e+03 6.90963232e+03 6.87219434e+03 7.00826953e+03 6.91990967e+03 6.66752344e+03 6.87661133e+03 7.04880811e+03 6.84607910e+03 6.76614502e+03 6.80550928e+03 6.86598926e+03 6.86347559e+03 6.70371680e+03 6.89628955e+03 6.90369580e+03 6.71416748e+03 6.86576172e+03 6.68083740e+03 6.71322266e+03 6.87074756e+03 6.62865527e+03 6.67765186e+03 6.75690576e+03 6.64564648e+03 6.45781592e+03 6.49652539e+03 6.83244141e+03 6.92661035e+03 6.48996533e+03 6.44241064e+03 6.66596143e+03 6.61688672e+03 6.61568555e+03 6.45202344e+03 6.38996973e+03 6.49362793e+03 6.58240088e+03 6.55442139e+03 6.36953760e+03 6.33060352e+03 6.42155176e+03 6.51329883e+03 6.32129248e+03 6.16479297e+03 6.20637793e+03 6.19332959e+03 6.29951904e+03 6.47530078e+03 6.31472705e+03 6.04569873e+03 6.05517480e+03 6.27503418e+03 6.35437402e+03 6.01739941e+03 6.10723975e+03 6.23310303e+03 5.95986621e+03 5.99538428e+03 5.88247412e+03 5.91452100e+03 6.14756982e+03 5.97941406e+03 5.77694580e+03 5.97452637e+03 5.94536572e+03 5.71823926e+03 5.80535254e+03 5.85352930e+03 5.80800977e+03 5.60148340e+03 5.52945410e+03 5.70761914e+03 5.77556885e+03 5.63534082e+03 5.48608984e+03 5.46989111e+03 5.59671240e+03 5.64344971e+03 5.38270020e+03 5.31580518e+03 5.37005713e+03 5.46205615e+03 5.41329443e+03 5.19173242e+03 5.20287061e+03 5.31848096e+03 5.30007910e+03 5.14288574e+03 5.17075586e+03 5.15438525e+03 4.99743604e+03 5.15906787e+03 5.19645557e+03 4.90903223e+03 4.74071484e+03 4.80339941e+03 4.91360840e+03 4.90649658e+03 4.82032178e+03 4.68968311e+03 4.66193506e+03 4.80012305e+03 4.78691357e+03 4.56813135e+03 4.50446777e+03 4.57320557e+03 4.67534033e+03 4.51817676e+03 4.34034131e+03 4.38791504e+03 4.36922949e+03 4.32270898e+03 4.27707080e+03 4.27303662e+03 4.21835889e+03 4.10721680e+03 4.12493701e+03 4.14283154e+03 4.07056836e+03 3.92804175e+03 3.89898218e+03 3.94655591e+03 3.91676465e+03 3.82337720e+03 3.77167725e+03 3.76009546e+03 3.82717847e+03 3.78702100e+03 3.59064844e+03 3.61261670e+03 3.61072974e+03 3.54529321e+03 3.45248584e+03 3.38767383e+03 3.43650269e+03 3.38573486e+03 3.26530542e+03 3.15070605e+03 3.20455737e+03 3.26313940e+03 3.17787720e+03 3.12607446e+03 3.05370459e+03 3.03170190e+03 2.93151440e+03 2.79470801e+03 2.84875269e+03 2.86731250e+03 2.80243384e+03 2.75612061e+03 2.64367773e+03 2.60860132e+03 2.62827930e+03 2.61494019e+03 2.59210864e+03 2.47842163e+03 2.38336328e+03 2.31105371e+03 2.32789478e+03 2.35432788e+03 2.27510571e+03 2.20582275e+03 2.07137158e+03 2.06818188e+03 2.09746191e+03 2.00515210e+03 1.98211963e+03 1.90962109e+03 1.84482385e+03 1.85507019e+03 1.76262354e+03 1.69984534e+03 1.71619946e+03 1.67390015e+03 1.56668274e+03 1.48281494e+03 1.46522937e+03 1.43576001e+03 1.43191248e+03 1.41088977e+03 1.31124902e+03 1.23220459e+03 1.17128638e+03 1.15534924e+03 1.14794421e+03 1.07604614e+03 9.96640381e+02 9.35882935e+02 9.00686523e+02 8.76740356e+02 8.43858154e+02 7.87583984e+02 7.24964966e+02 6.83532959e+02 6.27350220e+02 5.60631531e+02 5.25246094e+02 4.86144501e+02 4.42359406e+02 4.00816193e+02 3.34327759e+02 2.77621155e+02 2.38508453e+02 1.96901459e+02 1.47763184e+02 9.45804062e+01 4.57248154e+01 -2.50275564e+00 -5.13495674e+01 -1.01970161e+02 -1.49745682e+02 -1.96444809e+02 -2.39299286e+02 -2.94166077e+02 -3.43051910e+02 -3.78654755e+02 -4.35299957e+02 -4.93404297e+02 -5.42412659e+02 -5.87754700e+02 -6.22293396e+02 -6.77820801e+02 -7.42332825e+02 -7.93475647e+02 -8.40527527e+02 -8.51366760e+02 -8.92071045e+02 -9.66959351e+02 -1.03943481e+03 -1.09828101e+03 -1.12468921e+03 -1.16034290e+03 -1.17614392e+03 -1.25098633e+03 -1.35056799e+03 -1.36582715e+03 -1.39914148e+03 -1.44982251e+03 -1.48483459e+03 -1.51484729e+03 -1.57591406e+03 -1.64923071e+03 -1.71025854e+03 -1.76857031e+03 -1.77295276e+03 -1.77460803e+03 -1.85768091e+03 -1.93171167e+03 -1.99077820e+03 -2.05384619e+03 -2.04868115e+03 -2.09906177e+03 -2.13746143e+03 -2.19487305e+03 -2.31009155e+03 -2.30770581e+03 -2.32800854e+03 -2.35793408e+03 -2.34870239e+03 -2.44635938e+03 -2.62403003e+03 -2.62932568e+03 -2.57845581e+03 -2.66660889e+03 -2.67950464e+03 -2.65050391e+03 -2.76980469e+03 -2.86964648e+03 -2.89820679e+03 -2.95000928e+03 -2.90399438e+03 -2.95277271e+03 -3.09245361e+03 -3.16387134e+03 -3.28036206e+03 -3.23151538e+03 -3.12296704e+03 -3.15408472e+03 -3.31725513e+03 -3.42575000e+03 -3.45298584e+03 -3.45542310e+03 -3.35772314e+03 -3.47925342e+03 -3.67463843e+03 -3.62768408e+03 -3.64121582e+03 -3.65048462e+03 -3.69322290e+03 -3.82472266e+03 -3.76999585e+03 -3.78832275e+03 -4.02673340e+03 -4.06784229e+03 -3.99958667e+03 -3.94916724e+03 -3.87639282e+03 -4.00976465e+03 -4.21135986e+03 -4.36249414e+03 -4.30594922e+03 -4.12940918e+03 -4.12175195e+03 -4.30403467e+03 -4.45961670e+03 -4.42609717e+03 -4.41795508e+03 -4.37561621e+03 -4.43399854e+03 -4.59382764e+03 -4.68095264e+03 -4.71070117e+03 -4.68010498e+03 -4.74571924e+03 -4.72982227e+03 -4.62589209e+03 -4.74956396e+03 -4.87919971e+03 -4.93205762e+03 -5.06093848e+03 -4.90909033e+03 -4.81364404e+03 -4.99249609e+03 -5.10919043e+03 -5.24634131e+03 -5.20819287e+03 -5.02516357e+03 -5.01506201e+03 -5.20293506e+03 -5.41914062e+03 -5.45292578e+03 -5.31140039e+03 -5.25939062e+03 -5.30609619e+03 -5.31036621e+03 -5.37890039e+03 -5.53836328e+03 -5.62019287e+03 -5.52734912e+03 -5.43277686e+03 -5.43641699e+03 -5.57422314e+03 -5.76252441e+03 -5.82471191e+03 -5.82431152e+03 -5.65329541e+03 -5.51123975e+03 -5.68257178e+03 -5.87049268e+03 -6.02160938e+03 -5.98396289e+03 -5.75990186e+03 -5.66299609e+03 -5.87747900e+03 -6.15731592e+03 -6.04511279e+03 -6.08497852e+03 -6.01881055e+03 -5.88070996e+03 -6.09600342e+03 -6.17237354e+03 -6.13676465e+03 -6.12606104e+03 -6.24066113e+03 -6.23994873e+03 -6.14270459e+03 -6.21495117e+03 -6.27413721e+03 -6.40027051e+03 -6.38726758e+03 -6.20539502e+03 -6.29178467e+03 -6.21426758e+03 -6.38629980e+03 -6.70704590e+03 -6.57556201e+03 -6.30449365e+03 -6.29047070e+03 -6.35688721e+03 -6.58095410e+03 -6.79121973e+03 -6.60341260e+03 -6.38706250e+03 -6.55913428e+03 -6.67341162e+03 -6.62398291e+03 -6.72108887e+03 -6.95007861e+03 -7.56592969e+03 -8.75945117e+03 -1.42817754e+04 -2.06449668e+04 -14077006. 38653256. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -20479820. 31591046. -76856240. -2.58431172e+04 -1.05352744e+04 -9.29955957e+03 -8.24848145e+03 -7.62806250e+03 -7.10853857e+03 -6.77306885e+03 -6.96608545e+03 -7.27120312e+03 -7.19295312e+03 -6.97068994e+03 -6.66479150e+03 -6.60653760e+03 -6.97584229e+03 -7.36117578e+03 -7.07833301e+03 -6.81859424e+03 -6.70135303e+03 -6.75771973e+03 -7.07779541e+03 -7.04717578e+03 -6.75230029e+03 -6.68043750e+03 -6.87024561e+03 -6.81532471e+03 -6.67305762e+03 -6.66595508e+03 -6.90490723e+03 -7.10221973e+03 -7.04813135e+03 -6.68435791e+03 -6.39958105e+03 -6.56633545e+03 -6.91262891e+03 -7.03853369e+03 -6.82044922e+03 -6.50019629e+03 -6.45004980e+03 -6.71535742e+03 -7.01604980e+03 -6.79109619e+03 -6.39895312e+03 -6.39690674e+03 -6.73895801e+03 -6.72291357e+03 -6.57680518e+03 -6.57604785e+03 -6.46021240e+03 -6.56868115e+03 -6.56984766e+03 -6.27361865e+03 -6.27270508e+03 -6.58704248e+03 -6.69871191e+03 -6.56446729e+03 -6.26403857e+03 -6.04289941e+03 -6.39097559e+03 -6.75677344e+03 -6.52596387e+03 -6.20374268e+03 -5.99926465e+03 -5.91326709e+03 -6.26060986e+03 -6.58838525e+03 -6.35928467e+03 -6.22477148e+03 -6.13060498e+03 -5.97356934e+03 -6.02788184e+03 -6.15741113e+03 -5.97796924e+03 -5.88101562e+03 -6.08384766e+03 -5.97392432e+03 -5.70700244e+03 -5.78091846e+03 -6.03651465e+03 -6.12841895e+03 -5.98318457e+03 -5.78271191e+03 -5.60484766e+03 -5.51742578e+03 -5.79997070e+03 -6.05982666e+03 -5.79503662e+03 -5.43536963e+03 -5.40287939e+03 -5.60830859e+03 -5.81260107e+03 -5.76318262e+03 -5.45606934e+03 -5.35445068e+03 -5.49452979e+03 -5.44158740e+03 -5.36883984e+03 -5.36019531e+03 -5.30218115e+03 -5.34282812e+03 -5.29044092e+03 -5.11074658e+03 -5.10896729e+03 -5.23012305e+03 -5.29831201e+03 -5.26206152e+03 -5.07781885e+03 -4.87860205e+03 -4.88090430e+03 -5.11468262e+03 -5.13665674e+03 -4.88540186e+03 -4.69228125e+03 -4.61894287e+03 -4.81520850e+03 -5.06458984e+03 -4.84995068e+03 -4.55124072e+03 -4.54459668e+03 -4.61831348e+03 -4.58360547e+03 -4.45905273e+03 -4.44035449e+03 -4.55660889e+03 -4.56417480e+03 -4.40827441e+03 -4.22755029e+03 -4.18803564e+03 -4.36578076e+03 -4.46141895e+03 -4.32662939e+03 -4.14520654e+03 -4.02504590e+03 -3.93249146e+03 -4.03485449e+03 -4.22112744e+03 -4.06220386e+03 -3.81365918e+03 -3.74943213e+03 -3.88533447e+03 -4.00843384e+03 -3.84516406e+03 -3.68745239e+03 -3.63861963e+03 -3.64710791e+03 -3.65204956e+03 -3.59712256e+03 -3.45992822e+03 -3.37420801e+03 -3.47604419e+03 -3.49643652e+03 -3.32791504e+03 -3.21807837e+03 -3.23011157e+03 -3.27741504e+03 -3.31256445e+03 -3.20788501e+03 -2.97601050e+03 -2.96002686e+03 -3.05354761e+03 -3.02399976e+03 -2.92904883e+03 -2.83536987e+03 -2.78112915e+03 -2.76639771e+03 -2.77792603e+03 -2.69247241e+03 -2.59320972e+03 -2.62954126e+03 -2.64247266e+03 -2.53455151e+03 -2.41552295e+03 -2.37235107e+03 -2.39083667e+03 -2.41818994e+03 -2.37241235e+03 -2.24804321e+03 -2.12484497e+03 -2.06237183e+03 -2.11490674e+03 -2.17545337e+03 -2.05650488e+03 -1.89664807e+03 -1.84684167e+03 -1.86981543e+03 -1.88289014e+03 -1.82601270e+03 -1.73110925e+03 -1.66170227e+03 -1.62459094e+03 -1.57062646e+03 -1.53125867e+03 -1.50388831e+03 -1.44768384e+03 -1.40630139e+03 -1.35534460e+03 -1.27575793e+03 -1.23574902e+03 -1.22293433e+03 -1.18864539e+03 -1.13474487e+03 -1.03849255e+03 -9.67630981e+02 -9.72338806e+02 -9.64002686e+02 -8.97026672e+02 -8.22745789e+02 -7.51876526e+02 -6.93244141e+02 -6.82272034e+02 -6.69452698e+02 -6.02376099e+02 -5.21233276e+02 -4.66760559e+02 -4.34821960e+02 -3.93882721e+02 -3.43942230e+02 -2.94546997e+02 -2.42986053e+02 -1.92563828e+02 -1.42369568e+02 -9.18046722e+01 -4.54686623e+01 2.29243708e+00 5.14485703e+01 1.03804733e+02 1.50753448e+02 1.87712753e+02 2.33065979e+02 2.91593231e+02 3.52509521e+02 3.98168152e+02 4.36037384e+02 4.95559418e+02 5.50907593e+02 5.75095032e+02 6.00708313e+02 6.61299561e+02 7.45597778e+02 8.18791199e+02 8.52961304e+02 8.55223877e+02 8.71823547e+02 9.38631592e+02 1.04528577e+03 1.13000818e+03 1.14929199e+03 1.12880750e+03 1.17595105e+03 1.30363721e+03 1.34441211e+03 1.32821594e+03 1.37726685e+03 1.43691223e+03 1.48507959e+03 1.58636719e+03 1.60093213e+03 1.59309778e+03 1.67380042e+03 1.68434399e+03 1.78369897e+03 1.88324841e+03 1.82495532e+03 1.90904395e+03 2.01784436e+03 2.01980579e+03 2.05777930e+03 2.10322754e+03 2.15836377e+03 2.21854956e+03 2.25081030e+03 2.22878516e+03 2.27561108e+03 2.43617969e+03 2.54763550e+03 2.53540723e+03 2.46538306e+03 2.45425098e+03 2.56113867e+03 2.72023877e+03 2.81530103e+03 2.80448901e+03 2.71526074e+03 2.77617529e+03 2.90328906e+03 2.91376733e+03 2.96738818e+03 3.01333325e+03 3.03334814e+03 3.08102930e+03 3.25022900e+03 3.20721851e+03 3.13082837e+03 3.25483862e+03 3.22365186e+03 3.40115918e+03 3.47962598e+03 3.40204272e+03 3.61986792e+03 3.54138452e+03 3.42763354e+03 3.59718994e+03 3.57142090e+03 3.66394409e+03 3.95927417e+03 3.81407031e+03 3.63395605e+03 3.73305762e+03 3.94214648e+03 4.17425830e+03 4.10874170e+03 3.91472876e+03 3.85275635e+03 3.96994556e+03 4.20751221e+03 4.39149365e+03 4.35150977e+03 4.18371191e+03 4.17206104e+03 4.31999512e+03 4.42750732e+03 4.39869287e+03 4.38232568e+03 4.45471631e+03 4.51572168e+03 4.67372705e+03 4.71301465e+03 4.54128223e+03 4.55231836e+03 4.63042578e+03 4.69638770e+03 4.80965527e+03 4.80419629e+03 4.96169971e+03 4.92229297e+03 4.75038330e+03 4.89448926e+03 4.83489941e+03 4.99569531e+03 5.36133643e+03 5.12116650e+03 4.84319141e+03 4.98664502e+03 5.26719971e+03 5.42707471e+03 5.48196826e+03 5.21613721e+03 5.02139404e+03 5.16960205e+03 5.45558496e+03 5.71159180e+03 5.57571924e+03 5.27514014e+03 5.29131641e+03 5.48636279e+03 5.61062549e+03 5.81694580e+03 5.82447266e+03 5.49445654e+03 5.46901465e+03 5.75821191e+03 5.85658008e+03 5.68582520e+03 5.65518311e+03 5.79948584e+03 5.77289258e+03 5.97571924e+03 6.06105176e+03 5.75361963e+03 5.77144727e+03 5.97362744e+03 5.97992188e+03 6.00976172e+03 5.95498682e+03 6.11614746e+03 6.27610498e+03 6.13600586e+03 5.98917139e+03 5.88945508e+03 6.14736572e+03 6.48541943e+03 6.41964062e+03 6.10625342e+03 5.95018750e+03 6.19274219e+03 6.57464404e+03 6.41588867e+03 6.10490430e+03 6.19877441e+03 6.39127393e+03 6.56536768e+03 6.75698096e+03 6.62433252e+03 6.28267822e+03 6.12549609e+03 6.33346484e+03 6.71594043e+03 6.73263721e+03 6.49924365e+03 6.53191797e+03 6.55102295e+03 6.74324707e+03 6.67744824e+03 6.54082861e+03 6.54111377e+03 6.40348438e+03 6.72168262e+03 6.94503369e+03 6.66133691e+03 6.70502197e+03 6.76363184e+03 6.88750391e+03 6.74198877e+03 6.45784619e+03 6.74274658e+03 7.08000635e+03 6.93149561e+03 6.57458301e+03 6.67260889e+03 7.06213037e+03 7.02019580e+03 6.87372559e+03 6.90678223e+03 6.64204492e+03 6.65872900e+03 7.09709570e+03 7.07011621e+03 6.79325195e+03 6.64262793e+03 6.63368359e+03 6.94802051e+03 7.24599121e+03 6.94949268e+03 6.81228223e+03 6.95265234e+03 6.89143066e+03 7.17784473e+03 7.19658350e+03 6.75907080e+03 6.74341064e+03 6.90101709e+03 6.91937109e+03 6.95047461e+03 6.94014355e+03 7.15021289e+03 7.01552100e+03 6.79838135e+03 6.85164404e+03 6.75913281e+03 7.00807861e+03 7.42636328e+03 7.19704199e+03 6.76620654e+03 6.72495117e+03 6.94688770e+03 7.06644043e+03 7.63344482e+03 7.97342139e+03 7.42510059e+03 8.55613867e+03 1.66207305e+04 1.61790359e+05 -35459156. 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. 0. 0. 0. 0. 0. 0. -99286584. -2554518. 1.22419199e+04 1.94144453e+04 1.07023027e+04 8.55853320e+03 8.63184863e+03 6.87133838e+03 6.43444189e+03 6.57114062e+03 6.49421191e+03 6.32297266e+03 6.44796582e+03 6.39857471e+03 6.29525830e+03 6.29968896e+03 6.26369189e+03 6.24143213e+03 6.21506592e+03 6.22131836e+03 6.16801172e+03 6.01319043e+03 5.99449219e+03 6.21837500e+03 6.18385645e+03 5.91087012e+03 5.88886426e+03 6.19568408e+03 6.17017627e+03 5.96277979e+03 5.92930811e+03 5.88312646e+03 5.89054297e+03 5.85648291e+03 5.81788770e+03 5.80489551e+03 5.72711768e+03 5.62235938e+03 5.60244922e+03 5.80075293e+03 5.79172754e+03 5.60862500e+03 5.60195996e+03 5.58717773e+03 5.57461133e+03 5.51074609e+03 5.47498633e+03 5.44864648e+03 5.28386670e+03 5.25200195e+03 5.31739453e+03 5.28329883e+03 5.45036572e+03 5.44686182e+03 5.26052197e+03 5.06134912e+03 4.97307617e+03 5.29399512e+03 5.31086523e+03 5.06660742e+03 4.94565039e+03 4.97220508e+03 4.93863281e+03 4.83694580e+03 5.04479199e+03 4.98490967e+03 4.65133691e+03 4.59910596e+03 4.81210840e+03 4.95020850e+03 4.78289355e+03 4.66369580e+03 4.65464258e+03 4.56059717e+03 4.49241309e+03 4.50115820e+03 4.50167871e+03 4.44812744e+03 4.32518408e+03 4.27022021e+03 4.32096973e+03 4.28266992e+03 4.33692090e+03 4.25109131e+03 4.07376538e+03 4.11342090e+03 4.09005176e+03 4.13037891e+03 4.11056982e+03 3.98295532e+03 3.92755005e+03 3.81500562e+03 3.68717627e+03 3.82935571e+03 3.84805884e+03 3.60335889e+03 3.59486011e+03 3.76044727e+03 3.80216626e+03 3.65588989e+03 3.51004321e+03 3.45549243e+03 3.42620312e+03 3.34583301e+03 3.29830981e+03 3.32083472e+03 3.26259497e+03 3.27518506e+03 3.20078320e+03 3.09006787e+03 3.10269507e+03 2.97776611e+03 2.98495020e+03 3.10469409e+03 2.99858911e+03 2.87556494e+03 2.75678320e+03 2.70140234e+03 2.81532520e+03 2.78219189e+03 2.64299854e+03 2.53185229e+03 2.49135742e+03 2.51473608e+03 2.45852954e+03 2.48093604e+03 2.46094727e+03 2.33360767e+03 2.24515747e+03 2.20931323e+03 2.24724854e+03 2.19353882e+03 2.09499512e+03 2.01164319e+03 1.96726221e+03 1.97073645e+03 1.86985815e+03 1.84391443e+03 1.91201794e+03 1.83501184e+03 1.73735449e+03 1.63743311e+03 1.58380762e+03 1.63921387e+03 1.59458203e+03 1.49890076e+03 1.40745935e+03 1.35052637e+03 1.35369519e+03 1.30523547e+03 1.25226184e+03 1.17724634e+03 1.14974695e+03 1.15072449e+03 1.07318347e+03 1.03433911e+03 9.92090210e+02 9.22608398e+02 8.52788391e+02 8.04940796e+02 7.77383911e+02 7.28580750e+02 6.82716797e+02 6.12802429e+02 5.71637146e+02 5.60482361e+02 4.86811768e+02 4.21814148e+02 3.85623932e+02 3.37795044e+02 2.97924438e+02 2.44042877e+02 1.87688187e+02 1.46845642e+02 9.89285202e+01 4.82850266e+01 -5.89477360e-01 -4.89412651e+01 -9.65504227e+01 -1.44810425e+02 -1.96171341e+02 -2.38921158e+02 -2.91808197e+02 -3.59404053e+02 -4.02515656e+02 -4.31788239e+02 -4.63001526e+02 -5.27560913e+02 -6.12697998e+02 -6.49505066e+02 -6.80384827e+02 -7.15982483e+02 -7.56524536e+02 -8.24893921e+02 -8.74341797e+02 -9.42916382e+02 -9.75547546e+02 -9.90304443e+02 -1.06547998e+03 -1.11957141e+03 -1.18629895e+03 -1.22666418e+03 -1.24966003e+03 -1.29076501e+03 -1.33074707e+03 -1.40608325e+03 -1.42060571e+03 -1.48974170e+03 -1.62394397e+03 -1.63270325e+03 -1.63898523e+03 -1.64379761e+03 -1.67958801e+03 -1.82169653e+03 -1.88333154e+03 -1.88303076e+03 -1.86788708e+03 -1.91007922e+03 -2.02249377e+03 -2.07015454e+03 -2.16835498e+03 -2.20566724e+03 -2.19810596e+03 -2.17627026e+03 -2.21576978e+03 -2.40478931e+03 -2.43462231e+03 -2.41491553e+03 -2.42109888e+03 -2.45591138e+03 -2.63005737e+03 -2.69171631e+03 -2.60029590e+03 -2.62240820e+03 -2.80557739e+03 -2.86246143e+03 -2.76310059e+03 -2.79960596e+03 -2.99033130e+03 -3.04061938e+03 -2.99682715e+03 -2.97500146e+03 -3.00718677e+03 -3.23377881e+03 -3.25926221e+03 -3.19363477e+03 -3.22966553e+03 -3.25407251e+03 -3.35280200e+03 -3.41589331e+03 -3.43086890e+03 -3.37933496e+03 -3.49447583e+03 -3.68979688e+03 -3.64344873e+03 -3.70478784e+03 -3.78010181e+03 -3.75405591e+03 -3.79601733e+03 -3.81582764e+03 -3.83232886e+03 -3.79791187e+03 -3.82769556e+03 -3.95012769e+03 -4.01670435e+03 -4.18053223e+03 -4.09003442e+03 -4.00485474e+03 -4.17497119e+03 -4.23764258e+03 -4.37458984e+03 -4.33963477e+03 -4.27227539e+03 -4.33665918e+03 -4.32978027e+03 -4.43456250e+03 -4.49294775e+03 -4.62231787e+03 -4.61447998e+03 -4.52041895e+03 -4.58064941e+03 -4.49353223e+03 -4.68782080e+03 -5.00588916e+03 -4.90750928e+03 -4.79579883e+03 -4.72287500e+03 -4.68596875e+03 -4.95421094e+03 -5.15300049e+03 -5.05561426e+03 -4.88437500e+03 -4.90058252e+03 -5.08759863e+03 -5.09783154e+03 -5.24226855e+03 -5.22163623e+03 -5.12064062e+03 -5.22703125e+03 -5.25257666e+03 -5.43648096e+03 -5.45498682e+03 -5.20521875e+03 -5.26645996e+03 -5.57370898e+03 -5.49991992e+03 -5.25407666e+03 -5.48159766e+03 -5.79000928e+03 -5.71372412e+03 -5.59660352e+03 -5.50609082e+03 -5.52959521e+03 -5.84905566e+03 -5.86645508e+03 -5.75016846e+03 -5.62630908e+03 -5.61663867e+03 -5.83004395e+03 -5.89733105e+03 -5.87578320e+03 -5.75784570e+03 -5.92343555e+03 -6.13075146e+03 -5.99401123e+03 -6.11810303e+03 -6.06206641e+03 -5.91521973e+03 -6.07720654e+03 -6.11836426e+03 -6.16320215e+03 -6.13840479e+03 -6.08459668e+03 -5.97545361e+03 -6.18994189e+03 -6.60578955e+03 -6.26462939e+03 -5.98684375e+03 -6.18136719e+03 -6.43805908e+03 -6.63051709e+03 -6.48352100e+03 -6.29282666e+03 -6.48154834e+03 -6.49022852e+03 -6.27336768e+03 -6.19873779e+03 -6.60836133e+03 -6.61547412e+03 -6.42760547e+03 -6.46522217e+03 -6.24004053e+03 -6.49114941e+03 -6.93056299e+03 -6.72310645e+03 -6.58420752e+03 -6.41555322e+03 -6.33370020e+03 -6.72596631e+03 -7.07624756e+03 -6.90930225e+03 -6.54693311e+03 -6.51967871e+03 -6.66398340e+03 -6.76095215e+03 -6.92495117e+03 -6.76728809e+03 -6.55915479e+03 -6.82120117e+03 -6.76849609e+03 -6.94622266e+03 -6.89817529e+03 -6.67843945e+03 -6.87897510e+03 -6.89354053e+03 -6.83556494e+03 -6.65370947e+03 -6.77584668e+03 -7.13478564e+03 -7.09015625e+03 -6.79067773e+03 -6.63498730e+03 -6.80794092e+03 -7.18458252e+03 -7.14855176e+03 -6.89892383e+03 -6.73251318e+03 -6.71475000e+03 -6.90756543e+03 -6.99196631e+03 -6.95226025e+03 -6.75629053e+03 -6.91993652e+03 -7.14710449e+03 -6.95400977e+03 -7.09044043e+03 -7.10468750e+03 -6.89589648e+03 -6.92430322e+03 -6.93265234e+03 -6.93364355e+03 -6.94719434e+03 -6.88442285e+03 -6.83013574e+03 -7.14587891e+03 -7.12047314e+03 -6.75333789e+03 -6.74512598e+03 -6.88305762e+03 -7.01313477e+03 -7.31246631e+03 -7.04252197e+03 -6.64569727e+03 -6.94492383e+03 -7.26564307e+03 -7.07689014e+03 -6.74953955e+03 -6.75594385e+03 -6.82743213e+03 -6.90208496e+03 -6.90134717e+03 -6.71035498e+03 -6.85820117e+03 -7.18521240e+03 -7.01757129e+03 -6.85661914e+03 -6.67756348e+03 -6.70846387e+03 -7.10096777e+03 -6.99589404e+03 -6.80301367e+03 -6.69644385e+03 -6.42843604e+03 -6.57255469e+03 -6.93829785e+03 -7.19505957e+03 -6.77350684e+03 -6.46166064e+03 -6.64090186e+03 -6.73622656e+03 -6.96875391e+03 -6.83491895e+03 -6.55426172e+03 -6.69602197e+03 -6.66750977e+03 -6.55187451e+03 -6.43756104e+03 -6.55824365e+03 -6.81110352e+03 -6.68616553e+03 -6.56177734e+03 -6.45345801e+03 -6.40012744e+03 -6.68854688e+03 -6.68282275e+03 -6.50414697e+03 -6.30851709e+03 -6.21381885e+03 -6.37687500e+03 -6.36567773e+03 -6.56994434e+03 -6.60825684e+03 -6.27732031e+03 -6.09910059e+03 -6.30793994e+03 -6.55388770e+03 -6.33943701e+03 -6.17924512e+03 -6.15874561e+03 -6.15046143e+03 -6.09199707e+03 -5.93942480e+03 -6.16556348e+03 -6.23089551e+03 -6.02360303e+03 -6.14666357e+03 -6.18767334e+03 -6.07324805e+03 -6.04487744e+03 -5.97000586e+03 -5.93307080e+03 -5.77062842e+03 -5.66953223e+03 -5.89712207e+03 -6.00608398e+03 -5.75157520e+03 -5.48708350e+03 -5.64577441e+03 -5.95680566e+03 -5.94907178e+03 -5.59399023e+03 -5.36902734e+03 -5.64121338e+03 -5.81025830e+03 -5.63406885e+03 -5.56826416e+03 -5.37152246e+03 -5.13697021e+03 -5.32377393e+03 -5.61123584e+03 -5.59977783e+03 -5.25878711e+03 -5.03366113e+03 -5.31932324e+03 -5.50980762e+03 -5.31157031e+03 -5.01750146e+03 -4.87295801e+03 -5.01128857e+03 -5.06336621e+03 -5.15942676e+03 -5.20001758e+03 -4.98827148e+03 -4.84785791e+03 -4.82057422e+03 -4.98738770e+03 -4.85387939e+03 -4.67776123e+03 -4.83293018e+03 -4.78918457e+03 -4.71957520e+03 -4.56723779e+03 -4.51969092e+03 -4.74726514e+03 -4.56954443e+03 -4.30894580e+03 -4.37434961e+03 -4.52564990e+03 -4.50141748e+03 -4.36167334e+03 -4.41645996e+03 -4.40755176e+03 -4.26007520e+03 -4.10697070e+03 -4.03847412e+03 -4.22598779e+03 -4.11184229e+03 -3.94777075e+03 -4.03706177e+03 -3.98668652e+03 -3.91517163e+03 -3.83663696e+03 -3.87916895e+03 -3.87777759e+03 -3.73803003e+03 -3.74851294e+03 -3.72594775e+03 -3.70245264e+03 -3.65446753e+03 -3.57400977e+03 -3.46842456e+03 -3.32931323e+03 -3.30560571e+03 -3.44160669e+03 -3.56368311e+03 -3.32716943e+03 -3.07704102e+03 -3.16264917e+03 -3.30832397e+03 -3.29378052e+03 -3.07624487e+03 -2.90017090e+03 -3.01330054e+03 -3.02964478e+03 -2.89162256e+03 -2.96240625e+03 -2.85744189e+03 -2.65506348e+03 -2.68621411e+03 -2.79513843e+03 -2.75684326e+03 -2.56990063e+03 -2.42828979e+03 -2.49632178e+03 -2.61081226e+03 -2.49868140e+03 -2.32322607e+03 -2.22120776e+03 -2.28688623e+03 -2.32611035e+03 -2.20942651e+03 -2.13302441e+03 -2.09508984e+03 -2.06530029e+03 -2.01198572e+03 -2.01244104e+03 -1.93363538e+03 -1.81680603e+03 -1.81213721e+03 -1.78410510e+03 -1.77529443e+03 -1.68233496e+03 -1.59169165e+03 -1.61729199e+03 -1.52255725e+03 -1.43665857e+03 -1.45248438e+03 -1.43052588e+03 -1.37799304e+03 -1.30652722e+03 -1.29317517e+03 -1.25014990e+03 -1.14817981e+03 -1.07207092e+03 -1.03016504e+03 -1.05645776e+03 -9.81149170e+02 -8.87952148e+02 -1.00033698e+03 -1.35038953e+03 -4.80988916e+03 -278286944. 0. 0. 0. 0. 0. 0. 0. 0. 263891712. -6.62446562e+04 -6.62446562e+04 -2.91143757e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -432891424. 8.82789125e+05 2.64674756e+03 1.37485706e+03 8.79393616e+02 7.64877808e+02 7.77234192e+02 7.86933777e+02 8.62010986e+02 9.16401978e+02 9.52455078e+02 1.00326691e+03 1.03993298e+03 1.05526221e+03 1.13360315e+03 1.22391565e+03 1.23385669e+03 1.26685510e+03 1.34109985e+03 1.40581042e+03 1.46325476e+03 1.46693335e+03 1.47222253e+03 1.55098267e+03 1.64218799e+03 1.69501062e+03 1.72480762e+03 1.73838440e+03 1.79526013e+03 1.90679883e+03 1.98906580e+03 1.97831580e+03 1.94123157e+03 2.01097888e+03 2.12651587e+03 2.15362817e+03 2.19562109e+03 2.25640796e+03 2.23852979e+03 2.32757446e+03 2.43311035e+03 2.38499780e+03 2.41695752e+03 2.54228223e+03 2.69096704e+03 2.75336963e+03 2.60779736e+03 2.56560327e+03 2.68604785e+03 2.84315308e+03 2.93858911e+03 2.86375830e+03 2.89822876e+03 3.04101172e+03 3.05288135e+03 3.09295923e+03 3.09409180e+03 3.04267041e+03 3.19652417e+03 3.34814697e+03 3.27619214e+03 3.30521045e+03 3.41770312e+03 3.39601855e+03 3.50237402e+03 3.58007056e+03 3.49788452e+03 3.50998535e+03 3.63000635e+03 3.79840967e+03 3.82124170e+03 3.70811450e+03 3.78028735e+03 3.81287207e+03 3.89715137e+03 4.03794873e+03 3.92378052e+03 3.92315649e+03 4.07116162e+03 4.20431787e+03 4.25637402e+03 4.15168555e+03 4.06503369e+03 4.15719873e+03 4.32486328e+03 4.41784766e+03 4.45928857e+03 4.41396875e+03 4.40164014e+03 4.53623340e+03 4.65945752e+03 4.57388867e+03 4.45891943e+03 4.57703613e+03 4.76953369e+03 4.85275195e+03 4.79424561e+03 4.70135938e+03 4.69072070e+03 4.89098389e+03 5.00831104e+03 4.87928223e+03 4.90500635e+03 5.08676660e+03 5.23603809e+03 5.25710693e+03 5.00905908e+03 4.92144629e+03 5.14302930e+03 5.26348389e+03 5.27940234e+03 5.26090918e+03 5.33528418e+03 5.46181201e+03 5.36648633e+03 5.37747607e+03 5.51374121e+03 5.44380420e+03 5.41243750e+03 5.59466699e+03 5.67072217e+03 5.70130322e+03 5.64380176e+03 5.51142871e+03 5.57444043e+03 5.78586182e+03 5.88501270e+03 5.80930859e+03 5.73929834e+03 5.80877588e+03 5.99404346e+03 6.07998438e+03 5.90794141e+03 5.73393555e+03 5.84618018e+03 6.05893457e+03 6.10766992e+03 6.05506934e+03 6.02703613e+03 6.06530029e+03 6.21551367e+03 6.29364502e+03 6.21009180e+03 6.20108496e+03 6.15198730e+03 6.24669824e+03 6.24668359e+03 6.20006299e+03 6.29098145e+03 6.34676367e+03 6.48312109e+03 6.59956543e+03 6.38028076e+03 6.26197705e+03 6.38098975e+03 6.52414014e+03 6.63550146e+03 6.60329932e+03 6.33404834e+03 6.37501074e+03 6.68614990e+03 6.86703760e+03 6.61584277e+03 6.41719336e+03 6.53520020e+03 6.79628174e+03 6.79528809e+03 6.47754883e+03 6.50847363e+03 6.77355518e+03 6.81873242e+03 6.71987354e+03 6.84489014e+03 6.86462256e+03 6.61249219e+03 6.80756348e+03 7.01800342e+03 6.73566943e+03 6.72573877e+03 6.85942773e+03 6.97777100e+03 7.04200342e+03 6.90909082e+03 6.65379297e+03 6.72856348e+03 7.00207080e+03 7.23319434e+03 7.20164551e+03 6.82270752e+03 6.87686816e+03 7.17075098e+03 7.07329736e+03 6.79238721e+03 6.82698486e+03 6.97334521e+03 7.15697998e+03 7.23137354e+03 7.18257080e+03 6.96967334e+03 6.80637305e+03 7.03532959e+03 7.20150586e+03 6.98923193e+03 7.01133301e+03 7.15896826e+03 7.22430957e+03 7.27985986e+03 7.03856494e+03 6.83904736e+03 6.96829150e+03 7.05944043e+03 7.29861230e+03 7.30051172e+03 6.96786426e+03 6.94704443e+03 7.14713135e+03 7.24407324e+03 7.21221240e+03 6.95639697e+03 6.97475293e+03 7.18327246e+03 7.22345996e+03 7.17140820e+03 6.99444531e+03 6.91481250e+03 7.07672559e+03 7.25968213e+03 7.04439355e+03 7.06205908e+03 7.16210254e+03 7.16616748e+03 7.25027637e+03 7.02278418e+03 6.85744824e+03 6.99846387e+03 7.04676660e+03 7.12937646e+03 6.93418994e+03 6.78047314e+03 7.03166211e+03 7.23163525e+03 7.10058057e+03 6.94813477e+03 6.97120312e+03 6.85487256e+03 6.87326611e+03 7.02403125e+03 7.24508447e+03 6.99358594e+03 6.77798828e+03 6.96439697e+03 6.87015771e+03 6.93182666e+03 6.88110742e+03 6.68522900e+03 6.82310254e+03 6.97501465e+03 6.69388379e+03 6.62940723e+03 6.73828076e+03 6.92896533e+03 6.97642578e+03 6.61457080e+03 6.54514307e+03 6.71156494e+03 6.75541406e+03 6.84159473e+03 6.59693066e+03 6.58599170e+03 6.50836572e+03 6.53418750e+03 6.74048242e+03 6.63773877e+03 6.39380762e+03 6.50054053e+03 6.70270801e+03 6.46510498e+03 6.37741357e+03 6.32372754e+03 6.29717188e+03 6.51513232e+03 6.58113330e+03 6.36009180e+03 6.21302881e+03 6.28308008e+03 6.37433984e+03 6.43672412e+03 6.21680957e+03 6.29075732e+03 6.31177490e+03 6.00622803e+03 6.04778320e+03 6.08595312e+03 6.07015039e+03 6.16047949e+03 6.05319922e+03 6.01239160e+03 6.13378223e+03 5.96894189e+03 5.82016064e+03 5.92088232e+03 5.99746484e+03 5.95131348e+03 5.72157959e+03 5.65236377e+03 5.89430225e+03 5.95057715e+03 5.67169287e+03 5.55389014e+03 5.61501807e+03 5.72726416e+03 5.75853027e+03 5.51480127e+03 5.48230762e+03 5.43499316e+03 5.50992578e+03 5.56916162e+03 5.33991455e+03 5.33272119e+03 5.34210107e+03 5.28183887e+03 5.32504492e+03 5.38343994e+03 5.20501123e+03 5.03229590e+03 5.25826807e+03 5.38405078e+03 5.05377490e+03 4.83036230e+03 4.90661475e+03 5.05738525e+03 5.01737305e+03 4.86888379e+03 4.78295068e+03 4.79554053e+03 4.89225293e+03 4.86435938e+03 4.69023291e+03 4.64014648e+03 4.61106250e+03 4.66757812e+03 4.63524902e+03 4.46033350e+03 4.47756152e+03 4.43466797e+03 4.38881006e+03 4.42580176e+03 4.38736426e+03 4.26092529e+03 4.18742383e+03 4.25727881e+03 4.23644043e+03 4.12223975e+03 4.03403198e+03 4.01933740e+03 4.06678076e+03 4.02839087e+03 3.85020703e+03 3.81581128e+03 3.84250049e+03 3.91380249e+03 3.88201025e+03 3.69349634e+03 3.73792065e+03 3.65760132e+03 3.48507397e+03 3.47427612e+03 3.48209277e+03 3.56104321e+03 3.48975635e+03 3.29154272e+03 3.21792065e+03 3.27847681e+03 3.33691479e+03 3.27783252e+03 3.18849512e+03 3.11277295e+03 3.03778784e+03 2.96718530e+03 2.91448193e+03 2.96666943e+03 2.95566650e+03 2.80245703e+03 2.76203687e+03 2.73691333e+03 2.71330566e+03 2.70838794e+03 2.64091260e+03 2.63368823e+03 2.52757837e+03 2.38773755e+03 2.36038452e+03 2.38975146e+03 2.40336084e+03 2.36263745e+03 2.25339307e+03 2.10403271e+03 2.09392847e+03 2.09951440e+03 2.04432727e+03 2.05532520e+03 1.99207715e+03 1.86611157e+03 1.87744446e+03 1.83628418e+03 1.74906567e+03 1.72675110e+03 1.66082788e+03 1.58962634e+03 1.53880103e+03 1.50774292e+03 1.47013293e+03 1.46239392e+03 1.44920081e+03 1.33666675e+03 1.23588770e+03 1.19545251e+03 1.17702441e+03 1.16453186e+03 1.11067444e+03 1.01344214e+03 9.54123657e+02 9.29521362e+02 9.06949036e+02 8.64973877e+02 7.92710938e+02 7.37686157e+02 6.88262085e+02 6.34978699e+02 5.82240479e+02 5.45063965e+02 5.02455414e+02 4.47822296e+02 4.00457336e+02 3.38785797e+02 2.89549255e+02 2.48117508e+02 1.98573318e+02 1.50364700e+02 9.73608322e+01 4.62572975e+01 -2.48820210e+00 -5.24008026e+01 -1.04069351e+02 -1.55249527e+02 -2.00718979e+02 -2.40071762e+02 -2.94822113e+02 -3.49380829e+02 -3.92262177e+02 -4.52366913e+02 -5.09575439e+02 -5.43224548e+02 -5.87306885e+02 -6.42829773e+02 -7.05132202e+02 -7.61603333e+02 -8.01952698e+02 -8.51969055e+02 -8.69642761e+02 -9.13215210e+02 -9.91608643e+02 -1.05173425e+03 -1.11684729e+03 -1.16001819e+03 -1.17909082e+03 -1.20316089e+03 -1.27735876e+03 -1.36908838e+03 -1.40517505e+03 -1.43279138e+03 -1.47847571e+03 -1.50048145e+03 -1.55906799e+03 -1.63963220e+03 -1.68032263e+03 -1.73654504e+03 -1.76335413e+03 -1.78714673e+03 -1.84017297e+03 -1.93556641e+03 -1.98883740e+03 -2.01686975e+03 -2.08719263e+03 -2.07274170e+03 -2.13782324e+03 -2.22066528e+03 -2.24258569e+03 -2.35071411e+03 -2.36065894e+03 -2.32724121e+03 -2.38068213e+03 -2.43127539e+03 -2.54443433e+03 -2.70740674e+03 -2.68978979e+03 -2.61384448e+03 -2.65303589e+03 -2.70404419e+03 -2.74315771e+03 -2.87682910e+03 -2.96052881e+03 -2.91466016e+03 -2.94363501e+03 -2.97681226e+03 -3.07000684e+03 -3.19656592e+03 -3.19587183e+03 -3.32159497e+03 -3.28547046e+03 -3.14947876e+03 -3.24984888e+03 -3.40880713e+03 -3.50531494e+03 -3.58618896e+03 -3.51465527e+03 -3.38241919e+03 -3.54398315e+03 -3.75996143e+03 -3.73668848e+03 -3.73097314e+03 -3.76012744e+03 -3.73280518e+03 -3.85714868e+03 -3.92321216e+03 -3.90428027e+03 -4.08473706e+03 -4.06343286e+03 -4.02829858e+03 -4.09741211e+03 -4.03866040e+03 -4.12161914e+03 -4.27283545e+03 -4.42761621e+03 -4.35181201e+03 -4.15496338e+03 -4.24939795e+03 -4.44464697e+03 -4.55816797e+03 -4.55876709e+03 -4.46635107e+03 -4.45333105e+03 -4.57940186e+03 -4.71581104e+03 -4.78052539e+03 -4.78669385e+03 -4.78004248e+03 -4.77733789e+03 -4.81477832e+03 -4.84451074e+03 -4.88242773e+03 -4.97471240e+03 -5.01213477e+03 -5.08199072e+03 -4.99487939e+03 -4.98501172e+03 -5.17408643e+03 -5.18625879e+03 -5.34215283e+03 -5.27918457e+03 -5.06493115e+03 -5.14560547e+03 -5.31365576e+03 -5.50515088e+03 -5.60755908e+03 -5.41567773e+03 -5.29119629e+03 -5.39594287e+03 -5.52225293e+03 -5.57467139e+03 -5.62264355e+03 -5.65653320e+03 -5.55250537e+03 -5.50943115e+03 -5.63531445e+03 -5.78648291e+03 -5.90717236e+03 -5.84957031e+03 -5.91387109e+03 -5.79450879e+03 -5.62969775e+03 -5.80078711e+03 -5.94898682e+03 -6.11553027e+03 -6.13494678e+03 -5.86263379e+03 -5.79416113e+03 -6.01275928e+03 -6.29958740e+03 -6.22847949e+03 -6.16319238e+03 -6.13259521e+03 -5.99256250e+03 -6.19342676e+03 -6.37146826e+03 -6.25794727e+03 -6.27305176e+03 -6.29106543e+03 -6.32915576e+03 -6.34960547e+03 -6.37620947e+03 -6.45521680e+03 -6.47220898e+03 -6.45127295e+03 -6.32984375e+03 -6.42367676e+03 -6.50434912e+03 -6.52766016e+03 -6.79006543e+03 -6.62243359e+03 -6.40042627e+03 -6.51170312e+03 -6.43654541e+03 -6.68734570e+03 -6.99644775e+03 -6.86966553e+03 -6.51100781e+03 -6.47197363e+03 -6.76269482e+03 -6.88905762e+03 -6.76468652e+03 -7.15863818e+03 -7.49419922e+03 -9.20158008e+03 -1.03443594e+04 -1.79733770e+04 -6.99361641e+04 38653256. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -59734588. -1.03065508e+05 -2.06793477e+04 -1.38177119e+04 -9.56430469e+03 -8.71972559e+03 -7.45895605e+03 -7.33872754e+03 -7.30347510e+03 -7.24594336e+03 -6.87395459e+03 -7.03237695e+03 -7.40807812e+03 -7.38523877e+03 -7.00312695e+03 -6.72635889e+03 -6.83604443e+03 -7.23084326e+03 -7.43787256e+03 -7.16028125e+03 -6.91384180e+03 -6.81155957e+03 -6.91439111e+03 -7.26672949e+03 -7.24963623e+03 -6.93839502e+03 -6.83880127e+03 -6.85785498e+03 -6.95307227e+03 -6.96580176e+03 -6.84113574e+03 -6.88722266e+03 -7.11318506e+03 -7.23419922e+03 -6.89170410e+03 -6.54200781e+03 -6.70354395e+03 -7.02512109e+03 -7.24015918e+03 -6.93722461e+03 -6.58174414e+03 -6.56701514e+03 -6.92155176e+03 -7.15467871e+03 -6.90653418e+03 -6.47371582e+03 -6.49247461e+03 -6.76435938e+03 -6.93010254e+03 -6.92700439e+03 -6.76500342e+03 -6.56769727e+03 -6.53648389e+03 -6.74847656e+03 -6.51675537e+03 -6.41650049e+03 -6.73288574e+03 -6.72974658e+03 -6.67657471e+03 -6.41371143e+03 -6.17946924e+03 -6.50474902e+03 -6.86363037e+03 -6.65861914e+03 -6.24289648e+03 -6.04778027e+03 -6.14422559e+03 -6.49869385e+03 -6.68916846e+03 -6.46957422e+03 -6.32277832e+03 -6.20733887e+03 -6.02318652e+03 -6.16839355e+03 -6.35178809e+03 -6.13050098e+03 -6.08836523e+03 -6.11358740e+03 -6.15534766e+03 -5.99891016e+03 -5.90416846e+03 -6.07454834e+03 -6.16760498e+03 -6.12941064e+03 -5.93081592e+03 -5.65699072e+03 -5.65947559e+03 -5.95786182e+03 -6.18852051e+03 -5.89863477e+03 -5.50766504e+03 -5.55101172e+03 -5.72662988e+03 -5.85524902e+03 -5.85777539e+03 -5.61327295e+03 -5.52610254e+03 -5.50846924e+03 -5.55443115e+03 -5.60261426e+03 -5.47301562e+03 -5.41007373e+03 -5.36480371e+03 -5.38996875e+03 -5.37383984e+03 -5.26577148e+03 -5.30354688e+03 -5.32812158e+03 -5.35682080e+03 -5.17707324e+03 -4.91875244e+03 -4.98855420e+03 -5.20921924e+03 -5.28922314e+03 -5.01681055e+03 -4.73512354e+03 -4.72175146e+03 -4.96863135e+03 -5.19862939e+03 -4.92456982e+03 -4.63230664e+03 -4.69267383e+03 -4.65670361e+03 -4.65741846e+03 -4.67306787e+03 -4.57005518e+03 -4.61491064e+03 -4.53980029e+03 -4.47877539e+03 -4.45035986e+03 -4.30714990e+03 -4.38025879e+03 -4.50483984e+03 -4.43673145e+03 -4.23687598e+03 -4.07645337e+03 -4.04704297e+03 -4.17036670e+03 -4.30836865e+03 -4.09587402e+03 -3.83572510e+03 -3.86093091e+03 -4.01445117e+03 -4.08917944e+03 -3.89286060e+03 -3.74615747e+03 -3.73095190e+03 -3.67664966e+03 -3.70932031e+03 -3.70653125e+03 -3.51232788e+03 -3.45697363e+03 -3.53472266e+03 -3.54630200e+03 -3.46019189e+03 -3.33499414e+03 -3.31268799e+03 -3.31822461e+03 -3.36139233e+03 -3.24823462e+03 -3.02356445e+03 -3.02938354e+03 -3.08895581e+03 -3.08522290e+03 -3.02918140e+03 -2.88764160e+03 -2.82459741e+03 -2.82707031e+03 -2.85302783e+03 -2.79682666e+03 -2.67565552e+03 -2.66149707e+03 -2.63274561e+03 -2.58322876e+03 -2.51551050e+03 -2.42543604e+03 -2.42153223e+03 -2.44893481e+03 -2.43376758e+03 -2.29900928e+03 -2.14638574e+03 -2.12495947e+03 -2.17827930e+03 -2.20922583e+03 -2.07754541e+03 -1.92479407e+03 -1.90270374e+03 -1.90638037e+03 -1.90246118e+03 -1.86477759e+03 -1.75122925e+03 -1.68442603e+03 -1.66494507e+03 -1.63339392e+03 -1.58709558e+03 -1.52605835e+03 -1.47884326e+03 -1.41405859e+03 -1.38091187e+03 -1.33827771e+03 -1.27139648e+03 -1.23390674e+03 -1.19181982e+03 -1.15334131e+03 -1.06243579e+03 -9.91356995e+02 -9.87255249e+02 -9.73850342e+02 -9.28398682e+02 -8.41975891e+02 -7.57842773e+02 -7.13098389e+02 -7.03605103e+02 -6.85059143e+02 -6.14556030e+02 -5.37298950e+02 -4.77286865e+02 -4.31039001e+02 -3.98981903e+02 -3.59092285e+02 -3.03176575e+02 -2.47884140e+02 -1.96534088e+02 -1.46161377e+02 -9.46343384e+01 -4.65694733e+01 2.17322350e+00 5.20429611e+01 1.04253708e+02 1.53046997e+02 1.90502075e+02 2.42585693e+02 3.02029449e+02 3.53086182e+02 4.03693726e+02 4.48557495e+02 5.06265747e+02 5.60216125e+02 5.86995422e+02 6.14130493e+02 6.74266174e+02 7.61242676e+02 8.36902954e+02 8.71243530e+02 8.73040955e+02 8.94201355e+02 9.61874634e+02 1.06465991e+03 1.14483081e+03 1.17216882e+03 1.15573218e+03 1.20071558e+03 1.32695947e+03 1.37273193e+03 1.35200916e+03 1.39611353e+03 1.47742896e+03 1.52624426e+03 1.62113953e+03 1.63269592e+03 1.62263574e+03 1.71106140e+03 1.72158936e+03 1.81371143e+03 1.92356519e+03 1.87156165e+03 1.94620178e+03 2.06077246e+03 2.06607983e+03 2.10480151e+03 2.13850684e+03 2.20146997e+03 2.27988037e+03 2.29507373e+03 2.26258447e+03 2.33331177e+03 2.49491040e+03 2.58514160e+03 2.57864209e+03 2.53054565e+03 2.51561108e+03 2.60498193e+03 2.76994116e+03 2.88064453e+03 2.88016406e+03 2.77339380e+03 2.81706909e+03 2.97849683e+03 2.99720605e+03 3.00931421e+03 3.05946118e+03 3.10260327e+03 3.14576392e+03 3.30769849e+03 3.28384937e+03 3.19997412e+03 3.30320142e+03 3.27242603e+03 3.45565283e+03 3.59021143e+03 3.49307935e+03 3.66610083e+03 3.62749390e+03 3.51214282e+03 3.66334229e+03 3.64263867e+03 3.75432031e+03 4.03726123e+03 3.87962036e+03 3.72026807e+03 3.83638477e+03 4.02505127e+03 4.23190430e+03 4.17139600e+03 4.00336499e+03 3.92853857e+03 4.02891382e+03 4.30564111e+03 4.51325195e+03 4.44267188e+03 4.25388477e+03 4.24513525e+03 4.44706250e+03 4.55147119e+03 4.44681982e+03 4.43616357e+03 4.55562842e+03 4.61314014e+03 4.76699902e+03 4.81573877e+03 4.67076025e+03 4.69182080e+03 4.69971973e+03 4.76249121e+03 4.90796094e+03 4.90491309e+03 5.07097705e+03 5.01884570e+03 4.85108691e+03 5.00871582e+03 4.93250586e+03 5.10596338e+03 5.47361426e+03 5.22384961e+03 4.91640234e+03 5.05844336e+03 5.38275391e+03 5.54166797e+03 5.58440723e+03 5.35627441e+03 5.14705908e+03 5.26183057e+03 5.57570264e+03 5.88894434e+03 5.70715332e+03 5.38579590e+03 5.35642139e+03 5.58079492e+03 5.75247754e+03 5.92990039e+03 5.92407812e+03 5.62129541e+03 5.58412842e+03 5.81993262e+03 5.95402734e+03 5.90883740e+03 5.90152930e+03 5.84082910e+03 5.83853613e+03 6.11404346e+03 6.18099463e+03 5.89267969e+03 5.90597852e+03 6.09124023e+03 6.09723828e+03 6.15597266e+03 6.11999756e+03 6.28179785e+03 6.35830957e+03 6.18051660e+03 6.09401855e+03 6.06566553e+03 6.30075928e+03 6.63745557e+03 6.53955469e+03 6.24108789e+03 6.08097461e+03 6.36126611e+03 6.73377197e+03 6.48571289e+03 6.19488330e+03 6.33669922e+03 6.51588330e+03 6.67856445e+03 6.88758301e+03 6.81299365e+03 6.42795020e+03 6.26758936e+03 6.50202441e+03 6.87801562e+03 6.89833887e+03 6.68090625e+03 6.61912646e+03 6.67988281e+03 6.82294873e+03 6.75682520e+03 6.61764551e+03 6.64298096e+03 6.59643066e+03 6.87324219e+03 7.10177588e+03 6.81112109e+03 6.82942676e+03 6.90426514e+03 7.07005273e+03 6.89553076e+03 6.58192529e+03 6.93204492e+03 7.32104053e+03 7.02365576e+03 6.67804541e+03 6.85808350e+03 7.25137695e+03 7.18993066e+03 7.01197168e+03 7.05131689e+03 6.80741309e+03 6.80377002e+03 7.21267285e+03 7.19166162e+03 6.93670996e+03 6.78643457e+03 6.77697217e+03 7.10675195e+03 7.41488867e+03 7.14992090e+03 6.94536914e+03 7.05263672e+03 7.06841455e+03 7.35214502e+03 7.35041455e+03 6.92568750e+03 6.89015430e+03 7.02653320e+03 7.09575391e+03 7.15959424e+03 7.14243164e+03 7.28577051e+03 7.22097461e+03 6.98867334e+03 6.95038379e+03 6.84502295e+03 7.11282666e+03 7.55412305e+03 7.35554785e+03 6.93456348e+03 6.87745312e+03 7.11230859e+03 7.16687695e+03 7.90474658e+03 8.17160352e+03 7.41129248e+03 9.12690820e+03 1.48466367e+04 1.56483938e+05 -35459156. 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. 0. 0. 0. 0. 0. 0. 21068432. 2.24740176e+04 6.61003418e+03 9.16948047e+03 7.14927930e+03 6.93711475e+03 6.75155078e+03 6.49505469e+03 6.41729492e+03 6.65317383e+03 6.67189307e+03 6.50609277e+03 6.54766504e+03 6.50644043e+03 6.43898340e+03 6.46125684e+03 6.41429395e+03 6.35572363e+03 6.35696826e+03 6.36625049e+03 6.29210840e+03 6.11879736e+03 6.06697510e+03 6.36636719e+03 6.35888428e+03 6.00940674e+03 5.97112207e+03 6.29118799e+03 6.30596045e+03 6.10374365e+03 6.05972900e+03 6.03608545e+03 5.99874121e+03 5.96746826e+03 5.93702930e+03 5.90936035e+03 5.87508984e+03 5.74246631e+03 5.69127002e+03 5.93215820e+03 5.92573682e+03 5.73129736e+03 5.71120166e+03 5.67813037e+03 5.66211230e+03 5.62690381e+03 5.56345654e+03 5.57848340e+03 5.38939600e+03 5.32391455e+03 5.46906641e+03 5.41944238e+03 5.55240234e+03 5.57640332e+03 5.34544141e+03 5.16160059e+03 5.11193457e+03 5.40338428e+03 5.42781445e+03 5.17318896e+03 5.06425781e+03 5.08661133e+03 5.08144043e+03 4.99573535e+03 5.10317139e+03 5.06316602e+03 4.77306592e+03 4.70408936e+03 4.92056836e+03 5.01317334e+03 4.84371436e+03 4.74971680e+03 4.73373682e+03 4.67458154e+03 4.56084033e+03 4.53421777e+03 4.59905322e+03 4.56071631e+03 4.43426953e+03 4.39732812e+03 4.41200098e+03 4.35673975e+03 4.43595752e+03 4.37753613e+03 4.19579199e+03 4.22579883e+03 4.18057715e+03 4.18404492e+03 4.17184521e+03 4.05424927e+03 4.00993506e+03 3.90685425e+03 3.80634863e+03 3.92260400e+03 3.88724609e+03 3.65398657e+03 3.66738940e+03 3.84358643e+03 3.90269141e+03 3.73188257e+03 3.59884253e+03 3.49152271e+03 3.44173535e+03 3.43562207e+03 3.38642920e+03 3.38942871e+03 3.33796899e+03 3.34784277e+03 3.28418091e+03 3.16271362e+03 3.17507764e+03 3.04508813e+03 3.00866455e+03 3.13928516e+03 3.06031738e+03 2.93637524e+03 2.82444067e+03 2.76406348e+03 2.87253027e+03 2.83838770e+03 2.69613916e+03 2.58440356e+03 2.54316455e+03 2.56993652e+03 2.51597900e+03 2.53547925e+03 2.51039380e+03 2.38759058e+03 2.31236548e+03 2.27325464e+03 2.27730859e+03 2.22047241e+03 2.14071167e+03 2.06331714e+03 2.02055688e+03 2.02111377e+03 1.91569031e+03 1.86809241e+03 1.92642334e+03 1.86884888e+03 1.77479175e+03 1.66907239e+03 1.61805042e+03 1.67297766e+03 1.62109387e+03 1.53064575e+03 1.44050134e+03 1.38280957e+03 1.38284790e+03 1.32867993e+03 1.27932031e+03 1.20623975e+03 1.17822949e+03 1.18363696e+03 1.10413965e+03 1.04653601e+03 1.00063245e+03 9.43072693e+02 8.80295410e+02 8.27453613e+02 7.92317688e+02 7.45679138e+02 6.98053223e+02 6.24990112e+02 5.78694092e+02 5.67585266e+02 4.96877441e+02 4.29897430e+02 3.92991486e+02 3.44943756e+02 3.05459015e+02 2.49062576e+02 1.90881088e+02 1.50523087e+02 1.01340988e+02 4.90208359e+01 -7.29663968e-01 -4.96423454e+01 -9.97276917e+01 -1.49837357e+02 -2.00566803e+02 -2.43965286e+02 -2.98155243e+02 -3.65038513e+02 -4.09476776e+02 -4.45220886e+02 -4.78416901e+02 -5.34058289e+02 -6.19337524e+02 -6.64447205e+02 -6.95666504e+02 -7.30926636e+02 -7.72907104e+02 -8.39978943e+02 -8.91509521e+02 -9.66093872e+02 -9.95173340e+02 -1.01080560e+03 -1.08751855e+03 -1.14207593e+03 -1.21254944e+03 -1.24367859e+03 -1.26204138e+03 -1.32657581e+03 -1.37073596e+03 -1.43398328e+03 -1.44598755e+03 -1.52201685e+03 -1.66603137e+03 -1.66376538e+03 -1.67227014e+03 -1.68033484e+03 -1.70830261e+03 -1.86178552e+03 -1.93117651e+03 -1.92266357e+03 -1.90419519e+03 -1.94755566e+03 -2.06451001e+03 -2.11007617e+03 -2.21204858e+03 -2.24926855e+03 -2.24425000e+03 -2.22994360e+03 -2.25963574e+03 -2.45136035e+03 -2.47638940e+03 -2.45133740e+03 -2.48238452e+03 -2.52177930e+03 -2.68382788e+03 -2.73972510e+03 -2.65471948e+03 -2.67809009e+03 -2.85228638e+03 -2.92774756e+03 -2.82793335e+03 -2.85583301e+03 -3.04917139e+03 -3.10493457e+03 -3.06491382e+03 -3.04981982e+03 -3.08010181e+03 -3.28926733e+03 -3.29738354e+03 -3.23419653e+03 -3.31005127e+03 -3.34965576e+03 -3.47633813e+03 -3.51535181e+03 -3.46133960e+03 -3.41162158e+03 -3.56883374e+03 -3.82170215e+03 -3.75008301e+03 -3.73381396e+03 -3.82177246e+03 -3.83136670e+03 -3.87242603e+03 -3.90072534e+03 -3.91671729e+03 -3.87500098e+03 -3.89255005e+03 -4.03179639e+03 -4.12029883e+03 -4.27036865e+03 -4.18886572e+03 -4.07477637e+03 -4.22605615e+03 -4.35204395e+03 -4.49491943e+03 -4.43821143e+03 -4.35415283e+03 -4.41772119e+03 -4.42262646e+03 -4.51755029e+03 -4.57410547e+03 -4.71623340e+03 -4.73829785e+03 -4.65239258e+03 -4.64208545e+03 -4.55745508e+03 -4.76929199e+03 -5.10866553e+03 -5.01944092e+03 -4.91498682e+03 -4.83157471e+03 -4.74739648e+03 -5.02061182e+03 -5.29334229e+03 -5.18730713e+03 -4.98705713e+03 -4.98898242e+03 -5.16877539e+03 -5.22055762e+03 -5.38173340e+03 -5.39277393e+03 -5.27751123e+03 -5.27542529e+03 -5.30073535e+03 -5.54979688e+03 -5.57091846e+03 -5.31974463e+03 -5.36341602e+03 -5.69410693e+03 -5.63802344e+03 -5.41313477e+03 -5.54928760e+03 -5.88830713e+03 -5.82829248e+03 -5.70714062e+03 -5.61801904e+03 -5.64337354e+03 -5.97117188e+03 -6.00664551e+03 -5.89297266e+03 -5.75567432e+03 -5.72360986e+03 -5.94750195e+03 -6.00892969e+03 -5.99170215e+03 -5.87063525e+03 -6.03626660e+03 -6.29116357e+03 -6.11967480e+03 -6.27141895e+03 -6.25471729e+03 -6.07959863e+03 -6.20718506e+03 -6.26607471e+03 -6.26706055e+03 -6.25651709e+03 -6.16051025e+03 -6.06111035e+03 -6.33577588e+03 -6.75047559e+03 -6.43018213e+03 -6.12412939e+03 -6.35648486e+03 -6.49288672e+03 -6.70895996e+03 -6.57635693e+03 -6.37749414e+03 -6.66525537e+03 -6.68344092e+03 -6.39808740e+03 -6.33573926e+03 -6.73015234e+03 -6.79492578e+03 -6.62813232e+03 -6.53081543e+03 -6.29240674e+03 -6.63735059e+03 -7.14040479e+03 -6.89857373e+03 -6.71045850e+03 -6.55918164e+03 -6.42565869e+03 -6.81954932e+03 -7.19752783e+03 -7.03063867e+03 -6.68001611e+03 -6.63567773e+03 -6.81344434e+03 -6.89083740e+03 -7.10579932e+03 -6.91200439e+03 -6.72834375e+03 -6.94237842e+03 -6.87916064e+03 -7.14193262e+03 -7.12579834e+03 -6.86441455e+03 -6.91377588e+03 -6.96322070e+03 -7.09346729e+03 -6.90906152e+03 -6.85986572e+03 -7.21582178e+03 -7.19774805e+03 -6.96998193e+03 -6.82352002e+03 -6.91088672e+03 -7.29357275e+03 -7.29740576e+03 -7.06365332e+03 -6.91590723e+03 -6.85085840e+03 -7.04936768e+03 -7.07961279e+03 -7.09576904e+03 -6.91872021e+03 -7.04211523e+03 -7.34571436e+03 -7.10433691e+03 -7.25126318e+03 -7.32101904e+03 -7.07511426e+03 -7.01345508e+03 -6.97984717e+03 -7.16608057e+03 -7.20816455e+03 -6.93085254e+03 -6.91630469e+03 -7.32672266e+03 -7.37326123e+03 -6.91013867e+03 -6.78910352e+03 -6.96241211e+03 -7.20724902e+03 -7.44824707e+03 -7.17868213e+03 -6.84261719e+03 -7.15207471e+03 -7.35977100e+03 -7.13844922e+03 -6.97967969e+03 -6.99827930e+03 -6.92511133e+03 -6.96912451e+03 -7.03813086e+03 -6.81608496e+03 -7.02225244e+03 -7.35303271e+03 -7.08882275e+03 -7.10035645e+03 -6.94621338e+03 -6.83860059e+03 -7.15561914e+03 -7.12901025e+03 -6.97512012e+03 -6.83322656e+03 -6.60486670e+03 -6.73680908e+03 -7.06280518e+03 -7.33834814e+03 -6.90530908e+03 -6.66096289e+03 -6.80734717e+03 -6.88582080e+03 -7.05977197e+03 -7.04511328e+03 -6.77884619e+03 -6.75129248e+03 -6.68839258e+03 -6.71319238e+03 -6.55689502e+03 -6.69234717e+03 -6.94196191e+03 -6.75496777e+03 -6.81316211e+03 -6.64773779e+03 -6.50050244e+03 -6.84551465e+03 -6.85069238e+03 -6.58504248e+03 -6.41104150e+03 -6.36016602e+03 -6.51435693e+03 -6.50383887e+03 -6.67679736e+03 -6.74606055e+03 -6.45272119e+03 -6.28870117e+03 -6.35246826e+03 -6.61685107e+03 -6.50965137e+03 -6.35717432e+03 -6.24138770e+03 -6.21081738e+03 -6.28642236e+03 -6.18678809e+03 -6.34412744e+03 -6.34164990e+03 -6.11232764e+03 -6.28601270e+03 -6.34594629e+03 -6.16095264e+03 -6.12545312e+03 -6.09770801e+03 -6.07099170e+03 -5.86978711e+03 -5.77749023e+03 -6.07622803e+03 -6.12712891e+03 -5.80131055e+03 -5.57121582e+03 -5.82931934e+03 -6.17011963e+03 -6.02134082e+03 -5.65511426e+03 -5.51294580e+03 -5.81536816e+03 -5.83156445e+03 -5.60803174e+03 -5.72231836e+03 -5.55890039e+03 -5.26738867e+03 -5.40219043e+03 -5.66836523e+03 -5.75147168e+03 -5.41916699e+03 -5.11932764e+03 -5.39284668e+03 -5.63843555e+03 -5.43695703e+03 -5.15413721e+03 -5.05551025e+03 -5.16296484e+03 -5.16086572e+03 -5.27817578e+03 -5.21539307e+03 -5.01092188e+03 -4.99592480e+03 -4.97017383e+03 -5.07986133e+03 -4.96029346e+03 -4.77278564e+03 -4.89831152e+03 -4.84800879e+03 -4.85151465e+03 -4.73228125e+03 -4.60897607e+03 -4.84198926e+03 -4.68403906e+03 -4.43139600e+03 -4.48725977e+03 -4.56950146e+03 -4.56275391e+03 -4.45110205e+03 -4.49699023e+03 -4.49404150e+03 -4.35911035e+03 -4.20823535e+03 -4.12262158e+03 -4.30346533e+03 -4.18867432e+03 -4.03810327e+03 -4.11308105e+03 -4.06282886e+03 -4.01698901e+03 -3.95544800e+03 -4.00660986e+03 -3.92991406e+03 -3.77180469e+03 -3.86037085e+03 -3.84178906e+03 -3.75122119e+03 -3.70469678e+03 -3.64220581e+03 -3.56324878e+03 -3.43309326e+03 -3.34094946e+03 -3.47512842e+03 -3.63272461e+03 -3.38986426e+03 -3.15084619e+03 -3.25179492e+03 -3.40928955e+03 -3.33349121e+03 -3.10966138e+03 -2.99210620e+03 -3.11098120e+03 -3.06437524e+03 -2.92943262e+03 -3.01158447e+03 -2.93425366e+03 -2.75434863e+03 -2.70873267e+03 -2.79737207e+03 -2.83004077e+03 -2.64524194e+03 -2.48836792e+03 -2.54885034e+03 -2.65823071e+03 -2.55315405e+03 -2.38146338e+03 -2.27384131e+03 -2.32995386e+03 -2.39065552e+03 -2.26909302e+03 -2.15156494e+03 -2.12817847e+03 -2.10966431e+03 -2.05001929e+03 -2.05761743e+03 -1.96981006e+03 -1.85439868e+03 -1.85292090e+03 -1.82041687e+03 -1.80680457e+03 -1.71877051e+03 -1.62632556e+03 -1.62714636e+03 -1.54517395e+03 -1.49913818e+03 -1.50539624e+03 -1.44376672e+03 -1.38881104e+03 -1.33067761e+03 -1.32165955e+03 -1.27754724e+03 -1.17942786e+03 -1.09877002e+03 -1.05512646e+03 -1.07488989e+03 -9.98079529e+02 -9.51977905e+02 -1.13141565e+03 -2.05281592e+03 -7.55900244e+03 430693024. 0. 0. 0. 0. -812645376. -3.29115562e+05 6.50518688e+05 1.07055766e+05 -5.01078522e+02 -1.66338110e+03 -5.04398584e+03 -2.91143757e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -432891424. 8.82789125e+05 6.19429938e+05 2.22280859e+03 1.50225720e+03 7.84663757e+02 8.52851562e+02 8.05383240e+02 8.72021667e+02 9.40140808e+02 9.47127197e+02 9.72956360e+02 1.04017297e+03 1.08367834e+03 1.14217212e+03 1.23360730e+03 1.26780481e+03 1.26708289e+03 1.33932983e+03 1.42220300e+03 1.43969641e+03 1.46872742e+03 1.51538208e+03 1.58555835e+03 1.67302698e+03 1.71962280e+03 1.71847668e+03 1.71777454e+03 1.81571973e+03 1.92440869e+03 1.93384375e+03 1.98526001e+03 2.01992603e+03 2.04143542e+03 2.15336206e+03 2.16618726e+03 2.14508887e+03 2.22116870e+03 2.26935059e+03 2.35520728e+03 2.43224585e+03 2.41483325e+03 2.44843066e+03 2.57292139e+03 2.74720093e+03 2.72347559e+03 2.56583008e+03 2.60802881e+03 2.73470215e+03 2.83440015e+03 2.94534180e+03 2.93005127e+03 2.89454688e+03 3.01845776e+03 3.09358667e+03 3.05960620e+03 3.08533447e+03 3.11881006e+03 3.26562891e+03 3.43204321e+03 3.30106323e+03 3.23511230e+03 3.36424292e+03 3.47309155e+03 3.57677002e+03 3.56976221e+03 3.51349341e+03 3.53570239e+03 3.66269067e+03 3.87150854e+03 3.81740918e+03 3.64926001e+03 3.77235864e+03 3.90114429e+03 3.93329199e+03 4.03435840e+03 4.00625024e+03 3.93802051e+03 4.06552026e+03 4.24745264e+03 4.19281250e+03 4.13580176e+03 4.15942139e+03 4.22849121e+03 4.38141797e+03 4.51172314e+03 4.44649854e+03 4.33989990e+03 4.44594092e+03 4.59969482e+03 4.57110352e+03 4.54489648e+03 4.56555225e+03 4.68905713e+03 4.87847461e+03 4.81982812e+03 4.67715479e+03 4.69954150e+03 4.79248438e+03 4.91595166e+03 4.99100049e+03 4.95179248e+03 4.97000635e+03 5.12661914e+03 5.30658496e+03 5.21732959e+03 4.96459082e+03 5.03487500e+03 5.24002197e+03 5.31242578e+03 5.35229199e+03 5.27702930e+03 5.24459033e+03 5.44565039e+03 5.50539453e+03 5.38886230e+03 5.47029785e+03 5.52312354e+03 5.51020605e+03 5.68359131e+03 5.69833301e+03 5.53606055e+03 5.61351904e+03 5.66434912e+03 5.64346777e+03 5.86831982e+03 6.01261768e+03 5.83259277e+03 5.67042139e+03 5.84144971e+03 6.04030029e+03 5.97784326e+03 5.89956885e+03 5.87136230e+03 5.92323975e+03 6.13481982e+03 6.22291406e+03 6.04182275e+03 6.01613818e+03 6.10226318e+03 6.22102051e+03 6.28480469e+03 6.23836230e+03 6.22519580e+03 6.31051416e+03 6.40314258e+03 6.25171436e+03 6.15110547e+03 6.33250146e+03 6.37691650e+03 6.46784326e+03 6.64135938e+03 6.48493799e+03 6.29307275e+03 6.46265576e+03 6.65833154e+03 6.59616895e+03 6.53691406e+03 6.43834473e+03 6.47496680e+03 6.80572852e+03 6.86124316e+03 6.52867139e+03 6.48572168e+03 6.72334277e+03 6.87823535e+03 6.70314502e+03 6.51550781e+03 6.62818262e+03 6.84988037e+03 7.00274756e+03 6.76043945e+03 6.65843896e+03 6.77893164e+03 6.76512207e+03 6.84745361e+03 6.99974072e+03 6.86763965e+03 6.80462354e+03 6.96596680e+03 7.08641455e+03 6.86926611e+03 6.82403223e+03 6.84594922e+03 6.87542139e+03 7.01405518e+03 7.28513477e+03 7.21382422e+03 6.84488086e+03 6.92942090e+03 7.19872314e+03 6.95980469e+03 6.86531396e+03 6.91012988e+03 7.00142285e+03 7.26869043e+03 7.25324121e+03 6.97977783e+03 6885. 6.98055908e+03 7.13126025e+03 7.18389160e+03 7.04819971e+03 7.09873096e+03 7.24260645e+03 7.27211328e+03 7.11766064e+03 7.02662061e+03 7.04400537e+03 7.06452490e+03 7.15598633e+03 7.33204590e+03 7.32667188e+03 6.99219287e+03 7.06214160e+03 7.22821045e+03 7.11820215e+03 7.15551709e+03 7.06430176e+03 7.11192041e+03 7.36843164e+03 7.27515479e+03 7.07180273e+03 7.00835889e+03 7.03062158e+03 7.15032666e+03 7.23762305e+03 7.12486963e+03 7.05742578e+03 7.16024561e+03 7.25877539e+03 7.29178076e+03 7.03659180e+03 6.88399072e+03 7.05773242e+03 7.06936230e+03 7.21239990e+03 7.10928955e+03 6.86302002e+03 7.03227686e+03 7.22530762e+03 7.03928613e+03 6.95936475e+03 7.02293018e+03 7.01577441e+03 7.07536963e+03 6.91240723e+03 7.09978906e+03 7.07144043e+03 6.89048584e+03 7.04774219e+03 6.87852051e+03 6.87726318e+03 7.06901758e+03 6.82550537e+03 6.85673242e+03 6.95957227e+03 6.82057178e+03 6.63328076e+03 6.69415381e+03 6.99546631e+03 7.03127393e+03 6.68824902e+03 6.63156152e+03 6.78322559e+03 6.78313721e+03 6.79519678e+03 6.59327148e+03 6.59976660e+03 6.65627295e+03 6.76081543e+03 6.68791504e+03 6.55586621e+03 6.55177441e+03 6.55612695e+03 6.66295557e+03 6.48726758e+03 6.33199512e+03 6.39779834e+03 6.37459912e+03 6.46197998e+03 6.62891895e+03 6.49027637e+03 6.20263672e+03 6.21089990e+03 6.48091113e+03 6.52873975e+03 6.16128369e+03 6.26279199e+03 6.40778027e+03 6.11921094e+03 6.13374512e+03 6.04850244e+03 6.05423340e+03 6.29430664e+03 6.13282227e+03 5.94071387e+03 6.12482129e+03 6.11723193e+03 5.86960596e+03 5.93700293e+03 6.01671387e+03 5.98602783e+03 5.78048438e+03 5.67971924e+03 5.83231201e+03 5.95251270e+03 5.80460547e+03 5.60292725e+03 5.60770068e+03 5.75549756e+03 5.79253613e+03 5.51419385e+03 5.46295410e+03 5.51487061e+03 5.59764502e+03 5.56773584e+03 5.32611768e+03 5.33512354e+03 5.47173682e+03 5.43169531e+03 5.28456006e+03 5.32137451e+03 5.27689893e+03 5.10526514e+03 5.31773291e+03 5.35481396e+03 5.04542969e+03 4.85526709e+03 4.92240088e+03 5.05628271e+03 5.05981836e+03 4.95498682e+03 4.82085400e+03 4.79167676e+03 4.91482715e+03 4.91836865e+03 4.69222119e+03 4.59901318e+03 4.69536035e+03 4.80925928e+03 4.64135010e+03 4.44764014e+03 4.51840332e+03 4.50391992e+03 4.44906641e+03 4.39040430e+03 4.37976758e+03 4.32793506e+03 4.22951172e+03 4.26170801e+03 4.23906689e+03 4.16013721e+03 4.04361255e+03 4.02126050e+03 4.05440283e+03 4.02129565e+03 3.93546973e+03 3.87414966e+03 3.85180103e+03 3.93375195e+03 3.88376514e+03 3.69459180e+03 3.69465869e+03 3.70232031e+03 3.64867261e+03 3.54760889e+03 3.47591699e+03 3.55012378e+03 3.48670776e+03 3.33740527e+03 3.23535669e+03 3.29647803e+03 3.36161377e+03 3.26987524e+03 3.21762061e+03 3.13760181e+03 3.11346924e+03 3.01220508e+03 2.87490405e+03 2.92580493e+03 2.94377368e+03 2.88472876e+03 2.83224365e+03 2.71224707e+03 2.67664331e+03 2.71127148e+03 2.67696826e+03 2.65099756e+03 2.55266626e+03 2.43889429e+03 2.38148901e+03 2.40952881e+03 2.41180591e+03 2.32772803e+03 2.25674194e+03 2.14574365e+03 2.14341846e+03 2.13667578e+03 2.05842041e+03 2.04411890e+03 1.95432336e+03 1.89280139e+03 1.90729211e+03 1.80898132e+03 1.74470569e+03 1.75889941e+03 1.72051685e+03 1.61810327e+03 1.52914697e+03 1.50245911e+03 1.47774097e+03 1.47497583e+03 1.44414856e+03 1.34733508e+03 1.26850708e+03 1.20239160e+03 1.19136157e+03 1.17953442e+03 1.10657507e+03 1.02934265e+03 9.60170227e+02 9.27497437e+02 9.03345154e+02 8.65087891e+02 8.05002991e+02 7.45991516e+02 7.08789978e+02 6.47315369e+02 5.78063599e+02 5.38231079e+02 4.97583588e+02 4.52604218e+02 4.11634064e+02 3.45999176e+02 2.86668854e+02 2.43923859e+02 2.00063858e+02 1.49929993e+02 9.69377518e+01 4.77469025e+01 -1.53495514e+00 -5.04089851e+01 -1.04275528e+02 -1.54617783e+02 -2.04006348e+02 -2.46310959e+02 -2.99112061e+02 -3.48893555e+02 -3.85415985e+02 -4.45925659e+02 -5.09877594e+02 -5.56991943e+02 -5.99682861e+02 -6.37233154e+02 -6.96020691e+02 -7.62032715e+02 -8.16299561e+02 -8.64214539e+02 -8.70560120e+02 -9.16370605e+02 -9.95804443e+02 -1.06622461e+03 -1.12525049e+03 -1.15161548e+03 -1.19302063e+03 -1.20942834e+03 -1.28052966e+03 -1.38090076e+03 -1.39968628e+03 -1.44037585e+03 -1.48813000e+03 -1.52344080e+03 -1.55431311e+03 -1.61544238e+03 -1.69829736e+03 -1.75918652e+03 -1.81426465e+03 -1.81591309e+03 -1.82459021e+03 -1.90812146e+03 -1.97769165e+03 -2.04967285e+03 -2.12136206e+03 -2.10222266e+03 -2.14892554e+03 -2.19182520e+03 -2.25602148e+03 -2.37576025e+03 -2.37742188e+03 -2.39211255e+03 -2.41648535e+03 -2.41490454e+03 -2.50595190e+03 -2.70286792e+03 -2.71021411e+03 -2.64573022e+03 -2.73562207e+03 -2.74858398e+03 -2.71889551e+03 -2.83835742e+03 -2.94299780e+03 -2.98868848e+03 -3.02175146e+03 -2.97760522e+03 -3.04617798e+03 -3.17046729e+03 -3.23789160e+03 -3.37594336e+03 -3.32268750e+03 -3.19607983e+03 -3.24720850e+03 -3.40322021e+03 -3.52060376e+03 -3.54181860e+03 -3.54551733e+03 -3.45424927e+03 -3.57629492e+03 -3.75959058e+03 -3.72598096e+03 -3.75990796e+03 -3.74484692e+03 -3.79237158e+03 -3.93207031e+03 -3.87778931e+03 -3.90067163e+03 -4.14329785e+03 -4.17059863e+03 -4.10011865e+03 -4.05535010e+03 -3.98058423e+03 -4.11942188e+03 -4.33691162e+03 -4.48379395e+03 -4.41867139e+03 -4.24493701e+03 -4.23719873e+03 -4.42844580e+03 -4.57666748e+03 -4.54223975e+03 -4.54327344e+03 -4.49985889e+03 -4.53885889e+03 -4.71774170e+03 -4.80352197e+03 -4.83456689e+03 -4.83377881e+03 -4.88219336e+03 -4.84736719e+03 -4.75134766e+03 -4.86318359e+03 -5.01347070e+03 -5.09278320e+03 -5.20698877e+03 -5.05377881e+03 -4.92613428e+03 -5.11730859e+03 -5.27721289e+03 -5.38081250e+03 -5.34422314e+03 -5.16940820e+03 -5.13832422e+03 -5.33796436e+03 -5.56773730e+03 -5.59278223e+03 -5.46754590e+03 -5.41415039e+03 -5.45005664e+03 -5.46302441e+03 -5.51113672e+03 -5.65215771e+03 -5.76614258e+03 -5.69483740e+03 -5.58532373e+03 -5.58170898e+03 -5.71339258e+03 -5.89229297e+03 -6.00553027e+03 -5.99853027e+03 -5.78459033e+03 -5.65234961e+03 -5.81775586e+03 -6.04324170e+03 -6.21219727e+03 -6.15789893e+03 -5.90218311e+03 -5.79817236e+03 -6.04795068e+03 -6.34076465e+03 -6.20668213e+03 -6.22967383e+03 -6.16665430e+03 -6.02868018e+03 -6.25572412e+03 -6.32202051e+03 -6.30306299e+03 -6.33187012e+03 -6.39605029e+03 -6.40734863e+03 -6.27917041e+03 -6.40081104e+03 -6.48264990e+03 -6.59444629e+03 -6.52552246e+03 -6.40104443e+03 -6.46822363e+03 -6.36995996e+03 -6.51741650e+03 -6.89755322e+03 -6.77932031e+03 -6.45807422e+03 -6.43178516e+03 -6.53362061e+03 -6.79062695e+03 -6.96856299e+03 -6.72528564e+03 -6.58576660e+03 -6.67884229e+03 -6.77854199e+03 -6.76527246e+03 -6.86563379e+03 -6.98247998e+03 -7.14701611e+03 -7.13983740e+03 -7.96508105e+03 -9.65920508e+03 -3.51845078e+04 19326628. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -59734588. -14162799. 1.66975175e+06 3.73615225e+06 -2.41036250e+04 -1.53163965e+04 -7.83487988e+03 -7.83620898e+03 -7.51992090e+03 -7.15181250e+03 -6.87733887e+03 -7.08489551e+03 -7.51976807e+03 -7.43061328e+03 -7.06252588e+03 -6.83632520e+03 -6.79257080e+03 -7.17860742e+03 -7.53424365e+03 -7.22867578e+03 -6.99330127e+03 -6.88336914e+03 -6.94604736e+03 -7.29658057e+03 -7.25310693e+03 -6.90236182e+03 -6.89249316e+03 -7.10155811e+03 -7.02362354e+03 -6.80277832e+03 -6.90399121e+03 -7.10117188e+03 -7.27225488e+03 -7.22812402e+03 -6.89705908e+03 -6.53148486e+03 -6.75016309e+03 -7.13555859e+03 -7.24876270e+03 -7.00070508e+03 -6.68399561e+03 -6.59922656e+03 -6.90483447e+03 -7.21766260e+03 -6.97685059e+03 -6.54831201e+03 -6.55634277e+03 -6.87491162e+03 -6.88866357e+03 -6.73976709e+03 -6.71699023e+03 -6.63774951e+03 -6.74850879e+03 -6.76886963e+03 -6.43041406e+03 -6.43650635e+03 -6.77989844e+03 -6.86688672e+03 -6.72464795e+03 -6.39676562e+03 -6.18408545e+03 -6.52701953e+03 -6.92392139e+03 -6.71617334e+03 -6.37370312e+03 -6.16714502e+03 -6.10225684e+03 -6.41688965e+03 -6.76223145e+03 -6.53511914e+03 -6.38745117e+03 -6.27951123e+03 -6.14806494e+03 -6.22303076e+03 -6.33385107e+03 -6.14970166e+03 -6.05747363e+03 -6.25346338e+03 -6.13107520e+03 -5.86307812e+03 -5.93137305e+03 -6.18745264e+03 -6.29476318e+03 -6.14291602e+03 -5.95878711e+03 -5.75493164e+03 -5.67335645e+03 -5.94860352e+03 -6.21313818e+03 -5.97000293e+03 -5.57601709e+03 -5.55470020e+03 -5.75828809e+03 -5.95015479e+03 -5.89746045e+03 -5.60146875e+03 -5.49975000e+03 -5.63054932e+03 -5.60661963e+03 -5.51718994e+03 -5.50641064e+03 -5.44113623e+03 -5.48407227e+03 -5.44728467e+03 -5.24680518e+03 -5.24456982e+03 -5.38021777e+03 -5.44659229e+03 -5.39563184e+03 -5.21423340e+03 -5.00825684e+03 -5.00694434e+03 -5.23890186e+03 -5.28071875e+03 -5.04773779e+03 -4.82819531e+03 -4.72858203e+03 -4.94930713e+03 -5.21594824e+03 -4.96356494e+03 -4.66644287e+03 -4.65536914e+03 -4.75486230e+03 -4.70129053e+03 -4.57371777e+03 -4.56027344e+03 -4.68140674e+03 -4.68739307e+03 -4.52148926e+03 -4.33985498e+03 -4.30061328e+03 -4.47075000e+03 -4.59861035e+03 -4.44609766e+03 -4.25630225e+03 -4.13709717e+03 -4.03867603e+03 -4.15361182e+03 -4.34580762e+03 -4.15291211e+03 -3.90366382e+03 -3.84672168e+03 -3.99007251e+03 -4.12712549e+03 -3.95537231e+03 -3.77981470e+03 -3.73101221e+03 -3.73769165e+03 -3.74942676e+03 -3.69310156e+03 -3.56133081e+03 -3.47643750e+03 -3.57088647e+03 -3.58933374e+03 -3.42064868e+03 -3.30108081e+03 -3.31559985e+03 -3.36919165e+03 -3.40192700e+03 -3.28721997e+03 -3.06237451e+03 -3.04487231e+03 -3.13182568e+03 -3.10522021e+03 -3.01339819e+03 -2.92328271e+03 -2.86467944e+03 -2.83248462e+03 -2.85598877e+03 -2.76355273e+03 -2.65450464e+03 -2.69679492e+03 -2.71651660e+03 -2.60209839e+03 -2.47242334e+03 -2.44346851e+03 -2.45351270e+03 -2.48452954e+03 -2.44446484e+03 -2.30925537e+03 -2.18547095e+03 -2.12276465e+03 -2.16768213e+03 -2.23060400e+03 -2.11348218e+03 -1.95049438e+03 -1.89331812e+03 -1.91564075e+03 -1.94453052e+03 -1.88711682e+03 -1.77867883e+03 -1.70958276e+03 -1.67655273e+03 -1.61529639e+03 -1.57237158e+03 -1.54450012e+03 -1.48519763e+03 -1.44874133e+03 -1.39435059e+03 -1.30789062e+03 -1.26730530e+03 -1.25241052e+03 -1.22002368e+03 -1.17195996e+03 -1.07186365e+03 -9.94890686e+02 -9.99689636e+02 -9.93213135e+02 -9.26327576e+02 -8.47722534e+02 -7.74044861e+02 -7.16734985e+02 -7.05563232e+02 -6.86867554e+02 -6.17231323e+02 -5.34687256e+02 -4.79599976e+02 -4.49523315e+02 -4.10019928e+02 -3.57434723e+02 -3.04086548e+02 -2.50515930e+02 -1.98981033e+02 -1.45078278e+02 -9.22829666e+01 -4.35410347e+01 6.28192186e+00 5.55911789e+01 1.07580421e+02 1.52237411e+02 1.90076004e+02 2.38888443e+02 3.01235016e+02 3.63267273e+02 4.08731659e+02 4.47947266e+02 5.09084076e+02 5.63918640e+02 5.89866882e+02 6.17052124e+02 6.78375488e+02 7.67169739e+02 8.44988220e+02 8.76209473e+02 8.77500305e+02 8.95492798e+02 9.63587463e+02 1.07607874e+03 1.16123682e+03 1.17832996e+03 1.16008337e+03 1.20937207e+03 1.33502063e+03 1.38147827e+03 1.36798694e+03 1.41366089e+03 1.47389734e+03 1.52511523e+03 1.62839893e+03 1.64411633e+03 1.63594373e+03 1.71894446e+03 1.73366809e+03 1.83454248e+03 1.92448547e+03 1.86874353e+03 1.96623279e+03 2.08080396e+03 2.07349878e+03 2.09750049e+03 2.15806689e+03 2.23195386e+03 2.27967261e+03 2.30995581e+03 2.28541211e+03 2.33906177e+03 2.51145020e+03 2.61149072e+03 2.59661548e+03 2.53696729e+03 2.52702051e+03 2.63271533e+03 2.79130371e+03 2.88998926e+03 2.87828296e+03 2.79636377e+03 2.84970166e+03 2.97047095e+03 3.00478076e+03 3.05884326e+03 3.09198560e+03 3.11820532e+03 3.15509619e+03 3.32470898e+03 3.30645605e+03 3.21707739e+03 3.32278247e+03 3.31452710e+03 3.49453735e+03 3.57793042e+03 3.49047070e+03 3.71346191e+03 3.63818677e+03 3.53094189e+03 3.70668994e+03 3.66514380e+03 3.76550171e+03 4.07209521e+03 3.93377759e+03 3.73249487e+03 3.82335205e+03 4.04670874e+03 4.28804980e+03 4.20907764e+03 4.01903003e+03 3.97596631e+03 4.05513086e+03 4.30737354e+03 4.54015869e+03 4.45766309e+03 4.27877539e+03 4.29480566e+03 4.45870752e+03 4.54062500e+03 4.51105469e+03 4.49575293e+03 4.56301953e+03 4.65866797e+03 4.79794336e+03 4.82439307e+03 4.65312939e+03 4.67768555e+03 4.76047607e+03 4.82886914e+03 4.92342139e+03 4.94333789e+03 5.11143555e+03 5.03205469e+03 4.87742139e+03 5.04035596e+03 4.95547363e+03 5.14589893e+03 5.48339404e+03 5.25071826e+03 4.98772363e+03 5.12906055e+03 5.40322705e+03 5.61821240e+03 5.60619824e+03 5.33007080e+03 5.18594238e+03 5.30731494e+03 5.60249121e+03 5.88447168e+03 5.72051953e+03 5.40111719e+03 5.42430859e+03 5.61940918e+03 5.77477393e+03 5.97094678e+03 5.97327588e+03 5.65986670e+03 5.57764160e+03 5.92909424e+03 6.04697510e+03 5.81176074e+03 5.81937158e+03 5.97816992e+03 5.94710742e+03 6.13796191e+03 6.22142627e+03 5.89995947e+03 5.92577246e+03 6.12892773e+03 6.15127979e+03 6.19749170e+03 6.11797754e+03 6.25834473e+03 6.44775488e+03 6.31267236e+03 6.11825000e+03 6.00491406e+03 6.30506885e+03 6.70716064e+03 6.57244141e+03 6.27172705e+03 6.10847656e+03 6.34456396e+03 6.76313916e+03 6.60891406e+03 6.27116162e+03 6.35420361e+03 6.53364014e+03 6.71855420e+03 6.93899414e+03 6.82305566e+03 6.45546631e+03 6.32389648e+03 6.54917334e+03 6.85895117e+03 6.88198926e+03 6.68811182e+03 6.68853369e+03 6.71198877e+03 6.88668457e+03 6.88233154e+03 6.74610156e+03 6.72567578e+03 6.53760449e+03 6.85749512e+03 7.12311084e+03 6.83333496e+03 6.93022705e+03 6.97645312e+03 7.05296289e+03 6.88450537e+03 6.63361816e+03 6.93905859e+03 7.29589209e+03 7.12416016e+03 6.75308936e+03 6.81649219e+03 7.20794336e+03 7.23790137e+03 7.06747803e+03 7.09864062e+03 6.81552295e+03 6.81793213e+03 7.27619678e+03 7.24128369e+03 6.96112549e+03 6.82426270e+03 6.82048828e+03 7.15280176e+03 7.40742676e+03 7.15813623e+03 6.97646582e+03 7.11854932e+03 7.08758350e+03 7.34827100e+03 7.33817969e+03 6.95674219e+03 6.97179590e+03 7.10973877e+03 7.10019971e+03 7.14974902e+03 7.12292236e+03 7.33767334e+03 7.23114307e+03 6.99972705e+03 7.06785791e+03 6.91160352e+03 7.15928564e+03 7.60448438e+03 7.37939795e+03 7.01690234e+03 6.90477393e+03 7.02292139e+03 7.24009375e+03 7.56728564e+03 7.68129688e+03 8.13762305e+03 7.43974268e+03 1.08677480e+04 7.84219531e+04 -17729578. 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. 0. 0. 0. 0. 0. 0. -160556896. 30361858. 2.43834863e+04 1.47821328e+04 7.32767188e+03 7.20819092e+03 6.89386279e+03 6.55131104e+03 6.51950732e+03 6.66298291e+03 6.63217188e+03 6.49791846e+03 6.64484277e+03 6.58337598e+03 6.48360449e+03 6.48620361e+03 6.45458789e+03 6.39167041e+03 6.39663867e+03 6.42869629e+03 6.33686133e+03 6.18508008e+03 6.16281250e+03 6.41079688e+03 6.37627832e+03 6.04934229e+03 6.05724121e+03 6.34132373e+03 6.34871631e+03 6.12059375e+03 6.10225684e+03 6.04939893e+03 6.04197314e+03 6.01328613e+03 6.00783740e+03 5.96321094e+03 5.88182031e+03 5.77478906e+03 5.75711328e+03 5.96140039e+03 5.93950391e+03 5.75490576e+03 5.74851807e+03 5.73196045e+03 5.72628027e+03 5.65590576e+03 5.60526465e+03 5.60146826e+03 5.43251855e+03 5.39246582e+03 5.47082764e+03 5.42610547e+03 5.59182861e+03 5.59353662e+03 5.40112695e+03 5.18843506e+03 5.11405518e+03 5.43806787e+03 5.46230566e+03 5.19120898e+03 5.08461328e+03 5.12785889e+03 5.05956885e+03 4.96680176e+03 5.18125732e+03 5.11576123e+03 4.78042627e+03 4.72158008e+03 4.93698584e+03 5.08153662e+03 4.92961426e+03 4.79322461e+03 4.76733057e+03 4.69259180e+03 4.61372998e+03 4.61127051e+03 4.63154004e+03 4.57396875e+03 4.43962256e+03 4.38136963e+03 4.42815576e+03 4.38657715e+03 4.45690527e+03 4.36680127e+03 4.18967822e+03 4.23140088e+03 4.19245312e+03 4.24295459e+03 4.22201514e+03 4.07975488e+03 4.03433350e+03 3.91346851e+03 3.79180737e+03 3.92708154e+03 3.94289697e+03 3.70016724e+03 3.69752393e+03 3.87286230e+03 3.90351123e+03 3.75232910e+03 3.60791650e+03 3.54861865e+03 3.51757031e+03 3.43628345e+03 3.38467993e+03 3.41162549e+03 3.36073535e+03 3.36432715e+03 3.27560864e+03 3.16719360e+03 3.18157300e+03 3.06328784e+03 3.06601489e+03 3.18321973e+03 3.08277002e+03 2.95394751e+03 2.83117383e+03 2.77829956e+03 2.89366431e+03 2.86864600e+03 2.71635718e+03 2.59233154e+03 2.55081812e+03 2.57736792e+03 2.52839014e+03 2.55242065e+03 2.52827368e+03 2.39548145e+03 2.29943115e+03 2.26228076e+03 2.30980688e+03 2.25227539e+03 2.15215088e+03 2.06871509e+03 2.02226270e+03 2.01611157e+03 1.91527234e+03 1.89447522e+03 1.96147583e+03 1.88364990e+03 1.77989990e+03 1.68201868e+03 1.62915674e+03 1.68235864e+03 1.63599060e+03 1.54160742e+03 1.44538611e+03 1.38768311e+03 1.39157605e+03 1.34014343e+03 1.28487964e+03 1.21037402e+03 1.18383325e+03 1.17780798e+03 1.09670679e+03 1.06000085e+03 1.01829639e+03 9.46930481e+02 8.74208862e+02 8.24310852e+02 7.95272339e+02 7.44758057e+02 6.95899902e+02 6.25278015e+02 5.85528137e+02 5.73709839e+02 4.99030945e+02 4.32695343e+02 3.96245697e+02 3.47548065e+02 3.05124176e+02 2.49977554e+02 1.92171188e+02 1.50458145e+02 1.00865479e+02 4.87544823e+01 3.75764817e-01 -4.76415215e+01 -9.65524292e+01 -1.47986710e+02 -2.01843567e+02 -2.45650742e+02 -3.00339020e+02 -3.69724335e+02 -4.13463104e+02 -4.44086975e+02 -4.76837982e+02 -5.43321838e+02 -6.31467529e+02 -6.65894043e+02 -6.97922485e+02 -7.36735596e+02 -7.77006042e+02 -8.46009949e+02 -8.96190186e+02 -9.70223206e+02 -1.00205341e+03 -1.01736810e+03 -1.09494885e+03 -1.14997363e+03 -1.22219470e+03 -1.25960583e+03 -1.27875647e+03 -1.32309229e+03 -1.36565991e+03 -1.44723108e+03 -1.46091638e+03 -1.52862610e+03 -1.66444788e+03 -1.67506482e+03 -1.68885010e+03 -1.68793652e+03 -1.71996130e+03 -1.87316089e+03 -1.93618091e+03 -1.93586389e+03 -1.91907275e+03 -1.96017407e+03 -2.07429102e+03 -2.12495435e+03 -2.22689258e+03 -2.26643286e+03 -2.25977856e+03 -2.23788135e+03 -2.27489722e+03 -2.46544849e+03 -2.49979541e+03 -2.47764966e+03 -2.48495874e+03 -2.52427100e+03 -2.69560645e+03 -2.76167310e+03 -2.67092700e+03 -2.69649414e+03 -2.88371265e+03 -2.93497388e+03 -2.83574170e+03 -2.87095386e+03 -3.07064624e+03 -3.12481079e+03 -3.07033984e+03 -3.05435083e+03 -3.09234766e+03 -3.31937427e+03 -3.34699121e+03 -3.27142603e+03 -3.31936401e+03 -3.34323413e+03 -3.43708276e+03 -3.50092822e+03 -3.52589282e+03 -3.47454834e+03 -3.57894189e+03 -3.79396680e+03 -3.74736133e+03 -3.80642334e+03 -3.88151831e+03 -3.84747876e+03 -3.89476733e+03 -3.92597705e+03 -3.92504492e+03 -3.88626050e+03 -3.93366431e+03 -4.06146313e+03 -4.12922998e+03 -4.28307031e+03 -4.21341260e+03 -4.12100342e+03 -4.28697900e+03 -4.34529688e+03 -4.49193066e+03 -4.46217041e+03 -4.37866357e+03 -4.44724268e+03 -4.43911475e+03 -4.55421387e+03 -4.60683154e+03 -4.73134521e+03 -4.73457422e+03 -4.65258203e+03 -4.70623242e+03 -4.62239697e+03 -4.80963770e+03 -5.12898486e+03 -5.04703076e+03 -4.93481348e+03 -4.84601416e+03 -4.81909180e+03 -5.09522559e+03 -5.29867725e+03 -5.17816797e+03 -5.01698340e+03 -5.02989160e+03 -5.20010547e+03 -5.24103809e+03 -5.39901904e+03 -5.36774072e+03 -5.24605420e+03 -5.36548633e+03 -5.39574609e+03 -5.58004541e+03 -5.61801758e+03 -5.34141309e+03 -5.39532764e+03 -5.71846143e+03 -5.65532129e+03 -5.40431787e+03 -5.61070264e+03 -5.95240576e+03 -5.86776172e+03 -5.75577930e+03 -5.66718115e+03 -5.69159082e+03 -5.99761768e+03 -6.02983252e+03 -5.91374561e+03 -5.79052295e+03 -5.79518311e+03 -6.02334424e+03 -6.02141699e+03 -6.02358203e+03 -5.92532227e+03 -6.06432617e+03 -6.32548145e+03 -6.16755127e+03 -6.29027295e+03 -6.21996240e+03 -6.06191748e+03 -6.24738135e+03 -6.30435986e+03 -6.31412402e+03 -6.30069629e+03 -6.24560449e+03 -6.14260938e+03 -6.34196094e+03 -6.80441309e+03 -6.43961035e+03 -6.12484424e+03 -6.33001514e+03 -6.59379639e+03 -6.79590771e+03 -6.64556494e+03 -6.49504443e+03 -6.67021729e+03 -6.66218213e+03 -6.44219238e+03 -6.35416650e+03 -6.73703516e+03 -6.79537451e+03 -6.58720361e+03 -6.63481543e+03 -6.43979590e+03 -6.69003027e+03 -7.10392188e+03 -6.90906201e+03 -6.76790967e+03 -6.56966113e+03 -6.51301904e+03 -6.92901953e+03 -7.24331348e+03 -7.08237500e+03 -6.74093408e+03 -6.67229150e+03 -6.84501904e+03 -6.90325195e+03 -7.12586523e+03 -6.92958789e+03 -6.76330664e+03 -7.01194580e+03 -6.92630664e+03 -7.11803711e+03 -7.10218213e+03 -6.84415820e+03 -7.09145752e+03 -7.09548779e+03 -7.00602588e+03 -6.83729004e+03 -6.91809619e+03 -7.30572949e+03 -7.26844678e+03 -6.94003223e+03 -6.82152051e+03 -7.01968750e+03 -7.39538721e+03 -7.29769238e+03 -7.10239404e+03 -6.94503320e+03 -6.92541650e+03 -7.11789258e+03 -7.18185498e+03 -7.15768652e+03 -6.98133447e+03 -7.06875000e+03 -7.34703613e+03 -7.15306299e+03 -7.32486816e+03 -7.30552686e+03 -7.07883545e+03 -7.14872510e+03 -7.17444580e+03 -7.09445801e+03 -7.13524854e+03 -7.04788184e+03 -7.04674170e+03 -7.33502148e+03 -7.29842285e+03 -6.93942139e+03 -6.89203516e+03 -7.03702441e+03 -7.21270459e+03 -7.48237402e+03 -7.22742578e+03 -6.82555469e+03 -7.09450488e+03 -7.48250781e+03 -7.27432031e+03 -6.94326660e+03 -6.93409082e+03 -7.02592920e+03 -7.06685791e+03 -7.10805566e+03 -6.88614600e+03 -7.05208838e+03 -7.38967188e+03 -7.17927734e+03 -7.01896631e+03 -6.85119189e+03 -6.87344141e+03 -7.27358740e+03 -7.17911377e+03 -7.01645557e+03 -6.88616211e+03 -6.58773145e+03 -6.76694482e+03 -7.16962061e+03 -7.38148779e+03 -6.96081836e+03 -6.62811768e+03 -6.82616992e+03 -6.95026123e+03 -7.18214209e+03 -6.97253418e+03 -6.75231006e+03 -6.86805518e+03 -6.86052295e+03 -6.75059424e+03 -6.58356152e+03 -6.70157617e+03 -6.98334814e+03 -6.86435547e+03 -6.75826514e+03 -6.62644287e+03 -6.56993555e+03 -6.84979834e+03 -6.88293262e+03 -6.66973242e+03 -6.50162109e+03 -6.40120312e+03 -6.54421240e+03 -6.54689893e+03 -6.73220752e+03 -6.76218848e+03 -6.41054297e+03 -6.29472803e+03 -6.47033350e+03 -6.70095020e+03 -6.50645068e+03 -6.35164893e+03 -6.30622656e+03 -6.29550635e+03 -6.27163525e+03 -6.10040869e+03 -6.31677637e+03 -6.40192188e+03 -6.18649512e+03 -6.31529639e+03 -6.36757666e+03 -6.22644092e+03 -6.22156982e+03 -6.17130518e+03 -6.05720947e+03 -5.88176807e+03 -5.82307666e+03 -6.07200732e+03 -6.19044531e+03 -5.90438477e+03 -5.62783203e+03 -5.81325000e+03 -6.13950635e+03 -6.09472510e+03 -5.73644336e+03 -5.49047168e+03 -5.75373877e+03 -5.97491406e+03 -5.79675928e+03 -5.74978613e+03 -5.54795410e+03 -5.27878662e+03 -5.46715186e+03 -5.76565723e+03 -5.76475391e+03 -5.40543750e+03 -5.16588428e+03 -5.46362549e+03 -5.68481348e+03 -5.46939355e+03 -5.17678760e+03 -5.01104492e+03 -5.13440332e+03 -5.20123389e+03 -5.30827588e+03 -5.33891064e+03 -5.11252686e+03 -4.98600586e+03 -4.95668896e+03 -5.13212451e+03 -4.98523193e+03 -4.79751074e+03 -4.98117676e+03 -4.93600391e+03 -4.83512988e+03 -4.69491162e+03 -4.65824365e+03 -4.88348779e+03 -4.68699414e+03 -4.41143213e+03 -4.48609521e+03 -4.63539600e+03 -4.61933252e+03 -4.48086328e+03 -4.52828467e+03 -4.51304785e+03 -4.37507666e+03 -4.21656299e+03 -4.13234521e+03 -4.33798047e+03 -4.22252051e+03 -4.06438086e+03 -4.14677295e+03 -4.09356494e+03 -4.02110669e+03 -3.94543994e+03 -3.98715137e+03 -3.97486255e+03 -3.83432812e+03 -3.83992993e+03 -3.83076001e+03 -3.82492065e+03 -3.76013940e+03 -3.64639673e+03 -3.56002881e+03 -3.42159570e+03 -3.39515601e+03 -3.54092700e+03 -3.66581006e+03 -3.41847485e+03 -3.16362109e+03 -3.24673511e+03 -3.39992749e+03 -3.37274927e+03 -3.15803784e+03 -2.97903442e+03 -3.08971509e+03 -3.10891235e+03 -2.97404077e+03 -3.04254541e+03 -2.92594067e+03 -2.72730176e+03 -2.76675708e+03 -2.87234351e+03 -2.83120825e+03 -2.63270801e+03 -2.48819800e+03 -2.56279004e+03 -2.68331494e+03 -2.57263306e+03 -2.38528882e+03 -2.28185840e+03 -2.34712915e+03 -2.37817480e+03 -2.26205029e+03 -2.18604077e+03 -2.15178613e+03 -2.12790137e+03 -2.06457593e+03 -2.06544531e+03 -1.98404736e+03 -1.86387500e+03 -1.86215637e+03 -1.83068384e+03 -1.81868335e+03 -1.73282141e+03 -1.63733728e+03 -1.65700061e+03 -1.56678455e+03 -1.47732898e+03 -1.48539343e+03 -1.46513440e+03 -1.41597864e+03 -1.33900452e+03 -1.32555188e+03 -1.28845715e+03 -1.18827881e+03 -1.10520642e+03 -1.05590149e+03 -1.07571765e+03 -1.00674335e+03 -9.41422974e+02 -1.01231812e+03 -1.52320117e+03 -8.42224805e+03 215346512. 0. 0. 0. 0. -812645376. -3.29115562e+05 6.50518688e+05 1.07055766e+05 -5.01183594e+02 -1.15254187e+03 -2.52186987e+03 -1455718784. 0. 0.
================================================ FILE: config/m2dgr/ring32_M_2.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 201144560. 113401328. 1.60678463e+01 4.99960232e+00 -4.53779888e+00 -5.88477087e+00 -5.97438574e+00 -5.82587481e+00 -6.21096468e+00 -5.70433140e+00 -5.05896521e+00 -4.99526310e+00 -5.12207413e+00 -5.27889395e+00 -5.54332209e+00 -5.64076281e+00 -5.83279181e+00 -5.56179380e+00 -5.14274883e+00 -4.70646524e+00 -4.72374010e+00 -5.48171234e+00 -6.24423409e+00 -6.78327131e+00 -6.86710358e+00 -6.35420179e+00 -6.25680494e+00 -6.21762562e+00 -5.57078600e+00 -5.17166090e+00 -5.38738823e+00 -6.56880617e+00 -7.44207335e+00 -7.52088976e+00 -6.79005814e+00 -5.45213842e+00 -4.98875713e+00 -5.07720184e+00 -5.12963820e+00 -5.12834692e+00 -5.34290552e+00 -6.22155857e+00 -7.00200653e+00 -6.55312538e+00 -5.63803291e+00 -5.12675381e+00 -5.85156965e+00 -5.94659901e+00 -5.74753189e+00 -6.24275398e+00 -6.23261642e+00 -6.18978024e+00 -5.63151884e+00 -4.87421751e+00 -4.30074215e+00 -4.11646891e+00 -5.68968201e+00 -7.65222931e+00 -8.21309566e+00 -7.06542253e+00 -4.83452988e+00 -4.62190437e+00 -5.54965210e+00 -6.62128067e+00 -6.41573000e+00 -5.97615623e+00 -6.25546741e+00 -6.69690180e+00 -6.68478870e+00 -5.38403368e+00 -3.78844976e+00 -4.30717945e+00 -4.76856852e+00 -5.39198065e+00 -5.79928541e+00 -6.00047302e+00 -6.52064610e+00 -5.69595528e+00 -4.36143208e+00 -3.09806466e+00 -3.09290075e+00 -4.59454250e+00 -6.33267927e+00 -7.88799667e+00 -8.05368137e+00 -6.37041140e+00 -5.62356710e+00 -5.44278240e+00 -4.31636381e+00 -2.59162068e+00 -2.59818864e+00 -5.26229429e+00 -7.96770906e+00 -8.15096664e+00 -5.66601229e+00 -2.82246423e+00 -2.53728676e+00 -2.93904281e+00 -2.76196671e+00 -2.76979017e+00 -3.33807588e+00 -4.70854235e+00 -5.51711655e+00 -4.86258554e+00 -3.54389834e+00 -2.99892282e+00 -4.13592720e+00 -6.11847353e+00 -7.45315790e+00 -7.72990847e+00 -5.66854048e+00 -3.69163799e+00 -3.95503092e+00 -3.89757681e+00 -3.01219630e+00 -2.31545591e+00 -3.64161110e+00 -5.93916988e+00 -5.97430658e+00 -3.24585748e+00 -7.52615392e-01 -3.04069072e-01 -2.37632275e+00 -4.54745674e+00 -6.73451281e+00 -7.78572273e+00 -9.13032532e+00 -2.06175594e+01 -1.27184700e+02 -2.68729065e+02 -6606219. 7.72394550e+06 10930837. -16376169. 2.78985931e+02 1.51581741e+02 2.62712479e+01 -1.02835464e+01 -2.93263817e+01 -1.41191483e+02 -2.63339172e+02 53804900. -240486640. 7.11620850e+06 117234920. 5.50663150e+06 -7243306. 21696244. -14542091. -6791696. 8.38355450e+06 2.78052063e+02 1.49951675e+02 2.48133259e+01 6.25773287e+00 -6.34944582e+00 -4.73680115e+00 -6.23969841e+00 -6.24877644e+00 -5.73162174e+00 -2.97000575e+00 -1.44414651e+00 -3.82844329e+00 -6.45174503e+00 -6.32006931e+00 -5.88955498e+00 -5.75097799e+00 -8.84115505e+00 -1.11052170e+01 -1.18958473e+01 -7.47499704e+00 -1.86035991e+00 -5.53893745e-01 -8.41390371e-01 -1.01972365e+00 -1.44603801e+00 -3.11136746e+00 -6.78802633e+00 -8.09595680e+00 -5.31723213e+00 -1.69808519e+00 -8.93623412e-01 -3.88160467e+00 -6.28992128e+00 -6.89387274e+00 -7.30355930e+00 -6.65184069e+00 -7.78376579e+00 -7.78304529e+00 -6.37778044e+00 -5.99170256e+00 -6.47779036e+00 -9.14610386e+00 -1.05612125e+01 -1.01998644e+01 -5.12082291e+00 2.51221001e-01 1.16147268e+00 -7.85321891e-01 -1.47095776e+00 -2.04829264e+00 -3.51675701e+00 -7.03279161e+00 -7.35146332e+00 -3.24200153e+00 1.11640596e+00 2.19045997e+00 -1.28384984e+00 -3.59183812e+00 -3.88906717e+00 -3.75163007e+00 -3.56296515e+00 -5.11950874e+00 -6.80309200e+00 -4.95847797e+00 -1.95961201e+00 -3.80641848e-01 -2.91421771e+00 -7.03000164e+00 -8.09919357e+00 -4.81160641e+00 -1.10893130e+00 -1.73036814e-01 -1.56594694e+00 -1.54815423e+00 -2.00481248e+00 -1.53712094e+00 -1.16055119e+00 -9.76793885e-01 -8.17644298e-01 -4.57051843e-01 1.44335055e+00 1.56505442e+00 1.06761372e+00 6.42322972e-02 -3.58566952e+00 -5.76808119e+00 -8.28450203e+00 -6.39837360e+00 -3.40663671e+00 -1.83904603e-01 2.12884974e+00 -2.48478198e+00 -6.39725494e+00 -6.97412443e+00 -2.38423848e+00 6.27418756e-02 -1.61754608e+00 -4.02933788e+00 -1.71128702e+00 6.10862672e-03 -1.01575470e+00 -4.90253353e+00 -6.70418882e+00 -4.42482710e+00 -4.75473738e+00 -3.91208673e+00 -3.90014100e+00 -1.49191487e+00 -3.04783940e+00 -4.47095633e+00 -5.99550056e+00 -7.77673054e+00 -7.55262756e+00 -6.41129446e+00 -1.95942914e+00 1.11564755e+00 -1.43439198e+00 -7.96348143e+00 -1.04388618e+01 -7.45373678e+00 -5.80660486e+00 -7.40301704e+00 -8.93192577e+00 -5.03393650e+00 -2.60110617e+00 -1.97648537e+00 -2.80374217e+00 -2.45770168e+00 -1.98584557e+00 -4.11490107e+00 -4.22040272e+00 -2.04165745e+00 7.37344146e-01 -2.25779504e-01 8.24034691e-01 3.48236322e+00 3.56996751e+00 -5.92570901e-01 -4.59547234e+00 -4.15207005e+00 -2.69606161e+00 -3.16027546e+00 -6.00205517e+00 -4.53522158e+00 -2.41425014e+00 -2.40702057e+00 -5.59848356e+00 -7.78368759e+00 -5.73154306e+00 -4.88394022e+00 -3.38893676e+00 -4.08241606e+00 -9.57896173e-01 1.54457927e+00 5.29780030e-01 -1.72538781e+00 -2.84280753e+00 -7.27155149e-01 6.43470585e-02 1.57683623e+00 3.68882799e+00 3.12100172e+00 1.40109622e+00 -7.41584480e-01 1.21258616e+00 3.69935679e+00 1.10067451e+00 -4.54781008e+00 -5.44688320e+00 -1.79469061e+00 6.88582003e-01 -2.98671603e+00 -6.36819124e+00 -4.29688168e+00 -1.52848649e+00 1.66342199e+00 2.59349179e+00 4.81329298e+00 5.27112246e+00 3.25110626e+00 1.72228301e+00 1.42396283e+00 2.03068280e+00 7.92757869e-01 1.62192094e+00 4.05831766e+00 2.53180313e+00 -2.20427084e+00 -5.36629009e+00 -4.05258560e+00 -2.50975704e+00 -4.24609900e+00 -6.08939123e+00 -3.83806324e+00 -2.39842272e+00 -2.16481638e+00 -5.02102518e+00 -4.17186832e+00 -1.94256544e+00 -1.83763933e+00 -1.70163763e+00 -9.45247769e-01 3.62289333e+00 4.99613571e+00 2.92879009e+00 -6.52210951e-01 -3.30977249e+00 -2.34795904e+00 -8.49804521e-01 1.89376330e+00 7.40436077e+00 6.61607504e+00 -7.53749371e-01 -9.59864712e+00 -1.31369286e+01 -8.20221233e+00 -5.42598391e+00 -5.59699535e+00 -6.17877150e+00 -8.71821213e+00 -5.69769096e+00 -5.27801466e+00 -3.06660390e+00 -3.54250193e+00 -9.84742641e+00 -1.17134113e+01 -1.10219574e+01 -2.05581021e+00 3.96816182e+00 4.08680737e-01 -4.44105291e+00 -6.53108120e+00 -4.34854835e-01 4.63249922e+00 3.67291164e+00 3.06127453e+00 -2.74071664e-01 -3.28413057e+00 -5.44595337e+00 -7.66567326e+00 -4.86245489e+00 -1.97450292e+00 3.67291033e-01 4.87876564e-01 -5.14886570e+00 -8.69650078e+00 -1.14599733e+01 -8.20241356e+00 -1.47471440e+00 -1.01520920e+00 -9.83958542e-01 -4.11037832e-01 5.11390686e+00 4.73478270e+00 -4.47847652e+00 -1.02326536e+01 -1.06602201e+01 -5.45122433e+00 -2.56220269e+00 -2.25718737e+00 4.89235997e-01 1.75731674e-01 -2.70846343e+00 -5.01467323e+00 -8.23292637e+00 -6.57547140e+00 -7.12252855e+00 -6.92102718e+00 -6.24134302e+00 -5.88911295e+00 6.11639023e-01 2.21960568e+00 1.63333094e+00 -9.08642709e-01 -6.87380505e+00 -8.44048595e+00 -8.64720821e+00 -8.81218255e-01 5.05017948e+00 4.97448063e+00 -2.17216447e-01 -5.64717054e+00 -2.41343284e+00 3.20228958e+00 5.33273983e+00 4.44960499e+00 2.30139208e+00 6.88737109e-02 -1.79699457e+00 -4.19257593e+00 -1.09202707e+00 2.20283484e+00 4.08398247e+00 1.59661186e+00 -6.49872208e+00 -9.95579720e+00 -8.47896099e+00 -1.53566670e+00 4.01288319e+00 1.29202378e+00 -4.26643229e+00 -7.16375637e+00 -2.40580487e+00 3.07738614e+00 2.38620734e+00 -1.22048873e-02 -2.61281300e+00 -1.85017395e+00 -7.10787416e-01 -2.48986125e+00 -3.07716060e+00 -2.70758533e+00 -2.56013894e+00 -1.45391631e+00 -4.49452829e+00 -3.20711470e+00 -2.94931483e+00 -1.28129458e+00 2.68239498e-01 -2.99485135e+00 -1.36247233e-01 2.04432225e+00 7.19351339e+00 5.27129269e+00 -1.97160864e+00 -6.96453762e+00 -8.00301266e+00 -3.03001404e-01 5.15311432e+00 6.36357784e+00 3.60748553e+00 -8.38183045e-01 -1.56175971e+00 1.18776023e+00 3.69118357e+00 6.75674248e+00 4.01934052e+00 -7.56512165e-01 -5.77184105e+00 -6.14593315e+00 9.43054974e-01 6.02268267e+00 8.40300941e+00 6.00734329e+00 -4.57488537e-01 -5.13455582e+00 -5.66610432e+00 8.99520874e-01 6.55940723e+00 4.35549068e+00 -1.13697112e+00 -5.08773708e+00 -1.30025637e+00 4.80715561e+00 5.43847466e+00 3.68385601e+00 -1.50963509e+00 -4.29197884e+00 -4.48033857e+00 -3.81547308e+00 -3.17114204e-01 2.69937468e+00 3.09989047e+00 1.93598557e+00 -2.77431774e+00 -2.03963923e+00 1.55099273e-01 2.22261620e+00 5.40332031e+00 2.09353924e+00 1.61933076e+00 1.37451065e+00 5.22824335e+00 6.36441755e+00 -1.34967005e+00 -5.69698429e+00 -5.81509876e+00 1.68920314e+00 7.13931561e+00 7.15344477e+00 4.75626516e+00 -3.05669010e-01 -3.43191910e+00 -3.34815574e+00 -2.40404606e+00 6.50684357e-01 1.57336688e+00 4.97824162e-01 1.28472662e+00 6.55756950e-01 5.27044058e+00 5.45591116e+00 5.40328264e+00 4.30882120e+00 -3.06004554e-01 -4.35168833e-01 1.83293474e+00 8.47263241e+00 1.09555578e+01 8.90686798e+00 5.01610184e+00 1.25183213e+00 3.46139359e+00 7.87721634e+00 9.89214611e+00 8.49881649e+00 4.47146368e+00 2.46469140e+00 1.84112597e+00 1.48522127e+00 1.23592484e+00 8.71458054e-01 1.01773345e+00 -6.94887221e-01 -3.31316090e+00 -6.27729952e-01 4.81412077e+00 7.44012165e+00 5.11260128e+00 -8.46765995e-01 -3.33230996e+00 -2.12928295e+00 3.42971468e+00 6.74935293e+00 4.34830475e+00 2.06375146e+00 7.50149310e-01 2.74996018e+00 3.38340688e+00 1.50316095e+00 -6.58857003e-02 -1.92823315e+00 -2.52527571e+00 -1.70857477e+00 -2.49064398e+00 -1.35716304e-01 7.24765480e-01 8.26600373e-01 1.75248122e+00 -4.87349868e-01 1.23729038e+00 9.03809667e-01 2.95882893e+00 4.05159426e+00 3.52556914e-01 5.13907194e-01 1.76530574e-02 3.62826324e+00 5.16737938e+00 2.68131018e+00 1.52172971e+00 -3.24672675e+00 -1.39089501e+00 2.38935924e+00 6.45951986e+00 7.49005413e+00 2.43736410e+00 1.72644687e+00 2.76551342e+00 2.54308891e+00 1.27067435e+00 4.00400102e-01 5.13998985e+00 6.60641432e+00 2.02603221e+00 1.62936404e-01 3.97582024e-01 7.90117311e+00 7.92721319e+00 2.55127258e+01 3.32078781e+01 3.04379211e+02 8.57763916e+02 12271988. 179269984. 6380537. 4.71044650e+06 -810436672. 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. 0. 0. 0. 0. 0. 0. 0. 430126272. 1.43951733e+03 2.44966080e+02 4.83169937e+01 2.11784096e+01 8.31580162e+00 8.37431014e-01 -7.27487147e-01 -1.56569302e+00 2.25215173e+00 3.77254200e+00 3.53006053e+00 3.87090182e+00 2.48793244e+00 1.63843369e+00 1.81773376e+00 3.51597953e+00 4.95618916e+00 3.89764404e+00 2.26839852e+00 1.55956304e+00 9.63384748e-01 1.42461741e+00 2.14854121e+00 4.33036232e+00 5.30806160e+00 2.10660815e+00 1.04268348e+00 2.85059237e+00 6.78840303e+00 5.38427639e+00 1.69959080e+00 7.58901536e-01 2.30240417e+00 4.33734035e+00 4.35362434e+00 3.93937945e+00 4.05100679e+00 3.43357372e+00 2.61032891e+00 2.32011914e+00 3.07100534e+00 4.82233095e+00 3.58728194e+00 2.47923160e+00 5.58781624e-01 -1.84383023e+00 -6.76873505e-01 3.51325989e+00 8.98996067e+00 8.97046089e+00 4.31070566e+00 3.11546946e+00 3.87560320e+00 7.12377882e+00 6.94157887e+00 4.69044018e+00 3.60119462e+00 2.91911530e+00 4.11836481e+00 3.89139342e+00 3.32737279e+00 3.07668185e+00 1.36867166e+00 -3.35519202e-02 1.70278236e-01 2.13455248e+00 3.97167277e+00 3.32759309e+00 2.56056547e+00 1.03540957e+00 -7.42541671e-01 -1.63552690e+00 -1.80181420e+00 3.08705091e-01 1.62709343e+00 8.16237271e-01 2.28141356e+00 4.35717726e+00 8.29120445e+00 7.76746225e+00 5.00064373e+00 3.85500216e+00 3.05980635e+00 3.04803109e+00 2.95908189e+00 3.88826466e+00 5.24018383e+00 4.38114309e+00 3.47707987e+00 3.73465824e+00 3.68123126e+00 3.03923345e+00 1.41280699e+00 2.12654114e+00 3.75954866e+00 2.67927527e+00 2.79531169e+00 2.87769270e+00 4.97433853e+00 5.42212963e+00 2.97425771e+00 2.93594646e+00 4.02406931e+00 7.10850334e+00 7.61773729e+00 5.40502691e+00 4.44088554e+00 3.22452688e+00 3.11804032e+00 2.48000002e+00 2.35046577e+00 3.42611361e+00 3.47289777e+00 3.31904411e+00 3.11399961e+00 3.66926932e+00 4.98871565e+00 4.61997080e+00 4.60350895e+00 4.99178457e+00 3.93776417e+00 3.98865986e+00 4.54593182e+00 6.91775942e+00 7.15589428e+00 4.43610764e+00 3.57379508e+00 4.69059134e+00 6.87300825e+00 7.00457335e+00 5.02353001e+00 4.39753199e+00 3.90322852e+00 4.05871344e+00 4.57511139e+00 5.41436148e+00 6.50780487e+00 5.59207344e+00 4.56777191e+00 4.46396112e+00 5.14890242e+00 6.20504951e+00 5.50788116e+00 5.06208992e+00 4.91740131e+00 4.29014874e+00 4.12867165e+00 3.64140081e+00 3.98342752e+00 4.20065975e+00 3.69448137e+00 3.93133831e+00 4.41430807e+00 5.94469261e+00 6.87858725e+00 6.51082659e+00 5.96531868e+00 4.99634218e+00 4.79277706e+00 4.37293482e+00 3.91368437e+00 3.88184500e+00 4.20084143e+00 4.41121864e+00 4.30444717e+00 3.98976421e+00 4.60071039e+00 5.68752813e+00 6.56784201e+00 6.79906607e+00 5.40347528e+00 4.95749283e+00 5.24709177e+00 6.03295708e+00 5.89362812e+00 5.19577456e+00 5.28178310e+00 5.11622000e+00 5.08654070e+00 5.07464552e+00 5.41552830e+00 5.70160532e+00 5.32966471e+00 5.00776196e+00 5.12718248e+00 5.11526728e+00 5.03778028e+00 4.71886301e+00 4.35172892e+00 4.13029385e+00 3.96022725e+00 4.77881670e+00 5.37024021e+00 5.71846390e+00 5.68602705e+00 5.18995380e+00 5.26706648e+00 5.47253895e+00 6.13340187e+00 6.10546732e+00 5.64838362e+00 5.27635193e+00 5.13556671e+00 5.28252029e+00 5.18925095e+00 5.09203291e+00 5.15717840e+00 5.26525593e+00 5.31052971e+00 5.31037045e+00 5.41115522e+00 5.58632326e+00 5.59659958e+00 5.73454142e+00 5.72974205e+00 5.54053926e+00 5.38876581e+00 5.43492842e+00 5.61297703e+00 5.67619324e+00 5.66242123e+00 5.69228888e+00 5.71036863e+00 5.70765305e+00 5.68393946e+00 5.66744423e+00 5.67299271e+00 5.72815561e+00 5.76254654e+00 5.71359873e+00 5.62442970e+00 5.58846664e+00 5.67148066e+00 5.73138905e+00 5.69303942e+00 5.69909477e+00 5.68573093e+00 5.67614794e+00 5.65496635e+00 5.68823767e+00 5.69807768e+00 5.72370386e+00 5.70146084e+00 5.64343500e+00 5.50681591e+00 5.44607210e+00 5.52316904e+00 5.65271187e+00 5.67272949e+00 5.59659195e+00 5.63378000e+00 5.65775681e+00 5.91675138e+00 6.07764769e+00 6.09597635e+00 5.85934877e+00 5.54328156e+00 5.62309790e+00 5.64993525e+00 5.71689653e+00 5.69015217e+00 5.84994411e+00 5.81699991e+00 5.79164267e+00 5.63999510e+00 5.69049644e+00 5.53623724e+00 5.39298344e+00 5.43617582e+00 5.52653790e+00 5.40018511e+00 5.32737970e+00 5.35936308e+00 5.44693327e+00 5.39118671e+00 5.41625786e+00 5.59774017e+00 5.48167515e+00 5.36584949e+00 5.33123827e+00 5.53930140e+00 5.52861214e+00 5.29926348e+00 5.11595058e+00 5.21939135e+00 5.09110451e+00 4.89787102e+00 4.79123735e+00 5.09082699e+00 5.31634235e+00 5.33446980e+00 5.26884794e+00 5.26191902e+00 5.21878529e+00 5.36581802e+00 5.81275511e+00 6.23689651e+00 6.18974304e+00 5.86947203e+00 5.62831020e+00 5.48877621e+00 5.51499128e+00 5.54832554e+00 5.63899946e+00 5.49443102e+00 5.44888496e+00 5.57075262e+00 5.54014444e+00 5.00535631e+00 4.59282875e+00 4.58994102e+00 5.06792688e+00 5.36984253e+00 5.65059853e+00 5.97812939e+00 6.01564407e+00 5.72147846e+00 5.32093191e+00 5.36824083e+00 5.78503799e+00 5.35765505e+00 4.57807493e+00 4.39945793e+00 4.99279833e+00 5.83737755e+00 5.84928322e+00 5.94624281e+00 6.06367254e+00 5.40196609e+00 4.34837103e+00 3.92260885e+00 4.25755167e+00 5.00603533e+00 5.05322552e+00 5.13671780e+00 5.32227468e+00 5.45378780e+00 5.55220461e+00 5.47362328e+00 5.49637079e+00 5.16284657e+00 5.10268974e+00 5.40550184e+00 6.03419876e+00 6.88678217e+00 7.33313608e+00 7.16268635e+00 6.43065548e+00 5.86980915e+00 6.26368570e+00 6.48269558e+00 5.78155136e+00 4.73061037e+00 4.12000227e+00 4.98426533e+00 5.86437893e+00 6.28143454e+00 5.71153355e+00 5.37391424e+00 5.33631468e+00 5.52692604e+00 6.72141123e+00 7.80840492e+00 6.06057978e+00 2.99399686e+00 2.19838500e+00 3.69834518e+00 5.53303051e+00 5.36909676e+00 5.18555784e+00 4.91721201e+00 5.08625889e+00 5.35258341e+00 5.14593410e+00 4.15856218e+00 3.00074792e+00 3.82536817e+00 5.93200827e+00 7.39231825e+00 6.38824177e+00 4.85631657e+00 4.17794418e+00 4.22449017e+00 4.16612339e+00 3.77976894e+00 2.64509034e+00 1.85693657e+00 2.66180778e+00 4.00396919e+00 4.50366497e+00 3.87916112e+00 3.87140322e+00 4.54042387e+00 4.58598900e+00 4.39822149e+00 4.23389339e+00 3.97469521e+00 3.57223558e+00 2.99863434e+00 3.64080453e+00 4.23348665e+00 4.62454081e+00 5.42269897e+00 6.83243752e+00 8.79638863e+00 9.66832066e+00 8.30281067e+00 6.58113527e+00 5.35725355e+00 5.26798344e+00 5.40688419e+00 5.88701820e+00 5.90216780e+00 5.51604128e+00 5.09024525e+00 4.93420076e+00 4.64537907e+00 5.71587706e+00 7.15352106e+00 7.59620142e+00 6.26031733e+00 4.52245855e+00 4.34869576e+00 4.25045538e+00 3.98822427e+00 3.33194304e+00 3.16985679e+00 3.48882127e+00 4.03523159e+00 4.52781677e+00 4.73184013e+00 4.58766079e+00 3.32410717e+00 2.65925384e+00 2.65429449e+00 3.08443499e+00 3.62122393e+00 3.35046744e+00 2.87897873e+00 2.50548291e+00 2.90817857e+00 3.89554954e+00 4.73133326e+00 4.97422361e+00 4.72222424e+00 3.76600647e+00 2.54629087e+00 1.94291806e+00 3.13721561e+00 4.34334469e+00 5.13686705e+00 5.40390205e+00 6.00785112e+00 6.59414434e+00 6.23526573e+00 6.20109367e+00 1.05097318e+00 -9.16026878e+00 -2.41640148e+01 -9.30012703e+00 -2.09403778e+02 -1.15877014e+03 -84771944. 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. 0. 0. 0. 0. 0. 0. 2.87524922e+04 -1.71477844e+02 -2.59168930e+01 -1.05625172e+01 6.23750687e+00 7.19191313e+00 7.84965515e+00 2.34115410e+00 4.35542107e+00 5.04718351e+00 4.50128222e+00 1.43094862e+00 -1.89114571e+00 -2.54882884e+00 -1.51416445e+00 -2.04907343e-01 -9.94298756e-01 -1.20443070e+00 -1.15727103e+00 -6.90184474e-01 -1.06236018e-01 -1.82080850e-01 5.12535512e-01 1.61148632e+00 2.06473660e+00 1.87319553e+00 1.35474133e+00 2.51488280e+00 3.21252465e+00 3.77251816e+00 3.85577440e+00 3.45776772e+00 3.44368100e+00 3.17330456e+00 3.88943696e+00 4.26108646e+00 4.53942108e+00 3.77955174e+00 3.84469247e+00 4.00839615e+00 4.63868380e+00 3.54495144e+00 2.72092533e+00 2.32995796e+00 3.05428195e+00 3.95219040e+00 4.70706177e+00 5.55212927e+00 4.86733198e+00 5.51333570e+00 5.84088087e+00 6.23256207e+00 5.10019255e+00 3.57692623e+00 3.71325326e+00 4.24311638e+00 4.15342426e+00 3.96997309e+00 3.76689100e+00 4.12587261e+00 4.24813557e+00 3.66024017e+00 3.54582453e+00 5.39487183e-01 -2.02805758e+00 -2.87524223e+00 -2.16689968e+00 -1.29933655e+00 -3.22009850e+00 -4.41604376e+00 -2.77155566e+00 -7.01586246e-01 2.05004144e+00 2.68142772e+00 3.21061707e+00 5.07466459e+00 7.30831480e+00 9.37463284e+00 9.18106842e+00 6.66528463e+00 4.45649481e+00 2.95599580e+00 2.60190916e+00 2.84186459e+00 4.57685143e-01 -1.71625102e+00 -4.71771955e+00 -5.40604496e+00 -4.28655243e+00 -2.12975788e+00 1.63002402e-01 5.57350159e-01 -3.28761339e-02 -2.65673304e+00 -4.79492712e+00 -3.80584240e+00 -1.22859514e+00 7.70562887e-01 2.48266831e-01 -6.95794046e-01 -1.41089714e+00 -2.45041800e+00 3.83461535e-01 3.46067739e+00 5.01772642e+00 3.73937273e+00 1.29147160e+00 1.33476758e+00 6.37288809e-01 -8.84588659e-01 -2.18995929e+00 -4.33741045e+00 -4.16024542e+00 -1.64213097e+00 1.83038831e+00 5.04692173e+00 4.76747131e+00 3.92748284e+00 2.80856657e+00 2.43186617e+00 3.22243738e+00 3.50739646e+00 3.24027157e+00 2.41574597e+00 1.79090130e+00 1.20163226e+00 1.02366447e+00 1.00527763e+00 6.80327773e-01 -2.32541800e+00 -5.42317581e+00 -5.55652571e+00 -3.32130480e+00 -5.75373232e-01 -2.23732352e+00 -4.09043455e+00 -6.86220551e+00 -7.47855806e+00 -5.54677439e+00 -2.34673905e+00 6.09457493e-01 1.39340889e+00 1.40508425e+00 1.56545508e+00 1.71226406e+00 2.19788718e+00 2.59682178e+00 2.32028270e+00 1.19784403e+00 7.05397069e-01 1.00495839e+00 9.88252521e-01 4.67144668e-01 -7.83846736e-01 -3.46517253e+00 -6.30809832e+00 -5.86213255e+00 -3.07635808e+00 -1.96590289e-01 -2.74924994e+00 -5.50580835e+00 -7.61642742e+00 -7.80889750e+00 -8.40522861e+00 -8.76377106e+00 -6.42759562e+00 -4.59497833e+00 -1.63366973e+00 -1.18671250e+00 -3.45218122e-01 -9.64308977e-02 -1.08208632e+00 -1.12978625e+00 -1.24947846e+00 -9.45823789e-01 -1.61889625e+00 -1.10459709e+00 2.91126990e+00 6.42912483e+00 6.28622150e+00 2.75811601e+00 -3.20578724e-01 -1.21813405e+00 -1.39862192e+00 -5.80224037e-01 1.02686834e+00 -6.29355252e-01 -3.88415861e+00 -4.51731586e+00 -2.37010407e+00 2.14329287e-01 -4.70442355e-01 -1.19224298e+00 -1.49062145e+00 -8.98144066e-01 -1.12140501e+00 -1.21065438e+00 -1.75650811e+00 -1.82464111e+00 -1.87684333e+00 -1.85532868e+00 -1.78551686e+00 4.24081445e-01 2.92046142e+00 2.92656612e+00 1.14604700e+00 -1.25515938e+00 -1.23746753e-01 -3.22252005e-01 -1.16402316e+00 -1.82592237e+00 -2.02513504e+00 -1.43531847e+00 -1.27139628e+00 -1.02263927e+00 -1.27419925e+00 -1.80607402e+00 -1.44306242e+00 -9.16380525e-01 -8.45463693e-01 -7.19534814e-01 -7.85053015e-01 5.30889817e-03 -2.33290359e-01 -5.77649534e-01 -8.81122470e-01 -5.48799098e-01 1.43402803e+00 2.81188607e+00 2.78882170e+00 1.61476254e+00 7.49520734e-02 6.28563583e-01 1.81145251e-01 1.03964531e+00 1.60795081e+00 1.85260642e+00 1.23399448e+00 3.64381939e-01 1.24353206e+00 1.47077012e+00 1.23953295e+00 -1.34837061e-01 -1.36283052e+00 -1.57875884e+00 5.86412251e-01 3.10613203e+00 3.94966030e+00 1.94416440e+00 -3.92297530e+00 -7.80029392e+00 -7.66364908e+00 -4.29573536e+00 -1.73260629e+00 -4.79653120e+00 -7.01108408e+00 -6.41854429e+00 -3.06760335e+00 -5.83072782e-01 -6.49229646e-01 -7.81410098e-01 -1.06343639e+00 -1.49203515e+00 -1.06996226e+00 -6.59060657e-01 -7.70324647e-01 -1.78130591e+00 -2.88744378e+00 -1.36169732e+00 5.33327758e-02 5.22815168e-01 -1.62320125e+00 -3.28126121e+00 -3.40833759e+00 -3.31113124e+00 -3.43497753e+00 -3.38010287e+00 -3.74866891e+00 -3.47562504e+00 -5.20402765e+00 -6.40648603e+00 -5.85615158e+00 -3.40143013e+00 -8.56209219e-01 -7.46629477e-01 -1.35106349e+00 -2.46928668e+00 -2.97087526e+00 -1.08940208e+00 1.48729026e+00 1.46257722e+00 -4.88232136e-01 -2.83489656e+00 -1.98310435e+00 -1.81460059e+00 -1.87382555e+00 -2.49844790e+00 -4.82458973e+00 -7.28905964e+00 -7.21424913e+00 -5.24328279e+00 -2.18098164e+00 -2.17774367e+00 -2.33576274e+00 -2.53201342e+00 -2.58206582e+00 -4.25273323e+00 -6.86232662e+00 -7.41158485e+00 -6.39112043e+00 -3.89198518e+00 -4.05993986e+00 -3.66713691e+00 -3.52848697e+00 -2.85654473e+00 -3.30442333e+00 -4.01941776e+00 -4.82222319e+00 -4.22913885e+00 -3.50062418e+00 -2.99435663e+00 -3.02258277e+00 -2.43262458e+00 -1.71754611e+00 -1.17992091e+00 -6.89525425e-01 -1.22778666e+00 -3.71040821e+00 -6.96523046e+00 -9.08658981e+00 -9.57511044e+00 -9.24295425e+00 -8.55626774e+00 -5.02580643e+00 -3.42104435e+00 -1.76770377e+00 -2.59668422e+00 -2.59896350e+00 -4.32486153e+00 -6.68538475e+00 -6.11381054e+00 -5.01315403e+00 -1.38967800e+00 4.46544409e-01 9.90761340e-01 -3.39539289e-01 -2.53029060e+00 -3.17437220e+00 -4.45279646e+00 -6.89523458e+00 -8.39618111e+00 -7.01778889e+00 -4.32633972e+00 -1.32236373e+00 -2.98311067e+00 -5.14606285e+00 -6.50630379e+00 -6.19136333e+00 -4.43969154e+00 -3.21167922e+00 -1.22579873e+00 -1.21249008e+00 -1.65198517e+00 -1.66559887e+00 -1.64978671e+00 -1.77354336e+00 -2.01129818e+00 -2.45617628e+00 -2.58831930e+00 -2.82034326e+00 -3.10710454e+00 -3.71972203e+00 -6.00022507e+00 -8.57511520e+00 -6.79385471e+00 -3.31985664e+00 -2.39904618e+00 -6.11649942e+00 -8.15865135e+00 -6.98674250e+00 -4.87582922e+00 -6.38263035e+00 -7.65160894e+00 -7.85092831e+00 -6.31615019e+00 -4.39994526e+00 -4.50129509e+00 -4.83393574e+00 -5.90531492e+00 -5.83873224e+00 -5.31504154e+00 -4.32120895e+00 -3.98556733e+00 -3.99931955e+00 -4.77091551e+00 -4.87889385e+00 -5.55325222e+00 -6.32348442e+00 -7.93776751e+00 -5.85936451e+00 -2.36531949e+00 -2.61131978e+00 -6.08763790e+00 -8.29205227e+00 -5.88417149e+00 -4.12810564e+00 -5.03444672e+00 -6.12748337e+00 -4.68514824e+00 -2.25423193e+00 -9.27079797e-01 -1.51074541e+00 -2.01451325e+00 -3.61949992e+00 -5.70557880e+00 -5.83646822e+00 -3.79212284e+00 -3.49159336e+00 -6.20860672e+00 -6.53622484e+00 -4.90869570e+00 -2.57790136e+00 -2.60751581e+00 -2.79183650e+00 -1.72410154e+00 -5.41362047e-01 -1.82693875e+00 -4.25833893e+00 -6.20039511e+00 -5.22983932e+00 -4.50111961e+00 -4.51784420e+00 -4.58812284e+00 -4.67000628e+00 -4.70260334e+00 -4.48097038e+00 -3.45858717e+00 -3.50647688e+00 -4.85190582e+00 -6.64591122e+00 -7.05709553e+00 -6.35844231e+00 -7.26963234e+00 -9.22321606e+00 -8.30073833e+00 -5.43355560e+00 -2.39647532e+00 -2.11645770e+00 -3.33970737e+00 -3.16279769e+00 -2.86199188e+00 -3.11733413e+00 -4.25094318e+00 -5.44776249e+00 -5.39018297e+00 -4.80182648e+00 -4.33395481e+00 -3.34346390e+00 -3.13074231e+00 -3.33203721e+00 -3.60298061e+00 -3.57557917e+00 -3.49353886e+00 -4.92894173e+00 -5.95688534e+00 -5.44242811e+00 -4.15102816e+00 -3.79952121e+00 -4.83162260e+00 -4.17868280e+00 -2.90871501e+00 -3.28162169e+00 -6.05899191e+00 -9.16894341e+00 -9.66891193e+00 -8.55414581e+00 -8.02222538e+00 -8.47135735e+00 -7.93954039e+00 -6.99029303e+00 -6.11944437e+00 -6.37291813e+00 -6.25058317e+00 -6.57459545e+00 -7.50701618e+00 -7.44855118e+00 -6.19754219e+00 -4.44213915e+00 -5.13147926e+00 -6.67389154e+00 -6.94446898e+00 -5.52610397e+00 -5.54192066e+00 -6.87604046e+00 -5.92702293e+00 -3.05549216e+00 -1.19230044e+00 -2.33372331e+00 -3.93949628e+00 -3.43498254e+00 -2.25371170e+00 -2.02883863e+00 -2.92585111e+00 -3.53128266e+00 -2.88636112e+00 -2.59593439e+00 -2.94105935e+00 -3.93082333e+00 -5.42579556e+00 -7.00867796e+00 -7.83319139e+00 -7.81958961e+00 -5.68454838e+00 -3.94698930e+00 -3.11319399e+00 -4.16382694e+00 -4.99754238e+00 -4.99222136e+00 -4.87052965e+00 -4.20248604e+00 -2.97223401e+00 -3.30183721e+00 -4.44336653e+00 -5.61696482e+00 -5.61726046e+00 -5.62960386e+00 -6.75619078e+00 -7.62201262e+00 -7.40146732e+00 -6.36081934e+00 -5.61624146e+00 -5.55562639e+00 -5.46810865e+00 -5.42062092e+00 -5.73964977e+00 -5.98692513e+00 -5.93763208e+00 -5.61976385e+00 -5.40318775e+00 -5.23714256e+00 -5.21308851e+00 -5.36334991e+00 -6.22431374e+00 -7.36469507e+00 -7.34319162e+00 -6.67803097e+00 -6.49423599e+00 -7.19407463e+00 -7.08046913e+00 -6.46885872e+00 -5.81561756e+00 -6.56757307e+00 -7.21999645e+00 -6.98077297e+00 -6.18239260e+00 -5.07236958e+00 -5.00993633e+00 -5.03763914e+00 -5.68960524e+00 -6.39044619e+00 -6.44840193e+00 -5.86457682e+00 -5.92067242e+00 -6.61380911e+00 -6.76762152e+00 -6.24001837e+00 -5.46199894e+00 -5.95885706e+00 -6.57268715e+00 -6.49360275e+00 -5.59188461e+00 -4.90132141e+00 -5.28146076e+00 -5.96860886e+00 -6.09500170e+00 -6.08867264e+00 -5.88898706e+00 -5.92227936e+00 -6.04753304e+00 -6.08719730e+00 -6.56720877e+00 -6.79779863e+00 -6.66546631e+00 -6.26328564e+00 -5.85096264e+00 -5.88796520e+00 -5.82896614e+00 -5.82387066e+00 -5.83348417e+00 -5.76503420e+00 -5.80123615e+00 -5.71202564e+00 -5.71635437e+00 -5.63498878e+00 -5.28499746e+00 -5.03967714e+00 -5.39170122e+00 -5.98259163e+00 -6.18697500e+00 -5.82615137e+00 -5.54151821e+00 -5.53540325e+00 -5.57057381e+00 -5.60209513e+00 -5.57243204e+00 -5.64876127e+00 -5.69302368e+00 -5.73671722e+00 -5.85153246e+00 -6.06710482e+00 -6.72626257e+00 -8.02966404e+00 -7.08432388e+00 -6.53393459e+00 -2.43073330e+01 -5.94676666e+01 -7.87669850e+06 -34023064. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 402289120. 226802656. 4.19350967e+01 -5.99763203e+00 -1.04159384e+01 -4.88692379e+00 -4.38398218e+00 -3.68879008e+00 -3.39351535e+00 -3.20440459e+00 -3.08741426e+00 -3.06697989e+00 -3.09243608e+00 -3.12347627e+00 -3.16469407e+00 -3.17010760e+00 -3.19486094e+00 -3.14326859e+00 -3.07506943e+00 -3.00409365e+00 -3.00335097e+00 -3.11208606e+00 -3.21924853e+00 -3.30074167e+00 -3.32019639e+00 -3.24351263e+00 -3.23050618e+00 -3.21359587e+00 -3.12051010e+00 -3.06676912e+00 -3.09385252e+00 -3.26072645e+00 -3.37940311e+00 -3.39324880e+00 -3.29889655e+00 -3.11358976e+00 -3.04435468e+00 -3.05104256e+00 -3.06237721e+00 -3.07042837e+00 -3.10348845e+00 -3.23957348e+00 -3.35439706e+00 -3.27599382e+00 -3.12635660e+00 -3.04362535e+00 -3.13689137e+00 -3.11811137e+00 -3.06616092e+00 -3.13404441e+00 -3.16336989e+00 -3.16683578e+00 -3.10026789e+00 -2.99954820e+00 -2.93338728e+00 -2.90882158e+00 -3.12969446e+00 -3.42589498e+00 -3.49729872e+00 -3.33383822e+00 -3.00578856e+00 -2.97021914e+00 -3.16738176e+00 -3.43911576e+00 -3.41803074e+00 -3.26229382e+00 -3.18735600e+00 -3.25628304e+00 -3.25556087e+00 -3.05723977e+00 -2.78355908e+00 -2.88341403e+00 -2.96456647e+00 -3.03003860e+00 -3.04599023e+00 -3.03562069e+00 -3.17046475e+00 -3.06934643e+00 -2.93780303e+00 -2.73206782e+00 -2.71938324e+00 -2.94001961e+00 -3.22214794e+00 -3.44988966e+00 -3.48941779e+00 -3.22739387e+00 -3.16563964e+00 -3.11863756e+00 -2.93550134e+00 -2.64982629e+00 -2.61302376e+00 -3.00912309e+00 -3.37661982e+00 -3.38079071e+00 -2.98114848e+00 -2.57315254e+00 -2.52357054e+00 -2.58041239e+00 -2.57040191e+00 -2.54269814e+00 -2.64517379e+00 -2.82581782e+00 -2.94215250e+00 -2.83192992e+00 -2.60783982e+00 -2.32287598e+00 -2.23869181e+00 -2.54166436e+00 -3.00373101e+00 -3.38461590e+00 -3.11026931e+00 -2.73813581e+00 -2.65252233e+00 -2.64046860e+00 -2.55339336e+00 -2.56756783e+00 -2.68817115e+00 -2.88094926e+00 -2.82243395e+00 -2.47225070e+00 -2.26128602e+00 -2.14857841e+00 -2.41528010e+00 -2.68445015e+00 -3.07232928e+00 -3.29106879e+00 -5.01192427e+00 -1.40691376e+01 -8.83174438e+01 -1.59586288e+02 -3.83397560e+01 -3.85518646e+01 -3.23851013e+01 -2.46994915e+01 1.73456421e+02 1.05237846e+02 1.93300610e+01 -7.93258619e+00 -2.19828739e+01 -9.86080780e+01 -1.64293640e+02 -3.54625244e+01 -2.78799801e+01 -1.57007484e+01 -8.38701916e+00 -1.14907951e+01 -1.70538197e+01 -1.91669521e+01 -2.32660389e+01 -2.48564453e+01 -2.24929504e+01 1.70708084e+02 1.08026245e+02 2.11311016e+01 6.62410402e+00 -4.03474426e+00 -3.44867826e+00 -3.59577990e+00 -2.37953234e+00 -2.76165581e+00 -2.32367659e+00 -2.08886743e+00 -2.41989303e+00 -2.75160050e+00 -2.81157470e+00 -2.85152316e+00 -2.90063977e+00 -3.25402093e+00 -3.49638104e+00 -3.49413037e+00 -2.85824633e+00 -2.12007117e+00 -1.98595357e+00 -2.01977897e+00 -1.97649872e+00 -2.03889084e+00 -2.16843653e+00 -2.73629260e+00 -2.88016582e+00 -2.59810424e+00 -1.99562800e+00 -1.89409935e+00 -2.26174140e+00 -2.47183895e+00 -2.60597682e+00 -2.62399602e+00 -2.64559960e+00 -2.64485121e+00 -2.70697021e+00 -2.52891397e+00 -2.65336013e+00 -2.92070317e+00 -3.60364103e+00 -4.03128910e+00 -3.72293115e+00 -2.67018390e+00 -1.62006283e+00 -1.52232897e+00 -1.78405464e+00 -1.87286282e+00 -1.95552301e+00 -2.21579289e+00 -2.82135558e+00 -2.92935443e+00 -2.27978086e+00 -1.49773836e+00 -1.29645312e+00 -1.78955281e+00 -2.17630625e+00 -2.14854217e+00 -2.17566347e+00 -2.07504201e+00 -2.24052668e+00 -2.47969627e+00 -2.23061061e+00 -1.82700336e+00 -1.40425444e+00 -2.00955892e+00 -2.44381618e+00 -2.92441130e+00 -2.14841485e+00 -1.72370470e+00 -1.48818028e+00 -1.77045345e+00 -1.94241202e+00 -2.10825086e+00 -2.13834977e+00 -1.97026300e+00 -1.69323397e+00 -1.58029866e+00 -1.53821397e+00 -1.22033441e+00 -1.09748971e+00 -9.33577657e-01 -1.40075421e+00 -2.01158500e+00 -2.63655567e+00 -2.84416938e+00 -2.61052728e+00 -2.04485154e+00 -1.42674506e+00 -8.14722538e-01 -1.75941932e+00 -2.54455924e+00 -2.77342987e+00 -1.80448139e+00 -1.08504391e+00 -1.29072404e+00 -1.53974271e+00 -1.21650064e+00 -1.07620931e+00 -1.32623136e+00 -2.02363873e+00 -2.17955756e+00 -1.84943140e+00 -1.66682756e+00 -1.66845477e+00 -1.87750292e+00 -1.89158535e+00 -1.96224093e+00 -1.85859537e+00 -1.73463941e+00 -2.15935898e+00 -2.22933960e+00 -2.45543265e+00 -1.71016419e+00 -1.25795805e+00 -1.38518846e+00 -2.47431445e+00 -2.79135394e+00 -2.42342830e+00 -2.13674617e+00 -2.46846700e+00 -2.63742328e+00 -2.04818416e+00 -1.58030331e+00 -1.45558751e+00 -1.62812853e+00 -1.67905593e+00 -1.58300698e+00 -1.95093846e+00 -1.99006259e+00 -1.72280777e+00 -1.07011580e+00 -1.28595102e+00 -1.19269049e+00 -9.66139078e-01 -7.43032932e-01 -1.35914421e+00 -1.90036261e+00 -1.82412958e+00 -1.49062943e+00 -1.55803990e+00 -2.00989318e+00 -1.80045986e+00 -1.58157611e+00 -1.44918942e+00 -1.86811435e+00 -2.01032925e+00 -1.67556834e+00 -1.53390801e+00 -1.18125963e+00 -1.36243653e+00 -1.01277137e+00 -8.03039908e-01 -9.39503551e-01 -1.16567826e+00 -1.41838121e+00 -1.24989021e+00 -1.20355654e+00 -8.97926748e-01 -4.67747331e-01 -5.57479084e-01 -8.06909740e-01 -1.05678105e+00 -8.08658481e-01 -5.05080819e-01 -9.09096718e-01 -1.75673461e+00 -1.85815310e+00 -1.30950522e+00 -8.39264035e-01 -1.28003299e+00 -2.02055192e+00 -1.95601094e+00 -1.55078256e+00 -8.42423499e-01 -7.15067327e-01 -5.14526069e-01 -4.56673265e-01 -5.19680560e-01 -6.81512773e-01 -6.12600505e-01 -5.37261009e-01 -7.74858952e-01 -7.85733342e-01 -4.67996418e-01 -4.73538935e-01 -1.22112501e+00 -2.02242374e+00 -1.95071554e+00 -1.66508508e+00 -1.55491364e+00 -1.76977241e+00 -1.33166814e+00 -1.08859289e+00 -1.12080538e+00 -1.54328966e+00 -1.42211759e+00 -1.06840575e+00 -9.93516505e-01 -1.10401273e+00 -1.05919158e+00 -6.84105158e-01 -2.45581880e-01 -5.77809691e-01 -9.73843515e-01 -1.44289792e+00 -1.04763341e+00 -6.35059476e-01 -2.81502195e-02 7.40142941e-01 6.33179963e-01 -5.93123496e-01 -2.01434731e+00 -2.67544031e+00 -2.03216124e+00 -1.62078774e+00 -1.55680478e+00 -1.51637983e+00 -1.87539744e+00 -1.42508233e+00 -1.30823827e+00 -8.97863925e-01 -9.86460626e-01 -1.99769747e+00 -2.26839399e+00 -1.93070030e+00 -5.05889416e-01 3.95332068e-01 -7.51763508e-02 -8.32765102e-01 -1.13896716e+00 -2.95075774e-01 4.41308558e-01 4.15516168e-01 1.89057261e-01 -3.31890672e-01 -8.13689172e-01 -1.09098089e+00 -1.46717060e+00 -1.08045793e+00 -5.81974804e-01 -1.60835490e-01 -1.55412331e-01 -9.84013081e-01 -1.55073559e+00 -2.00151157e+00 -1.66733539e+00 -6.19598210e-01 -5.44313967e-01 -3.42351377e-01 -2.33733967e-01 7.05889821e-01 7.27934122e-01 -5.96067131e-01 -1.45807135e+00 -1.60654235e+00 -9.55282807e-01 -5.58364272e-01 -4.69983488e-01 -1.32957563e-01 -9.75624323e-02 -4.73891914e-01 -7.84923613e-01 -1.20578659e+00 -1.01475775e+00 -1.00417817e+00 -1.02106583e+00 -9.54738438e-01 -8.80904853e-01 -3.76795940e-02 2.14892596e-01 2.57417738e-01 -5.85981496e-02 -9.00755286e-01 -1.28552234e+00 -1.33306217e+00 -2.42712602e-01 6.88111901e-01 6.75495982e-01 4.12253588e-02 -7.59359539e-01 -2.00865045e-01 4.87440705e-01 1.11528981e+00 9.73231792e-01 4.79728848e-01 -1.13194354e-01 -4.89323586e-01 -7.05518901e-01 -3.12795997e-01 2.91897178e-01 5.90018153e-01 2.40894258e-01 -1.08817887e+00 -1.55917752e+00 -1.20371628e+00 -7.49974474e-02 7.43679523e-01 1.56765878e-01 -6.78316414e-01 -1.19104695e+00 -4.41851735e-01 4.30191427e-01 5.44152558e-01 2.66226172e-01 -1.57420859e-01 -7.07246305e-04 2.13702619e-01 -1.03514992e-01 -1.80082351e-01 -9.53239202e-02 2.70578653e-01 2.58376211e-01 -5.66510372e-02 -8.32078159e-02 -7.40499794e-03 4.53890972e-02 1.47529006e-01 -1.99600726e-01 3.69257361e-01 6.99653625e-01 1.38433826e+00 1.07713056e+00 5.05234227e-02 -7.40069807e-01 -9.55283165e-01 1.77120060e-01 1.07112610e+00 1.31397057e+00 1.01236832e+00 3.34134281e-01 1.56874329e-01 3.83746117e-01 7.41580486e-01 1.21416306e+00 8.25699449e-01 2.17150509e-01 -3.94479841e-01 -3.87953520e-01 5.85661948e-01 1.29456723e+00 1.67706251e+00 1.34577119e+00 3.40171963e-01 -4.13430989e-01 -4.21910197e-01 5.72334528e-01 1.45115876e+00 1.11206782e+00 2.79647291e-01 -2.38329232e-01 4.17880535e-01 1.38142967e+00 1.45343101e+00 1.12158585e+00 2.62940288e-01 -1.52278975e-01 -9.95468646e-02 1.61681827e-02 5.10440230e-01 8.70760322e-01 9.16734219e-01 7.10354388e-01 2.59303730e-02 2.01248705e-01 6.69533312e-01 1.08371127e+00 1.83716059e+00 1.23552978e+00 1.08518565e+00 7.87802279e-01 1.38822746e+00 1.62216890e+00 4.83666331e-01 -4.27642604e-03 -3.60868424e-02 1.02178812e+00 1.74334967e+00 1.66017091e+00 1.14434564e+00 2.95417517e-01 -5.40181994e-02 1.82453871e-01 4.03786480e-01 8.89678538e-01 1.00838518e+00 8.36305439e-01 9.06376541e-01 8.17729712e-01 1.53013432e+00 1.57789826e+00 1.60396826e+00 1.42783630e+00 7.72718847e-01 6.32561743e-01 9.66462135e-01 1.89542913e+00 2.34724951e+00 2.07762265e+00 1.51785398e+00 1.05746329e+00 1.47625935e+00 2.18084025e+00 2.47645259e+00 2.20193863e+00 1.63065410e+00 1.37990057e+00 1.29682434e+00 1.15958416e+00 1.12837827e+00 1.05651820e+00 1.09503686e+00 8.27969491e-01 4.73815858e-01 1.02029634e+00 1.97302294e+00 2.59316087e+00 2.35005784e+00 1.39427388e+00 7.43730605e-01 7.49597073e-01 1.51258159e+00 2.05462241e+00 1.81194150e+00 1.37124884e+00 1.21285939e+00 1.46629190e+00 1.58319402e+00 1.29684198e+00 1.00209618e+00 6.66898131e-01 5.31005919e-01 6.43714726e-01 6.02364838e-01 9.51806128e-01 1.18820512e+00 1.25789046e+00 1.39077544e+00 1.02687192e+00 1.20753515e+00 1.21206772e+00 1.50982690e+00 1.48516560e+00 6.50218248e-01 7.36763775e-01 8.39993715e-01 1.57929516e+00 1.89432085e+00 1.80306256e+00 1.71131754e+00 8.46721053e-01 9.34990168e-01 1.54654288e+00 2.19742846e+00 2.37904811e+00 1.52515256e+00 1.42610288e+00 1.57993531e+00 1.52138448e+00 1.30296445e+00 1.10901082e+00 1.79198432e+00 1.95387423e+00 1.31290865e+00 2.29383683e+00 2.91133451e+00 4.34353256e+00 3.97625613e+00 1.34025631e+01 2.01052341e+01 5.59535713e+01 3.08615784e+02 6.92939514e+02 179269984. 6380537. 4.71044650e+06 -810436672. 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. 0. 0. 0. 0. 0. 0. 0. 860252544. 2.88851587e+03 4.42013733e+02 -8.63506393e+01 -7.71113205e+01 -1.07868586e+01 -3.24411273e+00 3.28968577e-02 -1.06663442e+00 2.19389057e+00 2.38118601e+00 2.23705459e+00 2.29912615e+00 2.14479280e+00 2.04274035e+00 2.06603980e+00 2.23393321e+00 2.51339412e+00 2.47501659e+00 2.24602652e+00 2.14067316e+00 2.01378393e+00 2.16369867e+00 2.27993989e+00 2.65117764e+00 2.73653388e+00 2.22447467e+00 1.98747683e+00 2.30675912e+00 2.85262370e+00 2.63887525e+00 2.03077483e+00 1.94213545e+00 2.14731431e+00 2.45362639e+00 2.45816422e+00 2.52303529e+00 2.59534979e+00 2.56302166e+00 2.39874411e+00 2.26712322e+00 2.32793283e+00 2.53643727e+00 2.43446445e+00 2.25143766e+00 1.93214679e+00 1.55419135e+00 1.78104854e+00 2.67463517e+00 3.71441555e+00 3.72147012e+00 2.80865502e+00 2.37617636e+00 2.46120119e+00 2.90795732e+00 2.89516902e+00 2.63927007e+00 2.56126356e+00 2.48819041e+00 2.60440111e+00 2.53823638e+00 2.44637346e+00 2.41947103e+00 2.12948179e+00 1.92217827e+00 1.99266982e+00 2.28086710e+00 2.55861807e+00 2.47753167e+00 2.42750096e+00 2.19520044e+00 1.90000808e+00 1.72586679e+00 1.72111142e+00 2.04660559e+00 2.28459501e+00 2.14286685e+00 2.39318967e+00 2.68979859e+00 3.25673223e+00 3.19845057e+00 2.77071977e+00 2.60361552e+00 2.50342679e+00 2.50505352e+00 2.51661730e+00 2.62707424e+00 2.84945607e+00 2.64309335e+00 2.40063429e+00 2.41209197e+00 2.44730973e+00 2.34008050e+00 2.08554339e+00 2.25136113e+00 2.62440634e+00 2.50910187e+00 2.52191615e+00 2.52893567e+00 2.84361768e+00 2.90274930e+00 2.55208659e+00 2.54251671e+00 2.72010422e+00 3.15235305e+00 3.22932529e+00 2.91005993e+00 2.75090075e+00 2.57397723e+00 2.60567856e+00 2.51135492e+00 2.51164103e+00 2.62744522e+00 2.62973118e+00 2.60882568e+00 2.60782146e+00 2.71556687e+00 2.95607233e+00 2.93295074e+00 2.92188311e+00 2.83497000e+00 2.51100564e+00 2.54253674e+00 2.74182296e+00 3.21554375e+00 3.23766494e+00 2.83035946e+00 2.69704700e+00 2.86644220e+00 3.17677093e+00 3.21015239e+00 2.91583300e+00 2.71441007e+00 2.51725960e+00 2.56393099e+00 2.73576593e+00 2.98877168e+00 3.13234997e+00 2.96250463e+00 2.78000593e+00 2.79036522e+00 2.93248057e+00 3.10313582e+00 3.01183677e+00 2.95018315e+00 2.94351816e+00 2.83488011e+00 2.82330203e+00 2.74272728e+00 2.81754375e+00 2.84554148e+00 2.75031161e+00 2.77531075e+00 2.89595389e+00 3.14979744e+00 3.28317022e+00 3.20702600e+00 3.11509275e+00 2.97577286e+00 2.95584154e+00 2.85581708e+00 2.75926447e+00 2.79489207e+00 2.89424729e+00 2.94475150e+00 2.89707518e+00 2.85504723e+00 2.94697714e+00 3.11592245e+00 3.24921727e+00 3.29523897e+00 3.08467603e+00 3.01934004e+00 3.05671239e+00 3.17262840e+00 3.15166092e+00 3.03668189e+00 3.04982495e+00 3.03467584e+00 3.04172397e+00 3.05214477e+00 3.10233617e+00 3.14927435e+00 3.08197570e+00 3.02879143e+00 3.04401231e+00 3.05444431e+00 3.05362487e+00 3.00243950e+00 2.92963576e+00 2.87979269e+00 2.88885546e+00 3.04238844e+00 3.13796902e+00 3.16316748e+00 3.13927484e+00 3.06612992e+00 3.08763051e+00 3.11913300e+00 3.21428823e+00 3.20257759e+00 3.12915993e+00 3.07757020e+00 3.06315827e+00 3.09228134e+00 3.07678008e+00 3.06692529e+00 3.07922697e+00 3.09988713e+00 3.09967470e+00 3.09579659e+00 3.10375786e+00 3.12962794e+00 3.13648844e+00 3.16078901e+00 3.16315842e+00 3.13552260e+00 3.11252570e+00 3.12013102e+00 3.14503717e+00 3.15493894e+00 3.15352678e+00 3.15834999e+00 3.16102648e+00 3.16031361e+00 3.15649033e+00 3.15430617e+00 3.15566254e+00 3.16387606e+00 3.16832423e+00 3.16146016e+00 3.14909434e+00 3.14419079e+00 3.15541053e+00 3.16382384e+00 3.16127944e+00 3.16693044e+00 3.16354585e+00 3.16054368e+00 3.15257168e+00 3.15959334e+00 3.15415406e+00 3.15492320e+00 3.15036082e+00 3.14320564e+00 3.12445092e+00 3.11469221e+00 3.12529421e+00 3.14242530e+00 3.14494658e+00 3.13370419e+00 3.13947964e+00 3.14043760e+00 3.17645931e+00 3.19588661e+00 3.20064235e+00 3.16822791e+00 3.12670803e+00 3.13556194e+00 3.13594818e+00 3.14095044e+00 3.14564514e+00 3.18407607e+00 3.18286061e+00 3.16840959e+00 3.12975144e+00 3.14054132e+00 3.10644913e+00 3.09432054e+00 3.09618926e+00 3.11538720e+00 3.08028603e+00 3.07199216e+00 3.07996655e+00 3.09581208e+00 3.07972598e+00 3.07633305e+00 3.10718584e+00 3.09192562e+00 3.07810688e+00 3.06653500e+00 3.09624267e+00 3.09032536e+00 3.05370307e+00 3.03240991e+00 3.04376578e+00 3.01846290e+00 2.98533010e+00 2.96702456e+00 3.01978850e+00 3.05369401e+00 3.03709531e+00 3.01097798e+00 3.00458479e+00 3.02171063e+00 3.05783653e+00 3.18752623e+00 3.31077027e+00 3.29974008e+00 3.17145514e+00 3.06817365e+00 3.04035211e+00 3.05206847e+00 3.04265356e+00 3.05520272e+00 3.03024220e+00 3.03579402e+00 3.05957651e+00 3.04979134e+00 2.94676089e+00 2.91580510e+00 2.96170807e+00 3.03765345e+00 3.02114081e+00 3.00694060e+00 3.04528379e+00 3.08523154e+00 3.05182672e+00 3.00619459e+00 2.98989320e+00 3.03282666e+00 2.96284509e+00 2.83439422e+00 2.81396151e+00 2.89301229e+00 3.03359270e+00 3.03317237e+00 3.04181123e+00 3.06149101e+00 2.98335624e+00 2.85200548e+00 2.78725934e+00 2.81027603e+00 2.91204023e+00 2.87355590e+00 2.87433600e+00 2.87977266e+00 2.93125749e+00 2.97071004e+00 2.96892142e+00 2.97740841e+00 2.90350842e+00 2.87696266e+00 2.89485002e+00 2.99582601e+00 3.12279987e+00 3.21677494e+00 3.17424297e+00 3.09065938e+00 3.04246759e+00 3.07775784e+00 3.08798146e+00 2.91081357e+00 2.72356677e+00 2.57137609e+00 2.82608724e+00 3.16041756e+00 3.30521441e+00 3.06881547e+00 2.81787062e+00 2.77204800e+00 2.79961395e+00 3.03449917e+00 3.30822611e+00 3.03921866e+00 2.51480508e+00 2.31441045e+00 2.57065916e+00 2.85788393e+00 2.81756783e+00 2.74756217e+00 2.69425654e+00 2.71883893e+00 2.76856971e+00 2.74994445e+00 2.49637461e+00 2.26564837e+00 2.41806173e+00 2.83952379e+00 3.12281227e+00 2.93346620e+00 2.70542407e+00 2.58845639e+00 2.62705112e+00 2.56981134e+00 2.49303913e+00 2.35889745e+00 2.29546905e+00 2.41066599e+00 2.53719854e+00 2.54208326e+00 2.45025849e+00 2.46269631e+00 2.55920601e+00 2.54523373e+00 2.51389480e+00 2.51016498e+00 2.46277165e+00 2.43181491e+00 2.34017563e+00 2.44141364e+00 2.52842665e+00 2.59804416e+00 2.69544482e+00 2.81783843e+00 2.99189782e+00 3.09332776e+00 3.00895882e+00 2.89058304e+00 2.74613309e+00 2.74921131e+00 2.76804638e+00 2.76409125e+00 2.73326087e+00 2.65024686e+00 2.61329579e+00 2.55284929e+00 2.49925399e+00 2.65456414e+00 2.84923553e+00 2.89535666e+00 2.54203796e+00 2.13332081e+00 2.12581205e+00 2.22604060e+00 2.33033872e+00 2.22344518e+00 2.26034951e+00 2.31148529e+00 2.59736013e+00 2.88891721e+00 2.93030643e+00 2.71486044e+00 2.29934287e+00 2.12466073e+00 2.08023143e+00 2.09690785e+00 2.22844386e+00 2.19346786e+00 2.13810706e+00 2.02878213e+00 2.09439015e+00 2.16541886e+00 2.34071016e+00 2.32871842e+00 2.30736756e+00 2.13639140e+00 1.99150002e+00 2.08893657e+00 2.42192841e+00 2.56607652e+00 2.47482610e+00 2.29271555e+00 2.31085229e+00 2.30128908e+00 2.13803124e+00 5.19917428e-01 1.49926171e-01 -1.15322626e+00 7.86676884e-01 8.18457413e+00 -1.72007471e-01 3.24506798e+01 -1.82783086e+04 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. 0. 0. 0. 0. 0. 0. 5.95277344e+04 -2.67634796e+02 1.49732620e+02 1.22204720e+02 3.88568039e+01 1.96772938e+01 9.47439384e+00 3.49454117e+00 5.17938089e+00 2.35069966e+00 2.03385067e+00 1.49515831e+00 9.63468552e-01 8.80999923e-01 1.09592736e+00 1.26498818e+00 1.13424385e+00 1.08902025e+00 1.17049706e+00 1.27281713e+00 1.30167067e+00 1.22367072e+00 1.05600846e+00 9.71261382e-01 1.05171096e+00 1.23499370e+00 1.34368277e+00 1.46340358e+00 1.54671311e+00 1.69030440e+00 1.73474050e+00 1.68071294e+00 1.73385334e+00 1.69391119e+00 1.86236167e+00 1.84083116e+00 1.84418881e+00 1.65777576e+00 1.49652958e+00 1.43765390e+00 1.50057590e+00 1.54509473e+00 1.54775226e+00 1.46053469e+00 1.52380502e+00 1.62964475e+00 1.72154438e+00 1.83486331e+00 1.71994829e+00 1.81614459e+00 1.91648638e+00 1.91611457e+00 1.71531057e+00 1.39804149e+00 1.45458007e+00 1.54921436e+00 1.56745446e+00 1.55904043e+00 1.50444162e+00 1.55885208e+00 1.57093775e+00 1.61013782e+00 1.74143219e+00 1.34909701e+00 8.71051550e-01 5.82684278e-01 6.68676674e-01 8.23903561e-01 5.04962385e-01 1.97748959e-01 3.30809683e-01 6.26077652e-01 1.07269692e+00 1.16414905e+00 1.21419203e+00 1.50926328e+00 1.90271473e+00 2.25672412e+00 2.25490952e+00 1.84398198e+00 1.49209857e+00 1.28422463e+00 1.25571859e+00 1.33980536e+00 9.51025844e-01 2.96845287e-01 -8.21431801e-02 -2.63117582e-01 1.61287546e-01 2.75881648e-01 6.10333264e-01 6.40995443e-01 6.84940279e-01 3.83201122e-01 9.10283178e-02 1.75960436e-01 4.94400680e-01 7.43746221e-01 6.17582262e-01 4.92870063e-01 3.31993192e-01 1.59379765e-01 5.90513289e-01 1.14550996e+00 1.34397829e+00 1.10194242e+00 7.04563022e-01 7.11633503e-01 6.71132684e-01 4.43744004e-01 2.23278329e-01 -1.13443278e-01 -5.33698760e-02 4.04602170e-01 9.06341553e-01 1.35497391e+00 1.22548676e+00 1.07145131e+00 8.69034350e-01 8.40385258e-01 9.35941100e-01 9.26745176e-01 7.69322157e-01 6.46734059e-01 6.50255978e-01 6.68791175e-01 7.45507896e-01 7.26593554e-01 8.13273668e-01 2.85914630e-01 -2.76342899e-01 -4.48558092e-01 -2.57680491e-02 5.16054213e-01 2.68069565e-01 -8.04749802e-02 -5.69448590e-01 -7.18292832e-01 -4.44245398e-01 -6.61445260e-02 3.25323939e-01 3.11753064e-01 3.73624384e-01 4.87582892e-01 6.42879069e-01 7.95493066e-01 8.14304650e-01 7.21427441e-01 4.47858155e-01 3.63145411e-01 3.32905143e-01 3.16600442e-01 1.28973886e-01 -4.60322686e-02 -4.68045801e-01 -7.76197195e-01 -7.11805463e-01 -3.21583807e-01 1.24870837e-01 -2.95215368e-01 -6.23723328e-01 -1.03128672e+00 -1.11628485e+00 -1.33234215e+00 -1.46762145e+00 -1.08460045e+00 -7.23036587e-01 -1.05827145e-01 -4.69772443e-02 -5.07966336e-03 -8.96594450e-02 -2.17407331e-01 -9.63719487e-02 -9.86860916e-02 -4.86437678e-02 -1.92138210e-01 -8.99239480e-02 4.85988945e-01 9.43855286e-01 8.76873195e-01 3.81643951e-01 -4.38420251e-02 -2.84768969e-01 -4.39771712e-01 -4.53349769e-01 -1.39516890e-01 -3.61495316e-01 -8.14832509e-01 -9.26350176e-01 -5.72052896e-01 -1.66291445e-02 -5.88900223e-02 -5.14619276e-02 -1.11880511e-01 -5.34241572e-02 -9.70575064e-02 -1.25125021e-01 -1.91567466e-01 -2.20454529e-01 -2.54144877e-01 -2.46729746e-01 -2.93139696e-01 -3.05439625e-02 2.96002448e-01 2.90503263e-01 -8.95338785e-03 -4.22334939e-01 -2.92886078e-01 -3.35078090e-01 -4.66240823e-01 -6.44720376e-01 -6.27736986e-01 -5.40157259e-01 -4.70395476e-01 -4.24539179e-01 -4.15221632e-01 -4.83472049e-01 -4.22730774e-01 -3.54716957e-01 -3.53989393e-01 -4.09170747e-01 -3.15093368e-01 -1.73339471e-01 -2.22824484e-01 -3.70477170e-01 -4.78616685e-01 -4.56576943e-01 -1.69949308e-01 -2.20783297e-02 -1.75241511e-02 -2.57681221e-01 -4.28121418e-01 -2.68506497e-01 -2.77387351e-01 -1.96875155e-01 -1.22447632e-01 -1.78732321e-01 -1.92431092e-01 -3.67372811e-01 -2.25531250e-01 -2.14302987e-01 -1.67081654e-01 -3.79980206e-01 -5.90821505e-01 -7.21031547e-01 -3.09509277e-01 4.13483940e-02 7.36334100e-02 -2.92766243e-01 -1.10412121e+00 -1.57499480e+00 -1.57666171e+00 -1.15074730e+00 -1.00283277e+00 -1.71184087e+00 -1.79654646e+00 -1.36708081e+00 -6.06080234e-01 -4.31091726e-01 -5.09086788e-01 -5.49846292e-01 -6.18512869e-01 -7.99737394e-01 -7.89099395e-01 -7.22612381e-01 -7.46585786e-01 -9.35043752e-01 -1.20850658e+00 -1.09998274e+00 -8.59213650e-01 -7.32316792e-01 -9.36658084e-01 -1.15041757e+00 -1.09139049e+00 -1.36159372e+00 -1.70813811e+00 -1.87504482e+00 -1.75865054e+00 -1.61512589e+00 -1.86722088e+00 -1.92150915e+00 -1.88240778e+00 -1.58594155e+00 -1.39906061e+00 -1.26080215e+00 -1.37036097e+00 -1.48973513e+00 -1.58521760e+00 -1.25584769e+00 -7.76063323e-01 -7.55156994e-01 -1.05261564e+00 -1.41826403e+00 -1.37865770e+00 -1.48332155e+00 -1.34977174e+00 -1.37391937e+00 -1.62208581e+00 -2.12971282e+00 -2.17851591e+00 -1.88743448e+00 -1.34777868e+00 -1.38926530e+00 -1.38224959e+00 -1.39590311e+00 -1.22375751e+00 -1.41259110e+00 -1.84281075e+00 -2.00247860e+00 -1.90082943e+00 -1.53007972e+00 -1.59064233e+00 -1.51710176e+00 -1.58896625e+00 -1.54227841e+00 -1.66363788e+00 -1.80751157e+00 -1.79455447e+00 -1.67347002e+00 -1.46334004e+00 -1.48594534e+00 -1.52451992e+00 -1.39801300e+00 -1.27857137e+00 -9.25872326e-01 -7.14255214e-01 -7.64511228e-01 -1.35954130e+00 -2.06544828e+00 -2.40181065e+00 -2.41482806e+00 -2.38374114e+00 -2.22234678e+00 -1.84795833e+00 -1.64292312e+00 -1.44434869e+00 -1.51054096e+00 -1.43764246e+00 -1.75059783e+00 -2.11739159e+00 -2.10434604e+00 -1.93955314e+00 -1.36926293e+00 -1.00343049e+00 -8.86538625e-01 -1.06378913e+00 -1.51129901e+00 -1.94599342e+00 -2.53139138e+00 -2.96928287e+00 -2.82224679e+00 -2.37490916e+00 -1.92420208e+00 -1.59383798e+00 -1.96075213e+00 -2.43713498e+00 -2.64859056e+00 -2.40507388e+00 -1.92773926e+00 -1.60817921e+00 -1.46701002e+00 -1.51402605e+00 -1.72436130e+00 -1.62279725e+00 -1.67037606e+00 -1.66359651e+00 -1.69228542e+00 -1.76733744e+00 -1.81840229e+00 -1.86497521e+00 -1.91696036e+00 -1.97512066e+00 -2.40244031e+00 -2.79247665e+00 -2.58696365e+00 -2.01970577e+00 -2.00128317e+00 -2.68616509e+00 -3.11853838e+00 -2.69992042e+00 -2.21024132e+00 -2.23900986e+00 -2.52217937e+00 -2.56812406e+00 -2.41533256e+00 -2.21121216e+00 -2.21011496e+00 -2.24683666e+00 -2.42146087e+00 -2.42246699e+00 -2.36545157e+00 -2.20147634e+00 -2.13680696e+00 -2.16823745e+00 -2.24857926e+00 -2.29783940e+00 -2.38966990e+00 -2.48260570e+00 -2.70839071e+00 -2.41221309e+00 -1.97966111e+00 -2.08466077e+00 -2.54262495e+00 -2.85840106e+00 -2.49738169e+00 -2.28805113e+00 -2.56410933e+00 -2.90837383e+00 -2.56088638e+00 -1.89804220e+00 -1.42822087e+00 -1.64175272e+00 -1.98324692e+00 -2.48219490e+00 -2.76590800e+00 -2.67191505e+00 -2.20019388e+00 -2.18591452e+00 -2.69817734e+00 -2.83408475e+00 -2.58600712e+00 -2.18036985e+00 -2.13995051e+00 -2.21674538e+00 -2.12420130e+00 -1.85127485e+00 -2.13204145e+00 -2.55427742e+00 -2.94078803e+00 -2.72606993e+00 -2.53238606e+00 -2.43611813e+00 -2.43712211e+00 -2.45421219e+00 -2.53490615e+00 -2.55405068e+00 -2.37201715e+00 -2.37816548e+00 -2.34639859e+00 -2.41226506e+00 -2.47570777e+00 -2.57312512e+00 -2.94084907e+00 -3.21049547e+00 -2.98173022e+00 -2.39379716e+00 -1.97263992e+00 -2.09429455e+00 -2.41763687e+00 -2.38951874e+00 -2.28095627e+00 -2.16996956e+00 -2.10103250e+00 -2.29694438e+00 -2.47349143e+00 -2.58732891e+00 -2.46247292e+00 -2.28038764e+00 -2.28971076e+00 -2.36441422e+00 -2.43108606e+00 -2.40945864e+00 -2.40500355e+00 -2.63723087e+00 -2.71084690e+00 -2.56161070e+00 -2.42438745e+00 -2.48003840e+00 -2.64594030e+00 -2.49433565e+00 -2.32219839e+00 -2.40919423e+00 -2.83608222e+00 -3.27434492e+00 -3.35901427e+00 -3.21364284e+00 -3.15984273e+00 -3.28240275e+00 -3.20691919e+00 -3.03633094e+00 -2.87326503e+00 -2.90487909e+00 -2.90440869e+00 -3.02680349e+00 -3.27074909e+00 -3.28912854e+00 -3.01370239e+00 -2.64781880e+00 -2.81952310e+00 -3.15370607e+00 -3.20121694e+00 -2.90967512e+00 -2.83726096e+00 -3.03929734e+00 -2.84763622e+00 -2.40408516e+00 -2.15114760e+00 -2.38307905e+00 -2.66217279e+00 -2.61090612e+00 -2.42841148e+00 -2.37398148e+00 -2.49897647e+00 -2.57457542e+00 -2.43874097e+00 -2.41237044e+00 -2.49134874e+00 -2.70408726e+00 -2.93099689e+00 -3.17594886e+00 -3.28007174e+00 -3.25028849e+00 -2.89583945e+00 -2.62651372e+00 -2.52460623e+00 -2.71183896e+00 -2.87888598e+00 -2.87705159e+00 -2.88631725e+00 -2.75568390e+00 -2.59083056e+00 -2.59371281e+00 -2.76827955e+00 -2.90706205e+00 -2.93742394e+00 -2.96165395e+00 -3.16406083e+00 -3.28795004e+00 -3.25234151e+00 -3.08245969e+00 -2.99337792e+00 -2.97399664e+00 -2.96721387e+00 -2.94474268e+00 -3.02309871e+00 -3.04497218e+00 -3.03714275e+00 -2.97829509e+00 -2.96083951e+00 -2.95877886e+00 -2.96035647e+00 -3.01376867e+00 -3.16332674e+00 -3.34817362e+00 -3.33897972e+00 -3.23105121e+00 -3.19635201e+00 -3.29436159e+00 -3.28389263e+00 -3.18981290e+00 -3.10061693e+00 -3.20214915e+00 -3.30020809e+00 -3.27177000e+00 -3.16738820e+00 -2.99623823e+00 -2.97695422e+00 -2.96488547e+00 -3.08123970e+00 -3.19097638e+00 -3.22156024e+00 -3.14474869e+00 -3.13621902e+00 -3.21653080e+00 -3.21680737e+00 -3.15150499e+00 -3.04403567e+00 -3.12895250e+00 -3.23352861e+00 -3.24780321e+00 -3.11072850e+00 -3.00881791e+00 -3.05837727e+00 -3.17965722e+00 -3.20538855e+00 -3.21959400e+00 -3.17866373e+00 -3.17014766e+00 -3.16735458e+00 -3.16487527e+00 -3.23519230e+00 -3.28176427e+00 -3.28258896e+00 -3.23145390e+00 -3.17177582e+00 -3.16266489e+00 -3.16481495e+00 -3.15988493e+00 -3.16885996e+00 -3.15767956e+00 -3.16748857e+00 -3.15652895e+00 -3.15428233e+00 -3.14733243e+00 -3.09576392e+00 -3.05010176e+00 -3.10306048e+00 -3.17729855e+00 -3.21061945e+00 -3.14691472e+00 -3.11747074e+00 -3.12834024e+00 -3.14010167e+00 -3.14840007e+00 -3.14226818e+00 -3.15195870e+00 -3.15289068e+00 -3.21518230e+00 -3.25758982e+00 -3.46239018e+00 -3.81548262e+00 -4.07601118e+00 -4.86160851e+00 -4.65765476e+00 -1.96368217e+01 -4.41984253e+01 -7.87669850e+06 -34023064. 0. 0. 0. 0. 0. 54467284. 45908868. -11309393. 32765716. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 402289120. 226802656. -1.29240341e+02 -4.93974648e+01 -1.52379885e+01 -1.11798029e+01 -1.04512434e+01 -9.58732700e+00 -9.35324001e+00 -9.36875629e+00 -9.49940395e+00 -9.48402500e+00 -9.45145607e+00 -9.42339993e+00 -9.36279869e+00 -9.34372044e+00 -9.27606392e+00 -9.31084156e+00 -9.38494396e+00 -9.52584457e+00 -9.52399540e+00 -9.33632755e+00 -9.12164402e+00 -9.00395203e+00 -9.00865746e+00 -9.14707088e+00 -9.14127922e+00 -9.06771851e+00 -9.20713139e+00 -9.30932999e+00 -9.32669640e+00 -9.01033592e+00 -8.81354427e+00 -8.74009418e+00 -8.90354729e+00 -9.20487976e+00 -9.34613228e+00 -9.35217094e+00 -9.41882896e+00 -9.47484875e+00 -9.40964603e+00 -9.11883831e+00 -8.86306763e+00 -8.97507572e+00 -9.17460632e+00 -9.32563972e+00 -9.10430431e+00 -9.10333824e+00 -9.07348442e+00 -8.96931934e+00 -8.99522305e+00 -9.02377224e+00 -9.11941528e+00 -9.25915527e+00 -9.40217400e+00 -9.47322083e+00 -9.10565281e+00 -8.62674046e+00 -8.52138519e+00 -8.77377987e+00 -9.38578892e+00 -9.42507648e+00 -9.19428635e+00 -8.90475750e+00 -8.89134789e+00 -8.93935490e+00 -8.86498356e+00 -8.76272678e+00 -8.75376797e+00 -9.10884285e+00 -9.53895855e+00 -9.42069626e+00 -9.23617935e+00 -8.95706844e+00 -8.80743408e+00 -8.62555313e+00 -8.59934139e+00 -8.78590107e+00 -9.12544250e+00 -9.33254147e+00 -9.35649395e+00 -9.15108204e+00 -8.79906940e+00 -8.43729401e+00 -8.26759720e+00 -8.63396740e+00 -8.80306435e+00 -8.87709141e+00 -9.19007683e+00 -9.52054214e+00 -9.56274700e+00 -8.91330338e+00 -8.14903545e+00 -7.77364302e+00 -8.27873993e+00 -9.20798492e+00 -9.43828201e+00 -9.34576035e+00 -9.16104221e+00 -9.23851013e+00 -9.23133850e+00 -9.19455814e+00 -8.91640091e+00 -8.77899361e+00 -8.73634243e+00 -8.75488853e+00 -8.47502899e+00 -8.01615429e+00 -7.84058952e+00 -7.96774435e+00 -8.48784447e+00 -8.88871861e+00 -8.76142120e+00 -8.83057880e+00 -8.99419022e+00 -9.16592789e+00 -8.73646355e+00 -8.27795696e+00 -8.21676445e+00 -8.97489548e+00 -9.61474323e+00 -9.63260937e+00 -9.02338982e+00 -8.38987064e+00 -7.88977337e+00 -7.62071991e+00 -7.83001900e+00 -8.07599640e+00 -8.37926102e+00 -8.91460609e+00 -9.24650478e+00 -9.19915485e+00 -8.70679855e+00 -8.12861729e+00 -7.85246086e+00 -8.11537075e+00 -8.71498585e+00 -8.84803295e+00 -8.78709030e+00 -8.62946987e+00 -9.02296638e+00 -9.00911617e+00 -8.50053120e+00 -7.66724586e+00 -7.23051023e+00 -7.46230364e+00 -7.73597956e+00 -7.86871958e+00 -8.12823391e+00 -8.22699070e+00 -7.95988941e+00 -7.65412474e+00 -7.14104128e+00 -7.00221634e+00 -7.12857199e+00 -7.84584904e+00 -8.06352425e+00 -7.67558908e+00 -7.15748787e+00 -7.60825539e+00 -8.51269817e+00 -9.02518177e+00 -8.21924973e+00 -7.45507383e+00 -7.21550751e+00 -7.39600468e+00 -7.41888094e+00 -6.72387838e+00 -6.04825830e+00 -5.74398422e+00 -6.68344069e+00 -8.33497334e+00 -8.65573120e+00 -8.59440041e+00 -8.46364498e+00 -8.55351925e+00 -8.07878876e+00 -7.18971395e+00 -6.64810991e+00 -7.41389513e+00 -7.97633219e+00 -8.23169613e+00 -7.67400885e+00 -6.96713018e+00 -6.89757586e+00 -5.95542955e+00 -6.41449356e+00 -5.77459288e+00 -6.23814058e+00 -6.43329859e+00 -6.62953234e+00 -6.49902153e+00 -5.79775286e+00 -5.15217209e+00 -5.30635166e+00 -6.37003756e+00 -8.10342026e+00 -8.26679611e+00 -7.71572733e+00 -7.35967588e+00 -6.89110231e+00 -6.96090364e+00 -6.43296194e+00 -6.62776899e+00 -7.27694988e+00 -7.64362860e+00 -8.01734638e+00 -7.06928587e+00 -6.74640083e+00 -6.28518581e+00 -6.48314476e+00 -6.76188660e+00 -6.07121801e+00 -4.98885298e+00 -4.86482859e+00 -5.80309200e+00 -6.50441313e+00 -6.53353834e+00 -5.38984871e+00 -5.08239508e+00 -5.29458952e+00 -6.37166595e+00 -6.68120813e+00 -6.72879171e+00 -7.11622047e+00 -7.16384411e+00 -7.45532894e+00 -7.63163471e+00 -7.13191509e+00 -6.64075089e+00 -6.35130167e+00 -7.11031151e+00 -7.46542740e+00 -7.05520439e+00 -6.73118830e+00 -5.82109976e+00 -5.28480053e+00 -4.65944481e+00 -5.12807941e+00 -5.96111441e+00 -6.84360838e+00 -7.11822319e+00 -6.14485216e+00 -5.26035261e+00 -5.18977118e+00 -5.73985243e+00 -5.71074343e+00 -5.20868587e+00 -4.95381403e+00 -5.89825249e+00 -6.42148209e+00 -6.26581144e+00 -5.09432507e+00 -4.45476675e+00 -4.62215424e+00 -4.90430117e+00 -4.86780024e+00 -5.14217138e+00 -5.28597975e+00 -5.16245365e+00 -4.96050835e+00 -4.84707451e+00 -4.59924841e+00 -4.36579132e+00 -4.32449293e+00 -5.38377428e+00 -6.20018291e+00 -5.69424343e+00 -3.95066166e+00 -3.59981871e+00 -4.14634418e+00 -4.62597036e+00 -3.81954980e+00 -3.76580858e+00 -4.51478958e+00 -5.09208727e+00 -4.87031698e+00 -4.77045202e+00 -5.07089233e+00 -5.26781368e+00 -4.71956158e+00 -4.38512754e+00 -4.94743443e+00 -5.48911810e+00 -5.10078955e+00 -5.49076033e+00 -6.08377838e+00 -6.55528545e+00 -5.38543320e+00 -4.40427208e+00 -4.13358641e+00 -4.77809525e+00 -4.80760908e+00 -4.42174482e+00 -4.67413712e+00 -5.32618618e+00 -5.12455797e+00 -3.99871039e+00 -2.35071039e+00 -2.83760667e+00 -2.87903190e+00 -4.08340549e+00 -3.62842917e+00 -4.75610113e+00 -5.08334780e+00 -4.90555286e+00 -4.34598446e+00 -4.30547237e+00 -4.89415407e+00 -5.17702723e+00 -5.29394817e+00 -5.75723410e+00 -5.35605860e+00 -4.85396051e+00 -4.29685163e+00 -4.52253008e+00 -5.19209862e+00 -4.65449667e+00 -3.55395150e+00 -3.35960650e+00 -3.92504525e+00 -4.31149817e+00 -3.72128224e+00 -3.61247683e+00 -4.11630917e+00 -4.23848724e+00 -4.34392214e+00 -4.86914539e+00 -5.71028471e+00 -6.33418798e+00 -5.51681566e+00 -4.66317463e+00 -3.92656565e+00 -3.90361571e+00 -3.77379465e+00 -4.16895866e+00 -5.11871576e+00 -4.26111031e+00 -2.94953084e+00 -2.72945666e+00 -3.52020764e+00 -4.43855810e+00 -3.33377552e+00 -3.16078997e+00 -2.88613868e+00 -3.11451840e+00 -3.11302209e+00 -2.84225178e+00 -3.08321905e+00 -3.17991471e+00 -2.71693659e+00 -2.80892181e+00 -3.14682341e+00 -4.36901951e+00 -3.81667161e+00 -3.20928621e+00 -2.40209484e+00 -2.37403798e+00 -2.45981336e+00 -2.74278355e+00 -3.38966393e+00 -5.18262863e+00 -4.71508551e+00 -2.86037374e+00 -3.12115133e-01 7.58771718e-01 -6.27161920e-01 -1.47118533e+00 -1.55776739e+00 -8.49500954e-01 -8.97572935e-02 -6.51437581e-01 -8.52193654e-01 -1.13033199e+00 -1.30035806e+00 7.55086467e-02 1.60266295e-01 3.72223556e-02 -1.91152489e+00 -3.05526328e+00 -1.90719688e+00 -6.36409044e-01 -5.28222322e-02 -1.43688488e+00 -2.87673330e+00 -2.53870392e+00 -2.13114929e+00 -1.27079165e+00 -3.83917391e-01 -3.81595701e-01 3.07630539e-01 -8.67694736e-01 -1.42129672e+00 -1.91695011e+00 -1.47346830e+00 3.84043247e-01 1.39422596e+00 1.64496195e+00 2.56487757e-01 -1.15948248e+00 -8.69725525e-01 -4.36423957e-01 -5.79294801e-01 -1.88180733e+00 -2.02679563e+00 -2.47311190e-01 9.64300811e-01 1.34932244e+00 3.07715893e-01 -2.61056274e-01 -4.00356352e-01 -9.44275916e-01 -9.47172225e-01 -4.11264688e-01 4.26859967e-02 1.01719272e+00 9.97430921e-01 1.59779644e+00 1.29264569e+00 9.88805652e-01 3.30900818e-01 -1.25303257e+00 -1.68588030e+00 -1.06122017e+00 -3.78659278e-01 1.20689297e+00 1.42792439e+00 1.70070708e+00 -5.29893264e-02 -1.14487696e+00 -1.14144957e+00 4.04115647e-01 1.42815697e+00 8.09450865e-01 -9.11638021e-01 -8.68724465e-01 -7.57095337e-01 -3.39612275e-01 7.22045898e-02 5.84982872e-01 1.64176238e+00 7.72946417e-01 -2.87611723e-01 -7.91766346e-01 -4.00155723e-01 1.89895654e+00 2.93286753e+00 2.88713050e+00 1.28591335e+00 -3.55894834e-01 5.20242691e-01 1.43312681e+00 1.99176645e+00 6.00250542e-01 -7.44350702e-02 5.59671402e-01 1.61194992e+00 1.99130702e+00 1.53799975e+00 1.44268513e+00 1.44894159e+00 1.82035708e+00 1.54055071e+00 2.20042586e+00 1.93925512e+00 2.17846584e+00 1.89214230e+00 1.94509971e+00 1.83700204e+00 1.26289690e+00 1.90973675e+00 1.14297462e+00 3.58157873e-01 -1.01706266e+00 -4.24082547e-01 1.73772454e+00 3.14303946e+00 3.34305215e+00 1.20721054e+00 -2.32477933e-01 -8.06100965e-01 1.88668862e-01 1.39676225e+00 1.96215856e+00 1.23277891e+00 7.15458810e-01 1.06114484e-01 7.00915992e-01 1.92980480e+00 2.92436600e+00 3.50975776e+00 1.69689977e+00 7.82442987e-01 8.26340914e-02 8.42164338e-01 2.47124171e+00 3.36366534e+00 3.60335541e+00 1.88624072e+00 6.69784069e-01 1.25711679e+00 2.41841602e+00 3.89532709e+00 3.28526664e+00 1.75184834e+00 9.72958446e-01 1.04755521e+00 2.66722035e+00 2.93753695e+00 2.78461123e+00 2.45353365e+00 2.55522418e+00 1.70301867e+00 1.72906733e+00 1.76802146e+00 2.63328934e+00 2.09053206e+00 2.00830531e+00 1.71244526e+00 1.81185985e+00 1.48655188e+00 2.17247987e+00 1.87098253e+00 1.70352221e+00 1.18243170e+00 2.69021726e+00 4.12539864e+00 4.48384905e+00 3.02800274e+00 1.88843203e+00 1.81816566e+00 2.71693659e+00 3.94982076e+00 4.79674482e+00 4.40529966e+00 4.15632629e+00 3.81839538e+00 3.79810572e+00 3.77553320e+00 3.12876463e+00 3.37683368e+00 2.18750548e+00 1.99419594e+00 1.93750703e+00 2.46544123e+00 3.75766945e+00 3.66268516e+00 3.19616461e+00 1.55093861e+00 9.56516862e-01 1.51248324e+00 2.88277864e+00 4.09242105e+00 3.54250360e+00 2.33615613e+00 1.87233973e+00 2.36856174e+00 3.26781201e+00 3.78280091e+00 4.09276056e+00 4.31995344e+00 4.40203142e+00 4.45804644e+00 4.26960611e+00 4.96603489e+00 5.45308924e+00 5.41360521e+00 3.82938671e+00 3.29166818e+00 3.60198045e+00 5.14036989e+00 5.60110044e+00 5.09754992e+00 3.97202897e+00 3.44223523e+00 4.35198736e+00 4.77810955e+00 4.87905931e+00 4.13688326e+00 3.92069650e+00 4.42671156e+00 5.07176924e+00 5.49352074e+00 5.63692236e+00 5.29947472e+00 6.17206860e+00 5.75140381e+00 5.34359884e+00 4.57546520e+00 4.79459429e+00 5.09320688e+00 4.76147747e+00 4.64134121e+00 4.90532398e+00 4.84001684e+00 5.49846554e+00 5.32632828e+00 5.24105740e+00 4.38271952e+00 4.03982782e+00 4.87924147e+00 5.40456486e+00 6.59385204e+00 6.11978674e+00 5.37302876e+00 4.60553312e+00 4.41850233e+00 5.37390423e+00 5.22628832e+00 5.04239225e+00 5.34727526e+00 8.44446373e+00 8.69361401e+00 7.66095781e+00 6.00906372e+00 6.98132420e+00 8.85762882e+00 1.98795338e+01 1.63892612e+01 1.90661030e+01 1.73728790e+02 2.64558594e+02 -6.05405762e+02 -3.57975928e+03 -53644572. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 860252544. -3.35480640e+03 -4.75817108e+02 -5.73350105e+01 -3.52324677e+01 -6.74090195e+00 3.15593839e+00 4.63142061e+00 7.85017204e+00 8.26589775e+00 7.91789579e+00 7.67562962e+00 7.46704197e+00 7.67619228e+00 7.58723402e+00 7.46293402e+00 6.94965649e+00 6.84899521e+00 7.38542461e+00 7.98100185e+00 8.50907707e+00 8.84991360e+00 8.73271656e+00 8.17976189e+00 7.43430662e+00 6.95572042e+00 7.69880295e+00 7.86815023e+00 7.56906652e+00 6.44007540e+00 6.69099808e+00 7.53415585e+00 8.04283810e+00 7.77536917e+00 7.29711151e+00 7.27974319e+00 7.65288019e+00 7.64290237e+00 7.70079517e+00 7.69454241e+00 7.60577250e+00 7.25831127e+00 6.93764639e+00 7.23521852e+00 7.28471041e+00 7.91333914e+00 8.80704021e+00 9.21858120e+00 7.91107607e+00 6.19955540e+00 6.06405735e+00 7.54552031e+00 8.24793148e+00 8.00337219e+00 7.26242018e+00 7.34972477e+00 7.79744482e+00 8.04712772e+00 8.07362461e+00 8.01143074e+00 8.47504425e+00 9.00493431e+00 8.98218346e+00 9.04794312e+00 9.11865330e+00 9.19828606e+00 8.74636555e+00 8.43260956e+00 8.60317516e+00 8.79174995e+00 9.14906406e+00 9.46656227e+00 9.67313385e+00 9.81591320e+00 9.41145134e+00 9.11858463e+00 9.51167107e+00 9.39717197e+00 8.81936169e+00 7.35616875e+00 6.80502129e+00 7.34239101e+00 7.91816235e+00 8.52847862e+00 8.68599987e+00 8.69651794e+00 8.46758270e+00 8.25831699e+00 8.47054672e+00 8.66205597e+00 8.54920101e+00 8.49504948e+00 8.59047890e+00 8.92702484e+00 8.94518089e+00 8.64355659e+00 9.05073929e+00 8.93874741e+00 8.93346214e+00 8.35679436e+00 8.28335953e+00 8.91591930e+00 8.94523239e+00 8.56957912e+00 7.82304144e+00 7.80701017e+00 8.50410748e+00 8.79030418e+00 9.06879997e+00 9.08588409e+00 9.26555252e+00 9.32946777e+00 9.19129467e+00 9.10124874e+00 9.09722137e+00 9.07751274e+00 8.93214893e+00 8.70699501e+00 8.82162857e+00 8.89839840e+00 8.74139595e+00 8.94138145e+00 8.98100185e+00 8.86932659e+00 8.34963417e+00 8.30144215e+00 8.91861153e+00 9.16301632e+00 8.82623863e+00 8.38900375e+00 8.37812138e+00 8.96432877e+00 9.09898186e+00 9.21155262e+00 9.18914509e+00 9.13359547e+00 8.96077442e+00 8.62716293e+00 8.75233555e+00 9.02398109e+00 9.04419994e+00 8.90722275e+00 8.61861897e+00 8.79864693e+00 8.94564247e+00 8.96990395e+00 9.16393852e+00 9.16053486e+00 9.28541756e+00 9.15645885e+00 9.13321781e+00 9.24408531e+00 9.26444912e+00 9.19037342e+00 8.93770313e+00 8.74009514e+00 8.85529041e+00 8.96475124e+00 9.16616726e+00 9.24035740e+00 9.31050396e+00 9.45976543e+00 9.47437286e+00 9.44549465e+00 9.35378361e+00 9.37625599e+00 9.43760395e+00 9.35724545e+00 9.12198353e+00 8.91238499e+00 8.83469772e+00 9.15867519e+00 9.29688549e+00 9.24598885e+00 9.09130764e+00 9.14269352e+00 9.30419540e+00 9.26586628e+00 9.33557796e+00 9.37122726e+00 9.41627121e+00 9.32172680e+00 9.25092125e+00 9.31862164e+00 9.38226128e+00 9.35345078e+00 9.36234665e+00 9.42776489e+00 9.51205540e+00 9.62412453e+00 9.65127850e+00 9.69902134e+00 9.48855495e+00 9.36077309e+00 9.29565048e+00 9.28927231e+00 9.39949226e+00 9.36440659e+00 9.33376408e+00 9.18813992e+00 9.18537903e+00 9.29245949e+00 9.37566280e+00 9.42363548e+00 9.40267086e+00 9.43752861e+00 9.47249413e+00 9.45417786e+00 9.42589569e+00 9.40553188e+00 9.40477371e+00 9.37902641e+00 9.33878040e+00 9.34361553e+00 9.31901169e+00 9.32618237e+00 9.37188911e+00 9.40365982e+00 9.39244556e+00 9.35032177e+00 9.34149170e+00 9.34702778e+00 9.33790112e+00 9.33135986e+00 9.33233166e+00 9.33887196e+00 9.34218025e+00 9.33937168e+00 9.32501221e+00 9.31711864e+00 9.33140373e+00 9.35581493e+00 9.36639881e+00 9.33818245e+00 9.31858540e+00 9.32980728e+00 9.33811474e+00 9.34082413e+00 9.33236408e+00 9.33290768e+00 9.31967354e+00 9.31903744e+00 9.30938244e+00 9.31529903e+00 9.33507156e+00 9.36736107e+00 9.37826443e+00 9.34648132e+00 9.29769135e+00 9.30467510e+00 9.32549667e+00 9.33843327e+00 9.30497265e+00 9.24681282e+00 9.19201183e+00 9.17905807e+00 9.22683239e+00 9.29940128e+00 9.28833771e+00 9.27423096e+00 9.26098347e+00 9.26159954e+00 9.23093987e+00 9.23136234e+00 9.24198627e+00 9.26533794e+00 9.25555801e+00 9.29514027e+00 9.34534550e+00 9.32134819e+00 9.28075790e+00 9.27305698e+00 9.27150631e+00 9.26778316e+00 9.21404743e+00 9.23078823e+00 9.19280434e+00 9.11709499e+00 9.09899616e+00 9.10422039e+00 9.14912987e+00 9.14271927e+00 9.14797115e+00 9.19898224e+00 9.23432350e+00 9.18856239e+00 9.15133858e+00 9.11676025e+00 9.17590618e+00 9.15840244e+00 9.14817524e+00 9.09991932e+00 9.11024570e+00 9.15729237e+00 9.18225861e+00 9.13448524e+00 9.02311134e+00 8.94827843e+00 8.99007034e+00 9.00123692e+00 9.00773525e+00 8.98483944e+00 9.01387024e+00 8.98597622e+00 8.93693542e+00 8.98125076e+00 9.05236626e+00 9.09122562e+00 9.01345634e+00 9.01095200e+00 9.08915043e+00 9.11829090e+00 9.04799366e+00 8.93904018e+00 8.78483677e+00 8.68221760e+00 8.61044025e+00 8.72856331e+00 8.84389114e+00 8.87738895e+00 8.57736778e+00 8.44430733e+00 8.55651951e+00 8.68069077e+00 8.78511810e+00 8.69719505e+00 8.80956173e+00 8.67963982e+00 8.31896591e+00 8.08953762e+00 8.36097431e+00 8.78032303e+00 8.97439098e+00 8.83309555e+00 8.71059799e+00 8.68042946e+00 8.58695507e+00 8.60046673e+00 8.58642387e+00 8.60674953e+00 8.59340382e+00 8.65470028e+00 8.60902023e+00 8.43033791e+00 8.27961063e+00 8.02725601e+00 7.89486551e+00 7.91178131e+00 8.12744236e+00 8.27830505e+00 8.13017654e+00 8.06013107e+00 8.22173214e+00 8.45008469e+00 8.58554649e+00 8.41975403e+00 8.41869736e+00 8.29484177e+00 8.35093403e+00 8.17930412e+00 8.31085587e+00 8.22541618e+00 7.85491848e+00 7.52139139e+00 7.85070610e+00 8.66368866e+00 8.80495071e+00 8.51210117e+00 8.03562260e+00 7.94983101e+00 7.83507156e+00 7.85168219e+00 7.83304977e+00 7.83084011e+00 7.98224449e+00 8.21779919e+00 8.64947033e+00 8.00328350e+00 7.08619881e+00 6.68216324e+00 7.28811169e+00 8.14420319e+00 8.24831772e+00 8.22413158e+00 8.12566948e+00 8.21068096e+00 8.37027740e+00 8.60156536e+00 8.43115902e+00 8.09658813e+00 7.85307312e+00 7.99270821e+00 7.98427153e+00 7.86024618e+00 7.84159994e+00 7.86704159e+00 7.96286535e+00 8.12440777e+00 8.26660156e+00 7.97196293e+00 7.16270924e+00 6.97104883e+00 7.05694342e+00 6.88525009e+00 6.27913332e+00 5.66302443e+00 5.70847654e+00 6.37173605e+00 6.98677206e+00 7.39098549e+00 7.31744957e+00 7.16129446e+00 7.01256657e+00 7.35412836e+00 7.56368923e+00 7.57134199e+00 7.22128773e+00 7.19012213e+00 6.75239515e+00 6.36487293e+00 6.17183876e+00 6.73077965e+00 7.23238182e+00 7.35831213e+00 7.22840834e+00 7.16246414e+00 7.17614746e+00 7.16272259e+00 7.17810678e+00 7.30126238e+00 7.43501759e+00 7.27104521e+00 7.17567730e+00 7.23138428e+00 7.48577356e+00 7.36533451e+00 7.18849802e+00 6.73736143e+00 6.71137047e+00 6.77356625e+00 7.09414244e+00 7.17214823e+00 6.86801147e+00 6.55888319e+00 6.28640747e+00 6.22498608e+00 6.29046059e+00 6.62499857e+00 6.95268631e+00 6.44658995e+00 5.34949064e+00 3.62372160e+00 3.50914574e+00 3.03617764e+00 2.47609043e+00 1.38063633e+00 -8.13438225e+00 -6.94782257e+00 -1.38823354e+00 1.92856483e+01 -1.26997398e+02 7.50660229e+00 3.35985986e+03 -194268432. 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. 0. 0. 0. 0. 0. 0. 274490496. 3.89359302e+03 5.97174622e+02 1.03021851e+02 4.45502167e+01 2.60326939e+01 1.47154055e+01 9.95204926e+00 6.73826742e+00 4.89806747e+00 4.52058315e+00 4.87429762e+00 5.86906099e+00 6.26514101e+00 6.35838270e+00 5.90885830e+00 5.97679281e+00 5.91017246e+00 5.83124304e+00 5.67702246e+00 5.63588619e+00 5.94382048e+00 5.61652231e+00 5.05266905e+00 4.59528112e+00 4.66776085e+00 4.84000635e+00 4.69997025e+00 4.77574682e+00 4.75951338e+00 4.32628822e+00 4.11220932e+00 4.12670994e+00 4.53340960e+00 4.54909754e+00 4.34787941e+00 3.99117494e+00 3.89966869e+00 3.39381099e+00 3.00651336e+00 2.60377669e+00 3.30196047e+00 3.98274684e+00 4.30370712e+00 4.00509644e+00 3.55538630e+00 3.24465346e+00 3.18782997e+00 3.63957977e+00 3.44907188e+00 3.24749827e+00 2.63507128e+00 3.28092313e+00 3.96196628e+00 4.38499737e+00 3.88800812e+00 3.77188087e+00 3.51792717e+00 3.51370192e+00 3.29706693e+00 3.28418660e+00 3.45854878e+00 3.70949054e+00 4.28080654e+00 4.78174114e+00 4.76077843e+00 4.79833651e+00 4.53339052e+00 5.09370518e+00 5.29715300e+00 4.98667622e+00 4.25377321e+00 3.47670317e+00 3.11722732e+00 2.91526461e+00 2.27963185e+00 1.83927929e+00 1.84183574e+00 2.52642894e+00 3.11438751e+00 2.96214294e+00 2.80969524e+00 2.89511943e+00 3.15125537e+00 3.53722167e+00 3.67134285e+00 4.24323893e+00 4.42643929e+00 4.26655102e+00 3.58642650e+00 2.78612900e+00 2.54454494e+00 2.69851565e+00 3.47448087e+00 3.95654702e+00 3.44495249e+00 3.06770658e+00 2.72630978e+00 2.84525633e+00 2.74150562e+00 2.81630659e+00 3.38101172e+00 2.75503945e+00 1.88081861e+00 1.28734004e+00 1.51733148e+00 1.89795280e+00 1.80630255e+00 2.02497458e+00 2.26581812e+00 2.33042073e+00 2.79422522e+00 3.25726247e+00 2.86669302e+00 2.11081314e+00 1.23980892e+00 1.47875488e+00 1.48558140e+00 1.80487669e+00 1.81901383e+00 1.55127180e+00 1.35329080e+00 1.23613739e+00 1.50111485e+00 1.58749461e+00 2.00127101e+00 2.10104418e+00 2.01019835e+00 1.99639118e+00 2.57626939e+00 3.20962977e+00 3.03162432e+00 2.66477513e+00 1.87321103e+00 2.72014451e+00 3.19749141e+00 3.94160128e+00 3.57076383e+00 2.81341028e+00 1.84011042e+00 7.80408144e-01 6.29542172e-01 8.34173679e-01 1.07214093e+00 8.64722431e-01 7.12319016e-01 4.75916117e-01 5.30024171e-01 6.08935714e-01 6.38372421e-01 3.86297435e-01 5.62226236e-01 6.84756041e-01 1.16693521e+00 1.75833094e+00 2.42329168e+00 2.24265361e+00 1.40905178e+00 8.59163523e-01 1.39288354e+00 2.22780275e+00 2.68796277e+00 2.50249362e+00 2.46927595e+00 2.39146280e+00 2.11487842e+00 1.92637193e+00 1.19165266e+00 9.50043261e-01 5.62129796e-01 4.00774062e-01 4.25415963e-01 4.20276850e-01 3.02394927e-01 4.30463612e-01 6.53638005e-01 6.04823887e-01 -3.32160294e-01 -1.40204620e+00 -1.60933244e+00 -8.82872701e-01 3.87903489e-03 3.46156597e-01 2.41209060e-01 -3.68034333e-01 -8.51478457e-01 -3.95866245e-01 4.95490402e-01 7.29339600e-01 8.90753865e-02 -4.75832522e-01 -5.96977293e-01 -2.13570908e-01 -8.31164196e-02 -1.19334847e-01 -8.36205110e-02 -2.14722186e-01 -1.81487482e-02 3.13496776e-02 2.66507864e-01 2.35810831e-01 -9.91107672e-02 -6.88662350e-01 -1.30619681e+00 -1.34170437e+00 -1.18937504e+00 -9.08666849e-01 -1.23650289e+00 -1.31414986e+00 -8.49288046e-01 -5.43910921e-01 -4.64930296e-01 -1.03979278e+00 -1.21386421e+00 -1.08813524e+00 -9.48096037e-01 -8.83566320e-01 -1.08705556e+00 -1.31440413e+00 -1.47738278e+00 -1.80375612e+00 -1.54541683e+00 -1.72379160e+00 -1.84538412e+00 -1.94130790e+00 -2.08459902e+00 -2.13230109e+00 -2.54984593e+00 -2.97477746e+00 -2.84891272e+00 -2.80314732e+00 -2.12664080e+00 -2.42077303e+00 -2.03338242e+00 -2.41605973e+00 -2.53195906e+00 -2.79219890e+00 -2.52779627e+00 -2.31326842e+00 -2.75682926e+00 -3.00701952e+00 -3.33203173e+00 -2.70434070e+00 -2.36242366e+00 -2.14632154e+00 -2.85868669e+00 -3.58185840e+00 -4.00999165e+00 -3.33536911e+00 -1.81645036e+00 -6.40109479e-01 -6.46072030e-01 -1.73925602e+00 -2.61209750e+00 -2.42499280e+00 -1.80858552e+00 -1.79851711e+00 -2.35932040e+00 -2.92313099e+00 -3.03310919e+00 -2.84282684e+00 -2.74419832e+00 -2.63825631e+00 -2.83405781e+00 -3.03657532e+00 -3.10041809e+00 -2.97058344e+00 -2.84758615e+00 -3.31075740e+00 -3.78476262e+00 -3.66773152e+00 -3.16646791e+00 -2.98838544e+00 -3.36261654e+00 -3.31946707e+00 -3.53684139e+00 -3.60587883e+00 -3.47671890e+00 -3.35565543e+00 -2.87494898e+00 -2.80620098e+00 -2.85880780e+00 -3.39062691e+00 -4.13293600e+00 -3.94703269e+00 -3.84286690e+00 -3.50229836e+00 -3.53610039e+00 -4.19701529e+00 -4.75928402e+00 -4.68453884e+00 -3.94472575e+00 -3.32606030e+00 -3.78629971e+00 -4.13568592e+00 -3.84290051e+00 -3.87305450e+00 -2.97023869e+00 -2.81517386e+00 -2.69693589e+00 -3.28720856e+00 -4.34869909e+00 -4.52860212e+00 -4.82110643e+00 -4.62066031e+00 -4.37165070e+00 -3.65018463e+00 -3.02313328e+00 -3.03524542e+00 -3.36791372e+00 -3.98093367e+00 -3.94951463e+00 -4.05097628e+00 -4.17318583e+00 -4.25601673e+00 -3.93606257e+00 -3.85897017e+00 -3.66836500e+00 -3.83982825e+00 -4.06438446e+00 -4.49505472e+00 -4.63596058e+00 -4.66003466e+00 -4.72851133e+00 -4.90132952e+00 -5.17343903e+00 -4.85751724e+00 -4.27631807e+00 -3.41131115e+00 -2.94056439e+00 -2.79769659e+00 -3.03868437e+00 -3.57005715e+00 -5.16659451e+00 -5.73872852e+00 -6.07023382e+00 -5.36983347e+00 -5.30284023e+00 -4.83723021e+00 -4.22587585e+00 -4.60493612e+00 -4.56955910e+00 -5.62379217e+00 -5.78132105e+00 -6.29671860e+00 -5.92900085e+00 -5.43523264e+00 -5.36803055e+00 -5.37534952e+00 -4.72830009e+00 -4.16607809e+00 -4.31554365e+00 -5.07674503e+00 -5.79029274e+00 -5.32283211e+00 -5.07910872e+00 -4.84780312e+00 -4.98442459e+00 -5.17772436e+00 -5.55750990e+00 -6.09745026e+00 -6.12218714e+00 -5.85879612e+00 -5.64503050e+00 -5.86111784e+00 -6.10635328e+00 -6.31197405e+00 -6.12439060e+00 -6.22939682e+00 -6.10056305e+00 -6.05173635e+00 -5.76135445e+00 -5.50160599e+00 -4.90614843e+00 -5.37334347e+00 -6.15242863e+00 -6.77943754e+00 -6.09129810e+00 -5.58068562e+00 -5.27202320e+00 -5.59770775e+00 -5.14488888e+00 -4.87877798e+00 -4.79700613e+00 -5.31621742e+00 -5.96023560e+00 -6.05753326e+00 -5.79923964e+00 -5.46459150e+00 -5.51364374e+00 -5.83915615e+00 -6.11397600e+00 -6.23394871e+00 -6.20795202e+00 -5.97795391e+00 -6.07052279e+00 -5.85614681e+00 -5.76168966e+00 -5.63270617e+00 -6.25966883e+00 -7.24094915e+00 -7.06910419e+00 -6.23394394e+00 -5.62576056e+00 -6.27343464e+00 -6.75752592e+00 -6.56783581e+00 -6.43079281e+00 -6.68115234e+00 -7.20248270e+00 -7.20918083e+00 -7.21266413e+00 -7.24419737e+00 -7.16671419e+00 -6.82533216e+00 -6.68899059e+00 -6.99463272e+00 -6.91582394e+00 -6.48897266e+00 -6.57061481e+00 -6.94522667e+00 -7.49928570e+00 -7.56121635e+00 -7.58478069e+00 -7.92380810e+00 -7.95798159e+00 -7.75121641e+00 -7.22967911e+00 -6.76329517e+00 -6.97312069e+00 -7.01273727e+00 -7.16911077e+00 -7.15956593e+00 -7.30777454e+00 -7.42482328e+00 -7.46355438e+00 -7.63611126e+00 -7.61089849e+00 -7.31399918e+00 -6.85448551e+00 -6.63622522e+00 -6.82539034e+00 -6.76183414e+00 -6.52411652e+00 -6.76008606e+00 -7.12192869e+00 -7.82295752e+00 -8.00992489e+00 -7.87363100e+00 -8.01202106e+00 -8.06271744e+00 -8.06673908e+00 -7.68199301e+00 -7.37013674e+00 -7.39500475e+00 -7.54425049e+00 -7.75561523e+00 -7.96786594e+00 -8.00485325e+00 -7.97702885e+00 -7.98991871e+00 -8.07402420e+00 -8.13733387e+00 -7.88624811e+00 -7.61728573e+00 -7.71237564e+00 -8.00017166e+00 -8.26768875e+00 -8.05249214e+00 -8.29000187e+00 -8.58194923e+00 -8.49215603e+00 -7.83857107e+00 -7.13209009e+00 -6.97285604e+00 -7.26134396e+00 -7.39600801e+00 -7.37684011e+00 -7.57345486e+00 -7.79420948e+00 -7.96993065e+00 -7.89600468e+00 -7.89670563e+00 -7.84953833e+00 -7.60639954e+00 -7.60977697e+00 -7.84064579e+00 -8.21815205e+00 -8.10728645e+00 -7.86992073e+00 -7.86243343e+00 -8.17346573e+00 -8.07245350e+00 -7.78203964e+00 -7.98136282e+00 -8.66767025e+00 -9.08708096e+00 -8.84047604e+00 -8.57270813e+00 -8.70596600e+00 -9.07032108e+00 -9.05685139e+00 -8.88091373e+00 -8.72192860e+00 -8.96755886e+00 -9.11097813e+00 -9.06691551e+00 -8.86815453e+00 -8.53891563e+00 -8.19861317e+00 -8.01309776e+00 -8.05994892e+00 -8.57344723e+00 -9.01373768e+00 -9.19187260e+00 -8.97969723e+00 -8.76538372e+00 -8.73940754e+00 -8.75706863e+00 -8.85513973e+00 -9.21105289e+00 -9.19385910e+00 -8.92875576e+00 -8.63264465e+00 -8.55881882e+00 -8.60929871e+00 -8.41062832e+00 -8.21448231e+00 -8.25303173e+00 -8.53240013e+00 -8.74661922e+00 -8.80452919e+00 -8.76516914e+00 -8.79016113e+00 -8.72470188e+00 -8.70469093e+00 -8.73737717e+00 -8.79087257e+00 -8.91064548e+00 -8.98838520e+00 -9.07950974e+00 -9.04508495e+00 -8.87977314e+00 -8.56607437e+00 -8.60464859e+00 -8.67866135e+00 -8.72990799e+00 -8.48350143e+00 -8.55798626e+00 -8.75100517e+00 -8.96832085e+00 -8.79758835e+00 -8.67346859e+00 -8.71293259e+00 -8.94916821e+00 -9.16413403e+00 -9.19828987e+00 -9.17026615e+00 -9.03025532e+00 -8.88413429e+00 -8.88877869e+00 -9.01343536e+00 -9.00381851e+00 -8.83376980e+00 -8.83235359e+00 -8.93397141e+00 -9.12929249e+00 -8.99997616e+00 -8.89902115e+00 -8.92837334e+00 -9.13660145e+00 -9.27965355e+00 -9.20745850e+00 -9.06889534e+00 -9.01028538e+00 -9.02865410e+00 -9.13327694e+00 -9.19333839e+00 -9.14170456e+00 -9.10828972e+00 -9.00798702e+00 -8.95187378e+00 -9.03768921e+00 -9.10784531e+00 -9.17791271e+00 -9.09553432e+00 -9.10674095e+00 -9.16089725e+00 -9.22078991e+00 -9.25066090e+00 -9.24617100e+00 -9.26206303e+00 -9.26426792e+00 -9.24218845e+00 -9.38264847e+00 -9.43459892e+00 -9.39311123e+00 -9.30309486e+00 -9.39665222e+00 -9.55777359e+00 -9.43314648e+00 -9.32010746e+00 -9.27812386e+00 -9.39922810e+00 -9.43597126e+00 -9.59544849e+00 -9.86762047e+00 -9.99225616e+00 -1.01812162e+01 -1.25576105e+01 -2.99267654e+01 -3.72106972e+01 -2.94219284e+01 -3.08274612e+01 -8.46667557e+01 -3.35769875e+05 0. 0. 0. 0. 0. -252229952. -252229952. 20229712. 45908868. -11309393. 32765716. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -45045480. -7.74762192e+01 -2.76974258e+01 -2.20700130e+01 -1.99290047e+01 -2.19513340e+01 -2.18625011e+01 -2.12332325e+01 -2.04871330e+01 -2.03676395e+01 -2.03614731e+01 -2.03330593e+01 -2.03570976e+01 -2.04091434e+01 -2.04539623e+01 -2.03672771e+01 -2.02233753e+01 -2.01187096e+01 -2.01703644e+01 -2.04721889e+01 -2.07513027e+01 -2.08603878e+01 -2.07988777e+01 -2.05770397e+01 -2.05033703e+01 -2.04823151e+01 -2.02935619e+01 -2.02041473e+01 -2.03309307e+01 -2.06269798e+01 -2.08984375e+01 -2.08241100e+01 -2.05533867e+01 -2.01209488e+01 -2.00045967e+01 -2.00678596e+01 -2.01465302e+01 -2.01617470e+01 -2.02038498e+01 -2.03504982e+01 -2.05359726e+01 -2.02768841e+01 -2.01089973e+01 -1.98652802e+01 -2.01916637e+01 -2.02626915e+01 -2.03710384e+01 -2.05610046e+01 -2.04087334e+01 -2.03455963e+01 -1.99566994e+01 -1.96004124e+01 -1.92648563e+01 -1.92255077e+01 -1.97885857e+01 -2.05311489e+01 -2.07294674e+01 -2.03021832e+01 -1.94686661e+01 -1.91631794e+01 -1.94912567e+01 -1.97565079e+01 -2.00440884e+01 -1.99605350e+01 -2.01327229e+01 -1.99708500e+01 -1.98434448e+01 -1.95363617e+01 -1.92294807e+01 -1.94049473e+01 -1.94781551e+01 -1.96735134e+01 -1.97195530e+01 -1.97197666e+01 -1.97718964e+01 -1.95378208e+01 -1.90811806e+01 -1.85620708e+01 -1.85893688e+01 -1.92038479e+01 -1.95979996e+01 -2.00686131e+01 -1.98315544e+01 -1.93285275e+01 -1.89381657e+01 -1.87396870e+01 -1.85619946e+01 -1.80476742e+01 -1.83190365e+01 -1.89804516e+01 -1.99012413e+01 -1.98480682e+01 -1.92897205e+01 -1.83185253e+01 -1.81289520e+01 -1.82412281e+01 -1.81446953e+01 -1.81796494e+01 -1.82596111e+01 -1.84806595e+01 -1.89160385e+01 -1.87316074e+01 -1.86224594e+01 -1.85790291e+01 -1.93374996e+01 -1.99359493e+01 -2.00789146e+01 -1.96060123e+01 -1.87309532e+01 -1.80848312e+01 -1.83708096e+01 -1.82899895e+01 -1.75807419e+01 -1.67936058e+01 -1.76917934e+01 -1.93201504e+01 -1.94535141e+01 -1.83180561e+01 -1.67824593e+01 -1.66607094e+01 -1.71944103e+01 -1.81016865e+01 -1.88058319e+01 -1.89194870e+01 -1.82439823e+01 -1.78426361e+01 -1.73703194e+01 -1.69187698e+01 -1.63896484e+01 -1.63452473e+01 -1.69357014e+01 -1.76059780e+01 -1.77291927e+01 -1.77266197e+01 -1.72447643e+01 -1.69104977e+01 -1.63416290e+01 -1.65284481e+01 -1.62892342e+01 -1.66181183e+01 -1.74318695e+01 -1.90110283e+01 -1.96853790e+01 -1.92229881e+01 -1.82303982e+01 -1.85005703e+01 -1.78334427e+01 -1.75542908e+01 -1.70165615e+01 -1.72704353e+01 -1.83969879e+01 -1.87210503e+01 -1.80059166e+01 -1.66819038e+01 -1.59407291e+01 -1.68797379e+01 -1.77524700e+01 -1.73518524e+01 -1.64169483e+01 -1.55378590e+01 -1.65915165e+01 -1.74079323e+01 -1.70390205e+01 -1.68236866e+01 -1.67533703e+01 -1.82753258e+01 -1.93092079e+01 -1.99245701e+01 -1.79870720e+01 -1.56614466e+01 -1.46953611e+01 -1.50134964e+01 -1.54215479e+01 -1.57140760e+01 -1.59107456e+01 -1.67648182e+01 -1.72421360e+01 -1.66041603e+01 -1.56522112e+01 -1.51681242e+01 -1.57297382e+01 -1.74975758e+01 -1.71904926e+01 -1.73114967e+01 -1.62676849e+01 -1.73038750e+01 -1.75051193e+01 -1.69645004e+01 -1.58452158e+01 -1.56762552e+01 -1.51343365e+01 -1.49060364e+01 -1.50153942e+01 -1.46550522e+01 -1.38306217e+01 -1.35128698e+01 -1.38722630e+01 -1.44684830e+01 -1.53130894e+01 -1.55855064e+01 -1.55482931e+01 -1.52659492e+01 -1.40963783e+01 -1.34702673e+01 -1.23669815e+01 -1.37282705e+01 -1.45186281e+01 -1.52512360e+01 -1.49134731e+01 -1.50920010e+01 -1.50306053e+01 -1.47623034e+01 -1.37190208e+01 -1.29891777e+01 -1.29568796e+01 -1.35956678e+01 -1.48314695e+01 -1.47363291e+01 -1.45585041e+01 -1.36552477e+01 -1.30615339e+01 -1.30649271e+01 -1.35093060e+01 -1.42001305e+01 -1.37105026e+01 -1.30106602e+01 -1.27381430e+01 -1.27942514e+01 -1.30327816e+01 -1.27364731e+01 -1.24733849e+01 -1.32447844e+01 -1.22135925e+01 -1.39135180e+01 -1.28790073e+01 -1.44326982e+01 -1.36369743e+01 -1.35274601e+01 -1.15228558e+01 -1.11943979e+01 -1.25506754e+01 -1.39573679e+01 -1.30398922e+01 -1.11699400e+01 -1.10543795e+01 -1.15638885e+01 -1.31604948e+01 -1.20987625e+01 -1.15208998e+01 -1.10008202e+01 -1.13435965e+01 -1.15850096e+01 -1.06360588e+01 -1.28164368e+01 -1.19534216e+01 -1.14592485e+01 -9.16166878e+00 -1.09192276e+01 -1.28829489e+01 -1.50682297e+01 -1.44927368e+01 -1.37345352e+01 -1.10478554e+01 -1.09842615e+01 -9.54261780e+00 -1.08714008e+01 -1.26707430e+01 -1.43150482e+01 -1.34931412e+01 -1.26856232e+01 -1.23839884e+01 -1.25383043e+01 -1.09236174e+01 -1.02865658e+01 -1.00055008e+01 -1.05054331e+01 -9.91450024e+00 -9.09826469e+00 -1.00461884e+01 -1.05187664e+01 -1.04698677e+01 -1.00425596e+01 -9.41322231e+00 -8.51396561e+00 -7.88627672e+00 -8.54896259e+00 -9.93469429e+00 -1.06928101e+01 -1.02195368e+01 -1.06934071e+01 -1.11121550e+01 -1.20428514e+01 -1.17261944e+01 -9.66989517e+00 -1.01472931e+01 -1.03387318e+01 -1.10932198e+01 -9.88405609e+00 -1.04726772e+01 -1.08778582e+01 -1.10791168e+01 -9.45720100e+00 -8.10519028e+00 -7.53070974e+00 -8.40765858e+00 -8.44918633e+00 -6.93808889e+00 -5.66116571e+00 -5.73093510e+00 -6.90532970e+00 -8.35554600e+00 -8.83705616e+00 -9.03308296e+00 -7.70409012e+00 -6.56366062e+00 -7.30488443e+00 -9.60179806e+00 -9.63250637e+00 -7.95287895e+00 -7.00351572e+00 -1.00003214e+01 -1.12303629e+01 -9.48632526e+00 -7.02487898e+00 -5.07877254e+00 -5.43772125e+00 -4.19854546e+00 -4.60811901e+00 -5.25943422e+00 -5.75610590e+00 -5.75660324e+00 -5.46511030e+00 -6.30381346e+00 -6.05783892e+00 -4.86700630e+00 -5.11728525e+00 -6.75903368e+00 -7.64911079e+00 -6.49284220e+00 -5.07970953e+00 -5.50440502e+00 -7.27926111e+00 -7.47573233e+00 -6.87156773e+00 -5.94472313e+00 -6.87459660e+00 -6.98344326e+00 -6.56419277e+00 -6.30962229e+00 -6.35086584e+00 -5.45930767e+00 -2.94244647e+00 -2.24950528e+00 -2.39694405e+00 -4.34018230e+00 -4.96245193e+00 -5.54891348e+00 -6.08294916e+00 -6.04922056e+00 -4.66682053e+00 -4.31334019e+00 -6.41551542e+00 -8.02368355e+00 -7.88349390e+00 -5.55167866e+00 -5.28624487e+00 -6.18383265e+00 -6.55969334e+00 -7.70981646e+00 -5.95698929e+00 -6.34547853e+00 -4.93753958e+00 -5.79973173e+00 -7.43498898e+00 -8.54605770e+00 -8.80743885e+00 -6.08488083e+00 -2.95733953e+00 -3.43930316e+00 -4.80648708e+00 -6.48504257e+00 -4.81038713e+00 -2.92321348e+00 -2.34453535e+00 -9.89782751e-01 -3.13193107e+00 -4.71417713e+00 -6.28620720e+00 -5.00070381e+00 -3.40566730e+00 -2.51831198e+00 -2.91812229e+00 -3.49566960e+00 -5.21336746e+00 -5.87188673e+00 -6.19040346e+00 -4.26789427e+00 -1.90491211e+00 -2.05013776e+00 -3.12864542e+00 -3.37115526e+00 -1.62017417e+00 -1.74506354e+00 -4.69486094e+00 -6.66082191e+00 -5.65478182e+00 -3.42774820e+00 -2.31535769e+00 -2.54389405e+00 -1.30035925e+00 -1.33920062e+00 -2.62907743e+00 -3.48101616e+00 -4.74091578e+00 -2.84157586e+00 -3.66640162e+00 -3.69579911e+00 -4.45222378e+00 -4.23382854e+00 -1.23055303e+00 3.46965432e-01 -2.14828476e-01 -2.06724524e+00 -5.00617790e+00 -4.64031553e+00 -3.76850247e+00 -1.11580920e+00 8.19844782e-01 1.52394390e+00 -3.44684929e-01 -2.29312301e+00 -2.54326677e+00 -5.91105968e-02 -2.87672162e-01 3.47088933e-01 2.87167311e-01 8.81189525e-01 6.53375328e-01 -1.38270348e-01 1.55605423e+00 2.50613093e+00 2.36766553e+00 9.55984056e-01 -1.89262342e+00 -3.05555534e+00 -2.88004518e+00 -6.31676972e-01 1.69417882e+00 2.12032485e+00 -1.87554762e-01 -1.09065580e+00 6.89409792e-01 2.77578259e+00 2.59187675e+00 4.97846127e-01 2.63452858e-01 -5.76050095e-02 6.61703348e-01 -2.28666440e-01 -1.16568275e-01 2.75362015e-01 -1.64725792e+00 -5.17615266e-02 -4.22630042e-01 1.24019635e+00 7.73557007e-01 1.39555478e+00 3.20886517e+00 1.32178819e+00 1.49057674e+00 1.53906608e+00 3.64784980e+00 3.41830564e+00 1.27252567e+00 9.55774216e-04 9.33959335e-02 2.61490774e+00 3.81367612e+00 3.54268312e+00 2.59166002e+00 1.71628296e+00 2.79946613e+00 4.03599691e+00 5.36605740e+00 5.92332411e+00 4.98921013e+00 2.98475456e+00 1.10144532e+00 2.19310856e+00 4.31316710e+00 6.01927948e+00 5.87707424e+00 5.01321125e+00 3.34870386e+00 2.39017224e+00 2.45394015e+00 4.44017744e+00 6.10881376e+00 5.68722010e+00 3.92530084e+00 2.60393810e+00 3.07380223e+00 4.64564276e+00 4.81165218e+00 5.05881834e+00 3.24481797e+00 1.84644949e+00 1.91069925e+00 2.45978117e+00 4.37048721e+00 5.33800507e+00 5.68598890e+00 5.29203749e+00 3.58209085e+00 3.73558569e+00 5.10501480e+00 5.95227146e+00 6.65048218e+00 4.97959089e+00 5.12432194e+00 5.74131012e+00 7.02968597e+00 7.15547800e+00 4.79188871e+00 3.49611616e+00 3.84040999e+00 6.47688866e+00 8.10601711e+00 8.64472294e+00 8.50973225e+00 7.35140705e+00 6.08553982e+00 5.63024759e+00 5.54660463e+00 6.47594166e+00 6.59095812e+00 6.13051701e+00 6.82107019e+00 7.07300377e+00 8.61901665e+00 8.06827545e+00 8.21088314e+00 7.98997498e+00 6.90360498e+00 6.71736288e+00 7.69159937e+00 9.97244930e+00 1.06451721e+01 9.92791653e+00 9.10411358e+00 8.35490799e+00 8.91442013e+00 9.87510681e+00 1.02041578e+01 1.01847506e+01 8.73352814e+00 7.98645782e+00 7.82026815e+00 8.37815952e+00 8.65110683e+00 8.07825565e+00 8.37681389e+00 8.47306538e+00 7.11638689e+00 6.78495169e+00 7.32289505e+00 8.39496040e+00 7.52968121e+00 5.91947174e+00 5.93804598e+00 7.28491306e+00 9.59422016e+00 1.07691507e+01 9.56912327e+00 8.95591831e+00 8.68577671e+00 9.50948048e+00 9.84533215e+00 9.12203407e+00 9.26590443e+00 8.59511566e+00 8.69148827e+00 8.67867661e+00 8.55916500e+00 9.22681904e+00 9.68363571e+00 9.37212181e+00 9.25969505e+00 8.47212124e+00 9.46032524e+00 9.45393753e+00 1.05661583e+01 1.02318649e+01 9.13826752e+00 8.91434479e+00 9.10787964e+00 1.00210752e+01 1.05122204e+01 9.75372028e+00 9.22847652e+00 7.60429096e+00 8.84070015e+00 1.07056570e+01 1.21250801e+01 1.21946106e+01 1.10245733e+01 1.12116175e+01 1.20072536e+01 1.27948132e+01 1.46300716e+01 1.54321241e+01 1.57748289e+01 1.55919170e+01 1.46098614e+01 1.02816153e+01 1.15416565e+01 2.11523609e+01 2.99039307e+01 6.05035324e+01 4.29589539e+01 6.06867859e+02 3.59162427e+03 -53644572. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -79591544. -21474200. 3.50486255e+03 1.45045264e+03 1.80839554e+02 -3.94389557e+02 -2.97661896e+02 -2.58194675e+01 -6.62359285e+00 8.23569870e+00 1.30937462e+01 1.23527994e+01 1.20587883e+01 1.23581285e+01 1.42642469e+01 1.49692039e+01 1.56077232e+01 1.55925722e+01 1.54547749e+01 1.50094824e+01 1.48301353e+01 1.45175104e+01 1.50408764e+01 1.59104176e+01 1.61373749e+01 1.50358458e+01 1.48933420e+01 1.57599926e+01 1.71912975e+01 1.63412666e+01 1.52028246e+01 1.51006765e+01 1.57309523e+01 1.60696144e+01 1.59274960e+01 1.56494761e+01 1.62279510e+01 1.61893463e+01 1.58191366e+01 1.53696299e+01 1.54537497e+01 1.64438877e+01 1.59718285e+01 1.58229761e+01 1.54293146e+01 1.49839220e+01 1.53851957e+01 1.62771091e+01 1.79623566e+01 1.79514179e+01 1.66012211e+01 1.66101513e+01 1.67857037e+01 1.82396698e+01 1.77228985e+01 1.69277592e+01 1.61680965e+01 1.63254223e+01 1.71760941e+01 1.72754536e+01 1.69764194e+01 1.69118519e+01 1.64756184e+01 1.58507042e+01 1.61045074e+01 1.68025150e+01 1.76800861e+01 1.69644890e+01 1.67964420e+01 1.64120045e+01 1.62964268e+01 1.66238976e+01 1.70301361e+01 1.76551800e+01 1.74267883e+01 1.69929047e+01 1.74393711e+01 1.81309433e+01 1.94483833e+01 1.92560139e+01 1.82164917e+01 1.79435081e+01 1.76162548e+01 1.77405949e+01 1.78828468e+01 1.83130836e+01 1.88980637e+01 1.85366840e+01 1.84170265e+01 1.85885735e+01 1.84654140e+01 1.79790478e+01 1.72252979e+01 1.75664577e+01 1.82706776e+01 1.83095627e+01 1.83663540e+01 1.81566772e+01 1.83312645e+01 1.85263519e+01 1.78194084e+01 1.81348209e+01 1.85909843e+01 1.94435253e+01 1.94393501e+01 1.88178806e+01 1.86702652e+01 1.84208202e+01 1.81128788e+01 1.81962433e+01 1.80658779e+01 1.85402527e+01 1.82830219e+01 1.83191128e+01 1.83270321e+01 1.84393749e+01 1.88818092e+01 1.92197514e+01 1.93257198e+01 2.00539837e+01 1.98269157e+01 1.98067284e+01 1.94307365e+01 1.94608421e+01 1.99426556e+01 1.90903473e+01 1.91022320e+01 1.92594109e+01 2.01256142e+01 2.01487789e+01 1.94776154e+01 1.93939381e+01 1.93517723e+01 1.93675556e+01 1.93877888e+01 1.94980373e+01 1.97960377e+01 1.96142006e+01 1.95676003e+01 1.96034641e+01 1.97263432e+01 1.99465942e+01 1.96761112e+01 1.94928207e+01 1.94254551e+01 1.95049419e+01 1.94174500e+01 1.91542950e+01 1.89003410e+01 1.91875343e+01 1.93807735e+01 1.96082039e+01 1.95112038e+01 1.97946396e+01 2.01639042e+01 2.02477493e+01 2.02305355e+01 1.99061985e+01 1.98118935e+01 1.97161293e+01 1.96137810e+01 1.93208599e+01 1.94398804e+01 1.95423374e+01 1.97205143e+01 1.95368538e+01 1.96848812e+01 2.00914440e+01 2.04075756e+01 2.04951591e+01 2.00435638e+01 1.98889961e+01 2.00117779e+01 2.02305679e+01 2.02362766e+01 2.00366764e+01 2.00944710e+01 2.00302505e+01 2.00122604e+01 2.00994091e+01 2.01988564e+01 2.02878342e+01 2.01700459e+01 2.00861015e+01 2.02257442e+01 2.01695957e+01 2.01683483e+01 2.00228615e+01 1.99744339e+01 1.98756428e+01 1.98404408e+01 2.01187687e+01 2.03365631e+01 2.04656258e+01 2.04363461e+01 2.02551556e+01 2.02534122e+01 2.03478718e+01 2.05447559e+01 2.06062412e+01 2.04928455e+01 2.04382343e+01 2.03615780e+01 2.03942604e+01 2.03343601e+01 2.02937756e+01 2.03098812e+01 2.03358097e+01 2.03687973e+01 2.03828983e+01 2.04424419e+01 2.05015469e+01 2.05014133e+01 2.05361443e+01 2.05287571e+01 2.04550705e+01 2.04094181e+01 2.04335155e+01 2.04959602e+01 2.05237293e+01 2.05159359e+01 2.05246601e+01 2.05283146e+01 2.05298080e+01 2.05239449e+01 2.05175343e+01 2.05174809e+01 2.05316944e+01 2.05526028e+01 2.05326443e+01 2.05119591e+01 2.04917450e+01 2.05170879e+01 2.05152111e+01 2.05024643e+01 2.05004959e+01 2.05149059e+01 2.04858990e+01 2.04655228e+01 2.04595814e+01 2.04998341e+01 2.05329075e+01 2.05172920e+01 2.04834347e+01 2.04472370e+01 2.04679947e+01 2.04893360e+01 2.05110550e+01 2.04726906e+01 2.04438496e+01 2.04392643e+01 2.04506264e+01 2.05363274e+01 2.06017208e+01 2.05477581e+01 2.04397030e+01 2.02765045e+01 2.03170376e+01 2.03552971e+01 2.03915195e+01 2.03488941e+01 2.04723434e+01 2.04326096e+01 2.04419765e+01 2.02490330e+01 2.03179607e+01 2.03121681e+01 2.02886848e+01 2.01848831e+01 2.01880856e+01 2.01497841e+01 2.01696148e+01 2.00322762e+01 2.00099258e+01 2.00738125e+01 2.01477146e+01 2.02772121e+01 2.00788765e+01 2.00491848e+01 2.00325432e+01 2.02646370e+01 2.02836647e+01 2.00577888e+01 2.01265259e+01 2.01885872e+01 2.02817230e+01 1.99031944e+01 1.97546787e+01 1.96701336e+01 1.96624737e+01 1.96298866e+01 1.97471504e+01 1.99071026e+01 1.98449802e+01 1.98791885e+01 1.97431583e+01 1.96741161e+01 1.96009560e+01 1.96869564e+01 1.98450489e+01 1.97335796e+01 1.98233280e+01 1.98439274e+01 1.99080200e+01 1.97207470e+01 1.96774731e+01 1.96614723e+01 1.97412186e+01 1.95191936e+01 1.92771225e+01 1.90124302e+01 1.92245274e+01 1.95030556e+01 1.98155746e+01 1.98881016e+01 1.97160282e+01 1.94945393e+01 1.92664661e+01 1.93312435e+01 1.94555035e+01 1.93104267e+01 1.91229038e+01 1.90426617e+01 1.94221630e+01 1.97202053e+01 1.98839931e+01 1.97929230e+01 1.96845169e+01 1.93503513e+01 1.88689785e+01 1.86202526e+01 1.85825272e+01 1.88749428e+01 1.88431797e+01 1.88912182e+01 1.89134312e+01 1.90776176e+01 1.90023251e+01 1.89314880e+01 1.88972168e+01 1.90377350e+01 1.89096069e+01 1.91645775e+01 1.92273693e+01 1.96987000e+01 1.98079624e+01 1.95785255e+01 1.92361393e+01 1.88012905e+01 1.91486664e+01 1.93368702e+01 1.91915569e+01 1.88147945e+01 1.89845009e+01 1.92876472e+01 1.95772209e+01 1.90313644e+01 1.89437618e+01 1.86649990e+01 1.88505402e+01 1.87450714e+01 1.86198940e+01 1.84544048e+01 1.77600212e+01 1.71532860e+01 1.71284676e+01 1.73662567e+01 1.79056911e+01 1.76643581e+01 1.76425304e+01 1.75332298e+01 1.74781113e+01 1.78621845e+01 1.79982185e+01 1.82478409e+01 1.81110191e+01 1.80445099e+01 1.78943119e+01 1.77309837e+01 1.76165981e+01 1.72444077e+01 1.73101501e+01 1.74596157e+01 1.73059788e+01 1.69431534e+01 1.64916954e+01 1.63446579e+01 1.65677166e+01 1.71166630e+01 1.73456974e+01 1.73900490e+01 1.71674557e+01 1.72285538e+01 1.72653160e+01 1.70598297e+01 1.71006947e+01 1.69125900e+01 1.68576336e+01 1.58598328e+01 1.61669102e+01 1.65396996e+01 1.70193768e+01 1.70131855e+01 1.70174828e+01 1.75846519e+01 1.79171028e+01 1.75487118e+01 1.72500248e+01 1.68026695e+01 1.69591389e+01 1.66850052e+01 1.67860374e+01 1.61750050e+01 1.60136318e+01 1.59185114e+01 1.64471817e+01 1.65860615e+01 1.67187080e+01 1.68983135e+01 1.69546146e+01 1.67938766e+01 1.65063744e+01 1.64014206e+01 1.60967808e+01 1.54934082e+01 1.51275940e+01 1.50183592e+01 1.56427956e+01 1.58030205e+01 1.55699520e+01 1.52905321e+01 1.52261734e+01 1.51237755e+01 1.51104040e+01 1.50491104e+01 1.51704597e+01 1.49217615e+01 1.47979584e+01 1.46493149e+01 1.45352802e+01 1.43443155e+01 1.48766727e+01 1.48716593e+01 1.50085430e+01 1.48021841e+01 1.48621807e+01 1.47152815e+01 1.40416832e+01 1.35805635e+01 1.11142387e+01 1.06423626e+01 1.15166254e+01 1.58772736e+01 1.55514011e+01 1.32926006e+01 1.50409813e+01 8.66489792e+00 -2.14953899e+00 -4.17864847e+00 -1.73628902e+01 -8.28491116e+00 1.39113068e+02 2.92742090e+03 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. 0. 0. 0. 0. 0. 0. 0. 81798760. -9.84515625e+03 -1.76396680e+03 -2.02457779e+02 -4.65064850e+01 2.65666389e+01 5.70033569e+02 4.19501160e+02 9.51424103e+01 4.89609756e+01 2.41954727e+01 1.96839237e+01 1.57756128e+01 1.36511831e+01 1.07101259e+01 1.05806112e+01 1.01973248e+01 9.66465092e+00 9.10827446e+00 9.11841583e+00 9.30256939e+00 1.06159592e+01 1.20855417e+01 1.21842003e+01 1.17685966e+01 1.07204170e+01 1.09274683e+01 1.06932545e+01 1.03996334e+01 1.00616970e+01 9.62080574e+00 1.01270466e+01 1.05417910e+01 1.08284283e+01 1.06612196e+01 1.09232168e+01 1.00768185e+01 9.85638714e+00 9.44097328e+00 9.96228600e+00 9.48955536e+00 9.23699188e+00 9.22325611e+00 8.93338776e+00 9.22079468e+00 9.28727055e+00 9.77440453e+00 9.80843544e+00 9.14289951e+00 7.60255766e+00 7.32550097e+00 8.31714249e+00 9.70500946e+00 9.81167698e+00 9.28192711e+00 8.81831360e+00 8.71415806e+00 9.01070499e+00 9.49916649e+00 9.64236355e+00 9.33202457e+00 8.84168434e+00 7.13718557e+00 6.26823235e+00 5.96852303e+00 5.81217384e+00 5.76494074e+00 5.20699024e+00 6.13199472e+00 7.15109539e+00 7.80782700e+00 8.51689911e+00 8.57972527e+00 8.17450905e+00 8.54820347e+00 8.97276115e+00 1.05132980e+01 1.07399254e+01 1.04024057e+01 8.86908627e+00 7.44592905e+00 7.01397657e+00 6.93240499e+00 5.95122194e+00 6.42317200e+00 5.06072378e+00 5.26804018e+00 4.72506571e+00 6.01399183e+00 6.89738894e+00 7.10810184e+00 6.53946590e+00 5.34532070e+00 3.80337667e+00 3.56618381e+00 4.72272778e+00 5.30252695e+00 5.19909143e+00 4.36789274e+00 4.49733353e+00 4.12450600e+00 4.39212799e+00 5.07505274e+00 5.35474014e+00 5.78136921e+00 4.84737778e+00 4.61167526e+00 3.92468739e+00 3.22374368e+00 2.91428924e+00 1.74791598e+00 1.88181746e+00 2.03385878e+00 3.72745585e+00 5.52770710e+00 6.37925768e+00 6.45062780e+00 6.11801815e+00 5.55093765e+00 5.10161161e+00 4.99795532e+00 5.17599249e+00 4.47514582e+00 3.72894287e+00 3.21465087e+00 3.83086991e+00 4.11103439e+00 3.38188720e+00 2.01789021e+00 9.53599393e-01 1.30970800e+00 1.64726484e+00 1.41871619e+00 1.15769482e+00 6.67145908e-01 3.61703485e-01 1.50878504e-01 9.44639504e-01 1.96376598e+00 2.74469757e+00 3.21788430e+00 3.26684833e+00 3.12796950e+00 2.89728665e+00 2.49414372e+00 2.79639125e+00 2.51658535e+00 2.09798121e+00 1.30693305e+00 1.41682303e+00 1.58516240e+00 1.64235270e+00 1.65471625e+00 1.27376115e+00 5.30241549e-01 3.14303368e-01 8.12046289e-01 1.10184801e+00 6.41522944e-01 -5.11385202e-01 -2.97959328e-01 -9.70747113e-01 -7.73781538e-01 -1.40682006e+00 -4.39388573e-01 2.04763785e-01 7.67414331e-01 8.43065858e-01 7.01711655e-01 8.54742169e-01 -2.54090820e-02 -2.61570901e-01 -2.06454024e-01 -4.97797579e-01 -1.09409249e+00 -1.00317430e+00 1.03014207e+00 2.71673799e+00 2.52109075e+00 1.23993278e+00 4.24651317e-02 -4.91553620e-02 2.83614427e-01 8.56009126e-01 5.18106163e-01 -3.23867708e-01 -1.97829461e+00 -1.95962012e+00 -8.46330822e-01 -3.80667709e-02 -5.88828325e-01 -2.15482903e+00 -2.19586778e+00 -1.57223046e+00 -1.36782038e+00 -1.80556285e+00 -2.77883577e+00 -2.44594955e+00 -1.94034302e+00 -1.96182334e+00 -2.24779987e+00 -1.21098685e+00 7.55110532e-02 7.00327680e-02 -1.04808557e+00 -1.88445878e+00 -2.28415966e+00 -2.46707582e+00 -2.82136965e+00 -2.39792442e+00 -2.84142995e+00 -2.98299265e+00 -3.41211987e+00 -2.80531836e+00 -3.22068334e+00 -2.91662049e+00 -3.50340629e+00 -3.47632551e+00 -3.79585004e+00 -3.17362046e+00 -3.34519172e+00 -3.38337827e+00 -3.57459974e+00 -3.32763910e+00 -3.09666872e+00 -3.36361313e+00 -2.72419977e+00 -2.15875101e+00 -2.43124366e+00 -2.90092278e+00 -3.86337447e+00 -3.63244748e+00 -3.63577962e+00 -3.26648116e+00 -3.02540183e+00 -2.94711757e+00 -3.70839047e+00 -3.55412078e+00 -3.41113210e+00 -3.20283008e+00 -4.24306488e+00 -4.63191271e+00 -4.87211370e+00 -4.54590893e+00 -4.12129354e+00 -3.58660221e+00 -3.63711667e+00 -4.35137749e+00 -6.19840240e+00 -7.07019615e+00 -7.18372154e+00 -6.33189011e+00 -4.73893785e+00 -5.23975325e+00 -6.84614372e+00 -8.26667213e+00 -7.94942331e+00 -5.96213770e+00 -5.48609114e+00 -5.62478018e+00 -6.00154638e+00 -5.99468279e+00 -5.79614830e+00 -5.70602846e+00 -5.48575544e+00 -5.67509270e+00 -6.18208313e+00 -5.89780426e+00 -5.92977381e+00 -5.85591221e+00 -7.09562016e+00 -6.93668890e+00 -6.90334654e+00 -5.48466921e+00 -5.58761215e+00 -5.63079929e+00 -6.79545784e+00 -7.58464575e+00 -8.26450157e+00 -9.18833828e+00 -8.94510651e+00 -8.32516289e+00 -6.70681906e+00 -6.70870972e+00 -7.03272820e+00 -7.63580418e+00 -7.79871082e+00 -7.49132204e+00 -7.26768684e+00 -7.90362072e+00 -8.13398361e+00 -8.78059864e+00 -8.70844173e+00 -8.93018627e+00 -9.38008308e+00 -9.42391109e+00 -9.86197376e+00 -1.04967251e+01 -9.90739250e+00 -8.80712700e+00 -7.89835835e+00 -8.60505295e+00 -9.42263889e+00 -9.19470406e+00 -9.56866646e+00 -1.02243290e+01 -1.10227909e+01 -1.11179228e+01 -1.09573841e+01 -1.03514347e+01 -1.03489676e+01 -1.01490564e+01 -9.56706429e+00 -9.29565430e+00 -8.98949718e+00 -8.90742111e+00 -1.02561808e+01 -9.99060917e+00 -1.01375456e+01 -9.26448727e+00 -9.47739220e+00 -9.70584106e+00 -9.41415691e+00 -9.64314842e+00 -9.74204731e+00 -1.01330175e+01 -1.07260647e+01 -1.17721586e+01 -1.28357248e+01 -1.34853697e+01 -1.32000952e+01 -1.32843466e+01 -1.18578596e+01 -1.12494278e+01 -1.03350801e+01 -1.08081074e+01 -1.11178741e+01 -1.18460779e+01 -1.24368258e+01 -1.21875906e+01 -1.18356504e+01 -1.07860079e+01 -1.00339031e+01 -9.91325855e+00 -1.01805220e+01 -1.08105021e+01 -1.13966579e+01 -1.17543001e+01 -1.21970339e+01 -1.29166994e+01 -1.25529966e+01 -1.20717211e+01 -1.08883820e+01 -1.13708639e+01 -1.22288647e+01 -1.25893011e+01 -1.27215986e+01 -1.22508812e+01 -1.18739023e+01 -1.09879417e+01 -1.13483057e+01 -1.13050394e+01 -1.17069092e+01 -1.15444927e+01 -1.14945984e+01 -1.18791142e+01 -1.22210360e+01 -1.23263721e+01 -1.18329992e+01 -1.20013037e+01 -1.26545563e+01 -1.35480080e+01 -1.47485847e+01 -1.36990538e+01 -1.29700928e+01 -1.23574562e+01 -1.37672682e+01 -1.37132044e+01 -1.43540440e+01 -1.40332699e+01 -1.51367579e+01 -1.49847660e+01 -1.50987606e+01 -1.46604567e+01 -1.38757305e+01 -1.40549040e+01 -1.42717466e+01 -1.51484423e+01 -1.50770330e+01 -1.50445604e+01 -1.44101372e+01 -1.42932892e+01 -1.42048082e+01 -1.45567799e+01 -1.44763184e+01 -1.47929029e+01 -1.54390888e+01 -1.65148163e+01 -1.57744265e+01 -1.39766245e+01 -1.36146460e+01 -1.51079979e+01 -1.60293121e+01 -1.54441624e+01 -1.46705418e+01 -1.46000862e+01 -1.44213505e+01 -1.41413546e+01 -1.37672138e+01 -1.43480473e+01 -1.44933786e+01 -1.43266392e+01 -1.38373022e+01 -1.48024445e+01 -1.52284012e+01 -1.52315693e+01 -1.51071072e+01 -1.61434231e+01 -1.60149651e+01 -1.54812670e+01 -1.46641665e+01 -1.52923479e+01 -1.52856998e+01 -1.47014112e+01 -1.46258631e+01 -1.48532572e+01 -1.54652891e+01 -1.55440960e+01 -1.53159285e+01 -1.55166616e+01 -1.63042755e+01 -1.65980320e+01 -1.65593128e+01 -1.59985056e+01 -1.57961655e+01 -1.53858881e+01 -1.56961279e+01 -1.66037006e+01 -1.73427067e+01 -1.73687477e+01 -1.70415363e+01 -1.73016014e+01 -1.78671932e+01 -1.78487511e+01 -1.73102341e+01 -1.60505009e+01 -1.51642065e+01 -1.52663040e+01 -1.56166124e+01 -1.61478729e+01 -1.65824966e+01 -1.73490086e+01 -1.77052765e+01 -1.72898502e+01 -1.71111107e+01 -1.72336063e+01 -1.72175636e+01 -1.70349903e+01 -1.69972839e+01 -1.69730740e+01 -1.72409286e+01 -1.70907059e+01 -1.78417759e+01 -1.81255398e+01 -1.79898129e+01 -1.73827133e+01 -1.67932091e+01 -1.73335419e+01 -1.71179752e+01 -1.71523914e+01 -1.75193958e+01 -1.85648746e+01 -1.95460472e+01 -1.96041603e+01 -1.91943398e+01 -1.87831173e+01 -1.87523327e+01 -1.86477528e+01 -1.86194477e+01 -1.84588280e+01 -1.85440407e+01 -1.85874996e+01 -1.88543549e+01 -1.91772346e+01 -1.90876503e+01 -1.85815620e+01 -1.79599609e+01 -1.81342049e+01 -1.85685863e+01 -1.88718357e+01 -1.85083637e+01 -1.85150261e+01 -1.88005333e+01 -1.85854607e+01 -1.78175011e+01 -1.73513260e+01 -1.75701180e+01 -1.81055050e+01 -1.78759804e+01 -1.75392437e+01 -1.75233803e+01 -1.77736149e+01 -1.82400513e+01 -1.83745003e+01 -1.83229599e+01 -1.81948013e+01 -1.80757599e+01 -1.86101017e+01 -1.93275185e+01 -1.97894821e+01 -1.98871384e+01 -1.94180412e+01 -1.90252228e+01 -1.87780819e+01 -1.89574013e+01 -1.90200005e+01 -1.89992695e+01 -1.88002892e+01 -1.87035007e+01 -1.82688141e+01 -1.86731644e+01 -1.90366383e+01 -1.98031330e+01 -1.97468395e+01 -1.95801907e+01 -1.97886581e+01 -2.00002823e+01 -2.00059719e+01 -1.96717548e+01 -1.94205055e+01 -1.95128002e+01 -1.94361305e+01 -1.95444584e+01 -1.96223202e+01 -1.97272396e+01 -1.98175068e+01 -1.97441578e+01 -1.98023529e+01 -1.97687073e+01 -1.96773205e+01 -1.95016823e+01 -1.95685787e+01 -1.97285461e+01 -1.99104500e+01 -1.98999519e+01 -1.99750042e+01 -2.00239048e+01 -1.98760738e+01 -1.97041225e+01 -1.96669712e+01 -2.00360661e+01 -2.01999397e+01 -2.00989571e+01 -1.98293209e+01 -1.96929874e+01 -1.98111820e+01 -1.99962940e+01 -2.02205734e+01 -2.02565422e+01 -2.01618176e+01 -1.97555504e+01 -1.98723850e+01 -2.01384716e+01 -2.03722115e+01 -2.03966942e+01 -2.00175495e+01 -2.02969170e+01 -2.04069939e+01 -2.04131508e+01 -2.00554771e+01 -1.98452435e+01 -2.01250172e+01 -2.03222637e+01 -2.02617607e+01 -2.01979580e+01 -2.01702290e+01 -2.02551289e+01 -2.03511066e+01 -2.05100250e+01 -2.07154350e+01 -2.06661510e+01 -2.04950237e+01 -2.03693676e+01 -2.03906384e+01 -2.04741554e+01 -2.04393368e+01 -2.04501438e+01 -2.04680729e+01 -2.04190998e+01 -2.04458122e+01 -2.03228054e+01 -2.03932838e+01 -2.03616142e+01 -2.03438778e+01 -2.03143711e+01 -2.04206944e+01 -2.05857830e+01 -2.07119808e+01 -2.05868301e+01 -2.04554214e+01 -2.03763084e+01 -2.04141102e+01 -2.05392590e+01 -2.06822510e+01 -2.08130093e+01 -2.10067272e+01 -2.07645073e+01 -2.06834145e+01 -2.08147030e+01 -2.44961567e+01 -2.92043591e+01 -9.87035370e+01 -2.09306580e+02 19313596. 70713560. 0. 0. 0. 0. 0. -252229952. 1.63276025e+06 -1.68809509e+02 -1.36874536e+03 -11309393. 32765716. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 407427488. 7.45190674e+02 -2.28827477e+00 -3.82274895e+01 -4.10569115e+01 -3.84589310e+01 -3.91496201e+01 -3.81649857e+01 -3.82942657e+01 -3.83990707e+01 -3.84078712e+01 -3.83756332e+01 -3.83194847e+01 -3.81282692e+01 -3.79576416e+01 -3.78389282e+01 -3.79761543e+01 -3.81930923e+01 -3.82312698e+01 -3.82476616e+01 -3.79386597e+01 -3.77250710e+01 -3.74008751e+01 -3.74545364e+01 -3.76195831e+01 -3.78028641e+01 -3.78107452e+01 -3.82207565e+01 -3.83363037e+01 -3.80865326e+01 -3.73485985e+01 -3.69017639e+01 -3.71215591e+01 -3.74212151e+01 -3.79084129e+01 -3.79539146e+01 -3.78768921e+01 -3.77382774e+01 -3.74974518e+01 -3.74066429e+01 -3.71562271e+01 -3.68848114e+01 -3.69937706e+01 -3.72726898e+01 -3.74288139e+01 -3.71754761e+01 -3.71603775e+01 -3.73806076e+01 -3.72024460e+01 -3.69937668e+01 -3.70199203e+01 -3.70805931e+01 -3.75819550e+01 -3.76808815e+01 -3.77241974e+01 -3.68085747e+01 -3.60126877e+01 -3.57981911e+01 -3.63538361e+01 -3.70571175e+01 -3.69033432e+01 -3.66136246e+01 -3.62601051e+01 -3.64776649e+01 -3.65271339e+01 -3.61621780e+01 -3.57713470e+01 -3.57971382e+01 -3.63937874e+01 -3.70234642e+01 -3.67038040e+01 -3.66163483e+01 -3.66233978e+01 -3.64480057e+01 -3.62379456e+01 -3.59478416e+01 -3.62322998e+01 -3.69149132e+01 -3.72494202e+01 -3.74949493e+01 -3.64976883e+01 -3.58475838e+01 -3.45911102e+01 -3.48666115e+01 -3.56496010e+01 -3.60783119e+01 -3.58471870e+01 -3.58814468e+01 -3.69655952e+01 -3.64396515e+01 -3.53964767e+01 -3.39588280e+01 -3.43254509e+01 -3.57793198e+01 -3.65563927e+01 -3.63772011e+01 -3.54240379e+01 -3.62507896e+01 -3.58628464e+01 -3.58257675e+01 -3.46838608e+01 -3.48582726e+01 -3.52950020e+01 -3.58302498e+01 -3.62757950e+01 -3.53111115e+01 -3.45778694e+01 -3.37965736e+01 -3.38282051e+01 -3.47884140e+01 -3.52970352e+01 -3.51566200e+01 -3.47498207e+01 -3.53089790e+01 -3.55291405e+01 -3.52174149e+01 -3.42968254e+01 -3.40838814e+01 -3.42341080e+01 -3.48537827e+01 -3.53298836e+01 -3.50984764e+01 -3.47843895e+01 -3.33670959e+01 -3.29110069e+01 -3.32472076e+01 -3.36563988e+01 -3.40161552e+01 -3.50098915e+01 -3.54823380e+01 -3.52291641e+01 -3.42332954e+01 -3.38054314e+01 -3.31332512e+01 -3.25121651e+01 -3.24764099e+01 -3.32937164e+01 -3.33437271e+01 -3.37766266e+01 -3.43621407e+01 -3.46735954e+01 -3.32080650e+01 -3.15103092e+01 -2.99431839e+01 -3.04642963e+01 -3.06773949e+01 -3.15972710e+01 -3.18719883e+01 -3.18657646e+01 -3.12188110e+01 -3.13876381e+01 -3.15489082e+01 -3.14647331e+01 -3.20506783e+01 -3.27221756e+01 -3.29401169e+01 -3.19072514e+01 -3.09876633e+01 -3.14752312e+01 -3.10487614e+01 -3.10366573e+01 -2.98695965e+01 -2.95772953e+01 -3.03879776e+01 -3.07334576e+01 -3.15184402e+01 -2.99065437e+01 -2.88158073e+01 -2.74270267e+01 -2.91532574e+01 -3.07115364e+01 -3.15744324e+01 -3.18239613e+01 -3.18994732e+01 -3.16958542e+01 -3.01972294e+01 -2.79564342e+01 -2.79602585e+01 -2.93078060e+01 -3.21686668e+01 -3.17474728e+01 -2.96837902e+01 -2.86195984e+01 -2.73023796e+01 -2.79348030e+01 -2.65911160e+01 -2.76500149e+01 -2.71091805e+01 -2.90167427e+01 -2.90975704e+01 -2.94737968e+01 -2.83750210e+01 -2.88562469e+01 -2.82602997e+01 -2.94355755e+01 -3.04612331e+01 -3.06552429e+01 -3.06609688e+01 -3.04164925e+01 -3.12879524e+01 -2.90349388e+01 -2.74693394e+01 -2.67986164e+01 -2.85691605e+01 -3.15212097e+01 -3.06723995e+01 -3.03864861e+01 -2.71902580e+01 -2.87016926e+01 -2.86253548e+01 -2.85110569e+01 -2.72130928e+01 -2.80558453e+01 -2.87484913e+01 -2.92096634e+01 -2.73675518e+01 -2.65654888e+01 -2.41677189e+01 -2.54306316e+01 -2.75772171e+01 -3.05725651e+01 -2.96851101e+01 -2.77086029e+01 -2.57146969e+01 -2.51410618e+01 -2.46612034e+01 -2.65590649e+01 -2.71570072e+01 -2.76886787e+01 -2.66911983e+01 -2.63391361e+01 -2.55581932e+01 -2.66421909e+01 -2.69472504e+01 -2.69063072e+01 -2.49492817e+01 -2.46092339e+01 -2.45863018e+01 -2.50580387e+01 -2.61936588e+01 -2.66269093e+01 -2.42668266e+01 -2.19064388e+01 -2.24309330e+01 -2.50978851e+01 -2.61964989e+01 -2.62333107e+01 -2.47926044e+01 -2.38547077e+01 -2.18827839e+01 -2.10766525e+01 -2.08504581e+01 -2.13363476e+01 -2.43298950e+01 -2.19265690e+01 -2.29994373e+01 -2.12803841e+01 -2.46249084e+01 -2.28574581e+01 -2.21626835e+01 -2.02263298e+01 -1.87648830e+01 -2.01420822e+01 -2.09738331e+01 -2.25861931e+01 -2.36793785e+01 -2.13233204e+01 -1.90503426e+01 -1.74323978e+01 -2.00399609e+01 -1.95881214e+01 -1.84874287e+01 -1.68882046e+01 -2.01001148e+01 -2.12121925e+01 -2.21535225e+01 -2.14538517e+01 -2.12864017e+01 -2.14184780e+01 -1.97010155e+01 -1.98443317e+01 -1.84395409e+01 -2.14526386e+01 -2.22008896e+01 -2.27911587e+01 -2.21631927e+01 -2.02713356e+01 -2.11558762e+01 -2.00496731e+01 -1.99995289e+01 -1.83670807e+01 -1.69505882e+01 -1.51695843e+01 -1.58857403e+01 -1.51686993e+01 -1.53415766e+01 -1.45725689e+01 -1.76895676e+01 -1.84924030e+01 -1.90878315e+01 -1.51506557e+01 -1.56447449e+01 -1.62357864e+01 -1.85384693e+01 -1.71898174e+01 -1.56466265e+01 -1.45474319e+01 -1.59398470e+01 -1.54973717e+01 -1.64782314e+01 -1.53718538e+01 -1.64825115e+01 -1.57801542e+01 -1.71347103e+01 -1.78078232e+01 -1.92189064e+01 -1.68918381e+01 -1.32797909e+01 -1.19235859e+01 -1.36962423e+01 -1.46650896e+01 -1.33219452e+01 -1.16144276e+01 -1.45905113e+01 -1.56448641e+01 -1.53227444e+01 -1.47975721e+01 -1.51438160e+01 -1.56016445e+01 -1.36151981e+01 -1.35520163e+01 -1.43109226e+01 -1.40665712e+01 -1.36126957e+01 -1.31928616e+01 -1.46156464e+01 -1.33132696e+01 -1.23139277e+01 -1.07020445e+01 -1.18047333e+01 -1.03281755e+01 -9.72921467e+00 -7.95305920e+00 -1.14215183e+01 -1.17988939e+01 -1.13729315e+01 -8.09591770e+00 -8.00433731e+00 -9.95946503e+00 -1.15404234e+01 -1.04512062e+01 -1.11464357e+01 -1.22308445e+01 -1.42782679e+01 -1.30631094e+01 -1.10867710e+01 -1.00400724e+01 -9.81682396e+00 -1.06071234e+01 -1.05026064e+01 -1.21458063e+01 -1.28246222e+01 -9.80579281e+00 -7.17225170e+00 -4.54870844e+00 -7.29938698e+00 -7.52812147e+00 -9.11263847e+00 -9.11153030e+00 -9.37839508e+00 -9.82407951e+00 -9.63410282e+00 -8.79543495e+00 -6.44976521e+00 -3.06110024e+00 -1.80620432e+00 -2.66523242e+00 -7.04766226e+00 -9.31522560e+00 -8.84921455e+00 -6.51932430e+00 -8.31296253e+00 -1.10156918e+01 -1.24609184e+01 -9.53498554e+00 -9.01126575e+00 -8.59341049e+00 -7.45525742e+00 -4.64652157e+00 -2.36954165e+00 -1.74371028e+00 -4.24900055e+00 -5.34829473e+00 -6.35164022e+00 -4.54440975e+00 -2.29746652e+00 -1.52603865e+00 -3.95077229e-01 -3.41897702e+00 -3.55398536e+00 -4.77103424e+00 -5.41292763e+00 -7.76559973e+00 -6.63304186e+00 -1.63436043e+00 9.87384319e-01 9.46679354e-01 -1.55670440e+00 -2.61301994e+00 -2.83657455e+00 -4.61747599e+00 -3.31179261e+00 -1.37821949e+00 1.77633852e-01 1.38060480e-01 -9.35398042e-03 -5.13479412e-01 2.29170823e+00 1.93524289e+00 3.75448275e+00 2.90587127e-01 -1.68761104e-01 -1.89138520e+00 -4.60385501e-01 1.81047952e+00 4.25091839e+00 3.97131371e+00 6.01400495e-01 -2.92031908e+00 -1.90964532e+00 -1.41186941e+00 1.98265815e+00 -4.50973272e-01 -4.27211225e-01 -1.10889065e+00 -1.42472792e+00 -1.56621993e+00 -2.28590012e+00 2.26489305e-01 1.01237416e+00 8.61215234e-01 -1.07195604e+00 -1.52612829e+00 4.11863565e-01 3.42815781e+00 4.77796316e+00 2.91529369e+00 5.95524251e-01 -1.21728778e+00 -9.35955346e-01 3.44173932e+00 5.42023087e+00 5.75463486e+00 1.12219787e+00 6.14841104e-01 4.55647886e-01 2.80896997e+00 2.92385364e+00 8.65021348e-01 2.13150167e+00 3.14470172e+00 5.39897156e+00 3.29239821e+00 2.90656805e+00 7.54350519e+00 7.53628683e+00 6.51518202e+00 3.46628618e+00 3.99455810e+00 6.51969194e+00 4.45376778e+00 3.82006025e+00 2.71876216e+00 4.45360327e+00 6.33357286e+00 6.52583265e+00 6.57095909e+00 5.23979616e+00 4.19965553e+00 4.79840565e+00 5.04822731e+00 5.95933342e+00 6.44533443e+00 5.29635811e+00 5.77466822e+00 4.83296919e+00 5.41548681e+00 7.64369059e+00 9.69043827e+00 1.08839445e+01 8.35594463e+00 6.23756075e+00 5.04507303e+00 6.05220222e+00 8.24734688e+00 1.04523926e+01 1.00472670e+01 8.35751057e+00 7.04781055e+00 8.36800194e+00 1.07660532e+01 1.15463867e+01 9.10952950e+00 6.84629965e+00 7.31287813e+00 7.98275995e+00 8.92830944e+00 1.12345238e+01 1.21417627e+01 1.43039837e+01 1.08473005e+01 1.04275646e+01 9.33215237e+00 1.12748718e+01 1.27702312e+01 1.43249407e+01 1.25356178e+01 1.23139505e+01 8.59420776e+00 1.15556765e+01 1.04249744e+01 1.03159580e+01 7.60454273e+00 9.25027466e+00 1.54922476e+01 1.86310329e+01 1.71499405e+01 1.18305492e+01 8.09379387e+00 8.58092976e+00 8.11546898e+00 1.08374043e+01 1.16569777e+01 1.37240696e+01 1.39544401e+01 1.27638979e+01 1.29243126e+01 1.44813662e+01 1.50602846e+01 1.49331942e+01 1.36270332e+01 1.30478220e+01 1.31016636e+01 1.23440037e+01 1.47746286e+01 1.42888565e+01 1.29513245e+01 1.09659967e+01 1.08514719e+01 1.21579657e+01 1.25031300e+01 1.42339573e+01 1.44569416e+01 1.31574879e+01 1.18224115e+01 1.19447680e+01 1.41412849e+01 1.55714979e+01 1.49090567e+01 1.48678665e+01 1.52062778e+01 1.53307590e+01 1.61979980e+01 1.81875267e+01 1.83995171e+01 1.65011311e+01 1.36030111e+01 1.51321325e+01 1.56750431e+01 1.80911560e+01 1.84228153e+01 1.82480755e+01 1.54099922e+01 1.43144636e+01 1.54413338e+01 1.49284239e+01 1.58744307e+01 1.58243189e+01 1.73070278e+01 1.79649830e+01 1.88320580e+01 2.12485695e+01 2.15063496e+01 2.10338097e+01 1.91938362e+01 1.83876781e+01 1.93891926e+01 2.26364822e+01 2.05084324e+01 2.18751087e+01 1.95881271e+01 2.13591232e+01 1.93401470e+01 1.86766014e+01 2.01737137e+01 1.96826420e+01 2.02648716e+01 1.93580894e+01 1.97567234e+01 2.16515636e+01 2.29999962e+01 2.44165344e+01 2.28838692e+01 2.01844540e+01 1.85450153e+01 1.89910316e+01 2.04704189e+01 2.06522217e+01 1.91523933e+01 2.05737572e+01 1.56154289e+01 1.79298115e+01 1.60134830e+01 2.01645298e+01 2.08249493e+01 3.12347126e+01 1.76158752e+01 4.42107430e+01 2.38293896e+01 -2.67170925e+01 -3.22650909e+02 14296129. -632457472. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.27612750e+05 -2.88287903e+02 -4.53333664e+01 1.42855997e+01 1.95233459e+01 -1.19266987e+01 -2.24630489e+01 1.28953943e+01 1.98214397e+01 2.28640804e+01 2.69668732e+01 2.70611649e+01 2.80451679e+01 2.92447891e+01 3.00638313e+01 2.97082806e+01 2.83933678e+01 2.89149818e+01 2.94158592e+01 3.03691311e+01 2.93838730e+01 2.94116116e+01 2.82690983e+01 2.78843346e+01 2.75430069e+01 2.92519779e+01 3.13574429e+01 3.15805359e+01 3.10847931e+01 3.10472660e+01 3.13725033e+01 3.09906712e+01 3.07633476e+01 2.97265549e+01 2.92257671e+01 2.88241444e+01 3.00800533e+01 3.09902077e+01 3.22338829e+01 3.27653236e+01 3.28719254e+01 3.17727814e+01 3.23277779e+01 3.29035225e+01 3.35058708e+01 3.43518181e+01 3.34102783e+01 3.20100746e+01 3.01804352e+01 3.00294056e+01 3.15386143e+01 3.12808094e+01 3.17187347e+01 3.07155476e+01 3.07111511e+01 3.09184990e+01 3.17479954e+01 3.29580688e+01 3.37045593e+01 3.37287979e+01 3.30526772e+01 3.22083092e+01 3.28271179e+01 3.38804474e+01 3.35084763e+01 3.24358673e+01 3.13267212e+01 3.18664970e+01 3.33444290e+01 3.45184975e+01 3.54579124e+01 3.58732491e+01 3.58135185e+01 3.47854309e+01 3.38852234e+01 3.41229401e+01 3.31085701e+01 3.23382874e+01 3.11924076e+01 3.21799622e+01 3.40429001e+01 3.46265297e+01 3.54444199e+01 3.46438789e+01 3.47111511e+01 3.42643318e+01 3.44824371e+01 3.52894135e+01 3.51552124e+01 3.50349083e+01 3.50218048e+01 3.56838646e+01 3.62061615e+01 3.57253113e+01 3.49964790e+01 3.52737007e+01 3.52333527e+01 3.54869919e+01 3.49844971e+01 3.50269547e+01 3.54282990e+01 3.58705521e+01 3.57659874e+01 3.46041412e+01 3.36767120e+01 3.41753998e+01 3.47019501e+01 3.59519691e+01 3.57292595e+01 3.65617294e+01 3.63552094e+01 3.61098442e+01 3.56462212e+01 3.58686180e+01 3.61697159e+01 3.62624702e+01 3.54624481e+01 3.57748947e+01 3.57740479e+01 3.57243385e+01 3.61040344e+01 3.58997231e+01 3.56413116e+01 3.46889954e+01 3.49701042e+01 3.61886101e+01 3.69356766e+01 3.66257324e+01 3.59211922e+01 3.56757851e+01 3.66604881e+01 3.66956329e+01 3.68296852e+01 3.61161995e+01 3.59545364e+01 3.56109543e+01 3.55310822e+01 3.64397697e+01 3.70513954e+01 3.72458763e+01 3.68145561e+01 3.64026184e+01 3.69100723e+01 3.69699440e+01 3.69908791e+01 3.70257759e+01 3.74847450e+01 3.78490906e+01 3.79172668e+01 3.77625275e+01 3.80452003e+01 3.78441620e+01 3.76150513e+01 3.67475281e+01 3.62534752e+01 3.63371124e+01 3.68446808e+01 3.74139671e+01 3.75577316e+01 3.76523094e+01 3.76917229e+01 3.76590309e+01 3.75407372e+01 3.76101875e+01 3.78205528e+01 3.80839500e+01 3.78265648e+01 3.73123131e+01 3.70033989e+01 3.70489731e+01 3.77646713e+01 3.79987373e+01 3.78784065e+01 3.74510002e+01 3.74974022e+01 3.76900291e+01 3.76192436e+01 3.76224861e+01 3.77046738e+01 3.78639069e+01 3.78955231e+01 3.78822365e+01 3.79609261e+01 3.80274696e+01 3.79544258e+01 3.80675964e+01 3.81401215e+01 3.82920494e+01 3.82423401e+01 3.83465347e+01 3.85688858e+01 3.84420738e+01 3.82733688e+01 3.80366554e+01 3.80500565e+01 3.82731285e+01 3.82989426e+01 3.82717247e+01 3.79734840e+01 3.79786415e+01 3.80292892e+01 3.82124634e+01 3.83180084e+01 3.82903824e+01 3.82959595e+01 3.82484207e+01 3.82388382e+01 3.81889763e+01 3.82063484e+01 3.81985855e+01 3.82225037e+01 3.81667023e+01 3.82085381e+01 3.80906792e+01 3.81136742e+01 3.81721077e+01 3.82475243e+01 3.82177620e+01 3.81284409e+01 3.81049652e+01 3.81110306e+01 3.81184311e+01 3.81278191e+01 3.81332207e+01 3.81415176e+01 3.81477051e+01 3.81505470e+01 3.81328735e+01 3.81217880e+01 3.81351700e+01 3.81468849e+01 3.81558609e+01 3.81275330e+01 3.81312141e+01 3.81240807e+01 3.80899315e+01 3.80720596e+01 3.81114845e+01 3.80796814e+01 3.80584908e+01 3.80082283e+01 3.80326004e+01 3.80832596e+01 3.80964813e+01 3.81106224e+01 3.82571068e+01 3.82607193e+01 3.82543297e+01 3.79959412e+01 3.80142059e+01 3.79465027e+01 3.80253220e+01 3.78004532e+01 3.77966042e+01 3.77694702e+01 3.79185257e+01 3.78798752e+01 3.77450562e+01 3.77684669e+01 3.77902489e+01 3.78790970e+01 3.77537956e+01 3.78066406e+01 3.77459297e+01 3.77703476e+01 3.80125351e+01 3.78833580e+01 3.78288574e+01 3.75799294e+01 3.75868874e+01 3.78259354e+01 3.77320518e+01 3.77296257e+01 3.76752930e+01 3.77868462e+01 3.77139091e+01 3.75668221e+01 3.73612823e+01 3.74679871e+01 3.75597267e+01 3.76309471e+01 3.75601234e+01 3.74092712e+01 3.78457870e+01 3.79054451e+01 3.82076950e+01 3.80007439e+01 3.79001274e+01 3.77232018e+01 3.73422623e+01 3.71814728e+01 3.70110321e+01 3.69901848e+01 3.70417023e+01 3.70681496e+01 3.67186966e+01 3.65223656e+01 3.64937553e+01 3.61391296e+01 3.66890297e+01 3.66338196e+01 3.69828339e+01 3.67108002e+01 3.70675850e+01 3.73051796e+01 3.69309044e+01 3.63522377e+01 3.63767090e+01 3.67382126e+01 3.68883247e+01 3.64906616e+01 3.61437035e+01 3.52617226e+01 3.55423965e+01 3.53111343e+01 3.62159805e+01 3.59925842e+01 3.63379669e+01 3.59690399e+01 3.60475502e+01 3.64736595e+01 3.73220253e+01 3.71721687e+01 3.63931923e+01 3.55330544e+01 3.52821198e+01 3.53222008e+01 3.51720772e+01 3.52010078e+01 3.56279182e+01 3.58706512e+01 3.59268303e+01 3.54890976e+01 3.52394028e+01 3.54004478e+01 3.54926262e+01 3.55064850e+01 3.50249634e+01 3.48520317e+01 3.47010689e+01 3.50919418e+01 3.49669266e+01 3.49759750e+01 3.43047333e+01 3.38630257e+01 3.40638771e+01 3.42157593e+01 3.43992577e+01 3.37914276e+01 3.38071327e+01 3.35642052e+01 3.43313637e+01 3.46759453e+01 3.49587326e+01 3.34746399e+01 3.27247772e+01 3.22905540e+01 3.33772316e+01 3.41423264e+01 3.39088020e+01 3.39571686e+01 3.29732513e+01 3.32716713e+01 3.43120384e+01 3.56079865e+01 3.56345901e+01 3.45179291e+01 3.37718277e+01 3.32392731e+01 3.31928329e+01 3.29971886e+01 3.28095093e+01 3.29679985e+01 3.32305756e+01 3.38512383e+01 3.36920395e+01 3.36719208e+01 3.23141251e+01 3.13024902e+01 3.09780998e+01 3.14535484e+01 3.22445488e+01 3.25712662e+01 3.25506134e+01 3.25716515e+01 3.31089134e+01 3.28621101e+01 3.25179672e+01 3.16824169e+01 3.24075813e+01 3.27198830e+01 3.26168633e+01 3.14767227e+01 3.14759235e+01 3.12726727e+01 3.15448055e+01 3.14017563e+01 3.16725349e+01 3.17235203e+01 3.22836761e+01 3.19015198e+01 3.15949974e+01 3.01930637e+01 2.87229176e+01 2.79795303e+01 2.84367752e+01 2.98282070e+01 3.01516571e+01 2.99992962e+01 3.00762844e+01 3.00949459e+01 2.97724724e+01 2.89798737e+01 2.88318462e+01 2.92948208e+01 3.01750851e+01 3.04787941e+01 3.02747841e+01 2.94220638e+01 2.91357574e+01 2.88310108e+01 2.91959209e+01 2.90716953e+01 2.88384609e+01 2.93656979e+01 3.01486473e+01 3.11951504e+01 3.12901173e+01 3.05478134e+01 2.96873856e+01 2.90364494e+01 2.85784092e+01 2.86398048e+01 2.88278923e+01 2.88264904e+01 2.89904804e+01 2.96632614e+01 3.00027771e+01 3.01275902e+01 2.92862816e+01 2.82385521e+01 2.78627052e+01 2.69991684e+01 2.73404083e+01 2.71564465e+01 2.76379871e+01 2.63167458e+01 2.45047779e+01 2.55477848e+01 2.87962456e+01 3.50669174e+01 3.56341438e+01 3.69849014e+01 3.51742477e+01 3.38260956e+01 4.51157227e+01 4.99135818e+01 4.24219971e+01 2.27659340e+01 4.77895050e+02 5.01916473e+02 -1.87108184e+04 -138219504. 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. 0. 0. 0. 0. 0. 0. 0. 81798760. 7.88300049e+03 1.44549255e+03 1.07394402e+02 3.22111397e+01 1.13723593e+01 9.08708420e+01 9.41955795e+01 4.26246719e+01 2.95304470e+01 2.52248859e+01 2.68242435e+01 2.58337173e+01 2.44755936e+01 2.18062649e+01 2.26072865e+01 2.28308010e+01 2.25913048e+01 2.17787266e+01 2.09876900e+01 2.01456604e+01 1.97436695e+01 1.93789196e+01 1.91835995e+01 2.01028557e+01 2.09146442e+01 2.04752750e+01 1.87079277e+01 1.80673351e+01 1.84616394e+01 1.93006191e+01 1.89943562e+01 1.73975849e+01 1.69308910e+01 1.64399414e+01 1.82811356e+01 1.84745064e+01 1.91302795e+01 1.84049702e+01 1.82773056e+01 1.80146751e+01 1.73988113e+01 1.69583588e+01 1.68197689e+01 1.71350479e+01 1.66618652e+01 1.59825106e+01 1.56793089e+01 1.56067677e+01 1.51624870e+01 1.53039799e+01 1.47747965e+01 1.48146257e+01 1.34784365e+01 1.42212124e+01 1.42597122e+01 1.49389267e+01 1.41343851e+01 1.42643528e+01 1.36217270e+01 1.39208879e+01 1.31333046e+01 1.53059349e+01 1.68722382e+01 1.79277687e+01 1.66282291e+01 1.52965555e+01 1.49875584e+01 1.55898972e+01 1.49749174e+01 1.53281450e+01 1.45804882e+01 1.39517355e+01 1.36486664e+01 1.26952848e+01 1.16599903e+01 9.16912556e+00 7.22321224e+00 7.78931761e+00 1.06571293e+01 1.27289972e+01 1.29977398e+01 1.18386316e+01 1.36661062e+01 1.47847195e+01 1.57234468e+01 1.45587673e+01 1.39900904e+01 1.30432968e+01 1.29855509e+01 1.31375790e+01 1.29238462e+01 1.35826225e+01 1.38160477e+01 1.36391096e+01 1.19589672e+01 1.06814909e+01 1.09896746e+01 1.09846210e+01 1.09534483e+01 1.06703005e+01 1.01110573e+01 9.05222416e+00 8.61145878e+00 8.35793495e+00 9.36802006e+00 9.52078438e+00 8.99598217e+00 9.66460609e+00 1.03514338e+01 1.20651503e+01 1.14327793e+01 9.77384281e+00 7.38749886e+00 6.68293428e+00 6.74077606e+00 7.56234312e+00 8.01338768e+00 8.05674648e+00 7.79487848e+00 7.08394718e+00 7.71166801e+00 7.44069195e+00 6.85619259e+00 5.92952919e+00 5.85758495e+00 6.46589518e+00 6.30028582e+00 7.81737232e+00 8.40098953e+00 8.84231853e+00 7.14109278e+00 5.64264250e+00 5.61976576e+00 5.95695066e+00 7.97645044e+00 9.13006306e+00 8.74421501e+00 6.73791790e+00 5.60979128e+00 4.68460560e+00 4.14809656e+00 3.30885649e+00 3.54505038e+00 3.37110662e+00 3.59563589e+00 3.33761525e+00 3.67541718e+00 3.57610655e+00 3.23211956e+00 2.66643953e+00 2.36434340e+00 2.53199697e+00 3.51573086e+00 5.06048298e+00 4.88984108e+00 4.59434128e+00 2.91744947e+00 4.54853392e+00 5.03328991e+00 5.04526377e+00 5.22136688e+00 5.38171625e+00 5.96049833e+00 4.53179502e+00 3.73702598e+00 2.38577056e+00 2.08534122e+00 1.07120824e+00 9.35910344e-01 1.45797288e+00 1.83403587e+00 2.40064597e+00 1.81426728e+00 2.05957103e+00 6.20800674e-01 -1.07926202e+00 -3.22218418e+00 -2.83463740e+00 -1.44727361e+00 -3.33585769e-01 -5.35946667e-01 -6.31109297e-01 -6.45336688e-01 -2.18957400e+00 -2.11224437e+00 -1.72662497e+00 -7.69496143e-01 -1.13181102e+00 -1.63277185e+00 -9.47118104e-01 -1.52270472e+00 -1.39493620e+00 -1.87290525e+00 -1.63366628e+00 -1.65525150e+00 -2.74425173e+00 -3.39936495e+00 -3.73175240e+00 -3.27997398e+00 -2.42343640e+00 -3.18542838e+00 -4.25594425e+00 -4.50889635e+00 -4.00124931e+00 -3.09162283e+00 -3.88706803e+00 -3.34873176e+00 -3.90681767e+00 -4.80301428e+00 -4.98075247e+00 -4.28719425e+00 -3.70457816e+00 -4.53517962e+00 -4.16299295e+00 -4.19183540e+00 -4.99330139e+00 -5.25235462e+00 -4.58317614e+00 -3.54896593e+00 -4.40847445e+00 -4.92821836e+00 -4.92403841e+00 -4.38408566e+00 -4.30915022e+00 -4.73510408e+00 -6.56495333e+00 -7.61324692e+00 -8.20683002e+00 -7.96368170e+00 -8.69667530e+00 -8.52938652e+00 -8.80538559e+00 -8.75903606e+00 -9.57379818e+00 -9.85767460e+00 -9.49651241e+00 -8.70956039e+00 -9.11489964e+00 -9.05331516e+00 -8.50465870e+00 -8.24797344e+00 -8.46630955e+00 -8.75142288e+00 -8.75411510e+00 -9.41660595e+00 -1.12394743e+01 -1.25830956e+01 -1.02642460e+01 -7.38082933e+00 -6.28342104e+00 -6.92861319e+00 -8.14507580e+00 -6.52039671e+00 -6.99972963e+00 -7.78147268e+00 -9.40266132e+00 -1.01936445e+01 -9.72950554e+00 -1.06693554e+01 -1.12975054e+01 -1.18633585e+01 -1.10797663e+01 -9.72331715e+00 -9.31653500e+00 -8.92559147e+00 -9.85096645e+00 -1.01625690e+01 -1.05553312e+01 -1.14400101e+01 -1.27116833e+01 -1.38481741e+01 -1.33088760e+01 -1.35604982e+01 -1.35685558e+01 -1.35145254e+01 -1.28674622e+01 -1.22253485e+01 -1.20338879e+01 -1.10862751e+01 -1.17544489e+01 -1.23751316e+01 -1.45870314e+01 -1.49303675e+01 -1.60479965e+01 -1.60614891e+01 -1.48136320e+01 -1.46334743e+01 -1.57619009e+01 -1.71763172e+01 -1.65152702e+01 -1.58507175e+01 -1.59001122e+01 -1.62370224e+01 -1.58185072e+01 -1.60508251e+01 -1.58832769e+01 -1.52765436e+01 -1.46459732e+01 -1.52293777e+01 -1.51168594e+01 -1.54039745e+01 -1.56076193e+01 -1.65844498e+01 -1.66550694e+01 -1.52333536e+01 -1.42097254e+01 -1.36487465e+01 -1.48863554e+01 -1.68407688e+01 -1.75262260e+01 -1.73484955e+01 -1.76579113e+01 -1.91275654e+01 -1.87111073e+01 -1.80360165e+01 -1.71677761e+01 -1.79126987e+01 -1.84276505e+01 -1.77360840e+01 -1.68684978e+01 -1.74591103e+01 -1.77524319e+01 -1.81797886e+01 -1.84352913e+01 -1.88470783e+01 -1.86095200e+01 -1.79095154e+01 -1.71770821e+01 -1.68223782e+01 -1.70962772e+01 -1.78428822e+01 -1.89475174e+01 -1.91197586e+01 -1.92762489e+01 -2.00551395e+01 -2.05711479e+01 -2.02975616e+01 -1.93929729e+01 -1.88630886e+01 -2.11237316e+01 -2.25878067e+01 -2.35716305e+01 -2.22495270e+01 -2.24040661e+01 -2.14721012e+01 -2.11789703e+01 -2.06047153e+01 -2.04569092e+01 -2.04038258e+01 -2.05833740e+01 -2.18106499e+01 -2.31840000e+01 -2.36227112e+01 -2.19221401e+01 -2.13082504e+01 -2.10222759e+01 -2.20031967e+01 -2.24990749e+01 -2.35036526e+01 -2.43181438e+01 -2.40606480e+01 -2.41693192e+01 -2.37858467e+01 -2.39600735e+01 -2.32888279e+01 -2.33369408e+01 -2.28953419e+01 -2.35737591e+01 -2.38136692e+01 -2.46110401e+01 -2.31177464e+01 -2.18353748e+01 -2.20788345e+01 -2.37509670e+01 -2.41729069e+01 -2.23585205e+01 -2.19861488e+01 -2.25011959e+01 -2.38011112e+01 -2.31556129e+01 -2.25964317e+01 -2.32726498e+01 -2.38547287e+01 -2.50264473e+01 -2.50690269e+01 -2.59561062e+01 -2.57512054e+01 -2.54434242e+01 -2.48918171e+01 -2.56612434e+01 -2.60044270e+01 -2.66763039e+01 -2.63765926e+01 -2.61370392e+01 -2.57139778e+01 -2.55365887e+01 -2.43290176e+01 -2.53586998e+01 -2.67987404e+01 -2.75151005e+01 -2.66323338e+01 -2.56987019e+01 -2.67949467e+01 -2.66272717e+01 -2.70507374e+01 -2.68532104e+01 -2.76652946e+01 -2.81718826e+01 -2.93135700e+01 -2.94763126e+01 -3.00118961e+01 -2.87334709e+01 -2.73914700e+01 -2.70600853e+01 -2.75082245e+01 -2.83713894e+01 -2.72409916e+01 -2.78058167e+01 -2.81526604e+01 -2.89678898e+01 -2.87079849e+01 -2.91689644e+01 -2.95096264e+01 -3.04711971e+01 -2.96832218e+01 -2.90701561e+01 -2.84580269e+01 -2.88709202e+01 -2.94740772e+01 -2.94075241e+01 -2.97035580e+01 -2.98131657e+01 -2.95910892e+01 -2.95453739e+01 -2.96671467e+01 -2.99696770e+01 -2.94104385e+01 -2.86754112e+01 -2.91575699e+01 -2.96416531e+01 -2.92118645e+01 -2.78470535e+01 -2.85787411e+01 -3.05780163e+01 -3.19374828e+01 -3.16795044e+01 -3.11360970e+01 -3.09828053e+01 -3.16224937e+01 -3.10397339e+01 -3.08734455e+01 -3.03806992e+01 -3.06922607e+01 -3.12320690e+01 -3.15691547e+01 -3.22664642e+01 -3.26829300e+01 -3.25735512e+01 -3.20615997e+01 -3.21534996e+01 -3.24386559e+01 -3.17223892e+01 -3.16518784e+01 -3.19281521e+01 -3.32093506e+01 -3.29464111e+01 -3.25546417e+01 -3.22198105e+01 -3.29619904e+01 -3.28933945e+01 -3.25928345e+01 -3.13087521e+01 -3.12217598e+01 -3.14365864e+01 -3.15183315e+01 -3.14869499e+01 -3.19731407e+01 -3.23938599e+01 -3.29332047e+01 -3.24688759e+01 -3.26980858e+01 -3.29259262e+01 -3.29555321e+01 -3.31185913e+01 -3.35537834e+01 -3.43196030e+01 -3.39562454e+01 -3.32805939e+01 -3.31095924e+01 -3.36423836e+01 -3.40011902e+01 -3.33698502e+01 -3.42282410e+01 -3.53629532e+01 -3.63976555e+01 -3.58746071e+01 -3.49100609e+01 -3.51323242e+01 -3.52087173e+01 -3.55343475e+01 -3.53591385e+01 -3.57072525e+01 -3.60799942e+01 -3.57587776e+01 -3.52827263e+01 -3.48957329e+01 -3.45912819e+01 -3.43568497e+01 -3.40302277e+01 -3.41686592e+01 -3.49492264e+01 -3.55616722e+01 -3.62150688e+01 -3.58838463e+01 -3.60513992e+01 -3.59481735e+01 -3.57401962e+01 -3.59958000e+01 -3.66943741e+01 -3.65337448e+01 -3.58400421e+01 -3.53316727e+01 -3.55842781e+01 -3.55640068e+01 -3.50174446e+01 -3.48943863e+01 -3.52067871e+01 -3.58218689e+01 -3.59618721e+01 -3.58198967e+01 -3.59717407e+01 -3.59011421e+01 -3.58962479e+01 -3.58737869e+01 -3.58104782e+01 -3.60003815e+01 -3.61737976e+01 -3.64353027e+01 -3.61287308e+01 -3.59582291e+01 -3.54552460e+01 -3.51624527e+01 -3.52159157e+01 -3.59336586e+01 -3.62429161e+01 -3.61850967e+01 -3.58454895e+01 -3.61325607e+01 -3.64559708e+01 -3.64053154e+01 -3.61860847e+01 -3.62700233e+01 -3.65719452e+01 -3.73752632e+01 -3.72896271e+01 -3.75139961e+01 -3.70991287e+01 -3.67358322e+01 -3.65367622e+01 -3.69821129e+01 -3.69048271e+01 -3.66267090e+01 -3.63793678e+01 -3.71139946e+01 -3.73396912e+01 -3.71576576e+01 -3.65466576e+01 -3.68123703e+01 -3.71957092e+01 -3.77802582e+01 -3.76573830e+01 -3.73923988e+01 -3.73742714e+01 -3.73260765e+01 -3.71697502e+01 -3.71162643e+01 -3.72085037e+01 -3.74106293e+01 -3.73448792e+01 -3.72681732e+01 -3.72376785e+01 -3.73207626e+01 -3.76304436e+01 -3.77995033e+01 -3.80142097e+01 -3.79930611e+01 -3.79560699e+01 -3.78866577e+01 -3.78576050e+01 -3.77308464e+01 -3.76779099e+01 -3.77703285e+01 -3.79991455e+01 -3.82425728e+01 -3.81656418e+01 -3.77055092e+01 -3.71402969e+01 -3.68891945e+01 -3.76429291e+01 -3.80439529e+01 -3.85459557e+01 -3.81220474e+01 -3.81141396e+01 -3.72953987e+01 -3.69790154e+01 -3.93899040e+01 -4.22436638e+01 -3.10573750e+01 2.97200751e+00 5.55083389e+01 -2.95024353e+02 6.20418050e+06 0. 0. 0. 0. 0. 28417318. 318329024. -1.58831619e+02 -1.32433182e+02 -9.10525970e+01 -163128064. 0. 0. -233982096. -233982096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 407427488. 727483392. -1.11670341e+02 -1.22102859e+02 -1.13190765e+02 -6.22863770e+01 -6.52985458e+01 -7.13521042e+01 -7.04735413e+01 -6.35803871e+01 -5.98219261e+01 -5.75046883e+01 -5.82119293e+01 -6.16460495e+01 -6.29482117e+01 -6.30428085e+01 -6.28630600e+01 -6.33619804e+01 -6.28860626e+01 -6.03378372e+01 -5.90849533e+01 -6.04690094e+01 -6.49001617e+01 -6.92108994e+01 -6.87193298e+01 -6.75845947e+01 -6.61987534e+01 -6.39278336e+01 -6.37485847e+01 -6.35305099e+01 -6.61222534e+01 -6.84708405e+01 -7.04740143e+01 -6.97891846e+01 -6.40734940e+01 -5.90372047e+01 -5.58260498e+01 -5.39711609e+01 -5.58599358e+01 -5.62066345e+01 -5.73288269e+01 -6.29640961e+01 -6.70470352e+01 -6.68926849e+01 -5.99266205e+01 -5.33980026e+01 -5.08625984e+01 -5.44622726e+01 -6.22742119e+01 -6.54133072e+01 -6.51295242e+01 -6.21224289e+01 -5.82680817e+01 -5.67271309e+01 -5.42073517e+01 -5.39507332e+01 -5.70017624e+01 -6.25430908e+01 -6.50768738e+01 -5.87886276e+01 -5.38039093e+01 -5.21907921e+01 -5.40338135e+01 -5.80571785e+01 -5.75171051e+01 -5.72907600e+01 -6.20504951e+01 -6.89468842e+01 -6.95710373e+01 -5.96959953e+01 -5.08469849e+01 -4.95845604e+01 -5.65374413e+01 -6.70585327e+01 -6.66332855e+01 -6.29092865e+01 -5.99033356e+01 -5.78537292e+01 -5.35894966e+01 -4.85310097e+01 -4.52841949e+01 -5.05572433e+01 -6.16968536e+01 -7.42674026e+01 -7.17831726e+01 -6.59155197e+01 -6.01161156e+01 -5.57441444e+01 -5.30025787e+01 -5.15516739e+01 -5.81983643e+01 -6.66916504e+01 -7.45732727e+01 -7.21657715e+01 -5.97169342e+01 -4.66437340e+01 -3.81117477e+01 -3.65416641e+01 -4.53071251e+01 -5.04107742e+01 -5.63021889e+01 -6.53184433e+01 -7.29697495e+01 -7.11580963e+01 -5.94018669e+01 -4.97106476e+01 -5.09324036e+01 -6.08753319e+01 -7.10371017e+01 -7.13408661e+01 -6.84043732e+01 -6.81042404e+01 -6.48013687e+01 -6.17785072e+01 -5.68214340e+01 -5.28099594e+01 -5.36250000e+01 -5.97652283e+01 -6.38769379e+01 -5.88635750e+01 -4.85289688e+01 -4.19805374e+01 -4.53532867e+01 -6.22387009e+01 -7.58397446e+01 -6.94002762e+01 -6.42833710e+01 -6.80410461e+01 -7.37314148e+01 -6.13934364e+01 -4.48950844e+01 -3.89863319e+01 -5.14725990e+01 -6.88230972e+01 -7.61507874e+01 -6.90262451e+01 -5.95627556e+01 -5.32459641e+01 -4.82309761e+01 -5.15374260e+01 -5.23502884e+01 -5.58353577e+01 -6.46756287e+01 -7.38370895e+01 -7.48609085e+01 -6.70689850e+01 -5.61009369e+01 -4.94043312e+01 -5.29202461e+01 -6.57784042e+01 -7.09939728e+01 -6.93186798e+01 -6.79237442e+01 -7.00103378e+01 -6.52742081e+01 -5.33430443e+01 -3.67887955e+01 -3.47039680e+01 -4.54101982e+01 -5.31459694e+01 -5.11239777e+01 -5.05247421e+01 -5.75872879e+01 -5.59002342e+01 -5.23968086e+01 -4.29096489e+01 -4.69216881e+01 -5.53455887e+01 -6.54050674e+01 -6.02023163e+01 -4.42093887e+01 -2.92085609e+01 -2.21360931e+01 -2.54184723e+01 -3.74745331e+01 -4.14807243e+01 -4.00247459e+01 -4.68012199e+01 -4.17306786e+01 -3.15104504e+01 -1.48850775e+01 -5.70054007e+00 -7.56870317e+00 -2.50978203e+01 -5.35617218e+01 -6.18909340e+01 -6.51558990e+01 -6.61504288e+01 -6.77909393e+01 -6.09403534e+01 -4.54376640e+01 -3.84670525e+01 -4.75398331e+01 -6.48482132e+01 -6.55430603e+01 -4.92909050e+01 -3.61540718e+01 -2.91365833e+01 -1.81101360e+01 -1.81333351e+01 -1.99631844e+01 -3.22744980e+01 -4.04243584e+01 -3.89448433e+01 -3.38916321e+01 -1.81982670e+01 -8.62761974e+00 -4.27373934e+00 -2.24540653e+01 -5.23372307e+01 -6.26752014e+01 -5.73211098e+01 -4.96337280e+01 -4.70702095e+01 -4.40307350e+01 -3.12229710e+01 -2.52234573e+01 -4.30580177e+01 -6.34903488e+01 -7.13388748e+01 -5.63627434e+01 -3.99184456e+01 -3.31678009e+01 -3.17532387e+01 -3.79827919e+01 -3.58740501e+01 -2.78849506e+01 -3.76778908e+01 -4.74727097e+01 -4.62918854e+01 -3.15443783e+01 -1.91421185e+01 -1.83041134e+01 -2.80541039e+01 -4.49901619e+01 -5.63821983e+01 -5.57217979e+01 -5.53585663e+01 -5.41509743e+01 -5.06616325e+01 -3.16789570e+01 -1.97825356e+01 -1.86508846e+01 -2.57318897e+01 -4.10146675e+01 -4.72700806e+01 -5.87856598e+01 -5.77749710e+01 -3.79444046e+01 -3.50539322e+01 -3.76872902e+01 -4.97552299e+01 -5.47088089e+01 -5.63963509e+01 -6.40716476e+01 -3.84703636e+01 -1.11051226e+01 -3.58461916e-01 -2.33305893e+01 -3.94336166e+01 -4.13570251e+01 -3.59833908e+01 -5.15868416e+01 -5.77978859e+01 -4.44197998e+01 -2.12787628e+01 -1.45912399e+01 -3.84684639e+01 -4.10497208e+01 -4.32808228e+01 -4.42072678e+01 -5.68959122e+01 -4.94774895e+01 -3.03498878e+01 -2.06846123e+01 -1.29974089e+01 -4.18909788e+00 4.17767143e+00 -1.70126476e+01 -4.20400620e+01 -4.07838707e+01 -8.42070198e+00 -1.09743583e+00 -1.59174290e+01 -2.07654419e+01 -8.60159111e+00 -4.48926258e+00 -2.88793488e+01 -3.12535973e+01 -1.92579384e+01 -4.72108459e+00 -9.95920658e+00 -3.10428753e+01 -3.02813568e+01 -4.22720604e+01 -5.30938759e+01 -6.42210007e+01 -4.29112663e+01 -2.64285698e+01 -2.71014442e+01 -3.05367603e+01 -3.02616196e+01 -2.50594120e+01 -4.03645859e+01 -5.57467499e+01 -5.27566147e+01 -2.30991344e+01 -4.20581627e+00 -1.15996447e+01 -2.22703018e+01 -1.32753391e+01 1.03132558e+00 -7.84224081e+00 -1.61678810e+01 -2.37243290e+01 -1.95508213e+01 -3.28333054e+01 -4.59124870e+01 -4.07485771e+01 -3.71776123e+01 -3.89807472e+01 -4.72106667e+01 -4.46784630e+01 -4.15712051e+01 -4.19156265e+01 -2.57403431e+01 -8.92456245e+00 1.13297307e+00 -1.70906487e+01 -3.51947365e+01 -3.13457947e+01 -6.49916697e+00 -4.08435535e+00 -1.63477974e+01 -2.23784599e+01 -3.66207838e+00 -1.11557317e+00 -2.82118568e+01 -4.33727379e+01 -5.60866241e+01 -5.68851929e+01 -6.83259506e+01 -6.25832291e+01 -4.29091949e+01 -4.23981743e+01 -5.29316635e+01 -5.99923363e+01 -3.57920532e+01 -1.69610043e+01 -1.77911110e+01 -5.76662159e+00 1.58150434e+01 3.26174850e+01 1.84818001e+01 2.08870173e+00 -1.67389750e+00 -1.52400389e-01 -1.21554251e+01 -1.55005941e+01 -1.34946012e+01 2.18202472e+00 -6.08621264e+00 -3.08351116e+01 -4.58371239e+01 -5.56493301e+01 -5.34857330e+01 -6.10142059e+01 -4.93684158e+01 -2.22702389e+01 -1.75387306e+01 -2.40423584e+01 -4.01231346e+01 -2.52408218e+01 -1.37683954e+01 -2.97178516e+01 -2.39607315e+01 2.25209332e+00 3.82819633e+01 4.47620888e+01 1.74354172e+01 3.92176366e+00 6.05886078e+00 1.21791210e+01 2.46227322e+01 8.89149475e+00 6.95469713e+00 -3.52676940e+00 -2.26892304e+00 2.68575726e+01 2.20225143e+01 7.27650785e+00 -3.53549690e+01 -3.50011520e+01 1.20317659e+01 2.35199432e+01 9.55455399e+00 -3.60279388e+01 -3.57406197e+01 8.56607056e+00 3.52367134e+01 4.92879715e+01 3.58312798e+01 2.45505009e+01 1.46412134e+01 -1.49018784e+01 -1.66839504e+01 6.72592354e+00 3.24886665e+01 3.38538895e+01 -2.22339082e+00 -2.66016369e+01 -4.10500298e+01 -3.07552605e+01 6.85438633e+00 1.84601231e+01 2.35269523e+00 -3.71921616e+01 -3.35652237e+01 1.26772213e+01 5.40899811e+01 6.96925125e+01 3.33453026e+01 -6.01210117e+00 -1.81718731e+01 -2.07822094e+01 -5.23225975e+00 7.62844801e+00 2.21093655e+01 3.97204704e+01 3.10025673e+01 1.81217461e+01 1.07149124e+00 8.77457917e-01 1.29287930e+01 -8.61566365e-01 -8.56664658e+00 -7.90371561e+00 2.50143886e+00 3.14974594e+01 2.95869923e+01 2.07382526e+01 -1.87419128e+01 -3.33729897e+01 -2.17395363e+01 -1.07213125e+01 1.86005747e+00 -4.41097856e-01 1.22155466e+01 3.94764557e+01 3.83929710e+01 2.03784962e+01 1.05187445e+01 1.10168829e+01 2.05359917e+01 -3.20178151e+00 -1.49631548e+01 -1.91948719e+01 5.90710938e-01 2.63899078e+01 1.47369223e+01 -7.48017931e+00 -2.51948357e+01 -2.24651337e+01 5.23185205e+00 1.38436699e+01 1.30256729e+01 -8.39295387e+00 -1.38020811e+01 1.15172958e+01 2.62207470e+01 3.96708145e+01 3.06836472e+01 2.33863792e+01 1.55400848e+01 3.05175614e+00 -1.74626005e+00 7.68483496e+00 1.85623798e+01 3.26874313e+01 2.53450947e+01 1.41118412e+01 -7.51670790e+00 -1.47504549e+01 1.25852623e+01 1.37286997e+01 1.76342621e+01 7.49472666e+00 4.34797907e+00 1.34150515e+01 1.95066795e+01 3.94988594e+01 1.78754463e+01 -4.33286285e+00 -9.63547230e+00 -3.44222188e-01 1.78810196e+01 2.99179382e+01 3.29204216e+01 2.87800827e+01 1.07467318e+01 8.91832161e+00 1.63365211e+01 2.77110500e+01 3.50478706e+01 1.41553736e+01 -2.35705256e+00 -1.99492912e+01 -1.16293173e+01 9.96540833e+00 1.13775702e+01 5.45766735e+00 -9.95807266e+00 -1.25418625e+01 7.86938667e+00 1.25965042e+01 1.81296501e+01 1.86282501e-01 -6.97833729e+00 1.58767920e+01 1.38598995e+01 1.76218567e+01 2.12982273e+01 3.36517754e+01 3.61146431e+01 4.17041016e+00 -1.27484493e+01 -4.58563471e+00 1.74570789e+01 3.29691391e+01 1.64079304e+01 -4.37447166e+00 -1.50033884e+01 -1.87139778e+01 4.10316801e+00 1.80178432e+01 2.25195370e+01 7.31462908e+00 -6.30050421e+00 2.07054176e+01 4.21714020e+01 6.44637909e+01 5.17182808e+01 2.50931587e+01 1.34913387e+01 2.12462366e-01 1.44129839e+01 3.03927555e+01 4.31292725e+01 3.70536003e+01 9.02208138e+00 -8.61651993e+00 -3.06717396e+00 8.10049915e+00 2.18436394e+01 1.20375223e+01 2.56354904e+00 -8.11413383e+00 -2.44595647e+00 2.67730789e+01 3.82988853e+01 3.10421066e+01 2.25207281e+00 -8.23701477e+00 1.08801353e+00 1.15569706e+01 2.71550789e+01 2.45320110e+01 1.83089256e+01 1.07379665e+01 9.82237530e+00 1.96996040e+01 2.85030689e+01 3.36590767e+01 2.82431793e+01 8.77036953e+00 -3.59214091e+00 -4.84299183e+00 1.55869274e+01 3.68246918e+01 2.87856464e+01 1.29618397e+01 -1.59883022e+00 5.52650642e+00 3.51118164e+01 4.32088051e+01 3.60281563e+01 7.83720827e+00 -4.57041121e+00 1.95999527e+01 3.79335518e+01 5.06348114e+01 3.28867683e+01 1.43603411e+01 2.00759964e+01 2.15018559e+01 3.14847946e+01 3.15827961e+01 3.08953609e+01 3.33193893e+01 1.91743984e+01 2.12637062e+01 1.44187098e+01 2.13318844e+01 3.65770111e+01 3.20461617e+01 2.49898453e+01 7.26167440e-01 1.16218166e+01 4.02431221e+01 5.53933525e+01 4.76326675e+01 2.01269627e+01 1.71680183e+01 3.54330826e+01 3.88414154e+01 5.44850693e+01 4.74491806e+01 3.02808323e+01 1.80934830e+01 3.64242592e+01 7.67127914e+01 -1.37503528e+03 -4.22304443e+03 46472784. -264798400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -358400512. 51028948. -294265280. 54792452. -5.93773527e+10 3.50984802e+02 1.28295578e+02 3.00364456e+01 4.73357086e+01 4.46813927e+01 2.76356487e+01 2.77472343e+01 2.50898514e+01 2.97826900e+01 5.21211853e+01 6.09385529e+01 5.44361916e+01 2.78380108e+01 2.13123627e+01 4.06715240e+01 5.52807350e+01 6.30582008e+01 4.86654358e+01 3.25295105e+01 3.07216492e+01 3.32415619e+01 5.03997726e+01 6.03441887e+01 6.25133247e+01 5.44832878e+01 4.72301216e+01 4.66367340e+01 4.56231079e+01 4.50573044e+01 4.61754379e+01 3.94317322e+01 3.16191082e+01 2.62855606e+01 3.60556526e+01 5.88466415e+01 6.63497620e+01 6.07372131e+01 3.95899811e+01 3.33264503e+01 3.84328537e+01 4.33399658e+01 4.98683014e+01 4.52043343e+01 4.18464546e+01 4.49515953e+01 4.93564034e+01 5.87454376e+01 6.40821381e+01 6.57883606e+01 6.26071854e+01 4.68283424e+01 4.15279846e+01 4.04451180e+01 5.49189072e+01 6.80023880e+01 6.15588684e+01 4.68397980e+01 3.26693420e+01 3.37988281e+01 5.02615051e+01 5.99780693e+01 6.20605392e+01 4.71080017e+01 3.65640717e+01 4.16251640e+01 4.75984421e+01 5.69125633e+01 4.88019638e+01 4.09166260e+01 4.17145195e+01 5.01142464e+01 6.84840927e+01 7.57491379e+01 7.58232040e+01 6.68686523e+01 5.86620598e+01 6.08556900e+01 5.75970612e+01 5.68090897e+01 6.15947647e+01 6.09666138e+01 5.55994873e+01 4.72745056e+01 5.40041199e+01 7.28947067e+01 7.60343552e+01 6.84119186e+01 4.88844414e+01 4.28390884e+01 4.81967163e+01 5.03686790e+01 5.96692772e+01 5.87536278e+01 5.54872513e+01 5.12061920e+01 4.99495583e+01 6.02379379e+01 6.58490524e+01 6.55836411e+01 6.15804443e+01 5.26270065e+01 5.02238235e+01 4.70685959e+01 4.97286072e+01 5.85976410e+01 5.74931526e+01 5.40351028e+01 4.57561111e+01 4.54231224e+01 5.35887184e+01 5.83527565e+01 5.91573830e+01 5.09166603e+01 4.60609398e+01 5.11164780e+01 5.51503258e+01 6.38930168e+01 6.84632721e+01 6.78852234e+01 6.30413475e+01 5.48980141e+01 5.47181587e+01 6.12562103e+01 6.53478470e+01 6.70079803e+01 5.81934090e+01 5.33971710e+01 5.03177795e+01 5.25950089e+01 6.48553619e+01 6.81759262e+01 6.66311722e+01 5.57558098e+01 5.17993813e+01 5.77822418e+01 6.09218826e+01 6.06270599e+01 5.42163544e+01 4.84019852e+01 5.19808769e+01 5.49038544e+01 6.05547523e+01 5.83765411e+01 5.40895309e+01 5.34042473e+01 5.24350052e+01 5.38682823e+01 5.54336357e+01 5.82472992e+01 6.03455162e+01 5.62885361e+01 5.30941315e+01 5.19258957e+01 5.53505783e+01 6.03253860e+01 6.05675125e+01 5.92594452e+01 5.68924828e+01 5.70588875e+01 6.16379967e+01 6.44515381e+01 6.53636780e+01 6.27845573e+01 6.18322411e+01 6.34496880e+01 6.28575172e+01 6.42783127e+01 6.55452347e+01 6.57829514e+01 6.42815933e+01 6.26833076e+01 6.23122063e+01 6.19853287e+01 6.21983490e+01 6.25099258e+01 6.11956291e+01 5.89016571e+01 5.67957230e+01 5.66207314e+01 5.95632591e+01 6.18791275e+01 6.17953224e+01 5.93316498e+01 5.70312042e+01 5.83993416e+01 5.97588425e+01 6.24467201e+01 6.17858658e+01 6.07489662e+01 6.05609474e+01 6.07474594e+01 6.18085289e+01 6.30609703e+01 6.41312103e+01 6.42667542e+01 6.31288719e+01 6.29448013e+01 6.34666595e+01 6.44251785e+01 6.49916687e+01 6.34937248e+01 6.19828072e+01 6.10200081e+01 6.13106003e+01 6.26450424e+01 6.33060570e+01 6.33845367e+01 6.24800415e+01 6.23363457e+01 6.29632378e+01 6.32438889e+01 6.33795052e+01 6.31698875e+01 6.31425972e+01 6.33546906e+01 6.35609207e+01 6.38140373e+01 6.38704948e+01 6.37675858e+01 6.36327438e+01 6.36133461e+01 6.37013588e+01 6.39618187e+01 6.39158401e+01 6.32366219e+01 6.25235329e+01 6.24383774e+01 6.31550713e+01 6.35951843e+01 6.32754745e+01 6.36355171e+01 6.41815720e+01 6.44525986e+01 6.41933441e+01 6.33947449e+01 6.31470833e+01 6.29689369e+01 6.32247086e+01 6.36126938e+01 6.32423820e+01 6.25933151e+01 6.20654678e+01 6.23270073e+01 6.29352989e+01 6.30950165e+01 6.32855911e+01 6.30000725e+01 6.39351234e+01 6.49447556e+01 6.54357452e+01 6.45298538e+01 6.32618942e+01 6.35220604e+01 6.41644058e+01 6.43923340e+01 6.41619797e+01 6.39013329e+01 6.41691742e+01 6.45382690e+01 6.43126678e+01 6.40148087e+01 6.28563614e+01 6.24276695e+01 6.28755112e+01 6.31895485e+01 6.38393059e+01 6.29338875e+01 6.30047569e+01 6.23985100e+01 6.34619789e+01 6.36367836e+01 6.39375191e+01 6.28885078e+01 6.24312630e+01 6.28787117e+01 6.37850342e+01 6.36812401e+01 6.23864746e+01 6.05603371e+01 6.07668610e+01 6.00489235e+01 5.97652130e+01 5.98803406e+01 6.16739502e+01 6.30903358e+01 6.29178123e+01 6.31033821e+01 6.29946823e+01 6.29342079e+01 6.13069725e+01 6.12063217e+01 6.19712982e+01 6.35010109e+01 6.26696129e+01 6.29703064e+01 6.22442856e+01 6.31334114e+01 6.24701118e+01 6.21486549e+01 6.24177475e+01 6.21209335e+01 6.27157974e+01 6.23149529e+01 6.10717163e+01 5.88006668e+01 5.78877754e+01 5.91021118e+01 6.19127769e+01 6.24032631e+01 6.32059326e+01 6.11664696e+01 6.00722466e+01 5.88550034e+01 6.04158249e+01 6.35263596e+01 6.43059769e+01 6.24901848e+01 6.20122719e+01 6.28368073e+01 6.40135193e+01 6.28918266e+01 6.16308861e+01 6.15066566e+01 5.97258568e+01 5.86630821e+01 5.74017372e+01 5.74262276e+01 5.74308052e+01 5.75258560e+01 5.91197128e+01 5.87697220e+01 5.87037201e+01 5.85134697e+01 5.89133301e+01 5.77503319e+01 5.48718948e+01 5.60676689e+01 5.91601830e+01 6.10438080e+01 6.08791313e+01 5.82096329e+01 5.76973534e+01 5.69582901e+01 5.86718025e+01 5.93557701e+01 5.89995079e+01 5.66937523e+01 5.28583336e+01 4.88051033e+01 4.67867851e+01 4.57909584e+01 4.88206482e+01 5.19380684e+01 5.73628883e+01 5.93678627e+01 5.76692734e+01 5.58811760e+01 5.38865700e+01 4.94544792e+01 4.38191566e+01 4.65323601e+01 5.16408920e+01 5.61867485e+01 5.27830086e+01 4.84380379e+01 4.56490822e+01 4.94417191e+01 5.55872002e+01 5.89190865e+01 5.28990707e+01 4.48818703e+01 4.30681572e+01 4.77915573e+01 5.56733437e+01 5.62926750e+01 5.45674248e+01 5.21609306e+01 5.16896706e+01 5.26789055e+01 5.41341591e+01 4.97928467e+01 4.35613480e+01 4.48123589e+01 4.97976952e+01 5.42589531e+01 5.33175964e+01 5.35061951e+01 5.46004105e+01 5.49009476e+01 5.53563843e+01 5.12216072e+01 4.61148529e+01 4.59151840e+01 4.89252052e+01 5.30408211e+01 5.10572777e+01 5.04166832e+01 5.29840126e+01 5.71402321e+01 6.56135101e+01 7.09518051e+01 6.43689728e+01 5.52953529e+01 4.91322403e+01 5.13624916e+01 5.36771812e+01 5.45660286e+01 5.76857567e+01 5.76766129e+01 5.64962921e+01 5.42107201e+01 5.23608780e+01 5.18906212e+01 5.36439247e+01 5.41433716e+01 5.54140968e+01 5.41350441e+01 5.47344246e+01 5.34659958e+01 5.15593834e+01 4.61003761e+01 4.27592850e+01 4.50267982e+01 5.38105469e+01 6.05776863e+01 6.21986351e+01 5.73488960e+01 4.72313118e+01 4.33706741e+01 4.58211060e+01 4.85292130e+01 4.97026749e+01 4.70218849e+01 5.43487282e+01 6.25019417e+01 6.42669373e+01 5.63363838e+01 4.80165024e+01 4.73052368e+01 5.24020309e+01 5.64357300e+01 5.63694725e+01 5.30623322e+01 4.57346954e+01 4.65051727e+01 4.60588150e+01 4.72850533e+01 4.54010048e+01 5.05549660e+01 5.72089462e+01 5.83016052e+01 5.28756676e+01 4.67467308e+01 1.90494556e+01 2.36423378e+01 4.96879730e+01 1.37204834e+03 1.10407295e+04 -353220768. 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. 0. 0. 0. 0. 0. 0. 0. 119250520. -71518888. -17341892. -55024388. 1.02433662e+04 -7.76585266e+02 -9.05373291e+02 -7.68064041e+01 -1.94594421e+01 2.68733368e+01 1.50523539e+01 1.89152660e+01 1.90609207e+01 1.93373394e+01 1.77290478e+01 1.91154308e+01 2.18213520e+01 2.41349144e+01 3.33213463e+01 4.16737862e+01 3.70503922e+01 2.67592869e+01 2.36218357e+01 3.12679749e+01 3.82105103e+01 3.95050507e+01 4.43610954e+01 4.84949150e+01 5.51785583e+01 5.62390785e+01 5.34778709e+01 4.81088066e+01 4.54406281e+01 4.71479568e+01 4.75356560e+01 4.74424820e+01 3.68819656e+01 2.33155746e+01 2.04264927e+01 2.21370354e+01 2.72603550e+01 2.35991096e+01 2.45910053e+01 2.84693203e+01 2.87103157e+01 2.96273880e+01 2.33680801e+01 2.61551075e+01 3.00395813e+01 3.57704697e+01 3.03238697e+01 2.30098972e+01 1.98195992e+01 2.54512863e+01 2.64901390e+01 2.40915565e+01 1.81553860e+01 1.44716454e+01 1.32312145e+01 1.58392096e+01 2.59955807e+01 2.52669659e+01 1.89991398e+01 1.02738295e+01 6.44015646e+00 4.68248415e+00 2.81391811e+00 3.37607741e+00 6.58488989e+00 5.42926884e+00 8.81946659e+00 1.03082113e+01 1.31054945e+01 1.63060760e+01 1.74875565e+01 3.49258804e+01 5.02998276e+01 5.14435043e+01 3.72423897e+01 2.12785721e+01 2.13735065e+01 2.03501453e+01 1.00471945e+01 -2.46866083e+00 -1.70012875e+01 -2.34589367e+01 -1.33729420e+01 -3.74915689e-01 1.43676500e+01 1.12988997e+01 7.56088352e+00 5.20563507e+00 7.98456001e+00 1.06827183e+01 1.39110832e+01 1.32650356e+01 1.28620234e+01 1.30811729e+01 1.68387337e+01 1.58899488e+01 2.18417854e+01 2.25696163e+01 2.68724670e+01 2.49271832e+01 2.79780102e+01 2.98571377e+01 2.45737762e+01 8.96842861e+00 -5.83122206e+00 -1.28548679e+01 -1.53627291e+01 1.24434434e-01 1.34147720e+01 3.42679024e+01 3.21586037e+01 2.56210575e+01 2.58893948e+01 3.27152748e+01 3.84135857e+01 3.17042313e+01 2.03778172e+01 1.55523758e+01 9.29733372e+00 5.87187433e+00 -1.14206052e+00 -3.99413252e+00 -5.59067106e+00 -3.10750294e+00 -1.11810005e+00 2.94835325e-02 4.41368192e-01 1.18248796e+00 -1.18872185e+01 -2.52621460e+01 -3.97348480e+01 -4.03085403e+01 -2.92046204e+01 -1.68269920e+01 1.33038771e+00 5.58169603e+00 6.52350092e+00 6.72330952e+00 8.32732677e+00 1.16225662e+01 1.41106501e+01 1.04050589e+01 7.86025381e+00 8.43206978e+00 1.23008652e+01 1.20120611e+01 1.19570704e+01 6.46237612e+00 -7.66236496e+00 -2.90826626e+01 -2.90387077e+01 -1.73807888e+01 -1.34438944e+00 -1.62703819e+01 -3.26305466e+01 -4.78404922e+01 -4.35010262e+01 -2.68735065e+01 -1.52774811e+01 -3.37960577e+00 -1.73241007e+00 4.43242168e+00 5.88884974e+00 6.29908991e+00 6.59740400e+00 3.65602326e+00 3.54408336e+00 2.63378978e+00 3.75488782e+00 1.03754425e+00 -8.05849493e-01 3.95035148e+00 7.60426760e+00 -3.26119637e+00 -1.88719959e+01 -2.21275368e+01 -1.29921885e+01 -2.24220395e+00 -4.33213025e-01 6.79079056e+00 -4.80980873e+00 -1.95564690e+01 -2.52701492e+01 -1.38925028e+01 -3.49582219e+00 -8.95253086e+00 -8.15390110e+00 -7.16870928e+00 -5.49620008e+00 -1.05762663e+01 -1.21047945e+01 -7.23456860e+00 -5.13333464e+00 -4.04126120e+00 -6.09127140e+00 -9.46508312e+00 -1.25179863e+01 -1.58924170e+01 -2.40988846e+01 -3.13100605e+01 -3.90122948e+01 -3.48098984e+01 -2.57732048e+01 -1.71855659e+01 -6.52328873e+00 -4.43186045e+00 -3.17440772e+00 -4.11093044e+00 -5.55349064e+00 -5.03503561e+00 -5.06532907e+00 -2.48111653e+00 -7.02308714e-01 -2.83130527e+00 -3.64581561e+00 -4.72981977e+00 9.30018711e+00 2.03706646e+01 1.48438587e+01 1.20303762e+00 -9.68214321e+00 -6.36150026e+00 -5.49741554e+00 -1.59423723e+01 -2.92421455e+01 -3.20941391e+01 -2.31385956e+01 -1.02059698e+01 -1.20466423e+01 -1.30671005e+01 -1.58323851e+01 -1.53081989e+01 -1.64775066e+01 -1.56350527e+01 -1.61281414e+01 -1.64810104e+01 -1.72645817e+01 -1.97916832e+01 -2.17945919e+01 -2.15875893e+01 -2.03868084e+01 -2.81676674e+01 -4.43820610e+01 -5.05194168e+01 -4.50662804e+01 -3.13172264e+01 -2.32308636e+01 -2.44481411e+01 -3.80849991e+01 -5.26301575e+01 -4.74612541e+01 -3.22474289e+01 -1.78526840e+01 -1.59411154e+01 -1.38768806e+01 -1.66552105e+01 -1.80968819e+01 -7.99066114e+00 8.44748783e+00 1.03169613e+01 -1.63305497e+00 -1.72965870e+01 -1.65111389e+01 -1.50174503e+01 -1.49238014e+01 -1.91673317e+01 -2.92092896e+01 -3.86407738e+01 -3.96877518e+01 -3.27933693e+01 -2.35190735e+01 -2.32844181e+01 -2.20119991e+01 -3.14453716e+01 -4.06676636e+01 -3.73157768e+01 -2.74302731e+01 -1.26292362e+01 -1.26034460e+01 -1.00391521e+01 -1.45436411e+01 -1.89031944e+01 -2.13389091e+01 -2.13874302e+01 -2.04787045e+01 -2.03073540e+01 -1.90305080e+01 -1.88127327e+01 -1.91667271e+01 -2.23139477e+01 -2.84208527e+01 -4.38918915e+01 -5.73902016e+01 -6.37016449e+01 -5.91898270e+01 -4.17556763e+01 -2.91088200e+01 -1.93408966e+01 -2.22196369e+01 -2.59169750e+01 -2.72866211e+01 -3.01949692e+01 -2.92600536e+01 -2.88494530e+01 -2.46767349e+01 -2.61831207e+01 -2.53925934e+01 -2.69116249e+01 -2.68773327e+01 -3.07702103e+01 -3.17145634e+01 -2.98042450e+01 -2.98371773e+01 -2.82408218e+01 -2.84821625e+01 -2.58273773e+01 -2.42762794e+01 -2.33294621e+01 -3.13017921e+01 -3.90069847e+01 -4.08870506e+01 -4.52639122e+01 -5.35120659e+01 -6.48112183e+01 -6.48290863e+01 -5.95596466e+01 -6.00363808e+01 -5.59964561e+01 -5.91463242e+01 -5.19657936e+01 -4.43262520e+01 -3.55966415e+01 -4.36180267e+01 -5.74469604e+01 -5.51861229e+01 -4.77407684e+01 -3.84271507e+01 -4.06616631e+01 -4.06541595e+01 -3.92804413e+01 -3.69262161e+01 -3.82252998e+01 -4.16794815e+01 -5.46767883e+01 -6.46369247e+01 -6.04646606e+01 -5.13874893e+01 -3.95980377e+01 -4.84337158e+01 -5.22080765e+01 -5.66148262e+01 -5.89064789e+01 -6.45815659e+01 -7.43783569e+01 -6.51207809e+01 -5.25872231e+01 -3.92979736e+01 -3.43562698e+01 -3.02586517e+01 -3.22043037e+01 -3.70683060e+01 -5.25904236e+01 -6.18354683e+01 -7.48539429e+01 -7.84606781e+01 -7.05796661e+01 -7.02087631e+01 -6.97921143e+01 -7.01710663e+01 -5.93381386e+01 -4.64505272e+01 -4.39775620e+01 -4.53858795e+01 -4.81898613e+01 -4.83345337e+01 -5.58386688e+01 -6.14825439e+01 -6.16891823e+01 -5.16724319e+01 -4.01435432e+01 -3.93094215e+01 -4.02134972e+01 -4.35270805e+01 -4.36863365e+01 -4.12086754e+01 -3.64078217e+01 -3.55389748e+01 -3.65213165e+01 -4.67512131e+01 -5.60363426e+01 -5.92435799e+01 -5.46366692e+01 -5.10550499e+01 -5.03546677e+01 -4.57915382e+01 -4.05358162e+01 -3.94538994e+01 -5.06453934e+01 -6.22406921e+01 -6.52418060e+01 -6.13222847e+01 -5.46947441e+01 -5.36983719e+01 -5.37496033e+01 -5.05691948e+01 -4.75621567e+01 -3.91978226e+01 -4.71967087e+01 -6.05128670e+01 -6.09582520e+01 -4.96908989e+01 -3.91860847e+01 -4.55996857e+01 -5.63007050e+01 -6.35585327e+01 -6.03173523e+01 -5.28677368e+01 -4.70358543e+01 -4.92266159e+01 -4.95115623e+01 -5.77673492e+01 -6.32993851e+01 -6.47109451e+01 -6.18339424e+01 -5.93437614e+01 -6.16257401e+01 -5.83087807e+01 -6.34220467e+01 -7.11284180e+01 -7.18972397e+01 -6.44433746e+01 -5.46646996e+01 -5.85384865e+01 -6.57191925e+01 -6.81611099e+01 -6.45195160e+01 -5.62351990e+01 -5.39151230e+01 -5.32288094e+01 -5.44548111e+01 -5.15734215e+01 -4.66151199e+01 -4.60721436e+01 -5.02393074e+01 -5.70065002e+01 -6.04086266e+01 -6.19930115e+01 -5.97053528e+01 -5.71902809e+01 -5.16657410e+01 -4.87442932e+01 -4.53793526e+01 -4.56734543e+01 -4.83631096e+01 -5.30274200e+01 -5.36143532e+01 -5.13208008e+01 -5.37321739e+01 -5.79011192e+01 -5.53308487e+01 -5.01244698e+01 -4.23200989e+01 -4.14940300e+01 -4.39079514e+01 -5.09409676e+01 -5.98184242e+01 -6.72358704e+01 -7.52556000e+01 -7.31665497e+01 -6.50028839e+01 -6.18969727e+01 -6.65953217e+01 -6.65463257e+01 -6.04593582e+01 -5.67548561e+01 -5.68982239e+01 -5.71338158e+01 -5.65249596e+01 -5.89064827e+01 -5.81956062e+01 -5.49476547e+01 -4.98196182e+01 -5.20489082e+01 -5.64976006e+01 -5.59301758e+01 -5.34430161e+01 -5.76357117e+01 -6.65385513e+01 -6.56461792e+01 -5.64379692e+01 -4.79156837e+01 -4.98132668e+01 -5.67906418e+01 -6.44696732e+01 -6.46873779e+01 -6.01453476e+01 -5.73601418e+01 -6.18558960e+01 -6.46825790e+01 -6.39781380e+01 -5.97225494e+01 -6.01551895e+01 -6.65666733e+01 -7.49138947e+01 -7.97415771e+01 -8.04695663e+01 -6.89646912e+01 -5.75041504e+01 -5.55686607e+01 -6.61315689e+01 -7.35167007e+01 -6.92752380e+01 -6.29115944e+01 -5.92094154e+01 -5.69291420e+01 -5.43331375e+01 -5.37601357e+01 -5.54404793e+01 -5.85431938e+01 -6.25234795e+01 -6.65181351e+01 -7.11879654e+01 -7.05610809e+01 -6.54899979e+01 -6.09333649e+01 -6.09555931e+01 -6.18507385e+01 -6.05995636e+01 -6.07409821e+01 -6.09205170e+01 -6.15518761e+01 -6.13449821e+01 -5.99240227e+01 -6.23635941e+01 -6.56282730e+01 -6.66481323e+01 -6.74168320e+01 -6.87512054e+01 -6.77314377e+01 -6.40659866e+01 -6.03387909e+01 -6.06780128e+01 -6.06709824e+01 -6.02807121e+01 -6.05980072e+01 -6.50489807e+01 -6.90029831e+01 -7.21852036e+01 -7.22432327e+01 -6.70784454e+01 -6.28422546e+01 -6.02957115e+01 -6.35463066e+01 -6.68502884e+01 -6.57862015e+01 -6.36452980e+01 -6.23501472e+01 -6.31056900e+01 -6.51918945e+01 -6.63297958e+01 -6.61202698e+01 -6.68516769e+01 -7.05879974e+01 -7.43081131e+01 -7.27843170e+01 -6.72374725e+01 -6.40257568e+01 -6.62528763e+01 -6.89377441e+01 -6.94563904e+01 -6.65570831e+01 -6.40828171e+01 -6.52929077e+01 -6.71259308e+01 -6.97332535e+01 -7.02170792e+01 -6.76671906e+01 -6.44368973e+01 -6.14211655e+01 -6.13018150e+01 -6.17197647e+01 -6.14732857e+01 -6.18107452e+01 -6.29273300e+01 -6.47171631e+01 -6.48203735e+01 -6.35591202e+01 -6.21374397e+01 -6.11825447e+01 -6.15168076e+01 -6.36431122e+01 -6.58609467e+01 -6.53868942e+01 -6.37394676e+01 -6.27979355e+01 -6.28747597e+01 -6.29990730e+01 -6.28346939e+01 -6.28078690e+01 -6.31945343e+01 -6.31268425e+01 -6.37227211e+01 -6.50906982e+01 -6.57338943e+01 -6.53324127e+01 -6.53678284e+01 -1.00797569e+02 -6.00051086e+02 0. 0. 0. 0. 0. 28417318. 318329024. -60604248. -2.08527786e+02 -1.11213264e+02 -1.10601082e+02 28972150. -78539936. -233982096. -233982096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 407427488. 727483392. -82024408. -1.44853198e+03 -4.11141327e+02 -1.72964005e+02 -9.01162567e+01 -1.02619133e+02 -9.65799561e+01 -9.88565521e+01 -9.82319107e+01 -9.60714645e+01 -9.44666290e+01 -9.30431519e+01 -9.25260239e+01 -9.16623306e+01 -9.35085144e+01 -9.62391968e+01 -9.91143875e+01 -9.88491821e+01 -9.34311600e+01 -8.82725830e+01 -8.51772614e+01 -8.34866791e+01 -8.60506287e+01 -8.65371246e+01 -8.80745010e+01 -9.20752716e+01 -9.46277466e+01 -9.26966400e+01 -8.62820740e+01 -7.93278351e+01 -7.97026443e+01 -8.48087463e+01 -9.58214035e+01 -9.81948700e+01 -9.61661072e+01 -9.41698914e+01 -9.39547958e+01 -9.26949234e+01 -8.66082001e+01 -8.25096512e+01 -8.53354950e+01 -9.15271606e+01 -9.39401321e+01 -8.83240891e+01 -8.71186447e+01 -8.89316330e+01 -8.62244720e+01 -8.66790161e+01 -8.62258148e+01 -8.99334869e+01 -9.42927551e+01 -9.82948074e+01 -9.93900757e+01 -8.86548080e+01 -7.53107758e+01 -7.19184036e+01 -7.96988754e+01 -9.34241180e+01 -9.50135422e+01 -8.91289215e+01 -8.44614029e+01 -8.64735413e+01 -8.84668503e+01 -8.53571854e+01 -8.27445755e+01 -8.32021866e+01 -9.07474442e+01 -1.00349091e+02 -9.67895203e+01 -9.40414581e+01 -8.97976227e+01 -8.67248688e+01 -8.52584991e+01 -8.10211716e+01 -8.70168076e+01 -9.54912186e+01 -1.05390747e+02 -1.03082672e+02 -9.17138901e+01 -7.95975876e+01 -7.26487579e+01 -7.21386337e+01 -8.23922577e+01 -8.67150421e+01 -8.70312653e+01 -9.49683685e+01 -1.05393715e+02 -1.06194618e+02 -8.81265259e+01 -7.16859360e+01 -7.23958282e+01 -8.77953262e+01 -1.04207939e+02 -1.05319687e+02 -1.02205933e+02 -1.02151329e+02 -1.02599655e+02 -9.67270355e+01 -8.66965714e+01 -8.17097092e+01 -8.81089401e+01 -9.91492996e+01 -9.92686996e+01 -8.87248840e+01 -7.58865051e+01 -7.11948395e+01 -7.20196991e+01 -8.50091171e+01 -9.69957581e+01 -9.45249100e+01 -9.43168106e+01 -9.98190842e+01 -1.03582939e+02 -9.36277313e+01 -7.55859070e+01 -7.62831192e+01 -9.44846268e+01 -1.12708618e+02 -1.15750069e+02 -1.00095818e+02 -8.48146210e+01 -7.32588730e+01 -6.77500687e+01 -7.59412079e+01 -8.19965057e+01 -8.61610260e+01 -9.95246353e+01 -1.12631752e+02 -1.12966583e+02 -1.00532928e+02 -8.38946304e+01 -7.66616058e+01 -7.70857010e+01 -8.75207214e+01 -9.36112366e+01 -9.47875900e+01 -9.67216187e+01 -1.03354904e+02 -1.05839645e+02 -9.12967072e+01 -6.97182159e+01 -5.73652573e+01 -6.16447220e+01 -7.16392288e+01 -7.29467087e+01 -8.20158997e+01 -8.64717484e+01 -8.24107361e+01 -7.83571930e+01 -6.55992737e+01 -6.24919853e+01 -6.53113708e+01 -7.92464523e+01 -8.40155487e+01 -7.21040039e+01 -5.98624611e+01 -6.72111282e+01 -8.64786377e+01 -9.56748352e+01 -8.10200195e+01 -6.44905396e+01 -6.63818970e+01 -6.85869751e+01 -6.64222794e+01 -4.51130943e+01 -2.96480980e+01 -2.84225044e+01 -5.84857483e+01 -9.32042007e+01 -9.90494308e+01 -9.41200485e+01 -9.24961777e+01 -9.16715164e+01 -8.07666702e+01 -5.86472740e+01 -4.81660271e+01 -6.74826050e+01 -8.87448502e+01 -9.48669205e+01 -7.16636658e+01 -5.42686043e+01 -5.46111221e+01 -5.63521309e+01 -6.27287064e+01 -5.30166016e+01 -5.18731003e+01 -5.93845482e+01 -6.14757957e+01 -5.72445107e+01 -3.79550819e+01 -2.77810535e+01 -2.92019234e+01 -6.31640587e+01 -9.63393784e+01 -1.03315811e+02 -9.00800858e+01 -8.33716125e+01 -7.96959076e+01 -7.04086380e+01 -4.82805710e+01 -4.60898895e+01 -7.39563599e+01 -1.02265488e+02 -1.08545799e+02 -8.09866409e+01 -6.87223740e+01 -6.66753693e+01 -6.80130844e+01 -6.76060028e+01 -5.83990669e+01 -4.65184021e+01 -6.28114777e+01 -8.44547424e+01 -9.45074463e+01 -7.21099091e+01 -4.78539848e+01 -4.37027168e+01 -6.62649384e+01 -8.40927353e+01 -8.61266174e+01 -7.61918945e+01 -7.91412888e+01 -7.97789154e+01 -8.29425888e+01 -7.63517303e+01 -7.64202118e+01 -7.94142380e+01 -8.72453690e+01 -9.78677444e+01 -9.66870651e+01 -9.17717438e+01 -8.52248306e+01 -6.06414490e+01 -4.90439034e+01 -3.08598595e+01 -4.36307182e+01 -6.37159653e+01 -8.15570297e+01 -9.84535522e+01 -6.63539429e+01 -4.11506386e+01 -3.53581963e+01 -6.57293854e+01 -8.30359497e+01 -6.90861282e+01 -5.31626625e+01 -6.65765381e+01 -8.36691055e+01 -7.54232025e+01 -4.77947121e+01 -3.39623985e+01 -4.77456779e+01 -5.09038124e+01 -5.41430016e+01 -5.27675552e+01 -6.65493240e+01 -5.67167664e+01 -4.76139679e+01 -3.82767410e+01 -2.56102867e+01 -2.72089157e+01 -3.41891823e+01 -6.25423965e+01 -8.13380737e+01 -6.48834000e+01 -2.20048847e+01 -6.16789961e+00 -2.33842411e+01 -3.42016068e+01 -2.75321751e+01 -1.61825886e+01 -3.79357147e+01 -5.10459061e+01 -5.23527451e+01 -4.50341148e+01 -4.64145088e+01 -5.15963554e+01 -4.24240494e+01 -4.19205170e+01 -5.90977669e+01 -7.32901688e+01 -6.70580902e+01 -7.30564728e+01 -9.44345779e+01 -9.35453110e+01 -6.40423355e+01 -3.43900261e+01 -3.76364403e+01 -4.55440483e+01 -3.94489021e+01 -2.03192272e+01 -3.00673084e+01 -4.79089012e+01 -5.02094650e+01 -3.09943371e+01 -1.17306910e+01 -2.03714943e+01 -2.64494591e+01 -4.01348724e+01 -3.70865364e+01 -5.34162903e+01 -6.98061829e+01 -6.56845474e+01 -5.13666992e+01 -3.78395805e+01 -4.65881233e+01 -5.35478439e+01 -6.61048126e+01 -8.40337143e+01 -7.87521286e+01 -6.71373367e+01 -4.87475662e+01 -6.29959602e+01 -7.71176834e+01 -6.27125893e+01 -2.65308151e+01 -2.26962433e+01 -4.59526863e+01 -6.25887680e+01 -3.85904465e+01 -1.70626431e+01 -2.72305489e+01 -4.20512505e+01 -6.28695335e+01 -6.58455124e+01 -8.03475647e+01 -8.33215485e+01 -7.23793411e+01 -6.17823715e+01 -5.71752319e+01 -6.17117538e+01 -5.42346230e+01 -5.99432449e+01 -7.06546860e+01 -6.37586555e+01 -3.34264336e+01 -1.32968569e+01 -1.72329369e+01 -2.49524193e+01 -1.61936417e+01 -3.79340982e+00 -1.59727755e+01 -2.48978138e+01 -2.86876259e+01 -9.69889641e+00 -1.29356050e+01 -2.60538883e+01 -2.62319183e+01 -3.09316444e+01 -3.30226860e+01 -6.34475403e+01 -7.47152176e+01 -6.55189362e+01 -4.06929741e+01 -1.27561016e+01 -1.72265606e+01 -2.80599365e+01 -4.99682274e+01 -8.25181198e+01 -7.66705856e+01 -2.87533684e+01 2.86159210e+01 4.71105690e+01 1.63592167e+01 -3.54626799e+00 5.63734436e+00 9.95756721e+00 2.98413849e+01 5.76899481e+00 3.84114194e+00 -1.10431528e+01 -9.86333561e+00 3.08858376e+01 4.41795807e+01 4.50104370e+01 -9.33636761e+00 -4.56455002e+01 -2.34075165e+01 6.73482561e+00 2.12252655e+01 -1.69534473e+01 -4.90520096e+01 -4.43477974e+01 -4.30605507e+01 -2.03356495e+01 -3.64316392e+00 1.62386017e+01 2.90623016e+01 1.16108665e+01 -6.76673412e+00 -2.17989864e+01 -2.29350300e+01 1.43074112e+01 3.19978352e+01 5.24489250e+01 3.28029404e+01 -4.18460846e+00 -8.21528816e+00 -8.93019485e+00 -1.28771610e+01 -4.73953476e+01 -4.48125229e+01 1.69056988e+01 5.70753784e+01 6.02507324e+01 2.51031952e+01 5.67671156e+00 -3.84372473e-01 -1.96681499e+01 -1.84162560e+01 5.25972700e+00 2.34157581e+01 4.61442261e+01 3.30472145e+01 2.92354240e+01 2.79496784e+01 2.38941441e+01 2.53879166e+01 -1.48383970e+01 -1.80733109e+01 -1.17491360e+01 3.02102494e+00 3.86147079e+01 5.12650490e+01 5.28722191e+01 2.62086701e+00 -3.51101875e+01 -3.57822990e+01 8.07893336e-01 3.59987755e+01 1.29108591e+01 -2.52214317e+01 -4.20719414e+01 -3.08279266e+01 -1.29258766e+01 5.66784525e+00 1.63529797e+01 3.05603657e+01 7.66628504e+00 -1.18868017e+01 -2.66813869e+01 -8.18047810e+00 4.54636078e+01 7.03171082e+01 5.91413116e+01 1.76296425e+01 -1.94646397e+01 3.50778639e-01 3.14986572e+01 4.89119911e+01 1.70024223e+01 -1.27964230e+01 -6.84687710e+00 9.03762531e+00 2.47770348e+01 2.12211456e+01 1.53485889e+01 2.64053249e+01 2.66592522e+01 2.41591167e+01 2.72039909e+01 2.78625546e+01 4.52642860e+01 3.18582821e+01 2.55912151e+01 1.74842129e+01 1.17443209e+01 3.49509392e+01 2.02170525e+01 6.54906178e+00 -2.63058453e+01 -1.88916912e+01 2.76529732e+01 6.15873795e+01 7.34868546e+01 2.32025700e+01 -1.39482050e+01 -2.58153877e+01 -3.50800776e+00 2.73593102e+01 2.99138794e+01 1.07520971e+01 -7.35100222e+00 -2.34095516e+01 -5.41156006e+00 2.89059124e+01 6.88815308e+01 6.89632492e+01 1.94146519e+01 -2.10564079e+01 -3.61498451e+01 -2.08922005e+01 2.44572849e+01 6.02936592e+01 6.55768280e+01 2.49819927e+01 -1.40762024e+01 -2.87880397e+00 3.46665611e+01 6.01191101e+01 3.38284492e+01 -6.49705839e+00 -1.30425653e+01 1.86750913e+00 3.58400955e+01 5.89145241e+01 6.15753784e+01 5.49144669e+01 3.00296078e+01 9.57104015e+00 7.78714228e+00 1.78317833e+01 5.29046707e+01 4.75446625e+01 3.27276421e+01 2.02533607e+01 1.43811107e+00 2.73951492e+01 2.90654373e+01 3.60079613e+01 9.67112541e+00 1.79918563e+00 4.76112709e+01 7.12448044e+01 7.31045761e+01 2.86760483e+01 -2.07596517e+00 -6.56073046e+00 8.76116180e+00 4.16337090e+01 6.38770523e+01 6.25129623e+01 5.74236221e+01 3.41197662e+01 2.53167725e+01 3.21732635e+01 3.32298775e+01 4.28669548e+01 1.30144958e+01 1.27776079e+01 1.06976738e+01 1.91743317e+01 5.10288162e+01 5.29188347e+01 4.07116814e+01 -4.43380928e+00 -1.93393974e+01 -8.54837799e+00 1.52322245e+01 4.05067749e+01 2.50545158e+01 -5.43057024e-02 -1.53286781e+01 -6.00631142e+00 1.68839054e+01 3.11437817e+01 3.87705193e+01 4.41577339e+01 4.58072548e+01 4.53401375e+01 4.57452507e+01 5.22508430e+01 7.72353973e+01 5.51879463e+01 2.66340675e+01 3.16213036e+00 2.46923389e+01 6.55166245e+01 8.38464966e+01 7.45347519e+01 3.99218292e+01 1.68669071e+01 2.91013794e+01 4.62350121e+01 5.57175140e+01 4.68912735e+01 4.02085381e+01 5.23228111e+01 5.93831787e+01 6.86714859e+01 7.38149796e+01 7.62721100e+01 8.08416367e+01 6.30280800e+01 5.31048088e+01 5.19456329e+01 5.03943634e+01 6.59514999e+01 5.83068352e+01 5.65384064e+01 4.04480095e+01 3.10971260e+01 5.50362206e+01 5.81412697e+01 6.56568832e+01 4.53627510e+01 3.50384407e+01 5.09748001e+01 5.62202606e+01 8.61539841e+01 7.25651245e+01 5.46938133e+01 3.00207634e+01 1.98638382e+01 5.22243614e+01 6.28169937e+01 6.71755447e+01 7.05080643e+01 7.15297546e+01 6.81002960e+01 3.06521873e+01 2.40694237e+01 6.10661507e+01 5.44610939e+01 2.12975235e+01 -5.02754211e+01 -8.92772293e+00 -8.79815186e+02 -1.51508887e+03 4.20615820e+03 1.25005635e+04 46472784. -264798400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -358400512. 51028948. -4.02889844e+03 -1.45717896e+03 -2.84292278e+01 -1.44486679e+02 -1.96141663e+02 -3.70976715e+01 2.95455418e+01 4.22804909e+01 5.41221542e+01 5.39766502e+01 6.71897202e+01 7.69838638e+01 7.89676895e+01 7.03799667e+01 6.91000443e+01 8.43911667e+01 9.44434204e+01 9.22547302e+01 8.85288849e+01 8.04354782e+01 7.55918579e+01 5.88724174e+01 5.52248764e+01 7.83603363e+01 8.98366165e+01 8.00566101e+01 5.82808952e+01 7.23379135e+01 1.01250595e+02 1.05061996e+02 8.88610992e+01 7.10058670e+01 7.01673813e+01 7.40714722e+01 7.22918091e+01 7.74722519e+01 8.53892822e+01 9.05953751e+01 8.62424088e+01 7.48507004e+01 8.12169647e+01 8.91311340e+01 1.01581635e+02 1.17987480e+02 1.06043800e+02 8.43249817e+01 5.31159592e+01 5.49762383e+01 8.32235413e+01 8.79201584e+01 8.15232162e+01 6.07781372e+01 6.20525475e+01 7.81603928e+01 8.64082413e+01 9.36320953e+01 8.18939896e+01 7.95671158e+01 7.99593201e+01 8.49471130e+01 9.91823273e+01 1.08177475e+02 1.08731621e+02 9.73220367e+01 8.68717575e+01 9.02681961e+01 9.26090469e+01 1.03609055e+02 1.18111565e+02 1.25438835e+02 1.24677528e+02 1.08140923e+02 1.00833908e+02 1.08074600e+02 9.99787064e+01 8.69553146e+01 6.37978935e+01 6.98612061e+01 8.65826721e+01 9.24010544e+01 9.34623260e+01 9.51865768e+01 9.76035309e+01 9.08554459e+01 8.00883408e+01 8.24719467e+01 8.85071564e+01 8.97125931e+01 9.19573822e+01 9.66230545e+01 1.05597977e+02 1.00093216e+02 9.16697083e+01 1.01089951e+02 1.03141594e+02 1.00562820e+02 8.57604065e+01 8.08058701e+01 9.95629883e+01 1.00685577e+02 9.45490799e+01 7.33897095e+01 6.94878006e+01 8.28420639e+01 8.99721832e+01 9.68471069e+01 9.82501297e+01 1.02744118e+02 1.04920181e+02 9.68129425e+01 9.73030930e+01 9.83461227e+01 1.01436226e+02 9.80247192e+01 9.01976852e+01 9.24605713e+01 9.11076355e+01 8.86805038e+01 9.54660110e+01 9.62889786e+01 9.31938324e+01 7.86709213e+01 7.63266296e+01 9.52737961e+01 9.98289185e+01 9.34700089e+01 7.76144485e+01 7.72194366e+01 8.91074066e+01 9.20653152e+01 9.37678986e+01 9.47234497e+01 9.29144440e+01 8.97007141e+01 8.18279190e+01 8.72308350e+01 9.31727142e+01 9.43884659e+01 9.03511581e+01 8.32359314e+01 8.69280701e+01 8.95991745e+01 9.24069672e+01 9.75229034e+01 9.93053284e+01 1.01141029e+02 9.91131363e+01 9.78274460e+01 1.01945732e+02 9.97456589e+01 9.59258652e+01 8.67315521e+01 8.06563110e+01 8.37111969e+01 8.63283463e+01 9.31265335e+01 9.48004837e+01 9.74650803e+01 1.00481819e+02 1.00315918e+02 9.84698868e+01 9.75116501e+01 9.93357239e+01 1.01727066e+02 9.75420914e+01 9.01394882e+01 8.47157745e+01 8.34836121e+01 9.26787415e+01 9.55285339e+01 9.33775864e+01 8.86396027e+01 8.98354187e+01 9.44026794e+01 9.39632416e+01 9.48487244e+01 9.54655609e+01 9.53628082e+01 9.27864380e+01 9.06257248e+01 9.29400787e+01 9.56918259e+01 9.51938782e+01 9.55910797e+01 9.56082687e+01 9.76027679e+01 1.00036179e+02 1.01892807e+02 1.03449310e+02 9.85117722e+01 9.47023239e+01 9.20110855e+01 9.18698502e+01 9.52572021e+01 9.48032303e+01 9.31762466e+01 8.89634857e+01 8.94164886e+01 9.29097290e+01 9.53534698e+01 9.60849228e+01 9.51830063e+01 9.60195007e+01 9.67496643e+01 9.59588318e+01 9.53747940e+01 9.50786972e+01 9.53127213e+01 9.45660858e+01 9.34315720e+01 9.32099915e+01 9.23689728e+01 9.23759308e+01 9.37886734e+01 9.48711014e+01 9.45048752e+01 9.33348923e+01 9.29127655e+01 9.30491562e+01 9.28455505e+01 9.27330551e+01 9.27534637e+01 9.29060364e+01 9.29951553e+01 9.29408722e+01 9.25885315e+01 9.23332062e+01 9.25598755e+01 9.30757141e+01 9.33084564e+01 9.28569870e+01 9.24856110e+01 9.27552872e+01 9.28103638e+01 9.29372482e+01 9.29227219e+01 9.30091629e+01 9.27227173e+01 9.26966476e+01 9.24447708e+01 9.23911362e+01 9.26723862e+01 9.34988251e+01 9.36784058e+01 9.31611176e+01 9.23586197e+01 9.25115128e+01 9.32520752e+01 9.31069717e+01 9.29687881e+01 9.11388626e+01 8.97988663e+01 8.96322861e+01 9.08937607e+01 9.30288620e+01 9.25266418e+01 9.23533936e+01 9.18127823e+01 9.18982010e+01 9.10722580e+01 9.11348801e+01 9.12175369e+01 9.18651657e+01 9.10933914e+01 9.20439606e+01 9.27888184e+01 9.26866760e+01 9.24433746e+01 9.31750336e+01 9.39815063e+01 9.32220459e+01 9.26948090e+01 9.28200455e+01 9.27840347e+01 9.17971878e+01 9.29180832e+01 9.31791382e+01 9.30315399e+01 9.13437576e+01 9.17275391e+01 9.33364029e+01 9.35895462e+01 9.23157501e+01 9.31278000e+01 9.48433075e+01 9.55845032e+01 9.28821182e+01 9.16095657e+01 9.17081833e+01 9.27671738e+01 9.26171570e+01 9.26745605e+01 9.11553421e+01 8.87597275e+01 8.62232056e+01 8.60948944e+01 8.85274963e+01 8.88747482e+01 9.05876465e+01 8.95697250e+01 8.94167252e+01 8.78394394e+01 8.78215408e+01 8.89243469e+01 8.83470154e+01 8.87859344e+01 9.25013885e+01 9.50821686e+01 9.50534897e+01 9.19224396e+01 9.18349304e+01 8.88984528e+01 8.59239655e+01 8.34679642e+01 8.55869293e+01 8.80773697e+01 8.79174118e+01 8.59618378e+01 8.94479294e+01 9.37121735e+01 9.45096588e+01 9.02299271e+01 8.47401199e+01 8.35169754e+01 8.23083496e+01 8.31061630e+01 9.10768280e+01 9.76329422e+01 9.88682251e+01 9.32442322e+01 8.76487885e+01 8.76490250e+01 8.69429779e+01 8.53496780e+01 8.37918320e+01 8.36803055e+01 8.43408890e+01 8.39938889e+01 8.53058243e+01 8.56755981e+01 8.41881485e+01 7.98252945e+01 7.37545166e+01 6.92832565e+01 7.06658401e+01 7.63262482e+01 8.20290909e+01 7.92801514e+01 7.73959198e+01 7.97143936e+01 8.44472809e+01 8.85171127e+01 8.49426880e+01 8.12225800e+01 7.78118439e+01 7.93523636e+01 8.10654907e+01 8.10787430e+01 7.91877670e+01 7.20744171e+01 6.32618561e+01 7.35368118e+01 9.16120911e+01 9.82175217e+01 8.90073776e+01 7.70508575e+01 7.88065567e+01 8.10632706e+01 8.37055130e+01 8.20895996e+01 7.98033600e+01 7.97661819e+01 8.42409210e+01 8.85934677e+01 8.40400238e+01 7.35322647e+01 6.70706177e+01 7.30419159e+01 8.07075882e+01 8.38429871e+01 8.27833328e+01 8.30023956e+01 8.50733948e+01 9.21534958e+01 9.86544876e+01 9.32905273e+01 8.45172882e+01 7.89154587e+01 8.37623062e+01 8.23006439e+01 7.86172943e+01 7.69915543e+01 7.80785904e+01 7.84568329e+01 7.95781326e+01 8.21835556e+01 8.86601944e+01 8.55873871e+01 8.14188309e+01 7.60561905e+01 7.39669418e+01 6.70688858e+01 5.33471222e+01 4.52721138e+01 4.99816399e+01 6.06044846e+01 6.83662872e+01 7.15728912e+01 7.02927246e+01 6.61268692e+01 6.39638176e+01 6.58586273e+01 6.92457733e+01 6.95805435e+01 7.27957458e+01 6.46815948e+01 5.51246796e+01 5.21967735e+01 5.98629837e+01 6.91329269e+01 6.84901505e+01 7.16915512e+01 7.44314880e+01 7.84084244e+01 7.47077408e+01 7.30954285e+01 7.34420471e+01 7.49797516e+01 7.38401718e+01 7.18436050e+01 7.66298218e+01 7.75234070e+01 7.78373260e+01 7.46528931e+01 7.22550964e+01 7.52812347e+01 7.78512878e+01 8.09816208e+01 7.85103760e+01 7.05010147e+01 6.37325554e+01 6.13750954e+01 6.39375992e+01 7.00213318e+01 8.07679291e+01 8.65296021e+01 7.32702713e+01 6.10520401e+01 4.86873627e+01 4.82872391e+01 4.41228943e+01 4.57464333e+01 5.65001221e+01 8.25431290e+01 1.09518272e+02 1.41750687e+02 1.96154556e+02 2.27067352e+02 1.08220520e+03 1.17936499e+03 -2.76302461e+04 -353220768. 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. 0. 0. 0. 0. 0. 0. 0. 119250520. -71518888. -17341892. -55024388. 1.02433662e+04 4.55917334e+03 2.17828687e+03 1.46625146e+03 4.03425232e+02 2.63890411e+02 2.04470337e+02 1.36016983e+02 1.12700294e+02 1.08101036e+02 1.24297401e+02 1.15813423e+02 4.74911575e+01 -2.22124119e+01 -1.56407957e+01 5.31905518e+01 1.51677277e+02 1.51640686e+02 2.24807236e+02 2.69568481e+02 2.84426483e+02 2.15897812e+02 1.94134048e+02 2.44468323e+02 2.59900024e+02 2.58934326e+02 2.47929733e+02 2.10278152e+02 1.16633667e+02 7.84144363e+01 5.76407394e+01 5.90626984e+01 5.24569664e+01 4.49291115e+01 3.62334290e+01 3.97754745e+01 4.58549767e+01 4.52369614e+01 3.85471268e+01 3.10153332e+01 2.50409946e+01 1.88178749e+01 2.14651203e+01 1.81458530e+01 1.59693642e+01 1.58233767e+01 2.09488506e+01 2.95698872e+01 2.66928215e+01 2.43265457e+01 2.55699406e+01 2.76090164e+01 3.01748371e+01 2.76406937e+01 2.59149284e+01 3.21879692e+01 3.55886650e+01 5.21723289e+01 6.30155830e+01 6.45956955e+01 6.02027435e+01 5.49261742e+01 6.73322906e+01 7.42285461e+01 6.35230980e+01 4.71381454e+01 2.95908222e+01 2.50596962e+01 2.18450089e+01 1.08108826e+01 -3.87427926e+00 -1.38851357e+01 -1.17833300e+01 3.15550804e+00 1.47454176e+01 2.33108654e+01 2.48598499e+01 2.20373020e+01 3.55521545e+01 4.87849121e+01 6.82754517e+01 7.41951904e+01 6.52812729e+01 5.15040970e+01 3.68519478e+01 3.23696136e+01 3.53435707e+01 5.32362480e+01 6.96127014e+01 6.48747177e+01 4.48811989e+01 3.05797367e+01 3.27781563e+01 3.87044182e+01 4.28395805e+01 4.90377998e+01 2.86042767e+01 7.88096476e+00 -2.04733086e+00 7.22865152e+00 2.52618065e+01 2.45503597e+01 2.98556099e+01 3.68393631e+01 4.35319061e+01 5.26709938e+01 5.07498894e+01 3.61945534e+01 1.65275040e+01 -3.95340943e+00 -3.81554246e+00 2.47615647e+00 9.19265556e+00 9.64502621e+00 1.42550421e+00 -7.47632012e-02 8.65291953e-01 3.43456268e+00 6.70535326e+00 1.23006334e+01 1.60904560e+01 1.43230438e+01 1.69962692e+01 3.60562286e+01 5.93980637e+01 5.97786674e+01 4.39715652e+01 2.72432632e+01 3.46075363e+01 4.41024094e+01 5.68824234e+01 6.19107361e+01 5.08253975e+01 3.14948807e+01 1.35078583e+01 7.20525408e+00 4.84918213e+00 5.41085196e+00 6.64541817e+00 4.53806734e+00 -2.36905992e-01 -1.13505185e+00 5.53571081e+00 8.11573029e+00 7.30954790e+00 6.72684431e+00 9.77239609e+00 1.74418640e+01 3.57312813e+01 5.14736328e+01 4.69303551e+01 2.56209393e+01 7.26972342e+00 2.29642220e+01 4.08223610e+01 5.33804245e+01 5.29622955e+01 5.77370911e+01 6.14145813e+01 4.66869698e+01 3.28776283e+01 1.39019041e+01 1.17667551e+01 6.33393812e+00 2.98353958e+00 9.06092167e+00 8.59154415e+00 7.54379034e+00 4.02642059e+00 5.99429464e+00 5.25852633e+00 -2.07786312e+01 -4.24588547e+01 -4.24454117e+01 -2.00264797e+01 8.76456201e-01 5.69508266e+00 5.72158623e+00 -3.75303566e-01 -7.90869856e+00 3.20976973e+00 2.47481098e+01 2.44461784e+01 1.03173323e+01 -9.74423313e+00 -5.79085350e+00 -2.07130814e+00 9.17786360e-01 -4.98252487e+00 -3.92076039e+00 -4.49206686e+00 2.40712237e+00 4.04352522e+00 4.95458508e+00 1.74450183e+00 -9.10739839e-01 -1.74470692e+01 -3.42287407e+01 -3.42084885e+01 -2.21673717e+01 -6.60142803e+00 -1.57500668e+01 -1.56439390e+01 -9.77397823e+00 -2.45846176e+00 -1.29974627e+00 -6.77752256e+00 -1.04769621e+01 -1.18868971e+01 -1.03736057e+01 -5.46652365e+00 -7.12608099e+00 -1.02551460e+01 -1.25225134e+01 -1.53442183e+01 -1.42522821e+01 -1.88874187e+01 -1.57790613e+01 -1.64857216e+01 -1.51017733e+01 -1.85167580e+01 -3.03338909e+01 -3.92471390e+01 -4.01419067e+01 -3.35745888e+01 -2.36160851e+01 -2.63710194e+01 -2.38179417e+01 -2.95535984e+01 -3.25953903e+01 -3.11683941e+01 -3.01537952e+01 -2.63345146e+01 -3.37492485e+01 -3.48636284e+01 -3.38773842e+01 -2.63385010e+01 -1.94321327e+01 -1.90129414e+01 -3.54393539e+01 -5.28907471e+01 -5.69858055e+01 -4.32968559e+01 -5.11315489e+00 1.64412785e+01 1.54759426e+01 -8.84734058e+00 -2.63191833e+01 -6.78446102e+00 9.04688549e+00 7.70219803e+00 -1.31025410e+01 -3.00985565e+01 -3.24513283e+01 -3.40548630e+01 -3.19406719e+01 -2.93564930e+01 -3.19818516e+01 -3.63883820e+01 -3.45400352e+01 -2.82004128e+01 -1.95207787e+01 -3.28618507e+01 -4.37689400e+01 -4.91395798e+01 -3.23607330e+01 -1.64863758e+01 -1.29863968e+01 -1.61593609e+01 -1.72876625e+01 -1.98224392e+01 -1.90002174e+01 -2.24628620e+01 -1.18870974e+01 -3.98230290e+00 -9.10849571e+00 -2.84511375e+01 -4.29837456e+01 -4.18447990e+01 -3.44382095e+01 -2.82584209e+01 -2.74643459e+01 -4.17089958e+01 -6.03396187e+01 -5.91276817e+01 -4.68997917e+01 -3.19988194e+01 -3.80236435e+01 -3.89836578e+01 -4.10434380e+01 -3.59756432e+01 -2.22661247e+01 -6.05306053e+00 -9.19049072e+00 -2.27605648e+01 -4.16999474e+01 -3.98627701e+01 -3.69307327e+01 -3.52617264e+01 -3.72131500e+01 -2.79231548e+01 -1.18283281e+01 -7.64445305e+00 -1.35132780e+01 -3.05273418e+01 -2.90426979e+01 -3.37377281e+01 -3.60007858e+01 -4.00081215e+01 -3.87650223e+01 -3.33345451e+01 -2.90704517e+01 -3.05218353e+01 -3.55780334e+01 -3.93682137e+01 -4.34844131e+01 -4.84563026e+01 -5.35485382e+01 -5.42266006e+01 -5.46160355e+01 -5.16666718e+01 -3.79994354e+01 -2.06391811e+01 -1.01949434e+01 -7.20364046e+00 -7.14837694e+00 -7.22922754e+00 -2.94019375e+01 -4.25015831e+01 -5.58063889e+01 -4.98273048e+01 -4.91857109e+01 -3.76589546e+01 -2.47581062e+01 -2.94894791e+01 -3.62519455e+01 -5.83008308e+01 -7.06140137e+01 -7.42281265e+01 -6.68036194e+01 -5.48549919e+01 -5.49918556e+01 -4.65338821e+01 -3.12960682e+01 -2.10394859e+01 -3.22560616e+01 -4.86369324e+01 -6.74264984e+01 -5.62580299e+01 -4.38936195e+01 -3.52106552e+01 -3.73087921e+01 -4.84915161e+01 -5.75759087e+01 -7.00157776e+01 -6.90938110e+01 -6.71972046e+01 -6.83277359e+01 -6.74583511e+01 -6.56012650e+01 -6.50695877e+01 -6.49624405e+01 -6.60475388e+01 -6.47611313e+01 -6.32001343e+01 -5.79615059e+01 -4.43409691e+01 -2.90085144e+01 -4.21472130e+01 -6.57228088e+01 -6.77182465e+01 -4.64668312e+01 -3.11763535e+01 -4.38156395e+01 -5.79348564e+01 -4.90352173e+01 -4.06513100e+01 -3.83906212e+01 -4.75847435e+01 -5.82230835e+01 -5.59319344e+01 -5.35310974e+01 -4.90451889e+01 -5.38213501e+01 -5.79710045e+01 -6.26009521e+01 -6.33761749e+01 -6.35315323e+01 -5.99767532e+01 -6.01806526e+01 -5.60814629e+01 -5.02629318e+01 -3.93327065e+01 -5.15121689e+01 -7.48725662e+01 -7.27230453e+01 -5.03321190e+01 -3.68410759e+01 -5.49834290e+01 -6.96487427e+01 -6.37605782e+01 -5.50794487e+01 -6.41196518e+01 -8.21023483e+01 -9.25376740e+01 -8.76762772e+01 -8.13256073e+01 -7.02551041e+01 -5.83615379e+01 -5.93232994e+01 -7.50379333e+01 -7.60047455e+01 -5.93833275e+01 -5.56369362e+01 -6.86292572e+01 -8.28032379e+01 -8.23313675e+01 -7.92441025e+01 -8.64024048e+01 -9.55636978e+01 -8.93620224e+01 -7.41163406e+01 -6.03360786e+01 -6.64346466e+01 -7.17335052e+01 -7.34239883e+01 -7.28060150e+01 -7.15117569e+01 -7.28852692e+01 -7.57835541e+01 -8.33125992e+01 -8.23322601e+01 -7.02868195e+01 -5.65172310e+01 -5.35064926e+01 -6.06488800e+01 -5.70322876e+01 -4.46604652e+01 -4.92935638e+01 -6.91661835e+01 -8.87341309e+01 -9.08228989e+01 -8.25165710e+01 -8.52924957e+01 -8.81946259e+01 -8.63316040e+01 -7.91759949e+01 -7.19584656e+01 -7.22978134e+01 -7.69204712e+01 -7.92049103e+01 -8.60775909e+01 -8.69536209e+01 -8.57532578e+01 -8.47205887e+01 -8.49120483e+01 -8.51083908e+01 -7.71701965e+01 -6.84280930e+01 -6.94178467e+01 -7.63685074e+01 -7.97552567e+01 -7.54673920e+01 -8.14311676e+01 -9.23262863e+01 -9.15950623e+01 -7.27768021e+01 -5.17750511e+01 -4.79606056e+01 -5.61857643e+01 -5.97894249e+01 -5.60959816e+01 -5.98209877e+01 -6.56098099e+01 -7.22920685e+01 -7.02810898e+01 -7.17955933e+01 -7.00470352e+01 -6.69544601e+01 -6.78314819e+01 -7.56760483e+01 -8.59426727e+01 -8.21787109e+01 -7.33341141e+01 -7.13200607e+01 -7.98372879e+01 -7.89665604e+01 -7.06085663e+01 -7.63086700e+01 -9.48594437e+01 -1.07269897e+02 -1.00365219e+02 -9.17489548e+01 -9.58335266e+01 -1.05198921e+02 -1.05653130e+02 -1.00035957e+02 -9.48764572e+01 -9.90017014e+01 -1.01174179e+02 -9.97050858e+01 -9.41436386e+01 -8.41551666e+01 -7.47715073e+01 -6.95410767e+01 -6.98333588e+01 -8.17262573e+01 -9.23979950e+01 -9.83765335e+01 -9.31361237e+01 -8.79940186e+01 -8.82936859e+01 -8.89203796e+01 -9.40425797e+01 -1.01814522e+02 -9.94655685e+01 -9.30178757e+01 -8.64621048e+01 -8.62754974e+01 -8.59195938e+01 -7.91921997e+01 -7.36983337e+01 -7.50131226e+01 -8.10048370e+01 -8.61809540e+01 -8.66101761e+01 -8.75270309e+01 -8.74346237e+01 -8.54315186e+01 -8.32622910e+01 -8.36476059e+01 -8.62808304e+01 -8.79500427e+01 -8.95774307e+01 -8.98205032e+01 -9.00476456e+01 -8.52695999e+01 -7.84191132e+01 -7.74632492e+01 -8.11535797e+01 -8.20559845e+01 -7.73815308e+01 -7.86836700e+01 -8.23522415e+01 -8.64628067e+01 -8.17318039e+01 -7.82338028e+01 -8.04082565e+01 -8.53320923e+01 -9.19072037e+01 -9.23713989e+01 -9.22250595e+01 -8.80760498e+01 -8.38862381e+01 -8.38287354e+01 -8.76386337e+01 -8.73212280e+01 -8.33576965e+01 -8.32514648e+01 -8.63891754e+01 -9.18753510e+01 -8.88204727e+01 -8.57953644e+01 -8.64119720e+01 -9.22306671e+01 -9.59051514e+01 -9.30428696e+01 -8.88698578e+01 -8.85987015e+01 -8.88759689e+01 -9.02796249e+01 -8.96749878e+01 -8.89991379e+01 -8.87358627e+01 -8.57880173e+01 -8.42944260e+01 -8.48219833e+01 -8.75407791e+01 -9.02413940e+01 -9.01825409e+01 -9.06342316e+01 -9.05684662e+01 -9.03524780e+01 -9.11249313e+01 -9.11272964e+01 -9.21054382e+01 -9.18752289e+01 -9.23849258e+01 -9.42759628e+01 -9.60274429e+01 -9.37009964e+01 -9.02202225e+01 -8.90820618e+01 -9.16083221e+01 -9.33345413e+01 -9.36021576e+01 -9.28958359e+01 -9.29494095e+01 -9.27181625e+01 -9.25517197e+01 -9.10008163e+01 -8.52802811e+01 -7.78394623e+01 -9.05938873e+01 -1.05798599e+02 -1.19898659e+02 -2.22913986e+02 3.66559131e+03 0. 0. 0. 0. 0. 28417318. 318329024. -60604248. -1.53969727e+03 -1.66814771e+03 37697876. 28972150. -78539936. -233982096. -233982096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 99733608. 129633552. 77189736. 5.08419914e+01 6.60054255e+00 -9.93518066e+01 -8.98532028e+01 -8.55165253e+01 -8.62035522e+01 -9.36662827e+01 -9.90387573e+01 -1.03903099e+02 -1.04225052e+02 -1.00794846e+02 -9.92237625e+01 -1.00336075e+02 -9.87680664e+01 -9.52300644e+01 -9.24483414e+01 -9.60103607e+01 -1.03627205e+02 -1.08042946e+02 -1.05509331e+02 -9.97573547e+01 -9.58906631e+01 -9.65876694e+01 -9.82351608e+01 -9.65783997e+01 -9.38900604e+01 -9.55456390e+01 -1.00767242e+02 -1.03688324e+02 -1.01626495e+02 -9.69378281e+01 -9.49801178e+01 -9.88821869e+01 -1.05182579e+02 -1.08342514e+02 -1.05019730e+02 -1.05695740e+02 -1.10388794e+02 -1.06814140e+02 -9.73903809e+01 -9.07520142e+01 -9.84307556e+01 -1.14130341e+02 -1.19201897e+02 -1.11707001e+02 -1.03368416e+02 -9.81559982e+01 -9.71339264e+01 -9.71930847e+01 -9.71772919e+01 -9.56621628e+01 -9.78082733e+01 -1.11034889e+02 -1.21969604e+02 -1.16920624e+02 -1.04115509e+02 -9.67613907e+01 -1.02993019e+02 -1.11723106e+02 -1.14896072e+02 -1.05796013e+02 -1.03448654e+02 -1.07513954e+02 -1.04756851e+02 -9.46892929e+01 -8.34276886e+01 -8.59026642e+01 -1.03222595e+02 -1.08899551e+02 -1.02331558e+02 -8.94863663e+01 -9.19855270e+01 -1.02037346e+02 -9.87957306e+01 -9.13423920e+01 -8.67384186e+01 -9.40093536e+01 -1.10096268e+02 -1.15698357e+02 -1.09918991e+02 -9.21096954e+01 -8.35003433e+01 -8.66737289e+01 -9.51577606e+01 -9.17526932e+01 -8.26684875e+01 -8.28202896e+01 -9.43232422e+01 -1.00522377e+02 -8.79848175e+01 -7.34318924e+01 -7.19472961e+01 -9.01577225e+01 -1.05840591e+02 -1.07031517e+02 -9.40268402e+01 -9.00023270e+01 -9.28162155e+01 -8.37644653e+01 -6.57284927e+01 -5.59186172e+01 -7.22949142e+01 -9.91255264e+01 -1.13030701e+02 -1.04767181e+02 -8.88555832e+01 -7.14714813e+01 -6.04750710e+01 -6.45116196e+01 -7.03570862e+01 -7.06639862e+01 -7.10280380e+01 -8.79796448e+01 -1.04680244e+02 -9.50414200e+01 -6.66517258e+01 -5.37421455e+01 -6.48248672e+01 -9.26630325e+01 -1.04164619e+02 -9.36404037e+01 -8.08204803e+01 -8.06465225e+01 -8.17041550e+01 -7.01454315e+01 -4.30327072e+01 -4.42753792e+01 -6.62313385e+01 -9.11628494e+01 -9.02067261e+01 -7.54864807e+01 -6.31057816e+01 -6.06258812e+01 -6.40607605e+01 -7.33229370e+01 -7.89842453e+01 -6.52717743e+01 -5.98102341e+01 -7.15895081e+01 -8.53079376e+01 -8.88130951e+01 -8.04152756e+01 -7.91260605e+01 -8.72746735e+01 -8.72483063e+01 -7.84608536e+01 -6.68280411e+01 -6.10131798e+01 -7.35849228e+01 -8.01453629e+01 -7.59262466e+01 -6.48262405e+01 -7.41550369e+01 -1.10551079e+02 -1.27825706e+02 -1.00303314e+02 -6.91016083e+01 -6.34753647e+01 -8.38196640e+01 -9.30942764e+01 -9.21849747e+01 -9.23068848e+01 -1.04902649e+02 -1.22735764e+02 -1.29385895e+02 -1.16902122e+02 -9.04624176e+01 -6.98568192e+01 -8.39716797e+01 -9.56310043e+01 -9.39618073e+01 -7.59235992e+01 -8.63091583e+01 -1.18500168e+02 -1.18774086e+02 -1.02304573e+02 -8.63985901e+01 -1.04492393e+02 -1.44917877e+02 -1.61221558e+02 -1.37085541e+02 -9.06921005e+01 -7.10563354e+01 -7.63721619e+01 -7.50617828e+01 -6.22380676e+01 -7.00657806e+01 -9.78952866e+01 -1.29120972e+02 -1.22454872e+02 -9.49488449e+01 -5.53428574e+01 -3.77496109e+01 -4.62774849e+01 -7.45970688e+01 -9.77061844e+01 -9.96798553e+01 -1.07401466e+02 -1.22194916e+02 -1.14324577e+02 -8.30193176e+01 -4.90916290e+01 -6.59349899e+01 -1.08519875e+02 -1.34765259e+02 -1.06740021e+02 -5.79264221e+01 -4.32234306e+01 -6.35929298e+01 -9.02801056e+01 -7.70583725e+01 -5.70503349e+01 -6.27514534e+01 -8.83957443e+01 -9.49546280e+01 -6.89890518e+01 -3.20130463e+01 -2.42246704e+01 -4.16205635e+01 -6.41369400e+01 -6.31343269e+01 -5.32722702e+01 -5.59351959e+01 -7.26214981e+01 -5.79009056e+01 -3.91441994e+01 -3.27017212e+01 -3.91638145e+01 -5.82216072e+01 -6.50418396e+01 -6.10544930e+01 -6.07346992e+01 -5.97675629e+01 -7.70462799e+01 -6.10896645e+01 -3.69599609e+01 -2.48966217e+01 -3.76736565e+01 -9.01252823e+01 -1.17340439e+02 -1.09674278e+02 -5.25065689e+01 -1.89598618e+01 -1.57637949e+01 -3.97391663e+01 -5.66050148e+01 -4.14295921e+01 -4.62288666e+01 -6.19789314e+01 -7.17958679e+01 -5.17188225e+01 -3.78367577e+01 -6.85098190e+01 -1.04353958e+02 -9.69606705e+01 -7.51749878e+01 -6.40427551e+01 -7.50996552e+01 -9.76186676e+01 -7.05583572e+01 -5.07957878e+01 -3.44399948e+01 -5.05880928e+01 -8.02896347e+01 -9.17231064e+01 -9.65317688e+01 -6.60040359e+01 -5.57611961e+01 -5.04448776e+01 -7.80160065e+01 -7.64228439e+01 -7.48973465e+01 -7.95977707e+01 -9.80428467e+01 -1.06845459e+02 -7.06766968e+01 -5.05129051e+01 -4.84206238e+01 -7.74763565e+01 -6.61173401e+01 -5.50365372e+01 -3.93885193e+01 -3.54383469e+01 -3.76119957e+01 -3.86415367e+01 -6.72774734e+01 -8.27844849e+01 -8.77848282e+01 -8.15340500e+01 -7.00394897e+01 -5.71713753e+01 -2.53753548e+01 -9.25494957e+00 -2.07660370e+01 -7.06926498e+01 -8.17609558e+01 -7.24742661e+01 -5.37768745e+01 -5.38693466e+01 -3.71258812e+01 3.05044866e+00 2.16352558e+01 -5.65282106e-01 -4.95381050e+01 -6.60759506e+01 -4.85239449e+01 -2.38946381e+01 -1.74948578e+01 -3.72526398e+01 -3.63269997e+01 -4.13804169e+01 -1.74920940e+01 -2.84201121e+00 -2.35158587e+00 -2.55758648e+01 -4.04076385e+01 -1.51402655e+01 1.14200191e+01 -3.64678478e+00 -3.81294250e+01 -3.10621929e+01 -6.12037516e+00 -5.14714479e+00 -2.64933052e+01 -2.78996754e+01 5.64252377e+00 1.92729244e+01 6.45614004e+00 -3.19150963e+01 -2.90518265e+01 -1.77065926e+01 8.13150823e-01 -1.07039995e+01 -2.71506691e+01 -1.97030354e+01 -2.15910702e+01 4.08425760e+00 8.08591938e+00 1.15593605e+01 -6.10704231e+00 -1.36180525e+01 -5.23913920e-01 1.47732334e+01 4.17005634e+00 -2.53210392e+01 -3.13371658e+01 -2.90250130e+01 -4.20941315e+01 -7.69136353e+01 -6.80447617e+01 -3.86662064e+01 -2.46325054e+01 -4.44231567e+01 -6.84610138e+01 -3.85413704e+01 -2.11784782e+01 -3.19203645e-01 1.45109053e+01 1.70808487e+01 -1.00598252e+00 -4.90750275e+01 -5.69953232e+01 -2.45090675e+01 1.17052908e+01 -1.00345068e+01 -5.47377663e+01 -8.28353119e+01 -5.01936455e+01 -2.21193352e+01 -2.61334648e+01 -4.15189934e+01 -6.36947403e+01 -8.81394730e+01 -1.24751694e+02 -1.13818039e+02 -7.61756210e+01 -6.21534615e+01 -8.17365494e+01 -1.00995430e+02 -5.75667839e+01 -3.24481926e+01 -1.65354919e+01 -2.27679939e+01 -3.01082172e+01 -5.23677063e+01 -1.10430588e+02 -1.22381828e+02 -7.75157471e+01 1.02918301e+01 3.01208439e+01 -3.59112663e+01 -9.70296402e+01 -1.01661255e+02 -5.70500908e+01 -3.35454521e+01 -4.67399521e+01 -8.01673203e+01 -1.00597664e+02 -7.37156143e+01 -1.79094296e+01 -3.97670865e+00 -3.32136459e+01 -7.29650269e+01 -1.11404648e+02 -1.09848221e+02 -8.94232330e+01 -3.26523247e+01 2.70119934e+01 4.72738991e+01 8.53026295e+00 -6.77024384e+01 -1.10323082e+02 -7.02929306e+01 -1.13289871e+01 -1.21335621e+01 -7.32891998e+01 -1.32400406e+02 -1.09533302e+02 -4.49621315e+01 1.10855398e+01 1.30648165e+01 -2.78636761e+01 -6.06842079e+01 -7.96942749e+01 -4.13684540e+01 -2.29127865e+01 -1.02389650e+01 -3.45521507e+01 -5.00818710e+01 -2.11255608e+01 7.29652691e+00 4.18884010e+01 4.26974449e+01 2.69786129e+01 -4.09459352e+00 -5.97356033e+01 -7.53875198e+01 -3.72700539e+01 4.57444267e+01 8.45621643e+01 5.36429214e+01 -2.21157646e+01 -6.81931686e+01 -5.30611267e+01 -2.16476040e+01 -1.87556438e+01 -4.22924423e+01 -5.54156189e+01 -6.25620461e+01 -2.43047237e+01 4.60224539e-01 3.12201424e+01 3.62919312e+01 2.08923569e+01 -8.42365399e-02 -3.46132622e+01 -2.81193504e+01 -2.83938026e+00 3.03781776e+01 3.13934746e+01 -6.62343562e-01 -4.03776054e+01 -2.80406284e+01 6.79023790e+00 2.98473988e+01 2.94460565e-01 -4.44668961e+01 -4.18635063e+01 -7.71692610e+00 4.16632538e+01 3.99327049e+01 2.97959477e-01 -3.07721596e+01 -5.51991348e+01 -1.36591578e+01 6.21245813e+00 2.82243042e+01 2.58456306e+01 2.90477676e+01 3.70436058e+01 1.74618664e+01 2.67519608e+01 4.60599937e+01 4.41458778e+01 1.26715298e+01 -4.22115593e+01 -5.62703171e+01 -2.64048901e+01 4.43620796e+01 1.01625740e+02 9.44195633e+01 2.91820698e+01 -3.82845306e+01 -6.01418037e+01 -1.41715460e+01 3.88326302e+01 5.13427582e+01 1.19030399e+01 -3.03871117e+01 -1.47499228e+01 2.28908558e+01 5.94322205e+01 6.55414047e+01 5.12147179e+01 1.98802147e+01 -1.17792120e+01 -6.37223005e+00 2.88045845e+01 7.52502289e+01 8.34708786e+01 4.74290161e+01 4.45381498e+00 1.33463907e+00 4.06549225e+01 6.78503494e+01 5.92260323e+01 3.41853714e+01 2.36948776e+01 1.53154469e+01 2.84030113e+01 3.82828751e+01 2.78489304e+01 2.18557034e+01 6.58650017e+00 2.99036884e+01 4.92791786e+01 7.58659286e+01 9.37595596e+01 7.07089539e+01 5.26053734e+01 1.54000587e+01 2.68996549e+00 1.93460674e+01 5.44151649e+01 6.48551865e+01 3.01813641e+01 -8.18297958e+00 -4.91551256e+00 1.72379036e+01 5.84933052e+01 6.91375580e+01 5.34506798e+01 2.94108810e+01 2.10734196e+01 5.37810059e+01 8.44682541e+01 1.13799927e+02 1.09856171e+02 7.05713654e+01 7.15313263e+01 8.61082535e+01 1.22518204e+02 1.26115982e+02 1.13199425e+02 8.72226715e+01 3.83331223e+01 1.77032413e+01 2.81667786e+01 7.06780396e+01 8.71200180e+01 5.77219696e+01 2.17320766e+01 2.38512840e+01 6.66984634e+01 9.82612457e+01 8.88550034e+01 4.64238319e+01 7.69075918e+00 3.55000520e+00 3.96376190e+01 7.97532120e+01 9.04762421e+01 9.10719147e+01 7.98482437e+01 6.65797119e+01 4.05904846e+01 3.87914276e+01 5.16163635e+01 6.01295586e+01 4.45288849e+01 7.82014418e+00 -1.21616583e+01 1.78635731e+01 6.57114029e+01 8.80911102e+01 6.11051407e+01 1.59532890e+01 6.85120630e+00 3.47012863e+01 7.98941650e+01 8.88047791e+01 6.17022934e+01 4.62692070e+01 3.90979118e+01 6.41769485e+01 7.51944199e+01 7.32273483e+01 6.40725174e+01 3.86559677e+01 4.55823975e+01 5.10837097e+01 9.34377594e+01 1.30657181e+02 1.50107666e+02 1.38161026e+02 9.71683197e+01 5.91391335e+01 4.64756546e+01 9.51076965e+01 1.97798660e+02 1.80999817e+02 3.88376770e+01 8.44831238e+02 1.52336487e+03 3.10982513e+02 3.47845886e+02 4.73280548e+02 2.53022568e+02 4.20615820e+03 1.25005635e+04 46472784. -264798400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -581454912. 7.36337402e+03 2.59627832e+03 -6.99805527e+01 1.81375977e+03 1.40909448e+03 2.34261337e+02 1.28888962e+02 8.38021622e+01 9.31762314e+01 1.04771393e+02 1.01574944e+02 8.74869080e+01 4.92183037e+01 4.93296013e+01 6.79220963e+01 9.94790573e+01 9.63794785e+01 6.70946884e+01 4.10761261e+01 3.55026398e+01 5.81529732e+01 9.76808701e+01 1.05410629e+02 7.79786301e+01 4.52264099e+01 4.40640640e+01 7.03037262e+01 7.31670990e+01 5.75393105e+01 5.39228020e+01 7.02346573e+01 8.96921234e+01 8.83155823e+01 9.25411301e+01 1.00465912e+02 1.02812798e+02 8.20093765e+01 4.82124405e+01 4.31956100e+01 6.63479538e+01 9.00186462e+01 9.14959564e+01 6.86801529e+01 4.13729935e+01 4.40803604e+01 7.89446030e+01 1.21821724e+02 1.21107300e+02 8.17902603e+01 6.03136940e+01 5.68595886e+01 7.90705948e+01 8.85945435e+01 9.40255814e+01 9.55360794e+01 9.01558228e+01 7.70267410e+01 5.72690849e+01 6.45800018e+01 8.57469635e+01 9.03896255e+01 7.45962372e+01 4.96974716e+01 5.18950119e+01 6.52389145e+01 8.49376602e+01 9.43179016e+01 7.47478867e+01 5.05996780e+01 2.93831234e+01 4.14631310e+01 6.91549835e+01 7.95052338e+01 6.18873749e+01 4.87736893e+01 5.24084511e+01 7.94824142e+01 8.56545563e+01 7.92770767e+01 6.63928757e+01 6.93515854e+01 6.86409760e+01 6.17403374e+01 6.94235611e+01 8.84889221e+01 9.79924164e+01 8.09695969e+01 5.29421272e+01 4.68880730e+01 5.57162018e+01 7.51830521e+01 8.87956009e+01 9.08084335e+01 7.71049500e+01 6.58577499e+01 6.85106583e+01 9.14657364e+01 1.01386772e+02 8.48644409e+01 6.82887650e+01 6.89974365e+01 9.28899612e+01 1.05934044e+02 1.02235687e+02 9.86167908e+01 9.31195908e+01 8.70036087e+01 6.87157364e+01 7.02182159e+01 8.50405045e+01 9.82821198e+01 9.71635208e+01 8.37466965e+01 8.13620224e+01 8.99513397e+01 9.72773895e+01 1.04542297e+02 1.00649452e+02 8.83992157e+01 7.54983368e+01 7.39067078e+01 9.32547989e+01 1.03116554e+02 9.49353867e+01 8.76765289e+01 8.71358261e+01 9.73025665e+01 9.61553726e+01 9.49790955e+01 9.94095840e+01 1.01577950e+02 9.80728836e+01 8.23977432e+01 8.27001495e+01 9.44769211e+01 1.04359322e+02 1.02801544e+02 9.24789352e+01 9.29155350e+01 1.02208252e+02 1.06583496e+02 1.12342697e+02 1.05207001e+02 9.59084244e+01 8.63065186e+01 8.78750839e+01 9.74463196e+01 9.95255890e+01 9.51957932e+01 9.48586655e+01 9.73941879e+01 1.04807877e+02 1.09589333e+02 1.12721527e+02 1.14115486e+02 1.08411781e+02 1.01975769e+02 9.10436401e+01 8.69868011e+01 8.92382278e+01 9.50076523e+01 9.58363495e+01 8.83107147e+01 8.21902542e+01 8.62648010e+01 9.80132751e+01 1.06083771e+02 1.06315536e+02 9.62725906e+01 9.11074905e+01 9.14508362e+01 9.75265045e+01 9.88047867e+01 9.53900833e+01 9.63452911e+01 9.60951157e+01 9.55262604e+01 9.52514267e+01 9.98160629e+01 1.05923363e+02 1.06730110e+02 1.04409981e+02 1.00614937e+02 9.69814758e+01 9.65760803e+01 9.79794159e+01 9.84947891e+01 9.46746140e+01 9.09369583e+01 9.28074341e+01 9.84507828e+01 1.03463615e+02 1.04108292e+02 9.99952011e+01 9.90224075e+01 9.86756210e+01 1.02291985e+02 1.01809708e+02 9.99403763e+01 9.69323349e+01 9.50013428e+01 9.47757874e+01 9.35392151e+01 9.51583328e+01 9.80547562e+01 1.00082802e+02 9.99496307e+01 9.80266190e+01 9.80068817e+01 9.94191895e+01 1.00928093e+02 1.02262955e+02 1.01239021e+02 9.92711945e+01 9.78576202e+01 9.85864792e+01 9.99729004e+01 1.00169395e+02 9.97903137e+01 9.96658020e+01 9.97419357e+01 9.98771896e+01 9.98820114e+01 9.97786102e+01 9.96788635e+01 9.97182312e+01 1.00022812e+02 1.00708984e+02 1.01081924e+02 1.00915749e+02 1.00411240e+02 1.00261078e+02 1.00402321e+02 9.98306427e+01 9.87938156e+01 9.83177414e+01 9.85985107e+01 9.99992142e+01 1.00508270e+02 1.00911690e+02 1.00354309e+02 9.91938019e+01 9.85585403e+01 9.88774872e+01 1.00192520e+02 1.00951187e+02 1.00282310e+02 9.95536423e+01 9.93438034e+01 9.99372177e+01 1.00555870e+02 9.99918365e+01 9.94863434e+01 9.87725449e+01 9.85260468e+01 9.85613251e+01 9.77886353e+01 9.80799408e+01 9.81365280e+01 9.92189865e+01 9.85533752e+01 9.76528244e+01 9.74003754e+01 9.80883255e+01 9.85531998e+01 9.78164368e+01 9.73839493e+01 9.67177963e+01 9.46134109e+01 9.50244293e+01 9.61997223e+01 9.79939880e+01 9.58543549e+01 9.55002747e+01 9.57074966e+01 9.58761292e+01 9.54002304e+01 9.46877136e+01 9.47897263e+01 9.45254745e+01 9.52790298e+01 9.61366196e+01 9.66272049e+01 9.51947556e+01 9.49480515e+01 9.31587372e+01 9.40426483e+01 9.42681656e+01 9.53277893e+01 9.36344147e+01 9.36366577e+01 9.31411591e+01 9.66387787e+01 9.95682144e+01 1.01660133e+02 9.91044769e+01 9.75746765e+01 9.53405380e+01 9.49958572e+01 9.41117249e+01 9.53548508e+01 9.66097565e+01 9.51582413e+01 9.52441025e+01 9.55067749e+01 9.49849014e+01 9.22399673e+01 9.09171524e+01 9.23597412e+01 9.37050781e+01 9.30257034e+01 9.34949722e+01 9.47346649e+01 9.70234222e+01 9.72093506e+01 9.69736862e+01 9.45438080e+01 9.27657776e+01 8.68428650e+01 8.38398209e+01 8.28628922e+01 8.68911972e+01 9.07876434e+01 9.26789627e+01 9.48693695e+01 9.38609314e+01 8.81649628e+01 8.21155014e+01 8.30628738e+01 8.87988052e+01 9.36312790e+01 9.40528030e+01 9.32522583e+01 9.52315521e+01 9.51584702e+01 9.45705795e+01 9.26349335e+01 9.42179031e+01 9.49843140e+01 9.36618576e+01 9.15843353e+01 9.34326553e+01 9.89721756e+01 1.06079712e+02 1.06264824e+02 1.01321205e+02 9.32420959e+01 9.37033691e+01 9.58029480e+01 9.37464752e+01 9.23191147e+01 9.07194290e+01 9.89753571e+01 1.03384972e+02 1.05306244e+02 9.71690063e+01 9.01720810e+01 8.49379044e+01 9.00410233e+01 1.02017784e+02 1.15456894e+02 1.07995827e+02 9.21790771e+01 8.24813080e+01 8.67122269e+01 9.36871948e+01 9.46364975e+01 9.92668381e+01 1.01320862e+02 9.82030258e+01 8.92885818e+01 8.24903183e+01 8.16486588e+01 8.50840225e+01 9.17640839e+01 1.00419594e+02 9.83357239e+01 9.26187897e+01 8.48431168e+01 8.26894989e+01 8.22662735e+01 8.14074707e+01 7.68145142e+01 7.42056732e+01 7.41544952e+01 8.02014999e+01 8.31582794e+01 8.12444382e+01 7.62567139e+01 7.67260590e+01 8.04663925e+01 8.03075180e+01 7.63660278e+01 8.30721664e+01 8.86397324e+01 8.64506226e+01 7.42524796e+01 6.98727570e+01 7.60754013e+01 8.05787888e+01 8.25417252e+01 8.69694901e+01 9.16477966e+01 9.20156326e+01 9.23850861e+01 8.95793915e+01 8.65634918e+01 7.98078384e+01 7.88919601e+01 8.35458832e+01 8.15608292e+01 7.74825439e+01 7.46624680e+01 7.57643204e+01 7.67610168e+01 8.50857162e+01 9.39267654e+01 9.45747833e+01 8.30446701e+01 7.25017319e+01 7.13775253e+01 7.15071869e+01 7.11342926e+01 7.30316162e+01 7.58026276e+01 7.33714294e+01 6.32600632e+01 5.42116241e+01 5.37473412e+01 5.98569260e+01 6.65547638e+01 6.78334122e+01 6.44157104e+01 6.41136246e+01 6.67513809e+01 6.77205734e+01 5.28186684e+01 3.69212265e+01 3.73335991e+01 5.71318779e+01 7.40993652e+01 7.43841782e+01 5.67150421e+01 1.34173985e+01 -4.97219810e+01 -1.27328110e+02 -1.44719772e+02 -6.69417496e+01 -8.37789490e+02 -1.39203503e+03 2.81688171e+02 2.70554108e+02 2.57490326e+02 2.70968170e+02 3.11656830e+02 3.01536621e+02 2.45698914e+02 8.30172119e+01 -7.89437408e+01 -4.30957764e+03 -2.76302461e+04 -353220768. 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. 0. 0. 0. 0. 0. 0. 0. 0. 92172128. 55503048. 34729552. -6.12898877e+03 -2.57863892e+03 -1.23962532e+02 -5.73759613e+01 3.08448830e+01 1.26170111e+01 9.47824001e+00 9.46557713e+00 2.36285572e+01 4.68214760e+01 4.28217812e+01 3.96291161e+01 3.65091286e+01 3.77061348e+01 2.85706005e+01 1.46580286e+01 2.53701611e+01 4.92057762e+01 5.51331635e+01 4.01240273e+01 2.36613598e+01 3.37070160e+01 3.35245056e+01 2.88434391e+01 1.82815380e+01 1.41653614e+01 1.37816315e+01 1.88349171e+01 3.13911705e+01 3.50672684e+01 3.56351357e+01 3.11944103e+01 4.63600731e+01 6.85207520e+01 7.39414368e+01 6.19654961e+01 4.74016190e+01 5.16659775e+01 5.72441597e+01 5.75428200e+01 6.19179878e+01 6.60312195e+01 6.93361511e+01 7.09867172e+01 7.14047852e+01 6.45947266e+01 6.14516678e+01 5.61500778e+01 6.31943016e+01 5.93221359e+01 5.61219254e+01 5.75595779e+01 6.14297333e+01 6.67073288e+01 6.68599167e+01 5.87747192e+01 4.37243729e+01 2.38327045e+01 1.29494781e+01 1.76433201e+01 2.97507648e+01 3.89655266e+01 2.73471432e+01 1.43806944e+01 1.98156071e+01 3.77678833e+01 5.51638107e+01 5.56226425e+01 5.64429855e+01 6.61051407e+01 8.24252548e+01 6.79055786e+01 4.29879265e+01 2.16743908e+01 2.86898766e+01 4.00380783e+01 3.56317635e+01 3.58913231e+01 3.47043419e+01 3.79709320e+01 3.78321800e+01 3.86683922e+01 2.85377769e+01 2.55210552e+01 2.17774391e+01 2.86642265e+01 2.71266708e+01 8.67993927e+00 -1.11790934e+01 -7.04264593e+00 9.09820843e+00 2.74792614e+01 2.04897099e+01 1.19677401e+01 -1.58873987e+00 -5.40123606e+00 7.67199469e+00 2.90834885e+01 3.37747879e+01 2.47404823e+01 1.75666296e+00 -8.98031414e-01 1.77275467e+00 1.30155153e+01 2.33587685e+01 1.83895760e+01 2.47680035e+01 2.13019066e+01 2.72734356e+01 1.98072701e+01 1.95139980e+01 2.15621490e+01 1.17107821e+01 3.07876557e-01 1.17370200e+00 1.14851818e+01 2.56685047e+01 2.59314060e+01 2.97497177e+01 3.10170269e+01 3.52848663e+01 3.77192612e+01 3.37082710e+01 9.69915867e+00 -1.69749851e+01 -2.04808674e+01 -4.58064842e+00 1.64666729e+01 2.62216339e+01 3.53132477e+01 3.40531082e+01 2.34843349e+01 1.74484959e+01 2.54073792e+01 2.44375725e+01 2.28238544e+01 1.95931530e+01 1.87294369e+01 1.61824913e+01 1.34527731e+01 1.10616169e+01 1.40109844e+01 1.09798040e+01 6.96524143e+00 3.02750683e+00 2.71012354e+00 -1.11030281e-01 -2.61399174e+00 -3.67324877e+00 2.39598036e+00 7.06425047e+00 1.23155613e+01 1.18479147e+01 1.22772598e+01 1.61008396e+01 1.87447720e+01 1.09302702e+01 -2.17240524e+01 -3.97149391e+01 -4.11475258e+01 -2.95238590e+01 -1.70869007e+01 -1.68344326e+01 -9.70422268e+00 -6.92429638e+00 -8.94147682e+00 -1.14671307e+01 -1.15401869e+01 -8.20928574e+00 -5.83946705e+00 -1.31048691e+00 2.08547764e+01 3.68772621e+01 4.95413170e+01 4.44858322e+01 2.83532104e+01 7.69904375e+00 -1.27042122e+01 -1.11466389e+01 -8.69522381e+00 -4.17219687e+00 -5.16538239e+00 -1.90752423e+00 -4.48179674e+00 -4.78629112e+00 -1.91892779e+00 -5.59949303e+00 -7.86404276e+00 -8.71493435e+00 -5.08847189e+00 -3.20038748e+00 -1.41489191e+01 -1.92913895e+01 -2.42815361e+01 -2.13476696e+01 -1.24481020e+01 9.82992935e+00 3.50659294e+01 4.37567978e+01 4.08163986e+01 3.25969620e+01 3.75931168e+01 2.20438538e+01 2.95890141e+00 -2.06795692e+01 -2.45933952e+01 -2.43081989e+01 -1.99001350e+01 -1.80610619e+01 -1.94446812e+01 -2.73859043e+01 -2.81775303e+01 -2.66788540e+01 -1.99951267e+01 -1.92649021e+01 -1.90240917e+01 -3.79680862e+01 -5.83435249e+01 -5.33408089e+01 -3.55477524e+01 -1.54032984e+01 -7.13252020e+00 1.32348740e+00 1.81431828e+01 2.97300377e+01 2.25441208e+01 1.11751890e+01 -1.34525738e+01 -7.74770737e+00 -1.38382626e+00 6.55922794e+00 4.54659653e+00 -4.07967138e+00 -1.95422029e+00 -1.90695012e+00 -2.66159797e+00 -1.23068590e+01 -1.96184120e+01 -1.70071926e+01 -1.46223038e-01 1.98850899e+01 3.60661125e+01 4.32530937e+01 4.52292967e+00 -3.37835693e+01 -5.46323318e+01 -3.77259407e+01 -1.71526794e+01 -1.97924004e+01 -1.66778889e+01 -2.07119522e+01 -1.84869061e+01 -2.29905262e+01 -2.71463814e+01 -3.17163429e+01 -2.81806545e+01 -2.73531208e+01 -4.02793427e+01 -6.43780518e+01 -6.99213333e+01 -5.94192429e+01 -4.28980484e+01 -3.11612167e+01 -2.00880756e+01 -1.96871033e+01 -3.13020420e+01 -3.56705742e+01 -2.50156441e+01 -2.45341320e+01 -3.28851509e+01 -4.48219604e+01 -4.54916077e+01 -4.47439346e+01 -4.40596619e+01 -4.03072357e+01 -4.19649925e+01 -3.62234306e+01 -3.80874405e+01 -3.93876266e+01 -5.00698166e+01 -5.33947029e+01 -5.20038414e+01 -3.36114845e+01 -1.10946369e+01 -1.29930124e+01 -2.92022934e+01 -5.15048866e+01 -4.48993530e+01 -3.90796738e+01 -3.22281952e+01 -3.05489159e+01 -2.83399849e+01 -2.95937347e+01 -2.06336861e+01 -1.56983938e+01 -2.02881336e+01 -3.83817368e+01 -5.39691048e+01 -5.40779572e+01 -5.09827156e+01 -6.06374626e+01 -7.52312469e+01 -8.05631638e+01 -7.62839508e+01 -6.23646049e+01 -6.30648994e+01 -6.11833000e+01 -5.89900017e+01 -5.34426651e+01 -5.11540070e+01 -5.56128044e+01 -6.60031052e+01 -6.37026939e+01 -6.00871582e+01 -5.55108681e+01 -5.85463486e+01 -5.72898407e+01 -5.41538239e+01 -4.15766373e+01 -2.88601418e+01 -3.06302166e+01 -3.97973976e+01 -4.97408295e+01 -4.87990494e+01 -5.50528030e+01 -6.27707901e+01 -5.95262527e+01 -3.57777443e+01 -1.79256248e+01 -1.69333038e+01 -3.65615349e+01 -5.04759674e+01 -5.04737015e+01 -4.86837502e+01 -4.93978577e+01 -5.20032883e+01 -3.86035309e+01 -2.13319836e+01 -1.77857857e+01 -3.21783981e+01 -5.26784668e+01 -5.09030495e+01 -5.09722595e+01 -5.12513733e+01 -5.41521912e+01 -5.27267570e+01 -4.47386742e+01 -3.85270729e+01 -3.83416901e+01 -4.59938011e+01 -5.31157074e+01 -4.93039322e+01 -3.10847454e+01 -8.66795349e+00 -7.70012474e+00 -2.53333931e+01 -4.44615440e+01 -5.14473114e+01 -5.87697830e+01 -5.96585541e+01 -5.28628922e+01 -3.35711975e+01 -1.98453789e+01 -4.70544577e+00 -1.96080494e+00 -1.96661453e+01 -3.67596359e+01 -5.71300049e+01 -4.35352402e+01 -3.14519138e+01 -4.63117332e+01 -7.68452454e+01 -9.30934372e+01 -7.70927353e+01 -6.20291290e+01 -6.43379898e+01 -6.76226349e+01 -6.81073837e+01 -7.09422379e+01 -7.34399567e+01 -7.66346664e+01 -7.75912628e+01 -7.94388428e+01 -8.01160126e+01 -7.85025330e+01 -8.16560516e+01 -8.03748398e+01 -8.14663925e+01 -7.06210251e+01 -5.80913391e+01 -5.79132729e+01 -6.98472595e+01 -8.83796692e+01 -7.55955582e+01 -5.58565712e+01 -6.75060349e+01 -9.62374115e+01 -9.62534485e+01 -6.10691414e+01 -4.05185661e+01 -5.42242088e+01 -7.30980835e+01 -6.45939178e+01 -4.88697319e+01 -4.42121773e+01 -5.39453049e+01 -6.86776276e+01 -6.93011322e+01 -6.67318726e+01 -6.70845566e+01 -6.70891647e+01 -7.91919479e+01 -8.98288498e+01 -7.71536255e+01 -5.22396240e+01 -4.10137138e+01 -5.18451080e+01 -6.28015480e+01 -5.06625938e+01 -4.15619049e+01 -3.93939857e+01 -5.06747284e+01 -6.35279198e+01 -6.25047836e+01 -6.17503281e+01 -5.99776649e+01 -6.48215942e+01 -5.98077087e+01 -4.93416138e+01 -4.60997963e+01 -4.87105789e+01 -6.32554283e+01 -7.14560394e+01 -7.82371521e+01 -7.99189301e+01 -7.76819153e+01 -9.35717316e+01 -1.12983727e+02 -1.09238434e+02 -8.49151840e+01 -6.35260811e+01 -7.06333923e+01 -8.08647461e+01 -7.38481293e+01 -5.90075531e+01 -5.87152672e+01 -6.79576416e+01 -7.95891876e+01 -8.26105118e+01 -8.40041809e+01 -8.57045441e+01 -8.32579117e+01 -8.15765152e+01 -7.91393585e+01 -7.41290970e+01 -7.22473907e+01 -7.55224609e+01 -8.27728119e+01 -8.66326370e+01 -8.88653030e+01 -8.83001251e+01 -9.76556549e+01 -1.06404579e+02 -9.69296494e+01 -7.51145477e+01 -6.40233994e+01 -7.61293640e+01 -8.83237000e+01 -9.51302795e+01 -9.80926514e+01 -9.97800446e+01 -9.74766541e+01 -9.49518890e+01 -9.76982727e+01 -9.60505447e+01 -9.73402023e+01 -9.44751205e+01 -9.67485046e+01 -9.85102539e+01 -1.00594772e+02 -9.72678528e+01 -9.35542450e+01 -9.49042511e+01 -9.97545853e+01 -1.01792572e+02 -9.63633575e+01 -9.12650986e+01 -8.90462799e+01 -8.43963089e+01 -7.62653656e+01 -7.50028381e+01 -8.00157242e+01 -8.09262009e+01 -6.49296951e+01 -5.54821587e+01 -6.20359268e+01 -7.33262558e+01 -7.09789734e+01 -6.21475945e+01 -6.15280914e+01 -7.20821228e+01 -7.90721893e+01 -8.16423721e+01 -8.11663132e+01 -8.07536392e+01 -7.98177338e+01 -8.06718216e+01 -8.45889587e+01 -8.02069626e+01 -7.27115555e+01 -6.84260788e+01 -7.55428314e+01 -8.41171951e+01 -8.44757538e+01 -7.86466064e+01 -8.55174942e+01 -9.64632034e+01 -1.02486519e+02 -9.74086380e+01 -9.12102356e+01 -9.45250015e+01 -9.48381271e+01 -9.44773865e+01 -9.45513535e+01 -9.54121552e+01 -9.47096558e+01 -9.21079254e+01 -9.35980759e+01 -9.60996475e+01 -9.85846100e+01 -9.77899017e+01 -9.55880051e+01 -9.51234741e+01 -8.99534073e+01 -8.54946136e+01 -8.62549133e+01 -9.27556076e+01 -1.00648514e+02 -1.01685486e+02 -1.01684319e+02 -1.05177948e+02 -1.10750183e+02 -1.11113678e+02 -1.06855484e+02 -1.00245216e+02 -9.90763245e+01 -9.87902985e+01 -9.29715271e+01 -8.63462830e+01 -8.47428665e+01 -9.06395874e+01 -9.52961884e+01 -9.57642288e+01 -9.69433899e+01 -9.91537094e+01 -9.84641037e+01 -1.00596115e+02 -1.04857681e+02 -1.03238373e+02 -9.69929733e+01 -9.21069260e+01 -9.37536240e+01 -9.29844894e+01 -8.62104950e+01 -8.22319107e+01 -8.53869858e+01 -9.28900757e+01 -9.46132355e+01 -9.21787643e+01 -9.19288025e+01 -9.52981262e+01 -9.97156219e+01 -9.88937683e+01 -9.65617828e+01 -9.61351700e+01 -9.77276840e+01 -1.00632355e+02 -1.02212318e+02 -1.03101639e+02 -1.03410530e+02 -1.02106224e+02 -1.02768669e+02 -1.02379364e+02 -1.00477783e+02 -9.78191223e+01 -9.73254013e+01 -9.90911942e+01 -1.00504997e+02 -9.96394119e+01 -1.03604843e+02 -1.19263885e+02 -1.22516037e+02 -1.32837708e+02 -2.92733795e+02 -4.42322601e+02 -4.29718964e+02 -4.29814392e+02 -1.66540203e+01 -8.37271500e+00 -7.03445663e+01 -6.88856812e+01 -2.07908279e+02 -3.29049652e+02 -4.19949554e+02 -4.25139618e+02 -4.49646362e+02 -8.16741211e+02 -4.68411650e+06 0. 0. 0. 0. 0. 0. 0. 0. -602414912. -58188716. 37697876. 28972150. -78539936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.39530163e+09 -56100592. -2.50368384e+03 -1.35071228e+03 -1.27881250e+03 -1.25158362e+03 -1.53402267e+02 -9.87318115e+01 -1.53091629e+02 -1.37602570e+02 -1.49409515e+02 -1.46647049e+02 -1.45772415e+02 -1.47996628e+02 -1.49354065e+02 -1.48010010e+02 -1.46213928e+02 -1.47511703e+02 -1.51017868e+02 -1.52461792e+02 -1.48036636e+02 -1.41521118e+02 -1.41933395e+02 -1.49098022e+02 -1.57993454e+02 -1.62030014e+02 -1.58109924e+02 -1.58021545e+02 -1.59818924e+02 -1.58275757e+02 -1.54149597e+02 -1.51765762e+02 -1.57283875e+02 -1.71015213e+02 -1.72001877e+02 -1.62692307e+02 -1.47972412e+02 -1.43074142e+02 -1.44353958e+02 -1.43262970e+02 -1.39352127e+02 -1.37705231e+02 -1.44835403e+02 -1.62023087e+02 -1.71357407e+02 -1.65466370e+02 -1.52743423e+02 -1.45829269e+02 -1.45431488e+02 -1.48947800e+02 -1.54081329e+02 -1.52396347e+02 -1.55462433e+02 -1.58096191e+02 -1.53296082e+02 -1.38356201e+02 -1.23981911e+02 -1.30207016e+02 -1.55166199e+02 -1.65776291e+02 -1.56881485e+02 -1.38347763e+02 -1.39824829e+02 -1.53405716e+02 -1.55561020e+02 -1.43181503e+02 -1.29195450e+02 -1.33291885e+02 -1.54778885e+02 -1.68869080e+02 -1.61893204e+02 -1.45738815e+02 -1.42335815e+02 -1.44285858e+02 -1.45636002e+02 -1.38988434e+02 -1.32428635e+02 -1.38183167e+02 -1.41297134e+02 -1.36408600e+02 -1.23255455e+02 -1.21430389e+02 -1.28460007e+02 -1.41511353e+02 -1.51510696e+02 -1.55002640e+02 -1.44182404e+02 -1.38435898e+02 -1.40285095e+02 -1.27282623e+02 -1.06921944e+02 -9.84169846e+01 -1.21119095e+02 -1.54209259e+02 -1.69167908e+02 -1.54828110e+02 -1.25405609e+02 -1.00232407e+02 -9.20461273e+01 -9.84096451e+01 -1.04934395e+02 -1.04146599e+02 -1.13236305e+02 -1.36149948e+02 -1.51672379e+02 -1.43244446e+02 -1.23109749e+02 -1.16382957e+02 -1.24864708e+02 -1.41428665e+02 -1.48068054e+02 -1.32699326e+02 -1.21361809e+02 -1.22440086e+02 -1.26161636e+02 -1.12361397e+02 -9.03663406e+01 -9.00983810e+01 -1.12826370e+02 -1.34547409e+02 -1.29235016e+02 -1.07636749e+02 -9.18680115e+01 -9.38846893e+01 -1.11326996e+02 -1.30923065e+02 -1.40374756e+02 -1.28252487e+02 -1.28053894e+02 -1.39927551e+02 -1.40088974e+02 -1.19409073e+02 -1.00432472e+02 -1.02777496e+02 -1.25128616e+02 -1.37124619e+02 -1.25139496e+02 -1.10888748e+02 -1.02636658e+02 -1.13567131e+02 -1.09232086e+02 -8.91005020e+01 -8.11367111e+01 -1.07289589e+02 -1.55971893e+02 -1.79940475e+02 -1.63117523e+02 -1.34533432e+02 -1.27177490e+02 -1.30089493e+02 -1.38243988e+02 -1.35678360e+02 -1.37436752e+02 -1.52085876e+02 -1.72799881e+02 -1.77685928e+02 -1.52447586e+02 -1.05608734e+02 -8.87242432e+01 -1.13566147e+02 -1.39945129e+02 -1.35281479e+02 -1.21119469e+02 -1.36076675e+02 -1.69849274e+02 -1.64116196e+02 -1.33855591e+02 -1.06167931e+02 -1.35062149e+02 -1.90904358e+02 -2.19371719e+02 -1.89827484e+02 -1.39671448e+02 -1.16998436e+02 -1.20363197e+02 -1.14568520e+02 -1.05062538e+02 -1.16465240e+02 -1.51118423e+02 -1.91290649e+02 -1.65586365e+02 -1.25693710e+02 -8.85279541e+01 -1.03005066e+02 -1.23015099e+02 -1.39106522e+02 -1.46076157e+02 -1.44345367e+02 -1.58805817e+02 -1.74597351e+02 -1.62391891e+02 -1.23156334e+02 -9.16710281e+01 -1.11793205e+02 -1.58294342e+02 -1.88762497e+02 -1.61939514e+02 -1.15729507e+02 -9.32419815e+01 -9.89558258e+01 -9.87189636e+01 -6.82596588e+01 -5.59400635e+01 -8.71887589e+01 -1.33755142e+02 -1.35585068e+02 -1.04800079e+02 -6.90176468e+01 -6.47973785e+01 -7.15171280e+01 -8.92078094e+01 -1.05303429e+02 -1.08182777e+02 -1.20634178e+02 -1.38316284e+02 -1.21563339e+02 -8.69797821e+01 -7.13226395e+01 -7.74639587e+01 -1.07754684e+02 -1.10469978e+02 -9.74447098e+01 -8.73378906e+01 -8.99236374e+01 -1.11726677e+02 -9.41971664e+01 -7.10913467e+01 -5.62294197e+01 -5.82972794e+01 -9.19630508e+01 -1.08102875e+02 -8.80594711e+01 -4.31436386e+01 -3.95299683e+01 -7.16938858e+01 -1.08223526e+02 -1.09902031e+02 -9.08714600e+01 -9.36268539e+01 -1.08552246e+02 -1.08804482e+02 -7.40535507e+01 -5.30910568e+01 -8.04970703e+01 -1.07415314e+02 -8.75099335e+01 -6.31479378e+01 -6.87352753e+01 -9.22830658e+01 -1.14166550e+02 -9.85035400e+01 -1.06998024e+02 -1.13820656e+02 -1.22296471e+02 -1.28145264e+02 -1.38201843e+02 -1.42755814e+02 -1.02358101e+02 -8.15004959e+01 -6.95419846e+01 -1.09824593e+02 -1.02928444e+02 -1.03503975e+02 -1.18008072e+02 -1.44017792e+02 -1.53341782e+02 -9.87528076e+01 -6.25524635e+01 -5.84537392e+01 -1.09383514e+02 -1.21621391e+02 -1.11685371e+02 -9.58160553e+01 -9.63241425e+01 -1.29278320e+02 -1.06778008e+02 -8.55956421e+01 -3.99783287e+01 -2.76125526e+01 -3.23868294e+01 -6.04478188e+01 -9.11744843e+01 -7.59998703e+01 -4.61081047e+01 -2.34093952e+01 -3.80088043e+01 -2.06703300e+01 -1.56670704e+01 -4.48761520e+01 -9.27571945e+01 -9.97080536e+01 -4.54353447e+01 -2.30956974e+01 -5.06788445e+01 -9.80486450e+01 -8.21850662e+01 -5.19880104e+01 -4.14453354e+01 -5.33383904e+01 -7.64940567e+01 -7.34738235e+01 -8.35982285e+01 -5.59686737e+01 -4.21305695e+01 -3.90443611e+01 -5.38340111e+01 -6.34015846e+01 -4.52687416e+01 -3.04600220e+01 -2.43982849e+01 -1.22440739e+01 3.01432476e+01 5.60109291e+01 4.93557816e+01 2.49016476e+01 2.47450047e+01 5.29454193e+01 6.74903793e+01 3.85386162e+01 -1.52848959e+01 -2.58554993e+01 -1.40600672e+01 -1.39613066e+01 -3.64578247e+01 -7.55472260e+01 -8.10837479e+01 -7.98540726e+01 -4.74536667e+01 -2.79235210e+01 -2.00827160e+01 -1.96778545e+01 -1.59571123e+01 -3.10692334e+00 1.24381361e+01 1.33919697e+01 7.86620998e+00 3.35408249e+01 6.50495300e+01 5.28403320e+01 7.15228081e+00 -1.59746780e+01 -1.58668594e+01 -3.87394180e+01 -6.20566826e+01 -7.80348740e+01 -3.42762337e+01 -3.05668468e+01 -2.32015553e+01 -1.69558525e+01 -1.56550913e+01 -3.14397984e+01 -7.99897079e+01 -8.43759995e+01 -4.06149673e+01 1.17349377e+01 1.25090075e+01 -2.13497696e+01 -5.74769173e+01 -4.79534683e+01 -2.24387417e+01 1.29655571e+01 1.91055927e+01 1.56257057e+00 -2.54879551e+01 -7.60775299e+01 -9.36462784e+01 -1.00858063e+02 -9.65001144e+01 -9.21111908e+01 -9.28120728e+01 -5.04619217e+01 -5.19318428e+01 -4.48537331e+01 -4.59731445e+01 -4.66244202e+01 -6.99169083e+01 -1.46930984e+02 -1.67630920e+02 -1.22293869e+02 -1.37969980e+01 4.52944679e+01 -1.35469646e+01 -9.59892807e+01 -1.00729958e+02 -1.07183018e+01 8.67874527e+01 6.58146744e+01 -6.70151186e+00 -6.49890442e+01 -6.62039490e+01 -1.96312943e+01 -2.68060055e+01 -5.51298790e+01 -8.34095764e+01 -8.21829376e+01 -3.33668785e+01 -4.08162193e+01 -7.08372955e+01 -9.81558456e+01 -8.91014252e+01 -4.56912460e+01 -5.90170250e+01 -6.14348030e+01 -1.13528624e+01 5.64236412e+01 5.32770271e+01 -6.54268570e+01 -1.40277740e+02 -1.18575294e+02 -2.77179813e+01 2.25164223e+01 9.22529411e+00 -3.30523720e+01 -5.85218697e+01 -7.32584076e+01 -3.07052937e+01 -2.84586678e+01 -3.11804314e+01 -5.08165398e+01 -6.54123077e+01 -2.40794449e+01 -7.83474982e-01 5.38012276e+01 4.43703728e+01 1.54314804e+01 -2.84778709e+01 -9.32927933e+01 -1.12937706e+02 -6.92858963e+01 3.85789604e+01 1.01931145e+02 5.76667862e+01 -4.35330505e+01 -8.47264786e+01 -3.20117378e+00 9.93080750e+01 1.00643173e+02 1.14465942e+01 -3.66872406e+01 -3.17512722e+01 1.37152729e+01 1.15916815e+01 -6.83784580e+00 -3.78799210e+01 -6.01553574e+01 -5.94664116e+01 -8.91515961e+01 -9.66533966e+01 -5.55456963e+01 7.61907578e+00 4.39853783e+01 -5.78676891e+00 -5.40809288e+01 -4.48735237e+01 2.30466385e+01 9.14404907e+01 6.62252655e+01 -3.53285646e+00 -2.84777088e+01 2.85478020e+00 6.15844269e+01 4.86094017e+01 1.92383230e+00 -4.32422981e+01 -7.29889145e+01 -4.01705132e+01 -4.35070953e+01 -1.45839062e+01 -1.39305544e+01 -1.36893167e+01 -2.56627197e+01 -5.81560860e+01 -2.81175938e+01 1.13336477e+01 6.00715599e+01 4.23905907e+01 -2.55318737e+01 -7.75840683e+01 -5.41541939e+01 2.23066177e+01 7.98013916e+01 8.07579422e+01 3.28707466e+01 8.98530579e+00 3.41277003e+00 3.14646263e+01 1.73836365e+01 -4.64372587e+00 -3.15230904e+01 -7.03616257e+01 -6.97746353e+01 -2.68914471e+01 3.76925926e+01 5.36102715e+01 3.67800789e+01 7.12297630e+00 -3.47572250e+01 -5.87194939e+01 -1.57759399e+01 6.94185410e+01 1.07322266e+02 5.84587440e+01 -1.22149076e+01 -1.90345592e+01 5.78750000e+01 1.40866089e+02 1.33055923e+02 4.62108040e+01 -4.79881477e+01 -8.22391739e+01 -3.23878517e+01 1.69956169e+01 2.72200623e+01 1.12962408e+01 -5.34996605e+00 2.19165020e+01 1.02663050e+01 2.07564507e+01 4.70424500e+01 5.97576561e+01 6.33212967e+01 1.54648113e+01 1.74810677e+01 6.31356964e+01 1.26630394e+02 1.23100296e+02 2.49898586e+01 -4.28725090e+01 -2.20727825e+01 6.09852066e+01 1.16472160e+02 1.18551895e+02 5.60621109e+01 -8.51340199e+00 -3.84285774e+01 1.07896652e+01 4.39769478e+01 7.80535736e+01 7.69042664e+01 6.26514931e+01 6.89050064e+01 6.74220428e+01 1.16752518e+02 1.35247726e+02 1.35534485e+02 1.06682251e+02 3.79512520e+01 2.04195938e+01 5.66524010e+01 1.26226067e+02 1.43860352e+02 1.06344452e+02 5.08392754e+01 4.67103539e+01 8.96102905e+01 1.47119720e+02 1.58373306e+02 1.01857941e+02 4.80201340e+01 2.97961597e+01 7.12875595e+01 1.08516144e+02 1.01760460e+02 7.09879837e+01 3.54759712e+01 2.87712193e+01 2.57565346e+01 5.27037125e+01 9.57810745e+01 1.11823021e+02 7.17080536e+01 8.72850537e-01 -2.79856701e+01 1.78618717e+01 7.72472382e+01 1.13223381e+02 8.74152603e+01 4.21351814e+01 1.91864376e+01 3.21500626e+01 7.00594788e+01 6.94502716e+01 4.53050346e+01 1.30422812e+01 7.76740885e+00 4.79360657e+01 7.70284500e+01 7.52427750e+01 4.47962570e+01 5.47954798e+00 1.31714230e+01 1.23977566e+01 3.60135422e+01 6.12597046e+01 7.95259628e+01 8.45802612e+01 4.14054337e+01 1.86012497e+01 2.79182472e+01 6.36973267e+01 1.00153160e+02 7.69686737e+01 4.69073563e+01 1.88261528e+01 6.08190804e+01 1.33186768e+02 1.71064316e+02 1.44144913e+02 8.57535706e+01 6.57220078e+01 1.24959541e+02 2.02872650e+02 2.59203430e+02 4.73049866e+02 6.55744568e+02 1.83446143e+03 1.84103333e+03 3.38255200e+03 8.68585742e+03 -91836320. -38148644. -21558220. -24492244. -131928816. -469972736. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -262827248. 49404384. 1.41000371e+04 3.87960791e+03 1.25261963e+03 2.50515991e+02 3.62231293e+02 4.07277588e+02 2.80660034e+02 1.91889648e+02 1.79458160e+02 1.41350952e+02 1.00889977e+02 7.83106461e+01 8.25201950e+01 1.22716660e+02 1.53147522e+02 1.41372040e+02 9.15172424e+01 4.91411934e+01 5.79829750e+01 8.68066101e+01 1.08558746e+02 1.17510666e+02 1.24842171e+02 1.39927094e+02 1.14426033e+02 1.06851845e+02 1.30495636e+02 1.50409378e+02 1.21259834e+02 5.78409920e+01 3.56292343e+01 8.33906708e+01 1.41516129e+02 1.69597565e+02 1.50885391e+02 9.77815323e+01 5.82196884e+01 3.85207405e+01 7.36827240e+01 9.84453583e+01 1.04473419e+02 8.02763748e+01 6.32536354e+01 7.71540375e+01 7.51770935e+01 9.56510239e+01 1.16980728e+02 1.36663376e+02 1.20049004e+02 6.54803009e+01 5.96214828e+01 9.84451752e+01 1.53660477e+02 1.66625839e+02 1.25880775e+02 8.77461243e+01 8.33072891e+01 1.15673965e+02 1.32005295e+02 1.07071350e+02 6.27670975e+01 4.48728180e+01 6.08146820e+01 1.06694199e+02 1.42406403e+02 1.43316513e+02 1.11903351e+02 7.56322937e+01 5.04468117e+01 3.79203186e+01 4.75295181e+01 6.88033905e+01 9.70759888e+01 1.10000587e+02 1.00366623e+02 1.06885956e+02 1.35660736e+02 1.66533768e+02 1.64620193e+02 1.29954330e+02 1.07156624e+02 1.10081383e+02 1.23625725e+02 1.42530685e+02 1.57758316e+02 1.48503372e+02 1.17120224e+02 9.76927948e+01 1.15747276e+02 1.37984406e+02 1.32052872e+02 1.15710678e+02 1.13119087e+02 1.25822647e+02 1.19070709e+02 1.19829369e+02 1.30221573e+02 1.42040070e+02 1.37333176e+02 1.04328606e+02 1.00878548e+02 1.27472412e+02 1.72239029e+02 1.89214935e+02 1.63671570e+02 1.33463791e+02 1.18586761e+02 1.25685837e+02 1.34119690e+02 1.34025925e+02 1.28657532e+02 1.15625923e+02 1.09342056e+02 1.22894531e+02 1.49179367e+02 1.59152191e+02 1.50793381e+02 1.42074036e+02 1.41939743e+02 1.30985764e+02 1.31142029e+02 1.51849762e+02 1.77389587e+02 1.78055435e+02 1.41443726e+02 1.27560074e+02 1.44328766e+02 1.72818710e+02 1.76466049e+02 1.50449692e+02 1.29607391e+02 1.23734329e+02 1.30460464e+02 1.47906158e+02 1.61841415e+02 1.61931488e+02 1.42867981e+02 1.28968063e+02 1.39454636e+02 1.58523087e+02 1.67179459e+02 1.59682602e+02 1.49801559e+02 1.42858307e+02 1.32398026e+02 1.28087311e+02 1.33114609e+02 1.41195587e+02 1.43212692e+02 1.31333450e+02 1.28322876e+02 1.39799088e+02 1.62386642e+02 1.76982346e+02 1.69602661e+02 1.50294891e+02 1.34349594e+02 1.35605515e+02 1.43891678e+02 1.46402664e+02 1.44226776e+02 1.44402008e+02 1.39620010e+02 1.40248642e+02 1.41083878e+02 1.47804016e+02 1.59084213e+02 1.62757675e+02 1.64421371e+02 1.50825745e+02 1.46390610e+02 1.53290314e+02 1.60242111e+02 1.56857422e+02 1.42376099e+02 1.37333008e+02 1.41872650e+02 1.48395706e+02 1.53012512e+02 1.53702271e+02 1.51043549e+02 1.48730179e+02 1.47057739e+02 1.53616806e+02 1.51506744e+02 1.47998154e+02 1.41587616e+02 1.36971939e+02 1.33575577e+02 1.30183334e+02 1.36244125e+02 1.45428665e+02 1.51415817e+02 1.51380798e+02 1.46460114e+02 1.46295166e+02 1.51596985e+02 1.57929962e+02 1.59805817e+02 1.52650406e+02 1.45013565e+02 1.41948624e+02 1.43996887e+02 1.46688034e+02 1.47430847e+02 1.47615768e+02 1.47150604e+02 1.46254227e+02 1.47400909e+02 1.49739136e+02 1.51077866e+02 1.49987823e+02 1.49826462e+02 1.49722946e+02 1.48960846e+02 1.48472626e+02 1.49161072e+02 1.50167755e+02 1.50477203e+02 1.50532364e+02 1.50924637e+02 1.51180374e+02 1.51165100e+02 1.50922348e+02 1.50765244e+02 1.50852493e+02 1.51478714e+02 1.51892288e+02 1.51396774e+02 1.50336945e+02 1.49715256e+02 1.50520172e+02 1.51214783e+02 1.50952011e+02 1.50902878e+02 1.50952545e+02 1.50795090e+02 1.50799240e+02 1.50898972e+02 1.50970581e+02 1.50905045e+02 1.50247742e+02 1.49740295e+02 1.48424973e+02 1.48136398e+02 1.48266693e+02 1.49425171e+02 1.49602127e+02 1.48781937e+02 1.48741943e+02 1.48854797e+02 1.51229233e+02 1.52756561e+02 1.53004822e+02 1.52226852e+02 1.50250824e+02 1.50670654e+02 1.50434677e+02 1.50205307e+02 1.49217697e+02 1.49561127e+02 1.49890076e+02 1.49596191e+02 1.48279129e+02 1.47991257e+02 1.48086334e+02 1.47757935e+02 1.47236816e+02 1.45594574e+02 1.43986404e+02 1.43468674e+02 1.45801285e+02 1.46724808e+02 1.46801758e+02 1.45408447e+02 1.45105515e+02 1.43360901e+02 1.43426559e+02 1.44080353e+02 1.47180893e+02 1.47092606e+02 1.45543213e+02 1.43461044e+02 1.45128769e+02 1.44779861e+02 1.44606812e+02 1.43491150e+02 1.45889526e+02 1.46329575e+02 1.44847626e+02 1.43844284e+02 1.44572372e+02 1.44598755e+02 1.42913651e+02 1.44390228e+02 1.48852249e+02 1.49913879e+02 1.47891571e+02 1.45533142e+02 1.44965881e+02 1.46729523e+02 1.47038254e+02 1.47709183e+02 1.45736557e+02 1.44697754e+02 1.45493118e+02 1.46693069e+02 1.43470383e+02 1.40708282e+02 1.38214523e+02 1.40046066e+02 1.38380356e+02 1.33872253e+02 1.35706329e+02 1.39174728e+02 1.45217163e+02 1.43854477e+02 1.43814682e+02 1.44851196e+02 1.41789169e+02 1.42863861e+02 1.42598999e+02 1.44419144e+02 1.46288513e+02 1.48385376e+02 1.50780319e+02 1.47290741e+02 1.43283340e+02 1.41138290e+02 1.39372879e+02 1.39310196e+02 1.41902710e+02 1.44133026e+02 1.44196289e+02 1.46618622e+02 1.47602539e+02 1.45579620e+02 1.40308746e+02 1.37883240e+02 1.39534897e+02 1.42555359e+02 1.44882278e+02 1.46476425e+02 1.44182495e+02 1.40564178e+02 1.39965485e+02 1.41050293e+02 1.43704727e+02 1.43928757e+02 1.41786255e+02 1.36495529e+02 1.34992966e+02 1.30472443e+02 1.32468201e+02 1.28853638e+02 1.31943314e+02 1.31317047e+02 1.35226364e+02 1.33773865e+02 1.30136719e+02 1.34516998e+02 1.40221100e+02 1.35840103e+02 1.23366364e+02 1.19510162e+02 1.24050209e+02 1.30474167e+02 1.28361618e+02 1.17883018e+02 1.05151405e+02 1.06339127e+02 1.19213234e+02 1.31657822e+02 1.23373985e+02 1.12422935e+02 1.10590385e+02 1.19856682e+02 1.31346313e+02 1.25933167e+02 1.16535645e+02 1.10948875e+02 1.13274406e+02 1.17062225e+02 1.13113098e+02 1.02717850e+02 9.58078995e+01 1.04960449e+02 1.20004753e+02 1.25959030e+02 1.18160477e+02 1.16400589e+02 1.19327286e+02 1.23562454e+02 1.22464600e+02 1.14540733e+02 1.03346436e+02 1.04867058e+02 1.12196892e+02 1.25712677e+02 1.25394447e+02 1.25630508e+02 1.24551857e+02 1.37033661e+02 1.55282455e+02 1.59930008e+02 1.44065491e+02 1.25792892e+02 1.17946259e+02 1.14853012e+02 1.03505661e+02 1.02688713e+02 1.24390564e+02 1.47961548e+02 1.50954773e+02 1.33995834e+02 1.14230003e+02 1.16839348e+02 1.19415932e+02 1.31618317e+02 1.36961639e+02 1.30493301e+02 1.16807259e+02 9.99340286e+01 9.85923233e+01 9.63795700e+01 1.16035332e+02 1.38538223e+02 1.40493500e+02 1.27038971e+02 1.06717300e+02 9.51381607e+01 8.24901810e+01 8.46590805e+01 1.02044952e+02 1.09584244e+02 1.14435112e+02 1.11819550e+02 1.10456627e+02 1.09944908e+02 1.14940285e+02 1.22596634e+02 1.21196899e+02 1.00686333e+02 3.78610954e+01 -1.31558704e+01 -2.38298855e+01 2.00145550e+01 4.31891212e+01 -8.23849670e+02 -3.87872241e+03 -8.28658496e+03 100345072. -27297106. 37546556. 159366480. 174401680. 495519616. 29042484. -45076500. 52400016. -48749412. 1504559616. 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. 0. 0. 0. 0. 0. 0. 0. -105792512. 89272640. -2.92394121e+04 -1.21588125e+04 -1.30308606e+03 5.39682198e+01 4.13091705e+02 -3.76169067e+03 -2.23543018e+03 -4.97840515e+02 -2.40595169e+02 -1.40806320e+02 -2.42602482e+01 -4.79946470e+00 -9.25275135e+00 -3.62517357e+01 -2.78099823e+01 8.53267136e+01 1.96440765e+02 1.92709412e+02 7.88653336e+01 -9.55193710e+01 -1.19704308e+02 -2.41962921e+02 -2.99299164e+02 -3.00293518e+02 -1.98771439e+02 -1.67115097e+02 -2.56399689e+02 -2.76647705e+02 -2.66891083e+02 -2.39573151e+02 -1.66614746e+02 -2.37956963e+01 3.63553276e+01 5.73835602e+01 6.05407143e+01 6.90800476e+01 8.32578125e+01 9.63213959e+01 9.44788589e+01 8.38690796e+01 9.01602173e+01 9.63430405e+01 1.02224998e+02 1.05616508e+02 1.08323853e+02 1.00590347e+02 7.32994080e+01 5.20606575e+01 4.64028435e+01 5.97895317e+01 7.24990463e+01 8.08933487e+01 8.36163330e+01 7.56198273e+01 6.41778717e+01 6.42456589e+01 7.38807144e+01 8.27182617e+01 8.47464676e+01 9.20746384e+01 7.87616196e+01 5.83979149e+01 4.36441917e+01 3.61795845e+01 3.39235420e+01 2.75441742e+01 3.41328163e+01 4.47620201e+01 4.86064529e+01 5.34508553e+01 7.25349045e+01 8.21871338e+01 8.44603043e+01 7.31688919e+01 6.89073105e+01 7.09069138e+01 4.98659439e+01 2.43390827e+01 2.09967499e+01 3.08290443e+01 5.06595116e+01 1.43417101e+01 -1.82503319e+01 -3.06685810e+01 -1.07810764e+01 7.20473003e+00 6.06043386e+00 8.57393742e+00 1.68971119e+01 1.55204258e+01 -1.02767220e+01 -3.32720184e+01 -2.52716465e+01 1.09418163e+01 3.74094009e+01 4.60611877e+01 3.80563278e+01 3.39617538e+01 2.32421608e+01 4.47956696e+01 6.33535004e+01 5.69623299e+01 3.00621986e+01 1.90624733e+01 3.48369789e+01 4.67061348e+01 1.75999851e+01 -4.28893757e+00 -6.63426685e+00 1.96274338e+01 4.61138268e+01 5.88552628e+01 6.40683517e+01 6.17700768e+01 5.24297409e+01 4.53330383e+01 4.31196480e+01 5.01113815e+01 4.77891998e+01 3.70172348e+01 3.35039749e+01 3.30663185e+01 3.64101181e+01 2.84646931e+01 2.80448742e+01 2.29913502e+01 -5.50633335e+00 -3.86767120e+01 -3.32784576e+01 -5.90761852e+00 1.83295517e+01 -6.53545094e+00 -3.59617958e+01 -4.14690857e+01 -2.70787373e+01 -5.41288328e+00 4.63346291e+00 1.30901890e+01 2.36146946e+01 1.82781506e+01 1.17109537e+01 7.79951286e+00 1.72854443e+01 3.11167088e+01 3.30072823e+01 2.19556007e+01 8.80261612e+00 8.40844059e+00 7.53359985e+00 8.47586823e+00 -6.80219746e+00 -3.80729141e+01 -7.20306396e+01 -6.69962311e+01 -4.09775467e+01 -1.26931801e+01 -4.08634377e+01 -6.82259750e+01 -6.54879532e+01 -3.71743507e+01 -1.17340832e+01 -1.76871033e+01 -1.70287590e+01 -1.84693794e+01 -1.21130848e+01 -1.18992891e+01 -8.29794216e+00 -4.19229126e+00 -3.69033146e+00 -1.91662216e+01 -3.35208702e+01 -2.93909798e+01 -1.56308918e+01 9.50498521e-01 9.48265266e+00 1.62236767e+01 -6.13976002e+00 -3.56243362e+01 -4.06300774e+01 -2.61273994e+01 -1.29234571e+01 -1.31051445e+01 -5.42898607e+00 -2.56355000e+01 -5.89373665e+01 -6.64147568e+01 -4.45291481e+01 -1.34452915e+01 -1.49755478e+01 -1.79650707e+01 -1.89947376e+01 -1.40473528e+01 -2.13975811e+01 -2.19051952e+01 -4.81061592e+01 -6.95957031e+01 -7.32544403e+01 -4.76783333e+01 -2.47522049e+01 -2.55209084e+01 -2.44049091e+01 -4.82993889e+01 -6.96341476e+01 -7.30774155e+01 -3.87104149e+01 -1.15025396e+01 -1.80625134e+01 -2.82992687e+01 -3.25137558e+01 -2.65333061e+01 -1.72970581e+01 -1.49155750e+01 -1.39631720e+01 -1.84761562e+01 -1.95757961e+01 -1.68919907e+01 -1.88186703e+01 -5.62593555e+00 -1.71101391e+00 5.62198544e+00 1.88131356e+00 -4.83622742e+00 -3.83079934e+00 -4.09274769e+00 -8.84604275e-01 -4.75366640e+00 -9.88804913e+00 -8.61422443e+00 -1.59275446e+01 -1.46668386e+01 -1.22834635e+01 -2.93838739e+00 -1.64902759e+00 -1.20524645e+01 -1.64968624e+01 -2.25100899e+01 -1.27094374e+01 -1.90231247e+01 -1.55749598e+01 -2.91832142e+01 -3.47156334e+01 -3.85593147e+01 -1.88357811e+01 3.06136680e+00 -1.12271442e+01 -4.85110397e+01 -8.15200882e+01 -7.82516708e+01 -6.39862404e+01 -5.37972488e+01 -5.05423317e+01 -5.94428444e+01 -6.96388168e+01 -7.32960129e+01 -6.46321716e+01 -5.15214996e+01 -4.08878326e+01 -3.18803787e+01 -2.91864014e+01 -3.42500916e+01 -4.55258102e+01 -5.24992638e+01 -5.88546562e+01 -5.84332733e+01 -6.16021538e+01 -4.67226524e+01 -4.24193878e+01 -3.63964348e+01 -5.08589363e+01 -7.15820618e+01 -9.05786285e+01 -8.51562119e+01 -7.25051880e+01 -5.88661118e+01 -5.90021896e+01 -5.76599388e+01 -7.32351074e+01 -9.27352371e+01 -9.95228424e+01 -9.39812393e+01 -7.34516220e+01 -6.15999451e+01 -4.69478226e+01 -5.64553719e+01 -6.64962616e+01 -6.92573853e+01 -5.87263336e+01 -5.43862038e+01 -5.38196487e+01 -6.43523102e+01 -7.00002670e+01 -7.02314606e+01 -7.33452759e+01 -7.24511337e+01 -1.00189087e+02 -1.21116005e+02 -1.17424698e+02 -8.90189056e+01 -6.33629112e+01 -7.29653015e+01 -8.23083801e+01 -8.13971634e+01 -7.85262527e+01 -9.53233185e+01 -1.17537888e+02 -1.18126526e+02 -9.70491638e+01 -7.39958801e+01 -8.19736862e+01 -8.30218353e+01 -7.73925323e+01 -6.40128555e+01 -6.44641266e+01 -7.21680222e+01 -8.46082230e+01 -8.18421402e+01 -6.87693634e+01 -6.42132950e+01 -6.68361893e+01 -7.05424652e+01 -6.26515884e+01 -7.51623459e+01 -9.24900894e+01 -9.77075348e+01 -1.09190071e+02 -1.28645355e+02 -1.49705231e+02 -1.54460632e+02 -1.45902008e+02 -1.49039810e+02 -1.25198143e+02 -1.15754105e+02 -9.13114929e+01 -7.81487427e+01 -5.47701302e+01 -5.67475395e+01 -6.64595566e+01 -7.26135254e+01 -7.14953690e+01 -7.03677063e+01 -7.10338211e+01 -6.87897491e+01 -6.25679131e+01 -8.11419449e+01 -1.07566116e+02 -1.25657440e+02 -1.25919006e+02 -1.08795990e+02 -1.01839149e+02 -9.53827438e+01 -8.27150421e+01 -9.88552399e+01 -1.05003021e+02 -1.16454453e+02 -1.16454933e+02 -1.20297981e+02 -1.31343689e+02 -1.13470413e+02 -9.84330444e+01 -9.26702728e+01 -1.10468857e+02 -1.18648079e+02 -1.09668007e+02 -9.24064560e+01 -1.06771851e+02 -1.21064491e+02 -1.27896805e+02 -1.16794327e+02 -1.07859528e+02 -1.29174271e+02 -1.47987549e+02 -1.40584518e+02 -1.08751366e+02 -9.51981659e+01 -1.15522263e+02 -1.32373367e+02 -1.09365944e+02 -8.08004684e+01 -9.77128677e+01 -1.28628265e+02 -1.43411453e+02 -1.34048279e+02 -1.24640503e+02 -1.29397278e+02 -1.41503754e+02 -1.54293594e+02 -1.45205856e+02 -1.20074089e+02 -9.86336060e+01 -1.00335129e+02 -1.05683945e+02 -1.11977043e+02 -1.09237045e+02 -1.10217026e+02 -1.16854942e+02 -1.32407410e+02 -1.29739716e+02 -1.11567680e+02 -1.07783432e+02 -1.15093178e+02 -1.34951202e+02 -1.36090118e+02 -1.28045822e+02 -1.24133713e+02 -1.16385696e+02 -1.15813751e+02 -1.06838051e+02 -9.65527954e+01 -9.26152573e+01 -9.70591736e+01 -1.29055786e+02 -1.50504715e+02 -1.33157349e+02 -9.41243134e+01 -9.16390381e+01 -1.26426125e+02 -1.39406326e+02 -1.19919174e+02 -1.08211746e+02 -1.20520447e+02 -1.28872864e+02 -1.23137680e+02 -1.07236427e+02 -1.16561844e+02 -1.28480148e+02 -1.36947632e+02 -1.27349510e+02 -1.14476738e+02 -1.14182991e+02 -1.15891342e+02 -1.30292206e+02 -1.39373245e+02 -1.39831818e+02 -1.25397652e+02 -1.26102066e+02 -1.57140030e+02 -1.77888031e+02 -1.71659485e+02 -1.44176025e+02 -1.43188324e+02 -1.55000854e+02 -1.41543106e+02 -1.11893753e+02 -9.86291809e+01 -1.16103973e+02 -1.31883575e+02 -1.31376053e+02 -1.26076241e+02 -1.30497192e+02 -1.28812973e+02 -1.31361099e+02 -1.30675980e+02 -1.27417320e+02 -1.21464287e+02 -1.16145676e+02 -1.21736053e+02 -1.27111801e+02 -1.36881134e+02 -1.38219376e+02 -1.40424484e+02 -1.47875336e+02 -1.52903580e+02 -1.47656403e+02 -1.36162674e+02 -1.36023270e+02 -1.48632492e+02 -1.50666824e+02 -1.44696014e+02 -1.51466217e+02 -1.78291977e+02 -1.97591995e+02 -1.87337265e+02 -1.60187057e+02 -1.52493866e+02 -1.61426743e+02 -1.62026627e+02 -1.49662186e+02 -1.39414719e+02 -1.38060333e+02 -1.34992599e+02 -1.36994705e+02 -1.41667877e+02 -1.41099533e+02 -1.31813049e+02 -1.27965256e+02 -1.45267044e+02 -1.56361038e+02 -1.49806824e+02 -1.36932022e+02 -1.49170593e+02 -1.59983795e+02 -1.50316269e+02 -1.25011169e+02 -1.09820564e+02 -1.13899162e+02 -1.17346817e+02 -1.21243813e+02 -1.18930984e+02 -1.22401337e+02 -1.21560005e+02 -1.29290512e+02 -1.31683395e+02 -1.32087097e+02 -1.24426781e+02 -1.30173737e+02 -1.51640533e+02 -1.66093414e+02 -1.71521576e+02 -1.65934555e+02 -1.57050446e+02 -1.46586288e+02 -1.38056320e+02 -1.39907578e+02 -1.39775635e+02 -1.39539993e+02 -1.39809982e+02 -1.40830032e+02 -1.38348038e+02 -1.39732635e+02 -1.42617996e+02 -1.43442917e+02 -1.43797058e+02 -1.41863083e+02 -1.52955688e+02 -1.63188690e+02 -1.64293396e+02 -1.54601074e+02 -1.46649628e+02 -1.47520294e+02 -1.48208511e+02 -1.47760620e+02 -1.48075821e+02 -1.50126022e+02 -1.51759232e+02 -1.55324905e+02 -1.60432449e+02 -1.56481293e+02 -1.49790848e+02 -1.46074463e+02 -1.60692322e+02 -1.70312363e+02 -1.66506485e+02 -1.53461700e+02 -1.52294327e+02 -1.59303970e+02 -1.58618927e+02 -1.53341156e+02 -1.47489716e+02 -1.54783539e+02 -1.59508881e+02 -1.63772629e+02 -1.64523056e+02 -1.56812973e+02 -1.51448868e+02 -1.51456253e+02 -1.65722656e+02 -1.72451569e+02 -1.65795700e+02 -1.53755478e+02 -1.55392029e+02 -1.62837616e+02 -1.63470581e+02 -1.58011124e+02 -1.51692413e+02 -1.56011017e+02 -1.60542786e+02 -1.62599152e+02 -1.58931076e+02 -1.54011780e+02 -1.52577682e+02 -1.57412384e+02 -1.61977890e+02 -1.63349640e+02 -1.58684143e+02 -1.52779816e+02 -1.55012756e+02 -1.58665924e+02 -1.60316833e+02 -1.57532700e+02 -1.56789581e+02 -1.60037674e+02 -1.58576080e+02 -1.54510788e+02 -1.49677856e+02 -1.49199707e+02 -1.49380188e+02 -1.51916641e+02 -1.55310013e+02 -1.56037659e+02 -1.55194412e+02 -1.53119400e+02 -1.59457977e+02 -1.75859253e+02 -1.83155960e+02 -2.00466415e+02 -4.04627563e+02 -1.16426526e+03 -2.57557544e+03 -33968180. 49141656. 4.67992365e-01 -7.91602554e+01 -2.87347382e+02 -2.77945435e+02 -8.35924316e+02 -1.79519519e+03 -39407868. 330658784. -243484976. 86649528. 166590096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.39530163e+09 -56100592. -2.50368384e+03 -1.35071228e+03 -1.27881250e+03 -8.86966125e+02 -5.20909973e+02 -2.90581146e+02 -3.03537842e+02 -3.39996399e+02 -3.52282501e+02 -3.26281128e+02 -3.15035553e+02 -3.04008606e+02 -3.03222107e+02 -3.10760284e+02 -3.14180145e+02 -3.11313324e+02 -3.14361755e+02 -3.20337433e+02 -3.27101807e+02 -3.19550598e+02 -3.03983459e+02 -2.94850891e+02 -2.99164978e+02 -3.10598633e+02 -3.18326141e+02 -3.16769775e+02 -3.13944092e+02 -3.17938812e+02 -3.22994141e+02 -3.18800507e+02 -3.07288635e+02 -3.00977112e+02 -3.04621918e+02 -3.14976715e+02 -3.18511597e+02 -3.09517578e+02 -2.95236542e+02 -2.88877441e+02 -2.95507629e+02 -2.94105469e+02 -2.85678253e+02 -2.91419067e+02 -3.08405853e+02 -3.22714417e+02 -3.05305695e+02 -2.75818329e+02 -2.65150208e+02 -2.80625031e+02 -2.97282257e+02 -3.07228851e+02 -3.09258698e+02 -3.07556427e+02 -3.05754547e+02 -3.09297180e+02 -3.04559265e+02 -2.79149719e+02 -2.57761932e+02 -2.64089874e+02 -2.89222229e+02 -3.04987885e+02 -2.93835022e+02 -2.74891724e+02 -2.66781372e+02 -2.82697327e+02 -2.88674255e+02 -2.82006042e+02 -2.87308014e+02 -3.05342163e+02 -3.25562103e+02 -3.20012970e+02 -2.84017609e+02 -2.73278870e+02 -2.86289154e+02 -3.14867065e+02 -3.10596283e+02 -2.87384003e+02 -2.90827209e+02 -3.04745453e+02 -3.16445404e+02 -3.02191895e+02 -2.69926056e+02 -2.54727020e+02 -2.65596954e+02 -2.98823395e+02 -3.17641266e+02 -3.08888458e+02 -2.92260345e+02 -2.97601074e+02 -3.16003235e+02 -3.14008301e+02 -2.89504913e+02 -2.78732269e+02 -3.04386200e+02 -3.36192200e+02 -3.35929688e+02 -2.97677185e+02 -2.64934296e+02 -2.64222015e+02 -2.87635132e+02 -2.93294922e+02 -2.87234131e+02 -3.07513672e+02 -3.44860474e+02 -3.64157104e+02 -3.27229675e+02 -2.71542114e+02 -2.41070770e+02 -2.59195251e+02 -2.90004395e+02 -3.25408417e+02 -3.46843475e+02 -3.40208313e+02 -3.31768829e+02 -3.29339996e+02 -3.22209534e+02 -2.85552887e+02 -2.52510986e+02 -2.73016907e+02 -3.30692932e+02 -3.56302185e+02 -3.30628204e+02 -2.71078125e+02 -2.46240372e+02 -2.68713989e+02 -2.94054138e+02 -2.99938751e+02 -2.92655334e+02 -3.16172852e+02 -3.64846527e+02 -3.64051361e+02 -3.17200958e+02 -2.66090057e+02 -2.70543915e+02 -2.97749298e+02 -3.22965393e+02 -3.25243866e+02 -3.18490509e+02 -2.96177246e+02 -2.83879089e+02 -3.11273315e+02 -3.24993073e+02 -2.98542816e+02 -2.72958954e+02 -2.64042328e+02 -2.80093842e+02 -2.80709717e+02 -2.62601807e+02 -2.61079010e+02 -2.75304260e+02 -2.96799164e+02 -3.10970703e+02 -2.88483765e+02 -2.77228485e+02 -2.80941711e+02 -3.00092163e+02 -2.76417755e+02 -2.06928650e+02 -1.74487961e+02 -2.27515564e+02 -2.89826324e+02 -2.99389008e+02 -2.62921173e+02 -2.41593765e+02 -2.40205139e+02 -2.37358536e+02 -2.10737579e+02 -1.80612885e+02 -1.69810135e+02 -1.88107635e+02 -2.37257401e+02 -2.67806244e+02 -2.36546158e+02 -2.14608444e+02 -2.24080246e+02 -2.63173859e+02 -2.35903824e+02 -1.76559265e+02 -1.74767258e+02 -2.03627335e+02 -2.30924530e+02 -1.91090271e+02 -1.22954033e+02 -8.32719421e+01 -1.25710060e+02 -1.99919800e+02 -2.43364914e+02 -2.35660507e+02 -2.42867065e+02 -2.64349792e+02 -2.49889954e+02 -1.95942871e+02 -1.34620148e+02 -1.49175156e+02 -1.95926743e+02 -2.76385925e+02 -3.06038666e+02 -2.88767883e+02 -2.30099274e+02 -1.77483292e+02 -1.76802917e+02 -1.57282623e+02 -1.37329590e+02 -1.42422394e+02 -2.07470657e+02 -2.72501343e+02 -2.44126022e+02 -1.45649124e+02 -9.05012054e+01 -1.44792725e+02 -2.46866226e+02 -2.83964508e+02 -2.38940567e+02 -1.85626648e+02 -2.06295624e+02 -2.45063553e+02 -2.33746338e+02 -1.77576096e+02 -1.62859039e+02 -2.11877777e+02 -2.90817993e+02 -3.06683929e+02 -2.66524811e+02 -2.19296860e+02 -2.20819519e+02 -2.40788635e+02 -2.38552322e+02 -2.05009216e+02 -2.19533905e+02 -2.61743011e+02 -2.74572540e+02 -2.74069214e+02 -2.18147537e+02 -2.07277695e+02 -2.11992584e+02 -2.18861511e+02 -2.17301712e+02 -1.77448257e+02 -2.07012161e+02 -2.58005829e+02 -2.81510742e+02 -2.52441605e+02 -1.44214203e+02 -9.13276062e+01 -9.79698639e+01 -2.18550995e+02 -2.79244446e+02 -2.87414001e+02 -2.37768677e+02 -2.04706985e+02 -2.35036423e+02 -2.20894928e+02 -1.88939362e+02 -1.67206741e+02 -2.05571045e+02 -2.38725098e+02 -1.82374130e+02 -1.09731621e+02 -1.21247856e+02 -1.54414795e+02 -1.74147781e+02 -1.49025970e+02 -1.01304146e+02 -1.53404709e+02 -1.88787491e+02 -2.24357529e+02 -1.95093628e+02 -1.34074173e+02 -1.09505836e+02 -9.10301971e+01 -1.44632858e+02 -1.73592804e+02 -1.86204391e+02 -1.34520645e+02 -1.29268250e+02 -1.35649719e+02 -1.25369202e+02 -8.22557526e+01 -6.39913826e+01 -1.33030716e+02 -1.75545898e+02 -1.76964111e+02 -1.17690712e+02 -1.35139908e+02 -1.54426132e+02 -1.83252228e+02 -1.96248337e+02 -1.84134949e+02 -1.89357162e+02 -1.24779854e+02 -9.64631729e+01 -7.80633774e+01 -8.60277100e+01 -1.06859764e+02 -1.30129181e+02 -1.98490616e+02 -2.26423401e+02 -1.98128967e+02 -9.73588486e+01 -6.42215805e+01 -8.39205780e+01 -1.21380569e+02 -1.25574326e+02 -1.43537811e+02 -2.23341736e+02 -2.64138794e+02 -2.32662460e+02 -1.30591919e+02 -9.45778427e+01 -1.35006821e+02 -1.84520248e+02 -1.88826111e+02 -1.36905518e+02 -1.36795502e+02 -1.28392380e+02 -1.87904037e+02 -2.06043961e+02 -2.09155762e+02 -1.50973083e+02 -1.33721588e+02 -1.79751770e+02 -2.26645920e+02 -1.90146835e+02 -1.12775543e+02 -1.28457047e+02 -1.76994904e+02 -1.88653458e+02 -1.44494171e+02 -1.39855988e+02 -2.01180069e+02 -2.30746445e+02 -2.05608963e+02 -1.27334801e+02 -1.33115616e+02 -1.55392090e+02 -1.84997849e+02 -1.59950790e+02 -1.24089287e+02 -1.35378845e+02 -1.24993668e+02 -1.71580841e+02 -1.75912628e+02 -1.91384842e+02 -1.55159851e+02 -1.46052917e+02 -1.67363358e+02 -1.96359695e+02 -1.68716934e+02 -1.07372650e+02 -9.73935242e+01 -1.00302376e+02 -6.75635529e+01 9.11299324e+00 -9.47773075e+00 -7.32099991e+01 -9.57688370e+01 -5.77552032e+01 2.42067289e+00 -6.25529099e+01 -9.14926529e+01 -1.35981445e+02 -1.62481201e+02 -1.68792297e+02 -1.33877716e+02 -3.02081833e+01 -1.19760008e+01 -7.95811157e+01 -1.55019699e+02 -1.11720238e+02 -1.98369236e+01 3.90630875e+01 -2.64502106e+01 -7.22352829e+01 -6.43402481e+01 -3.39289513e+01 5.68630409e+00 5.80256920e+01 1.44055893e+02 1.25462563e+02 4.76523933e+01 1.36344242e+01 4.77191277e+01 9.48610916e+01 1.09055042e+01 -3.95406532e+01 -6.65616608e+01 -6.02626991e+01 -4.44948006e+01 -2.49503446e+00 1.24537659e+02 1.50553391e+02 5.60799026e+01 -1.04808960e+02 -1.39192215e+02 -2.64332557e+00 1.12655487e+02 1.17992111e+02 3.53236389e+01 -1.10262241e+01 2.00694885e+01 9.57744598e+01 1.41980560e+02 9.70630341e+01 -2.23767414e+01 -5.97778664e+01 -9.79139519e+00 7.13496475e+01 1.60039078e+02 1.51881668e+02 1.07726646e+02 3.60091734e+00 -1.06443695e+02 -1.45986221e+02 -7.63070984e+01 7.86597595e+01 1.71144180e+02 9.66002731e+01 -1.65426579e+01 -1.30604706e+01 1.09868225e+02 2.26516937e+02 1.81856873e+02 5.97050781e+01 -4.37601280e+01 -4.92854462e+01 2.75466461e+01 9.78535843e+01 1.41156021e+02 6.93836746e+01 3.24442863e+01 3.84645867e+00 5.32351799e+01 9.11807404e+01 3.77982101e+01 -2.65684547e+01 -9.23025970e+01 -9.18512955e+01 -6.13151665e+01 5.06729746e+00 1.17370712e+02 1.54595947e+02 8.04652405e+01 -7.80054092e+01 -1.56588211e+02 -9.19185333e+01 6.39033928e+01 1.60974991e+02 1.33891708e+02 6.77733307e+01 5.12339935e+01 1.06450600e+02 1.36954071e+02 1.53573074e+02 7.85097580e+01 2.17701874e+01 -3.63464012e+01 -4.71473999e+01 -1.32295961e+01 3.28972321e+01 1.01400887e+02 9.28509445e+01 5.61352005e+01 -2.11211605e+01 -2.05012608e+01 4.38156586e+01 1.21885368e+02 9.39821701e+01 1.99278126e+01 -1.53519135e+01 4.69853096e+01 1.39847427e+02 1.40792938e+02 7.35311432e+01 -2.73661308e+01 -2.05552464e+01 5.70078201e+01 1.28702820e+02 1.81582184e+02 9.85176926e+01 6.51923981e+01 2.40987015e+01 2.08094902e+01 4.40440512e+00 -1.01465197e+01 3.65622482e+01 2.51005611e+01 -1.66504936e+01 -1.20202694e+01 4.80720406e+01 1.52043381e+02 1.91410309e+02 1.33259247e+02 -3.25218010e+00 -1.07716125e+02 -9.62646332e+01 4.08865776e+01 1.80559967e+02 2.24086700e+02 1.31403336e+02 1.83696594e+01 -7.41779089e+00 6.54972305e+01 1.58441071e+02 1.32485352e+02 6.48334808e+01 3.96903872e+00 -5.01320422e-01 2.78535271e+01 7.88602753e+01 1.46741333e+02 1.40416656e+02 7.77587738e+01 -1.41348791e+01 -3.53009911e+01 3.68776321e+01 1.34260788e+02 1.37702988e+02 5.35710449e+01 -2.24264455e+00 1.68136768e+01 7.45842209e+01 1.02120827e+02 1.24878967e+02 1.00028938e+02 7.52166977e+01 8.56327820e+01 1.00385544e+02 1.34276993e+02 9.71818161e+01 5.57768059e+01 1.25259838e+01 -1.72476254e+01 3.25464363e+01 6.52565155e+01 1.43325989e+02 1.71082275e+02 1.36334946e+02 6.49671707e+01 5.04753227e+01 1.19637566e+02 1.99691818e+02 1.83081299e+02 1.36046692e+02 5.29531898e+01 3.14839020e+01 7.41070938e+01 1.22595474e+02 1.50085999e+02 7.98344650e+01 2.77465954e+01 -2.53256454e+01 -1.67294178e+01 5.53933640e+01 4.68272667e+01 2.30966434e+01 -4.98960037e+01 -4.82489281e+01 -1.94144688e+01 3.45482254e+01 1.34439606e+02 1.74978851e+02 1.51770340e+02 6.77490616e+01 4.05474358e+01 9.62099380e+01 1.80076462e+02 1.68911575e+02 9.08618088e+01 1.96385975e+01 5.40503883e+01 1.38807007e+02 2.21098022e+02 2.26168991e+02 1.56244171e+02 7.34651184e+01 5.46811829e+01 5.50969124e+01 7.73767242e+01 1.06742805e+02 1.59971329e+02 1.68431458e+02 1.40652786e+02 1.23094093e+02 1.56776047e+02 2.40099777e+02 2.75251495e+02 2.11475830e+02 1.14312042e+02 7.01830902e+01 1.29022522e+02 2.20640182e+02 2.41678955e+02 1.92044952e+02 1.03950172e+02 9.23350143e+01 1.40775528e+02 1.72228027e+02 1.89380707e+02 1.41175415e+02 1.20749596e+02 1.34428146e+02 1.50524536e+02 2.02588821e+02 1.87366257e+02 1.84794815e+02 1.09230392e+02 3.14171333e+01 -5.89642906e+00 6.58452320e+00 9.76800308e+01 1.72705475e+02 1.99628540e+02 9.62305450e+01 -1.29904846e+02 -9.07666321e+01 2.26528549e+02 -2.69561743e+03 -7.56222900e+03 -198983744. -617869120. -49712756. -192484304. 579302528. -29793058. -195099296. 783052096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -262827248. 49404384. 1.41000371e+04 6.22114600e+03 -2.52528857e+03 -2.14856689e+03 -5.50155457e+02 -4.12316498e+02 -7.76336288e+01 5.66329117e+01 1.72603958e+02 2.07219223e+02 1.72004227e+02 1.52700577e+02 1.89785141e+02 2.76399811e+02 2.79355011e+02 2.39857620e+02 1.81119492e+02 1.91885345e+02 2.51816437e+02 3.11194366e+02 3.19135834e+02 2.72148865e+02 1.93208572e+02 1.83085464e+02 2.39473236e+02 3.06041565e+02 3.06759155e+02 2.54622208e+02 2.51395889e+02 2.85857300e+02 2.97918823e+02 2.64977417e+02 2.27825272e+02 2.30304794e+02 2.26607864e+02 2.07148026e+02 2.06543030e+02 2.47287598e+02 3.18539093e+02 3.24067627e+02 2.74657715e+02 2.29114136e+02 2.29162262e+02 2.79751129e+02 3.39305908e+02 3.32052368e+02 2.64309143e+02 1.74768066e+02 1.79489502e+02 2.54617325e+02 3.03633972e+02 3.11560303e+02 2.68674164e+02 2.50902283e+02 2.45436951e+02 2.41369354e+02 2.51759689e+02 2.75670502e+02 3.15966522e+02 3.05302338e+02 2.59902985e+02 2.52036453e+02 2.82709564e+02 3.38608002e+02 3.36811859e+02 3.05388611e+02 2.64035217e+02 2.41064636e+02 2.87093567e+02 3.43973846e+02 3.90740143e+02 3.64674591e+02 3.04279449e+02 2.82807098e+02 3.16082672e+02 3.45196228e+02 3.44463043e+02 2.89166779e+02 2.79883270e+02 2.87886322e+02 3.18963287e+02 3.11394592e+02 3.14553497e+02 3.26362549e+02 3.10647705e+02 2.76458313e+02 2.62504791e+02 3.01272827e+02 3.60920319e+02 3.66948151e+02 3.44504913e+02 3.01358215e+02 2.74074524e+02 2.74745453e+02 3.07669434e+02 3.32927704e+02 3.29583282e+02 2.79506500e+02 2.63314545e+02 2.95287323e+02 3.36719666e+02 3.31880890e+02 2.86574493e+02 2.60856842e+02 2.66678467e+02 2.72685944e+02 2.82678833e+02 2.99834747e+02 3.33981079e+02 3.30979828e+02 3.03681183e+02 2.82384430e+02 2.86031250e+02 3.13886566e+02 3.17266846e+02 2.99087799e+02 2.85106110e+02 2.71488037e+02 2.76349396e+02 3.01105682e+02 3.23867188e+02 3.32148743e+02 2.93159363e+02 2.76877319e+02 2.91767426e+02 3.03893341e+02 3.06620331e+02 2.89655457e+02 2.94671478e+02 2.97654053e+02 2.87610992e+02 2.83731476e+02 2.91102966e+02 3.22935669e+02 3.22837189e+02 2.99173950e+02 2.82372528e+02 2.84033600e+02 3.06545166e+02 3.04184998e+02 2.88545197e+02 2.80936768e+02 2.71955414e+02 2.86130066e+02 3.04838593e+02 3.24725159e+02 3.22636749e+02 3.03061035e+02 2.99726074e+02 3.06309723e+02 3.07338470e+02 3.00248260e+02 2.87296143e+02 2.79431519e+02 2.75639282e+02 2.75794830e+02 2.87847565e+02 2.98877502e+02 3.20551086e+02 3.26058868e+02 3.24187469e+02 3.11545441e+02 3.11941833e+02 3.23852356e+02 3.37332611e+02 3.28215393e+02 3.08353363e+02 2.92502960e+02 2.91764587e+02 3.11535645e+02 3.23194702e+02 3.21402039e+02 3.09393799e+02 3.05752380e+02 3.13901245e+02 3.13158783e+02 3.14876190e+02 3.15671112e+02 3.15680359e+02 3.06281891e+02 2.95258514e+02 2.94150299e+02 2.99243835e+02 3.08052643e+02 3.14209412e+02 3.15703796e+02 3.13655090e+02 3.13884796e+02 3.20950562e+02 3.28276489e+02 3.25329559e+02 3.13911346e+02 3.03978821e+02 3.02430908e+02 3.10671997e+02 3.13271515e+02 3.14123444e+02 3.07018097e+02 3.08539062e+02 3.12962524e+02 3.18796783e+02 3.22500854e+02 3.22867218e+02 3.25872345e+02 3.22358887e+02 3.16679596e+02 3.12617920e+02 3.13074249e+02 3.17127075e+02 3.17155640e+02 3.14444672e+02 3.11506134e+02 3.09208435e+02 3.11228058e+02 3.15204834e+02 3.18101288e+02 3.16588867e+02 3.13749207e+02 3.13455505e+02 3.14351013e+02 3.14567169e+02 3.14357971e+02 3.14001740e+02 3.14009735e+02 3.14278381e+02 3.14487244e+02 3.14489471e+02 3.13839081e+02 3.12388092e+02 3.11566681e+02 3.11761230e+02 3.12731537e+02 3.12781281e+02 3.12546478e+02 3.13723938e+02 3.15772034e+02 3.16604431e+02 3.15891571e+02 3.13124207e+02 3.11986053e+02 3.11241302e+02 3.12244324e+02 3.14378296e+02 3.15809021e+02 3.15345123e+02 3.13023468e+02 3.10939941e+02 3.11926300e+02 3.13088654e+02 3.12556183e+02 3.10646729e+02 3.09332153e+02 3.11018555e+02 3.12137482e+02 3.13127899e+02 3.13378113e+02 3.12567444e+02 3.14122040e+02 3.12964111e+02 3.12520538e+02 3.10025452e+02 3.11101196e+02 3.12847198e+02 3.12714600e+02 3.11612366e+02 3.10953461e+02 3.12970856e+02 3.12970825e+02 3.14076721e+02 3.17401215e+02 3.15571289e+02 3.12925110e+02 3.09461060e+02 3.13335999e+02 3.13676727e+02 3.13457825e+02 3.13804260e+02 3.14282104e+02 3.14263031e+02 3.13085083e+02 3.13546112e+02 3.12445374e+02 3.10722321e+02 3.08941254e+02 3.10766937e+02 3.10008698e+02 3.14702667e+02 3.11539337e+02 3.12727661e+02 3.09615692e+02 3.14775696e+02 3.13900024e+02 3.13279846e+02 3.05999573e+02 3.00958405e+02 2.96468414e+02 2.99197418e+02 3.03317688e+02 3.06765320e+02 3.06740936e+02 3.06199890e+02 3.01793549e+02 2.99844696e+02 3.03395050e+02 3.03946594e+02 3.01849701e+02 3.01133087e+02 3.06707153e+02 3.10024078e+02 3.06578217e+02 3.02933777e+02 3.03033752e+02 3.00074463e+02 2.95630981e+02 2.92050354e+02 2.91207458e+02 2.94245972e+02 2.99183502e+02 3.02004211e+02 3.10965118e+02 3.13859680e+02 3.18158752e+02 3.08666260e+02 3.01936920e+02 2.95252197e+02 2.89560272e+02 2.88616211e+02 2.99633118e+02 3.14082794e+02 3.12176331e+02 3.00226379e+02 2.88504028e+02 2.89090057e+02 2.90945709e+02 2.85608063e+02 2.82910370e+02 2.81836334e+02 2.87311127e+02 2.83889343e+02 2.83302032e+02 2.86752167e+02 2.91108368e+02 2.85901367e+02 2.71803162e+02 2.56490326e+02 2.53927887e+02 2.63096405e+02 2.78994202e+02 2.77778717e+02 2.71025299e+02 2.71357086e+02 2.75866028e+02 2.82796234e+02 2.66400757e+02 2.56514160e+02 2.49100128e+02 2.65364075e+02 2.78675049e+02 2.89994080e+02 2.77239746e+02 2.54632950e+02 2.32094223e+02 2.47410248e+02 2.75687347e+02 2.87191833e+02 2.77836792e+02 2.66452240e+02 2.63564911e+02 2.52521698e+02 2.41608826e+02 2.48356033e+02 2.65593140e+02 2.78464600e+02 2.81138123e+02 2.72197571e+02 2.59229065e+02 2.42410461e+02 2.45257065e+02 2.58733582e+02 2.71750854e+02 2.74857178e+02 2.74161224e+02 2.75591431e+02 2.81861267e+02 2.88340759e+02 2.88418762e+02 2.76888306e+02 2.65405304e+02 2.68735504e+02 2.75611877e+02 2.74244446e+02 2.65403076e+02 2.64971893e+02 2.74262634e+02 2.59912537e+02 2.47649551e+02 2.49033157e+02 2.76429840e+02 2.85562103e+02 2.68969208e+02 2.56016724e+02 2.49330261e+02 2.41279022e+02 2.29475845e+02 2.29559326e+02 2.26010651e+02 2.25764481e+02 2.29433289e+02 2.46601776e+02 2.50633759e+02 2.42489929e+02 2.40233246e+02 2.49996017e+02 2.52297256e+02 2.49438278e+02 2.48802658e+02 2.30662323e+02 2.15037399e+02 2.12251541e+02 2.35619385e+02 2.58376251e+02 2.52697296e+02 2.51963058e+02 2.47484482e+02 2.47589188e+02 2.38805969e+02 2.46080704e+02 2.63039307e+02 2.77531433e+02 2.76787933e+02 2.65987335e+02 2.49756638e+02 2.46769211e+02 2.51569305e+02 2.55719604e+02 2.45583618e+02 2.43387695e+02 2.70234344e+02 3.01859680e+02 3.02611572e+02 2.63500763e+02 2.27433151e+02 2.25609512e+02 2.63446381e+02 3.49406464e+02 4.63290436e+02 6.06494324e+02 6.44994568e+02 5.66735168e+02 3.72084302e+03 9.56298926e+03 90718984. 46596104. 255343664. 40227700. 515740128. -505740128. -84828240. 56905364. -35013028. -87598776. -177720176. -470063296. 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. 0. 0. 0. 0. 0. 0. -105792512. 89272640. -2.92394121e+04 -1.21588125e+04 -1.30308606e+03 4.75519922e+03 3.46452173e+03 9.67197876e+02 4.67022064e+02 2.81846008e+02 2.43233032e+02 2.75060303e+02 2.73528290e+02 2.42123154e+02 1.97583176e+02 1.95347168e+02 1.88374298e+02 1.87763947e+02 1.87104034e+02 2.09831345e+02 2.39645782e+02 2.10618057e+02 1.64079163e+02 1.51096024e+02 1.85473236e+02 2.06779984e+02 1.87913574e+02 1.82111618e+02 1.87448486e+02 2.01314713e+02 2.13066879e+02 2.16221390e+02 2.09048615e+02 1.81405380e+02 1.71194443e+02 1.63569473e+02 1.76251099e+02 1.43637161e+02 1.01328590e+02 9.14057770e+01 1.14175430e+02 1.44058273e+02 1.31457535e+02 1.16651077e+02 1.10610298e+02 1.00032005e+02 9.55676727e+01 8.75357971e+01 8.22348557e+01 8.03336945e+01 9.05767670e+01 9.59491272e+01 9.80020370e+01 8.46788330e+01 8.87218552e+01 9.72483597e+01 9.44390106e+01 8.62008438e+01 7.20171661e+01 7.42223053e+01 8.92010345e+01 1.19321793e+02 1.53668381e+02 1.69948318e+02 1.53539398e+02 1.27054565e+02 1.10661743e+02 1.35197449e+02 1.59785812e+02 1.48698364e+02 1.10364967e+02 7.02373886e+01 6.52023773e+01 6.57681580e+01 4.77441711e+01 1.70344753e+01 3.97755775e+01 9.02007065e+01 1.27383911e+02 1.11064903e+02 8.72728882e+01 9.03437881e+01 8.69069290e+01 8.62193222e+01 8.08819122e+01 8.06759644e+01 8.03367996e+01 9.59392166e+01 9.99592667e+01 1.05224617e+02 8.78990250e+01 9.19359741e+01 1.28315109e+02 1.72254089e+02 1.57254028e+02 1.17925369e+02 7.88894653e+01 9.53448792e+01 1.12133896e+02 1.33568039e+02 1.45461151e+02 1.20934708e+02 7.90086594e+01 6.58326111e+01 7.98696365e+01 1.24016373e+02 1.21256721e+02 1.10530426e+02 8.25729523e+01 6.44130783e+01 7.65866470e+01 6.77591324e+01 6.97825317e+01 5.37976646e+01 6.64494247e+01 6.92450562e+01 6.53427505e+01 8.18330917e+01 1.05656830e+02 9.98657150e+01 7.32985535e+01 4.25880737e+01 3.91587868e+01 3.50875816e+01 3.26625748e+01 2.95452118e+01 1.48479223e+01 1.61219463e+01 5.99058113e+01 1.14031334e+02 1.16670380e+02 8.26288605e+01 3.82656517e+01 1.27172575e+01 -5.23509979e+00 1.66977882e+00 2.25757713e+01 2.97798023e+01 1.02820892e+01 1.22404661e+01 1.52131453e+01 2.32744923e+01 2.73459988e+01 3.10145874e+01 2.86643143e+01 2.60523338e+01 2.35475998e+01 2.79879971e+01 3.64318199e+01 3.73200417e+01 3.56425209e+01 4.04089165e+01 4.45061760e+01 4.83938332e+01 3.38903580e+01 2.49641132e+01 1.38077574e+01 1.13481684e+01 6.42112303e+00 -7.45682812e+00 -1.13151102e+01 3.05115318e+00 6.86474304e+01 1.01694313e+02 1.03190353e+02 7.80964737e+01 5.55714569e+01 5.09998322e+01 3.65439034e+01 2.70654831e+01 3.08314552e+01 3.58351250e+01 3.42513809e+01 3.04098988e+01 2.08945160e+01 1.07347498e+01 -3.68186646e+01 -7.32473297e+01 -1.02200912e+02 -9.73603516e+01 -6.10154991e+01 -2.19104424e+01 1.70014153e+01 1.60379848e+01 6.81495571e+00 1.90767813e+00 -1.16916525e+00 -8.53311062e+00 -1.27320633e+01 -1.51182508e+01 -2.48468189e+01 -1.94027920e+01 -1.70568199e+01 -1.32965279e+01 -1.98436203e+01 -2.40046406e+01 -7.83623743e+00 6.34913146e-01 6.60601091e+00 -1.43980670e+00 -1.94943924e+01 -5.83353043e+01 -1.10263206e+02 -1.29918976e+02 -1.31150269e+02 -1.13822487e+02 -1.27913795e+02 -9.57911148e+01 -5.87627602e+01 -1.45941582e+01 -1.29529791e+01 -1.55988369e+01 -2.56992683e+01 -3.14325848e+01 -2.54754066e+01 -1.10153780e+01 -1.38918715e+01 -2.15035534e+01 -3.89936333e+01 -4.04011803e+01 -4.47788849e+01 -6.68234587e+00 3.86531029e+01 2.32210712e+01 -1.86079216e+01 -6.31730270e+01 -7.80401764e+01 -9.23076630e+01 -1.38400574e+02 -1.62960068e+02 -1.52396347e+02 -1.23877823e+02 -7.72135696e+01 -8.41084747e+01 -9.82926559e+01 -1.17193626e+02 -1.22004120e+02 -1.05411507e+02 -1.04783607e+02 -1.03903587e+02 -1.08020012e+02 -9.27394333e+01 -7.92168503e+01 -8.31420670e+01 -1.19093567e+02 -1.65535461e+02 -2.02022766e+02 -2.15951065e+02 -1.34496277e+02 -5.79927101e+01 -1.61667080e+01 -5.23564262e+01 -9.41124039e+01 -9.65964127e+01 -1.06370865e+02 -1.03151344e+02 -1.05624969e+02 -9.38066864e+01 -9.06888657e+01 -8.29112473e+01 -9.04277191e+01 -9.24110794e+01 -6.74419632e+01 -2.55970364e+01 -1.48096905e+01 -4.04254417e+01 -7.15754700e+01 -9.57702560e+01 -1.20574242e+02 -1.24659233e+02 -1.03844444e+02 -1.00804092e+02 -1.27034775e+02 -1.27163269e+02 -1.07198700e+02 -8.32861023e+01 -7.96797638e+01 -8.94986420e+01 -9.51566315e+01 -1.03298019e+02 -1.00940651e+02 -1.09019516e+02 -1.08381714e+02 -1.07014313e+02 -9.09840317e+01 -8.89059525e+01 -9.34412231e+01 -1.30599136e+02 -1.73243668e+02 -1.64750061e+02 -1.34701248e+02 -1.01354042e+02 -1.16286972e+02 -1.20022522e+02 -1.29734055e+02 -1.41125595e+02 -1.51708862e+02 -1.55490845e+02 -1.76734222e+02 -1.87868683e+02 -1.85096039e+02 -1.46253784e+02 -1.15259285e+02 -1.12377831e+02 -1.22971733e+02 -1.03372078e+02 -7.66546555e+01 -6.92892227e+01 -7.83923492e+01 -1.07762939e+02 -1.04034111e+02 -1.10976555e+02 -1.16002937e+02 -1.31542480e+02 -1.39128204e+02 -1.34894226e+02 -1.16344559e+02 -1.21352173e+02 -1.27134369e+02 -1.34764236e+02 -1.30236221e+02 -1.36121460e+02 -1.44449768e+02 -1.71868500e+02 -1.99621262e+02 -1.97400696e+02 -1.85836243e+02 -1.68656036e+02 -1.70708527e+02 -1.54716370e+02 -1.40569077e+02 -1.50621506e+02 -2.03116699e+02 -2.37232285e+02 -2.38434692e+02 -1.93547409e+02 -1.69319031e+02 -1.75438416e+02 -1.87388016e+02 -1.88291092e+02 -1.75967224e+02 -1.93609009e+02 -2.29183777e+02 -2.42453934e+02 -2.17448883e+02 -1.78582504e+02 -1.83339096e+02 -1.85638367e+02 -1.87953613e+02 -1.83903320e+02 -1.87261169e+02 -2.00404541e+02 -2.10531143e+02 -2.18685211e+02 -2.02262878e+02 -1.93412109e+02 -1.94306854e+02 -2.33774582e+02 -2.79969635e+02 -2.85893402e+02 -2.52689560e+02 -2.13407394e+02 -2.07032257e+02 -1.94370804e+02 -1.90813141e+02 -2.01386124e+02 -2.49606369e+02 -2.82448364e+02 -3.16485565e+02 -3.18697540e+02 -2.87931305e+02 -2.54179428e+02 -2.14994888e+02 -2.44644821e+02 -2.66853882e+02 -2.36258377e+02 -1.73253021e+02 -1.45279327e+02 -1.79230042e+02 -2.13212723e+02 -2.07907974e+02 -2.00820450e+02 -1.97327454e+02 -1.96444046e+02 -1.93906738e+02 -1.92161804e+02 -1.89289627e+02 -1.88707825e+02 -1.87728668e+02 -1.90950378e+02 -1.86566391e+02 -1.92657944e+02 -1.96239212e+02 -2.21249557e+02 -2.42666443e+02 -2.39925873e+02 -2.14578125e+02 -1.82595047e+02 -2.12843201e+02 -2.51771835e+02 -2.30164841e+02 -1.69060623e+02 -1.67463165e+02 -2.38260117e+02 -2.81745880e+02 -2.56497742e+02 -2.23285919e+02 -2.39278931e+02 -2.73937805e+02 -2.83289948e+02 -2.68296967e+02 -2.40218262e+02 -2.40663239e+02 -2.43173340e+02 -2.41950760e+02 -2.43039154e+02 -2.20569061e+02 -2.02066650e+02 -2.26028488e+02 -2.74549774e+02 -2.99831024e+02 -2.87335327e+02 -2.64212433e+02 -2.88219666e+02 -3.09033295e+02 -3.14942291e+02 -2.94886353e+02 -2.65448029e+02 -2.69368622e+02 -2.72267548e+02 -2.79043274e+02 -2.65659088e+02 -2.72657349e+02 -2.93118286e+02 -3.02801788e+02 -3.01871765e+02 -2.72850006e+02 -2.58826355e+02 -2.47840714e+02 -2.49255234e+02 -2.53794617e+02 -2.18845520e+02 -1.80528976e+02 -1.92743011e+02 -2.44491714e+02 -2.85598083e+02 -2.73376068e+02 -2.53095856e+02 -2.68787933e+02 -2.96505157e+02 -2.98250732e+02 -2.80172119e+02 -2.59324280e+02 -2.52914322e+02 -2.52213852e+02 -2.51561798e+02 -2.60462402e+02 -2.63968262e+02 -2.68362976e+02 -2.79229889e+02 -2.85293884e+02 -2.80446075e+02 -2.68110321e+02 -2.58896576e+02 -2.57135071e+02 -2.58925842e+02 -2.43500122e+02 -2.25319901e+02 -2.47744324e+02 -2.90678741e+02 -3.12533173e+02 -2.87389221e+02 -2.63352997e+02 -2.51505539e+02 -2.46919922e+02 -2.44224869e+02 -2.50576859e+02 -2.58068604e+02 -2.54383179e+02 -2.56202850e+02 -2.54059158e+02 -2.57874268e+02 -2.53803329e+02 -2.53075363e+02 -2.49831253e+02 -2.60205017e+02 -2.68007355e+02 -2.64092041e+02 -2.53571808e+02 -2.49501633e+02 -2.62539185e+02 -2.75280548e+02 -2.82876709e+02 -2.94512665e+02 -3.11643616e+02 -3.13400055e+02 -3.01867310e+02 -3.00940948e+02 -3.34891266e+02 -3.55759460e+02 -3.41262299e+02 -3.17091980e+02 -3.21475098e+02 -3.40970398e+02 -3.44443573e+02 -3.25847656e+02 -3.10143219e+02 -3.05961700e+02 -3.03998749e+02 -3.08893799e+02 -3.10186798e+02 -3.09796997e+02 -3.02455841e+02 -3.15217133e+02 -3.28632599e+02 -3.36789978e+02 -3.21873352e+02 -3.08366241e+02 -3.11612549e+02 -3.25332611e+02 -3.14093903e+02 -2.90182556e+02 -2.78526642e+02 -2.86935608e+02 -3.00184906e+02 -2.95630615e+02 -2.96696228e+02 -2.96346741e+02 -2.95541565e+02 -2.93448029e+02 -2.95080261e+02 -3.01746674e+02 -3.00461395e+02 -2.97042542e+02 -2.91958954e+02 -2.93955383e+02 -2.98637451e+02 -2.98074799e+02 -3.08001862e+02 -3.18123016e+02 -3.18443115e+02 -3.07439819e+02 -2.91401154e+02 -2.88674011e+02 -2.87843628e+02 -2.80464447e+02 -2.70263947e+02 -2.71432190e+02 -2.81387390e+02 -2.94130127e+02 -2.97129700e+02 -2.97579102e+02 -3.10809204e+02 -3.24479248e+02 -3.27860657e+02 -3.17015717e+02 -3.09337555e+02 -3.09156372e+02 -3.07322937e+02 -3.02876495e+02 -3.03858704e+02 -2.99268097e+02 -2.91586639e+02 -2.95982178e+02 -3.08936096e+02 -3.17985474e+02 -3.14491272e+02 -3.16349701e+02 -3.31526978e+02 -3.39975952e+02 -3.35074768e+02 -3.19364471e+02 -3.16266388e+02 -3.20854034e+02 -3.22323853e+02 -3.15443268e+02 -3.06427460e+02 -3.07773376e+02 -3.13094849e+02 -3.14814209e+02 -3.11583984e+02 -3.05735443e+02 -3.02552551e+02 -3.00999115e+02 -3.01573425e+02 -3.04655731e+02 -3.04162994e+02 -3.03518158e+02 -3.07381805e+02 -3.12943085e+02 -3.15290680e+02 -3.11938538e+02 -3.08892242e+02 -3.11212067e+02 -3.02924744e+02 -2.73447205e+02 -2.65489960e+02 -2.31841522e+02 9.50462112e+01 4.98334869e+02 -63534160. -51011248. -1.99611206e+03 -9.82385620e+02 -4.08544128e+02 -4.17672607e+02 -1.06506805e+02 -1.96730053e+00 -44103736. -500997376. -95892992. -58033076. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -669568320. -669568320. -334784160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.39530163e+09 -56100592. -69213064. 231219792. -1.48288586e+03 -7.30297607e+02 -3.90970184e+02 -5.77277344e+02 -3.03167877e+02 -3.08818268e+02 -2.85638947e+02 -2.87961609e+02 -2.90482147e+02 -2.87603790e+02 -2.85677338e+02 -2.88873810e+02 -2.93370605e+02 -2.90934448e+02 -2.82860260e+02 -2.78859161e+02 -2.84334045e+02 -2.96327026e+02 -2.97028900e+02 -2.87158569e+02 -2.73758606e+02 -2.69806213e+02 -2.75083893e+02 -2.73411743e+02 -2.67156342e+02 -2.67292908e+02 -2.73034454e+02 -2.78069000e+02 -2.69515778e+02 -2.53464478e+02 -2.49293976e+02 -2.61605621e+02 -2.75818268e+02 -2.83717194e+02 -2.84156555e+02 -2.88916290e+02 -2.96605469e+02 -3.00020966e+02 -2.89348450e+02 -2.61034454e+02 -2.42346497e+02 -2.48560883e+02 -2.69232025e+02 -2.85635864e+02 -2.85314545e+02 -2.77045410e+02 -2.67787598e+02 -2.70546356e+02 -2.66228943e+02 -2.59610229e+02 -2.65568634e+02 -2.88032501e+02 -3.12984650e+02 -3.07996613e+02 -2.70304047e+02 -2.55013733e+02 -2.66154968e+02 -2.90866516e+02 -2.86799316e+02 -2.62805542e+02 -2.60834686e+02 -2.81187744e+02 -3.05966492e+02 -2.99439728e+02 -2.63702393e+02 -2.37311600e+02 -2.44855804e+02 -2.65339294e+02 -2.74505890e+02 -2.69159821e+02 -2.69737579e+02 -2.84940918e+02 -3.00181396e+02 -2.91456818e+02 -2.79720154e+02 -2.83498627e+02 -2.98821350e+02 -3.05091309e+02 -2.96351379e+02 -2.80209290e+02 -2.62567810e+02 -2.55617584e+02 -2.66001526e+02 -2.74230896e+02 -2.72311920e+02 -2.89119568e+02 -3.18781006e+02 -3.33036530e+02 -3.03166046e+02 -2.53601685e+02 -2.26466660e+02 -2.40012527e+02 -2.79078888e+02 -3.22599304e+02 -3.36428497e+02 -3.26192871e+02 -3.16123413e+02 -3.23701965e+02 -3.10928162e+02 -2.73049347e+02 -2.42050018e+02 -2.50920853e+02 -2.83087769e+02 -2.94201996e+02 -2.83095337e+02 -2.56774567e+02 -2.49329803e+02 -2.67236938e+02 -2.79525787e+02 -2.78850708e+02 -2.73043549e+02 -2.92271027e+02 -3.31210876e+02 -3.38272156e+02 -3.05077057e+02 -2.63504974e+02 -2.62283722e+02 -2.90044647e+02 -3.15584473e+02 -3.18003052e+02 -2.91853119e+02 -2.61424164e+02 -2.47550110e+02 -2.63151428e+02 -2.59370880e+02 -2.36903778e+02 -2.32828339e+02 -2.63565460e+02 -2.95858398e+02 -2.94504944e+02 -2.63310547e+02 -2.47593430e+02 -2.64104431e+02 -2.80050690e+02 -2.90296478e+02 -2.74142181e+02 -2.82469025e+02 -3.06415588e+02 -3.17801819e+02 -2.79749542e+02 -2.01262970e+02 -1.63606384e+02 -1.91153931e+02 -2.40808212e+02 -2.53514420e+02 -2.40842911e+02 -2.21006012e+02 -2.29433136e+02 -2.26830856e+02 -2.04997940e+02 -1.66912094e+02 -1.56800598e+02 -1.96160172e+02 -2.70573395e+02 -3.09088501e+02 -2.64111694e+02 -2.19245316e+02 -2.15216919e+02 -2.38452103e+02 -2.15107834e+02 -1.57940979e+02 -1.64254684e+02 -2.16625351e+02 -2.69499359e+02 -2.33111084e+02 -1.52018829e+02 -1.02281990e+02 -1.30856369e+02 -1.88737030e+02 -2.22639145e+02 -2.21614822e+02 -2.33542343e+02 -2.44810959e+02 -2.30614349e+02 -1.79159378e+02 -1.20739067e+02 -1.54048553e+02 -2.08245102e+02 -2.60795532e+02 -2.48689209e+02 -2.17838043e+02 -1.89018372e+02 -1.73728455e+02 -1.67571472e+02 -1.47471207e+02 -1.15781410e+02 -1.36785583e+02 -1.95269180e+02 -2.51787659e+02 -2.31913940e+02 -1.60485718e+02 -1.20144897e+02 -1.37338196e+02 -1.97912704e+02 -2.20729126e+02 -2.15783737e+02 -2.21554367e+02 -2.79470093e+02 -3.02436188e+02 -2.58802826e+02 -1.79640198e+02 -1.61107803e+02 -1.88803635e+02 -2.49323563e+02 -2.76029785e+02 -2.66988617e+02 -2.36422943e+02 -2.08440781e+02 -2.09700211e+02 -1.86438354e+02 -1.57379990e+02 -1.77885849e+02 -2.24513885e+02 -2.43306625e+02 -2.36047272e+02 -1.89786896e+02 -1.83345383e+02 -1.95842453e+02 -2.12388336e+02 -2.14189651e+02 -1.84395660e+02 -2.06560364e+02 -2.42748154e+02 -2.66299866e+02 -2.67445465e+02 -2.04977753e+02 -1.67812485e+02 -2.01247635e+02 -2.70774445e+02 -2.81763397e+02 -2.20446136e+02 -1.61108795e+02 -1.64138992e+02 -2.05396729e+02 -2.06058456e+02 -1.75075272e+02 -1.63225800e+02 -2.05857285e+02 -2.26766464e+02 -1.91737686e+02 -1.64806091e+02 -2.07745468e+02 -2.29222458e+02 -2.05006607e+02 -1.77566360e+02 -1.41296997e+02 -1.67490219e+02 -1.35707840e+02 -1.28886612e+02 -1.26769463e+02 -1.26499474e+02 -1.01262405e+02 -8.24442825e+01 -1.40702713e+02 -1.73519669e+02 -1.87248123e+02 -1.35858749e+02 -1.54257141e+02 -1.53300461e+02 -1.23292290e+02 -7.52954483e+01 -6.51149445e+01 -1.45977386e+02 -1.99554764e+02 -2.05819366e+02 -1.34310684e+02 -1.06164894e+02 -1.12527855e+02 -1.36991714e+02 -1.48441788e+02 -9.88494034e+01 -1.18778343e+02 -1.50069656e+02 -2.29399811e+02 -2.58953552e+02 -2.41333694e+02 -1.82042084e+02 -1.32232224e+02 -1.64034836e+02 -2.09188904e+02 -2.31490784e+02 -2.00707581e+02 -2.20837219e+02 -2.18154892e+02 -1.66608459e+02 -1.12447281e+02 -1.10471634e+02 -2.07672379e+02 -2.29717941e+02 -1.86014404e+02 -1.14941635e+02 -1.37099915e+02 -1.80320328e+02 -1.93236603e+02 -1.79244293e+02 -1.40290421e+02 -1.50971130e+02 -1.25574203e+02 -1.63684677e+02 -1.76610474e+02 -1.79550858e+02 -1.44116394e+02 -1.29024139e+02 -1.61019348e+02 -1.98044525e+02 -1.99269241e+02 -2.12952866e+02 -2.82935852e+02 -3.17418884e+02 -3.08815186e+02 -2.69522003e+02 -2.69603882e+02 -2.99879486e+02 -3.22774109e+02 -2.89796234e+02 -2.27706177e+02 -1.93298126e+02 -1.94549942e+02 -1.72595093e+02 -1.48845139e+02 -9.54755325e+01 -8.60414810e+01 -7.14677963e+01 -1.19844818e+02 -1.50514389e+02 -1.61143448e+02 -1.41289215e+02 -1.54534836e+02 -1.81595963e+02 -2.11172592e+02 -2.03391602e+02 -1.98348053e+02 -2.41336639e+02 -2.81730225e+02 -2.57819763e+02 -1.90971542e+02 -1.68438873e+02 -1.70238205e+02 -1.23550797e+02 -8.07333984e+01 -5.22358971e+01 -1.11841248e+02 -1.11878853e+02 -1.25692970e+02 -1.57928802e+02 -1.62494812e+02 -1.17815430e+02 -1.94038391e+01 -1.28340542e+00 -8.12989044e+01 -1.59952469e+02 -1.49494049e+02 -9.16565247e+01 -4.10019722e+01 -7.52232895e+01 -1.16790779e+02 -1.66494690e+02 -1.60288986e+02 -1.13569679e+02 -7.25747147e+01 -1.09713173e+01 -5.53365183e+00 -1.57978761e+00 6.67615604e+00 1.48422775e+01 8.62587357e+00 -6.67242126e+01 -7.76441193e+01 -7.55385666e+01 -7.29665070e+01 -6.01415787e+01 -1.73029938e+01 1.01333626e+02 1.35658524e+02 5.71463318e+01 -1.02122314e+02 -1.81857544e+02 -8.68037415e+01 4.04292831e+01 4.09555855e+01 -9.52771225e+01 -2.38472824e+02 -2.09825897e+02 -7.50487595e+01 1.30598640e+01 1.36095505e+01 -7.99429092e+01 -6.97294235e+01 -1.68111916e+01 3.77261810e+01 4.44178352e+01 -2.60618439e+01 -2.73546066e+01 1.38535976e+01 4.92510414e+01 4.59113045e+01 -1.04633999e+00 2.62381020e+01 3.16532135e+01 -5.08853989e+01 -1.51473251e+02 -1.51556976e+02 1.80072346e+01 1.36555588e+02 1.07111542e+02 -2.95202770e+01 -1.17606667e+02 -9.23108368e+01 3.48292637e+00 5.88688354e+01 6.99693146e+01 -1.78099499e+01 -2.26222858e+01 -1.70788708e+01 2.13556576e+01 4.98099785e+01 -1.90138733e+00 -4.18547630e+01 -1.16980530e+02 -1.06037010e+02 -6.63193970e+01 5.41135740e+00 1.05636475e+02 1.34726120e+02 6.45054855e+01 -9.31891632e+01 -1.77313644e+02 -1.08109947e+02 5.10957756e+01 1.09133423e+02 -2.01031876e+01 -1.66667389e+02 -1.67473877e+02 -1.50164614e+01 5.70633926e+01 4.84902763e+01 -3.64761734e+01 -3.53119659e+01 1.30375271e+01 7.75238953e+01 1.24845726e+02 1.25746887e+02 1.61220657e+02 1.55795197e+02 9.45743561e+01 8.76522720e-01 -3.63045959e+01 3.85120049e+01 1.10748207e+02 8.66647415e+01 -1.47241507e+01 -1.13982170e+02 -8.04965591e+01 3.48324280e+01 7.57118759e+01 3.27498436e+01 -6.91274567e+01 -5.27016869e+01 3.70639648e+01 1.00725105e+02 1.56913696e+02 9.08869629e+01 1.06685051e+02 6.72441330e+01 7.19647675e+01 8.68114090e+01 1.07824013e+02 1.53454453e+02 1.01736343e+02 5.13212318e+01 -1.96142807e+01 1.46568089e+01 1.05589775e+02 1.91875793e+02 1.35263428e+02 3.11328888e+01 -4.36635056e+01 -4.69056931e+01 1.70637093e+01 5.08712769e+01 7.27761536e+01 4.26418762e+01 6.49485626e+01 1.03367195e+02 1.57170334e+02 2.03839218e+02 1.87577621e+02 9.81054840e+01 2.76999397e+01 2.50330124e+01 6.73742142e+01 1.06676544e+02 1.64973450e+02 1.87854935e+02 1.05344582e+02 -2.49559498e+01 -6.80611267e+01 1.65370483e+01 1.32007950e+02 1.33684235e+02 2.18002338e+01 -9.16475677e+01 -7.06778107e+01 6.70768814e+01 2.03394302e+02 2.51111618e+02 1.71000549e+02 9.68212967e+01 1.02066788e+02 1.35983994e+02 1.68637451e+02 1.04341743e+02 1.13480270e+02 9.64830322e+01 7.04783478e+01 4.92619934e+01 6.16248550e+01 1.36295471e+02 1.26129776e+02 3.75356712e+01 -5.99510765e+01 -4.22160950e+01 1.02857422e+02 2.08431717e+02 1.70290085e+02 5.41530914e+01 -2.31901245e+01 -1.52728834e+01 9.12383881e+01 1.88958023e+02 2.33410965e+02 1.47559402e+02 1.01701691e+02 5.72695312e+01 6.23834152e+01 7.11761322e+01 5.63190880e+01 6.01335602e+01 2.15198755e+00 -2.64618320e+01 -2.60089188e+01 1.85294952e+01 1.12681412e+02 1.51072556e+02 9.50844879e+01 1.15372314e+01 -1.68495121e+01 4.66072197e+01 1.30433960e+02 1.26409721e+02 6.22018204e+01 -1.67928505e+01 -2.72999420e+01 6.79866486e+01 1.48761307e+02 1.72756989e+02 9.70896072e+01 3.48029556e+01 5.47450066e+01 1.05741989e+02 1.74056396e+02 1.85394165e+02 1.77413193e+02 1.34325455e+02 7.10473633e+01 6.68602753e+01 1.33003128e+02 2.40580658e+02 2.72601288e+02 1.96652603e+02 1.13418709e+02 6.49908447e+01 1.07262062e+02 1.79061172e+02 2.15962372e+02 1.98082474e+02 1.38573685e+02 1.43181549e+02 1.83218262e+02 2.25674026e+02 2.29102951e+02 1.60689026e+02 1.15245964e+02 1.25968597e+02 1.75396454e+02 2.52056168e+02 2.49913666e+02 2.47831192e+02 2.09891602e+02 1.71926773e+02 1.49679672e+02 1.37650879e+02 1.94547958e+02 2.35060211e+02 2.19610092e+02 1.70745956e+02 1.19070595e+02 1.55425446e+02 2.17212952e+02 2.56046722e+02 1.97619858e+02 8.47172928e+01 2.23147697e+01 8.33466644e+01 1.74735870e+02 2.14736237e+02 1.10028961e+02 -3.61218605e+01 -1.35326233e+02 -4.80897034e+02 -7.17505981e+02 -2.95759253e+03 -4.05863550e+03 4.74496246e+02 5.68807251e+02 7.45609192e+02 1.02593872e+03 1.34492847e+03 6.48419128e+02 7.80030762e+03 2.15313691e+04 -195099296. 783052096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -262827248. 49404384. -287266112. 74028328. -2.31381582e+04 -9.24226660e+03 -2.94832153e+03 -4.31397766e+02 -9.27642059e+00 4.74778671e+01 8.31040878e+01 1.42813034e+02 2.36869354e+02 2.70830627e+02 2.53525681e+02 1.86955963e+02 1.50062561e+02 1.60448517e+02 2.14824936e+02 2.81169952e+02 2.82683472e+02 2.61420380e+02 2.38852295e+02 2.38701004e+02 2.41997986e+02 2.20781067e+02 2.49438080e+02 2.43564209e+02 1.93992477e+02 1.57969574e+02 1.91147354e+02 2.85747253e+02 3.31049255e+02 2.73210693e+02 1.99901886e+02 1.56829453e+02 1.82178513e+02 2.69173218e+02 3.37667175e+02 3.72043152e+02 3.01526337e+02 2.56027618e+02 2.51270370e+02 3.00798218e+02 3.27437927e+02 3.03972595e+02 2.99976013e+02 2.69350464e+02 2.37890900e+02 2.23352692e+02 2.52053162e+02 3.40066895e+02 3.43853851e+02 2.77674286e+02 1.90693375e+02 1.72463303e+02 2.38707825e+02 3.06370361e+02 3.05264679e+02 2.55304474e+02 2.34446869e+02 2.76765015e+02 3.50073303e+02 3.76201202e+02 3.48739410e+02 2.68745789e+02 2.14959915e+02 2.17621857e+02 2.66750488e+02 3.29254730e+02 3.71298828e+02 3.92484100e+02 3.71389221e+02 3.34559601e+02 2.91858673e+02 2.73956146e+02 2.86034851e+02 2.83820953e+02 2.41411499e+02 2.01147644e+02 1.99585876e+02 2.51709137e+02 2.88950409e+02 2.85594269e+02 2.62380096e+02 2.29156891e+02 2.06820190e+02 2.28335648e+02 2.83684937e+02 3.15005219e+02 2.81152832e+02 2.41868271e+02 2.49775528e+02 2.75488831e+02 2.81182892e+02 2.66156738e+02 2.78749573e+02 2.74864044e+02 2.56191193e+02 2.41295700e+02 2.53963394e+02 3.06879913e+02 3.07677246e+02 2.62262360e+02 2.00689392e+02 1.80398941e+02 2.22739136e+02 2.66957825e+02 2.90829468e+02 2.78599976e+02 2.63932800e+02 2.60576050e+02 2.73997040e+02 2.97239899e+02 3.09957367e+02 2.85380005e+02 2.43502747e+02 2.29412140e+02 2.43736359e+02 2.59391235e+02 2.62586121e+02 2.82726471e+02 2.82603271e+02 2.50562149e+02 2.11872971e+02 2.12503922e+02 2.61197388e+02 2.82056488e+02 2.55698593e+02 2.19530579e+02 2.17209747e+02 2.56323425e+02 2.91969818e+02 3.01819122e+02 2.89751801e+02 2.61165222e+02 2.38425613e+02 2.44126770e+02 2.72919281e+02 2.95420929e+02 2.78450073e+02 2.48701813e+02 2.38429398e+02 2.49310837e+02 2.66141174e+02 2.75946136e+02 2.93516815e+02 2.99456879e+02 2.91566284e+02 2.77649841e+02 2.76599823e+02 2.96607544e+02 3.04910095e+02 2.87193817e+02 2.51099228e+02 2.29705231e+02 2.39222916e+02 2.73834015e+02 2.98803864e+02 2.94912689e+02 2.78295471e+02 2.71869141e+02 2.78597961e+02 2.79535278e+02 2.89117065e+02 2.85478973e+02 2.82781921e+02 2.73733276e+02 2.60527130e+02 2.56910187e+02 2.53881683e+02 2.73202911e+02 2.80300751e+02 2.69679779e+02 2.60794983e+02 2.65826691e+02 2.90713043e+02 2.98386658e+02 2.92260132e+02 2.80128632e+02 2.73500275e+02 2.72985260e+02 2.79177338e+02 2.82227570e+02 2.83616638e+02 2.73398956e+02 2.76853790e+02 2.83238831e+02 2.93619537e+02 3.02635498e+02 3.08718842e+02 3.13064819e+02 3.03504364e+02 2.89263916e+02 2.80974884e+02 2.81408142e+02 2.88204254e+02 2.89239532e+02 2.81298370e+02 2.72833435e+02 2.69311035e+02 2.79145508e+02 2.92113586e+02 2.97760925e+02 2.95115448e+02 2.90008484e+02 2.87770477e+02 2.87882416e+02 2.88954742e+02 2.91297302e+02 2.89228210e+02 2.85916077e+02 2.84293762e+02 2.86476685e+02 2.87293610e+02 2.87715485e+02 2.88440735e+02 2.88505676e+02 2.87175720e+02 2.86198029e+02 2.86198517e+02 2.86092194e+02 2.85523926e+02 2.85120972e+02 2.85234131e+02 2.85568573e+02 2.85709351e+02 2.85569122e+02 2.84771973e+02 2.84190247e+02 2.84830231e+02 2.86366913e+02 2.87070923e+02 2.85694092e+02 2.84459320e+02 2.84803864e+02 2.84878357e+02 2.84774902e+02 2.84997559e+02 2.84999054e+02 2.84787445e+02 2.84771149e+02 2.84758179e+02 2.86205994e+02 2.86415771e+02 2.88738892e+02 2.88342133e+02 2.88450378e+02 2.85553772e+02 2.85838654e+02 2.85795227e+02 2.85294739e+02 2.85027466e+02 2.82563477e+02 2.81427521e+02 2.79519501e+02 2.80276215e+02 2.82548492e+02 2.82160248e+02 2.82712769e+02 2.83788177e+02 2.85420593e+02 2.83934143e+02 2.82197021e+02 2.81287781e+02 2.84241760e+02 2.84114655e+02 2.84379639e+02 2.83763062e+02 2.85897858e+02 2.87388885e+02 2.88804962e+02 2.90236053e+02 2.87462311e+02 2.86593201e+02 2.84145966e+02 2.86743835e+02 2.87366272e+02 2.88815704e+02 2.87518494e+02 2.85644775e+02 2.80798828e+02 2.78983887e+02 2.82150726e+02 2.85922394e+02 2.84656006e+02 2.81546295e+02 2.80264679e+02 2.82111328e+02 2.79244446e+02 2.79211761e+02 2.81062469e+02 2.83299011e+02 2.81748932e+02 2.80218903e+02 2.83046021e+02 2.79757019e+02 2.73774597e+02 2.70344208e+02 2.74585144e+02 2.77128601e+02 2.75903473e+02 2.72115051e+02 2.72956421e+02 2.72279419e+02 2.74058228e+02 2.74136993e+02 2.72664551e+02 2.68302094e+02 2.69790924e+02 2.70455048e+02 2.75035706e+02 2.73617096e+02 2.79655212e+02 2.88907745e+02 2.85819122e+02 2.79393097e+02 2.65071777e+02 2.68075348e+02 2.68985840e+02 2.67991180e+02 2.67791199e+02 2.61924042e+02 2.62002533e+02 2.62779663e+02 2.62564453e+02 2.59466125e+02 2.56461914e+02 2.62728638e+02 2.63808685e+02 2.63853912e+02 2.62620148e+02 2.67018921e+02 2.63169403e+02 2.60691681e+02 2.57994690e+02 2.51386093e+02 2.49398621e+02 2.52080109e+02 2.63252350e+02 2.66404358e+02 2.61860840e+02 2.54775146e+02 2.50831406e+02 2.51793289e+02 2.62006439e+02 2.73859131e+02 2.70446411e+02 2.60217896e+02 2.45197571e+02 2.45328812e+02 2.48656891e+02 2.56199524e+02 2.61760010e+02 2.64886292e+02 2.67765503e+02 2.70700775e+02 2.67550018e+02 2.64447388e+02 2.53881073e+02 2.55029358e+02 2.60636078e+02 2.62003937e+02 2.57153687e+02 2.56936157e+02 2.61758789e+02 2.64489532e+02 2.61710876e+02 2.59164001e+02 2.58638855e+02 2.71639252e+02 2.88126678e+02 2.86260071e+02 2.65406860e+02 2.43309799e+02 2.54657608e+02 2.71463165e+02 2.75800964e+02 2.65882294e+02 2.47874466e+02 2.55924057e+02 2.63999786e+02 2.71225311e+02 2.66831116e+02 2.59141876e+02 2.65068207e+02 2.80252869e+02 2.92787292e+02 2.77926941e+02 2.49680481e+02 2.39042801e+02 2.49139694e+02 2.54577194e+02 2.52796661e+02 2.45558090e+02 2.41452850e+02 2.53141556e+02 2.65642731e+02 2.63811005e+02 2.47441345e+02 2.28364059e+02 2.30932449e+02 2.34638489e+02 2.39668579e+02 2.22299484e+02 1.94205246e+02 1.84708008e+02 2.07412949e+02 2.31173203e+02 2.39182312e+02 2.35116089e+02 2.52419678e+02 2.53167511e+02 2.19060516e+02 1.79149200e+02 1.71394547e+02 2.00416885e+02 2.29207138e+02 2.28729462e+02 2.28752609e+02 2.08147705e+02 1.93670181e+02 1.99799133e+02 2.23952271e+02 2.48673340e+02 2.43757843e+02 2.45006546e+02 2.14773041e+02 1.75742126e+02 1.72210800e+02 1.91407913e+02 2.27356415e+02 2.48367981e+02 2.63605072e+02 2.62679626e+02 2.32332779e+02 2.20430191e+02 2.09613617e+02 2.09669495e+02 2.09661224e+02 2.00711761e+02 1.86666840e+02 1.79150879e+02 1.85407364e+02 2.18384674e+02 3.22925262e+02 3.87735229e+02 3.81647888e+02 2.75821564e+02 2.29171967e+02 2.02439673e+03 3.45158252e+03 7.62473389e+02 6.98943176e+02 6.73149658e+02 6.78500305e+02 6.54582214e+02 4.18550415e+02 6.68868042e+02 2.07419174e+02 -2.08526169e+02 -8.95540039e+03 -2.30549746e+04 -177720176. -470063296. 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. 0. 0. 0. 0. 0. 0. -105792512. 89272640. -35849148. -31183894. -633875520. 3.12474316e+04 1.24188984e+04 3.82409814e+03 6.55268616e+02 2.94908142e+02 2.04974396e+02 2.14562927e+02 2.10431213e+02 2.11983475e+02 2.08075668e+02 2.15128983e+02 2.20920776e+02 2.21461075e+02 2.18777466e+02 1.86864258e+02 1.76637100e+02 1.82099838e+02 2.10743851e+02 2.05750290e+02 1.81609100e+02 1.45682449e+02 1.30524811e+02 1.33302460e+02 1.28962524e+02 1.25459984e+02 1.05733574e+02 9.59161835e+01 8.63001785e+01 8.93167725e+01 8.46248245e+01 8.61192245e+01 8.80405884e+01 8.76607666e+01 8.22694397e+01 7.61625443e+01 8.59189453e+01 9.31220932e+01 9.05323944e+01 8.18139572e+01 7.33943024e+01 6.83432236e+01 6.85409622e+01 8.23835602e+01 1.17409492e+02 1.44223465e+02 1.47773102e+02 1.31149689e+02 1.07249741e+02 9.20180054e+01 8.04402695e+01 9.42398300e+01 1.12956314e+02 1.15230309e+02 9.70698776e+01 7.99168167e+01 7.12981186e+01 5.98695488e+01 7.27206039e+01 9.90543442e+01 1.15246880e+02 1.30325043e+02 1.35713058e+02 1.35168442e+02 1.21072876e+02 1.05238434e+02 1.10947693e+02 1.04340157e+02 6.60061264e+01 5.04496651e+01 5.53371582e+01 8.06529770e+01 8.99045792e+01 8.25803070e+01 1.10555672e+02 1.50649811e+02 1.46166046e+02 1.23750885e+02 9.19569016e+01 1.48015991e+02 1.96358215e+02 2.03673599e+02 1.61135925e+02 1.37190842e+02 1.38554108e+02 1.45673599e+02 1.28412949e+02 1.28807617e+02 1.59444122e+02 1.91249527e+02 1.79845276e+02 1.25059349e+02 8.22557144e+01 6.36685867e+01 7.32022781e+01 8.60711746e+01 9.79985657e+01 6.12489624e+01 3.05891209e+01 4.64721603e+01 8.99569092e+01 9.65229034e+01 6.73187866e+01 4.30744743e+01 8.92348709e+01 1.23000641e+02 1.23970398e+02 7.57663879e+01 3.51014328e+01 1.98811703e+01 2.09384174e+01 2.08053989e+01 2.98549423e+01 3.80283241e+01 4.42814217e+01 3.74922714e+01 3.80648956e+01 4.83654900e+01 5.46379471e+01 5.38532372e+01 4.23071442e+01 4.45413437e+01 4.14292221e+01 4.66655121e+01 8.38555145e+01 1.27113945e+02 1.19527351e+02 8.07790833e+01 3.98113976e+01 7.80123749e+01 1.22694046e+02 1.20864738e+02 9.05319977e+01 5.42143402e+01 5.39211044e+01 4.90278854e+01 3.41347084e+01 4.58587265e+01 5.38642616e+01 5.35921478e+01 2.75305252e+01 1.81757963e+00 2.13580203e+00 1.88607025e+01 4.35195351e+01 3.77490387e+01 3.64075737e+01 3.01624260e+01 4.64420395e+01 8.74022598e+01 1.33110474e+02 1.35988632e+02 1.02193359e+02 5.83185081e+01 9.03715820e+01 1.27016190e+02 1.20585709e+02 6.99449768e+01 2.33349323e+01 2.37309608e+01 2.88102016e+01 3.20360489e+01 3.16354866e+01 3.32374878e+01 3.06110134e+01 2.46067524e+01 1.73934860e+01 4.50352898e+01 7.11163559e+01 6.82351074e+01 3.38433113e+01 -1.36644733e+00 -4.64977407e+00 -7.25152016e+00 2.45805683e+01 5.67977562e+01 5.52720871e+01 2.81233444e+01 6.31131887e+00 9.42052078e+00 -6.08109570e+00 2.01675892e+01 6.40199509e+01 7.87668915e+01 4.37477226e+01 2.61695409e+00 2.05396485e+00 3.62841558e+00 -1.39454496e+00 -6.46057081e+00 5.35400391e+00 8.71389198e+00 4.87517395e+01 8.48506165e+01 8.30308990e+01 3.43142128e+01 -9.92799950e+00 3.13715959e+00 6.03906155e+00 4.42100868e+01 7.04007492e+01 7.02296066e+01 1.54665194e+01 -3.57656250e+01 -3.50401459e+01 -2.55771656e+01 -1.45923920e+01 -2.06943512e+01 -3.29189644e+01 -4.33751373e+01 -4.71783638e+01 -4.69663315e+01 -4.78132019e+01 -5.65030937e+01 -5.41913185e+01 -7.21343231e+01 -8.19690933e+01 -9.47946701e+01 -9.26993484e+01 -8.29481049e+01 -8.90051193e+01 -9.04799728e+01 -8.88542099e+01 -7.89215164e+01 -7.20229263e+01 -8.19129639e+01 -7.68658600e+01 -7.78319321e+01 -8.25773315e+01 -1.02193939e+02 -1.10700989e+02 -1.00892876e+02 -9.09019241e+01 -8.03750305e+01 -8.95469513e+01 -7.49938660e+01 -8.20497360e+01 -6.27028656e+01 -6.00044174e+01 -5.41183815e+01 -8.06409073e+01 -1.13421356e+02 -9.56916428e+01 -4.82058983e+01 -1.16945686e+01 -2.46793232e+01 -4.51854515e+01 -5.41075325e+01 -5.15779610e+01 -4.79400749e+01 -3.91941948e+01 -4.14651985e+01 -4.98191338e+01 -6.19262314e+01 -7.29378510e+01 -9.05046158e+01 -9.73725357e+01 -9.15977478e+01 -7.23977509e+01 -6.41635742e+01 -6.17588387e+01 -6.95802917e+01 -7.42857590e+01 -9.00202713e+01 -9.55560913e+01 -1.02281952e+02 -8.46165924e+01 -5.28551216e+01 -2.13293285e+01 -3.21582069e+01 -5.39032288e+01 -8.66817398e+01 -9.12475357e+01 -9.79524307e+01 -7.32406082e+01 -5.05352783e+01 -3.50201912e+01 -3.70173950e+01 -6.12119789e+01 -8.51105652e+01 -1.21692375e+02 -1.10797813e+02 -9.76102295e+01 -8.74193954e+01 -9.82663498e+01 -1.08882004e+02 -1.18741356e+02 -1.13076424e+02 -1.02978874e+02 -9.70568008e+01 -8.80059509e+01 -8.77314301e+01 -5.07152138e+01 -2.45760689e+01 -4.05646477e+01 -8.32187195e+01 -1.22631699e+02 -1.05399017e+02 -8.91451874e+01 -9.55235443e+01 -1.00977394e+02 -8.54940414e+01 -5.49521599e+01 -5.67923431e+01 -8.81713104e+01 -1.23421440e+02 -1.07644997e+02 -1.04513649e+02 -1.11214981e+02 -1.38445251e+02 -1.42729248e+02 -1.38457764e+02 -1.23224350e+02 -1.34057739e+02 -1.52270996e+02 -1.53201797e+02 -1.49110123e+02 -1.41174271e+02 -1.54689377e+02 -1.31477615e+02 -1.05486153e+02 -1.02481697e+02 -9.08090591e+01 -6.43121109e+01 -3.24924774e+01 -3.11152897e+01 -5.51145058e+01 -5.31742325e+01 -7.99384842e+01 -8.66408157e+01 -1.19637878e+02 -1.48025742e+02 -1.90935196e+02 -1.98419464e+02 -1.89303253e+02 -1.78134491e+02 -1.76075623e+02 -1.70353394e+02 -1.67270874e+02 -1.69802139e+02 -1.85828217e+02 -1.59231277e+02 -1.21754555e+02 -1.03027550e+02 -1.10981659e+02 -1.40896454e+02 -1.42824234e+02 -1.50310135e+02 -1.68334656e+02 -1.51057007e+02 -1.52229523e+02 -1.40791977e+02 -1.45857788e+02 -1.28787567e+02 -9.97230682e+01 -1.20861008e+02 -1.52970642e+02 -1.67373428e+02 -1.34407364e+02 -1.21368828e+02 -1.37893265e+02 -1.77026749e+02 -1.55293076e+02 -1.29898224e+02 -1.19255653e+02 -1.39205032e+02 -1.59264420e+02 -1.28688629e+02 -1.04943214e+02 -1.08915298e+02 -1.52156250e+02 -1.85244141e+02 -1.70312637e+02 -1.49944504e+02 -1.78415665e+02 -2.17846191e+02 -1.95862808e+02 -1.49205521e+02 -1.24543518e+02 -1.38949738e+02 -1.49653458e+02 -1.51016190e+02 -1.30740479e+02 -1.11264511e+02 -1.18855629e+02 -1.62761841e+02 -1.99981400e+02 -1.97389587e+02 -1.88776031e+02 -1.82929520e+02 -1.91691208e+02 -1.89754654e+02 -1.84908737e+02 -1.75906113e+02 -1.78060455e+02 -1.95000488e+02 -1.99061752e+02 -1.94744980e+02 -1.69521378e+02 -1.58540726e+02 -1.67929764e+02 -1.74681030e+02 -1.93056122e+02 -1.90923157e+02 -1.92530106e+02 -2.04470398e+02 -2.13472198e+02 -2.18846619e+02 -1.74961853e+02 -1.47060760e+02 -1.78942917e+02 -2.38989090e+02 -2.44087570e+02 -1.93353760e+02 -1.74649765e+02 -2.01027832e+02 -2.16699509e+02 -1.93727798e+02 -1.86874985e+02 -1.92301743e+02 -2.18346359e+02 -2.01138977e+02 -1.93838547e+02 -1.87442322e+02 -2.05593277e+02 -2.28969345e+02 -2.27527298e+02 -2.24811630e+02 -1.99216629e+02 -1.83884979e+02 -1.81210022e+02 -2.02898407e+02 -2.03372787e+02 -1.61199158e+02 -1.33901443e+02 -1.49961899e+02 -1.92470581e+02 -1.95244873e+02 -1.79800430e+02 -2.01503540e+02 -2.43941437e+02 -2.60525482e+02 -2.37232681e+02 -2.17904449e+02 -2.17516022e+02 -2.24346436e+02 -2.13456635e+02 -2.15411972e+02 -2.15713028e+02 -2.23597031e+02 -2.30329376e+02 -2.40888260e+02 -2.47718765e+02 -2.40209595e+02 -2.34701035e+02 -2.20667252e+02 -2.19301529e+02 -2.16143036e+02 -2.08058151e+02 -2.06413757e+02 -2.17086349e+02 -2.35604752e+02 -2.28813080e+02 -2.06126358e+02 -1.99362396e+02 -2.06940063e+02 -2.00495087e+02 -1.67462250e+02 -1.45647125e+02 -1.66113876e+02 -2.08964172e+02 -2.19905487e+02 -2.12107880e+02 -2.10181961e+02 -2.28652588e+02 -2.40581131e+02 -2.43378830e+02 -2.46784271e+02 -2.51658661e+02 -2.45372772e+02 -2.46938644e+02 -2.53520889e+02 -2.55934280e+02 -2.30772095e+02 -2.18160309e+02 -2.33744720e+02 -2.50692566e+02 -2.31953918e+02 -2.20104980e+02 -2.35237762e+02 -2.70091675e+02 -2.88258881e+02 -2.87622131e+02 -2.86959412e+02 -2.80017273e+02 -2.77408661e+02 -2.71556274e+02 -2.76730499e+02 -2.68362366e+02 -2.66276642e+02 -2.63900513e+02 -2.77783234e+02 -2.66356018e+02 -2.37048599e+02 -2.14952072e+02 -2.11423141e+02 -2.20265091e+02 -2.31238708e+02 -2.44486465e+02 -2.56720520e+02 -2.56640076e+02 -2.61262695e+02 -2.63959473e+02 -2.65353790e+02 -2.60633484e+02 -2.62068970e+02 -2.61600952e+02 -2.60585358e+02 -2.63354797e+02 -2.63544098e+02 -2.69215759e+02 -2.52259857e+02 -2.37532578e+02 -2.34591019e+02 -2.50449570e+02 -2.61751495e+02 -2.59868652e+02 -2.59477448e+02 -2.61174652e+02 -2.62711548e+02 -2.61934540e+02 -2.61746735e+02 -2.53841095e+02 -2.43326324e+02 -2.49150665e+02 -2.62846344e+02 -2.66962097e+02 -2.44236008e+02 -2.31013931e+02 -2.41302734e+02 -2.63311066e+02 -2.64524170e+02 -2.56445251e+02 -2.57067413e+02 -2.64312561e+02 -2.72573242e+02 -2.63254517e+02 -2.57108459e+02 -2.49668747e+02 -2.46333923e+02 -2.57874237e+02 -2.66205139e+02 -2.66415710e+02 -2.46016083e+02 -2.37892853e+02 -2.49630020e+02 -2.69053070e+02 -2.66551361e+02 -2.55919098e+02 -2.52897247e+02 -2.61931366e+02 -2.71129486e+02 -2.66366913e+02 -2.60233154e+02 -2.56846069e+02 -2.62040009e+02 -2.68000397e+02 -2.72273834e+02 -2.65947510e+02 -2.59368500e+02 -2.57194214e+02 -2.64915314e+02 -2.74901276e+02 -2.70819092e+02 -2.65322906e+02 -2.65311737e+02 -2.71888794e+02 -2.71991608e+02 -2.65788086e+02 -2.66880737e+02 -2.73829346e+02 -2.82062042e+02 -2.82759125e+02 -2.83335022e+02 -2.78653961e+02 -2.73616150e+02 -2.71834473e+02 -2.74255005e+02 -2.77562408e+02 -2.66089447e+02 -2.41571915e+02 -2.40721420e+02 -2.14055634e+02 -4.01986160e+01 -6.60145950e+01 -1.09732666e+03 -1.09530627e+03 -1.09115759e+03 -1.08935547e+03 -1.08798145e+03 -1.08606250e+03 -1.10253113e+03 -1.11606006e+03 -1.13043054e+03 -1.15519812e+03 -1.03125879e+03 -9.03267822e+02 2.68783960e+03 -1244824576. 0. 0. 0. 0. 0. 0. 0. -276036416. -777565376. 45655232. -3.29351465e+03 -3.52398853e+03 -5.42480859e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 431099104. -114127752. -1.59339404e+03 -1.21532387e+02 -1.93593521e+02 -2.81831116e+02 -2.66858521e+02 -2.28960464e+02 -2.21174545e+02 -2.44448502e+02 -2.55626236e+02 -2.65745087e+02 -2.65988800e+02 -2.58322906e+02 -2.55704727e+02 -2.59095795e+02 -2.56037384e+02 -2.49302841e+02 -2.41969498e+02 -2.48792465e+02 -2.65026917e+02 -2.73756378e+02 -2.68320862e+02 -2.55507431e+02 -2.49073593e+02 -2.50540466e+02 -2.53033173e+02 -2.49034180e+02 -2.42846436e+02 -2.47254700e+02 -2.58935425e+02 -2.65735291e+02 -2.60964417e+02 -2.49323502e+02 -2.44925522e+02 -2.52997543e+02 -2.67898346e+02 -2.75872467e+02 -2.69289185e+02 -2.69753479e+02 -2.78588654e+02 -2.74772736e+02 -2.56112000e+02 -2.39353394e+02 -2.53807312e+02 -2.85039490e+02 -2.96651520e+02 -2.79568787e+02 -2.59802124e+02 -2.49525208e+02 -2.49065170e+02 -2.52722488e+02 -2.54555237e+02 -2.48679825e+02 -2.51051437e+02 -2.77014801e+02 -3.00616699e+02 -2.91984650e+02 -2.65039612e+02 -2.48653137e+02 -2.58884705e+02 -2.76508148e+02 -2.85648254e+02 -2.68929199e+02 -2.65332886e+02 -2.71126587e+02 -2.63973145e+02 -2.40626923e+02 -2.18335541e+02 -2.23273605e+02 -2.61874573e+02 -2.74407593e+02 -2.61033722e+02 -2.31272964e+02 -2.33723358e+02 -2.56865417e+02 -2.51727386e+02 -2.37698822e+02 -2.25953064e+02 -2.41489151e+02 -2.75999817e+02 -2.92708252e+02 -2.81053986e+02 -2.42464798e+02 -2.18843948e+02 -2.26987518e+02 -2.45724945e+02 -2.43063110e+02 -2.24000244e+02 -2.24273682e+02 -2.49764893e+02 -2.61024536e+02 -2.35429657e+02 -1.99788208e+02 -1.96570648e+02 -2.32462708e+02 -2.66115448e+02 -2.65374512e+02 -2.40059998e+02 -2.32239182e+02 -2.40929504e+02 -2.22214111e+02 -1.88322922e+02 -1.70423645e+02 -2.03972855e+02 -2.58389160e+02 -2.87230988e+02 -2.67612183e+02 -2.32770264e+02 -1.97859924e+02 -1.76540909e+02 -1.79013306e+02 -1.85114365e+02 -1.83627762e+02 -1.90654022e+02 -2.25587463e+02 -2.60305573e+02 -2.38846619e+02 -1.77622910e+02 -1.51784393e+02 -1.78350403e+02 -2.40601501e+02 -2.67193085e+02 -2.39154846e+02 -2.12771896e+02 -2.03096909e+02 -2.09839127e+02 -1.83139938e+02 -1.39368622e+02 -1.42292221e+02 -1.91468170e+02 -2.39091156e+02 -2.33768219e+02 -2.00504761e+02 -1.76511826e+02 -1.73480728e+02 -1.80087234e+02 -2.01011368e+02 -2.08999054e+02 -1.82379059e+02 -1.66213943e+02 -1.90826080e+02 -2.17243912e+02 -2.23969940e+02 -2.08405365e+02 -2.09285248e+02 -2.28594467e+02 -2.29472321e+02 -2.10926575e+02 -1.83968231e+02 -1.67914612e+02 -1.88610840e+02 -1.99199432e+02 -1.92352570e+02 -1.76516586e+02 -2.00109177e+02 -2.72108154e+02 -3.08555786e+02 -2.54770279e+02 -1.84068451e+02 -1.70631363e+02 -2.05910950e+02 -2.28949463e+02 -2.25787308e+02 -2.27767883e+02 -2.54949509e+02 -2.89639313e+02 -2.99728882e+02 -2.75962097e+02 -2.25364090e+02 -1.93838638e+02 -2.25261597e+02 -2.45630966e+02 -2.32711121e+02 -1.95126709e+02 -2.14371384e+02 -2.78749481e+02 -2.74025482e+02 -2.45162872e+02 -2.21443497e+02 -2.57257416e+02 -3.25959625e+02 -3.57746368e+02 -3.19768677e+02 -2.44236252e+02 -2.04039185e+02 -2.11161194e+02 -1.99810089e+02 -1.76072937e+02 -1.87565033e+02 -2.36980453e+02 -3.01954987e+02 -2.83494049e+02 -2.38099899e+02 -1.55487930e+02 -1.25653938e+02 -1.43660873e+02 -2.02380081e+02 -2.53540131e+02 -2.56600281e+02 -2.66928406e+02 -2.87434540e+02 -2.67190643e+02 -2.02987289e+02 -1.44160858e+02 -1.70587387e+02 -2.66750641e+02 -3.15305603e+02 -2.64307922e+02 -1.61060211e+02 -1.25025269e+02 -1.70199051e+02 -2.21473099e+02 -2.00464523e+02 -1.54671021e+02 -1.62915695e+02 -2.18571777e+02 -2.36360046e+02 -1.81419220e+02 -9.72564392e+01 -8.70498352e+01 -1.24772888e+02 -1.74009048e+02 -1.66119125e+02 -1.48623932e+02 -1.45090469e+02 -1.72888947e+02 -1.55027817e+02 -1.13442963e+02 -1.02576202e+02 -9.85653458e+01 -1.59571671e+02 -1.70524872e+02 -1.61239822e+02 -1.47954010e+02 -1.55037292e+02 -1.99018890e+02 -1.61647400e+02 -1.13332520e+02 -8.11887360e+01 -1.06292038e+02 -2.09303711e+02 -2.73091522e+02 -2.63643799e+02 -1.56432526e+02 -8.94431152e+01 -8.01281281e+01 -1.12657921e+02 -1.44086105e+02 -1.12179405e+02 -1.21320534e+02 -1.48023743e+02 -1.68401245e+02 -1.31616074e+02 -1.01777412e+02 -1.59923294e+02 -2.33555145e+02 -2.21895065e+02 -1.84311813e+02 -1.63674911e+02 -1.80861420e+02 -2.28770569e+02 -1.77990784e+02 -1.44891678e+02 -1.02921242e+02 -1.23732887e+02 -1.81954498e+02 -2.12023682e+02 -2.31820419e+02 -1.76036667e+02 -1.46988541e+02 -1.37225708e+02 -1.81112244e+02 -1.85164337e+02 -1.74585220e+02 -1.84294083e+02 -2.23358887e+02 -2.41870285e+02 -1.78933594e+02 -1.31626419e+02 -1.30858368e+02 -1.82601593e+02 -1.68296463e+02 -1.44578262e+02 -1.15800133e+02 -9.72680588e+01 -1.10738441e+02 -9.76432266e+01 -1.56808304e+02 -1.69168091e+02 -1.91849152e+02 -1.89096985e+02 -1.69132812e+02 -1.47751358e+02 -8.20753708e+01 -6.05215721e+01 -7.48782806e+01 -1.70372620e+02 -1.93019318e+02 -1.75474319e+02 -1.38575897e+02 -1.44007370e+02 -1.26998367e+02 -3.68771362e+01 5.09290361e+00 -2.44223156e+01 -1.33609482e+02 -1.64729233e+02 -1.27004234e+02 -7.21862946e+01 -5.62996445e+01 -1.13927162e+02 -1.11208664e+02 -1.18155258e+02 -4.41342468e+01 -2.97315311e+01 -1.82730255e+01 -7.92977524e+01 -8.67416229e+01 -4.82180672e+01 -1.16666298e+01 -5.49700050e+01 -1.26303223e+02 -9.42240372e+01 -3.71073990e+01 -3.01247597e+01 -6.24945602e+01 -7.22189789e+01 -7.08574355e-02 2.35274658e+01 -2.56625009e+00 -8.18115997e+01 -7.54748993e+01 -4.75264130e+01 -1.27893543e+01 -3.59737206e+01 -6.85254669e+01 -6.63525009e+01 -7.22780609e+01 -2.52755985e+01 -7.98628283e+00 2.67088413e+00 -3.73018036e+01 -4.30890198e+01 -2.28580494e+01 2.15787182e+01 -1.05989418e+01 -6.78199921e+01 -8.42647171e+01 -7.31796722e+01 -9.73603973e+01 -1.63220428e+02 -1.51287598e+02 -8.18845825e+01 -6.33314209e+01 -1.03891930e+02 -1.63083527e+02 -1.00979858e+02 -6.31203957e+01 -2.33949604e+01 1.76598854e+01 2.77014847e+01 -7.88636637e+00 -1.15156021e+02 -1.34975281e+02 -6.09851341e+01 2.03806534e+01 -2.14913311e+01 -1.11989891e+02 -1.66628159e+02 -1.06376152e+02 -6.03372269e+01 -7.25805588e+01 -9.45485229e+01 -1.30727707e+02 -1.75131561e+02 -2.47550934e+02 -2.30284119e+02 -1.59648499e+02 -1.29202530e+02 -1.57438995e+02 -1.97812546e+02 -1.17648056e+02 -7.36511230e+01 -3.89476318e+01 -5.07844162e+01 -5.41396027e+01 -9.92197037e+01 -2.02767944e+02 -2.37759338e+02 -1.45283691e+02 -9.56062913e-01 4.56853485e+01 -8.74277649e+01 -2.00905762e+02 -2.10683121e+02 -1.13471275e+02 -5.42732010e+01 -8.35220642e+01 -1.71020294e+02 -2.16627136e+02 -1.72288208e+02 -3.83999939e+01 -2.94811487e+00 -6.06542015e+01 -1.48107849e+02 -2.30245407e+02 -2.15174057e+02 -1.75604935e+02 -6.74851761e+01 4.45087814e+01 8.92758255e+01 2.37017498e+01 -1.30225891e+02 -2.17851166e+02 -1.47601395e+02 -2.74477253e+01 -3.09784126e+01 -1.49389496e+02 -2.61240570e+02 -2.19749893e+02 -9.36009064e+01 1.30090494e+01 2.35440598e+01 -5.47327652e+01 -1.22769623e+02 -1.74724670e+02 -1.02858383e+02 -5.84241982e+01 -1.86953583e+01 -7.12945709e+01 -1.03480934e+02 -5.30254021e+01 1.18720255e+01 8.89990768e+01 9.66099930e+01 5.43696671e+01 -1.49223003e+01 -1.30796387e+02 -1.62260071e+02 -8.55620804e+01 7.74491806e+01 1.58240982e+02 8.49212418e+01 -6.79076843e+01 -1.61805008e+02 -1.17010323e+02 -5.49840546e+01 -4.98682480e+01 -1.01095253e+02 -1.18206490e+02 -1.19874199e+02 -4.49813271e+01 8.27818298e+00 7.27433167e+01 8.27999039e+01 4.49156837e+01 -5.27425289e+00 -7.63752213e+01 -7.08357849e+01 -2.36542702e+01 5.10051613e+01 5.72526245e+01 -5.14353132e+00 -7.69597931e+01 -4.95169830e+01 2.37904167e+01 6.27993011e+01 4.49848509e+00 -9.13699036e+01 -8.54813538e+01 -1.35331497e+01 1.04921547e+02 1.01116776e+02 1.81769753e+01 -5.88792343e+01 -1.00280357e+02 -1.33526373e+01 2.83437691e+01 6.09438972e+01 6.36816406e+01 6.98020782e+01 8.07442398e+01 4.20716629e+01 6.11212692e+01 1.04834450e+02 9.38513412e+01 4.00553970e+01 -5.35908241e+01 -8.63849640e+01 -3.17212658e+01 1.05717758e+02 2.18978088e+02 2.06413071e+02 6.82209320e+01 -6.20528259e+01 -9.85431747e+01 1.96755219e+00 1.13439247e+02 1.40614075e+02 6.62561035e+01 -1.80177345e+01 -1.43380344e+00 5.60668640e+01 1.21071564e+02 1.35940842e+02 1.15025215e+02 5.95564041e+01 -5.15019846e+00 1.33415759e+00 6.57238083e+01 1.66092743e+02 1.89075684e+02 1.10522591e+02 2.72433338e+01 3.46754951e+01 1.16783058e+02 1.62368088e+02 1.30605911e+02 8.59287338e+01 6.54288025e+01 4.99059219e+01 7.60961990e+01 1.02273262e+02 9.38199692e+01 7.91786575e+01 4.84255028e+01 8.49584122e+01 1.25852661e+02 1.76603287e+02 2.07148346e+02 1.59995544e+02 1.16577843e+02 4.35964622e+01 1.93300343e+01 5.87315102e+01 1.30193512e+02 1.45915298e+02 7.60729675e+01 -3.80743623e+00 1.21994600e+01 6.52920990e+01 1.46578995e+02 1.72058624e+02 1.31707062e+02 8.95060349e+01 6.28630981e+01 1.36179611e+02 1.92066498e+02 2.51679764e+02 2.39494385e+02 1.63962601e+02 1.69107498e+02 1.96583176e+02 2.77669830e+02 2.88425537e+02 2.57606506e+02 1.96566772e+02 9.53508987e+01 5.04882088e+01 7.52626266e+01 1.60206146e+02 2.03878235e+02 1.40144363e+02 6.14003067e+01 5.86634712e+01 1.54691757e+02 2.17832581e+02 1.98576553e+02 1.09967445e+02 4.23797684e+01 3.94712296e+01 1.10610260e+02 1.95966980e+02 2.19169235e+02 2.16128616e+02 1.89665039e+02 1.58365601e+02 1.06818657e+02 1.00575974e+02 1.25050301e+02 1.48481857e+02 1.15483109e+02 4.32427101e+01 1.02571380e+00 6.88693466e+01 1.61806320e+02 2.11082809e+02 1.56629288e+02 7.23079758e+01 5.77152061e+01 1.02306755e+02 1.88766541e+02 1.99122314e+02 1.50940399e+02 1.24681435e+02 1.16595879e+02 1.73280151e+02 1.87294128e+02 1.79600037e+02 1.55743729e+02 1.11990074e+02 1.26709312e+02 1.29237976e+02 1.98909439e+02 2.56382233e+02 2.47088669e+02 2.04714569e+02 1.34942078e+02 8.86955719e+01 8.20619583e+01 1.35047150e+02 2.56815063e+02 2.79378601e+02 2.63440887e+02 2.97863373e+02 6.55706726e+02 3.12222095e+03 4.81795361e+03 1.34492847e+03 6.48419128e+02 7.80030762e+03 2.15313691e+04 -195099296. 783052096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -554315968. 3.57637539e+04 5.60117920e+03 1.35608716e+03 9.33015869e+02 4.85899902e+02 3.46249390e+02 2.54880157e+02 2.23340591e+02 2.60390808e+02 2.73763214e+02 2.34839005e+02 1.49087631e+02 1.45954269e+02 1.91630295e+02 2.50636765e+02 2.33500031e+02 1.65208160e+02 1.12212234e+02 1.08054146e+02 1.63142914e+02 2.45486221e+02 2.65265198e+02 2.10899994e+02 1.41638947e+02 1.42944656e+02 1.94656708e+02 1.97402618e+02 1.58300598e+02 1.43100861e+02 1.76581390e+02 2.12361099e+02 2.15499451e+02 2.24483032e+02 2.50203445e+02 2.49791931e+02 2.08194717e+02 1.37867920e+02 1.32263412e+02 1.84003586e+02 2.30550232e+02 2.29280106e+02 1.77750763e+02 1.23482895e+02 1.32427307e+02 2.02567337e+02 2.86369415e+02 2.79639221e+02 2.04700974e+02 1.64143478e+02 1.61062164e+02 2.00649368e+02 2.12988083e+02 2.17469589e+02 2.25313873e+02 2.14856781e+02 2.02197525e+02 1.68780258e+02 1.79737000e+02 2.19892105e+02 2.26399460e+02 2.05157196e+02 1.56347382e+02 1.54287048e+02 1.80669159e+02 2.23965668e+02 2.45620758e+02 1.99932922e+02 1.41834351e+02 1.01674820e+02 1.28715668e+02 1.90411621e+02 2.12335861e+02 1.76706970e+02 1.47560226e+02 1.54981216e+02 2.11002884e+02 2.23495087e+02 2.09195587e+02 1.81654221e+02 1.88135498e+02 1.85734192e+02 1.76604950e+02 1.94898834e+02 2.33376389e+02 2.46715225e+02 2.08165634e+02 1.54525497e+02 1.45021332e+02 1.68873367e+02 2.04644363e+02 2.34916306e+02 2.35778992e+02 2.13272125e+02 1.85886017e+02 1.94368332e+02 2.41566345e+02 2.60354523e+02 2.20876160e+02 1.80303421e+02 1.86866440e+02 2.34621399e+02 2.60687897e+02 2.56708527e+02 2.50235947e+02 2.43457565e+02 2.25725677e+02 1.90297165e+02 1.91078705e+02 2.22932892e+02 2.48803223e+02 2.46333191e+02 2.17633545e+02 2.13428741e+02 2.31371338e+02 2.47850998e+02 2.62527405e+02 2.58471558e+02 2.32290329e+02 2.07955902e+02 2.02470657e+02 2.42932449e+02 2.61605225e+02 2.43818893e+02 2.32070084e+02 2.31380356e+02 2.51022736e+02 2.47023712e+02 2.44249496e+02 2.55391693e+02 2.60999634e+02 2.53504410e+02 2.23449905e+02 2.21987228e+02 2.45324783e+02 2.61656708e+02 2.61053101e+02 2.38107651e+02 2.44005234e+02 2.59053925e+02 2.71695038e+02 2.79304657e+02 2.67317688e+02 2.45170227e+02 2.26049362e+02 2.26294754e+02 2.47104431e+02 2.51408417e+02 2.46219818e+02 2.46411453e+02 2.53101288e+02 2.69113708e+02 2.76240906e+02 2.80640045e+02 2.77669434e+02 2.65974823e+02 2.54014328e+02 2.35143921e+02 2.31908905e+02 2.35648315e+02 2.49100861e+02 2.48883514e+02 2.36390182e+02 2.22577042e+02 2.30163147e+02 2.52434845e+02 2.69576233e+02 2.70674896e+02 2.50509720e+02 2.39823502e+02 2.40659454e+02 2.51939606e+02 2.55678757e+02 2.50976883e+02 2.53787933e+02 2.50738144e+02 2.48610184e+02 2.48963242e+02 2.59845215e+02 2.71287567e+02 2.70769196e+02 2.65874512e+02 2.57938354e+02 2.51375793e+02 2.49290344e+02 2.51521851e+02 2.53873947e+02 2.47409180e+02 2.40454086e+02 2.43796494e+02 2.55077957e+02 2.65562958e+02 2.67064575e+02 2.58583557e+02 2.56143341e+02 2.55232544e+02 2.62087006e+02 2.60535553e+02 2.55962265e+02 2.50465317e+02 2.47836090e+02 2.48388367e+02 2.45406509e+02 2.48085159e+02 2.53449493e+02 2.57929474e+02 2.57694672e+02 2.53698181e+02 2.53677155e+02 2.56649994e+02 2.60003296e+02 2.62358856e+02 2.60370758e+02 2.56483856e+02 2.53966751e+02 2.55402756e+02 2.58013031e+02 2.58361755e+02 2.57458466e+02 2.57322418e+02 2.57558197e+02 2.57903076e+02 2.57875732e+02 2.57637299e+02 2.57497375e+02 2.57481384e+02 2.58066742e+02 2.59348053e+02 2.60251038e+02 2.59988251e+02 2.58832184e+02 2.58702972e+02 2.58770050e+02 2.57596313e+02 2.55559082e+02 2.54621841e+02 2.55270279e+02 2.57692505e+02 2.58828278e+02 2.59375641e+02 2.58272491e+02 2.55927872e+02 2.54541107e+02 2.54955200e+02 2.57757172e+02 2.58577393e+02 2.58200806e+02 2.55880478e+02 2.56853302e+02 2.57746765e+02 2.58984741e+02 2.57693451e+02 2.56094055e+02 2.55927475e+02 2.55268631e+02 2.55651428e+02 2.53429504e+02 2.54259964e+02 2.54615051e+02 2.56162567e+02 2.54470291e+02 2.52439697e+02 2.53656723e+02 2.54611374e+02 2.54737442e+02 2.51493851e+02 2.52137955e+02 2.51979599e+02 2.49657990e+02 2.52071640e+02 2.54468384e+02 2.56902740e+02 2.50120819e+02 2.48106842e+02 2.49208847e+02 2.50053925e+02 2.48234604e+02 2.47146729e+02 2.48072052e+02 2.47814102e+02 2.50283539e+02 2.50234680e+02 2.51317261e+02 2.47128082e+02 2.49957428e+02 2.45284195e+02 2.47063828e+02 2.45289444e+02 2.48413589e+02 2.44122055e+02 2.42777664e+02 2.41378021e+02 2.48070221e+02 2.51936554e+02 2.55741608e+02 2.48714172e+02 2.45733398e+02 2.42102020e+02 2.44749435e+02 2.44497665e+02 2.46963486e+02 2.49422729e+02 2.46200729e+02 2.46602814e+02 2.47068054e+02 2.46256836e+02 2.40134933e+02 2.36893585e+02 2.39597366e+02 2.42921494e+02 2.40917221e+02 2.43729614e+02 2.47157654e+02 2.52901215e+02 2.50469574e+02 2.46734772e+02 2.40326126e+02 2.38046143e+02 2.28688751e+02 2.24661118e+02 2.18669479e+02 2.27051575e+02 2.32223862e+02 2.40579956e+02 2.44970505e+02 2.46369308e+02 2.31214722e+02 2.15492828e+02 2.16730316e+02 2.31219955e+02 2.43680634e+02 2.44401138e+02 2.39486389e+02 2.44237930e+02 2.45941803e+02 2.46940460e+02 2.40943878e+02 2.41289352e+02 2.43816574e+02 2.37804962e+02 2.33466263e+02 2.35102783e+02 2.47486862e+02 2.59163055e+02 2.61665649e+02 2.52880051e+02 2.38639893e+02 2.37603668e+02 2.43661789e+02 2.43952682e+02 2.38172165e+02 2.33710999e+02 2.44392014e+02 2.54820526e+02 2.57024292e+02 2.43788239e+02 2.30248581e+02 2.21639969e+02 2.31363693e+02 2.55906677e+02 2.75455597e+02 2.59521088e+02 2.25701218e+02 2.12841339e+02 2.23510788e+02 2.35430313e+02 2.38302673e+02 2.47156693e+02 2.54706573e+02 2.45487198e+02 2.30741821e+02 2.20224670e+02 2.21142273e+02 2.24588440e+02 2.37981995e+02 2.53571640e+02 2.52445602e+02 2.34672958e+02 2.17925766e+02 2.14079926e+02 2.15177673e+02 2.09668213e+02 1.99544220e+02 1.91350067e+02 1.94373993e+02 2.05689301e+02 2.15240723e+02 2.09612030e+02 2.01226028e+02 1.99276886e+02 2.09118500e+02 2.07779236e+02 2.02282623e+02 2.12313705e+02 2.24544052e+02 2.19725235e+02 1.88464310e+02 1.74674301e+02 1.91153946e+02 2.04768524e+02 2.14860382e+02 2.24251526e+02 2.35906586e+02 2.33509140e+02 2.34616470e+02 2.33947891e+02 2.29123276e+02 2.07953323e+02 2.00707840e+02 2.06599945e+02 2.09143951e+02 2.05876541e+02 2.03355576e+02 2.01674164e+02 1.97271133e+02 2.13221954e+02 2.32056183e+02 2.35757034e+02 2.11491211e+02 1.86166992e+02 1.88165268e+02 1.84792221e+02 1.92381378e+02 1.96016235e+02 2.05583038e+02 1.92245972e+02 1.70146759e+02 1.49744385e+02 1.47468628e+02 1.61950012e+02 1.81803375e+02 1.84999222e+02 1.78325424e+02 1.72405441e+02 1.78629684e+02 1.80112488e+02 1.47056091e+02 1.17743599e+02 1.15440071e+02 1.51977081e+02 1.82402420e+02 1.80767792e+02 1.57774796e+02 1.12286560e+02 4.22507362e+01 1.24265203e+01 -9.01045380e+01 -2.13622570e+01 -1.38483047e+02 -1.95623340e+03 -6.07578674e+02 -9.88912231e+02 -3.51771533e+03 6.54582214e+02 4.18550415e+02 6.68868042e+02 2.07419174e+02 -2.08526169e+02 -8.95540039e+03 -2.30549746e+04 -177720176. -470063296. 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. 0. 0. 0. 0. 0. 0. 0. 0. -711993856. 95752328. -50690692. -1.54831104e+04 -5.84260498e+03 -9.10345764e+02 -2.26164886e+02 6.58670521e+00 5.67432251e+01 4.10392876e+01 3.61991539e+01 6.92352753e+01 1.06393616e+02 1.06940552e+02 1.10197350e+02 1.10437866e+02 1.03778214e+02 8.43267365e+01 5.85958366e+01 9.03892822e+01 1.36406494e+02 1.47298401e+02 1.09847290e+02 8.33936462e+01 9.79333267e+01 1.12578476e+02 1.06496635e+02 9.28064423e+01 6.94899216e+01 5.97478790e+01 5.99822388e+01 8.21939545e+01 9.14912338e+01 9.66205444e+01 8.51693497e+01 1.15634743e+02 1.58495071e+02 1.69898422e+02 1.45652954e+02 1.14253700e+02 1.18194870e+02 1.36882751e+02 1.41441177e+02 1.51232040e+02 1.55383835e+02 1.64431793e+02 1.74354630e+02 1.74996384e+02 1.59841492e+02 1.44338120e+02 1.37711441e+02 1.54857605e+02 1.51141479e+02 1.42318481e+02 1.38998444e+02 1.48848480e+02 1.59311432e+02 1.57541229e+02 1.37401443e+02 9.37625275e+01 5.01307945e+01 3.38019104e+01 5.96293335e+01 9.02468262e+01 1.07289200e+02 7.87223740e+01 4.93966751e+01 5.87739906e+01 9.37239075e+01 1.28115265e+02 1.28728546e+02 1.26290955e+02 1.47012787e+02 1.82338623e+02 1.52268356e+02 9.88077240e+01 5.38346672e+01 7.50774536e+01 1.02831367e+02 1.03638885e+02 1.05672211e+02 1.05543884e+02 1.11643646e+02 1.08356392e+02 1.00053360e+02 7.97653275e+01 6.75227585e+01 6.34388542e+01 7.11747055e+01 6.95302658e+01 3.18266926e+01 -1.43935089e+01 -2.87880361e-01 3.61073914e+01 7.77465439e+01 6.15025368e+01 4.28559494e+01 2.01554260e+01 6.69583797e+00 3.18228321e+01 7.30354614e+01 8.21342392e+01 6.08163109e+01 1.37327490e+01 1.15392189e+01 2.53025551e+01 5.22328835e+01 7.04808960e+01 5.44273453e+01 5.78738136e+01 5.39790001e+01 6.90306168e+01 5.46722488e+01 5.13967285e+01 5.36368980e+01 3.24892616e+01 7.07155526e-01 5.53144503e+00 3.69446373e+01 7.01164856e+01 7.34004822e+01 7.67956009e+01 7.53842239e+01 7.42782364e+01 8.25059738e+01 8.41873856e+01 4.03081169e+01 -1.53160934e+01 -2.39338207e+01 7.94364309e+00 4.87837372e+01 6.90844955e+01 8.22255402e+01 7.48225861e+01 5.96297150e+01 4.82972450e+01 6.40646057e+01 5.93061523e+01 5.92230339e+01 5.12884140e+01 4.26595383e+01 3.18856640e+01 3.15663548e+01 3.22174950e+01 3.84355278e+01 3.25455551e+01 2.34031258e+01 2.25861664e+01 1.51879730e+01 8.88202477e+00 -1.07818820e-01 -5.46201849e+00 8.65928650e+00 1.16628895e+01 1.84506302e+01 2.08402805e+01 2.49289417e+01 4.18199234e+01 4.28612061e+01 3.12348442e+01 -3.14097595e+01 -6.90613251e+01 -7.70605850e+01 -5.46169815e+01 -3.18856850e+01 -2.33232059e+01 -1.37894220e+01 -8.11522388e+00 -1.70253201e+01 -1.98613033e+01 -1.77565937e+01 -1.87581177e+01 -2.04601040e+01 -1.81256084e+01 2.66997147e+01 7.14892426e+01 1.02715775e+02 9.86264420e+01 5.62112274e+01 8.94138908e+00 -3.14494801e+01 -2.90343266e+01 -2.05131855e+01 -1.63766613e+01 -1.87523804e+01 -1.47077837e+01 -1.28722019e+01 -8.04764462e+00 2.41199470e+00 -7.03348684e+00 -1.38931065e+01 -1.81403294e+01 -1.45595093e+01 -1.23993130e+01 -2.97730789e+01 -3.83578835e+01 -4.12938957e+01 -3.86691284e+01 -2.64200268e+01 4.64407253e+00 5.14621925e+01 7.18116302e+01 7.48152313e+01 5.98795509e+01 7.33820801e+01 3.44698753e+01 -1.38010550e+01 -5.73049278e+01 -5.44015961e+01 -4.40481606e+01 -4.36107597e+01 -4.70310555e+01 -5.18934937e+01 -6.64015121e+01 -6.48910141e+01 -6.67704239e+01 -5.40314636e+01 -5.05234451e+01 -4.66072121e+01 -8.67983322e+01 -1.36288467e+02 -1.22086182e+02 -7.99718323e+01 -3.42048798e+01 -1.68196754e+01 -6.17374992e+00 3.67370338e+01 5.78804321e+01 4.67475510e+01 1.38665733e+01 -4.10995102e+01 -3.17494488e+01 -2.25913239e+01 -1.88219714e+00 -5.89581680e+00 -1.79133034e+01 -1.66837921e+01 -1.92679863e+01 -1.59592495e+01 -3.28218231e+01 -4.61871986e+01 -4.68890114e+01 -1.26791143e+01 2.68734875e+01 6.35204315e+01 7.16033859e+01 -2.23053885e+00 -8.65769196e+01 -1.28145828e+02 -9.92949829e+01 -5.28799667e+01 -5.03728943e+01 -3.95145798e+01 -4.57274017e+01 -5.05974693e+01 -6.08292923e+01 -7.00344543e+01 -7.95058823e+01 -7.83351135e+01 -7.84183731e+01 -1.02266785e+02 -1.46183060e+02 -1.53703751e+02 -1.32708740e+02 -1.02074875e+02 -8.22064285e+01 -6.23929405e+01 -5.71165390e+01 -7.88463669e+01 -8.01414566e+01 -6.05228806e+01 -6.21246223e+01 -8.15630341e+01 -1.05563103e+02 -1.11437462e+02 -1.03123741e+02 -1.00670044e+02 -9.72533112e+01 -9.89776077e+01 -9.28279572e+01 -9.58301315e+01 -9.87952194e+01 -1.16612900e+02 -1.18535011e+02 -1.19166222e+02 -8.21054611e+01 -4.52699203e+01 -5.27292061e+01 -8.67438126e+01 -1.17448082e+02 -1.01866310e+02 -1.00514580e+02 -1.01391518e+02 -9.98567200e+01 -9.02695236e+01 -8.52497940e+01 -6.71260910e+01 -5.56209526e+01 -6.02472038e+01 -9.67910919e+01 -1.28358536e+02 -1.33160706e+02 -1.22394127e+02 -1.41544403e+02 -1.67247482e+02 -1.84218719e+02 -1.70637009e+02 -1.42695816e+02 -1.46552979e+02 -1.46382721e+02 -1.45209625e+02 -1.31003784e+02 -1.25807976e+02 -1.36460220e+02 -1.46693436e+02 -1.47718597e+02 -1.42904343e+02 -1.46426132e+02 -1.50164017e+02 -1.40760880e+02 -1.32977600e+02 -1.05908302e+02 -8.39826355e+01 -8.80778580e+01 -1.04794548e+02 -1.21750038e+02 -1.19875618e+02 -1.33424866e+02 -1.49357529e+02 -1.44440872e+02 -1.02853920e+02 -7.02824020e+01 -6.84010773e+01 -1.06074913e+02 -1.33819519e+02 -1.31070038e+02 -1.19484726e+02 -1.19083122e+02 -1.32202438e+02 -1.14631577e+02 -8.34825821e+01 -6.99496002e+01 -9.45525894e+01 -1.34829773e+02 -1.32319336e+02 -1.34241882e+02 -1.31803635e+02 -1.38963547e+02 -1.41049362e+02 -1.31469986e+02 -1.24404205e+02 -1.16308121e+02 -1.30566422e+02 -1.39539841e+02 -1.41109619e+02 -1.01070786e+02 -5.39985542e+01 -4.93322220e+01 -8.99413300e+01 -1.33419083e+02 -1.38967758e+02 -1.55653412e+02 -1.56168488e+02 -1.51993271e+02 -1.03210365e+02 -7.54886627e+01 -3.70120277e+01 -4.03005066e+01 -6.70291138e+01 -1.05126152e+02 -1.44929062e+02 -1.20375999e+02 -9.75906372e+01 -1.27942596e+02 -1.94042847e+02 -2.22206848e+02 -1.91813995e+02 -1.61146255e+02 -1.66443176e+02 -1.71381943e+02 -1.76552948e+02 -1.77276230e+02 -1.86298859e+02 -1.89345032e+02 -1.91906876e+02 -1.94613007e+02 -1.99451355e+02 -2.06378494e+02 -2.09016937e+02 -1.99762924e+02 -1.93435333e+02 -1.69042419e+02 -1.51368164e+02 -1.54347702e+02 -1.82387573e+02 -2.15136749e+02 -1.85949310e+02 -1.47893692e+02 -1.73291443e+02 -2.35782990e+02 -2.41683975e+02 -1.70678299e+02 -1.29143082e+02 -1.50671021e+02 -1.90322815e+02 -1.75325974e+02 -1.42958221e+02 -1.33978317e+02 -1.46765396e+02 -1.77509857e+02 -1.76789200e+02 -1.75817429e+02 -1.79019699e+02 -1.80805420e+02 -2.04670563e+02 -2.27899292e+02 -2.07210831e+02 -1.60273315e+02 -1.35051971e+02 -1.50650681e+02 -1.71774002e+02 -1.48515228e+02 -1.27522987e+02 -1.23156593e+02 -1.47216431e+02 -1.79257828e+02 -1.75011978e+02 -1.69627731e+02 -1.61077316e+02 -1.78391068e+02 -1.70903656e+02 -1.48251404e+02 -1.38578568e+02 -1.44051407e+02 -1.80519562e+02 -1.96606354e+02 -2.06217270e+02 -1.99940018e+02 -1.95977402e+02 -2.30306244e+02 -2.73874542e+02 -2.64270142e+02 -2.12984955e+02 -1.74811188e+02 -1.88140747e+02 -2.14660797e+02 -1.99171783e+02 -1.72261368e+02 -1.69782257e+02 -1.88887344e+02 -2.10872910e+02 -2.19862076e+02 -2.20358032e+02 -2.19867783e+02 -2.12796310e+02 -2.11597763e+02 -2.06001358e+02 -1.98085175e+02 -1.91412384e+02 -1.98702133e+02 -2.11696518e+02 -2.21988998e+02 -2.21565552e+02 -2.19484207e+02 -2.38490295e+02 -2.61523926e+02 -2.41784210e+02 -1.99959366e+02 -1.77813400e+02 -2.02876938e+02 -2.28713974e+02 -2.44618408e+02 -2.52002960e+02 -2.52566193e+02 -2.45054932e+02 -2.37137482e+02 -2.41281494e+02 -2.41345245e+02 -2.46016724e+02 -2.44531021e+02 -2.51505844e+02 -2.51913574e+02 -2.54622559e+02 -2.39358246e+02 -2.31189789e+02 -2.36798630e+02 -2.51730942e+02 -2.58729614e+02 -2.46396225e+02 -2.34902115e+02 -2.27332169e+02 -2.15459335e+02 -1.96044418e+02 -1.96355408e+02 -2.12131363e+02 -2.17754822e+02 -1.85841354e+02 -1.64509567e+02 -1.79121231e+02 -2.03911560e+02 -1.97583389e+02 -1.78055603e+02 -1.75725830e+02 -1.96465240e+02 -2.12244583e+02 -2.16401169e+02 -2.18646683e+02 -2.14306381e+02 -2.14703888e+02 -2.15227249e+02 -2.25362778e+02 -2.16589218e+02 -2.02738510e+02 -1.94942459e+02 -2.07073593e+02 -2.21911896e+02 -2.19741623e+02 -2.09235001e+02 -2.19590775e+02 -2.42955963e+02 -2.53654541e+02 -2.48878601e+02 -2.36355515e+02 -2.41355560e+02 -2.39716751e+02 -2.40571564e+02 -2.40701553e+02 -2.44751877e+02 -2.43496902e+02 -2.40588150e+02 -2.42086243e+02 -2.45300537e+02 -2.50325943e+02 -2.47895813e+02 -2.45256866e+02 -2.47089310e+02 -2.37829239e+02 -2.28310303e+02 -2.28247467e+02 -2.40791473e+02 -2.56278870e+02 -2.60265106e+02 -2.61283142e+02 -2.69256622e+02 -2.79453644e+02 -2.77920746e+02 -2.66766724e+02 -2.54923660e+02 -2.53367371e+02 -2.54202148e+02 -2.40794174e+02 -2.29049698e+02 -2.27444763e+02 -2.38936279e+02 -2.46770370e+02 -2.46327042e+02 -2.47532211e+02 -2.52621933e+02 -2.52383667e+02 -2.58564911e+02 -2.67156158e+02 -2.61696289e+02 -2.48148331e+02 -2.38664948e+02 -2.44684738e+02 -2.44573639e+02 -2.31605438e+02 -2.22256287e+02 -2.26556747e+02 -2.41897797e+02 -2.47625534e+02 -2.43965240e+02 -2.40795639e+02 -2.47354797e+02 -2.56963959e+02 -2.56908722e+02 -2.51116241e+02 -2.50289856e+02 -2.52854858e+02 -2.58896851e+02 -2.61277008e+02 -2.63378815e+02 -2.63380096e+02 -2.61323914e+02 -2.61830353e+02 -2.63030762e+02 -2.59591888e+02 -2.54959915e+02 -2.52219208e+02 -2.55451431e+02 -2.58262360e+02 -2.55516403e+02 -2.50844437e+02 -2.51187927e+02 -2.55587677e+02 -2.67991699e+02 -2.85344299e+02 -2.96923370e+02 -3.09125854e+02 -3.06714050e+02 -2.63983917e+02 -2.41630783e+02 -2.22842880e+02 -2.53672729e+02 -2.72425629e+02 -2.69593353e+02 -2.46960052e+02 -4.12043671e+02 -5.45339111e+02 2.68783960e+03 -1244824576. 0. 0. 0. 0. 357199328. 357199328. -692914048. -145753472. -7.42732080e+03 45655232. -3.29351465e+03 -3.52398853e+03 -5.42480859e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 663051200. 105610992. -1.33806714e+03 -9.84275635e+02 -2.70593628e+02 -3.70289673e+02 -2.65216644e+02 -1.11190308e+02 -2.07629501e+02 -2.04393112e+02 -2.26674103e+02 -2.24049149e+02 -2.22427628e+02 -2.25173386e+02 -2.27215561e+02 -2.23526321e+02 -2.19083160e+02 -2.21532516e+02 -2.29905411e+02 -2.33947525e+02 -2.27411469e+02 -2.14930237e+02 -2.14326447e+02 -2.23537033e+02 -2.37634995e+02 -2.41018677e+02 -2.34851776e+02 -2.36239456e+02 -2.42815689e+02 -2.43055435e+02 -2.35729080e+02 -2.29230118e+02 -2.37354630e+02 -2.54769974e+02 -2.58755157e+02 -2.46094284e+02 -2.30889481e+02 -2.22118668e+02 -2.22802338e+02 -2.17380707e+02 -2.09634811e+02 -2.04620148e+02 -2.15782333e+02 -2.45362411e+02 -2.63464447e+02 -2.54990540e+02 -2.33281235e+02 -2.16509140e+02 -2.16922852e+02 -2.23683044e+02 -2.33636063e+02 -2.31823517e+02 -2.37084473e+02 -2.43193405e+02 -2.36343597e+02 -2.11481018e+02 -1.85996674e+02 -1.89319595e+02 -2.27611710e+02 -2.45885681e+02 -2.36723709e+02 -2.11602844e+02 -2.14738129e+02 -2.34557022e+02 -2.34107574e+02 -2.15415268e+02 -1.93411133e+02 -2.01212692e+02 -2.31590225e+02 -2.58097015e+02 -2.48712784e+02 -2.29635117e+02 -2.18719589e+02 -2.25444138e+02 -2.23110016e+02 -2.06592575e+02 -1.89852112e+02 -1.97085281e+02 -2.06129929e+02 -2.00545563e+02 -1.85749100e+02 -1.79575882e+02 -1.88005051e+02 -2.02217682e+02 -2.20947952e+02 -2.27053467e+02 -2.20181458e+02 -2.11013351e+02 -2.12317184e+02 -1.91443253e+02 -1.59622513e+02 -1.47879471e+02 -1.76988907e+02 -2.27161911e+02 -2.53451889e+02 -2.39893692e+02 -1.98869873e+02 -1.60225296e+02 -1.43074493e+02 -1.50205399e+02 -1.56653793e+02 -1.49966431e+02 -1.63254913e+02 -2.01218063e+02 -2.32265167e+02 -2.22107056e+02 -1.89312347e+02 -1.79312988e+02 -1.91937103e+02 -2.19574036e+02 -2.24012375e+02 -2.03729706e+02 -1.88685257e+02 -1.90331070e+02 -1.93414795e+02 -1.72931931e+02 -1.34217850e+02 -1.27164764e+02 -1.62129669e+02 -2.01958694e+02 -2.02702301e+02 -1.68425354e+02 -1.43413422e+02 -1.40583511e+02 -1.65429932e+02 -1.94786194e+02 -2.09907440e+02 -1.94116852e+02 -1.94210297e+02 -2.12843826e+02 -2.17324326e+02 -1.86697937e+02 -1.51617676e+02 -1.52797241e+02 -1.82636948e+02 -2.01203934e+02 -1.83031097e+02 -1.67900787e+02 -1.58977325e+02 -1.73337570e+02 -1.59264206e+02 -1.35728027e+02 -1.26544304e+02 -1.64213577e+02 -2.39043594e+02 -2.75080597e+02 -2.44163452e+02 -1.89886520e+02 -1.76740311e+02 -1.92680740e+02 -2.14637604e+02 -2.10389633e+02 -2.09333359e+02 -2.28935104e+02 -2.62366943e+02 -2.80245361e+02 -2.44580536e+02 -1.71851730e+02 -1.30668320e+02 -1.70320435e+02 -2.09448090e+02 -2.08398804e+02 -1.81009857e+02 -2.05583023e+02 -2.62900269e+02 -2.57695801e+02 -2.01466904e+02 -1.52744507e+02 -1.87151138e+02 -2.67042419e+02 -3.08984650e+02 -2.79483398e+02 -2.19280762e+02 -1.88418411e+02 -1.87280151e+02 -1.76282867e+02 -1.59771286e+02 -1.75744049e+02 -2.24012695e+02 -2.84462860e+02 -2.52946884e+02 -1.93000061e+02 -1.47112473e+02 -1.52619537e+02 -1.90429504e+02 -2.11135696e+02 -2.27680634e+02 -2.28967773e+02 -2.46609558e+02 -2.79840607e+02 -2.57787476e+02 -1.97305756e+02 -1.49544220e+02 -1.55424469e+02 -2.24229019e+02 -2.65440369e+02 -2.55016663e+02 -1.90024399e+02 -1.59754623e+02 -1.65640137e+02 -1.60069366e+02 -1.02639450e+02 -7.87265015e+01 -1.28450226e+02 -2.04595245e+02 -2.18812088e+02 -1.85819229e+02 -1.27704857e+02 -9.68508835e+01 -1.02596489e+02 -1.33513885e+02 -1.66204483e+02 -1.62102341e+02 -1.82229355e+02 -2.06835876e+02 -1.81512787e+02 -1.32539688e+02 -1.12705284e+02 -1.20156845e+02 -1.67034241e+02 -1.76998245e+02 -1.63720261e+02 -1.45187347e+02 -1.39237167e+02 -1.66166336e+02 -1.41195328e+02 -9.99771805e+01 -7.91525345e+01 -7.23834457e+01 -1.42572403e+02 -1.85957123e+02 -1.59687668e+02 -9.08310547e+01 -6.84503860e+01 -1.19860817e+02 -1.62448486e+02 -1.61894821e+02 -1.24683014e+02 -1.26312103e+02 -1.56971115e+02 -1.67241119e+02 -1.17685860e+02 -1.00414703e+02 -1.29059799e+02 -1.59755798e+02 -1.12298759e+02 -9.71943970e+01 -1.21229050e+02 -1.50441467e+02 -1.66448334e+02 -1.38327225e+02 -1.60802383e+02 -1.77572021e+02 -1.84571289e+02 -1.97616104e+02 -2.11578293e+02 -2.23709579e+02 -1.62145538e+02 -1.36720184e+02 -1.22802261e+02 -1.66880142e+02 -1.49848404e+02 -1.46222473e+02 -1.73180222e+02 -2.16307953e+02 -2.27069870e+02 -1.47333359e+02 -9.63067017e+01 -9.63173828e+01 -1.61729477e+02 -1.90361572e+02 -1.78921188e+02 -1.46967453e+02 -1.28035278e+02 -1.68710373e+02 -1.50423904e+02 -1.17620720e+02 -4.98796768e+01 -2.57792435e+01 -4.08231010e+01 -9.45823212e+01 -1.43826157e+02 -1.08989319e+02 -5.65998535e+01 -2.74511986e+01 -5.38979683e+01 -3.16483498e+01 -4.09700241e+01 -8.14573822e+01 -1.41749878e+02 -1.33561920e+02 -3.87887077e+01 -1.34121284e+01 -5.66537781e+01 -1.31499313e+02 -1.08149750e+02 -6.74359665e+01 -5.87166710e+01 -7.48735886e+01 -1.11361603e+02 -9.96088257e+01 -1.17519539e+02 -6.07004242e+01 -4.63385201e+01 -3.97168045e+01 -8.70675201e+01 -9.62753677e+01 -6.52782898e+01 -2.40262814e+01 -3.23177223e+01 -2.15683861e+01 4.01270981e+01 8.03113403e+01 7.99806824e+01 5.15695190e+01 5.70769234e+01 8.69587936e+01 1.09524406e+02 8.37022858e+01 1.52819748e+01 -2.44217930e+01 -3.37655563e+01 -2.75518932e+01 -4.23597450e+01 -8.80858078e+01 -1.16779915e+02 -1.42292099e+02 -8.94438324e+01 -5.73977242e+01 -2.71748562e+01 -3.75036812e+01 -2.25997829e+01 1.37370378e-01 2.89872551e+01 2.02567520e+01 1.69121990e+01 5.66589508e+01 9.84860077e+01 7.54189301e+01 1.27547169e+01 -1.44110107e+00 -9.28939247e+00 -5.72508583e+01 -1.01102982e+02 -1.20726395e+02 -5.52382965e+01 -5.08800774e+01 -3.82437820e+01 -2.58527803e+00 1.94773841e+00 -4.06840935e+01 -1.40817276e+02 -1.56277298e+02 -6.94921799e+01 1.29008875e+01 1.06484642e+01 -5.22658195e+01 -1.02617546e+02 -7.41802444e+01 -2.82422409e+01 2.42056980e+01 1.99806957e+01 -2.49489880e+01 -6.37134857e+01 -1.22927612e+02 -1.20330605e+02 -1.21038361e+02 -1.31665802e+02 -1.31213821e+02 -1.39433167e+02 -5.84755478e+01 -4.94630547e+01 -3.61638069e+01 -3.41643600e+01 -5.23359070e+01 -9.89267731e+01 -2.21461700e+02 -2.41197952e+02 -1.60204895e+02 -1.51290762e+00 8.20604401e+01 -1.06843014e+01 -1.26262329e+02 -1.33214249e+02 8.16254234e+00 1.45663330e+02 1.12307190e+02 -2.94486980e+01 -1.15827431e+02 -1.01785271e+02 -1.55929327e+01 -1.98153973e+01 -7.67773514e+01 -1.17605522e+02 -1.24333061e+02 -6.00402603e+01 -5.74395599e+01 -1.00237625e+02 -1.31507599e+02 -1.22599625e+02 -6.56375656e+01 -8.65870438e+01 -9.75599823e+01 -1.38298264e+01 8.58972397e+01 8.91167221e+01 -8.08397827e+01 -1.95320297e+02 -1.69431564e+02 -2.74098549e+01 5.61167107e+01 3.60252380e+01 -6.28386078e+01 -1.03470436e+02 -1.07517860e+02 -2.73796806e+01 -2.63112202e+01 -3.29018211e+01 -5.46438103e+01 -8.91706924e+01 -3.64168053e+01 -1.37423098e+00 9.10113983e+01 8.39535751e+01 4.18478661e+01 -3.08743572e+01 -1.34951355e+02 -1.64074951e+02 -9.44889984e+01 6.19896126e+01 1.47047592e+02 7.69205627e+01 -7.87374496e+01 -1.31796143e+02 -1.53223455e+00 1.55525146e+02 1.54145142e+02 -2.38215852e+00 -6.78051758e+01 -5.79679298e+01 3.15831280e+01 2.58939743e+01 -1.48290386e+01 -8.50202713e+01 -1.21661812e+02 -1.20880592e+02 -1.46285431e+02 -1.46203201e+02 -7.94302521e+01 3.25905418e+01 7.28413239e+01 -5.34725375e-02 -7.90926743e+01 -5.36724167e+01 5.96121559e+01 1.51464691e+02 1.08853729e+02 -1.15187616e+01 -4.82348595e+01 2.67253423e+00 9.83454971e+01 8.65956039e+01 6.13160074e-01 -5.13505707e+01 -1.06008072e+02 -4.09710388e+01 -6.08087807e+01 -1.87943802e+01 -2.10341091e+01 -2.58047047e+01 -5.40220032e+01 -1.04154678e+02 -6.82411728e+01 -5.70242357e+00 7.02761078e+01 4.65776863e+01 -3.52431679e+01 -1.14625671e+02 -6.18847351e+01 4.59113045e+01 1.18572182e+02 1.12170303e+02 4.28589897e+01 2.21103001e+01 1.07836514e+01 4.04473686e+01 1.08976383e+01 -3.27558403e+01 -8.39518204e+01 -1.28083221e+02 -1.08110428e+02 -8.83042145e+00 6.61990814e+01 8.09261703e+01 3.89194756e+01 -1.53158712e+00 -6.19904175e+01 -8.84718552e+01 -3.71167469e+00 1.33173248e+02 1.80559296e+02 9.20665054e+01 -2.50437660e+01 -2.77990875e+01 8.23516617e+01 2.02893799e+02 1.84853836e+02 4.83615494e+01 -8.42148209e+01 -1.26455307e+02 -4.21594887e+01 3.28688889e+01 2.51261826e+01 -1.59873629e+01 -4.66010208e+01 1.69077454e+01 1.86520615e+01 3.67621803e+01 7.39720383e+01 9.54870224e+01 9.02291260e+01 1.28145752e+01 2.59816742e+01 1.10072067e+02 2.09933563e+02 1.87083496e+02 4.40278702e+01 -6.34850349e+01 -1.77697983e+01 1.03124413e+02 1.93771912e+02 1.88620926e+02 8.26825027e+01 -1.29127722e+01 -5.73602524e+01 2.87935295e+01 7.45132599e+01 1.15689972e+02 1.11360016e+02 9.97232971e+01 1.16690277e+02 1.14651512e+02 1.73114151e+02 2.09923401e+02 2.13656906e+02 1.73296783e+02 7.81807327e+01 3.65615349e+01 9.47431335e+01 1.80355270e+02 2.10773758e+02 1.50908569e+02 6.83225174e+01 7.92458725e+01 1.37363907e+02 2.26618042e+02 2.35938995e+02 1.51043045e+02 6.74081497e+01 3.18282108e+01 9.88592377e+01 1.65107620e+02 1.59390579e+02 1.13292053e+02 4.10744362e+01 3.24426422e+01 4.37612610e+01 8.98259583e+01 1.53587296e+02 1.49610184e+02 8.75651169e+01 -1.11738195e+01 -4.05566254e+01 2.99870796e+01 1.15010880e+02 1.73541534e+02 1.33786774e+02 5.88111076e+01 2.12533875e+01 4.57442856e+01 1.03555931e+02 1.00648514e+02 6.03109169e+01 1.89253254e+01 2.25091553e+01 8.65667191e+01 1.36119278e+02 1.21095367e+02 8.23268814e+01 8.32170868e+00 1.68678703e+01 1.49369431e+01 4.84793282e+01 8.83746643e+01 1.12875580e+02 1.30731354e+02 7.69917908e+01 3.77102585e+01 6.12268906e+01 1.17166672e+02 1.68458862e+02 1.29912567e+02 6.64570694e+01 2.73764687e+01 8.97508621e+01 2.06139069e+02 2.60167542e+02 1.96597122e+02 7.92906570e+01 1.43485231e+01 5.68953667e+01 1.39305939e+02 2.02123657e+02 2.61611938e+02 3.21579895e+02 3.15551849e+02 2.88753021e+02 2.47288379e+03 4.90176123e+03 1.33909424e+04 2.88836836e+04 -281970400. -68863568. 121455656. -295212160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 832060288. -590784000. 59325776. 254382512. 143809264. 2.32940859e+04 1.03033408e+04 4.75208691e+03 2.86068823e+03 7.43706848e+02 3.84446991e+02 3.39254608e+02 3.03989105e+02 2.31816711e+02 1.32789566e+02 1.01037285e+02 1.26935532e+02 2.00125809e+02 2.37262665e+02 2.28018478e+02 1.71437088e+02 1.05009132e+02 1.05298882e+02 1.24417709e+02 1.45278778e+02 1.45867050e+02 1.51856064e+02 1.76766312e+02 1.46097839e+02 1.40730804e+02 1.93155029e+02 2.37466476e+02 2.05500031e+02 1.10936852e+02 6.05485535e+01 1.21168930e+02 1.96160614e+02 2.40380051e+02 2.17769348e+02 1.32820572e+02 6.83240509e+01 3.50783195e+01 1.05224411e+02 1.55208649e+02 1.64381546e+02 1.19469696e+02 9.01680145e+01 1.14440514e+02 1.20035149e+02 1.45538116e+02 1.75001205e+02 1.91580872e+02 1.67526840e+02 8.63813858e+01 8.04910812e+01 1.51681702e+02 2.37817581e+02 2.56585052e+02 1.88591675e+02 1.22264839e+02 1.22282593e+02 1.75068726e+02 1.96341309e+02 1.56806885e+02 8.26286316e+01 6.35878525e+01 8.86272583e+01 1.66581482e+02 2.23568558e+02 2.27638199e+02 1.79034531e+02 1.19126358e+02 7.80611038e+01 6.23901978e+01 7.76466904e+01 1.10906982e+02 1.51138260e+02 1.69701202e+02 1.61261749e+02 1.64295074e+02 2.07415527e+02 2.48004562e+02 2.47899338e+02 1.96893295e+02 1.61899704e+02 1.66150452e+02 1.86346954e+02 2.22714096e+02 2.47384201e+02 2.31072281e+02 1.78008255e+02 1.52094925e+02 1.82873016e+02 2.21712769e+02 2.12994156e+02 1.90783600e+02 1.82063934e+02 1.97051208e+02 1.85533844e+02 1.89010651e+02 2.10081329e+02 2.26962463e+02 2.12427246e+02 1.62741302e+02 1.59407730e+02 2.08774567e+02 2.70440521e+02 2.86858276e+02 2.44655945e+02 2.04866348e+02 1.85940918e+02 1.95946854e+02 2.08174088e+02 2.13569885e+02 1.99355316e+02 1.76341599e+02 1.64236938e+02 1.92904282e+02 2.35469269e+02 2.49140533e+02 2.31830444e+02 2.16378006e+02 2.14967285e+02 1.99204651e+02 2.00209137e+02 2.31564056e+02 2.72026794e+02 2.66712067e+02 2.21264908e+02 2.01721512e+02 2.32147049e+02 2.67757355e+02 2.69751068e+02 2.33288177e+02 1.97464508e+02 1.87305984e+02 2.00427094e+02 2.28710648e+02 2.51331375e+02 2.46085892e+02 2.18303696e+02 1.97313980e+02 2.13058243e+02 2.41598175e+02 2.53651108e+02 2.44432739e+02 2.28492218e+02 2.18987289e+02 2.02528473e+02 1.97750397e+02 2.06023590e+02 2.19831192e+02 2.20948486e+02 2.01042496e+02 1.93475754e+02 2.10223740e+02 2.47708954e+02 2.69791992e+02 2.59479614e+02 2.24714264e+02 2.01153702e+02 2.05394501e+02 2.23626358e+02 2.30724655e+02 2.25096313e+02 2.23330795e+02 2.13561981e+02 2.18915924e+02 2.21742477e+02 2.30770309e+02 2.44144867e+02 2.48655167e+02 2.52606445e+02 2.32861038e+02 2.24722412e+02 2.35212097e+02 2.44841278e+02 2.40421036e+02 2.16840958e+02 2.09518692e+02 2.15149048e+02 2.26183777e+02 2.33423508e+02 2.34791458e+02 2.29027100e+02 2.25482758e+02 2.24270172e+02 2.33981216e+02 2.31315186e+02 2.26271515e+02 2.17656693e+02 2.08453293e+02 2.02747742e+02 1.98685715e+02 2.08074753e+02 2.22383957e+02 2.30137497e+02 2.29830902e+02 2.22772797e+02 2.22044891e+02 2.30361908e+02 2.39509232e+02 2.42107162e+02 2.31736832e+02 2.19037933e+02 2.14333267e+02 2.17555191e+02 2.23135086e+02 2.25468521e+02 2.25053421e+02 2.23837921e+02 2.21642456e+02 2.24101593e+02 2.27373611e+02 2.29610474e+02 2.27394272e+02 2.26635422e+02 2.26139648e+02 2.25499069e+02 2.25551132e+02 2.26875305e+02 2.28008026e+02 2.27925964e+02 2.28050339e+02 2.28540985e+02 2.29031067e+02 2.28950333e+02 2.28651718e+02 2.28434265e+02 2.28475388e+02 2.29326401e+02 2.29997086e+02 2.29400635e+02 2.27697601e+02 2.26954346e+02 2.28169495e+02 2.29491608e+02 2.29049332e+02 2.28711395e+02 2.28396790e+02 2.28054520e+02 2.28081909e+02 2.28325027e+02 2.28370361e+02 2.28332108e+02 2.26896896e+02 2.26386353e+02 2.23954620e+02 2.24676025e+02 2.25126221e+02 2.26857330e+02 2.26090668e+02 2.25965439e+02 2.27914871e+02 2.28174164e+02 2.29870209e+02 2.30884628e+02 2.32342422e+02 2.31014679e+02 2.27808655e+02 2.27665466e+02 2.27405441e+02 2.26148285e+02 2.23812683e+02 2.24415466e+02 2.25205780e+02 2.25385712e+02 2.23905243e+02 2.24637100e+02 2.25173706e+02 2.24198090e+02 2.21136383e+02 2.20373291e+02 2.17812531e+02 2.17255280e+02 2.18760361e+02 2.20217651e+02 2.22197220e+02 2.19606903e+02 2.18990326e+02 2.17477554e+02 2.18810928e+02 2.19414597e+02 2.23324051e+02 2.22733139e+02 2.21989441e+02 2.16927429e+02 2.18959686e+02 2.18564774e+02 2.19313004e+02 2.18573242e+02 2.22971985e+02 2.23647003e+02 2.20085114e+02 2.16358994e+02 2.18374039e+02 2.18875748e+02 2.15368591e+02 2.17659958e+02 2.23981110e+02 2.27434830e+02 2.24977707e+02 2.23895905e+02 2.22663162e+02 2.24307785e+02 2.20680771e+02 2.22798553e+02 2.21324738e+02 2.23017288e+02 2.24707870e+02 2.26566406e+02 2.23529160e+02 2.20203018e+02 2.16568283e+02 2.20497818e+02 2.14233978e+02 2.02862915e+02 1.98953888e+02 2.06614670e+02 2.20803421e+02 2.21314606e+02 2.19390442e+02 2.18207169e+02 2.18737167e+02 2.22764908e+02 2.24066208e+02 2.22249283e+02 2.22133301e+02 2.24023987e+02 2.27420090e+02 2.19580353e+02 2.15697662e+02 2.14833603e+02 2.16569031e+02 2.13307770e+02 2.13144592e+02 2.13734818e+02 2.15428482e+02 2.22325241e+02 2.25666336e+02 2.22958694e+02 2.13346786e+02 2.06662262e+02 2.08777206e+02 2.14682999e+02 2.19986053e+02 2.18704651e+02 2.05532623e+02 1.92704575e+02 1.94138977e+02 2.04048782e+02 2.19030380e+02 2.18713745e+02 2.17143585e+02 2.08791992e+02 2.01734573e+02 1.94484879e+02 1.87215393e+02 1.85239243e+02 1.85454666e+02 1.88431961e+02 1.98562164e+02 2.02459381e+02 2.00758026e+02 1.97052933e+02 2.00411774e+02 1.97806335e+02 1.91477890e+02 1.89155029e+02 1.91249954e+02 1.97309296e+02 1.94480621e+02 1.81155243e+02 1.62116348e+02 1.64230148e+02 1.86065918e+02 2.03517990e+02 1.93217804e+02 1.71878525e+02 1.68824646e+02 1.74494263e+02 1.91815231e+02 1.85581818e+02 1.77196228e+02 1.69541718e+02 1.69960281e+02 1.74347107e+02 1.67213852e+02 1.51036163e+02 1.35284561e+02 1.50523163e+02 1.80217255e+02 1.90855743e+02 1.78506958e+02 1.73141632e+02 1.78430832e+02 1.85781891e+02 1.89040298e+02 1.79146347e+02 1.63578552e+02 1.57008255e+02 1.73540497e+02 1.96269760e+02 1.95351700e+02 1.86815414e+02 1.79782013e+02 1.95864639e+02 2.24159088e+02 2.33403717e+02 2.06966766e+02 1.81741226e+02 1.72531815e+02 1.76948822e+02 1.60912689e+02 1.54830170e+02 1.82671555e+02 2.20880066e+02 2.28618805e+02 2.01156876e+02 1.71243607e+02 1.69723297e+02 1.69301819e+02 1.86724472e+02 2.00577667e+02 1.92651566e+02 1.73258240e+02 1.47513718e+02 1.51601654e+02 1.47954285e+02 1.77985886e+02 2.18542892e+02 2.20143326e+02 1.97706390e+02 1.71221497e+02 1.63177429e+02 1.48007736e+02 1.34941605e+02 1.49979080e+02 1.66546249e+02 1.75604477e+02 1.74270706e+02 1.69023010e+02 1.75312164e+02 1.82336639e+02 1.87893814e+02 1.86788589e+02 1.89629837e+02 1.17767715e+02 2.02057037e+02 -3.99332161e+01 -1.49364975e+02 -3.67199341e+02 -2.06787891e+03 -3.43265088e+03 -8.15973486e+03 -1.89022998e+03 -5.35594629e+03 -2.18023730e+04 80638648. 162401248. -72514064. 94560432. -166013808. -56322572. 782541056. 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. 0. 0. -859660928. -859660928. -859660928. 0. 0. 1923205760. -120397120. -65511108. -2.33428320e+04 -1.08983770e+04 -1.13037952e+03 -4.03780579e+02 -4.19740869e+03 -2.65745605e+03 -3.34979919e+02 -6.79073191e+00 7.40276108e+01 6.07411003e+01 5.80992126e+01 6.13595810e+01 7.14981003e+01 6.27901764e+01 5.30764580e+01 4.84902267e+01 5.34568672e+01 8.09849548e+01 9.35453491e+01 8.69994354e+01 5.79953384e+01 5.73199005e+01 7.86518784e+01 1.14566841e+02 1.22486916e+02 1.27652428e+02 1.34969650e+02 1.42763245e+02 1.49173706e+02 1.51576950e+02 1.56040344e+02 1.58105560e+02 1.59657333e+02 1.56629456e+02 1.46548080e+02 1.49760010e+02 1.48916153e+02 1.56703094e+02 1.39352142e+02 1.35245483e+02 1.39965851e+02 1.53580536e+02 1.58542847e+02 1.59065826e+02 1.54278824e+02 1.41387421e+02 1.03789459e+02 7.26013641e+01 6.50217743e+01 8.16351852e+01 1.04051125e+02 1.15834267e+02 1.28051682e+02 1.17473526e+02 9.73491287e+01 9.57590866e+01 1.09680534e+02 1.25711884e+02 1.24174538e+02 1.36285294e+02 1.21247498e+02 9.64310379e+01 7.91447449e+01 6.40847321e+01 5.91620941e+01 5.56438484e+01 6.93614960e+01 8.02290726e+01 7.51519165e+01 7.54497528e+01 1.06017647e+02 1.17738609e+02 1.13365211e+02 8.93729553e+01 8.41012573e+01 9.22110367e+01 6.31423492e+01 1.89323330e+01 2.09398651e+01 3.73037338e+01 6.31509438e+01 6.40006113e+00 -3.76004219e+01 -4.38766632e+01 -5.10848951e+00 1.86240768e+01 1.50528336e+01 9.22678185e+00 2.68343906e+01 2.46379738e+01 -9.79915333e+00 -4.99121056e+01 -3.71011124e+01 1.07966471e+01 5.27175636e+01 6.60183716e+01 5.69210510e+01 4.69069519e+01 3.20084114e+01 6.55984268e+01 9.53841553e+01 7.88205032e+01 3.77097054e+01 3.02425365e+01 6.16686783e+01 8.20411148e+01 3.53157768e+01 7.74248302e-01 1.42268252e+00 4.45082664e+01 8.45470276e+01 9.07869949e+01 8.83462067e+01 8.00565491e+01 7.26757584e+01 6.07605057e+01 5.96136436e+01 5.91613770e+01 5.26505013e+01 4.22510872e+01 3.37791519e+01 3.81256180e+01 4.48077393e+01 4.73348618e+01 4.52423515e+01 4.24789009e+01 6.61735058e+00 -3.29079933e+01 -3.36125526e+01 -2.27187562e+00 3.12476654e+01 -1.04008474e+01 -5.22896538e+01 -5.40080490e+01 -2.11789036e+01 6.79572058e+00 5.95429468e+00 1.48343668e+01 3.41206627e+01 2.77662334e+01 1.63514576e+01 1.28215971e+01 2.79526443e+01 5.04450073e+01 5.00138779e+01 3.60089264e+01 1.03336849e+01 8.46475315e+00 1.98258305e+00 5.19193459e+00 -9.31449699e+00 -5.17086372e+01 -9.93400421e+01 -1.02498795e+02 -6.81676407e+01 -2.18514633e+01 -5.30237999e+01 -8.75441132e+01 -8.91332169e+01 -4.32861481e+01 -4.88345051e+00 -8.31669331e+00 -1.35162725e+01 -1.64106731e+01 -1.48659573e+01 -2.02840347e+01 -1.86456566e+01 -1.50908928e+01 -9.42728901e+00 -3.62485046e+01 -6.01360435e+01 -5.84697495e+01 -2.75793209e+01 6.82081223e-01 2.21639490e+00 4.74387026e+00 -2.65703049e+01 -6.01715317e+01 -6.40369034e+01 -4.49152832e+01 -2.10451088e+01 -1.86408024e+01 -1.83920026e+00 -3.18902016e+01 -8.40775986e+01 -9.69285049e+01 -6.18927155e+01 -2.23752155e+01 -2.91768723e+01 -3.78692856e+01 -3.02396603e+01 -2.67790279e+01 -4.11984367e+01 -4.55688515e+01 -8.78946609e+01 -1.24713730e+02 -1.25328888e+02 -8.18567657e+01 -4.15021706e+01 -5.95240097e+01 -6.14771690e+01 -9.43222885e+01 -1.20326912e+02 -1.14116501e+02 -6.23667793e+01 -1.65946369e+01 -2.38939629e+01 -3.45813522e+01 -4.54105186e+01 -3.54618797e+01 -2.75505047e+01 -1.73252602e+01 -1.47840776e+01 -2.39528427e+01 -2.90784473e+01 -2.76518650e+01 -3.03341160e+01 -1.11063328e+01 -1.72260538e-01 1.56297693e+01 1.48474646e+01 2.55210817e-01 -2.63164783e+00 -3.01386428e+00 -3.01209760e+00 -1.31794128e+01 -1.94618950e+01 -1.13370657e+01 -2.14838409e+01 -2.63712730e+01 -2.67780266e+01 -8.06751633e+00 -4.07479763e+00 -1.40301266e+01 -2.51858425e+01 -3.28548279e+01 -2.94589100e+01 -4.07898788e+01 -4.00091934e+01 -5.86175766e+01 -6.15424309e+01 -6.27888031e+01 -3.65870743e+01 -4.12889242e+00 -2.33410683e+01 -7.50771866e+01 -1.14434006e+02 -1.03266907e+02 -8.01213760e+01 -7.06668930e+01 -8.24540863e+01 -9.04503403e+01 -1.00767372e+02 -9.61230469e+01 -9.05373077e+01 -8.32561569e+01 -6.94184952e+01 -5.58938828e+01 -4.94382019e+01 -6.15606194e+01 -7.77583618e+01 -9.21862030e+01 -9.12640991e+01 -8.27008743e+01 -7.44340134e+01 -6.56381607e+01 -6.43263168e+01 -6.38551331e+01 -7.99266052e+01 -1.14581665e+02 -1.44927795e+02 -1.48207138e+02 -1.26738815e+02 -9.72245712e+01 -8.51474686e+01 -8.58874969e+01 -1.06673630e+02 -1.34688919e+02 -1.49801987e+02 -1.58274078e+02 -1.35005737e+02 -1.14154701e+02 -8.03443527e+01 -8.82376404e+01 -9.44512024e+01 -9.57693481e+01 -8.40312958e+01 -7.96429825e+01 -7.32184525e+01 -8.20307693e+01 -9.27907944e+01 -1.09360924e+02 -1.19662979e+02 -1.22103783e+02 -1.53973282e+02 -1.80712769e+02 -1.69276230e+02 -1.27971535e+02 -9.42087097e+01 -1.13567673e+02 -1.32856506e+02 -1.26568001e+02 -1.18148438e+02 -1.37749496e+02 -1.75917404e+02 -1.77395401e+02 -1.44816696e+02 -1.06047890e+02 -1.20607384e+02 -1.29848236e+02 -1.24312584e+02 -1.04472328e+02 -1.00845955e+02 -1.08052032e+02 -1.14349060e+02 -1.01823242e+02 -8.01239319e+01 -8.07014694e+01 -8.69645004e+01 -9.99762650e+01 -9.53278580e+01 -1.18982735e+02 -1.46017731e+02 -1.59661697e+02 -1.71896881e+02 -1.95732788e+02 -2.23633240e+02 -2.30160889e+02 -2.09583221e+02 -2.05536743e+02 -1.85413849e+02 -1.83912674e+02 -1.54565475e+02 -1.13414383e+02 -6.54901581e+01 -5.72606468e+01 -7.45996704e+01 -8.94862747e+01 -9.63935318e+01 -1.00552544e+02 -1.09319756e+02 -1.06966202e+02 -9.97245178e+01 -1.22357552e+02 -1.62579163e+02 -1.77467712e+02 -1.70586487e+02 -1.43759308e+02 -1.38278748e+02 -1.34403625e+02 -1.18897049e+02 -1.41720016e+02 -1.49633820e+02 -1.61275345e+02 -1.59048248e+02 -1.75420959e+02 -2.07220047e+02 -1.90725220e+02 -1.59227661e+02 -1.45045090e+02 -1.80919067e+02 -1.91042648e+02 -1.76327164e+02 -1.39910141e+02 -1.67533569e+02 -1.94781952e+02 -2.05436508e+02 -1.87739532e+02 -1.66057709e+02 -1.97882385e+02 -2.25622162e+02 -2.20708374e+02 -1.84020340e+02 -1.52953934e+02 -1.78218994e+02 -1.94707184e+02 -1.67241165e+02 -1.24694351e+02 -1.44433746e+02 -1.91825562e+02 -2.17028198e+02 -2.08952576e+02 -1.94702209e+02 -1.92823212e+02 -2.15516815e+02 -2.40345474e+02 -2.35196503e+02 -1.88713120e+02 -1.56392227e+02 -1.57271164e+02 -1.67718338e+02 -1.69129364e+02 -1.65411514e+02 -1.62241928e+02 -1.63404877e+02 -1.75649567e+02 -1.78877823e+02 -1.65579407e+02 -1.63912689e+02 -1.69132721e+02 -1.95904465e+02 -2.09774933e+02 -2.02001511e+02 -1.94087097e+02 -1.77373718e+02 -1.79146805e+02 -1.76464233e+02 -1.67709991e+02 -1.58669266e+02 -1.61568512e+02 -2.04491821e+02 -2.38297104e+02 -2.04286819e+02 -1.43923431e+02 -1.39743027e+02 -1.93982483e+02 -2.12305374e+02 -1.83428848e+02 -1.64166626e+02 -1.84429214e+02 -2.00128311e+02 -1.98034576e+02 -1.78081161e+02 -1.90156631e+02 -1.97796173e+02 -2.03792664e+02 -1.88582001e+02 -1.69622101e+02 -1.75017120e+02 -1.76989044e+02 -2.01369110e+02 -2.17373047e+02 -2.22879593e+02 -1.98092575e+02 -1.98352188e+02 -2.39356812e+02 -2.68730896e+02 -2.50604950e+02 -2.12672989e+02 -2.13097321e+02 -2.32058121e+02 -2.13043320e+02 -1.69674683e+02 -1.50266418e+02 -1.73861679e+02 -1.95430481e+02 -1.96747711e+02 -1.94652328e+02 -2.07189758e+02 -2.08988892e+02 -2.07947266e+02 -2.00060867e+02 -1.92468536e+02 -1.82739853e+02 -1.78170563e+02 -1.82753738e+02 -1.93373962e+02 -2.08418289e+02 -2.14780762e+02 -2.16519592e+02 -2.24131317e+02 -2.26131958e+02 -2.17230804e+02 -2.02128433e+02 -2.06440781e+02 -2.29300812e+02 -2.34524124e+02 -2.28814835e+02 -2.38169510e+02 -2.70936737e+02 -2.89977448e+02 -2.70956696e+02 -2.32598038e+02 -2.25045822e+02 -2.33316772e+02 -2.35625931e+02 -2.17948456e+02 -2.04671875e+02 -2.00337875e+02 -1.99412186e+02 -1.96224869e+02 -2.04541199e+02 -2.02575455e+02 -1.97895050e+02 -1.97307999e+02 -2.24952759e+02 -2.40705154e+02 -2.23374527e+02 -2.07970245e+02 -2.28077759e+02 -2.45978119e+02 -2.27837982e+02 -1.90918533e+02 -1.68490509e+02 -1.72116150e+02 -1.76676575e+02 -1.87299637e+02 -1.88328400e+02 -1.91159592e+02 -1.86449249e+02 -1.97080353e+02 -2.01064941e+02 -2.04488983e+02 -1.90764954e+02 -2.04081573e+02 -2.33291962e+02 -2.55373505e+02 -2.58830536e+02 -2.52132507e+02 -2.42154465e+02 -2.30808655e+02 -2.16818298e+02 -2.17525101e+02 -2.14141846e+02 -2.15149979e+02 -2.13764572e+02 -2.18631653e+02 -2.15986465e+02 -2.16521896e+02 -2.17955841e+02 -2.15956161e+02 -2.16603088e+02 -2.13108521e+02 -2.31909317e+02 -2.47329422e+02 -2.49366013e+02 -2.33972534e+02 -2.22684357e+02 -2.25869904e+02 -2.27360809e+02 -2.27454926e+02 -2.25554001e+02 -2.26143661e+02 -2.25826263e+02 -2.34156281e+02 -2.45176590e+02 -2.40830048e+02 -2.27746750e+02 -2.25715622e+02 -2.47760773e+02 -2.61898529e+02 -2.50792206e+02 -2.30210449e+02 -2.29232330e+02 -2.39619904e+02 -2.39049057e+02 -2.32455200e+02 -2.23571259e+02 -2.33676208e+02 -2.41806885e+02 -2.48514648e+02 -2.52577972e+02 -2.40749832e+02 -2.33791260e+02 -2.32656357e+02 -2.51737198e+02 -2.58724854e+02 -2.44680878e+02 -2.27999115e+02 -2.31421219e+02 -2.45726685e+02 -2.48111588e+02 -2.40707047e+02 -2.32000061e+02 -2.38217484e+02 -2.45395676e+02 -2.48727081e+02 -2.43357224e+02 -2.36887268e+02 -2.33370605e+02 -2.40568848e+02 -2.48063065e+02 -2.50057266e+02 -2.43177628e+02 -2.32395920e+02 -2.36607254e+02 -2.41691986e+02 -2.42191162e+02 -2.35866943e+02 -2.35947083e+02 -2.42913712e+02 -2.41225052e+02 -2.34286179e+02 -2.26769394e+02 -2.25929367e+02 -2.25349213e+02 -2.30074158e+02 -2.35543854e+02 -2.38572632e+02 -2.35494431e+02 -2.31130951e+02 -2.29344559e+02 -2.30003799e+02 -2.32972351e+02 -2.36984909e+02 -2.51446976e+02 -2.62912231e+02 -2.50553757e+02 -2.60723602e+02 -2.81704590e+02 -2.86325165e+02 -2.90171326e+02 -2.60250427e+02 -2.51821594e+02 -5.02887390e+02 -7.42067993e+02 -8.90290710e+02 -1.67442798e+03 -3.55834717e+03 297563104. -1244824576. 0. 0. 0. 0. 357199328. 357199328. -692914048. -145753472. -7.42732080e+03 45655232. 111135896. 281210752. 155932272. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 663051200. 105610992. -1.33806714e+03 -9.84275635e+02 -1.01729419e+03 -8.41887390e+02 -7.92404785e+02 -6.60970581e+02 -4.86126923e+02 -2.51540054e+02 -2.50893524e+02 -2.14610291e+02 -2.01736435e+02 -1.92012451e+02 -1.91292969e+02 -1.98095490e+02 -1.99861664e+02 -1.96102264e+02 -1.98533920e+02 -2.06503784e+02 -2.13741165e+02 -2.06331711e+02 -1.90028442e+02 -1.81785828e+02 -1.86829559e+02 -1.99001266e+02 -2.04897308e+02 -2.02292603e+02 -1.98781830e+02 -2.02549881e+02 -2.09578491e+02 -2.05327682e+02 -1.94857834e+02 -1.88274185e+02 -1.92063507e+02 -2.03210434e+02 -2.06481430e+02 -1.97308777e+02 -1.80956390e+02 -1.73866394e+02 -1.80425903e+02 -1.81380814e+02 -1.73356110e+02 -1.77643417e+02 -1.95681015e+02 -2.10949829e+02 -1.97052292e+02 -1.61999084e+02 -1.53113327e+02 -1.69210815e+02 -1.89175705e+02 -1.98825897e+02 -1.96811615e+02 -1.92325684e+02 -1.89435333e+02 -1.94997086e+02 -1.93272476e+02 -1.66804840e+02 -1.47367004e+02 -1.52728439e+02 -1.77039490e+02 -1.92137589e+02 -1.83821136e+02 -1.69130478e+02 -1.60340103e+02 -1.73246445e+02 -1.74478287e+02 -1.67766129e+02 -1.75747284e+02 -1.96827835e+02 -2.20931931e+02 -2.18000946e+02 -1.83274658e+02 -1.68325043e+02 -1.77685135e+02 -2.02709854e+02 -1.97850616e+02 -1.74190445e+02 -1.80331635e+02 -1.96002365e+02 -2.06752228e+02 -1.92476761e+02 -1.57540207e+02 -1.43884171e+02 -1.52442123e+02 -1.89724884e+02 -2.12345169e+02 -2.05497086e+02 -1.87940140e+02 -1.86404312e+02 -2.05306061e+02 -2.05215271e+02 -1.82149582e+02 -1.69913254e+02 -1.90917496e+02 -2.27727188e+02 -2.30762100e+02 -1.96238800e+02 -1.60796600e+02 -1.59805862e+02 -1.84411026e+02 -1.91413940e+02 -1.83371979e+02 -1.98273087e+02 -2.30354492e+02 -2.49462296e+02 -2.18338699e+02 -1.68209824e+02 -1.38006485e+02 -1.53076630e+02 -1.82720932e+02 -2.21873093e+02 -2.41839890e+02 -2.36614044e+02 -2.24856781e+02 -2.29374374e+02 -2.23756363e+02 -1.88233322e+02 -1.52128647e+02 -1.70169556e+02 -2.29503403e+02 -2.52341263e+02 -2.25074081e+02 -1.66217010e+02 -1.40450638e+02 -1.68828186e+02 -1.94678177e+02 -2.02689743e+02 -1.93018478e+02 -2.15338089e+02 -2.61006775e+02 -2.59167114e+02 -2.09652359e+02 -1.66946365e+02 -1.68235291e+02 -2.02334854e+02 -2.23827240e+02 -2.29089462e+02 -2.15353088e+02 -1.91274445e+02 -1.78826218e+02 -2.09376282e+02 -2.21562195e+02 -1.95224457e+02 -1.73190552e+02 -1.70269836e+02 -1.86881683e+02 -1.86278534e+02 -1.61132462e+02 -1.63044434e+02 -1.85143326e+02 -2.13533401e+02 -2.24294876e+02 -1.92965225e+02 -1.78888626e+02 -1.88830765e+02 -2.11026245e+02 -1.91077423e+02 -1.12069679e+02 -7.75038300e+01 -1.18529068e+02 -1.87712524e+02 -2.00717804e+02 -1.66506363e+02 -1.45841248e+02 -1.50607697e+02 -1.47618347e+02 -1.20131767e+02 -8.36176605e+01 -7.51829147e+01 -9.14359131e+01 -1.41943420e+02 -1.78055542e+02 -1.51291794e+02 -1.28573761e+02 -1.35316589e+02 -1.67443665e+02 -1.47510529e+02 -8.03596954e+01 -8.84824448e+01 -1.16365585e+02 -1.41911926e+02 -1.05765038e+02 -2.98419800e+01 3.31406236e+00 -3.44228096e+01 -1.09001556e+02 -1.54906281e+02 -1.43275528e+02 -1.56209091e+02 -1.71957031e+02 -1.60864624e+02 -1.09635704e+02 -4.78736992e+01 -5.42548561e+01 -9.95031891e+01 -1.85611526e+02 -2.25544998e+02 -2.01387711e+02 -1.38212479e+02 -9.03742371e+01 -8.71529846e+01 -7.50860062e+01 -4.93878288e+01 -6.79526672e+01 -1.16947815e+02 -1.78716904e+02 -1.43954391e+02 -6.20233307e+01 -2.70376320e+01 -7.23228531e+01 -1.70740250e+02 -1.95036942e+02 -1.56827744e+02 -9.57327423e+01 -1.18676903e+02 -1.63885895e+02 -1.59573105e+02 -1.02190498e+02 -8.15074234e+01 -1.37967453e+02 -2.20185608e+02 -2.26741318e+02 -1.85909637e+02 -1.42184814e+02 -1.45622055e+02 -1.64739136e+02 -1.62015884e+02 -1.37589828e+02 -1.58730515e+02 -1.90156509e+02 -1.99991638e+02 -1.88341797e+02 -1.36633423e+02 -1.21629776e+02 -1.29520920e+02 -1.33121628e+02 -1.35376221e+02 -1.00236740e+02 -1.38514740e+02 -1.78238205e+02 -2.08826721e+02 -1.84377655e+02 -8.76718979e+01 -2.01035976e+01 -3.16887646e+01 -1.40394852e+02 -2.04971680e+02 -2.05902420e+02 -1.58042221e+02 -1.28969788e+02 -1.62492752e+02 -1.67978897e+02 -1.41777557e+02 -1.14095650e+02 -1.41529800e+02 -1.65089798e+02 -1.07837410e+02 -3.29164505e+01 -4.90708389e+01 -8.88632812e+01 -1.13441750e+02 -9.26373901e+01 -4.82294464e+01 -9.90532455e+01 -1.33926010e+02 -1.74854752e+02 -1.45782455e+02 -7.83376617e+01 -4.11118546e+01 -1.52444410e+01 -6.92995529e+01 -1.00430382e+02 -1.09450386e+02 -6.68823776e+01 -5.91814499e+01 -6.63279343e+01 -5.05225639e+01 -1.61610851e+01 6.56894922e-01 -6.65919266e+01 -1.07797455e+02 -1.04542549e+02 -5.13545647e+01 -6.46975327e+01 -9.32528687e+01 -1.22182907e+02 -1.39401276e+02 -1.24690826e+02 -1.31729080e+02 -7.13071823e+01 -4.92053719e+01 -2.38633175e+01 -3.19969425e+01 -5.07909698e+01 -7.07270126e+01 -1.34599106e+02 -1.59183640e+02 -1.48025177e+02 -5.62180481e+01 -3.77268143e+01 -5.24769974e+01 -8.21426773e+01 -6.15023041e+01 -8.53841324e+01 -1.69433105e+02 -2.14168808e+02 -1.77507599e+02 -6.57259521e+01 -3.67581100e+01 -7.36870651e+01 -1.37591965e+02 -1.52071915e+02 -9.17993927e+01 -8.45689926e+01 -7.61144791e+01 -1.45285126e+02 -1.67036530e+02 -1.78336456e+02 -1.15847839e+02 -9.49218445e+01 -1.26905403e+02 -1.72953461e+02 -1.41456223e+02 -7.15610962e+01 -9.88858490e+01 -1.39486893e+02 -1.39302429e+02 -9.69388199e+01 -9.60691452e+01 -1.65264389e+02 -1.96819504e+02 -1.73395065e+02 -8.45900040e+01 -8.70004959e+01 -1.12774185e+02 -1.57823792e+02 -1.34394028e+02 -9.27469330e+01 -9.97602997e+01 -8.72318420e+01 -1.33613541e+02 -1.45174438e+02 -1.54597473e+02 -1.19325150e+02 -1.10033081e+02 -1.36723373e+02 -1.71676407e+02 -1.47453033e+02 -8.22990646e+01 -6.25385590e+01 -5.71307869e+01 -3.66567879e+01 2.16888008e+01 4.97566253e-01 -6.10858955e+01 -6.74949951e+01 -2.51694546e+01 2.81715107e+01 -3.29401894e+01 -6.45812759e+01 -9.57772217e+01 -1.36212769e+02 -1.48117722e+02 -1.10973885e+02 -6.34425306e+00 1.67474060e+01 -5.03924026e+01 -1.28221405e+02 -8.97670898e+01 -4.09389734e+00 5.29677467e+01 -2.63156700e+00 -4.79297485e+01 -3.56059189e+01 -1.31648111e+01 2.85549660e+01 7.90717239e+01 1.50101791e+02 1.25726295e+02 5.37144470e+01 3.41631470e+01 6.28693123e+01 1.09143562e+02 2.21693745e+01 -1.36037502e+01 -4.30290489e+01 -2.79539375e+01 -2.43708267e+01 1.91951599e+01 1.31657761e+02 1.67783951e+02 8.19245911e+01 -6.76661377e+01 -1.20489769e+02 4.49724913e+00 1.23624619e+02 1.32728928e+02 4.85678520e+01 -9.56038094e+00 2.09577713e+01 1.01508186e+02 1.43580490e+02 1.06558022e+02 -1.91844788e+01 -4.35132332e+01 1.60080261e+01 1.01097832e+02 1.91798019e+02 1.84581268e+02 1.47262711e+02 3.37578545e+01 -8.39907303e+01 -1.35700089e+02 -6.36025467e+01 9.76424408e+01 1.81049942e+02 1.03161964e+02 -1.36022558e+01 -6.95109320e+00 1.15720749e+02 2.25885666e+02 1.82421310e+02 5.71324883e+01 -4.31589851e+01 -5.08141785e+01 3.06200123e+01 1.00736389e+02 1.58057693e+02 8.69103699e+01 4.80236130e+01 6.21283722e+00 5.48521118e+01 8.85180435e+01 4.71156044e+01 -2.50082626e+01 -1.01160469e+02 -1.10096832e+02 -5.39437370e+01 2.40012341e+01 1.35096512e+02 1.59663742e+02 7.56487350e+01 -8.40547485e+01 -1.58509171e+02 -7.94490356e+01 7.85738220e+01 1.62936707e+02 1.18601425e+02 4.94014778e+01 5.28120270e+01 1.09337975e+02 1.34136810e+02 1.39143143e+02 6.01182709e+01 1.74573860e+01 -4.10515060e+01 -4.19870529e+01 6.05873632e+00 5.53736954e+01 1.16234024e+02 9.24260406e+01 4.60033302e+01 -2.23516674e+01 -1.87255363e+01 3.87590370e+01 1.19284500e+02 8.54485626e+01 2.25882397e+01 -1.82456913e+01 4.13558655e+01 1.38241135e+02 1.39252167e+02 6.73860626e+01 -5.51410828e+01 -5.05881844e+01 4.17392540e+01 1.19500923e+02 1.59356598e+02 6.73752365e+01 3.55838470e+01 3.86311769e+00 7.76140165e+00 4.54880857e+00 3.59167480e+00 4.30826797e+01 1.72344742e+01 -1.60154343e+01 -1.49826276e+00 5.63045006e+01 1.57028946e+02 1.84460831e+02 1.21569733e+02 -2.12506523e+01 -1.31141968e+02 -1.11064461e+02 1.97326870e+01 1.50833359e+02 1.95927078e+02 9.64868698e+01 -9.65571499e+00 -2.98538933e+01 4.88967476e+01 1.38726151e+02 1.12752419e+02 4.80594444e+01 -2.59254112e+01 -3.76863365e+01 -1.39719009e+01 5.17499847e+01 1.23726929e+02 1.18829819e+02 4.38044090e+01 -5.91599846e+01 -8.31376419e+01 7.32640409e+00 1.01649117e+02 9.53943024e+01 1.13835926e+01 -3.61738892e+01 -8.12853241e+00 3.86073494e+01 5.96599236e+01 7.85501175e+01 5.69565735e+01 2.97862740e+01 5.62793236e+01 6.29353752e+01 1.00085670e+02 5.64362106e+01 2.61799107e+01 -3.06935902e+01 -5.67216492e+01 -1.83689480e+01 3.50239105e+01 1.11431084e+02 1.43762634e+02 1.00869537e+02 2.24648781e+01 9.69300842e+00 8.73731384e+01 1.80492035e+02 1.70862305e+02 1.12901733e+02 1.95432148e+01 7.47604907e-01 3.76872368e+01 8.29841919e+01 9.67695847e+01 2.28834000e+01 -3.62130432e+01 -8.72256927e+01 -6.57703018e+01 1.71536694e+01 1.77580490e+01 -1.07250824e+01 -8.64401169e+01 -9.74649658e+01 -7.23410492e+01 -1.49070120e+01 8.81128006e+01 1.36163635e+02 1.14628197e+02 3.61141243e+01 -9.54710770e+00 5.33016701e+01 1.34827850e+02 1.35291214e+02 4.55498085e+01 -2.40098248e+01 3.30208635e+00 8.84824677e+01 1.57960358e+02 1.68423050e+02 9.36688614e+01 8.02186108e+00 -1.20316648e+01 2.01153731e+00 3.41254501e+01 6.22135429e+01 1.09113678e+02 1.15802361e+02 9.48779678e+01 7.30617447e+01 1.06152954e+02 1.77751648e+02 2.24646896e+02 1.65552780e+02 7.04049149e+01 2.05079765e+01 6.53761902e+01 1.60647980e+02 1.75403214e+02 1.33701492e+02 4.91960983e+01 4.33033867e+01 9.51448975e+01 1.20125816e+02 1.24726593e+02 6.88794174e+01 5.51889839e+01 6.72942276e+01 9.13594131e+01 1.37272034e+02 1.26419289e+02 1.19604469e+02 5.20937500e+01 -5.20174578e-02 1.43979397e+01 5.82533150e+01 1.29852036e+02 1.82118103e+02 1.83932693e+02 1.26976318e+02 3.24144673e+00 -2.36646557e+01 3.98831797e+00 -6.87098846e+01 -5.05289246e+02 -5.75851904e+03 -1.27426934e+04 50594832. -247784640. 147008224. -182095648. 273444416. 211863024. 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. 0. 0. 0. 0. 0. 0. 0. 0. 832060288. -590784000. 59325776. 254382512. 143809264. 2.32940859e+04 1.03033408e+04 1.59178491e+03 -2.89435278e+03 -2.03084888e+03 -1.85243546e+02 3.61312561e+01 1.04903656e+02 1.15047554e+02 7.49936752e+01 7.59126663e+01 1.05994553e+02 1.97546753e+02 1.95153030e+02 1.55257462e+02 9.31686249e+01 1.09953911e+02 1.79578644e+02 2.30929108e+02 2.35603104e+02 1.82197372e+02 1.02960014e+02 8.84068604e+01 1.41445908e+02 2.10197769e+02 2.10382675e+02 1.63560913e+02 1.60315857e+02 1.97091980e+02 2.10466278e+02 1.83215179e+02 1.47220169e+02 1.45865891e+02 1.34450546e+02 1.15270683e+02 1.15150642e+02 1.54420090e+02 2.28469452e+02 2.36540192e+02 1.89791000e+02 1.48607071e+02 1.48539948e+02 1.97007309e+02 2.43095108e+02 2.35995926e+02 1.66753143e+02 8.93345795e+01 9.69433060e+01 1.73650925e+02 2.13640533e+02 2.21473663e+02 1.76968811e+02 1.63678131e+02 1.59107880e+02 1.53104156e+02 1.64131424e+02 1.79431381e+02 2.16358780e+02 2.01403687e+02 1.65576889e+02 1.58830231e+02 1.85288101e+02 2.35142822e+02 2.34487381e+02 2.09941971e+02 1.72134415e+02 1.55200592e+02 1.95369507e+02 2.49683411e+02 2.92256683e+02 2.65818665e+02 2.06161865e+02 1.85514801e+02 2.23589890e+02 2.49876526e+02 2.44218796e+02 1.89069092e+02 1.78725250e+02 1.93951660e+02 2.19700714e+02 2.15711441e+02 2.17817642e+02 2.31214233e+02 2.09874435e+02 1.73941620e+02 1.55922104e+02 1.97825470e+02 2.51367935e+02 2.64670624e+02 2.44198486e+02 2.15263138e+02 1.83331177e+02 1.79188965e+02 2.01660675e+02 2.27347534e+02 2.19487289e+02 1.74385574e+02 1.53659546e+02 1.95693726e+02 2.26872894e+02 2.28914139e+02 1.77016953e+02 1.57302628e+02 1.63580902e+02 1.71499771e+02 1.78785187e+02 1.94155579e+02 2.29321991e+02 2.28716034e+02 1.98501770e+02 1.73519608e+02 1.76757553e+02 2.05171143e+02 2.11515854e+02 1.92542709e+02 1.78050369e+02 1.60411835e+02 1.68348221e+02 1.96813644e+02 2.26618546e+02 2.34592484e+02 1.93400162e+02 1.73182114e+02 1.89501099e+02 2.01695770e+02 2.03531067e+02 1.83665924e+02 1.86349075e+02 1.90161011e+02 1.81232559e+02 1.74650818e+02 1.80093384e+02 2.09014755e+02 2.12886429e+02 1.90691391e+02 1.76415131e+02 1.76702850e+02 1.99047501e+02 1.94647568e+02 1.79118210e+02 1.66429916e+02 1.57792557e+02 1.72281647e+02 1.96668091e+02 2.16017288e+02 2.14092117e+02 1.94172150e+02 1.90184479e+02 1.96174240e+02 1.95126770e+02 1.89199356e+02 1.76320053e+02 1.69407532e+02 1.65820663e+02 1.64742645e+02 1.74114349e+02 1.89586105e+02 2.08700500e+02 2.13171539e+02 2.06434967e+02 1.96737305e+02 1.98610519e+02 2.11307251e+02 2.24925919e+02 2.15455276e+02 1.94477188e+02 1.77042053e+02 1.78561401e+02 1.98718323e+02 2.09563965e+02 2.10764114e+02 1.98896606e+02 1.96917160e+02 1.99269455e+02 1.98181717e+02 2.00939713e+02 2.04359436e+02 2.04405243e+02 1.94619690e+02 1.83821472e+02 1.84092438e+02 1.88684113e+02 1.97333069e+02 2.03992355e+02 2.05762131e+02 2.03273132e+02 2.00693344e+02 2.07954712e+02 2.15832428e+02 2.12503647e+02 2.00617264e+02 1.89729904e+02 1.89177673e+02 1.97077484e+02 1.99363220e+02 2.00531281e+02 1.93968307e+02 1.95496155e+02 1.99614700e+02 2.05809647e+02 2.09082016e+02 2.09245499e+02 2.12088333e+02 2.09500870e+02 2.03485275e+02 1.98750656e+02 1.99076309e+02 2.03764282e+02 2.04246307e+02 2.01064026e+02 1.97673477e+02 1.95088028e+02 1.97138107e+02 2.01030457e+02 2.03933289e+02 2.02691071e+02 2.00013474e+02 1.99620285e+02 2.00421295e+02 2.00557083e+02 2.00422333e+02 2.00090683e+02 2.00108612e+02 2.00305176e+02 2.00405731e+02 2.00361450e+02 1.99930588e+02 1.98687592e+02 1.97709915e+02 1.98077972e+02 1.98995605e+02 1.99157700e+02 1.98833084e+02 1.99917679e+02 2.01690643e+02 2.02695786e+02 2.02035370e+02 1.99793106e+02 1.98531754e+02 1.97730133e+02 1.98701141e+02 2.00979828e+02 2.02069061e+02 2.01227097e+02 1.98166122e+02 1.97042053e+02 1.98254578e+02 2.00674881e+02 2.01022537e+02 1.99420639e+02 1.97413223e+02 1.97648560e+02 1.99024307e+02 1.99994110e+02 2.00880676e+02 2.00714676e+02 2.02681381e+02 2.01526871e+02 2.00690094e+02 1.97937286e+02 1.99703690e+02 2.01080261e+02 2.00816086e+02 1.99318176e+02 1.99564529e+02 2.01882812e+02 2.02202408e+02 2.02324127e+02 2.03900131e+02 2.02112000e+02 1.97897018e+02 1.96378860e+02 2.00579559e+02 2.02631775e+02 2.00738602e+02 1.99695541e+02 2.01659927e+02 2.03133530e+02 2.02341843e+02 2.01680878e+02 2.00382278e+02 1.99279831e+02 1.98446274e+02 2.00646851e+02 2.00413254e+02 2.05160294e+02 2.04361237e+02 2.03763306e+02 1.98673355e+02 2.01236420e+02 2.01697998e+02 2.01993942e+02 1.94139847e+02 1.89404709e+02 1.87361298e+02 1.93275467e+02 1.98477676e+02 2.01147354e+02 2.00079895e+02 1.97503265e+02 1.93480286e+02 1.89888565e+02 1.94184967e+02 1.94696121e+02 1.96300476e+02 1.95698853e+02 1.99552078e+02 1.99566895e+02 1.96926529e+02 1.94713242e+02 1.96535934e+02 1.93046417e+02 1.85696960e+02 1.78106186e+02 1.81355530e+02 1.84415466e+02 1.91461960e+02 1.92567169e+02 2.05835129e+02 2.09265366e+02 2.13380493e+02 2.03948578e+02 1.98785492e+02 1.89493439e+02 1.84436920e+02 1.84946106e+02 2.01312119e+02 2.15556580e+02 2.11116409e+02 1.95653030e+02 1.80583572e+02 1.77926300e+02 1.80250565e+02 1.78127991e+02 1.75912277e+02 1.73890625e+02 1.77701767e+02 1.80707809e+02 1.77591583e+02 1.83064941e+02 1.84960464e+02 1.79763824e+02 1.71304199e+02 1.62157211e+02 1.62957382e+02 1.66327133e+02 1.75560455e+02 1.73229233e+02 1.68325912e+02 1.70647507e+02 1.77783676e+02 1.82165314e+02 1.69894684e+02 1.56690948e+02 1.51066772e+02 1.66473846e+02 1.80605728e+02 1.89287766e+02 1.77786636e+02 1.50867081e+02 1.29587402e+02 1.44288239e+02 1.79846649e+02 1.94354904e+02 1.83559708e+02 1.67398163e+02 1.62348724e+02 1.50544022e+02 1.45441711e+02 1.51254013e+02 1.65869888e+02 1.75446045e+02 1.73906784e+02 1.69295502e+02 1.53900543e+02 1.38620728e+02 1.39983795e+02 1.55801254e+02 1.74360382e+02 1.79235107e+02 1.79032074e+02 1.80410522e+02 1.87496460e+02 1.94024002e+02 1.91562668e+02 1.77954742e+02 1.69923340e+02 1.74384186e+02 1.82192673e+02 1.82974838e+02 1.73506577e+02 1.70584427e+02 1.76415359e+02 1.62230209e+02 1.53363113e+02 1.54293259e+02 1.86456223e+02 1.98727859e+02 1.85648666e+02 1.67638718e+02 1.59563370e+02 1.48382431e+02 1.38052673e+02 1.35624817e+02 1.25418564e+02 1.26562088e+02 1.34864487e+02 1.60404587e+02 1.66577332e+02 1.56585800e+02 1.51926544e+02 1.54931473e+02 1.59927032e+02 1.60759933e+02 1.58411880e+02 1.39385742e+02 1.19437248e+02 1.16405685e+02 1.34994217e+02 1.56043579e+02 1.60684158e+02 1.64964615e+02 1.59759903e+02 1.54313766e+02 1.46533539e+02 1.56688644e+02 1.76120178e+02 1.95352158e+02 1.98549942e+02 1.85582367e+02 1.61786453e+02 1.56871674e+02 1.62577866e+02 1.64630814e+02 1.61754517e+02 1.57647980e+02 1.89563309e+02 2.11634323e+02 2.15801468e+02 1.81092087e+02 1.49313095e+02 1.47377487e+02 1.68688278e+02 2.08360916e+02 2.91491730e+02 3.33273529e+02 4.12205597e+02 3.79939423e+02 5.17547363e+02 4.72308203e+03 1.58778857e+03 3.77022998e+03 1.26752607e+04 114522296. 111852504. -453658336. 82206544. 179536304. -67716808. -679112128. -474933664. 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. 0. -859660928. -859660928. -859660928. 0. 0. 1923205760. -120397120. -65511108. -2.33428320e+04 -1.08983770e+04 -1.13037952e+03 -4.03780579e+02 4.40108154e+03 2.88851636e+03 5.59165039e+02 2.34485794e+02 1.77161713e+02 2.02413498e+02 1.98310287e+02 1.72554184e+02 1.38188995e+02 1.41644485e+02 1.40870926e+02 1.35961502e+02 1.37363480e+02 1.57087738e+02 1.81120865e+02 1.53347763e+02 1.00126503e+02 8.26294632e+01 1.18913651e+02 1.46819244e+02 1.29910065e+02 1.14329803e+02 1.25638298e+02 1.38107025e+02 1.56695007e+02 1.60230820e+02 1.51891754e+02 1.31429153e+02 1.20420731e+02 1.21306442e+02 1.34242462e+02 1.00606873e+02 6.00379791e+01 4.33182068e+01 6.61469574e+01 9.16382980e+01 8.96385574e+01 7.58963928e+01 7.06115494e+01 5.32131081e+01 4.17247314e+01 3.25704384e+01 2.22447910e+01 2.15398884e+01 3.65893059e+01 5.53606644e+01 6.16304398e+01 4.50789566e+01 4.02629089e+01 4.47759438e+01 4.78886032e+01 4.39203339e+01 3.29256287e+01 2.53357563e+01 3.63415031e+01 7.94012527e+01 1.23732635e+02 1.46066437e+02 1.14310455e+02 7.99991455e+01 6.13780136e+01 8.86508255e+01 1.17230278e+02 1.04683380e+02 7.21044693e+01 3.74324303e+01 3.72605171e+01 3.62050438e+01 1.60760136e+01 -2.73181839e+01 8.23693037e-01 4.96542282e+01 1.00719749e+02 8.17189407e+01 5.21488266e+01 5.21906357e+01 4.85055466e+01 4.56509438e+01 3.25913849e+01 3.44730034e+01 4.28158836e+01 5.95993042e+01 6.72616730e+01 6.45677872e+01 5.65867691e+01 5.97220039e+01 9.46317139e+01 1.38085312e+02 1.17753288e+02 8.78792801e+01 4.87117119e+01 6.85091782e+01 8.47325439e+01 1.01047028e+02 1.09359116e+02 8.17800674e+01 4.49851799e+01 3.29314880e+01 5.24889565e+01 9.52328339e+01 9.53786545e+01 8.71246490e+01 5.85606804e+01 3.97977905e+01 4.70490189e+01 4.43805237e+01 4.97656937e+01 4.00500870e+01 4.65382843e+01 4.31575699e+01 3.42868843e+01 5.67033920e+01 8.99149933e+01 8.33166733e+01 5.04313431e+01 1.38058519e+01 1.20460033e+01 8.60269165e+00 9.46250725e+00 8.45651054e+00 1.48485017e+00 -1.89553642e+00 3.93568459e+01 9.08734818e+01 9.75234451e+01 6.37222748e+01 1.68102303e+01 -6.88857138e-01 -1.42522507e+01 -5.15383625e+00 6.03469467e+00 1.45957775e+01 -1.87868750e+00 4.16368818e+00 8.51799488e-01 4.12888908e+00 5.20440626e+00 1.33938408e+01 2.01459370e+01 2.34794407e+01 1.67717075e+01 1.72826595e+01 2.25682793e+01 2.31790447e+01 2.60767651e+01 2.26037331e+01 2.97448273e+01 3.78759842e+01 3.00572758e+01 2.50090599e+01 1.57549686e+01 1.53408833e+01 2.18938541e+00 -1.43023596e+01 -1.88114548e+01 -7.80602694e+00 4.80282631e+01 8.44207611e+01 9.03387222e+01 6.65804291e+01 3.66474876e+01 3.04438400e+01 1.73559361e+01 8.54663754e+00 1.90275841e+01 2.20865822e+01 2.18443089e+01 1.75610962e+01 1.83586617e+01 1.41793375e+01 -3.36025925e+01 -8.15200119e+01 -1.14554039e+02 -1.07802956e+02 -6.34311028e+01 -2.05125751e+01 2.06552391e+01 1.42931004e+01 3.98323631e+00 -8.91244411e+00 -2.10085964e+00 -5.02860451e+00 -2.87380099e+00 -1.06891251e+01 -2.53727016e+01 -1.73324528e+01 -9.27715015e+00 -7.69808674e+00 -1.30595274e+01 -2.46720104e+01 -7.67268944e+00 -2.55380297e+00 7.80492067e+00 8.72281170e+00 -3.46661568e+00 -4.57809486e+01 -9.32013550e+01 -1.17648880e+02 -1.20985275e+02 -1.13707458e+02 -1.22271225e+02 -8.94143524e+01 -3.61856766e+01 8.90018940e+00 1.55294285e+01 8.47563088e-01 -8.84737778e+00 -1.17018852e+01 -1.13940639e+01 1.01537123e-01 -2.56725955e+00 -4.17498541e+00 -1.21491880e+01 -1.55255070e+01 -1.80771809e+01 1.96900234e+01 6.33612900e+01 5.27426033e+01 1.18235998e+01 -3.22337341e+01 -5.26678276e+01 -7.05707855e+01 -1.14984344e+02 -1.39809525e+02 -1.31353577e+02 -9.82225418e+01 -4.55035858e+01 -6.13072319e+01 -7.13658142e+01 -9.58332901e+01 -9.01251373e+01 -8.09665680e+01 -8.42082901e+01 -8.84440384e+01 -8.83759689e+01 -6.98273697e+01 -5.73001099e+01 -6.03266983e+01 -9.63397141e+01 -1.36374405e+02 -1.75130325e+02 -1.85581619e+02 -1.16720337e+02 -3.75100670e+01 2.65981585e-01 -1.96624432e+01 -6.59271393e+01 -6.74253998e+01 -8.33885574e+01 -7.96608047e+01 -7.50134201e+01 -6.69311218e+01 -5.99767075e+01 -6.34633408e+01 -6.93876572e+01 -7.08507156e+01 -3.70261116e+01 8.61327553e+00 1.42068110e+01 -6.47587442e+00 -4.05347672e+01 -6.23977013e+01 -8.95395508e+01 -9.88491440e+01 -7.90176926e+01 -7.60395813e+01 -9.07755432e+01 -8.76407700e+01 -6.21531982e+01 -4.48866196e+01 -4.41321869e+01 -5.17102852e+01 -5.61653748e+01 -6.52681198e+01 -6.62655716e+01 -7.53220596e+01 -7.37077332e+01 -7.21899414e+01 -5.28481331e+01 -4.24290504e+01 -4.32769737e+01 -7.69576187e+01 -1.22724457e+02 -1.27794510e+02 -9.64526825e+01 -5.90962715e+01 -7.23231735e+01 -8.20647964e+01 -8.91944122e+01 -8.38780823e+01 -8.60945740e+01 -9.21603012e+01 -1.10912949e+02 -1.29702408e+02 -1.28066986e+02 -9.89903717e+01 -7.08403397e+01 -6.95140457e+01 -8.55025406e+01 -6.80087128e+01 -3.93526802e+01 -2.19081039e+01 -3.73212738e+01 -6.49488525e+01 -6.35700417e+01 -6.58348312e+01 -6.70549469e+01 -7.89458389e+01 -7.91486282e+01 -7.04026184e+01 -5.88779297e+01 -6.44879150e+01 -7.27253342e+01 -7.35994949e+01 -7.03297119e+01 -8.15020752e+01 -9.34254761e+01 -1.19049423e+02 -1.37169556e+02 -1.33148392e+02 -1.18093117e+02 -1.00985107e+02 -1.01021927e+02 -9.26242676e+01 -8.09483109e+01 -8.70347824e+01 -1.27540047e+02 -1.64787506e+02 -1.75659500e+02 -1.44572342e+02 -1.13020065e+02 -1.07582626e+02 -1.18114845e+02 -1.23770256e+02 -1.17204903e+02 -1.37896622e+02 -1.78268661e+02 -1.90192184e+02 -1.65826233e+02 -1.17639030e+02 -1.20858818e+02 -1.20385384e+02 -1.28955826e+02 -1.23252449e+02 -1.21851952e+02 -1.30405975e+02 -1.46090790e+02 -1.55150146e+02 -1.48538589e+02 -1.35064560e+02 -1.39426620e+02 -1.73464554e+02 -2.21038544e+02 -2.20924103e+02 -1.84796173e+02 -1.45231689e+02 -1.41331772e+02 -1.31351608e+02 -1.36483047e+02 -1.41679352e+02 -1.83866913e+02 -2.08554199e+02 -2.39100601e+02 -2.38514786e+02 -2.10090530e+02 -1.76701828e+02 -1.39398987e+02 -1.66184799e+02 -1.92779022e+02 -1.64911667e+02 -1.03367874e+02 -7.16600571e+01 -9.98385239e+01 -1.37051941e+02 -1.32269913e+02 -1.34652313e+02 -1.28108978e+02 -1.27028816e+02 -1.17922997e+02 -1.14086334e+02 -1.12694252e+02 -1.09022484e+02 -1.05036499e+02 -1.02189262e+02 -1.05335899e+02 -1.10934845e+02 -1.14695992e+02 -1.35306686e+02 -1.62525574e+02 -1.60396027e+02 -1.36380783e+02 -1.04913460e+02 -1.32773682e+02 -1.68394547e+02 -1.41812424e+02 -8.38066559e+01 -8.38518677e+01 -1.55409286e+02 -1.96934616e+02 -1.73550674e+02 -1.39912598e+02 -1.55097702e+02 -1.91038086e+02 -1.98602509e+02 -1.85784607e+02 -1.56723068e+02 -1.59285233e+02 -1.62552856e+02 -1.61102448e+02 -1.61021042e+02 -1.37772522e+02 -1.13771027e+02 -1.36829590e+02 -1.82587128e+02 -2.12939789e+02 -1.92902771e+02 -1.75124161e+02 -1.96533340e+02 -2.19796265e+02 -2.24928436e+02 -2.03353745e+02 -1.75458008e+02 -1.80203720e+02 -1.85034775e+02 -1.92770874e+02 -1.78925964e+02 -1.90491653e+02 -2.16573105e+02 -2.26964233e+02 -2.20326294e+02 -1.83378326e+02 -1.64098358e+02 -1.54474106e+02 -1.61512665e+02 -1.70945099e+02 -1.39483215e+02 -9.66923981e+01 -1.06047173e+02 -1.52598007e+02 -1.96214478e+02 -1.86303207e+02 -1.62812943e+02 -1.76988098e+02 -2.04330521e+02 -2.08011581e+02 -1.90206284e+02 -1.64052139e+02 -1.60581146e+02 -1.60535629e+02 -1.60609344e+02 -1.62395996e+02 -1.63862244e+02 -1.73138580e+02 -1.87691925e+02 -1.95049942e+02 -1.85625702e+02 -1.70283127e+02 -1.64708206e+02 -1.64512604e+02 -1.68346115e+02 -1.46007141e+02 -1.24138664e+02 -1.45826385e+02 -1.89107910e+02 -2.15976135e+02 -1.90319305e+02 -1.65031570e+02 -1.48912308e+02 -1.46325302e+02 -1.46545898e+02 -1.53479446e+02 -1.58195602e+02 -1.54807556e+02 -1.58508469e+02 -1.57587402e+02 -1.59442917e+02 -1.51484711e+02 -1.49044693e+02 -1.49511429e+02 -1.65767105e+02 -1.72831207e+02 -1.66433731e+02 -1.54779068e+02 -1.49178406e+02 -1.60575165e+02 -1.69559113e+02 -1.76691254e+02 -1.91761658e+02 -2.08500961e+02 -2.11685486e+02 -1.97401505e+02 -1.96196762e+02 -2.26648987e+02 -2.48646179e+02 -2.36495819e+02 -2.14320602e+02 -2.18891266e+02 -2.38293549e+02 -2.39218231e+02 -2.20042389e+02 -2.06929535e+02 -2.05243988e+02 -2.06970230e+02 -2.06998322e+02 -2.07823975e+02 -2.07189133e+02 -1.97456329e+02 -2.03486588e+02 -2.16994064e+02 -2.27606110e+02 -2.18079056e+02 -2.02268112e+02 -2.03243164e+02 -2.13871979e+02 -2.01541550e+02 -1.80519348e+02 -1.71432587e+02 -1.77281281e+02 -1.90260193e+02 -1.85412674e+02 -1.88209839e+02 -1.87382462e+02 -1.88968582e+02 -1.87189392e+02 -1.87378052e+02 -1.89832123e+02 -1.88196762e+02 -1.86436188e+02 -1.82929855e+02 -1.86254425e+02 -1.90245758e+02 -1.89923676e+02 -1.99540390e+02 -2.09041321e+02 -2.09261856e+02 -1.96199814e+02 -1.81277542e+02 -1.78028854e+02 -1.79196503e+02 -1.71688980e+02 -1.62281616e+02 -1.64653351e+02 -1.75377975e+02 -1.85885452e+02 -1.85886810e+02 -1.85597229e+02 -1.98846466e+02 -2.13320419e+02 -2.15633972e+02 -2.05647964e+02 -1.97554947e+02 -1.97882950e+02 -1.96325714e+02 -1.92746017e+02 -1.93206665e+02 -1.88412598e+02 -1.79599564e+02 -1.85589249e+02 -1.99277054e+02 -2.08538971e+02 -2.03498474e+02 -2.03363785e+02 -2.16658493e+02 -2.25582886e+02 -2.22223572e+02 -2.06888626e+02 -2.02227707e+02 -2.07283646e+02 -2.09714630e+02 -2.03698456e+02 -1.92976425e+02 -1.94430527e+02 -2.00185120e+02 -2.00967270e+02 -1.98045380e+02 -1.93172302e+02 -1.91897705e+02 -1.90623383e+02 -1.89171616e+02 -1.91624466e+02 -1.91179535e+02 -1.90713699e+02 -1.94549728e+02 -1.98932983e+02 -2.01812286e+02 -1.99336212e+02 -1.97494263e+02 -2.00773788e+02 -2.05278564e+02 -2.04823059e+02 -2.00673813e+02 -1.89079865e+02 -1.72803543e+02 -1.64285355e+02 -1.49246780e+02 -1.46562546e+02 -1.92576111e+02 -2.20475372e+02 -2.50260086e+02 -2.28062408e+02 -2.33855057e+02 -2.15513611e+02 -2.14492325e+02 -1.15300369e+01 3.30610748e+02 -83640960. -1301312768. 0. 0. 0. 0. 357199328. 357199328. -692914048. 249883472. -61330512. -132356048. -132356048. -488244768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 663051200. 105610992. 152648112. -515747552. 72426760. -1.66019897e+03 -8.06047485e+02 -1.83763657e+02 -3.07047058e+02 -4.69853241e+02 -2.00223618e+02 -1.76850739e+02 -1.76736465e+02 -1.74886612e+02 -1.73252304e+02 -1.76442184e+02 -1.79439026e+02 -1.76834549e+02 -1.68560822e+02 -1.64530594e+02 -1.71155548e+02 -1.83933502e+02 -1.83994293e+02 -1.73142792e+02 -1.59120407e+02 -1.56767990e+02 -1.62424057e+02 -1.60777267e+02 -1.53389816e+02 -1.52849503e+02 -1.60594238e+02 -1.67319595e+02 -1.59880219e+02 -1.42087646e+02 -1.38404831e+02 -1.49205002e+02 -1.63314255e+02 -1.71430466e+02 -1.72041885e+02 -1.77921677e+02 -1.85259369e+02 -1.88282089e+02 -1.77144424e+02 -1.47676651e+02 -1.31799866e+02 -1.38556915e+02 -1.59674164e+02 -1.75544724e+02 -1.74938644e+02 -1.68343765e+02 -1.58365082e+02 -1.59651413e+02 -1.53025665e+02 -1.46075119e+02 -1.53020966e+02 -1.79531296e+02 -2.06885345e+02 -2.04277802e+02 -1.63940186e+02 -1.43890717e+02 -1.51190994e+02 -1.73897888e+02 -1.71365494e+02 -1.53664688e+02 -1.54968323e+02 -1.73225510e+02 -1.92491104e+02 -1.85573273e+02 -1.53509827e+02 -1.29577637e+02 -1.37023605e+02 -1.56766190e+02 -1.65067810e+02 -1.56949463e+02 -1.56931274e+02 -1.70913940e+02 -1.87771011e+02 -1.83190323e+02 -1.74162201e+02 -1.76166183e+02 -1.90799759e+02 -1.96296661e+02 -1.88096558e+02 -1.70042358e+02 -1.51852615e+02 -1.50383606e+02 -1.57984344e+02 -1.66816101e+02 -1.61947556e+02 -1.81984253e+02 -2.14153198e+02 -2.28237976e+02 -1.97803070e+02 -1.42450882e+02 -1.16594742e+02 -1.32389923e+02 -1.75547745e+02 -2.15645142e+02 -2.29413162e+02 -2.19693115e+02 -2.13021133e+02 -2.16492935e+02 -2.02618423e+02 -1.60919495e+02 -1.32324539e+02 -1.41568314e+02 -1.76505707e+02 -1.86720612e+02 -1.71377792e+02 -1.45785217e+02 -1.40890518e+02 -1.61533859e+02 -1.75756287e+02 -1.74314255e+02 -1.69506882e+02 -1.86100967e+02 -2.23407578e+02 -2.30710693e+02 -1.96747345e+02 -1.58714920e+02 -1.58782562e+02 -1.89715820e+02 -2.15859528e+02 -2.18155548e+02 -1.91834198e+02 -1.60677292e+02 -1.46626862e+02 -1.64902176e+02 -1.65886368e+02 -1.45574020e+02 -1.38977509e+02 -1.67014191e+02 -2.02791214e+02 -2.01044250e+02 -1.69388046e+02 -1.50279236e+02 -1.66546555e+02 -1.81434708e+02 -1.88524445e+02 -1.71898331e+02 -1.84903397e+02 -2.12030777e+02 -2.20940338e+02 -1.79844879e+02 -1.03696495e+02 -6.92357101e+01 -1.00100937e+02 -1.51100693e+02 -1.67765701e+02 -1.54738693e+02 -1.36726120e+02 -1.36793610e+02 -1.31558365e+02 -1.05940613e+02 -7.05436935e+01 -5.91212997e+01 -9.37806168e+01 -1.69898972e+02 -2.08610001e+02 -1.69766663e+02 -1.22640526e+02 -1.21818863e+02 -1.46985718e+02 -1.26425415e+02 -7.05212097e+01 -7.37821350e+01 -1.25898056e+02 -1.76035950e+02 -1.36423935e+02 -4.89992561e+01 -2.99201608e+00 -3.62647324e+01 -1.06544914e+02 -1.40757767e+02 -1.40930969e+02 -1.46272339e+02 -1.55748459e+02 -1.37420227e+02 -8.71266022e+01 -3.07923260e+01 -6.25572739e+01 -1.16961876e+02 -1.63668640e+02 -1.57700165e+02 -1.27959984e+02 -1.08923149e+02 -8.93948441e+01 -8.68899231e+01 -6.19905205e+01 -3.94764023e+01 -5.44869766e+01 -1.18047287e+02 -1.66762573e+02 -1.60849899e+02 -9.82344894e+01 -4.81469727e+01 -5.79477959e+01 -1.08726730e+02 -1.38266388e+02 -1.37349594e+02 -1.46676804e+02 -2.05351944e+02 -2.23780792e+02 -1.60212158e+02 -9.28238373e+01 -7.44145355e+01 -1.16886299e+02 -1.63981369e+02 -1.87874893e+02 -1.81976074e+02 -1.53986481e+02 -1.25367805e+02 -1.26847656e+02 -1.07661980e+02 -7.74019623e+01 -1.03822266e+02 -1.49859009e+02 -1.78985352e+02 -1.72167099e+02 -1.24506630e+02 -1.08288528e+02 -1.17607597e+02 -1.28871246e+02 -1.31244751e+02 -9.66864395e+01 -1.24191437e+02 -1.72153931e+02 -2.00281937e+02 -2.08552658e+02 -1.34908966e+02 -9.22686996e+01 -1.06160278e+02 -1.72384293e+02 -1.88042084e+02 -1.48094086e+02 -1.02506508e+02 -1.09428612e+02 -1.37934525e+02 -1.32213501e+02 -9.13545074e+01 -8.17551498e+01 -1.45843628e+02 -1.71041458e+02 -1.40700317e+02 -8.89024963e+01 -1.29362152e+02 -1.45746338e+02 -1.33493195e+02 -1.07501411e+02 -9.82072830e+01 -1.17019379e+02 -9.10734253e+01 -6.75666504e+01 -6.17769928e+01 -4.12463074e+01 -2.50226231e+01 -1.34075232e+01 -8.34562912e+01 -1.11601479e+02 -1.13660866e+02 -5.86443481e+01 -7.15180435e+01 -7.86341858e+01 -6.01171761e+01 -1.91395054e+01 -3.46964407e+00 -7.17915192e+01 -1.10755669e+02 -1.13386688e+02 -4.66081085e+01 -3.35563431e+01 -3.92942162e+01 -7.09403305e+01 -8.24518127e+01 -4.59832458e+01 -6.52675476e+01 -9.26133118e+01 -1.52814011e+02 -1.77222366e+02 -1.60955963e+02 -1.11837692e+02 -6.59741821e+01 -9.65128326e+01 -1.48700623e+02 -1.73210205e+02 -1.57484268e+02 -1.80044220e+02 -1.68226379e+02 -1.21880997e+02 -5.49621849e+01 -5.92593689e+01 -1.54026230e+02 -1.77616272e+02 -1.39499039e+02 -5.92949333e+01 -8.78210144e+01 -1.27039291e+02 -1.37853195e+02 -1.14300758e+02 -7.52714081e+01 -7.43950882e+01 -6.79576187e+01 -1.19897102e+02 -1.40056015e+02 -1.35014664e+02 -8.90894928e+01 -6.93776855e+01 -1.05193214e+02 -1.39753159e+02 -1.39643723e+02 -1.40244705e+02 -2.05076187e+02 -2.49709854e+02 -2.44592941e+02 -2.16628204e+02 -2.19682327e+02 -2.61843170e+02 -2.75904358e+02 -2.44608765e+02 -1.61168655e+02 -1.28169296e+02 -1.17559166e+02 -1.41755661e+02 -1.31007401e+02 -8.04699020e+01 -4.22445679e+01 -1.23851738e+01 -5.82570152e+01 -8.75798569e+01 -1.24028534e+02 -1.18774910e+02 -1.33823074e+02 -1.53463272e+02 -1.80452209e+02 -1.68705765e+02 -1.61861938e+02 -2.01663757e+02 -2.41373947e+02 -2.20290939e+02 -1.58315872e+02 -1.43971100e+02 -1.33038086e+02 -7.93361053e+01 -3.17644520e+01 -1.55997324e+01 -8.04985123e+01 -8.48478622e+01 -8.96033478e+01 -1.30675400e+02 -1.32395874e+02 -9.32974472e+01 4.36582375e+00 2.86291981e+01 -4.91394806e+01 -1.23136177e+02 -1.23688812e+02 -6.63357773e+01 -1.01705847e+01 -3.23566551e+01 -7.77235870e+01 -1.30426727e+02 -1.39571381e+02 -8.54518509e+01 -4.81862183e+01 1.35739117e+01 6.17661476e+00 5.76593924e+00 3.17039146e+01 3.57211418e+01 5.13732643e+01 -3.26002846e+01 -4.33857155e+01 -5.55681992e+01 -6.33565102e+01 -4.29182320e+01 1.36475086e+01 1.40415161e+02 1.64442719e+02 7.21754837e+01 -8.65555038e+01 -1.69746414e+02 -7.86850128e+01 5.13984909e+01 6.23923378e+01 -7.29379959e+01 -2.19972961e+02 -1.88489609e+02 -4.70919037e+01 3.36648903e+01 2.36192703e+01 -6.19429359e+01 -4.92409286e+01 5.78268051e+00 4.45954628e+01 5.71674042e+01 -6.00061893e+00 -7.29050875e-01 3.81117744e+01 7.59009781e+01 6.80536575e+01 1.87809792e+01 3.38930397e+01 4.50991707e+01 -4.17974930e+01 -1.27148170e+02 -1.26782570e+02 4.79707794e+01 1.52120255e+02 1.18814316e+02 -1.69082985e+01 -8.99091187e+01 -7.49978638e+01 7.01282549e+00 4.02547073e+01 6.17399864e+01 -6.56726646e+00 -5.95768309e+00 7.59926701e+00 2.62366924e+01 6.20226974e+01 8.10712039e-01 -2.59312382e+01 -1.11360207e+02 -1.08973351e+02 -8.15174179e+01 -6.68623734e+00 1.10169655e+02 1.41222534e+02 7.39323959e+01 -8.43649368e+01 -1.61362366e+02 -9.98708420e+01 5.96400871e+01 1.12203651e+02 -9.78309345e+00 -1.67651489e+02 -1.64872406e+02 -1.38418894e+01 5.86590652e+01 5.29638023e+01 -2.74913158e+01 -1.81142693e+01 3.07461166e+01 9.46082230e+01 1.32431946e+02 1.28802216e+02 1.52652740e+02 1.51646927e+02 7.98164139e+01 -2.28188648e+01 -6.41574097e+01 9.01949120e+00 8.60963745e+01 6.22445221e+01 -5.03298798e+01 -1.39080032e+02 -9.10865173e+01 3.04016399e+01 6.99126129e+01 1.73534241e+01 -6.88564835e+01 -4.91204948e+01 3.35949211e+01 9.37707520e+01 1.44362228e+02 7.76326523e+01 9.22924805e+01 5.36367149e+01 6.00847664e+01 6.34278755e+01 9.50262527e+01 1.56983368e+02 1.16285980e+02 4.45210609e+01 -3.56995621e+01 -7.75108910e+00 8.61335068e+01 1.68217575e+02 1.15257484e+02 5.53401709e+00 -7.37310028e+01 -5.04016342e+01 2.48242798e+01 5.05876999e+01 6.28750114e+01 4.32877998e+01 6.63489456e+01 9.40271683e+01 1.40572357e+02 1.97932831e+02 1.75110825e+02 8.18957138e+01 7.68832064e+00 -9.75255966e-01 3.54920311e+01 7.72468338e+01 1.44087677e+02 1.78817566e+02 9.38198318e+01 -3.65037842e+01 -8.90913010e+01 -3.19139004e+00 1.15800262e+02 1.15263596e+02 4.79306364e+00 -1.21122993e+02 -9.79328690e+01 3.96712227e+01 1.81808289e+02 2.21629578e+02 1.34258179e+02 5.93299599e+01 6.49449005e+01 1.08257393e+02 1.33743179e+02 8.69254379e+01 8.08521805e+01 7.75254669e+01 3.03070145e+01 1.38377600e+01 1.73396091e+01 8.49868622e+01 7.70721130e+01 -7.29964828e+00 -9.41582489e+01 -6.89820786e+01 7.03294830e+01 1.88226562e+02 1.48460724e+02 2.04635944e+01 -6.99604950e+01 -6.89907227e+01 3.85411148e+01 1.35096863e+02 1.76408005e+02 9.64754181e+01 4.85218735e+01 7.65438080e+00 1.76731777e+01 3.55518494e+01 2.51703968e+01 2.95209446e+01 -2.85920906e+01 -6.06290627e+01 -6.77190018e+01 -2.20332203e+01 7.98376846e+01 1.13282875e+02 5.20770607e+01 -4.08591499e+01 -6.47234879e+01 -8.33073902e+00 8.15311203e+01 7.47164154e+01 2.19594002e+01 -7.27169495e+01 -8.36755371e+01 2.13856027e-01 9.40474472e+01 1.34917953e+02 6.71819153e+01 -2.73133612e+00 -6.49431586e-01 5.08246384e+01 1.25049812e+02 1.34024475e+02 1.23339584e+02 8.97066498e+01 2.72897320e+01 1.80980186e+01 6.61732483e+01 1.73009964e+02 2.23382599e+02 1.57840698e+02 7.16438522e+01 1.41074953e+01 5.23903694e+01 1.25006744e+02 1.56183517e+02 1.33166565e+02 7.81252975e+01 8.47494125e+01 1.27226067e+02 1.81300125e+02 1.82986359e+02 1.23311729e+02 6.70244980e+01 8.25128403e+01 1.20933434e+02 1.97606445e+02 1.89109512e+02 1.88063385e+02 1.50873795e+02 1.16702408e+02 9.41808395e+01 8.05875702e+01 1.35442215e+02 1.72931534e+02 1.48179642e+02 8.97060623e+01 3.83141289e+01 7.46248932e+01 1.35662552e+02 1.71072906e+02 1.16683411e+02 6.09851718e-01 -4.03343201e+01 1.77273045e+01 1.44926361e+02 2.17315765e+02 1.75611710e+02 9.63501587e+01 3.36265297e+01 -1.12969952e+01 -6.13100586e+01 -7.11988525e+01 -5.70125084e+01 -2.06793359e+03 -3.37039209e+03 5.32515991e+02 7.64335510e+02 8.24194031e+02 1.47319275e+02 6.40329980e+03 1.80019297e+04 273444416. 211863024. 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. 0. 0. 0. 0. 0. 0. 0. 0. 832060288. -590784000. 59325776. 254382512. 143809264. -214572256. -490165120. -1.13133955e+04 -4.47679199e+03 -6.29822632e+02 -1.21560509e+02 -3.76215820e+01 -5.87029517e-01 6.48265915e+01 1.55661224e+02 1.87720718e+02 1.64518448e+02 9.73931961e+01 5.51893082e+01 6.94530334e+01 1.24156364e+02 2.00606674e+02 2.01983444e+02 1.81625229e+02 1.63903381e+02 1.58509323e+02 1.53955276e+02 1.23138725e+02 1.60852844e+02 1.66028671e+02 1.18988747e+02 7.67878799e+01 1.09056534e+02 2.07233826e+02 2.56153442e+02 1.95769852e+02 1.18937355e+02 7.43364410e+01 1.00382561e+02 1.84947235e+02 2.52131546e+02 2.80477478e+02 2.12571014e+02 1.64595093e+02 1.60417328e+02 2.08085754e+02 2.39564011e+02 2.12249039e+02 2.03907745e+02 1.79299637e+02 1.51036255e+02 1.37159821e+02 1.58841293e+02 2.40424423e+02 2.47557739e+02 1.78670944e+02 9.90097885e+01 8.05645294e+01 1.46674377e+02 2.09655014e+02 2.04801727e+02 1.57649582e+02 1.36401321e+02 1.81949493e+02 2.53548569e+02 2.78216370e+02 2.52434448e+02 1.70925049e+02 1.15286957e+02 1.13509743e+02 1.62251495e+02 2.25446228e+02 2.67809204e+02 2.85876770e+02 2.61917023e+02 2.27431870e+02 1.95246353e+02 1.80539658e+02 1.90783432e+02 1.80650131e+02 1.38731979e+02 1.00894325e+02 1.02015709e+02 1.56780746e+02 1.93717285e+02 1.88652039e+02 1.67972870e+02 1.29065735e+02 1.09428535e+02 1.28486206e+02 1.86782242e+02 2.15810684e+02 1.82450043e+02 1.40529999e+02 1.46071350e+02 1.71824951e+02 1.80747757e+02 1.65837433e+02 1.71875900e+02 1.71466202e+02 1.53657166e+02 1.42692963e+02 1.56079956e+02 2.05832016e+02 2.11583969e+02 1.60760513e+02 1.02306931e+02 8.17779541e+01 1.25001678e+02 1.64649414e+02 1.82463013e+02 1.73624039e+02 1.61829742e+02 1.55281647e+02 1.67163437e+02 1.92529327e+02 2.05439590e+02 1.79449005e+02 1.35093414e+02 1.22148705e+02 1.37676468e+02 1.54610046e+02 1.59353195e+02 1.77177551e+02 1.76116516e+02 1.42878235e+02 1.04557632e+02 1.08217484e+02 1.58704742e+02 1.79215912e+02 1.50538788e+02 1.10403831e+02 1.05877052e+02 1.44201385e+02 1.78491379e+02 1.88440308e+02 1.73974228e+02 1.48437454e+02 1.29121536e+02 1.36655838e+02 1.65894531e+02 1.86227966e+02 1.69701996e+02 1.41704895e+02 1.34950211e+02 1.44855667e+02 1.57829697e+02 1.65217926e+02 1.82545090e+02 1.90263565e+02 1.81271057e+02 1.67593781e+02 1.64785233e+02 1.84960846e+02 1.92558609e+02 1.78762131e+02 1.41372757e+02 1.20448311e+02 1.30435806e+02 1.66261108e+02 1.89001312e+02 1.82858917e+02 1.66527512e+02 1.60032166e+02 1.68518417e+02 1.69116684e+02 1.80546814e+02 1.74825562e+02 1.72316711e+02 1.61536423e+02 1.49591705e+02 1.44568130e+02 1.41582108e+02 1.61331207e+02 1.71103348e+02 1.61288132e+02 1.51231049e+02 1.55136520e+02 1.78426941e+02 1.87153015e+02 1.80384705e+02 1.69669495e+02 1.62272659e+02 1.62720596e+02 1.68790787e+02 1.72264816e+02 1.72664169e+02 1.63505005e+02 1.65664536e+02 1.71865891e+02 1.78633545e+02 1.87797775e+02 1.93607117e+02 1.98596191e+02 1.88146912e+02 1.74321655e+02 1.67807724e+02 1.69147873e+02 1.76706863e+02 1.77083954e+02 1.68746674e+02 1.60271652e+02 1.57549118e+02 1.68341171e+02 1.80962784e+02 1.86034317e+02 1.82236328e+02 1.76727585e+02 1.74520325e+02 1.75213364e+02 1.76777069e+02 1.78968155e+02 1.76641724e+02 1.72970642e+02 1.70899414e+02 1.72939575e+02 1.73795853e+02 1.74329971e+02 1.75281006e+02 1.75187637e+02 1.73844269e+02 1.72709854e+02 1.72834152e+02 1.72698898e+02 1.72146957e+02 1.71685837e+02 1.71816864e+02 1.72137909e+02 1.72334641e+02 1.72359756e+02 1.71398438e+02 1.70691895e+02 1.71118057e+02 1.73029938e+02 1.73821350e+02 1.72549011e+02 1.70921768e+02 1.71265686e+02 1.71652054e+02 1.72065109e+02 1.72168610e+02 1.71923401e+02 1.71769730e+02 1.71810928e+02 1.71820526e+02 1.72600998e+02 1.73003372e+02 1.75647369e+02 1.75323151e+02 1.74672562e+02 1.72229965e+02 1.73072815e+02 1.73843430e+02 1.72140427e+02 1.71962555e+02 1.68783859e+02 1.66749176e+02 1.65077744e+02 1.66446243e+02 1.70410858e+02 1.70130310e+02 1.70217529e+02 1.70167816e+02 1.72112259e+02 1.72064987e+02 1.72671051e+02 1.72900482e+02 1.73163727e+02 1.71691208e+02 1.70284119e+02 1.71909180e+02 1.75065308e+02 1.73393738e+02 1.76631927e+02 1.76530624e+02 1.77439056e+02 1.74271317e+02 1.72155746e+02 1.72824005e+02 1.72950043e+02 1.74982712e+02 1.74702148e+02 1.73637558e+02 1.68882660e+02 1.69732605e+02 1.68179443e+02 1.74205627e+02 1.71706039e+02 1.75517334e+02 1.73601318e+02 1.70515549e+02 1.64406555e+02 1.65695358e+02 1.70991364e+02 1.73494659e+02 1.69300568e+02 1.68296631e+02 1.72764038e+02 1.70337006e+02 1.64209137e+02 1.57632202e+02 1.58876465e+02 1.60532654e+02 1.64446548e+02 1.62390076e+02 1.64727081e+02 1.63866058e+02 1.65031693e+02 1.64153900e+02 1.60914261e+02 1.58560257e+02 1.61613098e+02 1.65256683e+02 1.69051758e+02 1.62138641e+02 1.68660660e+02 1.77393112e+02 1.81702667e+02 1.74428513e+02 1.58575516e+02 1.58729935e+02 1.57374634e+02 1.62546677e+02 1.66049301e+02 1.58350677e+02 1.56361938e+02 1.52908203e+02 1.57201004e+02 1.51987167e+02 1.49372925e+02 1.55377060e+02 1.58275665e+02 1.58138824e+02 1.57376007e+02 1.60271454e+02 1.57168198e+02 1.55598053e+02 1.53486359e+02 1.47816895e+02 1.42472580e+02 1.44565903e+02 1.51897614e+02 1.56945328e+02 1.55900467e+02 1.52541321e+02 1.47780090e+02 1.50344879e+02 1.60996002e+02 1.74017548e+02 1.69790085e+02 1.61440933e+02 1.43294601e+02 1.42719177e+02 1.45199310e+02 1.55603241e+02 1.59405457e+02 1.65245239e+02 1.70269455e+02 1.72040222e+02 1.69527084e+02 1.66716141e+02 1.59604782e+02 1.55814728e+02 1.52325256e+02 1.55797195e+02 1.51256210e+02 1.55913910e+02 1.54900620e+02 1.54931137e+02 1.54912613e+02 1.49990997e+02 1.56730927e+02 1.65922012e+02 1.89014282e+02 1.79803329e+02 1.59307434e+02 1.39838120e+02 1.50627625e+02 1.71594681e+02 1.74503143e+02 1.65231705e+02 1.48505173e+02 1.52539154e+02 1.64672455e+02 1.72782013e+02 1.72312607e+02 1.67321762e+02 1.70686295e+02 1.86834610e+02 1.97787796e+02 1.83368134e+02 1.56928177e+02 1.46094376e+02 1.55908508e+02 1.61212830e+02 1.56432739e+02 1.49520493e+02 1.43441910e+02 1.53080032e+02 1.70446457e+02 1.69425262e+02 1.53999252e+02 1.28676559e+02 1.29895020e+02 1.38296875e+02 1.44213989e+02 1.28682037e+02 9.73001862e+01 8.56842651e+01 1.11047615e+02 1.39682220e+02 1.48078033e+02 1.43818848e+02 1.63927780e+02 1.72242035e+02 1.39888474e+02 9.22899323e+01 7.97214355e+01 1.10535049e+02 1.45172272e+02 1.53300629e+02 1.48926300e+02 1.25827072e+02 1.12108742e+02 1.19522705e+02 1.42784775e+02 1.60865356e+02 1.58485184e+02 1.56957260e+02 1.26479652e+02 8.27204666e+01 7.90065994e+01 1.00259735e+02 1.30111206e+02 1.40132492e+02 1.57558228e+02 1.63080948e+02 1.43627991e+02 1.25008484e+02 1.17506126e+02 1.20982887e+02 1.21441032e+02 1.13067162e+02 1.07548920e+02 1.03588089e+02 1.03737373e+02 1.00386871e+02 1.71044510e+02 8.83398743e+01 3.25196167e+02 4.34794708e+02 6.42896118e+02 2.41158838e+03 3.63460864e+03 4.76111084e+02 3.91101135e+02 2.57060211e+02 -1.07522802e+01 8.07991257e+01 4.18175537e+02 1.57941467e+02 -4.05560638e+02 -9.45770898e+03 -2.42044238e+04 -679112128. -474933664. 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. 0. -859660928. -859660928. -859660928. 0. 0. 1923205760. -120397120. -65511108. -74777120. 350898656. -136748576. -83981680. 1.42022559e+04 5.97002148e+03 8.45539185e+02 3.34228699e+02 1.60819321e+02 1.51877945e+02 1.49635849e+02 1.48453522e+02 1.45331833e+02 1.48972748e+02 1.61090607e+02 1.65997711e+02 1.63459503e+02 1.35869812e+02 1.28125519e+02 1.31051407e+02 1.59115326e+02 1.49373001e+02 1.26230408e+02 9.23612747e+01 8.85760956e+01 8.28294296e+01 6.78457489e+01 5.28141479e+01 4.88684235e+01 3.94758606e+01 2.72939949e+01 2.55839558e+01 2.80457973e+01 3.94181900e+01 4.53347740e+01 3.44575157e+01 2.18190575e+01 9.06124973e+00 3.12494850e+01 4.37415886e+01 3.87576599e+01 2.34607067e+01 1.87933636e+01 1.59697599e+01 1.89760380e+01 2.61208534e+01 5.93921814e+01 8.64702530e+01 9.88795624e+01 8.46351700e+01 7.01410828e+01 5.89522400e+01 4.85513000e+01 5.21553879e+01 6.66403961e+01 6.45152206e+01 5.37735138e+01 3.45391426e+01 3.08255348e+01 1.42075891e+01 3.00362377e+01 5.68047829e+01 7.48477707e+01 9.05240021e+01 8.92257385e+01 9.81436539e+01 8.14944305e+01 7.12164459e+01 7.19297180e+01 6.53827438e+01 3.73920746e+01 1.89022579e+01 2.38867893e+01 4.03273354e+01 5.08868637e+01 4.32001648e+01 7.08831100e+01 1.11922050e+02 1.10843163e+02 9.45224686e+01 7.03322372e+01 1.18828148e+02 1.63974335e+02 1.64232330e+02 1.27986221e+02 1.02236504e+02 1.04238548e+02 1.11486359e+02 9.27446060e+01 9.95504303e+01 1.28144730e+02 1.68311478e+02 1.59749313e+02 1.09008980e+02 6.39166489e+01 3.97748604e+01 4.93489609e+01 5.14337540e+01 6.72409363e+01 3.70313072e+01 1.29621515e+01 3.28393326e+01 7.05677719e+01 7.78188324e+01 4.03037834e+01 1.46646366e+01 6.13602829e+01 9.27540283e+01 8.48330536e+01 3.87392464e+01 3.09827256e+00 -4.43221092e+00 -5.05316067e+00 3.40744519e+00 1.18071260e+01 2.16271992e+01 1.77115536e+01 1.59004717e+01 2.10309353e+01 3.16186256e+01 3.81038704e+01 3.76942940e+01 3.10365028e+01 3.26075516e+01 3.02032623e+01 3.33354492e+01 6.75430222e+01 1.02497749e+02 1.04873451e+02 6.59936523e+01 3.00534496e+01 6.69999466e+01 1.07567978e+02 1.09130913e+02 7.54898453e+01 4.71602364e+01 4.53995018e+01 3.30128288e+01 9.14840317e+00 1.48439112e+01 2.73827286e+01 3.56678543e+01 2.42264614e+01 2.42805719e+00 -1.43774462e+00 5.97973251e+00 2.34596157e+01 2.85103855e+01 3.46075935e+01 2.89031258e+01 4.17731895e+01 8.42003326e+01 1.33647766e+02 1.31899887e+02 9.52829666e+01 5.21022110e+01 7.91555023e+01 1.12818275e+02 1.05438354e+02 6.00609589e+01 1.72954941e+01 2.22047577e+01 2.69107895e+01 3.03628407e+01 2.91964378e+01 3.34790268e+01 3.75866928e+01 3.32486382e+01 2.87297344e+01 4.58618546e+01 6.88344345e+01 6.25215645e+01 3.62626991e+01 2.93751287e+00 2.97550142e-01 -3.39502501e+00 2.56364231e+01 6.35967407e+01 6.29509964e+01 4.26377563e+01 1.44851685e+01 1.17313528e+01 -7.44679308e+00 2.01849880e+01 7.07566071e+01 7.99022446e+01 4.56946793e+01 5.40285969e+00 1.42972221e+01 2.16461849e+01 1.31309767e+01 9.80076408e+00 2.34160023e+01 2.56845455e+01 6.17060394e+01 9.06480331e+01 9.02913818e+01 5.20219116e+01 1.33672819e+01 2.64739971e+01 2.52129173e+01 5.81295738e+01 8.07995148e+01 7.07360535e+01 1.68668022e+01 -2.72419109e+01 -2.09243259e+01 -1.31318550e+01 -5.87754154e+00 -1.85236015e+01 -2.74960346e+01 -3.58570557e+01 -3.77394295e+01 -2.93431168e+01 -2.54905434e+01 -2.76626034e+01 -2.65341778e+01 -4.99608040e+01 -6.05357704e+01 -7.56409302e+01 -7.64670105e+01 -6.46526031e+01 -6.45645218e+01 -6.21814384e+01 -6.38167877e+01 -6.36903648e+01 -6.05959358e+01 -6.93992691e+01 -5.62326241e+01 -5.02140694e+01 -5.15901260e+01 -7.02656326e+01 -6.94242554e+01 -6.11491394e+01 -5.21269302e+01 -5.33608894e+01 -5.89831886e+01 -5.05404396e+01 -5.15611534e+01 -3.16742783e+01 -2.95579166e+01 -3.19253101e+01 -6.45043640e+01 -1.00705551e+02 -7.41313629e+01 -1.25573521e+01 2.95388947e+01 1.17130957e+01 -2.31779766e+01 -2.66371555e+01 -2.21795349e+01 -1.71687317e+01 -1.77644234e+01 -1.84120483e+01 -2.17642975e+01 -2.90816555e+01 -4.98513489e+01 -6.46560822e+01 -7.61420898e+01 -6.21208000e+01 -4.94763756e+01 -3.24208984e+01 -3.01035595e+01 -4.27789612e+01 -5.31992950e+01 -6.59029999e+01 -6.30261993e+01 -6.74068298e+01 -5.46973076e+01 -2.01952000e+01 1.24872932e+01 1.43838701e+01 -1.54200897e+01 -3.91031723e+01 -5.35409851e+01 -5.09495506e+01 -4.03452377e+01 -1.53616076e+01 -1.76186323e+00 8.42506027e+00 -1.43574352e+01 -3.65976067e+01 -6.90524979e+01 -6.08620377e+01 -5.48939934e+01 -4.84474030e+01 -6.14555550e+01 -6.96415253e+01 -8.14791489e+01 -6.93758621e+01 -5.61983566e+01 -4.56002121e+01 -4.14907684e+01 -4.70698280e+01 -1.54421272e+01 1.10932331e+01 4.64390421e+00 -4.13373795e+01 -7.54388275e+01 -6.07661514e+01 -3.90000916e+01 -4.65181541e+01 -5.36724281e+01 -3.36648903e+01 -2.22414827e+00 -2.91283989e+00 -4.17327538e+01 -7.95102997e+01 -6.55616074e+01 -5.35346222e+01 -6.05301590e+01 -7.17091827e+01 -7.93711929e+01 -7.37034760e+01 -6.92086334e+01 -8.31370850e+01 -1.10253204e+02 -1.18123795e+02 -1.12882637e+02 -9.47772141e+01 -9.73663712e+01 -7.20372467e+01 -4.21043625e+01 -3.43516808e+01 -2.67946491e+01 -1.28305225e+01 1.70407829e+01 2.04888210e+01 8.09650135e+00 4.75321740e-01 -1.79535103e+01 -2.30728493e+01 -5.46555862e+01 -9.96762238e+01 -1.48752197e+02 -1.56889389e+02 -1.42502869e+02 -1.29514908e+02 -1.20425667e+02 -1.18154366e+02 -1.09559151e+02 -1.14752045e+02 -1.20772568e+02 -9.99316330e+01 -5.74828110e+01 -4.53875008e+01 -5.59507217e+01 -8.08747711e+01 -8.55490875e+01 -9.07690353e+01 -1.12028175e+02 -9.25290756e+01 -8.95967712e+01 -7.81388321e+01 -7.41883698e+01 -5.70696411e+01 -2.40978909e+01 -5.01044273e+01 -8.39702072e+01 -9.77033615e+01 -6.27448120e+01 -5.75890808e+01 -7.16910477e+01 -1.05156952e+02 -7.53701477e+01 -4.96234703e+01 -4.42136002e+01 -6.62515869e+01 -8.84322968e+01 -5.75407867e+01 -2.65904007e+01 -3.38758163e+01 -7.36531906e+01 -1.06873978e+02 -8.36463013e+01 -6.60169296e+01 -9.20926895e+01 -1.33329910e+02 -1.17602844e+02 -7.38293076e+01 -5.20876274e+01 -5.95486717e+01 -7.48110352e+01 -7.21934891e+01 -5.25019608e+01 -2.65265980e+01 -3.43602867e+01 -8.07155304e+01 -1.15222748e+02 -1.18637634e+02 -1.07613640e+02 -1.00789467e+02 -1.05163712e+02 -1.11649429e+02 -1.14718071e+02 -9.84608917e+01 -9.42533493e+01 -1.12299850e+02 -1.20496918e+02 -1.16453545e+02 -8.53355026e+01 -7.39102402e+01 -8.27423019e+01 -9.24178467e+01 -1.10477760e+02 -1.09353470e+02 -1.17224861e+02 -1.29020386e+02 -1.40388809e+02 -1.35573471e+02 -8.83862534e+01 -5.66717644e+01 -9.11393738e+01 -1.52389709e+02 -1.54243561e+02 -1.05388718e+02 -8.51273041e+01 -1.16229774e+02 -1.35495132e+02 -1.19791130e+02 -1.03705399e+02 -1.07275528e+02 -1.27730476e+02 -1.21338463e+02 -1.14785477e+02 -1.07770126e+02 -1.20175522e+02 -1.40098709e+02 -1.40191315e+02 -1.38188965e+02 -1.14776611e+02 -9.75292587e+01 -9.76109085e+01 -1.21185905e+02 -1.22699959e+02 -8.11685944e+01 -5.17196808e+01 -6.88701019e+01 -1.10407852e+02 -1.13335915e+02 -9.55667496e+01 -1.11954155e+02 -1.50633591e+02 -1.65131958e+02 -1.36836563e+02 -1.18913567e+02 -1.23611908e+02 -1.34390457e+02 -1.17873077e+02 -1.14151642e+02 -1.12179695e+02 -1.23567116e+02 -1.33362076e+02 -1.46490829e+02 -1.51022995e+02 -1.49216019e+02 -1.39993744e+02 -1.23953384e+02 -1.14732704e+02 -1.12155159e+02 -1.07020432e+02 -1.04378777e+02 -1.13486008e+02 -1.26673965e+02 -1.29788177e+02 -1.13168404e+02 -1.10580704e+02 -1.14179466e+02 -1.05445679e+02 -7.44530792e+01 -5.36134987e+01 -7.24517899e+01 -1.10545349e+02 -1.21911484e+02 -1.11702019e+02 -1.09520500e+02 -1.27727478e+02 -1.43136810e+02 -1.51123276e+02 -1.52200470e+02 -1.52405090e+02 -1.38594116e+02 -1.40982788e+02 -1.52006668e+02 -1.55754745e+02 -1.26943230e+02 -1.08532639e+02 -1.25687050e+02 -1.43793793e+02 -1.27522812e+02 -1.12518333e+02 -1.30643600e+02 -1.68691422e+02 -1.92892685e+02 -1.87669357e+02 -1.85546341e+02 -1.75450577e+02 -1.75903336e+02 -1.72768295e+02 -1.74992691e+02 -1.65304779e+02 -1.58810806e+02 -1.60278854e+02 -1.74179398e+02 -1.64490723e+02 -1.34092896e+02 -1.14274002e+02 -1.12566269e+02 -1.17326164e+02 -1.30142746e+02 -1.41038651e+02 -1.55527252e+02 -1.52480927e+02 -1.55858521e+02 -1.57985336e+02 -1.60988907e+02 -1.56536758e+02 -1.58908707e+02 -1.54861359e+02 -1.54370087e+02 -1.57570328e+02 -1.58845367e+02 -1.60632156e+02 -1.43695404e+02 -1.29320389e+02 -1.28035736e+02 -1.42376495e+02 -1.54452744e+02 -1.53631332e+02 -1.52594666e+02 -1.52880981e+02 -1.55650711e+02 -1.57601913e+02 -1.57261963e+02 -1.47952682e+02 -1.36047836e+02 -1.40783096e+02 -1.53834122e+02 -1.57926193e+02 -1.37724472e+02 -1.24509483e+02 -1.33622345e+02 -1.53588135e+02 -1.54205002e+02 -1.42931763e+02 -1.44907242e+02 -1.54178162e+02 -1.64542419e+02 -1.53462036e+02 -1.44545425e+02 -1.36782669e+02 -1.33306625e+02 -1.46833237e+02 -1.56214035e+02 -1.57318481e+02 -1.37827011e+02 -1.31376694e+02 -1.46037811e+02 -1.62982773e+02 -1.61134338e+02 -1.46030106e+02 -1.44271515e+02 -1.50925018e+02 -1.60936234e+02 -1.54863556e+02 -1.46894318e+02 -1.44494766e+02 -1.49926361e+02 -1.57800125e+02 -1.59634979e+02 -1.53436600e+02 -1.46277710e+02 -1.46044189e+02 -1.52309464e+02 -1.63395370e+02 -1.60243118e+02 -1.55514664e+02 -1.55032349e+02 -1.60320450e+02 -1.61118988e+02 -1.54923203e+02 -1.56614624e+02 -1.63150635e+02 -1.69816833e+02 -1.71062271e+02 -1.72272049e+02 -1.68620865e+02 -1.63158585e+02 -1.60659714e+02 -1.63236237e+02 -1.67989365e+02 -1.69560089e+02 -1.69326126e+02 -1.66375198e+02 -1.62428665e+02 -1.48584778e+02 -1.37538651e+02 -1.48180939e+02 -1.39206909e+02 -1.24327042e+02 -1.22632011e+02 -1.29867401e+02 -1.66529999e+02 -1.78995453e+02 -5.13177338e+01 -4.73158302e+01 -5.25906128e+02 -4.88884216e+02 -3.74624634e+02 1.50361420e+02 28971730. 0. 0. 0. 0. 0. 0. -276646528. -276646528. -2.33673926e+03 -2.83143140e+03 -2.83143140e+03 -488244768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 8910349. -3.75655762e+02 1.03373161e+02 4.00264206e+01 -8.17296371e+01 -9.22418823e+01 -1.28731705e+02 -1.39451889e+02 -1.49585419e+02 -1.51478363e+02 -1.45481003e+02 -1.43100250e+02 -1.46416214e+02 -1.43467850e+02 -1.35571503e+02 -1.29335327e+02 -1.35966324e+02 -1.51398285e+02 -1.58713943e+02 -1.53769272e+02 -1.42126144e+02 -1.36628311e+02 -1.38721878e+02 -1.41929337e+02 -1.36663147e+02 -1.30189850e+02 -1.34001801e+02 -1.46343521e+02 -1.52787415e+02 -1.47830475e+02 -1.36601364e+02 -1.32277206e+02 -1.41846741e+02 -1.55332855e+02 -1.61702148e+02 -1.53882294e+02 -1.54229507e+02 -1.63809387e+02 -1.58038803e+02 -1.39337326e+02 -1.25768417e+02 -1.41253876e+02 -1.72878952e+02 -1.80882858e+02 -1.64522293e+02 -1.48211044e+02 -1.38687073e+02 -1.39879700e+02 -1.40382141e+02 -1.42878860e+02 -1.39235291e+02 -1.42948242e+02 -1.68713013e+02 -1.85997452e+02 -1.79139313e+02 -1.53253937e+02 -1.39002502e+02 -1.46217392e+02 -1.63322708e+02 -1.71726486e+02 -1.58613342e+02 -1.53867798e+02 -1.59546524e+02 -1.51351166e+02 -1.33687256e+02 -1.12889122e+02 -1.14909386e+02 -1.46012177e+02 -1.58281403e+02 -1.49376587e+02 -1.25206184e+02 -1.33947891e+02 -1.56577621e+02 -1.50534454e+02 -1.28857666e+02 -1.19726387e+02 -1.32965744e+02 -1.65478806e+02 -1.75260498e+02 -1.67468292e+02 -1.35423492e+02 -1.17336159e+02 -1.22076187e+02 -1.34554443e+02 -1.31376160e+02 -1.15308029e+02 -1.18554665e+02 -1.42525406e+02 -1.54222733e+02 -1.30993393e+02 -9.44615860e+01 -8.78771744e+01 -1.20898880e+02 -1.54436874e+02 -1.58075394e+02 -1.30971924e+02 -1.23766487e+02 -1.31242889e+02 -1.16664192e+02 -8.23741684e+01 -6.25165215e+01 -9.27411957e+01 -1.42048050e+02 -1.71520538e+02 -1.59676697e+02 -1.31673141e+02 -9.43735580e+01 -7.22774277e+01 -7.78333893e+01 -9.00991135e+01 -8.53618927e+01 -8.85730438e+01 -1.22259186e+02 -1.56635864e+02 -1.38602859e+02 -8.37126617e+01 -6.08189583e+01 -8.16340179e+01 -1.35529251e+02 -1.59346573e+02 -1.36785461e+02 -1.11427818e+02 -1.08905533e+02 -1.11646141e+02 -9.16194763e+01 -4.51158333e+01 -5.07369499e+01 -9.47178574e+01 -1.39712036e+02 -1.37997803e+02 -1.05590263e+02 -7.99963150e+01 -7.67702332e+01 -8.86626434e+01 -1.12278603e+02 -1.18928726e+02 -8.97193146e+01 -7.70023956e+01 -9.75734024e+01 -1.20699753e+02 -1.21736694e+02 -1.05432343e+02 -1.05116776e+02 -1.29919495e+02 -1.29974777e+02 -1.08012215e+02 -8.16875916e+01 -7.41280594e+01 -1.06241821e+02 -1.15676140e+02 -1.05429596e+02 -7.94619217e+01 -9.82032242e+01 -1.69987549e+02 -2.07602386e+02 -1.63399857e+02 -9.42130432e+01 -7.92662735e+01 -1.11404839e+02 -1.34392303e+02 -1.31423279e+02 -1.33391052e+02 -1.58011368e+02 -1.96221481e+02 -2.04527222e+02 -1.88655212e+02 -1.35469620e+02 -9.72992630e+01 -1.18712715e+02 -1.34189972e+02 -1.29540024e+02 -9.40851212e+01 -1.22000145e+02 -1.86104797e+02 -1.78427582e+02 -1.45071167e+02 -1.17809074e+02 -1.60628204e+02 -2.37665573e+02 -2.72706055e+02 -2.33969284e+02 -1.63064667e+02 -1.12264008e+02 -1.21908470e+02 -1.04988297e+02 -9.57798920e+01 -1.01129082e+02 -1.50868332e+02 -2.11707443e+02 -2.12060959e+02 -1.62178680e+02 -6.97192993e+01 -3.07076759e+01 -5.45532379e+01 -1.17344269e+02 -1.63580566e+02 -1.58418945e+02 -1.77767792e+02 -2.02924347e+02 -1.90261078e+02 -1.33924744e+02 -7.07756729e+01 -1.02989685e+02 -1.78977951e+02 -2.25723557e+02 -1.73651932e+02 -7.99761581e+01 -4.99291649e+01 -9.32418365e+01 -1.47144073e+02 -1.21360275e+02 -7.30503540e+01 -8.44883728e+01 -1.40113312e+02 -1.65322906e+02 -1.11148338e+02 -3.24943466e+01 -1.25999126e+01 -5.45917473e+01 -9.87463150e+01 -9.50242844e+01 -7.17330627e+01 -6.88583374e+01 -8.91380234e+01 -6.64515915e+01 -3.21532326e+01 -3.57839508e+01 -4.95383987e+01 -9.44927139e+01 -1.11326111e+02 -9.07840118e+01 -9.00082245e+01 -8.03994598e+01 -1.14039078e+02 -7.79531860e+01 -4.17034798e+01 -2.39634800e+01 -4.29086609e+01 -1.37046844e+02 -1.84925034e+02 -1.76187759e+02 -6.41666183e+01 -1.28337622e+01 -7.99010706e+00 -6.01897926e+01 -7.76578217e+01 -4.82735252e+01 -4.53296318e+01 -7.86911621e+01 -1.01135071e+02 -6.37822304e+01 -3.81978111e+01 -9.44377213e+01 -1.73692139e+02 -1.56836960e+02 -1.13479240e+02 -8.33102722e+01 -1.05512848e+02 -1.48109833e+02 -9.10201950e+01 -5.51162720e+01 -1.66905975e+01 -4.83527985e+01 -1.09170235e+02 -1.42338531e+02 -1.70432114e+02 -1.16093437e+02 -8.00787201e+01 -6.13343582e+01 -1.08449547e+02 -1.27882477e+02 -1.20020004e+02 -1.36993881e+02 -1.65316086e+02 -1.87536163e+02 -1.10304306e+02 -6.83419113e+01 -7.20705032e+01 -1.28923553e+02 -1.16414169e+02 -8.60603943e+01 -5.25671730e+01 -2.66583519e+01 -4.18784752e+01 -3.28072395e+01 -9.79882431e+01 -1.25319023e+02 -1.58713150e+02 -1.54099777e+02 -1.28414215e+02 -9.50442352e+01 -3.03678875e+01 -9.13802236e-02 -1.60748501e+01 -1.07912033e+02 -1.24836769e+02 -1.08555466e+02 -7.96450806e+01 -9.81776733e+01 -7.55646744e+01 8.45489216e+00 5.49119339e+01 1.65655975e+01 -8.34317627e+01 -1.05451027e+02 -6.50429382e+01 -3.79628778e+00 9.17348576e+00 -4.11450272e+01 -4.68678551e+01 -6.09245338e+01 -9.75945175e-01 2.23389187e+01 3.86023369e+01 -2.30623188e+01 -4.64110107e+01 -6.75211668e+00 4.61482277e+01 1.08935928e+01 -5.16143112e+01 -3.31505203e+01 -6.64673686e-01 -2.75313711e+00 -5.38341789e+01 -4.30710335e+01 2.27599773e+01 6.02761269e+01 3.84377899e+01 -4.94743156e+01 -3.54880295e+01 -1.21241789e+01 3.31094780e+01 7.87114763e+00 -3.49551086e+01 -1.92981319e+01 -2.03266029e+01 3.42878304e+01 4.67797585e+01 4.67217674e+01 9.41602325e+00 -5.24237776e+00 2.31948738e+01 5.21884079e+01 3.10973778e+01 -3.05911617e+01 -4.38141518e+01 -5.34200554e+01 -8.00558014e+01 -1.30502029e+02 -1.06499390e+02 -3.47162514e+01 -2.63723030e+01 -6.23149529e+01 -1.16965683e+02 -5.06349907e+01 -2.69989738e+01 -1.80754387e+00 3.25300407e+01 5.17315407e+01 2.04799843e+01 -8.22334747e+01 -1.05443420e+02 -3.89232597e+01 3.31968880e+01 -5.80697536e-01 -9.19188156e+01 -1.40755875e+02 -8.95066910e+01 -3.09937744e+01 -4.14056244e+01 -6.50631027e+01 -1.13427803e+02 -1.58136993e+02 -2.20331619e+02 -1.90861084e+02 -1.29166565e+02 -1.13624687e+02 -1.47418121e+02 -1.85306107e+02 -9.36990204e+01 -5.59383354e+01 -2.47316017e+01 -4.46949425e+01 -4.68034134e+01 -8.37937698e+01 -1.95269043e+02 -2.26586426e+02 -1.44452942e+02 1.46099787e+01 6.04567871e+01 -6.05753822e+01 -1.79511612e+02 -1.92279297e+02 -1.03873146e+02 -4.57328644e+01 -7.98279190e+01 -1.52678680e+02 -1.86545013e+02 -1.35862061e+02 -2.00263615e+01 2.18004942e+00 -5.99356499e+01 -1.42794540e+02 -2.30472458e+02 -2.20231705e+02 -1.81294312e+02 -6.54521942e+01 5.60243797e+01 9.91624069e+01 3.04423561e+01 -1.23344955e+02 -2.04179382e+02 -1.31431610e+02 -2.69972591e+01 -2.80853252e+01 -1.44916672e+02 -2.47623337e+02 -2.08337112e+02 -7.83139648e+01 2.60082417e+01 3.30509529e+01 -5.35261726e+01 -1.13097748e+02 -1.56374634e+02 -8.60015106e+01 -5.69656563e+01 -3.14922523e+01 -7.36028366e+01 -1.04857658e+02 -4.93891373e+01 1.71006451e+01 1.03954414e+02 1.12176498e+02 5.22015343e+01 -1.99375801e+01 -1.33074814e+02 -1.51147491e+02 -6.99397354e+01 9.57031021e+01 1.69783905e+02 9.80372849e+01 -6.23231888e+01 -1.45022202e+02 -1.13051987e+02 -4.11060791e+01 -4.00973282e+01 -8.82406387e+01 -1.16663170e+02 -1.21993950e+02 -4.63778038e+01 -2.50969028e+00 5.06366272e+01 5.00628281e+01 1.11042280e+01 -2.83610172e+01 -7.86923828e+01 -5.59619484e+01 -5.18934202e+00 5.78386040e+01 5.80415497e+01 -2.04110551e+00 -7.21484070e+01 -4.05651321e+01 2.34141426e+01 6.10490494e+01 1.51940882e+00 -8.94823151e+01 -9.76691132e+01 -3.62560234e+01 6.86861877e+01 7.54185104e+01 -2.87625480e+00 -7.16803513e+01 -1.10813461e+02 -2.35778351e+01 9.60054755e-01 4.55132904e+01 4.28865204e+01 4.91748161e+01 5.95088730e+01 2.63192348e+01 5.34727135e+01 7.43927765e+01 5.85564728e+01 4.68283129e+00 -9.19550018e+01 -1.18070259e+02 -6.29793320e+01 8.29681854e+01 1.92498764e+02 1.70776428e+02 4.12063065e+01 -8.90050430e+01 -1.18902672e+02 -2.86036682e+01 7.46933823e+01 9.95917130e+01 2.53754597e+01 -6.68744507e+01 -3.82050171e+01 2.66405220e+01 1.07118866e+02 1.21876038e+02 9.21714706e+01 2.71239834e+01 -4.52958641e+01 -3.80902786e+01 4.07977333e+01 1.43954819e+02 1.56184647e+02 7.21819153e+01 -3.52885208e+01 -1.64858875e+01 7.47307129e+01 1.35070084e+02 1.08952690e+02 4.87992477e+01 3.06925964e+01 1.34748812e+01 3.98814087e+01 6.23816109e+01 3.14957733e+01 2.75112782e+01 1.95027500e-01 4.82997665e+01 7.90020065e+01 1.37779556e+02 1.70451080e+02 1.36581207e+02 8.23445511e+01 6.01119661e+00 -2.89463539e+01 1.46723289e+01 9.05374680e+01 1.07257278e+02 2.76668262e+01 -5.61116447e+01 -4.86117401e+01 1.39244194e+01 1.04307121e+02 1.25518448e+02 8.79960556e+01 4.32767296e+01 3.66826477e+01 1.04725372e+02 1.62161133e+02 2.11282608e+02 1.93483948e+02 1.11883698e+02 1.20867119e+02 1.48613998e+02 2.25674438e+02 2.31500275e+02 2.08290283e+02 1.59732178e+02 5.54217491e+01 1.50104427e+01 2.92908974e+01 1.14531693e+02 1.54416077e+02 9.38078842e+01 1.13017082e+01 1.15563316e+01 1.03407372e+02 1.75723114e+02 1.51788040e+02 6.59044800e+01 -1.38849795e+00 -1.06811037e+01 5.93260078e+01 1.45945602e+02 1.71343826e+02 1.59458588e+02 1.25803192e+02 1.00201332e+02 5.05540810e+01 4.52633705e+01 6.80001373e+01 9.51184464e+01 6.70407028e+01 -5.01730394e+00 -5.16781349e+01 2.17374182e+00 1.02579613e+02 1.57973709e+02 1.06842873e+02 8.19921684e+00 -1.33676453e+01 3.76710014e+01 1.27688286e+02 1.37771881e+02 8.27462921e+01 5.43083344e+01 5.09251404e+01 1.06038681e+02 1.22856819e+02 1.12134666e+02 8.91319656e+01 4.02960815e+01 5.05585327e+01 5.56810036e+01 1.35119049e+02 1.88796356e+02 1.79658936e+02 1.37352386e+02 6.49830551e+01 3.44280128e+01 3.54465942e+01 1.18958412e+02 2.56224915e+02 3.14139801e+02 2.90699982e+02 1.18036430e+02 7.01541290e+01 -4.97430468e+00 -3.60630112e+01 1.90333923e+03 2.98563647e+03 6.40329980e+03 1.80019297e+04 273444416. 211863024. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 260286800. 184363616. 208756752. -209869424. 3.00213496e+04 1.01439209e+04 2.90452393e+03 4.03635864e+02 1.84709412e+02 1.22161682e+02 1.14996490e+02 1.55716660e+02 1.63796021e+02 1.40780899e+02 5.83408089e+01 6.02645950e+01 1.03199028e+02 1.66911530e+02 1.56771347e+02 9.48212280e+01 3.89846153e+01 2.34494419e+01 7.27286987e+01 1.51251907e+02 1.67432526e+02 1.13911240e+02 5.25383797e+01 5.40427094e+01 1.00935768e+02 1.02513412e+02 6.84680252e+01 6.08011627e+01 9.27195053e+01 1.28963135e+02 1.31214813e+02 1.41711273e+02 1.57205048e+02 1.56266357e+02 1.16214050e+02 4.74277992e+01 4.16367836e+01 8.67739029e+01 1.33722076e+02 1.35115585e+02 8.94437561e+01 4.15089111e+01 4.78917694e+01 1.16040939e+02 1.93382111e+02 1.86506058e+02 1.08266762e+02 7.01239319e+01 6.56066360e+01 1.10482552e+02 1.27483833e+02 1.38466507e+02 1.43287445e+02 1.28982697e+02 1.04478600e+02 6.13719940e+01 7.64026184e+01 1.17488861e+02 1.31756073e+02 1.03628426e+02 5.53904381e+01 5.60459862e+01 8.26425400e+01 1.25020958e+02 1.42673676e+02 1.00491737e+02 4.64424744e+01 4.71468353e+00 2.95682411e+01 8.95066071e+01 1.09821083e+02 7.77239304e+01 5.45740089e+01 6.25725670e+01 1.13355911e+02 1.22459618e+02 1.09436729e+02 8.69155350e+01 9.05827713e+01 9.08330154e+01 7.49748764e+01 9.53488388e+01 1.29833862e+02 1.48242966e+02 1.09332565e+02 5.63808937e+01 4.67810783e+01 6.30526505e+01 1.01847221e+02 1.34207306e+02 1.37591293e+02 1.06994072e+02 7.83260422e+01 8.61962280e+01 1.34884598e+02 1.58660477e+02 1.18787445e+02 8.65729065e+01 8.51887741e+01 1.35402756e+02 1.57881638e+02 1.54033798e+02 1.46107254e+02 1.36108429e+02 1.23560974e+02 8.97145996e+01 9.35886307e+01 1.19624687e+02 1.44151138e+02 1.38925491e+02 1.11341095e+02 1.06353302e+02 1.26219322e+02 1.42128906e+02 1.59298767e+02 1.52002396e+02 1.23466011e+02 9.62844925e+01 8.86632462e+01 1.30273468e+02 1.47860062e+02 1.34859100e+02 1.21337273e+02 1.21365791e+02 1.38825745e+02 1.35838562e+02 1.34009003e+02 1.43893570e+02 1.50043304e+02 1.43868576e+02 1.14984871e+02 1.15079056e+02 1.36591507e+02 1.52085342e+02 1.48840836e+02 1.28095657e+02 1.32699066e+02 1.49209213e+02 1.59813919e+02 1.69966858e+02 1.55540558e+02 1.32620331e+02 1.13892395e+02 1.16308708e+02 1.36440720e+02 1.40516998e+02 1.36253448e+02 1.37072769e+02 1.43223984e+02 1.53047440e+02 1.62029388e+02 1.67704544e+02 1.71429153e+02 1.62073883e+02 1.46158630e+02 1.25890465e+02 1.19719147e+02 1.27749565e+02 1.38772141e+02 1.36961227e+02 1.23621613e+02 1.11980026e+02 1.21019653e+02 1.42527084e+02 1.58123856e+02 1.56281036e+02 1.36188049e+02 1.26367867e+02 1.27134987e+02 1.40495941e+02 1.42273071e+02 1.39380829e+02 1.38337418e+02 1.36832886e+02 1.34326187e+02 1.33822998e+02 1.44162643e+02 1.55898056e+02 1.56158951e+02 1.50928009e+02 1.42680481e+02 1.36594757e+02 1.35919556e+02 1.37673386e+02 1.39285507e+02 1.31294632e+02 1.24654556e+02 1.28383148e+02 1.40865356e+02 1.51265747e+02 1.51646362e+02 1.43246323e+02 1.40875977e+02 1.40651611e+02 1.48183777e+02 1.47198029e+02 1.42939178e+02 1.36230835e+02 1.32993439e+02 1.32925079e+02 1.30005585e+02 1.33309570e+02 1.39905731e+02 1.44532669e+02 1.44061066e+02 1.39298996e+02 1.39090042e+02 1.41967300e+02 1.45422226e+02 1.48019196e+02 1.46076477e+02 1.42178085e+02 1.39186935e+02 1.40248306e+02 1.42944550e+02 1.43470856e+02 1.42815262e+02 1.42584198e+02 1.42689819e+02 1.42984985e+02 1.43004120e+02 1.42821411e+02 1.42723572e+02 1.42740555e+02 1.43204803e+02 1.44421844e+02 1.45512207e+02 1.45196014e+02 1.44196579e+02 1.43831848e+02 1.44064575e+02 1.42927307e+02 1.40932129e+02 1.40121384e+02 1.40406342e+02 1.42786301e+02 1.43716003e+02 1.44828888e+02 1.44076416e+02 1.41714767e+02 1.40819031e+02 1.41223328e+02 1.43958115e+02 1.44612289e+02 1.43207062e+02 1.41804291e+02 1.41518646e+02 1.44419876e+02 1.45617249e+02 1.45589020e+02 1.43078461e+02 1.41370728e+02 1.39971817e+02 1.39799759e+02 1.38710434e+02 1.39886566e+02 1.40740829e+02 1.42975616e+02 1.41119049e+02 1.40303284e+02 1.39186951e+02 1.39593063e+02 1.37917252e+02 1.35530319e+02 1.36054718e+02 1.34415405e+02 1.33614151e+02 1.34439255e+02 1.39787018e+02 1.41258362e+02 1.36882263e+02 1.34114319e+02 1.35784821e+02 1.36994934e+02 1.35243469e+02 1.32885437e+02 1.33041824e+02 1.32816818e+02 1.35418213e+02 1.36786957e+02 1.37873352e+02 1.34587799e+02 1.34334610e+02 1.30134567e+02 1.29383041e+02 1.31599548e+02 1.35578751e+02 1.33976791e+02 1.30912964e+02 1.29998444e+02 1.37200272e+02 1.43073196e+02 1.45976959e+02 1.40202820e+02 1.35446533e+02 1.31799667e+02 1.33269501e+02 1.35990662e+02 1.38528137e+02 1.39504074e+02 1.33468658e+02 1.32994690e+02 1.32188675e+02 1.33304443e+02 1.28853928e+02 1.28612930e+02 1.30458588e+02 1.30398239e+02 1.31732040e+02 1.34523010e+02 1.39990463e+02 1.45062897e+02 1.41394150e+02 1.40854996e+02 1.33366318e+02 1.30486679e+02 1.16210838e+02 1.06424400e+02 1.07600899e+02 1.18608086e+02 1.28550201e+02 1.32332016e+02 1.39252533e+02 1.38831467e+02 1.25175423e+02 1.09378326e+02 1.12695351e+02 1.27236763e+02 1.39888107e+02 1.41335968e+02 1.38258347e+02 1.40070877e+02 1.40043594e+02 1.43161194e+02 1.37813248e+02 1.36319031e+02 1.36179733e+02 1.30841263e+02 1.26938774e+02 1.32350372e+02 1.39391113e+02 1.51857880e+02 1.47402573e+02 1.47186111e+02 1.30538040e+02 1.33250748e+02 1.36156235e+02 1.37119659e+02 1.30096481e+02 1.27644913e+02 1.41555649e+02 1.56616989e+02 1.57936600e+02 1.39568924e+02 1.24367722e+02 1.18253410e+02 1.26856522e+02 1.51907608e+02 1.68651703e+02 1.57556961e+02 1.20867981e+02 1.06477745e+02 1.17010048e+02 1.26671577e+02 1.36847260e+02 1.47012573e+02 1.62779678e+02 1.52797928e+02 1.38777100e+02 1.20491211e+02 1.22887566e+02 1.24552299e+02 1.39369675e+02 1.44588242e+02 1.40111206e+02 1.24005630e+02 1.13360130e+02 1.09393227e+02 1.11911423e+02 1.11133881e+02 1.06610191e+02 1.00787354e+02 1.00130836e+02 1.10531891e+02 1.21641930e+02 1.15089951e+02 1.08961281e+02 1.05665581e+02 1.12154068e+02 1.13575890e+02 1.03844887e+02 1.21206787e+02 1.35938217e+02 1.35983078e+02 1.10559631e+02 9.37587509e+01 1.06060944e+02 1.12969109e+02 1.19058876e+02 1.27857635e+02 1.38959702e+02 1.39476837e+02 1.46450562e+02 1.46426620e+02 1.41108414e+02 1.17710930e+02 1.10904022e+02 1.17679832e+02 1.19484116e+02 1.16523430e+02 1.12379013e+02 1.14622551e+02 1.14885361e+02 1.36041901e+02 1.53543274e+02 1.54459366e+02 1.33261902e+02 1.13870087e+02 1.08381805e+02 1.03351654e+02 1.02637917e+02 1.04137154e+02 1.07963928e+02 1.03900291e+02 9.07594452e+01 7.04608917e+01 6.35170326e+01 7.16514435e+01 9.48363037e+01 9.70379257e+01 8.98293533e+01 8.58473587e+01 9.01757278e+01 9.62622528e+01 6.63333359e+01 3.38372612e+01 2.78024254e+01 6.21647797e+01 9.86534882e+01 1.03268044e+02 7.97430038e+01 4.29785538e+01 -7.06493607e+01 -2.43928329e+02 -4.69297455e+02 -2.31390405e+03 -3.34074072e+03 4.76111084e+02 3.91101135e+02 2.57060211e+02 -1.07522802e+01 8.07991257e+01 4.18175537e+02 1.57941467e+02 -4.05560638e+02 -9.45770898e+03 -2.42044238e+04 -679112128. -474933664. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1845488128. 137870960. 354110240. -1.35753594e+04 -4.96951123e+03 -3.93579071e+02 -3.96113930e+01 2.59349174e+01 1.77124843e-01 5.12929630e+00 3.28951263e+01 6.45783386e+01 5.48461304e+01 4.64223824e+01 4.63925858e+01 4.55262718e+01 2.55063515e+01 2.74483705e+00 2.73366661e+01 7.71980133e+01 8.95187302e+01 5.41667099e+01 2.26285210e+01 4.34250908e+01 4.64393921e+01 3.85290031e+01 2.07982216e+01 1.38610449e+01 1.08242016e+01 1.89118156e+01 3.76888313e+01 4.50514526e+01 4.25015068e+01 3.14230194e+01 6.19122543e+01 9.77471008e+01 1.03916985e+02 8.13082962e+01 6.03112259e+01 6.80240250e+01 8.24766464e+01 8.43994141e+01 9.80514221e+01 1.08503151e+02 1.13760078e+02 1.19247650e+02 1.17353233e+02 1.08540611e+02 9.71648102e+01 8.64591293e+01 9.32261887e+01 9.46527481e+01 9.18301163e+01 9.24387894e+01 9.16076965e+01 1.03084076e+02 1.10122055e+02 9.92428818e+01 6.31141777e+01 1.86200542e+01 -4.94748163e+00 1.43288603e+01 4.28671036e+01 6.22022972e+01 3.29602623e+01 7.62180519e+00 1.92927361e+01 5.78534889e+01 9.11679916e+01 9.14623032e+01 9.00973969e+01 1.08475609e+02 1.49318985e+02 1.23190239e+02 7.14766312e+01 2.32453098e+01 2.96771240e+01 5.58547554e+01 5.33247681e+01 6.32790527e+01 5.69780083e+01 6.28539886e+01 5.13251534e+01 4.98753891e+01 3.82730904e+01 3.32423897e+01 3.63982468e+01 4.49303474e+01 4.20392265e+01 6.90061855e+00 -3.77530975e+01 -1.47020197e+01 1.32912350e+01 4.91087379e+01 2.61412640e+01 1.29865646e+01 -8.25415325e+00 -2.73355103e+01 -1.03048277e+00 4.12376518e+01 5.86040459e+01 3.72898788e+01 -8.43186092e+00 -1.00429029e+01 -6.84867811e+00 1.76896191e+01 3.20181885e+01 3.06929111e+01 3.40655403e+01 3.14173222e+01 3.78948479e+01 2.74157543e+01 2.97555866e+01 3.56928101e+01 1.14902897e+01 -1.79153805e+01 -1.71078873e+01 1.24917994e+01 3.97728348e+01 4.04232407e+01 5.28705139e+01 5.11765251e+01 5.82310028e+01 5.61028633e+01 5.82848511e+01 1.42694073e+01 -2.69648037e+01 -3.17405910e+01 1.85305250e+00 3.49627495e+01 5.61799889e+01 7.05602722e+01 6.92721329e+01 5.07138214e+01 3.81538239e+01 5.11937790e+01 3.15461235e+01 2.46504765e+01 2.30096989e+01 3.36422195e+01 3.26256561e+01 2.12195873e+01 1.79366951e+01 2.02642059e+01 1.92413998e+01 1.00819016e+01 1.12356548e+01 9.35125256e+00 8.07094383e+00 -6.91268563e-01 -7.54279661e+00 1.56662956e-01 8.50637150e+00 1.45016174e+01 1.68014030e+01 2.42634373e+01 3.33079834e+01 3.55793266e+01 2.52767677e+01 -2.92432594e+01 -6.60222778e+01 -7.07850647e+01 -5.02016220e+01 -2.30338688e+01 -2.19785938e+01 -2.12106919e+00 7.64300871e+00 2.03930044e+00 -7.38345861e+00 -1.19381294e+01 -1.30123072e+01 -8.58810902e+00 8.65231216e-01 4.86419258e+01 8.73021240e+01 1.09351562e+02 1.00568344e+02 5.56452293e+01 1.47684393e+01 -2.77174416e+01 -1.57075825e+01 -9.24856186e+00 6.44225061e-01 -8.48178387e+00 -1.15253544e+00 -9.62098658e-01 4.03241777e+00 8.50987053e+00 -2.31233621e+00 -8.98021793e+00 -7.51931953e+00 9.59594250e-01 7.58908558e+00 -1.74755001e+01 -3.03355389e+01 -4.13513069e+01 -3.89251595e+01 -2.51852646e+01 1.38972788e+01 6.01237602e+01 8.13810349e+01 8.32974472e+01 7.59530334e+01 8.53395691e+01 5.23934326e+01 3.50181198e+00 -5.15292015e+01 -6.31125488e+01 -5.42099075e+01 -3.63635979e+01 -3.33367577e+01 -3.65054092e+01 -5.18029099e+01 -5.09638672e+01 -4.77136574e+01 -3.66298561e+01 -3.74437981e+01 -4.03509178e+01 -7.61464386e+01 -1.14014297e+02 -1.02984444e+02 -7.22572479e+01 -3.50349655e+01 -1.74801731e+01 2.53337288e+00 4.52234612e+01 7.27753906e+01 5.76155052e+01 2.93387222e+01 -2.26106339e+01 -5.57364750e+00 5.99195385e+00 2.85754089e+01 2.58548355e+01 1.37619801e+01 1.27705679e+01 1.46530886e+01 1.18295383e+01 -4.76495886e+00 -1.98804493e+01 -1.92220478e+01 1.27606268e+01 5.13493576e+01 8.85523148e+01 1.00083969e+02 3.21812096e+01 -4.46463776e+01 -8.53151169e+01 -6.33173447e+01 -2.16275330e+01 -2.47433281e+01 -1.24128733e+01 -1.92607880e+01 -2.13875618e+01 -3.34302254e+01 -3.79272270e+01 -3.50216179e+01 -2.42443695e+01 -2.62332954e+01 -6.26135826e+01 -1.09625702e+02 -1.18178703e+02 -9.80908127e+01 -7.02234726e+01 -4.97715378e+01 -2.34115620e+01 -1.95308037e+01 -3.73019142e+01 -4.20924301e+01 -2.46242809e+01 -2.09355221e+01 -4.33807220e+01 -6.22687340e+01 -7.16420441e+01 -6.66935883e+01 -6.14512901e+01 -5.17430725e+01 -5.64418259e+01 -5.04834251e+01 -5.28652039e+01 -5.41055603e+01 -7.45493698e+01 -8.75463867e+01 -8.44767914e+01 -5.39274940e+01 -4.44446516e+00 -1.56812537e+00 -3.38159828e+01 -7.46924133e+01 -6.43765869e+01 -5.60665665e+01 -5.52735786e+01 -6.18404083e+01 -6.21398125e+01 -5.18335190e+01 -2.99055614e+01 -1.00440397e+01 -1.53925295e+01 -4.92706566e+01 -7.86059418e+01 -8.07743530e+01 -6.59517212e+01 -8.46349487e+01 -1.19746109e+02 -1.32732162e+02 -1.21581322e+02 -8.99743729e+01 -9.44030685e+01 -9.02900543e+01 -9.22159119e+01 -7.78440475e+01 -7.98383484e+01 -8.23837738e+01 -1.00060135e+02 -9.16918411e+01 -9.24692154e+01 -8.94860764e+01 -9.56874008e+01 -8.46627197e+01 -7.44848328e+01 -5.13838959e+01 -3.12274456e+01 -3.54632378e+01 -5.20516739e+01 -7.11333008e+01 -6.92738419e+01 -7.95991592e+01 -9.20880661e+01 -9.03664246e+01 -4.78691673e+01 -1.27410107e+01 -7.21235752e+00 -3.92853966e+01 -6.71957397e+01 -6.64750900e+01 -6.23449631e+01 -6.12231293e+01 -6.77037430e+01 -4.77815170e+01 -6.76100874e+00 -5.78961313e-01 -2.79722691e+01 -7.46566849e+01 -7.16591339e+01 -7.19200516e+01 -6.86450653e+01 -7.47090378e+01 -6.97633133e+01 -6.09562798e+01 -4.71657028e+01 -4.36257324e+01 -5.49932747e+01 -6.79676819e+01 -6.32279205e+01 -3.05097160e+01 1.50640421e+01 1.70838108e+01 -1.92832222e+01 -6.11249619e+01 -6.88981323e+01 -7.62076187e+01 -7.64568405e+01 -7.11724625e+01 -3.09009476e+01 -7.21616220e+00 2.89942532e+01 3.20999641e+01 -1.76858580e+00 -3.72024117e+01 -7.81980438e+01 -5.10716705e+01 -2.61012936e+01 -5.67814598e+01 -1.19023170e+02 -1.55030609e+02 -1.26893448e+02 -8.61915665e+01 -9.01460800e+01 -9.02489853e+01 -9.76637726e+01 -9.88809814e+01 -1.10910103e+02 -1.19110703e+02 -1.23748299e+02 -1.25972923e+02 -1.23574699e+02 -1.19644600e+02 -1.17592628e+02 -1.20690247e+02 -1.18022820e+02 -1.02377785e+02 -7.10937195e+01 -7.91935501e+01 -1.00538383e+02 -1.33640793e+02 -1.04272453e+02 -7.25078735e+01 -1.01289383e+02 -1.59153076e+02 -1.57127838e+02 -8.84320831e+01 -4.70585785e+01 -7.40407715e+01 -1.05825417e+02 -8.91852493e+01 -5.46191254e+01 -4.98213959e+01 -6.34191170e+01 -9.30995941e+01 -9.04458847e+01 -8.87566986e+01 -9.39933243e+01 -9.55935745e+01 -1.18918892e+02 -1.37705399e+02 -1.10831329e+02 -6.38953514e+01 -3.76665993e+01 -6.19486542e+01 -8.09680786e+01 -6.05931015e+01 -4.17379341e+01 -3.71162796e+01 -6.01487961e+01 -8.73850327e+01 -8.47616119e+01 -8.18212967e+01 -7.66875076e+01 -8.95078506e+01 -7.72640991e+01 -5.57915802e+01 -4.98170242e+01 -5.66778297e+01 -8.63103790e+01 -1.05391502e+02 -1.13134293e+02 -1.13104080e+02 -1.00115089e+02 -1.37401611e+02 -1.75037811e+02 -1.71101044e+02 -1.24985245e+02 -8.73819962e+01 -9.71161423e+01 -1.15000160e+02 -9.99785767e+01 -7.33819809e+01 -7.32928391e+01 -9.19060745e+01 -1.15590347e+02 -1.21179260e+02 -1.21739822e+02 -1.22833199e+02 -1.21322632e+02 -1.20685905e+02 -1.13120438e+02 -9.66401215e+01 -9.06704788e+01 -9.79952164e+01 -1.14551140e+02 -1.22931564e+02 -1.28456345e+02 -1.26067825e+02 -1.48099396e+02 -1.69900421e+02 -1.51136047e+02 -1.04322968e+02 -7.86007462e+01 -1.02900276e+02 -1.31001190e+02 -1.44541000e+02 -1.49256302e+02 -1.50523544e+02 -1.46138779e+02 -1.41191284e+02 -1.44035843e+02 -1.40278442e+02 -1.41317734e+02 -1.38752136e+02 -1.46789230e+02 -1.48527954e+02 -1.50463959e+02 -1.38390884e+02 -1.36255569e+02 -1.43023270e+02 -1.53632156e+02 -1.57065979e+02 -1.45099152e+02 -1.34593338e+02 -1.27798027e+02 -1.11709869e+02 -9.73908997e+01 -9.31091156e+01 -1.08063553e+02 -1.08790382e+02 -7.93820953e+01 -6.02756500e+01 -7.41028061e+01 -9.77269363e+01 -9.49936523e+01 -7.50320206e+01 -7.47062302e+01 -9.35108337e+01 -1.08758965e+02 -1.10652977e+02 -1.08900902e+02 -1.08337128e+02 -1.06677185e+02 -1.08563103e+02 -1.16835197e+02 -1.10361160e+02 -9.70330124e+01 -8.75193634e+01 -9.97712784e+01 -1.16139183e+02 -1.16102379e+02 -1.05864151e+02 -1.18795090e+02 -1.39019424e+02 -1.50961456e+02 -1.42339920e+02 -1.31183105e+02 -1.36626495e+02 -1.35553711e+02 -1.35125549e+02 -1.32521255e+02 -1.35149734e+02 -1.35660645e+02 -1.33088654e+02 -1.35387619e+02 -1.38008560e+02 -1.44271118e+02 -1.41346405e+02 -1.36486832e+02 -1.34042435e+02 -1.25950562e+02 -1.17629189e+02 -1.19768196e+02 -1.32338623e+02 -1.46849899e+02 -1.50827896e+02 -1.49011368e+02 -1.56409668e+02 -1.65079483e+02 -1.65695358e+02 -1.58095795e+02 -1.48323090e+02 -1.48268967e+02 -1.47983856e+02 -1.33181793e+02 -1.19189659e+02 -1.16694260e+02 -1.27187752e+02 -1.34146118e+02 -1.33020813e+02 -1.35904037e+02 -1.41564560e+02 -1.41108231e+02 -1.47479492e+02 -1.55903976e+02 -1.52154953e+02 -1.38449615e+02 -1.29212891e+02 -1.33227844e+02 -1.32028580e+02 -1.18089432e+02 -1.10170006e+02 -1.15072144e+02 -1.30887375e+02 -1.35315643e+02 -1.30386536e+02 -1.29624817e+02 -1.35079147e+02 -1.44944778e+02 -1.43123322e+02 -1.38169907e+02 -1.37824890e+02 -1.40985229e+02 -1.46433060e+02 -1.48741516e+02 -1.49730988e+02 -1.50676270e+02 -1.47956116e+02 -1.48622116e+02 -1.48996994e+02 -1.44617767e+02 -1.40534485e+02 -1.38452072e+02 -1.42344498e+02 -1.45314346e+02 -1.42918579e+02 -1.39480164e+02 -1.41290878e+02 -1.61970245e+02 -1.77401123e+02 -1.81978622e+02 -4.63170135e+02 -7.16678467e+02 -6.52877625e+02 -6.86634949e+02 -6.92765869e+02 -3.61652679e+01 -7.75777435e+01 -4.32663544e+02 -5.55817566e+02 -5.25906128e+02 -4.88884216e+02 -3.74624634e+02 1.50361420e+02 28971730. 0. 0. 0. 0. 0. 0. -276646528. -276646528. -2.33673926e+03 -2.83143140e+03 -2.83143140e+03 -488244768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 569779712. 179301872. -134445168. 7.08827393e+02 2.88070038e+02 -1.90117096e+02 -8.32542953e+01 5.98496399e+01 -8.89950714e+01 -1.09370277e+02 -1.09225372e+02 -1.11162590e+02 -1.12360184e+02 -1.09140244e+02 -1.05258347e+02 -1.07678001e+02 -1.15859131e+02 -1.20075615e+02 -1.13602783e+02 -1.01641945e+02 -1.02097961e+02 -1.12522774e+02 -1.26010193e+02 -1.28325287e+02 -1.22205826e+02 -1.23517479e+02 -1.29267761e+02 -1.30488083e+02 -1.23989342e+02 -1.18167610e+02 -1.24431030e+02 -1.40475769e+02 -1.44041397e+02 -1.33762955e+02 -1.20218239e+02 -1.12182877e+02 -1.10085358e+02 -1.03694359e+02 -9.56815567e+01 -9.30124283e+01 -1.03691803e+02 -1.33442352e+02 -1.49643616e+02 -1.41873322e+02 -1.20585831e+02 -1.05588036e+02 -1.06677155e+02 -1.12604279e+02 -1.22676300e+02 -1.18927063e+02 -1.23371536e+02 -1.29694168e+02 -1.23989723e+02 -1.00937592e+02 -7.45784988e+01 -7.84224472e+01 -1.14277092e+02 -1.33059479e+02 -1.24032761e+02 -1.03019615e+02 -1.06468079e+02 -1.23307060e+02 -1.23257858e+02 -1.03341866e+02 -8.26831512e+01 -8.65065765e+01 -1.19461540e+02 -1.42730942e+02 -1.36130569e+02 -1.14639900e+02 -1.08343742e+02 -1.16986748e+02 -1.17224014e+02 -1.02860069e+02 -8.20947952e+01 -8.76727524e+01 -9.87775269e+01 -9.80406113e+01 -8.39496918e+01 -7.75404205e+01 -8.63938217e+01 -1.03418381e+02 -1.20517067e+02 -1.24505295e+02 -1.12843018e+02 -1.01649445e+02 -1.02647583e+02 -8.64958878e+01 -5.92127457e+01 -4.96552582e+01 -7.73593369e+01 -1.28850830e+02 -1.52135513e+02 -1.35239182e+02 -9.25156174e+01 -5.11699142e+01 -3.58684807e+01 -4.38669930e+01 -5.40713158e+01 -5.05777931e+01 -6.22396011e+01 -9.93122101e+01 -1.29521332e+02 -1.17551620e+02 -8.89931183e+01 -7.50164413e+01 -8.57349930e+01 -1.10796860e+02 -1.16773643e+02 -1.01614647e+02 -8.34869614e+01 -8.66087799e+01 -8.99419708e+01 -7.27753754e+01 -3.28538513e+01 -2.62468109e+01 -5.51886711e+01 -9.53988342e+01 -9.54916611e+01 -6.64961319e+01 -4.32998848e+01 -4.23953209e+01 -6.83887482e+01 -9.69407349e+01 -1.07422058e+02 -9.15930710e+01 -9.19815674e+01 -1.15519836e+02 -1.18529182e+02 -8.96610107e+01 -6.08995018e+01 -5.96669006e+01 -8.91127014e+01 -1.04069344e+02 -8.84517136e+01 -7.08148575e+01 -6.13113289e+01 -7.34107437e+01 -6.44170761e+01 -3.43930702e+01 -2.57714024e+01 -6.59691620e+01 -1.39448685e+02 -1.80094757e+02 -1.48764877e+02 -9.66501846e+01 -7.36303635e+01 -8.44070129e+01 -1.01923653e+02 -1.03675911e+02 -1.07528008e+02 -1.33958603e+02 -1.66596878e+02 -1.71751770e+02 -1.26362495e+02 -5.10372276e+01 -2.14247456e+01 -6.62179947e+01 -1.15801567e+02 -1.14453186e+02 -9.11571808e+01 -1.10810707e+02 -1.67273300e+02 -1.64453079e+02 -1.05320442e+02 -5.02622452e+01 -8.88195267e+01 -1.84393295e+02 -2.39266083e+02 -1.99307159e+02 -1.24490868e+02 -8.31896210e+01 -8.48712769e+01 -7.93638763e+01 -6.67345734e+01 -8.18217697e+01 -1.29812851e+02 -1.94656372e+02 -1.65808289e+02 -1.13354912e+02 -5.75473022e+01 -7.02737122e+01 -9.41266632e+01 -1.22397102e+02 -1.32434082e+02 -1.32368134e+02 -1.51243500e+02 -1.83325562e+02 -1.68018936e+02 -1.02767555e+02 -4.02182922e+01 -5.24057426e+01 -1.20600441e+02 -1.77369888e+02 -1.66268600e+02 -1.18221107e+02 -8.49826126e+01 -7.91002960e+01 -6.59190445e+01 -1.39471073e+01 1.11535702e+01 -4.20807686e+01 -1.14816689e+02 -1.45242859e+02 -1.03721725e+02 -5.20812569e+01 -2.70337181e+01 -3.96984978e+01 -5.96475716e+01 -8.13762131e+01 -7.39856262e+01 -9.41893082e+01 -1.23828400e+02 -9.51314545e+01 -4.89536972e+01 -2.28100948e+01 -3.54119720e+01 -7.65000153e+01 -8.38255386e+01 -6.68103790e+01 -5.91796570e+01 -6.61154556e+01 -1.05641212e+02 -7.67184525e+01 -3.35767593e+01 -1.11653216e-01 4.86127806e+00 -5.90104332e+01 -1.00370567e+02 -8.83647232e+01 -1.86540012e+01 -3.12155008e+00 -4.09236526e+01 -9.40857239e+01 -8.28750229e+01 -4.96144142e+01 -5.33207321e+01 -9.61966095e+01 -1.06867783e+02 -4.42005997e+01 -7.83249331e+00 -4.09108467e+01 -8.06595078e+01 -5.11201210e+01 -2.64286900e+01 -4.40781708e+01 -6.39478149e+01 -8.02301254e+01 -6.20948982e+01 -9.58219681e+01 -1.13504807e+02 -1.13442482e+02 -1.28121613e+02 -1.48621872e+02 -1.54785522e+02 -8.04088669e+01 -5.16878242e+01 -5.01591415e+01 -1.08945793e+02 -9.30447235e+01 -8.53321686e+01 -9.94989395e+01 -1.43382004e+02 -1.60714050e+02 -9.24550781e+01 -4.37750320e+01 -4.06308937e+01 -1.08824921e+02 -1.14128296e+02 -9.64310303e+01 -5.96804199e+01 -6.25241776e+01 -1.16578003e+02 -1.02001320e+02 -6.53959885e+01 6.51170349e+00 3.29918404e+01 1.43061390e+01 -3.55579758e+01 -7.79368668e+01 -4.66805420e+01 2.81510258e+00 2.41999989e+01 5.49533188e-01 2.65511894e+01 2.97221737e+01 -1.61509724e+01 -8.30966110e+01 -8.96952667e+01 5.66159534e+00 3.26592751e+01 -5.38164759e+00 -8.38538895e+01 -5.12080421e+01 -1.01174583e+01 1.47162807e+00 -2.67528992e+01 -6.32293320e+01 -5.58938065e+01 -6.98085251e+01 -2.24488754e+01 1.26578796e+00 6.78319836e+00 -3.90280037e+01 -6.44038696e+01 -2.12303905e+01 1.58065195e+01 2.86730099e+01 2.52099628e+01 9.73357468e+01 1.35904236e+02 1.30473404e+02 9.98574219e+01 9.99922867e+01 1.43309219e+02 1.60455139e+02 1.24808434e+02 4.19348488e+01 1.01321487e+01 5.07147837e+00 2.78889160e+01 9.75288677e+00 -4.16287766e+01 -8.21991882e+01 -9.94965134e+01 -3.87384453e+01 -9.52284813e+00 1.51345119e+01 -4.72877264e+00 7.75705814e+00 2.91492577e+01 6.01511536e+01 5.27541122e+01 5.47484360e+01 9.64352951e+01 1.34682037e+02 1.11600632e+02 5.84396057e+01 5.57544594e+01 4.45271873e+01 -1.54567804e+01 -7.24985733e+01 -9.37083664e+01 -2.95866261e+01 -1.73219700e+01 -6.85808086e+00 3.48638306e+01 3.55980682e+01 -2.78726673e+00 -9.53961334e+01 -1.16570961e+02 -3.80662766e+01 2.98107796e+01 2.75787678e+01 -2.93180561e+01 -7.42320557e+01 -4.26218452e+01 1.63687382e+01 6.41328583e+01 6.70801239e+01 1.10827465e+01 -2.19482594e+01 -7.44059906e+01 -6.79922333e+01 -6.70368347e+01 -9.79416428e+01 -1.14421791e+02 -1.24507172e+02 -3.10514450e+01 -1.65413589e+01 -9.40338612e+00 -1.57713537e+01 -3.13619137e+01 -8.94114609e+01 -2.09911530e+02 -2.27606995e+02 -1.28306168e+02 3.30496674e+01 1.03329018e+02 6.15991688e+00 -1.24773941e+02 -1.26792404e+02 8.51664162e+00 1.57775650e+02 1.19225319e+02 -8.82404518e+00 -8.38514709e+01 -7.61608887e+01 8.44676495e+00 -8.18435192e+00 -5.46654778e+01 -9.70963516e+01 -1.08578796e+02 -3.49414787e+01 -3.83699684e+01 -6.75296402e+01 -1.17314407e+02 -1.12360916e+02 -6.93811874e+01 -8.32301941e+01 -9.83106003e+01 -1.74602585e+01 8.41816177e+01 7.82166443e+01 -7.82202682e+01 -1.83486206e+02 -1.39543655e+02 -9.84454727e+00 6.23453255e+01 3.94376030e+01 -5.08901482e+01 -9.47081375e+01 -1.08398544e+02 -2.55949516e+01 -1.23932676e+01 -2.27503681e+01 -6.37651787e+01 -9.27254257e+01 -2.94872131e+01 1.39867477e+01 9.23444519e+01 8.84798813e+01 6.70854797e+01 -1.51852942e+00 -1.04173729e+02 -1.45485901e+02 -7.19331665e+01 8.07521667e+01 1.56220444e+02 8.93636322e+01 -7.07337723e+01 -1.18671730e+02 7.55057573e-01 1.66167984e+02 1.61224792e+02 1.79562550e+01 -5.41130333e+01 -4.44360542e+01 2.78170738e+01 2.91816044e+01 -2.07738972e+01 -8.34321442e+01 -1.33226379e+02 -1.23259468e+02 -1.53103546e+02 -1.53531494e+02 -8.71518707e+01 1.91188107e+01 6.62574997e+01 -7.04376602e+00 -7.80620346e+01 -5.69317513e+01 4.62071495e+01 1.34798050e+02 9.41381149e+01 -1.93432331e+01 -4.66836472e+01 -1.65060878e-01 9.50377808e+01 6.74659729e+01 -1.43854427e+01 -7.87603683e+01 -1.25466843e+02 -5.95491486e+01 -6.03113022e+01 -2.67169685e+01 -2.99712429e+01 -4.90793953e+01 -6.90708389e+01 -1.18840012e+02 -6.88875046e+01 6.95858300e-01 7.62943573e+01 4.40702133e+01 -4.94245148e+01 -1.25455818e+02 -7.17016830e+01 3.43411140e+01 1.10505188e+02 8.84114456e+01 2.17593803e+01 -1.22028713e+01 -2.15234852e+01 3.95094013e+00 -8.67634773e+00 -3.58005867e+01 -8.35066299e+01 -1.40971863e+02 -1.20649719e+02 -2.44851036e+01 4.77836189e+01 5.55391273e+01 6.90651703e+00 -2.94450970e+01 -8.68873138e+01 -1.17518044e+02 -2.43094234e+01 1.04483635e+02 1.62662216e+02 6.69293289e+01 -4.95300255e+01 -5.70680923e+01 4.96858940e+01 1.83401855e+02 1.66652817e+02 3.68398857e+01 -1.05909760e+02 -1.53740448e+02 -7.48720322e+01 -2.98096871e+00 2.65742993e+00 -3.32667542e+01 -5.99235840e+01 -1.44703436e+01 -1.57600317e+01 -2.08019829e+00 3.82364311e+01 5.14370461e+01 5.33340950e+01 -1.18089123e+01 8.18766499e+00 8.72387924e+01 1.81726761e+02 1.63314972e+02 1.58638363e+01 -9.19160767e+01 -6.67516327e+01 6.24534302e+01 1.48328705e+02 1.55087982e+02 5.29282341e+01 -4.14287300e+01 -8.22567749e+01 -7.58996773e+00 3.99935722e+01 8.16052704e+01 7.80257339e+01 6.32112999e+01 7.28618927e+01 7.67844696e+01 1.41780045e+02 1.76289932e+02 1.73232864e+02 1.22538620e+02 2.51016541e+01 -7.30983591e+00 4.77177086e+01 1.43305420e+02 1.70500366e+02 1.13920128e+02 2.39239254e+01 2.93180866e+01 8.85984650e+01 1.82772522e+02 1.93141113e+02 1.10613342e+02 1.85362968e+01 -2.38728943e+01 4.75628090e+01 1.18954796e+02 1.24088890e+02 6.65001678e+01 6.07881594e+00 1.02475595e+00 5.62741661e+00 3.25805283e+01 9.96949463e+01 1.16709854e+02 6.65744781e+01 -4.98300629e+01 -9.25986862e+01 -2.69081573e+01 6.50871964e+01 1.30441040e+02 8.59017029e+01 1.25618515e+01 -2.95660305e+01 -2.69745851e+00 6.04623070e+01 5.52606544e+01 5.94650364e+00 -4.88711624e+01 -4.91057205e+01 2.39631767e+01 7.55904999e+01 6.19463348e+01 6.25325871e+00 -5.81071205e+01 -4.75701714e+01 -3.67503471e+01 -9.78071117e+00 2.79760475e+01 5.38469048e+01 7.13440399e+01 1.25235882e+01 -2.56998558e+01 -9.10822105e+00 5.08023529e+01 1.05609962e+02 6.55953064e+01 6.54613590e+00 -3.01452847e+01 3.03763561e+01 1.50976685e+02 2.12998260e+02 1.52625763e+02 1.33096685e+01 -6.77338638e+01 -2.75898933e+01 5.49848328e+01 9.17775269e+01 9.44562607e+01 1.08021210e+02 1.56337799e+02 8.52729111e+01 2.27505295e+02 3.36633392e+02 2.56777539e+03 3.46949756e+03 6.51618750e+03 1.62634033e+04 -113888552. 2.29388518e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.00599859e+10 -368908384. 7.37914697e+03 1.88488135e+03 -4.15241974e+02 1.50659839e+03 5.43239453e+03 2.94695703e+03 6.85092896e+02 3.07070435e+02 2.32652267e+02 1.96523941e+02 1.39274811e+02 5.41960297e+01 2.55599041e+01 4.36793022e+01 1.04605537e+02 1.42627502e+02 1.35479584e+02 8.50916672e+01 1.44040785e+01 1.50805168e+01 3.60067825e+01 5.95316582e+01 6.11659203e+01 6.18145866e+01 8.80240402e+01 6.24252281e+01 6.21691933e+01 1.09338997e+02 1.44686493e+02 1.12133385e+02 2.02620735e+01 -2.94235249e+01 2.94924507e+01 1.04357811e+02 1.52765549e+02 1.28525970e+02 4.70901756e+01 -1.89698105e+01 -4.69188728e+01 1.65312233e+01 6.18464127e+01 6.68798752e+01 2.20981770e+01 -7.95912266e+00 1.88666115e+01 2.31324539e+01 5.30462074e+01 8.33203964e+01 1.00529884e+02 7.80348816e+01 -1.26324677e+00 -7.56550074e+00 5.74107475e+01 1.38293839e+02 1.56242538e+02 8.82533417e+01 2.61890488e+01 3.12362251e+01 8.14049988e+01 1.04160263e+02 6.01027031e+01 -1.06940374e+01 -3.07227879e+01 -3.25097585e+00 7.43349686e+01 1.27213066e+02 1.29105286e+02 8.43861465e+01 2.09892960e+01 -1.94079857e+01 -3.93039856e+01 -1.69815178e+01 2.00641060e+01 5.59723892e+01 7.33922653e+01 6.09906540e+01 7.01871185e+01 1.12581070e+02 1.52846329e+02 1.47233688e+02 9.27647400e+01 5.41188545e+01 6.54887543e+01 8.96794434e+01 1.25542931e+02 1.44746902e+02 1.25455948e+02 7.39135284e+01 4.60343819e+01 7.70689392e+01 1.16110039e+02 1.11321548e+02 8.61590805e+01 7.89724426e+01 9.33167267e+01 8.46058960e+01 8.59865799e+01 1.05654678e+02 1.17731354e+02 1.03713890e+02 5.17838020e+01 4.81798172e+01 9.55692978e+01 1.58247253e+02 1.80630737e+02 1.38249893e+02 9.47900162e+01 7.74727707e+01 8.81891556e+01 1.04922005e+02 1.08136772e+02 9.87770920e+01 7.49907227e+01 6.16845970e+01 8.51343384e+01 1.27269760e+02 1.40934631e+02 1.25830093e+02 1.10608994e+02 1.06410561e+02 9.00184250e+01 8.96811295e+01 1.23698227e+02 1.62632294e+02 1.60632492e+02 1.10427834e+02 8.89519424e+01 1.16992615e+02 1.56646927e+02 1.62497177e+02 1.26704834e+02 9.27374496e+01 8.57715683e+01 9.88561096e+01 1.27322510e+02 1.47379425e+02 1.39002106e+02 1.07003853e+02 8.46450424e+01 1.02055038e+02 1.31901367e+02 1.41177902e+02 1.31110260e+02 1.19045967e+02 1.10404129e+02 9.21045303e+01 8.30797348e+01 9.16367493e+01 1.07179893e+02 1.08697403e+02 9.11021576e+01 8.33950577e+01 1.02477196e+02 1.35890045e+02 1.57849304e+02 1.44952148e+02 1.12323616e+02 9.06372452e+01 9.64029083e+01 1.13434021e+02 1.20147202e+02 1.11014816e+02 1.09560349e+02 9.86274796e+01 1.05026924e+02 1.07289101e+02 1.17071739e+02 1.29602600e+02 1.34841553e+02 1.37210403e+02 1.20212067e+02 1.11968933e+02 1.21349335e+02 1.31879684e+02 1.26739128e+02 1.05794365e+02 9.62242203e+01 1.03875084e+02 1.13176552e+02 1.20095543e+02 1.19925026e+02 1.14534279e+02 1.11627167e+02 1.10169273e+02 1.20187912e+02 1.18688408e+02 1.13447266e+02 1.04791229e+02 9.59093246e+01 9.10571976e+01 8.67653656e+01 9.58265152e+01 1.09252518e+02 1.16580009e+02 1.16699188e+02 1.09624908e+02 1.09525101e+02 1.16529350e+02 1.24828842e+02 1.28037674e+02 1.17695465e+02 1.05715805e+02 1.00306137e+02 1.03911400e+02 1.09215981e+02 1.11584579e+02 1.11147293e+02 1.09485085e+02 1.07578186e+02 1.09534172e+02 1.13319313e+02 1.15059807e+02 1.13214874e+02 1.12575195e+02 1.12140549e+02 1.11474312e+02 1.11546700e+02 1.12810074e+02 1.13850784e+02 1.13922554e+02 1.13851250e+02 1.14377983e+02 1.14771248e+02 1.14757088e+02 1.14426979e+02 1.14191162e+02 1.14238174e+02 1.15108582e+02 1.15817955e+02 1.15266472e+02 1.13661186e+02 1.12737282e+02 1.14180145e+02 1.15682983e+02 1.15467667e+02 1.14895050e+02 1.14682922e+02 1.14462654e+02 1.14165779e+02 1.14054161e+02 1.14057381e+02 1.14312073e+02 1.13389137e+02 1.12553177e+02 1.10039871e+02 1.10117027e+02 1.10928429e+02 1.13681816e+02 1.13371101e+02 1.12032944e+02 1.11793518e+02 1.12373291e+02 1.16415642e+02 1.19410469e+02 1.20247795e+02 1.18500549e+02 1.14341621e+02 1.14388100e+02 1.14282127e+02 1.14684708e+02 1.12576996e+02 1.12743942e+02 1.12948357e+02 1.13123482e+02 1.10174644e+02 1.10644165e+02 1.10402702e+02 1.09941490e+02 1.07275833e+02 1.07279716e+02 1.06639656e+02 1.06110306e+02 1.08004601e+02 1.09563560e+02 1.12019203e+02 1.10045891e+02 1.09870911e+02 1.06888855e+02 1.06570618e+02 1.07332024e+02 1.12765244e+02 1.11899445e+02 1.12609032e+02 1.09033928e+02 1.11943047e+02 1.07329948e+02 1.07974007e+02 1.08258560e+02 1.13263687e+02 1.11525764e+02 1.09792648e+02 1.08859245e+02 1.11224480e+02 1.11296280e+02 1.06467133e+02 1.07746117e+02 1.12308998e+02 1.18132927e+02 1.17878075e+02 1.18962784e+02 1.17659096e+02 1.15707184e+02 1.13586426e+02 1.15826019e+02 1.14351967e+02 1.12831375e+02 1.12420189e+02 1.18321404e+02 1.14480476e+02 1.11215553e+02 1.06336403e+02 1.10321297e+02 1.01724709e+02 9.27958832e+01 9.14527206e+01 9.86806946e+01 1.09215454e+02 1.09884621e+02 1.07715195e+02 1.05451431e+02 1.00157875e+02 1.07576683e+02 1.09128258e+02 1.10960434e+02 1.10471176e+02 1.18089729e+02 1.19821060e+02 1.10684547e+02 1.07327606e+02 1.09610809e+02 1.10739189e+02 1.06827271e+02 1.09363922e+02 1.13586456e+02 1.15810638e+02 1.16390068e+02 1.20319748e+02 1.16665466e+02 1.13032600e+02 1.08356979e+02 1.09231400e+02 1.10486328e+02 1.15554047e+02 1.12263611e+02 1.03365585e+02 8.70861435e+01 9.36097107e+01 1.02963997e+02 1.15923904e+02 1.15457359e+02 1.07986191e+02 1.03335930e+02 9.86662064e+01 9.45041199e+01 8.87600327e+01 8.31021729e+01 9.26480103e+01 9.33197174e+01 9.97444229e+01 9.46285858e+01 9.85146103e+01 1.01356163e+02 1.05570557e+02 9.86482162e+01 9.43682327e+01 9.25915222e+01 9.66777496e+01 1.00220741e+02 9.45727386e+01 8.29474716e+01 6.14255104e+01 6.71693954e+01 8.56426468e+01 1.12614304e+02 1.00674713e+02 8.34417648e+01 7.02495270e+01 8.16043091e+01 9.65157318e+01 9.49567413e+01 8.10652161e+01 6.86609039e+01 6.75124207e+01 7.52319717e+01 7.08886719e+01 5.66913490e+01 4.74332848e+01 6.31173744e+01 8.84019165e+01 9.56665039e+01 8.39952850e+01 7.80924072e+01 7.84378815e+01 9.05704575e+01 9.49267960e+01 8.49352875e+01 6.65037537e+01 6.99245682e+01 8.29218979e+01 1.06379631e+02 1.02544441e+02 1.00395905e+02 9.27803268e+01 1.07805931e+02 1.33888794e+02 1.46066559e+02 1.21202278e+02 9.30449753e+01 8.15440445e+01 8.20092926e+01 6.66444702e+01 5.98572578e+01 9.72271423e+01 1.44777496e+02 1.50605728e+02 1.15224648e+02 8.11582870e+01 7.82478790e+01 8.50818710e+01 1.05355110e+02 1.19054436e+02 1.09584511e+02 8.44419785e+01 6.67057190e+01 6.60996323e+01 6.08274612e+01 8.62270584e+01 1.25745979e+02 1.33612976e+02 1.08045113e+02 7.74297638e+01 6.28477516e+01 5.39303780e+01 5.22210960e+01 7.51371689e+01 8.41750031e+01 8.95995026e+01 8.98168640e+01 9.58631821e+01 1.02539635e+02 1.06172516e+02 1.03589081e+02 1.01628860e+02 1.00977119e+02 1.09885872e+02 1.13701607e+02 9.81230774e+01 7.96773071e+01 -1.71139374e+01 -7.95595322e+01 -9.00100327e+00 5.04742012e+01 2.95631714e+02 -2.91444580e+03 -7.90668164e+03 -265973216. -129420576. -128813800. 261197248. -433912480. 679879680. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.46511590e+09 -162604928. -3.49388828e+04 -1.36611895e+04 -2.30558057e+03 -5.20950537e+03 -3.15437378e+03 -6.26938110e+02 -1.73125931e+02 -5.38984299e+00 1.20615091e+01 1.63697453e+01 1.75444126e+01 6.43736219e+00 -1.39654338e+00 -1.13353682e+01 -1.02859545e+01 -5.92596054e+00 2.12053604e+01 2.81997318e+01 2.06383705e+01 -9.26960850e+00 -4.26288986e+00 1.91957798e+01 5.41336594e+01 5.82560501e+01 6.25187340e+01 6.84906464e+01 8.40903397e+01 9.24708557e+01 9.74761429e+01 1.06002022e+02 1.02730247e+02 1.05696732e+02 9.44538727e+01 9.27804184e+01 1.05385254e+02 1.14537560e+02 1.18799004e+02 9.39859619e+01 8.16932831e+01 8.19258347e+01 9.55080948e+01 1.01782471e+02 1.13797752e+02 1.16918961e+02 1.09791344e+02 6.72159042e+01 3.36213226e+01 1.58518524e+01 3.14914856e+01 4.50496788e+01 5.74714317e+01 7.16081924e+01 7.07262650e+01 5.98057709e+01 5.10258789e+01 5.40360680e+01 6.86361389e+01 7.43281784e+01 9.29189911e+01 7.45197449e+01 5.74197998e+01 4.07240715e+01 2.39415588e+01 1.42768126e+01 4.19924545e+00 2.06566753e+01 3.27778969e+01 2.98109970e+01 3.92115440e+01 6.51074371e+01 8.12757263e+01 6.93323593e+01 5.07504158e+01 4.70645370e+01 5.43944588e+01 3.03284950e+01 -1.08842258e+01 -6.69542408e+00 7.71994925e+00 2.70420227e+01 -2.47178860e+01 -7.05700760e+01 -6.86297760e+01 -4.22997017e+01 -2.08333988e+01 -2.70701466e+01 -3.04886398e+01 -1.14710608e+01 -2.08761158e+01 -4.25324173e+01 -8.32086792e+01 -7.23393555e+01 -3.16933041e+01 1.38401642e+01 3.58873596e+01 3.46762962e+01 3.03774776e+01 1.81653576e+01 3.75261230e+01 5.88723717e+01 3.64829483e+01 -1.26647961e+00 -1.19473124e+01 2.61214523e+01 5.09307098e+01 3.97283912e+00 -3.00261822e+01 -1.99320736e+01 3.04793339e+01 6.12691307e+01 6.39133072e+01 6.40034561e+01 6.17252083e+01 5.37182655e+01 3.63165092e+01 3.66991997e+01 4.40238380e+01 4.58547554e+01 3.23546562e+01 2.26625118e+01 2.13406620e+01 2.52150612e+01 2.04260712e+01 1.79825706e+01 1.56309662e+01 -2.26927299e+01 -6.09572601e+01 -5.69647675e+01 -1.83591442e+01 1.78471699e+01 -2.24983177e+01 -6.40154114e+01 -6.91848602e+01 -3.67319717e+01 -4.00570107e+00 8.98703218e-01 7.82849836e+00 2.66675873e+01 1.69155178e+01 9.58214760e+00 3.21676284e-02 1.65736961e+01 3.30888519e+01 3.23804626e+01 1.69450035e+01 -9.86126587e-02 7.85206020e-01 2.28872800e+00 4.20341873e+00 -1.02031984e+01 -5.52471085e+01 -1.02805672e+02 -1.04143242e+02 -6.90606918e+01 -3.29935112e+01 -6.47141571e+01 -1.02024223e+02 -9.37478180e+01 -4.28909836e+01 5.66781235e+00 5.50992441e+00 -6.33201122e+00 -1.42488937e+01 -1.84607925e+01 -1.69115772e+01 -2.01174850e+01 -1.45240870e+01 -1.51618938e+01 -3.60299683e+01 -6.63531036e+01 -5.80270996e+01 -3.20301208e+01 4.78846550e+00 7.85110092e+00 8.66696930e+00 -2.81302547e+01 -6.93686752e+01 -6.66854401e+01 -4.27896957e+01 -2.03778725e+01 -2.14270039e+01 -2.84951901e+00 -2.87508507e+01 -7.63655472e+01 -8.90414963e+01 -5.67373047e+01 -2.16274166e+01 -2.92522259e+01 -3.44164009e+01 -2.55484600e+01 -1.82464314e+01 -3.01311893e+01 -3.48182144e+01 -7.25260162e+01 -1.05024651e+02 -1.06543808e+02 -6.95913849e+01 -3.44158516e+01 -4.48912964e+01 -4.92862663e+01 -8.24459000e+01 -1.07789551e+02 -1.02389244e+02 -5.21409111e+01 -9.64980030e+00 -1.65947533e+01 -2.30021057e+01 -3.18741550e+01 -1.98802872e+01 -1.13822470e+01 -2.88456893e+00 -5.82990170e+00 -9.21352386e+00 -9.95144272e+00 -3.57421637e+00 -5.61370182e+00 1.16903076e+01 2.69560738e+01 3.46719475e+01 3.49625664e+01 1.81891460e+01 1.97468014e+01 1.91846790e+01 1.68353500e+01 1.35764675e+01 7.56111097e+00 1.74892998e+01 2.32528877e+00 -7.14792967e+00 -8.05160141e+00 1.42448969e+01 1.54876595e+01 8.33348179e+00 -2.87756395e+00 -1.81770396e+00 3.75519824e+00 -9.13235569e+00 -4.56748581e+00 -2.89845505e+01 -3.52232857e+01 -4.46609802e+01 -1.05113316e+01 2.86750584e+01 6.43492413e+00 -5.73352470e+01 -1.04531487e+02 -8.91149521e+01 -5.87245674e+01 -4.99594536e+01 -5.16901131e+01 -4.86709633e+01 -5.10071182e+01 -5.29865189e+01 -5.61541672e+01 -5.02399025e+01 -3.44715614e+01 -1.91635895e+01 -1.26472597e+01 -2.49469814e+01 -3.90065956e+01 -5.38135643e+01 -5.66477013e+01 -4.94776421e+01 -4.41176567e+01 -3.27294197e+01 -3.00856400e+01 -1.81745872e+01 -3.40680656e+01 -7.20000458e+01 -1.11119202e+02 -1.03015381e+02 -7.60531769e+01 -4.29546623e+01 -3.83441544e+01 -3.74655571e+01 -5.58312263e+01 -7.99721756e+01 -9.44209518e+01 -1.04466187e+02 -7.92569809e+01 -5.45188560e+01 -2.41839027e+01 -3.94484062e+01 -5.33695717e+01 -6.36013374e+01 -4.90237427e+01 -4.34954185e+01 -3.22591553e+01 -4.70073357e+01 -6.28401375e+01 -7.27716293e+01 -7.78713074e+01 -7.43340607e+01 -1.10604813e+02 -1.36195160e+02 -1.28612869e+02 -8.43499603e+01 -5.12916565e+01 -5.94397469e+01 -7.75021896e+01 -7.20528259e+01 -7.29897919e+01 -9.37153244e+01 -1.27383873e+02 -1.23483925e+02 -8.35084991e+01 -4.53130035e+01 -6.46510544e+01 -8.76246185e+01 -8.13136673e+01 -5.85143623e+01 -4.84499779e+01 -6.02603531e+01 -7.40092392e+01 -6.04889755e+01 -3.35734634e+01 -2.81355400e+01 -3.37123871e+01 -5.01337471e+01 -3.86257782e+01 -6.43263550e+01 -9.68031845e+01 -1.04897743e+02 -1.15785820e+02 -1.32492264e+02 -1.62843262e+02 -1.62000198e+02 -1.49580505e+02 -1.52234879e+02 -1.34530624e+02 -1.28847183e+02 -9.75407944e+01 -6.49158249e+01 -2.13279686e+01 -1.19986010e+01 -2.17105217e+01 -3.27411919e+01 -4.00548439e+01 -4.55882225e+01 -4.84980125e+01 -4.05040817e+01 -3.32727547e+01 -6.05261497e+01 -1.03770172e+02 -1.18084084e+02 -1.13639046e+02 -9.24013748e+01 -8.40991745e+01 -7.85914383e+01 -5.65134811e+01 -6.89311981e+01 -7.01994247e+01 -8.72460022e+01 -1.03300385e+02 -1.20628487e+02 -1.48893463e+02 -1.20671921e+02 -8.87711945e+01 -7.53261108e+01 -1.10441963e+02 -1.17172356e+02 -1.03580963e+02 -7.05653381e+01 -9.77438812e+01 -1.26172905e+02 -1.36989151e+02 -1.13166458e+02 -8.68295135e+01 -1.16027420e+02 -1.46985977e+02 -1.39913071e+02 -9.67400589e+01 -6.41877670e+01 -8.78328018e+01 -1.08884361e+02 -8.33692474e+01 -4.74016304e+01 -6.61892700e+01 -1.15371002e+02 -1.36612381e+02 -1.24608253e+02 -1.09564613e+02 -1.21206451e+02 -1.42113968e+02 -1.61605286e+02 -1.47223862e+02 -1.06830688e+02 -7.37720032e+01 -7.42911758e+01 -8.41442947e+01 -9.05992889e+01 -8.69541931e+01 -8.36032715e+01 -8.97127380e+01 -1.07545380e+02 -1.07280754e+02 -8.85111465e+01 -8.25729904e+01 -9.07088318e+01 -1.19659904e+02 -1.33193573e+02 -1.23434029e+02 -1.11988571e+02 -9.04564972e+01 -9.69806137e+01 -9.31736755e+01 -8.60671082e+01 -7.02008743e+01 -7.04669952e+01 -1.13966270e+02 -1.44696228e+02 -1.12124481e+02 -5.22066956e+01 -5.13895226e+01 -1.01486221e+02 -1.21137611e+02 -9.46950607e+01 -8.13287506e+01 -1.00578728e+02 -1.10957748e+02 -1.07010910e+02 -8.38405151e+01 -9.60578156e+01 -1.01429054e+02 -1.11329025e+02 -9.98420792e+01 -7.64921494e+01 -7.78877335e+01 -7.73343735e+01 -1.05379166e+02 -1.24437195e+02 -1.26415619e+02 -1.02701653e+02 -1.00723686e+02 -1.45574158e+02 -1.75396118e+02 -1.60142563e+02 -1.17513931e+02 -1.14186745e+02 -1.31536636e+02 -1.14884682e+02 -7.95773392e+01 -6.63020172e+01 -9.76571808e+01 -1.15731491e+02 -1.11272972e+02 -9.84264450e+01 -1.13141060e+02 -1.21458435e+02 -1.24005051e+02 -1.14876617e+02 -1.03537743e+02 -9.23189087e+01 -8.53547287e+01 -9.21747131e+01 -1.01107765e+02 -1.13653610e+02 -1.17437744e+02 -1.20308212e+02 -1.34090561e+02 -1.38125229e+02 -1.26867119e+02 -1.13243172e+02 -1.13366982e+02 -1.30174103e+02 -1.31371262e+02 -1.28672409e+02 -1.38595108e+02 -1.71948288e+02 -1.93563217e+02 -1.77670792e+02 -1.37762817e+02 -1.25056000e+02 -1.35335068e+02 -1.39784286e+02 -1.23696945e+02 -1.11085732e+02 -1.03481033e+02 -9.80224915e+01 -1.00166618e+02 -1.11680420e+02 -1.11381592e+02 -1.00661575e+02 -9.88662033e+01 -1.27817360e+02 -1.42391342e+02 -1.29365295e+02 -1.10085197e+02 -1.24244705e+02 -1.33995300e+02 -1.18135757e+02 -8.56176300e+01 -6.33839188e+01 -6.81560974e+01 -7.03143387e+01 -7.95490417e+01 -8.61588058e+01 -9.10261536e+01 -9.24445496e+01 -9.65874557e+01 -1.01854988e+02 -9.99483871e+01 -8.78279419e+01 -9.81736145e+01 -1.27445831e+02 -1.46738281e+02 -1.49011322e+02 -1.44809235e+02 -1.32116440e+02 -1.22004974e+02 -1.09574234e+02 -1.13899567e+02 -1.09965851e+02 -1.04290154e+02 -1.02094742e+02 -1.07601799e+02 -1.11373985e+02 -1.14822273e+02 -1.13980515e+02 -1.10571365e+02 -1.08387199e+02 -1.06909363e+02 -1.22473297e+02 -1.39199921e+02 -1.41990738e+02 -1.30524811e+02 -1.17676201e+02 -1.18557816e+02 -1.17388634e+02 -1.18354866e+02 -1.14329453e+02 -1.13776108e+02 -1.15330635e+02 -1.27108406e+02 -1.38758652e+02 -1.31874054e+02 -1.18854813e+02 -1.15999680e+02 -1.37545609e+02 -1.50194855e+02 -1.41657364e+02 -1.20989922e+02 -1.22362724e+02 -1.30401260e+02 -1.30263870e+02 -1.20714249e+02 -1.12960083e+02 -1.23888725e+02 -1.31472610e+02 -1.38915726e+02 -1.42553818e+02 -1.30892014e+02 -1.21298737e+02 -1.20184494e+02 -1.40719788e+02 -1.49094543e+02 -1.35964569e+02 -1.19041176e+02 -1.21412888e+02 -1.34516724e+02 -1.35165039e+02 -1.27959557e+02 -1.20355453e+02 -1.25716354e+02 -1.32590103e+02 -1.33642868e+02 -1.29538940e+02 -1.23161942e+02 -1.21619423e+02 -1.27752281e+02 -1.34378220e+02 -1.34467880e+02 -1.28336304e+02 -1.18093140e+02 -1.22209816e+02 -1.26883415e+02 -1.27081352e+02 -1.21456566e+02 -1.21105057e+02 -1.28436234e+02 -1.27542336e+02 -1.20871002e+02 -1.13494850e+02 -1.12846680e+02 -1.12502327e+02 -1.16538391e+02 -1.21843697e+02 -1.24358269e+02 -1.21880592e+02 -1.16710922e+02 -1.14127419e+02 -1.13721031e+02 -1.16919540e+02 -1.19776527e+02 -1.19507294e+02 -1.39010773e+02 -1.63798752e+02 -1.59743698e+02 -1.32730255e+02 -1.02949760e+02 -1.28922928e+02 -1.30202499e+02 -1.45208313e+02 -5.15707397e+02 -1.14250586e+03 346091712. 152486128. 121745680. -315469920. 4.43371233e+10 0. 0. 0. 0. 0. 0. -276646528. -276646528. 575466752. -272882528. -272882528. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 569779712. 179301872. -134445168. 8.47798157e+02 3.48325073e+02 -2.67269684e+02 -5.28902039e+02 -3.94354218e+02 -1.75049026e+02 -1.38158096e+02 -1.05542038e+02 -8.08455582e+01 -7.91304092e+01 -8.45802307e+01 -8.66191101e+01 -8.25237732e+01 -8.53274994e+01 -9.26142044e+01 -9.91554184e+01 -9.20375900e+01 -7.60909424e+01 -6.88835602e+01 -7.44532547e+01 -8.64619598e+01 -9.21431808e+01 -8.99176865e+01 -8.69255219e+01 -9.07564163e+01 -9.57101135e+01 -9.03731918e+01 -7.84315796e+01 -7.23110580e+01 -7.73086243e+01 -8.88708725e+01 -9.30420227e+01 -8.47826385e+01 -7.22868423e+01 -6.59591751e+01 -7.26517105e+01 -7.08814850e+01 -6.27062302e+01 -6.95008240e+01 -8.79055786e+01 -1.00551682e+02 -8.19661102e+01 -5.04012451e+01 -4.22586975e+01 -5.88728294e+01 -7.49730072e+01 -8.55925980e+01 -8.67312164e+01 -8.56556091e+01 -8.35059204e+01 -8.42578278e+01 -7.94739151e+01 -5.31241112e+01 -3.51899948e+01 -4.24413490e+01 -6.85849533e+01 -8.73088837e+01 -7.81077271e+01 -6.08298645e+01 -4.83250389e+01 -6.33381615e+01 -6.84375687e+01 -6.31517906e+01 -7.02151871e+01 -8.87353058e+01 -1.12187859e+02 -1.06529869e+02 -7.26529770e+01 -6.07572098e+01 -7.16512909e+01 -9.90962601e+01 -9.05788879e+01 -6.94285583e+01 -7.24839401e+01 -9.16886215e+01 -1.00712257e+02 -8.60192642e+01 -5.33336868e+01 -3.85499077e+01 -4.81415825e+01 -7.93279343e+01 -1.00319519e+02 -9.39855423e+01 -7.97908936e+01 -8.39676666e+01 -1.01026115e+02 -9.77943039e+01 -7.41165466e+01 -6.16827621e+01 -8.57175217e+01 -1.19850807e+02 -1.25648895e+02 -8.90534897e+01 -5.79278870e+01 -5.62633934e+01 -8.32572937e+01 -9.01932678e+01 -8.27204742e+01 -9.74676132e+01 -1.32015869e+02 -1.50973969e+02 -1.23174721e+02 -6.92285843e+01 -4.03241272e+01 -5.08058929e+01 -8.20213242e+01 -1.16473297e+02 -1.40429688e+02 -1.33709976e+02 -1.26200607e+02 -1.26459114e+02 -1.19677147e+02 -8.41315689e+01 -5.26975403e+01 -7.35799866e+01 -1.32053131e+02 -1.56612930e+02 -1.33753494e+02 -7.57171249e+01 -4.67480927e+01 -6.27500343e+01 -8.55925446e+01 -9.16151123e+01 -9.22007904e+01 -1.15111427e+02 -1.63085129e+02 -1.61459335e+02 -1.14870087e+02 -6.25488052e+01 -6.25772629e+01 -9.71291046e+01 -1.25345039e+02 -1.25518814e+02 -1.11178947e+02 -8.85323486e+01 -7.75315094e+01 -1.07359367e+02 -1.22791397e+02 -1.02545998e+02 -7.51845016e+01 -7.09095917e+01 -8.75552292e+01 -8.88209991e+01 -6.65252914e+01 -6.62644577e+01 -8.57236557e+01 -1.10510277e+02 -1.19659584e+02 -9.18628159e+01 -8.07031708e+01 -8.94542923e+01 -1.16743385e+02 -9.61615829e+01 -2.39679985e+01 1.41985798e+01 -3.41331444e+01 -1.02562607e+02 -1.15012657e+02 -7.61309814e+01 -4.98484192e+01 -5.29452095e+01 -5.35045280e+01 -2.45547028e+01 1.41947794e+01 2.48238354e+01 6.86336756e+00 -4.87933655e+01 -8.53721390e+01 -6.36970177e+01 -4.82593689e+01 -5.67614899e+01 -8.99353790e+01 -6.31706734e+01 4.84258747e+00 -1.91824877e+00 -2.98289585e+01 -6.18349152e+01 -2.06961040e+01 5.90163765e+01 9.48894501e+01 5.76083870e+01 -2.57606640e+01 -7.13814545e+01 -5.66570892e+01 -6.69738617e+01 -8.28289108e+01 -7.51634369e+01 -1.49862022e+01 5.40253448e+01 4.94604034e+01 -7.06400681e+00 -1.05407394e+02 -1.38422882e+02 -1.02730888e+02 -3.93952408e+01 -3.99072558e-01 -9.39106274e+00 8.01609707e+00 2.84870586e+01 2.18989029e+01 -4.59681282e+01 -1.09759270e+02 -8.16883011e+01 1.30567331e+01 6.31805458e+01 7.84705114e+00 -8.81738892e+01 -1.19879814e+02 -7.50650177e+01 -2.19899998e+01 -4.52318115e+01 -9.07048187e+01 -7.65129318e+01 -2.37296715e+01 -3.50107288e+00 -4.87221107e+01 -1.23781700e+02 -1.36512650e+02 -1.05132149e+02 -5.75361862e+01 -5.73195686e+01 -7.78262100e+01 -8.62301254e+01 -6.87257690e+01 -9.08341064e+01 -1.27215385e+02 -1.29538773e+02 -1.16098083e+02 -7.37209854e+01 -5.44342041e+01 -7.42993469e+01 -6.97334137e+01 -7.05468903e+01 -3.47964935e+01 -6.63082733e+01 -1.10355331e+02 -1.28778305e+02 -1.06391212e+02 -9.82635593e+00 4.56996078e+01 4.25068893e+01 -7.17989883e+01 -1.25779846e+02 -1.40652832e+02 -9.27550354e+01 -7.29247284e+01 -9.72584152e+01 -8.85323410e+01 -5.65098572e+01 -3.42233124e+01 -7.23481445e+01 -1.01692879e+02 -3.85435104e+01 3.93443680e+01 2.97750587e+01 -1.60954514e+01 -4.53649330e+01 -1.68857059e+01 3.17982578e+01 -1.83828678e+01 -5.74197769e+01 -1.04429420e+02 -7.85423813e+01 -2.30760975e+01 1.12094069e+01 2.64053135e+01 -3.28768463e+01 -6.21297455e+01 -6.47900391e+01 -6.47197008e+00 9.87500095e+00 9.99962711e+00 2.15529728e+01 5.06951637e+01 6.90205841e+01 -8.03227806e+00 -5.49447250e+01 -5.54627075e+01 2.00927067e+01 2.38913631e+01 -9.41238022e+00 -5.56835403e+01 -9.14921646e+01 -7.40491333e+01 -7.00416260e+01 -1.18767099e+01 1.75930767e+01 4.36199608e+01 3.91740837e+01 2.23402100e+01 -1.08274622e+01 -6.79795456e+01 -1.00531563e+02 -8.35748749e+01 3.13390207e+00 1.90191135e+01 1.66289687e+00 -2.04945087e+01 -7.68341589e+00 -2.89724445e+01 -1.21338745e+02 -1.57603500e+02 -1.13046165e+02 -2.72925258e+00 2.24160690e+01 -1.65565300e+01 -7.87751465e+01 -1.00639534e+02 -6.27346230e+01 -5.75202293e+01 -3.25506363e+01 -8.56710968e+01 -1.07440224e+02 -1.17553635e+02 -6.96625137e+01 -4.78739738e+01 -8.60837250e+01 -1.31228104e+02 -9.02499313e+01 -3.07716656e+01 -4.84272995e+01 -8.79507065e+01 -8.14901199e+01 -3.93520279e+01 -4.36838379e+01 -1.15996086e+02 -1.39279022e+02 -1.19316696e+02 -4.44723663e+01 -5.04400215e+01 -7.07619095e+01 -9.74294281e+01 -7.98259201e+01 -4.00964737e+01 -5.46507416e+01 -6.41123734e+01 -1.24979271e+02 -1.43523773e+02 -1.34568344e+02 -9.17688828e+01 -6.54091873e+01 -8.65434799e+01 -1.18050911e+02 -1.03648216e+02 -4.29397507e+01 -2.61854725e+01 -2.43369522e+01 8.41560936e+00 6.49912186e+01 4.55072899e+01 -3.29040375e+01 -4.51964912e+01 2.38927618e-01 5.68856468e+01 -9.04574299e+00 -4.05774879e+01 -6.39095840e+01 -9.48544540e+01 -1.06665833e+02 -7.19145660e+01 3.66446114e+01 6.07873802e+01 -1.91361084e+01 -9.19311981e+01 -5.93643875e+01 4.02060547e+01 8.75608826e+01 3.09800682e+01 -2.32792835e+01 -1.06096210e+01 2.28346367e+01 6.89151382e+01 1.09957268e+02 1.74544250e+02 1.50352219e+02 8.08418427e+01 5.92726974e+01 9.43937073e+01 1.46827728e+02 6.36235809e+01 1.72940178e+01 -2.57792187e+01 -2.47473645e+00 -7.99197197e-01 5.28156509e+01 1.54099869e+02 1.84000458e+02 9.79124680e+01 -5.94860535e+01 -1.01817421e+02 2.77888813e+01 1.58411499e+02 1.68496445e+02 7.37617950e+01 1.06346779e+01 4.64466858e+01 1.23471359e+02 1.64665588e+02 1.16588234e+02 -5.97839451e+00 -3.07180767e+01 2.84083328e+01 1.12954216e+02 2.06219543e+02 1.98035889e+02 1.57475525e+02 4.21357880e+01 -7.54214096e+01 -1.15461319e+02 -4.39283409e+01 1.10214241e+02 1.86179886e+02 1.12962357e+02 1.09850187e+01 1.62685108e+01 1.41009018e+02 2.46400131e+02 1.96006256e+02 5.20161552e+01 -4.74218636e+01 -5.13314018e+01 3.72115173e+01 9.08171310e+01 1.50052521e+02 7.76764526e+01 4.97435036e+01 2.49064903e+01 6.90113373e+01 1.05842972e+02 4.37639999e+01 -1.52688770e+01 -9.90992737e+01 -1.10427376e+02 -5.93728180e+01 1.10271654e+01 1.34954147e+02 1.45368912e+02 7.04474411e+01 -9.13495636e+01 -1.63391510e+02 -9.01525040e+01 6.88693924e+01 1.59064621e+02 1.30754471e+02 6.23116531e+01 6.44865417e+01 1.04510513e+02 1.33094559e+02 1.38691025e+02 6.19213028e+01 6.57940769e+00 -5.28066025e+01 -4.91006126e+01 -1.92087059e+01 2.97061806e+01 8.78907166e+01 8.18255310e+01 1.93644390e+01 -4.22741203e+01 -4.68767548e+01 2.22286434e+01 9.81556549e+01 6.70979385e+01 -3.34129000e+00 -3.76465797e+01 2.70149765e+01 1.28319138e+02 1.26551704e+02 6.24202118e+01 -4.21671448e+01 -4.88476219e+01 1.91441345e+01 8.87340775e+01 1.43655228e+02 7.01566086e+01 3.65527802e+01 -8.30033302e+00 -1.57637739e+01 -2.24474106e+01 -3.75936623e+01 7.08910656e+00 -8.99886703e+00 -3.61988640e+01 -2.60049171e+01 3.00193329e+01 1.25428131e+02 1.69171371e+02 1.11071281e+02 -2.14919815e+01 -1.46611359e+02 -1.30201324e+02 -2.46852804e-02 1.36658646e+02 1.76318741e+02 8.21324615e+01 -2.63034782e+01 -5.43571892e+01 1.02605858e+01 1.01500198e+02 7.96609039e+01 1.73433533e+01 -5.30196877e+01 -6.48438339e+01 -3.08226814e+01 3.53143425e+01 1.03672470e+02 8.95724258e+01 1.66527863e+01 -8.00631866e+01 -9.02111740e+01 -1.53212414e+01 8.87335587e+01 6.89658279e+01 -1.78838749e+01 -7.93428268e+01 -4.69549217e+01 1.17704687e+01 3.65390320e+01 5.72246399e+01 1.92792263e+01 -3.56059837e+00 2.36985245e+01 4.18607903e+01 7.24152374e+01 2.52405682e+01 -1.14340410e+01 -6.54652634e+01 -1.02899673e+02 -6.36422806e+01 -1.85915356e+01 5.43627090e+01 8.27985535e+01 3.93148766e+01 -2.62970486e+01 -3.71047516e+01 4.66730728e+01 1.27755287e+02 1.22559906e+02 6.41655426e+01 -1.76974411e+01 -4.43200645e+01 -1.46173315e+01 2.80683613e+01 4.76044693e+01 -1.13462200e+01 -6.53554688e+01 -1.18722145e+02 -1.01721298e+02 -2.58300877e+01 -2.35283928e+01 -5.75243340e+01 -1.30165939e+02 -1.43041138e+02 -1.10681625e+02 -6.43232498e+01 3.47941589e+01 7.25653610e+01 5.33195152e+01 -2.56170483e+01 -6.17760735e+01 9.02580643e+00 7.92294769e+01 8.53793793e+01 -1.59773302e+01 -7.14694214e+01 -5.08960609e+01 3.71751595e+01 1.06783386e+02 1.13642570e+02 4.43511009e+01 -3.79164772e+01 -6.09435997e+01 -5.32026672e+01 -2.76541882e+01 2.77676821e+00 5.77499809e+01 5.99323616e+01 3.80391884e+01 1.44569921e+01 5.21799583e+01 1.23714188e+02 1.71029846e+02 1.03265121e+02 1.33233137e+01 -3.68187981e+01 2.12987690e+01 1.14581169e+02 1.30805618e+02 7.88449860e+01 -1.33499651e+01 -2.92211399e+01 3.01629658e+01 5.95154686e+01 6.89908981e+01 1.04799099e+01 8.40876341e-01 8.37141609e+00 3.28057747e+01 8.08516006e+01 7.65531311e+01 7.27979813e+01 -7.41017818e-01 -5.44770927e+01 -4.60173874e+01 -1.15091591e+01 6.89321594e+01 1.04001137e+02 1.02325172e+02 2.42978668e+01 -1.04676048e+02 -1.55647552e+02 -1.37524307e+02 2.58642750e+01 7.71717987e+01 1.53751266e+02 1.86323730e+02 -3.44904077e+03 -9.26673047e+03 383080544. 427584608. -1181876096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.00599859e+10 -368908384. 7.37914697e+03 1.88488135e+03 -4.15241974e+02 1.50659839e+03 2.45236743e+03 1.05044495e+03 -2.93400610e+03 -1.93834705e+03 -1.99512787e+02 -1.45040878e+02 -7.60080109e+01 -3.10642223e+01 -6.00371718e-01 2.53220577e+01 1.00755959e+02 1.04868614e+02 6.23886032e+01 5.43423796e+00 1.35272083e+01 7.68234711e+01 1.34331635e+02 1.49801666e+02 9.65981522e+01 2.15470963e+01 5.74955130e+00 6.94139099e+01 1.28765137e+02 1.28146912e+02 7.29373093e+01 7.55510254e+01 1.15146759e+02 1.24495705e+02 9.19953461e+01 4.51932716e+01 4.46122932e+01 3.33522835e+01 1.83077297e+01 2.00448380e+01 6.29812813e+01 1.40594650e+02 1.45688065e+02 9.54724808e+01 4.42734833e+01 4.68341904e+01 9.66589127e+01 1.48741547e+02 1.38592499e+02 7.06195908e+01 -8.64381313e+00 1.57427263e+00 7.61704941e+01 1.17990280e+02 1.26012016e+02 8.31114120e+01 6.67345963e+01 5.35176392e+01 4.87804375e+01 6.44727783e+01 9.04454422e+01 1.31986984e+02 1.15044724e+02 7.65341797e+01 6.06949234e+01 9.01367035e+01 1.41080826e+02 1.39363037e+02 1.14261101e+02 6.78287277e+01 5.25642433e+01 9.28431931e+01 1.50959473e+02 1.93165192e+02 1.66934143e+02 1.06418953e+02 8.61876755e+01 1.20239265e+02 1.44232925e+02 1.38795425e+02 8.60383682e+01 7.47380295e+01 9.00467682e+01 1.13754013e+02 1.14107887e+02 1.10873398e+02 1.26894180e+02 1.09201126e+02 7.78353119e+01 6.05819626e+01 9.36339951e+01 1.48095230e+02 1.57071335e+02 1.39041122e+02 1.01039925e+02 7.01965256e+01 6.85553284e+01 9.60716629e+01 1.23386360e+02 1.16527359e+02 6.84366302e+01 4.88586578e+01 8.37248306e+01 1.20433853e+02 1.21862663e+02 7.33143005e+01 5.25013809e+01 5.45320091e+01 6.17915192e+01 7.06673126e+01 8.98139648e+01 1.24811134e+02 1.20980179e+02 9.12212982e+01 6.91999283e+01 7.26346283e+01 1.03056595e+02 1.07802109e+02 8.98470459e+01 7.32096405e+01 5.59470215e+01 6.30433807e+01 9.30272903e+01 1.19972824e+02 1.25952080e+02 8.24241409e+01 6.59008102e+01 8.13261108e+01 9.49092407e+01 9.78689575e+01 7.95371475e+01 8.19920120e+01 8.22393188e+01 7.19573746e+01 6.65134048e+01 7.19600983e+01 1.04465012e+02 1.04539726e+02 8.29238434e+01 6.54600525e+01 6.81239014e+01 8.84625626e+01 8.59194717e+01 6.98584824e+01 5.95343933e+01 4.80219421e+01 6.19082947e+01 8.43720856e+01 1.05052422e+02 1.03301765e+02 8.29598312e+01 7.80003738e+01 8.62943573e+01 8.58879929e+01 8.33124161e+01 6.57572479e+01 5.91943932e+01 5.21702385e+01 5.40146370e+01 6.34966202e+01 7.72709885e+01 9.94449387e+01 1.04896271e+02 9.88676529e+01 8.47295685e+01 8.40373459e+01 9.89382629e+01 1.12726990e+02 1.05805687e+02 8.17145691e+01 6.65836029e+01 6.75560989e+01 8.85088730e+01 9.74158478e+01 9.72806015e+01 8.52018661e+01 8.42257690e+01 8.89046936e+01 8.87508698e+01 8.99483337e+01 9.14538727e+01 9.17134323e+01 8.20077591e+01 7.10364075e+01 7.12731857e+01 7.58218689e+01 8.41338120e+01 9.03902664e+01 9.21434631e+01 8.88181839e+01 8.80337372e+01 9.62276077e+01 1.03158630e+02 9.78224640e+01 8.51551132e+01 7.62054214e+01 7.66528473e+01 8.48280029e+01 8.74789734e+01 8.78099670e+01 8.04958115e+01 8.18212357e+01 8.63085403e+01 9.17648697e+01 9.44673462e+01 9.48627167e+01 9.84128571e+01 9.56043472e+01 8.97087326e+01 8.52968521e+01 8.55549927e+01 8.96979904e+01 8.92532120e+01 8.66074677e+01 8.31252213e+01 8.07447586e+01 8.26132202e+01 8.67861404e+01 9.00117493e+01 8.87978363e+01 8.60293198e+01 8.55582047e+01 8.62100449e+01 8.64334030e+01 8.63499146e+01 8.61017914e+01 8.61038284e+01 8.63181915e+01 8.64582367e+01 8.63937302e+01 8.57128143e+01 8.43895035e+01 8.35814972e+01 8.39740677e+01 8.49376602e+01 8.52844772e+01 8.51200943e+01 8.61758118e+01 8.80643082e+01 8.86593399e+01 8.81606979e+01 8.52968445e+01 8.45835800e+01 8.34991760e+01 8.41755447e+01 8.63576736e+01 8.75959930e+01 8.74055405e+01 8.48860397e+01 8.37874908e+01 8.50981827e+01 8.65702515e+01 8.64860535e+01 8.38576889e+01 8.28437042e+01 8.29329300e+01 8.46063766e+01 8.45245514e+01 8.55321808e+01 8.53765717e+01 8.71489105e+01 8.66094131e+01 8.66832581e+01 8.49434586e+01 8.63561096e+01 8.68348007e+01 8.80835419e+01 8.69858704e+01 8.77473679e+01 8.98294144e+01 8.92236633e+01 8.94597626e+01 9.16428223e+01 9.06454163e+01 8.85035782e+01 8.44006195e+01 9.03176804e+01 9.05036850e+01 8.93492126e+01 8.68756256e+01 8.85399628e+01 9.04196243e+01 9.04831772e+01 9.21735840e+01 9.04567795e+01 8.91675034e+01 8.68552017e+01 8.85334167e+01 8.77266159e+01 8.88773041e+01 8.89205780e+01 8.91495819e+01 8.95918503e+01 9.14640198e+01 9.20354004e+01 9.20255585e+01 8.60408325e+01 7.93994980e+01 7.51117249e+01 7.88937531e+01 8.45565948e+01 9.05980530e+01 8.82291260e+01 8.47975082e+01 8.12600708e+01 8.36899719e+01 8.89633789e+01 8.87667770e+01 8.51455002e+01 8.50962753e+01 8.97215042e+01 9.13021469e+01 8.86579819e+01 8.64007874e+01 8.66588135e+01 8.42843475e+01 8.23816071e+01 7.72610550e+01 7.56343613e+01 7.54908752e+01 8.28900452e+01 9.20398026e+01 1.02990173e+02 1.13225372e+02 1.07644760e+02 9.59549561e+01 8.48691711e+01 8.41891632e+01 8.02984390e+01 7.44246979e+01 8.66325836e+01 1.01015724e+02 1.00512917e+02 8.61893005e+01 7.60093231e+01 7.72312164e+01 7.93095627e+01 7.32360306e+01 7.23024216e+01 7.10885849e+01 7.73812332e+01 7.48473129e+01 7.45559235e+01 7.92915039e+01 8.51592255e+01 8.21597290e+01 6.83062973e+01 5.21099701e+01 5.14576187e+01 5.83478127e+01 7.39918747e+01 7.23355713e+01 6.76554337e+01 6.94146042e+01 7.03965988e+01 7.48166199e+01 5.85166473e+01 4.44151382e+01 4.45189133e+01 6.15192604e+01 7.71340332e+01 8.17076340e+01 7.36614456e+01 5.47867546e+01 3.70865326e+01 4.86935081e+01 7.78028793e+01 8.85919266e+01 7.90512543e+01 6.73512344e+01 6.33075485e+01 4.81351852e+01 3.57620583e+01 4.14615822e+01 5.34710579e+01 7.33369370e+01 7.49970398e+01 7.74738693e+01 6.08699875e+01 5.25655594e+01 5.29876518e+01 6.90682526e+01 7.85660248e+01 8.41349564e+01 7.97974167e+01 8.15936127e+01 8.54977341e+01 9.11641006e+01 8.67266312e+01 7.93155289e+01 6.98718414e+01 7.78196030e+01 8.26327515e+01 7.97971039e+01 7.05771255e+01 7.52347488e+01 8.44828415e+01 6.72535095e+01 4.91662788e+01 5.56318398e+01 8.19885712e+01 9.62031555e+01 7.96401672e+01 7.60821457e+01 6.75736542e+01 6.25540504e+01 4.82043800e+01 5.13542633e+01 4.59925842e+01 4.72072411e+01 4.47917747e+01 6.12337418e+01 6.81145554e+01 6.17400932e+01 6.25155411e+01 6.40587692e+01 6.95477524e+01 6.93485565e+01 7.27459183e+01 4.99851036e+01 3.01440392e+01 2.11725140e+01 4.68290138e+01 6.52125320e+01 7.35846558e+01 7.60474777e+01 7.71413803e+01 7.36639099e+01 6.75734940e+01 7.18828735e+01 8.81417694e+01 1.06401817e+02 1.08734978e+02 9.86698456e+01 7.88618546e+01 7.78605499e+01 8.34169617e+01 8.60116425e+01 7.83862610e+01 7.28293152e+01 1.02934616e+02 1.33109055e+02 1.37348312e+02 1.02596687e+02 6.96399689e+01 6.87608566e+01 8.74017334e+01 1.22957359e+02 2.27897583e+02 4.05610626e+02 6.47975220e+02 2.65897485e+03 3.56887158e+03 2.46699158e+02 -2.08974396e+02 6.45676611e+03 1.62303662e+04 -842406336. -2.92679066e+09 -3.45275264e+09 -452864768. -773293056. -5.49951642e+09 -238931136. -2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -2.46511590e+09 -162604928. -3.49388828e+04 -1.36611895e+04 -2.30558057e+03 -8.95491150e+02 4.01293262e+03 2.81534766e+03 6.18066650e+02 4.26478882e+02 2.01405273e+02 1.50710159e+02 1.02948112e+02 6.25735893e+01 6.70166092e+01 7.38146667e+01 7.95425034e+01 8.23353348e+01 1.01347374e+02 1.25759445e+02 9.59241562e+01 4.67011604e+01 3.75575638e+01 6.94583282e+01 1.02568611e+02 8.42232971e+01 7.94269028e+01 7.45450668e+01 8.58476562e+01 9.82475815e+01 1.04191605e+02 9.62381516e+01 7.08127060e+01 6.78721466e+01 6.03073654e+01 6.51697693e+01 3.08696537e+01 -2.74105525e+00 -4.44149828e+00 1.68432808e+01 3.89179001e+01 2.87249546e+01 1.42377234e+01 9.07164669e+00 5.75848043e-01 -8.06781578e+00 -1.14651031e+01 -2.20560246e+01 -2.07209492e+01 -1.42558327e+01 -4.29222727e+00 3.60049677e+00 -2.48240471e+00 -5.53404570e-01 -1.88342285e+00 -4.61494398e+00 -8.04895973e+00 -1.60463657e+01 -2.29233665e+01 -8.95156670e+00 2.57109547e+01 7.37570648e+01 9.55460434e+01 8.30959854e+01 5.65318108e+01 3.29399757e+01 5.17203827e+01 7.23910980e+01 6.50394363e+01 2.43303356e+01 -1.04448643e+01 -1.43769341e+01 -8.85248470e+00 -2.78613873e+01 -6.33695221e+01 -3.77359047e+01 1.11727591e+01 5.52363281e+01 4.85328598e+01 2.29719276e+01 2.34605236e+01 6.91776800e+00 1.19770498e+01 6.98964977e+00 2.00966129e+01 2.12669373e+01 4.07014732e+01 4.65809059e+01 4.82887878e+01 3.42805443e+01 3.31348419e+01 6.79532013e+01 1.06305344e+02 8.82871399e+01 5.64230690e+01 1.98327980e+01 3.58282967e+01 5.19463158e+01 7.82093887e+01 9.37984009e+01 5.95736542e+01 1.18315725e+01 2.75957823e-01 2.04992905e+01 6.49289322e+01 6.23658676e+01 5.68086052e+01 3.37354813e+01 1.88695107e+01 2.93580818e+01 2.35477352e+01 2.60894432e+01 1.08858242e+01 2.18599148e+01 2.18870335e+01 2.17772141e+01 4.25698700e+01 7.12887268e+01 7.04786301e+01 4.26718407e+01 3.21014452e+00 -4.78449821e+00 -1.95972328e+01 -1.22889500e+01 -1.96650372e+01 -2.05738220e+01 -2.56188717e+01 1.57433672e+01 5.86447639e+01 6.70452194e+01 3.86584167e+01 8.97418499e+00 -2.05602570e+01 -3.91605377e+01 -4.75442162e+01 -2.24600868e+01 -8.82653713e+00 -1.88014736e+01 -4.17882156e+00 7.65324736e+00 9.07066822e+00 -2.56309032e+00 -5.82951212e+00 -2.03886300e-01 4.00603104e+00 -1.07476330e+00 4.23221493e+00 1.22724781e+01 1.44301500e+01 1.90636120e+01 2.41626205e+01 2.40848083e+01 2.27423935e+01 8.73113346e+00 -2.53204608e+00 -7.21049833e+00 -5.73328209e+00 -3.47034645e+00 -1.19588299e+01 -2.25782986e+01 -1.36342192e+01 4.00335541e+01 7.87348328e+01 8.38393097e+01 6.58836823e+01 4.17780266e+01 3.44804459e+01 1.55346937e+01 6.08363867e+00 1.43069849e+01 1.61256390e+01 1.38982868e+01 1.24942713e+01 1.43088179e+01 5.76716566e+00 -4.00720482e+01 -7.79903946e+01 -1.02894371e+02 -9.69059448e+01 -5.20810928e+01 -1.20687933e+01 2.97040939e+01 1.73120594e+01 8.75275517e+00 -3.20771646e+00 -1.92611694e+00 -9.19092560e+00 -3.35337877e+00 -6.51527262e+00 -1.16742325e+01 -1.00935526e+01 -5.62898397e+00 -5.96770239e+00 -1.28016233e+01 -1.24493980e+01 1.15475025e+01 2.21465702e+01 2.16451511e+01 1.54042063e+01 4.89734554e+00 -2.76677017e+01 -7.67891617e+01 -9.88759918e+01 -1.00215424e+02 -8.77721024e+01 -1.00593246e+02 -6.80909271e+01 -2.31795540e+01 2.40283546e+01 2.62876759e+01 1.76235085e+01 5.26581573e+00 3.64281297e+00 6.46793032e+00 2.23349133e+01 1.75176468e+01 1.13364048e+01 -3.08690929e+00 -1.53914452e+00 5.35512686e+00 3.77321968e+01 7.51376266e+01 5.84731979e+01 2.97151337e+01 -7.87002993e+00 -2.96288338e+01 -5.19025116e+01 -8.93563766e+01 -1.14507545e+02 -1.00460747e+02 -7.88186722e+01 -2.44093971e+01 -3.86702499e+01 -5.06212730e+01 -6.74245834e+01 -6.44305649e+01 -4.97047844e+01 -5.71968193e+01 -6.11319733e+01 -6.13402557e+01 -4.68820686e+01 -3.13975945e+01 -3.17619286e+01 -6.11672401e+01 -1.02240685e+02 -1.41126831e+02 -1.59853302e+02 -8.95518341e+01 -1.73486328e+01 2.66413860e+01 3.73110962e+00 -3.68942604e+01 -3.33763313e+01 -4.75138245e+01 -3.50169830e+01 -3.59177170e+01 -2.36453037e+01 -2.31998386e+01 -1.90708904e+01 -2.90977974e+01 -2.92251492e+01 3.80515027e+00 4.86339417e+01 5.39085999e+01 2.48544044e+01 -2.99875998e+00 -1.89341240e+01 -3.83683395e+01 -4.47712746e+01 -3.32582130e+01 -3.21166496e+01 -5.31158257e+01 -5.99384003e+01 -4.19112129e+01 -1.72825623e+01 -5.70827627e+00 -7.73538399e+00 -1.30111332e+01 -1.83699780e+01 -1.77153225e+01 -2.70432758e+01 -2.48226624e+01 -1.80577087e+01 -1.97857690e+00 4.28357172e+00 -3.78580117e+00 -4.06508942e+01 -8.96768799e+01 -8.35036469e+01 -4.94424744e+01 -1.09121742e+01 -2.88091145e+01 -3.53513031e+01 -3.33730431e+01 -2.92222347e+01 -3.70508842e+01 -4.70738487e+01 -7.54126892e+01 -9.27324982e+01 -8.96567612e+01 -4.67783432e+01 -1.08396368e+01 -1.06664820e+01 -2.15386791e+01 -6.02767706e+00 2.85165520e+01 3.15252953e+01 1.96936951e+01 -1.02818527e+01 -4.14046526e+00 -7.23398972e+00 -1.03440409e+01 -2.14067707e+01 -2.52374001e+01 -2.35031090e+01 -1.42313623e+01 -1.88390446e+01 -2.24734020e+01 -2.09912319e+01 -1.91127968e+01 -2.40403976e+01 -3.18476105e+01 -5.88762894e+01 -8.59636765e+01 -8.39628448e+01 -6.58910828e+01 -4.81338882e+01 -5.54185715e+01 -4.76724930e+01 -2.77478294e+01 -2.62402515e+01 -6.61647263e+01 -1.03819946e+02 -1.06377350e+02 -7.36518860e+01 -5.23381042e+01 -5.57891235e+01 -5.70430756e+01 -5.73539047e+01 -5.34943962e+01 -7.94628830e+01 -1.15757599e+02 -1.21768585e+02 -9.70526657e+01 -5.61696930e+01 -6.26390343e+01 -6.12430496e+01 -6.16882248e+01 -5.41750526e+01 -5.75612793e+01 -6.74024658e+01 -8.11093674e+01 -8.58051453e+01 -7.26551208e+01 -6.54792099e+01 -6.52125778e+01 -1.00887573e+02 -1.42698120e+02 -1.47776047e+02 -1.12516159e+02 -7.20455627e+01 -6.33971634e+01 -5.70050354e+01 -5.73620949e+01 -6.46378098e+01 -1.06464233e+02 -1.36371643e+02 -1.72259262e+02 -1.78956604e+02 -1.41992859e+02 -1.08094902e+02 -6.62842026e+01 -9.59507980e+01 -1.16899849e+02 -9.12008820e+01 -3.00723515e+01 2.86963868e+00 -2.26870613e+01 -6.02542686e+01 -5.86155701e+01 -5.71325378e+01 -5.08285561e+01 -5.00630379e+01 -4.26463394e+01 -3.85750732e+01 -3.30802383e+01 -2.90156155e+01 -3.38556786e+01 -3.73100739e+01 -3.98991928e+01 -3.87996254e+01 -4.17808723e+01 -5.56228600e+01 -8.40553131e+01 -7.91315155e+01 -5.93745651e+01 -2.63082581e+01 -5.67589569e+01 -9.11799164e+01 -6.60421448e+01 -3.99918365e+00 -3.01748133e+00 -7.11438293e+01 -1.17983978e+02 -9.49377518e+01 -6.36525002e+01 -8.09433365e+01 -1.14090820e+02 -1.17517029e+02 -1.02695442e+02 -7.64763489e+01 -7.87984924e+01 -8.29769211e+01 -7.36125488e+01 -7.35715714e+01 -4.95563545e+01 -3.40520248e+01 -6.54770126e+01 -1.12287720e+02 -1.40672913e+02 -1.16734329e+02 -9.42622528e+01 -1.15653465e+02 -1.30343384e+02 -1.38723846e+02 -1.14386147e+02 -8.84314880e+01 -8.70166626e+01 -9.19434128e+01 -1.00025490e+02 -9.11827316e+01 -1.03914398e+02 -1.25523064e+02 -1.30009155e+02 -1.22400482e+02 -9.46193771e+01 -7.89876251e+01 -7.06626358e+01 -7.07507172e+01 -7.82452011e+01 -3.92813530e+01 -9.54564095e-01 -8.70940971e+00 -5.94068146e+01 -9.72103806e+01 -8.59770203e+01 -6.81724091e+01 -8.43459396e+01 -1.15201370e+02 -1.15553955e+02 -9.66602631e+01 -7.17940521e+01 -6.67594910e+01 -6.62445450e+01 -6.68334122e+01 -7.29922104e+01 -7.38992538e+01 -7.92871628e+01 -9.08754654e+01 -9.64909515e+01 -9.19971008e+01 -7.74253082e+01 -7.03169403e+01 -6.22693405e+01 -6.54392395e+01 -4.66236725e+01 -2.99954910e+01 -4.67601433e+01 -9.35371017e+01 -1.17947891e+02 -9.55803299e+01 -6.55363388e+01 -5.22824249e+01 -4.49503784e+01 -4.31058578e+01 -4.64126930e+01 -5.44487419e+01 -5.22764893e+01 -5.83100700e+01 -5.63453560e+01 -5.87777481e+01 -5.32443047e+01 -5.15886803e+01 -4.98861275e+01 -6.15549049e+01 -6.67531738e+01 -6.37220154e+01 -5.23636017e+01 -5.00947571e+01 -6.11777802e+01 -7.41380386e+01 -7.82447739e+01 -9.29846954e+01 -1.08785194e+02 -1.12595474e+02 -9.96760712e+01 -9.49317551e+01 -1.28321014e+02 -1.47790314e+02 -1.31918488e+02 -1.05459297e+02 -1.11458046e+02 -1.33022308e+02 -1.35221329e+02 -1.15286736e+02 -9.92853622e+01 -9.79927368e+01 -9.74986649e+01 -1.03171806e+02 -1.05488388e+02 -1.04237808e+02 -9.64132233e+01 -1.03025459e+02 -1.20238976e+02 -1.28437134e+02 -1.17760422e+02 -1.00066315e+02 -1.01273155e+02 -1.12560425e+02 -9.85619507e+01 -7.58243103e+01 -6.35242348e+01 -7.32194138e+01 -8.21824951e+01 -7.63338318e+01 -7.63967438e+01 -7.95525055e+01 -8.24415817e+01 -8.09396973e+01 -8.22280807e+01 -8.64302139e+01 -8.36252289e+01 -8.07944412e+01 -7.45128098e+01 -7.72827377e+01 -8.05209351e+01 -8.10753784e+01 -9.15636139e+01 -9.88687820e+01 -9.92018738e+01 -8.52464600e+01 -7.29834976e+01 -7.02177124e+01 -7.15911407e+01 -6.43949585e+01 -5.44156189e+01 -5.37740669e+01 -6.05785408e+01 -7.07438354e+01 -7.25927124e+01 -7.46189728e+01 -8.94273453e+01 -1.03404602e+02 -1.05686363e+02 -9.57764206e+01 -8.75656204e+01 -8.83314285e+01 -8.57105179e+01 -8.18273010e+01 -8.41467514e+01 -7.90722504e+01 -7.09785919e+01 -7.37892075e+01 -8.56235886e+01 -9.49872131e+01 -9.07693558e+01 -9.18714600e+01 -1.06233902e+02 -1.14553444e+02 -1.11285912e+02 -9.47344360e+01 -9.04290237e+01 -9.54080963e+01 -9.62841187e+01 -9.05387878e+01 -8.07040253e+01 -8.24471741e+01 -8.82548523e+01 -8.98036499e+01 -8.68230362e+01 -8.04154053e+01 -7.72301941e+01 -7.58283768e+01 -7.59679031e+01 -7.79749527e+01 -7.86814728e+01 -7.79701080e+01 -8.32080154e+01 -8.72799454e+01 -8.99685440e+01 -8.55911255e+01 -8.23255005e+01 -8.31432343e+01 -8.70488052e+01 -8.54142838e+01 -6.68476791e+01 -5.17609749e+01 -4.44363136e+01 1.90807831e+02 2.79120483e+02 -2.35222641e+02 -2.84354767e+02 -2.49195480e+02 -4.23894714e+02 -1.60091812e+02 2.87934814e+02 1.98967957e+03 -1510672640. -9642282. 2.78443069e+10 2.78443069e+10 -2.51446886e+09 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. 569779712. 179301872. -134445168. -95973960. -172146704. -215503696. -7.76854370e+02 -3.08276306e+02 -3.67273254e+01 -7.45573883e+01 -8.70114365e+01 -1.28222549e+02 -1.21041565e+02 -1.04388359e+02 -7.66985092e+01 -7.15185699e+01 -8.15755997e+01 -8.67098999e+01 -1.12566574e+02 -1.32084885e+02 -1.06181000e+02 -7.04108124e+01 -5.49287643e+01 -4.93779259e+01 -5.21669464e+01 -4.90609131e+01 -4.11246567e+01 -4.06311493e+01 -4.67557640e+01 -5.18698921e+01 -4.41378021e+01 -2.81615582e+01 -2.44236050e+01 -3.62923622e+01 -5.08806229e+01 -5.93871918e+01 -5.95108223e+01 -6.42634506e+01 -7.20035629e+01 -7.59618073e+01 -6.46001511e+01 -3.42519722e+01 -1.87653313e+01 -2.55814056e+01 -4.65973701e+01 -6.12929840e+01 -5.95734253e+01 -5.42481842e+01 -4.37498627e+01 -4.96448898e+01 -4.63429756e+01 -4.17277336e+01 -4.53845253e+01 -6.60701523e+01 -9.07427750e+01 -8.83804550e+01 -5.19249382e+01 -3.38350525e+01 -4.11084251e+01 -6.22973328e+01 -5.92082481e+01 -4.12822609e+01 -4.08995590e+01 -6.01278038e+01 -8.24301605e+01 -7.81258545e+01 -4.43107834e+01 -2.10682812e+01 -2.74937820e+01 -4.88589935e+01 -5.34958801e+01 -4.62112617e+01 -4.89770699e+01 -6.57759171e+01 -8.53146591e+01 -7.59109421e+01 -6.38124886e+01 -6.74844208e+01 -8.05996094e+01 -8.57439194e+01 -7.70472565e+01 -6.28421021e+01 -4.72792244e+01 -3.93686256e+01 -4.90053787e+01 -6.09778862e+01 -6.27995224e+01 -7.69122162e+01 -1.01512314e+02 -1.10916733e+02 -8.37178497e+01 -3.36591873e+01 -1.05334978e+01 -2.45203915e+01 -6.56357422e+01 -1.10151527e+02 -1.26621445e+02 -1.15390312e+02 -1.03785088e+02 -1.11024338e+02 -9.84041138e+01 -6.07202492e+01 -2.91258793e+01 -4.18153534e+01 -7.03457718e+01 -8.28033981e+01 -7.15623550e+01 -4.23987274e+01 -3.61699905e+01 -5.01517067e+01 -7.01697006e+01 -6.60770798e+01 -6.15339012e+01 -8.08598557e+01 -1.22297928e+02 -1.32566116e+02 -1.00647713e+02 -6.13271599e+01 -6.05953789e+01 -9.06343613e+01 -1.15628555e+02 -1.14566574e+02 -8.64032745e+01 -5.86328239e+01 -4.88404388e+01 -6.35515633e+01 -6.31693344e+01 -3.97714806e+01 -3.25644264e+01 -5.86719856e+01 -9.11490479e+01 -9.27183685e+01 -6.01192741e+01 -4.09741707e+01 -6.24014778e+01 -8.01987457e+01 -8.99370880e+01 -7.27009735e+01 -7.91720886e+01 -1.10423271e+02 -1.19994774e+02 -8.44748764e+01 -8.82548332e+00 3.00416012e+01 -1.62462687e+00 -4.98782120e+01 -6.97142410e+01 -5.57414551e+01 -3.94440155e+01 -4.23767776e+01 -4.06713066e+01 -1.72114773e+01 1.45237694e+01 2.30756321e+01 -2.59478416e+01 -9.82732620e+01 -1.29611176e+02 -7.64003143e+01 -2.89741364e+01 -3.30964432e+01 -5.45657234e+01 -3.14313984e+01 2.60925350e+01 1.94050102e+01 -4.04218864e+01 -9.37189255e+01 -5.36947403e+01 3.81996498e+01 9.04421921e+01 5.33549500e+01 -1.13730097e+01 -4.90482941e+01 -4.55008087e+01 -5.74489326e+01 -7.10751419e+01 -5.59405556e+01 -6.68506479e+00 5.47019997e+01 2.48729115e+01 -2.39059143e+01 -8.30679779e+01 -7.04376526e+01 -4.39505348e+01 -6.96058941e+00 5.23258924e+00 9.71779060e+00 2.08626881e+01 5.48268280e+01 3.36542053e+01 -2.30062904e+01 -8.98109970e+01 -6.42331848e+01 2.79802370e+00 5.11024895e+01 2.87650337e+01 -1.87953625e+01 -4.82195930e+01 -4.35306015e+01 -5.95280991e+01 -1.12546295e+02 -1.43195847e+02 -9.18882828e+01 -1.35555601e+00 2.15639534e+01 -1.29639845e+01 -8.59161911e+01 -1.00815674e+02 -9.19215546e+01 -6.58408051e+01 -5.02948112e+01 -4.63254852e+01 -2.38893127e+01 5.34169960e+00 -2.38716316e+01 -6.88207550e+01 -9.26157303e+01 -8.71370316e+01 -5.44548225e+01 -4.31798439e+01 -5.01984863e+01 -5.11028481e+01 -4.89606895e+01 -1.85518017e+01 -4.89755058e+01 -9.23490143e+01 -1.21306076e+02 -1.19671974e+02 -4.92642212e+01 -1.14374323e+01 -3.11336021e+01 -1.02883629e+02 -1.14404640e+02 -6.67206955e+01 -1.63722076e+01 -2.53190422e+01 -6.77031097e+01 -6.15549393e+01 -2.39645653e+01 -5.09054756e+00 -5.52372856e+01 -9.01174698e+01 -6.65791245e+01 -4.16524391e+01 -6.76963196e+01 -8.23402634e+01 -5.28821373e+01 -2.60336056e+01 -5.55223608e+00 -3.82967377e+01 -1.22387180e+01 6.30664587e-01 1.28517838e+01 2.96795483e+01 5.28801689e+01 6.15059700e+01 -1.62544880e+01 -4.76049995e+01 -5.07682953e+01 7.42694378e+00 -8.02556324e+00 -1.74256687e+01 -1.99809387e-01 4.03536873e+01 5.38615913e+01 -1.66883869e+01 -6.91698456e+01 -7.62790833e+01 -7.34585810e+00 3.70016003e+00 -1.00526857e+01 -3.82174530e+01 -3.07145500e+01 3.00305653e+01 1.42102852e+01 -2.26441765e+01 -9.84034882e+01 -1.22264351e+02 -9.72882843e+01 -4.04093513e+01 5.27391255e-01 -3.58658180e+01 -8.69244537e+01 -1.02965103e+02 -7.22780609e+01 -1.09509392e+02 -1.15870689e+02 -7.59077606e+01 -6.80658281e-01 2.09221959e+00 -8.52863007e+01 -1.20108459e+02 -8.06903610e+01 -9.02426434e+00 -2.49261932e+01 -6.06668015e+01 -7.00967407e+01 -5.17805061e+01 -1.50630198e+01 -1.52929296e+01 1.02527499e+00 -4.77749977e+01 -7.84397812e+01 -8.86281357e+01 -4.39644890e+01 -2.35868664e+01 -5.26056824e+01 -9.01425705e+01 -9.45129242e+01 -1.04686554e+02 -1.74631516e+02 -2.17516068e+02 -2.15549408e+02 -1.85145401e+02 -1.78385315e+02 -2.16292877e+02 -2.26055023e+02 -1.94561600e+02 -1.13039970e+02 -7.77918243e+01 -7.07545624e+01 -8.93362656e+01 -6.92704544e+01 -1.56699142e+01 2.67841969e+01 3.26847115e+01 -3.18700008e+01 -6.05165291e+01 -6.89799118e+01 -4.81258659e+01 -6.59733582e+01 -9.45814285e+01 -1.20560402e+02 -1.06946144e+02 -1.11874496e+02 -1.52144257e+02 -1.87660141e+02 -1.67264328e+02 -1.11830780e+02 -1.05552956e+02 -1.00656532e+02 -4.02431526e+01 1.74278412e+01 5.18267174e+01 -1.23014479e+01 -2.22893314e+01 -4.60944214e+01 -8.46375427e+01 -9.13803940e+01 -4.80345726e+01 3.58316803e+01 6.16180725e+01 -2.06283741e+01 -8.00471115e+01 -7.60045700e+01 -1.64430122e+01 2.43702583e+01 -1.97801895e+01 -7.81268997e+01 -1.25906807e+02 -1.14557060e+02 -5.63512115e+01 -1.44599075e+01 4.34830132e+01 4.25405884e+01 3.50847549e+01 5.18978386e+01 6.45924606e+01 7.74520721e+01 -1.53387499e+01 -2.68482590e+01 -3.10903740e+01 -1.67083378e+01 -3.97018266e+00 4.44462128e+01 1.66111496e+02 1.89241653e+02 1.00703812e+02 -5.81248322e+01 -1.31113861e+02 -3.82270851e+01 8.78337860e+01 1.00870277e+02 -3.83625145e+01 -1.82527832e+02 -1.50837326e+02 -1.49260902e+01 6.77638016e+01 5.99232864e+01 -2.54702892e+01 -1.28028345e+01 3.28584671e+01 7.88435669e+01 8.54264145e+01 7.48188543e+00 -7.14681685e-01 3.47793579e+01 8.16623459e+01 7.92077179e+01 3.03736515e+01 4.90269508e+01 5.99856949e+01 -1.21576157e+01 -1.13541626e+02 -1.06511292e+02 5.56644707e+01 1.64875870e+02 1.26206650e+02 -9.67012882e+00 -7.19229660e+01 -4.93875656e+01 3.77390938e+01 7.93831558e+01 9.54037857e+01 1.84727898e+01 1.14505730e+01 1.82750340e+01 5.72080078e+01 7.92706299e+01 2.75413132e+01 -2.32986107e+01 -9.51775818e+01 -9.39251099e+01 -5.85312920e+01 1.19528084e+01 1.08859016e+02 1.48161865e+02 6.99240723e+01 -7.84764175e+01 -1.61425125e+02 -9.11195679e+01 7.97319565e+01 1.31028183e+02 9.03176212e+00 -1.60883957e+02 -1.64536423e+02 -2.27972622e+01 5.70559731e+01 5.46119537e+01 -2.39215031e+01 -3.08220387e+01 9.24817848e+00 7.45638428e+01 1.34895172e+02 1.34948166e+02 1.66303040e+02 1.49776871e+02 8.49580612e+01 -1.74053955e+01 -5.28177986e+01 2.74329052e+01 1.00367790e+02 7.88021851e+01 -3.25229607e+01 -1.22014488e+02 -9.23599243e+01 1.83238163e+01 4.79048691e+01 7.24761152e+00 -7.57502747e+01 -5.24814949e+01 1.94474697e+01 8.70764160e+01 1.39703674e+02 8.46964264e+01 7.90507202e+01 4.47392044e+01 5.03759575e+01 7.00380630e+01 9.05235672e+01 1.40514053e+02 9.08554611e+01 2.13435535e+01 -4.84818840e+01 -1.33287420e+01 9.31052475e+01 1.60320908e+02 1.00854050e+02 -1.40300856e+01 -7.86700668e+01 -6.90455856e+01 8.24514580e+00 3.27847939e+01 4.55144157e+01 7.59091091e+00 3.06678982e+01 7.54869461e+01 1.33020432e+02 1.88908295e+02 1.63605316e+02 6.96668396e+01 -6.50729895e+00 -1.67105274e+01 2.11709042e+01 6.00965691e+01 1.20073341e+02 1.48351120e+02 6.14481087e+01 -6.26814461e+01 -1.18854263e+02 -3.14308910e+01 8.60673981e+01 9.73193436e+01 -1.76859035e+01 -1.46552292e+02 -1.31912537e+02 7.09595585e+00 1.50290527e+02 2.05891678e+02 1.21146858e+02 4.29625931e+01 3.41335182e+01 7.23484421e+01 1.06689789e+02 5.67352180e+01 5.85566788e+01 3.34468956e+01 6.30358505e+00 -9.43549538e+00 -4.53729677e+00 6.18839722e+01 4.83255615e+01 -2.45404034e+01 -1.20258057e+02 -1.03816513e+02 3.92640991e+01 1.43635666e+02 1.12204033e+02 -9.64770508e+00 -9.44351501e+01 -9.84501953e+01 -8.33539486e-01 9.80809784e+01 1.40712204e+02 6.67323074e+01 1.93576508e+01 -2.25724106e+01 -2.89006634e+01 -1.41926460e+01 -1.99983768e+01 -1.94641228e+01 -8.66775436e+01 -1.21854088e+02 -1.12764862e+02 -6.45698013e+01 3.16412086e+01 6.29520798e+01 1.62808266e+01 -7.48747177e+01 -1.00680817e+02 -4.66804466e+01 3.83457756e+01 3.70514755e+01 -2.25010509e+01 -1.02401703e+02 -1.15478386e+02 -3.54752808e+01 5.52450371e+01 9.44896469e+01 1.74551506e+01 -5.76833878e+01 -5.71276550e+01 1.07192383e+01 6.52292175e+01 7.25117493e+01 6.21046867e+01 4.01892662e+01 -1.60138454e+01 -2.95763435e+01 2.21818256e+01 1.28204575e+02 1.64801910e+02 9.68388977e+01 1.26670980e+01 -5.36132927e+01 -1.05543003e+01 6.16659508e+01 1.08683167e+02 9.18054352e+01 3.33821869e+01 3.12012711e+01 7.10547256e+01 1.21175606e+02 1.33435593e+02 5.78820877e+01 9.00754356e+00 2.61005554e+01 7.79276886e+01 1.39567139e+02 1.25820618e+02 1.20209412e+02 9.71565323e+01 5.70363770e+01 3.28294907e+01 1.99754086e+01 8.56644135e+01 1.24729630e+02 9.76279602e+01 3.77813148e+01 -1.16254234e+01 3.31850243e+01 9.27843323e+01 1.29215500e+02 6.29369583e+01 -5.45370750e+01 -1.17937408e+02 -4.76773338e+01 9.70019531e+01 1.82241760e+02 1.34841949e+02 5.18923569e+01 1.75913239e+01 7.91109085e+00 -3.04152274e+00 -5.05916176e+01 4.76360512e+01 -7.44389877e+01 -1.88387161e+02 -2.34830298e+03 -3.57317749e+03 8.98205811e+02 -1.20042084e+02 6.23405322e+03 2.10859531e+04 -1181876096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.00599859e+10 -368908384. 229960080. -631162048. 733718848. -255099600. -957214848. -465375296. -1.80225840e+04 -8.50500293e+03 -2.39819141e+03 -4.15225586e+02 -2.86547333e+02 1.41915125e+03 2.05167198e+01 -1.25471729e+03 1.81555191e+02 1.26996126e+01 -1.73604950e+02 -1.76769913e+02 -1.05085159e+02 -1.16555222e+02 -7.05642090e+01 -1.24706306e+01 3.60129395e+01 4.12365265e+01 2.37235947e+01 5.52690315e+01 6.25456734e+01 1.43853922e+01 -1.98256664e+01 1.90992146e+01 1.14636124e+02 1.66206558e+02 1.04743484e+02 3.01355457e+01 -2.05115299e+01 7.12538958e+00 9.06883087e+01 1.60477280e+02 1.92328430e+02 1.26605377e+02 7.55862503e+01 6.70863037e+01 1.11496727e+02 1.44920929e+02 1.18338242e+02 1.14138924e+02 7.86165085e+01 4.97708969e+01 3.39370995e+01 6.22876358e+01 1.44818298e+02 1.49987183e+02 8.50530701e+01 4.35668039e+00 -1.38496389e+01 5.24546585e+01 1.13012207e+02 1.07673683e+02 5.82854309e+01 3.88897247e+01 8.90787354e+01 1.53644302e+02 1.73109070e+02 1.39675919e+02 6.72565613e+01 1.68450451e+01 1.80920620e+01 6.23010330e+01 1.22376183e+02 1.63632401e+02 1.84177124e+02 1.64393555e+02 1.24125168e+02 8.89295731e+01 7.16916428e+01 8.83271332e+01 7.78039932e+01 3.58113899e+01 -3.87304449e+00 1.76784790e+00 5.29800301e+01 9.36424866e+01 8.04053802e+01 5.76944122e+01 2.25132618e+01 6.12553644e+00 2.53837147e+01 7.25133438e+01 1.01192902e+02 7.42674103e+01 3.96474228e+01 4.90150604e+01 6.84918823e+01 7.67360992e+01 5.99211502e+01 7.11587372e+01 6.85480881e+01 4.87465858e+01 3.62871208e+01 5.16499481e+01 1.05545372e+02 1.10797119e+02 6.12560844e+01 2.45197010e+00 -2.52804737e+01 1.40326519e+01 5.87020264e+01 8.09866028e+01 7.20281067e+01 5.38594284e+01 5.14643936e+01 6.13073006e+01 8.63664246e+01 1.00138115e+02 7.53155289e+01 3.09912815e+01 1.99056244e+01 3.81220741e+01 5.46575432e+01 5.56814423e+01 6.87879868e+01 6.72659683e+01 3.48690834e+01 -1.06423211e+00 2.75515771e+00 5.21742325e+01 7.52522507e+01 4.62477112e+01 7.66601658e+00 7.90617824e-01 3.69867134e+01 7.43840790e+01 8.24529724e+01 7.16567688e+01 4.11005211e+01 2.05722866e+01 2.80452957e+01 5.74949188e+01 8.06544418e+01 6.22555428e+01 3.19211044e+01 2.08467922e+01 2.92275581e+01 4.36082687e+01 5.47256279e+01 7.36695862e+01 8.01008530e+01 7.11603317e+01 5.77553558e+01 5.66876068e+01 7.39502792e+01 8.15926743e+01 6.21633644e+01 3.08672009e+01 8.92111301e+00 2.10887089e+01 5.20500565e+01 7.45951233e+01 7.29443283e+01 5.47042274e+01 4.89431992e+01 5.44867706e+01 5.75887070e+01 6.72996445e+01 6.32862015e+01 6.25184669e+01 5.34818878e+01 4.00915031e+01 3.16064377e+01 2.85807190e+01 4.51684799e+01 5.41876144e+01 4.58426208e+01 3.57152672e+01 4.01562004e+01 6.12350197e+01 7.18610458e+01 6.50862961e+01 5.54442253e+01 4.86287994e+01 4.99073944e+01 5.37933578e+01 5.77501945e+01 6.00100327e+01 5.09293556e+01 5.22978210e+01 5.66232719e+01 6.65517349e+01 7.56397400e+01 8.06367188e+01 8.45623322e+01 7.47057877e+01 6.18873100e+01 5.46240349e+01 5.36654205e+01 6.11613312e+01 6.09917336e+01 5.50617943e+01 4.65587654e+01 4.30284615e+01 5.27713318e+01 6.47285461e+01 7.02457275e+01 6.68882294e+01 6.17615318e+01 5.94762230e+01 5.99426193e+01 6.17286491e+01 6.38464508e+01 6.18184433e+01 5.82685204e+01 5.63563728e+01 5.80730858e+01 5.86655540e+01 5.93611450e+01 6.00529366e+01 6.00543137e+01 5.87380447e+01 5.78546410e+01 5.77440948e+01 5.77903824e+01 5.72720451e+01 5.68940277e+01 5.69082642e+01 5.72637367e+01 5.74354744e+01 5.72597160e+01 5.64303207e+01 5.58993874e+01 5.65217628e+01 5.80070000e+01 5.88634758e+01 5.73628464e+01 5.61627655e+01 5.63453026e+01 5.68875465e+01 5.67025604e+01 5.71417503e+01 5.71999855e+01 5.71550827e+01 5.65116959e+01 5.65950203e+01 5.77527313e+01 5.90031586e+01 6.07867661e+01 6.05274048e+01 5.95017891e+01 5.75191078e+01 5.78284569e+01 5.90461922e+01 5.89476013e+01 5.78188019e+01 5.43699913e+01 5.15612373e+01 5.15279198e+01 5.23285294e+01 5.63642197e+01 5.59425697e+01 5.66343460e+01 5.66481972e+01 5.91771660e+01 5.89651985e+01 5.82194557e+01 5.72746964e+01 6.01891708e+01 6.00959015e+01 5.97479134e+01 5.90242538e+01 6.11193199e+01 6.35670242e+01 6.33231163e+01 6.40006638e+01 6.13151169e+01 6.05668907e+01 5.82454109e+01 5.86522942e+01 5.89116440e+01 6.21212044e+01 6.19633789e+01 6.15463066e+01 5.62981606e+01 5.70608749e+01 5.90740929e+01 6.01978149e+01 5.71452065e+01 5.58014526e+01 5.78751106e+01 6.14507446e+01 5.78922768e+01 5.76753159e+01 5.87134399e+01 6.08057518e+01 5.70546684e+01 5.50929871e+01 5.98485832e+01 6.04003220e+01 5.36463089e+01 4.79457741e+01 4.83365250e+01 4.72409859e+01 4.51100731e+01 4.80137825e+01 4.68415337e+01 4.47831039e+01 4.34863548e+01 4.97443962e+01 5.27546921e+01 5.00036469e+01 5.27550316e+01 5.70643883e+01 5.91213150e+01 5.63400040e+01 6.28930473e+01 7.29505920e+01 7.22309799e+01 6.49688644e+01 5.66930275e+01 5.30981522e+01 5.58105583e+01 5.54925652e+01 6.09977913e+01 5.62090988e+01 5.24726105e+01 4.86208458e+01 4.53645935e+01 3.80355949e+01 3.85264740e+01 4.73964005e+01 5.34432373e+01 5.14351082e+01 4.94064865e+01 5.10760803e+01 5.07381058e+01 4.51579590e+01 4.41498718e+01 4.06497040e+01 4.04869995e+01 4.55844650e+01 5.17892723e+01 5.79544678e+01 5.39849243e+01 5.02034492e+01 4.35351982e+01 4.14158669e+01 5.23296204e+01 6.05377960e+01 5.73585739e+01 4.59592514e+01 4.29691505e+01 4.31175003e+01 5.21057320e+01 5.19355621e+01 5.24269409e+01 5.15908012e+01 5.65592651e+01 7.31457825e+01 6.43206100e+01 6.44980392e+01 5.31572342e+01 6.14372368e+01 5.93197365e+01 5.40962791e+01 4.35417252e+01 4.94807968e+01 6.18220444e+01 6.60305252e+01 5.47133789e+01 4.76173859e+01 5.06884232e+01 6.68388214e+01 8.67351303e+01 8.53328781e+01 6.77966995e+01 3.98215103e+01 5.17776070e+01 7.14628983e+01 8.45146255e+01 7.07086258e+01 5.14873085e+01 5.05951767e+01 6.51971512e+01 7.54061508e+01 7.80355682e+01 7.09137421e+01 7.76484909e+01 9.03488922e+01 9.57399139e+01 7.93781662e+01 5.44123344e+01 4.86949844e+01 6.04616127e+01 6.49413757e+01 5.53902359e+01 4.47668152e+01 4.52118034e+01 6.58286972e+01 8.12613220e+01 8.03790741e+01 6.38951797e+01 4.09896698e+01 3.83232574e+01 4.05621834e+01 4.33708344e+01 3.11631260e+01 6.22377777e+00 1.35459673e+00 1.85034809e+01 4.11745949e+01 5.48768005e+01 6.02398529e+01 7.23281860e+01 7.23601532e+01 3.31160278e+01 -7.21032429e+00 -7.73126030e+00 2.19380951e+01 5.31975746e+01 4.96192627e+01 4.83677063e+01 2.97723274e+01 9.70837498e+00 1.28347054e+01 3.90280151e+01 6.48487778e+01 6.91783066e+01 7.57228317e+01 4.61784210e+01 1.24148655e+01 2.16887212e+00 2.79466209e+01 5.51622238e+01 7.06474152e+01 8.06910324e+01 8.61096725e+01 6.19325218e+01 5.00397415e+01 3.65563126e+01 3.40037613e+01 3.23734703e+01 2.83961868e+01 2.79297009e+01 2.79978371e+01 2.94154377e+01 2.36355705e+01 1.25884485e+01 8.20805168e+00 2.45750751e+01 4.59956474e+01 1.38936768e+02 1.75586563e+02 1.05453537e+02 3.14646626e+01 -2.06327377e+02 1.44113232e+03 2.54019824e+03 3.29325348e+02 -2.75204803e+02 -8.86899023e+03 -2.12220195e+04 -773293056. -5.49951642e+09 -238931136. -2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -2.46511590e+09 -162604928. -411763936. -674604352. -257204592. 69439952. 2.54077715e+04 1.18186709e+04 2.05919116e+03 1.35393542e+03 5.50576477e+02 3.58879974e+02 2.66666382e+02 2.18505920e+02 2.18814301e+02 2.40351883e+02 4.67941992e+03 3.21381055e+03 7.42064575e+02 3.16614227e+02 2.20831497e+02 1.81183777e+02 1.60631104e+02 1.26185966e+02 6.21248322e+01 4.19721527e+01 1.71590862e+01 1.65186501e+01 1.33334160e+00 6.77884281e-01 -3.11141038e+00 -1.00644293e+01 -1.74748993e+01 -2.62762737e+01 -1.72844162e+01 -1.56768322e+01 -2.38403854e+01 -2.82167740e+01 -3.29022179e+01 -1.64963856e+01 -7.39597893e+00 -3.14468384e+00 -1.37826729e+01 -2.20101604e+01 -3.48600159e+01 -3.78143921e+01 -2.61361485e+01 1.81013508e+01 5.31899109e+01 5.93482971e+01 3.74399071e+01 2.07405281e+01 1.17163906e+01 -2.32993937e+00 -1.97935060e-01 9.35696983e+00 1.52757053e+01 9.88239574e+00 -1.92855847e+00 -5.85589504e+00 -3.01324711e+01 -1.19161406e+01 6.52841139e+00 2.82365093e+01 4.36486740e+01 5.35530968e+01 6.01042938e+01 3.95206261e+01 2.52454243e+01 2.90367756e+01 1.87680912e+01 -1.00056524e+01 -2.09412899e+01 -1.15361919e+01 1.09642019e+01 9.95849895e+00 7.26188564e+00 2.93980217e+01 6.92930984e+01 6.67298660e+01 5.18651123e+01 2.95022717e+01 8.10818253e+01 1.25111023e+02 1.25514748e+02 9.43239594e+01 7.24031372e+01 8.26552048e+01 8.80786362e+01 7.35726471e+01 7.72892303e+01 9.60281677e+01 1.27013992e+02 1.12465607e+02 6.77160416e+01 2.18772469e+01 7.48359060e+00 6.83165216e+00 1.80424156e+01 3.30709763e+01 1.63370934e+01 -1.14648256e+01 5.78959846e+00 4.18038101e+01 5.49048424e+01 1.72137127e+01 -8.90955830e+00 3.85296402e+01 7.40836334e+01 6.95141144e+01 1.48308477e+01 -2.85524750e+01 -3.16215000e+01 -3.14795055e+01 -2.49067688e+01 -2.32766552e+01 -6.08692026e+00 -2.85447288e+00 -1.05512104e+01 -1.24297104e+01 2.04186916e+00 1.55155697e+01 1.42162266e+01 1.03637695e+01 8.20102024e+00 1.18171053e+01 9.07284737e+00 4.77550278e+01 8.93571930e+01 8.60590897e+01 4.82322845e+01 3.70747590e+00 4.64329071e+01 8.45825500e+01 8.97310486e+01 5.47743950e+01 2.70046139e+01 2.09000435e+01 1.38198547e+01 -4.22118950e+00 6.29008341e+00 1.08258429e+01 1.70072517e+01 -3.20113111e+00 -1.85821171e+01 -1.44492960e+01 7.67019844e+00 2.18494396e+01 1.56486988e+01 8.52379608e+00 1.37969484e+01 3.24404869e+01 7.90582962e+01 1.26858231e+02 1.23551056e+02 8.66664047e+01 4.11789703e+01 7.90862045e+01 1.18305962e+02 1.10882034e+02 5.13594170e+01 1.90477252e+00 8.56350422e+00 2.43499660e+01 3.12694302e+01 2.64031639e+01 2.47103500e+01 2.44887466e+01 1.45923166e+01 1.26694736e+01 3.88846855e+01 7.08647232e+01 6.46622391e+01 3.35158310e+01 -7.62987554e-01 -7.60222387e+00 -6.62310219e+00 3.00442200e+01 6.39564896e+01 5.83369865e+01 3.14631634e+01 1.47075682e+01 1.58400564e+01 -2.34303331e+00 2.29618511e+01 6.93953705e+01 8.25194855e+01 5.16139030e+01 1.68441734e+01 2.07054729e+01 2.44263515e+01 1.26585159e+01 3.87790370e+00 1.05138493e+01 1.41148205e+01 5.70912781e+01 9.35007172e+01 9.44250412e+01 4.94474602e+01 1.53226709e+01 2.94502048e+01 3.76767883e+01 6.78406143e+01 9.67361603e+01 9.08505707e+01 3.98257561e+01 -6.55553865e+00 1.70041764e+00 6.86554623e+00 1.33600330e+01 -6.27272427e-01 -1.22917671e+01 -1.93876305e+01 -1.95074959e+01 -1.39691601e+01 -1.57929945e+01 -1.83438187e+01 -1.55755119e+01 -3.89337387e+01 -6.23374748e+01 -7.39430466e+01 -7.01547318e+01 -4.86483040e+01 -4.63212662e+01 -4.32626572e+01 -4.53286133e+01 -4.11684570e+01 -3.46443214e+01 -4.36247826e+01 -3.50398445e+01 -2.71120472e+01 -2.77809010e+01 -4.66668015e+01 -5.22130928e+01 -4.56374817e+01 -3.61156807e+01 -3.65733566e+01 -3.81919746e+01 -2.68469143e+01 -2.93858242e+01 -1.12797079e+01 -2.67465210e+00 3.55653262e+00 -2.84965744e+01 -6.75122223e+01 -4.74886818e+01 1.35880165e+01 5.01616974e+01 4.01860275e+01 1.38768415e+01 1.95268905e+00 2.56546092e+00 1.82942963e+00 1.32575922e+01 1.28434658e+01 1.12713442e+01 3.74424386e+00 -7.28560448e+00 -2.04097710e+01 -2.73523216e+01 -1.79544468e+01 -5.07266665e+00 5.32318068e+00 3.72437406e+00 -1.26127768e+00 -4.05303526e+00 -1.62546024e+01 -2.09471378e+01 -2.91071339e+01 -1.32812977e+01 2.10356960e+01 5.65183983e+01 5.10156670e+01 2.79968338e+01 -9.69853878e+00 -1.51749630e+01 -2.29452457e+01 4.61068201e+00 2.86012478e+01 4.26877441e+01 4.82695351e+01 2.23275547e+01 1.06773138e+00 -3.09502716e+01 -2.11156254e+01 -1.21633463e+01 -7.43890095e+00 -1.64499645e+01 -2.01164036e+01 -2.94555111e+01 -1.96237621e+01 -4.86307764e+00 4.47792053e+00 1.07644329e+01 6.64114952e+00 4.15750809e+01 6.23825264e+01 5.34251366e+01 1.12703257e+01 -1.85778561e+01 -5.73846865e+00 5.60579443e+00 1.03013599e+00 -2.82823277e+00 2.00543041e+01 5.23087730e+01 5.04914589e+01 1.05644855e+01 -3.08905735e+01 -1.59896193e+01 1.89632252e-01 -1.84243369e+00 -2.54676628e+01 -3.10843735e+01 -2.43556271e+01 -7.41987848e+00 -1.82771072e+01 -4.11936455e+01 -4.88561935e+01 -4.34893990e+01 -3.39487839e+01 -4.82940559e+01 -2.62787857e+01 5.96103621e+00 1.49492645e+01 2.61995010e+01 4.63368073e+01 7.50394592e+01 7.16495514e+01 5.57054367e+01 6.03247948e+01 4.44133492e+01 3.74794044e+01 4.59101534e+00 -2.89087315e+01 -7.28158264e+01 -8.10256577e+01 -6.97586823e+01 -5.94629173e+01 -5.18438492e+01 -4.71741180e+01 -4.69151573e+01 -5.43680534e+01 -6.30243988e+01 -3.65002937e+01 5.74336863e+00 2.15203037e+01 1.39953690e+01 -1.43860130e+01 -2.63822746e+01 -2.79664154e+01 -4.49558411e+01 -2.97773800e+01 -3.07657185e+01 -1.34567747e+01 -2.77482486e+00 1.52966337e+01 4.20105705e+01 1.79561329e+01 -1.07638216e+01 -2.55984039e+01 7.01272917e+00 1.57301588e+01 4.12464237e+00 -3.08580265e+01 -7.17567968e+00 1.95219040e+01 3.35775452e+01 1.11430321e+01 -1.34117680e+01 1.33327684e+01 4.03965759e+01 3.12813320e+01 -1.46130657e+01 -4.12915955e+01 -1.43403835e+01 5.14453411e+00 -2.63043785e+01 -6.47147369e+01 -4.23070984e+01 1.20171824e+01 3.26888161e+01 1.80634022e+01 -3.06870770e+00 2.31100535e+00 2.50922260e+01 4.66161804e+01 3.27773094e+01 -7.78086042e+00 -4.44567375e+01 -4.12655830e+01 -3.37550049e+01 -2.85031872e+01 -3.34228973e+01 -3.35240860e+01 -2.54801998e+01 -7.18407726e+00 -5.00917101e+00 -2.44529037e+01 -3.16246834e+01 -2.85860233e+01 1.88259995e+00 1.27568378e+01 -2.49602318e+00 -1.58260393e+01 -3.60861740e+01 -3.11736679e+01 -3.62718430e+01 -4.15209618e+01 -5.22630310e+01 -4.93139725e+01 -9.79885960e+00 2.21199474e+01 -1.31944160e+01 -7.22905426e+01 -7.64643402e+01 -2.30860786e+01 -4.12016058e+00 -3.56668320e+01 -5.30487289e+01 -3.10093155e+01 -2.02996712e+01 -2.52793331e+01 -4.88402405e+01 -3.72407722e+01 -2.67268810e+01 -2.03149281e+01 -3.13756237e+01 -5.40077362e+01 -5.22131462e+01 -5.22686882e+01 -2.81676598e+01 -1.02509022e+01 -6.62455845e+00 -3.33975983e+01 -3.31437149e+01 1.21631899e+01 4.37347488e+01 2.99536324e+01 -1.62309208e+01 -1.85458221e+01 -5.48316193e+00 -1.97247753e+01 -6.07177124e+01 -7.29612961e+01 -4.63241653e+01 -2.11642780e+01 -2.69636459e+01 -3.50552750e+01 -2.70756092e+01 -2.21223984e+01 -2.45932884e+01 -3.00458164e+01 -4.42719307e+01 -5.38890800e+01 -6.19058418e+01 -4.90881424e+01 -4.02407646e+01 -3.01379604e+01 -2.93248844e+01 -2.41325302e+01 -1.02362852e+01 -1.01826468e+01 -2.37917843e+01 -4.05378113e+01 -3.49127045e+01 -1.47888803e+01 -1.29384546e+01 -1.40620947e+01 -8.02668190e+00 2.69904575e+01 4.44425430e+01 2.85179577e+01 -1.26549063e+01 -2.45928631e+01 -1.81897583e+01 -1.31961870e+01 -2.85692596e+01 -3.63498726e+01 -4.58615532e+01 -5.31645889e+01 -5.39222679e+01 -4.56455956e+01 -4.49334717e+01 -5.68998032e+01 -5.65704727e+01 -2.97083626e+01 -1.76190720e+01 -2.94867401e+01 -4.61572227e+01 -2.61463051e+01 -1.61303387e+01 -3.36551781e+01 -6.77407913e+01 -8.81769562e+01 -8.67220612e+01 -8.54315948e+01 -7.69921265e+01 -6.65046234e+01 -6.06447754e+01 -6.37639313e+01 -6.05747261e+01 -5.50740128e+01 -5.41569290e+01 -6.63114319e+01 -5.78777580e+01 -2.98715553e+01 -1.21973095e+01 -1.03595495e+01 -1.51493359e+01 -2.49940872e+01 -3.65482292e+01 -4.96125755e+01 -4.99953537e+01 -5.24461899e+01 -5.49420128e+01 -5.46901550e+01 -4.98410683e+01 -4.84015961e+01 -4.56759338e+01 -4.80000305e+01 -5.29859619e+01 -5.58098831e+01 -5.64987488e+01 -3.87150002e+01 -2.13176594e+01 -1.90525703e+01 -3.22114410e+01 -4.57278099e+01 -4.43313484e+01 -4.49792938e+01 -4.39681473e+01 -4.85552559e+01 -4.70669861e+01 -4.63873482e+01 -3.40814934e+01 -2.51186409e+01 -3.10747356e+01 -4.46874771e+01 -4.84861336e+01 -2.81024742e+01 -1.61609135e+01 -2.44188347e+01 -4.45867157e+01 -4.42894821e+01 -3.77214775e+01 -3.65594902e+01 -4.47406158e+01 -5.19067726e+01 -4.21505699e+01 -3.62368202e+01 -2.89457417e+01 -2.61653004e+01 -3.72061729e+01 -4.55130081e+01 -4.60550537e+01 -2.63588047e+01 -1.72462215e+01 -3.08318062e+01 -4.81924171e+01 -4.61814461e+01 -3.35535660e+01 -3.08944187e+01 -3.79249077e+01 -4.59759865e+01 -4.16574440e+01 -3.71462440e+01 -3.47338066e+01 -3.93908806e+01 -4.52129745e+01 -4.85847168e+01 -4.14453354e+01 -3.37558365e+01 -3.28344345e+01 -3.96157150e+01 -5.07285538e+01 -4.65580826e+01 -4.16837654e+01 -4.12674484e+01 -4.73686218e+01 -4.83932343e+01 -4.11728592e+01 -4.16611328e+01 -4.78881340e+01 -5.59661026e+01 -5.81766930e+01 -5.82805634e+01 -5.36540985e+01 -4.69330635e+01 -4.51435928e+01 -4.79897385e+01 -5.37160492e+01 -5.58944588e+01 -5.61727715e+01 -5.39282646e+01 -5.20550232e+01 -5.34333725e+01 -3.58220367e+01 -2.36136665e+01 -3.14509716e+01 -6.15985641e+01 -7.59395905e+01 -5.35344315e+01 -4.76816330e+01 -3.93508186e+01 2.82116528e+01 6.42539597e+01 -2.01881866e+01 -235291968. -9.32597852e+03 2.78443069e+10 -2.51446886e+09 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. 0. 0. 0. 1.05792151e+03 4.04661713e+02 5.35920792e+01 2.04015636e+01 -1.15044031e+01 -3.46831665e+01 -3.61384697e+01 -2.96637707e+01 -2.76397285e+01 -3.18435726e+01 -2.81826591e+01 -2.03269691e+01 -1.40366440e+01 -2.11138115e+01 -3.77452049e+01 -4.61858406e+01 -4.01470947e+01 -2.90130444e+01 -2.30788937e+01 -2.49863873e+01 -2.77530270e+01 -2.41891613e+01 -1.81703873e+01 -2.28292027e+01 -3.30354080e+01 -3.95315781e+01 -3.52344360e+01 -2.52392159e+01 -2.20992565e+01 -2.95721111e+01 -4.21542778e+01 -4.86954498e+01 -4.24991493e+01 -4.41674423e+01 -5.34654160e+01 -4.58016777e+01 -2.53006954e+01 -1.05704823e+01 -2.72322769e+01 -5.96625252e+01 -6.97702866e+01 -5.40408897e+01 -3.60574722e+01 -2.54197197e+01 -2.36535587e+01 -2.83452301e+01 -2.98252506e+01 -2.98156662e+01 -3.26841240e+01 -6.07402954e+01 -8.00055466e+01 -7.02746735e+01 -4.29907875e+01 -2.43266888e+01 -3.57053680e+01 -5.33475113e+01 -6.52833557e+01 -4.85403976e+01 -4.37724991e+01 -5.02080879e+01 -4.39214859e+01 -2.39870949e+01 -8.66708696e-01 -4.45294333e+00 -3.65974159e+01 -4.86057472e+01 -3.95293045e+01 -1.35585709e+01 -1.82017193e+01 -3.65782890e+01 -3.50770454e+01 -2.01700745e+01 -9.26382065e+00 -2.25326138e+01 -5.60765305e+01 -7.39935837e+01 -6.51139755e+01 -3.01127415e+01 -7.54775763e+00 -1.25092344e+01 -2.85586357e+01 -2.60257473e+01 -7.55684376e+00 -9.12752438e+00 -3.30996399e+01 -4.69617043e+01 -2.24766197e+01 1.07537832e+01 1.36601124e+01 -2.22077541e+01 -5.32269554e+01 -5.13518600e+01 -2.64912624e+01 -2.22384396e+01 -3.19190083e+01 -1.35448790e+01 2.43554802e+01 4.24668083e+01 1.49681416e+01 -3.69457664e+01 -6.77466202e+01 -5.39423523e+01 -2.13620720e+01 1.57771320e+01 4.05959702e+01 3.35033684e+01 2.44627495e+01 2.13911819e+01 1.53474197e+01 -2.03479710e+01 -5.32100372e+01 -3.32041359e+01 2.19571819e+01 4.82328987e+01 2.60220699e+01 -2.92432671e+01 -6.13281784e+01 -4.23550377e+01 -1.82330284e+01 -8.08132076e+00 -1.04695520e+01 1.34901018e+01 5.92238426e+01 6.22657242e+01 1.66331043e+01 -3.29669914e+01 -3.41431007e+01 -3.28987241e-01 2.29560986e+01 2.80723209e+01 1.35447035e+01 -5.70330143e+00 -2.16925659e+01 8.89800835e+00 2.30571404e+01 1.22871530e+00 -2.48443966e+01 -3.00664978e+01 -1.53427277e+01 -1.43755550e+01 -3.38557129e+01 -2.83901367e+01 -1.17200413e+01 1.05209484e+01 1.96060638e+01 -5.21796799e+00 -1.95884209e+01 -9.40711975e+00 1.68097706e+01 -1.09293044e+00 -7.46430511e+01 -1.11513626e+02 -5.86152878e+01 9.05090332e+00 1.21344357e+01 -2.71676350e+01 -5.07956314e+01 -4.00182266e+01 -4.01239777e+01 -6.71528931e+01 -1.02855156e+02 -1.09438065e+02 -8.77972717e+01 -4.08548164e+01 -8.81573582e+00 -3.26926346e+01 -5.15642891e+01 -4.40685768e+01 -1.45638123e+01 -3.12447472e+01 -9.98694077e+01 -8.99430389e+01 -6.16082535e+01 -2.32220192e+01 -6.19343147e+01 -1.43897568e+02 -1.85285843e+02 -1.49667618e+02 -6.16944885e+01 -2.18246441e+01 -2.86933842e+01 -2.23254509e+01 -6.48347616e-01 -1.54509268e+01 -7.67085571e+01 -1.44863052e+02 -1.43815109e+02 -8.32825394e+01 1.14563341e+01 4.63635674e+01 1.58387890e+01 -4.47543640e+01 -7.55423813e+01 -7.10519409e+01 -9.29976807e+01 -1.17787254e+02 -1.08311935e+02 -3.35501518e+01 1.91179523e+01 -5.39485741e+00 -1.04778450e+02 -1.43927689e+02 -9.17422638e+01 4.51348400e+00 3.36917381e+01 -1.12554588e+01 -6.34082222e+01 -3.78904343e+01 3.31051540e+00 -4.10973692e+00 -5.51209412e+01 -6.58860550e+01 -1.46215792e+01 5.54674644e+01 6.62501221e+01 2.88389397e+01 -2.08818741e+01 -2.15397625e+01 2.96838284e+00 1.35134315e+01 -1.09126873e+01 3.71870470e+00 3.55497398e+01 4.39507370e+01 3.86247520e+01 -7.16174126e-01 -1.49915981e+01 -1.87650347e+00 -1.56198406e+00 -5.93407011e+00 -4.16192894e+01 -1.29710827e+01 3.30805092e+01 5.71282578e+01 4.10844421e+01 -5.71168976e+01 -1.15410454e+02 -1.07730820e+02 6.35658932e+00 6.44008179e+01 7.05190201e+01 1.95351696e+01 -2.74460959e+00 2.52697601e+01 2.27787991e+01 -8.74672127e+00 -3.44638824e+01 -1.60527599e+00 2.70003395e+01 -2.80527935e+01 -1.04500824e+02 -9.65889053e+01 -5.03052940e+01 -2.11735210e+01 -4.83592796e+01 -1.06853241e+02 -5.73780479e+01 -1.46293001e+01 3.34203110e+01 1.32144480e+01 -4.78351517e+01 -8.05831375e+01 -9.78418503e+01 -3.28725014e+01 -1.21336861e+01 -7.84154224e+00 -6.66484909e+01 -6.68546219e+01 -6.59353027e+01 -7.13254471e+01 -1.04687744e+02 -1.23710632e+02 -5.36428108e+01 -5.31458330e+00 -1.32343292e+00 -7.17835464e+01 -7.43403625e+01 -4.10071869e+01 2.00045085e+00 3.24614563e+01 1.67289467e+01 1.88030682e+01 -4.02103958e+01 -7.21947479e+01 -9.73347168e+01 -8.77428055e+01 -6.73350296e+01 -3.74524422e+01 2.42470951e+01 6.05556335e+01 3.68788414e+01 -5.16416740e+01 -7.04315262e+01 -4.98096542e+01 -3.93633270e+01 -4.78975258e+01 -2.11543236e+01 7.97502518e+01 1.08525612e+02 5.92183266e+01 -4.90429535e+01 -7.36215286e+01 -3.66487007e+01 2.40640373e+01 4.63729553e+01 6.59467459e+00 1.62138712e+00 -1.99915180e+01 3.65835762e+01 6.54391479e+01 7.10894318e+01 2.27981377e+01 -9.14060020e+00 2.81973267e+01 7.65313034e+01 4.86007195e+01 -1.02657290e+01 5.64290905e+00 4.92622108e+01 5.36651001e+01 2.27538128e+01 2.52703056e+01 9.21571579e+01 1.11208473e+02 7.33434296e+01 4.36094046e+00 -3.68650764e-01 2.98674355e+01 5.29873505e+01 4.17159004e+01 6.74042797e+00 1.44135637e+01 1.63185425e+01 6.82619553e+01 9.41909103e+01 9.50032349e+01 6.19024467e+01 4.35696411e+01 7.19598923e+01 1.05064110e+02 8.03754349e+01 1.07758760e+01 -1.07245407e+01 -9.09498882e+00 -2.72090855e+01 -8.45603409e+01 -6.56567230e+01 -9.14354146e-01 1.06035385e+01 -3.69463730e+01 -1.00572411e+02 -3.58966293e+01 3.09905624e+00 3.26190681e+01 6.45074539e+01 7.05996170e+01 3.83781738e+01 -6.42918243e+01 -8.25073547e+01 -4.26448059e+00 6.45692673e+01 2.96699429e+01 -6.28072433e+01 -1.11671028e+02 -5.17731514e+01 -3.42801523e+00 -1.53067818e+01 -5.07379074e+01 -9.76907043e+01 -1.39260681e+02 -2.00879898e+02 -1.77615555e+02 -1.08132523e+02 -8.61878357e+01 -1.16792007e+02 -1.57153412e+02 -7.79819870e+01 -3.28020477e+01 3.92898893e+00 -9.35221577e+00 -1.77574635e+01 -7.12630234e+01 -1.82569000e+02 -2.13427521e+02 -1.20673668e+02 4.59361191e+01 8.81586227e+01 -4.49743118e+01 -1.69902405e+02 -1.79797775e+02 -8.68254700e+01 -3.28898659e+01 -6.30118675e+01 -1.36275513e+02 -1.77372742e+02 -1.32224182e+02 -2.10998306e+01 1.13874664e+01 -4.34202805e+01 -1.22371666e+02 -2.10131653e+02 -2.11434174e+02 -1.76780365e+02 -6.25524139e+01 5.17863159e+01 9.48486862e+01 2.51421452e+01 -1.20374893e+02 -1.97937851e+02 -1.25883797e+02 -1.25765409e+01 -2.19171772e+01 -1.45738586e+02 -2.48278336e+02 -1.94264572e+02 -5.21668739e+01 4.68738861e+01 4.95064354e+01 -3.68469009e+01 -1.00080025e+02 -1.56362091e+02 -8.82054291e+01 -5.47027130e+01 -1.75168247e+01 -6.58691025e+01 -9.78949738e+01 -4.33746109e+01 1.28701792e+01 1.01246651e+02 1.13688759e+02 6.44296265e+01 -1.59017849e+01 -1.38475082e+02 -1.56728134e+02 -8.26635742e+01 8.12344971e+01 1.51888748e+02 7.99934311e+01 -7.80194626e+01 -1.64572144e+02 -1.25138771e+02 -5.52887497e+01 -5.46962585e+01 -1.03227066e+02 -1.37533127e+02 -1.40960571e+02 -5.71378899e+01 1.29321346e+01 7.45850983e+01 7.01147537e+01 2.53038158e+01 -2.27233620e+01 -7.84603424e+01 -6.98503494e+01 -1.11623230e+01 5.05581589e+01 4.80214233e+01 -1.84099331e+01 -9.67849503e+01 -5.87734604e+01 1.47935562e+01 5.05801315e+01 -1.45832891e+01 -1.24905396e+02 -1.17754639e+02 -4.69076118e+01 6.26879120e+01 6.56529922e+01 -1.81274796e+01 -8.59659882e+01 -1.37406570e+02 -5.64558067e+01 -2.28806286e+01 2.26148739e+01 3.60058441e+01 4.53967705e+01 5.17492638e+01 3.14243722e+00 2.36941757e+01 6.64902267e+01 6.13312454e+01 3.62602162e+00 -9.26153259e+01 -1.36063766e+02 -8.19250259e+01 4.99024429e+01 1.67724106e+02 1.52563293e+02 1.66233044e+01 -1.17141449e+02 -1.57963028e+02 -6.25788727e+01 5.84011612e+01 8.31374512e+01 9.71205330e+00 -7.96297455e+01 -4.71183777e+01 1.97766781e+01 7.68184509e+01 8.65721130e+01 5.77080688e+01 3.29246879e+00 -6.23000374e+01 -5.45071297e+01 1.01307878e+01 1.11843254e+02 1.28569855e+02 5.24937592e+01 -5.17597275e+01 -4.31661453e+01 3.77873917e+01 9.63636322e+01 6.52879791e+01 1.87502041e+01 -5.57175827e+00 -1.75837212e+01 1.85981979e+01 4.23162575e+01 1.22487402e+01 -1.49554644e+01 -4.63906212e+01 3.52222323e+00 4.55475540e+01 1.01587708e+02 1.37855499e+02 9.54891129e+01 5.24582329e+01 -2.25320892e+01 -5.11630669e+01 -8.02947140e+00 6.09954643e+01 7.22178040e+01 -6.80680561e+00 -8.43963699e+01 -7.61664886e+01 -3.01618671e+01 5.24174805e+01 7.61442871e+01 5.27544975e+01 9.01027298e+00 -1.84024429e+01 4.19634705e+01 9.74208298e+01 1.64690216e+02 1.47144485e+02 7.27875061e+01 6.65111923e+01 9.88272552e+01 1.69935135e+02 1.89797943e+02 1.60828796e+02 1.07516884e+02 9.85518837e+00 -2.73046684e+01 -2.12862182e+00 7.71592560e+01 1.11145729e+02 4.93624420e+01 -2.48042164e+01 -2.34714165e+01 6.29004440e+01 1.28574661e+02 1.06792152e+02 1.89740334e+01 -5.55483551e+01 -6.03983269e+01 6.36878347e+00 9.00453720e+01 1.12514488e+02 1.04509293e+02 7.81034470e+01 4.85151672e+01 5.22455215e+00 4.26015794e-01 2.35849075e+01 3.98982124e+01 4.06682777e+00 -7.60905075e+01 -1.17162674e+02 -5.03696709e+01 4.93126068e+01 9.80636749e+01 3.41709557e+01 -5.54476013e+01 -7.31139526e+01 -1.76507015e+01 7.52173309e+01 9.07103729e+01 3.45448036e+01 3.82800150e+00 -1.10783958e+01 4.26231613e+01 5.43202477e+01 4.87075653e+01 3.10243378e+01 -1.55323019e+01 1.85745239e-01 1.36983814e+01 8.34559479e+01 1.41210648e+02 1.16253845e+02 8.17242279e+01 2.52108359e+00 -1.27423429e+01 -1.02639747e+00 8.51336060e+01 1.73651642e+02 1.82956406e+02 1.11931442e+02 5.13374672e+01 2.58663605e+02 2.61807648e+02 1.16233101e+02 1.91789404e+03 2.69793237e+03 6.23405322e+03 2.10859531e+04 -1181876096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 9.54779688e+03 3.64835889e+03 3.75939423e+02 2.74183167e+02 1.82649750e+02 1.61292313e+02 9.44191818e+01 6.82328110e+01 -1.69039841e+01 -1.62241974e+01 2.07127113e+01 7.86139450e+01 6.71061707e+01 -6.74936354e-01 -5.82386017e+01 -6.82577286e+01 -6.41853809e+00 6.88895493e+01 8.43264542e+01 1.96210384e+01 -3.85324669e+01 -4.03453255e+01 1.11315804e+01 7.41955757e+00 -2.64106750e+01 -3.27028847e+01 -2.95361471e+00 3.83653564e+01 4.06554680e+01 5.22916832e+01 7.20885849e+01 6.79148865e+01 3.14917641e+01 -4.18931122e+01 -4.27743454e+01 9.22959685e-01 4.65802765e+01 4.20460358e+01 -7.27324724e+00 -6.09385185e+01 -5.21146927e+01 1.96718216e+01 1.05724327e+02 9.64938278e+01 1.57314348e+01 -2.87149239e+01 -3.01960239e+01 1.46678247e+01 2.91217556e+01 3.68586617e+01 4.45656166e+01 3.23625793e+01 1.31801176e+01 -3.65288658e+01 -1.75581017e+01 2.39347134e+01 4.30501862e+01 1.12698250e+01 -4.09154129e+01 -4.11194382e+01 -1.58078337e+01 2.86110821e+01 4.60701218e+01 4.07191849e+00 -5.43787498e+01 -9.62317429e+01 -7.04226379e+01 -9.13049221e+00 1.15697765e+01 -2.21306915e+01 -4.67393799e+01 -3.98432388e+01 1.22520885e+01 2.30233212e+01 8.34300327e+00 -1.60433788e+01 -1.34593830e+01 -1.04572992e+01 -2.36263180e+01 -5.74873161e+00 2.53052025e+01 4.08844223e+01 5.46963978e+00 -4.74987907e+01 -5.54476585e+01 -3.60557518e+01 4.69277334e+00 3.20692062e+01 3.63544083e+01 5.35312176e+00 -1.91443539e+01 -1.49226208e+01 3.39517555e+01 5.25087852e+01 1.74642086e+01 -1.56594429e+01 -1.36591187e+01 3.27888336e+01 5.08545837e+01 4.54582100e+01 3.98637505e+01 3.30773048e+01 1.71455688e+01 -1.97589951e+01 -1.67964630e+01 1.24199505e+01 3.51922455e+01 3.45754662e+01 7.46361303e+00 4.86614466e+00 2.11577110e+01 3.42583847e+01 5.11084137e+01 4.49493408e+01 1.97744980e+01 -8.29396439e+00 -1.45645800e+01 2.30994682e+01 4.14181976e+01 2.57674751e+01 1.58074074e+01 1.26748295e+01 3.08762379e+01 2.81574821e+01 2.68289547e+01 3.76194229e+01 4.05951233e+01 3.61759605e+01 3.82038093e+00 3.93255687e+00 2.48642330e+01 4.45711403e+01 4.19238815e+01 2.33535786e+01 2.25222988e+01 3.82601204e+01 4.82006264e+01 6.26066132e+01 4.92982063e+01 2.78117161e+01 7.75624514e+00 1.14474983e+01 3.19547749e+01 3.47757988e+01 2.58762112e+01 2.49749832e+01 3.05952759e+01 4.68120384e+01 5.41350937e+01 6.07419701e+01 6.11227150e+01 4.90615005e+01 3.48751717e+01 1.41074753e+01 8.56686592e+00 1.26294632e+01 2.49189987e+01 2.54293365e+01 1.18542242e+01 -4.93676543e-01 7.44276333e+00 3.07397881e+01 4.69402847e+01 4.55515099e+01 2.44884109e+01 1.35550718e+01 1.52897882e+01 2.76422901e+01 3.00846596e+01 2.43024559e+01 2.51603470e+01 2.38037491e+01 2.24121532e+01 2.16543598e+01 3.05304317e+01 4.21470222e+01 4.11605530e+01 3.62641983e+01 2.79153214e+01 2.31696415e+01 2.12327728e+01 2.55855446e+01 2.60317440e+01 1.88043652e+01 1.10236492e+01 1.63221970e+01 2.77167664e+01 3.72655182e+01 3.71521034e+01 2.93300209e+01 2.67036915e+01 2.56713810e+01 3.23432922e+01 3.15307617e+01 2.68889332e+01 2.14659882e+01 1.87707653e+01 1.93243389e+01 1.63596497e+01 1.89493179e+01 2.46435490e+01 2.92789860e+01 2.94267731e+01 2.56470375e+01 2.53927193e+01 2.78167648e+01 3.13911076e+01 3.40140266e+01 3.19914551e+01 2.77393150e+01 2.48124619e+01 2.62459488e+01 2.89107876e+01 2.91555748e+01 2.82532749e+01 2.81011925e+01 2.82737770e+01 2.86078129e+01 2.86137447e+01 2.84118919e+01 2.82635479e+01 2.83283577e+01 2.89195156e+01 3.03097134e+01 3.11281414e+01 3.08466091e+01 2.97676315e+01 2.93595867e+01 2.95627232e+01 2.84011002e+01 2.67935867e+01 2.60689774e+01 2.66745396e+01 2.93015366e+01 2.96990833e+01 3.04594841e+01 2.97948208e+01 2.79522781e+01 2.71971760e+01 2.74463692e+01 3.07746525e+01 3.17796936e+01 3.00220699e+01 2.73060608e+01 2.73420830e+01 2.93679447e+01 3.11250229e+01 3.00839939e+01 2.84166489e+01 2.82225761e+01 2.78004189e+01 2.87408581e+01 2.66054134e+01 2.74115753e+01 2.69707222e+01 2.96515160e+01 2.74059296e+01 2.55601063e+01 2.45487957e+01 2.56078606e+01 2.68003101e+01 2.42003307e+01 2.23373966e+01 2.28261681e+01 2.16133728e+01 2.22064648e+01 2.32804565e+01 2.69325848e+01 2.51672802e+01 2.46699333e+01 2.38000889e+01 2.50231953e+01 2.32849216e+01 2.19604549e+01 2.23980675e+01 2.18557281e+01 2.25947781e+01 2.48666286e+01 2.55987854e+01 2.40921612e+01 2.27823238e+01 2.08619347e+01 2.19937782e+01 1.80296555e+01 2.04020576e+01 1.81883793e+01 2.08869343e+01 2.03936386e+01 2.58684063e+01 3.37985268e+01 3.66841278e+01 3.30782967e+01 2.74080448e+01 2.34061737e+01 2.71538372e+01 2.62000408e+01 3.00288029e+01 2.71668377e+01 2.29209270e+01 2.10752754e+01 2.48234997e+01 2.84427414e+01 2.55099411e+01 2.39932747e+01 2.70468941e+01 2.68738575e+01 2.07470951e+01 2.34863739e+01 2.86796761e+01 3.60525894e+01 3.41340027e+01 3.45022240e+01 2.55108585e+01 1.65300255e+01 3.52340102e+00 5.91382623e-01 5.71889639e+00 1.54927702e+01 2.14232788e+01 2.39360905e+01 2.41575165e+01 2.80177231e+01 1.73290825e+01 5.45323324e+00 7.18616009e+00 1.94297085e+01 3.04071274e+01 2.84600410e+01 2.55646038e+01 2.98100357e+01 3.23805428e+01 3.20922394e+01 3.00517445e+01 3.21665878e+01 3.34860458e+01 2.53064022e+01 2.05080147e+01 2.62223587e+01 4.17771225e+01 5.73410645e+01 5.78275681e+01 4.97155075e+01 3.35592041e+01 3.68640671e+01 4.00154266e+01 4.08310089e+01 3.83454285e+01 3.33038406e+01 4.50084915e+01 5.21975174e+01 5.51748161e+01 3.57569733e+01 2.10089760e+01 1.41240845e+01 2.93677101e+01 4.88627281e+01 6.78852234e+01 5.30822372e+01 2.46939411e+01 1.47697191e+01 2.05699577e+01 3.69887619e+01 3.82181854e+01 5.71282921e+01 6.43826828e+01 5.93068886e+01 4.32018127e+01 2.90674133e+01 2.14746704e+01 2.55201893e+01 3.67422905e+01 5.27964439e+01 5.29794044e+01 3.79783859e+01 2.65796509e+01 1.77180119e+01 1.95544720e+01 1.61136818e+01 1.08315935e+01 8.81567669e+00 1.47204132e+01 2.05326900e+01 2.58683147e+01 1.97112637e+01 1.64717865e+01 1.66652489e+01 2.65445862e+01 2.12157803e+01 1.25036116e+01 2.33201046e+01 3.69805183e+01 3.21886902e+01 4.41619205e+00 -6.65588570e+00 1.01734123e+01 2.18688431e+01 2.57265301e+01 2.91366959e+01 4.38307800e+01 4.55828743e+01 5.36481590e+01 4.76253891e+01 4.51088715e+01 2.73010349e+01 2.53645039e+01 3.48099289e+01 3.18670902e+01 2.63524990e+01 1.69812565e+01 1.48078289e+01 1.11697941e+01 3.83295593e+01 6.31775665e+01 7.33635406e+01 4.24013367e+01 2.63711090e+01 1.69281063e+01 1.64662247e+01 1.11152163e+01 1.00431852e+01 1.90832996e+01 9.02765274e+00 -7.75781441e+00 -2.79142590e+01 -2.58216152e+01 -1.34205523e+01 9.17588234e+00 8.74879837e+00 4.53037071e+00 -3.37463951e+00 -8.01548302e-01 6.58337784e+00 -2.06952839e+01 -4.88297844e+01 -4.86439514e+01 -1.45730505e+01 2.69918823e+01 2.99131908e+01 4.27263308e+00 -3.74316864e+01 -1.36854935e+02 -4.07835449e+02 -5.74423279e+02 -6.10184387e+02 -7.69916992e+02 -2.84964917e+03 -4.11768750e+03 -3.16083221e+02 -2.96124783e+01 3.29325348e+02 -2.75204803e+02 -8.86899023e+03 -2.12220195e+04 -773293056. -5.49951642e+09 -238931136. -2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.22521787e+04 -5.72014111e+03 -8.77440674e+02 -5.78614563e+02 -2.38433914e+02 -1.58199478e+02 -9.11446609e+01 -1.97648087e+01 -2.45637169e+01 -2.52340508e+01 -1.58508902e+01 -2.06552753e+01 -4.39435387e+01 -7.32193298e+01 -4.22319756e+01 3.60656905e+00 1.10533466e+01 -2.43756618e+01 -5.62304649e+01 -3.41675758e+01 -2.32390480e+01 -2.08269939e+01 -2.89411392e+01 -4.57229347e+01 -4.44354630e+01 -3.94279099e+01 -2.03450527e+01 -2.09273930e+01 -1.33449335e+01 -1.24208145e+01 2.30273609e+01 5.51873970e+01 5.67818413e+01 3.30472488e+01 1.16707373e+01 1.81712551e+01 3.78391685e+01 4.50635796e+01 5.85875664e+01 6.32385902e+01 6.10464401e+01 7.07136383e+01 7.14669495e+01 6.50952225e+01 5.37339821e+01 4.41844978e+01 5.00645866e+01 4.49265137e+01 4.21839027e+01 4.60467415e+01 4.79779091e+01 6.14074974e+01 6.82979584e+01 5.82520599e+01 1.68276901e+01 -3.33942261e+01 -5.29891243e+01 -3.58786201e+01 -8.26216316e+00 1.07700472e+01 -7.67935848e+00 -3.19606476e+01 -2.45047836e+01 1.04280529e+01 4.96201324e+01 4.98336716e+01 4.63703423e+01 6.03344345e+01 1.00414619e+02 7.31590271e+01 2.53133030e+01 -2.42337971e+01 -1.45280275e+01 1.22197056e+01 1.38358841e+01 2.59061718e+01 3.30057411e+01 4.22968369e+01 3.22174492e+01 1.65948391e+01 -9.04789925e+00 -1.42135525e+01 -1.43740396e+01 4.22833443e+00 1.48523641e+00 -3.04878159e+01 -7.13823471e+01 -6.06988716e+01 -2.75371914e+01 4.23852825e+00 -6.40671301e+00 -2.65083523e+01 -4.98956947e+01 -6.13474159e+01 -3.15261307e+01 1.76010933e+01 2.22205811e+01 1.04623928e+01 -3.48017120e+01 -2.18384304e+01 -1.88408546e+01 7.04172754e+00 1.81406040e+01 7.83734989e+00 7.33956242e+00 2.64156151e+00 1.35596876e+01 2.76688409e+00 2.55926275e+00 2.63303566e+00 -1.59516535e+01 -4.99796371e+01 -5.08333588e+01 -1.96149254e+01 2.51471863e+01 3.59751358e+01 4.33434105e+01 3.26174316e+01 3.89434814e+01 4.76742058e+01 5.46191978e+01 1.05109453e+01 -5.04242134e+01 -6.48798523e+01 -3.82398872e+01 8.00533390e+00 3.05995312e+01 4.79304771e+01 4.97349281e+01 2.83491611e+01 1.84776058e+01 2.87895775e+01 2.02417278e+01 1.76768112e+01 1.13024664e+01 1.82295513e+01 1.24508352e+01 1.03295765e+01 -2.16411591e-01 2.08028650e+00 -1.77367246e+00 1.00984955e+00 -4.10353374e+00 -6.97308969e+00 -1.18081694e+01 -1.00519257e+01 -9.55738926e+00 5.20446539e+00 1.08014307e+01 1.78968525e+01 1.05037909e+01 1.61748028e+01 2.08236713e+01 3.13561611e+01 1.48615713e+01 -4.29265823e+01 -7.81502686e+01 -8.40872269e+01 -6.33628044e+01 -4.08737221e+01 -3.24687004e+01 -1.69642925e+01 -7.97806358e+00 -2.19314537e+01 -2.11530113e+01 -2.43065128e+01 -1.16048574e+01 -1.57846680e+01 -6.73455191e+00 3.97334099e+01 8.07926025e+01 1.06660080e+02 9.39984055e+01 4.87191620e+01 7.94957829e+00 -3.54886093e+01 -2.51994209e+01 -1.59694281e+01 2.44283819e+00 -6.02794945e-01 3.47993541e+00 -8.07318401e+00 -1.58218062e+00 1.23078156e+00 -1.67569682e-01 -9.45049095e+00 -8.52441597e+00 -3.70991302e+00 -1.04503942e+00 -1.63878632e+01 -2.33065205e+01 -2.64174728e+01 -2.46008835e+01 -1.83309155e+01 2.00848618e+01 6.37195702e+01 9.10269699e+01 8.86553116e+01 8.28139725e+01 8.81090546e+01 5.54411926e+01 9.33486557e+00 -3.52560921e+01 -4.41580124e+01 -3.38846092e+01 -1.95705853e+01 -1.54636936e+01 -2.46551037e+01 -4.29270782e+01 -3.33514137e+01 -2.46538048e+01 -1.14975796e+01 -1.46666965e+01 -2.05185204e+01 -5.39896088e+01 -9.60015106e+01 -7.90527267e+01 -4.72122917e+01 -3.61528659e+00 1.17292185e+01 2.95876141e+01 6.57101135e+01 9.28308029e+01 8.45033493e+01 5.55144386e+01 8.39370155e+00 2.38902931e+01 3.65119362e+01 4.28816299e+01 3.29771004e+01 2.02022572e+01 3.20480614e+01 3.68454018e+01 3.76309166e+01 2.39749393e+01 6.17811155e+00 7.66255426e+00 3.31361427e+01 7.68270340e+01 1.11415085e+02 1.30078644e+02 5.78950386e+01 -1.45091085e+01 -5.89630394e+01 -3.44523811e+01 2.93550825e+00 -9.99094427e-01 1.57266569e+01 2.83653116e+00 7.15245157e-02 -1.35526934e+01 -1.57417850e+01 -1.36491432e+01 -1.09788446e+01 -8.37767601e+00 -4.29884529e+01 -8.48065491e+01 -9.62714996e+01 -6.66981735e+01 -3.75774384e+01 -1.16002245e+01 1.19184589e+01 2.06981697e+01 1.67550755e+00 -5.01486349e+00 9.90779877e+00 1.20191660e+01 -8.72367477e+00 -3.16409512e+01 -3.53279381e+01 -3.50265236e+01 -3.31030045e+01 -2.52255993e+01 -2.06378918e+01 -9.53299141e+00 -1.87255459e+01 -2.65747890e+01 -4.14836884e+01 -4.34559097e+01 -3.65341797e+01 4.16948199e-01 4.65082970e+01 3.90257378e+01 3.92719388e+00 -3.56932831e+01 -1.71867752e+01 -9.16623402e+00 -2.59310484e+00 -3.18095565e+00 6.31353807e+00 8.09231091e+00 3.29605827e+01 4.70399513e+01 4.38144531e+01 4.04246712e+00 -3.19497910e+01 -3.09921188e+01 -2.38723640e+01 -4.04589043e+01 -7.62027817e+01 -8.29375153e+01 -7.15613556e+01 -4.18475800e+01 -4.73835030e+01 -4.76779022e+01 -4.33434753e+01 -3.71265182e+01 -2.91287708e+01 -3.49908257e+01 -4.12668953e+01 -3.75155258e+01 -3.15086708e+01 -3.46539154e+01 -4.16515427e+01 -4.06340942e+01 -3.18280926e+01 -2.40666509e+00 2.71965504e+01 2.29405842e+01 4.17905617e+00 -1.49811983e+01 -7.89835310e+00 -1.61783028e+01 -3.50807571e+01 -3.39209175e+01 6.02063227e+00 4.34588966e+01 4.77619705e+01 1.31899853e+01 -1.16331825e+01 -9.78919506e+00 -4.32867956e+00 -5.04490376e+00 -8.53150463e+00 1.40421133e+01 5.12945595e+01 5.33816719e+01 2.69723454e+01 -2.03242397e+01 -1.43034763e+01 -1.22924213e+01 -3.28170109e+00 -1.15875788e+01 -1.15114708e+01 -3.17162323e+00 9.09413052e+00 1.48173351e+01 5.46637630e+00 3.12781006e-01 -7.62280762e-01 3.18055477e+01 7.38144684e+01 8.10552444e+01 4.80172691e+01 4.81862593e+00 -6.37932348e+00 -1.44172201e+01 -1.01621132e+01 1.55593741e+00 4.06111259e+01 6.75128555e+01 9.69858170e+01 9.97249451e+01 6.44236298e+01 3.57146149e+01 -5.94058132e+00 2.16680470e+01 4.20098801e+01 1.66134872e+01 -4.32190666e+01 -7.48658066e+01 -5.00452271e+01 -1.52726641e+01 -1.94286423e+01 -1.99687634e+01 -2.59951630e+01 -2.81059952e+01 -3.35413971e+01 -3.45747833e+01 -3.69829826e+01 -4.25254097e+01 -3.97477684e+01 -3.86864929e+01 -3.77041473e+01 -4.06280823e+01 -3.77463303e+01 -2.04971638e+01 4.92445517e+00 2.75423503e+00 -2.14745312e+01 -5.33554802e+01 -2.81119709e+01 9.05647087e+00 -1.36092281e+01 -7.22997360e+01 -7.85530472e+01 -1.10026779e+01 3.62194977e+01 1.68235664e+01 -1.66155357e+01 5.59611440e-01 3.14527626e+01 3.63105392e+01 2.02162380e+01 -4.88074684e+00 -4.65964222e+00 -8.07385683e-01 -1.04589128e+01 -1.12560139e+01 -3.58947334e+01 -5.29984093e+01 -2.26871471e+01 2.39278336e+01 5.08064232e+01 2.99329853e+01 9.62246799e+00 2.75084915e+01 4.19768410e+01 4.78232117e+01 3.16183987e+01 4.28492403e+00 2.79301739e+00 3.40791798e+00 1.25653744e+01 3.43871522e+00 1.45424738e+01 3.30750694e+01 4.06783867e+01 3.44163589e+01 4.98861504e+00 -1.25325584e+01 -2.51682281e+01 -2.37535362e+01 -1.66098309e+01 -5.22021713e+01 -9.15256958e+01 -8.47702866e+01 -3.39087219e+01 4.01143980e+00 -5.08837605e+00 -2.43386135e+01 -6.10230494e+00 2.19928493e+01 2.34620628e+01 5.68574286e+00 -2.20819740e+01 -2.71483669e+01 -2.61849918e+01 -2.37284737e+01 -1.91331234e+01 -2.19945660e+01 -1.56700478e+01 -5.56546354e+00 9.43906128e-01 -7.01374578e+00 -1.85775013e+01 -2.45610790e+01 -2.90706005e+01 -2.77686348e+01 -4.86653862e+01 -6.63034821e+01 -4.95748520e+01 -2.80933428e+00 1.94559460e+01 -2.40746331e+00 -3.14529877e+01 -4.83836746e+01 -5.62661781e+01 -5.59056625e+01 -5.04475975e+01 -4.20610123e+01 -4.46515884e+01 -3.76075745e+01 -4.07904472e+01 -4.22955818e+01 -4.80352173e+01 -5.36542778e+01 -5.45433540e+01 -4.38951721e+01 -3.22506371e+01 -3.43730698e+01 -4.70711594e+01 -5.36686478e+01 -4.13875427e+01 -3.02527618e+01 -2.34433880e+01 -1.39492493e+01 5.95027637e+00 6.49982882e+00 -2.57348442e+00 -8.49670219e+00 2.33053894e+01 4.43566132e+01 2.94065361e+01 2.96067309e+00 5.75849295e+00 2.70930214e+01 3.25873299e+01 1.35714312e+01 -4.07117271e+00 -7.50464344e+00 -7.61710072e+00 -2.26164317e+00 -1.10433951e-01 -6.42743051e-01 -8.29527283e+00 -2.35843587e+00 1.42089577e+01 2.07149105e+01 1.10443020e+01 -7.83675766e+00 -5.46728373e+00 5.75176191e+00 -7.10788918e+00 -2.88759747e+01 -4.31778221e+01 -3.40916672e+01 -2.52045670e+01 -2.92002831e+01 -2.94158955e+01 -2.82717552e+01 -2.74727173e+01 -2.96935940e+01 -2.79932137e+01 -2.54073086e+01 -2.79508953e+01 -3.12022305e+01 -3.42456207e+01 -3.27570877e+01 -2.85848618e+01 -2.98109055e+01 -1.78336372e+01 -9.73954964e+00 -1.01242151e+01 -2.40522957e+01 -3.72444229e+01 -3.97160149e+01 -3.84090691e+01 -4.61997490e+01 -5.69531937e+01 -5.78050156e+01 -5.05884476e+01 -4.02013321e+01 -3.78046608e+01 -3.53539162e+01 -2.15265331e+01 -8.04987144e+00 -4.45356083e+00 -1.32670498e+01 -2.24827442e+01 -2.34108715e+01 -2.63756790e+01 -2.83733864e+01 -2.55953465e+01 -3.05312405e+01 -4.03449402e+01 -3.76173630e+01 -2.59423008e+01 -1.68632355e+01 -2.26055431e+01 -2.21302299e+01 -7.34201813e+00 2.42836356e+00 -1.39197445e+00 -1.73901215e+01 -2.20179195e+01 -1.70817795e+01 -1.52530060e+01 -2.02497787e+01 -3.03945980e+01 -2.89654655e+01 -2.37342396e+01 -2.09152050e+01 -2.39542370e+01 -3.04207535e+01 -3.41176224e+01 -3.63244858e+01 -3.62669334e+01 -3.36913109e+01 -3.36600151e+01 -3.49157906e+01 -3.04902515e+01 -2.58298206e+01 -2.31411514e+01 -2.70265503e+01 -3.07355671e+01 -2.98073158e+01 -2.60272198e+01 -2.89698830e+01 -4.63548317e+01 -5.82360573e+01 -7.67257919e+01 -7.31645508e+01 -3.32907806e+02 -5.20019348e+02 3.08823090e+02 1.61219818e+02 -2.47894379e+02 -1.19210823e+02 -2.80282745e+02 -2.28746143e+03 -2.01881866e+01 -235291968. -9.32597852e+03 2.78443069e+10 -2.51446886e+09 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. 2.45095987e+09 3.12392163e+03 9.21575562e+02 1.50072800e+02 1.18151878e+02 2.41381729e+02 1.37861237e+02 -2.01631241e+01 1.59348984e+01 2.69002171e+01 6.96721497e+01 6.49804840e+01 4.77839241e+01 1.94057312e+01 1.40688591e+01 2.47564621e+01 2.99009056e+01 5.53621063e+01 7.22340851e+01 4.75311775e+01 1.22892923e+01 -3.52356219e+00 -9.09428024e+00 -6.22231245e+00 -8.64434242e+00 -1.84333668e+01 -1.82782001e+01 -1.16679983e+01 -4.15941191e+00 -1.20271997e+01 -2.98901501e+01 -3.37360420e+01 -2.05194340e+01 -4.96627045e+00 2.24137592e+00 4.60089684e-01 5.30655098e+00 1.33604183e+01 1.79199104e+01 6.59465742e+00 -2.42548637e+01 -4.13203392e+01 -3.32776833e+01 -1.09533520e+01 3.40763235e+00 2.84741497e+00 -3.45908117e+00 -1.38092661e+01 -7.85573339e+00 -1.24274607e+01 -1.57725248e+01 -1.34286213e+01 8.12330246e+00 3.32159843e+01 3.08615627e+01 -4.27890396e+00 -2.44305439e+01 -1.64944477e+01 6.31381321e+00 4.37183523e+00 -1.47467060e+01 -1.61940289e+01 3.89658141e+00 2.61871033e+01 2.01728153e+01 -1.53242636e+01 -3.89990082e+01 -2.95965176e+01 -9.05066395e+00 -4.04387045e+00 -1.18715858e+01 -1.04013424e+01 6.95793533e+00 2.36573715e+01 1.58007545e+01 4.81744576e+00 9.09819794e+00 2.50886307e+01 3.03112354e+01 2.35450096e+01 7.22904921e+00 -9.46548843e+00 -1.59457293e+01 -4.65189409e+00 5.13483763e+00 5.74447346e+00 2.23050556e+01 5.27454147e+01 6.34700165e+01 3.40686073e+01 -1.73637581e+01 -4.32266769e+01 -2.67301350e+01 1.41115160e+01 5.61782799e+01 7.08006592e+01 6.02105980e+01 4.78785439e+01 5.21838646e+01 4.08243484e+01 1.01689875e+00 -2.83214970e+01 -1.56495247e+01 1.64777565e+01 2.87286549e+01 1.56074495e+01 -1.08996677e+01 -1.78364124e+01 1.29937196e+00 1.78724785e+01 1.22004433e+01 7.59701681e+00 3.03684864e+01 7.28901215e+01 7.90589066e+01 4.57163582e+01 8.78878784e+00 9.32928371e+00 3.49763794e+01 6.07672195e+01 6.13983536e+01 4.05078125e+01 8.89132309e+00 -2.36062193e+00 1.14117880e+01 1.34347162e+01 -8.60525227e+00 -1.51726170e+01 1.12244234e+01 4.59888077e+01 4.56818657e+01 1.33300619e+01 -7.93422270e+00 1.71124973e+01 3.30904617e+01 3.98230400e+01 1.92804604e+01 3.14035664e+01 6.41089478e+01 7.20203400e+01 3.39500465e+01 -4.15069618e+01 -7.84382706e+01 -4.73553429e+01 -2.92294860e+00 1.56354761e+01 1.24243021e-01 -1.51478548e+01 -1.07396183e+01 -1.21537590e+01 -3.40299072e+01 -6.49544830e+01 -7.84721527e+01 -3.91912804e+01 3.22812271e+01 6.96886444e+01 3.05986423e+01 -1.64459705e+01 -1.55153790e+01 9.31632042e+00 -1.19124451e+01 -6.88417511e+01 -6.16027985e+01 -8.10652351e+00 4.40988464e+01 3.21015048e+00 -8.42773132e+01 -1.31696228e+02 -9.97389526e+01 -3.85525932e+01 -6.42759705e+00 -9.57532597e+00 7.03717899e+00 1.86400394e+01 3.55438733e+00 -4.76352310e+01 -1.04993309e+02 -7.24001160e+01 -1.69069424e+01 4.02058449e+01 3.12054310e+01 1.31201351e+00 -3.80234184e+01 -5.89600945e+01 -6.21509933e+01 -7.16926270e+01 -1.01625771e+02 -7.83743286e+01 -1.89590702e+01 4.21796150e+01 1.97623444e+01 -4.31730423e+01 -9.14338074e+01 -6.59712906e+01 -1.76349106e+01 6.95872164e+00 -1.57429206e+00 1.92849064e+01 7.46933517e+01 9.83496323e+01 4.43381348e+01 -4.49954109e+01 -6.03742714e+01 -3.40991325e+01 4.04792786e+01 5.01002388e+01 4.95011406e+01 2.12561035e+01 2.35151482e+00 1.43934160e-01 -2.43616085e+01 -5.23146667e+01 -2.93591537e+01 1.86868401e+01 4.83568535e+01 4.39107437e+01 5.93705893e+00 -1.24009886e+01 -5.84504604e+00 7.06275940e-01 6.36781883e+00 -1.44782667e+01 1.83886051e+01 6.17312317e+01 8.22925186e+01 8.40292282e+01 1.38986912e+01 -2.49345036e+01 -2.63194036e+00 6.56792831e+01 7.76971817e+01 3.13523865e+01 -1.46110582e+01 -2.57779551e+00 2.88520832e+01 2.53145390e+01 -1.51426668e+01 -2.82122459e+01 2.01728344e+01 5.36403656e+01 3.18160706e+01 2.92984486e+00 3.31188126e+01 4.44491081e+01 1.83658695e+01 -9.26031494e+00 -3.16767693e+01 -4.65605736e+00 -2.94253139e+01 -3.63680801e+01 -3.42052536e+01 -5.38333588e+01 -7.99310303e+01 -1.00500587e+02 -2.90144272e+01 1.80348003e+00 7.23467541e+00 -4.60161629e+01 -2.73896027e+01 -1.76041565e+01 -3.84525795e+01 -8.00672073e+01 -9.83020172e+01 -2.16549339e+01 2.77897968e+01 4.47345161e+01 -1.88010578e+01 -3.65267029e+01 -3.54088211e+01 -1.24966946e+01 -8.19902611e+00 -5.79493294e+01 -3.91047287e+01 -1.24878483e+01 5.77686729e+01 8.11991501e+01 6.45096130e+01 7.30535221e+00 -3.72783165e+01 -2.02117026e-01 5.05965500e+01 7.29795532e+01 4.43561707e+01 7.47438507e+01 7.79761810e+01 3.56988716e+01 -3.08262234e+01 -2.84412956e+01 5.26791115e+01 8.46072540e+01 4.31708374e+01 -2.87146130e+01 -1.01983080e+01 3.20805702e+01 5.12213974e+01 3.47200851e+01 -4.92935944e+00 -1.64387875e+01 -2.99891510e+01 1.86452694e+01 5.86383476e+01 6.55177536e+01 1.78580093e+01 -8.72838020e+00 1.63351517e+01 5.62414436e+01 6.63934937e+01 8.61176529e+01 1.49769394e+02 1.84596100e+02 1.76611282e+02 1.60922668e+02 1.64136810e+02 2.00369980e+02 2.02707977e+02 1.70761414e+02 9.01780472e+01 5.84305115e+01 4.64352722e+01 6.16831398e+01 5.04960518e+01 9.76881218e+00 -2.29653435e+01 -3.95026627e+01 1.91952343e+01 4.85450706e+01 6.24105644e+01 4.19407921e+01 6.33346329e+01 8.39014206e+01 1.09279633e+02 9.49537506e+01 1.00346657e+02 1.42926208e+02 1.69576584e+02 1.45394379e+02 8.84564133e+01 8.23234177e+01 8.71888123e+01 2.57540760e+01 -2.16656933e+01 -5.67915955e+01 7.61124182e+00 1.66395702e+01 4.09200096e+01 8.18119202e+01 8.83888626e+01 4.43026886e+01 -4.50960464e+01 -6.77202148e+01 8.31303883e+00 7.07762375e+01 6.30040512e+01 2.62806034e+00 -4.55310364e+01 -8.53546715e+00 4.29579926e+01 1.01379608e+02 9.08118134e+01 3.89117088e+01 -9.71448803e+00 -6.95058289e+01 -7.17691116e+01 -7.16428833e+01 -8.49317551e+01 -8.74772644e+01 -8.74418793e+01 -2.95139837e+00 4.49005651e+00 1.00907068e+01 4.05195904e+00 -7.62891960e+00 -4.97418556e+01 -1.76980255e+02 -1.98033447e+02 -1.20999535e+02 4.14743385e+01 1.25027687e+02 3.15541019e+01 -8.49903564e+01 -1.02014053e+02 3.66540680e+01 1.73698837e+02 1.39070160e+02 9.32119465e+00 -7.24157333e+01 -6.28179359e+01 1.92923641e+01 1.30944920e+01 -4.22853699e+01 -9.23751450e+01 -9.96900864e+01 -1.60636959e+01 -8.08983231e+00 -4.71831551e+01 -9.12207184e+01 -9.47068253e+01 -4.33982773e+01 -6.15616379e+01 -6.13880615e+01 1.68772221e+01 1.18093605e+02 1.07130898e+02 -5.92125702e+01 -1.74626419e+02 -1.35496445e+02 -2.16534138e+00 6.99147644e+01 5.08616791e+01 -2.82804966e+01 -6.48727875e+01 -8.66901169e+01 -1.89601765e+01 -2.16193542e+01 -2.99585991e+01 -6.34217682e+01 -7.90999680e+01 -2.66578865e+01 2.08966312e+01 9.80563660e+01 1.02987244e+02 6.04543495e+01 -1.28797665e+01 -1.18957253e+02 -1.54170639e+02 -7.90052261e+01 8.50201111e+01 1.74717422e+02 1.00024765e+02 -7.13197403e+01 -1.24829353e+02 4.12992060e-01 1.72889832e+02 1.73960007e+02 3.28650894e+01 -5.59202347e+01 -5.79041214e+01 1.21876049e+01 2.21048431e+01 -1.85600624e+01 -7.74872894e+01 -1.32651260e+02 -1.27858772e+02 -1.61268326e+02 -1.48312592e+02 -8.81753845e+01 1.53302364e+01 5.06797867e+01 -2.37375393e+01 -9.88861694e+01 -7.47004089e+01 4.21810455e+01 1.36255447e+02 1.02647804e+02 -6.18116665e+00 -4.64376488e+01 -7.84019089e+00 7.54673767e+01 6.34049835e+01 -1.24034967e+01 -8.49300156e+01 -1.34782333e+02 -7.57694016e+01 -7.97795410e+01 -4.52449837e+01 -5.18167381e+01 -6.11037979e+01 -7.93587799e+01 -1.30711594e+02 -8.12299500e+01 -1.49297428e+01 6.64628143e+01 2.16569347e+01 -8.34235382e+01 -1.62665802e+02 -9.39998856e+01 2.54882069e+01 1.02495331e+02 9.39315720e+01 8.19127655e+00 -2.41194153e+01 -4.59081573e+01 -5.58533144e+00 -2.50757084e+01 -6.61172791e+01 -1.15727707e+02 -1.69997711e+02 -1.46872391e+02 -6.27249069e+01 1.65445595e+01 2.95719490e+01 4.54054445e-01 -3.94152184e+01 -9.95965958e+01 -1.35014847e+02 -6.24351807e+01 6.51768646e+01 1.25187187e+02 3.94236412e+01 -7.41430206e+01 -7.48710938e+01 5.15381012e+01 1.82494370e+02 1.51103683e+02 4.28959990e+00 -1.34964554e+02 -1.80675568e+02 -9.62135620e+01 -2.54086246e+01 -2.00311813e+01 -5.49832840e+01 -8.33042068e+01 -3.39987755e+01 -4.32790070e+01 -2.79816990e+01 9.34990788e+00 3.28101616e+01 3.05923843e+01 -3.52687569e+01 -3.01194534e+01 4.74730453e+01 1.37744354e+02 1.23859398e+02 -1.74335003e+01 -1.27789200e+02 -9.40852814e+01 3.05859451e+01 1.20009209e+02 1.17304703e+02 1.09201651e+01 -8.76778412e+01 -1.29051819e+02 -5.26214256e+01 2.40559578e-01 4.80476837e+01 5.24795990e+01 3.60872116e+01 3.94430389e+01 3.44132500e+01 9.97744751e+01 1.35775894e+02 1.31456100e+02 8.11812515e+01 -1.59464560e+01 -4.16201820e+01 1.02431755e+01 1.04193054e+02 1.26295296e+02 7.30373688e+01 -1.05704746e+01 -7.40975618e+00 4.99996414e+01 1.35179214e+02 1.46015396e+02 5.69636192e+01 -3.64727478e+01 -7.22677689e+01 5.71330881e+00 8.00860443e+01 7.62411575e+01 1.87463932e+01 -4.49884300e+01 -5.09326401e+01 -4.47644157e+01 -1.44404192e+01 3.89761581e+01 5.00800209e+01 1.29175615e+00 -9.66014633e+01 -1.39915909e+02 -7.75000687e+01 2.26738167e+00 6.06640549e+01 2.39330616e+01 -3.49678345e+01 -7.38329773e+01 -6.16712227e+01 -1.48492947e+01 -6.24789953e+00 -3.79490623e+01 -8.36184387e+01 -9.56939468e+01 -3.20616798e+01 2.23174152e+01 1.14526100e+01 -3.24491882e+01 -1.03463547e+02 -9.48157043e+01 -9.17239914e+01 -6.35418053e+01 -2.37295666e+01 -2.46841741e+00 5.34386110e+00 -5.70005722e+01 -9.83998718e+01 -6.74393234e+01 -1.26887646e+01 3.49326439e+01 -8.79062462e+00 -6.80670013e+01 -9.55113678e+01 -3.45146904e+01 9.26144028e+01 1.40354446e+02 7.79693985e+01 -6.71018982e+01 -1.35546631e+02 -8.23020935e+01 2.00557842e+01 6.13955307e+01 1.03238541e+02 1.88373322e+02 1.11049408e+02 -1.91495346e+02 -2.04356766e+02 1.57828766e+02 2.71481616e+03 3.49682202e+03 5.99845410e+03 1.40377344e+04 -8.38895411e+09 5.06882816e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.52564122e+09 -415164064. 2.36061445e+04 8.28300488e+03 6.68530273e+02 2.30033665e+01 3.82297119e+02 9.65521164e+01 -2.27549992e+01 3.56271411e+03 2.32470679e+03 4.48664001e+02 3.17640656e+02 -1.41280981e+03 7.85855293e+00 1.26327869e+03 -1.35734390e+02 3.41607056e+01 2.22876724e+02 2.24743652e+02 1.49263321e+02 1.56483368e+02 1.13461243e+02 5.64371147e+01 1.09333696e+01 6.40034008e+00 2.54771881e+01 -1.01738529e+01 -2.46285839e+01 2.47916851e+01 6.61386795e+01 2.92731018e+01 -6.97514267e+01 -1.24589676e+02 -6.05259781e+01 1.72700157e+01 6.34044075e+01 3.57345428e+01 -4.69033241e+01 -1.13576607e+02 -1.37731232e+02 -7.38092041e+01 -2.46586781e+01 -1.95019665e+01 -6.61376419e+01 -9.37539673e+01 -6.64456482e+01 -5.61747093e+01 -2.94611397e+01 -1.52459157e+00 1.25451775e+01 -1.62055626e+01 -9.57886810e+01 -1.04155396e+02 -3.60734329e+01 4.55183907e+01 6.61576080e+01 -1.33096948e-01 -6.31806946e+01 -6.02757988e+01 -1.24241095e+01 9.39440727e+00 -4.14482498e+01 -1.09432915e+02 -1.26716301e+02 -9.22943344e+01 -1.82771549e+01 3.21804504e+01 2.88527660e+01 -1.67896576e+01 -7.57598267e+01 -1.13686798e+02 -1.31624954e+02 -1.16927490e+02 -7.77707825e+01 -4.15515213e+01 -2.34971409e+01 -4.01314964e+01 -3.19851856e+01 9.77819443e+00 5.11462708e+01 4.89037666e+01 -1.52086413e+00 -4.26777191e+01 -3.16646843e+01 -7.93054867e+00 2.92284031e+01 4.77255287e+01 2.68125381e+01 -2.40798416e+01 -5.30783882e+01 -2.40464134e+01 1.20146532e+01 5.43590879e+00 -9.15852356e+00 -1.79497948e+01 -3.18030906e+00 -1.80035172e+01 -1.52021227e+01 2.47737908e+00 1.52549400e+01 4.89540577e-01 -5.01232605e+01 -5.75841026e+01 -8.21909904e+00 5.36708565e+01 7.99379349e+01 3.77398224e+01 -6.83441067e+00 -2.61415348e+01 -1.52245874e+01 6.66732788e-01 4.69579130e-01 -1.21202850e+01 -3.76691093e+01 -5.00128174e+01 -2.39638424e+01 2.20737095e+01 3.48417358e+01 1.64367390e+01 -9.28435445e-01 -2.49817157e+00 -1.69978676e+01 -1.39433270e+01 1.73972359e+01 5.67760544e+01 5.21493034e+01 2.76277852e+00 -2.10699596e+01 7.96285629e+00 4.82185097e+01 5.49785194e+01 1.63704967e+01 -2.11466084e+01 -2.98211861e+01 -1.67087116e+01 1.30216646e+01 3.58090134e+01 2.91698818e+01 -1.51409793e+00 -2.47878571e+01 -6.44692135e+00 2.44192257e+01 3.52041435e+01 2.57522984e+01 1.09213171e+01 1.37886560e+00 -1.67578182e+01 -2.41596756e+01 -1.52659616e+01 -1.21416128e+00 2.34252095e+00 -1.73006115e+01 -2.59865913e+01 -1.00433769e+01 2.61393738e+01 4.94955597e+01 3.90625381e+01 6.06869221e+00 -1.87015476e+01 -1.61120949e+01 2.03431576e-01 6.58862352e+00 6.02642596e-01 -2.40368652e+00 -1.19535198e+01 -7.46516418e+00 -5.01852226e+00 5.45977736e+00 1.81648750e+01 2.54147377e+01 2.77841835e+01 1.06532497e+01 2.32107544e+00 1.22000570e+01 2.27369194e+01 1.64988785e+01 -5.41885233e+00 -1.67082214e+01 -8.15694237e+00 8.12368572e-01 7.88998699e+00 6.42712879e+00 1.21220732e+00 -2.00449896e+00 -3.29838085e+00 6.74847555e+00 5.31221390e+00 -8.84097099e-01 -1.00864010e+01 -1.96631393e+01 -2.41756802e+01 -2.85071678e+01 -1.88015060e+01 -4.48642445e+00 2.61956072e+00 2.76956129e+00 -4.73353100e+00 -4.59391499e+00 1.52695787e+00 9.50436306e+00 1.32142658e+01 3.68824315e+00 -7.33476353e+00 -1.31399288e+01 -9.76706028e+00 -4.77424145e+00 -2.93014932e+00 -3.19536853e+00 -4.34543562e+00 -6.05841780e+00 -3.85425162e+00 -5.89072764e-01 1.63301325e+00 -3.42138529e-01 -1.15370274e+00 -1.74828970e+00 -2.52447724e+00 -2.73089600e+00 -1.53684568e+00 -4.94293451e-01 -4.73304152e-01 -4.25212502e-01 9.46048647e-02 4.92295682e-01 3.76624346e-01 -1.78927705e-02 -1.83704004e-01 -5.21617420e-02 7.39968121e-01 1.06457949e+00 4.86895770e-01 -1.13729072e+00 -1.74382699e+00 -4.12635148e-01 7.20439076e-01 5.10382295e-01 2.71132439e-01 3.52123231e-01 -1.72454804e-01 -3.97576511e-01 -4.05336112e-01 1.75018102e-01 2.74097323e-01 -4.47656721e-01 -1.21792173e+00 -2.79756951e+00 -2.73978925e+00 -2.49425197e+00 -6.50264800e-01 -1.98519433e+00 -3.05969501e+00 -2.85718775e+00 -6.23618662e-01 3.11088967e+00 5.25592947e+00 4.48853636e+00 3.02267647e+00 -5.26686966e-01 9.95643616e-01 6.43008173e-01 7.87784338e-01 -1.85900366e+00 -2.28396463e+00 -1.75712895e+00 2.81900942e-01 -1.84703135e+00 -2.20960474e+00 -3.24498725e+00 -1.80926430e+00 -3.84971547e+00 -4.20612955e+00 -6.61092997e+00 -8.34465313e+00 -8.35509396e+00 -5.42613697e+00 -1.68410814e+00 -1.64235151e+00 -3.46092391e+00 -7.45491314e+00 -6.61963129e+00 -5.53652048e+00 -3.94845128e-01 2.03623819e+00 -1.83873379e+00 -4.99522448e+00 -4.60565901e+00 1.11806774e+00 1.45948565e+00 -8.93967688e-01 1.02516818e+00 1.37119329e+00 -2.06146479e+00 -5.67684269e+00 -2.48402023e+00 1.12122148e-01 -4.43731403e+00 -3.86833501e+00 1.71568835e+00 9.57382774e+00 7.15603542e+00 5.91794109e+00 5.99882269e+00 5.99032879e+00 7.57727957e+00 6.95368814e+00 7.97856712e+00 2.68561864e+00 2.06920815e+00 4.99379635e+00 4.05995035e+00 1.32991922e+00 -3.05159473e+00 -7.41253734e-01 -9.06726170e+00 -1.83775234e+01 -1.57657337e+01 -7.87216330e+00 2.67736268e+00 2.26746488e+00 1.90227437e+00 6.92999601e-01 -3.15873885e+00 2.10052299e+00 4.77347326e+00 7.65382481e+00 6.26374197e+00 1.21313248e+01 1.23902225e+01 5.44602489e+00 1.99816799e+00 1.06229246e+00 2.46486759e+00 -7.64865637e-01 1.70856094e+00 7.20224285e+00 7.78783083e+00 1.33340235e+01 1.31903830e+01 9.63714504e+00 1.23029673e+00 -6.54712296e+00 -4.28008509e+00 -1.04018998e+00 7.19247198e+00 1.05215969e+01 1.04086554e+00 -4.78826523e+00 -2.81658101e+00 6.95940590e+00 9.96997356e+00 5.38690424e+00 -2.54808009e-01 -5.09532785e+00 -6.09516740e-01 -1.70124745e+00 -4.45059061e+00 -1.81260586e+01 -1.53368902e+01 -1.19581642e+01 -1.13703573e+00 -2.82407570e+00 -3.44846177e+00 -4.53771830e+00 3.81289768e+00 -1.69674575e+00 -8.06966209e+00 -1.46599302e+01 -8.18637180e+00 -2.52128392e-01 -2.19752407e+00 -1.66117249e+01 -3.78160019e+01 -3.33705978e+01 -1.68335209e+01 5.59388304e+00 -9.34107590e+00 -2.55601921e+01 -3.19439468e+01 -1.91878109e+01 -3.21499610e+00 -6.85587263e+00 -2.03520355e+01 -2.85956631e+01 -2.87053699e+01 -2.28626385e+01 -2.78879623e+01 -3.86207657e+01 -4.26326141e+01 -2.96900520e+01 -1.00049658e+01 -3.31550527e+00 -1.33612013e+01 -1.91811562e+01 -1.19058647e+01 -2.00626826e+00 -5.74465930e-01 -2.40991459e+01 -4.26529922e+01 -4.26013412e+01 -2.19750652e+01 1.64005868e-02 4.44089234e-01 -6.93729162e+00 -4.27647924e+00 1.33890371e+01 4.21459923e+01 3.98317566e+01 1.81226387e+01 -4.27507782e+00 -8.62762833e+00 -1.02871952e+01 -2.74808025e+01 -3.54180527e+01 7.22908080e-01 4.17951813e+01 4.80822525e+01 1.54671774e+01 -1.44631062e+01 -1.00946722e+01 -5.20229387e+00 1.50638990e+01 2.96531410e+01 2.38341541e+01 1.66205490e+00 -2.43566074e+01 -2.37275066e+01 -3.10442238e+01 -3.73421133e-01 3.59691620e+01 4.46666603e+01 2.30445442e+01 -1.11541214e+01 -3.53228645e+01 -5.24024544e+01 -5.66259575e+01 -2.90444546e+01 -1.41574163e+01 -9.03920472e-01 1.87690049e-01 -4.40861955e-02 8.77322865e+00 1.10437613e+01 9.90914631e+00 8.82711124e+00 1.27237642e+00 -3.84166794e+01 -1.44025665e+02 -2.49853210e+02 -2.41952469e+02 -2.34638580e+02 -1.99455750e+02 -3.72797302e+02 -1.84015106e+02 -2.01933842e+01 5.36335632e+02 -2.37358740e+03 -5.27603027e+02 -3.51101343e+03 -4.60387734e+04 -415372064. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1442105088. 1442105088. -694983616. -3.84125430e+04 -1.12075137e+04 -1.33510620e+03 -9.87401428e+02 -2.86893188e+02 -2.03578461e+02 -1.72294220e+02 -1.69675339e+02 -7.18097458e+01 3.72853928e+01 9.98049927e+01 4.73974991e+01 -2.01897907e+01 -1.68792760e+00 -8.96152592e+00 -4.55325928e+03 -3.16192700e+03 -7.20650330e+02 -2.98135559e+02 -1.96619064e+02 -1.56039856e+02 -1.33708633e+02 -1.00234138e+02 -3.59595604e+01 -2.20982838e+01 -1.02331781e+00 -1.28426182e+00 1.74613075e+01 2.07517128e+01 3.52683029e+01 4.13163719e+01 4.50266342e+01 4.79689522e+01 4.01051369e+01 4.27505455e+01 4.76121559e+01 5.98157005e+01 7.30745239e+01 6.08570786e+01 4.13364639e+01 3.29216270e+01 3.61564903e+01 4.72090111e+01 5.42949867e+01 6.31682510e+01 5.44839859e+01 1.63904324e+01 -2.36206303e+01 -2.81537170e+01 -1.01931057e+01 6.60774374e+00 1.10073709e+01 2.67116795e+01 2.73464069e+01 1.73039970e+01 1.19873114e+01 1.90759010e+01 2.87389793e+01 3.42684746e+01 5.83244781e+01 3.75581398e+01 1.60253925e+01 -6.88198996e+00 -1.69511185e+01 -2.88581314e+01 -3.75344658e+01 -2.06624737e+01 -6.53357077e+00 -4.82016897e+00 7.19039679e+00 4.10951424e+01 5.26245155e+01 4.25080948e+01 1.45755119e+01 4.40809727e+00 3.71195316e+00 -2.56150074e+01 -6.25916862e+01 -5.93684158e+01 -3.94387474e+01 -1.62501507e+01 -6.79846802e+01 -1.09647766e+02 -1.08475502e+02 -7.19640427e+01 -4.57245522e+01 -5.49718475e+01 -6.09689255e+01 -5.14660187e+01 -5.54138565e+01 -7.92437668e+01 -1.07566887e+02 -9.62959137e+01 -4.62721977e+01 -2.74100304e+00 1.69958191e+01 6.40345144e+00 -4.66825628e+00 -2.12246132e+01 5.26856184e+00 3.69615555e+01 2.03577328e+01 -2.02521572e+01 -3.49885025e+01 -1.51572955e+00 2.38270130e+01 -2.62576847e+01 -6.11677818e+01 -5.97189598e+01 -5.05412340e+00 4.35225105e+01 5.27864990e+01 4.47058830e+01 3.01787395e+01 2.29755325e+01 1.29896774e+01 7.47509098e+00 1.52531128e+01 1.41337194e+01 1.07363176e+00 -1.29710159e+01 -5.18157911e+00 4.93495321e+00 9.43658733e+00 5.89678717e+00 4.22209501e+00 -3.88442688e+01 -8.24403610e+01 -7.73896408e+01 -3.40767670e+01 6.62746763e+00 -3.68479004e+01 -7.81023865e+01 -8.26955872e+01 -4.90363083e+01 -1.80009651e+01 -1.58148575e+01 -1.12367802e+01 4.22035599e+00 -6.53895140e+00 -1.04979668e+01 -1.46315222e+01 5.60215664e+00 2.26338272e+01 1.54708586e+01 1.54712892e+00 -1.03292656e+01 -7.56790113e+00 -5.71500921e+00 -1.03816376e+01 -2.77637405e+01 -6.85489349e+01 -1.15973190e+02 -1.13366402e+02 -8.10598679e+01 -3.17859497e+01 -6.66377869e+01 -1.06821426e+02 -1.08727493e+02 -4.88218727e+01 -6.63772523e-01 -8.69024467e+00 -2.46443672e+01 -3.49999962e+01 -2.65818977e+01 -2.57970181e+01 -2.37298698e+01 -1.21039200e+01 -9.98850727e+00 -3.34457436e+01 -7.17392197e+01 -6.94233170e+01 -4.10651474e+01 -4.78653336e+00 4.00737476e+00 2.52514791e+00 -2.96555004e+01 -6.42856522e+01 -6.06902962e+01 -3.51583138e+01 -1.76278400e+01 -1.97195911e+01 -3.67804885e+00 -2.45922985e+01 -6.89048920e+01 -8.62704468e+01 -5.95143051e+01 -1.78550911e+01 -1.31694784e+01 -1.73820515e+01 -1.40192165e+01 -1.20945816e+01 -2.26753216e+01 -2.58609734e+01 -7.25157928e+01 -1.08463737e+02 -1.03798309e+02 -5.73684387e+01 -1.95943604e+01 -3.74711761e+01 -3.72596893e+01 -7.06600952e+01 -1.00784615e+02 -9.52895432e+01 -4.22345963e+01 8.06468487e+00 -6.38480997e+00 -1.83466587e+01 -2.60776958e+01 -1.23376226e+01 2.98035812e+00 9.01012230e+00 1.15190468e+01 5.10586691e+00 1.57925856e+00 6.27418137e+00 4.01686049e+00 3.24038620e+01 4.80547447e+01 6.05471916e+01 5.34781799e+01 3.70331268e+01 3.20897636e+01 3.05304413e+01 3.33020592e+01 3.30132713e+01 2.57971592e+01 3.48391533e+01 2.88467293e+01 2.28029842e+01 2.26702156e+01 4.13787117e+01 4.62441978e+01 3.49125519e+01 2.09595833e+01 2.04151573e+01 2.53607445e+01 1.32806444e+01 1.27059622e+01 -4.42919445e+00 -5.63127708e+00 -5.46438122e+00 1.95925350e+01 4.92368736e+01 2.57289715e+01 -2.93155899e+01 -6.43160400e+01 -5.15600243e+01 -2.31939831e+01 -1.46851501e+01 -1.97477665e+01 -2.38254528e+01 -3.63946838e+01 -3.83549843e+01 -3.18241329e+01 -2.34936008e+01 -1.07100325e+01 -4.58247773e-02 8.23968601e+00 -2.42990837e-01 -1.38045378e+01 -2.07975330e+01 -1.82468414e+01 -1.45963564e+01 -1.71026478e+01 -6.67639637e+00 -6.32400703e+00 4.72471535e-01 -1.26081114e+01 -4.32868805e+01 -7.74662628e+01 -7.89475098e+01 -5.61829987e+01 -2.28105183e+01 -1.23996153e+01 -6.15151024e+00 -2.90065269e+01 -5.03005981e+01 -6.20516243e+01 -6.49850159e+01 -4.12664413e+01 -2.07455521e+01 9.28434658e+00 -3.56375217e-01 -1.13468819e+01 -1.34800415e+01 -6.83565378e+00 3.73813105e+00 8.90999985e+00 -6.85511947e-01 -2.29976749e+01 -3.38215561e+01 -3.57824287e+01 -2.97887287e+01 -5.90297737e+01 -8.68117065e+01 -7.28873291e+01 -3.48441505e+01 -3.74792290e+00 -2.52326469e+01 -3.67195625e+01 -3.26309395e+01 -2.54191971e+01 -4.80940590e+01 -7.86989899e+01 -7.39743958e+01 -3.20032463e+01 1.03602896e+01 1.39808512e+00 -1.68726940e+01 -1.89270229e+01 -1.25848579e+00 5.20189238e+00 1.03058958e+00 -1.60681610e+01 -5.06911278e+00 1.27803040e+01 1.88516235e+01 1.39407864e+01 7.71948671e+00 1.86882668e+01 -9.77717686e+00 -4.23659363e+01 -4.59078789e+01 -5.39415054e+01 -7.23318481e+01 -1.04523819e+02 -1.06166588e+02 -8.76531219e+01 -9.07661972e+01 -6.81125259e+01 -6.44815292e+01 -3.31275482e+01 -2.27051735e+00 3.59386864e+01 4.45506516e+01 3.18695965e+01 2.48805180e+01 1.60253601e+01 1.62224865e+01 1.43191929e+01 1.94951859e+01 2.40317383e+01 -3.82961297e+00 -4.60707932e+01 -6.11877136e+01 -4.72549133e+01 -1.80092621e+01 -8.54739952e+00 -4.18670273e+00 1.01608019e+01 -6.35678005e+00 -8.43859005e+00 -2.03700294e+01 -2.46877079e+01 -4.53462372e+01 -7.39743729e+01 -5.42505302e+01 -2.35979557e+01 -1.33879919e+01 -4.81146049e+01 -5.73508110e+01 -4.07834206e+01 -4.25804615e+00 -2.99110508e+01 -5.62992249e+01 -7.18704071e+01 -4.91419373e+01 -2.62045250e+01 -5.43319778e+01 -7.68655396e+01 -6.67353897e+01 -2.17497196e+01 5.37467146e+00 -2.14877148e+01 -3.64239426e+01 -8.97903538e+00 2.83598175e+01 4.65694189e-01 -5.24810944e+01 -7.18257980e+01 -5.47906952e+01 -3.23256302e+01 -3.70691071e+01 -6.30629883e+01 -9.07653046e+01 -8.10734940e+01 -3.66029320e+01 2.26383567e+00 4.33180141e+00 -4.15137100e+00 -1.07425709e+01 -9.99762535e+00 -1.18758345e+01 -1.58950157e+01 -3.28498001e+01 -3.54691505e+01 -1.54408407e+01 -4.55243969e+00 2.39471102e+00 -2.70790386e+01 -3.93617783e+01 -3.37419968e+01 -2.20545654e+01 -4.45479345e+00 -7.94274616e+00 -2.99762559e+00 7.65950012e+00 1.62048569e+01 1.20719852e+01 -3.51230278e+01 -7.01648483e+01 -3.26095581e+01 3.13147659e+01 3.80222740e+01 -1.79898930e+01 -3.91256294e+01 -9.71058750e+00 4.57002783e+00 -1.64212704e+01 -2.78305302e+01 -2.04848194e+01 -4.79461461e-01 -1.18001137e+01 -2.12705975e+01 -2.84049072e+01 -1.85589828e+01 -2.53283882e+00 -2.21968579e+00 -2.37207413e+00 -2.02137203e+01 -3.57971573e+01 -3.82342339e+01 -1.52145805e+01 -1.37782183e+01 -6.32704735e+01 -9.25916901e+01 -8.11791458e+01 -3.27665596e+01 -2.90855007e+01 -4.24543648e+01 -2.67192116e+01 1.24117317e+01 2.35849247e+01 -1.15786684e+00 -2.36928864e+01 -1.69917927e+01 -7.43590021e+00 -2.00291252e+01 -2.63756580e+01 -2.69813480e+01 -1.89396057e+01 -1.70763803e+00 9.17141342e+00 1.45577602e+01 4.10932732e+00 -4.27293158e+00 -1.66114330e+01 -2.16745491e+01 -3.05318851e+01 -3.95702934e+01 -3.90392036e+01 -2.43180218e+01 -5.47273684e+00 -9.46999168e+00 -2.98664703e+01 -3.52828560e+01 -3.17392082e+01 -4.03034668e+01 -7.30768433e+01 -9.27648697e+01 -7.77736130e+01 -3.97398338e+01 -2.82039814e+01 -3.43844948e+01 -3.62791824e+01 -2.21575642e+01 -1.17884550e+01 -5.25613880e+00 1.67489827e+00 1.09055316e+00 -8.33060265e+00 -1.05621500e+01 5.57093906e+00 7.75601101e+00 -1.69765701e+01 -3.22547798e+01 -1.99797516e+01 -6.29969883e+00 -2.88310013e+01 -4.39303665e+01 -2.38732738e+01 1.09036341e+01 3.36816864e+01 3.17990379e+01 2.97121964e+01 2.16310425e+01 1.83242397e+01 1.40252171e+01 1.72889671e+01 8.10544586e+00 -1.45638347e-01 1.19858384e+00 1.60425358e+01 9.34111500e+00 -2.49157028e+01 -4.40056877e+01 -4.74689026e+01 -3.83874512e+01 -2.91898994e+01 -1.52143955e+01 -2.34292006e+00 2.86570370e-01 2.81728911e+00 3.26395345e+00 9.61832285e-01 -3.86332941e+00 -2.50787640e+00 -5.78052950e+00 -6.09586525e+00 -1.79531598e+00 1.38678059e-01 4.08441015e-03 -1.76056271e+01 -3.34068069e+01 -3.37140961e+01 -1.96280270e+01 -7.14892483e+00 -8.11134434e+00 -8.66113663e+00 -9.14394760e+00 -5.05102062e+00 -6.82891417e+00 -7.71918774e+00 -1.92828674e+01 -2.87272205e+01 -2.48670387e+01 -1.18553724e+01 -7.58303213e+00 -2.78251648e+01 -4.10673485e+01 -3.30174217e+01 -1.15451536e+01 -9.89893436e+00 -1.78787270e+01 -1.70740566e+01 -8.08762932e+00 3.38363588e-01 -1.01597118e+01 -1.81915989e+01 -2.63988190e+01 -2.94809151e+01 -2.05719719e+01 -9.97389317e+00 -9.44557762e+00 -2.84124374e+01 -3.80946312e+01 -2.44701843e+01 -5.91710472e+00 -7.69188929e+00 -2.10529900e+01 -2.50935993e+01 -1.85048428e+01 -1.02302036e+01 -1.35497093e+01 -1.81041584e+01 -2.05857906e+01 -1.58268700e+01 -1.07103300e+01 -7.46539211e+00 -1.46577463e+01 -2.24143753e+01 -2.25254383e+01 -1.62122002e+01 -4.69423008e+00 -9.73745823e+00 -1.48031549e+01 -1.67058983e+01 -1.10415154e+01 -9.29584026e+00 -1.45465202e+01 -1.35943060e+01 -7.82220840e+00 -1.30738533e+00 9.32699621e-01 1.72870278e+00 -2.55945230e+00 -9.02153778e+00 -1.13621416e+01 -8.16000175e+00 -3.32818341e+00 -1.43034995e+00 -1.33727062e+00 -7.14432859e+00 -3.03576698e+01 -4.91474648e+01 -5.96623764e+01 -4.53206635e+01 -4.50658386e+02 -1.28890173e+03 1.37678735e+03 4.05575867e+02 -6.32332336e+02 -2.66430725e+02 -3.06222717e+02 -8.02185742e+03 3.20020429e+09 -4.62466458e+09 -4.62466458e+09 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. 2.45095987e+09 3.12392163e+03 9.21575562e+02 1.50072800e+02 1.18151878e+02 -2.76845459e+02 -2.16643173e+02 -3.68128395e+01 -9.92798710e+00 2.53639412e+01 3.68342285e+01 3.76195641e+01 3.09699459e+01 2.86441193e+01 3.16542492e+01 2.78784828e+01 1.88178997e+01 1.26704054e+01 2.09359684e+01 3.79439888e+01 4.57217598e+01 4.07494774e+01 2.99157066e+01 2.43250065e+01 2.70093479e+01 2.96500111e+01 2.57549820e+01 1.88565636e+01 2.28628960e+01 3.27473145e+01 3.74489098e+01 3.33173485e+01 2.30744057e+01 2.02505875e+01 2.75806561e+01 4.08038216e+01 4.80679855e+01 4.14373779e+01 4.29373245e+01 5.16785164e+01 4.63423233e+01 2.60543861e+01 1.03866014e+01 2.47911510e+01 5.87134247e+01 6.84261322e+01 5.45718002e+01 3.57112846e+01 2.70862789e+01 2.60249844e+01 3.07303143e+01 3.07880440e+01 2.90811653e+01 3.24938393e+01 5.99514656e+01 7.63333054e+01 6.84973602e+01 4.09556694e+01 2.41811829e+01 3.60810051e+01 5.58330154e+01 6.54976807e+01 4.76616974e+01 4.28959885e+01 4.99921570e+01 4.44902611e+01 2.34012089e+01 1.35390425e+00 3.35384369e+00 3.58243752e+01 4.73486252e+01 3.96284943e+01 1.40294552e+01 2.00639668e+01 3.91034431e+01 3.48599968e+01 1.72390156e+01 6.35476828e+00 2.13809853e+01 5.44503174e+01 7.04610062e+01 6.10097160e+01 2.74788723e+01 6.03019428e+00 1.07739735e+01 2.47671967e+01 1.98459187e+01 4.25949287e+00 9.23494816e+00 3.54410744e+01 4.68897247e+01 2.21042309e+01 -1.25374060e+01 -1.62950630e+01 2.02809334e+01 5.14990387e+01 5.22416916e+01 2.57494812e+01 2.25190239e+01 3.12731209e+01 1.41750422e+01 -2.41053524e+01 -4.50043907e+01 -1.20735540e+01 4.04299011e+01 6.93207626e+01 5.47094498e+01 2.24536133e+01 -1.36790714e+01 -3.71753387e+01 -3.15506115e+01 -2.41008701e+01 -2.42390213e+01 -1.57915878e+01 1.95986328e+01 5.20712013e+01 3.50396500e+01 -1.52698565e+01 -4.24150581e+01 -2.27375317e+01 2.99071445e+01 5.77884445e+01 3.70826530e+01 1.19609823e+01 5.27222776e+00 8.95316410e+00 -1.48721085e+01 -6.07035599e+01 -6.07021599e+01 -1.40720205e+01 3.52373772e+01 3.54298668e+01 3.43417835e+00 -2.35580616e+01 -2.92577724e+01 -1.35239391e+01 8.50015831e+00 1.95123997e+01 -1.19200888e+01 -2.68893833e+01 -4.42152452e+00 2.07710152e+01 2.75026093e+01 1.65234356e+01 1.60882854e+01 3.61803207e+01 3.14020748e+01 1.55522451e+01 -9.27372837e+00 -1.50167036e+01 1.09468250e+01 2.60748959e+01 1.45652905e+01 -1.00013571e+01 7.18116283e+00 7.89173889e+01 1.09805450e+02 5.95221405e+01 -1.14691954e+01 -1.63189220e+01 2.10344391e+01 4.75606689e+01 3.98506775e+01 3.95205078e+01 6.27517433e+01 9.45837631e+01 1.07043358e+02 8.91477661e+01 4.24569397e+01 7.70699310e+00 3.80900650e+01 5.85281944e+01 5.04928246e+01 1.56183853e+01 3.18152695e+01 9.52706299e+01 9.04744110e+01 6.31928864e+01 2.65688591e+01 6.48582993e+01 1.43990662e+02 1.83089157e+02 1.48263733e+02 6.39294243e+01 2.19510231e+01 2.31635056e+01 1.87405586e+01 5.46393573e-01 1.36356411e+01 6.56968002e+01 1.22591751e+02 1.12890785e+02 6.41601257e+01 -2.49503765e+01 -5.26270180e+01 -3.25353737e+01 2.97794552e+01 6.72774353e+01 7.13125458e+01 9.24892731e+01 1.19247749e+02 1.00055557e+02 3.28352394e+01 -1.77304535e+01 1.80877476e+01 1.03754448e+02 1.43341995e+02 9.31294403e+01 4.88901043e+00 -3.26166306e+01 1.28662691e+01 5.93389130e+01 3.58040695e+01 -1.05106812e+01 9.03052151e-01 5.29140129e+01 6.84715805e+01 1.58723259e+01 -5.96980133e+01 -6.88643188e+01 -2.95637817e+01 1.54941301e+01 1.27516937e+01 -8.07465267e+00 -4.37676525e+00 2.16644535e+01 5.35428905e+00 -3.41561737e+01 -4.41662636e+01 -3.96722870e+01 7.10156965e+00 1.69601078e+01 3.80041957e+00 7.47837782e-01 -3.06084841e-01 3.87160721e+01 4.90667963e+00 -3.08051128e+01 -5.66830254e+01 -3.52893333e+01 5.44583778e+01 1.03926285e+02 9.56963272e+01 -1.19607143e+01 -6.37541237e+01 -6.89403534e+01 -2.57951298e+01 -2.17847013e+00 -3.38444061e+01 -3.06174297e+01 5.55752420e+00 3.04331913e+01 -7.97527075e+00 -3.66650696e+01 1.94076366e+01 1.03674431e+02 8.64650345e+01 4.05689545e+01 1.29375553e+01 3.81333389e+01 9.72881851e+01 4.37933121e+01 8.49127865e+00 -3.41304588e+01 -6.52228785e+00 5.90359001e+01 8.64820938e+01 1.09627258e+02 4.88653717e+01 2.54154224e+01 1.20857706e+01 5.89716148e+01 5.98247299e+01 5.74248848e+01 6.00782127e+01 9.24017487e+01 1.14139580e+02 4.91429977e+01 7.31136751e+00 -1.50465310e+00 5.74934158e+01 4.59892006e+01 2.34476128e+01 -5.92006779e+00 -2.25428028e+01 -8.66322899e+00 -1.70929203e+01 4.22977715e+01 6.67205658e+01 8.47037811e+01 7.09417038e+01 5.30220833e+01 2.69876747e+01 -4.13601799e+01 -6.94092789e+01 -4.38154793e+01 5.39886398e+01 7.17487793e+01 5.11009865e+01 3.12868843e+01 3.94721107e+01 1.26999283e+01 -8.01341476e+01 -1.17139877e+02 -7.96622772e+01 2.66179886e+01 5.04861526e+01 1.53766031e+01 -4.27050171e+01 -5.65942154e+01 -5.86600828e+00 -1.15028596e+00 1.43822060e+01 -4.23484573e+01 -7.09865570e+01 -6.82042694e+01 -1.37694254e+01 1.58268175e+01 -3.17589760e+01 -8.59502258e+01 -5.98467903e+01 9.57454109e+00 -5.04029655e+00 -5.05144234e+01 -6.21336555e+01 -2.48641930e+01 -2.73222427e+01 -8.65429840e+01 -1.15040459e+02 -7.78777847e+01 -7.27199125e+00 -3.36996126e+00 -3.11639748e+01 -6.27632294e+01 -4.76373329e+01 -2.24867306e+01 -2.50432987e+01 -1.65884895e+01 -5.73263130e+01 -7.79258881e+01 -8.70191422e+01 -5.23825951e+01 -4.08311653e+01 -7.21566696e+01 -1.04492340e+02 -6.84216385e+01 2.73617816e+00 2.13012924e+01 1.30380335e+01 2.86055527e+01 8.45347214e+01 6.84243011e+01 8.18586254e+00 -9.61797535e-01 3.73204498e+01 9.88009109e+01 3.26459961e+01 -5.16446733e+00 -4.16496315e+01 -7.75476379e+01 -9.03037720e+01 -5.66983757e+01 4.57092171e+01 7.19384842e+01 -2.67143655e+00 -6.41682053e+01 -2.68426952e+01 6.59425049e+01 1.17082092e+02 5.87546844e+01 1.28291626e+01 2.06984043e+01 5.10489082e+01 9.36649628e+01 1.35916092e+02 2.11033051e+02 1.83739594e+02 1.15966461e+02 8.98353043e+01 1.24887161e+02 1.68067291e+02 8.19231873e+01 3.50739708e+01 -1.13322115e+00 1.22607775e+01 3.16635742e+01 8.12871170e+01 1.95143829e+02 2.11129120e+02 1.11304695e+02 -5.49997253e+01 -9.43666534e+01 4.64975586e+01 1.62897064e+02 1.65451675e+02 7.53971481e+01 2.80229015e+01 5.39001808e+01 1.32193069e+02 1.76676498e+02 1.36604507e+02 1.59980841e+01 -2.50917149e+01 2.96519909e+01 1.11295456e+02 2.18622879e+02 2.15522812e+02 1.77634232e+02 6.02621803e+01 -5.11694908e+01 -9.79596176e+01 -3.11265945e+01 1.14381340e+02 1.94235489e+02 1.21319023e+02 1.10336723e+01 1.84882698e+01 1.39555573e+02 2.56016327e+02 2.04790146e+02 6.68548813e+01 -3.79640656e+01 -4.42949677e+01 4.50664253e+01 1.11069862e+02 1.65710632e+02 9.12787170e+01 4.71296577e+01 8.75122547e+00 5.71164780e+01 9.56681442e+01 4.45597610e+01 -1.10230513e+01 -9.83009796e+01 -1.02038857e+02 -6.15906334e+01 1.87426510e+01 1.29286774e+02 1.50063004e+02 7.64926834e+01 -7.91105347e+01 -1.55314392e+02 -8.76225204e+01 6.93012848e+01 1.55194519e+02 1.18807190e+02 4.78924255e+01 4.64112968e+01 9.80863724e+01 1.29103592e+02 1.36859421e+02 5.40163956e+01 -9.46014214e+00 -6.17160683e+01 -5.92791023e+01 -2.44042740e+01 1.90937881e+01 7.82399292e+01 7.54546738e+01 1.60472088e+01 -4.75104599e+01 -5.08249741e+01 1.91632481e+01 9.87312469e+01 6.48892212e+01 -6.04494047e+00 -4.71961784e+01 1.04750404e+01 1.13904488e+02 1.07654686e+02 4.67251740e+01 -6.30468483e+01 -5.80526237e+01 2.16525669e+01 8.72910919e+01 1.36460037e+02 4.64684219e+01 1.14408522e+01 -2.91687393e+01 -3.49900513e+01 -3.93596039e+01 -4.60733223e+01 -3.23888922e+00 -2.84270668e+01 -7.02075272e+01 -7.02399063e+01 -1.30913448e+01 7.87615738e+01 1.31895096e+02 7.44112930e+01 -5.77065086e+01 -1.70910873e+02 -1.49759598e+02 -9.44208145e+00 1.19298401e+02 1.60692627e+02 5.81866760e+01 -5.39481239e+01 -7.33365021e+01 1.40302181e-01 8.59394684e+01 5.26342316e+01 -8.01708317e+00 -5.53869896e+01 -6.30023270e+01 -4.63700562e+01 -2.85096908e+00 6.03944168e+01 4.96793594e+01 -1.82205582e+01 -1.14590828e+02 -1.28055252e+02 -5.14318657e+01 4.75464897e+01 3.63722725e+01 -4.19989395e+01 -9.35208130e+01 -5.09244423e+01 -4.13051128e+00 1.85381260e+01 2.77977333e+01 -9.62172604e+00 -3.60330963e+01 -1.04458084e+01 1.44112406e+01 5.15610313e+01 -4.66745675e-01 -4.01501350e+01 -9.78767166e+01 -1.30177612e+02 -8.74430542e+01 -3.95550346e+01 4.40255737e+01 6.70857697e+01 2.13824978e+01 -5.38807564e+01 -6.15926208e+01 1.16640673e+01 8.67640533e+01 7.05540695e+01 2.03203621e+01 -6.00572891e+01 -8.11421356e+01 -4.88700790e+01 -5.47369337e+00 2.61654873e+01 -3.77146339e+01 -9.14764786e+01 -1.57381485e+02 -1.43312317e+02 -7.28857117e+01 -7.60553131e+01 -9.62300034e+01 -1.64130783e+02 -1.70972687e+02 -1.54439911e+02 -1.04222267e+02 -2.81473947e+00 3.16218987e+01 6.43324661e+00 -7.56914368e+01 -1.11158768e+02 -5.09973450e+01 2.94437485e+01 3.58487434e+01 -5.04783821e+01 -1.19957855e+02 -9.72254105e+01 -1.34961796e+01 5.48902168e+01 6.14654541e+01 -1.20128298e+01 -9.86938171e+01 -1.20229599e+02 -1.05136391e+02 -7.39149399e+01 -4.55191345e+01 -6.86955070e+00 -2.10784483e+00 -2.58553905e+01 -4.26308441e+01 -1.39080706e+01 6.18746109e+01 1.01645744e+02 4.30612297e+01 -5.07434692e+01 -9.52657547e+01 -3.67752914e+01 5.46787415e+01 7.17914581e+01 2.14985313e+01 -6.97907257e+01 -7.84688034e+01 -3.03237419e+01 1.15829870e-01 1.13975554e+01 -4.06718788e+01 -5.80350494e+01 -5.01237297e+01 -2.95342770e+01 1.88055210e+01 1.50660858e-01 -1.28620548e+01 -8.27088242e+01 -1.30086136e+02 -1.07744812e+02 -7.56715851e+01 -4.39839554e+00 5.06444407e+00 -1.67277355e+01 -1.02637062e+02 -1.82671509e+02 -1.62680222e+02 -7.29034042e+01 -2.19245148e+01 -2.70492615e+02 -2.95917328e+02 -1.11939636e+02 -3.43269238e+03 -7.53721875e+03 -651326016. -408989312. -2.73790259e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.52564122e+09 -415164064. 2.36061445e+04 8.28300488e+03 6.68530273e+02 2.30033665e+01 3.82297119e+02 9.65521164e+01 -3.09627441e+03 -2.05959204e+03 -2.90612335e+02 -2.61656830e+02 -1.42512177e+02 -1.09442429e+02 -9.36800919e+01 -6.63111191e+01 1.60484276e+01 1.79210186e+01 -1.72739792e+01 -7.78927460e+01 -6.66484680e+01 -1.43535960e+00 5.72878227e+01 6.65689621e+01 1.10421696e+01 -6.74648590e+01 -8.56977921e+01 -2.48334942e+01 3.58635101e+01 4.35911369e+01 -1.13914404e+01 -1.31259346e+01 1.45761557e+01 2.49171619e+01 -1.39341366e+00 -3.75400391e+01 -3.70387039e+01 -4.48510628e+01 -6.47600555e+01 -6.48316650e+01 -3.28769989e+01 3.91590233e+01 3.83520699e+01 -3.56865191e+00 -4.69309692e+01 -4.20000458e+01 4.61993599e+00 5.77222290e+01 5.16764793e+01 -1.97876186e+01 -1.03489677e+02 -9.44843674e+01 -1.34441051e+01 2.64062290e+01 2.76625748e+01 -2.10408878e+01 -3.29222107e+01 -3.79937744e+01 -4.58567390e+01 -3.54441071e+01 -1.65323524e+01 3.56787872e+01 1.76463985e+01 -2.40180054e+01 -4.50885811e+01 -1.19350348e+01 4.26019592e+01 4.34219093e+01 1.54266052e+01 -2.52991524e+01 -4.55715714e+01 -4.85222054e+00 5.02740479e+01 9.41968384e+01 7.36922531e+01 1.03160257e+01 -1.25562363e+01 1.84093552e+01 4.68388596e+01 4.38475647e+01 -1.06240911e+01 -2.41700439e+01 -1.12315178e+01 1.32316418e+01 1.14194269e+01 1.10364218e+01 2.27731552e+01 2.91924930e+00 -3.00383015e+01 -4.39336014e+01 -7.21499920e+00 4.75568962e+01 5.52158089e+01 3.51082611e+01 -6.62924147e+00 -3.01815319e+01 -3.65630722e+01 -3.01264620e+00 1.84913177e+01 1.80595894e+01 -3.34360237e+01 -5.23072853e+01 -1.79159298e+01 1.79692745e+01 1.67826939e+01 -3.07470970e+01 -5.02661819e+01 -4.42435455e+01 -4.01480827e+01 -3.42398682e+01 -1.94734077e+01 1.69934883e+01 1.62981358e+01 -1.29463577e+01 -3.67683411e+01 -3.80093880e+01 -1.04920177e+01 -7.13874292e+00 -2.31914864e+01 -3.64640694e+01 -5.23681221e+01 -4.55364075e+01 -1.97956982e+01 7.98982668e+00 1.57193832e+01 -2.26920586e+01 -4.22068672e+01 -2.67366505e+01 -1.56851015e+01 -1.31758528e+01 -3.30546875e+01 -3.09388256e+01 -2.68888474e+01 -3.68130302e+01 -3.87957458e+01 -3.31140327e+01 -1.49724090e+00 -5.02546549e+00 -2.81836605e+01 -4.43721695e+01 -4.00933952e+01 -2.05413570e+01 -2.12882557e+01 -3.64742241e+01 -4.57920532e+01 -5.81895142e+01 -4.55568352e+01 -2.56014194e+01 -7.64338255e+00 -1.00494041e+01 -3.16493073e+01 -3.35441628e+01 -2.84873123e+01 -2.61511574e+01 -3.28579712e+01 -4.49049225e+01 -5.21457214e+01 -5.73001595e+01 -5.82736015e+01 -4.84962082e+01 -3.48842506e+01 -1.46360178e+01 -7.51355028e+00 -1.29256802e+01 -2.49238625e+01 -2.60468254e+01 -1.16687145e+01 1.37837958e+00 -6.97502947e+00 -2.93271599e+01 -4.52875938e+01 -4.24035149e+01 -2.19875908e+01 -1.03901329e+01 -1.32067585e+01 -2.70923805e+01 -3.04721470e+01 -2.35564671e+01 -2.37639008e+01 -2.23322506e+01 -2.20762444e+01 -2.20811577e+01 -3.14427776e+01 -4.42104073e+01 -4.27408180e+01 -3.84795723e+01 -2.91568508e+01 -2.46024437e+01 -2.22277737e+01 -2.51731300e+01 -2.63870544e+01 -2.05634651e+01 -1.29784155e+01 -1.65717182e+01 -2.72242870e+01 -3.77694016e+01 -3.82918930e+01 -3.01943607e+01 -2.76965656e+01 -2.67323666e+01 -3.36275940e+01 -3.21879959e+01 -2.74680882e+01 -2.19302807e+01 -1.90122490e+01 -1.91890450e+01 -1.65095482e+01 -1.94487476e+01 -2.51313267e+01 -2.97889423e+01 -2.97658844e+01 -2.58832474e+01 -2.54460869e+01 -2.81502209e+01 -3.13266850e+01 -3.40806503e+01 -3.19254818e+01 -2.81419315e+01 -2.49445763e+01 -2.61985970e+01 -2.87647209e+01 -2.91429214e+01 -2.83242626e+01 -2.81052666e+01 -2.82969036e+01 -2.86162548e+01 -2.86127110e+01 -2.83999805e+01 -2.82155571e+01 -2.84013424e+01 -2.88031731e+01 -3.02308083e+01 -3.09671059e+01 -3.07268791e+01 -2.97321663e+01 -2.93413239e+01 -2.93155499e+01 -2.80688381e+01 -2.61754913e+01 -2.54334373e+01 -2.60021420e+01 -2.85487118e+01 -2.91209641e+01 -2.98376102e+01 -2.94432335e+01 -2.77445755e+01 -2.75156269e+01 -2.76778584e+01 -3.12333107e+01 -3.15897026e+01 -3.06684036e+01 -2.77784977e+01 -2.82958813e+01 -2.97793121e+01 -3.12031765e+01 -2.98253250e+01 -2.79111481e+01 -2.79160690e+01 -2.69561806e+01 -2.77098579e+01 -2.62112617e+01 -2.77751331e+01 -2.82614384e+01 -3.06010113e+01 -2.79920864e+01 -2.57153797e+01 -2.40909538e+01 -2.50367489e+01 -2.57308025e+01 -2.39647312e+01 -2.36026096e+01 -2.40245171e+01 -2.33400822e+01 -2.38793983e+01 -2.49422359e+01 -2.68062840e+01 -2.46087837e+01 -2.39951534e+01 -2.42272892e+01 -2.47314816e+01 -2.36434612e+01 -2.22983379e+01 -2.29957294e+01 -2.18291912e+01 -2.38291092e+01 -2.59555473e+01 -2.69209156e+01 -2.31313534e+01 -2.24422073e+01 -2.02627106e+01 -2.28277664e+01 -1.92940884e+01 -2.13868389e+01 -1.85964546e+01 -1.91523457e+01 -1.88181496e+01 -2.59494686e+01 -3.58697586e+01 -4.16730423e+01 -3.65413818e+01 -3.01900158e+01 -2.57813492e+01 -2.87361736e+01 -2.69756031e+01 -3.15601482e+01 -3.11093102e+01 -2.70937996e+01 -2.26900845e+01 -2.43398342e+01 -2.74393616e+01 -2.49295597e+01 -2.38547649e+01 -2.65842876e+01 -2.79968834e+01 -2.22007084e+01 -2.39054203e+01 -2.82596874e+01 -3.54504585e+01 -3.39957733e+01 -3.38540916e+01 -2.47909927e+01 -1.55521345e+01 -4.48601186e-01 3.21807718e+00 -2.82848477e+00 -1.52379379e+01 -2.37483044e+01 -2.64776993e+01 -2.61313896e+01 -2.90684929e+01 -2.04046974e+01 -8.37899590e+00 -8.25606918e+00 -2.01966915e+01 -3.32532578e+01 -3.35185814e+01 -2.84742737e+01 -3.23784790e+01 -3.24280739e+01 -3.31628571e+01 -3.25818100e+01 -3.39327698e+01 -3.69420433e+01 -2.93442631e+01 -2.58428288e+01 -3.14802780e+01 -3.79511833e+01 -5.11618156e+01 -5.16283455e+01 -4.97460594e+01 -3.70558510e+01 -4.07619514e+01 -4.17848091e+01 -4.05322762e+01 -3.44904251e+01 -2.98301888e+01 -3.96035004e+01 -4.81431580e+01 -5.44882393e+01 -3.79422836e+01 -2.35450935e+01 -1.67348328e+01 -3.36019135e+01 -5.19326134e+01 -6.83732452e+01 -5.16886940e+01 -2.57129078e+01 -1.55995531e+01 -2.04799023e+01 -3.34076614e+01 -3.37735481e+01 -5.44981155e+01 -6.36192932e+01 -5.65954247e+01 -4.05499039e+01 -2.62210350e+01 -2.12397537e+01 -2.27123451e+01 -3.40888176e+01 -5.11703568e+01 -5.37393532e+01 -3.85163231e+01 -2.76765785e+01 -2.23041573e+01 -2.33451710e+01 -1.79125557e+01 -9.27836609e+00 -7.69635677e+00 -8.98576832e+00 -1.43677740e+01 -2.20759583e+01 -1.97447548e+01 -1.94850006e+01 -1.89922199e+01 -2.88117085e+01 -2.16784306e+01 -1.17650938e+01 -2.30175610e+01 -3.59355469e+01 -3.14577026e+01 -6.48681819e-02 1.16505423e+01 -4.74383545e+00 -2.04382362e+01 -2.03778534e+01 -2.35796032e+01 -4.43373566e+01 -5.74759445e+01 -6.52232819e+01 -5.44530373e+01 -4.31372528e+01 -2.77763233e+01 -2.62018871e+01 -3.65084991e+01 -3.24609222e+01 -2.76019268e+01 -1.96395283e+01 -2.22536316e+01 -1.59958677e+01 -4.24394150e+01 -6.39964333e+01 -7.23709106e+01 -4.77934151e+01 -2.96647320e+01 -2.33631210e+01 -2.09183121e+01 -2.08088131e+01 -1.70152836e+01 -2.77816486e+01 -1.13777580e+01 1.50635433e+00 2.54637299e+01 2.13989773e+01 7.70150185e+00 -1.08828115e+01 -7.83934784e+00 -5.87747514e-01 5.44847441e+00 9.76267636e-01 -5.62866116e+00 2.07959309e+01 5.11120415e+01 5.33309059e+01 1.91947575e+01 -2.52588673e+01 -2.98284092e+01 -2.33423305e+00 4.42561111e+01 1.50275681e+02 4.10463196e+02 5.83328064e+02 6.24543884e+02 7.97037781e+02 2.65315356e+03 3.68780566e+03 -7.42011292e+02 5.46947314e+03 5.44294434e+02 5.33073877e+03 2.05273613e+04 -355944800. -804032064. -290804128. -543421312. 2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 1442105088. 1442105088. -694983616. -3.84125430e+04 -1.12075137e+04 -1.33510620e+03 4.00486694e+03 2.82696484e+03 7.56350098e+02 6.62917358e+02 5.00213989e+02 1.75460358e+02 7.08590240e+01 6.71460190e+01 3.41834221e+01 -1.17179489e+00 3.37878752e+00 5.58774042e+00 6.19800234e+00 5.61842871e+00 3.35412979e+01 5.85077972e+01 3.43822823e+01 -1.26960907e+01 -1.91766987e+01 9.65725708e+00 3.24332047e+01 1.33440771e+01 1.08074856e+01 2.07628193e+01 3.08589001e+01 3.94463005e+01 4.07079124e+01 3.92696381e+01 2.63576050e+01 2.39618320e+01 1.40654860e+01 1.58450832e+01 -2.04224072e+01 -4.98562241e+01 -5.62067146e+01 -3.32576599e+01 -1.44623194e+01 -2.07626381e+01 -3.88850937e+01 -4.21730042e+01 -5.87094154e+01 -6.47480087e+01 -7.12159348e+01 -7.71718445e+01 -8.14565353e+01 -6.99225845e+01 -5.61184082e+01 -4.41901436e+01 -4.88296471e+01 -4.63377457e+01 -4.04631195e+01 -4.68210640e+01 -5.07938156e+01 -6.54857483e+01 -7.02539978e+01 -5.41360550e+01 -1.17821655e+01 3.49887238e+01 5.30428696e+01 2.81987362e+01 1.40559840e+00 -1.79194660e+01 9.57976055e+00 3.41815758e+01 2.07951241e+01 -1.72005253e+01 -5.19921951e+01 -5.01650772e+01 -4.58607635e+01 -6.70764160e+01 -1.06505928e+02 -8.15250626e+01 -3.01735897e+01 2.13660011e+01 1.32165174e+01 -9.89957333e+00 -9.15797615e+00 -2.01950531e+01 -2.65048752e+01 -3.96976509e+01 -3.21617699e+01 -2.15005684e+01 2.20872879e+00 9.50795650e+00 9.52772903e+00 -1.16569185e+01 -9.14842224e+00 2.31963577e+01 7.29356079e+01 6.02706223e+01 2.88087044e+01 -8.50399208e+00 2.15965891e+00 2.27905025e+01 4.76960945e+01 5.85741806e+01 2.82987652e+01 -1.84997959e+01 -2.53193073e+01 -1.09850073e+01 3.47363930e+01 2.52778225e+01 2.29144726e+01 -3.80213451e+00 -1.15083075e+01 -7.15380955e+00 -2.34926128e+00 -3.17977858e+00 -6.92969275e+00 -3.83427072e+00 -4.08294678e+00 -1.11831589e+01 1.26055384e+01 4.95036469e+01 5.57165031e+01 2.17180653e+01 -1.69326897e+01 -2.78463135e+01 -3.42608986e+01 -3.24564552e+01 -4.02788773e+01 -4.55887108e+01 -5.09890518e+01 -4.94080591e+00 5.20860443e+01 6.38047371e+01 3.64676666e+01 -8.55687046e+00 -2.91905174e+01 -4.38911819e+01 -3.79676094e+01 -1.99179211e+01 -1.20541277e+01 -2.39505672e+01 -1.42235394e+01 -1.33235855e+01 -1.00482273e+01 -1.57902651e+01 -9.56170273e+00 -6.41743517e+00 4.14973021e+00 -2.29165539e-01 1.70188797e+00 -1.38786256e+00 3.28800470e-01 2.37384245e-01 6.00135231e+00 1.25302105e+01 1.36170969e+01 -5.10409594e+00 -1.09966545e+01 -1.59642143e+01 -9.89185429e+00 -1.71493607e+01 -2.29955730e+01 -2.38846836e+01 -9.40143776e+00 5.07301941e+01 8.19461746e+01 8.74903870e+01 6.74986420e+01 4.73050613e+01 4.14780388e+01 1.99384251e+01 9.89862537e+00 1.97604980e+01 2.31144924e+01 2.43611794e+01 1.39650497e+01 1.23346643e+01 1.67371035e+00 -4.53106995e+01 -8.27705994e+01 -1.07869415e+02 -9.42323303e+01 -4.97212257e+01 -1.14652300e+01 3.14086761e+01 2.11920452e+01 1.69232273e+01 -8.36262703e-01 4.28925037e+00 -2.65877366e+00 5.71062279e+00 -3.43567044e-01 -1.56557524e+00 5.61332417e+00 1.39632339e+01 5.66611290e+00 -4.66528606e+00 -9.53667641e+00 6.99618530e+00 1.80395622e+01 2.34204216e+01 2.36745682e+01 1.20841255e+01 -2.98486309e+01 -6.64481354e+01 -9.23894806e+01 -8.73578873e+01 -8.34185715e+01 -8.68494263e+01 -5.56022797e+01 -9.10566711e+00 3.63033562e+01 4.77200966e+01 3.79755936e+01 2.24552212e+01 1.67519913e+01 2.26019993e+01 4.34480095e+01 3.84197960e+01 3.59307556e+01 2.23948421e+01 1.89460754e+01 2.00906887e+01 5.46382523e+01 9.55121841e+01 8.12933273e+01 4.59113579e+01 6.67619801e+00 -1.29300919e+01 -3.18984127e+01 -7.11850967e+01 -9.40049820e+01 -7.99159775e+01 -4.81888885e+01 -3.03129387e+00 -2.32962513e+01 -3.83684616e+01 -5.00886993e+01 -3.99440956e+01 -3.24771729e+01 -3.81454048e+01 -4.39248543e+01 -4.13033905e+01 -2.98988647e+01 -1.33434143e+01 -1.41478109e+01 -4.29364357e+01 -7.83218994e+01 -1.15354347e+02 -1.25820923e+02 -5.07766266e+01 2.41832638e+01 6.28741379e+01 3.27905655e+01 -5.25949621e+00 8.44534338e-01 -1.31951513e+01 -3.34580803e+00 -1.79845482e-01 8.60179138e+00 1.32050982e+01 1.07602949e+01 9.86630440e+00 6.47296381e+00 3.92068939e+01 8.05014725e+01 9.44176331e+01 7.01840591e+01 3.88678780e+01 1.32728996e+01 -1.57089405e+01 -1.98728027e+01 1.48893106e+00 1.12345905e+01 -6.14353514e+00 -8.77560139e+00 1.03008947e+01 2.84476986e+01 3.02319756e+01 2.68950653e+01 2.52639465e+01 1.85531254e+01 1.89589577e+01 1.30949802e+01 2.00840855e+01 2.17666931e+01 3.67365456e+01 3.85102730e+01 3.36054878e+01 -4.30156565e+00 -4.54460258e+01 -3.66388359e+01 -2.03204584e+00 3.17494335e+01 1.48047228e+01 5.41755438e+00 -1.26103067e+00 -1.62065312e-01 -7.66414261e+00 -1.12857847e+01 -3.52635422e+01 -4.70256844e+01 -4.49311447e+01 -5.46709347e+00 2.64440708e+01 3.17239246e+01 1.95692825e+01 3.88492241e+01 6.93200760e+01 8.20162888e+01 7.10924530e+01 4.01328545e+01 3.83666878e+01 3.58673019e+01 3.58846664e+01 3.37207603e+01 2.87744961e+01 3.66811943e+01 4.67355881e+01 4.37167549e+01 3.89314575e+01 3.82348328e+01 4.46506882e+01 3.73907089e+01 2.86736660e+01 -4.00453107e-03 -2.72383347e+01 -2.25223351e+01 -6.60190392e+00 1.14528217e+01 5.47217131e+00 1.29675589e+01 3.10025024e+01 2.50193176e+01 -1.19190664e+01 -4.62498093e+01 -4.33851204e+01 -7.35862303e+00 1.64722824e+01 9.53171158e+00 -1.23065257e+00 -3.63144588e+00 3.93136668e+00 -1.90663910e+01 -5.28361855e+01 -6.11362228e+01 -3.19265709e+01 1.47825842e+01 1.24746847e+01 1.01215296e+01 2.00858307e+00 1.04256248e+01 1.33243742e+01 3.24703908e+00 -6.65348387e+00 -1.37388411e+01 -3.85719967e+00 3.62951946e+00 -3.24643040e+00 -3.79355736e+01 -8.44882965e+01 -8.53236694e+01 -5.03115768e+01 -1.05317974e+01 -8.22090149e-01 7.31301832e+00 6.13224220e+00 -3.55648398e+00 -4.11398506e+01 -6.84353485e+01 -9.72493591e+01 -1.01022896e+02 -7.36856613e+01 -4.63832397e+01 -4.81838369e+00 -2.50210094e+01 -4.50269737e+01 -2.28278885e+01 3.54212990e+01 6.83329620e+01 4.37286110e+01 7.18004417e+00 9.35366631e+00 1.23323669e+01 2.10315266e+01 2.45100002e+01 3.52957420e+01 3.77011528e+01 3.86806183e+01 3.56227150e+01 3.20018463e+01 3.34724236e+01 4.16633148e+01 4.67990913e+01 4.09867287e+01 1.56195641e+01 -1.00189915e+01 -2.63040566e+00 2.16153469e+01 5.07358627e+01 2.18728905e+01 -1.31544828e+01 1.52870731e+01 7.49119720e+01 8.16783981e+01 6.84170341e+00 -3.53836861e+01 -1.66862450e+01 1.91467133e+01 1.37634897e+00 -3.15833015e+01 -3.60588646e+01 -1.98875389e+01 7.46694279e+00 4.71930647e+00 1.89837396e+00 1.07709198e+01 1.35331650e+01 3.61230392e+01 5.52102318e+01 2.65084801e+01 -1.94321918e+01 -4.58223991e+01 -2.75758667e+01 -8.98637962e+00 -2.81313019e+01 -4.57998772e+01 -4.79189758e+01 -3.04529705e+01 -1.73558205e-01 -9.28484023e-01 -5.96564341e+00 -1.53920593e+01 -1.65491045e+00 -1.11740732e+01 -2.91996651e+01 -4.01541939e+01 -3.68146706e+01 -7.79387569e+00 9.56128979e+00 2.59010487e+01 2.68378334e+01 2.21933613e+01 5.41224174e+01 8.93284912e+01 8.00144958e+01 3.11121464e+01 -4.81767559e+00 2.17528200e+00 2.19124146e+01 1.37999284e+00 -2.19251461e+01 -2.34414330e+01 -3.95008636e+00 1.84034958e+01 2.35566692e+01 2.09972649e+01 2.40357208e+01 1.84661331e+01 2.27918663e+01 1.45957203e+01 6.23779821e+00 -7.16709495e-01 6.98967028e+00 1.81950474e+01 2.37399445e+01 2.68045330e+01 2.50159073e+01 4.83325844e+01 6.85467529e+01 5.20114822e+01 4.31109810e+00 -1.97178650e+01 2.56075311e+00 3.23978004e+01 4.80878448e+01 5.39459991e+01 5.32105331e+01 4.67217369e+01 4.15060196e+01 4.39405327e+01 3.68871040e+01 3.99154968e+01 4.10778465e+01 4.85267067e+01 5.30752678e+01 5.42254791e+01 4.55401649e+01 3.45388794e+01 3.65525017e+01 4.71008453e+01 5.42462082e+01 4.23814583e+01 3.31100311e+01 2.24751930e+01 1.30902376e+01 -5.68832111e+00 -6.13583231e+00 3.69027472e+00 6.01424551e+00 -2.56074142e+01 -4.61118240e+01 -3.34409561e+01 -8.21478462e+00 -1.11001987e+01 -3.01210308e+01 -3.40611076e+01 -1.68238468e+01 -1.52723157e+00 4.98686743e+00 6.17822504e+00 4.24329758e+00 9.53692198e-01 2.59962916e+00 1.04467993e+01 2.40107751e+00 -1.30763760e+01 -1.92954807e+01 -7.94411755e+00 1.03755360e+01 9.71115112e+00 -4.79345322e-01 9.93344307e+00 2.75513802e+01 3.92274399e+01 3.15205669e+01 2.32364979e+01 2.79041862e+01 2.84292622e+01 2.75030823e+01 2.58160915e+01 2.77341518e+01 2.71533852e+01 2.65060177e+01 2.92835026e+01 3.28218193e+01 3.61711044e+01 3.51761131e+01 2.99745750e+01 2.97048302e+01 1.83471947e+01 8.63061333e+00 9.07846069e+00 2.16930237e+01 3.77047844e+01 4.06986351e+01 3.94497757e+01 4.67015419e+01 5.62637291e+01 5.71107292e+01 4.93337669e+01 3.78411942e+01 3.46882591e+01 3.35699768e+01 2.03409863e+01 8.26093769e+00 4.78063393e+00 1.47011757e+01 2.25102386e+01 2.21439686e+01 2.40381222e+01 2.70608139e+01 2.63205166e+01 3.20952339e+01 4.12998276e+01 3.65334244e+01 2.39895592e+01 1.62136612e+01 2.22494946e+01 2.19320679e+01 6.39982891e+00 -3.04313970e+00 1.33704376e+00 1.63999634e+01 2.15004826e+01 1.65513878e+01 1.71815300e+01 2.24643574e+01 3.17073555e+01 2.96300468e+01 2.40940437e+01 2.21576939e+01 2.42612152e+01 2.94323902e+01 3.20670700e+01 3.40466309e+01 3.44034042e+01 3.14687004e+01 3.22141953e+01 3.36198387e+01 3.03126755e+01 2.53424702e+01 2.32713890e+01 2.79969063e+01 3.15655918e+01 2.98394794e+01 2.47638664e+01 2.78455639e+01 4.67035446e+01 5.95080833e+01 7.54950638e+01 7.13542862e+01 5.07517395e+02 1.36055737e+03 -9.70214905e+02 -3.67093048e+02 5.72902954e+02 1.10127876e+02 1.77400116e+02 1.66850232e+03 1552127104. 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. 0. 0. 2.45095987e+09 -4.46136576e+09 2.64844467e+09 777280384. -8.24539490e+02 -3.36793030e+02 -2.66646862e+00 3.63917503e+01 5.06885643e+01 5.35803833e+01 5.59487648e+01 5.79297752e+01 5.35414124e+01 4.92518272e+01 5.19398117e+01 6.03911552e+01 6.52175980e+01 5.94972687e+01 4.89932785e+01 5.68940659e+01 7.14092636e+01 8.75450668e+01 9.09232635e+01 8.61266403e+01 7.17024689e+01 6.50643311e+01 5.93942680e+01 6.72567215e+01 6.46756592e+01 6.93582764e+01 8.24796753e+01 8.61656189e+01 7.43648300e+01 6.05459251e+01 5.47877007e+01 5.54637032e+01 4.93963051e+01 4.08441315e+01 3.77593842e+01 4.93931122e+01 7.89494781e+01 9.45715332e+01 8.68368835e+01 6.57046890e+01 5.12658997e+01 5.19934196e+01 5.80983925e+01 6.79890366e+01 6.35915298e+01 6.80353012e+01 7.33452682e+01 6.99636307e+01 4.93131409e+01 2.05246334e+01 2.35590153e+01 5.83347473e+01 7.93546143e+01 7.00615234e+01 4.76824074e+01 4.98067398e+01 6.85898743e+01 6.88609238e+01 5.05788498e+01 3.01683617e+01 3.69201393e+01 7.03092346e+01 9.11494598e+01 8.23565369e+01 6.13204041e+01 5.79166336e+01 6.59360886e+01 6.48144531e+01 4.68626442e+01 2.78432198e+01 3.50608864e+01 4.70597496e+01 4.32514305e+01 2.72924690e+01 2.02154121e+01 2.63461170e+01 4.59913177e+01 6.37717438e+01 7.02089005e+01 5.65228653e+01 4.60308876e+01 4.83457947e+01 3.25313072e+01 4.28926182e+00 -1.02430506e+01 1.93134365e+01 6.75444412e+01 9.20042648e+01 7.51679916e+01 3.58669891e+01 -6.20717525e+00 -2.08098049e+01 -6.66823244e+00 2.75397158e+00 -6.84281886e-01 5.30478334e+00 4.66950035e+01 7.77403412e+01 6.96420822e+01 3.41632614e+01 1.36839991e+01 2.69465504e+01 5.23458138e+01 6.24831886e+01 4.38691139e+01 3.06971836e+01 3.50229759e+01 3.90699577e+01 1.61843014e+01 -2.73389530e+01 -3.39308434e+01 1.55638695e+00 4.37336578e+01 4.33098373e+01 1.93572540e+01 -7.93708754e+00 -8.94862461e+00 1.31539745e+01 4.38726616e+01 5.62841721e+01 4.26185646e+01 4.06612816e+01 6.27069511e+01 6.41945190e+01 3.80753670e+01 1.85633886e+00 5.33766794e+00 3.86474037e+01 5.66202278e+01 3.50040894e+01 1.68887291e+01 8.43644810e+00 2.37407417e+01 1.08372250e+01 -1.68718758e+01 -2.53121815e+01 1.25869169e+01 8.81422348e+01 1.24966888e+02 9.69949265e+01 5.24624100e+01 3.64274483e+01 5.27905045e+01 7.30609283e+01 7.12785950e+01 7.29445267e+01 8.57287598e+01 1.17334885e+02 1.28649216e+02 9.90158615e+01 2.42201385e+01 -1.77329998e+01 1.54158592e+01 6.13648033e+01 6.14132729e+01 3.86992912e+01 5.86318016e+01 1.16940613e+02 1.10845940e+02 6.19511490e+01 8.43244839e+00 5.10857697e+01 1.38403412e+02 1.85855652e+02 1.50797241e+02 8.46990204e+01 5.44641609e+01 5.12201729e+01 3.76985207e+01 2.03361435e+01 3.45585442e+01 9.02559967e+01 1.51728134e+02 1.25077652e+02 6.61628799e+01 8.91950512e+00 1.61412354e+01 4.88281364e+01 7.84664764e+01 9.72842865e+01 9.45210495e+01 1.08103943e+02 1.35381790e+02 1.22341537e+02 5.53492661e+01 -4.50870991e+00 1.49979286e+01 9.10809402e+01 1.42364594e+02 1.16392586e+02 6.49762344e+01 2.84566822e+01 3.63545456e+01 2.10495720e+01 -2.36590996e+01 -4.58716583e+01 3.15756512e+00 8.23263779e+01 1.03190826e+02 7.64900665e+01 8.00792217e+00 -1.47697363e+01 -5.91579247e+00 2.53376637e+01 5.02279091e+01 4.47152901e+01 6.85762482e+01 9.23271027e+01 6.89416656e+01 1.77162781e+01 -9.12745857e+00 4.30393964e-01 4.25147820e+01 5.55294952e+01 4.16929131e+01 3.65230713e+01 3.32155495e+01 5.77517738e+01 2.64722137e+01 -1.33023806e+01 -3.52212868e+01 -4.05113792e+01 2.37241802e+01 6.23786049e+01 4.21569633e+01 -2.58094845e+01 -4.27999992e+01 2.90262985e+00 5.12856026e+01 4.63324356e+01 1.72621231e+01 1.57778921e+01 5.82586899e+01 5.94143867e+01 1.42655420e+01 -2.71844387e+01 3.39063549e+00 3.00006809e+01 2.56650829e+00 -1.35518942e+01 9.18744278e+00 3.16739578e+01 5.05968666e+01 3.40457230e+01 6.59156799e+01 7.57639542e+01 6.75104141e+01 7.67610245e+01 1.02616806e+02 1.24954948e+02 6.14903336e+01 2.98615837e+01 1.79437656e+01 7.07965851e+01 5.73956375e+01 5.26314087e+01 6.98145828e+01 1.09193138e+02 1.30260971e+02 5.37830620e+01 8.77416039e+00 -6.72432232e+00 6.21412926e+01 7.40511093e+01 6.01700592e+01 3.27276840e+01 2.53221817e+01 8.17868958e+01 6.14301605e+01 3.65788078e+01 -3.59084854e+01 -6.16238899e+01 -4.70082397e+01 9.57686329e+00 5.60128670e+01 2.33668213e+01 -2.63650494e+01 -5.02855911e+01 -1.74590206e+01 -4.65150261e+01 -4.56976662e+01 -8.85746861e+00 6.35849915e+01 6.53325500e+01 -2.11526051e+01 -5.66690674e+01 -1.74851761e+01 5.85823631e+01 3.27819557e+01 -1.35984688e+01 -3.51928825e+01 -1.73226910e+01 2.50016899e+01 2.76586437e+01 4.51385612e+01 -4.67402124e+00 -3.80239334e+01 -4.57405243e+01 2.75750089e+00 2.79319649e+01 -2.65670323e+00 -4.22254601e+01 -4.86220322e+01 -6.48553925e+01 -1.33318420e+02 -1.64505753e+02 -1.53015503e+02 -1.34024826e+02 -1.39847733e+02 -1.77030701e+02 -1.79917084e+02 -1.50371475e+02 -6.85449066e+01 -4.16551819e+01 -2.68425655e+01 -4.15651321e+01 -2.51983585e+01 2.22389717e+01 4.78393822e+01 6.11124458e+01 2.29715943e+00 -2.53467731e+01 -3.50656128e+01 -1.42591219e+01 -3.00609112e+01 -5.10731888e+01 -8.26424637e+01 -7.41521378e+01 -7.93735428e+01 -1.26327049e+02 -1.54823532e+02 -1.38659302e+02 -7.39874573e+01 -6.08856163e+01 -5.88252716e+01 -7.42513037e+00 3.13757076e+01 5.69002380e+01 -1.17917681e+01 -1.65688858e+01 -2.79683609e+01 -6.27126312e+01 -6.50286179e+01 -2.49363632e+01 6.69954453e+01 8.52744446e+01 1.03620720e+01 -5.62794342e+01 -4.88284798e+01 1.64721813e+01 6.87012939e+01 3.81810989e+01 -2.17041245e+01 -7.79581375e+01 -7.30416183e+01 -2.63962307e+01 1.62487869e+01 7.32951202e+01 8.15897141e+01 8.37882614e+01 9.94823685e+01 9.88922577e+01 1.02774994e+02 1.97263737e+01 1.54720354e+01 1.17105579e+01 1.33774080e+01 1.95785275e+01 6.01823273e+01 1.84963669e+02 2.09045609e+02 1.26115082e+02 -3.79195786e+01 -1.13412086e+02 -2.67075195e+01 9.35216141e+01 1.03826775e+02 -2.97920742e+01 -1.61650375e+02 -1.34303848e+02 -5.33004427e+00 7.50158615e+01 6.45773926e+01 -2.47911625e+01 -2.68604088e+01 3.14939213e+01 8.26795959e+01 1.07195457e+02 2.26295509e+01 2.02497635e+01 5.53800850e+01 9.87179794e+01 1.00123207e+02 4.84373894e+01 8.02237778e+01 8.40653839e+01 -1.05815494e+00 -1.09569016e+02 -9.89168777e+01 6.89767456e+01 1.83694382e+02 1.35278198e+02 4.66804504e+00 -6.97060242e+01 -4.53015366e+01 3.74225121e+01 7.59691391e+01 9.51849365e+01 1.66412945e+01 9.70064545e+00 2.01388702e+01 6.32788010e+01 9.52828903e+01 3.51544724e+01 -1.50576935e+01 -8.70089569e+01 -9.00161972e+01 -5.59478455e+01 1.10025492e+01 1.25046478e+02 1.67156937e+02 8.87506409e+01 -7.44014053e+01 -1.68146896e+02 -9.76904373e+01 7.12180176e+01 1.23076965e+02 6.25749901e-02 -1.59178116e+02 -1.61921921e+02 -2.34873848e+01 5.78816071e+01 5.25844078e+01 -1.97777882e+01 -3.31275139e+01 1.16444035e+01 6.97441177e+01 1.28948853e+02 1.25240265e+02 1.63818054e+02 1.51278580e+02 8.95255280e+01 -1.65328293e+01 -5.47352562e+01 2.04237347e+01 9.48905640e+01 7.12460022e+01 -4.00157204e+01 -1.28965790e+02 -9.72578964e+01 1.74930096e+01 5.37407074e+01 8.09217644e+00 -8.52782669e+01 -7.22487335e+01 1.56796336e+00 7.67228317e+01 1.26981369e+02 7.14086914e+01 6.25788155e+01 3.38304787e+01 4.70195808e+01 5.88888779e+01 7.61035843e+01 1.19743195e+02 7.48655701e+01 5.44601679e+00 -7.13511581e+01 -3.57254066e+01 6.53850021e+01 1.39170212e+02 7.71153488e+01 -3.17289467e+01 -1.02004921e+02 -9.68190613e+01 -1.86931896e+01 1.59046698e+01 3.35662651e+01 -7.11970520e+00 1.26986313e+01 4.87347755e+01 9.45266647e+01 1.42877289e+02 1.17906700e+02 3.78989487e+01 -4.00171089e+01 -4.44562531e+01 -1.25549583e+01 2.69579983e+01 8.89297791e+01 1.22467293e+02 4.54966431e+01 -7.89343109e+01 -1.40256699e+02 -5.32000656e+01 4.92516060e+01 4.97168541e+01 -6.90745392e+01 -1.83780136e+02 -1.60386475e+02 -2.26916237e+01 1.21009598e+02 1.74737976e+02 8.67552872e+01 1.42930174e+01 8.11688709e+00 4.75338058e+01 7.68401184e+01 3.49314270e+01 4.38205261e+01 2.24484043e+01 -2.03091183e+01 -4.37973633e+01 -4.86708984e+01 2.26448040e+01 1.58570557e+01 -6.03520966e+01 -1.53131317e+02 -1.45755280e+02 3.65662026e+00 1.10379807e+02 8.23870163e+01 -4.55247345e+01 -1.32396072e+02 -1.36354904e+02 -3.35983696e+01 6.52577133e+01 1.05241234e+02 3.28898468e+01 -2.54814434e+01 -6.99755859e+01 -6.80278244e+01 -4.98607101e+01 -5.18144646e+01 -5.79979706e+01 -1.21314247e+02 -1.61265335e+02 -1.59390656e+02 -1.06496056e+02 -1.01651821e+01 2.32601528e+01 -3.30463028e+01 -1.24389893e+02 -1.48253860e+02 -9.71408844e+01 -5.87842417e+00 -5.99875736e+00 -7.04578552e+01 -1.60140366e+02 -1.78822601e+02 -8.37007446e+01 1.01634579e+01 4.78596802e+01 -1.94532356e+01 -8.90566559e+01 -8.77812958e+01 -4.82488022e+01 4.88082981e+00 1.70973015e+01 2.26687870e+01 -7.78398180e+00 -6.70708313e+01 -8.61453018e+01 -2.90945282e+01 7.56781921e+01 1.11551552e+02 4.85229836e+01 -3.07525940e+01 -8.55164108e+01 -5.35769730e+01 8.22526741e+00 5.25630150e+01 3.63646698e+01 -1.91622486e+01 -2.94994087e+01 8.07964230e+00 5.66958580e+01 6.56809921e+01 -6.06753540e+00 -5.79475670e+01 -5.10465698e+01 6.29289722e+00 7.52574387e+01 7.81770935e+01 6.80952911e+01 3.87657623e+01 -2.80046463e+00 -2.38973560e+01 -3.49959221e+01 2.72264633e+01 6.80761032e+01 4.96673737e+01 -8.69573236e-01 -5.07550621e+01 -1.11599646e+01 4.12136116e+01 6.93910294e+01 3.94405055e+00 -1.24360443e+02 -1.77105072e+02 -1.11778717e+02 4.17263031e+01 1.12555550e+02 5.11082916e+01 -5.58757439e+01 -7.80188293e+01 -1.01410843e+02 -1.66265259e+02 -1.11671341e+02 1.51180069e+02 1.63426331e+02 -1.54051773e+02 -2.62460425e+03 -4.06496436e+03 1.36677887e+02 7.91347046e+02 8.27101172e+03 8.05724766e+04 -2.73790259e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.52564122e+09 -415164064. 531736864. -1362843520. -1.25140419e+10 252639600. 662267456. -1.07171924e+04 -4.42431445e+03 -4.70909882e+02 -1.66125854e+02 -2.47973755e+02 -1.58099594e+02 -4.20115433e+01 1.15637712e+01 4.93909740e+00 -6.41960526e+01 -1.03731834e+02 -9.03728714e+01 -1.53414297e+01 4.88347549e+01 4.08779716e+01 -5.52028227e+00 -2.01180058e+01 -2.27069016e+01 -2.84008350e+01 -5.88541870e+01 -3.59059563e+01 -2.22462234e+01 -7.04449463e+01 -1.04877899e+02 -7.78417816e+01 1.33070917e+01 6.03168297e+01 -1.53003538e+00 -7.15177002e+01 -1.16919983e+02 -8.73664017e+01 -5.29754019e+00 5.93422241e+01 8.95868912e+01 2.66896229e+01 -1.86922626e+01 -2.35896130e+01 2.28819618e+01 4.92751083e+01 2.03787041e+01 1.07940645e+01 -1.59708147e+01 -4.17237511e+01 -5.31920967e+01 -2.64802513e+01 5.19160423e+01 5.48086700e+01 -1.50367775e+01 -9.55295486e+01 -1.19089111e+02 -4.95752525e+01 1.48733683e+01 1.52840881e+01 -3.06308975e+01 -5.29001656e+01 -9.80926132e+00 5.70238953e+01 7.99547958e+01 5.18465614e+01 -2.64986839e+01 -7.86835861e+01 -7.66030579e+01 -3.16156483e+01 3.05469952e+01 7.08508911e+01 9.00532150e+01 6.86847076e+01 2.82492352e+01 -8.07120609e+00 -2.53003693e+01 -7.72542000e+00 -1.37590990e+01 -5.69151993e+01 -9.78219223e+01 -9.83045120e+01 -4.82558289e+01 -1.11013346e+01 -1.99418392e+01 -4.22437668e+01 -7.68993683e+01 -9.75993195e+01 -7.68602524e+01 -2.68311768e+01 5.55186510e+00 -2.40364990e+01 -6.25973701e+01 -5.94771843e+01 -4.28714561e+01 -3.09841938e+01 -4.29588165e+01 -2.95719471e+01 -3.59195175e+01 -5.41195602e+01 -6.90325012e+01 -5.42368469e+01 -2.75276542e+00 1.86185110e+00 -4.61625977e+01 -1.08738892e+02 -1.28347748e+02 -8.95806274e+01 -4.27388992e+01 -2.78608456e+01 -3.57274437e+01 -5.26160851e+01 -5.20330276e+01 -4.09827461e+01 -1.79263439e+01 -4.84080410e+00 -2.95669022e+01 -7.41281509e+01 -8.46086197e+01 -6.72569351e+01 -5.02766380e+01 -5.07148819e+01 -3.69018784e+01 -3.75377083e+01 -7.01977844e+01 -1.07992317e+02 -1.06450035e+02 -5.68264694e+01 -3.48207703e+01 -6.34540100e+01 -1.03369705e+02 -1.08499474e+02 -7.15136185e+01 -3.38969765e+01 -2.42624683e+01 -3.65010071e+01 -6.63522491e+01 -9.05669861e+01 -8.08915100e+01 -5.11544724e+01 -2.74999676e+01 -4.80925560e+01 -7.97144699e+01 -8.93125610e+01 -7.88889618e+01 -6.46189957e+01 -5.50261078e+01 -3.76204987e+01 -3.12348804e+01 -4.08521042e+01 -5.56781616e+01 -5.69865913e+01 -3.95643005e+01 -2.92640133e+01 -4.65340080e+01 -8.00935745e+01 -1.05228104e+02 -9.46106262e+01 -6.11683426e+01 -3.63320885e+01 -3.86091995e+01 -5.55728493e+01 -6.40788116e+01 -5.91073074e+01 -5.56612968e+01 -4.48980637e+01 -4.82185707e+01 -5.22440605e+01 -6.14665909e+01 -7.30184937e+01 -8.03491669e+01 -8.18517075e+01 -6.63975525e+01 -5.77350006e+01 -6.77296066e+01 -7.80229645e+01 -7.09112930e+01 -5.06891632e+01 -3.92618027e+01 -4.76156960e+01 -5.59357834e+01 -6.43322449e+01 -6.44577103e+01 -5.89498596e+01 -5.59093285e+01 -5.47543678e+01 -6.54415894e+01 -6.29385223e+01 -5.65485649e+01 -4.70196686e+01 -3.78248405e+01 -3.28321495e+01 -2.91485939e+01 -3.95237312e+01 -5.31735344e+01 -5.96512413e+01 -5.94061737e+01 -5.21244583e+01 -5.26716728e+01 -5.89291039e+01 -6.66808624e+01 -7.10341873e+01 -6.12140694e+01 -4.99430885e+01 -4.37353020e+01 -4.74639397e+01 -5.27317200e+01 -5.46866989e+01 -5.43902473e+01 -5.31369629e+01 -5.13225517e+01 -5.35329170e+01 -5.67999496e+01 -5.91156235e+01 -5.70615883e+01 -5.62830544e+01 -5.55486412e+01 -5.47843857e+01 -5.45419731e+01 -5.56692619e+01 -5.66193352e+01 -5.68053856e+01 -5.68205681e+01 -5.73877182e+01 -5.77346687e+01 -5.76366692e+01 -5.72261200e+01 -5.70086899e+01 -5.71018486e+01 -5.80038300e+01 -5.83065987e+01 -5.77013931e+01 -5.60830574e+01 -5.54325867e+01 -5.67693939e+01 -5.76991806e+01 -5.76787567e+01 -5.74154015e+01 -5.77079773e+01 -5.72664604e+01 -5.70132027e+01 -5.68656311e+01 -5.68452911e+01 -5.71609802e+01 -5.69735069e+01 -5.62631264e+01 -5.44790154e+01 -5.41043777e+01 -5.51225014e+01 -5.62294197e+01 -5.51285477e+01 -5.34774437e+01 -5.43717384e+01 -5.66274071e+01 -6.05417290e+01 -6.23803062e+01 -6.12350502e+01 -5.95803490e+01 -5.65168381e+01 -5.77869301e+01 -5.78437042e+01 -5.75905304e+01 -5.55660286e+01 -5.58035660e+01 -5.58877525e+01 -5.64124031e+01 -5.38966522e+01 -5.34693756e+01 -5.29487419e+01 -5.48968620e+01 -5.27193642e+01 -5.14062538e+01 -4.77258377e+01 -4.75554085e+01 -4.99912071e+01 -5.24548759e+01 -5.46325264e+01 -5.31612854e+01 -5.15404854e+01 -4.77659454e+01 -4.90277901e+01 -4.87503433e+01 -5.51991692e+01 -5.75109215e+01 -5.48986740e+01 -5.18507233e+01 -5.20390778e+01 -5.54840622e+01 -5.50013809e+01 -5.28447685e+01 -5.56203575e+01 -5.50424118e+01 -5.23490829e+01 -5.04836578e+01 -5.34961548e+01 -5.57388611e+01 -5.29997826e+01 -5.56902657e+01 -6.26758919e+01 -6.48410797e+01 -6.02342262e+01 -5.81530075e+01 -6.24681396e+01 -6.32658310e+01 -6.36325073e+01 -6.15955200e+01 -6.01998634e+01 -5.58884506e+01 -5.48039360e+01 -5.86232872e+01 -5.72852516e+01 -5.56148415e+01 -5.53924141e+01 -5.60767746e+01 -4.82255020e+01 -3.71538811e+01 -3.94436531e+01 -4.65504646e+01 -5.31418610e+01 -5.34806252e+01 -5.34848938e+01 -5.54321022e+01 -5.40237541e+01 -5.85715523e+01 -6.15979729e+01 -6.12787857e+01 -6.30296898e+01 -6.55902481e+01 -6.82730865e+01 -5.28770065e+01 -5.21851158e+01 -5.10042686e+01 -5.56422348e+01 -5.16507492e+01 -5.28904800e+01 -5.77408867e+01 -5.90488129e+01 -6.17808495e+01 -6.58589401e+01 -6.27007408e+01 -5.85091896e+01 -4.83651619e+01 -5.33913307e+01 -5.51589508e+01 -6.41385803e+01 -6.39967880e+01 -5.41352386e+01 -4.70392532e+01 -4.54657135e+01 -5.88463860e+01 -6.06876869e+01 -5.58106537e+01 -5.04102135e+01 -4.50967712e+01 -4.59393845e+01 -4.15659485e+01 -3.99930458e+01 -3.24037933e+01 -3.25034332e+01 -4.02996140e+01 -5.26381378e+01 -5.67033691e+01 -5.28737030e+01 -4.72663231e+01 -4.69175720e+01 -4.26854897e+01 -3.96121635e+01 -3.46051788e+01 -3.69870949e+01 -4.61743546e+01 -4.38749619e+01 -2.41322403e+01 -3.62221599e-01 -7.73624182e+00 -2.97752838e+01 -5.59784317e+01 -4.12293320e+01 -2.85930099e+01 -1.88311920e+01 -2.98363171e+01 -4.41410751e+01 -3.64050751e+01 -2.64026108e+01 -1.86334286e+01 -2.36540451e+01 -2.74309444e+01 -1.79569206e+01 -6.54801369e+00 -3.95555615e+00 -1.82835541e+01 -3.80546951e+01 -4.19749718e+01 -3.31458817e+01 -2.82972507e+01 -2.82907848e+01 -4.38815842e+01 -3.88658829e+01 -2.54118195e+01 -1.50178266e+00 -1.17239122e+01 -2.94604607e+01 -4.95301933e+01 -4.09767265e+01 -3.72123070e+01 -4.14132462e+01 -6.21200294e+01 -8.92845230e+01 -8.63394470e+01 -6.58031769e+01 -3.84513321e+01 -3.44324303e+01 -2.96940060e+01 -1.53385668e+01 -6.06876707e+00 -3.99322090e+01 -8.14804535e+01 -8.97008286e+01 -5.81679268e+01 -3.09600410e+01 -3.81420898e+01 -4.67133026e+01 -5.99379158e+01 -6.88853760e+01 -5.88528557e+01 -4.44832230e+01 -2.19030762e+01 -2.33891563e+01 -1.30032606e+01 -4.16765823e+01 -8.21820450e+01 -9.48296432e+01 -7.48885269e+01 -3.73479729e+01 -1.24425907e+01 5.15264368e+00 6.77121830e+00 -1.69153404e+01 -3.10774746e+01 -4.05027657e+01 -4.41661263e+01 -4.37873116e+01 -5.06124268e+01 -5.38356934e+01 -5.24683914e+01 -5.13791313e+01 -3.69843521e+01 3.78011322e+00 1.07628281e+02 2.05790894e+02 1.91285294e+02 1.98884247e+02 1.79521622e+02 3.29605316e+02 1.37679718e+02 6.84404144e+01 -2.71728973e+02 1.35235242e+03 1.35402115e+02 8.26049377e+02 3.28034888e+03 -3.04405518e+03 -1.54466230e+04 -3.51511484e+04 -543421312. 2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 1442105088. 1442105088. -694983616. -1072801600. -869534464. -362033504. 2.58184141e+04 1.00313115e+04 2.89760132e+03 5.01285797e+02 4.01540161e+02 1.06397682e+02 3.64837151e+01 1.21772394e+01 1.06280518e+01 1.13609180e+01 1.25136375e+01 1.52341337e+01 -3.48336029e+01 -1.52752563e+02 -2.31468994e+02 -1.91242966e+02 -1.48134766e+02 -7.67276077e+01 8.55315628e+01 1.77136414e+02 1.62524277e+02 1.26575661e+02 1.67518097e+02 2.54961411e+02 1.42297607e+02 1.87194748e+02 1.63646881e+02 1.22956818e+02 1.34929895e+01 -2.31948929e+01 -4.17216187e+01 -5.75873489e+01 -7.40924301e+01 -8.98047714e+01 -9.62666473e+01 -8.55513763e+01 -6.48688354e+01 -6.01861343e+01 -5.90458641e+01 -6.90635757e+01 -7.70476227e+01 -8.91562500e+01 -8.00650558e+01 -4.32624893e+01 3.19015026e+00 1.46527863e+01 2.93194383e-01 -2.31558380e+01 -2.98725109e+01 -4.86298828e+01 -4.66043930e+01 -3.92768974e+01 -3.36255035e+01 -4.48441620e+01 -5.52416534e+01 -5.55998344e+01 -7.06162262e+01 -4.89028854e+01 -3.26496887e+01 -1.57606087e+01 -1.71384850e+01 -7.37946749e+00 -1.39973831e+00 -9.31684208e+00 -2.16709213e+01 -2.01234798e+01 -2.55310555e+01 -5.60465813e+01 -6.67376862e+01 -6.14609451e+01 -3.35945969e+01 -2.45119705e+01 -2.28539143e+01 2.05492878e+00 4.06694031e+01 2.90485554e+01 1.42371349e+01 -7.44469929e+00 5.51472549e+01 9.65405579e+01 9.21581268e+01 5.61205177e+01 2.97532196e+01 3.90272446e+01 4.23815384e+01 3.17938747e+01 3.81255150e+01 6.11162643e+01 9.37554474e+01 8.37130661e+01 3.36794930e+01 -1.15893373e+01 -2.81697388e+01 -1.57212067e+01 -7.19747353e+00 3.95560312e+00 -2.67054539e+01 -5.65066833e+01 -3.79852295e+01 6.71241331e+00 2.04449539e+01 -1.30065622e+01 -3.92182350e+01 1.07427607e+01 5.05459175e+01 4.47102203e+01 -9.54226303e+00 -5.59374313e+01 -5.79073029e+01 -5.07556190e+01 -4.13960152e+01 -3.89736977e+01 -2.31441803e+01 -1.48295803e+01 -1.85764256e+01 -2.11460781e+01 -1.29356861e+01 -3.35918903e+00 -1.40185881e+01 -2.56061306e+01 -2.56188583e+01 -1.61486626e+01 -8.47488689e+00 3.13969021e+01 6.86974716e+01 6.27477341e+01 2.22425098e+01 -8.21844578e+00 3.71184883e+01 8.46754761e+01 8.55926132e+01 5.01676903e+01 1.39261541e+01 8.12246799e+00 5.60915709e+00 -1.26138544e+01 -2.28131938e+00 2.27096200e+00 7.49988747e+00 -6.87812233e+00 -2.61024265e+01 -2.09122219e+01 -1.21309166e+01 3.54106545e+00 -1.54149961e+00 -2.42060566e+00 1.37331414e+00 2.34581203e+01 6.39665565e+01 1.06106880e+02 1.01607681e+02 7.25046768e+01 2.69269657e+01 5.66861038e+01 9.32351151e+01 9.19292755e+01 4.18106155e+01 -5.60079241e+00 -3.75427008e-01 1.26495275e+01 2.48650589e+01 2.07486210e+01 1.97827530e+01 1.36158009e+01 4.07392836e+00 4.48656607e+00 2.76668606e+01 6.60686188e+01 6.40674591e+01 4.16848106e+01 5.47325468e+00 -4.05472469e+00 -2.17745137e+00 3.14076385e+01 7.03197708e+01 6.65743790e+01 4.23169403e+01 1.98371468e+01 2.18314590e+01 7.10608768e+00 3.03618183e+01 7.65950851e+01 9.18462448e+01 6.42086945e+01 2.20015697e+01 1.66049442e+01 2.31452789e+01 1.78470688e+01 1.77655735e+01 2.38312073e+01 2.63935204e+01 6.89714355e+01 1.10638977e+02 1.09664917e+02 6.83945312e+01 2.75042477e+01 4.20061874e+01 4.11299057e+01 7.34939117e+01 1.02795662e+02 9.64606018e+01 4.42223129e+01 -2.23953247e+00 1.48662481e+01 2.74336281e+01 3.36085510e+01 1.62756977e+01 5.50854206e+00 -1.55260897e+00 4.17085588e-01 4.34793234e+00 1.04236660e+01 5.55321264e+00 3.77227378e+00 -1.91009369e+01 -3.15838184e+01 -4.06258316e+01 -3.55696716e+01 -2.76038971e+01 -2.60498524e+01 -2.78566055e+01 -2.68219414e+01 -2.00392952e+01 -1.14978933e+01 -2.19848766e+01 -1.49210091e+01 -1.13510914e+01 -1.08637857e+01 -2.93373528e+01 -3.26714211e+01 -1.37238474e+01 -3.12783575e+00 -3.53438663e+00 -1.38409605e+01 -1.51380372e+00 6.62316620e-01 1.59271946e+01 1.53570461e+01 1.53374062e+01 -8.38717651e+00 -3.54664841e+01 -1.25476017e+01 4.15616112e+01 7.37446594e+01 5.96542358e+01 3.41759377e+01 2.63046665e+01 3.38841476e+01 4.07615166e+01 5.37000465e+01 5.70951271e+01 5.14244843e+01 4.14271774e+01 2.56633415e+01 1.47432432e+01 1.41369972e+01 2.02701015e+01 3.11898117e+01 3.50732422e+01 3.54145737e+01 3.28150864e+01 3.43208122e+01 2.76879406e+01 2.50353832e+01 1.40275030e+01 2.64501324e+01 6.34549675e+01 1.01774071e+02 9.81407471e+01 6.77485123e+01 3.53988190e+01 2.61059742e+01 2.40578632e+01 3.85583725e+01 6.34650307e+01 7.81599960e+01 8.70328445e+01 6.00285645e+01 3.51348190e+01 7.35233927e+00 2.19133530e+01 3.41933289e+01 3.60958939e+01 2.65461178e+01 1.91346951e+01 1.20067425e+01 2.15124969e+01 3.73586159e+01 5.13509560e+01 5.31554985e+01 5.24074059e+01 8.35783615e+01 1.13681015e+02 1.01161354e+02 5.77434235e+01 2.39600544e+01 4.44875107e+01 6.28392181e+01 5.80904961e+01 4.96643639e+01 6.92848816e+01 1.02604332e+02 1.00342560e+02 5.97810173e+01 1.92113152e+01 3.15386410e+01 4.90621414e+01 4.75096130e+01 2.57932396e+01 2.25416927e+01 2.87104092e+01 4.50042953e+01 3.33366928e+01 1.25123072e+01 9.95386791e+00 1.53264151e+01 2.29247646e+01 1.12798281e+01 3.93342514e+01 7.36886902e+01 7.65038910e+01 8.44189529e+01 1.04360718e+02 1.36768097e+02 1.39583130e+02 1.18512619e+02 1.24160194e+02 1.01515030e+02 9.74246368e+01 6.72104263e+01 3.70653572e+01 -3.84660721e+00 -1.81749058e+01 -5.10226631e+00 4.24621391e+00 1.49308271e+01 1.45930738e+01 1.88230286e+01 1.42687740e+01 6.20278025e+00 3.21600075e+01 7.62738953e+01 9.64288330e+01 8.57704391e+01 5.53787613e+01 4.84558105e+01 4.04334221e+01 2.52434444e+01 4.21722450e+01 4.88976784e+01 6.24689751e+01 6.65158920e+01 8.18149490e+01 1.07906425e+02 8.21228561e+01 5.49251747e+01 4.42548523e+01 8.02049255e+01 8.88101349e+01 7.36145706e+01 3.83552628e+01 6.77335358e+01 9.58275604e+01 1.08259300e+02 8.23885651e+01 5.56802635e+01 8.24744263e+01 1.10377022e+02 1.02581940e+02 5.95931435e+01 2.84620476e+01 5.60445023e+01 7.44509964e+01 5.25381660e+01 1.10036125e+01 3.79224281e+01 8.50437393e+01 1.07593956e+02 8.65351944e+01 7.18775864e+01 7.76164703e+01 1.03888168e+02 1.25976379e+02 1.14450546e+02 6.69237823e+01 3.20717888e+01 3.43759537e+01 4.59815788e+01 4.67945290e+01 4.40943718e+01 4.82792320e+01 5.81102333e+01 7.47097778e+01 7.39446564e+01 5.37279587e+01 3.91558495e+01 3.33962517e+01 5.87513771e+01 7.71457748e+01 7.37083588e+01 6.28660774e+01 4.37788506e+01 5.20420418e+01 5.27038345e+01 4.48087044e+01 2.55721531e+01 2.61742878e+01 7.22832413e+01 1.09557793e+02 7.64253464e+01 1.56205101e+01 1.21311150e+01 6.26710129e+01 8.13795242e+01 5.10550308e+01 4.05142593e+01 6.05415039e+01 7.11222839e+01 6.26134491e+01 4.29215965e+01 5.65473824e+01 6.84503021e+01 7.82358398e+01 6.59020844e+01 4.67126923e+01 4.75574150e+01 4.83798332e+01 6.89504929e+01 8.31763153e+01 8.33706741e+01 6.34463348e+01 6.27123756e+01 1.11014832e+02 1.34726898e+02 1.21892319e+02 7.85495529e+01 7.54070129e+01 8.86226196e+01 7.10819168e+01 3.25289650e+01 2.30784969e+01 4.97610588e+01 6.98528824e+01 6.25524788e+01 5.13077812e+01 6.43180695e+01 7.09658508e+01 7.50729599e+01 6.77901154e+01 5.22436523e+01 3.99784508e+01 3.47099075e+01 4.34198494e+01 5.34611778e+01 6.66220398e+01 7.22894058e+01 7.60276337e+01 8.67351685e+01 8.70077744e+01 6.85007782e+01 4.89428673e+01 5.36466446e+01 7.57967453e+01 8.19470215e+01 7.73130112e+01 8.95861893e+01 1.22401596e+02 1.42937378e+02 1.29435150e+02 8.87479935e+01 7.74750137e+01 8.39405136e+01 8.77923126e+01 7.25484238e+01 5.57695694e+01 5.23140373e+01 4.62750740e+01 5.24564743e+01 5.93313560e+01 5.97266388e+01 4.60822487e+01 4.42792282e+01 7.30023880e+01 8.74569168e+01 7.41667557e+01 5.64673271e+01 7.42062225e+01 8.72554932e+01 6.94655914e+01 3.59918823e+01 1.40825043e+01 2.14426975e+01 2.49078922e+01 3.36124229e+01 3.29140892e+01 3.59938278e+01 3.46643066e+01 4.43190193e+01 5.44309006e+01 5.27205658e+01 3.62890739e+01 4.36325798e+01 7.76545334e+01 9.92962112e+01 1.03950676e+02 9.40892563e+01 8.22770462e+01 6.52094803e+01 5.35501137e+01 5.36795921e+01 5.14836655e+01 5.07480545e+01 5.26458168e+01 5.75197830e+01 5.63312263e+01 5.70295830e+01 5.80126381e+01 5.64112473e+01 5.63103981e+01 5.68229370e+01 7.18042145e+01 8.71745377e+01 8.62914581e+01 7.29076843e+01 6.22629967e+01 6.32934151e+01 6.21298141e+01 6.27259521e+01 6.13032227e+01 6.32936897e+01 6.35817184e+01 7.27310791e+01 8.33469467e+01 7.86017761e+01 6.46065140e+01 6.12506561e+01 8.33503189e+01 9.87048798e+01 8.91185760e+01 6.73232880e+01 6.57093124e+01 7.41699753e+01 7.39212875e+01 6.42405167e+01 5.51623459e+01 6.43670578e+01 7.29487534e+01 8.20837784e+01 8.47079544e+01 7.42970200e+01 6.35471687e+01 6.43411255e+01 8.38706512e+01 9.23502350e+01 7.95386810e+01 6.20333786e+01 6.53669205e+01 7.77513733e+01 8.05757217e+01 7.30407104e+01 6.53172302e+01 7.03213120e+01 7.56749878e+01 7.79334106e+01 7.23656387e+01 6.59396515e+01 6.24698601e+01 7.01012878e+01 7.84480667e+01 7.89228516e+01 7.25879974e+01 6.17003670e+01 6.66974182e+01 7.16177368e+01 7.37517319e+01 6.81530457e+01 6.72397842e+01 7.28354111e+01 7.12221375e+01 6.47090759e+01 5.64299583e+01 5.55298462e+01 5.44803276e+01 5.97922592e+01 6.54118423e+01 6.78448715e+01 6.45049667e+01 6.00298996e+01 5.72231827e+01 5.80211601e+01 6.47910309e+01 8.84159927e+01 1.08039192e+02 1.20033089e+02 1.08659149e+02 3.53159698e+02 5.27462158e+02 -3.12614075e+02 -2.07209549e+01 3.73411774e+02 4.20712799e+02 4.62951782e+02 1.42356653e+03 3.47438745e+03 386115904. 594307968. 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. 0. -297227584. 586463040. 563237184. 3.53333301e+03 1.18422192e+03 4.42879364e+02 1.57196335e+02 1.25612206e+02 9.01758041e+01 7.96190796e+01 7.87538528e+01 8.44520264e+01 8.67079544e+01 8.36076202e+01 8.72023926e+01 9.56209793e+01 1.02242111e+02 9.43170319e+01 7.62873840e+01 6.81355133e+01 7.41672287e+01 8.52520752e+01 9.09938126e+01 8.73963928e+01 8.58438263e+01 8.84597168e+01 9.43991928e+01 8.98195648e+01 7.92929688e+01 7.47151031e+01 7.93197021e+01 9.05184326e+01 9.36045303e+01 8.50130386e+01 7.07402420e+01 6.46953049e+01 7.27227249e+01 7.23131180e+01 6.23505363e+01 6.65229416e+01 8.62737732e+01 9.99900970e+01 8.51279984e+01 5.10821762e+01 4.13906593e+01 5.69862709e+01 7.66639328e+01 8.44275436e+01 8.40430527e+01 8.06434555e+01 8.04579620e+01 8.28655777e+01 7.98524399e+01 5.36746826e+01 3.61438904e+01 4.46094971e+01 7.03480606e+01 8.51980591e+01 7.39269028e+01 5.64704170e+01 4.84906731e+01 6.55396881e+01 7.01260147e+01 6.17547073e+01 6.75359116e+01 8.72895050e+01 1.06947678e+02 1.04806854e+02 7.13956833e+01 6.11530380e+01 7.01986542e+01 9.54746780e+01 8.99493179e+01 6.90943756e+01 7.55784149e+01 9.27968826e+01 1.03307999e+02 8.74265747e+01 5.46345253e+01 3.77907104e+01 4.94957962e+01 8.39613876e+01 1.04745750e+02 9.76051865e+01 8.35128708e+01 8.79276505e+01 1.04720734e+02 9.91855621e+01 7.56965637e+01 6.43092880e+01 8.92614365e+01 1.23332512e+02 1.26109123e+02 8.83074493e+01 5.67444458e+01 5.23996849e+01 8.00948639e+01 8.27716827e+01 7.77281876e+01 9.54342651e+01 1.31763504e+02 1.48092957e+02 1.15968971e+02 6.23062897e+01 3.50424728e+01 4.88721428e+01 8.12799377e+01 1.13979225e+02 1.36850296e+02 1.33503998e+02 1.27777557e+02 1.30005264e+02 1.19242424e+02 8.34379654e+01 4.85275269e+01 6.87666473e+01 1.20559570e+02 1.47001022e+02 1.26020798e+02 6.90507126e+01 4.13583565e+01 6.30016365e+01 9.08861084e+01 9.53792191e+01 9.49167633e+01 1.17999352e+02 1.66094849e+02 1.62395187e+02 1.18361664e+02 6.86977615e+01 6.85814209e+01 1.03066246e+02 1.27450554e+02 1.31392929e+02 1.13236893e+02 8.92395859e+01 7.78260727e+01 1.09366447e+02 1.24455528e+02 1.03609627e+02 7.50311203e+01 6.79232178e+01 8.39270248e+01 8.64159088e+01 6.98908005e+01 7.06597748e+01 8.74932022e+01 1.09753983e+02 1.11787437e+02 8.58634491e+01 7.60710068e+01 9.46933289e+01 1.15013275e+02 9.05472565e+01 1.29414673e+01 -2.45489883e+01 2.62500572e+01 9.39697342e+01 1.06605843e+02 7.29914703e+01 4.92673035e+01 5.43547173e+01 5.45565948e+01 3.02103157e+01 -8.79529095e+00 -2.65074158e+01 -7.86938667e+00 4.55193825e+01 8.20000153e+01 5.44229393e+01 3.22961197e+01 4.19999084e+01 7.75860519e+01 5.74296455e+01 -5.85446501e+00 -7.16462517e+00 1.69087887e+01 4.57342987e+01 1.71070194e+01 -5.72977676e+01 -9.49061356e+01 -5.66108475e+01 3.07658691e+01 6.76191177e+01 5.87728424e+01 6.04804726e+01 8.79369812e+01 7.44465256e+01 2.20689106e+01 -3.95639267e+01 -2.58371391e+01 2.46516304e+01 1.11867371e+02 1.39441925e+02 1.21401520e+02 5.82883415e+01 1.84220982e+01 1.58593779e+01 -6.64041400e-01 -2.62684269e+01 -9.98664665e+00 4.54530220e+01 1.00650871e+02 6.25938034e+01 -1.92826843e+01 -6.94920731e+01 -1.20512562e+01 8.17052612e+01 1.18788712e+02 7.63969116e+01 2.26019230e+01 4.75299454e+01 9.09225845e+01 8.24718094e+01 2.03366165e+01 -3.96569133e+00 4.75456772e+01 1.26519775e+02 1.40879791e+02 1.04989975e+02 6.60684662e+01 7.13861771e+01 8.76343994e+01 7.82126694e+01 4.92576866e+01 7.24305801e+01 1.12903664e+02 1.20862976e+02 1.09455185e+02 6.63087463e+01 5.27756081e+01 6.91077728e+01 6.54917145e+01 7.24145584e+01 3.24094009e+01 7.05585632e+01 1.01580124e+02 1.26014900e+02 1.00955269e+02 8.16598797e+00 -3.90250702e+01 -2.85497875e+01 7.86530914e+01 1.32263672e+02 1.42306641e+02 1.00505219e+02 7.40052032e+01 1.00768585e+02 9.94124680e+01 6.40616913e+01 4.19457626e+01 7.38796539e+01 1.02544746e+02 4.20548515e+01 -3.58538017e+01 -2.39178448e+01 2.41481819e+01 4.87016602e+01 2.49193306e+01 -3.24647446e+01 2.14898319e+01 5.38332329e+01 9.52191391e+01 6.90563660e+01 6.12541819e+00 -2.51924496e+01 -5.05534706e+01 3.10032129e+00 2.82041512e+01 4.39573479e+01 9.26252902e-01 -3.18386459e+00 -2.35260129e+00 -1.00396185e+01 -3.98939476e+01 -6.05376396e+01 7.00507975e+00 5.05810394e+01 5.55351257e+01 -3.88167810e+00 4.77689171e+00 2.84991608e+01 5.57281075e+01 7.90403442e+01 6.36071091e+01 6.90460434e+01 7.58297539e+00 -1.67359314e+01 -3.05197468e+01 -2.30461979e+01 1.09712803e+00 1.96419258e+01 8.70380707e+01 1.15392570e+02 9.98125534e+01 -4.00538445e+00 -2.45664711e+01 -1.39458311e+00 2.68985386e+01 2.30198822e+01 4.50882645e+01 1.39635529e+02 1.73426605e+02 1.36240952e+02 2.74492836e+01 2.00315022e+00 3.80809250e+01 9.50842514e+01 1.04247047e+02 4.78910828e+01 4.25046959e+01 3.14188900e+01 8.85774994e+01 1.14620216e+02 1.15198120e+02 6.77003479e+01 4.42649460e+01 9.04037781e+01 1.35161896e+02 1.05596481e+02 3.42658730e+01 5.43105888e+01 9.09055481e+01 9.46923828e+01 5.77262154e+01 6.20102615e+01 1.29341721e+02 1.54980743e+02 1.30444153e+02 5.35549965e+01 5.29685478e+01 6.86095047e+01 1.02372269e+02 8.31255646e+01 5.61410446e+01 6.47179947e+01 6.00608826e+01 1.04317329e+02 1.21249367e+02 1.22598991e+02 7.99490662e+01 7.21431732e+01 9.50269547e+01 1.30916275e+02 1.02483742e+02 4.12528381e+01 2.64282646e+01 2.04360142e+01 -2.37712622e+00 -6.05989227e+01 -4.29506989e+01 1.32442617e+01 2.51274490e+01 -1.00078621e+01 -5.80287933e+01 6.83111000e+00 3.49830971e+01 6.91131744e+01 1.06720268e+02 1.26113106e+02 8.66072464e+01 -1.71327019e+01 -4.61062393e+01 3.35800247e+01 1.00495941e+02 5.73576241e+01 -3.44292870e+01 -9.19561768e+01 -2.67962112e+01 2.02918243e+01 9.77841568e+00 -2.41958313e+01 -6.49776382e+01 -1.05721390e+02 -1.71769180e+02 -1.54266434e+02 -8.77746964e+01 -7.01238937e+01 -1.00079758e+02 -1.40324326e+02 -4.85784454e+01 -5.51503038e+00 2.15571938e+01 7.66192722e+00 -1.10298166e+01 -5.62477798e+01 -1.72331894e+02 -1.95194443e+02 -9.72334213e+01 6.64220047e+01 1.00335243e+02 -3.47162857e+01 -1.47981796e+02 -1.47815262e+02 -5.44838219e+01 -1.18235950e+01 -4.18343697e+01 -1.22411049e+02 -1.63281494e+02 -1.17153854e+02 2.35823154e+00 3.70337753e+01 -2.01408997e+01 -1.02859917e+02 -1.95579483e+02 -1.92219589e+02 -1.60242920e+02 -4.40727425e+01 6.65435104e+01 1.11466492e+02 3.82915993e+01 -1.08766701e+02 -1.91179886e+02 -1.13964348e+02 -6.39909554e+00 -1.03393068e+01 -1.30545700e+02 -2.36177216e+02 -1.94262070e+02 -6.63869629e+01 3.87289925e+01 4.96285515e+01 -3.39659653e+01 -9.90815506e+01 -1.51218323e+02 -7.31614685e+01 -3.90450592e+01 -4.67619610e+00 -5.75474129e+01 -9.28095093e+01 -4.06367760e+01 8.27199459e+00 8.91221771e+01 9.45440140e+01 5.91690903e+01 -1.23936596e+01 -1.18520554e+02 -1.47212616e+02 -7.27375107e+01 8.12117386e+01 1.62667053e+02 9.45853806e+01 -6.04587135e+01 -1.51480103e+02 -1.05564941e+02 -3.64087868e+01 -3.74833641e+01 -9.73265305e+01 -1.25009407e+02 -1.28041336e+02 -5.66711502e+01 -1.84385502e+00 5.54540253e+01 5.91989517e+01 2.71082954e+01 -2.00249157e+01 -8.32404785e+01 -8.16597748e+01 -2.50980072e+01 3.72596703e+01 3.77093430e+01 -3.36687012e+01 -1.13398430e+02 -8.33524628e+01 -8.39325428e+00 3.71984406e+01 -2.11041107e+01 -1.20013977e+02 -1.12778053e+02 -4.72281761e+01 5.66587143e+01 5.45166206e+01 -2.37839146e+01 -9.05752411e+01 -1.38423355e+02 -5.28870773e+01 -1.61965981e+01 2.11741505e+01 1.83401337e+01 1.29799767e+01 1.83115139e+01 -2.25539169e+01 1.09477453e+01 5.53338928e+01 5.83759003e+01 -9.08104229e+00 -1.12399063e+02 -1.63647690e+02 -1.07299919e+02 3.25578957e+01 1.46435928e+02 1.31895447e+02 -4.94898748e+00 -1.33697281e+02 -1.78485291e+02 -8.32527542e+01 1.36361761e+01 4.46959610e+01 -2.60058022e+01 -1.10735512e+02 -8.55833282e+01 -2.80502014e+01 3.51856194e+01 4.36436386e+01 2.07990093e+01 -3.41499214e+01 -9.49604111e+01 -8.53410873e+01 -1.29646206e+01 8.26849060e+01 9.43171005e+01 1.51675615e+01 -8.11952362e+01 -6.39793587e+01 2.12570591e+01 7.20174026e+01 3.32349625e+01 -2.05576210e+01 -3.93413620e+01 -5.82473831e+01 -2.74823074e+01 -1.43805075e+00 -2.23114624e+01 -3.34296074e+01 -7.30837936e+01 -2.52181110e+01 5.35080147e+00 6.27400169e+01 9.62746811e+01 5.31789742e+01 4.27239370e+00 -7.60350876e+01 -9.98016739e+01 -5.58735580e+01 2.11380177e+01 2.95261097e+01 -4.80582542e+01 -1.30668137e+02 -1.13845207e+02 -5.93192635e+01 2.49515724e+01 4.30157623e+01 1.01822643e+01 -3.17661152e+01 -5.87706642e+01 3.42846918e+00 5.73677177e+01 1.20078484e+02 1.07291138e+02 2.81471863e+01 2.97633324e+01 5.42268295e+01 1.27916794e+02 1.33797424e+02 1.09887215e+02 5.37787895e+01 -4.27577171e+01 -7.67084732e+01 -5.21940613e+01 3.16959763e+01 6.64650574e+01 -6.04439545e+00 -8.40299530e+01 -9.21067276e+01 7.19726562e+00 7.10918198e+01 5.19421043e+01 -3.84186096e+01 -1.08401253e+02 -1.18133331e+02 -4.26111832e+01 4.36981201e+01 6.53374252e+01 5.56193199e+01 2.10490704e+01 -9.05213451e+00 -5.80871506e+01 -6.20691605e+01 -3.54594955e+01 -1.07682619e+01 -4.09371452e+01 -1.06717545e+02 -1.52477951e+02 -9.61131668e+01 -5.45054388e+00 3.61571884e+01 -1.85337315e+01 -1.13013245e+02 -1.26930626e+02 -7.81030426e+01 1.02234411e+01 2.13898849e+01 -3.11040840e+01 -5.93278313e+01 -6.82276306e+01 -1.38256607e+01 -1.56886682e-01 -7.73100281e+00 -3.44994125e+01 -8.02788620e+01 -6.02848206e+01 -4.88422470e+01 2.27447586e+01 7.70598755e+01 5.97087402e+01 2.49334316e+01 -4.71123505e+01 -2.25163460e+01 6.54939270e+01 1.52807159e+02 1.87991547e+02 1.94001968e+02 6.78486755e+02 3.10959717e+03 1.36303101e+03 1.62572668e+03 4.82515039e+03 1.36677887e+02 7.91347046e+02 8.27101172e+03 8.05724766e+04 -2.73790259e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1953833344. 247863776. -391067040. 1030631616. 2.09693574e+04 8.27801758e+03 2.18763159e+03 1.78367065e+02 1.65574448e+02 4.90323868e+01 1.70680161e+01 5.06236076e+00 -1.87227478e+01 -9.86515732e+01 -1.04321632e+02 -7.51295700e+01 -1.27739315e+01 -2.21775398e+01 -8.35478516e+01 -1.39902176e+02 -1.49223312e+02 -9.27606735e+01 -1.23835955e+01 3.57872057e+00 -5.63558846e+01 -1.23449112e+02 -1.25005638e+02 -7.25063705e+01 -6.73219604e+01 -1.04369766e+02 -1.15166061e+02 -8.95069504e+01 -5.10750275e+01 -5.42075920e+01 -4.30621796e+01 -2.22653828e+01 -2.18665142e+01 -6.15178680e+01 -1.36975372e+02 -1.39848267e+02 -9.34557724e+01 -4.67423248e+01 -4.98605080e+01 -9.85674973e+01 -1.48006042e+02 -1.43670609e+02 -7.53878403e+01 3.37757683e+00 -3.20123649e+00 -8.11448364e+01 -1.18226700e+02 -1.19440529e+02 -7.58947525e+01 -6.07602310e+01 -5.01426468e+01 -4.39985886e+01 -5.90489464e+01 -7.99220200e+01 -1.26737289e+02 -1.08272316e+02 -6.95822296e+01 -5.44508820e+01 -8.46330566e+01 -1.36574036e+02 -1.36079956e+02 -1.11170425e+02 -7.01178436e+01 -5.10555534e+01 -9.28954239e+01 -1.48307266e+02 -1.89987595e+02 -1.69985229e+02 -1.09353294e+02 -8.69900513e+01 -1.23239433e+02 -1.55385117e+02 -1.52008591e+02 -9.26611404e+01 -7.26568375e+01 -8.52759781e+01 -1.10496101e+02 -1.09639435e+02 -1.09238937e+02 -1.23778130e+02 -1.02800011e+02 -7.11034317e+01 -5.58146172e+01 -9.41917038e+01 -1.47417603e+02 -1.60221680e+02 -1.45479492e+02 -1.00628250e+02 -7.69168015e+01 -6.76234055e+01 -1.02128105e+02 -1.18712189e+02 -1.18179024e+02 -6.84884186e+01 -5.08149834e+01 -8.46277466e+01 -1.20003143e+02 -1.19903976e+02 -7.62221603e+01 -5.57384148e+01 -5.82171440e+01 -6.49492493e+01 -7.29072571e+01 -8.94886932e+01 -1.22979424e+02 -1.22885132e+02 -9.25212631e+01 -6.96782990e+01 -7.04196854e+01 -9.92511063e+01 -1.05602631e+02 -8.82542877e+01 -7.13016815e+01 -5.23921127e+01 -5.99036217e+01 -8.99087906e+01 -1.18848785e+02 -1.23778282e+02 -8.31609726e+01 -6.30809555e+01 -7.90087585e+01 -9.26086578e+01 -9.62499771e+01 -7.90250778e+01 -7.95734787e+01 -8.20020523e+01 -7.20417786e+01 -6.99815903e+01 -7.51438751e+01 -1.05625877e+02 -1.00279732e+02 -7.89599838e+01 -6.15708542e+01 -6.80154800e+01 -8.68822861e+01 -8.52435532e+01 -6.90417328e+01 -6.17247429e+01 -5.14508629e+01 -6.59908676e+01 -8.48059998e+01 -1.02376274e+02 -9.99735565e+01 -7.99507217e+01 -7.61125031e+01 -8.31850891e+01 -8.55364761e+01 -8.24938660e+01 -6.77642517e+01 -5.92049255e+01 -5.26750107e+01 -5.26950226e+01 -6.28497543e+01 -7.51826096e+01 -9.58976974e+01 -1.03374084e+02 -9.90455627e+01 -8.61376343e+01 -8.44889526e+01 -9.91482239e+01 -1.12437584e+02 -1.06137627e+02 -8.40498886e+01 -6.87909622e+01 -7.07864151e+01 -9.10365295e+01 -1.00863037e+02 -9.83620224e+01 -8.56639481e+01 -8.29417725e+01 -8.96030960e+01 -8.83038025e+01 -9.10741882e+01 -9.13121033e+01 -9.09877930e+01 -8.12517242e+01 -6.84437790e+01 -7.00383072e+01 -7.31534653e+01 -8.26897888e+01 -8.80707932e+01 -9.15354385e+01 -8.96625137e+01 -8.90012512e+01 -9.48510208e+01 -1.01751671e+02 -9.71775970e+01 -8.73586044e+01 -7.67477036e+01 -7.63105621e+01 -8.35007172e+01 -8.60118637e+01 -8.66144714e+01 -8.12864761e+01 -8.23969727e+01 -8.75288391e+01 -9.23661957e+01 -9.55178070e+01 -9.53602905e+01 -9.87078934e+01 -9.55059128e+01 -8.94718246e+01 -8.48590622e+01 -8.53938675e+01 -8.95123520e+01 -8.95941544e+01 -8.64892273e+01 -8.34763184e+01 -8.08749084e+01 -8.29910660e+01 -8.65103226e+01 -8.96710205e+01 -8.84626007e+01 -8.60321579e+01 -8.55252228e+01 -8.62024918e+01 -8.63660507e+01 -8.63266830e+01 -8.60985641e+01 -8.61091690e+01 -8.63337402e+01 -8.65828629e+01 -8.63513794e+01 -8.59565964e+01 -8.45163193e+01 -8.37426758e+01 -8.39200134e+01 -8.49231567e+01 -8.53034668e+01 -8.53790588e+01 -8.66312332e+01 -8.88328323e+01 -8.93215485e+01 -8.84700851e+01 -8.54876251e+01 -8.46453094e+01 -8.40212708e+01 -8.47284241e+01 -8.60989761e+01 -8.71882706e+01 -8.68028107e+01 -8.44218597e+01 -8.30891800e+01 -8.35501022e+01 -8.59777527e+01 -8.56610336e+01 -8.47456512e+01 -8.27732849e+01 -8.34492874e+01 -8.41883469e+01 -8.43846130e+01 -8.55884018e+01 -8.58358917e+01 -8.74523163e+01 -8.64977951e+01 -8.55072937e+01 -8.41683960e+01 -8.60991440e+01 -8.78133163e+01 -8.96948318e+01 -8.71367264e+01 -8.66202545e+01 -8.62469406e+01 -8.61046829e+01 -8.60002670e+01 -8.71217194e+01 -8.57314529e+01 -8.62959595e+01 -8.69522858e+01 -9.25238419e+01 -9.23941116e+01 -9.01825943e+01 -8.87069702e+01 -8.87736053e+01 -8.89682083e+01 -8.89048309e+01 -9.13615646e+01 -9.12314072e+01 -8.98367157e+01 -8.76985550e+01 -8.93862991e+01 -8.92461319e+01 -8.87778397e+01 -8.59262772e+01 -8.60614853e+01 -8.76334610e+01 -9.14875412e+01 -9.21924438e+01 -9.13285294e+01 -8.56235428e+01 -7.69682312e+01 -7.17628403e+01 -7.27916183e+01 -8.16286774e+01 -8.66174774e+01 -8.80773697e+01 -8.48655472e+01 -7.82001877e+01 -7.94874954e+01 -8.27613831e+01 -8.80447693e+01 -8.58320084e+01 -8.59077301e+01 -8.96443634e+01 -8.94073105e+01 -8.61615753e+01 -8.16861343e+01 -8.62345352e+01 -8.47830048e+01 -8.11257401e+01 -7.43576431e+01 -7.35429001e+01 -7.86551895e+01 -8.55617142e+01 -9.18317566e+01 -1.03227867e+02 -1.09714752e+02 -1.08147255e+02 -9.62664108e+01 -8.40714035e+01 -8.03797760e+01 -7.75417404e+01 -7.65827332e+01 -8.62811203e+01 -1.00782379e+02 -1.01764343e+02 -8.99345169e+01 -7.58329697e+01 -7.47979813e+01 -7.79275970e+01 -7.29886856e+01 -7.29870682e+01 -7.38596802e+01 -7.62115631e+01 -7.38062286e+01 -7.15427933e+01 -7.54474411e+01 -7.79745178e+01 -7.25641708e+01 -6.57301102e+01 -5.54265633e+01 -4.88870316e+01 -5.54557457e+01 -6.19867859e+01 -6.14800262e+01 -5.73691635e+01 -6.67306595e+01 -7.41671906e+01 -7.64642563e+01 -6.27563515e+01 -5.23672066e+01 -4.46113663e+01 -5.73255615e+01 -6.96408768e+01 -8.11511765e+01 -7.07105637e+01 -5.35625954e+01 -3.32804146e+01 -5.12117996e+01 -7.12307129e+01 -8.52121811e+01 -7.40541763e+01 -6.70171432e+01 -6.24744415e+01 -4.77363396e+01 -4.12633171e+01 -4.66383400e+01 -5.91343422e+01 -7.52374420e+01 -7.82580719e+01 -7.86568375e+01 -6.15776787e+01 -4.50870857e+01 -4.09910164e+01 -5.78314514e+01 -6.93930054e+01 -7.51683197e+01 -7.29744339e+01 -7.91100464e+01 -8.91695633e+01 -9.19607925e+01 -9.05999069e+01 -8.24688263e+01 -7.54894333e+01 -7.69786072e+01 -7.75541534e+01 -7.28739853e+01 -6.44835587e+01 -7.27027130e+01 -8.20211334e+01 -6.89256592e+01 -5.49152832e+01 -6.05451355e+01 -9.07048035e+01 -1.03822250e+02 -8.97713242e+01 -7.89946442e+01 -7.67620239e+01 -7.26186371e+01 -4.81991234e+01 -4.21998329e+01 -3.32368317e+01 -3.95380554e+01 -4.38185425e+01 -5.67365227e+01 -6.80207291e+01 -5.95795288e+01 -6.29431381e+01 -6.41518173e+01 -6.75140457e+01 -6.29841995e+01 -6.91379013e+01 -4.62601509e+01 -3.09550362e+01 -1.97533131e+01 -3.81709671e+01 -5.69068222e+01 -6.37430687e+01 -6.98997726e+01 -6.54289780e+01 -6.63166809e+01 -5.53719826e+01 -7.40377502e+01 -8.90058746e+01 -1.13974747e+02 -1.11506645e+02 -9.39537582e+01 -7.44998093e+01 -7.40913467e+01 -8.24758072e+01 -8.41350784e+01 -7.57948837e+01 -7.04455261e+01 -9.85443726e+01 -1.28122452e+02 -1.32297607e+02 -9.43543015e+01 -5.80094376e+01 -5.50889816e+01 -7.33175659e+01 -1.19257179e+02 -2.43214371e+02 -1.71213959e+02 -3.59901489e+02 -2.03809113e+02 -2.01270569e+03 -3.12772632e+03 -2.19800095e+02 -2.64205933e+02 -3.99961884e+02 -2.18669815e+02 -4.65699188e+02 -8.45272095e+02 -3.04405518e+03 -1.54466230e+04 -3.51511484e+04 -543421312. 2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1682441600. 613805696. -635087040. -1.38181318e+04 -5.34608740e+03 -9.75133728e+02 -7.70844666e+02 -6.25215820e+02 -2.55323257e+02 -1.38184219e+02 -1.31061508e+02 -9.25014572e+01 -5.77466774e+01 -5.74364815e+01 -6.08053551e+01 -6.79035187e+01 -6.97285309e+01 -9.68575058e+01 -1.13475960e+02 -8.94326706e+01 -4.07878532e+01 -3.10047970e+01 -6.33380127e+01 -8.12323456e+01 -6.26174812e+01 -5.91984329e+01 -7.07178574e+01 -8.17771149e+01 -8.85553818e+01 -1.03515663e+02 -1.03327827e+02 -8.09710999e+01 -6.97025299e+01 -6.05066071e+01 -7.39352951e+01 -3.74076996e+01 -4.54406834e+00 8.72116566e+00 -1.05320368e+01 -3.44688911e+01 -2.56921520e+01 -1.47245779e+01 -7.73425055e+00 7.07462788e+00 1.54822931e+01 2.63346138e+01 3.12418804e+01 3.77333298e+01 2.32982578e+01 6.46493435e+00 -2.97227931e+00 9.00636387e+00 9.24582958e+00 -2.09214568e+00 -1.64495850e+00 8.15715373e-01 1.47707405e+01 1.87277718e+01 7.50475836e+00 -3.00639820e+01 -7.01606979e+01 -9.35923309e+01 -6.98677902e+01 -4.72440758e+01 -2.33469105e+01 -5.37187462e+01 -6.98461990e+01 -5.86786461e+01 -1.85080376e+01 1.51055002e+01 1.66576061e+01 1.37654371e+01 3.31187897e+01 7.09321518e+01 4.27017174e+01 -1.96763382e+01 -6.52945251e+01 -5.55210381e+01 -2.11965466e+01 -2.56997051e+01 -1.24542637e+01 -1.38055515e+01 -2.31133509e+00 -8.13181782e+00 -1.14599876e+01 -3.33766251e+01 -3.69911041e+01 -3.78189697e+01 -1.44843826e+01 -1.67598019e+01 -5.06305580e+01 -1.01190559e+02 -9.22501755e+01 -5.67971077e+01 -1.82845402e+01 -2.94383564e+01 -5.23587418e+01 -7.49728088e+01 -8.88175659e+01 -5.49941063e+01 -1.15685940e+01 -2.42748141e+00 -2.36137390e+01 -7.01764755e+01 -6.05171204e+01 -5.15652695e+01 -3.03798466e+01 -2.39436722e+01 -3.67168350e+01 -3.38813896e+01 -3.53870926e+01 -2.10841999e+01 -1.94733810e+01 -1.42527018e+01 -1.35197926e+01 -4.24114647e+01 -7.94104233e+01 -7.91924973e+01 -4.37647247e+01 -4.90250969e+00 2.56761265e+00 9.27252674e+00 1.18657732e+01 1.96823673e+01 2.28049812e+01 2.56021938e+01 -1.85106792e+01 -6.70448074e+01 -7.84699936e+01 -4.40752144e+01 -2.96262169e+00 1.43224564e+01 1.89487915e+01 1.74585438e+01 4.67166376e+00 2.12014461e+00 1.37595606e+01 5.91410220e-01 -2.59704638e+00 -6.08513308e+00 3.60679366e-02 -4.01358891e+00 -4.65521526e+00 -6.81417131e+00 2.29701877e+00 -1.49986267e+00 -6.04931259e+00 -7.16483879e+00 -4.75351524e+00 -7.80989838e+00 -2.14703426e+01 -2.43413696e+01 -6.37047195e+00 3.32504797e+00 7.36078453e+00 3.29133153e-01 9.37032795e+00 1.71490364e+01 2.22575874e+01 5.32332706e+00 -5.43992004e+01 -8.82855911e+01 -8.94259796e+01 -6.95291824e+01 -5.27200165e+01 -4.50296173e+01 -2.05775928e+01 -8.95623779e+00 -1.86485062e+01 -2.45878677e+01 -2.07000904e+01 -1.23317480e+01 -1.66621437e+01 -7.06999779e+00 3.53836021e+01 7.82148514e+01 1.03319580e+02 9.45690231e+01 5.51244926e+01 1.60309811e+01 -2.37040901e+01 -1.57008028e+01 -6.92397594e+00 6.02230453e+00 5.76775503e+00 1.32695284e+01 3.35219216e+00 6.88606548e+00 1.14494219e+01 9.89656448e+00 1.15442920e+00 3.26520324e+00 1.05217390e+01 1.74773159e+01 -2.17706060e+00 -1.10589867e+01 -1.91323280e+01 -1.84938412e+01 -3.99378371e+00 3.50759964e+01 7.75504990e+01 9.89131927e+01 9.37835007e+01 8.79873886e+01 9.62218628e+01 6.91671524e+01 2.92915001e+01 -1.36727800e+01 -2.34400349e+01 -1.92362537e+01 -8.53446198e+00 -1.60943949e+00 -1.34497142e+00 -2.12585735e+01 -2.27488155e+01 -2.32143955e+01 -1.47726479e+01 -8.34576797e+00 -8.47566223e+00 -3.89309273e+01 -8.00790710e+01 -6.56986694e+01 -2.65637283e+01 9.58920956e+00 3.12752666e+01 5.22096367e+01 9.65572815e+01 1.19457680e+02 1.01733185e+02 7.36494598e+01 2.48764687e+01 4.51838760e+01 5.89643250e+01 7.66763000e+01 6.76109238e+01 5.98649368e+01 6.12104836e+01 6.66169052e+01 5.95786781e+01 4.80089684e+01 3.34445686e+01 3.63383484e+01 6.96594315e+01 1.09754868e+02 1.44222198e+02 1.54770462e+02 7.94897385e+01 3.02225780e+00 -3.52054977e+01 -4.38497448e+00 4.19839706e+01 3.51584282e+01 4.14944992e+01 3.14260330e+01 3.46294670e+01 3.34750175e+01 2.88763542e+01 2.58800182e+01 2.93941288e+01 3.18517056e+01 5.86828701e-02 -4.28912430e+01 -5.32036552e+01 -3.61274872e+01 -3.59285450e+00 1.50926304e+01 4.88525429e+01 5.16504250e+01 3.78163605e+01 2.88841553e+01 5.02648277e+01 4.86947899e+01 2.91487617e+01 6.14456797e+00 5.63790655e+00 1.32987995e+01 1.68610783e+01 2.08341904e+01 1.92747459e+01 2.52437572e+01 2.40906677e+01 2.35331516e+01 1.15240660e+01 8.61697578e+00 1.11372766e+01 4.68899422e+01 8.66188965e+01 8.14740143e+01 4.79349594e+01 1.57788048e+01 2.83329067e+01 3.73087502e+01 4.29798584e+01 4.78884315e+01 5.58099556e+01 6.12828941e+01 8.75510406e+01 9.64014130e+01 9.28792191e+01 5.12821808e+01 2.29654865e+01 1.79534302e+01 3.01398239e+01 1.14804859e+01 -1.53674440e+01 -2.88974609e+01 -2.03926506e+01 1.32688751e+01 1.45614729e+01 1.91939507e+01 1.57165022e+01 1.81389065e+01 2.47073097e+01 1.93246994e+01 1.33475084e+01 1.51709385e+01 1.24984751e+01 1.14272470e+01 1.03386278e+01 2.69832764e+01 3.40756416e+01 5.97033157e+01 8.51925888e+01 8.59732361e+01 6.94657059e+01 4.94454918e+01 5.34210472e+01 4.83383751e+01 3.01648464e+01 3.66707344e+01 7.14188766e+01 1.05624290e+02 1.04087646e+02 6.68759308e+01 4.18251419e+01 4.50143433e+01 5.73450928e+01 6.55334320e+01 6.34617577e+01 8.96475830e+01 1.21400047e+02 1.25021332e+02 9.37816238e+01 4.75585251e+01 5.25865479e+01 5.76244545e+01 6.67290344e+01 5.79626999e+01 5.17081566e+01 6.26446190e+01 7.38165436e+01 8.25582581e+01 7.12669220e+01 6.55733032e+01 7.10741806e+01 1.03911911e+02 1.49532928e+02 1.52613907e+02 1.21008209e+02 7.84375076e+01 6.77480850e+01 5.98839302e+01 6.22677612e+01 7.06075821e+01 1.12474991e+02 1.41466568e+02 1.75404037e+02 1.75081894e+02 1.44487305e+02 1.14254883e+02 7.80588913e+01 9.86298141e+01 1.22609497e+02 1.00484390e+02 4.25102272e+01 9.47735977e+00 2.66755028e+01 6.83700714e+01 6.58202057e+01 6.43001633e+01 5.12797546e+01 4.94856911e+01 3.64285774e+01 4.07383614e+01 3.68112526e+01 3.89647064e+01 3.47738533e+01 3.56793213e+01 3.38080673e+01 3.50238304e+01 4.07141151e+01 6.16066628e+01 8.94373550e+01 8.53252640e+01 6.64680252e+01 3.37635231e+01 6.31814842e+01 9.82230682e+01 6.83621902e+01 7.49312925e+00 2.07381153e+00 7.80780029e+01 1.17844223e+02 9.17897873e+01 5.66884499e+01 7.61748123e+01 1.11250824e+02 1.16068886e+02 9.53911896e+01 6.76705704e+01 6.94542770e+01 7.79867401e+01 7.32653503e+01 7.50770035e+01 5.43131866e+01 3.32343864e+01 5.65589485e+01 1.02783401e+02 1.28424377e+02 1.08201080e+02 8.66023254e+01 1.10675812e+02 1.33243805e+02 1.41184219e+02 1.16330048e+02 8.61122818e+01 8.65649033e+01 9.56756058e+01 1.01753174e+02 8.69850159e+01 9.59391937e+01 1.18247192e+02 1.30056686e+02 1.26907921e+02 9.76787720e+01 8.49531097e+01 6.94622498e+01 6.59443359e+01 6.57597961e+01 3.41061974e+01 -8.54444563e-01 1.03390636e+01 6.12052612e+01 9.98674850e+01 9.09406357e+01 6.82014999e+01 8.59419556e+01 1.11917290e+02 1.14965538e+02 9.58630142e+01 7.19181213e+01 6.85994110e+01 6.97337112e+01 6.66500168e+01 7.11124191e+01 7.31488724e+01 8.01595535e+01 8.82378616e+01 9.05242615e+01 8.38083725e+01 7.18679123e+01 6.71002274e+01 6.34398994e+01 6.99805069e+01 5.03191109e+01 3.07812519e+01 4.73670235e+01 9.45981598e+01 1.20801010e+02 9.69120331e+01 6.65195999e+01 5.02737083e+01 4.65635986e+01 4.70875282e+01 5.26129341e+01 5.57132072e+01 5.40336456e+01 6.02517052e+01 5.65940819e+01 5.79639359e+01 5.33262062e+01 5.36884804e+01 5.24897995e+01 5.91340408e+01 6.80194473e+01 6.45409775e+01 5.51953392e+01 5.14315948e+01 6.23519936e+01 7.23386002e+01 7.82114792e+01 8.98872452e+01 1.06351524e+02 1.08331009e+02 9.84780350e+01 9.83069229e+01 1.33147537e+02 1.53114899e+02 1.39516266e+02 1.13825562e+02 1.19814240e+02 1.41273926e+02 1.45174973e+02 1.25625504e+02 1.08301926e+02 1.02511276e+02 1.03497803e+02 1.04354034e+02 1.05345230e+02 1.00908363e+02 9.42002869e+01 1.01716492e+02 1.19138405e+02 1.25670952e+02 1.14164490e+02 9.62456284e+01 9.78871765e+01 1.08218307e+02 9.67200394e+01 7.79796066e+01 6.87744751e+01 7.65311279e+01 8.59587555e+01 8.11473389e+01 8.22032089e+01 8.24482346e+01 8.23187180e+01 7.99907227e+01 8.03587189e+01 8.34997101e+01 7.94485626e+01 7.66615829e+01 7.25230789e+01 7.50492554e+01 7.93068466e+01 7.87527237e+01 8.93748703e+01 1.00572899e+02 1.01541756e+02 9.04500351e+01 7.24181900e+01 6.77148514e+01 6.78545914e+01 6.26132660e+01 5.30075226e+01 5.12369461e+01 5.98338737e+01 7.22402115e+01 7.40855103e+01 7.50613098e+01 8.81276550e+01 1.02843246e+02 1.06595657e+02 9.56511383e+01 8.76096802e+01 8.97648163e+01 8.89333725e+01 8.48781204e+01 8.44150848e+01 8.08873520e+01 7.29207687e+01 7.63699951e+01 8.70881042e+01 9.56517792e+01 9.09801712e+01 9.26633377e+01 1.07300011e+02 1.16219841e+02 1.10863892e+02 9.54111404e+01 9.19666672e+01 9.68201065e+01 9.70788727e+01 8.97118073e+01 8.02952347e+01 8.23207474e+01 8.84013977e+01 8.96651077e+01 8.75944977e+01 8.28646240e+01 8.06629486e+01 7.88893967e+01 7.83043442e+01 8.11721191e+01 8.01448364e+01 7.91453934e+01 8.24196472e+01 8.76805954e+01 8.90414963e+01 8.51311188e+01 8.25634155e+01 8.52662964e+01 8.88042755e+01 8.83891449e+01 8.71361923e+01 8.19406128e+01 7.53840332e+01 6.15574608e+01 5.07091064e+01 4.25312691e+01 2.79750843e+01 4.07873802e+01 7.85759430e+01 1.23348877e+02 1.67597107e+02 3.16600677e+02 8.94131836e+02 386115904. 594307968. 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. 1143110144. 446722944. 4.02959302e+03 1.74277026e+03 6.52376099e+02 5.90466919e+02 3.96424377e+02 1.64719315e+02 1.33331436e+02 1.19833481e+02 1.17943817e+02 1.15530907e+02 1.13703110e+02 1.17743423e+02 1.21222443e+02 1.19091682e+02 1.10801392e+02 1.06164948e+02 1.10376984e+02 1.20899384e+02 1.13220222e+02 1.00139229e+02 8.34212952e+01 8.14666290e+01 8.63939743e+01 9.98327179e+01 1.05127792e+02 1.10146713e+02 1.02396629e+02 1.04918739e+02 1.00509789e+02 8.74209366e+01 8.37965317e+01 9.50566940e+01 1.07845062e+02 1.13360130e+02 1.13427940e+02 1.19974174e+02 1.29079941e+02 1.31308121e+02 1.19476318e+02 8.92561264e+01 7.23067780e+01 8.03824921e+01 1.02522484e+02 1.16570236e+02 1.16239670e+02 1.09417000e+02 9.97987900e+01 1.04281700e+02 9.91314468e+01 9.43528214e+01 9.76098633e+01 1.18766495e+02 1.44740082e+02 1.40489975e+02 1.06280579e+02 8.68367462e+01 9.71103745e+01 1.18967857e+02 1.14852142e+02 9.52018738e+01 9.41709137e+01 1.12602066e+02 1.34701721e+02 1.28652573e+02 9.67392960e+01 7.48973160e+01 8.53224716e+01 1.07752899e+02 1.09616310e+02 1.01708603e+02 1.01199852e+02 1.21302315e+02 1.39482025e+02 1.32819000e+02 1.19632622e+02 1.20362267e+02 1.34884277e+02 1.43555817e+02 1.38444397e+02 1.18856056e+02 9.87704620e+01 9.17209091e+01 1.05400642e+02 1.16019569e+02 1.10938309e+02 1.26219276e+02 1.55934692e+02 1.70607407e+02 1.43106476e+02 9.43978806e+01 6.96419067e+01 8.30016632e+01 1.21456116e+02 1.59037842e+02 1.74347137e+02 1.64088715e+02 1.55387466e+02 1.60697815e+02 1.52130203e+02 1.12708946e+02 8.10548172e+01 8.87639008e+01 1.24107506e+02 1.42784210e+02 1.33960495e+02 1.06081039e+02 9.45207367e+01 1.10030228e+02 1.23594826e+02 1.21581505e+02 1.16353020e+02 1.36688385e+02 1.76089142e+02 1.83821411e+02 1.53494873e+02 1.12163467e+02 1.12870125e+02 1.35993637e+02 1.61321838e+02 1.62306244e+02 1.38848618e+02 1.07604271e+02 9.18403854e+01 1.09238487e+02 1.08621094e+02 8.79122314e+01 8.53185272e+01 1.13622536e+02 1.46701309e+02 1.43795990e+02 1.13021545e+02 9.62599869e+01 1.14493469e+02 1.31287201e+02 1.39532486e+02 1.26203133e+02 1.39650726e+02 1.67195969e+02 1.73573395e+02 1.31322189e+02 5.55694771e+01 1.90227375e+01 5.09099808e+01 9.48101044e+01 1.07372086e+02 9.14115448e+01 7.28743515e+01 7.73582764e+01 7.58192825e+01 6.32032547e+01 2.89517536e+01 1.64019871e+01 4.89405785e+01 1.25334061e+02 1.63644135e+02 1.27396446e+02 7.70856247e+01 7.64749451e+01 9.86357880e+01 8.12566910e+01 2.31312389e+01 2.92755814e+01 7.69764786e+01 1.30640915e+02 8.97598267e+01 6.75067282e+00 -4.44694099e+01 -1.27268496e+01 5.01469116e+01 8.54327698e+01 9.01359558e+01 1.03747208e+02 1.23045860e+02 1.06647850e+02 5.18853302e+01 -1.67891464e+01 8.71562672e+00 6.32745285e+01 1.15407089e+02 1.08196320e+02 8.50834274e+01 5.93152847e+01 4.18197060e+01 4.28467941e+01 2.80628834e+01 2.53146924e-02 1.22887325e+01 7.36604156e+01 1.33645355e+02 1.08274384e+02 3.34936562e+01 -2.15651264e+01 7.49672604e+00 5.86826553e+01 9.64065628e+01 9.14610901e+01 1.08191650e+02 1.54488632e+02 1.75469543e+02 1.25663956e+02 4.59054871e+01 3.07381401e+01 6.27952423e+01 1.25543594e+02 1.44946091e+02 1.42160324e+02 1.07195473e+02 7.50871735e+01 7.32066269e+01 5.33361855e+01 3.43874245e+01 6.26440811e+01 1.14553917e+02 1.32610825e+02 1.16194565e+02 7.48748169e+01 6.23837471e+01 7.81272354e+01 8.10404663e+01 8.23862076e+01 5.67983360e+01 8.73297348e+01 1.32889816e+02 1.57593796e+02 1.68169876e+02 9.70102158e+01 5.59092636e+01 7.23854675e+01 1.40108002e+02 1.54069870e+02 1.03382378e+02 5.51862679e+01 5.65169792e+01 8.94882660e+01 8.74204330e+01 4.64515915e+01 4.12765923e+01 8.42615280e+01 1.20897377e+02 9.01399307e+01 7.32781830e+01 1.02347206e+02 1.14227699e+02 8.53131256e+01 6.16672287e+01 4.35064926e+01 6.21191826e+01 2.82536602e+01 1.87532997e+01 2.24411545e+01 1.74128437e+01 -6.21430254e+00 -2.30462837e+01 4.91072044e+01 7.65654984e+01 8.89358902e+01 3.05394745e+01 4.56837654e+01 4.99739647e+01 2.77596340e+01 -1.86009712e+01 -3.74825745e+01 4.32561150e+01 8.39507141e+01 8.48562469e+01 1.32845984e+01 3.97742927e-01 3.08875484e+01 6.18898010e+01 7.73565903e+01 1.88850060e+01 3.44539604e+01 5.85993996e+01 1.25189949e+02 1.50996902e+02 1.37405762e+02 8.00917969e+01 3.27158012e+01 6.54877014e+01 1.15731209e+02 1.38143066e+02 1.04978256e+02 1.36447433e+02 1.36573563e+02 1.02038742e+02 3.14507904e+01 3.29465790e+01 1.14361122e+02 1.43434875e+02 1.09478508e+02 2.91437950e+01 5.56174049e+01 9.07529984e+01 1.18985481e+02 9.58300934e+01 5.75112343e+01 5.48631363e+01 3.44751778e+01 8.59396896e+01 1.10782364e+02 1.25051277e+02 7.70912628e+01 5.31362839e+01 8.04987411e+01 1.12654495e+02 1.21674721e+02 1.35903885e+02 2.01123108e+02 2.37821808e+02 2.23268326e+02 2.05397049e+02 2.06137390e+02 2.46880890e+02 2.57196320e+02 2.26928558e+02 1.47616425e+02 1.18956696e+02 1.10578087e+02 1.21299232e+02 9.38926849e+01 3.84452324e+01 1.02726984e+01 6.83843422e+00 6.32674828e+01 8.88370285e+01 9.38456039e+01 7.38993073e+01 8.81357193e+01 1.14235756e+02 1.45828674e+02 1.46207352e+02 1.41691772e+02 1.85053635e+02 2.19996933e+02 1.99688858e+02 1.39815781e+02 1.17161369e+02 1.19074890e+02 6.29588318e+01 2.23309307e+01 1.05972600e+00 6.68573608e+01 7.31635513e+01 7.78696747e+01 1.09309273e+02 1.09081367e+02 7.07867050e+01 -1.28979073e+01 -3.16736012e+01 3.52846107e+01 1.00259964e+02 9.70227509e+01 3.76928101e+01 -1.32754145e+01 1.38989906e+01 6.95841446e+01 1.22454895e+02 1.21270554e+02 7.16431885e+01 2.84743748e+01 -2.53512955e+01 -3.00678978e+01 -2.98832359e+01 -5.12099113e+01 -4.66921005e+01 -5.18106194e+01 2.66345081e+01 2.88495636e+01 2.89877319e+01 2.71624584e+01 1.80710983e+01 -2.05408802e+01 -1.38835297e+02 -1.61235092e+02 -8.41642227e+01 7.71056213e+01 1.56810699e+02 6.10826950e+01 -6.53604507e+01 -7.37226334e+01 6.70254059e+01 2.09491425e+02 1.68673126e+02 4.23499146e+01 -4.94889755e+01 -3.54373322e+01 5.87952232e+01 6.40764008e+01 9.14818859e+00 -4.86158867e+01 -6.30723915e+01 1.62669430e+01 1.42037153e+01 -2.62390423e+01 -6.64105148e+01 -6.33715820e+01 -1.57640572e+01 -4.52051010e+01 -4.58067627e+01 3.78154259e+01 1.35557068e+02 1.17097084e+02 -4.94977531e+01 -1.53781616e+02 -1.11006401e+02 1.50500259e+01 8.20725937e+01 5.36847687e+01 -3.67658653e+01 -6.90973663e+01 -8.14128265e+01 6.60721958e-01 7.46408367e+00 -9.88657570e+00 -5.01766396e+01 -8.76332092e+01 -2.42759590e+01 1.92787457e+01 9.35542984e+01 9.45483170e+01 6.24199600e+01 -4.20212328e-01 -1.08572838e+02 -1.46845612e+02 -7.76542816e+01 8.51712036e+01 1.72003433e+02 9.38777466e+01 -7.56262436e+01 -1.25496681e+02 9.98093319e+00 1.63601089e+02 1.63843735e+02 1.87623329e+01 -4.48434029e+01 -4.01379509e+01 3.52051735e+01 4.41722527e+01 -5.62211323e+00 -6.99520950e+01 -1.27921394e+02 -1.20348839e+02 -1.53989044e+02 -1.48536469e+02 -8.58520355e+01 1.79354935e+01 5.07636032e+01 -2.81134644e+01 -1.06946762e+02 -8.31584702e+01 3.34519196e+01 1.27925079e+02 8.92691956e+01 -3.13977547e+01 -6.15181999e+01 -1.60531063e+01 7.82325821e+01 5.46661263e+01 -1.53946609e+01 -9.31867065e+01 -1.38268082e+02 -8.04970779e+01 -7.90871582e+01 -4.71302719e+01 -6.47114716e+01 -7.24679565e+01 -9.15504074e+01 -1.39352005e+02 -9.85540771e+01 -3.36593285e+01 4.55046387e+01 1.13833780e+01 -9.23178864e+01 -1.67918381e+02 -1.08446342e+02 2.24616623e+00 7.32132568e+01 6.61571198e+01 -8.05342484e+00 -3.94014893e+01 -5.53110466e+01 -1.60450325e+01 -4.12836380e+01 -7.66914444e+01 -1.24943184e+02 -1.71152603e+02 -1.52148300e+02 -6.80456467e+01 7.91620874e+00 1.40239925e+01 -2.78956661e+01 -7.01619873e+01 -1.29136902e+02 -1.59494370e+02 -8.10663681e+01 4.86034470e+01 1.08626518e+02 2.03482304e+01 -7.99797974e+01 -9.19145889e+01 1.90795803e+01 1.36715210e+02 1.23752098e+02 -1.64168777e+01 -1.64944504e+02 -2.18535904e+02 -1.26435410e+02 -5.28641281e+01 -5.04032593e+01 -9.09020767e+01 -1.18001518e+02 -6.97321091e+01 -6.57122879e+01 -5.09182854e+01 -1.08943377e+01 -2.10158420e+00 -2.68619323e+00 -7.29125671e+01 -6.38788643e+01 9.64600372e+00 1.02631767e+02 8.86417236e+01 -5.62109222e+01 -1.64309906e+02 -1.30618515e+02 -7.79444933e+00 7.89236374e+01 8.06275940e+01 -1.71416588e+01 -1.14696945e+02 -1.60612137e+02 -8.48141098e+01 -2.75787735e+01 2.10474930e+01 1.08453131e+01 -1.29363174e+01 -8.16314220e+00 -4.90234995e+00 6.17863846e+01 9.90717010e+01 9.86032257e+01 4.73407478e+01 -5.34170914e+01 -9.29301605e+01 -3.75977211e+01 5.96177444e+01 8.97945938e+01 2.90559025e+01 -6.72871475e+01 -6.74713440e+01 -6.90028965e-01 9.31210251e+01 1.11299812e+02 1.58808651e+01 -7.65569763e+01 -1.18117485e+02 -4.35355873e+01 2.69793034e+01 3.00202694e+01 -1.51590099e+01 -7.49946060e+01 -8.84054337e+01 -9.70888824e+01 -6.08719101e+01 1.19155111e+01 3.12920399e+01 -3.28126144e+01 -1.42627457e+02 -1.78749207e+02 -1.18184296e+02 -3.14633560e+01 2.48408318e+01 -1.33640480e+01 -9.42014008e+01 -1.37866714e+02 -1.15243881e+02 -5.84190521e+01 -5.68810272e+01 -9.47727890e+01 -1.37906708e+02 -1.38715607e+02 -7.20750351e+01 -2.53824635e+01 -4.73705368e+01 -9.98510208e+01 -1.69131287e+02 -1.62429520e+02 -1.62450027e+02 -1.31942535e+02 -9.14561996e+01 -6.58799896e+01 -5.85067177e+01 -1.16999023e+02 -1.54242615e+02 -1.32791000e+02 -7.91130981e+01 -2.80208683e+01 -6.44830246e+01 -1.17758965e+02 -1.50399979e+02 -8.03972244e+01 3.44030228e+01 8.76540680e+01 2.26480980e+01 -1.11281975e+02 -1.41576996e+02 -2.11158905e+01 1.13707062e+02 -2.25062618e+01 1.71927509e+01 -2.09800529e+01 -2.46603851e+01 -6.07530884e+02 1.48394189e+03 2.97750049e+03 8.42532910e+03 3.03255820e+04 -4.30840986e+09 199014400. 4.81494426e+09 438012832. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 395975776. 1039180928. 1.53886475e+04 5.42511670e+03 -1.27893341e+02 6.27001526e+02 3.49654102e+03 2.18134131e+03 2.68785492e+02 3.52806511e+01 1.02881317e+02 2.50385838e+01 -7.92679291e+01 -1.29669373e+02 -1.25620796e+02 -6.17225494e+01 -2.38184757e+01 -3.72728119e+01 -1.15183487e+02 -1.78147018e+02 -1.66698013e+02 -1.22058235e+02 -1.12915382e+02 -1.13071136e+02 -1.09372314e+02 -7.19980774e+01 -1.00745712e+02 -1.08510315e+02 -6.31611023e+01 -2.23829975e+01 -5.24812050e+01 -1.45223297e+02 -1.92967194e+02 -1.34348343e+02 -6.12904663e+01 -1.66019688e+01 -4.36729546e+01 -1.27813744e+02 -1.94347855e+02 -2.28940491e+02 -1.67245041e+02 -1.21341988e+02 -1.11837120e+02 -1.56007339e+02 -1.84145355e+02 -1.57658737e+02 -1.50817520e+02 -1.23549057e+02 -9.84483185e+01 -8.81336212e+01 -1.15025429e+02 -1.89558716e+02 -1.94630692e+02 -1.31362518e+02 -5.53253479e+01 -3.32228241e+01 -9.51387482e+01 -1.57404999e+02 -1.56838196e+02 -1.10477455e+02 -8.94833069e+01 -1.37153412e+02 -2.11690781e+02 -2.28388855e+02 -1.97833740e+02 -1.18133003e+02 -6.52758789e+01 -6.46713791e+01 -1.14432922e+02 -1.77437317e+02 -2.15980392e+02 -2.33072601e+02 -2.16300201e+02 -1.80663940e+02 -1.41042969e+02 -1.22837288e+02 -1.36582199e+02 -1.32219208e+02 -9.06214066e+01 -5.15062332e+01 -5.48290939e+01 -1.03141464e+02 -1.39669708e+02 -1.28653809e+02 -1.09050720e+02 -7.49864807e+01 -5.52897339e+01 -7.45498505e+01 -1.26968666e+02 -1.60738678e+02 -1.30038712e+02 -9.40565796e+01 -9.53083954e+01 -1.20457596e+02 -1.25999146e+02 -1.14729546e+02 -1.22752663e+02 -1.19387436e+02 -9.97553864e+01 -8.61254654e+01 -1.01905945e+02 -1.52247681e+02 -1.57673462e+02 -1.10097260e+02 -4.77565346e+01 -2.97218132e+01 -6.96554642e+01 -1.16928406e+02 -1.31944214e+02 -1.25448906e+02 -1.07376991e+02 -1.06935013e+02 -1.15820854e+02 -1.40341553e+02 -1.52953751e+02 -1.29398819e+02 -8.60671997e+01 -7.48322372e+01 -9.12091141e+01 -1.09214409e+02 -1.10687119e+02 -1.26619698e+02 -1.26383095e+02 -9.08263397e+01 -5.29249344e+01 -5.46625290e+01 -1.06037659e+02 -1.27582314e+02 -9.92792969e+01 -5.89509926e+01 -5.26958580e+01 -9.18720932e+01 -1.31014603e+02 -1.40889465e+02 -1.25107025e+02 -9.58866653e+01 -7.32440414e+01 -8.26121368e+01 -1.13817863e+02 -1.35446014e+02 -1.15213776e+02 -8.28668518e+01 -7.32576981e+01 -8.58481827e+01 -1.02054695e+02 -1.12385376e+02 -1.28788574e+02 -1.32382019e+02 -1.22941795e+02 -1.09990479e+02 -1.10647049e+02 -1.27296638e+02 -1.36532761e+02 -1.19424141e+02 -8.65844116e+01 -6.20101814e+01 -7.40749969e+01 -1.07033699e+02 -1.30192871e+02 -1.27483589e+02 -1.10436378e+02 -1.04869606e+02 -1.08268463e+02 -1.12332405e+02 -1.19835594e+02 -1.18238106e+02 -1.14273582e+02 -1.06925980e+02 -9.48695221e+01 -8.79207764e+01 -8.68919754e+01 -1.01968407e+02 -1.11253616e+02 -1.00506233e+02 -9.03576889e+01 -9.59180756e+01 -1.17834641e+02 -1.29930130e+02 -1.23543365e+02 -1.12626381e+02 -1.04191605e+02 -1.03029427e+02 -1.08288330e+02 -1.11308983e+02 -1.11837029e+02 -1.03474045e+02 -1.05788620e+02 -1.13914261e+02 -1.23062027e+02 -1.32117523e+02 -1.36381378e+02 -1.39960464e+02 -1.30165131e+02 -1.17351082e+02 -1.10519875e+02 -1.12230568e+02 -1.18808868e+02 -1.19435204e+02 -1.12035980e+02 -1.03200012e+02 -9.97820282e+01 -1.09093506e+02 -1.21650024e+02 -1.26667000e+02 -1.23553169e+02 -1.18150429e+02 -1.16532272e+02 -1.17025345e+02 -1.18124184e+02 -1.19903221e+02 -1.17887627e+02 -1.14973663e+02 -1.12949562e+02 -1.14960999e+02 -1.15377594e+02 -1.16116692e+02 -1.16547211e+02 -1.17069649e+02 -1.16021194e+02 -1.15238739e+02 -1.15230301e+02 -1.15080002e+02 -1.14474457e+02 -1.14008209e+02 -1.14082710e+02 -1.14470421e+02 -1.14674026e+02 -1.14577026e+02 -1.13699532e+02 -1.13268318e+02 -1.13846306e+02 -1.15430542e+02 -1.16244164e+02 -1.14820732e+02 -1.13800194e+02 -1.13877533e+02 -1.14201408e+02 -1.13688095e+02 -1.13810402e+02 -1.13513451e+02 -1.13747749e+02 -1.14057800e+02 -1.14192436e+02 -1.14192535e+02 -1.14791718e+02 -1.16705513e+02 -1.17188988e+02 -1.15893356e+02 -1.14343506e+02 -1.15047432e+02 -1.16908264e+02 -1.15651230e+02 -1.14723618e+02 -1.11017403e+02 -1.09585136e+02 -1.09060783e+02 -1.10125206e+02 -1.13587456e+02 -1.13351486e+02 -1.13086197e+02 -1.13008820e+02 -1.14614105e+02 -1.15026581e+02 -1.15118156e+02 -1.15683350e+02 -1.16471840e+02 -1.16438705e+02 -1.14476265e+02 -1.15533356e+02 -1.16284172e+02 -1.19483490e+02 -1.20465500e+02 -1.21884308e+02 -1.18638680e+02 -1.17802513e+02 -1.16732742e+02 -1.17751007e+02 -1.17740189e+02 -1.19078735e+02 -1.19131973e+02 -1.19288521e+02 -1.14700157e+02 -1.14073898e+02 -1.16486259e+02 -1.17956444e+02 -1.17205559e+02 -1.15898354e+02 -1.17374466e+02 -1.17363686e+02 -1.12127747e+02 -1.12331635e+02 -1.14798744e+02 -1.17123108e+02 -1.13634727e+02 -1.11181992e+02 -1.14457481e+02 -1.10762054e+02 -1.05375092e+02 -1.00959335e+02 -1.06325554e+02 -1.06493477e+02 -1.06076447e+02 -1.03263405e+02 -9.98470612e+01 -9.87486725e+01 -1.01065849e+02 -1.08503586e+02 -1.09720230e+02 -1.09419922e+02 -1.09963173e+02 -1.14467888e+02 -1.12373360e+02 -1.10832794e+02 -1.15709518e+02 -1.26905296e+02 -1.26048714e+02 -1.18530518e+02 -1.07209099e+02 -1.05736839e+02 -1.05697289e+02 -1.05972237e+02 -1.06685684e+02 -1.02538124e+02 -9.95798111e+01 -9.97758179e+01 -9.66325378e+01 -9.47666626e+01 -9.21926346e+01 -1.06338150e+02 -1.08420387e+02 -1.07640991e+02 -1.04089943e+02 -1.05351601e+02 -1.04392120e+02 -1.00868660e+02 -1.00283577e+02 -9.71989975e+01 -9.14953842e+01 -9.30276489e+01 -9.74756393e+01 -1.04744812e+02 -1.01515518e+02 -9.86511154e+01 -9.28009033e+01 -9.27882004e+01 -1.04565063e+02 -1.09846840e+02 -1.13009583e+02 -9.69356613e+01 -9.22646790e+01 -8.81595230e+01 -9.88886414e+01 -1.07269447e+02 -1.14444534e+02 -1.13551155e+02 -1.17874207e+02 -1.20068695e+02 -1.21277016e+02 -1.11901848e+02 -1.01403793e+02 -9.85545654e+01 -1.04198448e+02 -1.06963341e+02 -1.08810028e+02 -1.08006798e+02 -1.12781158e+02 -1.11286171e+02 -1.08409004e+02 -9.84432526e+01 -1.00897797e+02 -1.25028542e+02 -1.49327805e+02 -1.45522171e+02 -1.17579590e+02 -9.29002686e+01 -1.04576393e+02 -1.21453636e+02 -1.29161285e+02 -1.18930283e+02 -1.03677551e+02 -1.11849335e+02 -1.21274872e+02 -1.24101593e+02 -1.19954643e+02 -1.18504440e+02 -1.28101715e+02 -1.36933289e+02 -1.38574615e+02 -1.20797760e+02 -1.01174850e+02 -9.76659012e+01 -1.12542397e+02 -1.16486969e+02 -1.12438354e+02 -1.01947716e+02 -1.07203201e+02 -1.20931587e+02 -1.36045471e+02 -1.27999611e+02 -1.04088036e+02 -8.45829010e+01 -8.64646835e+01 -9.09039307e+01 -8.72125397e+01 -6.71853790e+01 -4.27438087e+01 -4.02610893e+01 -6.27689018e+01 -8.99080582e+01 -1.00796745e+02 -1.07242371e+02 -1.22651207e+02 -1.26092079e+02 -9.25719910e+01 -5.17336502e+01 -4.21797676e+01 -7.38532867e+01 -1.04334259e+02 -1.02542274e+02 -9.39526596e+01 -8.01407700e+01 -6.64848938e+01 -7.30267563e+01 -8.64785233e+01 -1.12643723e+02 -1.14361786e+02 -1.19297432e+02 -8.95373535e+01 -4.80589523e+01 -3.90491714e+01 -5.67378960e+01 -9.28829346e+01 -1.10294456e+02 -1.34630371e+02 -1.32880447e+02 -1.12242569e+02 -9.06977386e+01 -7.70026855e+01 -7.40863800e+01 -7.92605591e+01 -7.29497070e+01 -7.04724808e+01 -6.56205826e+01 -7.00528183e+01 -7.24670258e+01 -8.24290161e+01 -1.64754318e+02 -2.38493362e+02 -3.36167511e+02 -2.75075348e+02 -1.91731537e+02 -7.85052872e+01 -1.38907883e+02 -2.31797943e+02 -1.18373184e+02 -3.89139954e+02 -4.74562061e+03 -1.12432539e+04 439682080. 157521280. 251309312. -2.69313126e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1878641536. -270095360. -3.07232441e+04 -1.18383350e+04 -1.71753357e+03 -1.06965588e+03 -4.26706445e+03 -2.85845215e+03 -5.86991089e+02 -4.46305969e+02 -1.84470139e+02 -1.23131264e+02 -1.08078850e+02 -1.05332817e+02 -1.07420113e+02 -1.06339355e+02 -1.11066574e+02 -5.35240211e+01 6.80089264e+01 1.54665955e+02 1.14085907e+02 7.20670090e+01 7.51147413e+00 -1.57360413e+02 -2.47548416e+02 -2.40892029e+02 -2.05976822e+02 -2.45534027e+02 -3.27886963e+02 -2.14611588e+02 -2.74211304e+02 -2.46936600e+02 -2.08276169e+02 -8.67159271e+01 -5.18385391e+01 -2.92364273e+01 -1.67089100e+01 -2.16460538e+00 5.90515566e+00 1.10439510e+01 -4.69231319e+00 -1.79221230e+01 -1.79815769e+01 -9.88741207e+00 1.78352821e+00 8.33902454e+00 1.45756550e+01 -3.04522991e+00 -3.80935707e+01 -7.21358185e+01 -8.00040894e+01 -6.27546844e+01 -4.56888924e+01 -3.50888710e+01 -2.08131695e+01 -3.11583672e+01 -4.00949135e+01 -3.86581459e+01 -1.89642906e+01 -2.47553706e+00 -9.05165672e+00 6.52912807e+00 -1.72089748e+01 -3.30228271e+01 -4.94512672e+01 -5.05954094e+01 -5.62498398e+01 -6.31558838e+01 -5.51793404e+01 -4.36054916e+01 -4.63567162e+01 -4.43066711e+01 -1.34030523e+01 -1.44580150e+00 -1.66406500e+00 -2.86935043e+01 -3.33616714e+01 -2.86033268e+01 -4.67759552e+01 -8.65920181e+01 -8.24825058e+01 -6.57389679e+01 -4.61637955e+01 -9.98255844e+01 -1.43259277e+02 -1.43272446e+02 -1.11501694e+02 -8.77449341e+01 -9.01397781e+01 -9.39288712e+01 -8.14761047e+01 -8.98527222e+01 -1.12094872e+02 -1.46037735e+02 -1.32693787e+02 -8.14489746e+01 -3.58152275e+01 -1.93725357e+01 -2.63455658e+01 -3.42772980e+01 -4.68053436e+01 -2.32421017e+01 2.10532379e+00 -1.42523851e+01 -5.01304245e+01 -5.56924057e+01 -2.22292194e+01 -9.74152923e-01 -5.38784065e+01 -9.15795822e+01 -8.47210388e+01 -3.04192791e+01 1.22400150e+01 1.58163490e+01 1.15960178e+01 3.62880969e+00 6.74210072e-01 -1.23911877e+01 -1.27497644e+01 -6.71611166e+00 -6.41456032e+00 -1.37015457e+01 -1.81351433e+01 -1.18334551e+01 -2.28901172e+00 -1.19853868e+01 -1.37611904e+01 -1.86648235e+01 -5.44907799e+01 -9.60328064e+01 -9.45274353e+01 -5.67189293e+01 -2.35594940e+01 -6.87192078e+01 -1.15450546e+02 -1.17144196e+02 -7.58221817e+01 -3.54808235e+01 -2.77009792e+01 -2.18837795e+01 -5.12578726e+00 -8.89514351e+00 -1.53600092e+01 -1.98434410e+01 -1.02119255e+01 5.97524405e+00 1.33273530e+00 -1.00033255e+01 -2.33760319e+01 -1.46189728e+01 -9.58636570e+00 -1.32100239e+01 -3.62771378e+01 -7.86653290e+01 -1.21053085e+02 -1.12405083e+02 -8.01433792e+01 -3.49288864e+01 -6.94852295e+01 -1.06543091e+02 -1.00338921e+02 -5.12297935e+01 -8.31250548e-01 -4.84682226e+00 -9.42883301e+00 -1.91900921e+01 -1.53383570e+01 -1.78589325e+01 -1.45952387e+01 -1.08373909e+01 -1.09997063e+01 -3.59935722e+01 -6.73502274e+01 -6.93977127e+01 -4.64500008e+01 -1.12182932e+01 -1.92738414e-01 1.93022072e-01 -3.47169456e+01 -6.90742645e+01 -6.49374619e+01 -4.00461807e+01 -1.52465124e+01 -1.04071522e+01 7.21547508e+00 -1.96417503e+01 -6.68167038e+01 -7.85485992e+01 -5.31669273e+01 -2.15018921e+01 -1.81842003e+01 -1.92348137e+01 -8.23403740e+00 -9.31493664e+00 -1.50885983e+01 -1.59056807e+01 -5.44386940e+01 -9.20869904e+01 -9.19600296e+01 -5.03607635e+01 -1.54563541e+01 -2.31171780e+01 -2.34476089e+01 -5.00387039e+01 -8.17317810e+01 -7.47438736e+01 -2.37344494e+01 2.35939369e+01 9.02185917e+00 1.92409664e-01 -5.43220234e+00 1.21325598e+01 2.10807877e+01 2.67782192e+01 2.10488911e+01 1.34382515e+01 1.40918617e+01 1.96604652e+01 2.52889614e+01 4.18597374e+01 5.78100510e+01 6.84733963e+01 6.80954056e+01 5.58442345e+01 5.51972923e+01 5.35138206e+01 5.79524803e+01 4.75243912e+01 4.07504349e+01 4.78265457e+01 4.49024544e+01 4.08198242e+01 4.22573929e+01 5.54076424e+01 5.75319443e+01 4.44730072e+01 4.39322701e+01 4.99883766e+01 5.64655685e+01 3.84574585e+01 3.44518814e+01 1.95025158e+01 2.25431328e+01 1.98953323e+01 4.93545723e+01 7.75640869e+01 5.73682365e+01 -1.53682458e+00 -3.27541084e+01 -1.60640697e+01 1.94413643e+01 1.91281528e+01 1.10386763e+01 -2.45516634e+00 -8.65647030e+00 -7.06259727e+00 3.73579085e-01 1.14229774e+01 2.57217426e+01 3.76421394e+01 3.77294998e+01 2.89238796e+01 2.13255863e+01 2.09623280e+01 2.01273823e+01 2.01913738e+01 1.98947563e+01 3.19357929e+01 3.56268997e+01 4.63594284e+01 3.00553417e+01 -5.24982119e+00 -4.45678673e+01 -3.95718193e+01 -6.18313408e+00 2.70230846e+01 3.44409103e+01 3.49980850e+01 1.99671898e+01 -8.73692513e+00 -2.87429180e+01 -3.37861176e+01 -1.11238897e+00 2.47516422e+01 5.29507751e+01 3.77051849e+01 3.16853714e+01 2.75561562e+01 3.38015633e+01 3.42558174e+01 4.32099762e+01 3.67464447e+01 2.86858196e+01 2.14932709e+01 1.80960712e+01 2.03097382e+01 -1.47927971e+01 -3.42910957e+01 -2.64834232e+01 1.94240208e+01 5.09781609e+01 3.45546761e+01 1.71092510e+01 2.02347851e+01 2.81275597e+01 1.05340843e+01 -1.98719997e+01 -1.88303699e+01 1.31974192e+01 4.78549767e+01 3.46225433e+01 2.57328587e+01 2.97471981e+01 5.75350838e+01 5.81860657e+01 5.27137566e+01 3.55349083e+01 4.49244576e+01 6.75918503e+01 6.77689819e+01 6.31826248e+01 5.50263443e+01 6.90283737e+01 5.24397507e+01 2.47060566e+01 1.97451248e+01 4.00881529e+00 -1.98281670e+01 -5.14950142e+01 -5.29883575e+01 -3.27333488e+01 -3.57437019e+01 -1.36874189e+01 -5.42057848e+00 2.81835098e+01 6.95857697e+01 1.18499779e+02 1.26545509e+02 1.07588837e+02 8.72328644e+01 8.23500671e+01 7.73154984e+01 7.25584183e+01 7.46205063e+01 9.08311920e+01 6.65892334e+01 2.15631542e+01 1.14861560e+00 6.78760099e+00 4.01556892e+01 5.00942688e+01 6.04420776e+01 7.89909439e+01 5.40872993e+01 5.28025246e+01 3.48014069e+01 3.32818489e+01 1.73184566e+01 -1.00411434e+01 1.49758768e+01 4.28292007e+01 6.10458794e+01 3.13379536e+01 2.24566441e+01 3.73178177e+01 6.77080688e+01 4.12744827e+01 1.14638071e+01 2.23433495e+00 2.68291645e+01 5.26783943e+01 2.14703217e+01 -6.02470255e+00 -6.50651217e-01 4.45318604e+01 7.47702560e+01 4.79099998e+01 2.92012138e+01 5.74976730e+01 1.00584908e+02 7.54848557e+01 2.93848095e+01 4.83219528e+00 2.31794968e+01 3.43593063e+01 3.56311188e+01 1.30273457e+01 -4.70233297e+00 3.62628031e+00 5.06726570e+01 8.25733414e+01 7.99724579e+01 7.22416458e+01 7.03433533e+01 8.00937500e+01 7.71300507e+01 7.07938690e+01 4.92606773e+01 4.90183334e+01 6.53348465e+01 7.63379745e+01 7.67774811e+01 5.28086319e+01 3.71744957e+01 4.16553879e+01 5.33827133e+01 7.82067871e+01 7.25320511e+01 7.08543243e+01 7.50644836e+01 9.24526520e+01 9.41025162e+01 5.32252884e+01 1.92425556e+01 5.11021271e+01 1.11119446e+02 1.15553123e+02 6.39647141e+01 4.31237450e+01 7.09815445e+01 8.62459793e+01 6.50760498e+01 5.67109871e+01 6.50647278e+01 8.45667953e+01 7.22326050e+01 6.05566750e+01 5.51870041e+01 6.83340378e+01 8.79747238e+01 8.96375198e+01 9.10746841e+01 6.80961456e+01 5.16960945e+01 4.95025673e+01 6.98973618e+01 7.12364731e+01 2.63547421e+01 4.45593166e+00 1.89804688e+01 5.78166504e+01 5.95693779e+01 4.66242218e+01 6.33827744e+01 1.01960800e+02 1.16181999e+02 9.24302750e+01 7.36788864e+01 7.59735336e+01 8.62558670e+01 7.55689468e+01 7.50974731e+01 7.45579376e+01 8.13268204e+01 8.97853012e+01 1.01732857e+02 1.05103844e+02 9.86466980e+01 8.90174866e+01 7.47628250e+01 7.01093903e+01 6.92368698e+01 6.10186806e+01 5.92478409e+01 7.45967255e+01 9.36263580e+01 8.82587967e+01 6.67323456e+01 6.28434372e+01 6.77120056e+01 5.51810837e+01 2.22978439e+01 5.88643026e+00 2.26106834e+01 6.35695038e+01 7.45016479e+01 6.68861389e+01 6.25258865e+01 8.13757477e+01 9.55787354e+01 1.00300232e+02 1.04465233e+02 1.01366302e+02 9.46960373e+01 9.39199753e+01 1.04270966e+02 1.04435036e+02 7.61668320e+01 6.20631371e+01 7.76770477e+01 9.57583160e+01 7.83568726e+01 6.47167130e+01 8.03825455e+01 1.18969795e+02 1.40207596e+02 1.35821686e+02 1.29262680e+02 1.22622810e+02 1.23579254e+02 1.21151474e+02 1.24259834e+02 1.14744354e+02 1.06251976e+02 1.03189529e+02 1.19882591e+02 1.12842262e+02 8.50261383e+01 6.33288498e+01 5.86780663e+01 6.45483856e+01 7.66355438e+01 9.22769165e+01 1.06000458e+02 1.01689697e+02 1.01954964e+02 1.02289619e+02 1.05230705e+02 1.02753922e+02 1.03817291e+02 1.02544250e+02 1.01898582e+02 1.04468262e+02 1.04889496e+02 1.06750938e+02 9.16231308e+01 7.66202087e+01 7.46616364e+01 8.72261429e+01 9.87436142e+01 9.75329819e+01 9.94146347e+01 9.82700043e+01 9.92098389e+01 9.92262421e+01 9.95778885e+01 9.21641083e+01 7.95451736e+01 8.54907379e+01 1.00290359e+02 1.05060081e+02 8.19715805e+01 6.71376877e+01 7.75248947e+01 9.90057602e+01 9.90748672e+01 8.79361115e+01 8.87943344e+01 9.67093201e+01 1.06366119e+02 9.69676285e+01 9.03382492e+01 8.39770813e+01 8.32998810e+01 9.50213318e+01 1.03277496e+02 1.01252754e+02 8.24786377e+01 7.40035629e+01 8.77425232e+01 1.04913383e+02 1.02274170e+02 8.94505463e+01 8.75633621e+01 9.49296112e+01 1.02534874e+02 9.69831390e+01 9.16424179e+01 8.87710190e+01 9.25239105e+01 9.98321381e+01 1.04976082e+02 9.91164627e+01 9.09189835e+01 8.87233810e+01 9.44492950e+01 1.05154419e+02 1.01180176e+02 9.76952286e+01 9.67680283e+01 1.02893723e+02 1.03477020e+02 9.69415894e+01 9.83928299e+01 1.04446663e+02 1.13653397e+02 1.14938553e+02 1.15495331e+02 1.09635384e+02 1.03513069e+02 1.01419670e+02 1.04120422e+02 1.08893478e+02 1.11570015e+02 1.11102760e+02 1.08599678e+02 1.03954910e+02 1.03227043e+02 9.25179291e+01 8.92999954e+01 6.82340012e+01 9.32725220e+01 -9.76824722e+01 1.54276306e+02 2.68354279e+02 -8.38790817e+01 -6.23262787e+01 2.26467972e+02 -4.01385269e+01 386115904. 594307968. 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. 1143110144. 446722944. 4.02959302e+03 1.74277026e+03 6.52376099e+02 -7.65899048e+01 -3.59101372e+01 5.98281593e+01 6.60506516e+01 6.14269905e+01 7.31973801e+01 8.55740585e+01 6.86367340e+01 2.21373459e+02 3.85738068e+02 5.30489258e+02 -3.04683502e+02 -2.09579712e+02 -2.03199368e+01 4.13091993e+00 2.79497852e+01 6.15418396e+01 6.97383499e+01 7.12408676e+01 6.76469727e+01 6.86526871e+01 6.98601074e+01 6.55439682e+01 6.14601135e+01 6.28821182e+01 7.38936310e+01 8.28121490e+01 8.50277405e+01 7.69568863e+01 6.44673386e+01 5.88503990e+01 6.01829109e+01 5.96971436e+01 5.85995674e+01 5.88263817e+01 6.80182190e+01 7.78144684e+01 7.65406113e+01 6.77030258e+01 6.15964584e+01 6.63457794e+01 6.67053070e+01 6.54780273e+01 7.05918198e+01 7.05981598e+01 7.19791260e+01 6.76072922e+01 6.03128242e+01 5.13766747e+01 4.58968201e+01 6.03289337e+01 8.04451828e+01 8.80316238e+01 7.76725693e+01 5.70920029e+01 5.60550537e+01 6.59438782e+01 7.33027267e+01 6.90546112e+01 6.10914764e+01 6.55049591e+01 7.42601852e+01 7.85277634e+01 6.67428513e+01 4.97229805e+01 5.38021164e+01 5.87697830e+01 6.39147987e+01 6.38018303e+01 6.24544449e+01 6.78462601e+01 6.28193436e+01 5.25095673e+01 4.02546616e+01 3.88466568e+01 5.09797935e+01 6.80810776e+01 8.35446701e+01 8.53642197e+01 6.96912231e+01 6.23249168e+01 6.11715851e+01 5.01822739e+01 3.06696033e+01 2.97120075e+01 5.40827980e+01 8.23920670e+01 8.53979721e+01 6.42269516e+01 3.65179100e+01 3.10248604e+01 3.24295082e+01 3.35389938e+01 3.45180855e+01 3.89059715e+01 5.12567368e+01 6.19495010e+01 5.95679131e+01 4.64079704e+01 4.05432816e+01 5.43768616e+01 7.38645401e+01 8.18336487e+01 7.96910248e+01 6.07142868e+01 4.52339172e+01 5.05997429e+01 5.06929474e+01 4.08586349e+01 2.79772301e+01 3.70998726e+01 6.11931076e+01 6.60442352e+01 4.38108521e+01 1.88292751e+01 1.23902855e+01 3.31759567e+01 5.39615784e+01 7.32352753e+01 8.00991669e+01 6.77506561e+01 5.86020966e+01 5.67587509e+01 3.98911552e+01 2.07855740e+01 1.23469782e+01 2.72424812e+01 4.96509857e+01 6.19942017e+01 6.04255562e+01 4.59861336e+01 3.71191177e+01 3.49921989e+01 3.11906567e+01 1.66151104e+01 1.64892063e+01 3.95870934e+01 7.89300919e+01 9.91923447e+01 8.66852493e+01 6.69057922e+01 5.87111092e+01 4.99217606e+01 4.74312935e+01 5.46571312e+01 6.26098022e+01 7.67702560e+01 8.53452072e+01 7.95292053e+01 5.59373817e+01 3.83073463e+01 5.06529846e+01 7.38140488e+01 7.13724442e+01 4.87413292e+01 3.39172821e+01 5.45900345e+01 8.31916885e+01 7.45814133e+01 6.13878059e+01 5.08038712e+01 8.57563553e+01 1.20806862e+02 1.36520447e+02 9.50593262e+01 3.92076759e+01 2.19508057e+01 2.32377968e+01 2.42458134e+01 2.32592754e+01 4.40173645e+01 7.66188736e+01 9.89079132e+01 7.15640335e+01 3.77917824e+01 2.19060898e+01 4.73270111e+01 6.82531662e+01 7.69881058e+01 7.28881378e+01 7.92713928e+01 8.99721375e+01 1.00718170e+02 7.99855118e+01 6.72053146e+01 5.95275040e+01 7.95245438e+01 1.03339676e+02 1.08633698e+02 6.49336395e+01 1.22893467e+01 6.47000492e-01 1.74403343e+01 2.02747021e+01 1.49497681e+01 2.01126099e+01 5.53279762e+01 7.18082581e+01 4.39605980e+01 1.66530108e+00 -1.45044270e+01 1.49180775e+01 3.64326782e+01 4.45871849e+01 4.41535072e+01 4.59327774e+01 5.41445923e+01 7.10574265e+01 4.84137115e+01 1.74317398e+01 2.38208413e+00 2.76483860e+01 7.10926056e+01 7.82526627e+01 4.79082947e+01 1.77457886e+01 1.42193451e+01 2.81286411e+01 1.99796562e+01 1.23349428e+01 8.09166336e+00 4.74831200e+00 1.81411343e+01 1.97981472e+01 1.86350613e+01 -4.11635351e+00 -6.35693121e+00 3.36154699e+00 1.53280706e+01 4.80594559e+01 5.75680313e+01 7.55963974e+01 6.12176704e+01 4.37761230e+01 1.54535952e+01 -4.51124334e+00 3.42974243e+01 6.77551498e+01 6.53970108e+01 2.59375114e+01 6.61158037e+00 2.40517025e+01 4.46691055e+01 2.63204651e+01 1.55866394e+01 2.57415657e+01 5.99993362e+01 7.37830276e+01 6.11708565e+01 6.64679565e+01 4.95561295e+01 4.12695274e+01 1.21376114e+01 3.46589508e+01 4.58938408e+01 6.10115814e+01 8.01847992e+01 8.75664368e+01 8.15017090e+01 2.90425949e+01 -6.11207581e+00 1.47414637e+01 8.05956268e+01 1.07246605e+02 7.75030441e+01 6.16451035e+01 6.79246674e+01 8.72145233e+01 5.33139496e+01 3.37124405e+01 1.84689503e+01 2.36437283e+01 1.93650990e+01 2.59544106e+01 5.03130074e+01 4.90986671e+01 2.39622612e+01 -3.06996250e+00 9.36176014e+00 -1.74233830e+00 -2.99354839e+01 -2.72739697e+01 1.40558443e+01 5.15534439e+01 3.73427048e+01 2.22348614e+01 3.52732162e+01 6.42924194e+01 5.05086746e+01 2.66924019e+01 2.49763927e+01 4.77236061e+01 6.54993973e+01 5.09889793e+01 5.11983528e+01 3.82889557e+01 3.66669998e+01 9.12012196e+00 -8.58526039e+00 7.93864071e-01 2.14158573e+01 2.51494617e+01 7.38359213e+00 -1.17458963e+01 -3.06865158e+01 -4.75503502e+01 -3.83558884e+01 -2.06916351e+01 -7.97755098e+00 -3.15417614e+01 -5.43134232e+01 -2.80629978e+01 2.87630844e+01 3.82754173e+01 1.12534103e+01 -8.71693325e+00 2.79651260e+01 6.38034706e+01 5.37152977e+01 3.15052166e+01 -4.64555883e+00 -1.58683624e+01 -3.57477989e+01 -4.14825096e+01 -3.06653824e+01 -2.33146954e+01 -1.96390877e+01 -2.52354794e+01 -1.62680473e+01 -3.03386517e+01 -5.33755722e+01 -3.99460449e+01 8.12303829e+00 3.56824760e+01 3.09889374e+01 2.62473488e+01 5.17989044e+01 7.47193832e+01 4.24848938e+01 3.02056408e+01 1.96105366e+01 3.57532806e+01 2.69856586e+01 1.41461744e+01 3.42467766e+01 2.85988102e+01 1.69803791e+01 -2.88000813e+01 -3.71845627e+01 -1.80285416e+01 1.33049488e+01 2.89506397e+01 1.50930166e+01 7.49821544e-01 -1.56999578e+01 -5.28006325e+01 -4.85812988e+01 1.87627888e+01 9.34654312e+01 1.21141098e+02 7.90003128e+01 5.93403816e+01 6.77039871e+01 6.42516556e+01 8.09649124e+01 5.39901047e+01 4.72288094e+01 3.14130745e+01 3.90308533e+01 1.04655449e+02 1.21487640e+02 1.04890213e+02 1.71525536e+01 -4.51348267e+01 -2.51906657e+00 5.34941139e+01 7.63650589e+01 5.60527325e+00 -6.13668861e+01 -3.89165306e+01 -2.27553673e+01 1.49661617e+01 2.97834816e+01 3.90856361e+01 6.11268425e+01 4.30332260e+01 3.11813641e+01 1.35806236e+01 -1.02649137e-01 4.45037384e+01 7.51330032e+01 1.03712158e+02 8.07419205e+01 2.05417500e+01 2.23171692e+01 1.93822670e+01 4.14631397e-01 -5.50361824e+01 -4.61354027e+01 5.52791595e+01 1.14032867e+02 1.11013428e+02 4.74768677e+01 1.36409473e+01 1.60435925e+01 1.05576611e+01 2.01034966e+01 4.32481422e+01 4.82152863e+01 7.30013046e+01 5.85709000e+01 7.01885071e+01 6.68033218e+01 4.77593231e+01 2.95013351e+01 -2.58102570e+01 -2.86486588e+01 -1.16265802e+01 1.53272686e+01 7.28014908e+01 9.01731339e+01 8.43859863e+01 -2.35700536e+00 -6.07549171e+01 -5.32257195e+01 1.60996017e+01 6.49828033e+01 2.69356537e+01 -4.60641747e+01 -6.02438278e+01 -3.58701363e+01 -9.09529972e+00 9.00403786e+00 1.29395723e+01 3.08288841e+01 1.17917252e+01 -4.06776381e+00 -1.24412193e+01 -1.20512925e-01 6.48214645e+01 9.73501740e+01 8.24456177e+01 1.44301720e+01 -3.86838188e+01 -1.02939043e+01 4.20101166e+01 6.09662056e+01 9.48320293e+00 -4.99291916e+01 -4.68605118e+01 -1.26169796e+01 2.15096645e+01 8.62037373e+00 -1.71982803e+01 -3.90919518e+00 2.51067848e+01 3.89992676e+01 4.61233749e+01 2.75936222e+01 4.22206345e+01 2.95345631e+01 2.77591839e+01 1.77624245e+01 4.12027788e+00 3.63027382e+01 6.85189438e+00 -1.67339382e+01 -6.66196671e+01 -4.56750069e+01 2.03444080e+01 6.86973495e+01 7.11364822e+01 1.93371281e-01 -5.50626793e+01 -6.30287132e+01 -3.17674026e+01 1.74394951e+01 2.52574520e+01 -8.05311775e+00 -3.00901775e+01 -4.45599060e+01 -1.81520557e+01 3.25561066e+01 7.11861267e+01 6.55390778e+01 -1.00258980e+01 -5.54122162e+01 -6.63357391e+01 -4.62377892e+01 1.39375505e+01 5.39337158e+01 5.11984406e+01 -1.85232658e+01 -7.19777756e+01 -4.48696976e+01 1.53670282e+01 5.15562744e+01 2.74888301e+00 -7.00700912e+01 -7.60029221e+01 -3.44025993e+01 2.45546741e+01 5.72836266e+01 4.55833778e+01 3.21425667e+01 -5.95576048e-01 -2.23379974e+01 -2.20150719e+01 -1.59311523e+01 2.12285213e+01 1.21119928e+01 -9.48641682e+00 -2.24934521e+01 -5.22842484e+01 -1.76458778e+01 -1.86502075e+01 -2.72784023e+01 -6.87050858e+01 -7.38870850e+01 1.16976309e+01 5.43834839e+01 5.02784805e+01 -3.03193512e+01 -8.07306137e+01 -8.31837769e+01 -4.90069733e+01 -9.79648232e-01 2.90424404e+01 2.35687332e+01 8.58643723e+00 -1.94536705e+01 -2.96146259e+01 -1.10089331e+01 -1.47262716e+01 -1.00685120e+01 -6.18875313e+01 -7.46068649e+01 -7.33862000e+01 -5.46702309e+01 -7.07606268e+00 -3.30803204e+00 -2.57447147e+01 -9.09081726e+01 -1.12348717e+02 -9.29335022e+01 -4.67579689e+01 -1.56427507e+01 -4.19297523e+01 -9.55032806e+01 -1.14163864e+02 -9.07882996e+01 -4.73726883e+01 -2.58903313e+01 -3.05588932e+01 -3.58617439e+01 -3.54187431e+01 -2.25037556e+01 -1.32245626e+01 3.58352280e+00 2.71983910e+01 -1.18140197e+00 -5.14399376e+01 -8.11716385e+01 -5.34499435e+01 4.54690266e+00 3.50621338e+01 2.13747540e+01 -3.29873276e+01 -7.90810089e+01 -5.13984070e+01 -2.37913857e+01 2.13193512e+00 -1.79795189e+01 -2.69882278e+01 -1.11238852e+01 3.72639704e+00 1.70324841e+01 1.95156517e+01 6.00333643e+00 7.50606346e+00 -5.62337542e+00 -5.84825087e+00 -1.79614305e+00 -1.01763954e+01 4.82952833e+00 -4.92375422e+00 -1.36493721e+01 -3.34766922e+01 -4.94861794e+01 -1.32172852e+01 -8.71905231e+00 -8.49032974e+00 -4.34879799e+01 -6.01335907e+01 -3.07271175e+01 -1.31663990e+01 2.54870720e+01 -1.19853282e+00 -4.98336525e+01 -9.32058945e+01 -9.47977982e+01 -2.91595592e+01 -1.70580349e+01 -4.99799995e+01 -1.16318481e+02 -1.29310120e+02 -1.40699554e+02 -1.48710144e+02 -1.74115662e+02 -3.14827393e+02 -2.92996216e+03 -1.70210498e+03 -3.25527661e+03 -9.80472949e+03 -91476496. 136346288. -104345336. -644055360. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 395975776. 1039180928. 1.53886475e+04 5.42511670e+03 -1.27893341e+02 6.27001526e+02 -1.20489645e+01 -1.93621497e+03 -4.95431213e+02 1.47282288e+02 1.54077072e+02 9.15923691e+01 4.05415192e+02 2.40439133e+02 9.72676468e+00 -1.61194611e+02 -2.60539612e+02 -2.32884537e+02 -2.63822845e+02 -2.13392059e+02 -1.79205536e+02 -1.02889786e+02 -9.37627258e+01 -7.64596634e+01 -8.46581345e+01 -8.12368240e+01 -4.25137138e+01 -2.76080437e+01 -4.77125244e+01 -7.79972992e+01 -5.98555603e+01 -1.73588810e+01 -6.31002092e+00 -2.91341324e+01 -5.61956291e+01 -6.18061981e+01 -5.39719810e+01 -4.01059036e+01 -2.25525589e+01 -1.08796606e+01 -1.87302513e+01 -3.44038658e+01 -5.22085075e+01 -3.47995796e+01 -2.07928028e+01 -8.20028782e+00 7.93117094e+00 -1.16506538e+01 -4.20738678e+01 -8.01294327e+01 -7.44861603e+01 -3.12949657e+01 -2.49776382e+01 -4.19477577e+01 -7.98884659e+01 -8.39344330e+01 -5.62203217e+01 -4.02822304e+01 -3.42763252e+01 -5.16385994e+01 -5.22450638e+01 -4.17550659e+01 -2.79151306e+01 -9.55771828e+00 -8.00594807e-01 -1.33047762e+01 -3.70508499e+01 -5.34068413e+01 -4.33198357e+01 -2.79443645e+01 -6.61250782e+00 1.38706732e+01 1.77785053e+01 1.12100048e+01 -1.35223007e+01 -2.86682434e+01 -1.76074944e+01 -2.98675880e+01 -5.09824371e+01 -8.97693634e+01 -8.35806961e+01 -5.58664627e+01 -4.08720627e+01 -3.84997177e+01 -4.00748482e+01 -4.33879852e+01 -5.32101364e+01 -6.03331909e+01 -4.96047783e+01 -3.64249954e+01 -4.26596832e+01 -4.48634071e+01 -4.04684563e+01 -2.56225300e+01 -3.20312614e+01 -4.71425247e+01 -3.64385452e+01 -3.74342232e+01 -4.10263481e+01 -6.12424622e+01 -6.33660812e+01 -3.76468201e+01 -3.53306847e+01 -5.08634605e+01 -8.31949387e+01 -9.05327148e+01 -6.80695801e+01 -5.28157845e+01 -4.04511337e+01 -3.95670166e+01 -3.71041718e+01 -3.39739990e+01 -4.21933556e+01 -4.10758476e+01 -3.85515251e+01 -3.87922440e+01 -4.93297729e+01 -6.23631248e+01 -5.80864944e+01 -5.68647766e+01 -6.03082962e+01 -4.85130043e+01 -4.83241081e+01 -5.78568115e+01 -8.37765274e+01 -8.49832458e+01 -5.56696358e+01 -4.60384750e+01 -5.75199738e+01 -8.04709091e+01 -8.25090256e+01 -6.35732117e+01 -5.56597404e+01 -5.15057907e+01 -5.33215675e+01 -5.97599678e+01 -7.03700714e+01 -7.63509750e+01 -6.49283066e+01 -5.19233246e+01 -5.59008942e+01 -6.64566727e+01 -7.72046661e+01 -6.83997498e+01 -6.24149132e+01 -5.85275383e+01 -5.36325607e+01 -5.29184723e+01 -5.10325775e+01 -5.50911522e+01 -5.59546661e+01 -4.82703896e+01 -4.65522804e+01 -5.27387924e+01 -7.04992447e+01 -8.38448715e+01 -7.88646393e+01 -6.98661041e+01 -5.80177078e+01 -5.70501633e+01 -5.61643333e+01 -5.19817352e+01 -4.86887856e+01 -5.20407410e+01 -5.46850166e+01 -5.54781227e+01 -5.20675774e+01 -5.73595772e+01 -6.71287231e+01 -7.54295120e+01 -7.63434830e+01 -6.39179230e+01 -6.04308472e+01 -6.47092133e+01 -7.30682297e+01 -7.02094269e+01 -6.17875061e+01 -6.03652802e+01 -5.94110413e+01 -6.01567612e+01 -6.13059998e+01 -6.41409302e+01 -6.65343246e+01 -6.31796074e+01 -6.01387672e+01 -6.22403679e+01 -6.21319923e+01 -6.08430405e+01 -5.56705055e+01 -5.10757179e+01 -4.95966682e+01 -4.82231674e+01 -5.58768082e+01 -6.16146164e+01 -6.55480270e+01 -6.55474091e+01 -6.09854584e+01 -6.17864799e+01 -6.42743912e+01 -6.99678192e+01 -7.06553879e+01 -6.48300629e+01 -6.05485764e+01 -5.82205315e+01 -6.04900551e+01 -6.06288490e+01 -6.05959053e+01 -6.09760094e+01 -6.16793938e+01 -6.13703918e+01 -6.16108589e+01 -6.28042946e+01 -6.48535156e+01 -6.46182938e+01 -6.56412735e+01 -6.54097214e+01 -6.41359482e+01 -6.30522346e+01 -6.35165329e+01 -6.47500076e+01 -6.52553787e+01 -6.52012711e+01 -6.56152878e+01 -6.57269363e+01 -6.56919403e+01 -6.54526901e+01 -6.52982330e+01 -6.53877258e+01 -6.60138321e+01 -6.62812119e+01 -6.57381744e+01 -6.48766632e+01 -6.46033936e+01 -6.53800278e+01 -6.59606476e+01 -6.54561539e+01 -6.54896622e+01 -6.53516998e+01 -6.52214432e+01 -6.52802887e+01 -6.53015442e+01 -6.54407043e+01 -6.55323486e+01 -6.56326218e+01 -6.51845627e+01 -6.37632370e+01 -6.29969559e+01 -6.39252510e+01 -6.51816864e+01 -6.52265930e+01 -6.42090836e+01 -6.45222015e+01 -6.50538254e+01 -6.81827240e+01 -6.98512497e+01 -7.00650635e+01 -6.77361450e+01 -6.49515305e+01 -6.54267883e+01 -6.55657501e+01 -6.59528732e+01 -6.57515335e+01 -6.66305771e+01 -6.66784668e+01 -6.66857986e+01 -6.50597382e+01 -6.57482376e+01 -6.45587997e+01 -6.39466476e+01 -6.30023346e+01 -6.21922646e+01 -6.17563744e+01 -6.17273293e+01 -6.32732582e+01 -6.15947571e+01 -6.04418907e+01 -5.95475426e+01 -6.21679688e+01 -6.13969498e+01 -6.05925102e+01 -6.13096390e+01 -6.35989075e+01 -6.41136475e+01 -6.01549034e+01 -5.80121040e+01 -5.88746681e+01 -5.88424606e+01 -5.62345085e+01 -5.63947105e+01 -5.94576530e+01 -6.35340729e+01 -6.31173782e+01 -6.28953285e+01 -6.30462646e+01 -6.22462463e+01 -6.17719612e+01 -6.44963760e+01 -6.91699295e+01 -6.94165039e+01 -6.58884430e+01 -6.27473335e+01 -6.44399414e+01 -6.28414078e+01 -6.44288635e+01 -6.31864624e+01 -6.47875595e+01 -6.33660660e+01 -6.45722046e+01 -6.43529587e+01 -5.94781799e+01 -5.46609192e+01 -5.56260414e+01 -5.88562851e+01 -5.97329559e+01 -6.04759903e+01 -6.39516563e+01 -6.59764862e+01 -6.24897728e+01 -5.95784988e+01 -6.11293449e+01 -6.62064590e+01 -6.24548073e+01 -5.64415016e+01 -5.46937943e+01 -6.06237183e+01 -6.81525421e+01 -6.97100067e+01 -6.96382523e+01 -6.69195175e+01 -5.75425072e+01 -4.88876152e+01 -4.57089882e+01 -5.12786827e+01 -5.74698639e+01 -5.92957230e+01 -6.03046417e+01 -6.21653290e+01 -6.30012283e+01 -6.13793526e+01 -5.96686897e+01 -5.98838234e+01 -5.88789024e+01 -5.90604210e+01 -6.29234734e+01 -6.91426544e+01 -7.38597412e+01 -7.53966141e+01 -7.75401840e+01 -7.28263855e+01 -6.86626663e+01 -6.59524994e+01 -6.82848206e+01 -6.06791077e+01 -5.67307625e+01 -5.24115181e+01 -5.96518631e+01 -5.80181236e+01 -6.21179314e+01 -5.79709930e+01 -6.20651321e+01 -5.72326508e+01 -5.96821175e+01 -6.69876022e+01 -8.05759964e+01 -6.35569458e+01 -4.21438522e+01 -3.37675209e+01 -4.93388977e+01 -6.38790321e+01 -6.09533920e+01 -5.73775177e+01 -5.23669624e+01 -5.51557961e+01 -5.78937378e+01 -6.02553673e+01 -5.18467865e+01 -4.69194298e+01 -4.82885246e+01 -6.16922607e+01 -7.24083328e+01 -6.37692642e+01 -5.41882172e+01 -4.40033951e+01 -4.58887520e+01 -4.43672562e+01 -4.05839615e+01 -3.07725239e+01 -2.36727371e+01 -3.15304031e+01 -4.52795258e+01 -5.20245285e+01 -4.84790344e+01 -5.01296692e+01 -5.20100250e+01 -5.55144196e+01 -5.13817368e+01 -5.27007179e+01 -4.53625984e+01 -4.82695923e+01 -4.03974457e+01 -4.69544868e+01 -4.49288177e+01 -4.81975594e+01 -5.41999741e+01 -6.70593643e+01 -9.12786865e+01 -9.93174210e+01 -9.08602905e+01 -7.41027222e+01 -6.44527969e+01 -5.98723717e+01 -5.60753174e+01 -5.97635880e+01 -6.60007553e+01 -6.92122192e+01 -6.75621796e+01 -5.96581917e+01 -5.38001900e+01 -6.24344940e+01 -7.67658539e+01 -8.23326416e+01 -7.67680664e+01 -6.52753830e+01 -6.13913269e+01 -5.30492744e+01 -4.65365219e+01 -3.70195236e+01 -4.21252823e+01 -4.82200775e+01 -5.15360107e+01 -4.35183868e+01 -4.04079933e+01 -4.16509933e+01 -3.78919220e+01 -3.55600700e+01 -4.10191994e+01 -4.49559021e+01 -4.96814613e+01 -4.34502182e+01 -3.85783348e+01 -3.61600800e+01 -4.09024963e+01 -5.20900841e+01 -5.77910767e+01 -5.82587128e+01 -5.35368118e+01 -2.88419476e+01 4.98120384e+01 2.75160007e+01 1.35335007e+02 4.96358795e+01 9.86383606e+02 1.45051172e+03 6.83872604e+01 -2.27103615e+01 3.50025116e+02 4.64831934e+03 1.12340645e+04 -166160512. -43137324. -74817408. 43299144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1878641536. -270095360. -3.07232441e+04 -1.18383350e+04 -1.71753357e+03 -1.06965588e+03 -5.99261108e+02 -4.90482086e+02 -3.83915375e+02 -3.34544708e+02 -2.47815964e+02 -1.74515915e+02 -1.48604660e+02 -2.15685959e+02 -2.83141357e+02 -2.77921204e+02 -2.82373383e+02 -2.53394012e+02 3.91945483e+03 2.26062207e+03 3.68163818e+02 8.04377747e+01 4.00598602e+01 1.69698029e+01 1.56289549e+01 1.14022815e+00 -2.32341499e+01 -4.14139938e+01 -5.17245636e+01 -5.17488518e+01 -4.57373390e+01 -3.68386345e+01 -3.82889748e+01 -4.78246880e+01 -5.52541771e+01 -5.55160713e+01 -4.60383263e+01 -4.40480080e+01 -4.04082489e+01 -4.45393600e+01 -3.87866173e+01 -3.20195198e+01 -3.15247822e+01 -3.79362297e+01 -5.01284485e+01 -6.06534309e+01 -6.83478622e+01 -6.01102333e+01 -6.26670151e+01 -6.55102158e+01 -6.57538986e+01 -5.26606789e+01 -4.07875633e+01 -4.43486633e+01 -5.01874733e+01 -4.44736748e+01 -3.80288467e+01 -3.08310223e+01 -3.68283806e+01 -4.12031288e+01 -3.84535370e+01 -3.53822212e+01 -1.30375490e+01 7.04943323e+00 1.40305805e+01 1.63635063e+01 1.18440866e+01 2.74301720e+01 3.12981663e+01 1.67164516e+01 -1.58131003e+00 -2.78345089e+01 -3.49848671e+01 -4.11380005e+01 -5.23523903e+01 -6.93321304e+01 -8.00192337e+01 -7.54501495e+01 -5.44086494e+01 -3.23699074e+01 -2.53089027e+01 -2.18997269e+01 -2.91701527e+01 -4.30650234e+00 1.72681561e+01 4.24894753e+01 5.41680489e+01 4.45863304e+01 2.65658264e+01 -5.97285666e-02 -2.05793881e+00 1.95779061e+00 3.01075516e+01 4.97586288e+01 4.35764313e+01 1.11166315e+01 -1.07909422e+01 -8.35990429e+00 2.88564634e+00 1.08383427e+01 2.00397816e+01 -4.99724817e+00 -3.49831772e+01 -4.50684395e+01 -2.89240017e+01 -7.35205126e+00 -1.45998354e+01 -1.35688868e+01 8.47711563e+00 2.70049648e+01 4.67334023e+01 3.93735008e+01 1.56881466e+01 -1.89795551e+01 -4.97545967e+01 -5.11366272e+01 -3.80658226e+01 -2.43724461e+01 -1.77931080e+01 -3.05337486e+01 -3.50491028e+01 -3.06580048e+01 -2.49164486e+01 -1.97675247e+01 -1.94315014e+01 -8.85326195e+00 -8.91315460e+00 -7.54728365e+00 1.86981449e+01 5.13691940e+01 5.50123863e+01 2.64691734e+01 -3.81113917e-01 1.98115025e+01 4.32589188e+01 6.15194664e+01 6.17947998e+01 4.61932907e+01 2.02932873e+01 -3.68399763e+00 -1.43726807e+01 -1.12090473e+01 -1.32070360e+01 -1.45855789e+01 -2.19593067e+01 -3.00416584e+01 -2.54220657e+01 -1.10566912e+01 -5.44231033e+00 -1.24104280e+01 -1.35507383e+01 -8.24988556e+00 8.88344193e+00 3.48283882e+01 6.30543213e+01 6.12501144e+01 3.40511780e+01 4.42156029e+00 2.50439396e+01 5.33921242e+01 7.27314453e+01 7.48051300e+01 7.54565048e+01 7.88914719e+01 5.43601456e+01 3.99720764e+01 1.58176155e+01 1.27370014e+01 3.32402372e+00 -2.14172959e+00 5.88476276e+00 9.28004169e+00 1.55798960e+01 1.20344734e+01 1.76716499e+01 6.28291321e+00 -2.56882668e+01 -5.56062317e+01 -4.78066826e+01 -1.29488707e+01 1.31160412e+01 1.94187202e+01 1.88172169e+01 9.55707645e+00 -7.03975582e+00 9.17728996e+00 4.18089409e+01 4.56939201e+01 2.60354042e+01 1.69768429e+00 8.85664368e+00 1.40705481e+01 1.68994598e+01 1.22703247e+01 1.28668966e+01 1.09755039e+01 2.80202274e+01 3.69739227e+01 3.70674171e+01 2.79466286e+01 2.06888332e+01 8.49585629e+00 -1.38567600e+01 -1.03161278e+01 7.80126810e+00 2.74750175e+01 1.11415682e+01 4.55985934e-01 5.27984476e+00 1.28737640e+01 1.77158718e+01 1.35231533e+01 1.02506676e+01 8.27353287e+00 1.00495882e+01 1.81374702e+01 1.74847527e+01 1.41190872e+01 1.45083399e+01 8.09734821e+00 6.00051546e+00 -2.22807908e+00 7.71128416e-01 3.76409984e+00 4.15709639e+00 4.68663168e+00 -8.25460529e+00 -1.85023232e+01 -1.93091850e+01 -1.15325270e+01 1.91293907e+00 -1.69256353e+00 5.67324936e-01 -8.30861568e+00 -1.17495918e+01 -1.41425238e+01 -7.46858311e+00 -2.32372594e+00 -5.44329262e+00 -5.60477638e+00 1.79268026e+00 1.43378382e+01 2.56025143e+01 2.39402924e+01 3.94740731e-01 -2.53632317e+01 -2.99672565e+01 -5.02679920e+00 4.52243805e+01 7.63402252e+01 7.35759354e+01 4.47407188e+01 1.99233341e+01 4.84304733e+01 6.97210846e+01 6.95746002e+01 3.88687134e+01 1.53240690e+01 1.48331556e+01 1.38830242e+01 1.67005844e+01 2.18286896e+01 1.89806004e+01 1.48390818e+01 1.13351822e+01 2.40558186e+01 3.61228828e+01 2.54929676e+01 1.08898811e+01 2.41970229e+00 2.17799110e+01 3.99202232e+01 5.14739227e+01 5.03990021e+01 4.95514107e+01 4.03487701e+01 3.85473595e+01 3.52139397e+01 5.34829636e+01 6.53644714e+01 5.92912636e+01 3.83708000e+01 1.64493942e+01 2.03497887e+01 2.14155960e+01 3.36551094e+01 3.60631638e+01 1.94725590e+01 -2.49494219e+00 -3.06948137e+00 1.07669640e+01 3.06475182e+01 2.21394596e+01 2.06585598e+01 2.25322685e+01 2.89428730e+01 5.59982262e+01 7.76497040e+01 7.51411514e+01 5.57677040e+01 2.88998604e+01 3.17705498e+01 3.25380783e+01 3.32237282e+01 3.26654663e+01 5.05181198e+01 7.38870163e+01 8.03428192e+01 6.98231277e+01 3.99462395e+01 4.14851494e+01 3.97600060e+01 4.43724022e+01 3.47564354e+01 3.64180679e+01 4.13020973e+01 4.85627403e+01 4.13702621e+01 3.33919182e+01 3.18735294e+01 3.68861160e+01 3.43452415e+01 2.66959915e+01 2.71057835e+01 2.89864006e+01 3.52161751e+01 4.82693977e+01 7.48059158e+01 9.28359985e+01 9.97778473e+01 9.57627869e+01 9.40442276e+01 6.77566986e+01 5.49427834e+01 4.13426704e+01 4.07430687e+01 3.26237259e+01 4.41489716e+01 6.31604462e+01 6.06860199e+01 5.12533951e+01 2.30603333e+01 7.80926228e+00 5.91567373e+00 1.43139496e+01 3.91161118e+01 4.58775024e+01 5.55334129e+01 6.93565674e+01 7.87221298e+01 6.95227509e+01 4.79289055e+01 2.10825558e+01 3.15394268e+01 4.29938736e+01 5.62534599e+01 5.70546722e+01 5.42349358e+01 5.03211555e+01 3.51400375e+01 2.62249374e+01 2.67832088e+01 2.99006844e+01 3.11021633e+01 2.75176392e+01 2.39915085e+01 2.73490505e+01 3.37710228e+01 4.33832626e+01 5.04412651e+01 5.15732803e+01 7.21660919e+01 9.22445374e+01 8.14481659e+01 4.43343773e+01 3.31842003e+01 6.14423599e+01 8.04427338e+01 6.78923721e+01 4.52411079e+01 6.41891785e+01 8.20226059e+01 8.71029816e+01 7.16688461e+01 5.86149178e+01 5.74542885e+01 6.32539558e+01 7.21991272e+01 7.50639343e+01 6.31548157e+01 4.53588257e+01 4.32124290e+01 4.48248405e+01 5.36401558e+01 5.22392311e+01 5.78209381e+01 6.52583008e+01 8.09723816e+01 6.24284096e+01 2.98287697e+01 3.22099228e+01 6.05761757e+01 8.45941696e+01 6.69999008e+01 5.37640610e+01 6.02604141e+01 6.65056686e+01 5.56289864e+01 3.75036697e+01 2.52586117e+01 2.92415924e+01 3.32493019e+01 5.26863480e+01 7.39740067e+01 6.70278168e+01 4.18205147e+01 3.70882416e+01 6.74515076e+01 7.45270538e+01 5.63975677e+01 3.57784462e+01 3.82515182e+01 4.29279060e+01 3.24897385e+01 1.62803574e+01 2.74295597e+01 5.01031342e+01 6.78896103e+01 5.74945831e+01 4.92135277e+01 5.02161140e+01 5.37804947e+01 5.89244232e+01 6.24729805e+01 6.00340080e+01 4.96178627e+01 4.82232246e+01 6.54960938e+01 8.35534439e+01 8.30032120e+01 7.14079285e+01 7.74040604e+01 9.76614304e+01 8.74828186e+01 5.78049011e+01 3.12944908e+01 3.32077522e+01 4.62608833e+01 4.33084335e+01 3.83941154e+01 4.50744896e+01 5.60163193e+01 6.57400055e+01 6.11875801e+01 5.27543793e+01 4.79241676e+01 4.26398277e+01 4.25261421e+01 4.59200745e+01 4.80886497e+01 4.85517998e+01 4.81518135e+01 6.04056969e+01 7.10426941e+01 6.59207840e+01 5.03392792e+01 4.66214943e+01 5.85017929e+01 5.50235901e+01 4.32482872e+01 4.69494820e+01 7.55149689e+01 1.05290932e+02 1.07251183e+02 9.12800522e+01 8.71465149e+01 9.19449615e+01 8.78324585e+01 7.41420746e+01 6.56196136e+01 6.87187729e+01 6.77574844e+01 6.74173203e+01 7.39181290e+01 7.39286957e+01 6.25134811e+01 4.92993736e+01 5.70599022e+01 7.23051682e+01 7.11024704e+01 6.02709579e+01 6.36385002e+01 7.84795303e+01 6.87240753e+01 3.81972656e+01 1.97717876e+01 2.83533707e+01 4.33425255e+01 3.94838409e+01 2.96587505e+01 2.90440502e+01 3.67458992e+01 4.28523140e+01 3.83756714e+01 3.61378098e+01 3.76730461e+01 4.72592392e+01 6.41327972e+01 7.86017456e+01 8.75610504e+01 8.83064880e+01 7.11985397e+01 5.36644630e+01 4.59721985e+01 5.26515884e+01 5.85200729e+01 5.60129280e+01 5.69105453e+01 5.13439484e+01 4.24930305e+01 4.46403694e+01 5.27115364e+01 6.09971619e+01 6.09785995e+01 6.27444000e+01 7.50454559e+01 8.36170731e+01 8.09740524e+01 7.11362305e+01 6.43552475e+01 6.51393051e+01 6.32215347e+01 6.37821426e+01 6.74047241e+01 7.04586639e+01 6.95330276e+01 6.71620255e+01 6.59966354e+01 6.42175293e+01 6.14810982e+01 6.22446251e+01 7.22701187e+01 8.50283890e+01 8.32261734e+01 7.48785172e+01 7.16838531e+01 7.89863281e+01 7.92419281e+01 7.33351135e+01 6.71894836e+01 7.39369202e+01 8.10509491e+01 8.04915161e+01 7.33604507e+01 6.21793442e+01 6.01695213e+01 6.07313690e+01 6.90039902e+01 7.60383606e+01 7.45862274e+01 6.70188293e+01 6.68387451e+01 7.44511566e+01 7.71534958e+01 7.31324310e+01 6.51973495e+01 6.88089447e+01 7.35433121e+01 7.37679749e+01 6.70211945e+01 6.09122734e+01 6.33433380e+01 6.95745239e+01 7.20775528e+01 7.22379456e+01 6.97829666e+01 6.88846664e+01 7.05820541e+01 7.11771164e+01 7.47083893e+01 7.52088089e+01 7.44304352e+01 7.14483109e+01 6.81675110e+01 6.74822464e+01 6.56970978e+01 6.61457443e+01 6.61700058e+01 6.69251175e+01 6.74301529e+01 6.76374664e+01 6.71912537e+01 6.59753647e+01 6.30809479e+01 6.20380783e+01 6.57430191e+01 7.00321274e+01 7.15156097e+01 7.36175232e+01 7.97968979e+01 9.00294037e+01 9.05676498e+01 1.33709488e+02 9.72742691e+01 7.73547516e+01 1.05188232e+02 6.41510620e+01 1.94640320e+02 4.49489166e+02 -125723448. -403240896. 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. -8.71589500e+05 -7.99744568e+01 6.75911427e+00 1.17215147e+01 2.40529575e+01 3.71536369e+01 3.93797951e+01 3.47054024e+01 3.57675552e+01 3.69063301e+01 3.52915535e+01 3.42013168e+01 3.46291161e+01 2.52996254e+01 2.18515472e+01 3.00101013e+01 4.86635323e+01 5.47346725e+01 4.53525085e+01 3.95153351e+01 3.24264984e+01 2.92456818e+01 3.06622124e+01 3.12086868e+01 3.20881004e+01 3.27989120e+01 3.60805359e+01 4.01853142e+01 4.06197815e+01 3.64352570e+01 3.20080566e+01 3.25873146e+01 3.30828400e+01 3.29953270e+01 3.61869469e+01 3.63868217e+01 3.59898109e+01 3.31323013e+01 3.01503086e+01 2.72531357e+01 2.57816124e+01 3.20817108e+01 4.09908524e+01 4.42393951e+01 3.89820824e+01 2.90898819e+01 2.80084648e+01 3.15964870e+01 3.16999073e+01 3.02511787e+01 3.32873878e+01 3.90312233e+01 4.23327637e+01 3.73329926e+01 2.92771149e+01 2.12711487e+01 2.21493816e+01 2.48074512e+01 2.72936935e+01 3.21664810e+01 3.54898453e+01 3.83114777e+01 3.36531754e+01 2.76560764e+01 2.17931957e+01 2.15250340e+01 3.05501423e+01 3.90655251e+01 4.28752975e+01 4.49516068e+01 4.02302780e+01 4.00793762e+01 3.56451797e+01 2.62255230e+01 1.86808624e+01 1.74015179e+01 2.64712200e+01 3.50260468e+01 3.77348518e+01 3.40352325e+01 2.59694366e+01 2.30564747e+01 2.08537083e+01 2.17433357e+01 2.49118290e+01 2.61524067e+01 2.89985981e+01 3.07827415e+01 3.03462067e+01 2.52868671e+01 1.87299232e+01 2.13859482e+01 3.07379379e+01 4.07151718e+01 4.10556488e+01 2.75917091e+01 1.95356083e+01 2.50564423e+01 2.87265339e+01 2.25079632e+01 1.73745880e+01 2.61161652e+01 4.17854805e+01 4.68915634e+01 3.55890007e+01 2.02942734e+01 1.16031237e+01 1.67269936e+01 2.13837852e+01 2.79824657e+01 3.42073402e+01 3.33693428e+01 3.35532150e+01 3.10363369e+01 2.05354404e+01 8.81767941e+00 5.65293694e+00 1.92905025e+01 3.64458466e+01 4.29981384e+01 3.59861259e+01 2.27822990e+01 1.73567200e+01 1.72293377e+01 1.67326069e+01 1.84949627e+01 2.48082962e+01 3.62153282e+01 5.02902603e+01 5.18143044e+01 4.23994904e+01 3.08926620e+01 2.79387608e+01 2.43726254e+01 1.73460827e+01 1.92676678e+01 2.26582394e+01 3.10873680e+01 2.96482830e+01 2.65611820e+01 2.40428200e+01 2.48960781e+01 3.21053429e+01 3.35596886e+01 2.74674854e+01 1.92405834e+01 1.68392811e+01 3.02080288e+01 4.13800049e+01 3.49301872e+01 3.01045532e+01 2.74609776e+01 3.65020409e+01 4.44385185e+01 4.41427689e+01 2.26878643e+01 7.14802027e-01 4.46877718e+00 2.99329433e+01 4.63909950e+01 4.61301956e+01 3.82786751e+01 4.19335823e+01 4.05583191e+01 2.54359798e+01 7.33791876e+00 3.28575277e+00 1.92572746e+01 3.28350487e+01 4.83420067e+01 5.81530151e+01 5.21501579e+01 4.93005905e+01 4.26161461e+01 3.48404465e+01 3.00572014e+01 2.76420784e+01 4.32338562e+01 5.02462044e+01 5.06376190e+01 3.71739159e+01 1.90342159e+01 1.52480431e+01 2.20436516e+01 2.55949879e+01 2.85326385e+01 2.68566227e+01 3.99252548e+01 4.39011536e+01 2.45793610e+01 -8.28089118e-01 -9.58002186e+00 8.00828171e+00 2.90368099e+01 4.87664070e+01 5.98140182e+01 5.16589966e+01 4.24384613e+01 3.22013474e+01 1.13889036e+01 -8.17270660e+00 -1.14261580e+01 1.61605530e+01 4.76093063e+01 6.37232933e+01 5.01104927e+01 1.87236557e+01 3.33868170e+00 9.73955822e+00 2.31119442e+01 2.43930302e+01 2.19089088e+01 1.93757496e+01 2.39051819e+01 2.61411591e+01 2.66214790e+01 1.49101372e+01 5.12738848e+00 6.02529526e+00 1.98121052e+01 4.07189331e+01 4.53049812e+01 4.54098816e+01 3.19833298e+01 1.46514616e+01 1.00879354e+01 7.97581100e+00 3.30492210e+01 4.53614006e+01 4.27675400e+01 2.66911640e+01 2.57568340e+01 3.95647125e+01 5.13928719e+01 2.52152576e+01 2.39600703e-01 -1.06101913e+01 1.61410141e+01 3.72484512e+01 3.74320908e+01 4.08692093e+01 2.19343433e+01 6.51881838e+00 -1.13365107e+01 1.27200451e+01 3.82646294e+01 3.73015785e+01 2.99867725e+01 3.52227516e+01 5.71911201e+01 5.49245796e+01 2.87806988e+01 2.03760185e+01 4.09179420e+01 4.60620842e+01 2.71726933e+01 1.86410656e+01 2.81844273e+01 3.66037674e+01 1.82556629e+01 7.14056349e+00 5.95387030e+00 2.62507896e+01 3.95106354e+01 3.64432564e+01 3.60511742e+01 2.12275219e+01 8.06954098e+00 2.99488378e+00 9.57797432e+00 8.41589546e+00 -5.53393936e+00 5.65798664e+00 2.05339184e+01 2.46175308e+01 3.36520600e+00 -1.13691139e+01 -5.54657364e+00 1.65329285e+01 2.27439060e+01 1.04339256e+01 6.61525297e+00 1.38200817e+01 1.84489136e+01 1.36674738e+01 2.93985844e+01 4.44447746e+01 4.54819641e+01 1.65867710e+01 -1.25416985e+01 -1.66163311e+01 -7.97820520e+00 3.80543709e+00 3.80390882e+00 5.63482952e+00 -2.86466861e+00 -1.52790108e+01 -1.53600492e+01 -7.71183157e+00 3.67370963e+00 -7.99142170e+00 -1.78910522e+01 -3.08403921e+00 2.98774223e+01 3.30304375e+01 7.64621258e+00 -1.33493176e+01 -3.16746807e+00 -2.97436857e+00 -1.29103928e+01 -1.58701839e+01 -1.57173233e+01 -1.98912640e+01 -3.32017517e+01 -3.65211525e+01 -2.83754311e+01 -3.39354362e+01 -3.80030556e+01 -3.14850159e+01 -1.15222788e+01 -2.77404642e+00 -1.47749376e+01 -1.06620436e+01 1.64923172e+01 3.46410713e+01 3.43078384e+01 2.81189384e+01 3.57283974e+01 4.31208267e+01 2.55226154e+01 6.20069504e+00 -6.18437815e+00 -1.07668376e+00 -4.02508593e+00 -1.74392109e+01 -1.78769321e+01 -1.82648392e+01 -2.78747520e+01 -3.84462357e+01 -3.47622108e+01 -5.42908382e+00 -3.30482626e+00 -6.65883684e+00 -1.29555502e+01 -6.02934027e+00 -6.50600576e+00 -3.45662842e+01 -3.24864731e+01 -4.10706234e+00 2.88242798e+01 4.08762741e+01 1.85759354e+01 1.82747173e+01 2.74729843e+01 3.79251671e+01 3.51763573e+01 4.75886822e+00 -1.03156557e+01 -2.24827614e+01 -5.69060230e+00 4.48186646e+01 5.67609253e+01 3.46525383e+01 -2.02652187e+01 -3.99606209e+01 -4.18955660e+00 1.19516573e+01 8.38503838e+00 -2.39702816e+01 -4.05369759e+01 -2.07047787e+01 -1.52229471e+01 1.63832986e+00 1.80024986e+01 2.28922653e+01 1.90081902e+01 -9.15470314e+00 -1.58151970e+01 -1.02335882e+01 4.76459646e+00 1.82852936e+01 4.01569796e+00 -1.08053637e+01 -3.05038261e+01 -1.78568325e+01 2.01724491e+01 3.77640114e+01 1.54564676e+01 -2.76815300e+01 -4.39501343e+01 -7.38527632e+00 2.98672428e+01 4.59025421e+01 1.76246357e+01 -1.79307079e+01 -2.07903748e+01 -2.30466576e+01 -4.52511644e+00 1.54271450e+01 2.71797047e+01 3.08814106e+01 5.32114458e+00 -5.30068815e-01 -6.81033897e+00 3.15473825e-01 7.87610435e+00 -5.92745352e+00 -2.17158184e+01 -3.18926010e+01 -1.87303581e+01 2.72066975e+01 3.75342407e+01 2.30081501e+01 -2.15689907e+01 -4.53620949e+01 -2.96684532e+01 -1.51655397e+01 1.57547784e+00 -1.62350597e+01 -3.17712421e+01 -2.64889679e+01 -1.61668587e+01 -7.39346838e+00 3.39081430e+00 2.96468401e+00 2.18373299e+00 -2.54207420e+01 -3.53872452e+01 -2.53080158e+01 5.06386280e+00 3.43713226e+01 1.42638445e+01 -1.66590862e+01 -4.20659523e+01 -3.07915249e+01 1.51902027e+01 2.72834911e+01 1.54774094e+01 -2.41464500e+01 -3.89767876e+01 -2.87071800e+00 4.12839470e+01 7.36397400e+01 5.39958496e+01 1.45476980e+01 -9.14904118e+00 -2.46748753e+01 -1.96550751e+01 7.28013158e-01 1.26198597e+01 9.68385887e+00 -1.92746296e+01 -3.17423725e+01 -3.63529091e+01 -2.55305386e+01 3.02034974e+00 -3.06842494e+00 -1.18383999e+01 -3.97821350e+01 -3.98283653e+01 -1.76602840e+01 7.69478130e+00 2.56438351e+01 7.83475733e+00 -1.30287278e+00 -9.34727573e+00 -5.66008139e+00 4.20520115e+00 2.16269627e+01 2.38630333e+01 2.39181747e+01 1.13256426e+01 1.19037628e+01 1.34016323e+01 8.42558002e+00 8.18954086e+00 -2.09081306e+01 -1.47650919e+01 -1.19853563e+01 -9.64163184e-01 8.96204758e+00 -6.99184465e+00 -8.19886303e+00 -5.38953924e+00 1.96042080e+01 5.28117485e+01 5.40382538e+01 4.18249283e+01 2.88769770e+00 -3.24700699e+01 -1.72202873e+01 1.02071924e+01 4.41575661e+01 4.79707794e+01 2.69776554e+01 5.21016502e+00 -3.05817528e+01 -3.88209686e+01 -2.57236500e+01 -5.85577011e+00 5.33281326e+00 -1.17753792e+01 -3.21617012e+01 -4.17920456e+01 -4.01277695e+01 -1.76529005e-01 2.27938404e+01 2.65827808e+01 -6.23498583e+00 -3.01082649e+01 -8.90313148e+00 2.38073235e+01 3.57240868e+01 9.78249645e+00 -2.08410511e+01 -2.00338898e+01 -2.53262997e+01 -1.71024475e+01 -2.40296674e+00 6.93350506e+00 -5.38625836e-01 -2.73334408e+01 -4.10039482e+01 -2.87291794e+01 -2.16890755e+01 -3.74037051e+00 -1.59809847e+01 -1.72471790e+01 -1.93645267e+01 -1.98992119e+01 5.06176472e+00 1.12273092e+01 9.49035740e+00 -2.37023983e+01 -3.70012131e+01 -3.89748268e+01 -2.95504436e+01 -2.97128105e+01 -2.79437771e+01 -2.86020679e+01 -2.51798611e+01 -3.60242882e+01 -3.73844604e+01 -2.88057537e+01 -1.79368916e+01 -6.39524889e+00 -1.71944141e+01 -1.42340612e+01 -1.09651537e+01 2.73522687e+00 1.13185940e+01 -1.54176140e+01 -2.49003029e+01 -3.12953701e+01 -2.29312458e+01 4.52812386e+00 1.81399727e+01 2.04416771e+01 -1.35446424e+01 -4.47399406e+01 -4.56581192e+01 -3.07025757e+01 -6.76086044e+00 -1.34486704e+01 -3.20801430e+01 -3.10516148e+01 -2.58088779e+01 -1.42150497e+01 -7.55263710e+00 -3.49073315e+00 -4.59545708e+00 -2.09863682e+01 -2.12351398e+01 -1.89607372e+01 -2.22476692e+01 -4.19111204e+00 1.40211856e+00 8.42831516e+00 -7.84940434e+00 -2.01957779e+01 -1.64070797e+01 -1.20780983e+01 -1.78140697e+01 -3.66729851e+01 -6.13525772e+01 -3.65225410e+01 -1.46449718e+01 1.32697477e+01 1.45887156e+01 2.46234012e+00 8.26352298e-01 -1.48324776e+01 -1.14442358e+01 -5.25604582e+00 -1.63478208e+00 1.23981924e+01 -2.83952534e-01 -3.60489011e+00 -1.57184181e+01 -2.22939377e+01 -7.35312176e+00 -2.05580521e+01 -3.38881340e+01 -5.30502930e+01 -4.75453300e+01 -1.81240864e+01 -5.04081774e+00 -4.16279078e+00 -4.55444221e+01 -9.50364532e+01 -5.46248131e+01 -6.19191895e+01 -8.15718293e-01 3.53203506e+01 2.35254517e+02 -1.70838242e+02 -2.65638000e+02 4.27060986e+03 8.75749902e+03 -91476496. 136346288. -104345336. -644055360. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 395975776. 1039180928. -5.57784326e+03 -2.16308740e+03 -3.47946442e+02 -2.00372299e+02 -8.68497086e+01 2.09152699e+01 -1.79849396e+01 -5.52301941e+01 -6.03597527e+01 -4.40100288e+01 -3.65014343e+01 -2.17027931e+01 -1.85480595e+01 -3.19265060e+01 -3.37993622e+01 -2.91717224e+01 -1.37837820e+01 -6.88782036e-01 -6.96697426e+00 -2.26007137e+01 -2.53906269e+01 -2.41583500e+01 -1.32012119e+01 -2.08825779e+01 -2.83177605e+01 -3.40534058e+01 -3.97417793e+01 -3.34020386e+01 -3.13579216e+01 -1.75956879e+01 -4.21160173e+00 -1.58531075e+01 -3.17917557e+01 -4.84291687e+01 -4.25036964e+01 -1.18288679e+01 5.92285872e+00 1.11143761e+01 -1.50946569e+01 -2.53388119e+01 -1.78183422e+01 -8.62256050e+00 -4.57778215e+00 -2.58100681e+01 -4.16066055e+01 -4.49631920e+01 -3.21370087e+01 -9.80596924e+00 3.91516894e-01 2.13620853e+00 -1.51731598e+00 -1.97950783e+01 -2.84136066e+01 -3.55257874e+01 -2.76382198e+01 -1.10091047e+01 -1.67343521e+01 -2.56363087e+01 -3.31111069e+01 -1.71002026e+01 6.48266268e+00 1.92750946e-01 -2.20172920e+01 -4.96203842e+01 -5.67551308e+01 -4.60688896e+01 -3.08421173e+01 -1.16141224e+01 -5.96467447e+00 -1.23110886e+01 -2.61041203e+01 -3.95705528e+01 -4.13574142e+01 -3.94297028e+01 -3.92524796e+01 -2.91250668e+01 -3.12094593e+01 -2.38645325e+01 -2.88691616e+01 -2.75603523e+01 -2.01392193e+01 -2.93588028e+01 -3.75919724e+01 -5.15822525e+01 -5.19580231e+01 -3.71944542e+01 -2.30621281e+01 -1.77570591e+01 -2.94469604e+01 -4.32933807e+01 -4.52402229e+01 -4.45410309e+01 -3.90330238e+01 -3.45940437e+01 -3.77519379e+01 -3.74476929e+01 -4.42694550e+01 -3.63155136e+01 -2.89768505e+01 -2.49629955e+01 -2.42147446e+01 -3.44692802e+01 -3.91935730e+01 -4.39239120e+01 -4.24535065e+01 -3.13869438e+01 -3.34653664e+01 -3.71048393e+01 -4.68115997e+01 -4.82256088e+01 -3.80084229e+01 -2.86190224e+01 -2.56636829e+01 -3.67948494e+01 -4.96630898e+01 -4.66756325e+01 -4.35530586e+01 -3.67879944e+01 -3.28639488e+01 -3.16040459e+01 -3.23279343e+01 -4.20283661e+01 -4.29690971e+01 -4.10885735e+01 -3.87671356e+01 -3.54394150e+01 -3.86893234e+01 -3.95562248e+01 -4.09615517e+01 -3.79935951e+01 -2.74313850e+01 -2.67813206e+01 -3.24093208e+01 -4.07849312e+01 -4.41125793e+01 -3.58093681e+01 -3.06494350e+01 -2.92860184e+01 -3.59853897e+01 -4.26953354e+01 -4.06961670e+01 -4.11402931e+01 -3.74253273e+01 -3.33429527e+01 -3.01554565e+01 -3.01273937e+01 -3.71281281e+01 -4.05178299e+01 -3.99031982e+01 -3.66582565e+01 -3.28686523e+01 -3.56906013e+01 -3.82581711e+01 -4.17758484e+01 -3.95499649e+01 -3.17322598e+01 -2.78603077e+01 -3.13689899e+01 -3.89071388e+01 -4.38560753e+01 -4.20607109e+01 -3.95838966e+01 -3.56404839e+01 -3.72241669e+01 -4.04365044e+01 -3.96675797e+01 -3.77733688e+01 -3.43468285e+01 -3.40377846e+01 -3.64252625e+01 -3.67223701e+01 -3.90354347e+01 -3.82364273e+01 -3.65578423e+01 -3.27754936e+01 -2.80113640e+01 -3.21635056e+01 -3.62880211e+01 -3.92724800e+01 -3.76396637e+01 -3.32564430e+01 -3.48572578e+01 -3.63435287e+01 -3.90060158e+01 -3.82817497e+01 -3.59172974e+01 -3.52808380e+01 -3.39904099e+01 -3.33190689e+01 -3.28449821e+01 -3.15828228e+01 -3.36065865e+01 -3.41934433e+01 -3.39666939e+01 -3.44963722e+01 -3.35422554e+01 -3.53339577e+01 -3.48725891e+01 -3.60812111e+01 -3.53676300e+01 -3.25450172e+01 -3.18696365e+01 -3.19836464e+01 -3.46257935e+01 -3.56291428e+01 -3.49547462e+01 -3.39008827e+01 -3.30942612e+01 -3.39636650e+01 -3.46420250e+01 -3.40948830e+01 -3.31984711e+01 -3.22065506e+01 -3.21499825e+01 -3.30587387e+01 -3.38350334e+01 -3.39997101e+01 -3.33318138e+01 -3.29014206e+01 -3.30480232e+01 -3.30698891e+01 -3.31555862e+01 -3.31440964e+01 -3.31512794e+01 -3.31670723e+01 -3.31858406e+01 -3.31300774e+01 -3.31816254e+01 -3.32366829e+01 -3.31442299e+01 -3.29885941e+01 -3.29387856e+01 -3.31173859e+01 -3.33239136e+01 -3.32362366e+01 -3.33512726e+01 -3.32852364e+01 -3.34433937e+01 -3.31229630e+01 -3.30213852e+01 -3.27780647e+01 -3.27543716e+01 -3.28470802e+01 -3.30801468e+01 -3.33131981e+01 -3.31364288e+01 -3.28857536e+01 -3.23790627e+01 -3.25306358e+01 -3.25140953e+01 -3.30252495e+01 -3.24182091e+01 -3.20292053e+01 -3.19132500e+01 -3.28572617e+01 -3.33772812e+01 -3.31911850e+01 -3.32863884e+01 -3.29114647e+01 -3.22429161e+01 -3.10041027e+01 -3.16026764e+01 -3.17650852e+01 -3.25317726e+01 -3.18899193e+01 -3.30390778e+01 -3.29836159e+01 -3.27643700e+01 -3.13540802e+01 -3.16403713e+01 -3.13101692e+01 -3.23992844e+01 -3.27897797e+01 -3.31080170e+01 -3.20348473e+01 -3.02993450e+01 -3.09731007e+01 -3.16287460e+01 -3.24037056e+01 -3.19299831e+01 -3.15945454e+01 -3.18739872e+01 -3.21910629e+01 -3.23488197e+01 -3.42362442e+01 -3.55730400e+01 -3.64273834e+01 -3.50343361e+01 -3.40501518e+01 -3.27751312e+01 -3.30599022e+01 -3.26289330e+01 -3.25780830e+01 -2.88027077e+01 -2.79554977e+01 -2.69047508e+01 -3.14060555e+01 -3.25204010e+01 -3.52432518e+01 -3.35341721e+01 -3.47665291e+01 -3.41348839e+01 -3.39494095e+01 -3.21730576e+01 -3.16336212e+01 -3.11053467e+01 -3.30246735e+01 -3.60160942e+01 -3.73840981e+01 -3.54436874e+01 -3.39447517e+01 -2.93154354e+01 -2.40008144e+01 -2.11876698e+01 -2.48109932e+01 -3.20439606e+01 -3.40222664e+01 -3.40511208e+01 -3.09450264e+01 -3.28351517e+01 -3.76103020e+01 -3.89040489e+01 -3.52418327e+01 -3.01850262e+01 -3.06827087e+01 -3.06300602e+01 -2.88147488e+01 -3.44386711e+01 -4.13503380e+01 -4.27185631e+01 -3.79252243e+01 -3.43839226e+01 -3.51724854e+01 -3.39745522e+01 -3.33874969e+01 -3.38672218e+01 -3.21072617e+01 -3.05001945e+01 -2.88545971e+01 -3.36657944e+01 -3.50436020e+01 -3.43921356e+01 -2.91757565e+01 -2.01445103e+01 -1.40961800e+01 -1.49463282e+01 -2.42312965e+01 -3.11366844e+01 -3.05308704e+01 -2.54212456e+01 -2.61307678e+01 -2.81021671e+01 -3.12828159e+01 -2.41580524e+01 -2.09582005e+01 -1.79664192e+01 -2.31956120e+01 -2.53464413e+01 -2.71191502e+01 -2.60734406e+01 -2.08429527e+01 -1.47484732e+01 -2.38401337e+01 -3.70665359e+01 -4.08515968e+01 -3.22746201e+01 -2.62101002e+01 -2.72460823e+01 -2.01106167e+01 -1.27719698e+01 -1.24526701e+01 -2.08022327e+01 -2.92713718e+01 -2.98570518e+01 -2.73943233e+01 -2.01821442e+01 -1.29111748e+01 -1.02740984e+01 -1.45962963e+01 -1.89183960e+01 -2.26053772e+01 -2.24051037e+01 -2.44017429e+01 -2.41959000e+01 -2.77910862e+01 -3.01672211e+01 -3.20869408e+01 -2.87829247e+01 -2.84279652e+01 -2.64374561e+01 -2.67807102e+01 -2.34673138e+01 -2.45524349e+01 -2.48196831e+01 -1.88298664e+01 -1.26657515e+01 -1.54065723e+01 -3.26942253e+01 -4.30352211e+01 -3.89277992e+01 -3.22875938e+01 -2.63825741e+01 -2.94309216e+01 -2.20235748e+01 -1.78810368e+01 -1.25047665e+01 -1.55709000e+01 -2.06730232e+01 -2.09500580e+01 -1.18876266e+01 -3.89407492e+00 -1.65342979e+01 -3.61060524e+01 -4.16558609e+01 -2.89491940e+01 -1.93326664e+01 -1.31358032e+01 -7.19474840e+00 -1.14407444e+01 -2.44359379e+01 -3.02228794e+01 -2.33623943e+01 -1.48422022e+01 -1.72902908e+01 -1.96936512e+01 -3.04604225e+01 -4.56107483e+01 -4.71610146e+01 -4.10524139e+01 -2.63510647e+01 -1.88854790e+01 -1.30053339e+01 -1.70510902e+01 -2.45595398e+01 -2.84233875e+01 -3.02444477e+01 -3.25104141e+01 -3.47217598e+01 -3.79469070e+01 -3.77670059e+01 -3.40422745e+01 -2.77644978e+01 -2.63342075e+01 -2.37506962e+01 3.84702373e+00 2.43071232e+01 6.15597115e+01 3.10844650e+01 -2.72997284e+00 -5.69187469e+01 -5.82676964e+01 -5.30810242e+01 -6.15313416e+01 -3.27185559e+00 5.55705261e+02 -1.77477379e+01 -9.22697656e+03 -43137324. -74817408. 43299144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1878641536. 8.88214258e+03 1.80150659e+03 1.05283440e+02 1.74584702e+02 4.27959747e+01 3.02686214e+01 1.98043270e+01 5.60543203e+00 -2.74921346e+00 -2.69160271e+01 -4.45779915e+01 -4.87891197e+01 -3.19880581e+01 -1.89409676e+01 -2.29818859e+01 -2.16239986e+01 -2.52786140e+01 -1.38438187e+02 -1.48196579e+02 -5.92991791e+01 -2.79683514e+01 -1.10398884e+01 -8.98388767e+00 -1.93702602e+01 -2.92803249e+01 -2.12392807e+01 -1.60872955e+01 -1.52110348e+01 -2.16856823e+01 -2.35957108e+01 -2.90658150e+01 -3.08274288e+01 -2.75593739e+01 -2.19902020e+01 -1.91542320e+01 -2.20044918e+01 -2.82045765e+01 -3.14685173e+01 -3.14139519e+01 -2.72110729e+01 -2.57359142e+01 -3.10284653e+01 -2.96230850e+01 -2.68754139e+01 -2.28327999e+01 -1.91127930e+01 -1.73749428e+01 3.05871749e+00 1.88030624e+01 2.20584335e+01 6.22658873e+00 -7.84642935e+00 -1.16906853e+01 -1.14165821e+01 -1.14773273e+01 -7.05395460e+00 -9.60657406e+00 -1.41800499e+01 -2.01601429e+01 -2.41554871e+01 -3.17987823e+01 -4.00492249e+01 -4.70339508e+01 -4.15196877e+01 -3.53283386e+01 -2.71925144e+01 -3.41944275e+01 -4.42802925e+01 -3.99040718e+01 -2.88953094e+01 -1.12331562e+01 -1.80217686e+01 -1.90243664e+01 -6.11784363e+00 1.95744514e+01 3.57537117e+01 3.31309662e+01 2.65070953e+01 2.56098728e+01 1.41081171e+01 4.60967636e+00 -1.25370932e+00 3.09359050e+00 7.32240725e+00 -9.35740566e+00 -2.39160919e+01 -2.71189594e+01 -1.36002932e+01 1.08333433e+00 -1.09007895e+00 -1.86136794e+00 -1.04284134e+01 -1.15299263e+01 -9.47979355e+00 -8.01873112e+00 -1.13872643e+01 -2.20971737e+01 -2.75058289e+01 -3.07243099e+01 -3.14612350e+01 -2.01350040e+01 -6.76407623e+00 8.52556896e+00 1.21603842e+01 -3.58360672e+00 -1.26817141e+01 -2.30950470e+01 -1.34138308e+01 -9.54764843e+00 -2.23070431e+01 -3.77896538e+01 -3.76124191e+01 -2.30352745e+01 -1.00580558e-01 3.41044712e+00 3.54287338e+00 -6.07304335e-01 -1.70704544e+00 -1.51949702e-02 2.89249444e+00 4.55388689e+00 1.62346661e+00 -1.65404487e+00 -8.15289402e+00 -5.03954077e+00 -7.94959450e+00 -1.06530542e+01 -1.54063225e+01 -1.69791298e+01 -1.69308357e+01 -1.77467175e+01 -1.57013159e+01 -5.89118862e+00 4.43527651e+00 -7.90694141e+00 -2.99184093e+01 -3.61863708e+01 -1.96624393e+01 -2.70367908e+00 -3.59787226e+00 -2.87307358e+00 -2.16472015e-01 1.33727944e+00 2.30213553e-01 -1.68612719e+00 -1.57667410e+00 -2.05089951e+00 2.18436074e+00 4.21006775e+00 2.54490137e+00 -1.70070446e+00 -4.42598295e+00 -3.34577942e+00 -2.80532694e+00 -8.55889618e-01 5.13147259e+00 7.44272804e+00 5.69695902e+00 2.02595353e+00 -1.16212368e+01 -3.03670921e+01 -5.24657974e+01 -5.34383965e+01 -3.68235283e+01 -2.35913048e+01 -7.46138859e+00 -5.30593443e+00 1.66965032e+00 2.01859927e+00 -3.95530701e+00 3.30078793e+00 1.47271433e+01 1.74890175e+01 6.49418640e+00 -4.34696627e+00 1.72009125e+01 3.64228706e+01 5.01193962e+01 4.21916695e+01 2.26438770e+01 6.69710016e+00 -2.24771023e+00 2.22575951e+00 6.10061121e+00 5.05117464e+00 2.72587347e+00 4.58454037e+00 9.61412239e+00 1.21771326e+01 8.72350216e+00 4.78120899e+00 2.08096457e+00 4.16476107e+00 5.83355379e+00 3.76387310e+00 1.38918447e+01 2.54788971e+01 2.80265522e+01 1.48937101e+01 5.44874620e+00 2.08606300e+01 3.54575539e+01 4.53326759e+01 4.61036110e+01 3.03568115e+01 1.86860142e+01 2.09079170e+00 2.44214487e+00 2.00574279e+00 2.24494576e+00 2.04510188e+00 -1.44412231e+00 -1.50017059e+00 -3.41711140e+00 -4.45637035e+00 -1.03949332e+00 -6.99762166e-01 7.73453534e-01 -4.29843330e+00 -9.02392673e+00 -8.24829674e+00 -1.09169283e+01 -5.90991497e+00 -5.65125799e+00 -2.28059840e+00 8.86100388e+00 2.04291039e+01 2.19850864e+01 1.23275204e+01 5.60815573e+00 1.18518715e+01 9.10016918e+00 8.46164989e+00 1.17068605e+01 1.45140591e+01 1.29106016e+01 6.76845264e+00 9.11418152e+00 1.44672194e+01 1.25588083e+01 1.29610157e+01 6.27532244e+00 7.61188745e+00 9.79190922e+00 1.53116875e+01 2.93156586e+01 3.92454338e+01 1.77349548e+01 -1.25868511e+01 -2.51857872e+01 -4.29686546e+00 1.35598059e+01 1.34644723e+00 -9.76930141e+00 -7.25728559e+00 1.04990988e+01 2.11889591e+01 1.66235142e+01 1.21570234e+01 9.64126778e+00 1.18474379e+01 1.90822411e+01 2.32865963e+01 2.30462914e+01 1.44923725e+01 8.78529644e+00 1.39573879e+01 2.29764709e+01 2.34794750e+01 1.77675190e+01 1.47019720e+01 2.30344563e+01 2.30005817e+01 1.72952900e+01 1.13944473e+01 5.50646162e+00 4.96530056e+00 1.23023045e+00 7.29274797e+00 2.16716232e+01 3.85643501e+01 4.11786079e+01 2.95913754e+01 1.31372843e+01 9.99324894e+00 1.06868229e+01 2.43703384e+01 3.92808571e+01 3.83600349e+01 2.65879478e+01 1.75311642e+01 2.63496304e+01 2.49619465e+01 2.70448837e+01 1.82177219e+01 2.12726936e+01 1.53925734e+01 1.61565514e+01 1.32044611e+01 1.64055252e+01 2.23178291e+01 2.52694893e+01 2.41028194e+01 2.17789001e+01 1.83405018e+01 1.34777880e+01 9.92157650e+00 5.33440733e+00 8.55684280e+00 1.29191141e+01 1.73212242e+01 1.39728279e+01 8.71088314e+00 6.86303329e+00 5.93766499e+00 8.99620628e+00 8.10805130e+00 6.89197636e+00 5.74987936e+00 8.64373684e+00 1.40103321e+01 1.39671268e+01 1.84726906e+01 3.00616703e+01 3.11730900e+01 2.77867260e+01 1.77184658e+01 1.62462482e+01 1.27345676e+01 1.14730577e+01 1.69964676e+01 2.96735840e+01 3.58725052e+01 3.23778152e+01 1.31866789e+01 -3.38064241e+00 -1.53453407e+01 -2.25570526e+01 -1.34907389e+01 -4.01878738e+00 2.16085835e+01 3.39146118e+01 3.41168022e+01 2.19574203e+01 2.07506752e+01 3.76214027e+01 3.56031036e+01 1.88197956e+01 -2.54009175e+00 8.25476408e-01 1.42848730e+01 2.64140301e+01 2.83497181e+01 1.57095394e+01 1.44418907e+01 1.68989811e+01 3.38082886e+01 4.87753143e+01 4.97559700e+01 3.90735016e+01 3.16178894e+01 4.30727310e+01 4.67556305e+01 4.03302383e+01 2.90562534e+01 3.57103729e+01 4.60349426e+01 4.86096191e+01 3.97741776e+01 2.77416134e+01 2.57581940e+01 2.05414925e+01 3.04330864e+01 3.65978928e+01 3.30179901e+01 2.32392826e+01 1.66098690e+01 1.23679705e+01 5.25579262e+00 3.34954548e+00 1.28235674e+01 2.07523270e+01 2.71286545e+01 3.41798210e+01 3.54054031e+01 4.21236649e+01 4.36531677e+01 4.17572250e+01 2.72300110e+01 2.10520573e+01 2.27915440e+01 2.55530739e+01 2.25139885e+01 1.84694366e+01 1.38540449e+01 1.04851208e+01 7.05387783e+00 2.04902973e+01 3.52614746e+01 3.18317623e+01 1.18416023e+01 9.16799927e+00 2.90352306e+01 3.83498688e+01 2.89061832e+01 1.37869225e+01 2.37224445e+01 3.80050583e+01 4.43336143e+01 3.60232239e+01 3.29310493e+01 3.90158844e+01 3.79907150e+01 2.52519455e+01 1.52152138e+01 1.61765003e+01 2.07732086e+01 2.75347328e+01 2.84716129e+01 3.46865807e+01 4.22844429e+01 4.41707344e+01 4.93450546e+01 5.03697548e+01 4.83550835e+01 3.70317955e+01 2.68753529e+01 2.73622246e+01 2.53518219e+01 2.45803719e+01 2.22434998e+01 3.01432972e+01 3.61543579e+01 4.01670837e+01 3.96418571e+01 4.04279938e+01 4.64090118e+01 4.19016724e+01 3.30825806e+01 2.31045151e+01 1.86505413e+01 1.35251741e+01 1.25734949e+01 1.53717432e+01 2.81552277e+01 3.96906853e+01 3.97417870e+01 3.95922203e+01 3.97854500e+01 4.12060356e+01 3.25945587e+01 2.51822643e+01 2.30713043e+01 2.74202118e+01 2.64119358e+01 3.25681572e+01 3.56010437e+01 3.77066612e+01 4.17311363e+01 4.41483002e+01 4.50843315e+01 3.82486801e+01 3.21041870e+01 2.99881744e+01 3.17955494e+01 3.49959717e+01 3.67376938e+01 4.32423401e+01 5.09865723e+01 5.40682526e+01 4.94410591e+01 3.77760468e+01 2.81777687e+01 2.02848473e+01 1.96928291e+01 2.08501472e+01 2.49039860e+01 2.35529194e+01 2.29612408e+01 2.04812851e+01 2.02352943e+01 1.98607082e+01 1.87115326e+01 1.96013603e+01 2.30881767e+01 3.08981075e+01 3.65740891e+01 3.49853821e+01 2.93764477e+01 3.09416866e+01 3.67260094e+01 3.47146225e+01 3.53533516e+01 3.77988014e+01 3.96054535e+01 3.32476959e+01 2.71016102e+01 3.32386398e+01 4.10500870e+01 4.17398338e+01 3.52800140e+01 3.56101189e+01 4.24349632e+01 4.51133766e+01 3.73049507e+01 3.44067612e+01 3.64594879e+01 3.43816109e+01 3.17862263e+01 2.84436378e+01 3.77548561e+01 4.35630341e+01 4.38027115e+01 3.88819695e+01 3.30690994e+01 3.26435738e+01 3.26896019e+01 3.82294922e+01 4.65731544e+01 4.50466995e+01 3.94144974e+01 3.13418827e+01 3.09320221e+01 2.94152050e+01 2.86425571e+01 2.91147671e+01 3.08495064e+01 3.23532982e+01 3.19904480e+01 3.34325638e+01 3.34471855e+01 3.41495514e+01 3.16880798e+01 3.02203331e+01 3.09791470e+01 3.60431290e+01 4.20100784e+01 4.09480362e+01 3.62220230e+01 3.43007431e+01 3.75819664e+01 3.59344139e+01 3.21775780e+01 2.78505650e+01 2.89550838e+01 2.91720161e+01 2.98888969e+01 3.04153843e+01 3.01905651e+01 2.93101311e+01 2.83295860e+01 3.25371819e+01 3.89540291e+01 4.19696350e+01 3.85756569e+01 3.79509163e+01 4.05176201e+01 4.04637337e+01 3.61506996e+01 3.34529114e+01 3.32890472e+01 3.32266350e+01 3.30971718e+01 3.40186768e+01 3.62687874e+01 3.54445457e+01 3.39153442e+01 3.53638725e+01 3.95515137e+01 4.13945389e+01 3.74941902e+01 3.53674126e+01 3.73487968e+01 3.78757629e+01 3.69341087e+01 3.31227036e+01 3.40097847e+01 3.53352318e+01 3.25505943e+01 2.90819397e+01 2.93515129e+01 3.43902168e+01 3.66900826e+01 3.45703888e+01 3.23185616e+01 3.17187862e+01 3.13907909e+01 3.36663895e+01 3.60465508e+01 3.74665108e+01 3.58887253e+01 3.44137650e+01 3.55403709e+01 3.75284424e+01 3.62559967e+01 3.43490601e+01 3.35083084e+01 3.95097771e+01 4.22256737e+01 5.04154396e+01 4.17393723e+01 1.20688889e+02 3.76490364e+01 -7.51835155e+00 1.31408249e+02 1.68303024e+02 -1.49896500e+02 -3.44644836e+02 -125723448. -403240896. 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. -499717472. -6.37376648e+02 -8.24172287e+01 5.41437798e+01 6.57274170e+01 1.11095451e+02 7.84886856e+01 2.81442795e+01 2.39132023e+01 2.29086323e+01 1.81481724e+01 1.37342129e+01 2.11934757e+01 -1.71415958e+01 -2.81880226e+01 8.67278748e+01 1.76018356e+02 1.30933960e+02 5.29399300e+01 4.26868286e+01 3.66449852e+01 2.72793026e+01 2.66591663e+01 2.67308407e+01 2.57410011e+01 2.53031750e+01 2.47398033e+01 2.41552696e+01 2.36801033e+01 2.36361370e+01 2.41161423e+01 2.48675289e+01 2.45513859e+01 2.40435905e+01 2.30698128e+01 2.36122665e+01 2.38348465e+01 2.41380806e+01 2.34714355e+01 2.38744717e+01 2.37935143e+01 2.47100964e+01 2.45793877e+01 2.45416298e+01 2.40543861e+01 2.38058414e+01 2.36763916e+01 2.32712727e+01 2.35856819e+01 2.35194778e+01 2.32930641e+01 2.30172157e+01 2.32814980e+01 2.32583752e+01 2.34533691e+01 2.35505657e+01 2.41520252e+01 2.39441376e+01 2.34702778e+01 2.25686073e+01 2.26012363e+01 2.28740215e+01 2.29283867e+01 2.24994354e+01 2.25224209e+01 2.26103592e+01 2.34032688e+01 2.32269173e+01 2.34781094e+01 2.28845882e+01 2.28545494e+01 2.32394218e+01 2.42079239e+01 2.50353603e+01 2.45917053e+01 2.44272957e+01 2.36979599e+01 2.26437283e+01 2.12369766e+01 2.13892708e+01 2.25586071e+01 2.29860687e+01 2.33779926e+01 2.30963326e+01 2.30349846e+01 2.31699982e+01 2.28426571e+01 2.22444057e+01 2.13120003e+01 2.17921486e+01 2.29321079e+01 2.37068462e+01 2.36289024e+01 2.22686806e+01 2.08179722e+01 1.95303688e+01 2.01257477e+01 2.04322052e+01 2.10361900e+01 2.15296898e+01 2.18356304e+01 2.24606342e+01 2.25302353e+01 2.29399014e+01 2.22392406e+01 2.12887592e+01 2.06824837e+01 2.19007721e+01 2.25005417e+01 2.20474110e+01 2.07541714e+01 1.97354546e+01 1.95774937e+01 1.86927662e+01 1.89833622e+01 2.02399559e+01 2.17397747e+01 2.21388836e+01 2.12840347e+01 2.00527439e+01 1.99721718e+01 1.94668427e+01 2.09446945e+01 2.20310249e+01 2.25457973e+01 2.18259544e+01 2.11156902e+01 2.17416592e+01 2.07114105e+01 1.92539577e+01 1.87869053e+01 2.00901928e+01 2.19260025e+01 2.21169720e+01 2.20587101e+01 2.13086586e+01 2.12837086e+01 2.15420341e+01 2.12160301e+01 2.03977718e+01 1.86663532e+01 1.98620358e+01 2.23192043e+01 2.41249695e+01 2.37239075e+01 2.12305565e+01 1.97813892e+01 1.84973850e+01 1.92428818e+01 2.04872532e+01 2.13724060e+01 2.17261543e+01 2.16582890e+01 2.07621498e+01 2.06860886e+01 2.07439384e+01 2.00883274e+01 1.96178875e+01 1.86095276e+01 1.94241352e+01 1.87605991e+01 1.84566345e+01 1.94056778e+01 2.10533619e+01 2.23725071e+01 2.28922672e+01 2.22710400e+01 2.18979988e+01 2.16658936e+01 2.01501255e+01 1.80938072e+01 1.60435257e+01 1.71817131e+01 1.82357559e+01 1.90878258e+01 1.75866337e+01 2.03792515e+01 2.08847141e+01 2.05821629e+01 1.62580776e+01 1.51252823e+01 1.75956135e+01 2.05036373e+01 2.29203720e+01 2.32903500e+01 2.16713562e+01 2.01458836e+01 1.96941223e+01 1.84277992e+01 1.83996563e+01 1.73878574e+01 1.90984268e+01 2.26249561e+01 2.36056118e+01 2.16192818e+01 1.71686974e+01 1.64724350e+01 1.74071407e+01 1.77493725e+01 1.86498566e+01 2.02692146e+01 2.19905853e+01 1.96915092e+01 1.70334110e+01 1.51254778e+01 1.70509624e+01 1.86645832e+01 1.87628841e+01 1.50911417e+01 1.53615131e+01 1.60292149e+01 1.92256489e+01 1.80515518e+01 1.74939270e+01 1.75918617e+01 1.63637104e+01 1.89309063e+01 1.76415157e+01 1.94798336e+01 1.45535364e+01 1.51187696e+01 1.56359291e+01 1.71256466e+01 1.63742294e+01 1.59820623e+01 1.48338137e+01 1.84821224e+01 1.53247061e+01 1.70191307e+01 1.24443541e+01 1.43580399e+01 1.59894304e+01 1.55967722e+01 1.51171074e+01 1.60892620e+01 1.65847473e+01 1.81198101e+01 1.58078566e+01 1.40969677e+01 1.14628630e+01 1.12026348e+01 1.62204151e+01 1.75465813e+01 1.76481400e+01 1.35858660e+01 1.48785744e+01 1.51064453e+01 1.66464729e+01 1.43878098e+01 1.33030853e+01 1.26018982e+01 1.41141329e+01 1.61612759e+01 1.54857998e+01 1.44516850e+01 1.34899988e+01 1.27377167e+01 1.36491718e+01 1.29858999e+01 1.50921631e+01 1.52951393e+01 1.66133766e+01 1.57758436e+01 1.59524326e+01 1.54380560e+01 1.69028511e+01 1.53534784e+01 1.49943886e+01 1.24865055e+01 1.30996990e+01 1.35332861e+01 1.41193590e+01 1.43074989e+01 1.49608393e+01 1.40913048e+01 1.52560253e+01 1.33562603e+01 1.31473274e+01 9.97867775e+00 1.05654125e+01 1.12435398e+01 1.15400333e+01 1.06185017e+01 1.13682127e+01 1.02705374e+01 9.88510418e+00 8.05066872e+00 1.04069967e+01 1.05197554e+01 1.04571571e+01 1.03050337e+01 1.16256981e+01 1.24700527e+01 1.03386812e+01 9.27010345e+00 1.04095325e+01 1.17544012e+01 1.22419777e+01 1.14502916e+01 1.06328115e+01 8.41584492e+00 8.46827316e+00 8.05782890e+00 9.39961624e+00 9.35103989e+00 6.92003250e+00 7.61237144e+00 7.83934402e+00 1.26230707e+01 1.28869085e+01 9.07631493e+00 1.02447510e+01 1.02606297e+01 1.12782555e+01 7.67261362e+00 6.15648127e+00 8.68913746e+00 9.35303497e+00 8.72433853e+00 6.08239651e+00 6.28390884e+00 7.98599529e+00 1.02806463e+01 7.67589140e+00 6.10890627e+00 5.94977140e+00 7.30344057e+00 7.60810709e+00 8.90703392e+00 1.07087221e+01 1.02961607e+01 8.64359665e+00 7.81695509e+00 7.99757957e+00 8.32477951e+00 7.61430740e+00 8.77570343e+00 8.58493519e+00 9.69051552e+00 9.31268406e+00 6.22765064e+00 4.59952068e+00 3.17346215e+00 5.73275995e+00 5.57939434e+00 7.16812992e+00 5.91256857e+00 4.60994911e+00 6.23310375e+00 8.09007359e+00 7.99602365e+00 6.06086159e+00 3.96904588e+00 3.27331567e+00 3.78593946e+00 3.87269378e+00 5.81118107e+00 5.18403769e+00 5.86117744e+00 4.88573217e+00 3.83868027e+00 5.45921326e+00 9.08473110e+00 1.04341869e+01 1.09119654e+01 8.01113415e+00 5.67252970e+00 4.99541998e+00 4.72489357e+00 7.43022633e+00 6.14824438e+00 7.50837803e+00 6.43707657e+00 6.95898008e+00 8.88531590e+00 9.37711906e+00 8.82449722e+00 6.65030003e+00 5.14658689e+00 4.79116344e+00 5.00117636e+00 4.87536860e+00 2.25563288e+00 1.35773396e+00 -1.77862144e+00 3.26298475e+00 5.65350151e+00 1.22058144e+01 1.11891460e+01 7.97513247e+00 6.07609177e+00 4.23127317e+00 6.40202522e+00 2.85767055e+00 2.74062848e+00 3.64087224e+00 6.47508383e+00 6.58213758e+00 2.19254589e+00 1.14474785e+00 1.82919651e-01 1.69181824e+00 -7.06303358e-01 2.21623302e+00 2.37467027e+00 3.97922230e+00 1.43177247e+00 2.38743591e+00 3.91505361e+00 4.21103811e+00 3.71216035e+00 3.03107858e+00 4.38419819e+00 5.58444881e+00 7.37751436e+00 8.62969685e+00 8.26990509e+00 7.80653811e+00 6.52073812e+00 6.55480671e+00 3.78974199e+00 -1.61728406e+00 -2.88517928e+00 -2.05642104e+00 3.47513390e+00 2.48216176e+00 1.44144511e+00 -6.41302764e-01 -1.84643686e+00 5.94727218e-01 2.76039362e-01 3.39593911e+00 -1.37899470e+00 1.30822286e-01 -1.23232174e+00 -1.31776440e+00 -3.52939272e+00 -3.52054787e+00 1.11710906e-01 1.71087503e+00 1.33298182e+00 -2.01916359e-02 -1.54544115e+00 1.05891302e-01 3.49409962e+00 5.50064659e+00 1.45074868e+00 -3.01715899e+00 -5.46817684e+00 -2.56348491e+00 1.07836115e+00 1.99221325e+00 -1.66158450e+00 -2.95690227e+00 6.27154857e-02 4.21754265e+00 1.94634783e+00 3.08049709e-01 -6.18621469e-01 1.94848776e+00 -2.12113166e+00 -3.30199391e-01 -3.00519061e+00 -3.49479365e+00 -3.78380370e+00 -4.48826647e+00 -2.54336643e+00 -4.85639381e+00 -2.14394116e+00 -1.61064327e-01 4.37228948e-01 -3.22317076e+00 -4.56453466e+00 -6.56443596e+00 -7.41205692e-01 4.52579796e-01 1.77306974e+00 -3.71189356e+00 -5.44496679e+00 -5.80584288e+00 -4.46106958e+00 -4.84454727e+00 -4.98080015e+00 -4.14074612e+00 -4.96830177e+00 -6.82225275e+00 -6.19521952e+00 -6.66088676e+00 -5.47958517e+00 -4.07294703e+00 -3.92384839e+00 -6.04949141e+00 -1.20279512e+01 -8.66901493e+00 -4.64289618e+00 -6.30786479e-01 -1.50805092e+00 -4.41961813e+00 -5.88667393e+00 -6.35733891e+00 -4.39632559e+00 -3.62168717e+00 -3.93698287e+00 -5.40582657e+00 -3.10692143e+00 -4.62280512e+00 -1.48894489e+00 -3.55349398e+00 -4.05077648e+00 -4.07961845e+00 -6.09063482e+00 -5.01853561e+00 -6.86841488e+00 -4.13253069e+00 -3.20618606e+00 -5.52479792e+00 -8.38794041e+00 -1.08230972e+01 -8.77685928e+00 -6.83023596e+00 -5.80095816e+00 -6.60872269e+00 -8.20636749e+00 -1.00236158e+01 -8.83748722e+00 -7.45147371e+00 -5.71222973e+00 -6.88032627e+00 -8.32670212e+00 -8.74475288e+00 -8.19358826e+00 -6.23693562e+00 -2.12539458e+00 -2.67579460e+00 -3.21444082e+00 -7.53262234e+00 -9.34095860e+00 -1.09415426e+01 -1.04949942e+01 -9.43636227e+00 -9.49140072e+00 -7.57315826e+00 -7.08886242e+00 -7.22819519e+00 -7.03489923e+00 -7.53088856e+00 -7.92515516e+00 -1.04003391e+01 -1.17197027e+01 -1.21621361e+01 -1.15208874e+01 -1.10969391e+01 -1.16698637e+01 -1.19128971e+01 -1.38240013e+01 -1.31447420e+01 -1.29835215e+01 -9.51056480e+00 -8.30225277e+00 -7.63265657e+00 -9.14076328e+00 -1.05449381e+01 -1.22495966e+01 -8.53971863e+00 -1.08844452e+01 -1.15742264e+01 -1.81774540e+01 -1.51392088e+01 -1.32392960e+01 -8.10092449e+00 -7.20076990e+00 -7.94195938e+00 -9.89430904e+00 -1.19443130e+01 -1.32367420e+01 -1.26728687e+01 -1.23471193e+01 -1.21695337e+01 -1.39414730e+01 -1.36358519e+01 -1.18526783e+01 -1.00790110e+01 -8.51282215e+00 -1.11725826e+01 -9.33137608e+00 -1.19980431e+01 -1.22105427e+01 -1.19354458e+01 -1.12529583e+01 -8.74976540e+00 -1.25058842e+01 -1.23482256e+01 -1.37737875e+01 -1.34188490e+01 -1.23720112e+01 -1.03371210e+01 -9.49396610e+00 -1.04993925e+01 -1.26293430e+01 -1.24296589e+01 -1.32888975e+01 -1.18335629e+01 -1.43440037e+01 -1.71999245e+01 -1.89200935e+01 -2.08729687e+01 -1.84606705e+01 -1.73821640e+01 -1.37839632e+01 -1.24450884e+01 -1.35748444e+01 -1.90635834e+01 -2.15185966e+01 -2.52836876e+01 -2.58257046e+01 -4.39296188e+01 -5.45811501e+01 -1.03048080e+02 -7.10837402e+01 7.80495605e+01 3.35772369e+02 1.66695044e+03 -1.33444838e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -260495952. -50067192. -7.09379688e+03 -3.33353125e+03 -6.07727722e+02 4.44541229e+02 1.19508659e+02 -9.96046219e+01 -1.00453117e+02 -7.54847946e+01 -1.91930008e+02 -1.18181129e+02 -2.74450130e+01 3.32303543e+01 6.13645172e+01 4.85440941e+01 6.71273651e+01 5.80984497e+01 4.46619606e+01 1.49540272e+01 8.71984005e+00 2.63901681e-01 -2.78332090e+00 -8.17605209e+00 -1.29665194e+01 -1.59315205e+01 -1.62759361e+01 -1.83704872e+01 -1.77899494e+01 -1.74432487e+01 -1.57720566e+01 -1.59766607e+01 -1.72945156e+01 -1.83702660e+01 -1.92172890e+01 -2.05463161e+01 -2.10882797e+01 -2.02256775e+01 -1.84187374e+01 -1.80906639e+01 -1.94508896e+01 -1.94673748e+01 -2.01913757e+01 -2.03720112e+01 -2.05989513e+01 -1.87028084e+01 -1.95445156e+01 -2.08033962e+01 -2.15378742e+01 -1.89941101e+01 -1.87241611e+01 -1.83101501e+01 -1.92593060e+01 -1.91278267e+01 -1.99750195e+01 -2.07782478e+01 -2.02345486e+01 -2.01746674e+01 -1.97097836e+01 -1.97710037e+01 -1.99408245e+01 -1.93154469e+01 -1.83323860e+01 -1.87053814e+01 -2.04727097e+01 -2.24206276e+01 -2.14803944e+01 -2.02234364e+01 -1.99060440e+01 -1.94294453e+01 -1.89132595e+01 -1.73563900e+01 -1.77527790e+01 -1.84136944e+01 -1.91014385e+01 -1.90148830e+01 -1.94823055e+01 -2.08082390e+01 -2.08414249e+01 -1.96958313e+01 -1.95974903e+01 -2.07001877e+01 -2.12915440e+01 -2.10333366e+01 -2.10481701e+01 -2.27223835e+01 -2.28098869e+01 -2.30098076e+01 -2.15670605e+01 -2.11042423e+01 -2.00577450e+01 -2.00295448e+01 -1.92579803e+01 -2.01516895e+01 -1.93563061e+01 -2.06634026e+01 -2.00410042e+01 -2.07322216e+01 -2.03078117e+01 -1.99883099e+01 -2.08302307e+01 -2.14858093e+01 -2.33398933e+01 -2.37704830e+01 -2.29371643e+01 -2.18242435e+01 -2.03087902e+01 -2.03122120e+01 -2.05281544e+01 -2.11000996e+01 -2.18323917e+01 -2.18982105e+01 -2.12072182e+01 -2.16038494e+01 -2.13247662e+01 -2.19687920e+01 -2.10592690e+01 -2.08404789e+01 -2.15069599e+01 -2.23146057e+01 -2.23033600e+01 -2.27213440e+01 -2.30139217e+01 -2.43527088e+01 -2.38107071e+01 -2.30834522e+01 -2.34576740e+01 -2.35267639e+01 -2.30342445e+01 -2.20174885e+01 -2.20062981e+01 -2.23347473e+01 -2.21484203e+01 -2.22703552e+01 -2.31722126e+01 -2.41102619e+01 -2.39958973e+01 -2.35212173e+01 -2.28868675e+01 -2.30535603e+01 -2.29155617e+01 -2.26406841e+01 -2.19560471e+01 -2.21140099e+01 -2.12283363e+01 -2.16200542e+01 -2.13695469e+01 -2.20951653e+01 -2.20886707e+01 -2.17717743e+01 -2.22975616e+01 -2.25407734e+01 -2.33657570e+01 -2.32216167e+01 -2.33954258e+01 -2.23663425e+01 -2.26869164e+01 -2.25117283e+01 -2.32248993e+01 -2.28988800e+01 -2.31181431e+01 -2.23966103e+01 -2.26277695e+01 -2.26286945e+01 -2.29490128e+01 -2.27022038e+01 -2.33401165e+01 -2.38629742e+01 -2.39250717e+01 -2.32572155e+01 -2.25955639e+01 -2.26374950e+01 -2.27149487e+01 -2.30907040e+01 -2.30094223e+01 -2.34503574e+01 -2.32793274e+01 -2.35946655e+01 -2.36528130e+01 -2.39913559e+01 -2.37525330e+01 -2.32600822e+01 -2.32906303e+01 -2.35521278e+01 -2.34138241e+01 -2.31129780e+01 -2.29860516e+01 -2.34508591e+01 -2.35305882e+01 -2.30931759e+01 -2.32059917e+01 -2.33713493e+01 -2.38759251e+01 -2.37352982e+01 -2.35509472e+01 -2.35120506e+01 -2.35243778e+01 -2.38816357e+01 -2.37650471e+01 -2.36234493e+01 -2.34577560e+01 -2.36717415e+01 -2.37425690e+01 -2.36971893e+01 -2.35620022e+01 -2.37646294e+01 -2.37294216e+01 -2.38349552e+01 -2.37650299e+01 -2.38505802e+01 -2.39203320e+01 -2.38952656e+01 -2.39915142e+01 -2.39319134e+01 -2.38884773e+01 -2.37999249e+01 -2.38647099e+01 -2.39408379e+01 -2.39641323e+01 -2.39358253e+01 -2.39398613e+01 -2.39454021e+01 -2.39365063e+01 -2.39258976e+01 -2.39195747e+01 -2.39063931e+01 -2.39244289e+01 -2.39276352e+01 -2.39110413e+01 -2.39050026e+01 -2.38897915e+01 -2.39765511e+01 -2.39800987e+01 -2.38658962e+01 -2.38277016e+01 -2.38071728e+01 -2.39338779e+01 -2.39008751e+01 -2.39935207e+01 -2.39539776e+01 -2.38495293e+01 -2.37327442e+01 -2.37696648e+01 -2.37577019e+01 -2.38666477e+01 -2.39495792e+01 -2.39485855e+01 -2.41111984e+01 -2.40872383e+01 -2.43937302e+01 -2.41512661e+01 -2.39659767e+01 -2.36584301e+01 -2.36746044e+01 -2.36248169e+01 -2.37523918e+01 -2.36916351e+01 -2.37082863e+01 -2.36584988e+01 -2.34136620e+01 -2.32525768e+01 -2.30320683e+01 -2.31196632e+01 -2.29732857e+01 -2.30132275e+01 -2.31692200e+01 -2.33308392e+01 -2.35748768e+01 -2.37692089e+01 -2.39296703e+01 -2.38554821e+01 -2.36758900e+01 -2.35510902e+01 -2.35082645e+01 -2.34934349e+01 -2.38982315e+01 -2.37396755e+01 -2.37219276e+01 -2.32917480e+01 -2.35195332e+01 -2.35089359e+01 -2.38859940e+01 -2.36345787e+01 -2.37329884e+01 -2.26477985e+01 -2.32123756e+01 -2.30269547e+01 -2.39104519e+01 -2.35415764e+01 -2.33853054e+01 -2.32291985e+01 -2.27836304e+01 -2.29944859e+01 -2.31373692e+01 -2.39683895e+01 -2.42762470e+01 -2.38567276e+01 -2.34748116e+01 -2.37573376e+01 -2.38184872e+01 -2.39597797e+01 -2.31210938e+01 -2.37269497e+01 -2.27846661e+01 -2.31211739e+01 -2.29951916e+01 -2.34715519e+01 -2.29237881e+01 -2.27369900e+01 -2.27301044e+01 -2.32834702e+01 -2.32530060e+01 -2.31385231e+01 -2.30544605e+01 -2.30556812e+01 -2.30568447e+01 -2.27871666e+01 -2.26405487e+01 -2.29661846e+01 -2.26797829e+01 -2.21998787e+01 -2.19656658e+01 -2.22914639e+01 -2.28241787e+01 -2.25666943e+01 -2.27295761e+01 -2.19893856e+01 -2.19470978e+01 -2.11147881e+01 -2.20296249e+01 -2.17681999e+01 -2.25408459e+01 -2.22375259e+01 -2.25120792e+01 -2.24179878e+01 -2.20648460e+01 -2.15517788e+01 -2.16259842e+01 -2.15895462e+01 -2.17966309e+01 -2.14387455e+01 -2.16793194e+01 -2.22548428e+01 -2.27792950e+01 -2.30008144e+01 -2.31613522e+01 -2.28184204e+01 -2.27333069e+01 -2.27981377e+01 -2.28430386e+01 -2.20335217e+01 -2.04822750e+01 -1.93354168e+01 -2.02563305e+01 -1.99638844e+01 -2.13613415e+01 -2.09249611e+01 -2.20263958e+01 -2.24506168e+01 -2.13169861e+01 -2.19160328e+01 -2.17526360e+01 -2.18488770e+01 -1.99556732e+01 -1.95142231e+01 -1.98236675e+01 -2.05084381e+01 -2.07254086e+01 -2.03428097e+01 -1.98890266e+01 -1.91781349e+01 -2.05391655e+01 -1.98788662e+01 -1.99132977e+01 -1.82799644e+01 -2.02710762e+01 -2.08927021e+01 -2.21460876e+01 -2.18164101e+01 -2.04373074e+01 -2.01453724e+01 -1.98164139e+01 -2.05626812e+01 -2.01668644e+01 -1.92080956e+01 -1.89816170e+01 -1.99934845e+01 -2.12365818e+01 -2.05864296e+01 -2.07135239e+01 -1.96257877e+01 -2.05773945e+01 -1.97433910e+01 -1.94953575e+01 -1.85278549e+01 -1.89038239e+01 -1.99191456e+01 -2.05127220e+01 -1.81932163e+01 -1.75348969e+01 -1.85725021e+01 -2.06592445e+01 -2.16849823e+01 -2.20311584e+01 -2.18877277e+01 -2.01855259e+01 -1.90678844e+01 -1.73694763e+01 -1.78439217e+01 -1.70900269e+01 -1.74046574e+01 -1.70882416e+01 -1.69408360e+01 -1.84133282e+01 -2.01485386e+01 -2.08530369e+01 -2.00665359e+01 -2.00593929e+01 -1.97736816e+01 -1.93702698e+01 -1.82715855e+01 -1.76784458e+01 -1.78696556e+01 -1.69723358e+01 -1.72776241e+01 -1.68449783e+01 -1.72128525e+01 -1.69214535e+01 -1.63783436e+01 -1.63613892e+01 -1.69437160e+01 -1.71385155e+01 -1.74777412e+01 -1.73374786e+01 -1.79246998e+01 -1.72980194e+01 -1.76748543e+01 -1.88363762e+01 -1.84439926e+01 -1.84750843e+01 -1.73724117e+01 -1.80128212e+01 -1.69762554e+01 -1.69160366e+01 -1.61381416e+01 -1.52712746e+01 -1.48432045e+01 -1.21589470e+01 -1.32761993e+01 -1.16205177e+01 -1.64864025e+01 -1.99129944e+01 -1.99359398e+01 -1.58299618e+01 -1.02666817e+01 2.99897614e+01 6.54227600e+01 6.69443970e+01 1.28239404e+03 2.69988599e+03 -200268336. -294410496. 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. 0. 0. 0. 0. 0. 0. 0. 0. -72111200. 101329312. -26924798. -36491876. 6.44787158e+03 2.87962354e+03 2.90795349e+02 2.19291134e+01 -3.09376373e+01 -1.95212135e+01 1.19909258e+01 2.11187840e+01 3.00443029e+00 -1.36981382e+01 -5.91383314e+00 -4.78177643e+00 -4.81495571e+00 -1.10154602e+03 -7.85656311e+02 -1.54127502e+02 -4.76084976e+01 -3.64005966e+01 -2.77634583e+01 -2.44319897e+01 -1.72509155e+01 -1.19544830e+01 -1.20111046e+01 -1.11854019e+01 -1.18816128e+01 -9.91406345e+00 -8.91867924e+00 -8.76017761e+00 -9.44051170e+00 -1.19586353e+01 -1.23734055e+01 -1.29784031e+01 -1.26525660e+01 -1.49364023e+01 -1.44444361e+01 -1.46528912e+01 -1.24008627e+01 -1.27047663e+01 -1.22330418e+01 -1.12010860e+01 -1.02746525e+01 -9.79393101e+00 -9.66800785e+00 -8.85601330e+00 -8.97264194e+00 -8.57339478e+00 -9.92573643e+00 -1.00918493e+01 -1.00213327e+01 -1.19961433e+01 -1.17369318e+01 -1.31577902e+01 -1.20248251e+01 -1.15556145e+01 -1.04857845e+01 -9.92965031e+00 -1.04408407e+01 -9.08167267e+00 -6.70132399e+00 -6.69576883e+00 -9.05067444e+00 -1.09854231e+01 -8.73892975e+00 -7.76935768e+00 -7.25536776e+00 -7.26051998e+00 -8.90405369e+00 -8.71580219e+00 -9.02802277e+00 -8.75624657e+00 -1.02361155e+01 -1.28155842e+01 -1.19363756e+01 -1.17663908e+01 -9.60059071e+00 -9.74482441e+00 -8.71432972e+00 -9.92893600e+00 -7.72455549e+00 -7.02721596e+00 -3.41004086e+00 -5.11839342e+00 -3.86751390e+00 -6.23164749e+00 -5.10679960e+00 -7.93880987e+00 -6.87040138e+00 -5.89978933e+00 -2.10497665e+00 -3.66189981e+00 -4.55900335e+00 -6.52945232e+00 -6.09379482e+00 -6.26454639e+00 -6.88238525e+00 -5.16409588e+00 -7.34641790e+00 -8.29047775e+00 -9.73036480e+00 -8.65509415e+00 -5.48577452e+00 -5.55374384e+00 -3.85313249e+00 -3.97669125e+00 -4.56837988e+00 -4.09141588e+00 -5.12317181e+00 -5.63731766e+00 -7.68262434e+00 -8.65861130e+00 -7.78253222e+00 -6.96626997e+00 -6.80108213e+00 -7.94760132e+00 -7.08099985e+00 -6.13459826e+00 -5.91344595e+00 -6.37716627e+00 -7.91587973e+00 -6.89728260e+00 -8.15948582e+00 -5.36937523e+00 -4.06272697e+00 -2.75394154e+00 -3.23629785e+00 -4.42712784e+00 -2.50389981e+00 -9.21654403e-01 4.68328483e-02 1.09132670e-01 1.14082289e+00 1.97168899e+00 3.71663272e-01 -1.00849032e+00 -2.46370053e+00 -2.67495823e+00 -3.51099753e+00 -3.25691223e+00 -2.24834871e+00 -2.69169760e+00 -2.26974392e+00 -3.87297773e+00 -3.58704376e+00 -3.52187562e+00 -1.38765562e+00 -1.42649782e+00 -9.43301916e-01 3.21921408e-01 1.39126706e+00 1.83155990e+00 -1.43836010e+00 -2.62868118e+00 -3.11193967e+00 7.88192078e-03 1.53304517e+00 1.19032824e+00 -7.22769380e-01 -9.92179155e-01 -7.20026672e-01 -5.23873940e-02 -9.91770566e-01 -1.51580954e+00 -2.34551287e+00 -2.39520860e+00 -2.30409193e+00 -1.41243887e+00 -3.22939038e-01 -6.01733804e-01 8.29492927e-01 1.32599354e+00 2.44686294e+00 -5.43802202e-01 -1.60237491e+00 -1.95968592e+00 4.18934643e-01 8.63605022e-01 9.62572575e-01 -4.04073268e-01 -1.17094982e+00 -2.33012724e+00 -9.47319806e-01 8.75793099e-01 2.12931824e+00 3.06549764e+00 2.05419970e+00 2.43210006e+00 5.98651469e-01 7.30092645e-01 1.51839018e-01 1.94710457e+00 2.01595998e+00 7.68338859e-01 -8.32188487e-01 -1.98433474e-01 1.64996290e+00 3.49009490e+00 1.71652842e+00 6.58221006e-01 -8.21678102e-01 9.37307298e-01 2.24026227e+00 2.30432940e+00 2.44855785e+00 2.92132902e+00 3.31040049e+00 3.05259800e+00 3.27542448e+00 2.16826582e+00 2.85390043e+00 2.48370123e+00 2.88637042e+00 2.60022116e+00 2.45735002e+00 2.34271002e+00 1.78652966e+00 2.02846408e+00 2.17907381e+00 2.78534102e+00 3.34301877e+00 3.32208610e+00 2.89133263e+00 1.29551911e+00 1.23335445e+00 1.75752330e+00 2.39371490e+00 3.69682002e+00 2.99711347e+00 2.86036587e+00 3.43615556e+00 2.39773631e+00 3.21417093e+00 2.52535701e+00 2.59154510e+00 3.52524185e+00 4.94410992e+00 5.66378927e+00 5.55456066e+00 5.51875544e+00 6.05277538e+00 6.05665779e+00 3.84995699e+00 5.94641447e+00 7.38422871e+00 1.10163507e+01 1.04958925e+01 9.23847866e+00 7.31528044e+00 7.53862953e+00 8.24450016e+00 9.39856815e+00 8.15889549e+00 7.02995443e+00 5.75656176e+00 5.47621250e+00 6.22828674e+00 7.43116570e+00 5.10321093e+00 4.57677746e+00 4.39732981e+00 7.48719025e+00 5.67072010e+00 7.13482046e+00 6.21096420e+00 5.50061750e+00 4.26998949e+00 5.87222672e+00 9.85238361e+00 8.31866074e+00 7.65831041e+00 7.36102009e+00 1.07337675e+01 1.17580738e+01 1.04715948e+01 8.75019360e+00 1.15142374e+01 1.36358976e+01 1.33251457e+01 1.02015619e+01 7.16030455e+00 6.99318743e+00 7.87763643e+00 8.95944023e+00 1.06576853e+01 9.42060852e+00 1.00382051e+01 9.70184517e+00 9.82996845e+00 1.16429710e+01 1.11509018e+01 1.04240189e+01 9.56865692e+00 1.12593155e+01 1.31021385e+01 1.27410536e+01 1.20090380e+01 1.16709986e+01 1.27445507e+01 1.16603136e+01 1.13646841e+01 1.14870539e+01 1.27475405e+01 1.34077549e+01 1.11032696e+01 9.93710518e+00 1.09022169e+01 1.27516260e+01 1.12872801e+01 1.02926826e+01 1.10761719e+01 1.31772022e+01 1.32693043e+01 1.33898201e+01 1.43138161e+01 1.55767231e+01 1.38973398e+01 1.11723299e+01 7.35870075e+00 9.27886868e+00 1.02363873e+01 1.19265375e+01 1.05770702e+01 1.29054146e+01 1.39080811e+01 1.56576061e+01 1.42087460e+01 1.54880171e+01 1.53439198e+01 1.45002823e+01 1.32432032e+01 1.04618425e+01 1.05298834e+01 1.10261250e+01 1.26138687e+01 1.30277824e+01 1.28976517e+01 1.19954529e+01 1.04671917e+01 1.13013620e+01 1.21404362e+01 1.42610044e+01 1.35307722e+01 1.35342150e+01 1.32849827e+01 1.47064800e+01 1.70518665e+01 1.70450115e+01 1.61498623e+01 1.36150017e+01 1.42392778e+01 1.49958372e+01 1.58228674e+01 1.75706940e+01 1.60147781e+01 1.47378550e+01 1.17775059e+01 1.19310408e+01 1.29785757e+01 1.37645073e+01 1.53594561e+01 1.45094948e+01 1.48022776e+01 1.56007557e+01 1.72489109e+01 1.54550009e+01 1.46366568e+01 1.44071016e+01 1.63259430e+01 1.72359886e+01 1.58297987e+01 1.54864998e+01 1.43743582e+01 1.58096418e+01 1.62931786e+01 1.59349594e+01 1.62750301e+01 1.60757713e+01 1.61125355e+01 1.69244289e+01 1.63246117e+01 1.54471989e+01 1.49288673e+01 1.55247250e+01 1.65756912e+01 1.60452290e+01 1.65374870e+01 1.71026306e+01 1.59676352e+01 1.56475134e+01 1.56523685e+01 1.65629025e+01 1.63700886e+01 1.52088757e+01 1.59874744e+01 1.62338696e+01 1.70848904e+01 1.84627266e+01 2.09194832e+01 2.09409275e+01 1.98588638e+01 1.78892078e+01 2.02786293e+01 2.20889988e+01 1.97069378e+01 1.62722797e+01 1.44890938e+01 1.71672916e+01 1.78885403e+01 1.77917061e+01 1.75743351e+01 1.80442238e+01 1.63963509e+01 1.65150070e+01 1.70306244e+01 1.70836239e+01 1.67519665e+01 1.67596684e+01 1.82104359e+01 1.87911186e+01 1.88723106e+01 1.80515156e+01 1.80179806e+01 1.78900795e+01 1.87403831e+01 1.87148170e+01 1.95595570e+01 1.95543461e+01 1.86218281e+01 1.78260441e+01 1.74795933e+01 1.83448868e+01 1.79752483e+01 1.81063576e+01 1.88721428e+01 1.95363483e+01 2.11526928e+01 2.13161564e+01 2.20688877e+01 2.20774002e+01 2.17623672e+01 2.05219517e+01 1.87759304e+01 1.79736652e+01 1.94079533e+01 1.96063461e+01 2.04693680e+01 1.93053150e+01 1.97301636e+01 1.97113762e+01 2.05034523e+01 2.15193157e+01 2.12792683e+01 1.99485455e+01 1.93359680e+01 1.92296410e+01 2.07196465e+01 2.02358379e+01 1.99400330e+01 1.98999004e+01 2.09935074e+01 2.22055645e+01 2.22716122e+01 2.11761990e+01 2.16187496e+01 2.14590397e+01 2.11513958e+01 2.05752773e+01 2.13431911e+01 2.25793362e+01 2.33308773e+01 2.33634510e+01 2.20385704e+01 2.16076794e+01 2.12272587e+01 2.27031212e+01 2.22572079e+01 2.19688377e+01 2.17709789e+01 2.20260773e+01 2.25295868e+01 2.26803131e+01 2.28572025e+01 2.15551109e+01 2.19368305e+01 2.26015320e+01 2.37907047e+01 2.26133003e+01 2.16356926e+01 2.14834118e+01 2.10599728e+01 2.04634819e+01 2.08070469e+01 2.14767818e+01 2.15070591e+01 2.07104912e+01 2.04153500e+01 2.12475262e+01 2.13984890e+01 2.14099979e+01 2.12836304e+01 2.11247540e+01 2.09122162e+01 2.11369953e+01 2.16137161e+01 2.23571320e+01 2.23989601e+01 2.21606483e+01 2.13945065e+01 2.07187729e+01 2.07175503e+01 2.15586777e+01 2.25745201e+01 2.30638962e+01 2.24590549e+01 2.23582153e+01 2.18219185e+01 2.23553753e+01 2.30740509e+01 2.38523197e+01 2.40977821e+01 2.31285973e+01 2.29741440e+01 2.32041931e+01 2.40027523e+01 2.35839672e+01 2.32736301e+01 2.30588932e+01 2.36549149e+01 2.33313560e+01 2.27321663e+01 2.21869183e+01 2.22412376e+01 2.24668961e+01 2.27519112e+01 2.25975666e+01 2.29285069e+01 2.31327229e+01 2.34760132e+01 2.37156944e+01 2.40957623e+01 2.39719906e+01 2.38802032e+01 2.39680099e+01 2.36698112e+01 2.34429779e+01 2.29746151e+01 2.35159531e+01 2.36056881e+01 2.32615051e+01 2.28280792e+01 2.27366886e+01 2.33470936e+01 2.33275986e+01 2.34792690e+01 2.32882385e+01 2.33463421e+01 2.32962341e+01 2.34464397e+01 2.38609600e+01 2.38469048e+01 2.37052402e+01 2.33257313e+01 2.37684612e+01 2.38842564e+01 2.41546574e+01 2.33511276e+01 2.32619171e+01 2.33889008e+01 2.37469177e+01 2.39080696e+01 2.37502995e+01 2.36336632e+01 2.34607658e+01 2.37630463e+01 2.40985394e+01 2.42765388e+01 2.42050629e+01 2.38693180e+01 2.40178032e+01 2.37127476e+01 2.37376862e+01 2.35667400e+01 2.34631100e+01 2.37612896e+01 2.37341290e+01 2.39127712e+01 2.36568241e+01 2.37813377e+01 2.37997627e+01 2.36713486e+01 2.36398296e+01 2.37520027e+01 2.41613655e+01 2.44301739e+01 2.44491882e+01 2.42534046e+01 2.38856640e+01 2.37955551e+01 2.41078434e+01 2.44478760e+01 2.52663403e+01 2.64715099e+01 2.82768974e+01 3.24984093e+01 3.25694199e+01 1.35569046e+02 6.51642761e+02 -85511624. 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. 114288424. 4.86762024e+02 1.00006088e+02 3.23734093e+01 2.22219067e+01 1.65808792e+01 1.38985033e+01 1.35976152e+01 1.36015768e+01 1.38793488e+01 1.41267815e+01 1.41719465e+01 1.40957832e+01 1.39456177e+01 1.36980791e+01 1.37740259e+01 1.37066126e+01 1.39440947e+01 1.38863058e+01 1.39497910e+01 1.38263607e+01 1.36812639e+01 1.34481764e+01 1.31658468e+01 1.29537630e+01 1.30958309e+01 1.31872501e+01 1.33481293e+01 1.37644920e+01 1.40376434e+01 1.36621056e+01 1.29969711e+01 1.24913225e+01 1.26843014e+01 1.32380199e+01 1.38990812e+01 1.42532434e+01 1.40330286e+01 1.38488741e+01 1.35878239e+01 1.33487072e+01 1.31042595e+01 1.29158154e+01 1.32576532e+01 1.34769983e+01 1.37582493e+01 1.34548807e+01 1.33937721e+01 1.33043299e+01 1.30424376e+01 1.32408438e+01 1.29220695e+01 1.33467035e+01 1.37133808e+01 1.40546827e+01 1.39556246e+01 1.30699730e+01 1.26622086e+01 1.23278751e+01 1.28744755e+01 1.37362413e+01 1.37904463e+01 1.33183374e+01 1.29693594e+01 1.33154068e+01 1.31937485e+01 1.25707560e+01 1.22000542e+01 1.23300838e+01 1.31824923e+01 1.36022234e+01 1.31230965e+01 1.27618895e+01 1.27462711e+01 1.28476973e+01 1.27299652e+01 1.26531382e+01 1.32080374e+01 1.36107874e+01 1.39388742e+01 1.40600863e+01 1.35764151e+01 1.26111279e+01 1.17099972e+01 1.19195080e+01 1.28844357e+01 1.33905888e+01 1.29162455e+01 1.32956495e+01 1.39542360e+01 1.43795977e+01 1.36087685e+01 1.26733427e+01 1.27890978e+01 1.38668785e+01 1.48854265e+01 1.50307121e+01 1.44216433e+01 1.41871986e+01 1.35541115e+01 1.31462173e+01 1.29160938e+01 1.29647713e+01 1.33088036e+01 1.34101496e+01 1.32697001e+01 1.24161263e+01 1.18858652e+01 1.15055437e+01 1.18385496e+01 1.24967165e+01 1.29627390e+01 1.24610100e+01 1.24362316e+01 1.32721558e+01 1.37728386e+01 1.35285120e+01 1.20994081e+01 1.23312540e+01 1.36570187e+01 1.52824678e+01 1.51824293e+01 1.37966013e+01 1.31280394e+01 1.18601141e+01 1.16037979e+01 1.13688393e+01 1.16799641e+01 1.17532978e+01 1.28799171e+01 1.43455353e+01 1.41603680e+01 1.32290983e+01 1.14563065e+01 1.11386347e+01 1.08054266e+01 1.19329891e+01 1.30216913e+01 1.32317810e+01 1.31412621e+01 1.31567373e+01 1.31049328e+01 1.21071634e+01 1.04149790e+01 9.64424324e+00 1.04379711e+01 1.16778650e+01 1.23942795e+01 1.29368591e+01 1.24655180e+01 1.21890574e+01 1.20785694e+01 1.10859261e+01 1.04092445e+01 1.04221220e+01 1.20692797e+01 1.26906958e+01 1.18608084e+01 1.01186209e+01 1.00117798e+01 1.02553921e+01 1.08219862e+01 9.15692139e+00 8.67970276e+00 9.40226078e+00 9.90427780e+00 9.93619061e+00 8.97490883e+00 7.92088556e+00 6.84079027e+00 7.59756231e+00 1.10423164e+01 1.23857279e+01 1.26365080e+01 1.25241776e+01 1.23757858e+01 1.16017437e+01 8.83933258e+00 8.34681702e+00 9.71010017e+00 1.28630219e+01 1.29043083e+01 1.12627316e+01 8.28607750e+00 8.05804825e+00 8.27245331e+00 1.01563578e+01 9.99582958e+00 9.34718895e+00 8.15347099e+00 8.88914776e+00 9.98018074e+00 1.07207880e+01 8.93629074e+00 8.74777126e+00 1.12527952e+01 1.44300823e+01 1.39347982e+01 1.19425030e+01 1.12497759e+01 1.11656694e+01 1.06944838e+01 9.13445663e+00 8.88754940e+00 1.10575857e+01 1.14925528e+01 1.15759211e+01 9.23686695e+00 9.99964905e+00 1.15341969e+01 1.23501854e+01 1.29001484e+01 1.05670347e+01 9.46350479e+00 8.61775208e+00 1.05127172e+01 1.10996933e+01 1.05868769e+01 9.38041210e+00 7.58949566e+00 8.51932144e+00 8.31378841e+00 9.41502953e+00 9.08704376e+00 1.10044384e+01 1.03369207e+01 1.06678171e+01 9.85731697e+00 1.02065868e+01 9.97250557e+00 9.74502850e+00 1.05231705e+01 9.88576031e+00 1.04814816e+01 1.11719294e+01 9.83289623e+00 8.50244045e+00 6.07148552e+00 6.04957342e+00 8.01980114e+00 1.05074120e+01 1.07446480e+01 8.90075493e+00 6.60094833e+00 8.51672459e+00 9.94898510e+00 1.02744732e+01 9.73648262e+00 9.23113060e+00 1.13712912e+01 1.09748163e+01 9.45297623e+00 6.62288523e+00 6.15769672e+00 6.92254162e+00 6.80956554e+00 7.22951889e+00 7.78429604e+00 9.66188431e+00 1.02908859e+01 9.20310879e+00 8.43687153e+00 6.59842443e+00 7.35842896e+00 7.74436188e+00 1.01471815e+01 1.22075777e+01 1.08638391e+01 8.22602463e+00 4.87845087e+00 5.25722504e+00 4.24716091e+00 4.33961964e+00 5.37304258e+00 7.69300985e+00 8.53210831e+00 8.09545231e+00 7.92159796e+00 8.67992210e+00 9.05754662e+00 7.47587585e+00 7.48280001e+00 9.07151222e+00 9.78401089e+00 8.15175533e+00 7.43844652e+00 9.32695484e+00 8.98769093e+00 6.70554829e+00 5.34260941e+00 6.45958757e+00 8.67465019e+00 8.28571796e+00 6.71568441e+00 5.86669016e+00 6.50557947e+00 5.42592430e+00 4.56829214e+00 4.26303673e+00 7.55106163e+00 8.11765957e+00 8.71837044e+00 7.15317917e+00 8.18585777e+00 8.23454094e+00 7.56606150e+00 6.80279684e+00 7.97054338e+00 9.10236263e+00 9.61626530e+00 8.41667843e+00 1.03165312e+01 8.89652157e+00 8.94104290e+00 7.17323065e+00 9.32925510e+00 1.00315065e+01 8.86662483e+00 4.80156660e+00 4.47083616e+00 6.80219221e+00 9.46248245e+00 6.91739702e+00 5.05896568e+00 4.85246849e+00 5.87176466e+00 6.01677179e+00 4.56165934e+00 6.68698406e+00 7.08229303e+00 7.71403360e+00 5.95139122e+00 6.14205647e+00 7.01899862e+00 6.61843729e+00 7.53057623e+00 8.72402000e+00 7.32489443e+00 4.88933706e+00 2.56072259e+00 4.15956354e+00 6.85100412e+00 5.96207047e+00 5.62030840e+00 2.69673872e+00 2.91471052e+00 2.26850486e+00 1.86033571e+00 2.71807981e+00 3.00087714e+00 3.92221045e+00 4.97814226e+00 4.95627832e+00 6.40368652e+00 6.78130674e+00 5.61126041e+00 5.00484705e+00 3.40824652e+00 5.58495569e+00 5.58559370e+00 6.02444983e+00 9.14614964e+00 9.03389835e+00 6.16115999e+00 2.19300255e-01 -9.71019804e-01 7.52352059e-01 2.38768148e+00 2.89036131e+00 3.11507225e+00 1.86950040e+00 1.00922859e+00 -8.96133840e-01 1.79829538e-01 -1.25178897e+00 -3.12812543e+00 -3.56634498e+00 -9.30295944e-01 3.67934370e+00 5.90524483e+00 1.80119872e+00 -5.47414362e-01 -8.53517652e-01 2.74161363e+00 4.41037512e+00 3.45371962e+00 4.70943642e+00 2.34086943e+00 2.57153010e+00 -1.41484118e+00 -6.72566354e-01 -1.84611106e+00 1.65209234e+00 3.23915410e+00 3.73645878e+00 6.45798862e-01 -2.29232931e+00 -4.98163557e+00 -3.11247921e+00 1.46572900e+00 3.16342044e+00 4.18370533e+00 1.97557604e+00 5.07657146e+00 4.70528555e+00 2.57057333e+00 -1.41458046e+00 -1.90642810e+00 -1.77183077e-01 6.76258147e-01 9.46312308e-01 1.41363060e+00 1.60380113e+00 -6.16076350e-01 -1.29976058e+00 -3.28295827e+00 -2.35918617e+00 -3.32047820e+00 -2.93481898e+00 -9.84652519e-01 -3.94575238e-01 2.70409799e+00 2.18650892e-01 6.30545080e-01 -2.06095171e+00 -4.81749105e+00 -5.44581079e+00 -2.75702000e+00 1.98359263e+00 2.16765833e+00 2.31210375e+00 -8.83243918e-01 -1.81575584e+00 -1.74127054e+00 1.46853554e+00 2.43652964e+00 1.98897982e+00 1.13297653e+00 -1.16435421e+00 -6.24943852e-01 -2.34962016e-01 1.89285982e+00 1.05738819e+00 -2.08063275e-01 -1.47135723e+00 -2.14332891e+00 -4.17513371e+00 -1.91548109e+00 -1.12251699e+00 4.83737975e-01 -1.99158347e+00 -3.84918070e+00 -2.66980410e+00 2.43447721e-01 1.28891325e+00 1.14348722e+00 -1.34635937e+00 -9.60971832e-01 -2.83248711e+00 -2.39369750e+00 -4.20221615e+00 -3.68615270e+00 -3.07114553e+00 -2.97246480e+00 -2.10472155e+00 -3.69162822e+00 -2.40576696e+00 -1.24118388e+00 -7.36730099e-01 -1.22776949e+00 -4.91990995e+00 -3.08344054e+00 -9.45583284e-01 8.16769838e-01 -3.31636786e-01 -4.38833427e+00 -4.96572971e+00 -6.35589886e+00 -2.97784686e+00 -6.23375893e-01 7.79871702e-01 -8.41380179e-01 -3.39150572e+00 -3.50545716e+00 -8.43060672e-01 -4.53425139e-01 -6.23702824e-01 -3.87818837e+00 -3.81050825e+00 -5.84902763e+00 -5.89920998e+00 -3.66050911e+00 -1.42145514e-01 1.07379985e+00 -1.05078542e+00 -2.95121908e+00 -4.62616205e+00 -4.47805548e+00 -1.71563268e+00 2.42295170e+00 5.72422445e-01 -1.98778689e+00 -6.78267241e+00 -5.17145824e+00 -3.82654262e+00 -1.62089014e+00 -1.45921099e+00 -3.99946594e+00 -4.81328106e+00 -5.19680309e+00 -5.13536119e+00 -5.16541481e+00 -4.33841038e+00 -3.62084723e+00 -4.28996992e+00 -4.99954319e+00 -4.00532246e+00 -3.49007535e+00 -3.70331144e+00 -1.41834784e+00 -2.44935703e+00 -2.10046387e+00 -4.21068668e+00 -2.41684890e+00 -1.22685456e+00 -3.28137231e+00 -5.91417885e+00 -7.55076742e+00 -4.82609034e+00 -2.05741072e+00 -1.49471045e+00 -3.75770044e+00 -6.38567209e+00 -8.90506172e+00 -8.74032974e+00 -8.11477280e+00 -4.36189938e+00 -3.79107666e+00 -4.60678816e+00 -6.09935379e+00 -5.93082571e+00 -3.39374542e+00 -3.21940136e+00 -3.44776154e+00 -4.34245300e+00 -6.14015961e+00 -6.69630051e+00 -4.22900677e+00 -1.01121493e-01 1.36275721e+00 -1.23215604e+00 -4.44272757e+00 -5.85069656e+00 -4.73660994e+00 -3.15160322e+00 -3.00678968e+00 -3.60415721e+00 -6.00925159e+00 -6.45155621e+00 -7.01975632e+00 -6.11055756e+00 -4.70951605e+00 -4.76562643e+00 -6.32432890e+00 -9.03824520e+00 -9.96914291e+00 -6.81850481e+00 -4.19138288e+00 -2.14522243e+00 -3.29551125e+00 -6.98548365e+00 -9.28188419e+00 -9.59842873e+00 -5.77369070e+00 -3.23375535e+00 -2.48471785e+00 -4.31865692e+00 -5.72785950e+00 -6.47178745e+00 -5.85718822e+00 -6.92213249e+00 -7.71323252e+00 -8.96876621e+00 -8.46943569e+00 -9.41588593e+00 -8.72245407e+00 -8.44848537e+00 -6.31402445e+00 -7.42915344e+00 -7.91451120e+00 -9.66411209e+00 -8.81668186e+00 -8.40802956e+00 -7.44580173e+00 -7.53372145e+00 -8.41083336e+00 -8.57017136e+00 -8.64439201e+00 -7.74355841e+00 -6.79232073e+00 -7.31740189e+00 -8.10749340e+00 -9.76289654e+00 -9.53190899e+00 -8.58308792e+00 -7.69525480e+00 -8.30521488e+00 -1.05192232e+01 -9.90719509e+00 -8.76738262e+00 -7.35178089e+00 -1.12193937e+01 -1.87651310e+01 -2.71460285e+01 -3.54757347e+01 -4.56322746e+01 -6.57003937e+01 -1.29790039e+02 -4.80516083e+02 -5.75902771e+02 8.87774124e+01 1.53328967e+03 6.98745361e+03 121238904. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 352181728. -363439936. 2.45572632e+03 9.33637146e+02 1.36098953e+02 1.05252190e+02 2.75908546e+01 5.91981554e+00 -5.99184561e+00 -7.19846535e+00 -6.83929729e+00 -7.42556572e+00 -8.41037178e+00 -1.13991613e+01 -1.35289488e+01 -1.38545122e+01 -1.36024933e+01 -1.05856409e+01 -9.85431671e+00 -1.03407488e+01 -1.20540638e+01 -1.26810923e+01 -1.27903328e+01 -1.17059412e+01 -1.08551369e+01 -1.12094259e+01 -1.24005661e+01 -1.28552151e+01 -1.20059147e+01 -1.08142405e+01 -1.15311203e+01 -1.17451239e+01 -1.19957447e+01 -1.14693766e+01 -1.14682751e+01 -1.14829063e+01 -1.18520718e+01 -1.22667418e+01 -1.17184429e+01 -1.14890375e+01 -1.09932404e+01 -1.15185947e+01 -1.23445148e+01 -1.36460400e+01 -1.40057554e+01 -1.40641127e+01 -1.46462126e+01 -1.41367054e+01 -1.23889542e+01 -8.95243168e+00 -8.90793324e+00 -1.02329693e+01 -1.08911295e+01 -1.02707167e+01 -9.11656284e+00 -9.53066826e+00 -1.12599907e+01 -1.21150112e+01 -1.26279249e+01 -1.16236935e+01 -1.13738756e+01 -1.11449575e+01 -1.12153273e+01 -1.25916891e+01 -1.38387575e+01 -1.38304577e+01 -1.27641602e+01 -1.19861622e+01 -1.27035055e+01 -1.38650742e+01 -1.36888351e+01 -1.39053822e+01 -1.34560575e+01 -1.44732084e+01 -1.36628504e+01 -1.34283142e+01 -1.41560907e+01 -1.44495506e+01 -1.41224747e+01 -1.26038494e+01 -1.26908407e+01 -1.31332455e+01 -1.28150406e+01 -1.25637455e+01 -1.29255743e+01 -1.38124771e+01 -1.35701914e+01 -1.27999458e+01 -1.18479061e+01 -1.24108000e+01 -1.21918507e+01 -1.31208324e+01 -1.31780186e+01 -1.40241299e+01 -1.36724720e+01 -1.35157566e+01 -1.43850546e+01 -1.46757803e+01 -1.40634604e+01 -1.34262247e+01 -1.25645685e+01 -1.38579721e+01 -1.31361809e+01 -1.29304056e+01 -1.19571409e+01 -1.21490803e+01 -1.31523848e+01 -1.29504290e+01 -1.39120436e+01 -1.39795122e+01 -1.45348520e+01 -1.42690916e+01 -1.30133829e+01 -1.31770086e+01 -1.32449446e+01 -1.38101807e+01 -1.35671434e+01 -1.31935339e+01 -1.34918671e+01 -1.37124557e+01 -1.31730385e+01 -1.37360392e+01 -1.34123144e+01 -1.31487646e+01 -1.23758163e+01 -1.22986822e+01 -1.38337107e+01 -1.38982239e+01 -1.36816511e+01 -1.26959782e+01 -1.30322704e+01 -1.41609888e+01 -1.40504007e+01 -1.38806629e+01 -1.32379045e+01 -1.32520638e+01 -1.32709637e+01 -1.28725376e+01 -1.31457462e+01 -1.31209211e+01 -1.34182959e+01 -1.31345930e+01 -1.27529020e+01 -1.27959967e+01 -1.29337177e+01 -1.34997301e+01 -1.40001316e+01 -1.39514513e+01 -1.35908213e+01 -1.32233982e+01 -1.33294954e+01 -1.38140125e+01 -1.40184374e+01 -1.38406153e+01 -1.34449701e+01 -1.26865997e+01 -1.28802748e+01 -1.29300432e+01 -1.35640163e+01 -1.36997051e+01 -1.38234339e+01 -1.39670353e+01 -1.38455734e+01 -1.36219387e+01 -1.36088419e+01 -1.39704065e+01 -1.43277302e+01 -1.42572184e+01 -1.36823635e+01 -1.32212152e+01 -1.32608137e+01 -1.36626511e+01 -1.37656698e+01 -1.34527836e+01 -1.31487427e+01 -1.33903341e+01 -1.36755848e+01 -1.36355534e+01 -1.34984856e+01 -1.35457106e+01 -1.36540651e+01 -1.36976957e+01 -1.37333336e+01 -1.38672190e+01 -1.41730394e+01 -1.39688683e+01 -1.40038958e+01 -1.41163540e+01 -1.44232941e+01 -1.44979658e+01 -1.43136520e+01 -1.44096756e+01 -1.42107191e+01 -1.39288902e+01 -1.36844807e+01 -1.35727863e+01 -1.38643751e+01 -1.37681770e+01 -1.36349993e+01 -1.32648344e+01 -1.32579508e+01 -1.35594015e+01 -1.37747278e+01 -1.39223175e+01 -1.38728428e+01 -1.39113951e+01 -1.39478083e+01 -1.39575577e+01 -1.39721031e+01 -1.39190741e+01 -1.39098635e+01 -1.38763342e+01 -1.38427067e+01 -1.38423452e+01 -1.37081947e+01 -1.37443600e+01 -1.38087654e+01 -1.39022169e+01 -1.38678141e+01 -1.38243809e+01 -1.38083382e+01 -1.38169355e+01 -1.37871494e+01 -1.37718439e+01 -1.37700987e+01 -1.37855778e+01 -1.37935867e+01 -1.37858496e+01 -1.37524548e+01 -1.37591457e+01 -1.37946157e+01 -1.38425198e+01 -1.38450937e+01 -1.37983160e+01 -1.37573357e+01 -1.37531834e+01 -1.37779007e+01 -1.37871923e+01 -1.38638105e+01 -1.38533926e+01 -1.38640203e+01 -1.37974234e+01 -1.37853184e+01 -1.37645330e+01 -1.37306108e+01 -1.37210751e+01 -1.37077723e+01 -1.37155848e+01 -1.38258057e+01 -1.38255091e+01 -1.38565922e+01 -1.37719574e+01 -1.38583899e+01 -1.37666874e+01 -1.36631088e+01 -1.36422548e+01 -1.37212801e+01 -1.38362617e+01 -1.36815119e+01 -1.36512794e+01 -1.36024818e+01 -1.36587524e+01 -1.34177694e+01 -1.35079975e+01 -1.34903841e+01 -1.37360630e+01 -1.33889217e+01 -1.34166374e+01 -1.34302826e+01 -1.36801748e+01 -1.36764946e+01 -1.37603502e+01 -1.38002138e+01 -1.37755003e+01 -1.38418674e+01 -1.38457727e+01 -1.38481331e+01 -1.35692577e+01 -1.36063967e+01 -1.35739756e+01 -1.37347193e+01 -1.37417955e+01 -1.36318693e+01 -1.41315250e+01 -1.39204311e+01 -1.40703735e+01 -1.36106987e+01 -1.35860786e+01 -1.35285606e+01 -1.33881540e+01 -1.34496374e+01 -1.36999912e+01 -1.36187229e+01 -1.37555342e+01 -1.37824478e+01 -1.40756407e+01 -1.36030359e+01 -1.33002224e+01 -1.28985672e+01 -1.31165676e+01 -1.28992453e+01 -1.27097702e+01 -1.30184526e+01 -1.30921717e+01 -1.36657677e+01 -1.38755836e+01 -1.39747057e+01 -1.32159014e+01 -1.29564085e+01 -1.29818115e+01 -1.35782423e+01 -1.32318268e+01 -1.27370462e+01 -1.29342899e+01 -1.30266676e+01 -1.29932470e+01 -1.25604725e+01 -1.25520592e+01 -1.30179415e+01 -1.31483164e+01 -1.29479961e+01 -1.26541185e+01 -1.26150970e+01 -1.25570478e+01 -1.23214741e+01 -1.24824133e+01 -1.25659304e+01 -1.31647606e+01 -1.31605101e+01 -1.39934607e+01 -1.45413609e+01 -1.41438084e+01 -1.34350166e+01 -1.28882971e+01 -1.27374868e+01 -1.27526960e+01 -1.29004107e+01 -1.34792776e+01 -1.40008669e+01 -1.36452074e+01 -1.32551537e+01 -1.19772768e+01 -1.19433937e+01 -1.16372690e+01 -1.14816437e+01 -1.21227131e+01 -1.18177767e+01 -1.24807224e+01 -1.18190126e+01 -1.25802336e+01 -1.24467926e+01 -1.23998156e+01 -1.25745916e+01 -1.27960157e+01 -1.30236635e+01 -1.23643856e+01 -1.29938774e+01 -1.21504583e+01 -1.28309479e+01 -1.19972439e+01 -1.24522638e+01 -1.19646854e+01 -1.17620440e+01 -1.04073744e+01 -1.14710331e+01 -1.20802326e+01 -1.34866838e+01 -1.26950932e+01 -1.18504944e+01 -1.21228714e+01 -1.21140099e+01 -1.27931252e+01 -1.23561859e+01 -1.20735226e+01 -1.11092043e+01 -1.21963444e+01 -1.24733095e+01 -1.35645180e+01 -1.23251925e+01 -1.18085060e+01 -1.17543344e+01 -1.24672575e+01 -1.25552855e+01 -1.22191648e+01 -1.16649475e+01 -1.20521889e+01 -1.30856848e+01 -1.31761789e+01 -1.31178579e+01 -1.19267273e+01 -1.19298630e+01 -1.15713034e+01 -1.14112282e+01 -1.12310705e+01 -1.11221180e+01 -1.21117077e+01 -1.19275265e+01 -1.21766605e+01 -1.11498127e+01 -1.16027040e+01 -1.06630449e+01 -1.05897055e+01 -9.86349678e+00 -9.77135372e+00 -9.07965374e+00 -8.64261341e+00 -8.90162849e+00 -8.90404797e+00 -9.44999027e+00 -9.71158504e+00 -1.06633034e+01 -1.05244732e+01 -1.01052275e+01 -9.24639606e+00 -8.80687141e+00 -9.20206928e+00 -1.05794516e+01 -1.12682629e+01 -1.06331196e+01 -8.67763805e+00 -8.27361584e+00 -9.38801765e+00 -1.08034391e+01 -1.13125277e+01 -1.04896641e+01 -1.05484686e+01 -1.11988649e+01 -1.11796741e+01 -1.05608253e+01 -9.37063122e+00 -9.31429768e+00 -9.62713909e+00 -1.05253992e+01 -1.14295931e+01 -1.17462292e+01 -1.11936293e+01 -1.14728193e+01 -1.09672956e+01 -1.17802591e+01 -1.09650230e+01 -1.10897684e+01 -1.01124277e+01 -9.65601063e+00 -8.92614937e+00 -7.95508623e+00 -8.42403603e+00 -9.79299259e+00 -1.20054874e+01 -1.39781284e+01 -9.85376263e+00 -3.00093913e+00 7.19992161e+00 1.53997087e+01 2.35437984e+01 2.14008160e+01 3.02374725e+01 7.39825287e+01 3.81820984e+02 4.79243103e+02 -1.70295197e+02 -1.12002281e+02 -1.06465381e+03 -4.37048828e+03 -294410496. 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. 0. 0. 0. 0. 0. 0. 0. 90807680. -1.64786951e+03 -6.26042786e+02 1.62381878e+01 -6.20826340e+01 -8.42279053e+01 -8.09795380e+01 -2.71629238e+01 -1.26387358e+01 -9.20846176e+00 -8.52753258e+00 -9.92335320e+00 -1.05234947e+01 -1.07848978e+01 -1.09056797e+01 -1.10621910e+01 -1.00718565e+01 -8.42482948e+00 -8.09397984e+00 -8.36858940e+00 -9.93946648e+00 -9.93320656e+00 -9.06717396e+00 -8.32021809e+00 -8.14341354e+00 -8.57430935e+00 -7.92311430e+00 -8.15534592e+00 -7.24961519e+00 -6.53255701e+00 -5.45878839e+00 -5.36308146e+00 -5.75697184e+00 -6.63845921e+00 -7.03497076e+00 -6.41490889e+00 -6.12744379e+00 -4.43765783e+00 -4.11559010e+00 -4.05654669e+00 -5.49798441e+00 -6.59245586e+00 -5.47073174e+00 -4.86583662e+00 -4.45282221e+00 -4.29122782e+00 -4.42060995e+00 -5.36917162e+00 -4.88512754e+00 -4.82369709e+00 -3.51075339e+00 -4.26017380e+00 -3.83052683e+00 -3.85450697e+00 -3.50562286e+00 -3.75532174e+00 -4.03712416e+00 -4.42282438e+00 -4.70311308e+00 -4.32299137e+00 -4.90429497e+00 -5.79876423e+00 -7.37804747e+00 -7.93161106e+00 -7.97832775e+00 -6.95914888e+00 -5.66251183e+00 -6.15307426e+00 -7.10782099e+00 -6.26519680e+00 -4.45717525e+00 -2.93045115e+00 -2.81268620e+00 -3.45697761e+00 -3.30759048e+00 -2.96139860e+00 -2.35291529e+00 -2.25433898e+00 -2.81999087e+00 -3.14643478e+00 -3.29717135e+00 -4.01693916e+00 -4.26814699e+00 -6.08498192e+00 -6.46902418e+00 -7.22571898e+00 -6.65448809e+00 -6.16861963e+00 -5.00259638e+00 -4.89756775e+00 -4.36137152e+00 -5.48858738e+00 -5.40780401e+00 -6.48566723e+00 -6.38044930e+00 -5.74863529e+00 -5.28250551e+00 -4.48374224e+00 -3.84757853e+00 -3.45340967e+00 -3.55527520e+00 -3.13048005e+00 -2.54969192e+00 -2.19725037e+00 -2.71537137e+00 -2.93368101e+00 -3.09602833e+00 -3.67197514e+00 -4.44300508e+00 -4.71761322e+00 -5.71540737e+00 -5.59684753e+00 -4.22438765e+00 -1.46794248e+00 -7.10271478e-01 -1.03111482e+00 -2.62661076e+00 -3.54529476e+00 -4.65400600e+00 -3.29342580e+00 -1.67304492e+00 -7.76087523e-01 -7.45956123e-01 -2.55327201e+00 -3.24485469e+00 -3.41203308e+00 -2.17087173e+00 -1.04800653e+00 -2.25493979e+00 -4.04999828e+00 -5.35307503e+00 -3.73773932e+00 -1.91085839e+00 -1.05966067e+00 -1.92005312e+00 -3.84494615e+00 -4.83722067e+00 -5.43289423e+00 -3.12766600e+00 -1.91653776e+00 -1.93512750e+00 -1.67447996e+00 -1.95197618e+00 -6.93415165e-01 -9.83681142e-01 -6.54121816e-01 -8.38703334e-01 -1.44996750e+00 -1.66295755e+00 -1.23595107e+00 -9.94305193e-01 -8.26872110e-01 -1.08285713e+00 -2.53670835e+00 -3.88354325e+00 -4.76967049e+00 -3.52325010e+00 -2.80161572e+00 -3.02207899e+00 -3.36133313e+00 -3.40073776e+00 -3.58588171e+00 -4.66269732e+00 -5.09503603e+00 -4.31896305e+00 -2.37775159e+00 -1.21986377e+00 -4.78549331e-01 -4.36706960e-01 2.94698328e-01 -3.04038823e-01 -3.53407234e-01 -7.68328071e-01 -2.08566755e-01 -1.04031873e+00 -6.35792971e-01 9.10364568e-01 3.36791992e+00 2.97017360e+00 1.10447359e+00 -3.00589710e-01 -4.09964800e-01 -4.86931026e-01 3.13345850e-01 1.64227211e+00 1.72921264e+00 -6.89513147e-01 -1.17849362e+00 -8.14493716e-01 1.03488612e+00 5.76377153e-01 4.40017968e-01 -3.55730832e-01 3.29192519e-01 -9.00364891e-02 8.46277058e-01 -2.10794717e-01 8.00347269e-01 -5.17783351e-02 -3.74391794e-01 -9.22796905e-01 6.16375685e-01 2.45291805e+00 1.71795166e+00 8.30481648e-01 4.04125005e-01 1.88985312e+00 2.13653231e+00 1.73907304e+00 1.79726362e+00 2.44760370e+00 2.60988474e+00 2.99498820e+00 2.49999142e+00 2.55665255e+00 2.25790858e+00 1.56110370e+00 1.98707795e+00 1.70651770e+00 2.09505820e+00 1.94117916e+00 2.19529557e+00 2.64779425e+00 3.21493649e+00 2.87395835e+00 3.07598305e+00 2.50620031e+00 2.61768103e+00 3.01460409e+00 2.86102009e+00 2.70829439e+00 2.26391888e+00 2.56523561e+00 3.16118002e+00 3.91769075e+00 4.68590879e+00 4.65604401e+00 4.02596855e+00 4.65504456e+00 5.41920757e+00 5.32450342e+00 3.18723297e+00 2.06352592e+00 2.48192334e+00 4.36322069e+00 4.83194637e+00 4.78005838e+00 3.94814873e+00 1.97551942e+00 -2.53590584e-01 -3.25142294e-01 1.32685626e+00 3.36482120e+00 1.22973764e+00 -6.65648133e-02 9.05317426e-01 3.54891205e+00 5.19854927e+00 4.85548162e+00 4.66023111e+00 4.12276125e+00 3.49506307e+00 3.39410138e+00 4.52319860e+00 4.66738653e+00 5.41705561e+00 4.06008196e+00 4.33228779e+00 4.46898985e+00 4.40045404e+00 3.43774557e+00 4.36206627e+00 5.14656448e+00 5.03860617e+00 2.38211966e+00 2.17616677e+00 2.90392971e+00 4.04737186e+00 3.05202031e+00 2.48682022e+00 1.68261492e+00 2.41678548e+00 3.09234691e+00 3.43312049e+00 5.41044188e+00 5.45219278e+00 6.00953197e+00 5.63626146e+00 6.00267887e+00 6.27660656e+00 4.64693451e+00 3.92741370e+00 3.65205503e+00 5.85826731e+00 6.06390142e+00 7.72356653e+00 4.27053738e+00 2.27455401e+00 1.73005795e+00 3.52859282e+00 6.01998568e+00 5.55544281e+00 6.24237585e+00 5.83882475e+00 5.24244499e+00 4.44411087e+00 4.62824392e+00 4.41660833e+00 3.88702846e+00 4.42946577e+00 4.68338680e+00 5.94945765e+00 5.83626938e+00 6.13252640e+00 5.34095287e+00 4.80016947e+00 4.16940355e+00 5.05565262e+00 6.61201668e+00 7.47954178e+00 7.92893553e+00 7.91759872e+00 8.46017265e+00 7.84674454e+00 7.04362106e+00 6.34730864e+00 5.19072008e+00 5.60357237e+00 5.14460611e+00 6.26986980e+00 4.24271345e+00 3.76979756e+00 3.04431009e+00 4.77127552e+00 6.20517397e+00 7.11107874e+00 6.50069427e+00 6.19530582e+00 5.45202589e+00 6.65915060e+00 6.41225863e+00 6.54877043e+00 7.56154108e+00 8.04728889e+00 8.99591255e+00 7.13670969e+00 6.34143829e+00 6.68362856e+00 6.01278782e+00 5.14790726e+00 4.41823387e+00 5.59579706e+00 7.41347694e+00 5.94183731e+00 6.30306339e+00 5.14679146e+00 6.75898552e+00 6.65126324e+00 8.87530994e+00 1.04179525e+01 1.10641756e+01 1.08822355e+01 1.06520920e+01 1.05585260e+01 9.98392010e+00 9.88141823e+00 1.02611113e+01 1.00459328e+01 9.72754860e+00 9.13675499e+00 8.25373840e+00 7.42986679e+00 6.36816454e+00 7.59521484e+00 8.81273651e+00 9.47659302e+00 7.16133070e+00 6.20820045e+00 6.89775372e+00 8.54817486e+00 9.47965622e+00 8.08032417e+00 8.67177010e+00 8.13744068e+00 8.63645077e+00 7.86625862e+00 7.66497183e+00 7.84125566e+00 8.93226242e+00 9.86398506e+00 1.05060892e+01 9.76351166e+00 9.64005089e+00 9.81982803e+00 9.43699932e+00 9.32132244e+00 8.30356026e+00 8.93286991e+00 9.05294704e+00 1.07856941e+01 1.05346851e+01 8.94702816e+00 7.92586279e+00 9.11495590e+00 1.04601717e+01 9.61293983e+00 9.25005245e+00 9.75630665e+00 1.00890284e+01 1.10955420e+01 1.11116753e+01 1.17935305e+01 1.04621382e+01 1.00542212e+01 9.95318413e+00 1.03780336e+01 1.03142185e+01 9.74395275e+00 1.00341721e+01 1.09621725e+01 1.23931494e+01 1.21627655e+01 1.24195023e+01 1.17849588e+01 1.23342180e+01 1.09868298e+01 1.03291359e+01 9.36423588e+00 9.84434605e+00 1.09334946e+01 1.10872946e+01 1.15731812e+01 1.05843697e+01 1.13007011e+01 1.10834618e+01 1.12143221e+01 1.01477194e+01 9.45100880e+00 9.05219173e+00 9.59383678e+00 1.01246223e+01 9.77965355e+00 8.68737888e+00 9.07556915e+00 1.06614628e+01 1.16537914e+01 1.20016146e+01 1.10426493e+01 1.24001637e+01 1.23560734e+01 1.23166866e+01 1.16224842e+01 1.08824129e+01 1.14061804e+01 1.15175228e+01 1.27479067e+01 1.30482082e+01 1.29010172e+01 1.26010914e+01 1.23876085e+01 1.26186171e+01 1.24036140e+01 1.19887400e+01 1.15703821e+01 1.19262800e+01 1.25962973e+01 1.31010952e+01 1.25484467e+01 1.30222130e+01 1.29283991e+01 1.26783590e+01 1.07308130e+01 9.23646355e+00 8.91566563e+00 9.93285275e+00 1.04538326e+01 1.03587065e+01 1.05757437e+01 1.13212233e+01 1.26003504e+01 1.14201384e+01 1.08960314e+01 1.04401236e+01 1.12741852e+01 1.12793083e+01 1.12536364e+01 1.23707180e+01 1.28158064e+01 1.24876757e+01 1.14678535e+01 1.18743401e+01 1.17224865e+01 1.11066895e+01 1.10261383e+01 1.28018894e+01 1.41434040e+01 1.45053816e+01 1.33800678e+01 1.34264717e+01 1.35208998e+01 1.34958963e+01 1.31660604e+01 1.25881395e+01 1.28954506e+01 1.31476927e+01 1.34260836e+01 1.35471487e+01 1.28449030e+01 1.22143345e+01 1.16419964e+01 1.17668858e+01 1.25286779e+01 1.31677217e+01 1.35400810e+01 1.32155333e+01 1.33965130e+01 1.33407145e+01 1.31185770e+01 1.33972969e+01 1.40613747e+01 1.41747627e+01 1.32175407e+01 1.30619726e+01 1.30460682e+01 1.28678865e+01 1.18780794e+01 1.16612844e+01 1.21866169e+01 1.27841759e+01 1.32723122e+01 1.30747671e+01 1.31761675e+01 1.29361925e+01 1.25246792e+01 1.23815193e+01 1.23719501e+01 1.28901691e+01 1.29154978e+01 1.28735809e+01 1.28192730e+01 1.24091854e+01 1.21929684e+01 1.19027557e+01 1.23122749e+01 1.26643591e+01 1.26636171e+01 1.21811228e+01 1.25246582e+01 1.30505285e+01 1.37222538e+01 1.33948936e+01 1.30139599e+01 1.30636683e+01 1.30043030e+01 1.32720146e+01 1.35223875e+01 1.37318678e+01 1.35798082e+01 1.29427891e+01 1.25611715e+01 1.29050674e+01 1.29871416e+01 1.29666281e+01 1.30878124e+01 1.32236500e+01 1.34893188e+01 1.31002884e+01 1.29978447e+01 1.32969074e+01 1.37540140e+01 1.40286779e+01 1.36514912e+01 1.33396807e+01 1.33116541e+01 1.34183769e+01 1.34454556e+01 1.33566074e+01 1.34371767e+01 1.34281273e+01 1.32739964e+01 1.30096731e+01 1.30888023e+01 1.33018198e+01 1.35688562e+01 1.33751783e+01 1.34083071e+01 1.33457060e+01 1.35474997e+01 1.35844822e+01 1.35554571e+01 1.35076351e+01 1.37683735e+01 1.39388781e+01 1.43270006e+01 1.41836395e+01 1.40194759e+01 1.35988302e+01 1.36735373e+01 1.38099833e+01 1.39324217e+01 1.40446129e+01 1.40199213e+01 1.40194101e+01 1.40600805e+01 1.43715219e+01 1.71113091e+01 2.18824177e+01 5.26168976e+01 6.37492752e+01 -8.75705643e+01 -7.79700989e+02 -85511624. 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. 114288424. -1.94564255e+02 2.90143757e+01 3.14307632e+01 1.38840837e+01 1.16928120e+01 9.32452106e+00 8.66703510e+00 8.64570999e+00 8.55021095e+00 8.55402184e+00 8.50119972e+00 8.50951195e+00 8.48474216e+00 8.59119511e+00 8.63527966e+00 8.54467297e+00 8.37582493e+00 8.18939495e+00 8.15307140e+00 8.21282673e+00 8.41775322e+00 8.55101109e+00 8.67532158e+00 8.58107281e+00 8.49001694e+00 8.49080849e+00 8.53159046e+00 8.35500336e+00 8.26823616e+00 8.36442757e+00 8.61536407e+00 8.70217037e+00 8.75483608e+00 8.75783730e+00 8.64383888e+00 8.36419392e+00 8.23976612e+00 8.12859821e+00 8.38023758e+00 8.27900219e+00 8.51944542e+00 8.57903194e+00 8.71536922e+00 8.44156933e+00 8.27798557e+00 8.33321953e+00 8.43687916e+00 8.53294563e+00 8.49269962e+00 8.53125858e+00 8.30802917e+00 8.23822784e+00 7.91706991e+00 7.93668699e+00 7.75055027e+00 8.10885334e+00 8.51835442e+00 8.90633106e+00 8.86671066e+00 8.50782299e+00 8.32649803e+00 8.25514984e+00 8.31690598e+00 8.30447578e+00 8.12629414e+00 8.12786484e+00 8.15670490e+00 8.46614838e+00 8.16262341e+00 7.98837185e+00 7.90547037e+00 7.84568834e+00 7.86593151e+00 7.87199259e+00 7.94898081e+00 7.82229662e+00 7.87337160e+00 7.79749870e+00 7.84224033e+00 7.50598001e+00 7.66101885e+00 7.97102833e+00 8.02910709e+00 7.99972582e+00 7.53849125e+00 7.49848795e+00 7.61258411e+00 7.89012766e+00 7.78803062e+00 7.71434450e+00 8.02642155e+00 8.52496529e+00 8.41318130e+00 7.81813240e+00 7.50853586e+00 7.93950605e+00 8.12720680e+00 7.83093739e+00 7.47400856e+00 7.47793484e+00 7.80660677e+00 7.79568481e+00 7.44050217e+00 6.90281868e+00 6.97058201e+00 7.35398674e+00 8.10475254e+00 8.51106644e+00 8.74870968e+00 8.10018635e+00 7.42741966e+00 7.32870102e+00 7.78917599e+00 8.02427387e+00 8.16865158e+00 7.97919083e+00 8.49991512e+00 8.44439411e+00 7.62104464e+00 7.00709486e+00 6.63721514e+00 7.42593479e+00 7.66714478e+00 8.05998516e+00 8.37788773e+00 7.82571745e+00 7.42076445e+00 6.72371912e+00 6.59305811e+00 6.56424856e+00 6.81514549e+00 6.87620735e+00 6.76102161e+00 7.15987492e+00 7.49528790e+00 7.98230410e+00 7.69547367e+00 7.11782885e+00 6.21326160e+00 5.91050577e+00 6.33216238e+00 7.27305079e+00 7.69954300e+00 7.80103111e+00 7.41288090e+00 7.79717779e+00 7.78453302e+00 7.82636833e+00 6.94661903e+00 6.56312847e+00 5.98483181e+00 6.52772617e+00 7.07895231e+00 7.54528236e+00 7.05906963e+00 6.85764313e+00 7.33408308e+00 8.33455276e+00 8.07123375e+00 6.91975403e+00 6.54005575e+00 7.21912050e+00 8.02266502e+00 7.23033524e+00 7.05214834e+00 7.02832317e+00 7.92486048e+00 8.22736454e+00 7.57099819e+00 6.63010883e+00 5.63575935e+00 6.05152655e+00 5.77246714e+00 5.61143208e+00 6.33782864e+00 6.30905867e+00 7.10423040e+00 6.54696703e+00 6.62829828e+00 6.04236507e+00 5.39320469e+00 5.87853146e+00 6.18356943e+00 6.10471821e+00 6.39068079e+00 5.85963917e+00 6.98504114e+00 6.20342016e+00 6.27519178e+00 6.16678047e+00 7.18375111e+00 7.32627249e+00 6.01445007e+00 5.84851885e+00 4.92275190e+00 5.46357965e+00 4.81251287e+00 5.79937363e+00 5.60228252e+00 5.80991030e+00 5.89978361e+00 5.97735548e+00 6.58948088e+00 5.99472141e+00 6.79100513e+00 6.04427576e+00 6.43966436e+00 5.48007059e+00 6.17460108e+00 5.67124510e+00 5.93251371e+00 5.63005400e+00 6.84855652e+00 6.27047110e+00 5.30648422e+00 4.88238430e+00 4.91505527e+00 6.93939352e+00 7.09591866e+00 7.69526005e+00 6.10706615e+00 4.81197739e+00 4.75929546e+00 5.52441454e+00 6.28301859e+00 6.16486216e+00 4.77422237e+00 4.75645876e+00 4.41645432e+00 5.94024801e+00 5.68938875e+00 5.89579678e+00 5.51975584e+00 5.89471149e+00 5.78623629e+00 6.71246004e+00 6.79477072e+00 6.70796108e+00 5.61442614e+00 6.03124475e+00 5.75469303e+00 5.10078955e+00 5.70940065e+00 6.09107924e+00 6.50152493e+00 4.63362551e+00 4.82461977e+00 4.82561922e+00 5.32946396e+00 4.55403852e+00 4.57430840e+00 5.02231598e+00 5.49364948e+00 6.30055523e+00 6.42565918e+00 6.12191963e+00 6.08399630e+00 6.35306025e+00 6.05779219e+00 5.94243574e+00 5.11304092e+00 6.44369841e+00 5.51155949e+00 5.02113724e+00 4.35830212e+00 4.08113956e+00 5.56256580e+00 6.49412251e+00 6.77924490e+00 5.85951471e+00 6.46664619e+00 6.72670031e+00 7.70437956e+00 6.04982662e+00 5.59972906e+00 4.89316940e+00 5.19074869e+00 5.21659899e+00 5.67643833e+00 5.08158064e+00 4.32911062e+00 2.81302953e+00 3.61072731e+00 4.32408619e+00 4.29407310e+00 3.56939244e+00 3.97309971e+00 4.77450514e+00 5.95441818e+00 5.64513683e+00 5.41583776e+00 4.63451099e+00 5.25864697e+00 4.89764118e+00 4.29694033e+00 4.62161970e+00 4.60627079e+00 5.49832964e+00 4.68775892e+00 6.11277533e+00 6.75699520e+00 6.69207573e+00 5.39677382e+00 3.76089787e+00 4.17308807e+00 4.86666584e+00 4.74712944e+00 3.94077992e+00 3.50346303e+00 3.07212853e+00 3.53598452e+00 3.45693135e+00 4.35901356e+00 4.33388090e+00 3.76021290e+00 2.89181256e+00 3.16075540e+00 4.80069208e+00 5.44509935e+00 5.20387793e+00 4.07067251e+00 3.98004770e+00 4.85476017e+00 4.66430140e+00 4.28396606e+00 2.61489463e+00 1.15882468e+00 8.42953384e-01 1.06088388e+00 2.74183798e+00 2.92542315e+00 2.88610506e+00 2.51196098e+00 3.22504449e+00 3.18845606e+00 1.81784344e+00 1.81301105e+00 2.39711642e+00 3.12821960e+00 2.17831659e+00 2.32274771e+00 4.06235504e+00 5.63780212e+00 4.19007730e+00 2.96399927e+00 8.04792941e-01 2.05898046e+00 1.87577033e+00 2.29656744e+00 1.57304692e+00 2.76719570e+00 2.75358748e+00 1.75951850e+00 6.53166413e-01 1.81969976e+00 3.13976479e+00 3.77275920e+00 2.49489522e+00 1.54054976e+00 6.40295804e-01 -4.40944314e-01 2.43216947e-01 1.58957863e+00 3.13579321e+00 2.89856958e+00 3.26568246e+00 3.08976460e+00 3.61948633e+00 2.14505100e+00 2.24775243e+00 1.81743729e+00 2.05348682e+00 2.48208308e+00 2.33985472e+00 3.06746531e+00 3.45145321e+00 3.85985875e+00 2.53683376e+00 1.65849316e+00 2.54748988e+00 3.68010378e+00 3.50158095e+00 1.59563315e+00 1.69197536e+00 1.03822792e+00 2.12235427e+00 1.06484818e+00 1.75463331e+00 1.64646447e+00 3.54142261e+00 3.31902552e+00 1.73788929e+00 -1.19516945e+00 9.45640266e-01 3.86350250e+00 5.41468000e+00 4.26970530e+00 1.90376616e+00 9.88187194e-01 9.94577333e-02 8.64460230e-01 1.82502002e-01 3.94311309e-01 -1.15662837e+00 2.24594998e+00 2.80664515e+00 4.58110237e+00 2.12368989e+00 1.18731558e+00 5.85219800e-01 4.09722924e-01 1.11350298e+00 1.58991039e+00 2.09823537e+00 2.37496519e+00 1.17127848e+00 1.29320931e+00 7.07724631e-01 1.25766408e+00 1.53678441e+00 4.07462791e-02 -9.31443051e-02 -4.67104316e-01 5.49525678e-01 1.39008629e+00 2.27604270e+00 2.66020012e+00 5.97040772e-01 -8.22401404e-01 -1.16539526e+00 7.03907311e-01 8.19966018e-01 7.07033575e-01 -9.14463937e-01 -5.26051760e-01 -4.54131991e-01 8.57944787e-01 1.22047365e+00 4.97803092e-01 1.02259648e+00 -5.31455517e-01 -7.97686875e-01 -1.92895448e+00 -1.45129967e+00 2.49740764e-01 4.14782286e-01 1.00626028e+00 -9.00888629e-03 -6.55912519e-01 -5.87828994e-01 1.21542374e-02 7.34893203e-01 6.19061649e-01 -3.67123544e-01 1.80494159e-01 -5.75045168e-01 -6.58879876e-01 -1.33270109e+00 -9.29076195e-01 5.11501372e-01 5.67599237e-01 -5.31432271e-01 8.91896561e-02 -1.24924883e-01 1.44810891e+00 -2.56828278e-01 -1.15311742e-01 -7.68049061e-01 -7.70861566e-01 3.02402265e-02 -1.14321506e+00 -1.70263743e+00 -3.73324656e+00 -3.11831927e+00 -1.91951668e+00 -1.12928057e+00 -3.53434294e-01 -1.62178433e+00 -2.14358759e+00 -2.56931043e+00 -1.20547342e+00 -9.08904135e-01 -1.08610857e+00 -2.93429565e+00 -2.46239781e+00 -3.47585201e+00 -1.79130542e+00 -1.62003970e+00 5.41262567e-01 -5.18355489e-01 -1.08088267e+00 -1.51863635e+00 -9.94949758e-01 -1.30609882e+00 -1.15856659e+00 -7.24911511e-01 -2.13736087e-01 -1.57420814e+00 -2.51481867e+00 -1.56528091e+00 -1.43172491e+00 -9.69228864e-01 -2.34969997e+00 -2.55372882e+00 -3.73908114e+00 -3.45130610e+00 -3.22685814e+00 -1.74498415e+00 -1.46317160e+00 -1.27364516e+00 -1.22750247e+00 -2.43721390e+00 -2.15759110e+00 -2.81902218e+00 -1.33507657e+00 -1.53621340e+00 -2.05282235e+00 -2.69074583e+00 -2.90908742e+00 -2.44074178e+00 -2.13714385e+00 -1.78472006e+00 -2.40251827e+00 -1.98466575e+00 -1.55642951e+00 -6.61512494e-01 -1.80124187e+00 -2.34490108e+00 -3.49420500e+00 -3.15527487e+00 -4.18416023e+00 -2.69162893e+00 -2.46541095e+00 -1.43448508e+00 -1.85100651e+00 -1.99675393e+00 -2.68399954e+00 -1.59695303e+00 -2.01757050e+00 -2.07373619e+00 -3.64477730e+00 -4.66988564e+00 -4.82680750e+00 -3.83958530e+00 -2.11369872e+00 -1.00059891e+00 -2.58621383e+00 -4.66527081e+00 -6.00835419e+00 -5.25776768e+00 -3.61942196e+00 -1.75709915e+00 -2.65933418e+00 -3.90313363e+00 -4.37637520e+00 -4.33442163e+00 -3.15882969e+00 -3.67118382e+00 -3.23511386e+00 -3.24704623e+00 -3.38254046e+00 -3.74461675e+00 -4.28900003e+00 -4.06099701e+00 -2.01462364e+00 -6.57573521e-01 -1.38497281e+00 -2.87095547e+00 -4.03776741e+00 -3.16020226e+00 -2.78142977e+00 -2.57036161e+00 -5.00163651e+00 -5.51775026e+00 -4.46185923e+00 -2.64874935e+00 -3.28425384e+00 -4.78099155e+00 -4.93698978e+00 -4.14537096e+00 -3.40958285e+00 -2.76154494e+00 -2.72153807e+00 -3.82763028e+00 -3.79408979e+00 -3.94469285e+00 -3.18615341e+00 -3.41677475e+00 -3.76866984e+00 -3.38848019e+00 -3.34729242e+00 -3.99396706e+00 -4.52672243e+00 -4.82523298e+00 -3.09077001e+00 -3.51834917e+00 -4.12133503e+00 -5.14879465e+00 -4.21656847e+00 -3.31771350e+00 -3.15529799e+00 -2.94530630e+00 -3.27545404e+00 -3.80629706e+00 -4.98914623e+00 -5.46873665e+00 -4.01846409e+00 -4.22207975e+00 -5.32584429e+00 -6.57229042e+00 -6.44527435e+00 -6.11572599e+00 -6.98272228e+00 -6.39311552e+00 -5.53667307e+00 -5.98941612e+00 -8.05998611e+00 -1.19120083e+01 -1.07302341e+01 -2.18218060e+01 -7.15802078e+01 -5.89616882e+02 -1.38674927e+03 95212064. 119133344. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 352181728. -363439936. 891320448. -2.32750342e+03 1.21355385e+02 2.50605484e+02 6.20717316e+01 2.50689297e+01 6.29370642e+00 2.04523563e-01 -3.21984220e+00 -3.00429344e+00 -3.44271851e+00 -4.98286533e+00 -5.92036867e+00 -6.94493198e+00 -5.78839207e+00 -6.51868629e+00 -6.05456591e+00 -5.62122488e+00 -5.64117050e+00 -4.95504475e+00 -5.37886906e+00 -5.40559578e+00 -7.16454363e+00 -7.97252226e+00 -6.26862717e+00 -5.55333805e+00 -6.21398592e+00 -7.61252880e+00 -7.00715828e+00 -5.11215067e+00 -5.08562851e+00 -5.78786850e+00 -6.83079624e+00 -6.89826727e+00 -6.83968353e+00 -6.56094885e+00 -6.32591105e+00 -6.12560797e+00 -6.46002960e+00 -6.44837046e+00 -6.50907373e+00 -6.33070183e+00 -6.24288321e+00 -5.85241175e+00 -5.32911777e+00 -5.88443947e+00 -6.26262140e+00 -6.85777760e+00 -6.59564924e+00 -5.82439899e+00 -6.10610247e+00 -6.77185726e+00 -7.67187405e+00 -7.36378527e+00 -6.76107883e+00 -7.05852175e+00 -7.08863354e+00 -7.79769850e+00 -7.75312233e+00 -7.89684391e+00 -7.53864765e+00 -6.83026123e+00 -6.19584942e+00 -6.07441998e+00 -6.48610449e+00 -6.79555988e+00 -6.96029329e+00 -7.03936958e+00 -6.80866623e+00 -6.06619835e+00 -5.87017822e+00 -6.29073811e+00 -6.99297762e+00 -7.29584599e+00 -7.03189707e+00 -7.68775415e+00 -7.99900961e+00 -8.46271896e+00 -8.12669945e+00 -7.49799442e+00 -7.71427822e+00 -7.21627569e+00 -7.78173971e+00 -7.71042299e+00 -8.21947098e+00 -8.01674366e+00 -7.48369789e+00 -7.27275181e+00 -7.26471376e+00 -7.49829340e+00 -7.38722277e+00 -7.47007990e+00 -7.67084026e+00 -8.12091923e+00 -7.75161600e+00 -7.57405233e+00 -7.52252960e+00 -7.80971527e+00 -8.10668850e+00 -7.32849360e+00 -6.94162893e+00 -6.97326946e+00 -7.40430927e+00 -7.61017990e+00 -7.10630131e+00 -7.09286070e+00 -7.19463491e+00 -7.30484772e+00 -7.34610415e+00 -7.39775610e+00 -7.49339628e+00 -7.11252689e+00 -7.09032583e+00 -7.17651939e+00 -7.38408279e+00 -7.26412153e+00 -7.28351593e+00 -7.61304092e+00 -7.85965014e+00 -7.62917995e+00 -7.85785341e+00 -7.84989119e+00 -8.38803959e+00 -8.15134144e+00 -7.66655302e+00 -7.45713949e+00 -7.65473270e+00 -8.15577698e+00 -8.30457592e+00 -7.87957859e+00 -7.66525555e+00 -7.49989319e+00 -7.62476492e+00 -7.80871487e+00 -7.75912619e+00 -7.81269693e+00 -7.68723059e+00 -7.67516708e+00 -7.96392584e+00 -8.11334229e+00 -8.23955536e+00 -7.92316866e+00 -7.84791088e+00 -7.91193199e+00 -8.06567764e+00 -8.05898476e+00 -8.14529133e+00 -7.90779066e+00 -7.97505713e+00 -7.78708410e+00 -7.98341799e+00 -7.92978525e+00 -8.20516396e+00 -8.42605114e+00 -8.45959091e+00 -8.61313057e+00 -8.34042549e+00 -8.35020542e+00 -8.01411629e+00 -8.09999561e+00 -8.25636482e+00 -8.36705112e+00 -8.11738396e+00 -7.91650438e+00 -8.07169437e+00 -8.23524570e+00 -8.57555199e+00 -8.59235287e+00 -9.05908585e+00 -8.56549358e+00 -8.57434559e+00 -8.45897198e+00 -8.62880421e+00 -8.75092793e+00 -8.51648331e+00 -8.54532337e+00 -8.31074429e+00 -8.22954559e+00 -8.28000546e+00 -8.37485027e+00 -8.58634186e+00 -8.50788021e+00 -8.40358543e+00 -8.40924931e+00 -8.59308529e+00 -8.58208847e+00 -8.49309349e+00 -8.15930271e+00 -8.07465363e+00 -8.15811539e+00 -8.44000149e+00 -8.57856941e+00 -8.63623428e+00 -8.52758026e+00 -8.37635517e+00 -8.34305763e+00 -8.49927521e+00 -8.62852287e+00 -8.64141083e+00 -8.54956341e+00 -8.48650837e+00 -8.39150715e+00 -8.40782261e+00 -8.41342831e+00 -8.43455315e+00 -8.43668175e+00 -8.47111893e+00 -8.45784950e+00 -8.42735195e+00 -8.40350819e+00 -8.45085621e+00 -8.50387478e+00 -8.54834366e+00 -8.53813934e+00 -8.47626400e+00 -8.44150734e+00 -8.46051407e+00 -8.49159145e+00 -8.50314426e+00 -8.50791264e+00 -8.52717209e+00 -8.53707123e+00 -8.54084587e+00 -8.53355026e+00 -8.52692509e+00 -8.53072262e+00 -8.53912544e+00 -8.54230404e+00 -8.53393364e+00 -8.52318382e+00 -8.50687408e+00 -8.49705601e+00 -8.50351906e+00 -8.50136375e+00 -8.51115608e+00 -8.50231075e+00 -8.50887680e+00 -8.46259308e+00 -8.46078682e+00 -8.46318817e+00 -8.53597641e+00 -8.55503464e+00 -8.42824364e+00 -8.42041874e+00 -8.35943985e+00 -8.46587276e+00 -8.45099640e+00 -8.46223450e+00 -8.41783333e+00 -8.36929226e+00 -8.38870525e+00 -8.47576904e+00 -8.60217190e+00 -8.65307522e+00 -8.63734341e+00 -8.58258247e+00 -8.51484394e+00 -8.51159763e+00 -8.50041580e+00 -8.62023163e+00 -8.68815613e+00 -8.64433575e+00 -8.39246178e+00 -8.43493366e+00 -8.55053329e+00 -8.71787071e+00 -8.26052189e+00 -8.24524117e+00 -8.15992832e+00 -8.41559029e+00 -8.37846565e+00 -8.27781391e+00 -8.45572758e+00 -8.42827034e+00 -8.45158863e+00 -8.21159649e+00 -8.20017147e+00 -8.31999111e+00 -8.53548622e+00 -8.55922794e+00 -8.21325302e+00 -8.16694450e+00 -8.22718811e+00 -8.45105553e+00 -8.21345711e+00 -8.03587532e+00 -8.10565662e+00 -8.35353279e+00 -8.48454285e+00 -8.42684364e+00 -8.32130527e+00 -8.37491512e+00 -8.34402561e+00 -8.28464031e+00 -8.05709267e+00 -8.12844086e+00 -8.00760269e+00 -8.09945488e+00 -8.07653522e+00 -7.64013958e+00 -7.96998787e+00 -7.90626669e+00 -8.33871937e+00 -8.14817333e+00 -8.21853542e+00 -8.54553318e+00 -8.38979340e+00 -8.19128418e+00 -8.08576584e+00 -8.15660000e+00 -8.02506447e+00 -8.16781044e+00 -8.39027786e+00 -8.31063557e+00 -8.24382305e+00 -7.88617373e+00 -8.17292786e+00 -7.94447660e+00 -7.86342096e+00 -7.90876007e+00 -7.83790636e+00 -8.16725922e+00 -7.86200905e+00 -7.97929525e+00 -7.85381556e+00 -8.11790562e+00 -8.25274372e+00 -7.85955620e+00 -7.79599762e+00 -7.65831327e+00 -7.85872555e+00 -7.74988747e+00 -7.76385117e+00 -7.64813614e+00 -7.94154501e+00 -8.07974815e+00 -8.40274906e+00 -8.24982929e+00 -8.42295647e+00 -7.47559738e+00 -7.76579857e+00 -7.63954449e+00 -8.26646042e+00 -8.37979603e+00 -8.98639297e+00 -8.20023060e+00 -8.02200222e+00 -7.30233479e+00 -8.10269737e+00 -7.96834993e+00 -8.42939758e+00 -7.90888882e+00 -8.11197090e+00 -7.11384106e+00 -7.62028551e+00 -7.07702160e+00 -7.34229517e+00 -7.36207056e+00 -7.65338802e+00 -7.34216261e+00 -7.72584629e+00 -7.42925501e+00 -7.54240561e+00 -6.61434364e+00 -6.86167240e+00 -7.67184782e+00 -7.53916311e+00 -7.95537615e+00 -7.05987024e+00 -7.64047766e+00 -7.24890471e+00 -7.76270247e+00 -7.74121952e+00 -7.29329109e+00 -6.52851057e+00 -6.40168858e+00 -7.16698027e+00 -7.27001524e+00 -6.88108778e+00 -6.78761530e+00 -7.24930763e+00 -7.50235510e+00 -7.16706467e+00 -6.80277538e+00 -6.58978939e+00 -6.46166420e+00 -6.62282896e+00 -7.15359163e+00 -7.35291529e+00 -7.54529333e+00 -7.03097343e+00 -7.01898146e+00 -6.49396801e+00 -7.04541826e+00 -6.61475277e+00 -7.25185156e+00 -5.79849434e+00 -6.59985971e+00 -6.25978327e+00 -7.49357700e+00 -6.36381054e+00 -6.42046833e+00 -6.42935038e+00 -8.18691158e+00 -9.06163502e+00 -8.63062763e+00 -7.65881205e+00 -6.66120481e+00 -6.42877197e+00 -6.60845041e+00 -6.70519257e+00 -6.92113829e+00 -6.66368294e+00 -6.39117336e+00 -6.30947018e+00 -5.88609457e+00 -6.71641493e+00 -7.00161171e+00 -7.32098913e+00 -6.43806934e+00 -6.39102077e+00 -6.67314005e+00 -7.26646471e+00 -7.48142672e+00 -7.33615923e+00 -7.11588335e+00 -6.37223816e+00 -6.39156246e+00 -6.54791880e+00 -7.18471622e+00 -7.18940020e+00 -6.83880758e+00 -6.07119274e+00 -5.69502640e+00 -6.07960081e+00 -6.24119091e+00 -6.45617247e+00 -5.74435520e+00 -5.99067688e+00 -6.16464806e+00 -6.51473522e+00 -6.78226423e+00 -6.26469803e+00 -6.02769804e+00 -5.23822880e+00 -4.95000505e+00 -5.17367887e+00 -6.32275534e+00 -6.79472160e+00 -7.25919580e+00 -5.92743778e+00 -5.40048790e+00 -5.71856117e+00 -6.08358335e+00 -4.50123215e+00 -4.40492582e+00 -1.52209747e+00 1.18311071e+01 1.15653067e+01 4.32849159e+01 4.65023224e+02 3.80194580e+03 -148975744. 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. 0. 0. 0. 0. 0. 0. 90807680. -25646524. 1.47703650e+03 1.06099341e+03 9.18728485e+01 -3.96147369e+02 -2.85201477e+02 -4.72141609e+01 -1.24143782e+01 -6.34460497e+00 -3.38753247e+00 -3.24539280e+00 -4.41833925e+00 -4.49934959e+00 -3.95838261e+00 -3.81144667e+00 -3.77588439e+00 -2.81853366e+00 -2.11711693e+00 -2.54492283e+00 -3.25280857e+00 -3.90439987e+00 -3.66526389e+00 -4.12565088e+00 -4.09305096e+00 -4.51042271e+00 -4.77519417e+00 -4.60115576e+00 -4.07914162e+00 -3.96994710e+00 -4.77592564e+00 -5.29716682e+00 -4.95957851e+00 -4.55950212e+00 -4.51606512e+00 -4.55378819e+00 -4.10379744e+00 -3.85602427e+00 -3.61187601e+00 -4.06670523e+00 -3.03670526e+00 -2.94557762e+00 -2.60339046e+00 -3.22638130e+00 -4.04643822e+00 -4.17395353e+00 -4.43178129e+00 -4.40926361e+00 -5.03714943e+00 -5.14412022e+00 -5.17592192e+00 -4.77021074e+00 -3.93917751e+00 -3.70664811e+00 -3.37993550e+00 -3.40309882e+00 -3.50324512e+00 -3.41282392e+00 -4.15796566e+00 -3.22025204e+00 -3.84387064e+00 -3.57860970e+00 -2.94393444e+00 -1.78306925e+00 -1.54015279e+00 -2.36634278e+00 -2.60706353e+00 -2.09115219e+00 -1.60074854e+00 -1.33497179e+00 -2.50040793e+00 -2.88893580e+00 -3.87202263e+00 -3.73387647e+00 -4.52171516e+00 -4.83032465e+00 -4.45142317e+00 -4.36828709e+00 -3.37099266e+00 -3.23334360e+00 -2.58994555e+00 -2.17031717e+00 -2.26876426e+00 -2.39946961e+00 -2.27619100e+00 -1.95836020e+00 -1.23970556e+00 -2.12216139e+00 -2.26908994e+00 -2.56018782e+00 -1.84117794e+00 -1.94992208e+00 -1.80205536e+00 -1.55541313e+00 -1.22379506e+00 -1.45867395e+00 -1.87315774e+00 -2.54089069e+00 -2.17878556e+00 -1.46284449e+00 -4.87279296e-01 -6.25500202e-01 -1.40909123e+00 -1.57714272e+00 -1.65254271e+00 -1.33030570e+00 -2.09876156e+00 -1.95642161e+00 -1.46959054e+00 -6.53665289e-02 3.99081588e-01 -4.83220816e-01 -1.30921412e+00 -1.58987319e+00 -1.42575812e+00 -9.38487709e-01 -1.46178544e+00 -1.40599322e+00 -2.18675280e+00 -2.83507037e+00 -3.14348292e+00 -2.95577788e+00 -1.30301321e+00 -6.07277811e-01 -1.91404030e-01 -7.92382479e-01 -1.18422890e+00 -8.98003519e-01 1.85099095e-01 1.29246294e+00 9.85311806e-01 6.68033734e-02 -1.17637455e+00 -9.47124600e-01 -1.03973305e+00 3.31440419e-02 -7.83251673e-02 -8.38986933e-02 -1.12318039e+00 -1.16888273e+00 -8.62303019e-01 -4.02833313e-01 -6.65973663e-01 -9.85313416e-01 -8.13915968e-01 -7.70849049e-01 -2.34571785e-01 -7.11549878e-01 -3.72827291e-01 -8.81819487e-01 -5.93737006e-01 -1.28080547e+00 -1.75608814e+00 -9.48041320e-01 5.18625796e-01 7.29162812e-01 6.43997341e-02 -5.63788474e-01 3.29666585e-01 9.70007122e-01 1.36436307e+00 1.75495660e+00 1.90950668e+00 1.87408125e+00 6.77117646e-01 -1.27480403e-01 -4.12584037e-01 2.84044981e-01 1.99523374e-01 -4.10644598e-02 1.55323833e-01 7.75093660e-02 4.23463017e-01 -2.63798125e-02 2.44566455e-01 2.15506390e-01 -6.24157563e-02 -5.07936358e-01 -2.96577781e-01 -1.59613296e-01 2.59099036e-01 3.15515310e-01 5.29675543e-01 1.03649747e+00 5.51134109e-01 8.97720993e-01 8.29796612e-01 8.85165632e-01 -5.76723576e-01 -2.67560810e-01 -3.95924836e-01 6.52444661e-01 -2.28592932e-01 6.67394698e-01 9.04268384e-01 1.36406541e+00 1.12068558e+00 1.31248689e+00 1.54698193e+00 1.16684759e+00 3.15326571e-01 2.08245162e-02 -2.18105197e-01 6.79527760e-01 9.11117315e-01 8.94237041e-01 2.29343653e-01 3.50327611e-01 1.07531095e+00 1.90062571e+00 1.23399043e+00 1.03708124e+00 9.09613788e-01 1.45351064e+00 1.56273544e+00 1.44936121e+00 1.29430437e+00 1.33807278e+00 1.59891725e+00 2.03554845e+00 2.12816668e+00 1.79231739e+00 1.27416444e+00 8.53798866e-01 1.04470921e+00 1.55117357e+00 1.77608740e+00 1.61810791e+00 1.01235032e+00 1.05281866e+00 1.22415113e+00 1.46775043e+00 1.91428137e+00 1.02019989e+00 9.82754350e-01 5.01423955e-01 1.00844681e+00 1.24747682e+00 7.58818328e-01 7.66655266e-01 1.10727811e+00 1.55427527e+00 1.77045691e+00 1.46941113e+00 8.66503000e-01 6.12747610e-01 -4.95271273e-02 1.54573470e-01 1.12100053e+00 2.68684983e+00 2.52401495e+00 2.00658703e+00 1.06632197e+00 2.33615994e+00 2.96026707e+00 3.07129741e+00 1.80930722e+00 1.19077289e+00 4.77924019e-01 6.17732048e-01 7.05696404e-01 2.32694554e+00 3.00765729e+00 3.09781575e+00 2.25863743e+00 3.63023353e+00 2.56109834e+00 2.36212659e+00 8.42925787e-01 1.64541590e+00 1.43459058e+00 1.72995734e+00 1.89699960e+00 2.03806543e+00 2.16576290e+00 1.69667614e+00 2.17919374e+00 2.60541439e+00 3.79291582e+00 3.74641943e+00 3.26108623e+00 2.35448837e+00 1.61862206e+00 1.99191952e+00 2.69657779e+00 3.20374179e+00 2.76662469e+00 2.20200586e+00 1.76952183e+00 2.00564122e+00 2.59735727e+00 3.10003400e+00 2.53954697e+00 2.63757825e+00 2.71660471e+00 2.80161858e+00 2.58359194e+00 3.16081500e+00 4.07381487e+00 3.85957336e+00 3.30230641e+00 2.56658673e+00 3.75106645e+00 3.92081666e+00 4.53421879e+00 3.74294901e+00 4.39744425e+00 4.60921478e+00 5.26884604e+00 5.02304840e+00 5.00929737e+00 4.99290752e+00 4.62826586e+00 4.55327797e+00 4.08995295e+00 4.56896400e+00 4.06647968e+00 3.97996640e+00 2.94158101e+00 3.86954308e+00 3.40672612e+00 4.57153416e+00 3.74264073e+00 3.97913575e+00 3.74732614e+00 4.11425018e+00 4.97762728e+00 5.64879990e+00 6.12385416e+00 6.46974421e+00 5.69173098e+00 5.53693438e+00 4.14400196e+00 3.96416759e+00 3.54704261e+00 4.11747503e+00 3.74996042e+00 4.39601755e+00 5.31177378e+00 5.77120161e+00 5.20269918e+00 4.17622042e+00 3.17759109e+00 3.22292161e+00 3.18555856e+00 4.11678982e+00 4.32081223e+00 4.48966551e+00 5.16731310e+00 5.34528255e+00 5.23879671e+00 4.58961296e+00 4.22948265e+00 5.32111740e+00 6.57318497e+00 6.57581091e+00 5.94780922e+00 5.30081940e+00 5.39646912e+00 4.86637306e+00 5.37190485e+00 5.15509176e+00 5.60304785e+00 5.21851730e+00 5.82470322e+00 5.54749727e+00 5.56372738e+00 5.03031969e+00 4.35233736e+00 3.71730447e+00 3.91348457e+00 5.09073019e+00 6.27704763e+00 5.94765472e+00 4.74841452e+00 4.03072882e+00 4.42986393e+00 5.30810022e+00 5.30927324e+00 5.35748005e+00 6.15362597e+00 6.59890270e+00 6.64211464e+00 6.11491632e+00 5.62900543e+00 6.10984135e+00 6.09967613e+00 6.66988897e+00 6.05881596e+00 5.83366537e+00 5.72339201e+00 6.20265484e+00 6.48142624e+00 6.50731230e+00 5.94323206e+00 5.66482115e+00 5.87315559e+00 6.56505728e+00 6.39793587e+00 5.59347630e+00 5.46745825e+00 5.81268263e+00 6.35981798e+00 5.70662260e+00 5.86130381e+00 5.38534832e+00 5.22486258e+00 5.04456854e+00 5.82453346e+00 6.08710957e+00 6.12694073e+00 5.13374424e+00 6.13724995e+00 6.44879198e+00 6.67836618e+00 5.95424080e+00 5.77043724e+00 6.53331137e+00 6.58628225e+00 6.61964560e+00 6.07617903e+00 5.78592300e+00 5.67511892e+00 5.08548784e+00 5.43086529e+00 5.41680908e+00 6.59333229e+00 6.53525209e+00 6.75442553e+00 6.31851578e+00 6.34200287e+00 6.79335070e+00 6.90480375e+00 7.23373079e+00 6.60900354e+00 6.39997339e+00 6.10930014e+00 6.71980810e+00 7.17812347e+00 7.51403618e+00 7.31262922e+00 7.45545435e+00 7.60592747e+00 7.30222654e+00 6.81889153e+00 5.88598013e+00 6.06194353e+00 5.90470743e+00 6.57903242e+00 6.57596827e+00 7.05383062e+00 6.92664623e+00 6.95513439e+00 6.81600046e+00 6.75170803e+00 6.66442823e+00 6.52220058e+00 6.50076246e+00 7.02768373e+00 6.69486475e+00 6.92142725e+00 6.75970221e+00 7.57098627e+00 7.18796158e+00 6.78151941e+00 6.13577175e+00 7.05686808e+00 7.34141636e+00 7.78304338e+00 7.10501051e+00 7.16779709e+00 7.07182074e+00 7.52518559e+00 7.34533978e+00 7.51819801e+00 7.82510090e+00 8.07305908e+00 8.22598743e+00 7.23024035e+00 6.75967216e+00 6.70131063e+00 7.54729033e+00 8.41374683e+00 8.53860092e+00 8.23072910e+00 7.30783749e+00 7.32926893e+00 7.41021299e+00 7.78393745e+00 7.39639378e+00 7.51356936e+00 8.24122047e+00 9.18847752e+00 9.28108597e+00 8.88162804e+00 7.73875809e+00 7.50024223e+00 7.51169634e+00 7.78176451e+00 7.87311506e+00 7.62921906e+00 8.00174904e+00 8.30171299e+00 8.28321743e+00 8.16075039e+00 7.67870855e+00 7.55858326e+00 7.60112476e+00 8.03391266e+00 8.37489510e+00 8.49992085e+00 8.21305561e+00 8.33448696e+00 8.04135895e+00 8.23311806e+00 8.04865170e+00 8.07825661e+00 7.96546698e+00 7.71733236e+00 7.49825716e+00 7.61834908e+00 7.90199137e+00 7.94317245e+00 7.77774477e+00 7.73811769e+00 8.05969429e+00 8.28838730e+00 8.31510448e+00 8.25415325e+00 8.02739811e+00 8.05681896e+00 8.16091251e+00 8.20785904e+00 8.16837883e+00 8.25831223e+00 8.40962315e+00 8.52588463e+00 8.31472111e+00 8.16279793e+00 7.87263489e+00 7.90821314e+00 8.05164242e+00 8.44945335e+00 8.36779594e+00 8.29769039e+00 8.42419052e+00 8.57084179e+00 8.35691929e+00 8.14822197e+00 8.16915321e+00 8.46487522e+00 8.51034641e+00 8.37666225e+00 8.23616314e+00 7.89350605e+00 7.82652330e+00 7.91752958e+00 8.00397778e+00 8.27332306e+00 8.24674702e+00 8.36492443e+00 8.47162247e+00 8.63829803e+00 8.73738956e+00 8.52393723e+00 8.34757328e+00 8.44888115e+00 8.58879852e+00 8.48470402e+00 8.26881886e+00 8.07984447e+00 8.32816887e+00 8.42523670e+00 8.54226685e+00 8.44904041e+00 8.42800236e+00 8.45990658e+00 8.47783661e+00 8.46732807e+00 8.53562260e+00 8.60869789e+00 8.77841759e+00 8.67554188e+00 8.61468983e+00 8.51876450e+00 8.49990940e+00 8.52764606e+00 8.43922520e+00 8.52412605e+00 8.59480190e+00 8.66391373e+00 8.51374626e+00 8.49393272e+00 8.42964935e+00 8.45472145e+00 8.47502995e+00 8.63164902e+00 8.74092960e+00 8.68767929e+00 8.62708378e+00 8.67585945e+00 8.65178585e+00 8.49622345e+00 8.38552189e+00 8.37565994e+00 8.59020615e+00 8.68761444e+00 8.71854782e+00 8.36289215e+00 7.97305965e+00 5.25890732e+00 -1.25315138e+06 0. 0. 0. 0. 0. 0. 0. 0. 64076936. -20606844. -20606844. -85423088. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -46614904. -81055048. 8.86864853e+01 3.33803215e+01 9.33198261e+00 6.83561325e+00 6.33526373e+00 6.21583939e+00 6.31591702e+00 6.32232237e+00 6.29353952e+00 6.30945635e+00 6.33868504e+00 6.29869938e+00 6.22479343e+00 6.21096659e+00 6.22431278e+00 6.16965103e+00 6.11059666e+00 6.09713125e+00 6.25072432e+00 6.36556387e+00 6.39481783e+00 6.27852821e+00 6.20407963e+00 6.17569256e+00 6.08555555e+00 6.05215549e+00 5.99477100e+00 5.98373842e+00 6.07463646e+00 6.13033342e+00 6.20189524e+00 6.10336113e+00 5.97148418e+00 5.95124769e+00 5.98219252e+00 6.16158199e+00 6.12763691e+00 6.12250233e+00 6.19498587e+00 6.26857519e+00 6.35571432e+00 6.10024548e+00 5.91397619e+00 5.86333418e+00 6.04222012e+00 6.05883312e+00 5.91734028e+00 5.95783949e+00 6.12469530e+00 6.06909609e+00 5.94075727e+00 5.94788551e+00 5.93468428e+00 5.92844439e+00 5.97177410e+00 6.17281675e+00 5.99799156e+00 5.52956200e+00 5.33664799e+00 5.60723543e+00 5.97800159e+00 6.08249521e+00 6.04192066e+00 5.99183750e+00 5.88095999e+00 5.92343092e+00 6.02965069e+00 6.07509327e+00 5.94405413e+00 5.84158897e+00 6.01611090e+00 5.98715687e+00 5.95775461e+00 5.83209324e+00 5.79834747e+00 5.90951300e+00 5.74390078e+00 5.90340710e+00 6.16383171e+00 6.53150654e+00 6.40094614e+00 6.09911394e+00 5.80716276e+00 5.57894182e+00 5.47887087e+00 5.82451630e+00 6.06940794e+00 6.20044136e+00 6.29163265e+00 6.37236357e+00 6.15489388e+00 5.54823589e+00 4.99969006e+00 4.76024866e+00 5.20691061e+00 5.70208311e+00 5.93945837e+00 5.98324347e+00 6.16337824e+00 6.43039846e+00 6.16507816e+00 5.85878277e+00 5.34852362e+00 5.75696850e+00 5.97249794e+00 6.26882410e+00 5.91021585e+00 5.64623976e+00 5.52904749e+00 5.38060045e+00 5.82138252e+00 5.99069166e+00 5.92820740e+00 5.89321804e+00 5.84413433e+00 5.98498249e+00 5.72616720e+00 5.59493494e+00 5.53580284e+00 5.54961634e+00 5.86649370e+00 6.01304054e+00 5.82167959e+00 5.55892086e+00 5.11673403e+00 5.05955839e+00 5.32994413e+00 5.84250879e+00 6.02666378e+00 6.06272316e+00 6.24763107e+00 6.16099882e+00 5.93873596e+00 5.96053314e+00 6.05523396e+00 6.03865433e+00 5.84143400e+00 5.57178831e+00 5.65793562e+00 5.87596560e+00 5.96587706e+00 6.16167307e+00 5.65636253e+00 5.65235996e+00 4.81644440e+00 4.48063374e+00 4.42409468e+00 4.92311954e+00 5.53253651e+00 5.77462530e+00 5.51726961e+00 5.34430647e+00 4.98431587e+00 5.07315874e+00 5.34505415e+00 5.62120914e+00 5.50456810e+00 5.09383917e+00 5.04251146e+00 4.99324417e+00 5.43465662e+00 5.90568304e+00 6.01126051e+00 5.77506065e+00 5.48317051e+00 5.36196661e+00 5.13900518e+00 4.37242365e+00 4.21002102e+00 3.99940777e+00 5.00958109e+00 5.27825594e+00 5.59665966e+00 5.58844757e+00 5.61008883e+00 5.29398584e+00 4.28240538e+00 4.14838219e+00 4.11034822e+00 5.08056831e+00 5.49296904e+00 5.45325327e+00 4.68093252e+00 4.94526291e+00 4.65187120e+00 4.80457163e+00 4.18147850e+00 3.99191332e+00 4.09261513e+00 4.10255766e+00 4.19220781e+00 3.25563407e+00 2.12968016e+00 2.07296681e+00 2.78767776e+00 4.31482458e+00 4.86109161e+00 5.16885948e+00 4.82575369e+00 4.97143507e+00 4.89950943e+00 5.18943596e+00 4.11393881e+00 3.99763083e+00 3.51846981e+00 4.56083345e+00 4.46861362e+00 4.68236923e+00 4.65937185e+00 4.63374424e+00 4.35009670e+00 3.81524396e+00 4.08772373e+00 3.06857657e+00 3.35202718e+00 4.38124418e+00 4.74618292e+00 5.09623051e+00 2.76521730e+00 3.15192747e+00 3.48488140e+00 4.67204571e+00 4.61361408e+00 4.23333168e+00 3.83745503e+00 4.45849466e+00 3.86563540e+00 4.38102913e+00 4.53491259e+00 5.20840931e+00 5.34865808e+00 4.98673868e+00 4.82884455e+00 4.42905378e+00 3.79105973e+00 3.68747163e+00 3.48231411e+00 4.07620621e+00 4.32929850e+00 4.42170429e+00 4.07546568e+00 4.11453009e+00 3.71805406e+00 3.23668003e+00 2.65303111e+00 3.80707574e+00 4.32651711e+00 4.09519958e+00 3.53761768e+00 3.80014968e+00 4.83981943e+00 4.66533470e+00 4.81963778e+00 4.08805323e+00 4.12012291e+00 3.39253950e+00 3.77549100e+00 4.26736689e+00 5.23808098e+00 4.31339025e+00 4.51544285e+00 4.13927650e+00 3.99032974e+00 3.03966331e+00 2.64545774e+00 2.83841729e+00 2.91916060e+00 2.55584812e+00 1.93828940e+00 1.93196607e+00 3.16850734e+00 3.72289205e+00 3.31031513e+00 1.31258416e+00 1.52777243e+00 1.82689404e+00 2.64812326e+00 2.93023467e+00 3.03018832e+00 2.87448478e+00 2.71182799e+00 2.64848948e+00 3.26026368e+00 3.30568266e+00 3.70962620e+00 4.07297945e+00 4.55103493e+00 4.63901949e+00 3.91153097e+00 3.32133389e+00 3.27004504e+00 3.39329886e+00 3.14675713e+00 2.32884049e+00 2.74254847e+00 3.51994276e+00 3.78650618e+00 3.79221320e+00 2.90432858e+00 2.33885503e+00 1.83590388e+00 2.38926363e+00 3.22385359e+00 3.34707403e+00 4.44762182e+00 4.06283617e+00 3.85886312e+00 2.51550651e+00 2.87493229e+00 3.00053430e+00 3.55022430e+00 3.40332055e+00 3.45818567e+00 2.90074182e+00 2.91034365e+00 2.86603713e+00 3.40585780e+00 2.92133546e+00 2.10897875e+00 2.06243277e+00 2.36452174e+00 3.09443951e+00 1.71910644e+00 1.02242625e+00 1.09281576e+00 2.78399754e+00 2.71255589e+00 2.86811471e+00 2.55380273e+00 3.56957722e+00 3.31672406e+00 3.58667254e+00 3.71429443e+00 3.99579501e+00 3.86966944e+00 3.30967712e+00 3.44099736e+00 2.93956923e+00 2.32706523e+00 2.19144964e+00 2.19562268e+00 2.16352963e+00 1.79412401e+00 1.03193092e+00 2.37471390e+00 2.52606702e+00 3.34962726e+00 2.52058339e+00 3.53310513e+00 3.18243313e+00 2.60832357e+00 9.25897777e-01 1.85303605e+00 3.44184971e+00 4.15515280e+00 3.65275979e+00 1.97432661e+00 1.41512787e+00 9.33792770e-01 1.64097536e+00 2.40158963e+00 2.45844960e+00 2.00282669e+00 7.12516129e-01 2.94491082e-01 -3.11420202e-01 6.03030205e-01 9.80289221e-01 1.23959005e+00 8.34239900e-01 5.84559917e-01 1.26905966e+00 1.91569436e+00 2.29693031e+00 2.59648347e+00 1.55462122e+00 6.11401021e-01 -3.54948431e-01 5.66181600e-01 1.48792326e+00 1.64089632e+00 9.93651628e-01 6.47632897e-01 1.22386956e+00 2.56513238e+00 2.21040964e+00 1.61494625e+00 8.54817748e-01 -4.87412177e-02 8.30579519e-01 -1.55780151e-01 1.20573962e+00 6.39370322e-01 9.63597834e-01 1.88341546e+00 1.80357885e+00 9.26156640e-01 -2.25566819e-01 -2.24282086e-01 7.56115377e-01 3.96516621e-01 -3.58674049e-01 4.07268673e-01 8.43667746e-01 1.46866739e+00 -6.74675465e-01 -1.03878736e+00 -1.44199026e+00 -2.49932140e-01 1.10372579e+00 1.48306739e+00 2.35826111e+00 1.26300585e+00 1.02179098e+00 3.14359754e-01 2.99716443e-01 -3.22049260e-01 -3.46581303e-02 -2.89104342e-01 -8.44736993e-01 -1.17360342e+00 2.82966405e-01 1.54893088e+00 7.40089238e-01 1.48929358e-01 3.02890748e-01 4.05638844e-01 -8.21600020e-01 -1.18268836e+00 4.20361347e-02 -1.25058308e-01 -8.21893990e-01 -1.77217531e+00 -1.08411896e+00 4.65388209e-01 8.18372369e-01 1.77191645e-01 -5.59866667e-01 -7.43709803e-01 -6.23522162e-01 -1.92261946e+00 -1.74313104e+00 -8.72854173e-01 1.02556206e-01 -2.56699204e-01 -2.02774048e+00 -1.82919812e+00 -2.01512218e+00 -8.24453115e-01 4.08452392e-01 1.54125616e-01 -6.39255643e-01 -1.77894771e+00 -1.11813557e+00 -2.91015863e-01 -5.43842435e-01 -2.51056645e-02 -2.78480709e-01 6.21137209e-02 -1.66670848e-02 -1.78251579e-01 -4.78644103e-01 -2.75156319e-01 -2.67101467e-01 1.56636059e-01 -5.83238900e-01 -1.02183974e+00 -1.68021512e+00 -1.36072385e+00 -6.93118989e-01 -1.11642528e+00 -6.13317847e-01 -5.61818242e-01 7.76670635e-01 9.24898684e-02 -6.17153943e-01 -2.06140471e+00 -1.54404294e+00 -1.05894125e+00 -4.99502063e-01 -1.12858355e+00 -4.92273778e-01 -5.53533673e-01 -2.56217152e-01 -8.57815385e-01 -6.14537656e-01 -8.17431688e-01 2.54446507e-01 -8.66329014e-01 -9.49336708e-01 -1.57387459e+00 -5.55496216e-01 -3.11699450e-01 -1.05222948e-01 1.43744290e-01 -6.46840215e-01 -1.90866077e+00 -2.38524961e+00 -2.02747154e+00 -1.80355513e+00 -2.01777387e+00 -3.06106400e+00 -2.51070786e+00 -1.87370682e+00 -4.27797556e-01 -9.78315413e-01 -9.35194075e-01 -1.70199430e+00 -2.16088462e+00 -2.43210602e+00 -2.20299840e+00 -1.24570155e+00 -1.19393766e+00 -1.22942352e+00 -1.27111018e+00 -2.06600881e+00 -3.02332711e+00 -2.36733723e+00 -1.47054768e+00 -5.72622240e-01 -1.71178198e+00 -2.50361443e+00 -2.23948574e+00 -1.13212633e+00 -8.20954859e-01 -1.49650013e+00 -2.29039741e+00 -2.08264804e+00 -1.40413237e+00 -1.32472444e+00 -1.11216187e+00 -9.33747470e-01 -1.08428013e+00 -1.75678468e+00 -1.78217518e+00 -1.57461667e+00 -1.00827360e+00 -8.08037460e-01 -1.26378441e+00 -1.16935337e+00 -2.15744638e+00 -1.27100515e+00 -1.39297843e+00 -7.70248413e-01 -9.57555950e-01 -1.82743442e+00 -1.80650198e+00 -1.69627130e+00 -1.28390157e+00 -1.31852913e+00 -1.88084197e+00 -1.63097894e+00 -2.18431282e+00 -1.94404614e+00 -1.36647475e+00 -1.01052940e+00 -1.25102651e+00 -1.94977188e+00 -2.67938781e+00 -3.05648565e+00 -3.42105484e+00 -3.84205818e+00 -3.59870434e+00 -2.91430736e+00 -2.37031889e+00 -2.86586499e+00 -3.41382599e+00 -3.14000964e+00 -2.97581911e+00 -3.24015450e+00 -3.46975493e+00 -3.51037288e+00 -3.11199880e+00 -2.46351314e+00 -2.95848703e+00 -4.05866718e+00 -4.81060266e+00 -4.26208305e+00 -3.60260081e+00 -4.49941969e+00 -4.55330181e+00 -4.49819279e+00 -3.79035640e+00 -4.19254971e+00 -3.91443992e+00 -4.01264858e+00 -3.49270296e+00 -3.73367882e+00 -3.25222921e+00 -3.13222814e+00 -3.09836030e+00 -3.17192745e+00 -3.07490516e+00 -2.76766276e+00 -2.09638500e+00 -3.03211761e+00 -3.47684789e+00 -4.38835812e+00 -3.76554418e+00 -3.40012050e+00 -3.67738795e+00 -4.28655434e+00 -5.36542988e+00 -4.80755234e+00 -4.38567686e+00 -3.52971220e+00 -3.80709004e+00 -3.63741302e+00 -4.18459892e+00 -3.60047936e+00 -4.63464546e+00 -4.01809263e+00 -4.58849335e+00 -3.33341455e+00 -3.75520825e+00 -5.71987391e+00 -7.55150700e+00 -1.13752155e+01 -1.07205772e+01 -2.29304962e+01 -4.09081421e+01 -2.05924576e+02 -2.76429657e+02 7.83736450e+02 3.42581543e+03 119133344. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -267719120. 2.75938989e+03 4.91176605e+02 7.49199295e+01 3.36793442e+01 1.66897411e+01 2.75484848e+00 -1.63865495e+00 -3.68710876e+00 -4.00007296e+00 -4.07700014e+00 -4.38188744e+00 -4.66165781e+00 -4.37766552e+00 -4.29248619e+00 -4.31084919e+00 -4.30814028e+00 -4.02851343e+00 -4.42689276e+00 -4.63965321e+00 -5.16099644e+00 -4.85203266e+00 -5.36141109e+00 -5.03188515e+00 -5.11114836e+00 -4.89060402e+00 -4.42586946e+00 -4.84310961e+00 -4.78269196e+00 -4.83732367e+00 -3.95476604e+00 -3.69754529e+00 -4.63840389e+00 -5.25160837e+00 -5.32585573e+00 -5.01821804e+00 -5.15473890e+00 -5.05072021e+00 -4.92798853e+00 -4.88573217e+00 -5.12157917e+00 -5.02911806e+00 -5.12241936e+00 -4.76499510e+00 -4.97866392e+00 -5.46246338e+00 -5.80427217e+00 -6.34633112e+00 -5.62328959e+00 -5.77258968e+00 -5.19533730e+00 -5.23482370e+00 -5.51177931e+00 -5.51374292e+00 -5.45127630e+00 -5.00065851e+00 -5.21324825e+00 -5.39959335e+00 -5.48476601e+00 -5.55005646e+00 -5.83220148e+00 -6.08177471e+00 -6.26785278e+00 -5.98563766e+00 -6.07936144e+00 -6.06622076e+00 -5.83191109e+00 -5.48613167e+00 -5.20057154e+00 -5.36704826e+00 -5.53402472e+00 -5.99406624e+00 -6.60633326e+00 -6.81101942e+00 -6.60313797e+00 -5.84805679e+00 -5.50262165e+00 -5.60836315e+00 -5.44841242e+00 -5.15715218e+00 -4.84228992e+00 -5.34277964e+00 -6.01587772e+00 -5.93081141e+00 -5.77142668e+00 -5.44614697e+00 -5.39178324e+00 -5.48214626e+00 -5.45246410e+00 -5.71519423e+00 -5.44872093e+00 -5.38460875e+00 -5.20790672e+00 -5.77259111e+00 -6.34592819e+00 -6.21480703e+00 -5.92883539e+00 -5.86331224e+00 -5.88210011e+00 -5.73697186e+00 -5.39473438e+00 -5.48002386e+00 -5.84619331e+00 -5.93374348e+00 -5.81426239e+00 -5.50212479e+00 -5.37052536e+00 -5.57597351e+00 -5.51257277e+00 -5.54789209e+00 -5.55072498e+00 -5.78760624e+00 -6.01098251e+00 -6.24950886e+00 -6.04904175e+00 -5.84539795e+00 -5.74025297e+00 -5.67937708e+00 -5.47398996e+00 -5.29958391e+00 -5.37519741e+00 -5.51468706e+00 -5.70123434e+00 -5.65262461e+00 -5.52781820e+00 -5.17669630e+00 -5.10758972e+00 -5.43569899e+00 -5.79344177e+00 -5.72327662e+00 -5.60192823e+00 -5.50566006e+00 -5.70505714e+00 -5.81317949e+00 -5.93720961e+00 -6.23669481e+00 -6.17302847e+00 -6.00620842e+00 -5.74168158e+00 -5.81105328e+00 -6.10074282e+00 -6.08315039e+00 -6.01533937e+00 -5.77054262e+00 -5.93046904e+00 -6.08225965e+00 -6.21755934e+00 -6.29754019e+00 -6.33129549e+00 -6.37052822e+00 -6.32557631e+00 -6.15064287e+00 -6.18393660e+00 -6.15205908e+00 -6.22577953e+00 -6.05834103e+00 -5.87135172e+00 -5.83062649e+00 -5.71213818e+00 -6.03507757e+00 -6.05565786e+00 -6.29507589e+00 -6.31142473e+00 -6.38091564e+00 -6.31465006e+00 -6.23165083e+00 -6.18349314e+00 -6.23314619e+00 -6.08560181e+00 -6.10123253e+00 -5.95607090e+00 -5.89668608e+00 -6.08416796e+00 -6.22345829e+00 -6.29724407e+00 -6.18565655e+00 -6.11603212e+00 -6.14540625e+00 -6.12719965e+00 -6.15671873e+00 -6.17346811e+00 -6.08687210e+00 -6.02819109e+00 -5.93319464e+00 -6.07819223e+00 -6.10837460e+00 -6.22806263e+00 -6.20765686e+00 -6.13689613e+00 -6.02093363e+00 -6.17493963e+00 -6.38763142e+00 -6.37923527e+00 -6.21053457e+00 -6.07135963e+00 -6.07550287e+00 -6.14860773e+00 -6.24710417e+00 -6.28138018e+00 -6.18504429e+00 -6.11040640e+00 -6.16212511e+00 -6.21792173e+00 -6.23107862e+00 -6.21297789e+00 -6.18464231e+00 -6.23987770e+00 -6.26708937e+00 -6.25463724e+00 -6.21962881e+00 -6.23381805e+00 -6.25116634e+00 -6.22263718e+00 -6.19952822e+00 -6.20919323e+00 -6.21698570e+00 -6.20376873e+00 -6.22490883e+00 -6.23090553e+00 -6.22018003e+00 -6.20211840e+00 -6.19686985e+00 -6.19205332e+00 -6.20105267e+00 -6.21016121e+00 -6.21369934e+00 -6.21309423e+00 -6.21490860e+00 -6.21096945e+00 -6.20475006e+00 -6.18298435e+00 -6.18239260e+00 -6.19875717e+00 -6.20716763e+00 -6.20786858e+00 -6.19082355e+00 -6.19479942e+00 -6.14774799e+00 -6.12415981e+00 -6.09052324e+00 -6.10758114e+00 -6.11627102e+00 -6.17203951e+00 -6.18799114e+00 -6.19458675e+00 -6.25526524e+00 -6.22535515e+00 -6.24957657e+00 -6.14524937e+00 -6.13616848e+00 -6.12454557e+00 -6.15857697e+00 -6.14648914e+00 -6.10392666e+00 -6.08288527e+00 -6.07354355e+00 -6.08073282e+00 -6.09302330e+00 -6.16133165e+00 -6.20071125e+00 -6.19456244e+00 -6.20497322e+00 -6.20825958e+00 -6.24723768e+00 -6.18104124e+00 -6.20377159e+00 -6.10183191e+00 -6.26445103e+00 -6.22511005e+00 -6.26780558e+00 -6.09676933e+00 -6.16811562e+00 -6.24466991e+00 -6.29329729e+00 -6.14439917e+00 -6.05610991e+00 -6.11000252e+00 -6.14974546e+00 -6.15351820e+00 -6.11801815e+00 -6.16745996e+00 -6.14316368e+00 -6.08733225e+00 -6.28327227e+00 -6.20794344e+00 -6.31592894e+00 -6.03432560e+00 -6.11271572e+00 -6.24283695e+00 -6.35963011e+00 -6.40710115e+00 -6.25970888e+00 -6.15329218e+00 -6.03167009e+00 -5.99289703e+00 -5.95596981e+00 -5.84940624e+00 -5.78465319e+00 -5.60537100e+00 -5.93791389e+00 -5.86748362e+00 -5.94174862e+00 -6.09968615e+00 -5.97768784e+00 -6.16478586e+00 -5.91155720e+00 -6.00923634e+00 -5.97042561e+00 -6.16245556e+00 -6.22152233e+00 -6.32722807e+00 -5.98100805e+00 -6.00201035e+00 -5.76740742e+00 -5.77614164e+00 -5.59923315e+00 -5.55668640e+00 -5.49648905e+00 -5.80390787e+00 -5.91985273e+00 -5.87474489e+00 -5.85319996e+00 -6.36806297e+00 -6.59209871e+00 -6.41569614e+00 -6.02381563e+00 -5.97269773e+00 -6.07231998e+00 -5.91170740e+00 -5.72160673e+00 -5.61976337e+00 -5.62166214e+00 -5.88735819e+00 -5.82209587e+00 -5.75182343e+00 -5.73807096e+00 -5.86273909e+00 -5.69724751e+00 -5.50333071e+00 -5.22289467e+00 -5.52634764e+00 -5.65793991e+00 -5.84998512e+00 -5.60769749e+00 -5.51811504e+00 -5.51406240e+00 -5.58826399e+00 -5.71158266e+00 -5.63991213e+00 -5.47982597e+00 -5.22234678e+00 -5.08780098e+00 -5.13509321e+00 -5.20856714e+00 -5.59103775e+00 -5.85191822e+00 -6.01854229e+00 -5.72157478e+00 -6.11425877e+00 -5.83012819e+00 -5.83458996e+00 -5.52792597e+00 -5.41818619e+00 -5.28287935e+00 -5.40024662e+00 -5.62202978e+00 -6.20694923e+00 -5.92836905e+00 -6.09633350e+00 -5.91777420e+00 -5.56572008e+00 -5.53600788e+00 -4.99929094e+00 -5.15790892e+00 -4.88137960e+00 -5.53504133e+00 -5.70241165e+00 -6.26911926e+00 -5.80810022e+00 -5.62676668e+00 -5.19198275e+00 -5.25239229e+00 -5.29794931e+00 -5.70213270e+00 -5.57358837e+00 -5.66241074e+00 -5.21853638e+00 -5.46938562e+00 -5.63754845e+00 -5.73249006e+00 -5.79998159e+00 -5.49628019e+00 -5.34767675e+00 -5.06330252e+00 -5.35066128e+00 -5.48139715e+00 -5.12665224e+00 -5.20297956e+00 -5.60857868e+00 -6.14399290e+00 -5.57247734e+00 -5.40151691e+00 -5.21773911e+00 -5.44714260e+00 -5.11238909e+00 -4.60430193e+00 -4.29935408e+00 -4.14017677e+00 -5.11963320e+00 -5.39310980e+00 -5.33025885e+00 -4.83096027e+00 -4.96427250e+00 -5.18947744e+00 -5.24108982e+00 -4.76481724e+00 -4.92117882e+00 -4.50251055e+00 -4.72122622e+00 -4.23638487e+00 -4.39844275e+00 -4.40134859e+00 -4.46666908e+00 -4.65480185e+00 -4.70817089e+00 -4.98968744e+00 -5.25417995e+00 -5.30477047e+00 -5.31912041e+00 -5.14288712e+00 -5.23977804e+00 -5.29773617e+00 -5.17058468e+00 -4.96403885e+00 -4.80287218e+00 -4.75511742e+00 -4.61971283e+00 -4.25766325e+00 -4.18585539e+00 -4.17894983e+00 -4.52236462e+00 -4.63222027e+00 -4.71952438e+00 -4.38838720e+00 -4.33810949e+00 -4.61393166e+00 -4.80240059e+00 -4.59829283e+00 -5.07979918e+00 -5.96345997e+00 -6.51173830e+00 -5.78015709e+00 -4.80735493e+00 -3.64470053e+00 -3.58906960e+00 -3.43454266e+00 -3.69141960e+00 -1.92867351e+00 -9.64956701e-01 1.08589134e+01 1.87335587e+01 1.28292637e+01 1.35115158e+02 4.99129333e+01 -4.24520557e+03 -148975744. 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. 0. 0. 0. 0. 0. 0. 5.67918062e+05 2.23162888e+02 2.64486370e+01 -4.39610634e+01 -8.93550491e+00 -6.09193850e+00 -4.38489437e+00 -3.19431829e+00 -4.15485477e+00 -4.25527668e+00 -4.32081938e+00 -3.91432381e+00 -3.51467133e+00 -3.47306418e+00 -3.27118850e+00 -3.24773335e+00 -3.73097968e+00 -3.96187449e+00 -4.00453186e+00 -3.34263134e+00 -2.96176577e+00 -2.49167705e+00 -2.80265951e+00 -3.54936695e+00 -3.69132996e+00 -3.41315937e+00 -2.60746336e+00 -2.52179718e+00 -2.69483232e+00 -2.98479342e+00 -3.40885520e+00 -3.54730678e+00 -3.57654548e+00 -3.08502817e+00 -2.95336056e+00 -3.03480864e+00 -2.87451148e+00 -2.80747151e+00 -2.75087094e+00 -2.77660179e+00 -2.80086875e+00 -2.72733593e+00 -3.09067273e+00 -3.11964059e+00 -2.90515995e+00 -2.64381719e+00 -2.50789618e+00 -2.42337584e+00 -2.41722059e+00 -1.82298696e+00 -1.93241191e+00 -1.72700191e+00 -2.74077964e+00 -2.56150723e+00 -2.63313556e+00 -2.22774816e+00 -2.07181025e+00 -2.21238375e+00 -2.27218771e+00 -2.33580804e+00 -2.18183613e+00 -1.83710074e+00 -2.23130870e+00 -2.84870839e+00 -3.09421492e+00 -3.22274780e+00 -3.11146021e+00 -3.23690176e+00 -3.08169436e+00 -2.59807611e+00 -2.52984667e+00 -2.39427042e+00 -2.34766150e+00 -2.38794470e+00 -2.13614941e+00 -1.56126177e+00 -1.47436833e+00 -1.60944057e+00 -2.13714767e+00 -2.18526983e+00 -1.87520087e+00 -1.80356610e+00 -1.31467748e+00 -1.40400255e+00 -1.67630637e+00 -2.09132409e+00 -2.52455449e+00 -2.52005005e+00 -2.31368780e+00 -1.81774831e+00 -1.95822096e+00 -1.85774493e+00 -2.54320812e+00 -2.74002409e+00 -2.58488059e+00 -2.11265159e+00 -1.61278009e+00 -1.97094190e+00 -1.93187964e+00 -2.26807690e+00 -2.40562868e+00 -2.32299685e+00 -1.51835990e+00 -1.15376031e+00 -9.02959764e-01 -1.26728189e+00 -1.54188764e+00 -1.77796841e+00 -2.04118562e+00 -1.98593593e+00 -2.11269498e+00 -1.86603129e+00 -1.58249795e+00 -1.35415936e+00 -1.27448845e+00 -1.31034625e+00 -9.18901622e-01 -6.05843961e-01 -4.38306421e-01 -1.15097034e+00 -1.59757936e+00 -1.57847822e+00 -1.27119780e+00 -6.00607336e-01 -6.94308341e-01 -8.49762380e-01 -1.12945569e+00 -1.48055816e+00 -1.51302660e+00 -1.76599908e+00 -1.30950677e+00 -8.91039729e-01 -5.46336889e-01 -1.16712677e+00 -2.01699162e+00 -2.24648881e+00 -2.12373686e+00 -1.44400513e+00 -1.41278732e+00 -7.94359446e-01 -3.83072644e-01 -3.66051435e-01 -3.24844241e-01 -1.33010224e-01 7.78203830e-03 1.44510493e-01 -1.45905033e-01 -2.76143670e-01 -4.19068575e-01 -5.39227128e-01 -4.93031219e-02 8.70757457e-03 -9.82477609e-03 -9.03627515e-01 -1.29358673e+00 -7.32108176e-01 -4.37250048e-01 1.21199444e-01 -6.74588740e-01 -9.50288951e-01 -1.67280328e+00 -1.95125437e+00 -1.72791171e+00 -1.44732952e+00 -6.49776578e-01 -1.23609141e-01 2.73044199e-01 2.46662602e-01 -7.21924081e-02 -3.29273164e-01 -5.24409950e-01 -3.50860655e-01 5.82582830e-03 -1.85764819e-01 -4.98133093e-01 -6.75895989e-01 -6.08986244e-03 7.83207059e-01 9.64956820e-01 2.57614195e-01 -1.02324530e-01 -2.91625053e-01 2.07931012e-01 -2.53673494e-01 -1.90904513e-01 -6.51384115e-01 -5.90863347e-01 -2.26746991e-01 1.35434285e-01 4.92013603e-01 -1.17710028e-02 1.49708286e-01 -3.84409726e-02 3.97471517e-01 6.35205269e-01 8.26373160e-01 9.99137938e-01 6.59565508e-01 9.96214807e-01 1.12703860e+00 1.10834742e+00 1.03723121e+00 1.23008907e+00 1.51028085e+00 1.56434727e+00 1.06526768e+00 9.38232780e-01 4.03298467e-01 4.78905082e-01 5.02296686e-01 4.42589760e-01 5.56620538e-01 6.06510520e-01 9.33453560e-01 5.91240168e-01 3.42405736e-01 3.67764711e-01 6.24846160e-01 8.02522480e-01 1.11213589e+00 1.24127388e+00 1.65961099e+00 1.64698577e+00 1.23087835e+00 9.33599412e-01 5.93751609e-01 8.96170497e-01 1.30459392e+00 1.50502169e+00 1.49224901e+00 1.49582160e+00 1.75137889e+00 1.72251689e+00 1.68177116e+00 1.55467463e+00 1.51821315e+00 1.56188238e+00 1.64491296e+00 1.72685719e+00 1.46513379e+00 1.34840846e+00 1.30368483e+00 1.28023899e+00 1.14002633e+00 1.78228974e+00 2.54325318e+00 2.81283522e+00 2.44981599e+00 1.43370092e+00 1.35912156e+00 1.44775450e+00 2.08775020e+00 2.32100987e+00 1.60909736e+00 8.48589122e-01 6.05691671e-01 8.72665644e-01 1.56023443e+00 1.33234537e+00 1.58837163e+00 1.57763171e+00 1.80092680e+00 1.85487986e+00 1.63036823e+00 1.69965696e+00 1.39114404e+00 1.35947454e+00 1.26798940e+00 1.09313178e+00 1.10946202e+00 1.19224620e+00 1.03567624e+00 1.41111159e+00 1.47644484e+00 2.18426466e+00 1.89935696e+00 1.82855773e+00 2.05778933e+00 1.13489449e+00 1.01513362e+00 5.32540023e-01 1.59458232e+00 2.06075120e+00 2.63816142e+00 1.92931151e+00 1.78984320e+00 1.71895850e+00 2.63473988e+00 3.04430580e+00 2.80049872e+00 2.87820125e+00 2.60338902e+00 3.21069980e+00 3.31583500e+00 3.37939405e+00 2.51323199e+00 2.11558485e+00 1.87876749e+00 2.06191969e+00 2.21336508e+00 2.74637914e+00 2.88409257e+00 2.79822016e+00 2.61754513e+00 3.10570669e+00 2.91588593e+00 2.08646846e+00 1.90296745e+00 1.91785145e+00 2.69653654e+00 2.43295383e+00 2.68855596e+00 2.64581037e+00 2.97842026e+00 2.90199590e+00 3.20348716e+00 3.11511326e+00 2.93469501e+00 2.39734292e+00 2.42791033e+00 2.50374794e+00 2.99796581e+00 3.08550882e+00 3.09253836e+00 2.94088602e+00 2.83665943e+00 2.72231269e+00 2.55900574e+00 2.07035756e+00 1.98584044e+00 2.19927716e+00 2.54142523e+00 3.39244175e+00 3.26658702e+00 3.54354143e+00 3.04802513e+00 3.64082575e+00 3.36782789e+00 3.09732556e+00 2.84532690e+00 3.44810843e+00 4.43959332e+00 4.49225092e+00 4.29500103e+00 3.57766628e+00 3.61403346e+00 3.89721036e+00 3.75918341e+00 3.35865831e+00 2.99538112e+00 3.81099272e+00 4.31124687e+00 4.62748909e+00 4.56047010e+00 4.31187391e+00 4.46220779e+00 3.71642947e+00 3.88542056e+00 3.64142346e+00 4.11524105e+00 4.00154877e+00 3.88298297e+00 3.94442964e+00 3.97729039e+00 4.02740002e+00 4.07294416e+00 3.63215971e+00 3.41666746e+00 3.23517561e+00 3.74214530e+00 4.14824390e+00 3.72848558e+00 3.24068713e+00 3.10525179e+00 3.71494436e+00 3.70077825e+00 3.54346704e+00 3.54334736e+00 3.55782819e+00 3.97673845e+00 3.55384183e+00 4.09648418e+00 3.73703551e+00 3.85894489e+00 4.06704664e+00 4.22995615e+00 4.09983492e+00 3.76520705e+00 3.64984751e+00 4.06365442e+00 3.89908624e+00 3.97994781e+00 3.79229355e+00 3.91133761e+00 4.06895542e+00 3.91001010e+00 4.03022099e+00 3.71859598e+00 4.31515789e+00 4.57880211e+00 4.44935799e+00 3.90103865e+00 3.76551771e+00 4.14515066e+00 4.25453234e+00 4.15851545e+00 4.01666355e+00 4.21065664e+00 4.76991463e+00 4.94431734e+00 5.25669718e+00 4.94393826e+00 4.96621895e+00 4.48747587e+00 4.48916674e+00 4.79866886e+00 4.77763271e+00 4.31440973e+00 4.24164820e+00 4.30052376e+00 4.46746635e+00 4.54861116e+00 4.59950876e+00 4.95509624e+00 4.88511181e+00 5.06791067e+00 4.71372700e+00 4.75070715e+00 4.96933079e+00 4.99722958e+00 4.88643169e+00 4.64437962e+00 5.03676271e+00 4.90025377e+00 5.05785465e+00 5.05522966e+00 5.54704523e+00 5.31259966e+00 5.05708981e+00 4.91400528e+00 5.03499746e+00 5.20582533e+00 4.68012619e+00 4.78276110e+00 4.83983374e+00 5.20232248e+00 5.13496351e+00 5.41440153e+00 5.58146095e+00 5.74814510e+00 5.37971783e+00 5.08497238e+00 5.21780968e+00 5.32264900e+00 5.50139380e+00 5.21606636e+00 5.04912710e+00 5.04508257e+00 4.81523800e+00 4.82609177e+00 4.80616617e+00 5.25612450e+00 5.45791483e+00 5.28450489e+00 5.28659010e+00 5.46721601e+00 5.51513529e+00 5.27920198e+00 5.13050413e+00 5.43842506e+00 5.38270807e+00 5.39015579e+00 5.22202206e+00 5.22690105e+00 5.31869173e+00 5.04105091e+00 5.08351135e+00 4.96420670e+00 5.20907354e+00 5.14044809e+00 5.48381472e+00 5.79293966e+00 5.91966343e+00 5.40125751e+00 5.43096972e+00 5.70069504e+00 5.96345663e+00 5.73941517e+00 5.38812923e+00 5.80753613e+00 5.77088976e+00 5.99595213e+00 5.72354984e+00 6.14705944e+00 6.34357738e+00 6.49627399e+00 6.05181599e+00 5.69345617e+00 5.81508160e+00 6.26127481e+00 6.75818062e+00 6.67480040e+00 6.55071163e+00 6.57902575e+00 6.44725800e+00 6.44045401e+00 5.97847271e+00 5.68760633e+00 5.45800257e+00 5.33442020e+00 5.24068880e+00 5.39311886e+00 5.77545595e+00 6.03812313e+00 5.98663425e+00 5.69291306e+00 5.80429840e+00 5.92858267e+00 6.13599205e+00 6.24494410e+00 6.27712202e+00 6.31020021e+00 6.09119034e+00 5.81410408e+00 5.77259731e+00 5.87352800e+00 5.97438478e+00 6.05483150e+00 5.92085600e+00 5.91560268e+00 5.94342422e+00 6.11137486e+00 6.16178036e+00 6.11615181e+00 6.05655050e+00 5.96904039e+00 5.99285412e+00 6.00866938e+00 6.27290583e+00 6.36635160e+00 6.43212891e+00 5.97575665e+00 5.70431805e+00 5.53713226e+00 5.86661434e+00 5.90912294e+00 5.95362520e+00 5.64103794e+00 5.63028431e+00 5.73189640e+00 5.88062143e+00 5.97607470e+00 5.91652536e+00 5.92095184e+00 6.06293201e+00 6.08223963e+00 6.10348797e+00 5.98474455e+00 5.86505842e+00 6.04908228e+00 6.07230043e+00 6.08218622e+00 5.97979784e+00 5.95609951e+00 6.02284050e+00 6.07813454e+00 6.11349106e+00 6.04624987e+00 6.00603008e+00 5.95973349e+00 6.02049160e+00 6.05056190e+00 6.09622335e+00 6.20039368e+00 6.13315582e+00 6.06633568e+00 5.93047476e+00 5.86444902e+00 5.89428806e+00 5.95973301e+00 6.10200644e+00 6.15187836e+00 6.20254517e+00 6.14392376e+00 6.13126659e+00 6.09011459e+00 6.17370844e+00 6.22007656e+00 6.18240595e+00 6.11023951e+00 6.16339540e+00 6.17606258e+00 6.20434856e+00 6.17905569e+00 6.28915644e+00 6.23972368e+00 6.23498440e+00 6.16129017e+00 6.29369164e+00 6.32414532e+00 6.41645670e+00 6.35774136e+00 6.29230070e+00 6.15915918e+00 6.15246105e+00 6.17113638e+00 6.14438200e+00 5.23421574e+00 5.55842018e+00 4.95704746e+00 1.64827824e+01 -81505232. 0. 0. 0. 0. 22237478. -42227944. 90862520. 16297160. 1.91553059e+01 -5.01517181e+01 -1.38811462e+02 -85423088. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -46614904. -81055048. -59658888. 1.31698624e+02 5.85512886e+01 1.90352879e+01 1.79404411e+01 1.57537651e+01 1.51433964e+01 1.45911045e+01 1.44016991e+01 1.53552990e+01 1.64665108e+01 1.65320358e+01 1.61428185e+01 1.58335800e+01 1.53279419e+01 1.50767794e+01 1.47340298e+01 1.53180523e+01 1.62392082e+01 1.71744499e+01 1.71572914e+01 1.55633430e+01 1.39790268e+01 1.29100008e+01 1.26910095e+01 1.35575981e+01 1.35136480e+01 1.36155882e+01 1.51411877e+01 1.62031040e+01 1.56732435e+01 1.31725159e+01 1.11826200e+01 1.11209965e+01 1.25640249e+01 1.52347479e+01 1.61948242e+01 1.60055027e+01 1.59136705e+01 1.58263760e+01 1.55517559e+01 1.36116028e+01 1.18646822e+01 1.24567585e+01 1.43729858e+01 1.54473038e+01 1.41023045e+01 1.39176922e+01 1.43839817e+01 1.33991613e+01 1.32608576e+01 1.34945650e+01 1.46965866e+01 1.62097588e+01 1.72117481e+01 1.78320084e+01 1.45524540e+01 1.02659111e+01 8.84111500e+00 1.11884193e+01 1.55465345e+01 1.61804829e+01 1.47191858e+01 1.33183489e+01 1.37178507e+01 1.45130539e+01 1.37645836e+01 1.26592464e+01 1.22942533e+01 1.44763002e+01 1.75288391e+01 1.66460934e+01 1.57112236e+01 1.42414112e+01 1.35055799e+01 1.33739767e+01 1.24293747e+01 1.40413733e+01 1.67823505e+01 1.96296635e+01 1.98356209e+01 1.65816936e+01 1.30351677e+01 9.93225670e+00 9.65191841e+00 1.30268822e+01 1.46215267e+01 1.48921089e+01 1.66822929e+01 1.99702606e+01 1.99395180e+01 1.43795471e+01 8.64882851e+00 8.60504818e+00 1.40182676e+01 1.93161659e+01 1.96542702e+01 1.84971657e+01 1.92087288e+01 1.94912872e+01 1.78399277e+01 1.48989582e+01 1.30245857e+01 1.52507210e+01 1.79140186e+01 1.86557732e+01 1.51242237e+01 1.09998198e+01 9.01757145e+00 9.03984642e+00 1.36384802e+01 1.73395824e+01 1.68421822e+01 1.59574099e+01 1.73006134e+01 1.86064358e+01 1.61930790e+01 1.12594728e+01 1.12589388e+01 1.67060165e+01 2.23798580e+01 2.35441399e+01 1.86355896e+01 1.44189720e+01 9.85398769e+00 8.04561424e+00 1.08032780e+01 1.34808817e+01 1.51777706e+01 1.87887058e+01 2.28292847e+01 2.30646973e+01 1.93361893e+01 1.51691055e+01 1.26769361e+01 1.20075388e+01 1.35705080e+01 1.53882141e+01 1.68504143e+01 1.87839680e+01 2.09879761e+01 2.12680683e+01 1.58370333e+01 9.14763451e+00 4.55310774e+00 6.16619349e+00 8.76830006e+00 1.08763609e+01 1.41193113e+01 1.60229034e+01 1.44652548e+01 1.33245134e+01 9.44664478e+00 7.79856825e+00 8.83052063e+00 1.34823465e+01 1.52918615e+01 1.19298840e+01 7.39263248e+00 9.41233540e+00 1.48488169e+01 1.86055145e+01 1.42513151e+01 8.65974140e+00 9.47154331e+00 1.01754951e+01 9.99374104e+00 2.93524766e+00 -1.46859026e+00 -2.33136916e+00 7.01346922e+00 1.75001125e+01 2.06171055e+01 2.00448360e+01 1.95230732e+01 1.76107979e+01 1.36311712e+01 5.74687672e+00 3.99157524e+00 1.03254709e+01 1.85981827e+01 2.04534798e+01 1.25846977e+01 7.65676403e+00 5.92957401e+00 6.09292269e+00 6.81499958e+00 4.39613438e+00 5.02856874e+00 7.14187336e+00 8.51015091e+00 6.38025284e+00 1.22728539e+00 -1.67005908e+00 -4.67638910e-01 1.11082516e+01 2.08155251e+01 2.29348717e+01 1.73844662e+01 1.63659153e+01 1.52971268e+01 1.31432505e+01 5.11967421e+00 4.32923460e+00 1.19209270e+01 1.95377884e+01 2.12895432e+01 1.38808422e+01 1.17670441e+01 1.16454048e+01 1.26992865e+01 1.17543039e+01 8.97729015e+00 3.71490669e+00 7.48619652e+00 1.50669413e+01 1.84655762e+01 1.42119150e+01 2.57751393e+00 7.41583169e-01 7.14112616e+00 1.49067965e+01 1.76611462e+01 1.40496092e+01 1.36998978e+01 1.37014723e+01 1.40945930e+01 1.55932636e+01 1.66323013e+01 1.73260670e+01 1.72423038e+01 1.85881672e+01 1.80804081e+01 1.73934212e+01 1.53556662e+01 8.82714939e+00 4.15373039e+00 6.86407983e-01 5.01933908e+00 1.11354914e+01 1.57425442e+01 1.90875111e+01 1.04837170e+01 2.11615705e+00 1.00588155e+00 1.03681984e+01 1.68088741e+01 1.34289351e+01 8.62861156e+00 1.27867765e+01 1.77225647e+01 1.54785900e+01 8.15681839e+00 3.45251298e+00 6.13271332e+00 4.63884926e+00 7.63424635e+00 9.26111889e+00 1.48648424e+01 1.14150028e+01 8.34260178e+00 5.87595987e+00 5.44542253e-01 6.80997789e-01 2.29739952e+00 1.04598875e+01 1.54757824e+01 9.89483356e+00 -1.77055526e+00 -5.64003849e+00 8.91661167e-01 2.60965133e+00 -1.76231228e-02 -5.81502008e+00 2.00737238e+00 6.35393906e+00 8.32810497e+00 7.51805592e+00 8.69234657e+00 9.30441189e+00 5.89749765e+00 5.99774122e+00 1.24340992e+01 1.57545223e+01 1.33477526e+01 1.46917877e+01 2.11091022e+01 2.19679565e+01 1.27930145e+01 3.94095111e+00 5.08239603e+00 7.87386513e+00 6.60117006e+00 -5.75895309e-02 3.45861197e+00 8.73349762e+00 8.01505756e+00 3.00884962e+00 -2.11329985e+00 1.51363945e+00 4.28427815e-01 2.95473242e+00 3.20262980e+00 9.57232285e+00 1.61004562e+01 1.36267586e+01 9.30979633e+00 5.83368492e+00 1.07051430e+01 1.18860121e+01 1.51939316e+01 1.88621616e+01 1.71867065e+01 1.25931072e+01 8.65406322e+00 1.38741264e+01 1.95721149e+01 1.33904371e+01 4.20236260e-01 -1.18791211e+00 5.49216127e+00 1.18801861e+01 3.15902662e+00 -4.20070982e+00 -4.82076071e-02 7.57311010e+00 1.37769079e+01 1.52463408e+01 1.87654591e+01 2.05628777e+01 1.58555231e+01 1.32466955e+01 1.34319315e+01 1.58681002e+01 1.34940109e+01 1.36883125e+01 1.90023556e+01 1.55626287e+01 5.64902020e+00 -9.23624575e-01 1.93092489e+00 6.05497074e+00 4.21437263e-01 -4.85654831e+00 -8.53182375e-02 3.86376452e+00 7.30675840e+00 1.38843215e+00 4.53269958e+00 5.90231085e+00 5.67580366e+00 3.62928534e+00 6.37965918e+00 1.64517670e+01 2.09825287e+01 1.64111137e+01 7.61601734e+00 6.84395254e-01 3.14496446e+00 6.34241009e+00 1.22176208e+01 2.25961151e+01 2.03603058e+01 5.01551533e+00 -1.30835943e+01 -1.86494255e+01 -9.89749336e+00 -4.09404039e+00 -4.77124023e+00 -4.67830944e+00 -9.36531734e+00 -3.87106776e+00 -3.12477398e+00 2.25260407e-01 -1.21502899e-01 -1.23474388e+01 -1.67164803e+01 -1.64860916e+01 1.54134557e-01 1.16206636e+01 4.88669205e+00 -5.76890898e+00 -9.43133926e+00 3.52867746e+00 1.37720747e+01 1.32551527e+01 9.79417229e+00 4.09395075e+00 -3.29451680e+00 -6.61376047e+00 -1.24970665e+01 -6.49653482e+00 6.14588976e-01 7.23368359e+00 7.91884136e+00 -5.02376461e+00 -1.41009197e+01 -2.04355793e+01 -1.26555243e+01 1.73049307e+00 3.51846671e+00 2.86505747e+00 4.25231743e+00 1.33995943e+01 1.30715971e+01 -7.10749674e+00 -1.73277111e+01 -1.86242447e+01 -7.15498877e+00 -9.01078701e-01 5.11789739e-01 5.10608387e+00 2.41382885e+00 -3.55662799e+00 -8.81130409e+00 -1.51835356e+01 -1.29079256e+01 -1.28232870e+01 -1.12782516e+01 -9.64603519e+00 -9.72737694e+00 3.07990122e+00 6.99739456e+00 5.28145552e+00 -1.12709558e+00 -1.31855001e+01 -1.61349621e+01 -1.66909695e+01 -1.86237705e+00 1.02154226e+01 1.03012867e+01 -1.62691236e+00 -1.23707399e+01 -5.88861465e+00 6.59991646e+00 1.01626692e+01 7.34525108e+00 1.99433839e+00 -2.45456338e+00 -4.61807966e+00 -1.02558823e+01 -3.19078517e+00 2.83075881e+00 8.05193233e+00 2.74264431e+00 -1.38676891e+01 -2.05075760e+01 -1.78230724e+01 -4.52597237e+00 6.95549297e+00 1.42131555e+00 -9.49307632e+00 -1.55379772e+01 -5.68218994e+00 4.38061810e+00 2.30732703e+00 -1.72938108e+00 -5.38986778e+00 -3.18498588e+00 -1.66796696e+00 -6.94131279e+00 -8.19961929e+00 -7.32130432e+00 -6.81429911e+00 -4.02936125e+00 -9.91815567e+00 -7.05045033e+00 -8.13319016e+00 -4.54779387e+00 -2.13810587e+00 -9.74306774e+00 -3.44551325e+00 9.60896492e-01 1.27361517e+01 8.62272644e+00 -5.99686050e+00 -1.60603161e+01 -1.82899418e+01 -3.58156300e+00 6.24128819e+00 8.17000294e+00 3.04707789e+00 -4.99029064e+00 -5.61192226e+00 1.51564613e-01 3.99849892e+00 8.59787750e+00 3.28541589e+00 -5.20979118e+00 -1.55476027e+01 -1.62311478e+01 -3.63102794e+00 6.57126474e+00 1.20661087e+01 8.65210438e+00 -4.16861343e+00 -1.54502640e+01 -1.76471844e+01 -5.04019928e+00 6.07835150e+00 1.43228269e+00 -9.28985405e+00 -1.61249332e+01 -7.97304678e+00 3.89400935e+00 4.51864815e+00 1.91195917e+00 -8.31591702e+00 -1.36752052e+01 -1.45027008e+01 -1.37386866e+01 -6.90403414e+00 -1.09791970e+00 2.77202092e-02 -2.56132698e+00 -1.24025097e+01 -1.17844458e+01 -7.14652395e+00 -2.13789320e+00 3.97823477e+00 -2.67594314e+00 -5.15067434e+00 -5.68879747e+00 2.39874339e+00 5.09453249e+00 -8.23435879e+00 -1.70649681e+01 -1.61460533e+01 -3.74939275e+00 5.72955799e+00 5.92719364e+00 3.24090481e+00 -6.57914448e+00 -1.45289984e+01 -1.61501904e+01 -1.35686846e+01 -5.90699434e+00 -2.81438637e+00 -6.79169273e+00 -6.27215385e+00 -8.10956764e+00 2.55581236e+00 3.85603142e+00 4.37804747e+00 9.06053662e-01 -9.22233677e+00 -1.06166391e+01 -5.42115641e+00 8.31613827e+00 1.41075344e+01 9.35796452e+00 4.50664371e-01 -8.43013763e+00 -3.71393681e+00 5.64994907e+00 1.00743542e+01 7.76459455e+00 -4.18142796e-01 -5.12673330e+00 -7.90094709e+00 -9.33790398e+00 -8.74682617e+00 -8.52987194e+00 -7.53469086e+00 -1.15960045e+01 -1.80196381e+01 -1.45924206e+01 -3.74307609e+00 1.80398023e+00 -1.72726429e+00 -1.40651941e+01 -1.93934135e+01 -1.76697903e+01 -4.98835087e+00 1.97429669e+00 -3.91888714e+00 -1.06569815e+01 -1.23088379e+01 -6.99736643e+00 -6.91767979e+00 -1.10076218e+01 -1.47057514e+01 -1.74295826e+01 -1.92711201e+01 -1.65295372e+01 -1.82766857e+01 -1.35328617e+01 -1.23838158e+01 -1.17144012e+01 -1.03222504e+01 -1.45897636e+01 -1.14519606e+01 -1.06983318e+01 -6.12799120e+00 -3.06412005e+00 -1.11076918e+01 -1.19366922e+01 -1.36281347e+01 -7.13775921e+00 -4.75534296e+00 -1.05438824e+01 -1.31640358e+01 -2.18725891e+01 -1.74935932e+01 -1.05164480e+01 -2.01549459e+00 -2.81187177e-01 -1.06314964e+01 -1.29385300e+01 -1.03438520e+01 -9.85271358e+00 -1.17307386e+01 -1.33699312e+01 -4.14082098e+00 -2.03122306e+00 -1.27502728e+01 -1.72311440e+01 -1.73112259e+01 -1.17050810e+01 -1.27696962e+01 -2.38495350e+01 -4.16509771e+00 3.24882278e+01 4.17818787e+02 1.71607434e+03 59566672. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -267719120. 74284096. -9019003. -19971854. 1.53249133e+03 5.45930542e+02 4.37559738e+01 1.05962467e+01 -1.07389116e+01 -1.79617538e+01 -1.21064377e+01 -1.03881149e+01 -1.14376574e+01 -1.15976677e+01 -1.38180714e+01 -1.65512714e+01 -1.58492031e+01 -1.37264023e+01 -1.03308535e+01 -1.26097803e+01 -1.66650639e+01 -1.78280067e+01 -1.96518002e+01 -1.81510124e+01 -1.69971600e+01 -1.22590551e+01 -9.44706154e+00 -1.63284607e+01 -1.82189598e+01 -1.47246714e+01 -6.21895552e+00 -9.27839947e+00 -1.76492786e+01 -2.01974297e+01 -1.69265480e+01 -1.24471426e+01 -1.23428888e+01 -1.29575634e+01 -1.30017691e+01 -1.40493107e+01 -1.61341724e+01 -1.63028221e+01 -1.53000059e+01 -1.23189707e+01 -1.52397757e+01 -1.75166473e+01 -2.08812866e+01 -2.54648418e+01 -2.23100319e+01 -1.61467342e+01 -6.78312159e+00 -6.75388384e+00 -1.53516245e+01 -1.65653915e+01 -1.45245581e+01 -7.66416836e+00 -8.57065105e+00 -1.34192142e+01 -1.48340406e+01 -1.60748329e+01 -1.36537943e+01 -1.39488792e+01 -1.45586576e+01 -1.52946711e+01 -1.98900604e+01 -2.36640568e+01 -2.28453732e+01 -1.82046776e+01 -1.41963892e+01 -1.54658546e+01 -1.75520153e+01 -2.07247734e+01 -2.53040829e+01 -2.70009918e+01 -2.69182663e+01 -2.18448582e+01 -1.87823086e+01 -2.06745663e+01 -1.74726124e+01 -1.37370329e+01 -6.87533855e+00 -9.23100090e+00 -1.52275391e+01 -1.61303234e+01 -1.67240696e+01 -1.59173107e+01 -1.67347431e+01 -1.50489511e+01 -1.26553173e+01 -1.39692822e+01 -1.54230204e+01 -1.55076027e+01 -1.58967533e+01 -1.78694725e+01 -2.10017185e+01 -1.95477161e+01 -1.65174580e+01 -1.87353439e+01 -1.87485638e+01 -1.81566067e+01 -1.40897236e+01 -1.31058550e+01 -1.83564892e+01 -1.85878448e+01 -1.64141102e+01 -1.06951103e+01 -9.48194885e+00 -1.41150169e+01 -1.55378437e+01 -1.80644073e+01 -1.81367435e+01 -1.96103001e+01 -1.99478874e+01 -1.79735851e+01 -1.79734097e+01 -1.80571327e+01 -1.85126743e+01 -1.74947472e+01 -1.53257408e+01 -1.59063730e+01 -1.58263979e+01 -1.47654600e+01 -1.65780869e+01 -1.60789986e+01 -1.49211664e+01 -1.03671598e+01 -9.75981903e+00 -1.54191465e+01 -1.74071789e+01 -1.54215441e+01 -1.12824001e+01 -1.11142893e+01 -1.52047939e+01 -1.60849724e+01 -1.67530384e+01 -1.68069897e+01 -1.60723343e+01 -1.45740376e+01 -1.23924427e+01 -1.41959391e+01 -1.63430195e+01 -1.62281399e+01 -1.47610893e+01 -1.27865038e+01 -1.45352287e+01 -1.56886425e+01 -1.60611172e+01 -1.71890717e+01 -1.73344021e+01 -1.78838406e+01 -1.73209095e+01 -1.69005890e+01 -1.82891922e+01 -1.78929062e+01 -1.72050190e+01 -1.40524817e+01 -1.20244789e+01 -1.23554926e+01 -1.33284369e+01 -1.54994030e+01 -1.61138248e+01 -1.71041889e+01 -1.80218487e+01 -1.80189095e+01 -1.74805984e+01 -1.70134468e+01 -1.72976990e+01 -1.77669811e+01 -1.67256908e+01 -1.45494432e+01 -1.27405577e+01 -1.19598551e+01 -1.49732656e+01 -1.60429363e+01 -1.57025499e+01 -1.41787853e+01 -1.40904989e+01 -1.55907640e+01 -1.52875843e+01 -1.58749952e+01 -1.59306822e+01 -1.57995901e+01 -1.51337757e+01 -1.43657999e+01 -1.54479361e+01 -1.61754322e+01 -1.60270214e+01 -1.58621836e+01 -1.60288315e+01 -1.67260303e+01 -1.76645737e+01 -1.81137428e+01 -1.83468647e+01 -1.66103325e+01 -1.54530697e+01 -1.47158012e+01 -1.49619532e+01 -1.61514149e+01 -1.60553112e+01 -1.54325371e+01 -1.40970984e+01 -1.42026396e+01 -1.52295656e+01 -1.59076309e+01 -1.61797104e+01 -1.58285275e+01 -1.60939999e+01 -1.62557526e+01 -1.60925331e+01 -1.58818607e+01 -1.58421955e+01 -1.59112844e+01 -1.57406330e+01 -1.53650465e+01 -1.53198805e+01 -1.50237265e+01 -1.50750446e+01 -1.54403877e+01 -1.57473288e+01 -1.56215553e+01 -1.53172674e+01 -1.51960306e+01 -1.52149124e+01 -1.51503334e+01 -1.51301584e+01 -1.51374998e+01 -1.51866922e+01 -1.52198544e+01 -1.52014332e+01 -1.50816088e+01 -1.50143299e+01 -1.51140175e+01 -1.52854042e+01 -1.53464775e+01 -1.51909189e+01 -1.50742750e+01 -1.51849623e+01 -1.51069832e+01 -1.51002016e+01 -1.50538368e+01 -1.51524305e+01 -1.51137342e+01 -1.51511011e+01 -1.50792093e+01 -1.50953894e+01 -1.53725376e+01 -1.55298367e+01 -1.56807432e+01 -1.52392750e+01 -1.51066580e+01 -1.49990788e+01 -1.52341442e+01 -1.50748968e+01 -1.50977736e+01 -1.46136751e+01 -1.43028402e+01 -1.42092743e+01 -1.45915604e+01 -1.51392593e+01 -1.51252804e+01 -1.50977278e+01 -1.50102892e+01 -1.49861469e+01 -1.46596231e+01 -1.47896976e+01 -1.50459003e+01 -1.52775412e+01 -1.50856714e+01 -1.50074024e+01 -1.56818533e+01 -1.55213633e+01 -1.55776024e+01 -1.55174189e+01 -1.57289600e+01 -1.55453911e+01 -1.52936687e+01 -1.54814253e+01 -1.54667091e+01 -1.50385246e+01 -1.52487164e+01 -1.54206591e+01 -1.53990135e+01 -1.48451233e+01 -1.52435246e+01 -1.57403698e+01 -1.60506954e+01 -1.53749065e+01 -1.59993420e+01 -1.66075039e+01 -1.68307114e+01 -1.57345476e+01 -1.51030703e+01 -1.51262531e+01 -1.51756182e+01 -1.50135527e+01 -1.49279728e+01 -1.44874382e+01 -1.37835178e+01 -1.24853735e+01 -1.37111578e+01 -1.41438932e+01 -1.47893400e+01 -1.49301367e+01 -1.48805313e+01 -1.52115688e+01 -1.43911953e+01 -1.47173376e+01 -1.46704750e+01 -1.41403704e+01 -1.43329411e+01 -1.56110220e+01 -1.63313007e+01 -1.58300066e+01 -1.47018976e+01 -1.41803350e+01 -1.33487272e+01 -1.28904696e+01 -1.26071882e+01 -1.40727654e+01 -1.46146450e+01 -1.47746258e+01 -1.39766006e+01 -1.51038265e+01 -1.64487267e+01 -1.60121212e+01 -1.46743956e+01 -1.33337231e+01 -1.36432791e+01 -1.32617016e+01 -1.31582174e+01 -1.53190823e+01 -1.72408237e+01 -1.77362843e+01 -1.61298218e+01 -1.48551159e+01 -1.46342916e+01 -1.46615400e+01 -1.37697935e+01 -1.35961523e+01 -1.30202637e+01 -1.36000748e+01 -1.32848730e+01 -1.46010656e+01 -1.41762285e+01 -1.34638710e+01 -1.14134703e+01 -1.04566326e+01 -9.04393578e+00 -1.01150131e+01 -1.07031183e+01 -1.23476019e+01 -1.12603073e+01 -1.09927368e+01 -1.18203487e+01 -1.39727364e+01 -1.53696861e+01 -1.46375456e+01 -1.40195923e+01 -1.37181587e+01 -1.43839188e+01 -1.33543386e+01 -1.31159897e+01 -1.30526838e+01 -1.09565344e+01 -8.92704391e+00 -1.20523348e+01 -1.81363640e+01 -1.93998356e+01 -1.60279121e+01 -1.31757717e+01 -1.26758280e+01 -1.35307274e+01 -1.25989075e+01 -1.29399576e+01 -1.16156034e+01 -1.26583710e+01 -1.47590370e+01 -1.75920849e+01 -1.61869926e+01 -1.21308680e+01 -9.18920994e+00 -1.11149340e+01 -1.36924324e+01 -1.54534130e+01 -1.45026340e+01 -1.47140913e+01 -1.49407244e+01 -1.79104042e+01 -1.92919979e+01 -1.82508659e+01 -1.45937243e+01 -1.33711100e+01 -1.32508583e+01 -1.37708731e+01 -1.31913652e+01 -1.35685463e+01 -1.31245108e+01 -1.34897194e+01 -1.36232100e+01 -1.50635614e+01 -1.54772406e+01 -1.57977219e+01 -1.42026272e+01 -1.40877018e+01 -1.14109716e+01 -8.42301178e+00 -2.27038169e+00 -3.30448896e-01 -3.99383974e+00 -8.34398365e+00 -1.14981203e+01 -1.15393944e+01 -1.13997097e+01 -1.01246490e+01 -9.67327309e+00 -9.83106995e+00 -1.05866718e+01 -1.04587107e+01 -1.15027771e+01 -8.79836750e+00 -5.58433294e+00 -4.73462725e+00 -7.84145355e+00 -1.08903971e+01 -1.10488148e+01 -1.08069668e+01 -1.22114315e+01 -1.35699749e+01 -1.38396111e+01 -1.37156906e+01 -1.32378569e+01 -1.36253624e+01 -1.23538132e+01 -1.17972116e+01 -1.27982140e+01 -1.44296637e+01 -1.39733191e+01 -1.24320383e+01 -1.14466629e+01 -1.24592581e+01 -1.37716532e+01 -1.41364784e+01 -1.30613050e+01 -1.07688503e+01 -8.95637608e+00 -9.37871170e+00 -1.07406864e+01 -1.26200361e+01 -1.60718498e+01 -1.88078384e+01 -1.72928753e+01 -1.29776134e+01 -8.75806904e+00 -6.66487646e+00 -5.13250923e+00 -3.06005073e+00 -3.94122696e+00 -6.04789782e+00 -6.74556589e+00 -1.25631781e+01 -2.60873280e+01 -2.40873775e+01 -2.98041878e+01 -3.08094574e+02 -2.13640649e+03 -74487872. 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. 0. 0. 0. 0. 0. 0. -246017968. 136248832. -1.88674280e+03 -6.56216553e+02 -6.43630219e+01 -4.51408882e+01 -2.84656105e+01 -1.58028049e+01 -1.33662167e+01 -1.10118914e+01 -1.51060953e+01 -1.94939251e+01 -1.91510696e+01 -1.67498531e+01 -1.48203793e+01 -1.59631863e+01 -1.63334808e+01 -1.65904922e+01 -1.67858334e+01 -1.52034864e+01 -1.42356529e+01 -1.16596031e+01 -9.91070271e+00 -1.01691895e+01 -1.11104469e+01 -1.17181053e+01 -8.23998547e+00 -5.94547653e+00 -5.41321182e+00 -5.76563692e+00 -6.60874557e+00 -7.01117229e+00 -7.45881462e+00 -6.04726171e+00 -4.03304100e+00 -3.38748264e+00 -4.00098801e+00 -4.24868488e+00 -4.24809980e+00 -3.52954578e+00 -5.83632374e+00 -7.40951443e+00 -8.41713047e+00 -6.58083010e+00 -3.77129674e+00 -2.09626293e+00 -4.65728730e-01 -1.76831710e+00 3.10520381e-01 2.36270428e+00 3.10163736e+00 7.41349876e-01 -3.04715705e+00 -2.95659423e+00 -1.72455561e+00 -2.00615597e+00 -1.60293627e+00 -2.99241877e+00 -2.23817873e+00 -3.31253552e+00 -3.99087667e+00 -4.68265200e+00 -1.03136654e+01 -1.59613771e+01 -1.70965347e+01 -1.50831671e+01 -1.24599915e+01 -1.63990841e+01 -1.85865746e+01 -1.55864515e+01 -1.08352261e+01 -4.52321768e+00 -2.58263326e+00 -2.29728770e+00 1.15105832e+00 6.25735617e+00 9.78752232e+00 9.38243294e+00 4.13214970e+00 -9.21068564e-02 -2.49694943e+00 -3.99570608e+00 -2.29574966e+00 -6.66576862e+00 -1.00785389e+01 -1.63815022e+01 -1.83321629e+01 -1.63386116e+01 -1.18554039e+01 -7.41580868e+00 -7.28610563e+00 -8.40370941e+00 -1.37740746e+01 -1.83536396e+01 -1.69749794e+01 -1.11589346e+01 -6.35550165e+00 -6.88132763e+00 -8.34515381e+00 -1.02694550e+01 -1.31779957e+01 -7.98866653e+00 -7.64831185e-01 2.63877225e+00 8.93167078e-01 -4.61802292e+00 -4.13121367e+00 -6.26697493e+00 -9.53299809e+00 -1.24363756e+01 -1.63893890e+01 -1.44109926e+01 -9.01312351e+00 -2.20528078e+00 3.03589177e+00 2.04012156e+00 1.34195530e+00 -4.07027714e-02 3.51598233e-01 1.71042156e+00 2.08545589e+00 1.81653714e+00 2.98406035e-02 -7.51817584e-01 -2.39469838e+00 -2.62292480e+00 -2.95476604e+00 -4.00907516e+00 -9.73442173e+00 -1.58470039e+01 -1.55863686e+01 -1.03392096e+01 -4.74785995e+00 -7.29591608e+00 -1.05159988e+01 -1.61252460e+01 -1.82838364e+01 -1.56026249e+01 -8.75911808e+00 -2.48339963e+00 -1.02669644e+00 -1.30842745e+00 -1.02210546e+00 4.37024057e-01 1.40308547e+00 2.46074653e+00 1.28189635e+00 -6.95739210e-01 -1.57717478e+00 -7.02423215e-01 -1.95469245e-01 -5.96308708e-01 -2.59835458e+00 -8.63551235e+00 -1.49313059e+01 -1.33111153e+01 -7.16714191e+00 -1.06902885e+00 -7.30087948e+00 -1.26543856e+01 -1.72207928e+01 -1.80462513e+01 -1.91359768e+01 -1.91808262e+01 -1.28483572e+01 -7.79429579e+00 -2.23495579e+00 -2.11871958e+00 -7.61988163e-01 -1.28826320e-01 -2.35928178e+00 -2.53746009e+00 -2.45580602e+00 -2.15549159e+00 -4.16240311e+00 -3.74718785e+00 4.61368752e+00 1.22003183e+01 1.21940670e+01 4.80600452e+00 -1.07591712e+00 -3.11420631e+00 -2.37626433e+00 -1.66821671e+00 2.10125566e+00 -1.40221584e+00 -7.08665323e+00 -7.89085579e+00 -2.90745449e+00 1.68030202e+00 5.56200929e-02 -1.23824835e+00 -1.19208002e+00 -1.67114154e-01 -7.49550760e-01 -6.08608723e-01 -1.68018997e+00 -1.76485920e+00 -1.52281034e+00 -9.76401865e-01 -3.92860055e-01 3.45660019e+00 8.69650745e+00 8.34566975e+00 5.13278913e+00 7.03327835e-01 3.48169136e+00 2.99264669e+00 1.09664464e+00 -7.20066011e-01 -2.56482333e-01 1.10751688e+00 2.03034449e+00 1.87963629e+00 9.12930071e-01 -5.85736692e-01 1.00691766e-01 1.34677541e+00 1.60100520e+00 2.40488267e+00 2.48550034e+00 4.73085117e+00 4.88960552e+00 4.71176910e+00 3.84775782e+00 3.34637952e+00 6.45248985e+00 9.19064808e+00 1.00454130e+01 7.92373800e+00 5.20139742e+00 6.24373722e+00 5.82254267e+00 7.91322803e+00 9.10038471e+00 9.82312584e+00 8.85440063e+00 7.44545555e+00 9.01084042e+00 8.61928177e+00 7.18779802e+00 3.99856853e+00 1.77337825e+00 2.02025151e+00 7.68071651e+00 1.34247713e+01 1.52088461e+01 1.10663996e+01 -3.73055845e-01 -8.44004345e+00 -8.02721119e+00 -5.62077880e-01 5.16633892e+00 -2.20292234e+00 -7.81479883e+00 -6.97119474e+00 1.01794612e+00 7.23295975e+00 7.52201271e+00 7.34199190e+00 6.08451176e+00 4.59781647e+00 4.93857479e+00 6.09222364e+00 6.65036249e+00 3.90790009e+00 2.13041115e+00 4.44792843e+00 7.79191971e+00 8.53816032e+00 5.25140333e+00 1.76989365e+00 1.94902873e+00 2.32027864e+00 2.24378967e+00 2.35267591e+00 1.42196691e+00 2.46683025e+00 -2.66453195e+00 -4.71329069e+00 -3.97748518e+00 2.56817555e+00 8.02861214e+00 8.33959579e+00 6.37371206e+00 3.67798758e+00 4.00951767e+00 8.05533504e+00 1.32298193e+01 1.25885611e+01 9.35078716e+00 5.42580748e+00 7.77488947e+00 8.77370453e+00 9.04948235e+00 7.06904268e+00 1.78196800e+00 -3.51227212e+00 -3.90839458e+00 5.48762381e-01 6.70757771e+00 7.29938793e+00 6.47922611e+00 5.78364944e+00 5.56423330e+00 2.61719394e+00 -2.48418641e+00 -3.23663306e+00 -2.29120278e+00 2.92414260e+00 2.19181681e+00 4.01099873e+00 3.85702205e+00 5.43373442e+00 4.53979921e+00 3.44052124e+00 2.43235612e+00 3.32888412e+00 5.78604269e+00 6.14668036e+00 7.35898972e+00 8.21860027e+00 9.81524754e+00 8.91040707e+00 8.47076988e+00 7.54508638e+00 3.53045416e+00 -1.19728744e+00 -5.75411367e+00 -6.44382143e+00 -5.74585676e+00 -4.21870136e+00 2.63014650e+00 5.70279169e+00 9.66546345e+00 8.03494263e+00 9.21758842e+00 5.47321653e+00 7.03320742e-01 9.15851831e-01 4.18097210e+00 1.21814499e+01 1.61427441e+01 1.62906036e+01 1.35682802e+01 9.40703011e+00 9.28578281e+00 7.31796646e+00 2.57308078e+00 -1.39043784e+00 1.06719625e+00 7.04154587e+00 1.35401840e+01 1.02511806e+01 5.98789358e+00 3.56869411e+00 3.67794919e+00 6.84665489e+00 8.99761009e+00 1.34795618e+01 1.35404329e+01 1.28725023e+01 1.25079498e+01 1.25851669e+01 1.21641588e+01 1.24162903e+01 1.11809683e+01 1.05284929e+01 1.06834879e+01 1.12436857e+01 1.08629494e+01 5.21018887e+00 -3.79081070e-01 2.77541518e+00 1.08974152e+01 1.33045073e+01 7.18744230e+00 2.88007569e+00 5.21180201e+00 8.38642883e+00 5.08832645e+00 2.76244855e+00 2.04050279e+00 5.28765869e+00 8.98232841e+00 8.57913303e+00 7.88828135e+00 5.56040335e+00 6.65170860e+00 8.39951038e+00 1.01740942e+01 9.99597549e+00 9.60608006e+00 8.57700157e+00 8.83854008e+00 7.61554670e+00 6.25524855e+00 3.23900509e+00 7.36138487e+00 1.39569674e+01 1.29833956e+01 5.60900497e+00 1.55999434e+00 6.94271660e+00 1.06899757e+01 8.77227116e+00 6.53608751e+00 9.80559063e+00 1.41598177e+01 1.72728367e+01 1.61409969e+01 1.62554054e+01 1.25526352e+01 8.54144859e+00 8.23195553e+00 1.28330402e+01 1.32864819e+01 8.00174332e+00 7.47611332e+00 1.05845537e+01 1.50132742e+01 1.49797888e+01 1.49334049e+01 1.74546566e+01 1.92659683e+01 1.73150978e+01 1.22140064e+01 9.00891685e+00 1.06402674e+01 1.22897949e+01 1.22158270e+01 1.14680738e+01 1.15429163e+01 1.12077141e+01 1.22286482e+01 1.42027044e+01 1.48902531e+01 1.12360544e+01 7.41264105e+00 6.16468096e+00 7.94522333e+00 6.81304312e+00 2.59503913e+00 4.46623755e+00 9.97258377e+00 1.66303177e+01 1.71726322e+01 1.54569178e+01 1.58531170e+01 1.65789032e+01 1.51420660e+01 1.25849113e+01 1.09325657e+01 1.15880270e+01 1.28948097e+01 1.38349009e+01 1.55728064e+01 1.59245577e+01 1.44937458e+01 1.42827253e+01 1.45751085e+01 1.55582399e+01 1.26478090e+01 1.05992060e+01 1.13898392e+01 1.48135843e+01 1.50044336e+01 1.27097578e+01 1.31001253e+01 1.62547722e+01 1.58789883e+01 1.11963396e+01 5.25599051e+00 4.35615969e+00 6.41517353e+00 6.85807037e+00 6.21238470e+00 6.86139536e+00 9.75413799e+00 1.17946110e+01 1.16786470e+01 1.12950373e+01 1.02435589e+01 8.60327530e+00 8.90940571e+00 1.18908005e+01 1.51326780e+01 1.41918383e+01 1.12006531e+01 1.13468895e+01 1.32238388e+01 1.28127413e+01 9.39648533e+00 1.14301510e+01 1.72061806e+01 2.13902493e+01 1.94184608e+01 1.61859798e+01 1.71824951e+01 1.95497265e+01 2.04473362e+01 1.84367676e+01 1.68386917e+01 1.79312992e+01 1.85167198e+01 1.88139801e+01 1.69272614e+01 1.41134911e+01 1.06897249e+01 8.73207664e+00 8.39977837e+00 1.23890047e+01 1.57984657e+01 1.78723583e+01 1.59114723e+01 1.44448318e+01 1.44322863e+01 1.48422012e+01 1.65014362e+01 1.91563206e+01 1.85679226e+01 1.63502407e+01 1.41976385e+01 1.38948326e+01 1.38569069e+01 1.16909428e+01 1.03738251e+01 1.08028698e+01 1.24955502e+01 1.39462328e+01 1.39629393e+01 1.41673431e+01 1.42716331e+01 1.37195044e+01 1.32179737e+01 1.30690603e+01 1.36683369e+01 1.43033600e+01 1.50818014e+01 1.55135317e+01 1.52173653e+01 1.30593042e+01 1.04853592e+01 1.04769850e+01 1.21452570e+01 1.24667759e+01 1.12676363e+01 1.13150263e+01 1.26309853e+01 1.39464874e+01 1.26394339e+01 1.16764078e+01 1.22011232e+01 1.36586065e+01 1.59615965e+01 1.60118179e+01 1.58787479e+01 1.45582361e+01 1.30021524e+01 1.31991768e+01 1.41968374e+01 1.39989328e+01 1.24939184e+01 1.21434450e+01 1.33149929e+01 1.49885244e+01 1.40961809e+01 1.29697542e+01 1.31585331e+01 1.48701448e+01 1.62662563e+01 1.53188133e+01 1.41620750e+01 1.39719706e+01 1.40502672e+01 1.42947693e+01 1.40272541e+01 1.37104301e+01 1.36836567e+01 1.29878683e+01 1.27977304e+01 1.29491854e+01 1.38155012e+01 1.45219774e+01 1.45156345e+01 1.46487780e+01 1.47094755e+01 1.48442669e+01 1.47956038e+01 1.46114254e+01 1.48159618e+01 1.49531574e+01 1.51696253e+01 1.58534203e+01 1.63782425e+01 1.56549559e+01 1.44278946e+01 1.39591169e+01 1.48817167e+01 1.55024233e+01 1.56204481e+01 1.54989700e+01 1.54024515e+01 1.52697840e+01 1.49986334e+01 1.49069490e+01 1.47851486e+01 1.29658985e+01 9.91731834e+00 -1.65388832e+01 -1.63778412e+02 -40752616. 0. 0. 0. 0. 22237478. -42227944. 90862520. 16297160. 2.77294785e-01 -3.42984123e+01 -5.60767593e+01 -42711544. 0. 0.
================================================ FILE: config/m2dgr/ring32_M_3.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 71192800. 1436088. 1.36346594e+03 1.12033386e+03 8.55616150e+02 8.55051880e+02 8.95150635e+02 9.99455017e+02 1.03132410e+03 1.08163525e+03 1.11647998e+03 1.13358618e+03 1.22156946e+03 1.31960352e+03 1.32863208e+03 1.36615100e+03 1.44740039e+03 1.51549792e+03 1.57756702e+03 1.58153540e+03 1.58283850e+03 1.66557800e+03 1.76566406e+03 1.83586279e+03 1.87330469e+03 1.88255859e+03 1.93338110e+03 2.04935156e+03 2.15255811e+03 2.13172314e+03 2.09050562e+03 2.17418896e+03 2.29387134e+03 2.32662744e+03 2.37034692e+03 2.43887500e+03 2.41941309e+03 2.51118970e+03 2.62660962e+03 2.56846143e+03 2.60698120e+03 2.74077295e+03 2.89518896e+03 2.96870850e+03 2.81697900e+03 2.76557837e+03 2.90053442e+03 3.07788306e+03 3.16255811e+03 3.08850537e+03 3.12973706e+03 3.28006396e+03 3.29152954e+03 3.34052197e+03 3.34395752e+03 3.27585962e+03 3.43656592e+03 3.60644556e+03 3.54033789e+03 3.56961597e+03 3.68816284e+03 3.66437402e+03 3.77901978e+03 3.86961084e+03 3.76595068e+03 3.77955249e+03 3.91187500e+03 4.09260742e+03 4.10493896e+03 4.01391382e+03 4.08608936e+03 4.10810645e+03 4.19189600e+03 4.33383398e+03 4.22301953e+03 4.23568311e+03 4.41235693e+03 4.51511816e+03 4.57531445e+03 4.50401709e+03 4.37239648e+03 4.46999023e+03 4.65530811e+03 4.77861719e+03 4.81255225e+03 4.76194922e+03 4.73633447e+03 4.89635400e+03 5.02630762e+03 4.89931885e+03 4.80241992e+03 4.92676758e+03 5.13943604e+03 5.22235449e+03 5.19421436e+03 5.10410693e+03 5.04889453e+03 5.25895312e+03 5.42605127e+03 5.25580469e+03 5.29536133e+03 5.49198828e+03 5.62618066e+03 5.64617773e+03 5.42417188e+03 5.30796094e+03 5.52112891e+03 5.68810400e+03 5.70215771e+03 5.69724854e+03 5.75286426e+03 5.87746045e+03 5.79376074e+03 5.79848389e+03 5.96214551e+03 5.84431494e+03 5.83575879e+03 6.01701611e+03 6.10819873e+03 6.15230469e+03 6.07605127e+03 5.93825537e+03 6.01661230e+03 6.20103076e+03 6.34346973e+03 6.30419385e+03 6.29055615e+03 6.77970459e+03 8.75354004e+03 9.74331445e+03 -8.66385500e+05 1.03574431e+06 1.46907425e+06 -2.19784850e+06 9.30510645e+03 8.96751758e+03 7.67704541e+03 7.26778857e+03 6.95975928e+03 8.94347852e+03 9.76652441e+03 7.59844650e+06 -34227304. 1028188. 16951284. 8.06068812e+05 -1.03928362e+06 3.21023375e+06 -2.14830350e+06 -9.95933688e+05 1.25265075e+06 9.67970996e+03 9.12331934e+03 7.75619287e+03 7.70525977e+03 7.19188037e+03 6.79497656e+03 6.78057031e+03 7.28665039e+03 7.44639014e+03 7.15853662e+03 6.91860156e+03 7.06972168e+03 7.33784375e+03 7.32789648e+03 7.00591602e+03 7.03834326e+03 7.29414648e+03 7.33657959e+03 7.31779980e+03 7.40624463e+03 7.43707178e+03 7.14975928e+03 7.34269189e+03 7.56992480e+03 7.23425781e+03 7.22283643e+03 7.43883008e+03 7.50705420e+03 7.57312891e+03 7.44433691e+03 7.18203320e+03 7.26327588e+03 7.48867627e+03 7.78560107e+03 7.76761523e+03 7.33985498e+03 7.39225244e+03 7.78517041e+03 7.62948389e+03 7.30313379e+03 7.35150000e+03 7.57428955e+03 7.69210938e+03 7.78816748e+03 7.76327783e+03 7.55054541e+03 7.35740234e+03 7.60133350e+03 7.78604248e+03 7.54287207e+03 7.52568750e+03 7.71305127e+03 7.83196875e+03 7.82101221e+03 7.61832129e+03 7.41010547e+03 7.49502051e+03 7.68266895e+03 7.91234082e+03 7.87696045e+03 7.47959424e+03 7.51376074e+03 7.70327295e+03 7.74559180e+03 7.68565527e+03 7.52692432e+03 7.51726172e+03 7.74231641e+03 7.85264307e+03 7.75747705e+03 7.56869385e+03 7.45656250e+03 7.64063037e+03 7.77492285e+03 7.57251025e+03 7.62062939e+03 7.75905811e+03 7.71908252e+03 7.85863477e+03 7.56578662e+03 7.37635303e+03 7.56465186e+03 7.59474902e+03 7.70386230e+03 7.47873242e+03 7.28853125e+03 7.59499023e+03 7.81606445e+03 7.68137598e+03 7.47866211e+03 7.54712646e+03 7.39921729e+03 7.37916260e+03 7.55771875e+03 7.77891162e+03 7.53093994e+03 7.32597363e+03 7.54747461e+03 7.41037988e+03 7.45917383e+03 7.45017432e+03 7.18900781e+03 7.39477051e+03 7.53246289e+03 7.26158252e+03 7.10944580e+03 7.25737158e+03 7.51197021e+03 7.54104297e+03 7.13476904e+03 7.06158545e+03 7.22974268e+03 7.31139453e+03 7.38512354e+03 7.15033008e+03 7.10181836e+03 7.02967627e+03 7.03097900e+03 7.31059473e+03 7.17714648e+03 6.85552979e+03 6.99207080e+03 7.24012109e+03 6.95924268e+03 6.89113037e+03 6.79516602e+03 6.74218506e+03 7.02776562e+03 7.12211084e+03 6.84058838e+03 6.71310938e+03 6.76952344e+03 6.87848193e+03 6.94327002e+03 6.71314844e+03 6.78663770e+03 6.80562598e+03 6.47995166e+03 6.52208643e+03 6.56718799e+03 6.55661035e+03 6.63541943e+03 6.55483447e+03 6.49426318e+03 6.59766943e+03 6.43412256e+03 6.27700879e+03 6.38150098e+03 6.47321875e+03 6.41700781e+03 6.15791211e+03 6.12061230e+03 6.35595703e+03 6.40622314e+03 6.10538135e+03 5.98135840e+03 6.03112500e+03 6.17034473e+03 6.21243701e+03 5.96561084e+03 5.92026709e+03 5.85387256e+03 5.93138135e+03 6.01413232e+03 5.78975049e+03 5.75947852e+03 5.75999902e+03 5.69733447e+03 5.74297607e+03 5.82050488e+03 5.63478174e+03 5.43237256e+03 5.64451855e+03 5.79047998e+03 5.44268799e+03 5.20799658e+03 5.34044092e+03 5.42821582e+03 5.37760938e+03 5.24769238e+03 5.15746826e+03 5.16806396e+03 5.25754883e+03 5.25604834e+03 5.07475586e+03 5.01493799e+03 4.97398438e+03 5.05650195e+03 5.00503223e+03 4.81087256e+03 4.82447412e+03 4.78062598e+03 4.71307617e+03 4.76620801e+03 4.73833545e+03 4.58964600e+03 4.53566846e+03 4.60248438e+03 4.56434912e+03 4.40975146e+03 4.34546826e+03 4.35404980e+03 4.40305225e+03 4.33907861e+03 4.14804736e+03 4.11866016e+03 4.14764014e+03 4.21392773e+03 4.19009229e+03 4.00375684e+03 4.03911377e+03 3.94417505e+03 3.74035449e+03 3.74889966e+03 3.76311328e+03 3.83308594e+03 3.76567529e+03 3.54614502e+03 3.47197437e+03 3.53756616e+03 3.60627734e+03 3.53705151e+03 3.42088647e+03 3.35296851e+03 3.27271387e+03 3.19556885e+03 3.14239307e+03 3.19103271e+03 3.19276221e+03 3.04236157e+03 2.98387842e+03 2.94241577e+03 2.92868555e+03 2.91366553e+03 2.84608862e+03 2.85314062e+03 2.71895459e+03 2.56061523e+03 2.54829370e+03 2.57577856e+03 2.58849365e+03 2.56388013e+03 2.42957764e+03 2.25528247e+03 2.25196045e+03 2.27563550e+03 2.20791162e+03 2.21147534e+03 2.14395215e+03 2.01046753e+03 2.02002637e+03 1.98923767e+03 1.89373730e+03 1.86098071e+03 1.78466101e+03 1.70940295e+03 1.66233911e+03 1.62178674e+03 1.58700989e+03 1.57942212e+03 1.56594751e+03 1.44165723e+03 1.32778845e+03 1.28755664e+03 1.26687549e+03 1.25542151e+03 1.19419641e+03 1.08822559e+03 1.02516174e+03 1.00325958e+03 9.82850098e+02 9.32961975e+02 8.54137451e+02 7.96375732e+02 7.40143433e+02 6.79119568e+02 6.24313965e+02 5.88835083e+02 5.44080750e+02 4.83090759e+02 4.32169495e+02 3.64600311e+02 3.11247498e+02 2.68916901e+02 2.16112411e+02 1.64531174e+02 1.05841812e+02 4.95632629e+01 -3.41827607e+00 -5.82850304e+01 -1.13104500e+02 -1.67700165e+02 -2.14959290e+02 -2.58250824e+02 -3.19364777e+02 -3.79435089e+02 -4.26811157e+02 -4.89822906e+02 -5.51549316e+02 -5.85064209e+02 -6.33075623e+02 -6.95470642e+02 -7.60745667e+02 -8.22257324e+02 -8.62963684e+02 -9.16153137e+02 -9.41380127e+02 -9.87688049e+02 -1.07247253e+03 -1.13298950e+03 -1.20299805e+03 -1.25552295e+03 -1.26944617e+03 -1.29303552e+03 -1.37951013e+03 -1.48079321e+03 -1.51954236e+03 -1.54607336e+03 -1.59459949e+03 -1.61861536e+03 -1.68471094e+03 -1.77232397e+03 -1.81056079e+03 -1.86903735e+03 -1.90397351e+03 -1.93047400e+03 -1.98299817e+03 -2.08851685e+03 -2.15219287e+03 -2.17319800e+03 -2.24111328e+03 -2.23155420e+03 -2.30908057e+03 -2.40058813e+03 -2.42335059e+03 -2.53699219e+03 -2.53487524e+03 -2.49738037e+03 -2.57483496e+03 -2.63262402e+03 -2.74394629e+03 -2.91156860e+03 -2.89754858e+03 -2.82117261e+03 -2.85652344e+03 -2.91515430e+03 -2.96400879e+03 -3.10242285e+03 -3.19463477e+03 -3.13861279e+03 -3.16652661e+03 -3.22458716e+03 -3.33760547e+03 -3.44434204e+03 -3.44414258e+03 -3.58203271e+03 -3.54412012e+03 -3.38639648e+03 -3.49552417e+03 -3.67667017e+03 -3.78476587e+03 -3.87270459e+03 -3.77868823e+03 -3.64117920e+03 -3.81461646e+03 -4.05835083e+03 -4.04799243e+03 -4.03006885e+03 -4.03650854e+03 -4.02720654e+03 -4.15606201e+03 -4.22821533e+03 -4.21234668e+03 -4.37680566e+03 -4.36734375e+03 -4.35615234e+03 -4.42873438e+03 -4.36851514e+03 -4.45403418e+03 -4.59002148e+03 -4.76476318e+03 -4.68778027e+03 -4.48358496e+03 -4.59384131e+03 -4.78253564e+03 -4.91312354e+03 -4.93861035e+03 -4.82642334e+03 -4.78292236e+03 -4.93571289e+03 -5.08176807e+03 -5.16527295e+03 -5.16484277e+03 -5.15092676e+03 -5.14036230e+03 -5.20709375e+03 -5.24256885e+03 -5.25846143e+03 -5.36381641e+03 -5.40740479e+03 -5.48774365e+03 -5.35575049e+03 -5.39750781e+03 -5.59938086e+03 -5.58691846e+03 -5.74229980e+03 -5.68759131e+03 -5.47544775e+03 -5.54107959e+03 -5.70508203e+03 -5.92553711e+03 -6.07621533e+03 -5.87320264e+03 -5.71131689e+03 -5.81920068e+03 -5.95122266e+03 -6.00698242e+03 -6.06166113e+03 -6.11476367e+03 -6.01307910e+03 -5.96594922e+03 -6.09989893e+03 -6.23619873e+03 -6.34785547e+03 -6.31786377e+03 -6.35475049e+03 -6.25400049e+03 -6.08955908e+03 -6.24839600e+03 -6.39098535e+03 -6.58025146e+03 -6.61479199e+03 -6.29337451e+03 -6.25897705e+03 -6.50354053e+03 -6.78964844e+03 -6.72740723e+03 -6.63948242e+03 -6.63830811e+03 -6.48401025e+03 -6.65956543e+03 -6.87572412e+03 -6.77589160e+03 -6.76448145e+03 -6.75490137e+03 -6.82422900e+03 -6.87119189e+03 -6.85613037e+03 -6.91679297e+03 -6.96403223e+03 -6.96549658e+03 -6.83582715e+03 -6.92934961e+03 -7.06546338e+03 -7.03201611e+03 -7.30733984e+03 -7.12177881e+03 -6.88284619e+03 -7.01479102e+03 -6.95604297e+03 -7.21389258e+03 -7.55876807e+03 -7.37401611e+03 -6.99124756e+03 -6.94058789e+03 -7.23154150e+03 -7.31875830e+03 -7.52905176e+03 -7.33268262e+03 -8.32786914e+03 -8.01519531e+03 -1.37978164e+04 -2.30682734e+04 4.53441750e+06 66448264. 2.31867550e+06 1.55539738e+06 -84543384. 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. 0. 0. 0. 0. 0. 0. 0. -209539664. -8.04047500e+04 -1.39668887e+04 -9.18071973e+03 -8.06825977e+03 -7.58370508e+03 -7.83836816e+03 -7.80261133e+03 -7.76184082e+03 -7.39706201e+03 -7.54184766e+03 -7.98897217e+03 -7.94098096e+03 -7.55913574e+03 -7.29216553e+03 -7.38028516e+03 -7.75401074e+03 -8.01567383e+03 -7.72564160e+03 -7.43198779e+03 -7.40132227e+03 -7.43323486e+03 -7.75880029e+03 -7.82044531e+03 -7.52999365e+03 -7.38440381e+03 -7.37225586e+03 -7.49977393e+03 -7.55352344e+03 -7.42611963e+03 -7.41814941e+03 -7.69463574e+03 -7.82959912e+03 -7.44018457e+03 -7.06528467e+03 -7.21420557e+03 -7.59448193e+03 -7.84405078e+03 -7.47754541e+03 -7.07486621e+03 -7.12820654e+03 -7.44499805e+03 -7.74466602e+03 -7.47252441e+03 -6.98149268e+03 -7.03266406e+03 -7.29906348e+03 -7.45231152e+03 -7.45586084e+03 -7.31682568e+03 -7.05433447e+03 -7.03787402e+03 -7.28394678e+03 -7.02700879e+03 -6.90400635e+03 -7.24222412e+03 -7.29848389e+03 -7.19274756e+03 -6.93039355e+03 -6.63554688e+03 -6.97749170e+03 -7.42618799e+03 -7.22687598e+03 -6.76603467e+03 -6.49518408e+03 -6.61299756e+03 -6.99981250e+03 -7.24200146e+03 -6.99385889e+03 -6.80758398e+03 -6.67421045e+03 -6.46387012e+03 -6.66668896e+03 -6.88801514e+03 -6.63374951e+03 -6.55633057e+03 -6.59319971e+03 -6.62364062e+03 -6.49902832e+03 -6.40473145e+03 -6.57374463e+03 -6.58550391e+03 -6.58730518e+03 -6.40867041e+03 -6.10930176e+03 -6.10770166e+03 -6.42124658e+03 -6.67255811e+03 -6.35536621e+03 -5.93913672e+03 -5.99814697e+03 -6.16319775e+03 -6.29244775e+03 -6.31423975e+03 -6.05666064e+03 -5.96808447e+03 -5.92681543e+03 -5.97627148e+03 -6.05739209e+03 -5.90466748e+03 -5.82840723e+03 -5.76277539e+03 -5.79637451e+03 -5.80045898e+03 -5.69797217e+03 -5.71748535e+03 -5.72296045e+03 -5.77478906e+03 -5.58598242e+03 -5.30622656e+03 -5.37530225e+03 -5.63887646e+03 -5.71522607e+03 -5.40043408e+03 -5.09863330e+03 -5.09779053e+03 -5.36341943e+03 -5.59375586e+03 -5.29479346e+03 -5.01088281e+03 -5.06855859e+03 -5.01743115e+03 -5.00796191e+03 -5.03885986e+03 -4.93825732e+03 -4.98692871e+03 -4.88525098e+03 -4.81940381e+03 -4.81252832e+03 -4.65546045e+03 -4.70030859e+03 -4.84462109e+03 -4.80133008e+03 -4.58225439e+03 -4.37884229e+03 -4.35766699e+03 -4.50513135e+03 -4.64961426e+03 -4.41875195e+03 -4.13377881e+03 -4.16072168e+03 -4.32692236e+03 -4.40189404e+03 -4.18834814e+03 -4.02888428e+03 -4.02238745e+03 -3.96601685e+03 -4.00524121e+03 -3.99427393e+03 -3.78085571e+03 -3.73000879e+03 -3.82186157e+03 -3.82559424e+03 -3.72966016e+03 -3.60568384e+03 -3.56837646e+03 -3.57049341e+03 -3.62358179e+03 -3.50282544e+03 -3.26969458e+03 -3.27347827e+03 -3.31365186e+03 -3.31725293e+03 -3.26964014e+03 -3.10962573e+03 -3.04851807e+03 -3.05484058e+03 -3.06836646e+03 -3.01695361e+03 -2.89542236e+03 -2.88081055e+03 -2.82725024e+03 -2.77910474e+03 -2.72419897e+03 -2.60620264e+03 -2.60876562e+03 -2.65160938e+03 -2.61787231e+03 -2.46718530e+03 -2.31769019e+03 -2.29027612e+03 -2.35010986e+03 -2.38962622e+03 -2.24130640e+03 -2.07281421e+03 -2.04858252e+03 -2.05991553e+03 -2.05665747e+03 -2.00772546e+03 -1.87748145e+03 -1.81039978e+03 -1.79466003e+03 -1.76034961e+03 -1.71131396e+03 -1.64408484e+03 -1.59974072e+03 -1.52432556e+03 -1.48372607e+03 -1.44529590e+03 -1.37635840e+03 -1.33266284e+03 -1.28413989e+03 -1.23750830e+03 -1.14309717e+03 -1.07052490e+03 -1.06146350e+03 -1.04697375e+03 -1.00015710e+03 -9.05074768e+02 -8.13152283e+02 -7.67217957e+02 -7.57313110e+02 -7.37660767e+02 -6.61448059e+02 -5.79976624e+02 -5.15286011e+02 -4.60685608e+02 -4.27099365e+02 -3.87286041e+02 -3.25582153e+02 -2.66109558e+02 -2.12023254e+02 -1.58826416e+02 -1.03657570e+02 -5.24063148e+01 -3.19622785e-01 5.46031418e+01 1.12050087e+02 1.66045776e+02 2.07653885e+02 2.63382599e+02 3.25549988e+02 3.78211548e+02 4.34535858e+02 4.84703278e+02 5.48238403e+02 6.06078796e+02 6.31315002e+02 6.61600891e+02 7.27885986e+02 8.21438354e+02 9.02583008e+02 9.40456116e+02 9.39603394e+02 9.66572571e+02 1.04150867e+03 1.14339185e+03 1.22951208e+03 1.26152295e+03 1.25177307e+03 1.29589465e+03 1.42281226e+03 1.47985144e+03 1.46038281e+03 1.50753674e+03 1.59351477e+03 1.64574280e+03 1.74790161e+03 1.75824854e+03 1.75485144e+03 1.85258960e+03 1.85414185e+03 1.95515845e+03 2.07409375e+03 2.01754138e+03 2.10008691e+03 2.22787695e+03 2.22564673e+03 2.26582837e+03 2.31254175e+03 2.37285767e+03 2.45503931e+03 2.47277417e+03 2.44190503e+03 2.51367871e+03 2.68900903e+03 2.79765405e+03 2.77931860e+03 2.71930322e+03 2.70605859e+03 2.80678955e+03 2.98972021e+03 3.11953491e+03 3.10748877e+03 2.99145776e+03 3.03472876e+03 3.20413892e+03 3.24040942e+03 3.24277490e+03 3.28839819e+03 3.34700366e+03 3.39228906e+03 3.57422412e+03 3.54283569e+03 3.44910742e+03 3.56682251e+03 3.53170117e+03 3.71369727e+03 3.85490283e+03 3.77492993e+03 3.95749683e+03 3.90962207e+03 3.79194604e+03 3.95649414e+03 3.92707886e+03 4.05027222e+03 4.36186768e+03 4.18346973e+03 4.00480151e+03 4.13891455e+03 4.35030078e+03 4.54775635e+03 4.52232031e+03 4.32575049e+03 4.21062207e+03 4.35592822e+03 4.67429053e+03 4.85777686e+03 4.79746777e+03 4.58448682e+03 4.57205811e+03 4.81054297e+03 4.93547314e+03 4.80651953e+03 4.77840479e+03 4.91117041e+03 4.96749414e+03 5.13672656e+03 5.16295020e+03 5.01164062e+03 5.09608105e+03 5.10460498e+03 5.13799902e+03 5.29140137e+03 5.29800098e+03 5.45340381e+03 5.38674463e+03 5.22327100e+03 5.40384326e+03 5.32192725e+03 5.48120361e+03 5.91050049e+03 5.65402783e+03 5.30732031e+03 5.44454834e+03 5.77338818e+03 5.97393896e+03 6.04699316e+03 5.78367725e+03 5.54557520e+03 5.66365820e+03 6.00403516e+03 6.32872070e+03 6.15154834e+03 5.81715479e+03 5.80142627e+03 6.00866455e+03 6.20390186e+03 6.41659863e+03 6.39593555e+03 6.05078857e+03 6.00205029e+03 6.29710986e+03 6.41862695e+03 6.37970410e+03 6.36207422e+03 6.30025244e+03 6.26804443e+03 6.59097656e+03 6.66983740e+03 6.36511670e+03 6.35691162e+03 6.56252783e+03 6.59782080e+03 6.62877930e+03 6.59223096e+03 6.76242188e+03 6.82556934e+03 6.64422363e+03 6.63362988e+03 6.55545312e+03 6.80914990e+03 7.13823828e+03 7.06214697e+03 6.73358691e+03 6.56996582e+03 6.85493115e+03 7.25518262e+03 7.00749756e+03 6.67740527e+03 6.83170996e+03 7.03484229e+03 7.21096680e+03 7.43414453e+03 7.33147168e+03 6.93340771e+03 6.74729346e+03 7.02838184e+03 7.38083105e+03 7.37157422e+03 7.17735742e+03 7.18239111e+03 7.21584570e+03 7.35908838e+03 7.26572266e+03 7.11356152e+03 7.19077344e+03 7.16815918e+03 7.43770312e+03 7.64891895e+03 7.38096533e+03 7.37420361e+03 7.40499170e+03 7.60818701e+03 7.45235303e+03 7.07592529e+03 7.39913623e+03 7.82978271e+03 7.56241992e+03 7.18078955e+03 7.38549805e+03 7.80105518e+03 7.72449561e+03 7.56472803e+03 7.60963037e+03 7.38011133e+03 7.33880518e+03 7.75585693e+03 7.84876660e+03 7.53335547e+03 7.32156982e+03 7.23927930e+03 7.63029443e+03 8.02491357e+03 7.68415527e+03 7.45820410e+03 7.62886133e+03 7.62937207e+03 7.86797363e+03 7.91996973e+03 7.45806006e+03 7.39609424e+03 7.58296338e+03 7.64058105e+03 7.69963525e+03 7.70962207e+03 7.87922363e+03 7.82902393e+03 7.49352783e+03 7.48434082e+03 7.37376709e+03 7.68214258e+03 8.13507715e+03 7.90778076e+03 7.46269971e+03 7.39822021e+03 7647. 8.14888721e+03 8.67473828e+03 9.51443750e+03 8.34812012e+03 1.57556475e+04 1.09856141e+05 -6.41029350e+06 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. 0. 0. 0. 0. 0. 0. -7.64077450e+06 46421. 1.02059482e+04 8.25738379e+03 7.27982959e+03 7.16063428e+03 7.28557129e+03 7.15850488e+03 6.91777588e+03 6.88072021e+03 7.16109229e+03 7.20809961e+03 6.99307861e+03 7.03995166e+03 7.03695898e+03 6.93519092e+03 6.94541699e+03 6.89865527e+03 6.86637109e+03 6.86163184e+03 6.82452539e+03 6.78749658e+03 6.62986719e+03 6.54095264e+03 6.87593457e+03 6.87720654e+03 6.51265234e+03 6.44771533e+03 6.77783691e+03 6.80471729e+03 6.58308984e+03 6.56202637e+03 6.50513281e+03 6.46513135e+03 6.44292578e+03 6.39369238e+03 6.37687109e+03 6.32468018e+03 6.15580713e+03 6.10406934e+03 6.40986230e+03 6.40861816e+03 6.20650098e+03 6.15379736e+03 6.13463037e+03 6.12079443e+03 6.06125049e+03 6.00726221e+03 6.02366016e+03 5.82041943e+03 5.72626562e+03 5.90571924e+03 5.87976562e+03 6.00948047e+03 6.01271924e+03 5.76549463e+03 5.56830469e+03 5.50417627e+03 5.82265088e+03 5.84327441e+03 5.57487842e+03 5.47752002e+03 5.47729492e+03 5.47881250e+03 5.38470996e+03 5.49759766e+03 5.44919141e+03 5.14545410e+03 5.07942969e+03 5.32185596e+03 5.40569434e+03 5.22571143e+03 5.12462598e+03 5.08818311e+03 5.03430225e+03 4.92524170e+03 4.89021289e+03 4.96246777e+03 4.91466113e+03 4.76986621e+03 4.74270117e+03 4.77063379e+03 4.70760449e+03 4.77655518e+03 4.71387549e+03 4.53015381e+03 4.55819775e+03 4.50932422e+03 4.49548340e+03 4.49513281e+03 4.38009863e+03 4.32382031e+03 4.20420459e+03 4.10776514e+03 4.23700537e+03 4.18554199e+03 3.94406421e+03 3.95613770e+03 4.12670410e+03 4.22466260e+03 4.03682471e+03 3.87873022e+03 3.77289697e+03 3.70749927e+03 3.70465869e+03 3.65992505e+03 3.66197144e+03 3.59718408e+03 3.60862280e+03 3.54196753e+03 3.40842236e+03 3.43829980e+03 3.28830518e+03 3.23468799e+03 3.37923413e+03 3.30261743e+03 3.17169702e+03 3.04363525e+03 2.97227344e+03 3.09177026e+03 3.05647412e+03 2.91333154e+03 2.79235254e+03 2.74332739e+03 2.77035669e+03 2.71749487e+03 2.74099805e+03 2.70649878e+03 2.57426099e+03 2.50077783e+03 2.45489990e+03 2.44909106e+03 2.39823364e+03 2.31315088e+03 2.23113989e+03 2.18547949e+03 2.17433594e+03 2.06407568e+03 2.01390710e+03 2.07583203e+03 2.01532471e+03 1.90985938e+03 1.80095056e+03 1.74857971e+03 1.80271094e+03 1.74667029e+03 1.64862573e+03 1.55416101e+03 1.49175964e+03 1.49218311e+03 1.43371301e+03 1.37790857e+03 1.30032544e+03 1.27110571e+03 1.27910315e+03 1.19611694e+03 1.12805054e+03 1.07737708e+03 1.01873413e+03 9.53127747e+02 8.96508911e+02 8.56782837e+02 8.06526917e+02 7.56588806e+02 6.78154724e+02 6.25857605e+02 6.13134583e+02 5.36563293e+02 4.64695404e+02 4.24534180e+02 3.71111176e+02 3.29825897e+02 2.69367676e+02 2.06450500e+02 1.63019043e+02 1.09837639e+02 5.33181763e+01 -1.76700675e+00 -5.58978539e+01 -1.09954987e+02 -1.62358765e+02 -2.16379456e+02 -2.62434418e+02 -3.20359833e+02 -3.94429901e+02 -4.41855469e+02 -4.79658966e+02 -5.15150146e+02 -5.74036987e+02 -6.66659790e+02 -7.17909912e+02 -7.49838074e+02 -7.87010376e+02 -8.33328064e+02 -9.06200684e+02 -9.61088196e+02 -1.03964514e+03 -1.07281763e+03 -1.09217676e+03 -1.17510608e+03 -1.22745776e+03 -1.30589404e+03 -1.34387915e+03 -1.35948425e+03 -1.43026709e+03 -1.48162573e+03 -1.54798315e+03 -1.55787488e+03 -1.64045508e+03 -1.79956006e+03 -1.79678467e+03 -1.80156287e+03 -1.81020349e+03 -1.84390100e+03 -2.00916687e+03 -2.08003027e+03 -2.06772241e+03 -2.05132910e+03 -2.10220166e+03 -2.22880225e+03 -2.27718115e+03 -2.38615210e+03 -2.42673853e+03 -2.42045068e+03 -2.40562085e+03 -2.43730249e+03 -2.64581079e+03 -2.66922119e+03 -2.63609717e+03 -2.68166895e+03 -2.72388647e+03 -2.89605908e+03 -2.95782520e+03 -2.86431274e+03 -2.88884424e+03 -3.07763452e+03 -3.16111816e+03 -3.04848047e+03 -3.07782593e+03 -3.29222388e+03 -3.35292456e+03 -3.30706494e+03 -3.28642065e+03 -3.31841821e+03 -3.55041626e+03 -3.56111987e+03 -3.48613110e+03 -3.56416943e+03 -3.62082739e+03 -3.76518872e+03 -3.79734717e+03 -3.71635791e+03 -3.67911157e+03 -3.84968311e+03 -4.11668652e+03 -4.04596533e+03 -4.02844360e+03 -4.12034961e+03 -4.12578076e+03 -4.16869824e+03 -4.20085254e+03 -4.22963818e+03 -4.17392188e+03 -4.19932275e+03 -4.35499609e+03 -4.43053369e+03 -4.61567969e+03 -4.51780908e+03 -4.37210889e+03 -4.53853027e+03 -4.69097754e+03 -4.86426953e+03 -4.79654785e+03 -4.70289355e+03 -4.74743994e+03 -4.75947900e+03 -4.90435986e+03 -4.94487158e+03 -5.06514062e+03 -5.10255957e+03 -5.02916797e+03 -5.00222510e+03 -4.90035742e+03 -5.15072070e+03 -5.51892773e+03 -5.43175098e+03 -5.30035645e+03 -5.18606494e+03 -5.12172217e+03 -5.41529346e+03 -5.73237598e+03 -5.60035938e+03 -5.36601758e+03 -5.38107422e+03 -5.57609082e+03 -5.65392383e+03 -5.79324658e+03 -5.79872412e+03 -5.70430420e+03 -5.70949072e+03 -5.71382910e+03 -5.96260107e+03 -6.01056982e+03 -5.73681885e+03 -5.76845068e+03 -6.13722754e+03 -6.12046533e+03 -5.84446143e+03 -5.97480127e+03 -6.32519434e+03 -6.30963184e+03 -6.16563867e+03 -6.05121973e+03 -6.08238232e+03 -6.44848535e+03 -6.49782861e+03 -6.34983984e+03 -6.21312842e+03 -6.18492969e+03 -6.39351514e+03 -6.46476855e+03 -6.45267969e+03 -6.32356592e+03 -6.50950684e+03 -6.77874365e+03 -6.60284131e+03 -6.75681396e+03 -6.75606299e+03 -6.57410596e+03 -6.70719287e+03 -6.75880225e+03 -6.76794531e+03 -6.69623682e+03 -6.61013867e+03 -6.55494189e+03 -6.87648535e+03 -7.26802881e+03 -6.92118408e+03 -6.63689844e+03 -6.86943994e+03 -7.00705469e+03 -7.26363525e+03 -7.08435010e+03 -6.86251611e+03 -7.20404590e+03 -7.23310010e+03 -6.87288525e+03 -6.84322607e+03 -7.30215527e+03 -7.38051318e+03 -7.14971191e+03 -7.05694678e+03 -6.78626855e+03 -7.15267676e+03 -7.69470020e+03 -7.45696094e+03 -7.24430420e+03 -7.06899414e+03 -6.97716113e+03 -7.35727197e+03 -7.76171045e+03 -7.57224951e+03 -7.19922998e+03 -7.16440283e+03 -7.36846387e+03 -7.43092188e+03 -7.64411816e+03 -7.48116650e+03 -7.27886523e+03 -7.45905518e+03 -7.46985645e+03 -7.70112744e+03 -7.67564404e+03 -7.43457861e+03 -7.46997998e+03 -7.45052783e+03 -7.62169629e+03 -7.47106104e+03 -7.40593506e+03 -7.82613281e+03 -7.78424121e+03 -7.51682422e+03 -7.35125635e+03 -7.41500830e+03 -7.89174072e+03 -7.82406934e+03 -7.62006641e+03 -7.44322656e+03 -7.38575488e+03 -7.60046143e+03 -7.63072998e+03 -7.64138672e+03 -7.46337988e+03 -7.61229004e+03 -7.90383252e+03 -7.66907959e+03 -7.86760791e+03 -7.87281689e+03 -7.66467773e+03 -7.56536719e+03 -7.49411426e+03 -7.77657129e+03 -7.79789355e+03 -7.49452051e+03 -7.42857080e+03 -7.85516504e+03 -7.95765967e+03 -7.46854834e+03 -7.28773047e+03 -7.47882031e+03 -7.78223242e+03 -8.04017041e+03 -7.74523193e+03 -7.36615430e+03 -7.71757031e+03 -7.89754443e+03 -7.70321387e+03 -7.54912793e+03 -7.54484131e+03 -7.46528223e+03 -7.47930371e+03 -7.61442188e+03 -7.37919141e+03 -7.55783350e+03 -7.91777197e+03 -7.63782520e+03 -7.62039551e+03 -7.46019238e+03 -7.36062695e+03 -7.72354346e+03 -7.69607715e+03 -7.52069482e+03 -7.32005127e+03 -7.11004053e+03 -7.26301025e+03 -7.62216846e+03 -7.87239209e+03 -7.46636230e+03 -7.20253662e+03 -7.34745947e+03 -7.39806348e+03 -7.61565039e+03 -7.57844092e+03 -7.32998486e+03 -7.26793262e+03 -7.22282031e+03 -7.21299414e+03 -7.05027344e+03 -7.24426221e+03 -7.51618750e+03 -7.26640625e+03 -7.31096143e+03 -7.19532422e+03 -6.98767627e+03 -7.38409033e+03 -7.40170752e+03 -7.12482910e+03 -6.94826074e+03 -6.82625049e+03 -7.04020654e+03 -7.01051025e+03 -7.21319434e+03 -7.26446582e+03 -6.96906885e+03 -6.78797803e+03 -6.84758398e+03 -7.14742920e+03 -7.01183691e+03 -6.84727148e+03 -6.71177441e+03 -6.67607227e+03 -6.75323389e+03 -6.70013818e+03 -6.84376318e+03 -6.84191895e+03 -6.59674072e+03 -6.77785791e+03 -6.84111230e+03 -6.64711670e+03 -6.59023584e+03 -6.57265381e+03 -6.55141162e+03 -6.35459326e+03 -6.24822266e+03 -6.55219238e+03 -6.59766162e+03 -6.22124658e+03 -6.00438574e+03 -6.29670703e+03 -6.65774023e+03 -6.51073340e+03 -6.09185303e+03 -5.96999902e+03 -6.29357129e+03 -6.26659326e+03 -6.03214307e+03 -6.15681201e+03 -5.97356396e+03 -5.66393945e+03 -5.82420898e+03 -6.11796875e+03 -6.20956885e+03 -5.84479492e+03 -5.52676611e+03 -5.82204443e+03 -6.06946631e+03 -5.86163477e+03 -5.55054053e+03 -5.43369385e+03 -5.56555469e+03 -5.58380664e+03 -5.68231250e+03 -5.62670215e+03 -5.39597266e+03 -5.39010254e+03 -5.35271191e+03 -5.48347510e+03 -5.33899902e+03 -5.15381055e+03 -5.30194873e+03 -5.23683545e+03 -5.23998193e+03 -5.11244141e+03 -4.97101465e+03 -5.20969043e+03 -5.04818799e+03 -4.78895312e+03 -4.86836035e+03 -4.92202295e+03 -4.90791748e+03 -4.79821973e+03 -4.86175439e+03 -4.86354834e+03 -4.70641455e+03 -4.52039648e+03 -4.45560303e+03 -4.64313965e+03 -4.51289502e+03 -4.35021191e+03 -4.43070898e+03 -4.38368896e+03 -4.32648975e+03 -4.26418848e+03 -4.33761035e+03 -4.24881738e+03 -4.07061304e+03 -4.17293262e+03 -4.14872021e+03 -4.03368799e+03 -3.99496704e+03 -3.93549512e+03 -3.85342017e+03 -3.70952881e+03 -3.59974561e+03 -3.73546167e+03 -3.90912793e+03 -3.66583691e+03 -3.39909082e+03 -3.50991187e+03 -3.68943311e+03 -3.59570752e+03 -3.35335254e+03 -3.22767944e+03 -3.36311743e+03 -3.31791895e+03 -3.15156616e+03 -3.23628760e+03 -3.18104761e+03 -2.97148926e+03 -2.91637695e+03 -3.01620264e+03 -3.04724146e+03 -2.85816724e+03 -2.69321558e+03 -2.75030908e+03 -2.85776807e+03 -2.75058325e+03 -2.57155151e+03 -2.45693701e+03 -2.51324365e+03 -2.58119702e+03 -2.45296606e+03 -2.32687427e+03 -2.29700049e+03 -2.27162280e+03 -2.20865112e+03 -2.21902759e+03 -2.11921143e+03 -2.00429968e+03 -2.00577271e+03 -1.96119214e+03 -1.94969092e+03 -1.85652502e+03 -1.75526624e+03 -1.75653333e+03 -1.66041467e+03 -1.61522949e+03 -1.62483118e+03 -1.55459729e+03 -1.49126001e+03 -1.42715808e+03 -1.42260120e+03 -1.37621399e+03 -1.27313293e+03 -1.19066821e+03 -1.14183459e+03 -1.15577063e+03 -1.06885876e+03 -9.69127136e+02 -9.56986816e+02 -9.93905151e+02 -1.02760217e+03 -7.30321960e+02 -7.46192200e+02 -1.91975110e+03 -2.58951733e+03 1.44595953e+05 -46060172. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 142385600. 2872176. 2.72696216e+03 1.44082776e+03 1.17387915e+03 8.70118286e+02 9.26905396e+02 1.06156445e+03 1.01987866e+03 1.02780969e+03 1.09212671e+03 1.14281519e+03 1.20797253e+03 1.30196985e+03 1.34176111e+03 1.34407971e+03 1.42068909e+03 1.50836414e+03 1.51947595e+03 1.54765454e+03 1.60015881e+03 1.67215381e+03 1.76500891e+03 1.82796497e+03 1.83281091e+03 1.82434131e+03 1.91849487e+03 2.03629761e+03 2.05732178e+03 2.09958325e+03 2.12679858e+03 2.16392578e+03 2.28652441e+03 2.29271167e+03 2.26979736e+03 2.35856885e+03 2.40979541e+03 2.49260132e+03 2.57093970e+03 2.54952612e+03 2.59413672e+03 2.72953467e+03 2.89836865e+03 2.87088794e+03 2.72330884e+03 2.76863965e+03 2.90137134e+03 3.00995996e+03 3.11306201e+03 3.10547729e+03 3.06742383e+03 3.19172095e+03 3.28515649e+03 3.23970117e+03 3.25710938e+03 3.29941602e+03 3.45426978e+03 3.62550415e+03 3.49660132e+03 3.41924829e+03 3.55419580e+03 3.68076538e+03 3.79186865e+03 3.78402759e+03 3.73118530e+03 3.73341650e+03 3.86941748e+03 4.09071753e+03 4.02268164e+03 3.87851782e+03 3.99931274e+03 4.11992529e+03 4.16101416e+03 4.25859863e+03 4.23907812e+03 4.17726367e+03 4.32574268e+03 4.45981982e+03 4.41911963e+03 4.39576660e+03 4.39760156e+03 4.46487988e+03 4.64052100e+03 4.79919092e+03 4.71786475e+03 4.57983789e+03 4.70409375e+03 4.87189307e+03 4.82245605e+03 4.79145117e+03 4.83612158e+03 4.96405127e+03 5.15330273e+03 5.11166553e+03 4.96135889e+03 4.98207324e+03 5.04950195e+03 5.20646973e+03 5.28686816e+03 5.23686816e+03 5.26610986e+03 5.44429248e+03 5.61240186e+03 5.51120654e+03 5.25744336e+03 5.31374316e+03 5.53605420e+03 5.63158740e+03 5.66908838e+03 5.59517969e+03 5.54741016e+03 5.76695020e+03 5.83236084e+03 5.69871729e+03 5.76779443e+03 5.83617529e+03 5.84962305e+03 6.00967236e+03 6.01452686e+03 5.89511523e+03 5.92445459e+03 5.96281201e+03 6.01036816e+03 6.17981982e+03 6.34797168e+03 6.21646240e+03 6.11627490e+03 6.68497852e+03 8.48620508e+03 8.69638770e+03 8.97321094e+03 8.83764844e+03 8.99012305e+03 9.28076367e+03 8.64380859e+03 8.49270508e+03 7.47936230e+03 7.18942822e+03 6.84373047e+03 8.57116895e+03 9.11416211e+03 9.45480664e+03 9.45334961e+03 9.63584961e+03 9.57175000e+03 9.42481738e+03 9.59107031e+03 9.71520898e+03 9.87562012e+03 1.00439414e+04 9.77731055e+03 8.89238477e+03 8.85263867e+03 7.72267676e+03 7.43958643e+03 7.00528662e+03 6.76782764e+03 6.75173096e+03 7.22053125e+03 7.26092432e+03 6.93180322e+03 6.84743652e+03 7.14086914e+03 7.28693506e+03 7.10612842e+03 6.91435742e+03 6.99089404e+03 7.24675000e+03 7.40623389e+03 7.15794824e+03 7.07525391e+03 7.16176123e+03 7.14232080e+03 7.29743945e+03 7.38123730e+03 7.20822607e+03 7.25409326e+03 7.42352588e+03 7.45489600e+03 7.28497949e+03 7.20998389e+03 7.22336426e+03 7.25657568e+03 7.42651465e+03 7.67164697e+03 7.70410352e+03 7.21553076e+03 7.33288281e+03 7.69435791e+03 7.42195312e+03 7.26473291e+03 7.35547217e+03 7.40816797e+03 7.64103857e+03 7.68779639e+03 7.40798096e+03 7.31002246e+03 7.39329004e+03 7.55341309e+03 7.61752393e+03 7.45538330e+03 7.47675928e+03 7.69396436e+03 7.75886426e+03 7.47944629e+03 7.40214453e+03 7.39848926e+03 7.51113281e+03 7.61650586e+03 7.77575195e+03 7.80460449e+03 7.42113916e+03 7.45510205e+03 7.65483838e+03 7.54867578e+03 7.49698389e+03 7.51579102e+03 7.52234424e+03 7.72035254e+03 7.74476221e+03 7.47212109e+03 7.44644238e+03 7.44272949e+03 7.51247949e+03 7.64233105e+03 7.51038721e+03 7.50797998e+03 7.59190918e+03 7.69415039e+03 7.73914014e+03 7.38847949e+03 7.27672168e+03 7.47218555e+03 7.51636523e+03 7.61122510e+03 7.50965771e+03 7.27045947e+03 7.45965234e+03 7.70802148e+03 7.44857324e+03 7.33366650e+03 7.44625977e+03 7.42080127e+03 7.42341846e+03 7.34686133e+03 7.51617578e+03 7.49491699e+03 7.28433008e+03 7.45481445e+03 7.26702686e+03 7.27756348e+03 7.45525488e+03 7.20062305e+03 7.24227734e+03 7.37316504e+03 7.25454980e+03 7.01461621e+03 7.05997266e+03 7.41758936e+03 7.51955811e+03 7.07371191e+03 6.98654150e+03 7.22243750e+03 7.16205420e+03 7.19743604e+03 6.98507031e+03 6.92998193e+03 7.06000830e+03 7.19047705e+03 7.11030029e+03 6.95608301e+03 6.87177100e+03 6.95174756e+03 7.07079150e+03 6.86900195e+03 6.73194482e+03 6.73968750e+03 6.72019580e+03 6.86478662e+03 7.02979639e+03 6.86231885e+03 6.59053711e+03 6.55668213e+03 6.85065430e+03 6.87854053e+03 6.50542969e+03 6.65358203e+03 6.82628662e+03 6.47025146e+03 6.46556738e+03 6.42139062e+03 6.40433154e+03 6.65223193e+03 6.51849316e+03 6.29932568e+03 6.45657275e+03 6.45107666e+03 6.24577539e+03 6.31527490e+03 6.34317773e+03 6.29246143e+03 6.10529346e+03 6.03239746e+03 6.18995312e+03 6.26837549e+03 6.14769678e+03 5.93083008e+03 5.90637256e+03 6.08741113e+03 6.12295605e+03 5.86991309e+03 5.80011670e+03 5.83078906e+03 5.90511865e+03 5.93945654e+03 5.66373779e+03 5.64356396e+03 5.78814551e+03 5.76733545e+03 5.57924072e+03 5.64160449e+03 5.61779541e+03 5.43681348e+03 5.59088721e+03 5.62526709e+03 5.33332129e+03 5.14426074e+03 5.22910840e+03 5.33913965e+03 5.32519629e+03 5.24181982e+03 5.10801660e+03 5.07434570e+03 5.21229834e+03 5.21019580e+03 4.97491553e+03 4.89011426e+03 4.99251562e+03 5.09248584e+03 4.90046875e+03 4.71909326e+03 4.78796729e+03 4.74579297e+03 4.67689111e+03 4.65541992e+03 4.64798779e+03 4.59579150e+03 4.49499219e+03 4.50225195e+03 4.47721289e+03 4.39824951e+03 4.28027490e+03 4.25916357e+03 4.30049658e+03 4.26718164e+03 4.15570850e+03 4.10850732e+03 4.09473755e+03 4.15551270e+03 4.11529395e+03 3.91929614e+03 3.91731592e+03 3.91180640e+03 3.84194849e+03 3.75880859e+03 3.68420142e+03 3.73537036e+03 3.69148022e+03 3.55185278e+03 3.42751514e+03 3.49281152e+03 3.55710449e+03 3.45836279e+03 3.38815796e+03 3.31746313e+03 3.30064966e+03 3.18469385e+03 3.03561670e+03 3.08817773e+03 3.11361597e+03 3.07344800e+03 3.00559155e+03 2.86097339e+03 2.84197510e+03 2.85324341e+03 2.83738306e+03 2.82305835e+03 2.68740894e+03 2.57838550e+03 2.51533545e+03 2.53617212e+03 2.55939404e+03 2.48562256e+03 2.39812988e+03 2.24807178e+03 2.24963257e+03 2.27674658e+03 2.18015259e+03 2.15387109e+03 2.07140674e+03 2.00598608e+03 2.01595447e+03 1.92187598e+03 1.84928674e+03 1.86205981e+03 1.82199512e+03 1.70724500e+03 1.61264136e+03 1.58752649e+03 1.56473035e+03 1.55934363e+03 1.53178918e+03 1.42454626e+03 1.33955371e+03 1.27067322e+03 1.25486682e+03 1.24790466e+03 1.16860852e+03 1.08590796e+03 1.01417773e+03 9.79685913e+02 9.57182983e+02 9.16799194e+02 8.54953979e+02 7.88264709e+02 7.44833801e+02 6.79748291e+02 6.07247620e+02 5.70968018e+02 5.29066895e+02 4.79615295e+02 4.36477722e+02 3.65064270e+02 3.01655243e+02 2.59226990e+02 2.14673782e+02 1.61482635e+02 1.03000702e+02 4.97038116e+01 -2.84390545e+00 -5.58534126e+01 -1.11269310e+02 -1.63447525e+02 -2.13741684e+02 -2.60398560e+02 -3.19106415e+02 -3.72411591e+02 -4.12198853e+02 -4.74218689e+02 -5.39399414e+02 -5.89076416e+02 -6.37482422e+02 -6.77044373e+02 -7.35765137e+02 -8.07373596e+02 -8.62017334e+02 -9.12678223e+02 -9.27686951e+02 -9.73493042e+02 -1.05342236e+03 -1.12646228e+03 -1.19266833e+03 -1.22361670e+03 -1.26202588e+03 -1.27762415e+03 -1.35669055e+03 -1.46939417e+03 -1.48250244e+03 -1.52177954e+03 -1.57504749e+03 -1.61195068e+03 -1.65289856e+03 -1.71414868e+03 -1.78917273e+03 -1.86283252e+03 -1.92760767e+03 -1.92409290e+03 -1.92537109e+03 -2.01720374e+03 -2.10250806e+03 -2.16741895e+03 -2.23234399e+03 -2.22363599e+03 -2.28031396e+03 -2.32396069e+03 -2.38978052e+03 -2.51037158e+03 -2.50371875e+03 -2.53291382e+03 -2.56838770e+03 -2.55165796e+03 -2.65539526e+03 -2.85148193e+03 -2.86478687e+03 -2.80528491e+03 -2.89126904e+03 -2.90590771e+03 -2.87815430e+03 -3.00929272e+03 -3.11721680e+03 -3.15121606e+03 -3.20197437e+03 -3.16680347e+03 -3.23852148e+03 -3.35675024e+03 -3.42522900e+03 -3.57729688e+03 -3.52707593e+03 -3.38101392e+03 -3.42273267e+03 -3.60329224e+03 -3.73345898e+03 -3.75918481e+03 -3.75058105e+03 -3.64428833e+03 -3.77953003e+03 -3.98814380e+03 -3.95134692e+03 -3.97607202e+03 -3.96295093e+03 -4.00942798e+03 -4.15765869e+03 -4.09424023e+03 -4.11721631e+03 -4.37034180e+03 -4.41375732e+03 -4.35293066e+03 -4.28641064e+03 -4.21847461e+03 -4.36741357e+03 -4.58331738e+03 -4.74344238e+03 -4.68356689e+03 -4.48111768e+03 -4.49138916e+03 -4.69435889e+03 -4.85713867e+03 -4.81943555e+03 -4.80626904e+03 -4.74531396e+03 -4.81357178e+03 -4.99160449e+03 -5.09846729e+03 -5.12124414e+03 -5.08616553e+03 -5.16359766e+03 -5.14609766e+03 -5.03068750e+03 -5.16504639e+03 -5.31086182e+03 -5.38188770e+03 -5.49827637e+03 -5.34161035e+03 -5.23437305e+03 -5.43299756e+03 -5.55029785e+03 -5.70950830e+03 -5.66412109e+03 -5.46641064e+03 -5.43569287e+03 -5.64030469e+03 -5.89667236e+03 -5.95334717e+03 -5.78984375e+03 -5.72068555e+03 -5.77248291e+03 -5.77282471e+03 -5.84977881e+03 -6.00398828e+03 -6.11749805e+03 -6.02174951e+03 -5.90917334e+03 -5.90746387e+03 -6.05457178e+03 -6.25076221e+03 -6.34141553e+03 -6.32261084e+03 -6.13011035e+03 -5.99651611e+03 -6.15595996e+03 -6.36826367e+03 -6.55976709e+03 -6.50160205e+03 -6.26634521e+03 -6.15998535e+03 -6.39875879e+03 -6.69019189e+03 -6.56239893e+03 -6.60763379e+03 -6.54706250e+03 -6.41161768e+03 -6.59166162e+03 -6.70107812e+03 -6.70063574e+03 -6.65860693e+03 -6.74406006e+03 -6.78031299e+03 -6.69258691e+03 -6.74839648e+03 -6.79021777e+03 -6.95937891e+03 -6.95439404e+03 -6.78005811e+03 -6.80547949e+03 -6.76692627e+03 -6.89744873e+03 -7.29161621e+03 -7.13024805e+03 -6.83255762e+03 -6.81345117e+03 -6.94047656e+03 -7.20888428e+03 -7.37666064e+03 -7.16546240e+03 -6.94914990e+03 -7.05109619e+03 -7.21008789e+03 -7.11380029e+03 -7.28179443e+03 -7.25583691e+03 -8.19205078e+03 -7.83824561e+03 -8.81948730e+03 -1.66526973e+04 -2.41260371e+04 66448264. 2.31867550e+06 1.55539738e+06 -84543384. 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. 0. 0. 0. 0. 0. 0. 0. -419079328. -1.61748641e+05 -2.53477012e+04 -1.08691543e+04 -1.04096426e+04 -8.42958301e+03 -7.92454102e+03 -7.73463770e+03 -7.74262695e+03 -7.22370557e+03 -7.42778760e+03 -7.87316895e+03 -7.79529688e+03 -7.47251172e+03 -7.27279541e+03 -7.24124756e+03 -7.57874316e+03 -7.94757568e+03 -7.65761328e+03 -7.37372949e+03 -7.29854785e+03 -7.36188086e+03 -7.69392578e+03 -7.66372217e+03 -7.38303955e+03 -7.29477441e+03 -7.47679883e+03 -7.40497314e+03 -7.22391602e+03 -7.28165869e+03 -7.47810645e+03 -7.69095215e+03 -7.67129443e+03 -7.27153467e+03 -6.94239648e+03 -7.13487793e+03 -7.55355664e+03 -7.70557715e+03 -7.39488281e+03 -7.06314795e+03 -6.97556104e+03 -7.28372754e+03 -7.65846484e+03 -7.41475342e+03 -6.95880859e+03 -6.97864795e+03 -7.33744482e+03 -7.29509766e+03 -7.11561426e+03 -7.13213281e+03 -7.03966504e+03 -7.15747852e+03 -7.17385596e+03 -6.81966846e+03 -6.81720752e+03 -7.16816162e+03 -7.33716455e+03 -7.14565723e+03 -6.76978418e+03 -6.53487207e+03 -6.90875195e+03 -7.32813525e+03 -7.13636426e+03 -6.75149609e+03 -6.50248779e+03 -6.43148828e+03 -6.82298877e+03 -7.17091992e+03 -6.94784961e+03 -6.72541748e+03 -6.64629297e+03 -6.46488477e+03 -6.55367627e+03 -6.74913525e+03 -6.51236572e+03 -6.39548730e+03 -6.59771582e+03 -6.48615430e+03 -6.20819873e+03 -6.29306104e+03 -6.55999268e+03 -6.62374902e+03 -6.51791455e+03 -6.33587500e+03 -6.09884131e+03 -5.98982178e+03 -6.28342480e+03 -6.60419922e+03 -6.30443115e+03 -5.90827051e+03 -5.85640674e+03 -6.08478613e+03 -6.31492041e+03 -6.25774561e+03 -5.94032568e+03 -5.82236133e+03 -5.95589014e+03 -5.91096387e+03 -5.85193213e+03 -5.84229639e+03 -5.77278906e+03 -5.79275000e+03 -5.74880029e+03 -5.54761572e+03 -5.57571631e+03 -5.68545557e+03 -5.74714697e+03 -5.69933643e+03 -5.52998047e+03 -5.29160205e+03 -5.29192920e+03 -5.55720264e+03 -5.60103027e+03 -5.31849072e+03 -5.10587988e+03 -5.00940234e+03 -5.24260547e+03 -5.50138477e+03 -5.26097217e+03 -4.95824609e+03 -4.94342773e+03 -5.03185938e+03 -4.98745117e+03 -4.85652686e+03 -4.83063721e+03 -4.96618555e+03 -4.95802100e+03 -4.77965381e+03 -4.60798779e+03 -4.55827734e+03 -4.72152197e+03 -4.85841650e+03 -4.72832764e+03 -4.50861768e+03 -4.36351807e+03 -4.26198145e+03 -4.40437109e+03 -4.59254297e+03 -4.38655078e+03 -4.13967969e+03 -4.08086230e+03 -4.21736328e+03 -4.34502246e+03 -4.17275781e+03 -3.99536426e+03 -3.95458960e+03 -3.96243066e+03 -3.97792261e+03 -3.91082227e+03 -3.75054785e+03 -3.67078809e+03 -3.78354370e+03 -3.79988770e+03 -3.61934033e+03 -3.49889160e+03 -3.51241724e+03 -3.56123730e+03 -3.59773071e+03 -3.48359985e+03 -3.25181421e+03 -3.22550684e+03 -3.30349683e+03 -3.28403125e+03 -3.18472095e+03 -3.09185596e+03 -3.03386157e+03 -2.99956079e+03 -3.01142480e+03 -2.92574829e+03 -2.82443945e+03 -2.86536353e+03 -2.86475171e+03 -2.75029126e+03 -2.62576611e+03 -2.57390967e+03 -2.60266455e+03 -2.63508423e+03 -2.57288574e+03 -2.44013721e+03 -2.31145215e+03 -2.24404419e+03 -2.29901636e+03 -2.36568140e+03 -2.23321362e+03 -2.05948120e+03 -2.00561267e+03 -2.03747607e+03 -2.05734619e+03 -1.98298962e+03 -1.87512939e+03 -1.80903687e+03 -1.76547705e+03 -1.70492358e+03 -1.66596008e+03 -1.63090308e+03 -1.57507178e+03 -1.53140881e+03 -1.47085059e+03 -1.38772876e+03 -1.34568347e+03 -1.32758911e+03 -1.28969812e+03 -1.23440771e+03 -1.13141724e+03 -1.05319519e+03 -1.05536133e+03 -1.04906628e+03 -9.77607727e+02 -8.92359680e+02 -8.15375610e+02 -7.53405334e+02 -7.41020264e+02 -7.28403625e+02 -6.53677490e+02 -5.66329163e+02 -5.07858582e+02 -4.72212677e+02 -4.29894714e+02 -3.75609009e+02 -3.19077911e+02 -2.63677032e+02 -2.10295502e+02 -1.55157898e+02 -9.98056335e+01 -4.93501968e+01 2.47986841e+00 5.61476974e+01 1.12877480e+02 1.63619629e+02 2.04245300e+02 2.54170792e+02 3.17096527e+02 3.81297119e+02 4.32930542e+02 4.75460846e+02 5.40722595e+02 5.99111328e+02 6.22565308e+02 6.52570496e+02 7.19839233e+02 8.12286438e+02 8.91830139e+02 9.29116577e+02 9.26675110e+02 9.50407288e+02 1.02378137e+03 1.13047559e+03 1.22366138e+03 1.24926489e+03 1.23239807e+03 1.27735303e+03 1.41014807e+03 1.46333289e+03 1.45034875e+03 1.49968689e+03 1.55740649e+03 1.61074121e+03 1.72312744e+03 1.74063757e+03 1.73855566e+03 1.82512842e+03 1.83025854e+03 1.93977893e+03 2.04226221e+03 1.98321863e+03 2.08013647e+03 2.19659570e+03 2.18826538e+03 2.23284155e+03 2.29208154e+03 2.34869067e+03 2.41096948e+03 2.44228882e+03 2.42174243e+03 2.47776929e+03 2.65256030e+03 2.77267627e+03 2.75029297e+03 2.67470361e+03 2.66505566e+03 2.78366479e+03 2.95981812e+03 3.07320459e+03 3.05588208e+03 2.95019995e+03 3.00834229e+03 3.15944116e+03 3.18259790e+03 3.21266895e+03 3.26746851e+03 3.30274390e+03 3.35007251e+03 3.53707349e+03 3.49088232e+03 3.40302783e+03 3.53715234e+03 3.50551489e+03 3.67217700e+03 3.79920190e+03 3.71604492e+03 3.90984351e+03 3.85270410e+03 3.74148975e+03 3.91465039e+03 3.87201147e+03 3.98972656e+03 4.30951807e+03 4.13836572e+03 3.93820703e+03 4.05780566e+03 4.28297900e+03 4.51418457e+03 4.48431689e+03 4.27679932e+03 4.17248682e+03 4.30537402e+03 4.58930176e+03 4.77243115e+03 4.73301367e+03 4.53261182e+03 4.53012158e+03 4.71454883e+03 4.81983252e+03 4.78210498e+03 4.75209229e+03 4.84470361e+03 4.91513867e+03 5.08008057e+03 5.10633203e+03 4.91337598e+03 4.97498828e+03 5.06030273e+03 5.11212842e+03 5.21347119e+03 5.24446338e+03 5.40753760e+03 5.32602979e+03 5.16392236e+03 5.34653027e+03 5.25160645e+03 5.40928320e+03 5.81686963e+03 5.57890918e+03 5.27420850e+03 5.39441650e+03 5.69458545e+03 5.91872168e+03 5.93417529e+03 5.67941260e+03 5.48438867e+03 5.61143994e+03 5.94187158e+03 6.18462988e+03 6.03631885e+03 5.75326318e+03 5.75218018e+03 5.95402246e+03 6.10260400e+03 6.30263525e+03 6.33238281e+03 5.96643164e+03 5.92999658e+03 6.27426465e+03 6.38570557e+03 6.16532812e+03 6.17728174e+03 6.28957520e+03 6.25952051e+03 6.49916064e+03 6.60266455e+03 6.26118994e+03 6.29216846e+03 6.49101562e+03 6.52275928e+03 6.54163721e+03 6.48175000e+03 6.63055762e+03 6.78788721e+03 6.66525879e+03 6.52128809e+03 6.39266797e+03 6.68973438e+03 7.06687549e+03 6.97504980e+03 6.65068115e+03 6.48859912e+03 6.70504150e+03 7.15224902e+03 7.00061328e+03 6.62375488e+03 6.70003906e+03 6.91847021e+03 7.12964258e+03 7.39487988e+03 7.19888818e+03 6.83532812e+03 6.70648535e+03 6.94317871e+03 7.28465381e+03 7.27693750e+03 7.13573340e+03 7.09541553e+03 7.12810059e+03 7.29824121e+03 7.26187891e+03 7.09754736e+03 7.10063867e+03 6.97995166e+03 7.31439062e+03 7.56867578e+03 7.28497607e+03 7.27977686e+03 7.34373340e+03 7.49188965e+03 7.31322070e+03 7.01440283e+03 7.32170947e+03 7.71748438e+03 7.53239062e+03 7.17747705e+03 7.23885938e+03 7.64852686e+03 7.63101514e+03 7.48111475e+03 7.49701318e+03 7.22873242e+03 7.21120947e+03 7.72772266e+03 7.70589941e+03 7.42875049e+03 7.23490479e+03 7.20227490e+03 7.54055615e+03 7.90114209e+03 7.57436084e+03 7.39489844e+03 7.53758936e+03 7.51478271e+03 7.79914990e+03 7.77602197e+03 7.36207080e+03 7.33062256e+03 7.54999365e+03 7.57190430e+03 7.57576514e+03 7.57057129e+03 7.75872021e+03 7.63403711e+03 7.37035400e+03 7.48356543e+03 7.32319141e+03 7.61853174e+03 8.04719385e+03 7.82931592e+03 7.33753662e+03 7.32999854e+03 7.63656689e+03 7.83985254e+03 7.99723926e+03 8.88833398e+03 8.47221777e+03 1.00521514e+04 4.54912578e+04 -16867494. 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. 0. 0. 0. 0. 0. 0. -15821683. 7.22483359e+04 1.15796025e+04 1.00061348e+04 8.00272119e+03 7.74201074e+03 7.13068213e+03 7.01655859e+03 7.01639258e+03 6.80318896e+03 7.04798584e+03 7.02289551e+03 6.83748096e+03 6.98538965e+03 6.98273926e+03 6.85717529e+03 6.84724805e+03 6.80463818e+03 6.78465967e+03 6.78410107e+03 6.74745361e+03 6.68789209e+03 6.55171875e+03 6.52030615e+03 6.76103711e+03 6.77678711e+03 6.43583496e+03 6.37901318e+03 6.70262256e+03 6.69349219e+03 6.50488135e+03 6.47456152e+03 6.40991504e+03 6.41075635e+03 6.37345947e+03 6.32922070e+03 6.29643896e+03 6.24097119e+03 6.09275830e+03 6.05788281e+03 6.31250000e+03 6.29641016e+03 6.11470117e+03 6.08950342e+03 6.06948877e+03 6.05707373e+03 5.99721094e+03 5.94255762e+03 5.93580078e+03 5.74023779e+03 5.69634131e+03 5.80934375e+03 5.76267139e+03 5.93421729e+03 5.94077490e+03 5.71510303e+03 5.48083594e+03 5.40285840e+03 5.75719434e+03 5.77430518e+03 5.51043018e+03 5.39635303e+03 5.40816504e+03 5.35747266e+03 5.26594727e+03 5.47429688e+03 5.41069678e+03 5.05478662e+03 5.01273975e+03 5.24002930e+03 5.38511816e+03 5.20094189e+03 5.05909277e+03 5.04592432e+03 4.97762158e+03 4.89618750e+03 4.88340088e+03 4.89680908e+03 4.83995801e+03 4.68715869e+03 4.64317139e+03 4.70141406e+03 4.64683984e+03 4.72272070e+03 4.61207129e+03 4.44541943e+03 4.47795898e+03 4.43469678e+03 4.48013477e+03 4.47231689e+03 4.33460889e+03 4.26973340e+03 4.13308740e+03 4.00788647e+03 4.16791504e+03 4.17468262e+03 3.91654932e+03 3.90305664e+03 4.08187671e+03 4.14863232e+03 3.98331519e+03 3.82594360e+03 3.75955811e+03 3.71455078e+03 3.63873877e+03 3.58935156e+03 3.61458862e+03 3.55160449e+03 3.56191235e+03 3.47588721e+03 3.35333569e+03 3.38073682e+03 3.24036182e+03 3.23896313e+03 3.37208838e+03 3.26616772e+03 3.13512573e+03 2.99301660e+03 2.92951440e+03 3.05533545e+03 3.02744775e+03 2.87868652e+03 2.75356519e+03 2.70327173e+03 2.72922437e+03 2.67892651e+03 2.70696216e+03 2.67401416e+03 2.53427051e+03 2.44156787e+03 2.40102515e+03 2.43744116e+03 2.38465283e+03 2.28232812e+03 2.19179834e+03 2.13953662e+03 2.13794165e+03 2.03259265e+03 2.00403967e+03 2.07619653e+03 1.99428027e+03 1.88524475e+03 1.78213635e+03 1.72394946e+03 1.77896118e+03 1.73094470e+03 1.62979431e+03 1.53105286e+03 1.46992004e+03 1.47286011e+03 1.41942346e+03 1.36002625e+03 1.27992725e+03 1.25198608e+03 1.25110547e+03 1.16705261e+03 1.12051782e+03 1.07693982e+03 1.00514154e+03 9.29445435e+02 8.76157471e+02 8.44532715e+02 7.92726746e+02 7.42278870e+02 6.66417786e+02 6.21013367e+02 6.08175415e+02 5.29505920e+02 4.59658386e+02 4.19767487e+02 3.66734680e+02 3.23830780e+02 2.65286438e+02 2.04112808e+02 1.60252106e+02 1.07601151e+02 5.24304085e+01 -7.51788557e-01 -5.34225578e+01 -1.05086670e+02 -1.57487274e+02 -2.13485260e+02 -2.59174835e+02 -3.16735046e+02 -3.91602203e+02 -4.37435089e+02 -4.69137146e+02 -5.03663727e+02 -5.72437744e+02 -6.66471375e+02 -7.07135742e+02 -7.37934875e+02 -7.77146423e+02 -8.23023132e+02 -8.97261536e+02 -9.49159729e+02 -1.02373828e+03 -1.06095154e+03 -1.07865588e+03 -1.15991528e+03 -1.21435315e+03 -1.29031580e+03 -1.33683362e+03 -1.35509985e+03 -1.39953210e+03 -1.45001038e+03 -1.53229602e+03 -1.54208118e+03 -1.61822632e+03 -1.76760510e+03 -1.77685181e+03 -1.78086121e+03 -1.78559448e+03 -1.82632507e+03 -1.98365601e+03 -2.04704004e+03 -2.04149255e+03 -2.03035498e+03 -2.07932031e+03 -2.19909717e+03 -2.25084814e+03 -2.35663623e+03 -2.39743262e+03 -2.39144482e+03 -2.36729834e+03 -2.40794214e+03 -2.62084497e+03 -2.64768164e+03 -2.61505176e+03 -2.63626367e+03 -2.67536719e+03 -2.85654517e+03 -2.92377686e+03 -2.82712573e+03 -2.85301294e+03 -3.05292627e+03 -3.11170166e+03 -3.00177954e+03 -3.04025000e+03 -3.25802368e+03 -3.31377637e+03 -3.25335376e+03 -3.23016040e+03 -3.27090308e+03 -3.51019727e+03 -3.54562012e+03 -3.46809253e+03 -3.51046973e+03 -3.53958936e+03 -3.65139966e+03 -3.71599805e+03 -3.72100635e+03 -3.67327612e+03 -3.80542407e+03 -4.02223486e+03 -3.94832080e+03 -4.01851636e+03 -4.11290283e+03 -4.07010376e+03 -4.11626465e+03 -4.15917676e+03 -4.16662939e+03 -4.12860498e+03 -4.15735498e+03 -4.30335645e+03 -4.36605029e+03 -4.54169824e+03 -4.44926953e+03 -4.35217334e+03 -4.51403369e+03 -4.58883691e+03 -4.76881982e+03 -4.73962256e+03 -4.64620459e+03 -4.68945947e+03 -4.71056104e+03 -4.82407324e+03 -4.86919727e+03 -5.00832324e+03 -5.00550732e+03 -4.91513379e+03 -4.98602393e+03 -4.88525000e+03 -5.08931592e+03 -5.44050635e+03 -5.32497070e+03 -5.21760107e+03 -5.13080859e+03 -5.08431934e+03 -5.39752002e+03 -5.61108496e+03 -5.48081104e+03 -5.30992676e+03 -5.31494482e+03 -5.51471484e+03 -5.54752393e+03 -5.70912012e+03 -5.69050391e+03 -5.57128613e+03 -5.68577246e+03 -5.71067090e+03 -5.89747412e+03 -5.94376904e+03 -5.65383301e+03 -5.70248779e+03 -6.04965527e+03 -5.98905713e+03 -5.71318750e+03 -5.93301270e+03 -6.29407422e+03 -6.22836133e+03 -6.09113916e+03 -5.96302637e+03 -6.01116260e+03 -6.37859863e+03 -6.40336133e+03 -6.25265039e+03 -6.10862451e+03 -6.09584424e+03 -6.35854688e+03 -6.37203076e+03 -6.38677783e+03 -6.26950244e+03 -6.44390625e+03 -6.68472070e+03 -6.51800635e+03 -6.65932617e+03 -6.57840674e+03 -6.43137646e+03 -6.59189453e+03 -6.66938672e+03 -6.68896143e+03 -6.64739404e+03 -6.59062158e+03 -6.52803076e+03 -6.74141211e+03 -7.17683057e+03 -6.82416309e+03 -6.50022119e+03 -6.74129346e+03 -6.98203711e+03 -7.18596143e+03 -7.03040723e+03 -6.86258203e+03 -7.04777490e+03 -7.08835059e+03 -6.83369531e+03 -6.75385596e+03 -7.15509424e+03 -7.22312939e+03 -6.98761670e+03 -7.02417139e+03 -6.79252246e+03 -7.06795166e+03 -7.51449756e+03 -7.31018945e+03 -7.18530371e+03 -6.97538184e+03 -6.89862500e+03 -7.32487500e+03 -7.68343652e+03 -7.46579102e+03 -7.08552002e+03 -7.07684277e+03 -7.26960059e+03 -7.30539600e+03 -7.54667969e+03 -7.35088330e+03 -7.17196143e+03 -7.40718311e+03 -7.37492676e+03 -7.56836523e+03 -7.52020703e+03 -7.27062695e+03 -7.48089014e+03 -7.50474512e+03 -7.44018701e+03 -7.23515332e+03 -7.34364111e+03 -7.79322998e+03 -7.68012695e+03 -7.38461084e+03 -7.24163037e+03 -7.40398486e+03 -7.84487158e+03 -7.74571143e+03 -7.48987207e+03 -7.32937598e+03 -7.32718994e+03 -7.52369287e+03 -7.62289453e+03 -7.56901904e+03 -7.39215918e+03 -7.52263867e+03 -7.81767236e+03 -7.55957764e+03 -7.71478613e+03 -7.75465137e+03 -7.54404004e+03 -7.51933154e+03 -7.56065479e+03 -7.55692432e+03 -7.54688135e+03 -7.46451904e+03 -7.45031787e+03 -7.75857031e+03 -7.81408252e+03 -7.36356104e+03 -7.28933203e+03 -7.43343848e+03 -7.61998242e+03 -7.88185059e+03 -7.68197656e+03 -7.23272803e+03 -7.51943359e+03 -7.84568750e+03 -7.69704980e+03 -7.35741553e+03 -7.33575000e+03 -7.39693848e+03 -7.46336182e+03 -7.49515576e+03 -7.27441650e+03 -7.43582422e+03 -7.79546973e+03 -7.62684229e+03 -7.41403857e+03 -7.28166699e+03 -7.29053857e+03 -7.67208154e+03 -7.61628564e+03 -7.41728027e+03 -7.26864355e+03 -7.02514941e+03 -7.14128125e+03 -7.56943994e+03 -7.81087451e+03 -7.34684131e+03 -7.02581055e+03 -7.22202002e+03 -7.35411816e+03 -7.58744873e+03 -7.42676416e+03 -7.14210254e+03 -7.27041504e+03 -7.24402051e+03 -7.15190576e+03 -6.97596680e+03 -7.11675391e+03 -7.41173096e+03 -7.26991309e+03 -7.15808643e+03 -6.99130957e+03 -6.96475000e+03 -7.30652148e+03 -7.28558936e+03 -7.08428662e+03 -6.86104492e+03 -6.76051807e+03 -6.95165918e+03 -6.91191748e+03 -7.11363721e+03 -7.16814209e+03 -6.80200195e+03 -6.63893066e+03 -6.86040283e+03 -7.07936230e+03 -6.86901807e+03 -6.73835938e+03 -6.68477686e+03 -6.64966016e+03 -6.60531982e+03 -6.46625293e+03 -6.69263428e+03 -6.79622412e+03 -6.54998682e+03 -6.69323340e+03 -6.71603760e+03 -6.61682715e+03 -6.55474561e+03 -6.48016650e+03 -6.43420801e+03 -6.27153271e+03 -6.16933398e+03 -6.41519189e+03 -6.55013037e+03 -6.21137158e+03 -5.94438965e+03 -6.17347656e+03 -6.49681396e+03 -6.45548242e+03 -6.08627588e+03 -5.83606494e+03 -6.12283887e+03 -6.31791699e+03 -6.12540527e+03 -6.05805566e+03 -5.84081104e+03 -5.58397998e+03 -5.79184668e+03 -6.11109961e+03 -6.09993262e+03 -5.72305371e+03 -5.47820410e+03 -5.77217725e+03 -5.97967725e+03 -5.77326904e+03 -5.46606299e+03 -5.28486865e+03 -5.44953418e+03 -5.52480811e+03 -5.62109424e+03 -5.64645166e+03 -5.42562891e+03 -5.27226611e+03 -5.23336133e+03 -5.43212549e+03 -5.26557471e+03 -5.08213281e+03 -5.27767725e+03 -5.21704443e+03 -5.12023633e+03 -4.96571143e+03 -4.92258643e+03 -5.15434521e+03 -4.96449805e+03 -4.67987158e+03 -4.77014355e+03 -4.91381299e+03 -4.88179297e+03 -4.74331006e+03 -4.80111035e+03 -4.80204492e+03 -4.63521533e+03 -4.45551807e+03 -4.39042334e+03 -4.60174121e+03 -4.47377637e+03 -4.29678369e+03 -4.37947021e+03 -4.32773828e+03 -4.26819287e+03 -4.16877197e+03 -4.22427588e+03 -4.21469678e+03 -4.06514478e+03 -4.08708350e+03 -4.04575586e+03 -4.02934888e+03 -3.97773926e+03 -3.87626123e+03 -3.76720288e+03 -3.62320459e+03 -3.58890356e+03 -3.73822241e+03 -3.87503955e+03 -3.61828394e+03 -3.34892529e+03 -3.43732568e+03 -3.60514722e+03 -3.57446729e+03 -3.34326050e+03 -3.15410840e+03 -3.27560034e+03 -3.30145874e+03 -3.14124097e+03 -3.20965356e+03 -3.11394507e+03 -2.88518701e+03 -2.91770679e+03 -3.04113721e+03 -2.99194312e+03 -2.79718677e+03 -2.64742529e+03 -2.71419800e+03 -2.83348145e+03 -2.71851196e+03 -2.53064478e+03 -2.41810864e+03 -2.48355371e+03 -2.52329346e+03 -2.40119531e+03 -2.32517725e+03 -2.28204785e+03 -2.24303174e+03 -2.18427368e+03 -2.18767114e+03 -2.09516919e+03 -1.97803064e+03 -1.98062500e+03 -1.93737268e+03 -1.92609790e+03 -1.83461670e+03 -1.73501099e+03 -1.75647424e+03 -1.65164734e+03 -1.56210889e+03 -1.57524670e+03 -1.54908655e+03 -1.48846680e+03 -1.41249207e+03 -1.40448792e+03 -1.35777075e+03 -1.25792053e+03 -1.17807227e+03 -1.12312390e+03 -1.13673181e+03 -1.06382605e+03 -9.51649597e+02 -9.42843262e+02 -9.78059326e+02 -9.32817078e+02 -8.23333618e+02 -8.11798279e+02 -1.69367725e+03 -2.45293604e+03 1.44595953e+05 -46060172. 0. 0. 0. 0. 0. 1355850624. -8.61302031e+04 1.62657861e+04 -4.36760586e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 142385600. 2872176. 3.66754565e+03 1.84445703e+03 9.75788086e+02 8.59637512e+02 9.15331482e+02 9.63731995e+02 9.71127380e+02 1.00905957e+03 1.04672559e+03 1.06305566e+03 1.14226782e+03 1.23362500e+03 1.24374512e+03 1.27568311e+03 1.35177551e+03 1.41809265e+03 1.47233093e+03 1.47699792e+03 1.48363904e+03 1.55990405e+03 1.64872510e+03 1.71020813e+03 1.74323413e+03 1.75312354e+03 1.80666284e+03 1.91790918e+03 2.00332153e+03 1.98936792e+03 1.95844263e+03 2.02922681e+03 2.13934375e+03 2.16907812e+03 2.20486499e+03 2.27271118e+03 2.26296362e+03 2.34610303e+03 2.45015845e+03 2.39865112e+03 2.43865601e+03 2.56185205e+03 2.70370972e+03 2.76404175e+03 2.62655957e+03 2.58676782e+03 2.71127197e+03 2.87389062e+03 2.95581689e+03 2.88611987e+03 2.91531934e+03 3.06007056e+03 3.08110400e+03 3.11471729e+03 3.11901416e+03 3.06604297e+03 3.21285327e+03 3.37052124e+03 3.30107935e+03 3.31766577e+03 3.44160571e+03 3.43134595e+03 3.53154395e+03 3.60206445e+03 3.52129761e+03 3.54107202e+03 3.65419653e+03 3.81762158e+03 3.83247925e+03 3.74120728e+03 3.81144629e+03 3.83996143e+03 3.91915088e+03 4.05386670e+03 3.95834863e+03 3.95671387e+03 4.11011475e+03 4.20921973e+03 4.27621338e+03 4.20384961e+03 4.09467725e+03 4.17447754e+03 4.35479199e+03 4.47298096e+03 4.48718115e+03 4.43877930e+03 4.42325684e+03 4.56560303e+03 4.69404199e+03 4.58515625e+03 4.49167432e+03 4.61454102e+03 4.81999219e+03 4.87098145e+03 4.83377441e+03 4.74721094e+03 4.72221875e+03 4.92390674e+03 5.05111816e+03 4.90692969e+03 4.93907227e+03 5.11636963e+03 5.26542139e+03 5.28602441e+03 5.06481836e+03 4.96659766e+03 5.17227393e+03 5.28588965e+03 5.30411133e+03 5.30297363e+03 5.37474365e+03 5.50077197e+03 5.43247949e+03 5.41357617e+03 5.55789795e+03 5.46713623e+03 5.46083350e+03 5.65112793e+03 5.68550977e+03 5.73509131e+03 5.67005713e+03 5.54762061e+03 5.65159863e+03 5.79445312e+03 5.92617871e+03 5.88236182e+03 5.77587305e+03 5.86514453e+03 6.04138770e+03 6.09958643e+03 5.93184717e+03 5.79134473e+03 5.91248535e+03 6.09739990e+03 6.14710254e+03 6.09363965e+03 6.07528271e+03 6.08622998e+03 6.27059473e+03 6.36632324e+03 6.27237305e+03 6.23252148e+03 6.16632764e+03 6.25587891e+03 6.31812744e+03 6.23919824e+03 6.32276758e+03 6.39266797e+03 6.53938330e+03 6.65940332e+03 6.43386963e+03 6.30137061e+03 6.43920215e+03 6.57855029e+03 6.68529004e+03 6.64271533e+03 6.39105322e+03 6.42561377e+03 6.76207422e+03 6.94428467e+03 6.66426270e+03 6.48117236e+03 6.60979736e+03 6.86957373e+03 6.81093506e+03 6.54066748e+03 6.59184082e+03 6.82789160e+03 6.85249707e+03 6.82978223e+03 6.88288525e+03 6.93051709e+03 6.68843066e+03 6.87457568e+03 7.03940234e+03 6.74259570e+03 6.79224072e+03 6.96527002e+03 6.99682617e+03 7.06396631e+03 6.93960400e+03 6.72545410e+03 6.77047559e+03 7.00479736e+03 7.24934717e+03 7.27176172e+03 6.84333203e+03 6.89009619e+03 7.28343652e+03 7.09871777e+03 6.84606250e+03 6.89015723e+03 7.03559131e+03 7.15721582e+03 7.30979980e+03 7.24229004e+03 7.03151904e+03 6.85474219e+03 7.12406006e+03 7.25501025e+03 7.06100244e+03 7.04602148e+03 7.18308789e+03 7.31356836e+03 7.30031250e+03 7.09476611e+03 6.90497217e+03 6.98439502e+03 7.16254102e+03 7.33314355e+03 7.38094092e+03 6.99785547e+03 7.02155469e+03 7.26821045e+03 7.28718555e+03 7.16318604e+03 7.05095654e+03 7.07848145e+03 7.26926562e+03 7.31544385e+03 7.23636768e+03 7.06339648e+03 6.95281348e+03 7.08679150e+03 7.23360303e+03 7.06960645e+03 7.13422510e+03 7.19592871e+03 7.23193506e+03 7.34620361e+03 7.04668066e+03 6.87723633e+03 7.08907764e+03 7.08936279e+03 7.18587695e+03 6.96554248e+03 6.83283887e+03 7.09566748e+03 7.28209375e+03 7.16940088e+03 6.96549512e+03 7.02829834e+03 6.90701367e+03 6.88358838e+03 7.06048096e+03 7.25473730e+03 7.07227002e+03 6.80169922e+03 7.03087109e+03 6.93353662e+03 6.92896484e+03 6.95474854e+03 6.71738428e+03 6.90797217e+03 7.04328320e+03 6.80001172e+03 6.62140625e+03 6.75899512e+03 7.01603125e+03 7.04788525e+03 6.66862646e+03 6.58036035e+03 6.75963770e+03 6.82970850e+03 6.86273779e+03 6.66235254e+03 6.64560596e+03 6.56406738e+03 6.56662012e+03 6.80422021e+03 6.69642139e+03 6.41296875e+03 6.55548242e+03 6.75105908e+03 6.51307080e+03 6.44210303e+03 6.35960547e+03 6.29735547e+03 6.56076367e+03 6.66291406e+03 6.38491797e+03 6.26305371e+03 6.31611475e+03 6.43880615e+03 6.47836230e+03 6.24726904e+03 6.35490918e+03 6.35799902e+03 6.04041113e+03 6.07569287e+03 6.12464697e+03 6.10600684e+03 6.20720654e+03 6.13130078e+03 6.05708447e+03 6.16820459e+03 6.01757520e+03 5.87507715e+03 5.98189062e+03 6.02860742e+03 5.96690869e+03 5.74902588e+03 5.70192725e+03 5.92590625e+03 5.98735791e+03 5.71681494e+03 5.57731299e+03 5.63188086e+03 5.76091064e+03 5.79278809e+03 5.57937061e+03 5.51327002e+03 5.47758496e+03 5.54246240e+03 5.61445068e+03 5.40509668e+03 5.36547998e+03 5.36454053e+03 5.32504785e+03 5.35944092e+03 5.42484521e+03 5.27238330e+03 5.07972656e+03 5.26182080e+03 5.38744287e+03 5.11257471e+03 4.87500684e+03 4.96751172e+03 5.06815186e+03 5.03389697e+03 4.90643311e+03 4.82957178e+03 4.82834473e+03 4.90219678e+03 4.89248242e+03 4.72460791e+03 4.67456787e+03 4.66614502e+03 4.73218701e+03 4.64013428e+03 4.49149268e+03 4.52565234e+03 4.45878955e+03 4.40880029e+03 4.46174805e+03 4.42426270e+03 4.28570898e+03 4.23443506e+03 4.29016846e+03 4.26905029e+03 4.13047314e+03 4.05603906e+03 4.06023486e+03 4.11355322e+03 4.05599976e+03 3.87111670e+03 3.84399268e+03 3.87551270e+03 3.94004126e+03 3.91603027e+03 3.72822632e+03 3.76126831e+03 3.68223901e+03 3.50869263e+03 3.50779541e+03 3.51687183e+03 3.56821338e+03 3.51365405e+03 3.32537842e+03 3.24623438e+03 3.30293921e+03 3.37078540e+03 3.30553662e+03 3.19473413e+03 3.12882202e+03 3.05996729e+03 2.98709521e+03 2.93438232e+03 2.98065283e+03 2.97690308e+03 2.84786719e+03 2.79313550e+03 2.74432056e+03 2.73295483e+03 2.71409033e+03 2.65923193e+03 2.66701538e+03 2.53639941e+03 2.39560938e+03 2.37913843e+03 2.40349951e+03 2.41963721e+03 2.39185718e+03 2.27070801e+03 2.10877173e+03 2.10851562e+03 2.12907788e+03 2.06135083e+03 2.06075024e+03 2.00260120e+03 1.88241931e+03 1.88768848e+03 1.85620959e+03 1.76539270e+03 1.73627454e+03 1.67057263e+03 1.60116931e+03 1.55330896e+03 1.51472009e+03 1.48280933e+03 1.47560791e+03 1.46060437e+03 1.34665833e+03 1.24262366e+03 1.20284265e+03 1.18755566e+03 1.17582751e+03 1.11689246e+03 1.01924011e+03 9.57835815e+02 9.37116272e+02 9.16410461e+02 8.69881531e+02 7.99336609e+02 7.44475403e+02 6.93627930e+02 6.37624817e+02 5.85205933e+02 5.49404541e+02 5.06203827e+02 4.49648407e+02 4.04660767e+02 3.42915497e+02 2.90939514e+02 2.49360641e+02 2.00656967e+02 1.52267990e+02 9.75844269e+01 4.63816605e+01 -2.50952363e+00 -5.26627998e+01 -1.05147308e+02 -1.57030457e+02 -2.02228622e+02 -2.42172287e+02 -2.96125946e+02 -3.51017700e+02 -3.95035706e+02 -4.55790070e+02 -5.15449097e+02 -5.47596924e+02 -5.90112366e+02 -6.45147949e+02 -7.09084900e+02 -7.70223083e+02 -8.08164490e+02 -8.56181641e+02 -8.77062073e+02 -9.20453796e+02 -1.00249762e+03 -1.05593262e+03 -1.12136145e+03 -1.17352222e+03 -1.18638025e+03 -1.20517969e+03 -1.28358093e+03 -1.38355505e+03 -1.41657715e+03 -1.44153406e+03 -1.48823633e+03 -1.51186865e+03 -1.57321472e+03 -1.65085449e+03 -1.69202930e+03 -1.75079688e+03 -1.78224988e+03 -1.80010925e+03 -1.84425415e+03 -1.94672986e+03 -2.00958240e+03 -2.03245093e+03 -2.09852881e+03 -2.08705078e+03 -2.15302271e+03 -2.23835400e+03 -2.26578003e+03 -2.37264478e+03 -2.36779297e+03 -2.33803027e+03 -2.40503857e+03 -2.45284229e+03 -2.55814941e+03 -2.71727148e+03 -2.70866309e+03 -2.63686353e+03 -2.67205298e+03 -2.72087036e+03 -2.76206470e+03 -2.89415503e+03 -2.97991675e+03 -2.93656152e+03 -2.96088623e+03 -3.00872949e+03 -3.12000952e+03 -3.20666870e+03 -3.21240601e+03 -3.35377637e+03 -3.31358667e+03 -3.15614502e+03 -3.26247632e+03 -3.43708691e+03 -3.53489624e+03 -3.60805859e+03 -3.52889673e+03 -3.40500171e+03 -3.55541309e+03 -3.78226343e+03 -3.79165991e+03 -3.76138623e+03 -3.77922705e+03 -3.75796582e+03 -3.87560962e+03 -3.95881616e+03 -3.91880566e+03 -4.09467212e+03 -4.08542261e+03 -4.07197437e+03 -4.14180176e+03 -4.06628247e+03 -4.16616357e+03 -4.29843896e+03 -4.44886230e+03 -4.39055957e+03 -4.18586035e+03 -4.28103760e+03 -4.46154248e+03 -4.59078320e+03 -4.60514893e+03 -4.49773730e+03 -4.47428027e+03 -4.60958203e+03 -4.74695557e+03 -4.81899463e+03 -4.82592236e+03 -4.81042480e+03 -4.80157227e+03 -4.85799023e+03 -4.89088672e+03 -4.92340527e+03 -5.00687207e+03 -5.06329346e+03 -5.13566211e+03 -5.01194141e+03 -5.02399512e+03 -5.21335498e+03 -5.21476758e+03 -5.37078906e+03 -5.31696436e+03 -5.11925244e+03 -5.17943457e+03 -5.33072217e+03 -5.53030127e+03 -5.68205811e+03 -5.47882520e+03 -5.33616406e+03 -5.44143994e+03 -5.55564746e+03 -5.61234082e+03 -5.65775342e+03 -5.72252686e+03 -5.61586523e+03 -5.55314502e+03 -5.67942139e+03 -5.81439697e+03 -5.94610107e+03 -5.92302148e+03 -5.95249170e+03 -5.82334863e+03 -5.67614014e+03 -5.83261230e+03 -5.98053516e+03 -6.15984961e+03 -6.17828271e+03 -5.87113770e+03 -5.85404346e+03 -6.08291797e+03 -6.33284570e+03 -6.26123047e+03 -6.20095947e+03 -6.21417627e+03 -6.03035547e+03 -6.21234180e+03 -6.42312598e+03 -6.32606152e+03 -6.29948389e+03 -6.30070752e+03 -6.38689795e+03 -6.41490283e+03 -6.38509375e+03 -6.46987598e+03 -6.52966699e+03 -6.50691553e+03 -6.38214893e+03 -6.46287891e+03 -6.57041064e+03 -6.58135010e+03 -6.80766943e+03 -6.64875928e+03 -6.43999170e+03 -6.55049365e+03 -6.49503223e+03 -6.77927393e+03 -7.04884521e+03 -6.83067920e+03 -6.56879102e+03 -6.51658691e+03 -6.80821875e+03 -7.11399316e+03 -6.92510596e+03 -6.68756201e+03 -1.02340293e+04 -1.02513164e+04 -1.71651816e+04 -1.11026047e+05 15265469. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -419079328. -1.65937156e+05 -2.42262031e+04 -9.24829883e+03 -8.88943066e+03 -7.82492822e+03 -7.30154980e+03 -7281. -7.45069678e+03 -6.88572656e+03 -7.03068018e+03 -7.42029053e+03 -7.37417334e+03 -7.08762354e+03 -6.81518311e+03 -6.90909521e+03 -7.26255615e+03 -7.51399072e+03 -7.23657861e+03 -6.93570850e+03 -6.90852686e+03 -6.95294385e+03 -7.25741406e+03 -7.31326123e+03 -7.01793994e+03 -6.92384814e+03 -6.88985693e+03 -6.99495166e+03 -7.01827002e+03 -6.89141504e+03 -6.92237891e+03 -7.18085352e+03 -7.30616895e+03 -6.95116699e+03 -6.58520166e+03 -6.76582275e+03 -7.09513281e+03 -7.29370850e+03 -6.97384961e+03 -6.61867334e+03 -6.64858301e+03 -6.92815039e+03 -7.25916455e+03 -6.96443457e+03 -6.52127051e+03 -6.57562695e+03 -6.85573779e+03 -6.97922314e+03 -6.94934521e+03 -6.82403076e+03 -6.57484473e+03 -6.62737012e+03 -6.81134912e+03 -6.54136230e+03 -6.45548438e+03 -6.77098779e+03 -6.81661230e+03 -6.72757178e+03 -6.45428906e+03 -6.20988623e+03 -6.53894287e+03 -6.91916895e+03 -6.75157471e+03 -6.30110156e+03 -6.06335254e+03 -6.16711670e+03 -6.55679004e+03 -6.77076807e+03 -6.53361963e+03 -6.36128125e+03 -6.21305176e+03 -6.03110010e+03 -6.21002295e+03 -6.43222852e+03 -6.21692822e+03 -6.12500244e+03 -6.17226172e+03 -6.18198438e+03 -6.03629004e+03 -5.96594678e+03 -6.12337988e+03 -6.17331982e+03 -6.17324658e+03 -6.00592432e+03 -5.72406494e+03 -5.70098291e+03 -5.99411475e+03 -6.24125635e+03 -5.91237451e+03 -5.54207373e+03 -5.58704639e+03 -5.76127490e+03 -5.87661670e+03 -5.89906543e+03 -5.66475977e+03 -5.57275000e+03 -5.54178711e+03 -5.57364111e+03 -5.64603027e+03 -5.51907227e+03 -5.45132422e+03 -5.39460107e+03 -5.40695166e+03 -5.40090820e+03 -5.31099121e+03 -5.33426416e+03 -5.35291309e+03 -5.38555518e+03 -5.21969775e+03 -4.96678857e+03 -5.02551709e+03 -5.25729492e+03 -5.32959131e+03 -5.04105273e+03 -4.76739844e+03 -4.75425635e+03 -5.00459326e+03 -5.20701709e+03 -4.96017773e+03 -4.67935400e+03 -4.72248877e+03 -4.68111865e+03 -4.69530762e+03 -4.70649902e+03 -4.59978418e+03 -4.65679541e+03 -4.58295215e+03 -4.50208643e+03 -4.48979297e+03 -4.34044385e+03 -4.40427441e+03 -4.53594922e+03 -4.47704492e+03 -4.27592090e+03 -4.10351367e+03 -4.07658447e+03 -4.19910059e+03 -4.34053613e+03 -4.12091211e+03 -3.86565991e+03 -3.88951538e+03 -4.03472974e+03 -4.11248535e+03 -3.91899268e+03 -3.75998462e+03 -3.75588989e+03 -3.70820361e+03 -3.74329272e+03 -3.73075244e+03 -3.53257373e+03 -3.48323560e+03 -3.56997217e+03 -3.57558838e+03 -3.48275122e+03 -3.36144482e+03 -3.33118042e+03 -3.33326270e+03 -3.38604126e+03 -3.27219189e+03 -3.05965527e+03 -3.05485645e+03 -3.09751367e+03 -3.10657227e+03 -3.05350415e+03 -2.90573828e+03 -2.84746265e+03 -2.85263770e+03 -2.86868677e+03 -2.81509253e+03 -2.69830249e+03 -2.68893970e+03 -2.64831470e+03 -2.59625928e+03 -2.54065894e+03 -2.43466260e+03 -2.43682544e+03 -2.47762012e+03 -2.44358813e+03 -2.30822510e+03 -2.16953125e+03 -2.13968823e+03 -2.19352466e+03 -2.23073657e+03 -2.09409888e+03 -1.93682788e+03 -1.91310046e+03 -1.92690503e+03 -1.92609802e+03 -1.87705615e+03 -1.75727686e+03 -1.69477380e+03 -1.68085620e+03 -1.64624536e+03 -1.59546472e+03 -1.53503467e+03 -1.49338135e+03 -1.42596252e+03 -1.38804346e+03 -1.34772839e+03 -1.28216431e+03 -1.24260657e+03 -1.20058215e+03 -1.15873059e+03 -1.07028210e+03 -1.00173444e+03 -9.94189941e+02 -9.81969421e+02 -9.36138794e+02 -8.47118774e+02 -7.62037720e+02 -7.17886475e+02 -7.08402832e+02 -6.89546204e+02 -6.18928528e+02 -5.41072754e+02 -4.80738831e+02 -4.33133240e+02 -4.02702179e+02 -3.64368561e+02 -3.05167236e+02 -2.48889648e+02 -1.98764557e+02 -1.47918747e+02 -9.51947632e+01 -4.63831367e+01 2.70923066e+00 5.27361984e+01 1.05330391e+02 1.53544189e+02 1.91883072e+02 2.44807968e+02 3.04504028e+02 3.55349060e+02 4.06695801e+02 4.51893829e+02 5.11158661e+02 5.65644836e+02 5.90078979e+02 6.18345947e+02 6.79954956e+02 7.67273315e+02 8.43233826e+02 8.78130920e+02 8.76966309e+02 9.02349609e+02 9.73150452e+02 1.06945972e+03 1.14995056e+03 1.17899109e+03 1.16797925e+03 1.20984326e+03 1.32992908e+03 1.38303076e+03 1.36389185e+03 1.40731238e+03 1.48616846e+03 1.53499548e+03 1.63215491e+03 1.64318274e+03 1.63939331e+03 1.72957190e+03 1.73082202e+03 1.82504297e+03 1.93623352e+03 1.88404492e+03 1.96291956e+03 2.08076685e+03 2.07728296e+03 2.11388745e+03 2.16195068e+03 2.21916626e+03 2.29239746e+03 2.31060669e+03 2.27988208e+03 2.34743750e+03 2.51184521e+03 2.61210205e+03 2.59671509e+03 2.54164575e+03 2.52599292e+03 2.62118188e+03 2.79374438e+03 2.91297852e+03 2.90063330e+03 2.79469238e+03 2.83467065e+03 2.99678418e+03 3.03040747e+03 3.02742505e+03 3.07130713e+03 3.12552197e+03 3.17022827e+03 3.33719263e+03 3.30434326e+03 3.22409448e+03 3.33280005e+03 3.29343872e+03 3.46366064e+03 3.60741797e+03 3.53132837e+03 3.69369287e+03 3.65156665e+03 3.53875537e+03 3.69327002e+03 3.66432104e+03 3.78284692e+03 4.07210034e+03 3.90745044e+03 3.74038257e+03 3.86120166e+03 4.06151172e+03 4.24310986e+03 4.22853076e+03 4.04437891e+03 3.93482056e+03 4.06625708e+03 4.35476758e+03 4.53549316e+03 4.47338184e+03 4.28775977e+03 4.27560449e+03 4.49119775e+03 4.60493945e+03 4.48260107e+03 4.45806494e+03 4.57694434e+03 4.64319580e+03 4.80583447e+03 4.84833838e+03 4.68689990e+03 4.73843604e+03 4.76585645e+03 4.79007373e+03 4.94396484e+03 4.96188916e+03 5.10527637e+03 5.03069580e+03 4.88165820e+03 5.05799219e+03 4.97111768e+03 5.11462891e+03 5.51883398e+03 5.29030664e+03 4.95834326e+03 5.08625977e+03 5.38693994e+03 5.58319189e+03 5.64377686e+03 5.40082764e+03 5.17487012e+03 5.29004346e+03 5.61062207e+03 5.90351611e+03 5.74093457e+03 5.43617432e+03 5.40565967e+03 5.59302588e+03 5.78638477e+03 5.99880518e+03 5.96545361e+03 5.65645508e+03 5.61375684e+03 5.88759766e+03 6.00110352e+03 5.94630615e+03 5.95015283e+03 5.89098730e+03 5.86329932e+03 6.16523975e+03 6.23160156e+03 5.93534961e+03 5.95594238e+03 6.11456250e+03 6.16536328e+03 6.20167969e+03 6.16262646e+03 6.30196143e+03 6.39396484e+03 6.22895166e+03 6.15384814e+03 6.09804883e+03 6.34980713e+03 6.69212598e+03 6.60757031e+03 6.28277002e+03 6.14604297e+03 6.40230664e+03 6.75623242e+03 6.55206055e+03 6.24889697e+03 6.37133691e+03 6.57660645e+03 6.73663867e+03 6.93906250e+03 6.84181543e+03 6.48805859e+03 6.31950928e+03 6.55251025e+03 6.90632324e+03 6.89576172e+03 6.69285449e+03 6.69833252e+03 6.72199219e+03 6.86817627e+03 6.82362158e+03 6.64493750e+03 6.69716797e+03 6.65843359e+03 6.98723486e+03 7.14054492e+03 6.87820654e+03 6.85484131e+03 6.90875146e+03 7.08940039e+03 6.93629199e+03 6.63200146e+03 6.90696533e+03 7.33296924e+03 7.08026709e+03 6.73110791e+03 6.88343555e+03 7.28387744e+03 7.20605225e+03 7.10383496e+03 7.07526660e+03 6.88129883e+03 6.84115723e+03 7.27108008e+03 7.28755859e+03 6.99710986e+03 6.82662793e+03 6.81129492e+03 7.15486523e+03 7.48658936e+03 7.18124658e+03 6.95801514e+03 7.10199951e+03 7.10161572e+03 7.37001611e+03 7.35658105e+03 6.94924072e+03 6.93178564e+03 7.07734961e+03 7.14683789e+03 7.21219482e+03 7.17060400e+03 7.32914209e+03 7.26308643e+03 6.98206494e+03 7.01685449e+03 6.93499512e+03 7.22452197e+03 7.53988379e+03 7.35491650e+03 7.01458545e+03 6.93896582e+03 7.46092773e+03 7.56942676e+03 7.51499023e+03 8.42544141e+03 9.70180566e+03 1.27297061e+04 1.07363242e+05 67072368. 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. 0. 0. 0. 0. 0. 0. -151458048. 1.34417141e+05 1.68280078e+04 9.05071191e+03 7.50391064e+03 7.38228271e+03 7.00137256e+03 6.66210889e+03 6.60839941e+03 6.43254053e+03 6.69277246e+03 6.70297363e+03 6.53755664e+03 6.56304639e+03 6.55450244e+03 6.49541748e+03 6.50181055e+03 6.44681152e+03 6.41571143e+03 6.41413867e+03 6.36692822e+03 6.34645068e+03 6.19316748e+03 6.11401904e+03 6.39748340e+03 6.42122607e+03 6.05918652e+03 6.03083447e+03 6.31187695e+03 6.34544873e+03 6.16020117e+03 6.13220801e+03 6.06196289e+03 6.04775879e+03 6.01586719e+03 5.97554980e+03 5.97687207e+03 5.92599365e+03 5.77084717e+03 5.72429248e+03 5.96820410e+03 5.97365039e+03 5.79350830e+03 5.75082275e+03 5.74140918e+03 5.73538965e+03 5.66133643e+03 5.60084912e+03 5.61616260e+03 5.42728467e+03 5.33904590e+03 5.52751318e+03 5.48488721e+03 5.60186377e+03 5.60967578e+03 5.39164600e+03 5.19391211e+03 5.13136719e+03 5.43592578e+03 5.45154297e+03 5.20636426e+03 5.10699170e+03 5.11220068e+03 5.10670801e+03 5.03384717e+03 5.14694385e+03 5.09576270e+03 4.80823145e+03 4.75362012e+03 4.97346484e+03 5.05800049e+03 4.87975342e+03 4.77969385e+03 4.75465771e+03 4.70713086e+03 4.60493799e+03 4.56778662e+03 4.62391260e+03 4.58746631e+03 4.46031543e+03 4.44035254e+03 4.44947168e+03 4.39710107e+03 4.46991260e+03 4.40372266e+03 4.23985303e+03 4.25273682e+03 4.19800830e+03 4.20389844e+03 4.20201123e+03 4.09347974e+03 4.03645093e+03 3.92539087e+03 3.83529761e+03 3.95980713e+03 3.90575195e+03 3.68177954e+03 3.68921265e+03 3.86061304e+03 3.94180859e+03 3.76574878e+03 3.61725049e+03 3.52833130e+03 3.46942383e+03 3.46053296e+03 3.41445288e+03 3.42013550e+03 3.35824048e+03 3.36929224e+03 3.30944946e+03 3.18614038e+03 3.20363623e+03 3.06488062e+03 3.02660083e+03 3.16120093e+03 3.08731250e+03 2.96539941e+03 2.84445850e+03 2.77683618e+03 2.88865259e+03 2.85901074e+03 2.72333130e+03 2.61021240e+03 2.56220557e+03 2.58462598e+03 2.53475024e+03 2.55777075e+03 2.52973242e+03 2.40225708e+03 2.33221240e+03 2.29136670e+03 2.28504785e+03 2.23622339e+03 2.15946680e+03 2.08040356e+03 2.03500391e+03 2.03121814e+03 1.92570129e+03 1.87977905e+03 1.94215076e+03 1.88519800e+03 1.78208020e+03 1.68103088e+03 1.63191882e+03 1.68331006e+03 1.63262195e+03 1.54074036e+03 1.45207495e+03 1.39384680e+03 1.39427295e+03 1.33951880e+03 1.28698291e+03 1.21394031e+03 1.18635193e+03 1.19187915e+03 1.11356799e+03 1.05145776e+03 1.00669598e+03 9.50559875e+02 8.87858276e+02 8.34595276e+02 7.96736816e+02 7.51079956e+02 7.03730774e+02 6.29570862e+02 5.81930176e+02 5.70446045e+02 5.00287262e+02 4.33789520e+02 3.96512329e+02 3.46611603e+02 3.07583405e+02 2.50909561e+02 1.92418869e+02 1.51868698e+02 1.01783531e+02 4.93168373e+01 -6.71405494e-01 -4.99059944e+01 -1.00308990e+02 -1.50357498e+02 -2.01988693e+02 -2.45713211e+02 -2.99991760e+02 -3.68879089e+02 -4.12142975e+02 -4.47308350e+02 -4.82103455e+02 -5.37815063e+02 -6.23726196e+02 -6.70059875e+02 -7.00138794e+02 -7.34892273e+02 -7.78116272e+02 -8.47596191e+02 -8.97686707e+02 -9.70890625e+02 -1.00312695e+03 -1.01970990e+03 -1.09761267e+03 -1.14809167e+03 -1.22112549e+03 -1.25562756e+03 -1.26922095e+03 -1.33414355e+03 -1.38329102e+03 -1.44705396e+03 -1.45464270e+03 -1.53173657e+03 -1.67942456e+03 -1.67742920e+03 -1.68318494e+03 -1.69222070e+03 -1.72266125e+03 -1.87328040e+03 -1.94252307e+03 -1.93218848e+03 -1.91463928e+03 -1.96506409e+03 -2.08302490e+03 -2.12768042e+03 -2.22681665e+03 -2.26503491e+03 -2.26382129e+03 -2.24632178e+03 -2.27462988e+03 -2.47326221e+03 -2.49198730e+03 -2.46201929e+03 -2.50372461e+03 -2.54275464e+03 -2.70120532e+03 -2.75887744e+03 -2.67428735e+03 -2.69780615e+03 -2.87816187e+03 -2.95021484e+03 -2.84363281e+03 -2.87395337e+03 -3.07864209e+03 -3.12937500e+03 -3.08439819e+03 -3.06638574e+03 -3.09880664e+03 -3.31792993e+03 -3.32530981e+03 -3.25544775e+03 -3.33294458e+03 -3.37234766e+03 -3.50608691e+03 -3.54666235e+03 -3.47527954e+03 -3.43975806e+03 -3.59939160e+03 -3.85158691e+03 -3.76545435e+03 -3.75375269e+03 -3.85153735e+03 -3.85604248e+03 -3.89211011e+03 -3.92993408e+03 -3.95187036e+03 -3.90394556e+03 -3.92463257e+03 -4.05883008e+03 -4.14663330e+03 -4.30584521e+03 -4.22300537e+03 -4.08950464e+03 -4.24637646e+03 -4.36807373e+03 -4.54352539e+03 -4.48649023e+03 -4.39364160e+03 -4.43710156e+03 -4.45890479e+03 -4.57668115e+03 -4.60887988e+03 -4.73662451e+03 -4.76744092e+03 -4.68668750e+03 -4.66918408e+03 -4.58049512e+03 -4.80901562e+03 -5.14881885e+03 -5.05717676e+03 -4.95586670e+03 -4.84880615e+03 -4.77839355e+03 -5.05570752e+03 -5.33907910e+03 -5.21904541e+03 -5.00491992e+03 -5.02458350e+03 -5.21214111e+03 -5.24908643e+03 -5.40700342e+03 -5.43238672e+03 -5.31152832e+03 -5.33352002e+03 -5.35905322e+03 -5.56823193e+03 -5.62600146e+03 -5.36786084e+03 -5.38517871e+03 -5.73205957e+03 -5.70400684e+03 -5.45699902e+03 -5.59020654e+03 -5.91936475e+03 -5.87415576e+03 -5.74958105e+03 -5.64511914e+03 -5.67440625e+03 -6.02161963e+03 -6.05436182e+03 -5.92828027e+03 -5.78997168e+03 -5.76428467e+03 -5.97709180e+03 -6.03229199e+03 -6.03539600e+03 -5.91048584e+03 -6.08619727e+03 -6.31727734e+03 -6.16327686e+03 -6.30114990e+03 -6.31378369e+03 -6.13836621e+03 -6.24867627e+03 -6.30326562e+03 -6.30980713e+03 -6.28179395e+03 -6.17607422e+03 -6.12621826e+03 -6.39667871e+03 -6.76820947e+03 -6.45741162e+03 -6.19877148e+03 -6.42995215e+03 -6.55386523e+03 -6.75903174e+03 -6.61496045e+03 -6.41684424e+03 -6.71115674e+03 -6.75875586e+03 -6.42950195e+03 -6.39819531e+03 -6.82450244e+03 -6.83653369e+03 -6.66124365e+03 -6.56617725e+03 -6.36990723e+03 -6.67962744e+03 -7.17090234e+03 -7.00290332e+03 -6.77050928e+03 -6.58765234e+03 -6.50253955e+03 -6.85985449e+03 -7.28633447e+03 -7.08490723e+03 -6.71787061e+03 -6.68106396e+03 -6.88216113e+03 -6.93907812e+03 -7.10302832e+03 -6.96459961e+03 -6.79820898e+03 -7.00981104e+03 -6.96133154e+03 -7.18297119e+03 -7.14878711e+03 -6.94074170e+03 -6.97908350e+03 -6.95552051e+03 -7.12677783e+03 -6.98250586e+03 -6.91281592e+03 -7.25811133e+03 -7.29595361e+03 -7.05217725e+03 -6.86407227e+03 -6.92460205e+03 -7.34065527e+03 -7.31993604e+03 -7.13120312e+03 -6.93050146e+03 -6.93490234e+03 -7.14092236e+03 -7.16455615e+03 -7.19159961e+03 -6.94843604e+03 -7.12996143e+03 -7.41540479e+03 -7.14382568e+03 -7.33860889e+03 -7.37837109e+03 -7.12673486e+03 -7.02783984e+03 -7.02041895e+03 -7.24818896e+03 -7.25796533e+03 -7.00655859e+03 -6.99005957e+03 -7.36547656e+03 -7.42875684e+03 -6.99618799e+03 -6.81420459e+03 -6.96635693e+03 -7.26881152e+03 -7.55311084e+03 -7.26015381e+03 -6.90933545e+03 -7.19078174e+03 -7.36686523e+03 -7.16551807e+03 -7.05013330e+03 -7.02901660e+03 -6.96971289e+03 -7.01296777e+03 -7.11794385e+03 -6.91405420e+03 -7.05563477e+03 -7.38114307e+03 -7.10423438e+03 -7.11100244e+03 -6.97109131e+03 -6.84687402e+03 -7.18603418e+03 -7.19910254e+03 -7.00547949e+03 -6.84557617e+03 -6.64452295e+03 -6.77961133e+03 -7.14650293e+03 -7.37255566e+03 -6.98841455e+03 -6.67255322e+03 -6.88632959e+03 -6.92959619e+03 -7.14198340e+03 -7.08470850e+03 -6.83353809e+03 -6.75328320e+03 -6.74918896e+03 -6.76815771e+03 -6.61760498e+03 -6.75794531e+03 -7.03783594e+03 -6.83294531e+03 -6.80648193e+03 -6.66844824e+03 -6.51242334e+03 -6.91499756e+03 -6.87608594e+03 -6.63063916e+03 -6.47433008e+03 -6.39816797e+03 -6.57793359e+03 -6.56355322e+03 -6.71804248e+03 -6.76611426e+03 -6.49938086e+03 -6.32054053e+03 -6.40805469e+03 -6.68207910e+03 -6.57798193e+03 -6.39936377e+03 -6.28847754e+03 -6.24680615e+03 -6.28787744e+03 -6.23698486e+03 -6.39467578e+03 -6.38950879e+03 -6.14951221e+03 -6.33026465e+03 -6.38162500e+03 -6.20320020e+03 -6.17422852e+03 -6.12716602e+03 -6.11539062e+03 -5.92362939e+03 -5.82863965e+03 -6.11867236e+03 -6.16665186e+03 -5.79876074e+03 -5.60528711e+03 -5.88579004e+03 -6.20682275e+03 -6.06381738e+03 -5.69122900e+03 -5.55974316e+03 -5.85077930e+03 -5.86606250e+03 -5.64290283e+03 -5.76963428e+03 -5.57579785e+03 -5.29910742e+03 -5.43985498e+03 -5.72167188e+03 -5.79996533e+03 -5.45683691e+03 -5.16394922e+03 -5.43769678e+03 -5.66862549e+03 -5.47777979e+03 -5.18739844e+03 -5.07119824e+03 -5.19265625e+03 -5.20438477e+03 -5.31965186e+03 -5.26234863e+03 -5.04821484e+03 -5.02788867e+03 -4.99157422e+03 -5.12421338e+03 -4.98461279e+03 -4.81003662e+03 -4.95485791e+03 -4.89484717e+03 -4.88360596e+03 -4.76204639e+03 -4.63856787e+03 -4.86279785e+03 -4.70411816e+03 -4.47284229e+03 -4.54095459e+03 -4.60042236e+03 -4.58794922e+03 -4.48693799e+03 -4.54223145e+03 -4.54125391e+03 -4.39386719e+03 -4.22010449e+03 -4.15954590e+03 -4.34606543e+03 -4.21384961e+03 -4.06763306e+03 -4.14576416e+03 -4.09818115e+03 -4.04403125e+03 -3.97537427e+03 -4.03606421e+03 -3.96313281e+03 -3.79726514e+03 -3.89267896e+03 -3.86699854e+03 -3.77643066e+03 -3.73073706e+03 -3.67540430e+03 -3.58813794e+03 -3.46035669e+03 -3.36456030e+03 -3.49445679e+03 -3.65468677e+03 -3.41907129e+03 -3.17141357e+03 -3.27407983e+03 -3.44342798e+03 -3.35740674e+03 -3.13131494e+03 -3.00976343e+03 -3.13340820e+03 -3.09590967e+03 -2.94636353e+03 -3.02197021e+03 -2.96731714e+03 -2.77029321e+03 -2.72419629e+03 -2.81955591e+03 -2.84493896e+03 -2.66980566e+03 -2.51467773e+03 -2.56610278e+03 -2.67081445e+03 -2.57244653e+03 -2.40001489e+03 -2.29013257e+03 -2.34513257e+03 -2.40917896e+03 -2.28594238e+03 -2.17523438e+03 -2.14638184e+03 -2.11715308e+03 -2.05999097e+03 -2.07323804e+03 -1.98073767e+03 -1.87137183e+03 -1.87330103e+03 -1.83055640e+03 -1.82175378e+03 -1.73359668e+03 -1.63761462e+03 -1.64563635e+03 -1.55350293e+03 -1.50463098e+03 -1.51887317e+03 -1.45629236e+03 -1.39340540e+03 -1.32574988e+03 -1.32674634e+03 -1.29046021e+03 -1.19124194e+03 -1.11321179e+03 -1.07339307e+03 -1.09234912e+03 -1.00510559e+03 -9.16429565e+02 -1.00014044e+03 -1.30495874e+03 -1.18628259e+03 -1.20490332e+03 -1.13096423e+03 -4.58549512e+03 -102366048. 0. 0. 0. 0. 0. -3.15935667e+09 -3.15935667e+09 120488216. -8.61302031e+04 1.62657861e+04 -4.36760586e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -438734144. 4.98015723e+03 1.52368591e+03 9.08891174e+02 8.92662964e+02 1.01095392e+03 9.68202209e+02 9.69680115e+02 1.01592078e+03 1.06004211e+03 1.12189575e+03 1.20780310e+03 1.24410132e+03 1.24687744e+03 1.31832214e+03 1.40012561e+03 1.40891443e+03 1.43256494e+03 1.48304065e+03 1.55369690e+03 1.63725378e+03 1.69539636e+03 1.70110535e+03 1.69054517e+03 1.78064148e+03 1.89369604e+03 1.90298181e+03 1.94333069e+03 1.97625757e+03 2.00792126e+03 2.12184399e+03 2.12845898e+03 2.10392603e+03 2.18291162e+03 2.23694897e+03 2.31054175e+03 2.37962109e+03 2.36292334e+03 2.40911841e+03 2.53671338e+03 2.69015088e+03 2.66082642e+03 2.52294556e+03 2.56853442e+03 2.69000391e+03 2.78863525e+03 2.88674341e+03 2.87997070e+03 2.84208691e+03 2.96219971e+03 3.05212817e+03 3.00221191e+03 3.01691089e+03 3.05937573e+03 3.20181323e+03 3.36798975e+03 3.24037012e+03 3.16933765e+03 3.29811328e+03 3.41388208e+03 3.51588916e+03 3.49801636e+03 3.46103223e+03 3.46633301e+03 3.59456909e+03 3.79180664e+03 3.73175293e+03 3.59333228e+03 3.71115552e+03 3.81948877e+03 3.86748511e+03 3.95116943e+03 3.93976245e+03 3.87521240e+03 4.00546704e+03 4.13629639e+03 4.10520508e+03 4.07431494e+03 4.07708203e+03 4.13554688e+03 4.30284473e+03 4.45791455e+03 4.37040967e+03 4.25044482e+03 4.35647266e+03 4.52206641e+03 4.47305371e+03 4.45165381e+03 4.49127246e+03 4.61256494e+03 4.79782471e+03 4.74710059e+03 4.58206592e+03 4.59453955e+03 4.68570605e+03 4.82463379e+03 4.89605762e+03 4.84679004e+03 4.87447363e+03 5.03908203e+03 5.21489990e+03 5.11532617e+03 4.87350098e+03 4.92973584e+03 5.13918506e+03 5.21018262e+03 5.23593555e+03 5.18262158e+03 5.15695654e+03 5.35278174e+03 5.41418604e+03 5.28556201e+03 5.36863770e+03 5.42641895e+03 5.41561328e+03 5.57441650e+03 5.58560693e+03 5.46546924e+03 5.49530518e+03 5.53343896e+03 5.57202588e+03 5.74127637e+03 5.89494043e+03 5.75680713e+03 5.58832568e+03 5.73906055e+03 5.92690967e+03 5.84134619e+03 5.76895801e+03 5.76756543e+03 5.82958105e+03 6.02794092e+03 6.09291895e+03 5.91854297e+03 5.88814600e+03 5.98096875e+03 6.13600781e+03 6.19803467e+03 6.12005518e+03 6.10054932e+03 6.17037549e+03 6.28783740e+03 6.17159619e+03 6.05266211e+03 6.18420264e+03 6.26760400e+03 6.35977197e+03 6.50745557e+03 6.38315039e+03 6.14867773e+03 6.32319775e+03 6.50738135e+03 6.46486914e+03 6.40042432e+03 6.30075146e+03 6.36293896e+03 6.66022949e+03 6.75177832e+03 6.42765820e+03 6.32150830e+03 6.62052734e+03 6.75948779e+03 6.61567383e+03 6.42920410e+03 6.49747559e+03 6.74848633e+03 6.86274707e+03 6.64786670e+03 6.56948145e+03 6.66338232e+03 6.63319336e+03 6.77983838e+03 6.86628906e+03 6.70029785e+03 6.73743066e+03 6.88746240e+03 6.88081055e+03 6.77336719e+03 6.70707959e+03 6.71758398e+03 6.74129248e+03 6.90224707e+03 7.14041064e+03 7.13679297e+03 6.70640137e+03 6.79493506e+03 7.13634180e+03 6.85806689e+03 6.75740820e+03 6.83842090e+03 6.89104541e+03 7.10753760e+03 7.13402734e+03 6.82332520e+03 6.76072461e+03 6.84674463e+03 6.98906982e+03 7.06387061e+03 6.93159863e+03 6.94556934e+03 7.17976514e+03 7.13951172e+03 6.95034668e+03 6.85324658e+03 6.90617432e+03 6.93285791e+03 7.09867822e+03 7.17821094e+03 7.18467285e+03 6.86323926e+03 6.92601953e+03 7.12552490e+03 6.99252246e+03 6.92647607e+03 6.98096240e+03 6.99161865e+03 7.20298486e+03 7.21885986e+03 6.93250830e+03 6.90980273e+03 6.89840381e+03 6.98770264e+03 7.09264453e+03 6.96370410e+03 6.99866260e+03 7.02431396e+03 7.13253906e+03 7.21641895e+03 6.82823047e+03 6.76387061e+03 6.95781982e+03 6.97118164e+03 7.05875732e+03 6.95116162e+03 6.74714600e+03 6.92760107e+03 7.14806299e+03 6.89290039e+03 6.81536084e+03 6.90556592e+03 6.89603320e+03 6.89727344e+03 6.83972656e+03 7.01343896e+03 6.95999463e+03 6.76077051e+03 6.90884326e+03 6.72346484e+03 6.74712207e+03 6.90030908e+03 6.69432812e+03 6.70586816e+03 6.82077930e+03 6.69017871e+03 6.49836328e+03 6.54248340e+03 6.85819775e+03 6.97637842e+03 6.55048193e+03 6.47931055e+03 6.68087061e+03 6.67675635e+03 6.66701611e+03 6.45881348e+03 6.44918701e+03 6.57881836e+03 6.66972803e+03 6.56575879e+03 6.44532861e+03 6.41923193e+03 6.44021387e+03 6.56484326e+03 6.35950293e+03 6.25501562e+03 6.24482178e+03 6.22516504e+03 6.35102930e+03 6.52665137e+03 6377. 6.07231641e+03 6.08861084e+03 6.36197461e+03 6.39825000e+03 6.05249219e+03 6.17256494e+03 6.30414795e+03 6.00466846e+03 6.02989844e+03 5.96401123e+03 5.94009131e+03 6.16704004e+03 6.06009277e+03 5.82858105e+03 6.00790527e+03 6.01041846e+03 5.79634131e+03 5.88257617e+03 5.88522900e+03 5.80495361e+03 5.65386914e+03 5.59765234e+03 5.73570947e+03 5.82872949e+03 5.70552979e+03 5.51251416e+03 5.47632178e+03 5.64972217e+03 5.67555615e+03 5.43585254e+03 5.36349512e+03 5.38344531e+03 5.49358350e+03 5.49193652e+03 5.24187500e+03 5.22171436e+03 5.35365039e+03 5.32229590e+03 5.17967676e+03 5.24004199e+03 5.21266211e+03 5.04489648e+03 5.17464209e+03 5.22776562e+03 4.96970947e+03 4.78027148e+03 4.83601904e+03 4.93457422e+03 4.94414893e+03 4.86331299e+03 4.74697510e+03 4.70771973e+03 4.81773438e+03 4.82564990e+03 4.60997852e+03 4.53984326e+03 4.64164258e+03 4.72051465e+03 4.51705371e+03 4.38500879e+03 4.46859521e+03 4.40260059e+03 4.33673779e+03 4.31438477e+03 4.32009766e+03 4.25303857e+03 4.15982178e+03 4.17123096e+03 4.15832324e+03 4.08274414e+03 3.96857227e+03 3.95229810e+03 3.99871997e+03 3.96679248e+03 3.85371899e+03 3.79744849e+03 3.78767798e+03 3.86223706e+03 3.81256543e+03 3.62709326e+03 3.63279370e+03 3.63561060e+03 3.57105518e+03 3.49000220e+03 3.42636792e+03 3.44949634e+03 3.41702783e+03 3.29990527e+03 3.17914941e+03 3.23555493e+03 3.30286548e+03 3.20395239e+03 3.14100146e+03 3.07342139e+03 3.05534399e+03 2.95438501e+03 2.81224658e+03 2.86425708e+03 2.89510449e+03 2.85552734e+03 2.78488843e+03 2.64852197e+03 2.63329810e+03 2.64559448e+03 2.63663989e+03 2.62490942e+03 2.48302075e+03 2.38872217e+03 2.33494849e+03 2.35191748e+03 2.37695483e+03 2.29978857e+03 2.22248242e+03 2.08706226e+03 2.08886450e+03 2.11334619e+03 2.01878918e+03 1.99568201e+03 1.92410889e+03 1.86178027e+03 1.86626978e+03 1.78202722e+03 1.71541187e+03 1.72444360e+03 1.68915369e+03 1.58411926e+03 1.49610864e+03 1.47304175e+03 1.45002734e+03 1.44504846e+03 1.42152307e+03 1.32142908e+03 1.24076416e+03 1.17842053e+03 1.16518408e+03 1.15905664e+03 1.08345178e+03 1.00506403e+03 9.38916138e+02 9.07682800e+02 8.88360657e+02 8.51491882e+02 7.93056335e+02 7.29632080e+02 6.90154114e+02 6.30874390e+02 5.63270569e+02 5.29083191e+02 4.90797089e+02 4.45714111e+02 4.04893036e+02 3.38091309e+02 2.79019592e+02 2.40204575e+02 1.99078247e+02 1.49695267e+02 9.53342743e+01 4.63260155e+01 -2.37451839e+00 -5.15887299e+01 -1.02844467e+02 -1.51043045e+02 -1.97838654e+02 -2.41309692e+02 -2.96127502e+02 -3.45880432e+02 -3.82219238e+02 -4.39855652e+02 -5.00443024e+02 -5.46618713e+02 -5.90376404e+02 -6.26509949e+02 -6.83564026e+02 -7.49591248e+02 -7.99716003e+02 -8.46155334e+02 -8.60005371e+02 -9.02480225e+02 -9.77252502e+02 -1.04421411e+03 -1.10573035e+03 -1.13695715e+03 -1.16923840e+03 -1.18554626e+03 -1.26132605e+03 -1.36041956e+03 -1.37388367e+03 -1.41309460e+03 -1.45969958e+03 -1.49340173e+03 -1.53197827e+03 -1.58767749e+03 -1.65907666e+03 -1.73130298e+03 -1.78968237e+03 -1.78502454e+03 -1.78442993e+03 -1.86897083e+03 -1.94706653e+03 -2.00916479e+03 -2.07394019e+03 -2.06585522e+03 -2.11614819e+03 -2.15354370e+03 -2.21635889e+03 -2.33034448e+03 -2.31825781e+03 -2.35205054e+03 -2.38428003e+03 -2.37125269e+03 -2.46102173e+03 -2.63738477e+03 -2.66017090e+03 -2.59950317e+03 -2.68242261e+03 -2.69616357e+03 -2.66633838e+03 -2.78865796e+03 -2.88918555e+03 -2.92292554e+03 -2.96745947e+03 -2.93884277e+03 -3.00036890e+03 -3.10553296e+03 -3.17467334e+03 -3.32005713e+03 -3.27151929e+03 -3.12999121e+03 -3.17520435e+03 -3.34561475e+03 -3.46436646e+03 -3.48625293e+03 -3.47480078e+03 -3.38242554e+03 -3.49889331e+03 -3.70011475e+03 -3.67774072e+03 -3.69294458e+03 -3.68011035e+03 -3.71330200e+03 -3.85163892e+03 -3.80939185e+03 -3.81915381e+03 -4.05070703e+03 -4.10556006e+03 -4.05462524e+03 -3.98179346e+03 -3.90662305e+03 -4.04845386e+03 -4.24736572e+03 -4.39963086e+03 -4.34846338e+03 -4.15788721e+03 -4.14880518e+03 -4.34461084e+03 -4.50569385e+03 -4.46902344e+03 -4.45303271e+03 -4.39495752e+03 -4.47221973e+03 -4.62657031e+03 -4.71613525e+03 -4.76077734e+03 -4.71730713e+03 -4.78500537e+03 -4.76272656e+03 -4.66701221e+03 -4.78131299e+03 -4.91601904e+03 -4.99249658e+03 -5.12080957e+03 -4.95268457e+03 -4.84603662e+03 -5.02514209e+03 -5.15048535e+03 -5.29587549e+03 -5.25793262e+03 -5.06330859e+03 -5.05336865e+03 -5.23311865e+03 -5.46292334e+03 -5.51367529e+03 -5.36826709e+03 -5.30705371e+03 -5.34425977e+03 -5.35008203e+03 -5.42334766e+03 -5.58248682e+03 -5.67002148e+03 -5.58702686e+03 -5.47951123e+03 -5.46597754e+03 -5.61549072e+03 -5.80858740e+03 -5.88181885e+03 -5.86080225e+03 -5.69020410e+03 -5.55060938e+03 -5.70154883e+03 -5.92774756e+03 -6.06671436e+03 -6.03521631e+03 -5.79585059e+03 -5.70214502e+03 -5.95608350e+03 -6.22582080e+03 -6.06993750e+03 -6.09585107e+03 -6.07341650e+03 -5.92729639e+03 -6.11313428e+03 -6.24709912e+03 -6.19127393e+03 -6.15163428e+03 -6.25191895e+03 -6.30168701e+03 -6.18979590e+03 -6.25302734e+03 -6.30955859e+03 -6.47232178e+03 -6.45801221e+03 -6.26656885e+03 -6.31591357e+03 -6.27685742e+03 -6.41205664e+03 -6.73184521e+03 -6.61492334e+03 -6.31918408e+03 -6.34421973e+03 -6.43021436e+03 -6.75127197e+03 -6.84447998e+03 -6.55135205e+03 -6.44048730e+03 -6.54391602e+03 -6.70455762e+03 -6.85707227e+03 -6.79066797e+03 -6.65935107e+03 -9.21666504e+03 -8.94625586e+03 -1.72696289e+04 -1.12885312e+05 15265469. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 25050002. -2.44711675e+06 -2.60119180e+04 -1.92686797e+04 -1.22524102e+04 -9.32965332e+03 -9.32975098e+03 -7.58692969e+03 -6.89345996e+03 -6.98110986e+03 -7.33747559e+03 -7.22985498e+03 -6.94682715e+03 -6.80779053e+03 -6.68736133e+03 -7.03028516e+03 -7.41252002e+03 -7.15629102e+03 -6.88353613e+03 -6.78549072e+03 -6.82188184e+03 -7.12698535e+03 -7.12705811e+03 -6.82360303e+03 -6.75333301e+03 -6.89224756e+03 -6.87913672e+03 -6.72077588e+03 -6.75362891e+03 -6.91127979e+03 -7.09687402e+03 -7.12095850e+03 -6.73427100e+03 -6.41115820e+03 -6.62856738e+03 -7.00166748e+03 -7.17154004e+03 -6.87876709e+03 -6.55458984e+03 -6.44829395e+03 -6.73769092e+03 -7.09922314e+03 -6.83783105e+03 -6.44846484e+03 -6.48018311e+03 -6.79289697e+03 -6.73549902e+03 -6.59659033e+03 -6.62301465e+03 -6.53044727e+03 -6.63469775e+03 -6.66748340e+03 -6.31330469e+03 -6.33397803e+03 -6.63236035e+03 -6.77637354e+03 -6.63986719e+03 -6.29823926e+03 -6.07963770e+03 -6.38935254e+03 -6.80051416e+03 -6.61083740e+03 -6.26164014e+03 -6.02077197e+03 -5.95936914e+03 -6.32172021e+03 -6.64601709e+03 -6.41476855e+03 -6.25121045e+03 -6.16240381e+03 -6.00134961e+03 -6.08527148e+03 -6.24398047e+03 -6.05331689e+03 -5.92754541e+03 -6.14753369e+03 -6.01479199e+03 -5.74158936e+03 -5.82007227e+03 -6.07965869e+03 -6.13879004e+03 -6.04568750e+03 -5.86799023e+03 -5.65644873e+03 -5.55930518e+03 -5.81603467e+03 -6.11289014e+03 -5.84830371e+03 -5.46342822e+03 -5.44607471e+03 -5.64063379e+03 -5.82305127e+03 -5.79438281e+03 -5.51236279e+03 -5.40400049e+03 -5.52882471e+03 -5.48003857e+03 -5.40668799e+03 -5.41034814e+03 -5.35477539e+03 -5.39131592e+03 -5.33221094e+03 -5.14660693e+03 -5.15775439e+03 -5.28904248e+03 -5.33549463e+03 -5.28920654e+03 -5.12462402e+03 -4.91224609e+03 -4.91338184e+03 -5.15256641e+03 -5.19259521e+03 -4.93125781e+03 -4.73306250e+03 -4.65088916e+03 -4.84645801e+03 -5.10293945e+03 -4.90343311e+03 -4.59218994e+03 -4.57877100e+03 -4.66241602e+03 -4.62975635e+03 -4.49497900e+03 -4.46809570e+03 -4.61401221e+03 -4.60617090e+03 -4.42784619e+03 -4.26819238e+03 -4.22589502e+03 -4.37082422e+03 -4.50828662e+03 -4.37565820e+03 -4.17953467e+03 -4.05540161e+03 -3.95476685e+03 -4.08242871e+03 -4.25909619e+03 -4.07266089e+03 -3.84176489e+03 -3.78575244e+03 -3.90711499e+03 -4.03335962e+03 -3.87048999e+03 -3.70557446e+03 -3.66876294e+03 -3.67901929e+03 -3.68739502e+03 -3.61977417e+03 -3.48559204e+03 -3.40779712e+03 -3.51252881e+03 -3.52217017e+03 -3.35733447e+03 -3.24412476e+03 -3.25988428e+03 -3.30335522e+03 -3.33745752e+03 -3.22793311e+03 -3.01612524e+03 -2.98878394e+03 -3.06237280e+03 -3.04087793e+03 -2.95704150e+03 -2.87137378e+03 -2.80795093e+03 -2.78120752e+03 -2.79357910e+03 -2.71351367e+03 -2.61811987e+03 -2.65696826e+03 -2.65934741e+03 -2.55063867e+03 -2.43464014e+03 -2.38563745e+03 -2.41462256e+03 -2.44362476e+03 -2.38464087e+03 -2.26573926e+03 -2.14597729e+03 -2.08260913e+03 -2.13137769e+03 -2.19115161e+03 -2.07192749e+03 -1.90938904e+03 -1.86129590e+03 -1.89048035e+03 -1.90816431e+03 -1.83883740e+03 -1.73877478e+03 -1.67668054e+03 -1.63792712e+03 -1.58415491e+03 -1.54249304e+03 -1.51124304e+03 -1.46011841e+03 -1.41925696e+03 -1.36427380e+03 -1.28696045e+03 -1.24661365e+03 -1.23151782e+03 -1.19801843e+03 -1.14526575e+03 -1.04905762e+03 -9.76929077e+02 -9.78489807e+02 -9.72813232e+02 -9.06556702e+02 -8.26809204e+02 -7.56049622e+02 -6.98455627e+02 -6.86981384e+02 -6.75734741e+02 -6.06730957e+02 -5.25250488e+02 -4.70925079e+02 -4.38038483e+02 -3.98312042e+02 -3.48087067e+02 -2.95911377e+02 -2.44764069e+02 -1.95098999e+02 -1.43685669e+02 -9.23610229e+01 -4.56951294e+01 2.33003211e+00 5.20278053e+01 1.04621872e+02 1.51567734e+02 1.89484482e+02 2.35491409e+02 2.93818207e+02 3.53861298e+02 4.02263031e+02 4.40970612e+02 5.00538879e+02 5.54951965e+02 5.77723267e+02 6.05810181e+02 6.67920776e+02 7.52649658e+02 8.26705322e+02 8.61645325e+02 8.59505432e+02 8.81216003e+02 9.48661987e+02 1.04800293e+03 1.13616724e+03 1.15985205e+03 1.14234985e+03 1.18417273e+03 1.30799976e+03 1.35748059e+03 1.34517029e+03 1.39091748e+03 1.44563086e+03 1.49395093e+03 1.59728064e+03 1.61408875e+03 1.61150476e+03 1.69151624e+03 1.69838232e+03 1.79486121e+03 1.89382202e+03 1.84278442e+03 1.92950513e+03 2.03596826e+03 2.02716772e+03 2.07080664e+03 2.12887622e+03 2.17865308e+03 2.23412451e+03 2.26645825e+03 2.24830884e+03 2.29835034e+03 2.45613184e+03 2.56872363e+03 2.55286743e+03 2.48199976e+03 2.47158276e+03 2.57698633e+03 2.74365747e+03 2.84898071e+03 2.83890332e+03 2.73049438e+03 2.78615234e+03 2.93922510e+03 2.95746533e+03 2.97793359e+03 3.02864673e+03 3.06457593e+03 3.10610522e+03 3.27422534e+03 3.23566113e+03 3.15647656e+03 3.27840259e+03 3.25085034e+03 3.40353711e+03 3.51818970e+03 3.44745581e+03 3.62543237e+03 3.57341357e+03 3.46824487e+03 3.62773584e+03 3.59513794e+03 3.69565845e+03 3.99267236e+03 3.83761060e+03 3.65906396e+03 3.76505469e+03 3.97441943e+03 4.18130078e+03 4.15185498e+03 3.96929810e+03 3.86447705e+03 3.99964453e+03 4.25722119e+03 4.42732422e+03 4.38193115e+03 4.20759521e+03 4.21183936e+03 4.38317139e+03 4.46373975e+03 4.42313574e+03 4.41189941e+03 4.48482520e+03 4.55835986e+03 4.71316455e+03 4.75376953e+03 4.55812451e+03 4.59798730e+03 4.68593115e+03 4.73782959e+03 4.84414111e+03 4.85729590e+03 5.02733984e+03 4.94030322e+03 4.79173193e+03 4.96276709e+03 4.86521582e+03 5.01911719e+03 5.39781885e+03 5.17880518e+03 4.88680664e+03 4.99495605e+03 5.28670068e+03 5.48226172e+03 5.52165820e+03 5.26418213e+03 5.07549316e+03 5.20125195e+03 5.50483008e+03 5.73502637e+03 5.61131934e+03 5.32743848e+03 5.31310010e+03 5.51117090e+03 5.66156396e+03 5.86241016e+03 5.87738574e+03 5.53725684e+03 5.50532129e+03 5.84717920e+03 5.92438428e+03 5.70177051e+03 5.73513135e+03 5.83740918e+03 5.81732861e+03 6.04157373e+03 6.10755957e+03 5.81313965e+03 5.82432764e+03 6.00876758e+03 6.02738379e+03 6.07184814e+03 6.00237988e+03 6.15941455e+03 6.31885986e+03 6.20302002e+03 6.03997949e+03 5.93407275e+03 6.18901270e+03 6.55801074e+03 6.46524072e+03 6.16420898e+03 6.00397803e+03 6.22910156e+03 6.61589453e+03 6.47833984e+03 6.15147021e+03 6.21659473e+03 6.41777197e+03 6.59861719e+03 6.84744092e+03 6.69590527e+03 6.35596094e+03 6.20115283e+03 6.42037256e+03 6.74658594e+03 6.77322070e+03 6.60033105e+03 6.56712842e+03 6.58336133e+03 6.75671387e+03 6.74009180e+03 6.61196094e+03 6.54962695e+03 6.44914648e+03 6.79139746e+03 7.03568848e+03 6.74277686e+03 6.77032764e+03 6.81631445e+03 6.95679248e+03 6.81199268e+03 6.49915918e+03 6.75669434e+03 7.17427441e+03 7.00147803e+03 6.65821143e+03 6.70262256e+03 7.09252002e+03 7.10271924e+03 6.90749023e+03 6.92067334e+03 6.70992432e+03 6.68200049e+03 7.13970459e+03 7.16436230e+03 6.88434180e+03 6.70002051e+03 6.68774463e+03 6.98630518e+03 7.29175537e+03 7.01396777e+03 6.85823193e+03 7.00206934e+03 6.99722607e+03 7.19939941e+03 7.19066650e+03 6.81545020e+03 6.80866797e+03 7.00245996e+03 7.01041406e+03 7.05440234e+03 6.99948877e+03 7.18336377e+03 7.11280322e+03 6.84512549e+03 6.95727686e+03 6.88758203e+03 7.06422607e+03 7.37098877e+03 7.20193164e+03 6.93086426e+03 6.87010254e+03 7.26202100e+03 7.33921191e+03 7.23924561e+03 7.68417529e+03 8.85075391e+03 9.49718652e+03 5.73875117e+04 -8565182. 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. 0. 0. 0. 0. 0. 0. 0. 41193472. 1.10661867e+05 2.03885840e+04 1.20247461e+04 1.15107266e+04 1.03603867e+04 8.17232422e+03 8.29335938e+03 6.78318701e+03 6.80130029e+03 6.56662695e+03 6.35833057e+03 6.51876660e+03 6.52761035e+03 6.33413965e+03 6.34239648e+03 6.32551709e+03 6.28736523e+03 6.28711768e+03 6.25328857e+03 6.19703174e+03 6.07916455e+03 6.05118604e+03 6.26539258e+03 6.27429688e+03 5.96849170e+03 5.91595215e+03 6.20442627e+03 6.22429150e+03 6.04801611e+03 6.00393506e+03 5.92623291e+03 5.92728906e+03 5.90868018e+03 5.86186719e+03 5.84317871e+03 5.78841699e+03 5.66246875e+03 5.63541113e+03 5.83618018e+03 5.82330176e+03 5.66412793e+03 5.63825488e+03 5.64016553e+03 5.62112646e+03 5.55814062e+03 5.50027246e+03 5.48355322e+03 5.32450098e+03 5.29276660e+03 5.38107666e+03 5.32387598e+03 5.48414160e+03 5.51297998e+03 5.29372852e+03 5.08269922e+03 5.01435205e+03 5.33210693e+03 5.33639307e+03 5.09157324e+03 5.00206787e+03 5.00546289e+03 4.96625830e+03 4.88539893e+03 5.07503027e+03 5.01964355e+03 4.68905615e+03 4.64555957e+03 4.85811230e+03 4.99605273e+03 4.83270068e+03 4.68256934e+03 4.68522217e+03 4.62028418e+03 4.53643994e+03 4.51501855e+03 4.53859814e+03 4.47599805e+03 4.35063379e+03 4.32268506e+03 4.36980664e+03 4.30608398e+03 4.37539697e+03 4.29228662e+03 4.11768213e+03 4.14795947e+03 4.11207227e+03 4.15515918e+03 4.14702734e+03 4.02844604e+03 3.95773267e+03 3.83109106e+03 3.72652319e+03 3.87007520e+03 3.87838794e+03 3.63370679e+03 3.61814062e+03 3.79305371e+03 3.84929443e+03 3.68894409e+03 3.54281079e+03 3.49249561e+03 3.45071021e+03 3.37269702e+03 3.32260913e+03 3.34967407e+03 3.29848633e+03 3.29716821e+03 3.22406494e+03 3.11635327e+03 3.13411768e+03 3.00133276e+03 3.00581079e+03 3.12867261e+03 3.02117603e+03 2.90528760e+03 2.77758057e+03 2.71599023e+03 2.83476392e+03 2.81108276e+03 2.66723779e+03 2.55171509e+03 2.51227905e+03 2.52931396e+03 2.48007935e+03 2.50663550e+03 2.47898486e+03 2.35355957e+03 2.26540015e+03 2.22681104e+03 2.26077759e+03 2.21197144e+03 2.11923999e+03 2.02885681e+03 1.98074268e+03 1.98565515e+03 1.88492053e+03 1.85869519e+03 1.92887366e+03 1.85124829e+03 1.74656812e+03 1.65159875e+03 1.59815808e+03 1.64901038e+03 1.60631604e+03 1.51120764e+03 1.41974280e+03 1.36528564e+03 1.36688586e+03 1.31577466e+03 1.26095349e+03 1.18703040e+03 1.15952576e+03 1.15854578e+03 1.08227759e+03 1.03914441e+03 9.99824524e+02 9.32582214e+02 8.60427368e+02 8.12278320e+02 7.82809021e+02 7.35683289e+02 6.89155334e+02 6.17602478e+02 5.75334656e+02 5.63174072e+02 4.91219147e+02 4.26393158e+02 3.89460114e+02 3.40278717e+02 3.00354156e+02 2.45959503e+02 1.89257095e+02 1.48830139e+02 9.99331894e+01 4.87184982e+01 -7.40290701e-01 -4.97636261e+01 -9.76807480e+01 -1.46065338e+02 -1.97975510e+02 -2.40551712e+02 -2.93937531e+02 -3.63945496e+02 -4.06314728e+02 -4.34577911e+02 -4.67206543e+02 -5.31092651e+02 -6.16874084e+02 -6.56047424e+02 -6.85426941e+02 -7.20264771e+02 -7.62515991e+02 -8.31755493e+02 -8.79841370e+02 -9.50463257e+02 -9.84621643e+02 -9.98080261e+02 -1.07452881e+03 -1.12795642e+03 -1.19745068e+03 -1.23848975e+03 -1.25659607e+03 -1.29886963e+03 -1.34604272e+03 -1.42164197e+03 -1.43113562e+03 -1.50143567e+03 -1.63618860e+03 -1.64644666e+03 -1.65339160e+03 -1.65763354e+03 -1.69326453e+03 -1.83569958e+03 -1.89991821e+03 -1.89471838e+03 -1.88115918e+03 -1.93093311e+03 -2.03937854e+03 -2.08410571e+03 -2.18581396e+03 -2.22393262e+03 -2.21843115e+03 -2.19522388e+03 -2.23289941e+03 -2.43106934e+03 -2.45379175e+03 -2.42383008e+03 -2.44681494e+03 -2.48292676e+03 -2.64545093e+03 -2.71118896e+03 -2.61950073e+03 -2.64480249e+03 -2.83566919e+03 -2.88487134e+03 -2.78393408e+03 -2.81894604e+03 -3.02232251e+03 -3.07381177e+03 -3.01814746e+03 -2.99469873e+03 -3.02678247e+03 -3.26259912e+03 -3.28486865e+03 -3.21048706e+03 -3.26436792e+03 -3.27665381e+03 -3.37517773e+03 -3.44451733e+03 -3.44888208e+03 -3.40719556e+03 -3.53224438e+03 -3.73635938e+03 -3.65851074e+03 -3.72633887e+03 -3.81247754e+03 -3.76847144e+03 -3.82221924e+03 -3.85563477e+03 -3.86545728e+03 -3.83404419e+03 -3.85859033e+03 -3.98623242e+03 -4.05191504e+03 -4.21492676e+03 -4.13048389e+03 -4.03954736e+03 -4.18722705e+03 -4.25221191e+03 -4.42712207e+03 -4.39172021e+03 -4.30048193e+03 -4.35530127e+03 -4.37802686e+03 -4.48742529e+03 -4.51616406e+03 -4.65900586e+03 -4.65070361e+03 -4.55606445e+03 -4.62899805e+03 -4.52279395e+03 -4.71353613e+03 -5.04066016e+03 -4.95320459e+03 -4.83649951e+03 -4.74105713e+03 -4.72856006e+03 -4.99972168e+03 -5.18928662e+03 -5.07627393e+03 -4.91605615e+03 -4.94628418e+03 -5.12923975e+03 -5.13539844e+03 -5.28226416e+03 -5.28079004e+03 -5.15988428e+03 -5.27658203e+03 -5.29460059e+03 -5.48263037e+03 -5.52827051e+03 -5.25465967e+03 -5.28436182e+03 -5.62159814e+03 -5.55308105e+03 -5.30115332e+03 -5.50859375e+03 -5.84785840e+03 -5.76386035e+03 -5.63265820e+03 -5.53324561e+03 -5.57488428e+03 -5.90933105e+03 -5.92416211e+03 -5.80217383e+03 -5.68792236e+03 -5.66961768e+03 -5.87723096e+03 -5.92184814e+03 -5.91551758e+03 -5.82002881e+03 -5.97667969e+03 -6.18854346e+03 -6.06054346e+03 -6.17386182e+03 -6.10458203e+03 -5.96203125e+03 -6.11872363e+03 -6.18272070e+03 -6.21054004e+03 -6.16364062e+03 -6.13665039e+03 -6.04569873e+03 -6.23238086e+03 -6.65650293e+03 -6.32009570e+03 -6.04336084e+03 -6.24055469e+03 -6.48480322e+03 -6.67014990e+03 -6.49820898e+03 -6.35961279e+03 -6.52767627e+03 -6.57708594e+03 -6.32745361e+03 -6.27554590e+03 -6.65890039e+03 -6.65773340e+03 -6.45709180e+03 -6.51253027e+03 -6.31611523e+03 -6.54825684e+03 -6.99567627e+03 -6.82566650e+03 -6.65196094e+03 -6.47560449e+03 -6.41307861e+03 -6.78512988e+03 -7.16098535e+03 -6.91983984e+03 -6.57981982e+03 -6.56073877e+03 -6.73579492e+03 -6.77447119e+03 -6.99241357e+03 -6.82356445e+03 -6.64440869e+03 -6.87037842e+03 -6.82592822e+03 -7.03180469e+03 -6.98538770e+03 -6.70817871e+03 -6.96108105e+03 -6.96407861e+03 -6.88988037e+03 -6.71007861e+03 -6.80677832e+03 -7.19555664e+03 -7.11336279e+03 -6.82538086e+03 -6.69812598e+03 -6.88468115e+03 -7.26800391e+03 -7.19069043e+03 -6.97880273e+03 -6.77469727e+03 -6.75642529e+03 -6.97938916e+03 -7.01818945e+03 -7.03155225e+03 -6.82365967e+03 -6.98213916e+03 -7.21287207e+03 -7.00942578e+03 -7.18709521e+03 -7.15562012e+03 -6.97532520e+03 -7.01009424e+03 -7.02229199e+03 -6.98665771e+03 -6.96899609e+03 -6.90234229e+03 -6.90610303e+03 -7.18214648e+03 -7.17866650e+03 -6.85421582e+03 -6.75112305e+03 -6.89537549e+03 -7.10817236e+03 -7.33623047e+03 -7.08946240e+03 -6.71209814e+03 -6.98186377e+03 -7.29002197e+03 -7.14526025e+03 -6.82491064e+03 -6.83370703e+03 -6.92506641e+03 -6.94870312e+03 -6.96682959e+03 -6.78762891e+03 -6.92955762e+03 -7.22866748e+03 -7.05589355e+03 -6.91899512e+03 -6.75719629e+03 -6.79675000e+03 -7.09448096e+03 -7.05623926e+03 -6.91190234e+03 -6.73414062e+03 -6.52656152e+03 -6.64794482e+03 -7.01253955e+03 -7.25516016e+03 -6.82502734e+03 -6.52056641e+03 -6.69121143e+03 -6.82544287e+03 -7.06884717e+03 -6.89984473e+03 -6.61583350e+03 -6.72783447e+03 -6.69010986e+03 -6.65701514e+03 -6.49493018e+03 -6.57800146e+03 -6.88354150e+03 -6.76420605e+03 -6.64392480e+03 -6.47452393e+03 -6.44275830e+03 -6.77679883e+03 -6.77302051e+03 -6.55340967e+03 -6.36053760e+03 -6.29206299e+03 -6.46168604e+03 -6.43330371e+03 -6.60528613e+03 -6.65679248e+03 -6.30872559e+03 -6.14816016e+03 -6.35781836e+03 -6.58874023e+03 -6.36986572e+03 -6.25291406e+03 -6.20825146e+03 -6.18152393e+03 -6.11843262e+03 -5.97382666e+03 -6.20109326e+03 -6.29356250e+03 -6.08088477e+03 -6.18627051e+03 -6.21010352e+03 -6.12116748e+03 -6.09591504e+03 -6.01753418e+03 -5.99416992e+03 -5.83112988e+03 -5.72911914e+03 -5.96293213e+03 -6.06920459e+03 -5.77145898e+03 -5.50547754e+03 -5.72389453e+03 -6.03749268e+03 -5.97892041e+03 -5.64774756e+03 -5.41502490e+03 -5.66345703e+03 -5.84618506e+03 -5.68268262e+03 -5.62663281e+03 -5.40404883e+03 -5.18467773e+03 -5.36343115e+03 -5.67193555e+03 -5.63942871e+03 -5.28847510e+03 -5.09185156e+03 -5.37148145e+03 -5.53741553e+03 -5.33965625e+03 -5.06891357e+03 -4.91660352e+03 -5.05275391e+03 -5.11211523e+03 -5.20395312e+03 -5.25009326e+03 -5.03702686e+03 -4.87627148e+03 -4.85950146e+03 -5.03295605e+03 -4.87108105e+03 -4.71170508e+03 -4.88701123e+03 -4.84105371e+03 -4.75131592e+03 -4.60380078e+03 -4.56351562e+03 -4.78743896e+03 -4.60219873e+03 -4.34088965e+03 -4.42203125e+03 -4.55183691e+03 -4.53431641e+03 -4.39013232e+03 -4.45199609e+03 -4.45547266e+03 -4.29772656e+03 -4.12915332e+03 -4.06695068e+03 -4.27354785e+03 -4.15569531e+03 -3.98425293e+03 -4.07413867e+03 -4.01547339e+03 -3.94963086e+03 -3.86685889e+03 -3.91545874e+03 -3.91066968e+03 -3.77203101e+03 -3.78148779e+03 -3.75284375e+03 -3.73653320e+03 -3.69411157e+03 -3.60058716e+03 -3.49859937e+03 -3.35652344e+03 -3.33142676e+03 -3.47022461e+03 -3.59281079e+03 -3.35442773e+03 -3.10646411e+03 -3.18520850e+03 -3.33653003e+03 -3.31325854e+03 -3.09949219e+03 -2.92111768e+03 -3.03735620e+03 -3.06342358e+03 -2.91593628e+03 -2.97378833e+03 -2.88678882e+03 -2.68081567e+03 -2.70432275e+03 -2.81892041e+03 -2.77745044e+03 -2.59706641e+03 -2.45302393e+03 -2.51243774e+03 -2.63106665e+03 -2.52277148e+03 -2.34491626e+03 -2.24083960e+03 -2.30639868e+03 -2.33994531e+03 -2.22111401e+03 -2.15883984e+03 -2.11920435e+03 -2.07786572e+03 -2.02500415e+03 -2.02744336e+03 -1.94530383e+03 -1.83640015e+03 -1.83417114e+03 -1.79639563e+03 -1.78692627e+03 -1.69988501e+03 -1.60952161e+03 -1.63272583e+03 -1.53206030e+03 -1.44589600e+03 -1.46349805e+03 -1.44238245e+03 -1.38073547e+03 -1.30151453e+03 -1.30008130e+03 -1.26432080e+03 -1.17041138e+03 -1.09606519e+03 -1.04869373e+03 -1.06719885e+03 -9.86979309e+02 -8.86701355e+02 -9.58494812e+02 -1.14567749e+03 -1.05769348e+03 -2.65820068e+03 -3.05015674e+03 -1.89622422e+05 -2.80026650e+06 0. 0. 0. 0. 0. -3.15935667e+09 -14147680. -1.60170081e+03 -1.92591602e+04 1.62657861e+04 -4.36760586e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1261755264. 2.18308574e+04 1.28036255e+03 9.27579834e+02 9.23900330e+02 8.65357849e+02 9.41869507e+02 9.53082275e+02 9.96841431e+02 1.01909991e+03 1.03172375e+03 1.11249329e+03 1.19902661e+03 1.20781775e+03 1.24184570e+03 1.31286694e+03 1.37629773e+03 1.43214111e+03 1.43398340e+03 1.43784766e+03 1.51580310e+03 1.60148938e+03 1.66220496e+03 1.69471802e+03 1.70035779e+03 1.75571252e+03 1.86681702e+03 1.94261597e+03 1.93072412e+03 1.90555627e+03 1.97278027e+03 2.07860938e+03 2.10475195e+03 2.14485254e+03 2.21045679e+03 2.19579419e+03 2.27831616e+03 2.37808765e+03 2.32847681e+03 2.37032397e+03 2.49172876e+03 2.62886011e+03 2.68439111e+03 2.55125146e+03 2.51066016e+03 2.63184521e+03 2.78697095e+03 2.87109766e+03 2.80241650e+03 2.83664282e+03 2.97572656e+03 2.99463672e+03 3.02984326e+03 3.03040967e+03 2.97836865e+03 3.12165381e+03 3.27247412e+03 3.20403809e+03 3.23175488e+03 3.33960986e+03 3.33150415e+03 3.42950635e+03 3.49948120e+03 3.42313867e+03 3.43572046e+03 3.55354053e+03 3.70763599e+03 3.72469580e+03 3.62903784e+03 3.70334131e+03 3.73223267e+03 3.81294531e+03 3.93523877e+03 3.83904370e+03 3.84904590e+03 3.98400049e+03 4.08678467e+03 4.15575293e+03 4.08656836e+03 3.97355103e+03 4.05078540e+03 4.23531934e+03 4.34652734e+03 4.36148096e+03 4.31105225e+03 4.29334619e+03 4.43796777e+03 4.55296240e+03 4.45209521e+03 4.35779980e+03 4.48558301e+03 4.68229883e+03 4.74301270e+03 4.67856348e+03 4.60727490e+03 4.59430957e+03 4.77771729e+03 4.90002734e+03 4.77773975e+03 4.79107031e+03 4.95915869e+03 5.11670264e+03 5.14229102e+03 4.92308789e+03 4.82139893e+03 5.01095654e+03 5.15314307e+03 5.15888672e+03 5.16528320e+03 5.22580859e+03 5.34687256e+03 5.25992188e+03 5.25865381e+03 5.40875391e+03 5.31554736e+03 5.30204199e+03 5.46761914e+03 5.54265234e+03 5.59113428e+03 5.50859814e+03 5.38882471e+03 5.46899902e+03 5.62835254e+03 5.76112158e+03 5.73280811e+03 5.62162354e+03 5.68893555e+03 5.86644629e+03 5.93896387e+03 5.76342188e+03 5.63169434e+03 5.73050879e+03 5.91510107e+03 5.98180420e+03 5.93881152e+03 5.89967529e+03 5.91978516e+03 6.08627783e+03 6.17015381e+03 6.07839795e+03 6.07072705e+03 6.00244092e+03 6.08904150e+03 6.13055762e+03 6.07385059e+03 6.14225586e+03 6.19972998e+03 6.35404980e+03 6.48388916e+03 6.25138672e+03 6.09872949e+03 6.23098486e+03 6.38466846e+03 6.51313037e+03 6.45067432e+03 6.21151270e+03 6.25421289e+03 6.57480273e+03 6.72522803e+03 6.49272852e+03 6.26827734e+03 6.41280469e+03 6.67517773e+03 6.63720557e+03 6.34524951e+03 6.38892578e+03 6.59651270e+03 6.66486621e+03 6.62667285e+03 6.71457666e+03 6.68520557e+03 6.45779590e+03 6.68733008e+03 6.81188330e+03 6.54229443e+03 6.59188086e+03 6.77675098e+03 6.79229346e+03 6.86724951e+03 6.74575488e+03 6.52994531e+03 6.58007471e+03 6.82052588e+03 7.07271387e+03 7.09992920e+03 6.63454199e+03 6.68837939e+03 7.06600928e+03 6.90221875e+03 6.62770557e+03 6.67722070e+03 6.83500537e+03 6.99915576e+03 7.07713721e+03 7.01620410e+03 6.80193701e+03 6.65338379e+03 6.90827686e+03 7.03409961e+03 6.81660596e+03 6.85117480e+03 7.01646094e+03 7.08290967e+03 7.12096191e+03 6.88454785e+03 6.69623877e+03 6.82528906e+03 6.95065283e+03 7.14555615e+03 7.14052930e+03 6.82100684e+03 6.83143896e+03 7.01619482e+03 7.04011865e+03 6.98853027e+03 6.81993066e+03 6.82218408e+03 7.05487402e+03 7.12609766e+03 6.99128662e+03 6.89306494e+03 6.75710645e+03 6.93611621e+03 7.03427295e+03 6.83657471e+03 6.93120312e+03 6.98131787e+03 7.02188037e+03 7.19135107e+03 6.83614990e+03 6.70071289e+03 6.87500684e+03 6.90469922e+03 7.00556201e+03 6.77491260e+03 6.64449268e+03 6.88803076e+03 7.03900928e+03 6.98752979e+03 6.77046191e+03 6.82721484e+03 6.74314062e+03 6.68067432e+03 6.85040137e+03 7.05426221e+03 6.86833887e+03 6.58910449e+03 6.80029980e+03 6.71369092e+03 6.75744775e+03 6.74898828e+03 6.52476611e+03 6.69650146e+03 6.83307422e+03 6.55679932e+03 6.48163379e+03 6.59038428e+03 6.76152295e+03 6.84758789e+03 6.45611572e+03 6.39135010e+03 6.60941016e+03 6.64550049e+03 6.69607959e+03 6.44892822e+03 6.41230664e+03 6.39429541e+03 6.39336816e+03 6.57634033e+03 6.50934766e+03 6.25796924e+03 6.36308301e+03 6.53218408e+03 6.30135400e+03 6.23018945e+03 6.18555225e+03 6.14105078e+03 6.35918555e+03 6.47559521e+03 6.22267236e+03 6.08984766e+03 6.15089795e+03 6.21873828e+03 6.28758545e+03 6.10003613e+03 6.16146729e+03 6.16819434e+03 5.86147168e+03 5.91193311e+03 5.94983936e+03 5.93557031e+03 6.01874170e+03 5.96767285e+03 5.86753564e+03 5.99212695e+03 5.85608936e+03 5.69785156e+03 5.81751807e+03 5.87380078e+03 5.79435400e+03 5.59471826e+03 5.54465234e+03 5.76334180e+03 5.82476514e+03 5.58194189e+03 5.40930615e+03 5.48177930e+03 5.61084717e+03 5.64068750e+03 5.41235498e+03 5.36689893e+03 5.29992334e+03 5.37269775e+03 5.44367285e+03 5.25681396e+03 5.23084180e+03 5.21819336e+03 5.16576074e+03 5.20897021e+03 5.27172021e+03 5.11252686e+03 4.91664844e+03 5.11439697e+03 5.25582080e+03 4.97417578e+03 4.74616553e+03 4.81150781e+03 4.89815039e+03 4.89576562e+03 4.75513184e+03 4.69994189e+03 4.69759619e+03 4.76674365e+03 4.74302734e+03 4.60296338e+03 4.53792725e+03 4.52958545e+03 4.59812109e+03 4.49520361e+03 4.36834961e+03 4.40619775e+03 4.33972217e+03 4.27154639e+03 4.33101660e+03 4.31220459e+03 4.17040381e+03 4.10502832e+03 4.17212451e+03 4.14394678e+03 4.01104102e+03 3.93728345e+03 3.94399927e+03 3.99522119e+03 3.94261719e+03 3.76043652e+03 3.72884302e+03 3.75598022e+03 3.83125879e+03 3.80133887e+03 3.62474121e+03 3.65431909e+03 3.57635327e+03 3.41058862e+03 3.41700488e+03 3.43059790e+03 3.46026685e+03 3.40498657e+03 3.22451099e+03 3.15205835e+03 3.20831763e+03 3.27629370e+03 3.21074878e+03 3.10415698e+03 3.04686548e+03 2.96821265e+03 2.89663062e+03 2.84787964e+03 2.89470337e+03 2.90092822e+03 2.76538306e+03 2.70632227e+03 2.66180737e+03 2.65231323e+03 2.64142822e+03 2.58908643e+03 2.59667944e+03 2.45456885e+03 2.32410718e+03 2.31823413e+03 2.33788843e+03 2.35271631e+03 2.31631079e+03 2.20343750e+03 2.05100317e+03 2.04630115e+03 2.07092651e+03 2.00167944e+03 2.00244543e+03 1.95075891e+03 1.82589954e+03 1.82844104e+03 1.80434912e+03 1.71581274e+03 1.68368555e+03 1.62397974e+03 1.55517017e+03 1.50967712e+03 1.47497900e+03 1.43853687e+03 1.43117786e+03 1.42144299e+03 1.30888184e+03 1.20493127e+03 1.16979944e+03 1.15302612e+03 1.14377966e+03 1.08661487e+03 9.88702332e+02 9.30823730e+02 9.10695312e+02 8.91288940e+02 8.46450745e+02 7.74845154e+02 7.22109558e+02 6.74779541e+02 6.20578857e+02 5.69396301e+02 5.33438293e+02 4.91481110e+02 4.38028198e+02 3.92105469e+02 3.32370026e+02 2.82779022e+02 2.42559433e+02 1.95052185e+02 1.47778412e+02 9.46960449e+01 4.47294083e+01 -2.50449991e+00 -5.13965836e+01 -1.01990799e+02 -1.52571732e+02 -1.96315506e+02 -2.35046417e+02 -2.87815887e+02 -3.41021820e+02 -3.83325134e+02 -4.43454803e+02 -5.01771484e+02 -5.31722473e+02 -5.73559448e+02 -6.26928223e+02 -6.88843872e+02 -7.47899536e+02 -7.84283997e+02 -8.31466919e+02 -8.53109924e+02 -8.93909302e+02 -9.71089294e+02 -1.02724048e+03 -1.09185730e+03 -1.13993213e+03 -1.14800171e+03 -1.17333472e+03 -1.25502124e+03 -1.33869324e+03 -1.37233337e+03 -1.40483606e+03 -1.44650647e+03 -1.46574805e+03 -1.52473376e+03 -1.60353613e+03 -1.64696570e+03 -1.70150793e+03 -1.72825720e+03 -1.74737732e+03 -1.79281189e+03 -1.89266479e+03 -1.95009534e+03 -1.97087012e+03 -2.03866003e+03 -2.02762415e+03 -2.09557935e+03 -2.17597632e+03 -2.19972070e+03 -2.30824683e+03 -2.29335938e+03 -2.26972852e+03 -2.33843433e+03 -2.38566479e+03 -2.48695825e+03 -2.63355542e+03 -2.63214893e+03 -2.56078027e+03 -2.59504517e+03 -2.64230835e+03 -2.68293823e+03 -2.80994531e+03 -2.89798511e+03 -2.85381860e+03 -2.87036792e+03 -2.92414453e+03 -3.02882202e+03 -3.10896582e+03 -3.12179272e+03 -3.25975244e+03 -3.21551367e+03 -3.06260645e+03 -3.17067432e+03 -3.34401758e+03 -3.43625708e+03 -3.50135767e+03 -3.43395996e+03 -3.30690210e+03 -3.44921631e+03 -3.67926538e+03 -3.68740381e+03 -3.65056616e+03 -3.66555835e+03 -3.64621875e+03 -3.77196558e+03 -3.84888550e+03 -3.81238184e+03 -3.97887402e+03 -3.98222852e+03 -3.95674121e+03 -4.01421411e+03 -3.94201172e+03 -4.03921436e+03 -4.18089893e+03 -4.32516357e+03 -4.25841113e+03 -4.06842969e+03 -4.15056055e+03 -4.33314941e+03 -4.46767578e+03 -4.47160254e+03 -4.36226318e+03 -4.34292529e+03 -4.47569434e+03 -4.61728174e+03 -4.66796777e+03 -4.68068359e+03 -4.68204541e+03 -4.66430811e+03 -4.70853369e+03 -4.74524756e+03 -4.79653076e+03 -4.86611279e+03 -4.90576270e+03 -5.00144775e+03 -4.86368604e+03 -4.88034570e+03 -5.06248438e+03 -5.06119971e+03 -5.22540527e+03 -5.17600830e+03 -4.95495117e+03 -5.03616406e+03 -5.17980469e+03 -5.36904590e+03 -5.50564502e+03 -5.32380078e+03 -5.19209570e+03 -5.26351416e+03 -5.38154736e+03 -5.46687695e+03 -5.50540820e+03 -5.54957275e+03 -5.44687939e+03 -5.41520703e+03 -5.49889014e+03 -5.65101660e+03 -5.78944873e+03 -5.73375098e+03 -5.75868994e+03 -5.67899854e+03 -5.52286377e+03 -5.67171045e+03 -5.82177441e+03 -5.98355225e+03 -5.98303906e+03 -5.70673975e+03 -5.67210205e+03 -5.91871582e+03 -6.17407910e+03 -6.09442676e+03 -6.01798877e+03 -6.02716455e+03 -5.85628271e+03 -6.04238818e+03 -6.23082812e+03 -6.14350977e+03 -6.11539453e+03 -6.09803320e+03 -6.20630078e+03 -6.22422510e+03 -6.21314551e+03 -6.29596826e+03 -6.36184033e+03 -6.34900684e+03 -6.17730127e+03 -6.27794189e+03 -6.39083105e+03 -6.38303369e+03 -6.60406396e+03 -6.46483594e+03 -6.23848779e+03 -6.36345264e+03 -6.35710986e+03 -6.63034424e+03 -6.89029150e+03 -6.60484766e+03 -6.39154688e+03 -6.34911621e+03 -6.64011426e+03 -7.09094922e+03 -6.97147705e+03 -6.43709033e+03 -1.18582842e+04 -1.34821279e+04 1.39985525e+06 314489440. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 12928603. -6.19341680e+04 -1.31654883e+04 -1.14451533e+04 -1.06301992e+04 -7.96314307e+03 -8.72070703e+03 -7.47048877e+03 -6.90203906e+03 -6.96636279e+03 -7.24449707e+03 -7.15752490e+03 -6.88268799e+03 -6.67287695e+03 -6.69357812e+03 -7.03028125e+03 -7.28095068e+03 -7.02548730e+03 -6.78253906e+03 -6.73357178e+03 -6.76171826e+03 -7.04035352e+03 -7.07813037e+03 -6.83877002e+03 -6.69433740e+03 -6.70915820e+03 -6.82700977e+03 -6.83955811e+03 -6.70304590e+03 -6.74596777e+03 -6.95306494e+03 -7.10352002e+03 -6.76213672e+03 -6.37745361e+03 -6.56188379e+03 -6.91052148e+03 -7.09466504e+03 -6.78109619e+03 -6.39136914e+03 -6.45958789e+03 -6.75726416e+03 -7.04508105e+03 -6.74084717e+03 -6.31379932e+03 -6.38159912e+03 -6.67480176e+03 -6.74899219e+03 -6.72225977e+03 -6.58172705e+03 -6.40192236e+03 -6.42874072e+03 -6.61871631e+03 -6.37237842e+03 -6.28592383e+03 -6.56698291e+03 -6.61023145e+03 -6.55677100e+03 -6.27585791e+03 -6.00937256e+03 -6.33895020e+03 -6.72790381e+03 -6.52176270e+03 -6.12866846e+03 -5.88908496e+03 -5.98773096e+03 -6.36593701e+03 -6.56546533e+03 -6.33393213e+03 -6.17383691e+03 -6.03404443e+03 -5.86122803e+03 -6.06806445e+03 -6.22669971e+03 -6.01607422e+03 -5.92867969e+03 -6.00114307e+03 -6.00656445e+03 -5.84705518e+03 -5.78021729e+03 -5.93537451e+03 -6.00007861e+03 -6.01016309e+03 -5.82972021e+03 -5.54842725e+03 -5.53381982e+03 -5.82701709e+03 -6.07061572e+03 -5.76368115e+03 -5.38501611e+03 -5.43095264e+03 -5.57766748e+03 -5.71195068e+03 -5.73292871e+03 -5.50883936e+03 -5.41453516e+03 -5.38193115e+03 -5.42504395e+03 -5.48305029e+03 -5.36877783e+03 -5.29995850e+03 -5.24097803e+03 -5.25782324e+03 -5.25050146e+03 -5.15113330e+03 -5.18365088e+03 -5.21350879e+03 -5.23157422e+03 -5.08454395e+03 -4.81681006e+03 -4.88235254e+03 -5.11690283e+03 -5.16496484e+03 -4.89742578e+03 -4.62882080e+03 -4.63711377e+03 -4.85998340e+03 -5.06248828e+03 -4.83233105e+03 -4.54030908e+03 -4.58983496e+03 -4.55489160e+03 -4.55031689e+03 -4.56032471e+03 -4.46804248e+03 -4.52782227e+03 -4.44438818e+03 -4.37755127e+03 -4.36116650e+03 -4.21757861e+03 -4.27664844e+03 -4.40407324e+03 -4.34602246e+03 -4.15345020e+03 -3.97874365e+03 -3.96342505e+03 -4.09290942e+03 -4.21338916e+03 -4.01860547e+03 -3.76558325e+03 -3.76838086e+03 -3.91622803e+03 -3.99487646e+03 -3.79460596e+03 -3.65499170e+03 -3.65127173e+03 -3.60838281e+03 -3.63913843e+03 -3.62023438e+03 -3.43138086e+03 -3.39004053e+03 -3.47625439e+03 -3.47254248e+03 -3.37856616e+03 -3.26585522e+03 -3.23539771e+03 -3.24312695e+03 -3.29107861e+03 -3.17633398e+03 -2.97118799e+03 -2.96931689e+03 -3.00662622e+03 -3.00973413e+03 -2.96747021e+03 -2.82591504e+03 -2.76651562e+03 -2.77141895e+03 -2.78503394e+03 -2.73592603e+03 -2.62181909e+03 -2.61149658e+03 -2.57304834e+03 -2.52202734e+03 -2.46663062e+03 -2.36278027e+03 -2.36734229e+03 -2.40606470e+03 -2.37132886e+03 -2.24249341e+03 -2.10811768e+03 -2.08034619e+03 -2.13253491e+03 -2.16398413e+03 -2.03430542e+03 -1.88113232e+03 -1.85885815e+03 -1.87303857e+03 -1.87099951e+03 -1.82299170e+03 -1.70468225e+03 -1.64612036e+03 -1.63451831e+03 -1.60101318e+03 -1.55013086e+03 -1.49101880e+03 -1.44957739e+03 -1.38515784e+03 -1.34865112e+03 -1.31079553e+03 -1.24572839e+03 -1.20643628e+03 -1.16600574e+03 -1.12600659e+03 -1.04092639e+03 -9.72740967e+02 -9.65037109e+02 -9.53069702e+02 -9.09168335e+02 -8.22531494e+02 -7.40122742e+02 -6.97616333e+02 -6.89120422e+02 -6.70337402e+02 -6.01304688e+02 -5.25248779e+02 -4.66957214e+02 -4.20577515e+02 -3.90677582e+02 -3.54220428e+02 -2.96066101e+02 -2.41484268e+02 -1.92798676e+02 -1.43304352e+02 -9.24827499e+01 -4.51550560e+01 2.51131868e+00 5.13092461e+01 1.02409660e+02 1.49202148e+02 1.86562714e+02 2.37859100e+02 2.95954712e+02 3.45071625e+02 3.94991577e+02 4.39328094e+02 4.96627533e+02 5.49233398e+02 5.72953552e+02 6.00805237e+02 6.61179199e+02 7.45277283e+02 8.17637329e+02 8.52316589e+02 8.51914917e+02 8.76531067e+02 9.45603638e+02 1.03636792e+03 1.11685474e+03 1.14930957e+03 1.13542798e+03 1.17428979e+03 1.29127246e+03 1.34380566e+03 1.32501147e+03 1.36641968e+03 1.44419434e+03 1.49264417e+03 1.58658508e+03 1.59612439e+03 1.58917566e+03 1.67944702e+03 1.68294934e+03 1.77011548e+03 1.88110291e+03 1.83248840e+03 1.90699792e+03 2.01594519e+03 2.01705225e+03 2.06116211e+03 2.09983569e+03 2.15359253e+03 2.22640308e+03 2.24590576e+03 2.21777197e+03 2.28078979e+03 2.43738501e+03 2.53588770e+03 2.52797070e+03 2.47349365e+03 2.45232373e+03 2.53975024e+03 2.70995142e+03 2.83061035e+03 2.82501733e+03 2.70316260e+03 2.74875220e+03 2.92386401e+03 2.94676416e+03 2.93850586e+03 2.98410352e+03 3.04032349e+03 3.08048047e+03 3.23968188e+03 3.20505127e+03 3.13017334e+03 3.23943457e+03 3.20702368e+03 3.36883105e+03 3.49534839e+03 3.43574170e+03 3.58632544e+03 3.53906250e+03 3.44794873e+03 3.58246655e+03 3.55363745e+03 3.67041187e+03 3.95587744e+03 3.79605469e+03 3.63202124e+03 3.76111987e+03 3.94721753e+03 4.12446191e+03 4.10803467e+03 3.93244214e+03 3.82124390e+03 3.94092725e+03 4.23206641e+03 4.40393164e+03 4.34622314e+03 4.15434375e+03 4.15573486e+03 4.37051904e+03 4.45941357e+03 4.34881201e+03 4.33425977e+03 4.43967871e+03 4.49952295e+03 4.67964258e+03 4.71267480e+03 4.56218750e+03 4.58928662e+03 4.61639258e+03 4.66259521e+03 4.79865186e+03 4.81932617e+03 4.95680420e+03 4.89014502e+03 4.74279004e+03 4.91814014e+03 4.83120557e+03 4.96667676e+03 5.34790283e+03 5.13836719e+03 4.81821875e+03 4.93875830e+03 5.23314551e+03 5.39719336e+03 5.47828369e+03 5.25156934e+03 5.03761426e+03 5.14453662e+03 5.45086572e+03 5.73549805e+03 5.59379834e+03 5.27034619e+03 5.25614893e+03 5.43611572e+03 5.63013037e+03 5.83472803e+03 5.78761523e+03 5.47583154e+03 5.45108740e+03 5.73629736e+03 5.81758789e+03 5.75802002e+03 5.77942725e+03 5.71758447e+03 5.68698193e+03 5.98066406e+03 6.05630713e+03 5.77804639e+03 5.77014795e+03 5.92287109e+03 5.98876074e+03 6.01263428e+03 5.98223438e+03 6.12437305e+03 6.24394531e+03 6.07864648e+03 5.98747070e+03 5.91893066e+03 6.16282178e+03 6.50918799e+03 6.39650635e+03 6.10347559e+03 5.96579150e+03 6.21325879e+03 6.57461426e+03 6.36705225e+03 6.04820410e+03 6.17749414e+03 6.38606396e+03 6.54607959e+03 6.76178271e+03 6.64870068e+03 6.28010498e+03 6.14222949e+03 6.35020361e+03 6.70938281e+03 6.70191260e+03 6.54430469e+03 6.49213574e+03 6.53292041e+03 6.72213916e+03 6.65590723e+03 6.44636719e+03 6.45870117e+03 6.46604541e+03 6.77447656e+03 6.94380420e+03 6.71590234e+03 6.67132080e+03 6.71663477e+03 6.90912939e+03 6.77542480e+03 6.42536084e+03 6.71387500e+03 7.12260205e+03 6.86329248e+03 6.55694385e+03 6.69493799e+03 7.06912305e+03 7.05444629e+03 6.87327686e+03 6.86306494e+03 6.65822656e+03 6.67347803e+03 7.06877197e+03 7.06747119e+03 6.81444385e+03 6.62255029e+03 6.63943994e+03 6.92452393e+03 7.28677588e+03 6.98569629e+03 6.79822314e+03 6.92595752e+03 6.91366748e+03 7.13863525e+03 7.11906396e+03 6.74390186e+03 6.71841162e+03 6.88085693e+03 6.93352295e+03 6.98926074e+03 6.98062207e+03 7.16907031e+03 7.08638867e+03 6.78750586e+03 6.78856885e+03 6.75292676e+03 7.02777979e+03 7.28085303e+03 7.13972266e+03 6.88587988e+03 6.78597314e+03 7.23916748e+03 7.36957178e+03 7.51447070e+03 7.98748193e+03 9.41653125e+03 1.28844590e+04 1.21028555e+05 -17152160. 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. 0. 0. 0. 0. 0. 0. 0. 41193472. 1.06774414e+05 2.03173262e+04 1.15811357e+04 1.05034355e+04 1.02411055e+04 7.31936279e+03 7.44216064e+03 6.71979688e+03 6.78184619e+03 6.61209473e+03 6.32134082e+03 6.40069775e+03 6.41375684e+03 6.29007617e+03 6.31388965e+03 6.25598535e+03 6.24020215e+03 6.23565088e+03 6.19494238e+03 6.13943799e+03 6.01262549e+03 5.94442920e+03 6.22026318e+03 6.22124121e+03 5.87262354e+03 5.84483398e+03 6.14753906e+03 6.15393311e+03 5.98639502e+03 5.95687354e+03 5.88477979e+03 5.88911963e+03 5.83306885e+03 5.80264941e+03 5.80119141e+03 5.76792920e+03 5.61818701e+03 5.55201465e+03 5.80006885e+03 5.80388281e+03 5.61909570e+03 5.57805713e+03 5.55810938e+03 5.55620801e+03 5.50006055e+03 5.44281006e+03 5.44071729e+03 5.27218213e+03 5.20801367e+03 5.34744336e+03 5.29317139e+03 5.43652002e+03 5.46448047e+03 5.23864209e+03 5.04978955e+03 4.97849756e+03 5.28816455e+03 5.29712402e+03 5.05714844e+03 4.95651025e+03 4.96959766e+03 4.96186719e+03 4.88528174e+03 4.99639160e+03 4.95337842e+03 4.66870264e+03 4.61101221e+03 4.81752393e+03 4.90477441e+03 4.73947607e+03 4.63882715e+03 4.62485254e+03 4.57366650e+03 4.46684521e+03 4.43316406e+03 4.48468262e+03 4.44666406e+03 4.33709570e+03 4.31204102e+03 4.33129053e+03 4.26461621e+03 4.33811328e+03 4.27646582e+03 4.10764648e+03 4.13412842e+03 4.09095044e+03 4.07893896e+03 4.06833569e+03 3.98084546e+03 3.91207422e+03 3.80999170e+03 3.72537915e+03 3.84605835e+03 3.79769580e+03 3.57169409e+03 3.58337671e+03 3.75328076e+03 3.83609155e+03 3.65980542e+03 3.51203394e+03 3.42123511e+03 3.37159253e+03 3.36060522e+03 3.31962769e+03 3.32606592e+03 3.26586963e+03 3.26930347e+03 3.21792114e+03 3.09346753e+03 3.11114355e+03 2.97413599e+03 2.94212256e+03 3.07035889e+03 2.98955371e+03 2.87737061e+03 2.76568188e+03 2.69506226e+03 2.80694751e+03 2.78185352e+03 2.63905078e+03 2.53257080e+03 2.49359082e+03 2.51366992e+03 2.46174023e+03 2.48419604e+03 2.45466724e+03 2.33791772e+03 2.26832861e+03 2.22310596e+03 2.22088550e+03 2.17472437e+03 2.10055420e+03 2.01738232e+03 1.97463269e+03 1.97311316e+03 1.86856543e+03 1.82732312e+03 1.88845996e+03 1.82992139e+03 1.73034973e+03 1.63348291e+03 1.58610632e+03 1.63588074e+03 1.58705493e+03 1.49503223e+03 1.41053845e+03 1.35626843e+03 1.35391467e+03 1.30092554e+03 1.25022412e+03 1.17883899e+03 1.15171680e+03 1.15744934e+03 1.08128552e+03 1.02160840e+03 9.77795776e+02 9.23564087e+02 8.61518250e+02 8.10571411e+02 7.74521973e+02 7.29370544e+02 6.83637207e+02 6.11312012e+02 5.64797119e+02 5.53602417e+02 4.86605774e+02 4.21478424e+02 3.85262360e+02 3.36949127e+02 2.98707275e+02 2.43665085e+02 1.86511520e+02 1.47496811e+02 9.88200989e+01 4.79282532e+01 -5.99164903e-01 -4.83829193e+01 -9.75011368e+01 -1.46008591e+02 -1.96274689e+02 -2.38564240e+02 -2.91055847e+02 -3.58746674e+02 -4.01229767e+02 -4.34212769e+02 -4.68185394e+02 -5.22218262e+02 -6.03989929e+02 -6.51687073e+02 -6.81305237e+02 -7.13882629e+02 -7.55864319e+02 -8.21842468e+02 -8.71767029e+02 -9.45166626e+02 -9.75235779e+02 -9.89075684e+02 -1.06456921e+03 -1.11534058e+03 -1.18653003e+03 -1.21785510e+03 -1.23218237e+03 -1.29750439e+03 -1.34502612e+03 -1.40575745e+03 -1.41455139e+03 -1.48839050e+03 -1.62879614e+03 -1.63030029e+03 -1.63664563e+03 -1.64312500e+03 -1.67346582e+03 -1.81880591e+03 -1.88638806e+03 -1.87874268e+03 -1.86180237e+03 -1.90952502e+03 -2.02161987e+03 -2.06483618e+03 -2.16482275e+03 -2.20128027e+03 -2.19726562e+03 -2.18073413e+03 -2.21065088e+03 -2.40480078e+03 -2.41905347e+03 -2.38979712e+03 -2.43389478e+03 -2.46969287e+03 -2.62276562e+03 -2.68102808e+03 -2.59649976e+03 -2.61852856e+03 -2.79744409e+03 -2.86684741e+03 -2.76310645e+03 -2.79078076e+03 -2.99120190e+03 -3.04506787e+03 -2.99835693e+03 -2.97871753e+03 -3.00718896e+03 -3.22647192e+03 -3.22778174e+03 -3.16153345e+03 -3.24588794e+03 -3.28028833e+03 -3.39475806e+03 -3.44495728e+03 -3.37557178e+03 -3.34147827e+03 -3.49559595e+03 -3.73479443e+03 -3.66937842e+03 -3.65103638e+03 -3.73231396e+03 -3.73713086e+03 -3.78608447e+03 -3.81926050e+03 -3.83956128e+03 -3.79705322e+03 -3.81410571e+03 -3.93234790e+03 -4.02951514e+03 -4.19112988e+03 -4.10733789e+03 -3.97444702e+03 -4.12335449e+03 -4.24591992e+03 -4.41944336e+03 -4.36151660e+03 -4.25855566e+03 -4.29552588e+03 -4.33214502e+03 -4.44615332e+03 -4.46381738e+03 -4.60823975e+03 -4.63830859e+03 -4.55269580e+03 -4.54114795e+03 -4.44253320e+03 -4.67838037e+03 -5.00482422e+03 -4.92187549e+03 -4.80221729e+03 -4.69739160e+03 -4.64232715e+03 -4.91178467e+03 -5.19311133e+03 -5.06994971e+03 -4.86935791e+03 -4.89334229e+03 -5.06468457e+03 -5.09079150e+03 -5.25054053e+03 -5.26098584e+03 -5.15330029e+03 -5.17739014e+03 -5.19803369e+03 -5.41994824e+03 -5.47791504e+03 -5.21670605e+03 -5.22420898e+03 -5.55143555e+03 -5.54330371e+03 -5.29043604e+03 -5.43373633e+03 -5.74827734e+03 -5.71988721e+03 -5.58682422e+03 -5.48313330e+03 -5.50212988e+03 -5.86060645e+03 -5.87326270e+03 -5.75578467e+03 -5.65255273e+03 -5.60782422e+03 -5.79867578e+03 -5.88258643e+03 -5.84892578e+03 -5.72877051e+03 -5.91706885e+03 -6.13178564e+03 -5.98870850e+03 -6.11797803e+03 -6.09860254e+03 -5.97491846e+03 -6.07105420e+03 -6.12728271e+03 -6.16031396e+03 -6.11974707e+03 -6.01309229e+03 -5.94831445e+03 -6.21359766e+03 -6.61281982e+03 -6.28808887e+03 -6.00810156e+03 -6.22199756e+03 -6.38551758e+03 -6.58029932e+03 -6.41798730e+03 -6.22016699e+03 -6.53346436e+03 -6.59355518e+03 -6.25453955e+03 -6.22945068e+03 -6.62214111e+03 -6.64889453e+03 -6.44554541e+03 -6.38531787e+03 -6.16154980e+03 -6.47519336e+03 -6.94540039e+03 -6.78269678e+03 -6.57304004e+03 -6.40618457e+03 -6.32239648e+03 -6.66163086e+03 -7.08846191e+03 -6.86038330e+03 -6.52510645e+03 -6.49127295e+03 -6.71013037e+03 -6.75474268e+03 -6.93953711e+03 -6.77970166e+03 -6.60473926e+03 -6.78270068e+03 -6.77248730e+03 -7.00838916e+03 -6.96276221e+03 -6.74094580e+03 -6.77252197e+03 -6.74804150e+03 -6.92063330e+03 -6.72612305e+03 -6.66279053e+03 -7.09466992e+03 -7.06852832e+03 -6.80426709e+03 -6.65116650e+03 -6.76308594e+03 -7.13691602e+03 -7.13117578e+03 -6.93203418e+03 -6.74459473e+03 -6.71072119e+03 -6.92860498e+03 -6.90363525e+03 -6.95295312e+03 -6.77049561e+03 -6.92111475e+03 -7.20568896e+03 -6.92296484e+03 -7.11050781e+03 -7.14050195e+03 -6.96765430e+03 -6.83889111e+03 -6.77894385e+03 -7.05585010e+03 -7.06085352e+03 -6.77816650e+03 -6.74412744e+03 -7.11241357e+03 -7.17447070e+03 -6.78867822e+03 -6.60341113e+03 -6.78545654e+03 -7.04310840e+03 -7.32079883e+03 -6.99992627e+03 -6.69998975e+03 -6.96827832e+03 -7.12265332e+03 -6.98420703e+03 -6.84255566e+03 -6.81355615e+03 -6.79497070e+03 -6.79843457e+03 -6.90230469e+03 -6.68389209e+03 -6.85151562e+03 -7.16915479e+03 -6.96874805e+03 -6.91085303e+03 -6.76411572e+03 -6.66153027e+03 -6.98582715e+03 -6.97247217e+03 -6.82076025e+03 -6.65507275e+03 -6.44299414e+03 -6.56825928e+03 -6.90949170e+03 -7.13102295e+03 -6.77613330e+03 -6.50814404e+03 -6.66552100e+03 -6.71275439e+03 -6.96728125e+03 -6.88001465e+03 -6.63843701e+03 -6.58986816e+03 -6.55520264e+03 -6.54067334e+03 -6.39492383e+03 -6.57124951e+03 -6.82032129e+03 -6.61387354e+03 -6.63472314e+03 -6.49937842e+03 -6.33147656e+03 -6.70854053e+03 -6.67485938e+03 -6.45533936e+03 -6.29907227e+03 -6.21090527e+03 -6.40007373e+03 -6.37729346e+03 -6.53902832e+03 -6.58330957e+03 -6.30844678e+03 -6.16293604e+03 -6.22654053e+03 -6.50213428e+03 -6.37059326e+03 -6.21471631e+03 -6.11813867e+03 -6.07610059e+03 -6.10591846e+03 -6.06259180e+03 -6.20061230e+03 -6.19301660e+03 -5.99823926e+03 -6.15583203e+03 -6.18997070e+03 -6.03794141e+03 -5.98863623e+03 -5.97171631e+03 -5.94235254e+03 -5.76975098e+03 -5.66687451e+03 -5.95421387e+03 -5.98851855e+03 -5.62910742e+03 -5.44489893e+03 -5.70087207e+03 -6.03951123e+03 -5.89302979e+03 -5.52673340e+03 -5.39743018e+03 -5.68912256e+03 -5.70331494e+03 -5.49834521e+03 -5.60657031e+03 -5.41219678e+03 -5.14912061e+03 -5.27161523e+03 -5.55034326e+03 -5.62551074e+03 -5.29796338e+03 -5.02858008e+03 -5.29721875e+03 -5.49874512e+03 -5.29676660e+03 -5.04022656e+03 -4.93397510e+03 -5.06378174e+03 -5.05700977e+03 -5.15839355e+03 -5.10487451e+03 -4.91031592e+03 -4.88274268e+03 -4.84769629e+03 -4.97645459e+03 -4.82606396e+03 -4.66071826e+03 -4.80891016e+03 -4.74563037e+03 -4.74369922e+03 -4.61803418e+03 -4.50912256e+03 -4.73153613e+03 -4.56165527e+03 -4.34678271e+03 -4.41801074e+03 -4.45839014e+03 -4452. -4.35464893e+03 -4.40576904e+03 -4.40640039e+03 -4.25883643e+03 -4.10396973e+03 -4.03474219e+03 -4.21517383e+03 -4.10116162e+03 -3.94768921e+03 -4.02586597e+03 -3.97446655e+03 -3.92251978e+03 -3.86234619e+03 -3.91849390e+03 -3.85436353e+03 -3.70284399e+03 -3.77754004e+03 -3.75330884e+03 -3.66440674e+03 -3.63062183e+03 -3.57453564e+03 -3.48938989e+03 -3.35381274e+03 -3.26490430e+03 -3.38874072e+03 -3.54995752e+03 -3.32276172e+03 -3.08384717e+03 -3.18041113e+03 -3.33513892e+03 -3.25759814e+03 -3.04737646e+03 -2.92049829e+03 -3.04361450e+03 -3.01122217e+03 -2.86719946e+03 -2.93139282e+03 -2.87787256e+03 -2.69343530e+03 -2.64311499e+03 -2.73945142e+03 -2.76775928e+03 -2.59668921e+03 -2.44066943e+03 -2.48842163e+03 -2.59366211e+03 -2.49675000e+03 -2.33012915e+03 -2.22752490e+03 -2.28070557e+03 -2.34076514e+03 -2.21688135e+03 -2.11021436e+03 -2.08395703e+03 -2.05809204e+03 -2.00351257e+03 -2.01298877e+03 -1.92596802e+03 -1.82091492e+03 -1.81504810e+03 -1.77830591e+03 -1.76798083e+03 -1.68019629e+03 -1.59265942e+03 -1.60229565e+03 -1.51011523e+03 -1.46175842e+03 -1.47450146e+03 -1.41112830e+03 -1.34987830e+03 -1.28843042e+03 -1.28921179e+03 -1.25839771e+03 -1.16024878e+03 -1.07994690e+03 -1.04033679e+03 -1.06645593e+03 -1.01422363e+03 -9.36395203e+02 -8.12256653e+02 -9.22370117e+02 -1.53687366e+03 -1.19643584e+04 160289632. 0. 0. 0. 0. 0. 2.20249702e+09 -7.46532062e+05 -1.23679163e+03 -1.12045837e+03 -2.25595386e+03 -462779840. 0. 0. 1.05506458e+10 1.05506458e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1261755264. 3885088. 1.26736938e+03 1.28865381e+03 1.27105786e+03 8.46152588e+02 9.01689270e+02 9.67615356e+02 1.03626282e+03 1.02945129e+03 1.05897461e+03 1.11220276e+03 1.16267981e+03 1.18652161e+03 1.24009497e+03 1.31327417e+03 1.35042004e+03 1.39398450e+03 1.43137927e+03 1.46083008e+03 1.54184534e+03 1.59131140e+03 1.61752979e+03 1.66992834e+03 1.69897791e+03 1.75879065e+03 1.86729578e+03 1.91300098e+03 1.89855969e+03 1.93161902e+03 2.00593970e+03 2.05298413e+03 2.07954590e+03 2.12548901e+03 2.18567334e+03 2.22110938e+03 2.30053369e+03 2.33961841e+03 2.29841992e+03 2.37464648e+03 2.50412524e+03 2.56907764e+03 2.60010693e+03 2.54596606e+03 2.56018872e+03 2.69035840e+03 2.75130566e+03 2.76142676e+03 2.78238062e+03 2.82908594e+03 2.92749268e+03 3.00925977e+03 3.01495093e+03 2.96274414e+03 3.00002661e+03 3.20263257e+03 3.25261768e+03 3.12092261e+03 3.17026782e+03 3.30172559e+03 3.38050220e+03 3.45707251e+03 3.43077246e+03 3.35832349e+03 3.43778564e+03 3.57168457e+03 3.63588916e+03 3.62922021e+03 3.60628809e+03 3.71641089e+03 3.81492700e+03 3.79663403e+03 3.79546558e+03 3.81935254e+03 3.89150928e+03 3.99249927e+03 4.01622559e+03 4.08741528e+03 4.07704614e+03 4.00575024e+03 4.10647412e+03 4.21605469e+03 4.23159961e+03 4.27544873e+03 4.27122363e+03 4.31925684e+03 4.47129102e+03 4.47684424e+03 4.35885498e+03 4.40832812e+03 4.54475830e+03 4.62295264e+03 4.63083154e+03 4.59527588e+03 4.62360645e+03 4.70350049e+03 4.80044287e+03 4.78198389e+03 4.70545850e+03 4.80358838e+03 4.97148096e+03 5.00081543e+03 4.99556592e+03 4.91258936e+03 4.92220117e+03 5.10037646e+03 5.12354199e+03 5.04276807e+03 5.07097461e+03 5.13422412e+03 5.27411865e+03 5.30577295e+03 5.26854102e+03 5.30762061e+03 5.31699170e+03 5.40798633e+03 5.45722607e+03 5.39685449e+03 5.44432422e+03 5.47778223e+03 5.46598633e+03 5.56013770e+03 5.60676172e+03 5.61833105e+03 5.67837842e+03 5.64476465e+03 5.63290869e+03 5.73777930e+03 5.80927051e+03 5.79297656e+03 5.77002930e+03 5.74184961e+03 5.78386768e+03 5.90205811e+03 5.89480322e+03 5.85745361e+03 5.93292188e+03 6.09765479e+03 6.12698047e+03 5.96139307e+03 6.02925244e+03 6.09601172e+03 6.06672656e+03 6.06482275e+03 6.04631592e+03 6.10852881e+03 6.21121826e+03 6.33779932e+03 6.32545898e+03 6.17846631e+03 6.12606445e+03 6.22200879e+03 6.39298486e+03 6.38170850e+03 6.35141748e+03 6.29465771e+03 6.40106152e+03 6.50563135e+03 6.47529785e+03 6.38906299e+03 6.31933643e+03 6.41356104e+03 6.66712354e+03 6.57243848e+03 6.30601953e+03 6.41070166e+03 6.63881152e+03 6.60096680e+03 6.51993457e+03 6.59113428e+03 6.59589355e+03 6.56698975e+03 6.70684082e+03 6.61345898e+03 6.54879834e+03 6.72027783e+03 6.80406396e+03 6.69770166e+03 6.70090332e+03 6.74823828e+03 6.59822168e+03 6.74215771e+03 6.74151123e+03 6.76927881e+03 6.91577539e+03 6.61904932e+03 6.67854590e+03 6.96365967e+03 6.82908594e+03 6.68543262e+03 6.78424121e+03 6.87397559e+03 6.86322461e+03 6.88246777e+03 6.86661035e+03 6.73023682e+03 6.75159521e+03 6.97756445e+03 7.05192334e+03 6.75560156e+03 6842. 7.03478906e+03 6.92564648e+03 6.89080762e+03 6.82222754e+03 6.77773096e+03 6.96624707e+03 6.94916064e+03 6.90275293e+03 6.91239990e+03 6.83277393e+03 6.89722168e+03 7.05978516e+03 6.90007129e+03 6.88569922e+03 6.92088574e+03 6.89709814e+03 6.93918311e+03 6.94867432e+03 6.86960449e+03 6.86382178e+03 6.88562305e+03 6.92351270e+03 6.92825684e+03 6.82068066e+03 6.94331787e+03 6.98597168e+03 6.91581348e+03 7.01797559e+03 6.87650244e+03 6.68355273e+03 6.85963232e+03 6.90458887e+03 6.84771289e+03 6.75373682e+03 6.71877686e+03 6.83833057e+03 6.94369824e+03 6.86941602e+03 6.76212988e+03 6.85604932e+03 6.89149072e+03 6.71672754e+03 6.65067236e+03 6.83769092e+03 6.79523486e+03 6.64258447e+03 6.86160645e+03 6.76716357e+03 6.61160400e+03 6.72033691e+03 6.63456250e+03 6.58839014e+03 6.66190381e+03 6.61279834e+03 6.54614990e+03 6.62999219e+03 6.65909082e+03 6.69591748e+03 6.49160205e+03 6.41060205e+03 6.59705273e+03 6.51545215e+03 6.52884229e+03 6.49851904e+03 6.41931006e+03 6.43439258e+03 6.43568457e+03 6.52285107e+03 6.38116602e+03 6.21569287e+03 6.38196582e+03 6.54438330e+03 6.27219092e+03 6.13765723e+03 6.20670312e+03 6.18234082e+03 6.28951123e+03 6.30890479e+03 6.15471143e+03 6.09617432e+03 6.17815332e+03 6.15075293e+03 6.16879395e+03 6.09595068e+03 6.11026904e+03 6.12221484e+03 5.86299707e+03 5.91552441e+03 5.98991309e+03 5.88469434e+03 5.97508740e+03 5.90354492e+03 5.79508887e+03 5.88367090e+03 5.78360693e+03 5.74597559e+03 5.91554688e+03 5.80874854e+03 5.65788574e+03 5.60840967e+03 5.51840723e+03 5.62419678e+03 5.69357227e+03 5.55853662e+03 5.48479199e+03 5.56174365e+03 5.55513232e+03 5.49942383e+03 5.37692480e+03 5.32233008e+03 5.31883008e+03 5.37593750e+03 5.37378271e+03 5.18160303e+03 5.15709570e+03 5.22225781e+03 5.22132666e+03 5.17889355e+03 5.14929395e+03 5.05771680e+03 4.98630029e+03 5.12400586e+03 5.12417383e+03 4.89990332e+03 4.80665332e+03 4.79880176e+03 4.84007959e+03 4.81781787e+03 4.72463232e+03 4.73945654e+03 4.74163379e+03 4.68024854e+03 4.68215430e+03 4.60053223e+03 4.52520264e+03 4.54948096e+03 4.55543652e+03 4.42637061e+03 4.33201123e+03 4.36451270e+03 4.32410059e+03 4.28339355e+03 4.29812109e+03 4.22952344e+03 4.13289111e+03 4.13573242e+03 4.19722119e+03 4.09473657e+03 3.97241895e+03 3.98076416e+03 3.96839062e+03 3.91267554e+03 3.85612695e+03 3.78162305e+03 3.75744922e+03 3.74416162e+03 3.75575708e+03 3.73938086e+03 3.62516602e+03 3.58756860e+03 3.53892847e+03 3.47070874e+03 3.44587671e+03 3.38117334e+03 3.37753320e+03 3.35183472e+03 3.26833813e+03 3.20132227e+03 3.16876855e+03 3.19505713e+03 3.17940601e+03 3.12958325e+03 3.04207764e+03 2.96775146e+03 2.92823315e+03 2.85854077e+03 2.84117944e+03 2.83868726e+03 2.78307910e+03 2.72405811e+03 2.63770703e+03 2.59049097e+03 2.61713062e+03 2.60122925e+03 2.56247437e+03 2.44976099e+03 2.35782520e+03 2.35740625e+03 2.32471729e+03 2.26733643e+03 2.23278296e+03 2.20627612e+03 2.13005688e+03 2.06136206e+03 2.01714124e+03 1.97028271e+03 1.98513721e+03 1.95787036e+03 1.85376685e+03 1.82325061e+03 1.76091406e+03 1.67900769e+03 1.68825793e+03 1.65318506e+03 1.55903650e+03 1.51680298e+03 1.47062634e+03 1.40577234e+03 1.39736414e+03 1.38491895e+03 1.29680396e+03 1.23051172e+03 1.19808215e+03 1.14942383e+03 1.10722278e+03 1.05460071e+03 1.00141760e+03 9.57759277e+02 9.18366638e+02 8.75965454e+02 8.21377747e+02 7.63326599e+02 7.22606567e+02 6.81948181e+02 6.23017639e+02 5.67413818e+02 5.23276611e+02 4.88473083e+02 4.45791626e+02 3.93066711e+02 3.32239227e+02 2.78557678e+02 2.38159470e+02 1.93592682e+02 1.45929291e+02 9.41233597e+01 4.58217850e+01 1.36260200e+00 -4.73413124e+01 -9.59686508e+01 -1.50008606e+02 -1.98716904e+02 -2.43041962e+02 -2.96686829e+02 -3.39316467e+02 -3.74640625e+02 -4.36428467e+02 -4.99178558e+02 -5.29043701e+02 -5.68786621e+02 -6.23789368e+02 -6.73191101e+02 -7.29685669e+02 -7.83812378e+02 -8.24894653e+02 -8.56935852e+02 -9.06367432e+02 -9.64938721e+02 -1.01286676e+03 -1.07525317e+03 -1.12657996e+03 -1.15228821e+03 -1.18966797e+03 -1.26439160e+03 -1.30752209e+03 -1.33973022e+03 -1.40954663e+03 -1.46028687e+03 -1.48023474e+03 -1.50075500e+03 -1.55298376e+03 -1.62411206e+03 -1.70706897e+03 -1.75238684e+03 -1.75092065e+03 -1.78615515e+03 -1.84709265e+03 -1.90854346e+03 -1.98420630e+03 -2.01487732e+03 -2.01214624e+03 -2.10514331e+03 -2.16848242e+03 -2.16724023e+03 -2.27053857e+03 -2.31123340e+03 -2.29624463e+03 -2.36084253e+03 -2.38033374e+03 -2.40968823e+03 -2.54276489e+03 -2.59112109e+03 -2.58957007e+03 -2.66489990e+03 -2.68062866e+03 -2.64913599e+03 -2.72265308e+03 -2.83060645e+03 -2.87175659e+03 -2.91900879e+03 -2.93232422e+03 -2.95808203e+03 -3.03900977e+03 -3.09998145e+03 -3.23583594e+03 -3.21429395e+03 -3.11220605e+03 -3.19118018e+03 -3.27892871e+03 -3.35136255e+03 -3.44871582e+03 -3.42007593e+03 -3.37679419e+03 -3.49286304e+03 -3.59124707e+03 -3.60199585e+03 -3.64889404e+03 -3.67298071e+03 -3.65469458e+03 -3.76098047e+03 -3.81761572e+03 -3.77318359e+03 -3.94300928e+03 -4.01466406e+03 -3.95694531e+03 -3.97229761e+03 -3.90280615e+03 -3.96203979e+03 -4.13826270e+03 -4.29512451e+03 -4.28498975e+03 -4.10474658e+03 -4.15985107e+03 -4.35636035e+03 -4.36491748e+03 -4.36700586e+03 -4.40952246e+03 -4.41405029e+03 -4.48012256e+03 -4.54857666e+03 -4.58922607e+03 -4.60200391e+03 -4.64066309e+03 -4.73857715e+03 -4.70082812e+03 -4.68186523e+03 -4.72109668e+03 -4.76630029e+03 -4.86835840e+03 -5.01898389e+03 -4.95053076e+03 -4.82241260e+03 -4.93463428e+03 -5.03605811e+03 -5.19136523e+03 -5.18525439e+03 -5.00846289e+03 -5.09638135e+03 -5178. -5.26281006e+03 -5.37666357e+03 -5.30486865e+03 -5.28710400e+03 -5.30423926e+03 -5.27971094e+03 -5.32296387e+03 -5.47594434e+03 -5.59311035e+03 -5.49004102e+03 -5.46045410e+03 -5.43341406e+03 -5.48840430e+03 -5.70001514e+03 -5.74709229e+03 -5.70295801e+03 -5.67683936e+03 -5.58362939e+03 -5.66620557e+03 -5.75986572e+03 -5.89984131e+03 -5.96592236e+03 -5.74794385e+03 -5.73326025e+03 -5.87683105e+03 -5.94772607e+03 -5.96186328e+03 -6.03655127e+03 -6.09077783e+03 -5.95422803e+03 -6.00390479e+03 -6.04623193e+03 -6.06636475e+03 -6.12872559e+03 -6.17401318e+03 -6.19072168e+03 -6.14836279e+03 -6.11976611e+03 -6.21302295e+03 -6.38886133e+03 -6.33825732e+03 -6.21302002e+03 -6.24295459e+03 -6.28520654e+03 -6.27753613e+03 -6.52333008e+03 -6.51369922e+03 -6.26537793e+03 -6.44279053e+03 -6.37278711e+03 -6.49817188e+03 -6.69001270e+03 -6.51730615e+03 -6.45681836e+03 -6.50610400e+03 -6.61024121e+03 -6.65084424e+03 -6.78808105e+03 -6.60269189e+03 -8.37922852e+03 -8.68771680e+03 -1.66537090e+04 -2.98714336e+04 3.28185375e+06 128801400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -15632281. 3.74871525e+06 -22097878. 4087152. -4.40459930e+09 -1.10397178e+04 -1.23309600e+04 -7.89150879e+03 -7.05616992e+03 -6.92922559e+03 -7.21109717e+03 -7.06482129e+03 -6.90439648e+03 -6.71858936e+03 -6.76278906e+03 -6.95556982e+03 -7.07097168e+03 -6.97599756e+03 -6.79993262e+03 -6.78287793e+03 -6.80791113e+03 -6.95418408e+03 -6.90777197e+03 -6.63817236e+03 -6.69761670e+03 -6.88240283e+03 -6.85305713e+03 -6.67685303e+03 -6.53436670e+03 -6.75452832e+03 -7.05055615e+03 -7.01130518e+03 -6.63745312e+03 -6.32730518e+03 -6.52951123e+03 -6.83555127e+03 -6.96206982e+03 -6.80550830e+03 -6.50929736e+03 -6.54573242e+03 -6.66922217e+03 -6.81495312e+03 -6.68856299e+03 -6.34394336e+03 -6.44857227e+03 -6.78957422e+03 -6.63482227e+03 -6.42869971e+03 -6.47603662e+03 -6.47388330e+03 -6.59311670e+03 -6.56373486e+03 -6.29869238e+03 -6.18556592e+03 -6.47557275e+03 -6.60210840e+03 -6.51075049e+03 -6.26351904e+03 -6.09561133e+03 -6.37628906e+03 -6.56413867e+03 -6.36969238e+03 -6.16322705e+03 -5.91065674e+03 -6.01542383e+03 -6.31221191e+03 -6.38555273e+03 -6.27033105e+03 -6.15809131e+03 -6.11586475e+03 -5.98149170e+03 -6.04497852e+03 -6.07904102e+03 -5.85922754e+03 -5.90295898e+03 -6.11530225e+03 -5.99774756e+03 -5.71843604e+03 -5.66024805e+03 -5.92327002e+03 -6.07823535e+03 -5.96592139e+03 -5.74293555e+03 -5.55407178e+03 -5.56251758e+03 -5.68754395e+03 -5.91525586e+03 -5.78790381e+03 -5.44882812e+03 -5.49869824e+03 -5.54897656e+03 -5.56424658e+03 -5.64403516e+03 -5.44017969e+03 -5.36979492e+03 -5.48632324e+03 -5.45399219e+03 -5.33110205e+03 -5.23558984e+03 -5.27296338e+03 -5.35762598e+03 -5.29439209e+03 -5.12796631e+03 -5.00921143e+03 -5.13927490e+03 -5.26130615e+03 -5.17817725e+03 -5.04134326e+03 -4.87832959e+03 -4.92558008e+03 -5.03675146e+03 -4.99877930e+03 -4.87365869e+03 -4.65736035e+03 -4.65296387e+03 -4.83882080e+03 -4.92753223e+03 -4.79310107e+03 -4.53141699e+03 -4.53480518e+03 -4.65445557e+03 -4.59122656e+03 -4.45525342e+03 -4.36227686e+03 -4.49618604e+03 -4.52418555e+03 -4.36310400e+03 -4.28368408e+03 -4.17918164e+03 -4.26619238e+03 -4.39824609e+03 -4.26641748e+03 -4.11765527e+03 -4.00858350e+03 -4.00286963e+03 -4.03946973e+03 -4.07825488e+03 -3.99459668e+03 -3.79375879e+03 -3.76506543e+03 -3.88828223e+03 -3.90161670e+03 -3.76729150e+03 -3.63227051e+03 -3.63747388e+03 -3.68619824e+03 -3.64644775e+03 -3.54001025e+03 -3.37683179e+03 -3.38295410e+03 -3.48183813e+03 -3.43251270e+03 -3.33438477e+03 -3.21351294e+03 -3.19070435e+03 -3.23167505e+03 -3.26524341e+03 -3.18224683e+03 -3.00342529e+03 -2.98478076e+03 -2.99735376e+03 -2.96049683e+03 -2.92588159e+03 -2.82817896e+03 -2.80715674e+03 -2.77869263e+03 -2.70863672e+03 -2.65302246e+03 -2.59819580e+03 -2.62427832e+03 -2.61651343e+03 -2.53334644e+03 -2.41465869e+03 -2.33104980e+03 -2.37121875e+03 -2.41280737e+03 -2.33747510e+03 -2.23169092e+03 -2.12323462e+03 -2.05103516e+03 -2.08372510e+03 -2.13428076e+03 -2.02670642e+03 -1.87834009e+03 -1.86296912e+03 -1.88231116e+03 -1.85101514e+03 -1.79208191e+03 -1.70227380e+03 -1.65985645e+03 -1.63649548e+03 -1.56695105e+03 -1.50532642e+03 -1.47026953e+03 -1.44667273e+03 -1.40037573e+03 -1.34112646e+03 -1.28687598e+03 -1.23127808e+03 -1.20406995e+03 -1.18061877e+03 -1.12899988e+03 -1.04008228e+03 -9.72533752e+02 -9.67699219e+02 -9.38950562e+02 -8.77492065e+02 -8.12604919e+02 -7.40204529e+02 -6.98375305e+02 -6.84794250e+02 -6.52753601e+02 -5.89541748e+02 -5.15112183e+02 -4.65415680e+02 -4.33505890e+02 -3.91044037e+02 -3.39112823e+02 -2.87560242e+02 -2.41674927e+02 -1.93153961e+02 -1.44733353e+02 -9.62896957e+01 -4.90272255e+01 -1.28637516e+00 5.06186256e+01 1.03164749e+02 1.52533157e+02 1.90496582e+02 2.36876480e+02 2.86630310e+02 3.33975586e+02 3.89759216e+02 4.36074066e+02 4.94152344e+02 5.42800354e+02 5.63425110e+02 6.03158020e+02 6.65895691e+02 7.43843872e+02 8.16022278e+02 8.45609558e+02 8.43768433e+02 8.66329773e+02 9.39031494e+02 1.03675024e+03 1.11511914e+03 1.14002856e+03 1.12370447e+03 1.16504932e+03 1.28863513e+03 1.33973792e+03 1.31858643e+03 1.35973767e+03 1.43430188e+03 1.48560938e+03 1.57830518e+03 1.58785669e+03 1.57898547e+03 1.67216199e+03 1.68058154e+03 1.76382874e+03 1.86720862e+03 1.81676416e+03 1.90522339e+03 2.01069922e+03 2.00290137e+03 2.04882275e+03 2.09008594e+03 2.14394849e+03 2.20169043e+03 2.23659326e+03 2.22355884e+03 2.26191260e+03 2.40806958e+03 2.53058643e+03 2.52603516e+03 2.45144897e+03 2.43848706e+03 2.52770264e+03 2.69495410e+03 2.82198706e+03 2.81387939e+03 2.68929126e+03 2.73576147e+03 2.90240039e+03 2.92273315e+03 2.92617090e+03 2.96965186e+03 3.02437329e+03 3.06943945e+03 3.21566699e+03 3.18280322e+03 3.12031494e+03 3.23874072e+03 3.20813281e+03 3.35191260e+03 3.45511792e+03 3.42055615e+03 3.57020605e+03 3.50171851e+03 3.43764355e+03 3.57379321e+03 3.53399609e+03 3.64479858e+03 3.93780005e+03 3.77515576e+03 3.60360962e+03 3.72745068e+03 3.93444482e+03 4.12690186e+03 4.08324658e+03 3.89348071e+03 3.80548657e+03 3.94756299e+03 4.21213232e+03 4.38038281e+03 4.31699902e+03 4.11850195e+03 4.12249414e+03 4.31728662e+03 4.42475830e+03 4.35416211e+03 4.33409912e+03 4.43544385e+03 4.49391895e+03 4.66072656e+03 4.68403418e+03 4.49967773e+03 4.53784033e+03 4.61746582e+03 4.67533447e+03 4.76530078e+03 4.79059375e+03 4.92909277e+03 4.86802393e+03 4.73931543e+03 4.87500586e+03 4.79887256e+03 4.96776709e+03 5.32337305e+03 5.06804980e+03 4.79759424e+03 4.92635498e+03 5.21149121e+03 5.41125195e+03 5.43018359e+03 5.17607666e+03 4.99667090e+03 5.12925049e+03 5.43631982e+03 5.68690137e+03 5.54448926e+03 5.28265723e+03 5.25708301e+03 5.43758643e+03 5.56036523e+03 5.74340674e+03 5.73738037e+03 5.44685986e+03 5.45758496e+03 5.77139795e+03 5.83666650e+03 5.65390674e+03 5.66785742e+03 5.70438965e+03 5.70481543e+03 5.97735303e+03 6.03567334e+03 5.76144482e+03 5.75026367e+03 5.83965283e+03 5.92364502e+03 5.98412988e+03 5.94095898e+03 6.11608643e+03 6.21558691e+03 6.04957568e+03 5.94098242e+03 5.86037256e+03 6.09885986e+03 6.46913574e+03 6.37174268e+03 6.06172607e+03 5.90763477e+03 6.19349658e+03 6.55569287e+03 6.33800879e+03 6.01426367e+03 6.11803955e+03 6.32998633e+03 6.52041504e+03 6.71584668e+03 6.59143066e+03 6.24252637e+03 6.15508643e+03 6.36643750e+03 6.59737109e+03 6.63911230e+03 6.52996826e+03 6.46590332e+03 6.50448438e+03 6.67479395e+03 6.62910107e+03 6.44455127e+03 6.42616309e+03 6.42741553e+03 6.74790283e+03 6.83967529e+03 6.62499707e+03 6.65785498e+03 6.71879541e+03 6.86641553e+03 6.70639014e+03 6.37253271e+03 6.70654004e+03 7.07640186e+03 6.90650928e+03 6.56275195e+03 6.63647656e+03 6.96197949e+03 6.98549023e+03 6.83995703e+03 6.83105322e+03 6.65475586e+03 6.62617871e+03 6.98882715e+03 7.03256152e+03 6.69091553e+03 6.56542725e+03 6.58819629e+03 6.95246484e+03 7.23834668e+03 6.93675684e+03 6.70190430e+03 6.88128125e+03 6.89476465e+03 7.12956201e+03 7.05861719e+03 6.65677539e+03 6.76513135e+03 6.96971533e+03 6.89569629e+03 6.93527490e+03 6.86401172e+03 7.01455176e+03 7.03539307e+03 6.80317432e+03 6.83487988e+03 6.77389893e+03 6.92526904e+03 7.20306787e+03 7.07908936e+03 6.75396826e+03 6.75875488e+03 7.02367725e+03 7.27910986e+03 7.61957227e+03 7.72003662e+03 6.95976221e+03 8.34192773e+03 1.51797861e+04 1.17348469e+05 53426952. 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. 0. 0. 0. 0. 0. 0. 0. -48947436. 6.41627950e+06 1.56498862e+06 4.90040650e+06 1.92910371e+04 1.05036660e+04 8.76500879e+03 6.97105273e+03 6.76098047e+03 6.58782080e+03 6.23900928e+03 6.43736279e+03 6.49090967e+03 6.27231201e+03 6.25910547e+03 6.22589600e+03 6.18984082e+03 6.19411279e+03 6.13442871e+03 6.06351953e+03 6.04906885e+03 6.02154150e+03 6.11992285e+03 6.12274707e+03 5.86172412e+03 5.84015527e+03 6.10132129e+03 6.10710791e+03 5.93102295e+03 5.90854932e+03 5.86212549e+03 5.85687500e+03 5.80327148e+03 5.77169092e+03 5.75046875e+03 5.72264355e+03 5.64346240e+03 5.60518457e+03 5.72293799e+03 5.72036377e+03 5.60287158e+03 5.57057617e+03 5.55686621e+03 5.52149756e+03 5.47465869e+03 5.43720312e+03 5.42220312e+03 5.23557373e+03 5.19886963e+03 5.29239502e+03 5.26450586e+03 5.42768945e+03 5.42044043e+03 5.19853857e+03 5.01278955e+03 4.96284082e+03 5.26774512e+03 5.27605371e+03 5.03648486e+03 4.91355762e+03 4.88694971e+03 4.90697119e+03 4.85507568e+03 4.99454297e+03 4.96978906e+03 4.64416650e+03 4.55514258e+03 4.77199316e+03 4.93444678e+03 4.75737891e+03 4.61424121e+03 4.60952344e+03 4.55510010e+03 4.46651025e+03 4.45598779e+03 4.41029199e+03 4.35002686e+03 4.33586816e+03 4.29176758e+03 4.30925879e+03 4.25381738e+03 4.29984082e+03 4.26218750e+03 4.10214258e+03 4.10798242e+03 4.08461353e+03 4.05302539e+03 4.03385278e+03 3.96174268e+03 3.90992725e+03 3.78440698e+03 3.66965576e+03 3.80366357e+03 3.81542847e+03 3.57788989e+03 3.56774805e+03 3.73210425e+03 3.78345483e+03 3.62708032e+03 3.49061743e+03 3.43206641e+03 3.38893604e+03 3.32169360e+03 3.26953809e+03 3.29429517e+03 3.23808032e+03 3.26969800e+03 3.21184473e+03 3.08428101e+03 3.09154297e+03 2.97080127e+03 2.93668579e+03 3.04342847e+03 2.96733911e+03 2.85804663e+03 2.75430103e+03 2.66408936e+03 2.77010815e+03 2.78210254e+03 2.64261914e+03 2.51977124e+03 2.48509424e+03 2.50160547e+03 2.44908447e+03 2.47907153e+03 2.44566089e+03 2.32188550e+03 2.23312744e+03 2.18708472e+03 2.23031738e+03 2.18661255e+03 2.09045435e+03 2.01921082e+03 1.97679993e+03 1.95929077e+03 1.86118420e+03 1.82488831e+03 1.88367993e+03 1.81720386e+03 1.72086707e+03 1.62954089e+03 1.57405725e+03 1.62343848e+03 1.58079004e+03 1.48603796e+03 1.40338599e+03 1.34900830e+03 1.34110913e+03 1.29426538e+03 1.24532471e+03 1.16703625e+03 1.14462292e+03 1.15674219e+03 1.08033240e+03 1.02174762e+03 9.77336914e+02 9.18772766e+02 8.59680237e+02 8.13531799e+02 7.77105164e+02 7.27632385e+02 6.74718323e+02 6.06676270e+02 5.67968933e+02 5.53226318e+02 4.83257996e+02 4.19988892e+02 3.83504700e+02 3.34592163e+02 2.96180878e+02 2.42119431e+02 1.85566513e+02 1.46609070e+02 9.85096359e+01 4.78993874e+01 -1.02956986e+00 -4.94654045e+01 -9.63484344e+01 -1.42902405e+02 -1.91151062e+02 -2.33692291e+02 -2.89156311e+02 -3.57980804e+02 -4.00452087e+02 -4.31947754e+02 -4.64486755e+02 -5.16723694e+02 -5.99009644e+02 -6.48297852e+02 -6.78356873e+02 -7.07408020e+02 -7.49878113e+02 -8.20750916e+02 -8.67315063e+02 -9.37412476e+02 -9.67285583e+02 -9.81774353e+02 -1.06098315e+03 -1.11081799e+03 -1.18154907e+03 -1.22353662e+03 -1.23696924e+03 -1.28448096e+03 -1.33132690e+03 -1.39504431e+03 -1.40545752e+03 -1.46885510e+03 -1.59932910e+03 -1.62022913e+03 -1.62892810e+03 -1.63313477e+03 -1.66923621e+03 -1.81275146e+03 -1.86978369e+03 -1.86400452e+03 -1.85729175e+03 -1.90103711e+03 -2.00999048e+03 -2.05702368e+03 -2.15273999e+03 -2.17437549e+03 -2.16771631e+03 -2.19103662e+03 -2.22350830e+03 -2.38898389e+03 -2.42130933e+03 -2.39091724e+03 -2.42706030e+03 -2.47105688e+03 -2.58875317e+03 -2.64311304e+03 -2.57951782e+03 -2.61332031e+03 -2.79789233e+03 -2.84205151e+03 -2.74544629e+03 -2.77295508e+03 -2.97635718e+03 -3.03177466e+03 -2.97566968e+03 -2.95064795e+03 -2.99060449e+03 -3.21525708e+03 -3.23096997e+03 -3.17329736e+03 -3.24217383e+03 -3.26908105e+03 -3.30644971e+03 -3.34922266e+03 -3.39158203e+03 -3.35235181e+03 -3.47848975e+03 -3.71504517e+03 -3.64367578e+03 -3.63413062e+03 -3.70591016e+03 -3.71678394e+03 -3.75863965e+03 -3.79607568e+03 -3.82615527e+03 -3.77446777e+03 -3.75247925e+03 -3.88456567e+03 -4.03136816e+03 -4.20159814e+03 -4.08644629e+03 -3.97701807e+03 -4.12030664e+03 -4.20782520e+03 -4.37164600e+03 -4.35161328e+03 -4.25998828e+03 -4.26950781e+03 -4.28889844e+03 -4.41563623e+03 -4.44544971e+03 -4.58966357e+03 -4.61111182e+03 -4.52611377e+03 -4.51268115e+03 -4.42557910e+03 -4.65526416e+03 -4.96498291e+03 -4.89638086e+03 -4.78694434e+03 -4.68733008e+03 -4.66470557e+03 -4.93508398e+03 -5.12104004e+03 -4.99700879e+03 -4.84174512e+03 -4.87537500e+03 -5.05892676e+03 -5.06270508e+03 -5.23206055e+03 -5.24606934e+03 -5.12469189e+03 -5.17448438e+03 -5.19690137e+03 -5.34636523e+03 -5.39814111e+03 -5.18977148e+03 -5.21718066e+03 -5.54066846e+03 -5.46823486e+03 -5.21818896e+03 -5.41944189e+03 -5.75568652e+03 -5.69950244e+03 -5.55289355e+03 -5.46081348e+03 -5.49437793e+03 -5.84084814e+03 -5.85658447e+03 -5.68824170e+03 -5.60736670e+03 -5.58912158e+03 -5.77781299e+03 -5.80703418e+03 -5.83252686e+03 -5.72868408e+03 -5.87624658e+03 -6.15256055e+03 -6.02540039e+03 -6.05894434e+03 -6.04298584e+03 -5.95674854e+03 -6.03373096e+03 -6.07976318e+03 -6.10358984e+03 -6.10843994e+03 -6.05452930e+03 -5.95777832e+03 -6.11869434e+03 -6.49340332e+03 -6.25338477e+03 -6.00511719e+03 -6.21820557e+03 -6.33292676e+03 -6.54736084e+03 -6.46955273e+03 -6.26837842e+03 -6.44203076e+03 -6.46257422e+03 -6.21323535e+03 -6.20279932e+03 -6.61522314e+03 -6.61293555e+03 -6.43420264e+03 -6.36834326e+03 -6.18062061e+03 -6.46986182e+03 -6.90609619e+03 -6.69800928e+03 -6.55971094e+03 -6.38764062e+03 -6.37432910e+03 -6.69336963e+03 -6.93827637e+03 -6.77401709e+03 -6.45724414e+03 -6.41829883e+03 -6.62265820e+03 -6.74243066e+03 -6.93764209e+03 -6.82494434e+03 -6.61354248e+03 -6.76998486e+03 -6.74024658e+03 -6.89913721e+03 -6.85860645e+03 -6.70338281e+03 -6.80177686e+03 -6.78029736e+03 -6.79071924e+03 -6.57142920e+03 -6.68302002e+03 -7.14675635e+03 -7.00060498e+03 -6.75133691e+03 -6.63013770e+03 -6.71468750e+03 -7.09166748e+03 -7.08960938e+03 -6.89652051e+03 -6.71786914e+03 -6.69052490e+03 -6.87953564e+03 -6.86811816e+03 -6.91367188e+03 -6.73323730e+03 -6.87555664e+03 -7.20220752e+03 -6.96756885e+03 -7.02960205e+03 -7.04531152e+03 -6.87117480e+03 -6.87872168e+03 -6.88227832e+03 -6.88786621e+03 -6.87666162e+03 -6.90982178e+03 -6.87570996e+03 -7.02711768e+03 -7.06820898e+03 -6.73933594e+03 -6.61806396e+03 -6.79276367e+03 -6.98084863e+03 -7.16155469e+03 -6.96571924e+03 -6.66775098e+03 -6.94169629e+03 -7.10933154e+03 -6.94163281e+03 -6.76801904e+03 -6.75076514e+03 -6.84483984e+03 -6.89609961e+03 -6.83739258e+03 -6.63901465e+03 -6.83331201e+03 -7.16865430e+03 -6.98322266e+03 -6.85181299e+03 -6.66542676e+03 -6.64034229e+03 -6.99962744e+03 -6.98953516e+03 -6.79190186e+03 -6.61296973e+03 -6.45308496e+03 -6.61745996e+03 -6.85097852e+03 -7.02966162e+03 -6.74586523e+03 -6.42850000e+03 -6.61154443e+03 -6.70131885e+03 -6.89151025e+03 -6.74921826e+03 -6.49245508e+03 -6.67516748e+03 -6.64756250e+03 -6.48175146e+03 -6.30170850e+03 -6.53117090e+03 -6.86126270e+03 -6.66071729e+03 -6.54239697e+03 -6.35824170e+03 -6.31142480e+03 -6.66060010e+03 -6.64072510e+03 -6.43570312e+03 -6.25048633e+03 -6.17297021e+03 -6.36585059e+03 -6.34499365e+03 -6.50878223e+03 -6.52475879e+03 -6.24512695e+03 -6.12539893e+03 -6.17319141e+03 -6.43925684e+03 -6.27476416e+03 -6.09367383e+03 -6.17855078e+03 -6.17331445e+03 -6.03925781e+03 -5.94147266e+03 -6.17975342e+03 -6.14099756e+03 -5.93714648e+03 -6.15086963e+03 -6.17086572e+03 -6.00877637e+03 -5.95219287e+03 -5.91552588e+03 -5.91209375e+03 -5.74694775e+03 -5.63923730e+03 -5.91086865e+03 -5.95369678e+03 -5.63116406e+03 -5.41765430e+03 -5.66610498e+03 -5.99293604e+03 -5.85354395e+03 -5.52788770e+03 -5.39392285e+03 -5.65141748e+03 -5.71069678e+03 -5.52544678e+03 -5.53272852e+03 -5.34205859e+03 -5.16098584e+03 -5.34580273e+03 -5.54139990e+03 -5.49924707e+03 -5.24477930e+03 -5.06671729e+03 -5.30232178e+03 -5.42854004e+03 -5.23449072e+03 -5.00499121e+03 -4.91704150e+03 -5.03297412e+03 -5.04543701e+03 -5.13839990e+03 -5.09121826e+03 -4.85692480e+03 -4.88901465e+03 -4.89413184e+03 -4.94266309e+03 -4.75330762e+03 -4.62261865e+03 -4.79706348e+03 -4.76150244e+03 -4.66436523e+03 -4.51756250e+03 -4.52851660e+03 -4.75720459e+03 -4.52954688e+03 -4.31319482e+03 -4.40060498e+03 -4.45524756e+03 -4.41913135e+03 -4.33126172e+03 -4.39588379e+03 -4.39147314e+03 -4.22978076e+03 -4.06941138e+03 -4.01453638e+03 -4.20122119e+03 -4.08838452e+03 -3.92544360e+03 -4.03450562e+03 -3.99555469e+03 -3.87471484e+03 -3.80194653e+03 -3.89544775e+03 -3.83489258e+03 -3.68477368e+03 -3.72927734e+03 -3.68925928e+03 -3.67033765e+03 -3.63744824e+03 -3.55885376e+03 -3.47755054e+03 -3.34259644e+03 -3.29232520e+03 -3.42403052e+03 -3.49883447e+03 -3.27280273e+03 -3.07656689e+03 -3.16618677e+03 -3.30066772e+03 -3.23911011e+03 -3.04424292e+03 -2.88938354e+03 -2.99144727e+03 -3.03812061e+03 -2.90905005e+03 -2.90651953e+03 -2.84575195e+03 -2.70506201e+03 -2.67990918e+03 -2.73866016e+03 -2.71100806e+03 -2.55451025e+03 -2.44164502e+03 -2.50511841e+03 -2.57003784e+03 -2.45799023e+03 -2.31008130e+03 -2.22792969e+03 -2.29531543e+03 -2.32064819e+03 -2.19531079e+03 -2.09843945e+03 -2.06192554e+03 -2.04913623e+03 -1.99676111e+03 -2.00159277e+03 -1.91256995e+03 -1.80625818e+03 -1.82373718e+03 -1.78491211e+03 -1.74854529e+03 -1.66212122e+03 -1.58558569e+03 -1.60078406e+03 -1.51508972e+03 -1.44962769e+03 -1.44898730e+03 -1.39900391e+03 -1.34835339e+03 -1.29546558e+03 -1.28324231e+03 -1.24265332e+03 -1.15512488e+03 -1.07618091e+03 -1.02916016e+03 -1.04747473e+03 -1.00591284e+03 -9.19670593e+02 -7.73296753e+02 -7.96229309e+02 -1.24485718e+03 -6.45872852e+03 -1.48200391e+05 0. 0. 0. 0. 0. 2.20249702e+09 -7.46532062e+05 1.32763438e+05 -6.59330994e+02 -4.88326996e+02 -9.51549835e+01 -2.55462148e+04 3.49749632e+09 1.05506458e+10 1.05506458e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1261755264. 3885088. -4.42376031e+05 3.01446338e+03 2.53770020e+03 1.08055212e+03 7.63668518e+02 1.01706030e+03 1.01639758e+03 1.03738391e+03 1.07460559e+03 1.11946130e+03 1.16767334e+03 1.18654883e+03 1.23481006e+03 1.30708313e+03 1.34664575e+03 1.39324902e+03 1.43372058e+03 1.46611462e+03 1.54228003e+03 1.58560950e+03 1.60544409e+03 1.65941406e+03 1.68607959e+03 1.73587708e+03 1.85075195e+03 1.91204553e+03 1.89471545e+03 1.92271118e+03 1.98825183e+03 2.04424487e+03 2.06012646e+03 2.09190723e+03 2.17749194e+03 2.22413721e+03 2.30681299e+03 2.34197705e+03 2.29850049e+03 2.36716772e+03 2.49545410e+03 2.55895679e+03 2.58193140e+03 2.53599854e+03 2.55393384e+03 2.68199316e+03 2.74777490e+03 2.75346973e+03 2773. 2.81742041e+03 2.91978467e+03 2.99901001e+03 3.00271265e+03 2.95743921e+03 3.00181372e+03 3.19564331e+03 3.23753125e+03 3.11024707e+03 3.14937305e+03 3.28943115e+03 3.37054321e+03 3.44961450e+03 3.41954712e+03 3.35130566e+03 3.42711328e+03 3.55551709e+03 3.61958496e+03 3.60949048e+03 3.58958838e+03 3.70405225e+03 3.80298999e+03 3.78464844e+03 3.78782959e+03 3.80543140e+03 3.87509814e+03 3.98315161e+03 4.00387378e+03 4.06194897e+03 4.07168652e+03 4.00908008e+03 4.10023438e+03 4.19228516e+03 4.21623340e+03 4.25558545e+03 4.25617188e+03 4.30587012e+03 4.44672559e+03 4.46549268e+03 4.34888037e+03 4.40778809e+03 4.52219531e+03 4.60498682e+03 4.60922314e+03 4.57281738e+03 4.60667139e+03 4.69784229e+03 4.78764062e+03 4.78570020e+03 4.69689453e+03 4.79351465e+03 4.95440674e+03 4.98917871e+03 4.98366113e+03 4.89266309e+03 4.90830615e+03 5.08911816e+03 5.10363379e+03 5.01571143e+03 5.05483545e+03 5.12802295e+03 5.25731982e+03 5.28211084e+03 5.25328271e+03 5.28768701e+03 5.31337354e+03 5.41274707e+03 5.43928320e+03 5.36928809e+03 5.41785742e+03 5.46370605e+03 5.45370557e+03 5.53684766e+03 5.58297510e+03 5.59957227e+03 5.65751953e+03 5.62138965e+03 5.60307617e+03 5.71956592e+03 5.79667871e+03 5.75749316e+03 5.76099072e+03 5.73411230e+03 5.75434033e+03 5.88666260e+03 5.86269531e+03 5.84940576e+03 5.91711816e+03 6.08426025e+03 6.10361719e+03 5.94481689e+03 6.01035059e+03 6.08612061e+03 6.04892969e+03 6.00849561e+03 6.04382715e+03 6.11480762e+03 6.19380811e+03 6.31506885e+03 6.26961816e+03 6.17914258e+03 6.11937451e+03 6.21645801e+03 6.35554736e+03 6.37457422e+03 6.33885742e+03 6.26891748e+03 6.35599512e+03 6.49091162e+03 6.45150586e+03 6.35897656e+03 6.30285107e+03 6.42819434e+03 6.58596436e+03 6.52812939e+03 6.30467578e+03 6.39450195e+03 6.61012354e+03 6.60781689e+03 6.50958984e+03 6.52397559e+03 6.58199658e+03 6.58587695e+03 6.65525098e+03 6.61303174e+03 6.48147070e+03 6.65786719e+03 6.82149805e+03 6.70622949e+03 6.68274072e+03 6.69706689e+03 6.60532959e+03 6.72584424e+03 6.72819287e+03 6.76358789e+03 6.88640576e+03 6.63010059e+03 6.64573145e+03 6.94008594e+03 6.80113574e+03 6.63983398e+03 6.75830908e+03 6.89020801e+03 6.86836719e+03 6.85429150e+03 6.83507471e+03 6.73028174e+03 6.69467773e+03 6.94859473e+03 7.02811035e+03 6.73162158e+03 6.77177881e+03 6.98850684e+03 6.89646826e+03 6.91056641e+03 6.79253223e+03 6.76224512e+03 6.92175146e+03 6.89609277e+03 6.89512988e+03 6.91901074e+03 6.81065771e+03 6.86055908e+03 6.98187695e+03 6.90033545e+03 6.85464062e+03 6.87004053e+03 6.91613428e+03 6.89371436e+03 6.87519434e+03 6.85512744e+03 6.84199365e+03 6.82763086e+03 6.91311426e+03 6.89956299e+03 6.82362939e+03 6.90475391e+03 6.98277002e+03 6.87500977e+03 7.03932910e+03 6.86950586e+03 6.65562256e+03 6.80565381e+03 6.87672852e+03 6.84285938e+03 6.72716211e+03 6.67530078e+03 6.80611914e+03 6.93994385e+03 6.84273633e+03 6.71802393e+03 6.82714941e+03 6.90109570e+03 6.69576123e+03 6.64476416e+03 6.81533301e+03 6.76745752e+03 6.59924365e+03 6.81217090e+03 6.70699121e+03 6.59892188e+03 6.68512402e+03 6.63112109e+03 6.57767725e+03 6.60808154e+03 6.59224121e+03 6.52340820e+03 6.60270996e+03 6.67367139e+03 6.68535059e+03 6.44603027e+03 6.39560791e+03 6.57956641e+03 6.49456689e+03 6.50601221e+03 6.47238867e+03 6.37373975e+03 6.38528369e+03 6.44381006e+03 6.49654395e+03 6.34769287e+03 6.18708691e+03 6.33649268e+03 6.53101953e+03 6.26088867e+03 6.11356787e+03 6.21128174e+03 6.17227588e+03 6.24919824e+03 6.29005322e+03 6.13471289e+03 6.10166797e+03 6.14032764e+03 6.12260498e+03 6.14665674e+03 6.09098389e+03 6.08465088e+03 6.12737695e+03 5.84668604e+03 5.91006104e+03 5.97133594e+03 5.84970117e+03 5.95651465e+03 5.89548438e+03 5.77048926e+03 5.84851514e+03 5.76650391e+03 5.72931250e+03 5.89009424e+03 5.79625244e+03 5.65356201e+03 5.57935596e+03 5.52242969e+03 5.60843799e+03 5.66423975e+03 5.51844482e+03 5.47005713e+03 5.56446631e+03 5.54382910e+03 5.46114404e+03 5.35372559e+03 5.32917285e+03 5.30046094e+03 5.33511279e+03 5.35092725e+03 5.16624023e+03 5.13983740e+03 5.21543652e+03 5.20276758e+03 5162. 5.12998047e+03 5.03662256e+03 4.96874658e+03 5.10857178e+03 5.11121045e+03 4.89069434e+03 4.78793213e+03 4.78525293e+03 4.81947559e+03 4.79471484e+03 4.70798340e+03 4.73183740e+03 4.71619775e+03 4.66443945e+03 4.66638037e+03 4.58687988e+03 4.49548535e+03 4.52415918e+03 4.54895703e+03 4.42940186e+03 4.30894482e+03 4.34357324e+03 4.31304932e+03 4.28371875e+03 4.30259570e+03 4.21336035e+03 4.12362549e+03 4.12914258e+03 4.18693701e+03 4.08131006e+03 3.95833838e+03 3.96386499e+03 3.94463403e+03 3.89491650e+03 3.83966577e+03 3.76096216e+03 3.75218604e+03 3.74820581e+03 3.73901099e+03 3.72478784e+03 3.60551270e+03 3.57099487e+03 3.52726074e+03 3.46370312e+03 3.42794775e+03 3.37324219e+03 3.38311475e+03 3.34320288e+03 3.26551953e+03 3.19817529e+03 3.16461011e+03 3.18811646e+03 3.17383545e+03 3.12595459e+03 3.03160547e+03 2.96550562e+03 2.92809082e+03 2.85112158e+03 2.82781055e+03 2.82048779e+03 2.76689868e+03 2.71612793e+03 2.63237793e+03 2.58125708e+03 2.60046313e+03 2.58725464e+03 2.54572241e+03 2.44422461e+03 2.35165747e+03 2.34521997e+03 2.31902930e+03 2.25811450e+03 2.23260547e+03 2.20362622e+03 2.11620654e+03 2.05163013e+03 2.01415210e+03 1.97246948e+03 1.98789624e+03 1.95150415e+03 1.84054517e+03 1.81043396e+03 1.75247815e+03 1.66614722e+03 1.67605823e+03 1.65299133e+03 1.56226270e+03 1.51477502e+03 1.46322327e+03 1.39965625e+03 1.39211865e+03 1.37976746e+03 1.29776904e+03 1.23140869e+03 1.19332605e+03 1.14787036e+03 1.10814624e+03 1.05553503e+03 1.00564734e+03 9.56876770e+02 9.08493225e+02 8.64069031e+02 8.17242065e+02 7.60908386e+02 7.21423340e+02 6.86523193e+02 6.27070374e+02 5.69068298e+02 5.19208435e+02 4.79477692e+02 4.37063965e+02 3.90104797e+02 3.34808563e+02 2.78661804e+02 2.33426575e+02 1.89401688e+02 1.43612457e+02 9.34110107e+01 4.59417496e+01 -5.28638363e-01 -4.75260429e+01 -9.71285095e+01 -1.48638351e+02 -1.97346054e+02 -2.40787552e+02 -2.90111938e+02 -3.32522675e+02 -3.67688782e+02 -4.33949158e+02 -5.03169769e+02 -5.30898254e+02 -5.66728577e+02 -6.18400757e+02 -6.70954163e+02 -7.31509460e+02 -7.81976257e+02 -8.21228699e+02 -8.48830811e+02 -8.99296997e+02 -9.63564758e+02 -1.00816168e+03 -1.06895239e+03 -1.12017310e+03 -1.14579578e+03 -1.18458459e+03 -1.25315784e+03 -1.29917712e+03 -1.33489697e+03 -1.40167139e+03 -1.45546851e+03 -1.47639465e+03 -1.49876550e+03 -1.55059900e+03 -1.62630151e+03 -1.70197632e+03 -1.73985522e+03 -1.74300867e+03 -1.77724451e+03 -1.83923743e+03 -1.90566858e+03 -1.98267346e+03 -2.01349207e+03 -2.00265662e+03 -2.08833862e+03 -2.16072070e+03 -2.16516162e+03 -2.27201562e+03 -2.30508862e+03 -2.28552393e+03 -2.35555811e+03 -2.36046069e+03 -2.39655859e+03 -2.54329785e+03 -2.58944214e+03 -2.58450342e+03 -2.65094238e+03 -2.66828931e+03 -2.64307495e+03 -2.71443091e+03 -2.82957227e+03 -2.86308911e+03 -2.90591064e+03 -2.92075879e+03 -2.94894360e+03 -3.02887476e+03 -3.09478589e+03 -3.22534131e+03 -3.19899707e+03 -3.09795557e+03 -3.17772583e+03 -3.25803784e+03 -3.34268604e+03 -3.43826611e+03 -3.40832397e+03 -3.36373340e+03 -3.47911182e+03 -3.57479565e+03 -3.58397412e+03 -3.63903198e+03 -3.65610815e+03 -3.64294946e+03 -3.76163037e+03 -3.79395288e+03 -3.76550000e+03 -3.94817505e+03 -3.99312451e+03 -3.92724756e+03 -3.95448291e+03 -3.89073096e+03 -3.95342334e+03 -4.11953174e+03 -4.28107227e+03 -4.27511865e+03 -4.07674097e+03 -4.13370312e+03 -4.33771875e+03 -4.35028857e+03 -4.34532178e+03 -4.39205322e+03 -4.39298193e+03 -4.46550146e+03 -4.53729395e+03 -4.58056641e+03 -4.57758252e+03 -4.62766992e+03 -4.71922949e+03 -4.68441895e+03 -4.66066455e+03 -4.71502051e+03 -4.76740186e+03 -4.85386572e+03 -4.98413770e+03 -4.91298047e+03 -4.82147412e+03 -4.93310840e+03 -5.02470947e+03 -5.16307471e+03 -5.15639551e+03 -4.99201904e+03 -5.08306445e+03 -5.16300391e+03 -5.23504492e+03 -5.36134277e+03 -5.29178174e+03 -5.25458398e+03 -5.28462305e+03 -5.25755469e+03 -5.27863037e+03 -5.45747559e+03 -5.58665674e+03 -5.48297314e+03 -5.43207520e+03 -5.41109521e+03 -5.47510498e+03 -5.68937305e+03 -5.71484424e+03 -5.68246289e+03 -5.64540869e+03 -5.54376904e+03 -5.63343701e+03 -5.74516113e+03 -5.88487939e+03 -5.94006201e+03 -5.73319336e+03 -5.73521045e+03 -5.86096289e+03 -5.92508643e+03 -5.95297363e+03 -6.01632275e+03 -6.05675586e+03 -5.94361768e+03 -5.95313867e+03 -6.00408496e+03 -6.04766406e+03 -6.12454395e+03 -6.16656836e+03 -6.16613965e+03 -6.13170898e+03 -6.12413184e+03 -6.17907227e+03 -6.34763574e+03 -6.31038672e+03 -6.18193945e+03 -6.20202832e+03 -6.24833447e+03 -6.24471533e+03 -6.51949756e+03 -6.47659326e+03 -6.25792285e+03 -6.41721631e+03 -6.34307764e+03 -6.44596631e+03 -6.66747119e+03 -6.48884326e+03 -6.43992822e+03 -6.47361816e+03 -6.61548438e+03 -6.67438184e+03 -6.76278369e+03 -6.54875879e+03 -8.93071680e+03 -9.48420215e+03 -1.58292822e+04 -2.94189531e+04 3.28185375e+06 128801400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -15632281. 3.74871525e+06 -2.66100762e+04 -1.81376094e+04 -9.50637500e+03 -7.41654053e+03 -9.41682520e+03 -7.87305078e+03 -6.91479492e+03 -6.90980713e+03 -7.15135400e+03 -7.07995068e+03 -6.86555518e+03 -6.70073584e+03 -6.76783350e+03 -6.96062695e+03 -7.04732275e+03 -6.96105859e+03 -6.78345947e+03 -6.75242383e+03 -6.75902979e+03 -6.91393701e+03 -6.89783301e+03 -6.58592578e+03 -6.69535791e+03 -6.88375439e+03 -6.83823877e+03 -6.68134814e+03 -6.56534180e+03 -6.74034131e+03 -6.99101807e+03 -6.99975684e+03 -6.57629053e+03 -6.30495068e+03 -6.52175000e+03 -6.79844141e+03 -6.93795068e+03 -6.78091113e+03 -6.48593896e+03 -6.54056299e+03 -6.65053027e+03 -6.76706299e+03 -6.69893848e+03 -6.33149072e+03 -6.42576807e+03 -6.74610107e+03 -6.64607129e+03 -6.42620361e+03 -6.47916748e+03 -6.48537256e+03 -6.57518848e+03 -6.54735889e+03 -6.27926318e+03 -6.16967139e+03 -6.45923682e+03 -6.59137939e+03 -6.51467090e+03 -6.23741064e+03 -6.06421338e+03 -6.33332227e+03 -6.53837402e+03 -6.37412891e+03 -6.15772754e+03 -5.92808008e+03 -6.01282617e+03 -6.30346436e+03 -6.35858057e+03 -6.25807227e+03 -6.13026172e+03 -6.10612939e+03 -5.99552832e+03 -6.00042676e+03 -6.05955420e+03 -5.84778564e+03 -5.91600391e+03 -6.12653223e+03 -6.00108301e+03 -5.69811426e+03 -5.63439209e+03 -5.89971777e+03 -6.05577783e+03 -5.95320703e+03 -5.72806934e+03 -5.54558057e+03 -5.55185840e+03 -5.67384229e+03 -5.88481055e+03 -5.77530713e+03 -5.43469043e+03 -5.47120459e+03 -5.54208740e+03 -5.55695508e+03 -5.63204053e+03 -5.41050635e+03 -5.35647217e+03 -5.46993896e+03 -5.43203809e+03 -5.32261816e+03 -5.21456396e+03 -5.25557031e+03 -5.33547217e+03 -5.28945264e+03 -5.12455615e+03 -4.99512598e+03 -5.11288232e+03 -5.25031299e+03 -5.17253760e+03 -5.03149023e+03 -4.84910449e+03 -4.92635254e+03 -5.02970508e+03 -4.99570264e+03 -4.86237402e+03 -4.63682617e+03 -4.64280225e+03 -4.83482373e+03 -4.91362793e+03 -4.75833594e+03 -4.51545312e+03 -4.53163281e+03 -4.63777979e+03 -4.57648975e+03 -4.44476807e+03 -4.35197803e+03 -4.47683691e+03 -4.51672559e+03 -4.35613037e+03 -4.26100879e+03 -4.16056006e+03 -4.25238525e+03 -4.39174316e+03 -4.26319287e+03 -4.09791455e+03 -3.99871289e+03 -3.99033301e+03 -4.02006714e+03 -4.06125146e+03 -3.99059985e+03 -3.77826880e+03 -3.75322632e+03 -3.87743628e+03 -3.88288770e+03 -3.75466382e+03 -3.62942334e+03 -3.62802930e+03 -3.67304028e+03 -3.64107593e+03 -3.53635889e+03 -3.37094556e+03 -3.37581299e+03 -3.47228296e+03 -3.42304932e+03 -3.32559204e+03 -3.21266943e+03 -3.17709473e+03 -3.22085205e+03 -3.25731006e+03 -3.17558447e+03 -2.99974438e+03 -2.97441895e+03 -2.99119946e+03 -2.96036328e+03 -2.91370923e+03 -2.82181885e+03 -2.81369995e+03 -2.77286230e+03 -2.69864624e+03 -2.64716235e+03 -2.58696875e+03 -2.61511401e+03 -2.60899341e+03 -2.52217358e+03 -2.40743091e+03 -2.32350244e+03 -2.36211060e+03 -2.40334009e+03 -2.33164575e+03 -2.22631860e+03 -2.12000269e+03 -2.04815771e+03 -2.07586841e+03 -2.13041626e+03 -2.02458044e+03 -1.87872632e+03 -1.86037671e+03 -1.87805896e+03 -1.84805103e+03 -1.79394031e+03 -1.70835339e+03 -1.66505078e+03 -1.64589917e+03 -1.56916980e+03 -1.50302917e+03 -1.46737622e+03 -1.44387000e+03 -1.40099377e+03 -1.34020776e+03 -1.28127698e+03 -1.22400525e+03 -1.19782422e+03 -1.17653479e+03 -1.12678052e+03 -1.04064587e+03 -9.72938660e+02 -9.67369690e+02 -9.41874939e+02 -8.81250366e+02 -8.18603333e+02 -7.46456055e+02 -7.02519836e+02 -6.87049255e+02 -6.52587158e+02 -5.90956360e+02 -5.15642639e+02 -4.64513855e+02 -4.36404846e+02 -3.97808258e+02 -3.45991760e+02 -2.91031342e+02 -2.42732620e+02 -1.94346405e+02 -1.42016388e+02 -9.02218628e+01 -4.08647652e+01 6.89427710e+00 5.37111282e+01 1.02579018e+02 1.46004059e+02 1.83970398e+02 2.37043900e+02 2.92211151e+02 3.39572052e+02 3.89787659e+02 4.33216034e+02 4.93660919e+02 5.41105286e+02 5.60182312e+02 5.99503662e+02 6.62145874e+02 7.41844116e+02 8.14542358e+02 8.42931396e+02 8.41494873e+02 8.63910461e+02 9.37672180e+02 1.03621838e+03 1.11232825e+03 1.13638025e+03 1.12184448e+03 1.15992847e+03 1.28269263e+03 1.33956641e+03 1.31326575e+03 1.35181860e+03 1.42579333e+03 1.47693604e+03 1.57439453e+03 1.58370825e+03 1.57157312e+03 1.66418506e+03 1.67457849e+03 1.75818860e+03 1.85984314e+03 1.80827625e+03 1.89567029e+03 2.00382800e+03 1.99904968e+03 2.04441943e+03 2.08158374e+03 2.13323145e+03 2.19465161e+03 2.23323022e+03 2.21561938e+03 2.25462158e+03 2.40490015e+03 2.52098315e+03 2.51758130e+03 2.44538037e+03 2.43138354e+03 2.51894531e+03 2.68500684e+03 2.81161279e+03 2.80270581e+03 2.68713428e+03 2.73383545e+03 2.88832104e+03 2.91445166e+03 2.92072192e+03 2.95859058e+03 3.01271631e+03 3.06058350e+03 3.20530908e+03 3.17497070e+03 3.11505029e+03 3.22920142e+03 3.19896362e+03 3.33252881e+03 3.44550317e+03 3.40922510e+03 3.55074951e+03 3.48816016e+03 3.42273218e+03 3.56986475e+03 3.51937524e+03 3.63370776e+03 3.92894189e+03 3.76827734e+03 3.58894067e+03 3.71028809e+03 3.92558203e+03 4.11764258e+03 4.06257251e+03 3.87729395e+03 3.80118628e+03 3.93469189e+03 4.18667920e+03 4.36368164e+03 4.29799023e+03 4.11031689e+03 4.11502783e+03 4.30491797e+03 4.40909375e+03 4.34499756e+03 4.31231104e+03 4.42104297e+03 4.47770020e+03 4.62707373e+03 4.66736963e+03 4.48669189e+03 4.51603418e+03 4.60541553e+03 4.66585498e+03 4.76036523e+03 4.77290918e+03 4.90865088e+03 4.85625146e+03 4.72756787e+03 4.85932373e+03 4.78764404e+03 4.95886865e+03 5.30510107e+03 5.06212598e+03 4.77363281e+03 4.91785254e+03 5.20802832e+03 5.40039502e+03 5.41704297e+03 5.15407471e+03 4.98010498e+03 5.10033447e+03 5.40648730e+03 5.66933350e+03 5.53825049e+03 5.25422168e+03 5.24709863e+03 5.42882812e+03 5.53189746e+03 5.72391650e+03 5.71662695e+03 5.43774463e+03 5.42783545e+03 5.74729297e+03 5.81380078e+03 5.63727832e+03 5.64398242e+03 5.69227783e+03 5.67500537e+03 5.94656738e+03 6.02772998e+03 5.74995312e+03 5.73440771e+03 5.82335254e+03 5.90619678e+03 5.97228613e+03 5.93481934e+03 6.10813330e+03 6.21914502e+03 6.02909570e+03 5.93035205e+03 5.82339014e+03 6.08532324e+03 6.45595996e+03 6.33736279e+03 6.04134668e+03 5.90568896e+03 6.15846582e+03 6.51826562e+03 6.33708691e+03 6.00553027e+03 6.13867871e+03 6.30251514e+03 6.52181152e+03 6.70413379e+03 6.58540137e+03 6.21761035e+03 6.12403467e+03 6.34057812e+03 6.57685400e+03 6.58808350e+03 6.51398193e+03 6.50469043e+03 6.48673877e+03 6.63435156e+03 6.61098047e+03 6.42650928e+03 6.38308643e+03 6.43216748e+03 6.75583057e+03 6.81428223e+03 6.63480469e+03 6.65989404e+03 6.70885156e+03 6.80566309e+03 6.70116943e+03 6.36219092e+03 6.67527490e+03 7.06419189e+03 6.87766992e+03 6.53407324e+03 6.56548975e+03 6.92545947e+03 6.96678369e+03 6.84216943e+03 6.80555420e+03 6.62902148e+03 6.64322852e+03 6.98944043e+03 7.00515527e+03 6.69944385e+03 6.57072998e+03 6.60517285e+03 6.91728564e+03 7.19693066e+03 6.88048193e+03 6.68300195e+03 6.83227295e+03 6.87688232e+03 7.08737061e+03 7.05171582e+03 6.61074805e+03 6.72941406e+03 6.94830225e+03 6.90371924e+03 6.92031982e+03 6.85690186e+03 7.02578467e+03 7.00021484e+03 6.79031055e+03 6.81620996e+03 6.68658594e+03 6.93014453e+03 7.24873828e+03 7.05553369e+03 6.75715723e+03 6.66570557e+03 7.01108301e+03 7.24745215e+03 7.60682959e+03 8.03729199e+03 7.15133301e+03 8.56967578e+03 1.32397559e+04 1.19849859e+05 53426952. 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. 0. 0. 0. 0. 0. 0. 0. -48947436. 6.41627950e+06 1.56498862e+06 4.90040650e+06 1.92910371e+04 1.53019355e+04 8.66125488e+03 8.46806445e+03 6.90060010e+03 6.72663428e+03 6.41188330e+03 6.51815625e+03 6.39643652e+03 6.14645996e+03 6.27146777e+03 6.24667383e+03 6.41727246e+03 6.43754883e+03 5.85914014e+03 5.75315869e+03 5.86863428e+03 5.99127588e+03 5.88471436e+03 5.75664502e+03 6.15458105e+03 5.97217969e+03 5.78709473e+03 6.02981104e+03 5.98255713e+03 5.75518018e+03 5.92323730e+03 6.09380322e+03 5.90373975e+03 5.78961182e+03 5.75099023e+03 5.69738281e+03 5.62289502e+03 5.61119531e+03 5.73767969e+03 5.71433154e+03 5.59654492e+03 5.55311963e+03 5.52675488e+03 5.50255713e+03 5.45745410e+03 5.41869727e+03 5.40454590e+03 5.22205518e+03 5.16840625e+03 5.28549756e+03 5.25634521e+03 5.41289209e+03 5.39763818e+03 5.17917334e+03 4.99698047e+03 4.95307910e+03 5.23962207e+03 5.25858838e+03 5.02268701e+03 4.88744336e+03 4.87178613e+03 4.90190479e+03 4.84285693e+03 4.97621680e+03 4.94194873e+03 4.62985156e+03 4.54452490e+03 4.75350146e+03 4.90382910e+03 4.74132324e+03 4.59328711e+03 4.58504688e+03 4.53757617e+03 4.44656543e+03 4.43962842e+03 4.41406250e+03 4.34931641e+03 4.31693018e+03 4.27473047e+03 4.29232227e+03 4.23691748e+03 4.29480518e+03 4.24164062e+03 4.07079590e+03 4.09478174e+03 4.06173145e+03 4.03928711e+03 4.01593384e+03 3.94826782e+03 3.90425195e+03 3.77638525e+03 3.64450293e+03 3.78371045e+03 3.79741553e+03 3.56439746e+03 3.55216479e+03 3.71512695e+03 3.77798340e+03 3.61903687e+03 3.47514868e+03 3.42088062e+03 3.38069141e+03 3.31872705e+03 3.26392456e+03 3.28255591e+03 3.22932349e+03 3.26270679e+03 3.20013501e+03 3.06779761e+03 3.07665820e+03 2.95141577e+03 2.91994141e+03 3.03417700e+03 2.96518115e+03 2.85511865e+03 2.74490381e+03 2.65718701e+03 2.76808521e+03 2.77500244e+03 2.63203638e+03 2.51516724e+03 2.48028271e+03 2.49792310e+03 2.43857227e+03 2.46747900e+03 2.44070776e+03 2.30869238e+03 2.21787622e+03 2.17482373e+03 2.21834033e+03 2.17679419e+03 2.07825171e+03 2.00958276e+03 1.96714636e+03 1.94150342e+03 1.84556104e+03 1.81254614e+03 1.87226379e+03 1.81070752e+03 1.71605762e+03 1.62627527e+03 1.56804712e+03 1.61651465e+03 1.57741394e+03 1.48356445e+03 1.40077954e+03 1.34451758e+03 1.33566858e+03 1.29109277e+03 1.24262939e+03 1.16304517e+03 1.14040369e+03 1.14945081e+03 1.06947314e+03 1.01205444e+03 9.69723267e+02 9.14067200e+02 8.52904846e+02 8.03597534e+02 7.65299133e+02 7.15807800e+02 6.63194824e+02 5.97099182e+02 5.62021667e+02 5.48697876e+02 4.80702484e+02 4.18255829e+02 3.82216156e+02 3.33876190e+02 2.94861053e+02 2.40975937e+02 1.84768860e+02 1.46118912e+02 9.76220398e+01 4.71730652e+01 1.36062384e+00 -4.44985046e+01 -9.23673325e+01 -1.42525772e+02 -1.92947144e+02 -2.34944275e+02 -2.89503174e+02 -3.56835266e+02 -3.96818634e+02 -4.31436401e+02 -4.67397858e+02 -5.20148560e+02 -6.01268677e+02 -6.46402100e+02 -6.75995728e+02 -7.05237793e+02 -7.48034729e+02 -8.19254578e+02 -8.65624451e+02 -9.33838684e+02 -9.64538208e+02 -9.80041504e+02 -1.05895813e+03 -1.10809436e+03 -1.17927881e+03 -1.21933142e+03 -1.23205530e+03 -1.27957373e+03 -1.32648035e+03 -1.39475049e+03 -1.40355103e+03 -1.46451575e+03 -1.59594055e+03 -1.61512146e+03 -1.62393127e+03 -1.62890857e+03 -1.66333301e+03 -1.80671265e+03 -1.86281921e+03 -1.85780554e+03 -1.85168726e+03 -1.89288525e+03 -2.00428625e+03 -2.05333643e+03 -2.14301001e+03 -2.16297852e+03 -2.16139062e+03 -2.18254858e+03 -2.21364893e+03 -2.38230249e+03 -2.41203174e+03 -2.38038696e+03 -2.41642261e+03 -2.46319458e+03 -2.58420825e+03 -2.63509253e+03 -2.57111328e+03 -2.60304248e+03 -2.78478687e+03 -2.83062280e+03 -2.73700537e+03 -2.76711230e+03 -2.96457324e+03 -3.02327563e+03 -2.96364526e+03 -2.94090869e+03 -2.98444336e+03 -3.20458691e+03 -3.21841748e+03 -3.16499048e+03 -3.22064502e+03 -3.25326660e+03 -3.30608423e+03 -3.34452002e+03 -3.38534424e+03 -3.34064038e+03 -3.46943237e+03 -3.71019263e+03 -3.64026660e+03 -3.62994800e+03 -3.70134863e+03 -3.71300146e+03 -3.75091016e+03 -3.78247559e+03 -3.81637573e+03 -3.76158057e+03 -3.74055029e+03 -3.86831665e+03 -4.01010156e+03 -4.17899072e+03 -4.06876611e+03 -3.96130225e+03 -4.10580762e+03 -4.19510400e+03 -4.36059131e+03 -4.34019629e+03 -4.25045947e+03 -4.25569873e+03 -4.26452930e+03 -4.39700635e+03 -4.43634814e+03 -4.56349121e+03 -4.59320166e+03 -4.52133008e+03 -4.50721143e+03 -4.41492090e+03 -4.63541406e+03 -4.93875342e+03 -4.87765332e+03 -4.76475977e+03 -4.66664502e+03 -4.64910449e+03 -4.92363184e+03 -5.08751807e+03 -4.97808252e+03 -4.83092725e+03 -4.86621582e+03 -5.02977148e+03 -5.05415918e+03 -5.22974902e+03 -5.23895703e+03 -5.11090283e+03 -5.17248877e+03 -5.18987451e+03 -5.31858545e+03 -5.37456738e+03 -5.18058008e+03 -5.20276807e+03 -5.53359668e+03 -5.45187549e+03 -5.20002539e+03 -5.41184961e+03 -5.72960840e+03 -5.66299609e+03 -5.54435449e+03 -5.43760449e+03 -5.47874121e+03 -5.82972803e+03 -5.82033984e+03 -5.67993066e+03 -5.57606055e+03 -5.57130225e+03 -5.77102734e+03 -5.79529102e+03 -5.79906738e+03 -5.70735938e+03 -5.86140088e+03 -6.13743799e+03 -5.98994727e+03 -6.02149414e+03 -6.02464062e+03 -5.93059912e+03 -6.01420020e+03 -6.04452930e+03 -6.09085547e+03 -6.07745459e+03 -6.04415527e+03 -5.94606689e+03 -6.10868750e+03 -6.48695215e+03 -6.21558350e+03 -5.95303369e+03 -6.16473193e+03 -6.33971436e+03 -6.53827051e+03 -6.41682129e+03 -6.24334766e+03 -6.41948633e+03 -6.45139453e+03 -6.20464600e+03 -6.15486133e+03 -6.54541895e+03 -6.59395264e+03 -6.42434619e+03 -6.32931348e+03 -6.15594434e+03 -6.43372754e+03 -6.86962451e+03 -6.69620068e+03 -6.53507373e+03 -6.37457959e+03 -6.33054590e+03 -6.68945947e+03 -6.92591846e+03 -6.74513818e+03 -6.43831934e+03 -6.42490479e+03 -6.61212354e+03 -6.72952148e+03 -6.88585205e+03 -6.77989355e+03 -6.59758936e+03 -6.73392773e+03 -6.71689893e+03 -6.83985254e+03 -6.79814648e+03 -6.70311084e+03 -6.76800732e+03 -6.75430273e+03 -6.73309131e+03 -6.55522021e+03 -6.70084033e+03 -7.12591602e+03 -6.97781934e+03 -6.73275049e+03 -6.61138623e+03 -6.70501709e+03 -7.10074951e+03 -7.06687842e+03 -6.87600244e+03 -6.70070947e+03 -6.67958838e+03 -6.84351172e+03 -6.86480273e+03 -6.86342529e+03 -6.70518799e+03 -6.84227148e+03 -7.15340723e+03 -6.92889160e+03 -6.98829053e+03 -7.02172119e+03 -6.85325830e+03 -6.85316162e+03 -6.85130908e+03 -6.82494922e+03 -6.83114160e+03 -6.85348340e+03 -6.84643652e+03 -7.01664160e+03 -7.04815283e+03 -6.69203223e+03 -6.61891943e+03 -6.80828174e+03 -6.98275439e+03 -7.16652002e+03 -6.92446143e+03 -6.63072559e+03 -6.93992139e+03 -7.08886719e+03 -6.90390771e+03 -6.73929395e+03 -6.70970801e+03 -6.85708789e+03 -6.87459717e+03 -6.80075781e+03 -6.61046045e+03 -6.80955957e+03 -7.13632715e+03 -6.97265430e+03 -6.83316504e+03 -6.67276318e+03 -6.57701074e+03 -6.96663135e+03 -6.93111523e+03 -6.75445264e+03 -6.60471338e+03 -6.40298389e+03 -6.58070020e+03 -6.84020996e+03 -7.03294873e+03 -6.72353760e+03 -6.41168896e+03 -6.58558105e+03 -6.68460986e+03 -6.86178613e+03 -6.71457959e+03 -6.48975342e+03 -6.66162939e+03 -6.62623047e+03 -6.48321436e+03 -6.29062939e+03 -6.48930371e+03 -6.82745654e+03 -6.65411084e+03 -6.54957227e+03 -6.35018750e+03 -6.30992871e+03 -6.62203857e+03 -6.62758447e+03 -6.39781982e+03 -6.22115576e+03 -6.16907715e+03 -6.36141650e+03 -6.33242529e+03 -6.49452832e+03 -6.47281738e+03 -6.22791650e+03 -6.09879980e+03 -6.15678857e+03 -6.40599219e+03 -6.24207617e+03 -6.08847168e+03 -6.15808154e+03 -6.16031445e+03 -6.01204541e+03 -5.91630127e+03 -6.14535547e+03 -6.10226514e+03 -5.90535107e+03 -6.12829443e+03 -6.14669873e+03 -6.00095752e+03 -5.95221826e+03 -5.90367334e+03 -5.88136523e+03 -5.70543213e+03 -5.62083154e+03 -5.88330957e+03 -5.95297998e+03 -5.61179492e+03 -5.41334375e+03 -5.64176123e+03 -5.94607861e+03 -5.83606592e+03 -5.51952100e+03 -5.37701270e+03 -5.62481934e+03 -5.69231934e+03 -5.49919336e+03 -5.51849707e+03 -5.33048145e+03 -5.14964844e+03 -5.32625635e+03 -5.53088965e+03 -5.48993652e+03 -5.23838281e+03 -5.04941260e+03 -5.27666846e+03 -5.41394336e+03 -5.22262793e+03 -4.98934375e+03 -4.88850732e+03 -5.01394922e+03 -5.01347070e+03 -5.10439844e+03 -5.06012549e+03 -4.83938867e+03 -4.87968799e+03 -4.87983496e+03 -4.91946289e+03 -4.74344043e+03 -4.60566992e+03 -4.78806641e+03 -4.76182666e+03 -4.66230078e+03 -4.50977148e+03 -4.50940039e+03 -4.73577979e+03 -4.51996924e+03 -4.29129297e+03 -4.36904541e+03 -4.43272705e+03 -4.40463867e+03 -4.31558984e+03 -4.37517480e+03 -4.37098047e+03 -4.20318213e+03 -4.05023901e+03 -4.00541968e+03 -4.18333740e+03 -4.07179785e+03 -3.91646704e+03 -4.01760791e+03 -3.97912549e+03 -3.86790137e+03 -3.78884741e+03 -3.87565869e+03 -3.81054834e+03 -3.66446899e+03 -3.72079785e+03 -3.68001538e+03 -3.65534888e+03 -3.62204370e+03 -3.53824731e+03 -3.47015381e+03 -3.33441821e+03 -3.27215674e+03 -3.39858569e+03 -3.48889209e+03 -3.26796899e+03 -3.06326978e+03 -3.14941577e+03 -3.29410962e+03 -3.22690576e+03 -3.02822290e+03 -2.88248999e+03 -2.97931396e+03 -3.02703003e+03 -2.88986133e+03 -2.89549756e+03 -2.83779199e+03 -2.68407300e+03 -2.66546313e+03 -2.72452979e+03 -2.69926758e+03 -2.54544434e+03 -2.43081494e+03 -2.49448413e+03 -2.55667969e+03 -2.44743384e+03 -2.30215601e+03 -2.21878149e+03 -2.27926636e+03 -2.30634155e+03 -2.18332617e+03 -2.08335254e+03 -2.04956592e+03 -2.04343335e+03 -1.99011145e+03 -1.99545459e+03 -1.90724719e+03 -1.79838599e+03 -1.81865198e+03 -1.77777625e+03 -1.73981738e+03 -1.65537280e+03 -1.57887183e+03 -1.59922217e+03 -1.51707031e+03 -1.44673218e+03 -1.44118726e+03 -1.38959412e+03 -1.34245984e+03 -1.29180664e+03 -1.28192542e+03 -1.24162378e+03 -1.14884070e+03 -1.06803711e+03 -1.02474768e+03 -1.04171594e+03 -9.92979065e+02 -8.98501770e+02 -7.73571777e+02 -8.26482300e+02 -1.33441602e+03 -7.05908447e+03 -2.66911188e+05 0. 0. 0. 0. 0. 2.20249702e+09 -7.46532062e+05 1.32763438e+05 2.37324927e+03 2.97410205e+03 -3.87646523e+04 -2.55462148e+04 3.49749632e+09 1.05506458e+10 1.05506458e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 199508688. 4.52900188e+05 2.67558719e+05 1.59048169e+03 1.63518970e+03 1.01414044e+03 7.54132935e+02 9.87938721e+02 9.93640137e+02 1.02003461e+03 1.06499170e+03 1.11753979e+03 1.16847485e+03 1.18598547e+03 1.23143274e+03 1.30595276e+03 1.34141577e+03 1.37989294e+03 1.42061816e+03 1.45669165e+03 1.54027417e+03 1.58877686e+03 1.61081226e+03 1.66769421e+03 1.68971069e+03 1.73408630e+03 1.84518933e+03 1.90826331e+03 1.88510095e+03 1.91505273e+03 1.99314587e+03 2.04764709e+03 2.06059155e+03 2.09171948e+03 2.16576343e+03 2.21380200e+03 2.30337012e+03 2.34006567e+03 2.29639722e+03 2.36551245e+03 2.50293848e+03 2.56340210e+03 2.57503076e+03 2.52437256e+03 2.54599487e+03 2.68230298e+03 2.75387061e+03 2.75100122e+03 2.77077441e+03 2.81644092e+03 2.91458984e+03 2.99203589e+03 2.99511035e+03 2.94875537e+03 2.98766406e+03 3.19296338e+03 3.24910425e+03 3.11956079e+03 3.15016260e+03 3.27868726e+03 3.36728223e+03 3.44598633e+03 3.42293140e+03 3.34631934e+03 3.42393555e+03 3.55813794e+03 3.61138965e+03 3.60447925e+03 3.58966455e+03 3.68899316e+03 3.77838916e+03 3.78793677e+03 3.78712842e+03 3.78957129e+03 3.86469580e+03 3.97854053e+03 3.99598291e+03 4.05226709e+03 4.06504761e+03 3.99650146e+03 4.10410059e+03 4.18794092e+03 4.21442676e+03 4.25515283e+03 4.24589893e+03 4.28919238e+03 4.44514111e+03 4.45480420e+03 4.33235498e+03 4.38833203e+03 4.51590869e+03 4.60423438e+03 4.60381396e+03 4.54869629e+03 4.58652979e+03 4.68349902e+03 4.76904395e+03 4.77429590e+03 4.68925586e+03 4.78656250e+03 4.96262598e+03 4.96920557e+03 4.96209229e+03 4.86605420e+03 4.87876514e+03 5.09759375e+03 5.08695215e+03 5.02513281e+03 5.05029297e+03 5.11446240e+03 5.24652881e+03 5.26803418e+03 5.22495947e+03 5.25474121e+03 5.29055566e+03 5.40069092e+03 5.43758789e+03 5.36747705e+03 5.40559668e+03 5.44053027e+03 5.43289404e+03 5.53031104e+03 5.57474609e+03 5.58087451e+03 5.62389746e+03 5.60423877e+03 5.58892383e+03 5.70272510e+03 5.79813818e+03 5.74070996e+03 5.73718359e+03 5.70152539e+03 5.75105908e+03 5.87639014e+03 5.85162061e+03 5.84881592e+03 5.88877783e+03 6.03875732e+03 6.07873047e+03 5.95792822e+03 6.01168066e+03 6.05918945e+03 6.03890137e+03 5.99035840e+03 6.02175635e+03 6.09328906e+03 6.19352197e+03 6.27657764e+03 6.28105469e+03 6.16442871e+03 6.09283936e+03 6.24428369e+03 6.32422314e+03 6.32075879e+03 6.33324316e+03 6.26769092e+03 6.35305615e+03 6.46304053e+03 6.44082129e+03 6.34122656e+03 6.26171777e+03 6.42876270e+03 6.59723145e+03 6.54407617e+03 6.30760010e+03 6.37859229e+03 6.60242236e+03 6.60904590e+03 6.50053320e+03 6.53507080e+03 6.57410742e+03 6.53872314e+03 6.63930225e+03 6.58377539e+03 6.45613574e+03 6.63601465e+03 6.77882373e+03 6.67971191e+03 6.67941846e+03 6.70230566e+03 6.58938184e+03 6.66330273e+03 6.72636475e+03 6.78718213e+03 6.88376562e+03 6.59838379e+03 6.63800293e+03 6.90677148e+03 6.79284473e+03 6.62059180e+03 6.74015479e+03 6.87935205e+03 6.84182568e+03 6.84968115e+03 6.82995166e+03 6.74780469e+03 6.72485938e+03 6.93656934e+03 7.03711816e+03 6.75655859e+03 6.78592920e+03 7.00504102e+03 6.90209131e+03 6.86034619e+03 6.79717334e+03 6.71376221e+03 6.90913721e+03 6.87111523e+03 6.84621387e+03 6.90463477e+03 6.77918164e+03 6.82746045e+03 6.97830322e+03 6.83366650e+03 6.82504150e+03 6.89357764e+03 6.88567871e+03 6.84624756e+03 6.89239307e+03 6.87514160e+03 6.82340771e+03 6.82818115e+03 6.92354785e+03 6.89181592e+03 6.78699854e+03 6.89051416e+03 6.96795020e+03 6.86437646e+03 6.97367920e+03 6.84653418e+03 6.67640576e+03 6.82417627e+03 6.83264355e+03 6.83181201e+03 6.73524365e+03 6.68113184e+03 6.83772363e+03 6.95971045e+03 6.81921680e+03 6.70365918e+03 6.78626025e+03 6.85015283e+03 6.69772559e+03 6.62006641e+03 6.82339502e+03 6.77318213e+03 6.58596289e+03 6.76544873e+03 6.69104492e+03 6.63440869e+03 6.68852588e+03 6.57144287e+03 6.56757666e+03 6.62181299e+03 6.57662451e+03 6.54369092e+03 6.59797363e+03 6.63605615e+03 6.65322314e+03 6.42053613e+03 6.36607373e+03 6.53058740e+03 6.48783301e+03 6.50322070e+03 6.46003711e+03 6.35849707e+03 6.39904541e+03 6.42572266e+03 6.52272412e+03 6.35846924e+03 6.15317725e+03 6.30446143e+03 6.56006543e+03 6.26617725e+03 6.10594434e+03 6.17587451e+03 6.15416943e+03 6.22929053e+03 6.28093115e+03 6.10770264e+03 6.08164600e+03 6.12155078e+03 6.11369580e+03 6.16509033e+03 6.05005127e+03 6.06845020e+03 6.11980664e+03 5.84085986e+03 5.89194385e+03 5.95137793e+03 5.84413477e+03 5.95302393e+03 5.88431641e+03 5.76598145e+03 5.84109619e+03 5.73991943e+03 5.72483740e+03 5.88810742e+03 5.77635986e+03 5.63030273e+03 5.56643164e+03 5.50183252e+03 5.60564893e+03 5.65314551e+03 5.54013135e+03 5.48158057e+03 5.54255273e+03 5.53354932e+03 5.46528564e+03 5.34068896e+03 5.29323633e+03 5.31447461e+03 5.34323438e+03 5.34474512e+03 5.17150732e+03 5.13079004e+03 5.19485596e+03 5.19155225e+03 5.15048535e+03 5.12422119e+03 5.03777002e+03 4.95847607e+03 5.07591016e+03 5.10543115e+03 4.90164111e+03 4.76683496e+03 4.76952637e+03 4.82562793e+03 4.79088916e+03 4.70366162e+03 4.73465576e+03 4.71188232e+03 4.65046924e+03 4.66580615e+03 4.58088477e+03 4.49832715e+03 4.51906494e+03 4.54541162e+03 4.41432910e+03 4.29572119e+03 4.34047266e+03 4.30696191e+03 4.27980811e+03 4.29404883e+03 4.21050391e+03 4.11093945e+03 4.12111768e+03 4.17366846e+03 4.07853345e+03 3.95471558e+03 3.94608350e+03 3.92696240e+03 3.88487646e+03 3.83447461e+03 3.76078857e+03 3.75028979e+03 3.73416626e+03 3.73200513e+03 3.71981958e+03 3.60356079e+03 3.56484180e+03 3.52062671e+03 3.45880493e+03 3.42050244e+03 3.34983374e+03 3.36638745e+03 3.34622510e+03 3.25848682e+03 3.18180566e+03 3.14780566e+03 3.17121973e+03 3.16390259e+03 3.12087598e+03 3.01995532e+03 2.95294312e+03 2.91257544e+03 2.82805103e+03 2.81535840e+03 2.81664673e+03 2.75891772e+03 2.69579443e+03 2.61947510e+03 2.58150659e+03 2.59535498e+03 2.58197534e+03 2.54134253e+03 2.43805371e+03 2.34313623e+03 2.33043335e+03 2.30046875e+03 2.25028735e+03 2.23201196e+03 2.19894751e+03 2.10886548e+03 2.04372083e+03 1.99424780e+03 1.95777869e+03 1.98379822e+03 1.94029114e+03 1.83256848e+03 1.80136255e+03 1.74317517e+03 1.66423914e+03 1.67721204e+03 1.64665979e+03 1.54806213e+03 1.49692297e+03 1.44775000e+03 1.38922620e+03 1.38637231e+03 1.38181934e+03 1.30071948e+03 1.22706946e+03 1.18373975e+03 1.13371130e+03 1.09674084e+03 1.04896313e+03 9.99672546e+02 9.47031189e+02 8.94096619e+02 8.54846680e+02 8.14373535e+02 7.61766357e+02 7.19366089e+02 6.79011230e+02 6.16749084e+02 5.56359314e+02 5.14115173e+02 4.80000519e+02 4.38519958e+02 3.86171356e+02 3.26894348e+02 2.74972870e+02 2.35870819e+02 1.95793732e+02 1.49662003e+02 9.71243515e+01 4.50046387e+01 -6.91148567e+00 -5.65237160e+01 -1.00729240e+02 -1.43290329e+02 -1.87710358e+02 -2.35252213e+02 -2.95651611e+02 -3.43255737e+02 -3.76669739e+02 -4.36757629e+02 -5.01863373e+02 -5.33133972e+02 -5.72193848e+02 -6.26679077e+02 -6.73051697e+02 -7.28644287e+02 -7.77769836e+02 -8.17669434e+02 -8.46461609e+02 -9.00882019e+02 -9.66598572e+02 -1.00908954e+03 -1.06756177e+03 -1.11783374e+03 -1.14633875e+03 -1.18397412e+03 -1.25596741e+03 -1.30234827e+03 -1.33393481e+03 -1.39777600e+03 -1.45288293e+03 -1.48049438e+03 -1.50360791e+03 -1.54839099e+03 -1.61344604e+03 -1.69269067e+03 -1.74055322e+03 -1.74890088e+03 -1.78304102e+03 -1.83309692e+03 -1.89917188e+03 -1.97439355e+03 -2.00830347e+03 -2.00708215e+03 -2.08323267e+03 -2.14676050e+03 -2.15301343e+03 -2.26068408e+03 -2.30411182e+03 -2.28059058e+03 -2.35723779e+03 -2.36909595e+03 -2.39250977e+03 -2.53043384e+03 -2.57534595e+03 -2.57324561e+03 -2.64405298e+03 -2.67186279e+03 -2.64698413e+03 -2.71056006e+03 -2.81647876e+03 -2.85481543e+03 -2.90329004e+03 -2.91855542e+03 -2.94759302e+03 -3.02779639e+03 -3.07673389e+03 -3.20927466e+03 -3.19480078e+03 -3.09791504e+03 -3.17960376e+03 -3.25389917e+03 -3.33613940e+03 -3.42219971e+03 -3.39487158e+03 -3.35677856e+03 -3.47973413e+03 -3.56251123e+03 -3.57343066e+03 -3.63225146e+03 -3.64337842e+03 -3.62932349e+03 -3.74593774e+03 -3.79269482e+03 -3.75011768e+03 -3.93506812e+03 -3.98379150e+03 -3.91853467e+03 -3.95845801e+03 -3.88931787e+03 -3.94334473e+03 -4.11097412e+03 -4.27925977e+03 -4.26823682e+03 -4.06392065e+03 -4.12433252e+03 -4.33045068e+03 -4.33750830e+03 -4.33496533e+03 -4.38824658e+03 -4.38499170e+03 -4.46311035e+03 -4.52476172e+03 -4.57005469e+03 -4.58620020e+03 -4.62087891e+03 -4.70895605e+03 -4.66742188e+03 -4.65569238e+03 -4.69599756e+03 -4.74375244e+03 -4.83552002e+03 -4.96862842e+03 -4.90880908e+03 -4.80375049e+03 -4.92429248e+03 -5.01503613e+03 -5.14833496e+03 -5.14492969e+03 -4.97390332e+03 -5.06355859e+03 -5.15717139e+03 -5.23167773e+03 -5.34972070e+03 -5.27859424e+03 -5.22914844e+03 -5.28471094e+03 -5.26381641e+03 -5.24399463e+03 -5.44614355e+03 -5.58045752e+03 -5.45280713e+03 -5.41546191e+03 -5.41112305e+03 -5.47039453e+03 -5.67523340e+03 -5.70468652e+03 -5.66828369e+03 -5.64424756e+03 -5.53232910e+03 -5.64560010e+03 -5.72491846e+03 -5.86708789e+03 -5.93008105e+03 -5.73053662e+03 -5.73631055e+03 -5.85416260e+03 -5.91211768e+03 -5.93971631e+03 -6.00708984e+03 -6.04117920e+03 -5.92184229e+03 -5.95697168e+03 -6.00788965e+03 -6.03567480e+03 -6.09989453e+03 -6.15566016e+03 -6.14959375e+03 -6.13739062e+03 -6.11331250e+03 -6.18512549e+03 -6.33712207e+03 -6.28531055e+03 -6.17224414e+03 -6.19564941e+03 -6.24995166e+03 -6.26004004e+03 -6.51545898e+03 -6.54937207e+03 -6.27547070e+03 -6.33638037e+03 -6.30312744e+03 -6.39486963e+03 -6.65643750e+03 -6.71633105e+03 -6.35345752e+03 -5.92522852e+03 -8.09447754e+03 -8.96909473e+03 -9.91778125e+03 -1.01831260e+04 -1.07391045e+04 -1.00669082e+04 -1.58292822e+04 -2.94189531e+04 3.28185375e+06 128801400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 28359492. -3.05143301e+04 -1.12721230e+04 -1.03541162e+04 -9.03706348e+03 -1.06004727e+04 -7.91824902e+03 -6.83040137e+03 -6.84746240e+03 -7.16657666e+03 -7.05884375e+03 -6.83958350e+03 -6.68755078e+03 -6.71520898e+03 -6.93267480e+03 -7.02325684e+03 -6.94967822e+03 -6.75902686e+03 -6.70187402e+03 -6.72126074e+03 -6.90649951e+03 -6.84894043e+03 -6.59796191e+03 -6.68250049e+03 -6.87820264e+03 -6.80444385e+03 -6.64979199e+03 -6.53960352e+03 -6.74024121e+03 -7.03493213e+03 -6.98844287e+03 -6.55492090e+03 -6.29250537e+03 -6.49599072e+03 -6.78443066e+03 -6.91127881e+03 -6.79459863e+03 -6.45500293e+03 -6.50532031e+03 -6.60517188e+03 -6.77737402e+03 -6.66714551e+03 -6.31276465e+03 -6.38924756e+03 -6.71505029e+03 -6.59826660e+03 -6.43109570e+03 -6.46514355e+03 -6.48420020e+03 -6.52242920e+03 -6.50881104e+03 -6.26998291e+03 -6.18147754e+03 -6.43443799e+03 -6.61795801e+03 -6.47737695e+03 -6.24075439e+03 -6.03447607e+03 -6.30238867e+03 -6.52458740e+03 -6.37399854e+03 -6.12889844e+03 -5.89468945e+03 -5.98354639e+03 -6.30293066e+03 -6.35627295e+03 -6.25021191e+03 -6.10839209e+03 -6.07938477e+03 -5.97889551e+03 -6.00205957e+03 -6.03216016e+03 -5.83526953e+03 -5.91289941e+03 -6.09869141e+03 -5.98549854e+03 -5.67658643e+03 -5.62877783e+03 -5.89826660e+03 -6.06616748e+03 -5.92536035e+03 -5.71701416e+03 -5.54416211e+03 -5.51747070e+03 -5.64905371e+03 -5.87208691e+03 -5.75885498e+03 -5.42085840e+03 -5.45932471e+03 -5.53145703e+03 -5.54462939e+03 -5.61471729e+03 -5.39229590e+03 -5.34332324e+03 -5.47053027e+03 -5.42828223e+03 -5.29018945e+03 -5.19472754e+03 -5.25967969e+03 -5.32604395e+03 -5.26643750e+03 -5.10057031e+03 -4.98874414e+03 -5.11076465e+03 -5.23519922e+03 -5.15631250e+03 -5.00903662e+03 -4.84197266e+03 -4.90034863e+03 -5.01667578e+03 -4.98287793e+03 -4.84085107e+03 -4.63126172e+03 -4.63411621e+03 -4.81677002e+03 -4.89258691e+03 -4.75914160e+03 -4.50269531e+03 -4.52922314e+03 -4.63892383e+03 -4.56242041e+03 -4.42972070e+03 -4.33696045e+03 -4.47145508e+03 -4.51690332e+03 -4.33777051e+03 -4.24008203e+03 -4.15993359e+03 -4.24360596e+03 -4.37510059e+03 -4.25724902e+03 -4.08634937e+03 -3.99111499e+03 -3.98219653e+03 -4.00495654e+03 -4.05561108e+03 -3.98260767e+03 -3.76806226e+03 -3.74178809e+03 -3.86701514e+03 -3.87792725e+03 -3.75220947e+03 -3.62969067e+03 -3.62708252e+03 -3.66407007e+03 -3.62004248e+03 -3.52093774e+03 -3.36456323e+03 -3.36248389e+03 -3.45787744e+03 -3.41282666e+03 -3.31607104e+03 -3.20143799e+03 -3.18037744e+03 -3.22347241e+03 -3.25932861e+03 -3.17550220e+03 -2.99223511e+03 -2.95742920e+03 -2.97522607e+03 -2.95032202e+03 -2.90438525e+03 -2.81026123e+03 -2.80318164e+03 -2.75716064e+03 -2.68419727e+03 -2.64339746e+03 -2.58613159e+03 -2.61581494e+03 -2.60322729e+03 -2.50855835e+03 -2.39899072e+03 -2.31947388e+03 -2.35629321e+03 -2.39298682e+03 -2.32459399e+03 -2.22215259e+03 -2.11107935e+03 -2.03714539e+03 -2.07026831e+03 -2.13126782e+03 -2.02931934e+03 -1.87526001e+03 -1.85269714e+03 -1.87236328e+03 -1.83836096e+03 -1.78275989e+03 -1.70136462e+03 -1.65098706e+03 -1.62308618e+03 -1.55676160e+03 -1.49759460e+03 -1.46858167e+03 -1.44700659e+03 -1.39483313e+03 -1.33459448e+03 -1.27644104e+03 -1.22611853e+03 -1.20263208e+03 -1.17588208e+03 -1.11693530e+03 -1.02687781e+03 -9.63596558e+02 -9.55656311e+02 -9.28325317e+02 -8.71901306e+02 -8.12767761e+02 -7.40762268e+02 -6.94209839e+02 -6.79315186e+02 -6.49019836e+02 -5.91204895e+02 -5.21356323e+02 -4.67680511e+02 -4.30811035e+02 -3.84835052e+02 -3.34123352e+02 -2.88895630e+02 -2.43882156e+02 -1.92058960e+02 -1.40372452e+02 -9.04024277e+01 -4.45314560e+01 1.01839566e+00 4.83605003e+01 9.92887650e+01 1.47086517e+02 1.87977539e+02 2.42032455e+02 2.95030884e+02 3.40756561e+02 3.90976471e+02 4.34184753e+02 4.93778961e+02 5.40031128e+02 5.56869141e+02 5.95765259e+02 6.58255493e+02 7.39974121e+02 8.13837402e+02 8.43396606e+02 8.42336975e+02 8.61829407e+02 9.31880615e+02 1.03385535e+03 1.11145435e+03 1.13151404e+03 1.11934155e+03 1.15799548e+03 1.27947144e+03 1.33671936e+03 1.31053027e+03 1.35391919e+03 1.42645605e+03 1.47192188e+03 1.56884692e+03 1.57880908e+03 1.56800671e+03 1.66010339e+03 1.67069482e+03 1.75566492e+03 1.85484473e+03 1.80542920e+03 1.89163867e+03 1.99939392e+03 1.99429346e+03 2.03480359e+03 2.07861987e+03 2.13263306e+03 2.18687671e+03 2.22019263e+03 2.20809692e+03 2.24859863e+03 2.39522314e+03 2.51479199e+03 2.50926465e+03 2.43887329e+03 2.42577563e+03 2.51198193e+03 2.67901904e+03 2.80335327e+03 2.79001294e+03 2.68538525e+03 2.72853906e+03 2.87751611e+03 2.90697949e+03 2.91447388e+03 2.94907251e+03 2.99595752e+03 3.05082593e+03 3.19880396e+03 3.16218115e+03 3.10792480e+03 3.22879834e+03 3.18935181e+03 3.32828003e+03 3.44019458e+03 3.39320654e+03 3.54926318e+03 3.48683081e+03 3.40813184e+03 3.56148169e+03 3.51781055e+03 3.62866113e+03 3.91473291e+03 3.74825122e+03 3.58718604e+03 3.70220312e+03 3.91444043e+03 4.10825635e+03 4.05716187e+03 3.85290356e+03 3.79771680e+03 3.94351782e+03 4.17177393e+03 4.36051074e+03 4.29235352e+03 4.09636377e+03 4.10605273e+03 4.29302344e+03 4.39065723e+03 4.32367139e+03 4.30139014e+03 4.41286133e+03 4.48056592e+03 4.62132471e+03 4.66634082e+03 4.46733740e+03 4.50381396e+03 4.60120947e+03 4.65769287e+03 4.74934521e+03 4.75881104e+03 4.88543408e+03 4.85433691e+03 4.72885889e+03 4.84295605e+03 4.77339502e+03 4.95338574e+03 5.29870117e+03 5.04122656e+03 4.75848633e+03 4.91389600e+03 5.19954004e+03 5.39034375e+03 5.40077881e+03 5.15576709e+03 4.97313770e+03 5.09124121e+03 5.39889697e+03 5.64875879e+03 5.52912695e+03 5.24866016e+03 5.22237793e+03 5.39452002e+03 5.54670654e+03 5.71102100e+03 5.70876611e+03 5.43699805e+03 5.42069385e+03 5.72864941e+03 5.81898340e+03 5.63578955e+03 5.64132275e+03 5.65294873e+03 5.66186230e+03 5.95208008e+03 6.01029297e+03 5.73415967e+03 5.71712207e+03 5.82737451e+03 5.87821924e+03 5.95876758e+03 5.92992285e+03 6.11021826e+03 6.19055225e+03 6.00294678e+03 5.90757422e+03 5.81176074e+03 6.06945605e+03 6.45438281e+03 6.33964746e+03 6.00806738e+03 5.89084082e+03 6.15389600e+03 6.52715283e+03 6.32498730e+03 5.97219434e+03 6.11305518e+03 6.28114111e+03 6.46722803e+03 6.69303906e+03 6.54490527e+03 6.21118359e+03 6.08117920e+03 6.33523828e+03 6.57760986e+03 6.59027734e+03 6.48326025e+03 6.45272852e+03 6.45863818e+03 6.61931592e+03 6.57789648e+03 6.39839355e+03 6.36519971e+03 6.39535156e+03 6.71739307e+03 6.82477100e+03 6.59222363e+03 6.63441699e+03 6.67751465e+03 6.79641895e+03 6.68298730e+03 6.35953467e+03 6.63852295e+03 6.99354248e+03 6.85171387e+03 6.51921387e+03 6.56113867e+03 6.93885303e+03 6.97212354e+03 6.77795117e+03 6.78580518e+03 6.60508984e+03 6.63161035e+03 6.98499170e+03 6.97391357e+03 6.66794775e+03 6.54324854e+03 6.56038330e+03 6.89465576e+03 7.20333887e+03 6.88817871e+03 6.69116064e+03 6.83737109e+03 6.85352246e+03 7.07180127e+03 7.02650293e+03 6.59513428e+03 6.73178906e+03 6.92094287e+03 6.86812549e+03 6.90556934e+03 6.86154541e+03 7.09210889e+03 7.20494824e+03 6.97961963e+03 6.88171191e+03 6.32804688e+03 8.59198242e+03 9.93623828e+03 1.05838945e+04 1.00679443e+04 9.92029199e+03 1.03343535e+04 1.07467012e+04 1.12658340e+04 1.16009365e+04 1.03171621e+04 1.01761475e+04 1.95611426e+04 1.19849859e+05 53426952. 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. 0. 0. 0. 0. 0. 0. 0. 0. -51509072. -3.08721825e+06 -1.97736375e+06 2.18576973e+04 1.59871445e+04 7.19728223e+03 7.57354150e+03 6.86420410e+03 6.71597607e+03 6.42571973e+03 6.54215137e+03 6.35075928e+03 6.12813818e+03 6.27410840e+03 6.23687988e+03 6.38409521e+03 6.43097559e+03 5.84711328e+03 5.74666797e+03 5.84296289e+03 5.96731934e+03 5.87101709e+03 5.74545850e+03 6.11827246e+03 5.95969629e+03 5.76986279e+03 6.01129492e+03 5.94764941e+03 5.73749658e+03 5.89843506e+03 6.07117725e+03 5.89069629e+03 5.80733643e+03 5.73686719e+03 5.70011816e+03 5.62002783e+03 5.60206445e+03 5.70195557e+03 5.69414795e+03 5.57456396e+03 5.53680859e+03 5.52557764e+03 5.49495996e+03 5.43928711e+03 5.41105420e+03 5.39139990e+03 5.21128857e+03 5.16108936e+03 5.26968213e+03 5.23440479e+03 5.39810547e+03 5.38173145e+03 5.16425244e+03 4.98254980e+03 4.93564355e+03 5.23239941e+03 5.24358838e+03 5.01462402e+03 4.87154004e+03 4.85543359e+03 4.91103320e+03 4.83522510e+03 4.96347021e+03 4.93055322e+03 4.61599268e+03 4.53461475e+03 4.75433887e+03 4.89697119e+03 4.73325146e+03 4.59273877e+03 4.57665430e+03 4.53062891e+03 4.43017871e+03 4.42020459e+03 4.39426758e+03 4.32267871e+03 4.30987646e+03 4.27420117e+03 4.27615039e+03 4.23204150e+03 4.28422412e+03 4.23018604e+03 4.06393237e+03 4.07913672e+03 4.05629614e+03 4.04828613e+03 4.00940454e+03 3.93514111e+03 3.89511499e+03 3.77024756e+03 3.63955591e+03 3.78719580e+03 3.79729077e+03 3.55897754e+03 3.55123364e+03 3.71049951e+03 3.76697070e+03 3.60686353e+03 3.46874731e+03 3.42010962e+03 3.37660132e+03 3.30332837e+03 3.24988843e+03 3.27834277e+03 3.22412671e+03 3.25913623e+03 3.19402271e+03 3.06912109e+03 3.07463501e+03 2.94983911e+03 2.91020288e+03 3.02750073e+03 2.95687256e+03 2.84574170e+03 2.73904883e+03 2.65254590e+03 2.76051196e+03 2.76778369e+03 2.63152393e+03 2.50972974e+03 2.47129126e+03 2.48902539e+03 2.42969214e+03 2.46153906e+03 2.43774512e+03 2.30335376e+03 2.21381104e+03 2.17605029e+03 2.22154712e+03 2.17675488e+03 2.07290796e+03 2.00384839e+03 1.96222876e+03 1.94454700e+03 1.85004541e+03 1.80910938e+03 1.86475000e+03 1.80519543e+03 1.71325964e+03 1.62155017e+03 1.56285437e+03 1.61241040e+03 1.57469519e+03 1.48034741e+03 1.39602747e+03 1.34028784e+03 1.33344800e+03 1.28903589e+03 1.23926660e+03 1.16116589e+03 1.13957947e+03 1.14976221e+03 1.07242883e+03 1.01335339e+03 9.68155701e+02 9.13412170e+02 8.52416992e+02 8.02827026e+02 7.67219360e+02 7.19515442e+02 6.68714661e+02 6.04539551e+02 5.68737000e+02 5.52818481e+02 4.82063202e+02 4.19981506e+02 3.82639832e+02 3.33750885e+02 2.95930969e+02 2.42242233e+02 1.85943939e+02 1.46807068e+02 9.84202423e+01 4.76380997e+01 -2.31138206e+00 -5.14471321e+01 -1.00219109e+02 -1.47623825e+02 -1.94663971e+02 -2.34664108e+02 -2.87543915e+02 -3.55003418e+02 -3.95521820e+02 -4.30016907e+02 -4.63443024e+02 -5.16469421e+02 -5.99299683e+02 -6.45537720e+02 -6.74544495e+02 -7.03118042e+02 -7.45690857e+02 -8.17904785e+02 -8.64341187e+02 -9.30910400e+02 -9.60815918e+02 -9.76349670e+02 -1.05439624e+03 -1.10458411e+03 -1.17415613e+03 -1.21847351e+03 -1.23602832e+03 -1.28396436e+03 -1.32967615e+03 -1.39394543e+03 -1.40531140e+03 -1.46546838e+03 -1.59214648e+03 -1.60891357e+03 -1.61914868e+03 -1.62576416e+03 -1.65924536e+03 -1.79960339e+03 -1.85963367e+03 -1.85197656e+03 -1.84323816e+03 -1.88799023e+03 -1.99866748e+03 -2.04768311e+03 -2.13944751e+03 -2.15965112e+03 -2.15312524e+03 -2.17444775e+03 -2.20827344e+03 -2.37539526e+03 -2.40855737e+03 -2.37872290e+03 -2.41371362e+03 -2.46152905e+03 -2.58384619e+03 -2.62957690e+03 -2.56844043e+03 -2.60434717e+03 -2.77718237e+03 -2.81734644e+03 -2.73691870e+03 -2.76809131e+03 -2.95988477e+03 -3.01830054e+03 -2.96031641e+03 -2.93589551e+03 -2.97590649e+03 -3.19555640e+03 -3.21542798e+03 -3.16078589e+03 -3.22362305e+03 -3.25483521e+03 -3.30394751e+03 -3.33607935e+03 -3.37239429e+03 -3.33221484e+03 -3.46277246e+03 -3.69518921e+03 -3.62579443e+03 -3.62249097e+03 -3.69418774e+03 -3.70493774e+03 -3.74387427e+03 -3.77467896e+03 -3.80170435e+03 -3.74594922e+03 -3.73765845e+03 -3.86943921e+03 -3.99530029e+03 -4.17138037e+03 -4.06555591e+03 -3.95772754e+03 -4.09834521e+03 -4.18728662e+03 -4.34882861e+03 -4.31469238e+03 -4.24537402e+03 -4.25347900e+03 -4.24888916e+03 -4.37956982e+03 -4.43544727e+03 -4.55367725e+03 -4.58122021e+03 -4.51446533e+03 -4.49279297e+03 -4.39877686e+03 -4.62072803e+03 -4.91811523e+03 -4.86009863e+03 -4.74895850e+03 -4.66221436e+03 -4.62889502e+03 -4.90447363e+03 -5.08745801e+03 -4.97855518e+03 -4.81362305e+03 -4.84996777e+03 -5.01021973e+03 -5.03753027e+03 -5.21786816e+03 -5.21646387e+03 -5.09372217e+03 -5.15158740e+03 -5.17652344e+03 -5.30832422e+03 -5.36518115e+03 -5.16261719e+03 -5.20052197e+03 -5.52905420e+03 -5.43217822e+03 -5.18372705e+03 -5.40140576e+03 -5.73561816e+03 -5.65388086e+03 -5.52094385e+03 -5.42123047e+03 -5.46161719e+03 -5.79893896e+03 -5.82170605e+03 -5.67133105e+03 -5.56779297e+03 -5.55998242e+03 -5.75007910e+03 -5.79006445e+03 -5.81169775e+03 -5.69487939e+03 -5.84856934e+03 -6.14077441e+03 -5.99006006e+03 -6.01146240e+03 -6.02555615e+03 -5.91259814e+03 -6.00469043e+03 -6.05622754e+03 -6.05981445e+03 -6.04284717e+03 -6.01881982e+03 -5.93227051e+03 -6.10226807e+03 -6.46779053e+03 -6.18246387e+03 -5.96680518e+03 -6.15994775e+03 -6.28856152e+03 -6.51597266e+03 -6.40026025e+03 -6.23553760e+03 -6.42465625e+03 -6.47226074e+03 -6.17000293e+03 -6.16450049e+03 -6.51469727e+03 -6.59658301e+03 -6.42455273e+03 -6.30488232e+03 -6.14208691e+03 -6.44894580e+03 -6.84416553e+03 -6.70523389e+03 -6.49894482e+03 -6.35164648e+03 -6.34263916e+03 -6.65132959e+03 -6.93119092e+03 -6.70429443e+03 -6.43889258e+03 -6.39349365e+03 -6.57747168e+03 -6.68533398e+03 -6.88947412e+03 -6.73296582e+03 -6.56540674e+03 -6.73527148e+03 -6.72144971e+03 -6.84024756e+03 -6.80625488e+03 -6.69760449e+03 -6.75417871e+03 -6.73182666e+03 -6.72540479e+03 -6.54235107e+03 -6.65988281e+03 -7.11716846e+03 -6.97469873e+03 -6.73025684e+03 -6.59375830e+03 -6.65496826e+03 -7.07405713e+03 -7.03010352e+03 -6.82933887e+03 -6.68621436e+03 -6.61573438e+03 -6.87322168e+03 -6.85992578e+03 -6.88413379e+03 -6.72124561e+03 -6.83715869e+03 -7.12439355e+03 -6.96080859e+03 -6.97983691e+03 -6.99206250e+03 -6.84740625e+03 -6.82554834e+03 -6.81483887e+03 -6.82451318e+03 -6.83180469e+03 -6.85915967e+03 -6.85645166e+03 -6.99876855e+03 -7.02549854e+03 -6.72180176e+03 -6.59633838e+03 -6.81860645e+03 -6.96575635e+03 -7.09863916e+03 -6.95254150e+03 -6.58917480e+03 -6.91550488e+03 -7.09405371e+03 -6.87735449e+03 -6.72998145e+03 -6.69590381e+03 -6.82030664e+03 -6.86486768e+03 -6.78398389e+03 -6.56172363e+03 -6.74759521e+03 -7.11443408e+03 -6.93596289e+03 -6.82732324e+03 -6.64325928e+03 -6.59461914e+03 -6.97101221e+03 -6.91686426e+03 -6.73170166e+03 -6.57559424e+03 -6.41527100e+03 -6.59661670e+03 -6.80125830e+03 -7.03823242e+03 -6.70084180e+03 -6.40270264e+03 -6.61219482e+03 -6.67516797e+03 -6.85312061e+03 -6.72521924e+03 -6.45456299e+03 -6.63060059e+03 -6.61841943e+03 -6.45906250e+03 -6.29266650e+03 -6.50217090e+03 -6.78661768e+03 -6.61545508e+03 -6.52159814e+03 -6.36278516e+03 -6.27751172e+03 -6.61217285e+03 -6.61705908e+03 -6.38911084e+03 -6.23175928e+03 -6.17399609e+03 -6.33849170e+03 -6.30893750e+03 -6.43132031e+03 -6.45721631e+03 -6.21860107e+03 -6.09267334e+03 -6.14864258e+03 -6.44322754e+03 -6.25414844e+03 -6.05932812e+03 -6.16183301e+03 -6.14474268e+03 -6.01641455e+03 -5.90742773e+03 -6.13015479e+03 -6.09976416e+03 -5.90970117e+03 -6.12767285e+03 -6.14734277e+03 -5.97862793e+03 -5.92124268e+03 -5.88822314e+03 -5.86356689e+03 -5.70500293e+03 -5.60842920e+03 -5.88084424e+03 -5.94924463e+03 -5.59484863e+03 -5.40083008e+03 -5.63221094e+03 -5.93965234e+03 -5.83648242e+03 -5.51885254e+03 -5.36180371e+03 -5.61407031e+03 -5.67018213e+03 -5.48299170e+03 -5.49302393e+03 -5.31863232e+03 -5.12399072e+03 -5.31753271e+03 -5.51544629e+03 -5.45903418e+03 -5.21737842e+03 -5.03597803e+03 -5.26105762e+03 -5.40498877e+03 -5.20740771e+03 -4.95981787e+03 -4.87602002e+03 -5.00744873e+03 -4.99982520e+03 -5.09794531e+03 -5.05387061e+03 -4.82720850e+03 -4.85411572e+03 -4.86668115e+03 -4.90521533e+03 -4.72925781e+03 -4.60237109e+03 -4.77276465e+03 -4.73178320e+03 -4.65279834e+03 -4.49816748e+03 -4.50566455e+03 -4.72429297e+03 -4.50564502e+03 -4.29227246e+03 -4.36296484e+03 -4.42800244e+03 -4.39638867e+03 -4.30583984e+03 -4.36348486e+03 -4.36343652e+03 -4.20176074e+03 -4.04606372e+03 -3.99988574e+03 -4.17940771e+03 -4.07013965e+03 -3.90523438e+03 -4.00699268e+03 -3.97370166e+03 -3.86260376e+03 -3.78019067e+03 -3.86923267e+03 -3.80263574e+03 -3.65629419e+03 -3.71566968e+03 -3.68070459e+03 -3.66227295e+03 -3.62252661e+03 -3.53080713e+03 -3.45958325e+03 -3.33249854e+03 -3.27276855e+03 -3.38918677e+03 -3.47387671e+03 -3.26488525e+03 -3.06318018e+03 -3.14441724e+03 -3.28977002e+03 -3.22243970e+03 -3.02141089e+03 -2.87771191e+03 -2.97773291e+03 -3.02620337e+03 -2.88526343e+03 -2.88842676e+03 -2.82976880e+03 -2.67651587e+03 -2.65796240e+03 -2.71183203e+03 -2.68776978e+03 -2.53165601e+03 -2.42588794e+03 -2.49222290e+03 -2.55224219e+03 -2.44248389e+03 -2.29960986e+03 -2.21220679e+03 -2.27636279e+03 -2.30346289e+03 -2.17900415e+03 -2.08411035e+03 -2.05083960e+03 -2.04355786e+03 -1.98621484e+03 -1.99117163e+03 -1.90818237e+03 -1.79725757e+03 -1.81673328e+03 -1.77575562e+03 -1.73647278e+03 -1.65254565e+03 -1.57560950e+03 -1.59598682e+03 -1.55476135e+03 -1.55148108e+03 -1.43798413e+03 -1.41135693e+03 -1.91924707e+03 -1.92235437e+03 -1.91819617e+03 -1.85325940e+03 -1.34299341e+03 -1.10170227e+03 -9.79655090e+02 -1.11882874e+03 -1.36593665e+03 -1.37143469e+03 -1.33258215e+03 -1.44030066e+03 -1.69976855e+03 -7.92323779e+03 -141366320. 0. 0. 0. 0. 0. 0. 0. 0. -1.66598246e+10 6.77701250e+04 -3.87646523e+04 -2.55462148e+04 3.49749632e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.26456832e+09 -1.45109719e+05 1.04390778e+02 8.45376160e+02 1.08499231e+03 1.03082068e+03 9.54782410e+02 8.97944031e+02 7.84528320e+02 9.70905823e+02 9.58661926e+02 1.00396747e+03 1.03812268e+03 1.09413574e+03 1.17945374e+03 1.23152112e+03 1.22861523e+03 1.26159729e+03 1.34185559e+03 1.38990625e+03 1.42578442e+03 1.47141431e+03 1.50872791e+03 1.54877161e+03 1.63900903e+03 1.70391724e+03 1.67663647e+03 1.72006018e+03 1.83061804e+03 1.89148059e+03 1.92969202e+03 1.92998938e+03 1.94054626e+03 2.04609924e+03 2.10200854e+03 2.11285132e+03 2.14269360e+03 2.18546143e+03 2.29147510e+03 2.33213452e+03 2.33618066e+03 2.36281836e+03 2.42063647e+03 2.56392798e+03 2.60049976e+03 2.52178345e+03 2.56080347e+03 2.64934106e+03 2.70882837e+03 2.79334521e+03 2.81811011e+03 2.80413647e+03 2.89169360e+03 2.95052026e+03 2.98132471e+03 3.02995093e+03 3.01454590e+03 3.08297144e+03 3.17308228e+03 3.17486377e+03 3.20463306e+03 3.23128516e+03 3.29186694e+03 3.39642725e+03 3.44930322e+03 3.46553149e+03 3.43404102e+03 3.43995337e+03 3.58613403e+03 3.64731982e+03 3.59933252e+03 3.65595166e+03 3.70776904e+03 3.77752539e+03 3.88930273e+03 3.89295020e+03 3.82414771e+03 3.86038623e+03 4.01002856e+03 4.08040063e+03 4.00878760e+03 3.97463501e+03 4.06113745e+03 4.15528564e+03 4.29647412e+03 4.32036963e+03 4.19375488e+03 4.24980859e+03 4.40962988e+03 4.43607471e+03 4.43419238e+03 4.37968311e+03 4.39128711e+03 4.57941406e+03 4.64468311e+03 4.55300195e+03 4.59645215e+03 4.66937695e+03 4.70316748e+03 4.73094482e+03 4.75433398e+03 4.83544385e+03 4.86736084e+03 4.95872559e+03 4.99777490e+03 4.85139062e+03 4.87918506e+03 5.03763672e+03 5.02666455e+03 5.06139502e+03 5.09234570e+03 5.12953955e+03 5.24589990e+03 5.22078662e+03 5.18779297e+03 5.29724902e+03 5.38121631e+03 5.29667236e+03 5.30849756e+03 5.39303223e+03 5.44075049e+03 5.43273389e+03 5.40311133e+03 5.46345996e+03 5.52963232e+03 5.68708496e+03 5.68586621e+03 5.49741602e+03 5.55990723e+03 5.74171729e+03 5.75948047e+03 5.71921143e+03 5.68469580e+03 5.64556885e+03 5.80155273e+03 5.96557666e+03 5.88942480e+03 5.80012354e+03 5.81777295e+03 5.98782520e+03 6.06063525e+03 6.10098828e+03 5.98546729e+03 5.86130225e+03 5.99759082e+03 6.03954541e+03 6.05522510e+03 6.14553027e+03 6.07597168e+03 6.16169092e+03 6.35804688e+03 6.27375000e+03 6.04639014e+03 6.10104004e+03 6.25893604e+03 6.33876270e+03 6.40988428e+03 6.34310840e+03 6.22170898e+03 6.29606494e+03 6.52230664e+03 6.38934033e+03 6.20751758e+03 6.35543115e+03 6.54236768e+03 6.54168945e+03 6.44334033e+03 6.37616797e+03 6.39704883e+03 6.49390479e+03 6.50581055e+03 6.55312158e+03 6.64963867e+03 6.51832910e+03 6.57789893e+03 6.72811963e+03 6.59608643e+03 6.51635400e+03 6.60500049e+03 6.72561865e+03 6.72522754e+03 6.71085840e+03 6.59335840e+03 6.54455664e+03 6.66816797e+03 6.97376367e+03 6.98030225e+03 6.57244922e+03 6.59477881e+03 6.89516699e+03 6.86954883e+03 6.72575439e+03 6.69684375e+03 6.67968604e+03 6.81416699e+03 6.92232910e+03 6.81196289e+03 6.74877197e+03 6.67580859e+03 6.80598584e+03 6.96642822e+03 6.95819336e+03 6.80561572e+03 6.78134766e+03 6.87529492e+03 6.89209277e+03 6.83485596e+03 6.78588184e+03 6.81989062e+03 6.82136768e+03 6.98294873e+03 7.05272705e+03 6.72045654e+03 6.73579395e+03 6.91836816e+03 6.94921777e+03 6.93632178e+03 6.75959619e+03 6.84096777e+03 7.02646240e+03 6.88294580e+03 6.89540576e+03 6.75296777e+03 6.65626416e+03 6.85289893e+03 7.00126904e+03 6.87049170e+03 6.84952246e+03 6.89866016e+03 6.83049512e+03 6.94422607e+03 6.92324756e+03 6.71414648e+03 6.66376660e+03 6.70460596e+03 6.88765137e+03 6.85242627e+03 6.73627930e+03 6.73098193e+03 6.85591064e+03 6.87016748e+03 6.73448145e+03 6.65387158e+03 6.68283301e+03 6.77704150e+03 6.72552490e+03 6.89353418e+03 6.70886182e+03 6.57741406e+03 6.73337842e+03 6.58135889e+03 6.63200684e+03 6.71319336e+03 6.58275195e+03 6.56020801e+03 6.54110596e+03 6.58421631e+03 6.58796631e+03 6.42410107e+03 6.66334033e+03 6.76477637e+03 6.43410498e+03 6.37874365e+03 6.45828467e+03 6.46982568e+03 6.57798584e+03 6.48031787e+03 6.30652490e+03 6.35213574e+03 6.49871094e+03 6.43108643e+03 6.36797461e+03 6.27981885e+03 6.27046094e+03 6.34550879e+03 6.24594727e+03 6.20341699e+03 6.17031641e+03 6.13605957e+03 6.17808008e+03 6.26486768e+03 6.19210742e+03 6.06713867e+03 6.00510059e+03 6.13654932e+03 6.23836719e+03 5.98044141e+03 6.02464697e+03 6.04996045e+03 5.82439697e+03 5.95085645e+03 5.97970801e+03 5.84659521e+03 5.88854443e+03 5.88066260e+03 5.80507129e+03 5.89691406e+03 5.79038232e+03 5.66560352e+03 5.69710156e+03 5.73609521e+03 5.74247021e+03 5.54638525e+03 5.52739453e+03 5.59676562e+03 5.61689014e+03 5.58617920e+03 5.47707764e+03 5.38304932e+03 5.49848047e+03 5.59314111e+03 5.39846631e+03 5.26591895e+03 5.23694531e+03 5.34764795e+03 5.39689941e+03 5.20684131e+03 5.13206494e+03 5.15221680e+03 5.15094141e+03 5.09437793e+03 5.13606250e+03 5.04916260e+03 4.91269141e+03 4.99960498e+03 5.07794434e+03 4.93326416e+03 4.71737109e+03 4.73977100e+03 4.84507617e+03 4.82411670e+03 4.78411865e+03 4.70228760e+03 4.61129590e+03 4.69720801e+03 4.74555469e+03 4.57735303e+03 4.48607129e+03 4.47396387e+03 4.56095264e+03 4.47213037e+03 4.28270557e+03 4.26233154e+03 4.29139502e+03 4.28361279e+03 4.25281982e+03 4.23861719e+03 4.14532666e+03 4.12291748e+03 4.09058472e+03 3.97743555e+03 3.94237231e+03 3.89458301e+03 3.92844043e+03 3.95586108e+03 3.81680127e+03 3.71914697e+03 3.73221460e+03 3.76189600e+03 3.81557178e+03 3.74403540e+03 3.54165674e+03 3.50890210e+03 3.52332910e+03 3.47666455e+03 3.40200562e+03 3.36457446e+03 3.35481079e+03 3.32762842e+03 3.25600928e+03 3.14358789e+03 3.15664014e+03 3.19902441e+03 3.16433423e+03 3.07252783e+03 2.94966895e+03 2.93647778e+03 2.88057397e+03 2.81641602e+03 2.89097314e+03 2.84767163e+03 2.69751978e+03 2.64681152e+03 2.64444751e+03 2.67456201e+03 2.63840308e+03 2.54010107e+03 2.47281836e+03 2.42498096e+03 2.37235107e+03 2.31194922e+03 2.29965039e+03 2.26931519e+03 2.24396582e+03 2.18880566e+03 2.05639844e+03 2.04264355e+03 2.02315466e+03 1.97434985e+03 1.98406567e+03 1.88288489e+03 1.79571350e+03 1.81905310e+03 1.79773413e+03 1.71259253e+03 1.65531824e+03 1.59234827e+03 1.52716101e+03 1.49745105e+03 1.47097510e+03 1.42260828e+03 1.39832495e+03 1.36449304e+03 1.28910376e+03 1.21801306e+03 1.16449744e+03 1.14119360e+03 1.11871924e+03 1.05457068e+03 9.79670898e+02 9.30564514e+02 8.99589050e+02 8.74911804e+02 8.42321045e+02 7.69081604e+02 6.98871460e+02 6.60536194e+02 6.12491028e+02 5.61193604e+02 5.34856506e+02 4.90169952e+02 4.28158722e+02 3.79917694e+02 3.27855682e+02 2.84730103e+02 2.47287109e+02 1.98095413e+02 1.42544235e+02 9.09373779e+01 4.34180527e+01 -1.28038836e+00 -4.95254860e+01 -9.95598221e+01 -1.49826294e+02 -1.99145126e+02 -2.41652222e+02 -2.95347595e+02 -3.44777313e+02 -3.85566071e+02 -4.36863312e+02 -4.82401093e+02 -5.24970581e+02 -5.78026672e+02 -6.27471191e+02 -6.84308411e+02 -7.34045227e+02 -7.64220215e+02 -8.07979370e+02 -8.50025208e+02 -9.01326233e+02 -9.53706299e+02 -1.00919446e+03 -1.06297913e+03 -1.10778955e+03 -1.15069409e+03 -1.18168787e+03 -1.24158594e+03 -1.31791455e+03 -1.36153760e+03 -1.37666125e+03 -1.41798865e+03 -1.46942065e+03 -1.51554651e+03 -1.58080603e+03 -1.63689087e+03 -1.66274207e+03 -1.70386975e+03 -1.75007153e+03 -1.79470215e+03 -1.86327893e+03 -1.90147852e+03 -1.95042615e+03 -2.00425366e+03 -2.02253540e+03 -2.08423535e+03 -2.09999072e+03 -2.15079614e+03 -2.26887427e+03 -2.26849609e+03 -2.28067383e+03 -2.36655200e+03 -2.37986328e+03 -2.40397852e+03 -2.55384546e+03 -2.60454053e+03 -2.53445703e+03 -2.58124268e+03 -2.65925586e+03 -2.68355151e+03 -2.78344751e+03 -2.81979175e+03 -2.78032861e+03 -2.85600317e+03 -2.92716162e+03 -3.01161865e+03 -3.06711548e+03 -3.05060083e+03 -3.13196826e+03 -3.14148682e+03 -3.10316724e+03 -3.18909863e+03 -3.31675830e+03 -3.33366504e+03 -3.38799365e+03 -3.42643286e+03 -3.33216821e+03 -3.43109009e+03 -3.60766309e+03 -3.64720264e+03 -3.62328760e+03 -3.53113013e+03 -3.61024512e+03 -3.80578564e+03 -3.80990283e+03 -3.79705322e+03 -3.89410547e+03 -3.87894019e+03 -3.91493628e+03 -3.99426123e+03 -3.90431860e+03 -3.96581226e+03 -4.12401660e+03 -4.20906738e+03 -4.18925244e+03 -4.09654395e+03 -4.13998730e+03 -4.29181738e+03 -4.39696777e+03 -4.38778906e+03 -4.32536914e+03 -4.31171875e+03 -4.41640527e+03 -4.54329346e+03 -4.65344824e+03 -4.62242773e+03 -4.53916748e+03 -4.61803760e+03 -4.64010010e+03 -4.67532568e+03 -4.77016064e+03 -4.75369629e+03 -4.81692432e+03 -4.92241016e+03 -4.87116211e+03 -4.87820605e+03 -4.97116064e+03 -4.98753320e+03 -5.05635254e+03 -5.05000732e+03 -4.99255371e+03 -5.04409814e+03 -5.16390723e+03 -5.27975342e+03 -5.32064453e+03 -5.23391797e+03 -5.16362207e+03 -5.26514551e+03 -5.28027637e+03 -5.33664844e+03 -5.47935986e+03 -5.40381885e+03 -5.35413477e+03 -5.40843457e+03 -5.47701416e+03 -5.58526904e+03 -5.71036963e+03 -5.67730908e+03 -5.62780371e+03 -5.59172119e+03 -5.50792432e+03 -5.62819629e+03 -5.77986523e+03 -5.84890869e+03 -5.85963330e+03 -5.72187207e+03 -5.71846973e+03 -5.85446045e+03 -5.94836816e+03 -5.93313818e+03 -5.95933154e+03 -5.92739648e+03 -5.85362695e+03 -5.99491162e+03 -6.14261523e+03 -6.10507129e+03 -5.98999756e+03 -6.05067676e+03 -6.10501807e+03 -6.17523486e+03 -6.22520752e+03 -6.16617969e+03 -6.29105957e+03 -6.19739551e+03 -6.16024951e+03 -6.32221777e+03 -6.32609961e+03 -6.29712695e+03 -6.45934326e+03 -6.39922314e+03 -6.26294824e+03 -6.38721729e+03 -6.49367090e+03 -6.51567773e+03 -7.20593164e+03 -7.14987598e+03 -7.56816064e+03 -6.88743115e+03 -1.42250107e+04 -1.89101973e+04 -6.08099950e+06 -2534636. -1.44473775e+06 -1.63376012e+06 -8694040. -3.98597750e+05 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6806928. 2.10658975e+06 -2.72596367e+04 -1.30791250e+04 -7.43235156e+03 -6.80496387e+03 -6.52766650e+03 -7.53331885e+03 -7.40609326e+03 -6.74847559e+03 -6.82033887e+03 -7.08126758e+03 -6.97278271e+03 -6.81261523e+03 -6.74034814e+03 -6.63236963e+03 -6.95597363e+03 -7.15379150e+03 -6.85460889e+03 -6.58036865e+03 -6.62597168e+03 -6.77015137e+03 -6.85708545e+03 -6.95974512e+03 -6.71435254e+03 -6.59191895e+03 -6.76557666e+03 -6.77276514e+03 -6.76401904e+03 -6.64390918e+03 -6.58270117e+03 -6.81759375e+03 -6.95644824e+03 -6.77521631e+03 -6.41832861e+03 -6.47411816e+03 -6.71121045e+03 -6.75932861e+03 -6.62934912e+03 -6.43934766e+03 -6.48212549e+03 -6.67865771e+03 -6.81305371e+03 -6.64725635e+03 -6.30444971e+03 -6.40830469e+03 -6.68134961e+03 -6.57794092e+03 -6.60901514e+03 -6.48983105e+03 -6.22516650e+03 -6.36828711e+03 -6.51014746e+03 -6.40491016e+03 -6.32324121e+03 -6.45328418e+03 -6.45139160e+03 -6.40722119e+03 -6.28062354e+03 -6.03217139e+03 -6.17493555e+03 -6.51777002e+03 -6.33809863e+03 -6.09189307e+03 -6.00163330e+03 -5.99713525e+03 -6.28754688e+03 -6.40251074e+03 -6.16839893e+03 -5.99434619e+03 -5.96021680e+03 -5.91086621e+03 -6.03688379e+03 -6.20187109e+03 -5.95643408e+03 -5.83858691e+03 -5.97610547e+03 -5.90000146e+03 -5.77366309e+03 -5.77766797e+03 -5.86082031e+03 -5.93279004e+03 -5.83520947e+03 -5.80123633e+03 -5.62537354e+03 -5.46063330e+03 -5.73748047e+03 -5.87712695e+03 -5.55436816e+03 -5.34490869e+03 -5.47803027e+03 -5.59115332e+03 -5.61410889e+03 -5.64453320e+03 -5.41954932e+03 -5.29612744e+03 -5.40606787e+03 -5.38048389e+03 -5.35269336e+03 -5.28735693e+03 -5.16295410e+03 -5.15147266e+03 -5.23327295e+03 -5.24447168e+03 -5.14489111e+03 -5.13191211e+03 -5.12878027e+03 -5.06428467e+03 -5.02601465e+03 -4.86278174e+03 -4.82319971e+03 -5.05280176e+03 -5.04048389e+03 -4.73964893e+03 -4.62306104e+03 -4.66674512e+03 -4.85793164e+03 -4.93732227e+03 -4.72459766e+03 -4.49644092e+03 -4.47807227e+03 -4.51652100e+03 -4.53429004e+03 -4.53241455e+03 -4.45495605e+03 -4.42677637e+03 -4.37127344e+03 -4.32493555e+03 -4.31407178e+03 -4.19994775e+03 -4.21143359e+03 -4.31377930e+03 -4.22241553e+03 -4.09015234e+03 -4.00626709e+03 -3.93331812e+03 -4.05533350e+03 -4.11726416e+03 -3.89209985e+03 -3.75543091e+03 -3.77754517e+03 -3.89143335e+03 -3.91546802e+03 -3.74936743e+03 -3.61345190e+03 -3.56685376e+03 -3.55764258e+03 -3.60433325e+03 -3.60415796e+03 -3.43384009e+03 -3.30856372e+03 -3.37340332e+03 -3.43263550e+03 -3.36096094e+03 -3.26336206e+03 -3.21859399e+03 -3.18128784e+03 -3.16782544e+03 -3.12244604e+03 -3.00528369e+03 -2.94325684e+03 -2.97448462e+03 -2.97333154e+03 -2.89211670e+03 -2.77598755e+03 -2.76635767e+03 -2.76417920e+03 -2.71919458e+03 -2.70607129e+03 -2.59571045e+03 -2.56749902e+03 -2.56612451e+03 -2.48515088e+03 -2.43783057e+03 -2.36059351e+03 -2.31415430e+03 -2.32273413e+03 -2.32875806e+03 -2.26371948e+03 -2.11146143e+03 -2.04765442e+03 -2.09346265e+03 -2.10897852e+03 -2.02770447e+03 -1.88855933e+03 -1.83223865e+03 -1.84085059e+03 -1.82760400e+03 -1.78471985e+03 -1.68284656e+03 -1.60830359e+03 -1.59253247e+03 -1.57736389e+03 -1.54735364e+03 -1.48040356e+03 -1.41636829e+03 -1.37439197e+03 -1.33045190e+03 -1.29166272e+03 -1.24772290e+03 -1.20558203e+03 -1.14526123e+03 -1.07578809e+03 -1.01707831e+03 -9.72457947e+02 -9.59595947e+02 -9.45630005e+02 -8.84042175e+02 -7.98615295e+02 -7.26655579e+02 -6.91003784e+02 -6.86701355e+02 -6.54710266e+02 -5.84323364e+02 -5.14372437e+02 -4.56109528e+02 -4.19307556e+02 -3.86298798e+02 -3.38154358e+02 -2.87095947e+02 -2.37891693e+02 -1.89074112e+02 -1.42216995e+02 -9.46948318e+01 -5.00596657e+01 -3.61094499e+00 4.75256805e+01 1.00661453e+02 1.51241150e+02 1.89220215e+02 2.38117844e+02 2.91182343e+02 3.37492035e+02 3.87860504e+02 4.32876190e+02 4.91367767e+02 5.43274170e+02 5.65016785e+02 5.94613464e+02 6.53123718e+02 7.35177856e+02 8.10423157e+02 8.42812744e+02 8.44785034e+02 8.66074829e+02 9.28106628e+02 1.02236475e+03 1.10254846e+03 1.12857373e+03 1.12006580e+03 1.15804797e+03 1.27102429e+03 1.32904431e+03 1.31257434e+03 1.35700964e+03 1.42412976e+03 1.46527124e+03 1.56546484e+03 1.58413611e+03 1.57043750e+03 1.65745728e+03 1.66887708e+03 1.75117017e+03 1.85040332e+03 1.81312708e+03 1.88697778e+03 1.98466748e+03 1.99039636e+03 2.03310657e+03 2.08125342e+03 2.13429297e+03 2.18799316e+03 2.20801611e+03 2.18822705e+03 2.24323657e+03 2.40980103e+03 2.51629468e+03 2.50062524e+03 2.43842554e+03 2.41513306e+03 2.50383130e+03 2.67263770e+03 2.79215820e+03 2.77940747e+03 2.68041064e+03 2.72301367e+03 2.86461523e+03 2.89362402e+03 2.91553687e+03 2.95205981e+03 2.99502686e+03 3.05236475e+03 3.19878223e+03 3.15295044e+03 3.10454346e+03 3.21965039e+03 3.16304028e+03 3.31420703e+03 3.46388184e+03 3.38800024e+03 3.53284912e+03 3.48905786e+03 3.39342285e+03 3.55048340e+03 3.52362817e+03 3.62361182e+03 3.90674658e+03 3.74820776e+03 3.58012915e+03 3.69014233e+03 3.90931396e+03 4.10332275e+03 4.05799292e+03 3.88009058e+03 3.82529175e+03 3.90695776e+03 4.12273096e+03 4.32635596e+03 4.27966602e+03 4.11859961e+03 4.10842822e+03 4.28408984e+03 4.35835791e+03 4.32170508e+03 4.33328174e+03 4.38637598e+03 4.44941455e+03 4.62464551e+03 4.67612598e+03 4.46281738e+03 4.46725928e+03 4.59620605e+03 4.64061328e+03 4.71947949e+03 4.73927002e+03 4.90778564e+03 4.82300732e+03 4.69160596e+03 4.89301367e+03 4.78328516e+03 4.91646680e+03 5.28170361e+03 5.04390723e+03 4.75997607e+03 4.92420605e+03 5.20041602e+03 5.36861328e+03 5.36542773e+03 5.11831006e+03 4.96058301e+03 5.10209961e+03 5.40151318e+03 5.62929053e+03 5.50958105e+03 5.22122559e+03 5.21799902e+03 5.42663623e+03 5.53723389e+03 5.70149414e+03 5.72999268e+03 5.42430566e+03 5.39228027e+03 5.68130566e+03 5.77798975e+03 5.61984082e+03 5.62043213e+03 5.69013916e+03 5.67471094e+03 5.92369922e+03 5.99091748e+03 5.72953223e+03 5.74748193e+03 5.84409277e+03 5.84777979e+03 5.92509570e+03 5.91967480e+03 6.07966406e+03 6.15246729e+03 6.00614307e+03 5.89271045e+03 5.80718701e+03 6.09025586e+03 6.42151953e+03 6.31376660e+03 6.02849707e+03 5.90211182e+03 6.13643408e+03 6.47444189e+03 6.29730811e+03 5.96131543e+03 6.10847998e+03 6.32057178e+03 6.45911426e+03 6.70660107e+03 6.57412402e+03 6.21670752e+03 6.09383838e+03 6.29931201e+03 6.53025000e+03 6.55086670e+03 6.46262354e+03 6.43792822e+03 6.47471436e+03 6.61120508e+03 6.54910156e+03 6.37319971e+03 6.44607568e+03 6.40715967e+03 6.68880762e+03 6.84866064e+03 6.61453760e+03 6.63960889e+03 6.68583057e+03 6.67490820e+03 6.58603320e+03 6.39706201e+03 6.70908105e+03 7.02795605e+03 6.84048193e+03 6.51999414e+03 6.52575000e+03 6.88633594e+03 6.99170703e+03 6.85054443e+03 6.79148242e+03 6.57711621e+03 6.56134619e+03 6.90211914e+03 6.92415869e+03 6.74992285e+03 6.59559082e+03 6.53183936e+03 6.93699414e+03 7.17158545e+03 6.79507178e+03 6.66063867e+03 6.81511426e+03 6.84304785e+03 7.02613330e+03 7.05996924e+03 6.67280908e+03 6.64732910e+03 6.79768506e+03 6.86059277e+03 7.00538379e+03 7.13834082e+03 7.22035889e+03 6.97805615e+03 6.78423730e+03 6.78779834e+03 8.13154346e+03 1.53236055e+04 2.18090742e+04 -5.83206950e+06 1.61249675e+06 -2.18745225e+06 -9317552. -10302088. -29288174. -1705541. 2.71037375e+06 -3.11176925e+06 3000966. -50659216. 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. 0. 0. 0. 0. 0. 0. 0. 50713344. -4564874. 2.49077188e+04 1.79988711e+04 1.13084893e+04 1.01870723e+04 9.80600098e+03 8.72073730e+03 8.34929004e+03 6.93969141e+03 6.64865625e+03 6.41987061e+03 6.52384766e+03 6.32834473e+03 6.13545654e+03 6.27633301e+03 6.26969727e+03 6.37425684e+03 6.40684326e+03 5.84975293e+03 5.75860498e+03 5.84183105e+03 5.95054980e+03 5.92953809e+03 5.78179736e+03 6.13394727e+03 5.97416211e+03 5.80780469e+03 6.04403223e+03 5.99890771e+03 5.74981104e+03 5.89432031e+03 6.04883936e+03 5.87862207e+03 5.79772070e+03 5.73913525e+03 5.69170508e+03 5.54017236e+03 5.51052393e+03 5.73945264e+03 5.74613574e+03 5.54064258e+03 5.52311963e+03 5.50091553e+03 5.49263574e+03 5.43166309e+03 5.38405078e+03 5.39441748e+03 5.26005078e+03 5.20843115e+03 5.24178174e+03 5.19664209e+03 5.36418262e+03 5.36574023e+03 5.17636670e+03 4.98906982e+03 4.92999170e+03 5.19707715e+03 5.21630469e+03 5.00512500e+03 4.86814941e+03 4.86873877e+03 4.90724023e+03 4.84040625e+03 4.95727393e+03 4.91854004e+03 4.61615430e+03 4.52716357e+03 4.74195020e+03 4.88670801e+03 4.72310889e+03 4.58523438e+03 4.55170410e+03 4.49611865e+03 4.46675830e+03 4.43744043e+03 4.43840869e+03 4.38832617e+03 4.28827197e+03 4.25292871e+03 4.24488037e+03 4.19314648e+03 4.29372412e+03 4.24562939e+03 4.07826074e+03 4.03845239e+03 3.99628125e+03 4.08798535e+03 4.06438037e+03 3.91371875e+03 3.88244482e+03 3.76403345e+03 3.66958862e+03 3.80781421e+03 3.75592847e+03 3.52012427e+03 3.52988672e+03 3.69722900e+03 3.78022168e+03 3.62554907e+03 3.45976367e+03 3.39041821e+03 3.35453516e+03 3.32914307e+03 3.28694946e+03 3.25629419e+03 3.19424292e+03 3.24166162e+03 3.19246558e+03 3.06896899e+03 3.04233423e+03 2.90680591e+03 2.92611206e+03 3.06169604e+03 2.95682910e+03 2.84209302e+03 2.71881421e+03 2.65967700e+03 2.78115649e+03 2.74293384e+03 2.60849268e+03 2.51061011e+03 2.45943555e+03 2.47371118e+03 2.42265894e+03 2.45518628e+03 2.43337329e+03 2.30277295e+03 2.23723486e+03 2.19853076e+03 2.19310693e+03 2.14974072e+03 2.07486475e+03 2.00336047e+03 1.96740930e+03 1.93218420e+03 1.83008997e+03 1.82480640e+03 1.88085315e+03 1.80479041e+03 1.71275183e+03 1.62294336e+03 1.56640869e+03 1.60923926e+03 1.56781409e+03 1.47402930e+03 1.39065344e+03 1.34059985e+03 1.34018164e+03 1.28527417e+03 1.23414404e+03 1.16284961e+03 1.13903394e+03 1.14923096e+03 1.07617175e+03 1.01612805e+03 9.70674255e+02 9.14900818e+02 8.53328247e+02 8.05966248e+02 7.65270325e+02 7.15219177e+02 6.72694275e+02 6.06595398e+02 5.66372131e+02 5.53176880e+02 4.82072845e+02 4.18704803e+02 3.81215271e+02 3.33000366e+02 2.94340729e+02 2.44018753e+02 1.89264282e+02 1.46711517e+02 9.81163483e+01 4.74696503e+01 -1.28041339e+00 -4.95866356e+01 -9.55831299e+01 -1.40713684e+02 -1.88802307e+02 -2.32301132e+02 -2.88110626e+02 -3.54423218e+02 -3.95212067e+02 -4.27472168e+02 -4.58523376e+02 -5.11962219e+02 -5.95435791e+02 -6.42612671e+02 -6.70833252e+02 -7.02387695e+02 -7.44661804e+02 -8.14208130e+02 -8.62746155e+02 -9.28031311e+02 -9.66812378e+02 -9.83892456e+02 -1.03824377e+03 -1.08698059e+03 -1.17057678e+03 -1.21500220e+03 -1.22760962e+03 -1.27782007e+03 -1.32417029e+03 -1.36970496e+03 -1.38281824e+03 -1.46793616e+03 -1.60588928e+03 -1.61449988e+03 -1.61442004e+03 -1.62036938e+03 -1.65354407e+03 -1.79487830e+03 -1.85994495e+03 -1.85268030e+03 -1.84373120e+03 -1.88449939e+03 -1.99351685e+03 -2.03889661e+03 -2.13046777e+03 -2.18381934e+03 -2.17406250e+03 -2.15048975e+03 -2.18745435e+03 -2.37426318e+03 -2.41039087e+03 -2.38081934e+03 -2.39042480e+03 -2.42646899e+03 -2.60138696e+03 -2.65487402e+03 -2.55401440e+03 -2.59230078e+03 -2.77573853e+03 -2.82113306e+03 -2.72998120e+03 -2.76853540e+03 -2.95241504e+03 -3.01368604e+03 -2.95904395e+03 -2.93067822e+03 -2.98108276e+03 -3.17882642e+03 -3.18863550e+03 -3.13665112e+03 -3.22798755e+03 -3.25605200e+03 -3.29543018e+03 -3.34032471e+03 -3.36843457e+03 -3.33374707e+03 -3.45498633e+03 -3.65325122e+03 -3.59767334e+03 -3.65468628e+03 -3.71218896e+03 -3.68945068e+03 -3.73182617e+03 -3.75510498e+03 -3.77613062e+03 -3.75521924e+03 -3.78809888e+03 -3.90490698e+03 -3.95623779e+03 -4.11199658e+03 -4.03248071e+03 -3.94255322e+03 -4.09522363e+03 -4.17786670e+03 -4.34773975e+03 -4.31789648e+03 -4.22422607e+03 -4.23138232e+03 -4.24997461e+03 -4.38295654e+03 -4.41956152e+03 -4.54058203e+03 -4.57329883e+03 -4.49954492e+03 -4.51620459e+03 -4.42546338e+03 -4.59162256e+03 -4.88957764e+03 -4.85184033e+03 -4.76133301e+03 -4.65712256e+03 -4.61919873e+03 -4.88025000e+03 -5.06743799e+03 -4.97472314e+03 -4.81876270e+03 -4.84566943e+03 -4.97878027e+03 -5.03493457e+03 -5.19636768e+03 -5.19066650e+03 -5.10231885e+03 -5.10729053e+03 -5.11938037e+03 -5.37569531e+03 -5.41582617e+03 -5.14476367e+03 -5.17072510e+03 -5.50169531e+03 -5.46936670e+03 -5.21299512e+03 -5.34538574e+03 -5.65554541e+03 -5.64974902e+03 -5.54445410e+03 -5.41620947e+03 -5.44485205e+03 -5.77190674e+03 -5.80859424e+03 -5.68168457e+03 -5.59274023e+03 -5.53806055e+03 -5.68903711e+03 -5.81921875e+03 -5.81983545e+03 -5.65910449e+03 -5.82003418e+03 -6.11533740e+03 -5.96142236e+03 -5.99550635e+03 -6.01454248e+03 -5.91818164e+03 -5.98529688e+03 -6.04785742e+03 -6.06922754e+03 -6.04259570e+03 -5.97993848e+03 -5.87936816e+03 -6.11509668e+03 -6.44677002e+03 -6.12686963e+03 -5.90141113e+03 -6.14644043e+03 -6.34117139e+03 -6.54191895e+03 -6.40412207e+03 -6.23796582e+03 -6.38704150e+03 -6.41983301e+03 -6.23686768e+03 -6.18076758e+03 -6.46759424e+03 -6.50570508e+03 -6.35531055e+03 -6.32335742e+03 -6.16150537e+03 -6.40281592e+03 -6.83851416e+03 -6.67341455e+03 -6.48669727e+03 -6.35081299e+03 -6.30544141e+03 -6.63601709e+03 -6.91139307e+03 -6.72846924e+03 -6.48022852e+03 -6.47532227e+03 -6.56743262e+03 -6.60706201e+03 -6.78698779e+03 -6.73859912e+03 -6.55117480e+03 -6.65375732e+03 -6.60904590e+03 -6.89456152e+03 -6.85513037e+03 -6.67541406e+03 -6.70324463e+03 -6.71445166e+03 -6.77183838e+03 -6.62273193e+03 -6.63709229e+03 -6.94789404e+03 -6.93596533e+03 -6.80600781e+03 -6.62276709e+03 -6.66395703e+03 -7.07725928e+03 -7.04334668e+03 -6.83299756e+03 -6.70722266e+03 -6.69130225e+03 -6.77517383e+03 -6.78919922e+03 -6.88877588e+03 -6.73043604e+03 -6.81332959e+03 -7.05689795e+03 -6.87556738e+03 -7.01905566e+03 -7.05514258e+03 -6.86735840e+03 -6.85336084e+03 -6.77722168e+03 -6.87588428e+03 -6.85108887e+03 -6.79474756e+03 -6.75781885e+03 -7.01079297e+03 -7.02962354e+03 -6.67474365e+03 -6.59207715e+03 -6.78360156e+03 -6.90400391e+03 -7.09180225e+03 -6.97755420e+03 -6.68977979e+03 -6.85820459e+03 -7.00783691e+03 -6.87262793e+03 -6.78134668e+03 -6.76683740e+03 -6.73215039e+03 -6.67969873e+03 -6.83277734e+03 -6.69394824e+03 -6.73320654e+03 -7.05341113e+03 -6.93369580e+03 -6.78848828e+03 -6.62490967e+03 -6.61190479e+03 -6.91369482e+03 -6.87441895e+03 -6.77320557e+03 -6.60863281e+03 -6.41816357e+03 -6.56325830e+03 -6.80153711e+03 -7.02117480e+03 -6.76086279e+03 -6.50970947e+03 -6.55616650e+03 -6.60348291e+03 -6.83843896e+03 -6.77960498e+03 -6.53084326e+03 -6.49214697e+03 -6.43958789e+03 -6.52456299e+03 -6.42069824e+03 -6.44414160e+03 -6.71294971e+03 -6.59342920e+03 -6.50726660e+03 -6.35063281e+03 -6.26569824e+03 -6.63163281e+03 -6.60436182e+03 -6.38274609e+03 -6.22595068e+03 -6.16237891e+03 -6.30699219e+03 -6.29021777e+03 -6.49086768e+03 -6.49029688e+03 -6.23806494e+03 -6.02633789e+03 -6.12634863e+03 -6.44599854e+03 -6.31479053e+03 -6.12229834e+03 -6.08071045e+03 -6.03261133e+03 -6.03059668e+03 -5.94581543e+03 -6.07472754e+03 -6.04185596e+03 -5.89930859e+03 -6.10233838e+03 -6.14565674e+03 -5.99471436e+03 -5.91445557e+03 -5.85744873e+03 -5.85343018e+03 -5.67847803e+03 -5.59928027e+03 -5.87926318e+03 -5.92977686e+03 -5.56918457e+03 -5.43856836e+03 -5.68904395e+03 -5.87112695e+03 -5.76745459e+03 -5.51639404e+03 -5.36452539e+03 -5.56657568e+03 -5.64726270e+03 -5.50691162e+03 -5.48677100e+03 -5.30718652e+03 -5.06513916e+03 -5.26385840e+03 -5.56027539e+03 -5.51004883e+03 -5.18619971e+03 -5.00079053e+03 -5.26345752e+03 -5.39647998e+03 -5.19281787e+03 -4.99795898e+03 -4.91393945e+03 -4.96249219e+03 -4.97720850e+03 -5.11593164e+03 -5.08834326e+03 -4.88620020e+03 -4.79067334e+03 -4.76745850e+03 -4.91809131e+03 -4.78289551e+03 -4.61989062e+03 -4.79096826e+03 -4.74821777e+03 -4.65056494e+03 -4.52313281e+03 -4.44651660e+03 -4.65765186e+03 -4.49756738e+03 -4.30125049e+03 -4.37695703e+03 -4.41942334e+03 -4.39549707e+03 -4.30287500e+03 -4.36137256e+03 -4.35455957e+03 -4.19531152e+03 -4.03720874e+03 -3.98564307e+03 -4.18056055e+03 -4.09366235e+03 -3.94157104e+03 -3.93199805e+03 -3.88214233e+03 -3.91537866e+03 -3.86138599e+03 -3.84268311e+03 -3.77268213e+03 -3.65007935e+03 -3.73616724e+03 -3.71155298e+03 -3.62642554e+03 -3.58619971e+03 -3.52303613e+03 -3.45408643e+03 -3.32349219e+03 -3.27006812e+03 -3.39673120e+03 -3.47612842e+03 -3.26621313e+03 -3.07669873e+03 -3.17555518e+03 -3.27006055e+03 -3.18765771e+03 -3.01192090e+03 -2.90200195e+03 -3.01002515e+03 -2.98057275e+03 -2.83548242e+03 -2.90721655e+03 -2.84195117e+03 -2.65052344e+03 -2.64362842e+03 -2.73786279e+03 -2.71805347e+03 -2.53278760e+03 -2.41970215e+03 -2.50432129e+03 -2.55672559e+03 -2.44087769e+03 -2.29479468e+03 -2.20957861e+03 -2.28390552e+03 -2.28096631e+03 -2.15682666e+03 -2.12722559e+03 -2.10003174e+03 -2.02318530e+03 -1.95742310e+03 -1.98136182e+03 -1.90580127e+03 -1.79395776e+03 -1.81222290e+03 -1.78184949e+03 -1.74011597e+03 -1.65629614e+03 -1.57616614e+03 -1.64067200e+03 -1.64949487e+03 -1.51986707e+03 -1.48610376e+03 -2.04819702e+03 -4.02246191e+03 -5.01722314e+03 2.50389469e+05 -3.54541531e+05 -2.32719751e+03 -1.70169580e+03 -1.42297595e+03 -1.74614392e+03 -2.72689014e+03 -3.48958911e+03 1.97084156e+05 -1.57085412e+06 1.12451875e+06 -3.92171844e+05 -107829184. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.26456832e+09 -1.45109719e+05 1.04390778e+02 8.45376160e+02 1.08499231e+03 1.24765161e+03 1.24231726e+03 8.92421875e+02 6.86639465e+02 9.30568298e+02 1.08135767e+03 1.03844067e+03 1.06251831e+03 1.09811340e+03 1.14494824e+03 1.19125500e+03 1.23915430e+03 1.27837671e+03 1.31732642e+03 1.39306812e+03 1.45089941e+03 1.48152686e+03 1.52476782e+03 1.51996912e+03 1.57066699e+03 1.67372412e+03 1.69967297e+03 1.72436707e+03 1.82399573e+03 1.91969666e+03 1.91226184e+03 1.91401807e+03 1.95704822e+03 1.98345728e+03 2.06672632e+03 2.16825415e+03 2.17604956e+03 2.20604077e+03 2.30068701e+03 2.31448901e+03 2.29915527e+03 2.36498047e+03 2.41588623e+03 2.47006128e+03 2.56575244e+03 2.56347461e+03 2.58706738e+03 2.68129956e+03 2.69344482e+03 2.71331104e+03 2.74824561e+03 2.81406812e+03 2.89523828e+03 2.94742993e+03 3.03498535e+03 3.01990942e+03 2.99961719e+03 3.11956226e+03 3.09738843e+03 3.09156860e+03 3.23487231e+03 3.27665015e+03 3.29487549e+03 3.39097192e+03 3.42237305e+03 3.40112866e+03 3.44139819e+03 3.46429565e+03 3.48467529e+03 3.58935864e+03 3.66466089e+03 3.71014575e+03 3.75167896e+03 3.76303589e+03 3.77334570e+03 3.80782788e+03 3.89018091e+03 3.90665405e+03 3.94812549e+03 4.11698340e+03 4.06954736e+03 3.94857837e+03 4.09184375e+03 4.13276758e+03 4.12837891e+03 4.26970459e+03 4.27737061e+03 4.26500977e+03 4.42014209e+03 4.49854590e+03 4.41356494e+03 4.35756104e+03 4.39013672e+03 4.46936914e+03 4.57663574e+03 4.62852979e+03 4.69104492e+03 4.74538477e+03 4.74451514e+03 4.68222949e+03 4.66650488e+03 4.82022510e+03 4.86555469e+03 4.81328955e+03 4.95069824e+03 4.94811230e+03 4.94108984e+03 5.07747852e+03 5.00874561e+03 4.92551514e+03 5.01937646e+03 5.18777393e+03 5.24705127e+03 5.18411377e+03 5.25051318e+03 5.33158350e+03 5.35733398e+03 5.36456445e+03 5.26858301e+03 5.27485742e+03 5.47718457e+03 5.50898145e+03 5.44006738e+03 5.52571094e+03 5.47734375e+03 5.47608496e+03 5.63599902e+03 5.63014111e+03 5.53379883e+03 5.62458447e+03 5.80112158e+03 5.83785498e+03 5.76967139e+03 5.65436035e+03 5.65181689e+03 5.84033789e+03 5.94348779e+03 5.83693945e+03 5.83242188e+03 6.03412695e+03 6.07452783e+03 6.01169629e+03 5.99189746e+03 5.85566162e+03 5.85818359e+03 5.99100049e+03 6.12866846e+03 6.13438086e+03 6.12480469e+03 6.23711426e+03 6.24822119e+03 6.15172412e+03 6.08694092e+03 6.11533643e+03 6.22906689e+03 6.36175293e+03 6.46560938e+03 6.41063477e+03 6.34465771e+03 6.22356396e+03 6.34224707e+03 6.42517529e+03 6.24566113e+03 6.29466748e+03 6.49657764e+03 6.60138818e+03 6.45801758e+03 6.40673340e+03 6.42373535e+03 6.36094336e+03 6.50713916e+03 6.67846436e+03 6.65880078e+03 6.56536719e+03 6.56902441e+03 6.61650049e+03 6.53770068e+03 6.52848877e+03 6.57535693e+03 6.58902832e+03 6.81338916e+03 6.87202930e+03 6.59310791e+03 6.56058301e+03 6.63887744e+03 6.75725537e+03 6.84488232e+03 6.57941748e+03 6.55156250e+03 6.82238428e+03 6.89510303e+03 6.74874756e+03 6.75872803e+03 6.72670361e+03 6.64985938e+03 6.80020947e+03 6.94649512e+03 6.78152832e+03 6.69758105e+03 6.88422900e+03 7.01089648e+03 6.86592285e+03 6.79904443e+03 6.77323389e+03 6.76235205e+03 6.95139160e+03 6.87423389e+03 6.78789062e+03 6.90993506e+03 6.85191650e+03 6.75158252e+03 6.85565576e+03 6.75403125e+03 6.78707520e+03 6.93717432e+03 6.92081445e+03 6.93647949e+03 6.83396680e+03 6.84933057e+03 6.80751562e+03 6.76159668e+03 6.90772021e+03 6.84359229e+03 6.70858740e+03 6.89504834e+03 6.91083398e+03 6.81092627e+03 6.83367969e+03 6.90666016e+03 6.79027148e+03 6.86875391e+03 6.98074512e+03 6.80084326e+03 6.68897217e+03 6.75487207e+03 6.71316846e+03 6.73966211e+03 6.76077197e+03 6.75355762e+03 6.79216992e+03 6.85181055e+03 6.78769287e+03 6.71676807e+03 6.74659424e+03 6.69334961e+03 6.69792041e+03 6.82320752e+03 6.61813574e+03 6.54837646e+03 6.74433496e+03 6.68748682e+03 6.59316846e+03 6.63408838e+03 6.62715820e+03 6.53583252e+03 6.51513086e+03 6.57288672e+03 6.67808545e+03 6.57658545e+03 6.59024365e+03 6.61221631e+03 6.39939355e+03 6.41407178e+03 6.43569238e+03 6.37242529e+03 6.53590527e+03 6.56597754e+03 6.40129883e+03 6.29709521e+03 6.35087012e+03 6.45560645e+03 6.40723828e+03 6.10280811e+03 6.25433398e+03 6.46157373e+03 6.27266797e+03 6.20391357e+03 6.17149365e+03 6.16666602e+03 6.17864648e+03 6.14082861e+03 6.04816699e+03 6.16028516e+03 6.16768604e+03 6.06350293e+03 6.10582861e+03 6.08743555e+03 6.02909619e+03 5.96381641e+03 5.77696533e+03 5.93815723e+03 6.08864404e+03 5.84359033e+03 5.81478271e+03 5.81363135e+03 5.84490625e+03 5.87080713e+03 5.66117139e+03 5.72599561e+03 5.82231152e+03 5.73780811e+03 5.65942041e+03 5.55131934e+03 5.52736426e+03 5.59019824e+03 5.54996191e+03 5.50126270e+03 5.53472363e+03 5.51542041e+03 5.47356348e+03 5.49064648e+03 5.42117578e+03 5.29303271e+03 5.23759912e+03 5.30479443e+03 5.34637842e+03 5.19131396e+03 5.11528320e+03 5.08544336e+03 5.09167188e+03 5.16541064e+03 5.09914941e+03 4.96003418e+03 4.93166260e+03 5.01365527e+03 5.03930420e+03 4.92457422e+03 4.74815479e+03 4.77235010e+03 4.82772412e+03 4.73771143e+03 4.70221680e+03 4.75623535e+03 4.69417578e+03 4.62340576e+03 4.65177197e+03 4.62153906e+03 4.52047314e+03 4.43304590e+03 4.45507471e+03 4.43681396e+03 4.28708984e+03 4.22012598e+03 4.26124219e+03 4.30177441e+03 4.29387012e+03 4.19624268e+03 4.07975806e+03 4.14740820e+03 4.15577979e+03 3.97338550e+03 3.90057251e+03 3.96585083e+03 4.01410913e+03 3.92354395e+03 3.76594189e+03 3.70972485e+03 3.73175732e+03 3.76274121e+03 3.76826685e+03 3.71538770e+03 3.58283350e+03 3.49338086e+03 3.47518994e+03 3.42531519e+03 3.40481079e+03 3.36693774e+03 3.32568091e+03 3.31572314e+03 3.27268237e+03 3.21171948e+03 3.14742456e+03 3.13981348e+03 3.18377466e+03 3.09810767e+03 2.95371265e+03 2.89760449e+03 2.91561401e+03 2.92334473e+03 2.91209033e+03 2.81776587e+03 2.66484131e+03 2.63592285e+03 2.68597461e+03 2.66772119e+03 2.62250977e+03 2.52774048e+03 2.44421851e+03 2.42409985e+03 2.37871997e+03 2.36682837e+03 2.30566382e+03 2.20106836e+03 2.21801685e+03 2.20811255e+03 2.12420557e+03 2.05273315e+03 1.96580237e+03 1.96102075e+03 2.00494006e+03 1.94257605e+03 1.82718555e+03 1.81174182e+03 1.80043201e+03 1.68870325e+03 1.62772192e+03 1.57877148e+03 1.54142163e+03 1.55823181e+03 1.49360437e+03 1.39996277e+03 1.37575134e+03 1.34653857e+03 1.27587158e+03 1.22524219e+03 1.20819055e+03 1.15596948e+03 1.08912476e+03 1.04694434e+03 9.95790955e+02 9.66329834e+02 9.32076294e+02 8.74301270e+02 8.18283386e+02 7.47942383e+02 7.03416687e+02 6.69153320e+02 6.25848083e+02 5.86408386e+02 5.36288086e+02 4.85014496e+02 4.25439301e+02 3.79472473e+02 3.38718842e+02 2.89609863e+02 2.37778687e+02 1.82130539e+02 1.35237961e+02 9.04125748e+01 4.60846672e+01 5.58225822e+00 -4.01061058e+01 -9.09290009e+01 -1.50445999e+02 -2.04142487e+02 -2.45832916e+02 -2.88370209e+02 -3.26139038e+02 -3.71609924e+02 -4.36300598e+02 -4.89911438e+02 -5.14135010e+02 -5.53616821e+02 -6.17701660e+02 -6.82013062e+02 -7.31312073e+02 -7.63417603e+02 -8.01488464e+02 -8.55242065e+02 -9.14798645e+02 -9.60521667e+02 -9.91016113e+02 -1.04063135e+03 -1.10449670e+03 -1.14383936e+03 -1.19743457e+03 -1.24213171e+03 -1.28313367e+03 -1.34815503e+03 -1.38455286e+03 -1.43241101e+03 -1.46697571e+03 -1.49900269e+03 -1.56416553e+03 -1.62390173e+03 -1.67137659e+03 -1.69268201e+03 -1.72577832e+03 -1.80425745e+03 -1.85863733e+03 -1.89986987e+03 -1.96138196e+03 -1.96118896e+03 -1.99543787e+03 -2.11009644e+03 -2.13746411e+03 -2.13090869e+03 -2.23938623e+03 -2.28920630e+03 -2.25168286e+03 -2.34976367e+03 -2.41505396e+03 -2.39432178e+03 -2.49782104e+03 -2.58042114e+03 -2.56187646e+03 -2.59438550e+03 -2.66677881e+03 -2.68502686e+03 -2.74890283e+03 -2.80196729e+03 -2.76923022e+03 -2.84589062e+03 -2.95491089e+03 -3.01425757e+03 -3.05578076e+03 -3.03457959e+03 -3.09233057e+03 -3.11776904e+03 -3.10501514e+03 -3.23122559e+03 -3.29286548e+03 -3.27410059e+03 -3.38702100e+03 -3.40982275e+03 -3.37485498e+03 -3.46380469e+03 -3.53082568e+03 -3.61371924e+03 -3.62491772e+03 -3.59282446e+03 -3.60235107e+03 -3.74315845e+03 -3.87595728e+03 -3.80059351e+03 -3.82734766e+03 -3.81557153e+03 -3.88353613e+03 -4.04313037e+03 -3.94722266e+03 -3.95239697e+03 -4.07632251e+03 -4.16539502e+03 -4.17129785e+03 -4.09247192e+03 -4.20689111e+03 -4.33317236e+03 -4.30688184e+03 -4.35319580e+03 -4.33570020e+03 -4.37177930e+03 -4.48008105e+03 -4.52522656e+03 -4.58744434e+03 -4.54243262e+03 -4.53561084e+03 -4.62447314e+03 -4.66233252e+03 -4.75670166e+03 -4.74436328e+03 -4.69029053e+03 -4.76380859e+03 -4.87802100e+03 -4.92041699e+03 -4.91745508e+03 -4.94184229e+03 -4.96498877e+03 -5.04903564e+03 -5.04670020e+03 -5.01521191e+03 -5.14582031e+03 -5.17096191e+03 -5.13930420e+03 -5.27797314e+03 -5.23223828e+03 -5.19370117e+03 -5.30408594e+03 -5.27758984e+03 -5.29454980e+03 -5.44276904e+03 -5.42492383e+03 -5.33822021e+03 -5.42377246e+03 -5.51518506e+03 -5.52557080e+03 -5.66197852e+03 -5.61818848e+03 -5.56210596e+03 -5.61904736e+03 -5.57577246e+03 -5.67356152e+03 -5.69049512e+03 -5.75721533e+03 -5.87027979e+03 -5.73344775e+03 -5.82147461e+03 -5.86212988e+03 -5.76271631e+03 -5.84875732e+03 -5.96401416e+03 -6.02582031e+03 -5.96292188e+03 -5.94449561e+03 -6.05977588e+03 -6.05763721e+03 -6.03245508e+03 -6.05518408e+03 -6.09140576e+03 -6.20641992e+03 -6.14946143e+03 -6.20553711e+03 -6.28351562e+03 -6.14084180e+03 -6.15640723e+03 -6.37223193e+03 -6.39454346e+03 -6.23679736e+03 -6.30933789e+03 -6.37381494e+03 -6.32451025e+03 -6.51506348e+03 -6.51779102e+03 -6.39299023e+03 -7.13010254e+03 -7.07324219e+03 -6.96645703e+03 -6.39051660e+03 -1.44464072e+04 -1.93686914e+04 -9395441. -29051356. -2.35885625e+06 -9067950. 27270078. -1.42323562e+06 -9259576. 11414557. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6806928. 2.10658975e+06 -2.72596367e+04 -1.31879873e+04 -7.06265723e+03 -8.92518848e+03 -7.31188916e+03 -7.75188672e+03 -7.32764844e+03 -6.84069727e+03 -6.89925293e+03 -7.03330029e+03 -6.87378711e+03 -6.77096045e+03 -6.79596191e+03 -6.86538184e+03 -6.93918457e+03 -6.90156055e+03 -6.79194580e+03 -6.63315137e+03 -6.82250391e+03 -6.87110693e+03 -6.82670166e+03 -6.83601025e+03 -6.64507861e+03 -6.61054004e+03 -6.75605566e+03 -6.77627051e+03 -6.78197363e+03 -6.54208496e+03 -6.53678662e+03 -6.84338623e+03 -6.98304736e+03 -6.72248877e+03 -6.42499121e+03 -6.43903809e+03 -6.64218311e+03 -6.68716797e+03 -6.63871631e+03 -6.46781592e+03 -6.64125977e+03 -6.66970459e+03 -6.61762158e+03 -6.59487646e+03 -6.31652246e+03 -6.44873486e+03 -6.74202246e+03 -6.57959863e+03 -6.53257471e+03 -6.41479688e+03 -6.26709717e+03 -6.36013818e+03 -6.52044727e+03 -6.47058789e+03 -6.24278418e+03 -6.39338037e+03 -6.39127539e+03 -6.34099512e+03 -6.32950830e+03 -6.15754150e+03 -6.23467090e+03 -6.36831787e+03 -6.17469434e+03 -6.08387793e+03 -6.03644189e+03 -6.16178174e+03 -6.36174756e+03 -6.26219092e+03 -6.07485791e+03 -5.96735205e+03 -6.02211475e+03 -5.97274707e+03 -6.04675635e+03 -6.10287646e+03 -5.87455762e+03 -5.87623730e+03 -6.04625586e+03 -5.96018896e+03 -5.84649365e+03 -5.66649805e+03 -5.75499316e+03 -5.93288428e+03 -5.85921387e+03 -5.76165674e+03 -5.60365234e+03 -5.54956494e+03 -5.68971436e+03 -5.77208643e+03 -5.56300879e+03 -5.40510059e+03 -5.60720850e+03 -5.55970117e+03 -5.41981641e+03 -5.57441455e+03 -5.41307764e+03 -5.34264355e+03 -5.43956543e+03 -5.40874805e+03 -5.36675830e+03 -5.18840967e+03 -5.16856836e+03 -5.21591943e+03 -5.28694141e+03 -5.27481885e+03 -5.06567920e+03 -5.08189014e+03 -5.07112354e+03 -5.00470117e+03 -5.02272021e+03 -4.89782227e+03 -4.88761816e+03 -5.00166553e+03 -4.94454248e+03 -4.75624072e+03 -4.60783984e+03 -4.73732617e+03 -4.89986475e+03 -4.83454297e+03 -4.68842236e+03 -4.49166943e+03 -4.47513623e+03 -4.56178809e+03 -4.57418213e+03 -4.56246826e+03 -4.39393652e+03 -4.36642773e+03 -4.34065186e+03 -4.30880518e+03 -4.39150293e+03 -4.21416455e+03 -4.16465723e+03 -4.25780762e+03 -4.16942725e+03 -4.09771631e+03 -4.03007349e+03 -4.03179761e+03 -4.06097632e+03 -3.98806421e+03 -3.86705957e+03 -3.74595947e+03 -3.82594165e+03 -3.91860840e+03 -3.83399731e+03 -3.70455396e+03 -3.58463574e+03 -3.57655469e+03 -3.61381396e+03 -3.61584741e+03 -3.56591187e+03 -3.37574512e+03 -3.31885400e+03 -3.38632251e+03 -3.40034741e+03 -3.39190991e+03 -3.26245996e+03 -3.18314453e+03 -3.14071313e+03 -3.13302734e+03 -3.13311182e+03 -3.01899561e+03 -2.98405322e+03 -2.96261011e+03 -2.93316089e+03 -2.90657324e+03 -2.77676709e+03 -2.79066382e+03 -2.80574731e+03 -2.69137671e+03 -2.67570093e+03 -2.59776343e+03 -2.55057422e+03 -2.55822217e+03 -2.51358447e+03 -2.44181519e+03 -2.32705005e+03 -2.30072095e+03 -2.32347388e+03 -2.32628442e+03 -2.26854590e+03 -2.11063892e+03 -2.03960217e+03 -2.07326660e+03 -2.07427661e+03 -2.00953662e+03 -1.88300085e+03 -1.85634607e+03 -1.85453369e+03 -1.80067920e+03 -1.77482129e+03 -1.68160632e+03 -1.62757349e+03 -1.62834473e+03 -1.59580518e+03 -1.53359448e+03 -1.45576941e+03 -1.41816919e+03 -1.37586877e+03 -1.33265356e+03 -1.31016003e+03 -1.23410522e+03 -1.18372571e+03 -1.14443628e+03 -1.08284558e+03 -1.03495630e+03 -9.93506775e+02 -9.74421753e+02 -9.37094482e+02 -8.76136230e+02 -8.02624207e+02 -7.29029480e+02 -7.10100586e+02 -6.98465088e+02 -6.41603943e+02 -5.76520386e+02 -5.09893372e+02 -4.56503723e+02 -4.27630951e+02 -4.00192657e+02 -3.47004211e+02 -2.87205994e+02 -2.39810104e+02 -1.93845474e+02 -1.46393219e+02 -9.62735977e+01 -4.48738174e+01 3.94737363e+00 5.43541107e+01 1.04137527e+02 1.50159973e+02 1.84911987e+02 2.37747559e+02 2.87649872e+02 3.25450378e+02 3.81798004e+02 4.30776215e+02 4.88644531e+02 5.36887390e+02 5.60213623e+02 6.01634216e+02 6.60068604e+02 7.34770569e+02 8.10223206e+02 8.36450745e+02 8.38957825e+02 8.64436462e+02 9.32799500e+02 1.03091663e+03 1.10405225e+03 1.12277551e+03 1.11425256e+03 1.15917175e+03 1.27506372e+03 1.32661230e+03 1.29677856e+03 1.33831140e+03 1.42674963e+03 1.47355396e+03 1.56469116e+03 1.57757117e+03 1.56252417e+03 1.65834644e+03 1.67379883e+03 1.74114417e+03 1.84394104e+03 1.81102258e+03 1.88809656e+03 1.98667139e+03 1.98809167e+03 2.03070935e+03 2.07411938e+03 2.13733545e+03 2.18858057e+03 2.21325391e+03 2.19226660e+03 2.23617261e+03 2.39960083e+03 2.51022095e+03 2.50008350e+03 2.44018335e+03 2.41892993e+03 2.49669336e+03 2.66394458e+03 2.79697705e+03 2.78984033e+03 2.68223242e+03 2.71288013e+03 2.86617969e+03 2.91334790e+03 2.89561792e+03 2.92846021e+03 2.99931299e+03 3.04956909e+03 3.18193506e+03 3.15431372e+03 3.10645728e+03 3.21642920e+03 3.16217725e+03 3.29584961e+03 3.43888525e+03 3.39276685e+03 3.53218311e+03 3.49099463e+03 3.39194702e+03 3.54386963e+03 3.51160547e+03 3.61182275e+03 3.89668311e+03 3.74348730e+03 3.57003760e+03 3.69999829e+03 3.92216992e+03 4.08674561e+03 4.03995190e+03 3.85999048e+03 3.81838477e+03 3.91192554e+03 4.12187842e+03 4.33771875e+03 4.27136182e+03 4.08245361e+03 4.08845312e+03 4.29473291e+03 4.38093604e+03 4.28904688e+03 4.31119189e+03 4.39755322e+03 4.43644971e+03 4.62336279e+03 4.66611572e+03 4.44284814e+03 4.47652881e+03 4.59771045e+03 4.64248584e+03 4.70602979e+03 4.73120557e+03 4.87369189e+03 4.81837842e+03 4.69689551e+03 4.86003564e+03 4.77512158e+03 4.91973975e+03 5.28024658e+03 5.00525537e+03 4.72716553e+03 4.91177979e+03 5.20882568e+03 5.37297266e+03 5.36404395e+03 5.11468213e+03 4.93631836e+03 5.09472705e+03 5.41005957e+03 5.64161182e+03 5.49819922e+03 5.24627441e+03 5.22132471e+03 5.39841211e+03 5.51719531e+03 5.66124805e+03 5.66906299e+03 5.42014355e+03 5.41775342e+03 5.66885840e+03 5.74092920e+03 5.65973877e+03 5.65533643e+03 5.63462061e+03 5.65486377e+03 5.90362061e+03 5.98417285e+03 5.78742969e+03 5.74850195e+03 5.74755957e+03 5.79496729e+03 5.93700391e+03 5.95871436e+03 6.11220361e+03 6.13968555e+03 5.93396045e+03 5.88022656e+03 5.80727539e+03 6.09598047e+03 6.42140967e+03 6.30454785e+03 5.98905273e+03 5.87805518e+03 6.15278711e+03 6.50717139e+03 6.25510352e+03 5.94987500e+03 6.11620703e+03 6.32705371e+03 6.44185547e+03 6.67024219e+03 6.50756006e+03 6.18178662e+03 6.10655029e+03 6.35252930e+03 6.46056006e+03 6.49500977e+03 6.47952441e+03 6.46266113e+03 6.43524951e+03 6.56895068e+03 6.52805420e+03 6.31495508e+03 6.41925879e+03 6.45969092e+03 6.73175244e+03 6.75009375e+03 6.56979932e+03 6.66922412e+03 6.63841699e+03 6.65456982e+03 6.56954785e+03 6.36846289e+03 6.70716260e+03 6.99458545e+03 6.77804590e+03 6.48660449e+03 6.53819434e+03 6.86423291e+03 6.96852002e+03 6.87990674e+03 6.75279297e+03 6.57243311e+03 6.62195654e+03 6.84496338e+03 6.85091309e+03 6.73342773e+03 6.58292871e+03 6.55246484e+03 6.96151123e+03 7.22586670e+03 6.81546240e+03 6.60048486e+03 6.81236914e+03 6.82819678e+03 7.01210791e+03 7.01884033e+03 6.59626172e+03 6.67062598e+03 6.84807959e+03 6.87690820e+03 6.99014893e+03 7.06102783e+03 7.18118604e+03 6.99222949e+03 6.80294336e+03 6.83085498e+03 7.85215723e+03 1.32007363e+04 2.17063594e+04 -3.74247450e+06 -1.92411225e+06 -10643127. -1.67169725e+06 -21806334. 21553496. 3627887. -2.40186875e+06 1.51527612e+06 3.78810925e+06 7.84434350e+06 -26928992. 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. 0. 0. 0. 0. 0. 0. 50713344. -4564874. 2.49077188e+04 1.79988711e+04 1.13084893e+04 8.24545117e+03 8.33322852e+03 6.77592529e+03 6.43435156e+03 6.63475000e+03 6.45355469e+03 6.19554688e+03 6.38842578e+03 6.34372168e+03 6.24223828e+03 6.22009033e+03 6.20471680e+03 6.14593457e+03 6.11177881e+03 6.06333838e+03 6.01876025e+03 6.01980762e+03 5.96247412e+03 6.03505566e+03 6.05143750e+03 5.79208545e+03 5.78165332e+03 6.07945020e+03 6.06202197e+03 5.86889062e+03 5.83027686e+03 5.79931836e+03 5.78184766e+03 5.77508740e+03 5.74144873e+03 5.70318262e+03 5.68058105e+03 5.58677051e+03 5.53456299e+03 5.69091455e+03 5.70435352e+03 5.53683936e+03 5.50761279e+03 5.51082666e+03 5.49175439e+03 5.41744629e+03 5.38094678e+03 5.39878857e+03 5.25318408e+03 5.18021826e+03 5.22508789e+03 5.20922705e+03 5.37061865e+03 5.36261768e+03 5.14113184e+03 4.99604199e+03 4.93902002e+03 5.20169629e+03 5.21871973e+03 4.98762305e+03 4.85549121e+03 4.81660449e+03 4.91520654e+03 4.87802441e+03 4.93788086e+03 4.91528320e+03 4.62563232e+03 4.48901660e+03 4.70875586e+03 4.87881201e+03 4.70835303e+03 4.57839014e+03 4.53374219e+03 4.48553271e+03 4.45595117e+03 4.43483887e+03 4.37436377e+03 4.32161914e+03 4.32243701e+03 4.30247363e+03 4.23212012e+03 4.18794385e+03 4.27839600e+03 4.26173340e+03 4.11052344e+03 4.03044629e+03 3.99415747e+03 4.04924512e+03 4.00745239e+03 3.90867749e+03 3.88451270e+03 3.75386694e+03 3.65028589e+03 3.78326782e+03 3.73545312e+03 3.51929199e+03 3.52719092e+03 3.68087231e+03 3.77087158e+03 3.60685645e+03 3.44597192e+03 3.38188013e+03 3.34689746e+03 3.32414185e+03 3.27580688e+03 3.24179541e+03 3.18678223e+03 3.25513965e+03 3.21750806e+03 3.07318970e+03 3.03133936e+03 2.90683472e+03 2.89536865e+03 3.02066821e+03 2.94378784e+03 2.83554443e+03 2.73414014e+03 2.64553101e+03 2.74156396e+03 2.75243604e+03 2.62878662e+03 2.51270728e+03 2.46138867e+03 2.47385889e+03 2.42360791e+03 2.45942212e+03 2.43528271e+03 2.30284033e+03 2.22825928e+03 2.18163501e+03 2.18238916e+03 2.14418799e+03 2.07245508e+03 2.01888879e+03 1.97922253e+03 1.92397229e+03 1.82895032e+03 1.80842126e+03 1.85590906e+03 1.79788855e+03 1.70865417e+03 1.61672351e+03 1.56432056e+03 1.60641223e+03 1.56221631e+03 1.47293774e+03 1.39138562e+03 1.34049072e+03 1.33562170e+03 1.27995764e+03 1.23302966e+03 1.15885376e+03 1.13595190e+03 1.15491150e+03 1.07905139e+03 1.00117065e+03 9.55104126e+02 9.13662964e+02 8.59547607e+02 8.09727905e+02 7.59174927e+02 7.09245605e+02 6.60567932e+02 5.95173706e+02 5.57986755e+02 5.43659424e+02 4.76231720e+02 4.14320648e+02 3.78136292e+02 3.30185974e+02 2.92444031e+02 2.39881348e+02 1.83714294e+02 1.42750885e+02 9.57952118e+01 4.67554207e+01 1.71812987e+00 -4.37180786e+01 -9.02589340e+01 -1.38159348e+02 -1.85999664e+02 -2.30338531e+02 -2.89560577e+02 -3.55201080e+02 -3.94812622e+02 -4.32791534e+02 -4.67871368e+02 -5.11866150e+02 -5.90286865e+02 -6.42892334e+02 -6.72688721e+02 -7.00202454e+02 -7.42638123e+02 -8.14219788e+02 -8.62481262e+02 -9.28927856e+02 -9.66059937e+02 -9.85745056e+02 -1.04504224e+03 -1.08885510e+03 -1.17072510e+03 -1.21465784e+03 -1.22173181e+03 -1.27971460e+03 -1.32753369e+03 -1.36407190e+03 -1.37333704e+03 -1.45133069e+03 -1.58917847e+03 -1.61185474e+03 -1.61384998e+03 -1.61872290e+03 -1.65061023e+03 -1.79432275e+03 -1.85480249e+03 -1.84817334e+03 -1.84517944e+03 -1.88094543e+03 -1.99321326e+03 -2.03590906e+03 -2.12217920e+03 -2.16355981e+03 -2.15038477e+03 -2.17794263e+03 -2.21178955e+03 -2.35601050e+03 -2.40041162e+03 -2.37589185e+03 -2.40105542e+03 -2.43736108e+03 -2.56952710e+03 -2.61931055e+03 -2.54210107e+03 -2.58844897e+03 -2.77116187e+03 -2.81386523e+03 -2.72530835e+03 -2.75332104e+03 -2.93554565e+03 -3.00872485e+03 -2.95654712e+03 -2.92393848e+03 -2.97346606e+03 -3.17826123e+03 -3.17679224e+03 -3.12559399e+03 -3.23913208e+03 -3.27561108e+03 -3.26915771e+03 -3.30147607e+03 -3.35921021e+03 -3.32621094e+03 -3.45356543e+03 -3.68938013e+03 -3.62428809e+03 -3.61120874e+03 -3.65771899e+03 -3.68133716e+03 -3.72211792e+03 -3.74337646e+03 -3.78545483e+03 -3.75653955e+03 -3.73633765e+03 -3.86997485e+03 -3.99890283e+03 -4.14316699e+03 -4.03874194e+03 -3.92988403e+03 -4.08447754e+03 -4.17494678e+03 -4.34705811e+03 -4.33744727e+03 -4.24913818e+03 -4.20589062e+03 -4.19882129e+03 -4.37049707e+03 -4.41688477e+03 -4.53058984e+03 -4.60736279e+03 -4.52266748e+03 -4.46304053e+03 -4.38866553e+03 -4.58064209e+03 -4.87510059e+03 -4.85205811e+03 -4.75747314e+03 -4.65791016e+03 -4.61915820e+03 -4.87635645e+03 -5.04463232e+03 -4.96057178e+03 -4.81813574e+03 -4.83570264e+03 -4.97390820e+03 -5.03135107e+03 -5.20791357e+03 -5.23800195e+03 -5.12688916e+03 -5.08930322e+03 -5.08553662e+03 -5.30043652e+03 -5.35709473e+03 -5.14930322e+03 -5.16692090e+03 -5.48695557e+03 -5.46869824e+03 -5.21494043e+03 -5.33669824e+03 -5.64936768e+03 -5.63482471e+03 -5.53293799e+03 -5.40460205e+03 -5.43328467e+03 -5.77077881e+03 -5.80319971e+03 -5.67145850e+03 -5.55758447e+03 -5.51989062e+03 -5.67892236e+03 -5.76374707e+03 -5.82624854e+03 -5.65802246e+03 -5.82124121e+03 -6.14281836e+03 -6.00114307e+03 -5.95916992e+03 -6.01772949e+03 -5.97595947e+03 -5.98757764e+03 -6.00519189e+03 -6.05177002e+03 -6.02530859e+03 -5.95603125e+03 -5.86918555e+03 -6.07045312e+03 -6.36610303e+03 -6.15074707e+03 -5.96315137e+03 -6.18629639e+03 -6.25693359e+03 -6.46447949e+03 -6.42473096e+03 -6.22033154e+03 -6.38177637e+03 -6.39181396e+03 -6.20531348e+03 -6.22544580e+03 -6.50910107e+03 -6.50732861e+03 -6.38462500e+03 -6.27208789e+03 -6.09804688e+03 -6.40157373e+03 -6.86627930e+03 -6.67718799e+03 -6.46542188e+03 -6.35715771e+03 -6.34386426e+03 -6.70308008e+03 -6.80368604e+03 -6.64920020e+03 -6.45872607e+03 -6.44400195e+03 -6.56751562e+03 -6.59379199e+03 -6.81181055e+03 -6.81547314e+03 -6.60342188e+03 -6.60809619e+03 -6.62470557e+03 -6.79122656e+03 -6.84011426e+03 -6.71539160e+03 -6.67329102e+03 -6.64748242e+03 -6.72518311e+03 -6.57410254e+03 -6.64385449e+03 -6.98632910e+03 -6.89621582e+03 -6.83636426e+03 -6.67534912e+03 -6.58808594e+03 -7.04598389e+03 -7.01220264e+03 -6.80170361e+03 -6.71537891e+03 -6.67134863e+03 -6.76103564e+03 -6.73976660e+03 -6.84763232e+03 -6.70002100e+03 -6.84792822e+03 -7.13306152e+03 -6.88013623e+03 -6.93637158e+03 -7.02462549e+03 -6.87616064e+03 -6.78551709e+03 -6.76990771e+03 -6.82161230e+03 -6.84793506e+03 -6.82932178e+03 -6.82358887e+03 -6.89800781e+03 -6.96491113e+03 -6.67973535e+03 -6.56509424e+03 -6.77071094e+03 -6.90925146e+03 -7.08020361e+03 -6.94290332e+03 -6.70721289e+03 -6.93936426e+03 -6.88087988e+03 -6.75994434e+03 -6.83339502e+03 -6.81412549e+03 -6.75661670e+03 -6.69113086e+03 -6.76300293e+03 -6.66064062e+03 -6.71889697e+03 -7.00961279e+03 -6.92573730e+03 -6.81772852e+03 -6.64462061e+03 -6.52308301e+03 -6.89717432e+03 -6.91108252e+03 -6.73512939e+03 -6.54522998e+03 -6.43655957e+03 -6.62721875e+03 -6.70991895e+03 -6.94180664e+03 -6.72237500e+03 -6.49401758e+03 -6.60544678e+03 -6.55985303e+03 -6.74086523e+03 -6.70889502e+03 -6.50370850e+03 -6.48966162e+03 -6.49863672e+03 -6.50431738e+03 -6.34680762e+03 -6.45445947e+03 -6.78102979e+03 -6.63033984e+03 -6.52398340e+03 -6.32599365e+03 -6.20973389e+03 -6.59496387e+03 -6.56187500e+03 -6.34880615e+03 -6.21494141e+03 -6.15655322e+03 -6.28821875e+03 -6.29851123e+03 -6.47985156e+03 -6.44161572e+03 -6.23501758e+03 -6.09816992e+03 -6.03881543e+03 -6.38370068e+03 -6.31279150e+03 -6.07748340e+03 -6.12683936e+03 -6.10777783e+03 -6.02096631e+03 -5.96848242e+03 -6.13454590e+03 -5.95372461e+03 -5.80081445e+03 -6.12813574e+03 -6.15963818e+03 -5.91142773e+03 -5.86026123e+03 -5.83945264e+03 -5.86543359e+03 -5.66287354e+03 -5.58634814e+03 -5.91300635e+03 -5.90124121e+03 -5.52251807e+03 -5.41482715e+03 -5.69942334e+03 -5.90505078e+03 -5.72475635e+03 -5.49279590e+03 -5.43592822e+03 -5.62034033e+03 -5.56722607e+03 -5.41522217e+03 -5.47225830e+03 -5.29904980e+03 -5.12201562e+03 -5.34039062e+03 -5.52073779e+03 -5.44925537e+03 -5.20151318e+03 -5.04577734e+03 -5.27963574e+03 -5.37316895e+03 -5.16173730e+03 -4.99565820e+03 -4.97831787e+03 -4.99268262e+03 -4.95978320e+03 -5.10452881e+03 -4.98476318e+03 -4.78930078e+03 -4.86485547e+03 -4.84156006e+03 -4.88039551e+03 -4.73050293e+03 -4.60222314e+03 -4.76054199e+03 -4.73289209e+03 -4.63331689e+03 -4.48772754e+03 -4.46510986e+03 -4.69827686e+03 -4.50110400e+03 -4.32225830e+03 -4.40051318e+03 -4.35920996e+03 -4.33683350e+03 -4.30076611e+03 -4.36079883e+03 -4.35031641e+03 -4.18658936e+03 -4.03122534e+03 -3.98434155e+03 -4.17025830e+03 -4.07728442e+03 -3.91957690e+03 -3.94384058e+03 -3.91811841e+03 -3.88881372e+03 -3.83721606e+03 -3.86421582e+03 -3.72455029e+03 -3.59739038e+03 -3.72672144e+03 -3.69671118e+03 -3.60622754e+03 -3.58118872e+03 -3.52081128e+03 -3.47283203e+03 -3.34369897e+03 -3.26557300e+03 -3.39491455e+03 -3.42594360e+03 -3.22792188e+03 -3.09103247e+03 -3.19240771e+03 -3.27413013e+03 -3.14400293e+03 -2.98366187e+03 -2.90244922e+03 -2.99174365e+03 -2.97849146e+03 -2.85599023e+03 -2.87700732e+03 -2.83740601e+03 -2.70856201e+03 -2.65461670e+03 -2.69207373e+03 -2.69203662e+03 -2.52329175e+03 -2.43427124e+03 -2.52571704e+03 -2.53259741e+03 -2.40807861e+03 -2.28010498e+03 -2.21834790e+03 -2.29718433e+03 -2.28483228e+03 -2.15075220e+03 -2.08791699e+03 -2.06341333e+03 -2.00948401e+03 -1.94815002e+03 -1.98064868e+03 -1.89377966e+03 -1.78102771e+03 -1.82358655e+03 -1.79389697e+03 -1.72415906e+03 -1.63976672e+03 -1.56809265e+03 -1.62440637e+03 -1.62691187e+03 -1.49240869e+03 -1.42562183e+03 -1.67828564e+03 -2.27819531e+03 -3.03817114e+03 3.31793938e+05 2.59283484e+05 -4.23522607e+03 -2.59360913e+03 -1.58686768e+03 -1.92127588e+03 -2.11044482e+03 -2.10051978e+03 1.61169172e+05 1.73862425e+06 3.16963156e+05 -263028352. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.28936320e+09 -4.28936320e+09 -2144681600. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.26456832e+09 -1.45109719e+05 -1.87298219e+05 6.80387812e+05 3.00344580e+03 1.66427832e+03 1.13292175e+03 1.23405432e+03 6.99323486e+02 9.96587036e+02 1.01678400e+03 1.01974744e+03 1.08853101e+03 1.11032617e+03 1.15189343e+03 1.21571399e+03 1.23476379e+03 1.27737549e+03 1.32816870e+03 1.35184326e+03 1.42801270e+03 1.51638062e+03 1.55939929e+03 1.55430481e+03 1.58694336e+03 1.65311548e+03 1.66096411e+03 1.72381104e+03 1.82759045e+03 1.85215417e+03 1.90143994e+03 1.96218005e+03 1.96302405e+03 1.99714172e+03 2.06175098e+03 2.09343042e+03 2.12435767e+03 2.22837036e+03 2.31905347e+03 2.30034277e+03 2.32110645e+03 2.38928369e+03 2.44423267e+03 2.50166699e+03 2.51534546e+03 2.50196265e+03 2.61645361e+03 2.72455029e+03 2.68226416e+03 2.71328491e+03 2.79722778e+03 2.78816992e+03 2.84643237e+03 2.96880347e+03 2.97780859e+03 2.98089355e+03 3.06785840e+03 3.19084082e+03 3.15991333e+03 3.09885156e+03 3.14121509e+03 3.20437549e+03 3.35118506e+03 3.44673169e+03 3.39613599e+03 3.40356519e+03 3.44056030e+03 3.47916406e+03 3.52919067e+03 3.56270923e+03 3.57414453e+03 3.66970239e+03 3.81552759e+03 3.78384351e+03 3.74835645e+03 3.85483081e+03 3.88896362e+03 3.89937793e+03 3.96955713e+03 4.01595972e+03 4.01940942e+03 4.02161523e+03 4.13956885e+03 4.16332812e+03 4.19717090e+03 4.24476367e+03 4.17017334e+03 4.28919287e+03 4.44297119e+03 4.37529346e+03 4.37184619e+03 4.44845361e+03 4.46481689e+03 4.51981982e+03 4.53926465e+03 4.50912598e+03 4.63826172e+03 4.79981055e+03 4.74876953e+03 4.64275195e+03 4.69656934e+03 4.85668262e+03 4.87722461e+03 4.85071045e+03 4.87301123e+03 4.86673926e+03 5.01791602e+03 5.17852490e+03 5.03445068e+03 4.95834229e+03 4.99826562e+03 5.07306299e+03 5.18670068e+03 5.26883838e+03 5.22262549e+03 5.23192041e+03 5.41577246e+03 5.43514600e+03 5.32821777e+03 5.25731055e+03 5.29199951e+03 5.43895947e+03 5.54381152e+03 5.57988916e+03 5.52602295e+03 5.56654248e+03 5.63440430e+03 5.53842676e+03 5.53828223e+03 5.62548340e+03 5.64294971e+03 5.76620312e+03 5.87159131e+03 5.69820312e+03 5.69372900e+03 5.88339355e+03 5.87285010e+03 5.74654590e+03 5.84964795e+03 6.03736426e+03 6.03060107e+03 5.99423682e+03 5.98703516e+03 5.97435840e+03 6.00948291e+03 5.96802539e+03 6.03470166e+03 6.11169141e+03 6.12143457e+03 6.16738525e+03 6.22042773e+03 6.23140576e+03 6.03559131e+03 6.14609961e+03 6.32455371e+03 6.26947510e+03 6.35587158e+03 6.46995996e+03 6.41212451e+03 6.27674023e+03 6.31163916e+03 6.28431982e+03 6.26263818e+03 6.39820752e+03 6.50592822e+03 6.47546826e+03 6.44459229e+03 6.43787012e+03 6.41654883e+03 6.44638184e+03 6.45171631e+03 6.46068311e+03 6.55475586e+03 6.64247119e+03 6.56424512e+03 6.54509521e+03 6.58163623e+03 6.63254443e+03 6.63069873e+03 6.62004590e+03 6.63136963e+03 6.70113721e+03 6.68285449e+03 6.67305615e+03 6.66293652e+03 6.74269434e+03 6.82749561e+03 6.58089551e+03 6.60631641e+03 6.84591064e+03 6.74963672e+03 6.78175146e+03 6.80767383e+03 6.68909717e+03 6.69192285e+03 6.75657373e+03 6.69937451e+03 6.69027295e+03 6.79175879e+03 6.91859180e+03 6.97879980e+03 6.88295166e+03 6.82397754e+03 6.81918359e+03 6.74587109e+03 6.74476123e+03 6.77051123e+03 6.88198584e+03 7.03351807e+03 6.82457568e+03 6.71313281e+03 6.87744727e+03 6.74003516e+03 6.83311768e+03 6.97205957e+03 6.80846680e+03 6.82592725e+03 6.85261914e+03 6.90538135e+03 6.88559082e+03 6.80181201e+03 6.75304785e+03 6.72191064e+03 6.79523584e+03 6.87575684e+03 6.88452832e+03 6.86059570e+03 6.86496777e+03 6.87173828e+03 6.82898926e+03 6.87927051e+03 6.88968018e+03 6.75621826e+03 6.67506006e+03 6.75613818e+03 6.80699756e+03 6.81487256e+03 6.76079834e+03 6.74567383e+03 6.75633057e+03 6.72169336e+03 6.77229932e+03 6.77058740e+03 6.84612012e+03 6.80637744e+03 6.55663965e+03 6.65505371e+03 6.66666357e+03 6.65281543e+03 6.73519971e+03 6.58224658e+03 6.51621582e+03 6.74198340e+03 6.73911084e+03 6.46924561e+03 6.44585400e+03 6.63902783e+03 6.64764160e+03 6.48573340e+03 6.53925146e+03 6.64574561e+03 6.44846045e+03 6.42960400e+03 6.47271826e+03 6.35674707e+03 6.43606885e+03 6.50487793e+03 6.31810596e+03 6.41477490e+03 6.51114404e+03 6.40702197e+03 6.27859033e+03 6.16605029e+03 6.31172803e+03 6.40289355e+03 6.22005225e+03 6.14956934e+03 6.22536621e+03 6.21042822e+03 6.14307959e+03 6.13746582e+03 6.15651562e+03 6.12390088e+03 6.04763086e+03 6.08502002e+03 6.15792920e+03 6.01871387e+03 5.96385254e+03 6.00725000e+03 5.84319678e+03 5.97937109e+03 6.02223877e+03 5.78966064e+03 5.87841748e+03 5.85299805e+03 5.73048242e+03 5.81004053e+03 5.75994189e+03 5.74982812e+03 5.82877490e+03 5.68963379e+03 5.63568115e+03 5.57922119e+03 5.51014795e+03 5.52365479e+03 5.51814648e+03 5.55531934e+03 5.56473730e+03 5.49033447e+03 5.45847217e+03 5.48315820e+03 5.38904053e+03 5.26556885e+03 5.24738086e+03 5.32925830e+03 5.35705908e+03 5.14551562e+03 5.04486035e+03 5.15263135e+03 5.21118555e+03 5.09541846e+03 5.01891992e+03 5.01056982e+03 4.98921973e+03 5.04598682e+03 4.97758838e+03 4.87462451e+03 4.75327588e+03 4.75642676e+03 4.80543115e+03 4.74148828e+03 4.75453857e+03 4.76003857e+03 4.66163525e+03 4.62727930e+03 4.68712500e+03 4.58581250e+03 4.46949658e+03 4.48854248e+03 4.51770166e+03 4.42475293e+03 4.26883350e+03 4.22251660e+03 4.29042529e+03 4.32325488e+03 4.24887061e+03 4.16040674e+03 4.12005176e+03 4.15815918e+03 4.10606836e+03 3.94761865e+03 3.93743823e+03 3.95044214e+03 3.96978687e+03 3.88124829e+03 3.73395703e+03 3.75449878e+03 3.75946729e+03 3.75494092e+03 3.75512891e+03 3.68175684e+03 3.55241382e+03 3.44456201e+03 3.49886108e+03 3.56558984e+03 3.45127783e+03 3.34294189e+03 3.28938550e+03 3.29557764e+03 3.32480786e+03 3.20532959e+03 3.13859961e+03 3.13181714e+03 3.14047485e+03 3.11229224e+03 2.94845532e+03 2.95428369e+03 2.95033130e+03 2.85222583e+03 2.84072925e+03 2.77030005e+03 2.71474927e+03 2.68612061e+03 2.63831445e+03 2.61056226e+03 2.59210400e+03 2.54670215e+03 2.44878833e+03 2.42722559e+03 2.41988965e+03 2.35321899e+03 2.28766797e+03 2.19174121e+03 2.18527344e+03 2.21996167e+03 2.14124121e+03 2.05976099e+03 1.98173267e+03 1.96234985e+03 1.98286743e+03 1.89869800e+03 1.83586548e+03 1.81857007e+03 1.75360437e+03 1.66490283e+03 1.64061121e+03 1.62523914e+03 1.56092151e+03 1.52802527e+03 1.46396729e+03 1.37942493e+03 1.37192468e+03 1.34478345e+03 1.28829993e+03 1.25771753e+03 1.19822717e+03 1.14637476e+03 1.08545312e+03 1.03405444e+03 1.00968414e+03 9.60201538e+02 9.00271179e+02 8.44970032e+02 8.08372803e+02 7.54407166e+02 7.06690979e+02 6.84999817e+02 6.32177917e+02 5.70511414e+02 5.17715515e+02 4.65826965e+02 4.21628052e+02 3.87264587e+02 3.41847229e+02 2.79496796e+02 2.25316223e+02 1.80747131e+02 1.40373154e+02 9.67607880e+01 4.92750130e+01 -4.00399351e+00 -5.15594635e+01 -9.52132034e+01 -1.38810715e+02 -1.86922729e+02 -2.37034470e+02 -2.88128052e+02 -3.28196014e+02 -3.68972046e+02 -4.31550110e+02 -4.88213593e+02 -5.29595520e+02 -5.66849731e+02 -6.13647095e+02 -6.77591492e+02 -7.34172485e+02 -7.70296753e+02 -8.03769104e+02 -8.50095398e+02 -9.09778931e+02 -9.64915039e+02 -1.00758759e+03 -1.04973096e+03 -1.08018823e+03 -1.13570654e+03 -1.20288293e+03 -1.23895081e+03 -1.28823120e+03 -1.33338232e+03 -1.37708496e+03 -1.42843689e+03 -1.47317029e+03 -1.49103638e+03 -1.54073938e+03 -1.62278662e+03 -1.67876013e+03 -1.72862598e+03 -1.74080444e+03 -1.78499951e+03 -1.82541003e+03 -1.88279321e+03 -1.97630298e+03 -1.97040063e+03 -2.01017419e+03 -2.10712476e+03 -2.09708350e+03 -2.12935205e+03 -2.23474365e+03 -2.27401782e+03 -2.30193726e+03 -2.37566846e+03 -2.37075439e+03 -2.35504053e+03 -2.48393994e+03 -2.56980078e+03 -2.55917456e+03 -2.65156665e+03 -2.69743237e+03 -2.64348218e+03 -2.71051733e+03 -2.77811499e+03 -2.80786890e+03 -2.90649976e+03 -2.94574731e+03 -2.96438403e+03 -3.02378833e+03 -3.06287183e+03 -3.12131104e+03 -3.12238135e+03 -3.12905176e+03 -3.21399219e+03 -3.27241821e+03 -3.27258618e+03 -3.32815747e+03 -3.40563452e+03 -3.40021069e+03 -3.48117212e+03 -3.53823730e+03 -3.56285669e+03 -3.62728857e+03 -3.56399316e+03 -3.63174536e+03 -3.79478149e+03 -3.79062231e+03 -3.79017627e+03 -3.85930566e+03 -3.89148755e+03 -3.92420728e+03 -3.97219116e+03 -3.87947827e+03 -3.91901807e+03 -4.11057422e+03 -4.19552588e+03 -4.20725537e+03 -4.12831738e+03 -4.14984570e+03 -4.31123682e+03 -4.31700342e+03 -4.30083496e+03 -4.36891797e+03 -4.39135107e+03 -4.43812158e+03 -4.50496387e+03 -4.58729248e+03 -4.56643555e+03 -4.52267871e+03 -4.69363135e+03 -4.67208838e+03 -4.63888232e+03 -4.70390674e+03 -4.68883057e+03 -4.79950098e+03 -4.94401758e+03 -4.94012891e+03 -4.83811377e+03 -4.86597949e+03 -4.99448242e+03 -5.05574268e+03 -5.07274316e+03 -5.03632861e+03 -5.12468799e+03 -5.17551367e+03 -5.17735303e+03 -5.23926562e+03 -5.24107715e+03 -5.26898340e+03 -5.33438916e+03 -5.17650439e+03 -5.20919189e+03 -5.47999365e+03 -5.46731982e+03 -5.42429346e+03 -5.43860791e+03 -5.41405664e+03 -5.43589307e+03 -5.63949609e+03 -5.70712354e+03 -5.59722949e+03 -5.56847803e+03 -5.56317285e+03 -5.64367627e+03 -5.76011133e+03 -5.79279980e+03 -5.82419775e+03 -5.76677637e+03 -5.83193701e+03 -5.83628906e+03 -5.74922363e+03 -5.81257227e+03 -5.97911377e+03 -6.01953125e+03 -5.94620508e+03 -5.95793066e+03 -6.00136279e+03 -6.02810352e+03 -5.98097559e+03 -6.09817139e+03 -6.12591553e+03 -6.11032471e+03 -6.12369824e+03 -6.12748096e+03 -6.33448096e+03 -6.18764160e+03 -6.15534717e+03 -6.33699414e+03 -6.21943213e+03 -6.19356982e+03 -6.33515869e+03 -6.39074609e+03 -6.30925000e+03 -6.52120215e+03 -6.60744287e+03 -6.47785889e+03 -6.97938770e+03 -6.77784814e+03 -8.05205713e+03 -8.72277148e+03 -9.67110449e+03 -9.56609668e+03 -9.76712207e+03 -1.01217881e+04 -1.08767119e+04 -9.59608789e+03 -1.72946758e+04 -2.92452227e+04 -9259576. 11414557. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6806928. 2.10658975e+06 -12905183. 3.29227225e+06 -2.20531191e+04 -1.58378467e+04 -1.03262588e+04 -8.43916992e+03 -7.44614844e+03 -6.96457520e+03 -6.97831787e+03 -7.06025146e+03 -6.84805371e+03 -6.78578906e+03 -6.85272705e+03 -6.80123047e+03 -6.91838574e+03 -6.90949512e+03 -6.74985791e+03 -6.66934570e+03 -6.82517871e+03 -6.86624463e+03 -6.81750342e+03 -6.82843848e+03 -6.61194336e+03 -6.60713477e+03 -6.92670020e+03 -6.76576025e+03 -6.58624023e+03 -6.50583154e+03 -6.64112012e+03 -6.89313477e+03 -6.93958398e+03 -6.69873096e+03 -6.43377539e+03 -6.47602881e+03 -6.65868164e+03 -6.67000293e+03 -6.63284521e+03 -6.54991748e+03 -6.58098682e+03 -6.62402539e+03 -6.62929980e+03 -6.60275830e+03 -6.36010986e+03 -6.44059668e+03 -6.84789453e+03 -6.51241064e+03 -6.32206641e+03 -6.37051660e+03 -6.31665430e+03 -6.57240869e+03 -6.56846484e+03 -6.32477783e+03 -6.24931348e+03 -6.40283398e+03 -6.52952783e+03 -6.34053369e+03 -6.25926172e+03 -6.12982666e+03 -6.25656787e+03 -6.40681641e+03 -6.18067480e+03 -6.19025977e+03 -6.12020508e+03 -6.06284717e+03 -6.23892334e+03 -6.24226758e+03 -6.10534375e+03 -5.98591699e+03 -6.07389209e+03 -6.09610791e+03 -6.02884229e+03 -6.05345410e+03 -5.81264111e+03 -5.81721680e+03 -6.11708496e+03 -5.91895215e+03 -5.66922607e+03 -5.61722949e+03 -5.84586865e+03 -6.03067188e+03 -5.82038525e+03 -5.74501025e+03 -5.64107568e+03 -5.50654150e+03 -5.62987207e+03 -5.75473828e+03 -5.60223584e+03 -5.43828711e+03 -5.56481152e+03 -5.54272070e+03 -5.47370215e+03 -5.59206006e+03 -5.35920312e+03 -5.30398145e+03 -5.53273096e+03 -5.38891406e+03 -5.24392871e+03 -5.19050732e+03 -5.14749268e+03 -5.30072607e+03 -5.30270654e+03 -5.10245361e+03 -5.02439844e+03 -5.13018408e+03 -5.13580762e+03 -5.02207812e+03 -5.03491357e+03 -4.94401123e+03 -4.86275244e+03 -4.98737744e+03 -4.91487109e+03 -4.74146191e+03 -4.66779736e+03 -4.71426758e+03 -4.84104346e+03 -4.82831934e+03 -4.69383691e+03 -4.49852246e+03 -4.42913574e+03 -4.62888379e+03 -4.60063281e+03 -4.44211377e+03 -4.35296826e+03 -4.38243115e+03 -4.43677100e+03 -4.31603418e+03 -4.26441699e+03 -4.17363818e+03 -4.20995410e+03 -4.30880908e+03 -4.15801953e+03 -4.09363525e+03 -4.06653149e+03 -3.97250391e+03 -4.01127075e+03 -3.98118213e+03 -3.88789429e+03 -3.80855103e+03 -3.80134277e+03 -3.87134741e+03 -3.81698291e+03 -3.74017993e+03 -3.61473267e+03 -3.55669360e+03 -3.65135449e+03 -3.63692822e+03 -3.53214966e+03 -3.39332788e+03 -3.32106787e+03 -3.39888110e+03 -3.41899609e+03 -3.32939819e+03 -3.21133423e+03 -3.17246362e+03 -3.16273730e+03 -3.15528760e+03 -3.15967651e+03 -3.03348169e+03 -2.96816016e+03 -2.99442725e+03 -2.93125854e+03 -2.85717065e+03 -2.79788354e+03 -2.79991821e+03 -2.77419556e+03 -2.67803369e+03 -2.62265015e+03 -2.56243970e+03 -2.56698096e+03 -2.61319604e+03 -2.51442529e+03 -2.37584277e+03 -2.32163330e+03 -2.32544678e+03 -2.34042334e+03 -2.31591699e+03 -2.26934473e+03 -2.13162793e+03 -2.01662231e+03 -2.05172363e+03 -2.08385352e+03 -2.02726257e+03 -1.90115381e+03 -1.84247681e+03 -1.84584119e+03 -1.81617859e+03 -1.78465784e+03 -1.70741003e+03 -1.64937439e+03 -1.62573267e+03 -1.56836670e+03 -1.51346643e+03 -1.46150159e+03 -1.41677515e+03 -1.40018530e+03 -1.33743213e+03 -1.27275171e+03 -1.22011755e+03 -1.18861145e+03 -1.15865186e+03 -1.09119910e+03 -1.04015393e+03 -9.88468262e+02 -9.69221863e+02 -9.40543884e+02 -8.65147583e+02 -8.04494446e+02 -7.46227600e+02 -7.04826782e+02 -6.87088562e+02 -6.39105408e+02 -5.80478088e+02 -5.14886230e+02 -4.65103973e+02 -4.44749023e+02 -4.00958527e+02 -3.36307007e+02 -2.87115143e+02 -2.45058502e+02 -1.94987457e+02 -1.41559967e+02 -8.84474869e+01 -3.91951599e+01 8.20446110e+00 5.35243645e+01 1.01755135e+02 1.43806030e+02 1.80741074e+02 2.36822479e+02 2.92997009e+02 3.40376221e+02 3.88139923e+02 4.28286621e+02 4.89454193e+02 5.36475830e+02 5.54824951e+02 5.96217224e+02 6.57164612e+02 7.35535889e+02 8.12223328e+02 8.38451965e+02 8.38963379e+02 8.62230713e+02 9.28910217e+02 1.03025403e+03 1.11482483e+03 1.13007410e+03 1.11177515e+03 1.15561633e+03 1.28223572e+03 1.32511536e+03 1.30540039e+03 1.34812341e+03 1.41188574e+03 1.46116394e+03 1.55696472e+03 1.58131763e+03 1.56422778e+03 1.64960730e+03 1.67530457e+03 1.75499646e+03 1.84029675e+03 1.80136572e+03 1.88796497e+03 1.98444373e+03 1.98333301e+03 2.02431482e+03 2.07614600e+03 2.13326587e+03 2.17978809e+03 2.21011133e+03 2.19974365e+03 2.23897095e+03 2.39647656e+03 2.51653101e+03 2.50281421e+03 2.42949951e+03 2.41483179e+03 2.50641797e+03 2.66622803e+03 2.79151685e+03 2.77300781e+03 2.67355005e+03 2.72798242e+03 2.85629395e+03 2.88904980e+03 2.90176147e+03 2.94837354e+03 3.00354956e+03 3.03885278e+03 3.17712231e+03 3.15187671e+03 3.10993408e+03 3.22231006e+03 3.18286011e+03 3.30491919e+03 3.42676270e+03 3.37465894e+03 3.53337109e+03 3.48874438e+03 3.38275293e+03 3.55009741e+03 3.51197412e+03 3.60336255e+03 3.90040942e+03 3.75401831e+03 3.55662305e+03 3.66363428e+03 3.90649243e+03 4.10819238e+03 4.04292017e+03 3.87124512e+03 3.82351685e+03 3.91708716e+03 4.12103809e+03 4.31555420e+03 4.25972510e+03 4.08023486e+03 4.11259521e+03 4.27282910e+03 4.32290186e+03 4.31422559e+03 4.33486572e+03 4.39490918e+03 4.43472021e+03 4.61710059e+03 4.66087207e+03 4.40399316e+03 4.43413428e+03 4.63784473e+03 4.66956982e+03 4.70108740e+03 4.73703516e+03 4.89323242e+03 4.81793066e+03 4.69115967e+03 4.85408740e+03 4.74944238e+03 4.92251172e+03 5.26149072e+03 4.99604932e+03 4.75462939e+03 4.92905957e+03 5.20725391e+03 5.39978564e+03 5.36465088e+03 5.08053467e+03 4.94234521e+03 5.10878564e+03 5.40485547e+03 5.59556104e+03 5.47480762e+03 5.21586816e+03 5.25281592e+03 5.44641846e+03 5.50742383e+03 5.62291797e+03 5.67841406e+03 5.41934473e+03 5.41198486e+03 5.71752881e+03 5.78112012e+03 5.54414355e+03 5.53051074e+03 5.70297314e+03 5.71176221e+03 5.89036133e+03 5.98162646e+03 5.76233105e+03 5.75651416e+03 5.77065381e+03 5.79168652e+03 5.92320020e+03 5.91345508e+03 6.09054785e+03 6.20602832e+03 6.01832324e+03 5.85808398e+03 5.77599023e+03 6.06721680e+03 6.42459424e+03 6.27623145e+03 6.01024951e+03 5.84497705e+03 6.09370410e+03 6.47134180e+03 6.30619385e+03 5.97491797e+03 6.06206152e+03 6.27884521e+03 6.47561475e+03 6.71559668e+03 6.53543896e+03 6.16402393e+03 6.14455078e+03 6.36001074e+03 6.43546240e+03 6.50252002e+03 6.48114062e+03 6.47607178e+03 6.42538281e+03 6.58660352e+03 6.57884375e+03 6.39951465e+03 6.42222461e+03 6.38454688e+03 6.65577441e+03 6.76671973e+03 6.55536914e+03 6.68839453e+03 6.67486475e+03 6.62956445e+03 6.52575537e+03 6.42036768e+03 6.67918262e+03 7.01343066e+03 6.86977490e+03 6.57002637e+03 6.48408789e+03 6.80282080e+03 6.98557666e+03 6.87660254e+03 6.78716895e+03 6.56079590e+03 6.57763623e+03 6.84480273e+03 6.87471826e+03 6.68179883e+03 6.57841162e+03 6.55171338e+03 6.94917871e+03 7.18111377e+03 6.79905615e+03 6.62734229e+03 6.85406104e+03 6.86293506e+03 7.03665869e+03 6.99315967e+03 6.61302246e+03 6.67844971e+03 6.89776953e+03 6.87583643e+03 6.94680762e+03 7.03772900e+03 7.00350000e+03 6.72372754e+03 6.51572510e+03 6.81254590e+03 8.82628223e+03 9.39485938e+03 1.08743096e+04 1.05714658e+04 1.00459355e+04 9.99489844e+03 1.03720049e+04 1.12669785e+04 1.08908496e+04 1.08230840e+04 1.07158145e+04 1.72102969e+04 2.59632656e+04 7.84434350e+06 -26928992. 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. 0. 0. 0. 0. 0. 0. 50713344. -4564874. 1.91930650e+06 1671625. 33559880. 1.82845879e+04 1.61365039e+04 9.78323535e+03 7.05129004e+03 6.71452588e+03 6.33305957e+03 6.10796436e+03 6.41408545e+03 6.39524365e+03 6.20949658e+03 6.21388916e+03 6.17318604e+03 6.13648193e+03 6.13092432e+03 6.08494971e+03 6.02669727e+03 6.04992871e+03 5.98799170e+03 6.02618994e+03 6.02551904e+03 5.81105615e+03 5.80323584e+03 6.06837012e+03 6.04048340e+03 5.87587451e+03 5.81656006e+03 5.80263965e+03 5.78826074e+03 5.80451660e+03 5.75805420e+03 5.68446533e+03 5.65573389e+03 5.57145654e+03 5.53575488e+03 5.69354297e+03 5.67783496e+03 5.54479932e+03 5.51482568e+03 5.50818359e+03 5.49259033e+03 5.41881445e+03 5.38306787e+03 5.37458496e+03 5.27049463e+03 5.22099268e+03 5.20612744e+03 5.16498682e+03 5.37654785e+03 5.37076758e+03 5.16488135e+03 4.96762158e+03 4.92270312e+03 5.20389551e+03 5.20097412e+03 4.98334863e+03 4.84095605e+03 4.81738037e+03 4.88022559e+03 4.82410547e+03 4.97031494e+03 4.92646973e+03 4.59331055e+03 4.48426855e+03 4.68756152e+03 4.92335010e+03 4.74854590e+03 4.58023975e+03 4546. 4.47187012e+03 4.47655518e+03 4.47472363e+03 4.37592529e+03 4.30942480e+03 4.29267676e+03 4.25503564e+03 4.23200684e+03 4.18617383e+03 4.26713525e+03 4.22895459e+03 4.07597754e+03 4.00511426e+03 3.97912964e+03 4.06518213e+03 4.03246924e+03 3.90890430e+03 3.88248193e+03 3.74006934e+03 3.61077124e+03 3.75992676e+03 3.77542529e+03 3.53799707e+03 3.52434521e+03 3.68839868e+03 3.75173779e+03 3.60064673e+03 3.44627979e+03 3.41596338e+03 3.39360645e+03 3.30622900e+03 3.25024756e+03 3.24199854e+03 3.18320215e+03 3.25238599e+03 3.19696680e+03 3.06118872e+03 3.01422559e+03 2.90381177e+03 2.93550757e+03 3.05081152e+03 2.95339819e+03 2.83714819e+03 2.72145801e+03 2.64214624e+03 2.75345752e+03 2.76087451e+03 2.62613672e+03 2.50548169e+03 2.45430884e+03 2.46691968e+03 2.42157861e+03 2.45595020e+03 2.43201025e+03 2.29567334e+03 2.20231909e+03 2.15916113e+03 2.20034204e+03 2.16073682e+03 2.07093384e+03 2.01089062e+03 1.95840417e+03 1.90514270e+03 1.81569495e+03 1.82111267e+03 1.87671155e+03 1.79881689e+03 1.70501758e+03 1.61573804e+03 1.56107483e+03 1.60543250e+03 1.56651013e+03 1.47478638e+03 1.38752502e+03 1.33646887e+03 1.33354785e+03 1.28190308e+03 1.23314441e+03 1.15543445e+03 1.13359143e+03 1.14289587e+03 1.06163293e+03 1.00126160e+03 9.61681519e+02 9.10656311e+02 8.43493591e+02 7.95380981e+02 7.51033020e+02 7.01898193e+02 6.61087646e+02 5.99775269e+02 5.67632690e+02 5.50669006e+02 4.77946686e+02 4.15644440e+02 3.78874329e+02 3.30820343e+02 2.91835114e+02 2.39029373e+02 1.82306839e+02 1.40362442e+02 9.50325851e+01 4.76190567e+01 -1.86541781e-01 -4.80589943e+01 -9.67408829e+01 -1.45923904e+02 -1.92906219e+02 -2.32609467e+02 -2.88388367e+02 -3.56502869e+02 -3.95351685e+02 -4.29274689e+02 -4.66070496e+02 -5.21036621e+02 -5.99914124e+02 -6.42330627e+02 -6.71955444e+02 -7.01828552e+02 -7.43127075e+02 -8.14286743e+02 -8.62474304e+02 -9.28420166e+02 -9.67851196e+02 -9.88828613e+02 -1.05053552e+03 -1.09204431e+03 -1.17199976e+03 -1.22668103e+03 -1.23924365e+03 -1.27931653e+03 -1.32619336e+03 -1.37643860e+03 -1.38503723e+03 -1.45471826e+03 -1.58331824e+03 -1.61040417e+03 -1.61301501e+03 -1.61578870e+03 -1.65342346e+03 -1.79573877e+03 -1.84718652e+03 -1.84225269e+03 -1.84816650e+03 -1.88160522e+03 -1.98911462e+03 -2.03378613e+03 -2.11902100e+03 -2.15775122e+03 -2.14072656e+03 -2.16574438e+03 -2.20929980e+03 -2.35594482e+03 -2.40904199e+03 -2.38650269e+03 -2.39574731e+03 -2.43271094e+03 -2.56920410e+03 -2.62360718e+03 -2.53874365e+03 -2.58434888e+03 -2.78817480e+03 -2.81424609e+03 -2.71520142e+03 -2.74900830e+03 -2.93760034e+03 -3.01076221e+03 -2.94703589e+03 -2.91317310e+03 -2.97010376e+03 -3.18548828e+03 -3.20344043e+03 -3.15573584e+03 -3.23482837e+03 -3.25458740e+03 -3.22218652e+03 -3.26981689e+03 -3.39743042e+03 -3.35957788e+03 -3.45174805e+03 -3.63692578e+03 -3.59753296e+03 -3.66148901e+03 -3.69381689e+03 -3.66981909e+03 -3.71992163e+03 -3.74269214e+03 -3.78205469e+03 -3.75024634e+03 -3.74341357e+03 -3.85991479e+03 -3.98042676e+03 -4.13518164e+03 -4.02628491e+03 -3.95578589e+03 -4.11457471e+03 -4.14618604e+03 -4.30351465e+03 -4.32943262e+03 -4.24804492e+03 -4.20712402e+03 -4.21379639e+03 -4.37260107e+03 -4.40796045e+03 -4.53032080e+03 -4.57258643e+03 -4.49334912e+03 -4.50536328e+03 -4.42934082e+03 -4.58885400e+03 -4.86699756e+03 -4.83147510e+03 -4.73523682e+03 -4.65507568e+03 -4.67270264e+03 -4.92243945e+03 -4.99539307e+03 -4.91936133e+03 -4.82421631e+03 -4.83189160e+03 -4.97291504e+03 -5.02513037e+03 -5.19232568e+03 -5.19632520e+03 -5.09690869e+03 -5.12915430e+03 -5.13358203e+03 -5.30142676e+03 -5.36313818e+03 -5.13838965e+03 -5.16276074e+03 -5.50115479e+03 -5.42173291e+03 -5.16489600e+03 -5.36408447e+03 -5.68058643e+03 -5.65837891e+03 -5.53997949e+03 -5.39111230e+03 -5.43911377e+03 -5.77815771e+03 -5.78243213e+03 -5.64517139e+03 -5.55674414e+03 -5.53397217e+03 -5.69126855e+03 -5.76744775e+03 -5.80744092e+03 -5.68422266e+03 -5.81313916e+03 -6.13307812e+03 -6.01262793e+03 -5.94754395e+03 -5.94933350e+03 -5.92044482e+03 -5.98093408e+03 -6.00491553e+03 -6.05963037e+03 -6.04727002e+03 -6.04591064e+03 -5.93036621e+03 -6.01322217e+03 -6.36807227e+03 -6.12798291e+03 -5.93673779e+03 -6.11170605e+03 -6.33016895e+03 -6.51271777e+03 -6.42453467e+03 -6.28394873e+03 -6.34408545e+03 -6.31216016e+03 -6.21240234e+03 -6.21528711e+03 -6.44626270e+03 -6.48475244e+03 -6.33765674e+03 -6.31811719e+03 -6.17893262e+03 -6.39631152e+03 -6.80970508e+03 -6.62236719e+03 -6.49030762e+03 -6.34965039e+03 -6.35512256e+03 -6.72032178e+03 -6.82804688e+03 -6.62324414e+03 -6.46759814e+03 -6.44858545e+03 -6.55834229e+03 -6.59645068e+03 -6.81422510e+03 -6.77623486e+03 -6.59104736e+03 -6.61855078e+03 -6.62863818e+03 -6.78819287e+03 -6.80647119e+03 -6.63550049e+03 -6.76814355e+03 -6.77948486e+03 -6.65491504e+03 -6.47938330e+03 -6.69338477e+03 -7.03464893e+03 -6.93553955e+03 -6.79019434e+03 -6.62136182e+03 -6.63171875e+03 -7.03876172e+03 -7.04508252e+03 -6.79216406e+03 -6.68084717e+03 -6.63885791e+03 -6.74823682e+03 -6.74144922e+03 -6.83269434e+03 -6.71832178e+03 -6.84301367e+03 -7.11669678e+03 -6.87305322e+03 -6.94229688e+03 -6.99461914e+03 -6.83217578e+03 -6.89319043e+03 -6.85920068e+03 -6.67735352e+03 -6.69716992e+03 -6.89490332e+03 -6.94339160e+03 -6.93962695e+03 -6.91828760e+03 -6.68497266e+03 -6.62981982e+03 -6.85077686e+03 -6.87266455e+03 -7.04007715e+03 -6.94446533e+03 -6.68925439e+03 -6.83688135e+03 -6.94245801e+03 -6.87594141e+03 -6.75253906e+03 -6.70151025e+03 -6.82444141e+03 -6.80585205e+03 -6.73511621e+03 -6.63420410e+03 -6.72018848e+03 -7.03516113e+03 -6.97952246e+03 -6.74962256e+03 -6.54479150e+03 -6.59709814e+03 -6.90113379e+03 -6.88724023e+03 -6.73259180e+03 -6.54975928e+03 -6.41858789e+03 -6.61831055e+03 -6.75103125e+03 -6.97014258e+03 -6.72070361e+03 -6.41996191e+03 -6.53556982e+03 -6.60041846e+03 -6.78401611e+03 -6.64052783e+03 -6.43597998e+03 -6.60466260e+03 -6.58090918e+03 -6.54196533e+03 -6.36961426e+03 -6.39345703e+03 -6.74697412e+03 -6.67635498e+03 -6.45106006e+03 -6.26153906e+03 -6.29339600e+03 -6.61716309e+03 -6.56560693e+03 -6.38808740e+03 -6.21661328e+03 -6.15175537e+03 -6.31154688e+03 -6.29051172e+03 -6.50121973e+03 -6.42870264e+03 -6.16798535e+03 -6.03125391e+03 -6.08778027e+03 -6.39756592e+03 -6.24140381e+03 -6.06604053e+03 -6.16126758e+03 -6.17312646e+03 -5.95470703e+03 -5.84156250e+03 -6.06306250e+03 -5.98965820e+03 -5.83150977e+03 -6.10720020e+03 -6.15332959e+03 -5.94872803e+03 -5.88575879e+03 -5.84201465e+03 -5.84013037e+03 -5.67660352e+03 -5.61338135e+03 -5.85348535e+03 -5.90691064e+03 -5.58151611e+03 -5.43763623e+03 -5.65324463e+03 -5.83843652e+03 -5.76308789e+03 -5.54874658e+03 -5.38048291e+03 -5.53533789e+03 -5.65760254e+03 -5.54139453e+03 -5.43886914e+03 -5.25526562e+03 -5.09845459e+03 -5.34595361e+03 -5.57138574e+03 -5.41172754e+03 -5.15306445e+03 -5.06505615e+03 -5.30382666e+03 -5.34310254e+03 -5.13289697e+03 -4.96331885e+03 -4.89810693e+03 -4.93511816e+03 -4.95211621e+03 -5.10594824e+03 -5.06174219e+03 -4.85615186e+03 -4.82450781e+03 -4.78606348e+03 -4.86444629e+03 -4.73064209e+03 -4.60191992e+03 -4.78819482e+03 -4.77624658e+03 -4.58940332e+03 -4.41152832e+03 -4.46979297e+03 -4.70379102e+03 -4.48427100e+03 -4.26424268e+03 -4.35860010e+03 -4.40842432e+03 -4.37313818e+03 -4.29058301e+03 -4.36136182e+03 -4.36564893e+03 -4.18035205e+03 -4.01243091e+03 -3.98539771e+03 -4.17427832e+03 -4.07944922e+03 -3.91895654e+03 -3.94107886e+03 -3.91166455e+03 -3.85904785e+03 -3.78816357e+03 -3.81684082e+03 -3.74186304e+03 -3.63963159e+03 -3.70149731e+03 -3.66285938e+03 -3.64193335e+03 -3.60611230e+03 -3.51827417e+03 -3.44462646e+03 -3.30335156e+03 -3.29490283e+03 -3.42858496e+03 -3.42452344e+03 -3.21740039e+03 -3.08055566e+03 -3.15532471e+03 -3.23386426e+03 -3.16028369e+03 -3.00738989e+03 -2.87348926e+03 -2.95886035e+03 -2.99754370e+03 -2.86862939e+03 -2.88544482e+03 -2.80934082e+03 -2.65833643e+03 -2.67471265e+03 -2.72992310e+03 -2.66233813e+03 -2.49762134e+03 -2.41592065e+03 -2.50719458e+03 -2.52899878e+03 -2.39933740e+03 -2.26910474e+03 -2.20992529e+03 -2.29470532e+03 -2.25448340e+03 -2.13014062e+03 -2.10929468e+03 -2.07245996e+03 -2.00854822e+03 -1.95094080e+03 -1.98052441e+03 -1.89771045e+03 -1.78215564e+03 -1.82445105e+03 -1.79083508e+03 -1.71463171e+03 -1.63545044e+03 -1.56887610e+03 -1.62927612e+03 -1.58028259e+03 -1.37233447e+03 -1.41075427e+03 -1.68390649e+03 -1.48979895e+03 -1.94737268e+03 -1.90088684e+03 -1.83326099e+03 -1.72296509e+03 -1.60394470e+03 -1.51890796e+03 -1.57673633e+03 -1.51268274e+03 -1.43054565e+03 -1.50675854e+03 -1.11621619e+03 -1.21971826e+03 -1.11638008e+04 -3.44552986e+09 0. 0. 0. 0. 0. 0. 0. -257262672. 6.40989188e+05 -3.54991016e+04 -1.90519080e+03 -3.10861230e+03 -637180544. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1331396224. -2.41632969e+05 3.95746307e+02 9.62290955e+02 1.00892035e+03 1.10082861e+03 6.99709839e+02 9.63120361e+02 1.00717181e+03 1.00523920e+03 1.06563086e+03 1.11893933e+03 1.16110608e+03 1.17546399e+03 1.22106067e+03 1.30391174e+03 1.34132373e+03 1.37280957e+03 1.41352344e+03 1.44829895e+03 1.53500342e+03 1.58996582e+03 1.60420007e+03 1.65034656e+03 1.67754382e+03 1.73167285e+03 1.84040833e+03 1.89237903e+03 1.87924780e+03 1.90875476e+03 1.98310596e+03 2.03522363e+03 2.05538477e+03 2.09563477e+03 2.15838159e+03 2.20667236e+03 2.28252417e+03 2.32156958e+03 2.28792090e+03 2.36108936e+03 2.49076489e+03 2.55137427e+03 2.57890332e+03 2.51731055e+03 2.53321606e+03 2.66406714e+03 2.74287598e+03 2.75971704e+03 2.75309814e+03 2.80050317e+03 2.89760229e+03 2.96953784e+03 2.98879248e+03 2.94264380e+03 2.97175049e+03 3.17610229e+03 3.23241748e+03 3.10724902e+03 3.13082617e+03 3.26060278e+03 3.35373584e+03 3.44775122e+03 3.40652148e+03 3.32797119e+03 3.40492505e+03 3.53626587e+03 3.60705737e+03 3.60604102e+03 3.57481470e+03 3.65642358e+03 3.75816553e+03 3.77589380e+03 3.77001538e+03 3.75276807e+03 3.84793115e+03 3.97173950e+03 3.98969458e+03 4.03173633e+03 4.02897192e+03 3.97200977e+03 4.08929883e+03 4.18161523e+03 4.20095312e+03 4.25036914e+03 4.23584570e+03 4.26073633e+03 4.40552979e+03 4.42778906e+03 4.32501172e+03 4.37421191e+03 4.49983301e+03 4.56555908e+03 4.59044092e+03 4.55015820e+03 4.57476611e+03 4.66159375e+03 4.73983105e+03 4.74949756e+03 4.66525830e+03 4.76696631e+03 4.92288916e+03 4.92049170e+03 4.91866113e+03 4.85789648e+03 4.89145068e+03 5.08256836e+03 5.07049170e+03 4.99527979e+03 5.02457227e+03 5.09607373e+03 5.22300342e+03 5.23521826e+03 5.19965039e+03 5.25671338e+03 5.28580469e+03 5.36301123e+03 5.40929980e+03 5.33702881e+03 5.37848975e+03 5.43533008e+03 5.40652344e+03 5.51306055e+03 5.54752588e+03 5.56394189e+03 5.58164307e+03 5.55875830e+03 5.59335693e+03 5.67997705e+03 5.72531738e+03 5.73199121e+03 5.71290918e+03 5.69135547e+03 5.72700684e+03 5.83620508e+03 5.83378320e+03 5.79479199e+03 5.84741357e+03 6.02396533e+03 6.05586914e+03 5.90743164e+03 5.97034424e+03 6.02802588e+03 6.02838965e+03 6.00022314e+03 5.99413525e+03 6.03901562e+03 6.15110156e+03 6.26264941e+03 6.25710254e+03 6.15761865e+03 6.05490283e+03 6.17178613e+03 6.29136816e+03 6.31607617e+03 6.28917871e+03 6.22909326e+03 6.30160059e+03 6.41632031e+03 6.43770801e+03 6.28269922e+03 6.22683936e+03 6.36212598e+03 6.56629980e+03 6.53287158e+03 6.29318701e+03 6.32938428e+03 6.55113477e+03 6.56876807e+03 6.50290332e+03 6.53064014e+03 6.58270508e+03 6.54089893e+03 6.59174463e+03 6.56259814e+03 6.45837891e+03 6.62713965e+03 6.71111475e+03 6.64294482e+03 6.67637939e+03 6.67085059e+03 6.58819336e+03 6.61304688e+03 6.71938477e+03 6.78053125e+03 6.82042236e+03 6.59713623e+03 6.59290820e+03 6.91898389e+03 6.75034473e+03 6.58931152e+03 6.73812695e+03 6.80043652e+03 6.82097217e+03 6.79906885e+03 6.79521191e+03 6.70965430e+03 6.66802344e+03 6.88357617e+03 6.98894336e+03 6.67996631e+03 6.76658594e+03 6.95459961e+03 6.85523438e+03 6.84749902e+03 6.75268164e+03 6.69636719e+03 6.87163965e+03 6.92709863e+03 6.78490723e+03 6.84912109e+03 6.74086816e+03 6.82628418e+03 6.96085059e+03 6.83105322e+03 6.82192822e+03 6.85313477e+03 6.89554883e+03 6.82078418e+03 6.83031445e+03 6.83038428e+03 6.76246191e+03 6.77152295e+03 6.88567041e+03 6.84652930e+03 6.77287646e+03 6.89943115e+03 6.92631885e+03 6.87024268e+03 6.95089648e+03 6.75521387e+03 6.64118945e+03 6.80529980e+03 6.83075098e+03 6.77448145e+03 6.67737842e+03 6.60666504e+03 6.76367090e+03 6.91433008e+03 6.74838818e+03 6.68081055e+03 6.80284863e+03 6.76134473e+03 6.65437598e+03 6.59008643e+03 6.78208301e+03 6.73212793e+03 6.58335352e+03 6.75180273e+03 6.67251025e+03 6.59511182e+03 6.66346143e+03 6.58314648e+03 6.52259961e+03 6.59977197e+03 6.54482471e+03 6.50340527e+03 6.61223584e+03 6.60464502e+03 6.58803174e+03 6.43164502e+03 6.36217920e+03 6.49885596e+03 6.43812061e+03 6.47620752e+03 6.42820215e+03 6.36013184e+03 6.34159424e+03 6.36886670e+03 6.49081250e+03 6.33331055e+03 6.06380127e+03 6.30775244e+03 6.55815918e+03 6.24960107e+03 6.08126465e+03 6.15423389e+03 6.12964209e+03 6.24470654e+03 6.23791699e+03 6.07082373e+03 6.02724512e+03 6.11678662e+03 6.10966064e+03 6.13444922e+03 6.03938184e+03 6.02637598e+03 6.07793750e+03 5.80834619e+03 5.86709717e+03 5.96755713e+03 5.82136670e+03 5.93418799e+03 5.86804932e+03 5.72075781e+03 5.81114941e+03 5.73533154e+03 5.73176904e+03 5.86382227e+03 5.74331934e+03 5.62158691e+03 5.54122607e+03 5.46034473e+03 5.60268164e+03 5.66188965e+03 5.48241553e+03 5.44542188e+03 5.52949658e+03 5.48496875e+03 5.43930127e+03 5.32662988e+03 5.29425684e+03 5.28412451e+03 5.30705859e+03 5.32995410e+03 5.15384521e+03 5.08294238e+03 5.17241748e+03 5.17498145e+03 5.12371729e+03 5.09916211e+03 5.01286768e+03 4.93374072e+03 5.07150000e+03 5.09573486e+03 4.88115039e+03 4.70314307e+03 4.75709717e+03 4.81925684e+03 4.76108447e+03 4.69881934e+03 4.70384668e+03 4.68914258e+03 4.64840039e+03 4.64950244e+03 4.55781836e+03 4.48255859e+03 4.50936475e+03 4.50054980e+03 4.40238818e+03 4.29493799e+03 4.31459668e+03 4.28249268e+03 4.26187402e+03 4.27699561e+03 4.18354248e+03 4.09408154e+03 4.10491357e+03 4.13912793e+03 4.06309595e+03 3.96343311e+03 3.93400171e+03 3.90292334e+03 3.86901855e+03 3.82193408e+03 3.74274512e+03 3.71705640e+03 3.72455127e+03 3.71319580e+03 3.69867676e+03 3.59725684e+03 3.54223926e+03 3.50523193e+03 3.44585205e+03 3.40596704e+03 3.34120337e+03 3.35212280e+03 3.33188184e+03 3.23938550e+03 3.16034692e+03 3.13708813e+03 3.15048755e+03 3.14527075e+03 3.11458887e+03 3.00197217e+03 2.94049390e+03 2.90478516e+03 2.81523193e+03 2.79946313e+03 2.79672729e+03 2.74589380e+03 2.68363696e+03 2.60375415e+03 2.57154028e+03 2.57778027e+03 2.57521143e+03 2.52743677e+03 2.42431738e+03 2.34101636e+03 2.32636572e+03 2.28899878e+03 2.22395215e+03 2.22226099e+03 2.20325781e+03 2.09923975e+03 2.02532666e+03 1.98561499e+03 1.95603247e+03 1.97619666e+03 1.93249402e+03 1.82098560e+03 1.78840405e+03 1.73551721e+03 1.65798193e+03 1.66197742e+03 1.63067053e+03 1.54485205e+03 1.49250061e+03 1.43527734e+03 1.37709387e+03 1.38677051e+03 1.38347852e+03 1.29244275e+03 1.22086011e+03 1.17663562e+03 1.13219983e+03 1.08981445e+03 1.04049707e+03 9.99547241e+02 9.43144775e+02 8.83486755e+02 8.48905884e+02 8.13174377e+02 7.55251953e+02 7.16956787e+02 6.77921265e+02 6.10068481e+02 5.50785828e+02 5.12277466e+02 4.77068390e+02 4.35471344e+02 3.84140106e+02 3.24803589e+02 2.72151093e+02 2.34826828e+02 1.96936295e+02 1.50642319e+02 9.67970734e+01 4.43575211e+01 -8.97770119e+00 -5.86255608e+01 -1.02122314e+02 -1.42374466e+02 -1.85149002e+02 -2.34532333e+02 -2.96866547e+02 -3.44885406e+02 -3.77832428e+02 -4.34792084e+02 -4.96613861e+02 -5.37577820e+02 -5.75047363e+02 -6.19989563e+02 -6.73288574e+02 -7.26297729e+02 -7.67021545e+02 -8.16859375e+02 -8.44441223e+02 -8.92651855e+02 -9.64718262e+02 -1.00751508e+03 -1.06955627e+03 -1.10503381e+03 -1.13606775e+03 -1.19065051e+03 -1.24668140e+03 -1.29672229e+03 -1.33072339e+03 -1.39215869e+03 -1.44881445e+03 -1.46998792e+03 -1.50055115e+03 -1.55052649e+03 -1.60141650e+03 -1.68641248e+03 -1.73119849e+03 -1.73924170e+03 -1.78530957e+03 -1.82224561e+03 -1.89596179e+03 -1.96463855e+03 -1.97470154e+03 -2.00196118e+03 -2.08809082e+03 -2.12912646e+03 -2.14520068e+03 -2.24861157e+03 -2.28596899e+03 -2.27805542e+03 -2.34697754e+03 -2.34950928e+03 -2.39657471e+03 -2.52906934e+03 -2.55386182e+03 -2.56025488e+03 -2.63442773e+03 -2.66638867e+03 -2.63316724e+03 -2.69367456e+03 -2.80217480e+03 -2.83457666e+03 -2.89482300e+03 -2.91311304e+03 -2.92756128e+03 -3.01417188e+03 -3.08666626e+03 -3.19066162e+03 -3.16032080e+03 -3.08231030e+03 -3.17158228e+03 -3.25377612e+03 -3.32806470e+03 -3.40023315e+03 -3.37237378e+03 -3.33221411e+03 -3.48076074e+03 -3.57472485e+03 -3.52037256e+03 -3.60961255e+03 -3.64980835e+03 -3.62687207e+03 -3.72526758e+03 -3.77191943e+03 -3.74394385e+03 -3.90291382e+03 -3.94377979e+03 -3.90450366e+03 -3.93905103e+03 -3.86362549e+03 -3.92640137e+03 -4.10308545e+03 -4.25932764e+03 -4.23259131e+03 -4.04901440e+03 -4.11074658e+03 -4.30993799e+03 -4.31958984e+03 -4.30875830e+03 -4.35501514e+03 -4.36317871e+03 -4.44537256e+03 -4.50286963e+03 -4.55097461e+03 -4.54771289e+03 -4.58117822e+03 -4.69320947e+03 -4.66750146e+03 -4.63314258e+03 -4.67536914e+03 -4.72516602e+03 -4.81680957e+03 -4.92363281e+03 -4.87169092e+03 -4.77857373e+03 -4.90186230e+03 -4.99271533e+03 -5.13342188e+03 -5.11977930e+03 -4.93425293e+03 -5.04850488e+03 -5.13934766e+03 -5.20852588e+03 -5.32024658e+03 -5.27844971e+03 -5.19295605e+03 -5.24167432e+03 -5.23537549e+03 -5.22363281e+03 -5.44698193e+03 -5.56525098e+03 -5.44863916e+03 -5.38400732e+03 -5.38655420e+03 -5.44587061e+03 -5.65276514e+03 -5.68232324e+03 -5.63843945e+03 -5.59895898e+03 -5.50352832e+03 -5.61016504e+03 -5.71197314e+03 -5.84875879e+03 -5.88177100e+03 -5.70742822e+03 -5.76386035e+03 -5.79108643e+03 -5.85683545e+03 -5.94734570e+03 -5.97301074e+03 -6.04166455e+03 -5.90133008e+03 -5.90569580e+03 -5.99544092e+03 -5.99889209e+03 -6.04092871e+03 -6.12707520e+03 -6.16013770e+03 -6.13589648e+03 -6.07363281e+03 -6.15053906e+03 -6.31010742e+03 -6.27280127e+03 -6.14663916e+03 -6.18541748e+03 -6.22480811e+03 -6.19813232e+03 -6.45563379e+03 -6.43088525e+03 -6.23512988e+03 -6.39504102e+03 -6.31068115e+03 -6.31313330e+03 -6.60402881e+03 -6.48399268e+03 -6.50806299e+03 -6.62666797e+03 -6.59817920e+03 -6.97266650e+03 -8.57433789e+03 -8.70354395e+03 -1.08767119e+04 -9.59608789e+03 -1.72946758e+04 -2.92452227e+04 -9259576. 11414557. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70624112. -1.05716977e+05 -1.44007520e+04 -9.60143652e+03 -8.70701953e+03 -7.40422217e+03 -6.88731152e+03 -6.99745850e+03 -7.14441064e+03 -6.95593701e+03 -6.83719727e+03 -6.66962061e+03 -6.69961914e+03 -6.89580518e+03 -7.01274658e+03 -6.86707520e+03 -6.75839160e+03 -6.72035498e+03 -6.74433984e+03 -6.90140479e+03 -6.81267773e+03 -6.57999561e+03 -6.63072900e+03 -6.80874121e+03 -6.77953125e+03 -6.59906006e+03 -6.50191895e+03 -6.70622461e+03 -6.98350293e+03 -6.94457471e+03 -6.57445459e+03 -6.31230078e+03 -6.47727734e+03 -6.74204248e+03 -6.89728760e+03 -6.74566357e+03 -6.45960352e+03 -6.46961035e+03 -6.57631934e+03 -6.76819336e+03 -6.65133008e+03 -6.30749463e+03 -6.38617090e+03 -6.71267432e+03 -6.56753467e+03 -6.34661816e+03 -6.41598584e+03 -6.43136572e+03 -6.51162793e+03 -6.50652979e+03 -6.21430518e+03 -6.12199609e+03 -6.43784912e+03 -6.60053760e+03 -6.47329590e+03 -6.18242334e+03 -6.01032422e+03 -6.32413086e+03 -6.50707373e+03 -6.30144385e+03 -6.11518408e+03 -5.90233301e+03 -5.97203516e+03 -6.24913867e+03 -6.32013330e+03 -6.20084375e+03 -6.07919678e+03 -6.06949512e+03 -5.98564355e+03 -5.96590527e+03 -6.00310889e+03 -5.79166504e+03 -5.84943311e+03 -6.06686279e+03 -5.94620557e+03 -5.67293848e+03 -5.59566504e+03 -5.86749316e+03 -6.03560254e+03 -5.86896680e+03 -5.68414795e+03 -5.51714648e+03 -5.49406982e+03 -5.64563281e+03 -5.86388574e+03 -5.73359912e+03 -5.39876562e+03 -5.43028711e+03 -5.47726807e+03 -5.50402881e+03 -5.59060742e+03 -5.35529980e+03 -5.35826855e+03 -5.48593652e+03 -5.37003906e+03 -5.26342139e+03 -5.19499902e+03 -5.21367529e+03 -5.31903369e+03 -5.24324414e+03 -5.05156348e+03 -4.98340039e+03 -5.12137744e+03 -5.17408594e+03 -5.12168018e+03 -5.00825928e+03 -4.82482617e+03 -4.85004297e+03 -5.00909082e+03 -4.97172754e+03 -4.83367627e+03 -4.61842188e+03 -4.60433496e+03 -4.79018555e+03 -4.88344287e+03 -4.72218945e+03 -4.49227295e+03 -4.49288770e+03 -4.61312256e+03 -4.54964893e+03 -4.41340479e+03 -4.33095020e+03 -4.43550781e+03 -4.47880762e+03 -4.30111328e+03 -4.24311035e+03 -4.16716455e+03 -4.22580713e+03 -4.34987793e+03 -4.23027734e+03 -4.08349878e+03 -3.97092017e+03 -3.95214038e+03 -3.99541675e+03 -4.03596973e+03 -3967. -3.75616382e+03 -3.72902466e+03 -3.86139893e+03 -3.86284204e+03 -3.74087817e+03 -3.61367480e+03 -3.60229858e+03 -3.64266187e+03 -3.61071069e+03 -3.50946118e+03 -3.34409082e+03 -3.35153125e+03 -3.44148926e+03 -3.40043677e+03 -3.29765723e+03 -3.19390991e+03 -3.17776929e+03 -3.20375806e+03 -3.24505957e+03 -3.17144214e+03 -2.95508447e+03 -2.94087769e+03 -2.98777539e+03 -2.93058081e+03 -2.88614746e+03 -2.80998462e+03 -2.76682178e+03 -2.73027637e+03 -2.69958423e+03 -2.63438086e+03 -2.57221167e+03 -2.60096680e+03 -2.58959570e+03 -2.50961890e+03 -2.37354297e+03 -2.30294971e+03 -2.36051514e+03 -2.39137451e+03 -2.31796729e+03 -2.20908716e+03 -2.09658618e+03 -2.02830176e+03 -2.06935840e+03 -2.11829688e+03 -2.01659705e+03 -1.87263464e+03 -1.84933801e+03 -1.85134131e+03 -1.82699731e+03 -1.78838330e+03 -1.70030750e+03 -1.64031299e+03 -1.60675500e+03 -1.55268811e+03 -1.49208838e+03 -1.45937183e+03 -1.44314050e+03 -1.38675012e+03 -1.33118127e+03 -1.27312317e+03 -1.21515698e+03 -1.19863745e+03 -1.17200134e+03 -1.10771497e+03 -1.02553040e+03 -9.60376587e+02 -9.45805603e+02 -9.19791443e+02 -8.67065735e+02 -8.10445679e+02 -7.37618164e+02 -6.89261536e+02 -6.75450745e+02 -6.47705139e+02 -5.89385193e+02 -5.20208984e+02 -4.67142731e+02 -4.28391541e+02 -3.80853821e+02 -3.30991608e+02 -2.87880219e+02 -2.44006882e+02 -1.90482132e+02 -1.38545212e+02 -8.92886200e+01 -4.49118652e+01 -5.66429943e-02 4.66658058e+01 9.80036240e+01 1.46552017e+02 1.87351685e+02 2.42097351e+02 2.95377899e+02 3.40741913e+02 3.90604492e+02 4.32386566e+02 4.91321259e+02 5.36632996e+02 5.53387573e+02 5.92791443e+02 6.54200378e+02 7.36318237e+02 8.11395081e+02 8.38747803e+02 8.37282593e+02 8.60010071e+02 9.24224609e+02 1.02568811e+03 1.11011902e+03 1.13080383e+03 1.11126965e+03 1.15334314e+03 1.28590247e+03 1.32226843e+03 1.30239331e+03 1.34856970e+03 1.41778296e+03 1.46764026e+03 1.55861536e+03 1.57676379e+03 1.56209290e+03 1.64678052e+03 1.66586011e+03 1.75555798e+03 1.84649695e+03 1.79658081e+03 1.87873730e+03 1.98699414e+03 1.99005750e+03 2.02532349e+03 2.06245166e+03 2.12160400e+03 2.18353711e+03 2.20175684e+03 2.19418945e+03 2.25035132e+03 2.39576855e+03 2.49837915e+03 2.48911035e+03 2.42974780e+03 2.41951465e+03 2.50480981e+03 2.66487451e+03 2.79291284e+03 2.76517993e+03 2.67191357e+03 2.73093994e+03 2.86660864e+03 2.88937036e+03 2.89149243e+03 2.94542407e+03 2.98515210e+03 3.02525732e+03 3.18439941e+03 3.15559937e+03 3.10150757e+03 3.20762378e+03 3.17543042e+03 3.32341064e+03 3.43526538e+03 3.36740771e+03 3.52376196e+03 3.49357593e+03 3.38887573e+03 3.54937573e+03 3.50525830e+03 3.59972046e+03 3.89702100e+03 3.75131006e+03 3.57572925e+03 3.67996533e+03 3.89673291e+03 4.09254980e+03 4.03582642e+03 3.84841895e+03 3.77965381e+03 3.92229590e+03 4.15983789e+03 4.33815869e+03 4.26786523e+03 4.06357715e+03 4.09739111e+03 4.28350537e+03 4.37289893e+03 4.29779834e+03 4.27689893e+03 4.40110889e+03 4.44054834e+03 4.59899658e+03 4.65427832e+03 4.45294385e+03 4.47715332e+03 4.57998486e+03 4.63145996e+03 4.71328662e+03 4.72872705e+03 4.87558545e+03 4.84161035e+03 4.69934570e+03 4.81520947e+03 4.74189893e+03 4.93255566e+03 5.27380713e+03 5.01145410e+03 4.74069043e+03 4.89933398e+03 5.17624512e+03 5.35909961e+03 5.39446533e+03 5.14371924e+03 4.95294775e+03 5.08354102e+03 5.38160742e+03 5.63351953e+03 5.49654492e+03 5.21477881e+03 5.21402490e+03 5.39533105e+03 5.52673096e+03 5.65552100e+03 5.66544434e+03 5.40548291e+03 5.40615283e+03 5.67280859e+03 5.77833447e+03 5.64485645e+03 5.62566895e+03 5.64600684e+03 5.64380908e+03 5.88784961e+03 5.98956006e+03 5.73787109e+03 5.70248633e+03 5.78626514e+03 5.84064551e+03 5.92813184e+03 5.89248535e+03 6.07371875e+03 6.18889844e+03 5.96434082e+03 5.86525635e+03 5.79973340e+03 6.06487061e+03 6.43741260e+03 6.29810596e+03 5.97914209e+03 5.86545215e+03 6.10145996e+03 6.47228369e+03 6.30486133e+03 5.97983545e+03 6.09248975e+03 6.24527295e+03 6.45188965e+03 6.68894287e+03 6.51424268e+03 6.16773779e+03 6.07445459e+03 6.32662402e+03 6.52562451e+03 6.56024512e+03 6.47780664e+03 6.44527588e+03 6.41867627e+03 6.58448193e+03 6.58486719e+03 6.39767676e+03 6.38913037e+03 6.38545459e+03 6.69081104e+03 6.79985596e+03 6.55847559e+03 6.60688477e+03 6.65659814e+03 6.78936133e+03 6.63093604e+03 6.31431055e+03 6.63778711e+03 6.99940625e+03 6.81264600e+03 6.48311963e+03 6.54366016e+03 6.88146143e+03 6.91717480e+03 6.79709082e+03 6.76414600e+03 6.54949121e+03 6.57846875e+03 6.93476270e+03 6.95293359e+03 6.66086475e+03 6.51013818e+03 6.54879736e+03 6.85804492e+03 7.16151855e+03 6.86260742e+03 6.62164111e+03 6.84093604e+03 6.83838281e+03 7.03104785e+03 7.02295801e+03 6.63063135e+03 6.66340918e+03 6.87218994e+03 6.83954248e+03 6.90626514e+03 6.82855225e+03 6.98391162e+03 7.08940381e+03 6.77884961e+03 6.97160889e+03 6.61860303e+03 6.89072803e+03 9.66840137e+03 7.56782666e+03 9.94727930e+03 8.49793359e+03 1.03720049e+04 1.12669785e+04 1.08908496e+04 1.08230840e+04 1.07158145e+04 1.72102969e+04 2.59632656e+04 7.84434350e+06 -26928992. 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. 0. 0. 0. 0. 0. 0. 0. 0. -14108127. -3.58977750e+06 1975401. 2.26907148e+04 1.35470273e+04 8.84856836e+03 7.11187012e+03 6.76605322e+03 6.40966748e+03 6.17714014e+03 6.37605029e+03 6.35314648e+03 6.19597656e+03 6.23107910e+03 6.18109082e+03 6.11276904e+03 6.15247363e+03 6.09135742e+03 6.02371631e+03 5.99728760e+03 5.92669678e+03 6.07205371e+03 6.10084717e+03 5.81014697e+03 5.78108545e+03 6.03525098e+03 6.05238916e+03 5.90269727e+03 5.85000195e+03 5.81237256e+03 5.78634570e+03 5.76163867e+03 5.74134424e+03 5.70253711e+03 5.67467188e+03 5.58792139e+03 5.54203320e+03 5.68283545e+03 5.67718213e+03 5.54283447e+03 5.51721338e+03 5.49582471e+03 5.47509766e+03 5.41251953e+03 5.37561816e+03 5.36368506e+03 5.21118457e+03 5.14494873e+03 5.24661816e+03 5.21281494e+03 5.38226416e+03 5.35283154e+03 5.13719482e+03 4.94629541e+03 4.91255078e+03 5.21749561e+03 5.21890234e+03 4.98292480e+03 4.86239746e+03 4.84619727e+03 4.89440479e+03 4.82248828e+03 4.94255566e+03 4.90299170e+03 4.58772949e+03 4.51499268e+03 4.73340674e+03 4.87236768e+03 4.71589746e+03 4.58397021e+03 4.56083545e+03 4.49250635e+03 4.40581396e+03 4.40431299e+03 4.37819873e+03 4.31696680e+03 4.29094629e+03 4.24835498e+03 4.26033350e+03 4.21688623e+03 4.26194287e+03 4.20519531e+03 4.05438477e+03 4.06524536e+03 4.04087842e+03 4.01641187e+03 3.99357520e+03 3.91905908e+03 3.88619165e+03 3.75974048e+03 3.62053784e+03 3.77004419e+03 3.77961230e+03 3.54679761e+03 3.53197998e+03 3.69261426e+03 3.75467017e+03 3.59036401e+03 3.45662329e+03 3.40976978e+03 3.36082104e+03 3.28411621e+03 3.24091211e+03 3.27235767e+03 3.21472778e+03 3.24466016e+03 3.17923022e+03 3.04642456e+03 3.05412354e+03 2.93888013e+03 2.90161011e+03 3.01452710e+03 2.94423340e+03 2.83080981e+03 2.72718872e+03 2.64313916e+03 2.74828223e+03 2.75321265e+03 2.62011646e+03 2.49895923e+03 2.45520679e+03 2.47279004e+03 2.42365259e+03 2.45350610e+03 2.42786157e+03 2.29527856e+03 2.20131836e+03 2.16582959e+03 2.21609692e+03 2.16681006e+03 2.06403760e+03 2.00130005e+03 1.95036243e+03 1.92975537e+03 1.84202063e+03 1.80074341e+03 1.85467578e+03 1.79707202e+03 1.70349060e+03 1.60872986e+03 1.55877124e+03 1.61293140e+03 1.56677832e+03 1.47534729e+03 1.38555054e+03 1.33027844e+03 1.33225134e+03 1.28232715e+03 1.23529065e+03 1.15796008e+03 1.13369543e+03 1.14599524e+03 1.06810938e+03 1.00646362e+03 9.64826721e+02 9.12270264e+02 8.47465881e+02 7.98679199e+02 7.62887573e+02 7.13750732e+02 6.65629883e+02 6.04330383e+02 5.67674805e+02 5.50318848e+02 4.80323639e+02 4.17360199e+02 3.81250549e+02 3.32754974e+02 2.94635376e+02 2.40859238e+02 1.84952759e+02 1.46608490e+02 9.89862137e+01 4.83539543e+01 -1.98234582e+00 -5.20176620e+01 -1.01127167e+02 -1.48674652e+02 -1.94846985e+02 -2.33252350e+02 -2.85449188e+02 -3.52847412e+02 -3.94119995e+02 -4.27397308e+02 -4.61108032e+02 -5.14708496e+02 -5.96421204e+02 -6.42534180e+02 -6.71286804e+02 -7.01824402e+02 -7.43854370e+02 -8.10909058e+02 -8.59890564e+02 -9.29608887e+02 -9.54444824e+02 -9.71519714e+02 -1.05284985e+03 -1.10008472e+03 -1.16953540e+03 -1.21258643e+03 -1.23059875e+03 -1.27987585e+03 -1.32375720e+03 -1.38787280e+03 -1.40001111e+03 -1.46173242e+03 -1.58974829e+03 -1.60011035e+03 -1.60554382e+03 -1.61874390e+03 -1.65417773e+03 -1.79597424e+03 -1.84726172e+03 -1.84142664e+03 -1.84409241e+03 -1.88096155e+03 -1.98848206e+03 -2.03512500e+03 -2.12928833e+03 -2.15348096e+03 -2.13696289e+03 -2.16420068e+03 -2.20306519e+03 -2.35840112e+03 -2.39330322e+03 -2.37321484e+03 -2.41135742e+03 -2.45108276e+03 -2.56902759e+03 -2.62286938e+03 -2.55816870e+03 -2.58944556e+03 -2.76801904e+03 -2.81716699e+03 -2.72240259e+03 -2.74819580e+03 -2.93826416e+03 -3.00559863e+03 -2.95516431e+03 -2.92289551e+03 -2.96084326e+03 -3.18160107e+03 -3.20111499e+03 -3.15316333e+03 -3.21997266e+03 -3.23984106e+03 -3.27448828e+03 -3.31847485e+03 -3.35646484e+03 -3.31582788e+03 -3.44688184e+03 -3.67453857e+03 -3.61820752e+03 -3.60631396e+03 -3.67254321e+03 -3.67533765e+03 -3.72485669e+03 -3.75663867e+03 -3.78708130e+03 -3.73584839e+03 -3.71990527e+03 -3.85686401e+03 -3.98261865e+03 -4.13627197e+03 -4.04049365e+03 -3.93609082e+03 -4.09214575e+03 -4.16435742e+03 -4.32625000e+03 -4.31216553e+03 -4.21645410e+03 -4.22380908e+03 -4.23500537e+03 -4.36396436e+03 -4.41775293e+03 -4.53861475e+03 -4.56795508e+03 -4.49178125e+03 -4.46637451e+03 -4.38099951e+03 -4.60243457e+03 -4.91878223e+03 -4.84479199e+03 -4.73641211e+03 -4.64765967e+03 -4.62251074e+03 -4.89252148e+03 -5.05479053e+03 -4.96242627e+03 -4.80397266e+03 -4.80987842e+03 -4.98334814e+03 -5.02291650e+03 -5.19266895e+03 -5.20502002e+03 -5.08709131e+03 -5.13738623e+03 -5.14547363e+03 -5.29287158e+03 -5.33464648e+03 -5.13303564e+03 -5.17560156e+03 -5.48173828e+03 -5.41337354e+03 -5.17225537e+03 -5.36790332e+03 -5.70728613e+03 -5.63856152e+03 -5.50251660e+03 -5.39744629e+03 -5.45151611e+03 -5.79579346e+03 -5.78557764e+03 -5.65845801e+03 -5.54071387e+03 -5.52580518e+03 -5.73045703e+03 -5.73314746e+03 -5.78637061e+03 -5.66527051e+03 -5.81542480e+03 -6.08703662e+03 -5.96359180e+03 -5.99132764e+03 -5.98135205e+03 -5.89185547e+03 -5.96643359e+03 -6.01039990e+03 -6.05495557e+03 -6.03661816e+03 -5.99561279e+03 -5.89584180e+03 -6.03833740e+03 -6.45243018e+03 -6.18957227e+03 -5.93894287e+03 -6.13935645e+03 -6.25613135e+03 -6.48792188e+03 -6.39202148e+03 -6.20174463e+03 -6.37624707e+03 -6.40002930e+03 -6.16489160e+03 -6.14165430e+03 -6.54150439e+03 -6.54299316e+03 -6.36706152e+03 -6.28991748e+03 -6.11947559e+03 -6.39521533e+03 -6.81317041e+03 -6.65419727e+03 -6.49279834e+03 -6.36310742e+03 -6.29062158e+03 -6.63653809e+03 -6.88650586e+03 -6.70823682e+03 -6.39741846e+03 -6.37004395e+03 -6.57920898e+03 -6.65770361e+03 -6.86564062e+03 -6.72030176e+03 -6.53670068e+03 -6.70784082e+03 -6.69470215e+03 -6.80107520e+03 -6.79153516e+03 -6.66363623e+03 -6.70331543e+03 -6.73914648e+03 -6.72732617e+03 -6.51923242e+03 -6.66979150e+03 -7.09231006e+03 -6.96372656e+03 -6.68594189e+03 -6.54502734e+03 -6.63785107e+03 -7.04595508e+03 -6.98682080e+03 -6.80726367e+03 -6.63350293e+03 -6.63734912e+03 -6.84031201e+03 -6.83020508e+03 -6.84759717e+03 -6.65713770e+03 -6.84611133e+03 -7.12551074e+03 -6.89923242e+03 -6.95331689e+03 -6.96368945e+03 -6.86504395e+03 -6.81489258e+03 -6.75703955e+03 -6.80975977e+03 -6.78488770e+03 -6.82527490e+03 -6.79621094e+03 -6.97037744e+03 -6.98748877e+03 -6.69873242e+03 -6.58436523e+03 -6.74417090e+03 -6.88745312e+03 -7.12814014e+03 -6.89495801e+03 -6.60214990e+03 -6.89630371e+03 -7.06199512e+03 -6.87559326e+03 -6.69383350e+03 -6.67284814e+03 -6.76566162e+03 -6.77820215e+03 -6.72506104e+03 -6.54452588e+03 -6.75617871e+03 -7.08646680e+03 -6.90796387e+03 -6.76188428e+03 -6.63138086e+03 -6.55648877e+03 -6.90893311e+03 -6.92306348e+03 -6.70318994e+03 -6.52482275e+03 -6.36756152e+03 -6.54587402e+03 -6.78311572e+03 -6.99433105e+03 -6.69295605e+03 -6.38524072e+03 -6.57701953e+03 -6.62480615e+03 -6.83760791e+03 -6.66944580e+03 -6.45324072e+03 -6.61188037e+03 -6.58528809e+03 -6.41891016e+03 -6.28554639e+03 -6.47982666e+03 -6.78927881e+03 -6.63050049e+03 -6.49188721e+03 -6.31026318e+03 -6.25542334e+03 -6.57221484e+03 -6.57578564e+03 -6.37719580e+03 -6.19121191e+03 -6.11319336e+03 -6.28980615e+03 -6.32058203e+03 -6.43563818e+03 -6.44745898e+03 -6.20733838e+03 -6.05919482e+03 -6.10353760e+03 -6.40039355e+03 -6.24632324e+03 -6.05520312e+03 -6.12981494e+03 -6.12687549e+03 -5.97320020e+03 -5.86865283e+03 -6.11288037e+03 -6.06469629e+03 -5.86972705e+03 -6.09917090e+03 -6.11740381e+03 -5.95499268e+03 -5.89947705e+03 -5.86377783e+03 -5.83400928e+03 -5.68106104e+03 -5.60945996e+03 -5.85945215e+03 -5.88502197e+03 -5.56147266e+03 -5.36956885e+03 -5.62499707e+03 -5.91434180e+03 -5.81624268e+03 -5.49392676e+03 -5.34026904e+03 -5.59737158e+03 -5.65540820e+03 -5.45121826e+03 -5.46951367e+03 -5.30531543e+03 -5.11748340e+03 -5.28127148e+03 -5.48733447e+03 -5.43121729e+03 -5.18375488e+03 -5.01053857e+03 -5.24907324e+03 -5.37177344e+03 -5.17541357e+03 -4.93738672e+03 -4.85029736e+03 -4.99163818e+03 -4.98721191e+03 -5.07828027e+03 -5.03553613e+03 -4.81483008e+03 -4.85593066e+03 -4.82201123e+03 -4.86322852e+03 -4.72747998e+03 -4.58306299e+03 -4.74828271e+03 -4.72321826e+03 -4.61746875e+03 -4.46291748e+03 -4.47712744e+03 -4.71115820e+03 -4.49594141e+03 -4.26748926e+03 -4.33376416e+03 -4.39671387e+03 -4.37143604e+03 -4.28476660e+03 -4.35110303e+03 -4.35684082e+03 -4.18829443e+03 -4.01736133e+03 -3.99015527e+03 -4.16321436e+03 -4.04414844e+03 -3.87946924e+03 -3.97662720e+03 -3.96411670e+03 -3.84239600e+03 -3.75728662e+03 -3.86456421e+03 -3.78520703e+03 -3.63690625e+03 -3.69634546e+03 -3.66873560e+03 -3.64682617e+03 -3.59959326e+03 -3.51996606e+03 -3.45230542e+03 -3.30847363e+03 -3.25960840e+03 -3.37971313e+03 -3.44880688e+03 -3.24801440e+03 -3.04531006e+03 -3.13059351e+03 -3.27247363e+03 -3.20833203e+03 -3.01151343e+03 -2.86475928e+03 -2.96394580e+03 -3.00788232e+03 -2.86576855e+03 -2.87869702e+03 -2.81834863e+03 -2.66959961e+03 -2.65328931e+03 -2.69637622e+03 -2.66372974e+03 -2.52636279e+03 -2.42057910e+03 -2.47464209e+03 -2.54001294e+03 -2.43067505e+03 -2.28373657e+03 -2.20313916e+03 -2.27157861e+03 -2.29497778e+03 -2.16836401e+03 -2.06902881e+03 -2.04116162e+03 -2.03658472e+03 -1.98003088e+03 -1.98778149e+03 -1.89734509e+03 -1.78675708e+03 -1.81058276e+03 -1.77315845e+03 -1.72497717e+03 -1.64287927e+03 -1.57032983e+03 -1.58634375e+03 -1.50072852e+03 -1.43077332e+03 -1.43894495e+03 -1.41818481e+03 -1.40989246e+03 -1.34045435e+03 -1.30965405e+03 -1.25624817e+03 -1.01283734e+03 -9.87587830e+02 -1.04415454e+03 -1.08369629e+03 -1.05135828e+03 -8.98627136e+02 -8.46124084e+02 -1.08466125e+03 -1.44732483e+03 -1.11638008e+04 -3.44552986e+09 0. 0. 0. 0. 1381557632. 1381557632. 8.02582875e+05 -231494368. -4.65549170e+03 -3.54991016e+04 -1.90519080e+03 -3.10861230e+03 -637180544. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 469363232. 1.79326781e+05 1.31527771e+03 1.47304993e+03 6.42729797e+02 9.16528381e+02 7.63691345e+02 9.08724487e+02 8.27546509e+02 9.81135010e+02 9.65397095e+02 9.95626770e+02 1.03136926e+03 1.09747668e+03 1.17703687e+03 1.22062756e+03 1.22247656e+03 1.25673010e+03 1.33985876e+03 1.38895117e+03 1.42791907e+03 1.46872327e+03 1.49878809e+03 1.54901978e+03 1.63458960e+03 1.68581812e+03 1.66998865e+03 1.71931604e+03 1.82667383e+03 1.88483789e+03 1.93137207e+03 1.92529309e+03 1.93024023e+03 2.02975061e+03 2.10021973e+03 2.12616357e+03 2.13839941e+03 2.17942480e+03 2.26980029e+03 2.31145483e+03 2.33753857e+03 2.35755396e+03 2.40429688e+03 2.54714258e+03 2.61046021e+03 2.52704053e+03 2.53931079e+03 2.63423047e+03 2.70570703e+03 2.79427319e+03 2.81078589e+03 2.78817188e+03 2.86726465e+03 2.94028613e+03 2.97998999e+03 3.03211353e+03 3.01682007e+03 3.06615088e+03 3.14677856e+03 3.16296826e+03 3.19787573e+03 3.22254419e+03 3.28296826e+03 3.40674561e+03 3.43839795e+03 3.43271484e+03 3.40923047e+03 3.44290625e+03 3.59849731e+03 3.64687378e+03 3.58040576e+03 3.64203589e+03 3.69290308e+03 3.76560376e+03 3.89230225e+03 3.87062109e+03 3.80770679e+03 3.85990186e+03 4.00563037e+03 4.05535864e+03 3.99700659e+03 3.95932202e+03 4.03970703e+03 4.14392236e+03 4.28940283e+03 4.32483984e+03 4.18929883e+03 4.22594580e+03 4.38667334e+03 4.41980127e+03 4.42396338e+03 4.36456543e+03 4.36631201e+03 4.56319043e+03 4.63960596e+03 4.56047021e+03 4.59835449e+03 4.65192920e+03 4.67746289e+03 4.71822510e+03 4.73908447e+03 4.80658838e+03 4.83749414e+03 4.93064502e+03 4.96738184e+03 4.84700586e+03 4.89479736e+03 5.02236816e+03 4.99977246e+03 5.05659814e+03 5.07325049e+03 5.10671924e+03 5.22852637e+03 5.21369629e+03 5.16476318e+03 5.30367627e+03 5.35252832e+03 5.26754590e+03 5.29017920e+03 5.37111670e+03 5.44123779e+03 5.42947314e+03 5.38252002e+03 5.42691113e+03 5.51526367e+03 5.69493604e+03 5.65989648e+03 5.48084668e+03 5.58165771e+03 5.70983350e+03 5.72685400e+03 5.72076953e+03 5.67218945e+03 5.65268994e+03 5.78468066e+03 5.93071143e+03 5.88449072e+03 5.75505664e+03 5.78325098e+03 5.95987061e+03 6.05088916e+03 6.08473730e+03 5.96796631e+03 5.84171240e+03 5.98073145e+03 6.02364746e+03 6.04936963e+03 6.11046387e+03 6.06403955e+03 6.13383057e+03 6.34398535e+03 6.22657178e+03 6.02963281e+03 6.11340527e+03 6.26030518e+03 6.30430713e+03 6.39465869e+03 6.30345264e+03 6.20795752e+03 6.28386230e+03 6.51061719e+03 6.40031689e+03 6.19905859e+03 6.30720801e+03 6.52989990e+03 6.50273633e+03 6.44536035e+03 6.32308350e+03 6.38233984e+03 6.49154834e+03 6.54088037e+03 6.54254883e+03 6.60934668e+03 6.48837012e+03 6.52027979e+03 6.73235889e+03 6.60462500e+03 6.47232324e+03 6.56432617e+03 6.68587109e+03 6.74725293e+03 6.69743896e+03 6.55685010e+03 6.54735107e+03 6.67916162e+03 6.92374414e+03 6.95183789e+03 6.56209131e+03 6.57051221e+03 6.90245752e+03 6.81127637e+03 6.67814600e+03 6.64869141e+03 6.63538330e+03 6.79750098e+03 6.88491260e+03 6.80391455e+03 6.77011572e+03 6.62429932e+03 6.77687939e+03 6.93442285e+03 6.89706836e+03 6.79345459e+03 6.75953174e+03 6.85388574e+03 6.89521289e+03 6.79893701e+03 6.76543994e+03 6.79479834e+03 6.83945703e+03 6.97115137e+03 7.02445801e+03 6.69890967e+03 6.73228760e+03 6.89760254e+03 6.90313916e+03 6.91624463e+03 6.74225391e+03 6.78870459e+03 6.98958252e+03 6.91586230e+03 6.88905420e+03 6.71265234e+03 6.65059668e+03 6.88284619e+03 6.94621436e+03 6.87463428e+03 6.81488037e+03 6.83893848e+03 6.82978320e+03 6.93387891e+03 6.87394873e+03 6.71816943e+03 6.63211133e+03 6.69861621e+03 6.88661670e+03 6.80199121e+03 6.67055518e+03 6.72156152e+03 6.85132520e+03 6.82729102e+03 6.76132031e+03 6.69864062e+03 6.63491309e+03 6.69801807e+03 6.71581885e+03 6.81278369e+03 6.69386230e+03 6.58673877e+03 6.75049658e+03 6.56194238e+03 6.57484082e+03 6.71773340e+03 6.51268311e+03 6.52165723e+03 6.58652148e+03 6.57716943e+03 6.48914893e+03 6.42878955e+03 6.63924609e+03 6.70903223e+03 6.41041943e+03 6.37989941e+03 6.44578662e+03 6.44214307e+03 6.53942676e+03 6.45242041e+03 6.30814746e+03 6.31477832e+03 6.45260645e+03 6.45354541e+03 6.34479688e+03 6.22854932e+03 6.29505615e+03 6.35675439e+03 6.21608008e+03 6.20062598e+03 6.13841406e+03 6.11929199e+03 6.17792627e+03 6.23871875e+03 6.19556787e+03 6.06660889e+03 6.00207617e+03 6.15193213e+03 6.22896240e+03 6.00912061e+03 5.99185791e+03 6.01786182e+03 5.78980127e+03 5.92307471e+03 6.00685303e+03 5.80031689e+03 5.84948096e+03 5.89521875e+03 5.78415332e+03 5.87344434e+03 5.79192432e+03 5.68284033e+03 5.69111865e+03 5.71306592e+03 5.73535205e+03 5.57144824e+03 5.47495947e+03 5.56093359e+03 5.64489551e+03 5.57014600e+03 5.46487256e+03 5.37824609e+03 5.45170020e+03 5.59120312e+03 5.40683984e+03 5.25784863e+03 5.22214404e+03 5.33923926e+03 5.40914990e+03 5.20769336e+03 5.08534668e+03 5.14687842e+03 5.14748926e+03 5.07136914e+03 5.12081006e+03 5.04990820e+03 4.90141943e+03 4.97486328e+03 5.07757520e+03 4.92741455e+03 4.67312256e+03 4.73767188e+03 4.85924268e+03 4.80683545e+03 4.75963281e+03 4.67784277e+03 4.60289893e+03 4.67643896e+03 4.73114307e+03 4.55668701e+03 4.47048584e+03 4.46841455e+03 4.51619775e+03 4.45482715e+03 4.28093506e+03 4.24766064e+03 4.28629004e+03 4.27449805e+03 4.25464697e+03 4.22198877e+03 4.12822656e+03 4.11698535e+03 4.05795703e+03 3.96359985e+03 3.94256592e+03 3.88419702e+03 3.91112109e+03 3.94673218e+03 3.81739771e+03 3.70307593e+03 3.70282690e+03 3.75506055e+03 3.80719360e+03 3.72846973e+03 3.54286670e+03 3.48612646e+03 3.51464014e+03 3.47143677e+03 3.38964551e+03 3.36561377e+03 3.34485620e+03 3.31430713e+03 3.23629517e+03 3.13080371e+03 3.16364038e+03 3.18579932e+03 3.15089160e+03 3.06797314e+03 2.93669873e+03 2.93144263e+03 2.88516650e+03 2.80912305e+03 2.87311426e+03 2.84093652e+03 2.69938818e+03 2.64278003e+03 2.62827759e+03 2.66846729e+03 2.62944946e+03 2.52796460e+03 2.46511060e+03 2.41783691e+03 2.37277173e+03 2.30374634e+03 2.29058350e+03 2.26047119e+03 2.23139990e+03 2.18610278e+03 2.05383154e+03 2.03138831e+03 2.01519214e+03 1.97654724e+03 1.98487366e+03 1.87701929e+03 1.78639526e+03 1.80910400e+03 1.79438770e+03 1.70964136e+03 1.64837830e+03 1.58034863e+03 1.52532715e+03 1.49906372e+03 1.46493823e+03 1.41219568e+03 1.39892773e+03 1.36768530e+03 1.28432800e+03 1.21591138e+03 1.15668677e+03 1.14058496e+03 1.11750171e+03 1.05129565e+03 9.78241211e+02 9.28146179e+02 8.97129761e+02 8.71545898e+02 8.42057922e+02 7.64656555e+02 6.97728210e+02 6.60399475e+02 6.07790222e+02 5.59630676e+02 5.34495667e+02 4.87900513e+02 4.26799774e+02 3.77861694e+02 3.26695831e+02 2.84148010e+02 2.46812683e+02 1.97883194e+02 1.40948944e+02 8.97397308e+01 4.27791481e+01 -8.86555314e-01 -4.90073776e+01 -9.97565231e+01 -1.50674713e+02 -1.99751526e+02 -2.42661591e+02 -2.95130493e+02 -3.43998688e+02 -3.85280701e+02 -4.35192444e+02 -4.77537048e+02 -5.24536499e+02 -5.78941101e+02 -6.22130615e+02 -6.83107239e+02 -7.30575439e+02 -7.55401978e+02 -8.08731873e+02 -8.49232422e+02 -8.95502808e+02 -9.49622375e+02 -1.00476697e+03 -1.06615649e+03 -1.10072827e+03 -1.14136633e+03 -1.18203174e+03 -1.23816125e+03 -1.31520093e+03 -1.35616724e+03 -1.37757153e+03 -1.41143958e+03 -1.45277368e+03 -1.51602832e+03 -1.58840186e+03 -1.63088818e+03 -1.66200159e+03 -1.70049011e+03 -1.73829224e+03 -1.79390833e+03 -1.86034607e+03 -1.89285950e+03 -1.93464526e+03 -1.98617224e+03 -2.02855420e+03 -2.08594824e+03 -2.08680957e+03 -2.14574561e+03 -2.25665332e+03 -2.26087451e+03 -2.28299707e+03 -2.36010522e+03 -2.36645435e+03 -2.40456104e+03 -2.55679883e+03 -2.59092529e+03 -2.51750708e+03 -2.57492993e+03 -2.65487500e+03 -2.67441943e+03 -2.77685156e+03 -2.80904077e+03 -2.77430493e+03 -2.85118481e+03 -2.91570898e+03 -2.99814771e+03 -3.05623218e+03 -3.05435425e+03 -3.12192407e+03 -3.11569849e+03 -3.09356104e+03 -3.19166455e+03 -3.30625806e+03 -3.32674219e+03 -3.37104297e+03 -3.41117896e+03 -3.31341675e+03 -3.42992627e+03 -3.62282422e+03 -3.61462793e+03 -3.59768750e+03 -3.53831836e+03 -3.60693896e+03 -3.77829565e+03 -3.79623730e+03 -3.78560693e+03 -3.87423877e+03 -3.87089111e+03 -3.91120947e+03 -3.97678247e+03 -3.90960962e+03 -3.95961450e+03 -4.11873340e+03 -4.19264209e+03 -4.15276367e+03 -4.08290161e+03 -4.12576318e+03 -4.27978271e+03 -4.38786816e+03 -4.37155518e+03 -4.30680078e+03 -4.29261035e+03 -4.41256152e+03 -4.54155957e+03 -4.65632324e+03 -4.59768848e+03 -4.51759961e+03 -4.60308008e+03 -4.63469678e+03 -4.65909814e+03 -4.75822607e+03 -4.75348975e+03 -4.80254443e+03 -4.91247559e+03 -4.84187939e+03 -4.85677881e+03 -4.95501318e+03 -4.98425537e+03 -5.04504053e+03 -5.01420264e+03 -4.93801416e+03 -5.03232959e+03 -5.16330859e+03 -5.25975684e+03 -5.32034961e+03 -5.23778369e+03 -5.14321436e+03 -5.24225391e+03 -5.25133008e+03 -5.31925684e+03 -5.48384814e+03 -5.39423193e+03 -5.36096387e+03 -5.37272949e+03 -5.42696924e+03 -5.58622021e+03 -5.70990723e+03 -5.65217188e+03 -5.59449609e+03 -5.57425293e+03 -5.48268213e+03 -5.60788721e+03 -5.78166748e+03 -5.85709473e+03 -5.82475537e+03 -5.69631543e+03 -5.70773340e+03 -5.80908545e+03 -5.90853564e+03 -5.92384473e+03 -5.95134961e+03 -5.92180029e+03 -5.84786328e+03 -5.98029980e+03 -6.12968066e+03 -6.09930371e+03 -5.94269043e+03 -6.03238281e+03 -6.11265283e+03 -6.15633154e+03 -6.18562354e+03 -6.15930615e+03 -6.25265479e+03 -6.20968555e+03 -6.13179639e+03 -6.30310791e+03 -6.30404932e+03 -6.24089551e+03 -6.39507129e+03 -6.30326416e+03 -6.17512744e+03 -6.39740479e+03 -6.39110205e+03 -6.41975000e+03 -6.70806885e+03 -6.62244043e+03 -6.33907715e+03 -6.48394971e+03 -8.76624805e+03 -1.03136396e+04 -1.71165684e+04 -2.01644434e+04 -11914131. -2.91965150e+06 5.01341750e+06 -35914360. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7938896. -17083144. 1.68124838e+06 7235108. 4.09605475e+06 -2.18553047e+04 -1.77106465e+04 -9.57482715e+03 -9.03665234e+03 -7.70607129e+03 -7.30382031e+03 -6.76672852e+03 -6.83577344e+03 -7.04058936e+03 -6.91332666e+03 -6.76958984e+03 -6.67670850e+03 -6.63035791e+03 -6.96771875e+03 -7.07661475e+03 -6.76601123e+03 -6.56383838e+03 -6.65735352e+03 -6.77797803e+03 -6.87202295e+03 -6.94647754e+03 -6.73093262e+03 -6.57083936e+03 -6.66182959e+03 -6.70245459e+03 -6.74015283e+03 -6.60068213e+03 -6.52247412e+03 -6.79333398e+03 -6.96916016e+03 -6.76453174e+03 -6.45754199e+03 -6.44338037e+03 -6.70777881e+03 -6.75657812e+03 -6.58147461e+03 -6.42407764e+03 -6.44665625e+03 -6.68029736e+03 -6.80989795e+03 -6.59614209e+03 -6.27128564e+03 -6.37602930e+03 -6.68290088e+03 -6.56875928e+03 -6.53628223e+03 -6.48124707e+03 -6.23253857e+03 -6.35375195e+03 -6.56062939e+03 -6.39257373e+03 -6.27917578e+03 -6.41845166e+03 -6.47270508e+03 -6.37684961e+03 -6.28661963e+03 -6.06180762e+03 -6.17220117e+03 -6.44579004e+03 -6.31102881e+03 -6.10497314e+03 -6.00437354e+03 -6.00011719e+03 -6.25468311e+03 -6.39729834e+03 -6.16483008e+03 -5.97581885e+03 -5.93259570e+03 -5.89812646e+03 -6.01964795e+03 -6.15248682e+03 -5.90152246e+03 -5.80032617e+03 -5.94099023e+03 -5.87753564e+03 -5.77680176e+03 -5.73504004e+03 -5.82229248e+03 -5.90695654e+03 -5.82809131e+03 -5.77655078e+03 -5.58577637e+03 -5.46795752e+03 -5.73613867e+03 -5.84588477e+03 -5.54184619e+03 -5.34905469e+03 -5.43811035e+03 -5.55780762e+03 -5.61616064e+03 -5.60934229e+03 -5.38113086e+03 -5.30884375e+03 -5.40290674e+03 -5.33539355e+03 -5.35224121e+03 -5.30144287e+03 -5.10543994e+03 -5.13992627e+03 -5.21727979e+03 -5.20882666e+03 -5.16449414e+03 -5.12526611e+03 -5.08889893e+03 -5.06029834e+03 -5.01815820e+03 -4.83238623e+03 -4.80232275e+03 -5.05324121e+03 -5.01881543e+03 -4.73672998e+03 -4.61317920e+03 -4.65795215e+03 -4.83676758e+03 -4.92074805e+03 -4.70320459e+03 -4.49765576e+03 -4.46246631e+03 -4.50655469e+03 -4.52020996e+03 -4.53288867e+03 -4.44731152e+03 -4.38595215e+03 -4.34942725e+03 -4.31563477e+03 -4.32184033e+03 -4.18972314e+03 -4.19990137e+03 -4.30457373e+03 -4.20315234e+03 -4.08810205e+03 -3.99467944e+03 -3.91280127e+03 -4.03587695e+03 -4.10300391e+03 -3.88049292e+03 -3.74811841e+03 -3.76149414e+03 -3.88693188e+03 -3.91273608e+03 -3.74833496e+03 -3.60662817e+03 -3.54210767e+03 -3.54648584e+03 -3.59168359e+03 -3.59314795e+03 -3.42125684e+03 -3.30215601e+03 -3.36769824e+03 -3.42427222e+03 -3.34305005e+03 -3.25265503e+03 -3.21609058e+03 -3.15859033e+03 -3.15428442e+03 -3.12638843e+03 -2.98143774e+03 -2.93635791e+03 -2.99834961e+03 -2.95637183e+03 -2.87346509e+03 -2.78139136e+03 -2.74448047e+03 -2.74437598e+03 -2.72966553e+03 -2.69892529e+03 -2.58841089e+03 -2.56252051e+03 -2.55212891e+03 -2.47991260e+03 -2.42476660e+03 -2.34996631e+03 -2.31815527e+03 -2.32969775e+03 -2.32041870e+03 -2.24423535e+03 -2.10477710e+03 -2.04594287e+03 -2.09137744e+03 -2.09682935e+03 -2.01415637e+03 -1.88548022e+03 -1.83106787e+03 -1.83005664e+03 -1.82491406e+03 -1.79023352e+03 -1.68179468e+03 -1.60353137e+03 -1.58505713e+03 -1.57343445e+03 -1.54423413e+03 -1.47276379e+03 -1.41215417e+03 -1.36833105e+03 -1.32668945e+03 -1.29243054e+03 -1.24037866e+03 -1.19595190e+03 -1.14031628e+03 -1.07538306e+03 -1.01912476e+03 -9.71229797e+02 -9.55628113e+02 -9.39991516e+02 -8.81106384e+02 -7.98495972e+02 -7.24103455e+02 -6.89531555e+02 -6.86676819e+02 -6.55071411e+02 -5.83263489e+02 -5.11429352e+02 -4.53918762e+02 -4.18359802e+02 -3.85737793e+02 -3.38471802e+02 -2.87705475e+02 -2.37485245e+02 -1.88132172e+02 -1.41224091e+02 -9.43746567e+01 -4.89322701e+01 -2.73105049e+00 4.74032249e+01 9.94260864e+01 1.50205002e+02 1.88314575e+02 2.37397232e+02 2.90653229e+02 3.37719330e+02 3.87276794e+02 4.31393890e+02 4.90384796e+02 5.42390747e+02 5.62624756e+02 5.92141479e+02 6.49821106e+02 7.32681824e+02 8.07871338e+02 8.39027527e+02 8.40731018e+02 8.64839233e+02 9.23732483e+02 1.01574060e+03 1.09993481e+03 1.13500867e+03 1.11386072e+03 1.15030103e+03 1.27694946e+03 1.31761255e+03 1.31037244e+03 1.35410107e+03 1.41734949e+03 1.46552026e+03 1.55849866e+03 1.58084106e+03 1.56700171e+03 1.64631885e+03 1.66572925e+03 1.75637891e+03 1.84546716e+03 1.80488416e+03 1.87123706e+03 1.97331226e+03 1.99279004e+03 2.02788416e+03 2.06746899e+03 2.12156519e+03 2.18936914e+03 2.19037598e+03 2.17380957e+03 2.25239624e+03 2.40763306e+03 2.50372925e+03 2.48927319e+03 2.43114087e+03 2.41203564e+03 2.50322974e+03 2.66244849e+03 2.78768774e+03 2.75582275e+03 2.66403125e+03 2.73250195e+03 2.85885034e+03 2.88219312e+03 2.89645142e+03 2.94687964e+03 2.99154126e+03 3.04243701e+03 3.18806592e+03 3.14554028e+03 3.10191089e+03 3.21037329e+03 3.16083423e+03 3.30422021e+03 3.45754883e+03 3.36666235e+03 3.51020728e+03 3.50297803e+03 3.37901953e+03 3.53617651e+03 3.51090430e+03 3.60184399e+03 3.88641919e+03 3.74585645e+03 3.57555737e+03 3.68166992e+03 3.90775879e+03 4.08165771e+03 4.02901636e+03 3.88130322e+03 3.81790771e+03 3.90126831e+03 4.11593896e+03 4.30412842e+03 4.27467578e+03 4.09278906e+03 4.10789502e+03 4.28235498e+03 4.34452100e+03 4.30231543e+03 4.30728223e+03 4.38152930e+03 4.41987646e+03 4.60520068e+03 4.66515332e+03 4.45334619e+03 4.45642432e+03 4.58558643e+03 4.63415869e+03 4.70970264e+03 4.73638916e+03 4.88742773e+03 4.81026611e+03 4.65555078e+03 4.86227002e+03 4.75588867e+03 4.90142871e+03 5.27873145e+03 5.01869336e+03 4.76587207e+03 4.90209473e+03 5.18470410e+03 5.35687793e+03 5.36451562e+03 5.10987646e+03 4.96160400e+03 5.09587598e+03 5.37339648e+03 5.60724707e+03 5.48426318e+03 5.19732666e+03 5.21004785e+03 5.40850684e+03 5.52128711e+03 5.66599707e+03 5.67913184e+03 5.40890430e+03 5.37047266e+03 5.65342188e+03 5.76379688e+03 5.63176660e+03 5.61659424e+03 5.67805176e+03 5.64548242e+03 5.89758936e+03 5.98480859e+03 5.72864551e+03 5.73951953e+03 5.82841504e+03 5.81506299e+03 5.90215918e+03 5.90125439e+03 6.06771045e+03 6.15926562e+03 5.98472119e+03 5.87567676e+03 5.81098242e+03 6.07762988e+03 6.39399219e+03 6.29516016e+03 6.02662256e+03 5.87514307e+03 6.10368408e+03 6.45375488e+03 6.27160645e+03 5.96941504e+03 6.08908252e+03 6.28027490e+03 6.42900439e+03 6.64892871e+03 6.51559424e+03 6.18665625e+03 6.09109033e+03 6.32563965e+03 6.53434229e+03 6.52826172e+03 6.44837500e+03 6.43416846e+03 6.44299512e+03 6.59962842e+03 6.52890674e+03 6.35466309e+03 6.45332471e+03 6.37097168e+03 6.64603857e+03 6.84969385e+03 6.57792871e+03 6.65186426e+03 6.64079883e+03 6.66252686e+03 6.52906299e+03 6.38738037e+03 6.68343457e+03 7.02378369e+03 6.83616553e+03 6.49693945e+03 6.50736475e+03 6.89391162e+03 6.95865576e+03 6.80565430e+03 6.78054541e+03 6.56366113e+03 6.52791846e+03 6.87730664e+03 6.86995996e+03 6.71734814e+03 6.60713086e+03 6.52208203e+03 6.84948926e+03 7.17757373e+03 6.84194238e+03 6.60094336e+03 6.80221094e+03 6.83465479e+03 7.02444189e+03 7.06087256e+03 6.64353418e+03 6.62167041e+03 6.84054053e+03 6.82355762e+03 6.89242090e+03 7.00805127e+03 6.84768945e+03 7.38764795e+03 7.29839648e+03 6.80935352e+03 8.54031152e+03 9.58301172e+03 1.86273848e+04 1.19021191e+04 2.00692344e+04 1.99386016e+04 -3.03897675e+06 -6.12702950e+06 2.78608075e+06 -3586535. 6.41523750e+06 2244814. 7399735. 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. 0. 0. -249400496. -249400496. -249400496. 0. 0. 3318850. 4221781. 2.21180575e+06 2.00392910e+04 1.63375947e+04 1.07579980e+04 1.03559424e+04 8.56783984e+03 8.22499316e+03 6.66815918e+03 6.60705615e+03 6.38557178e+03 6.18226270e+03 6.37912012e+03 6.31888428e+03 6.18282031e+03 6.21514844e+03 6.19100391e+03 6.13387744e+03 6.13942236e+03 6.10910645e+03 6.03801025e+03 5.96079932e+03 5.91579395e+03 6.08400928e+03 6.10212451e+03 5.79050244e+03 5.77510156e+03 6.03262207e+03 6.04557666e+03 5.90709033e+03 5.85275586e+03 5.81078613e+03 5.76301465e+03 5.75812891e+03 5.75184277e+03 5.71473438e+03 5.66913281e+03 5.51195557e+03 5.45549902e+03 5.72467334e+03 5.72494336e+03 5.51083984e+03 5.48910156e+03 5.47940137e+03 5.48570361e+03 5.41932666e+03 5.36419531e+03 5.35910840e+03 5.25938965e+03 5.22064990e+03 5.22036084e+03 5.17560303e+03 5.34771143e+03 5.35463867e+03 5.14726416e+03 4.97001318e+03 4.91175928e+03 5.18594141e+03 5.18466260e+03 4.98197119e+03 4.87035303e+03 4.86277832e+03 4.90217969e+03 4.82173340e+03 4.92252002e+03 4.89947168e+03 4.60027881e+03 4.51881396e+03 4.72102637e+03 4.86793066e+03 4.71581299e+03 4.58298340e+03 4.53455127e+03 4.47590723e+03 4.44245850e+03 4.42605908e+03 4.43916602e+03 4.38201562e+03 4.26986328e+03 4.24018066e+03 4.21971631e+03 4.18840332e+03 4.26879883e+03 4.21899707e+03 4.06725488e+03 4.03256128e+03 3.98829199e+03 4.06707910e+03 4.05002808e+03 3.91106909e+03 3.86801685e+03 3.75693457e+03 3.65676685e+03 3.80062671e+03 3.74196924e+03 3.50893506e+03 3.52516333e+03 3.68360815e+03 3.77228394e+03 3.59925659e+03 3.45901807e+03 3.39481128e+03 3.34376538e+03 3.32211890e+03 3.27955737e+03 3.24153735e+03 3.18411499e+03 3.23133618e+03 3.17787231e+03 3.05407104e+03 3.03202100e+03 2.90253027e+03 2.91592993e+03 3.05560181e+03 2.95328906e+03 2.83265112e+03 2.71053882e+03 2.65192261e+03 2.77013599e+03 2.73746851e+03 2.60403784e+03 2.50150781e+03 2.44799463e+03 2.46388623e+03 2.42290479e+03 2.45033862e+03 2.42089771e+03 2.29498877e+03 2.22593262e+03 2.18937012e+03 2.19317871e+03 2.14531860e+03 2.06630835e+03 2.00436304e+03 1.95874963e+03 1.92265356e+03 1.82438403e+03 1.81872546e+03 1.87622375e+03 1.79422437e+03 1.70406946e+03 1.61422583e+03 1.56464526e+03 1.61187549e+03 1.56317456e+03 1.46928735e+03 1.38290173e+03 1.33366357e+03 1.33830640e+03 1.28283057e+03 1.23474976e+03 1.15978833e+03 1.13373279e+03 1.14864319e+03 1.07187207e+03 1.00905969e+03 9.70107971e+02 9.12797363e+02 8.47514587e+02 8.03347717e+02 7.62526550e+02 7.10998718e+02 6.70457031e+02 6.05790283e+02 5.63924255e+02 5.50359314e+02 4.80561096e+02 4.16498749e+02 3.80626556e+02 3.32908783e+02 2.93240753e+02 2.43149002e+02 1.88642548e+02 1.47089966e+02 9.84341354e+01 4.74286194e+01 -6.49889231e-01 -4.84326744e+01 -9.43556976e+01 -1.40244110e+02 -1.88671112e+02 -2.31426483e+02 -2.86235870e+02 -3.52745819e+02 -3.95367920e+02 -4.26413147e+02 -4.57873535e+02 -5.10828857e+02 -5.92262390e+02 -6.40873718e+02 -6.68887146e+02 -7.00708801e+02 -7.42783752e+02 -8.09281677e+02 -8.60195862e+02 -9.25698853e+02 -9.60864380e+02 -9.80545166e+02 -1.03594873e+03 -1.08423108e+03 -1.16950684e+03 -1.21103101e+03 -1.22165051e+03 -1.27096375e+03 -1.31809204e+03 -1.36358374e+03 -1.37671985e+03 -1.46996790e+03 -1.60775598e+03 -1.60301428e+03 -1.60342029e+03 -1.61611963e+03 -1.64865735e+03 -1.79611780e+03 -1.85215515e+03 -1.84611133e+03 -1.84852039e+03 -1.88000903e+03 -1.98442566e+03 -2.02818335e+03 -2.12498413e+03 -2.17828784e+03 -2.16485522e+03 -2.14707080e+03 -2.18329419e+03 -2.36426807e+03 -2.39713550e+03 -2.37344702e+03 -2.38454517e+03 -2.41655786e+03 -2.59630981e+03 -2.65260254e+03 -2.54600122e+03 -2.58243799e+03 -2.77516919e+03 -2.81488306e+03 -2.71628247e+03 -2.75263501e+03 -2.93762451e+03 -3.00287329e+03 -2.95124487e+03 -2.92345288e+03 -2.96902710e+03 -3.16687109e+03 -3.18147437e+03 -3.12964722e+03 -3.21991846e+03 -3.25451855e+03 -3.27724731e+03 -3.32313647e+03 -3.36553003e+03 -3.32584302e+03 -3.44308105e+03 -3.63011670e+03 -3.59292139e+03 -3.65091992e+03 -3.70786523e+03 -3.66623462e+03 -3.71019824e+03 -3.75530737e+03 -3.77416040e+03 -3.73828198e+03 -3.77502832e+03 -3.89766895e+03 -3.94726392e+03 -4.09075317e+03 -4.02830420e+03 -3.93880908e+03 -4.09564258e+03 -4.16590186e+03 -4.31534863e+03 -4.30815479e+03 -4.20573535e+03 -4.22553809e+03 -4.23579639e+03 -4.36220264e+03 -4.40422363e+03 -4.53081006e+03 -4.56156299e+03 -4.49316895e+03 -4.50132178e+03 -4.41085254e+03 -4.58344531e+03 -4.86986963e+03 -4.85038232e+03 -4.73598975e+03 -4.63585010e+03 -4.60465820e+03 -4.87314648e+03 -5.04757471e+03 -4.96119434e+03 -4.80697168e+03 -4.82902734e+03 -4.98102930e+03 -5.03196289e+03 -5.16597510e+03 -5.17751172e+03 -5.08262158e+03 -5.09447705e+03 -5.11474219e+03 -5.34279248e+03 -5.40545264e+03 -5.13132617e+03 -5.15680908e+03 -5.46465186e+03 -5.46797461e+03 -5.20502344e+03 -5.31004590e+03 -5.64385596e+03 -5.63796289e+03 -5.53567139e+03 -5.40528369e+03 -5.41981445e+03 -5.77045752e+03 -5.78492383e+03 -5.65499219e+03 -5.54916211e+03 -5.51477051e+03 -5.68088232e+03 -5.76219580e+03 -5.82730664e+03 -5.65959277e+03 -5.81177393e+03 -6.08896875e+03 -5.95869971e+03 -6.00084424e+03 -5.97233105e+03 -5.88521045e+03 -5.98329980e+03 -6.02918213e+03 -6.05948486e+03 -6.02522070e+03 -5.95826514e+03 -5.87338916e+03 -6.06252881e+03 -6.39793115e+03 -6.13700928e+03 -5.89913770e+03 -6.12240186e+03 -6.29909473e+03 -6.55063428e+03 -6.38895850e+03 -6.20858496e+03 -6.37143799e+03 -6.38144629e+03 -6.22656982e+03 -6.18731787e+03 -6.45120459e+03 -6.44335889e+03 -6.35273975e+03 -6.33223193e+03 -6.16369629e+03 -6.38199561e+03 -6.81939795e+03 -6.64352588e+03 -6.46817822e+03 -6.32597803e+03 -6.26749268e+03 -6.61757373e+03 -6.93202686e+03 -6.70889551e+03 -6.44487158e+03 -6.46571582e+03 -6.54351904e+03 -6.58018652e+03 -6.80547998e+03 -6.71727832e+03 -6.53557666e+03 -6.61903174e+03 -6.60977295e+03 -6.84545557e+03 -6.83785498e+03 -6.63722705e+03 -6.66012549e+03 -6.68767090e+03 -6.78378711e+03 -6.62502588e+03 -6.62747607e+03 -6.93244678e+03 -6.88551562e+03 -6.77469824e+03 -6.59645654e+03 -6.61916797e+03 -7.08847363e+03 -7.04498828e+03 -6.80469824e+03 -6.67833789e+03 -6.64258398e+03 -6.73458740e+03 -6.78749268e+03 -6.85141113e+03 -6.70303516e+03 -6.79397363e+03 -7.08299414e+03 -6.83834912e+03 -6.96953076e+03 -7.02744531e+03 -6.83618262e+03 -6.79840576e+03 -6.76011084e+03 -6.84620752e+03 -6.85107568e+03 -6.76265723e+03 -6.77021045e+03 -6.93987451e+03 -7.02219141e+03 -6.67236621e+03 -6.60000684e+03 -6.77338477e+03 -6.92400146e+03 -7.13742236e+03 -6.95728906e+03 -6.66770947e+03 -6.83752100e+03 -6.99008008e+03 -6.87326562e+03 -6.78145068e+03 -6.74883594e+03 -6.67063525e+03 -6.66266211e+03 -6.78337793e+03 -6.65684277e+03 -6.71770947e+03 -7.00664453e+03 -6.90792139e+03 -6.73216211e+03 -6.63689551e+03 -6.62383057e+03 -6.90551416e+03 -6.89056250e+03 -6.71447803e+03 -6.54107324e+03 -6.39040674e+03 -6.52444189e+03 -6.80648828e+03 -6.97557666e+03 -6.72269824e+03 -6.46824756e+03 -6.51639453e+03 -6.54569580e+03 -6.81689893e+03 -6.74072021e+03 -6.51630420e+03 -6.47407178e+03 -6.42531885e+03 -6.53321582e+03 -6.42319922e+03 -6.41235791e+03 -6.67890576e+03 -6.59195850e+03 -6.46884619e+03 -6.30543408e+03 -6.25951562e+03 -6.61172070e+03 -6.58791406e+03 -6.34714746e+03 -6.21690967e+03 -6.13580957e+03 -6.27541016e+03 -6.32097412e+03 -6.48950391e+03 -6.43282959e+03 -6.20926025e+03 -6.01076855e+03 -6.09918408e+03 -6.42033301e+03 -6.29230225e+03 -6.11618018e+03 -6.05516260e+03 -6.03676416e+03 -6.00193701e+03 -5.92967529e+03 -6.06675684e+03 -6.02897803e+03 -5.87950098e+03 -6.06874805e+03 -6.11792285e+03 -5.97072070e+03 -5.88528027e+03 -5.83506104e+03 -5.83608838e+03 -5.66864990e+03 -5.59133740e+03 -5.85887451e+03 -5.87611523e+03 -5.53642920e+03 -5.41650342e+03 -5.68762842e+03 -5.87374561e+03 -5.75489941e+03 -5.51145605e+03 -5.37071631e+03 -5.54961084e+03 -5.59755566e+03 -5.46833350e+03 -5.46039795e+03 -5.30982324e+03 -5.07412891e+03 -5.24111621e+03 -5.53512158e+03 -5.49236475e+03 -5.16020605e+03 -4.99014844e+03 -5.26328418e+03 -5.38427930e+03 -5.17897363e+03 -4.97698975e+03 -4.88270801e+03 -4.94014844e+03 -4.94880273e+03 -5.10169531e+03 -5.07935400e+03 -4.86945752e+03 -4.78458496e+03 -4.74412988e+03 -4.88932471e+03 -4.77609473e+03 -4.60934229e+03 -4.76785596e+03 -4.73420996e+03 -4.62829541e+03 -4.50169775e+03 -4.44071143e+03 -4.65785986e+03 -4.49892090e+03 -4.27527979e+03 -4.35055566e+03 -4.40839307e+03 -4.37655615e+03 -4.28378516e+03 -4.35280664e+03 -4.33999902e+03 -4.18533447e+03 -4.02625317e+03 -3.97858594e+03 -4.16647070e+03 -4.08012427e+03 -3.93433618e+03 -3.91977295e+03 -3.87353662e+03 -3.89437769e+03 -3.83505249e+03 -3.84111597e+03 -3.75667700e+03 -3.64051025e+03 -3.72248389e+03 -3.70803760e+03 -3.61220532e+03 -3.55864795e+03 -3.51910718e+03 -3.44964014e+03 -3.30809082e+03 -3.26285352e+03 -3.39264307e+03 -3.46879565e+03 -3.25382153e+03 -3.07258130e+03 -3.16124146e+03 -3.25418750e+03 -3.17076440e+03 -3.01250293e+03 -2.89427856e+03 -3.00161475e+03 -2.96607642e+03 -2.82156934e+03 -2.90843506e+03 -2.83794165e+03 -2.64745508e+03 -2.63878442e+03 -2.72579395e+03 -2.69939771e+03 -2.53407739e+03 -2.42260986e+03 -2.48912744e+03 -2.54521680e+03 -2.43818384e+03 -2.28226465e+03 -2.20049243e+03 -2.28325293e+03 -2.27201050e+03 -2.14765381e+03 -2.11878247e+03 -2.09229639e+03 -2.01573718e+03 -1.95233350e+03 -1.97937317e+03 -1.89485974e+03 -1.78676001e+03 -1.81181189e+03 -1.77645996e+03 -1.73430371e+03 -1.64908875e+03 -1.56595374e+03 -1.58812915e+03 -1.50820422e+03 -1.42573853e+03 -1.44420312e+03 -1.48441113e+03 -1.46165710e+03 -1.26577405e+03 -1.32018884e+03 -1.37178711e+03 -1.02860022e+03 -1.01851617e+03 -1.00777637e+03 -1.04962207e+03 -1.58134924e+03 -1.39553113e+03 -1.16980615e+03 -1.85431360e+03 -3.10797974e+03 -8.61803750e+05 -3.44552986e+09 0. 0. 0. 0. 1381557632. 1381557632. 8.02582875e+05 -231494368. -4.65549170e+03 -3.54991016e+04 -5.51520508e+04 -1.22436906e+05 1129844736. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 469363232. 1.79326781e+05 1.31527771e+03 1.47304993e+03 1.02846533e+03 9.17847290e+02 1.07899292e+03 1.31368164e+03 1.17492212e+03 9.69030457e+02 1.11005408e+03 1.03423889e+03 1.05474866e+03 1.10661804e+03 1.14860608e+03 1.18521460e+03 1.24145007e+03 1.27328186e+03 1.30897717e+03 1.39327783e+03 1.44876819e+03 1.47910645e+03 1.51789246e+03 1.52306238e+03 1.57596082e+03 1.66724878e+03 1.69779993e+03 1.72218408e+03 1.81802551e+03 1.91544727e+03 1.91213928e+03 1.90599304e+03 1.94598157e+03 1.98184241e+03 2.07094067e+03 2.16564868e+03 2.17195166e+03 2.20956592e+03 2.29106909e+03 2.29970093e+03 2.30526733e+03 2.36382056e+03 2.40502197e+03 2.46126270e+03 2.57381812e+03 2.57629370e+03 2.57544507e+03 2.68080322e+03 2.69710571e+03 2.70543457e+03 2.75707324e+03 2.80465576e+03 2.87950244e+03 2.95029736e+03 3.02840918e+03 3.02366943e+03 3.00617651e+03 3.10362280e+03 3.08213623e+03 3.08784253e+03 3.24314331e+03 3.26997925e+03 3.28779785e+03 3.38849048e+03 3.41884985e+03 3.39313159e+03 3.43085400e+03 3.46164648e+03 3.50015039e+03 3.59381665e+03 3.64523364e+03 3.69178931e+03 3.73874756e+03 3.75414014e+03 3.78888330e+03 3.81890332e+03 3.88062769e+03 3.90537231e+03 3.95250342e+03 4.10255029e+03 4.05592993e+03 3.93669116e+03 4.06392017e+03 4.11690039e+03 4.13128369e+03 4.28101465e+03 4.25963232e+03 4.24776562e+03 4.40461621e+03 4.50341162e+03 4.42114160e+03 4.34049219e+03 4.37750439e+03 4.45956348e+03 4.57343994e+03 4.62209033e+03 4.67268701e+03 4.72957178e+03 4.73678027e+03 4.69722754e+03 4.65631152e+03 4.80130664e+03 4.85870215e+03 4.79470361e+03 4.92281885e+03 4.95096729e+03 4.94221387e+03 5.04984033e+03 5.00480908e+03 4.94793018e+03 5.02515674e+03 5.16450049e+03 5.23412500e+03 5.19852734e+03 5.23629688e+03 5.30731934e+03 5.34552783e+03 5.34894824e+03 5.26221533e+03 5.24599268e+03 5.47898145e+03 5.51185645e+03 5.39555957e+03 5.49943408e+03 5.47677344e+03 5.46618945e+03 5.61908936e+03 5.62747461e+03 5.54802002e+03 5.62568701e+03 5.79391797e+03 5.82820410e+03 5.77295605e+03 5.62496533e+03 5.64159473e+03 5.85438379e+03 5.92543848e+03 5.79931592e+03 5.85728613e+03 6.04241357e+03 6.04137354e+03 6.01114258e+03 5.97824072e+03 5.85599609e+03 5.85932910e+03 5.97869629e+03 6.12938818e+03 6.12990967e+03 6.09865039e+03 6.22310156e+03 6.22554395e+03 6.12710791e+03 6.09916113e+03 6.13958936e+03 6.19544238e+03 6.30791748e+03 6.43709766e+03 6.39330322e+03 6.33808252e+03 6.24125146e+03 6.37910742e+03 6.41998682e+03 6.21561377e+03 6.23892188e+03 6.46775586e+03 6.60512695e+03 6.40787256e+03 6.36773730e+03 6.37714844e+03 6.37878223e+03 6.52394043e+03 6.66255469e+03 6.63115186e+03 6.54237402e+03 6.56960059e+03 6.61757568e+03 6.52387109e+03 6.52575342e+03 6.56974805e+03 6.56969531e+03 6.76962988e+03 6.84662793e+03 6.57759619e+03 6.57944482e+03 6.65325488e+03 6.69468945e+03 6.82065527e+03 6.56277393e+03 6.51764307e+03 6.83185107e+03 6.88610254e+03 6.73696436e+03 6.69415967e+03 6.71619287e+03 6.67858008e+03 6.73914307e+03 6.88001562e+03 6.85147363e+03 6.70094678e+03 6.81089160e+03 6.99510986e+03 6.84072021e+03 6.77690137e+03 6.76024707e+03 6.75594629e+03 6.95810645e+03 6.84964209e+03 6.77619580e+03 6.96617383e+03 6.76224121e+03 6.73566602e+03 6.88871338e+03 6.74060059e+03 6.75574072e+03 6.93128516e+03 6.92622705e+03 6.91152295e+03 6.79849854e+03 6.86700391e+03 6.79424854e+03 6.75961133e+03 6.94223975e+03 6.75220996e+03 6.69753564e+03 6.88569238e+03 6.92360010e+03 6.80819873e+03 6.87067529e+03 6.93767969e+03 6.74031445e+03 6.85018457e+03 7.03573486e+03 6.75670947e+03 6.66653223e+03 6.74882324e+03 6.77129541e+03 6.68771875e+03 6.67691895e+03 6.72054883e+03 6.78013574e+03 6.84926660e+03 6.81885645e+03 6.71025000e+03 6.70842285e+03 6.68488721e+03 6.63540967e+03 6.77216846e+03 6.61868799e+03 6.60541309e+03 6.79363281e+03 6.63680322e+03 6.55005078e+03 6.61397510e+03 6.60330029e+03 6.51044922e+03 6.52942676e+03 6.58835449e+03 6.63650586e+03 6.59118945e+03 6.52562061e+03 6.57387646e+03 6.41329834e+03 6.39243311e+03 6.43061084e+03 6.33306104e+03 6.50671875e+03 6.60287500e+03 6.37383252e+03 6.27070068e+03 6.31867334e+03 6.50505273e+03 6.40814355e+03 6.10480713e+03 6.26913135e+03 6.44229736e+03 6.25463721e+03 6.18199023e+03 6.16044238e+03 6.16211035e+03 6.16372803e+03 6.12278906e+03 6.03825732e+03 6.19145947e+03 6.16879688e+03 6.04068115e+03 6.10852148e+03 6.08641895e+03 6.00242969e+03 5.96956299e+03 5.76678320e+03 5.93033301e+03 6.10633691e+03 5.82773975e+03 5.75680566e+03 5.80482373e+03 5.83160254e+03 5.82934668e+03 5.66702051e+03 5.73481250e+03 5.81688135e+03 5.71731104e+03 5.67760645e+03 5.59224756e+03 5.51016064e+03 5.54250488e+03 5.56757861e+03 5.49302002e+03 5.52139990e+03 5.52539258e+03 5.42574268e+03 5.45990332e+03 5.41972412e+03 5.28644043e+03 5.24368994e+03 5.30492285e+03 5.33189453e+03 5.18497021e+03 5.09850586e+03 5.07540625e+03 5.10725684e+03 5.15276318e+03 5.08834424e+03 4.95322021e+03 4.93261328e+03 4.99773486e+03 5.05927344e+03 4.92661914e+03 4.74065430e+03 4.78848438e+03 4.82300732e+03 4.72577539e+03 4.70286084e+03 4.72664355e+03 4.68881006e+03 4.61394873e+03 4.63846191e+03 4.61897852e+03 4.49904785e+03 4.44236865e+03 4.42816455e+03 4.42994141e+03 4.29033545e+03 4.20111182e+03 4.26945850e+03 4.28858545e+03 4.28736865e+03 4.19831494e+03 4.08049585e+03 4.14190820e+03 4.14315479e+03 3.96989258e+03 3.90980469e+03 3.95561255e+03 3.98293628e+03 3.91622778e+03 3.77626831e+03 3.69912451e+03 3.70514502e+03 3.75563916e+03 3.75673364e+03 3.71935815e+03 3.58533813e+03 3.47931104e+03 3.47512207e+03 3.41953149e+03 3.39024512e+03 3.37554785e+03 3.32880493e+03 3.31046387e+03 3.25710767e+03 3.20360815e+03 3.15041431e+03 3.12892700e+03 3.17166406e+03 3.09013306e+03 2.94530811e+03 2.90188721e+03 2.91571851e+03 2.91040259e+03 2.89037329e+03 2.81431714e+03 2.67284937e+03 2.62915479e+03 2.66964429e+03 2.66284839e+03 2.61696167e+03 2.52521289e+03 2.43256104e+03 2.42045166e+03 2.38493652e+03 2.35602832e+03 2.29770508e+03 2.19425830e+03 2.20945337e+03 2.20570215e+03 2.11765625e+03 2.04125940e+03 1.96394885e+03 1.96019507e+03 2.00580542e+03 1.93750305e+03 1.81381360e+03 1.79856360e+03 1.79788770e+03 1.69196313e+03 1.62635071e+03 1.56959949e+03 1.53582239e+03 1.55413208e+03 1.49083154e+03 1.39539807e+03 1.37009070e+03 1.34591284e+03 1.27825415e+03 1.22953076e+03 1.19894006e+03 1.14677368e+03 1.08660693e+03 1.04652026e+03 9.92157532e+02 9.60292358e+02 9.24846436e+02 8.68824890e+02 8.17283386e+02 7.44989319e+02 7.03078796e+02 6.67825867e+02 6.19569092e+02 5.81161743e+02 5.34782593e+02 4.84956787e+02 4.24599548e+02 3.76266022e+02 3.35878357e+02 2.88899750e+02 2.37138275e+02 1.83619797e+02 1.36481857e+02 9.18036728e+01 4.66326714e+01 3.51872826e+00 -4.33503799e+01 -9.30369873e+01 -1.48426651e+02 -2.00600769e+02 -2.42849518e+02 -2.87816803e+02 -3.29787750e+02 -3.74876526e+02 -4.38010010e+02 -4.89078522e+02 -5.16528870e+02 -5.57286621e+02 -6.18853699e+02 -6.83847656e+02 -7.30542786e+02 -7.58298828e+02 -7.99178406e+02 -8.54376160e+02 -9.09917542e+02 -9.53669434e+02 -9.89319458e+02 -1.04544507e+03 -1.10217041e+03 -1.13930981e+03 -1.19681995e+03 -1.24128809e+03 -1.28248425e+03 -1.34572131e+03 -1.38454309e+03 -1.42565649e+03 -1.45972131e+03 -1.50330347e+03 -1.56747729e+03 -1.62083777e+03 -1.67224231e+03 -1.69281140e+03 -1.72050916e+03 -1.80478052e+03 -1.86020996e+03 -1.89887207e+03 -1.94839966e+03 -1.95114026e+03 -2.00358057e+03 -2.10417798e+03 -2.12728369e+03 -2.12759448e+03 -2.23105737e+03 -2.28149023e+03 -2.25199170e+03 -2.35788281e+03 -2.40543408e+03 -2.38778979e+03 -2.50589038e+03 -2.57230200e+03 -2.54506494e+03 -2.58773560e+03 -2.66834619e+03 -2.69337671e+03 -2.75148022e+03 -2.79134229e+03 -2.76582349e+03 -2.84017407e+03 -2.95172437e+03 -3.00011377e+03 -3.03913501e+03 -3.04012158e+03 -3.08771948e+03 -3.11469482e+03 -3.10795679e+03 -3.22907935e+03 -3.28805859e+03 -3.26110840e+03 -3.37185767e+03 -3.41639160e+03 -3.37057690e+03 -3.47637134e+03 -3.55049146e+03 -3.57708936e+03 -3.61034106e+03 -3.58771265e+03 -3.58962256e+03 -3.74833984e+03 -3.87050464e+03 -3.79396704e+03 -3.82020337e+03 -3.82214990e+03 -3.87409448e+03 -4.03101440e+03 -3.97052808e+03 -3.94314111e+03 -4.07377368e+03 -4.16485840e+03 -4.15765381e+03 -4.07278687e+03 -4.20897217e+03 -4.32709766e+03 -4.28535596e+03 -4.34965576e+03 -4.32554785e+03 -4.36365918e+03 -4.49382275e+03 -4.51037354e+03 -4.58258789e+03 -4.52191846e+03 -4.51426416e+03 -4.61742383e+03 -4.63907959e+03 -4.74407373e+03 -4.73922070e+03 -4.67768018e+03 -4.77188672e+03 -4.89042432e+03 -4.90617285e+03 -4.89098193e+03 -4.92860693e+03 -4.96632959e+03 -5.02327441e+03 -5.02744336e+03 -4.97743262e+03 -5.14785254e+03 -5.16728418e+03 -5.14091895e+03 -5.27689160e+03 -5.22636719e+03 -5.16912598e+03 -5.32250293e+03 -5.26463965e+03 -5.27431250e+03 -5.44451514e+03 -5.39991162e+03 -5.36019629e+03 -5.41752002e+03 -5.49235254e+03 -5.53029248e+03 -5.65365430e+03 -5.60644629e+03 -5.55450293e+03 -5.61495850e+03 -5.56787988e+03 -5.64159033e+03 -5.68812939e+03 -5.76305518e+03 -5.85805420e+03 -5.71403223e+03 -5.82483789e+03 -5.85586133e+03 -5.75732861e+03 -5.86355469e+03 -5.93002393e+03 -6.02142627e+03 -5.96606396e+03 -5.91167578e+03 -6.04312793e+03 -6.04016064e+03 -6.02543213e+03 -6.03766504e+03 -6.08351074e+03 -6.22078516e+03 -6.14861426e+03 -6.13873096e+03 -6.24234521e+03 -6.14377002e+03 -6.12552539e+03 -6.32053125e+03 -6.37206201e+03 -6.20562256e+03 -6.28544238e+03 -6.27448633e+03 -6.21524951e+03 -6.55924170e+03 -6.45454736e+03 -6.30336963e+03 -6.66839941e+03 -6.59553662e+03 -6.42825342e+03 -6.47548926e+03 -8.30529297e+03 -8.98740039e+03 -1.66407773e+04 -2.00054824e+04 1.40079388e+06 -7004084. 4.11939175e+06 -5.13831350e+06 7554618. 49093276. 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. 0. 0. 0. 0. 0. 0. 0. 0. 7938896. -17083144. 1.68124838e+06 7235108. 4.09605475e+06 -2.18553047e+04 -1.77106465e+04 -1.09506572e+04 -8.75546191e+03 -9.17402051e+03 -7.57031787e+03 -6.88159229e+03 -6.78432129e+03 -6.94882373e+03 -6.86839551e+03 -6.79453662e+03 -6.76366846e+03 -6.83448682e+03 -6.91951074e+03 -6.91490186e+03 -6.75738379e+03 -6.60192822e+03 -6.81466064e+03 -6.89747852e+03 -6.80179346e+03 -6.84163623e+03 -6.66145557e+03 -6.64291943e+03 -6.73573682e+03 -6.77505225e+03 -6.80337598e+03 -6.56190674e+03 -6.46857422e+03 -6.80300391e+03 -6.95274902e+03 -6.75617822e+03 -6.42327197e+03 -6.43303809e+03 -6.67192236e+03 -6.71490527e+03 -6.58702441e+03 -6.44660010e+03 -6.60273584e+03 -6.72163965e+03 -6.62960742e+03 -6.57822998e+03 -6.29443848e+03 -6.41169434e+03 -6.70378076e+03 -6.55430322e+03 -6.49171387e+03 -6.43203174e+03 -6.25945312e+03 -6.38090771e+03 -6.57782324e+03 -6.46382031e+03 -6.21768457e+03 -6.36021924e+03 -6.40852930e+03 -6.30401709e+03 -6.32297314e+03 -6.14637158e+03 -6.28426611e+03 -6.32931396e+03 -6.18867676e+03 -6.09452686e+03 -6.00846387e+03 -6.15037109e+03 -6.31809277e+03 -6.23673438e+03 -6.09247754e+03 -5.94693604e+03 -5.99155518e+03 -5.98940479e+03 -6.04903760e+03 -6.07045020e+03 -5.84411963e+03 -5.88872461e+03 -6.00545117e+03 -5.93574609e+03 -5.86364014e+03 -5.67802148e+03 -5.74193896e+03 -5.90228418e+03 -5.85107227e+03 -5.73597266e+03 -5.57284619e+03 -5.56663818e+03 -5.68844385e+03 -5.74698828e+03 -5.57509961e+03 -5.42036963e+03 -5.58700342e+03 -5.53984619e+03 -5.44057959e+03 -5.55663867e+03 -5.38431396e+03 -5.35773926e+03 -5.44098145e+03 -5.36312109e+03 -5.36434570e+03 -5.21203271e+03 -5.08250537e+03 -5.20514502e+03 -5.27950977e+03 -5.24382422e+03 -5.09352979e+03 -5.05405518e+03 -5.05684766e+03 -5.04149365e+03 -5.01413623e+03 -4.85549707e+03 -4.88471631e+03 -5.01320996e+03 -4.93669678e+03 -4.75781934e+03 -4.61846582e+03 -4.71671729e+03 -4.90461963e+03 -4.81816943e+03 -4.65425488e+03 -4.49860986e+03 -4.48506592e+03 -4.55142334e+03 -4.57334180e+03 -4.57517725e+03 -4.39483740e+03 -4.34098584e+03 -4.33657080e+03 -4.32334375e+03 -4.38806689e+03 -4.20310156e+03 -4.15442578e+03 -4.25520215e+03 -4.15333838e+03 -4.07539966e+03 -4.02836987e+03 -4.01512451e+03 -4.04499292e+03 -3.98450000e+03 -3.85494775e+03 -3.74003076e+03 -3.81743701e+03 -3.92956030e+03 -3.83086475e+03 -3.69367627e+03 -3.57992676e+03 -3.57436743e+03 -3.60910059e+03 -3.59731860e+03 -3.55257056e+03 -3.37359033e+03 -3.32273926e+03 -3.37518091e+03 -3.40192432e+03 -3.38548438e+03 -3.27441772e+03 -3.18749902e+03 -3.11828735e+03 -3.12101196e+03 -3.13245850e+03 -3.02517529e+03 -2.98109106e+03 -2.96791919e+03 -2.91875439e+03 -2.89681470e+03 -2.78729614e+03 -2.76926343e+03 -2.78441089e+03 -2.69116260e+03 -2.67333569e+03 -2.59876831e+03 -2.55228418e+03 -2.54581079e+03 -2.50045972e+03 -2.44049634e+03 -2.31977026e+03 -2.29948218e+03 -2.33247363e+03 -2.32284277e+03 -2.25010278e+03 -2.10340723e+03 -2.04752637e+03 -2.07422388e+03 -2.06737476e+03 -2.00572876e+03 -1.88563147e+03 -1.85580371e+03 -1.84851074e+03 -1.79925232e+03 -1.77721533e+03 -1.67873596e+03 -1.62481396e+03 -1.62630139e+03 -1.58979944e+03 -1.52816284e+03 -1.45336548e+03 -1.41926868e+03 -1.37036609e+03 -1.32785608e+03 -1.31265259e+03 -1.23192969e+03 -1.17546863e+03 -1.14194910e+03 -1.08550159e+03 -1.03309009e+03 -9.90593201e+02 -9.69205383e+02 -9.29329834e+02 -8.70427307e+02 -8.02182861e+02 -7.28383667e+02 -7.08298645e+02 -6.98129456e+02 -6.41079712e+02 -5.76928345e+02 -5.09848267e+02 -4.56942505e+02 -4.26781097e+02 -3.96331055e+02 -3.44482697e+02 -2.87181793e+02 -2.39493607e+02 -1.92624420e+02 -1.44565399e+02 -9.50214386e+01 -4.48266411e+01 3.21829438e+00 5.19872208e+01 1.01183472e+02 1.47471283e+02 1.85214828e+02 2.39717270e+02 2.90490173e+02 3.27712830e+02 3.82185089e+02 4.31152191e+02 4.89147278e+02 5.37359070e+02 5.58108154e+02 5.98585022e+02 6.56534119e+02 7.34054260e+02 8.09839355e+02 8.36119690e+02 8.38182617e+02 8.63083862e+02 9.30731018e+02 1.02631921e+03 1.09848621e+03 1.13059839e+03 1.10971484e+03 1.14895728e+03 1.27751208e+03 1.32373083e+03 1.30235217e+03 1.33717102e+03 1.41964392e+03 1.47266724e+03 1.56247253e+03 1.57600403e+03 1.56037341e+03 1.65646936e+03 1.67319507e+03 1.74606689e+03 1.84334448e+03 1.80526746e+03 1.87452539e+03 1.97983020e+03 1.99264246e+03 2.02817004e+03 2.06672827e+03 2.12221118e+03 2.19192285e+03 2.20383203e+03 2.18159839e+03 2.24635767e+03 2.39830786e+03 2.50590771e+03 2.49160815e+03 2.43081812e+03 2.41448413e+03 2.49863892e+03 2.65655469e+03 2.79403320e+03 2.77038574e+03 2.67854321e+03 2.72457349e+03 2.85993457e+03 2.89665918e+03 2.88033423e+03 2.93192017e+03 2.99836743e+03 3.04909546e+03 3.17559961e+03 3.14829565e+03 3.11197119e+03 3216. 3.15435425e+03 3.28222314e+03 3.44716650e+03 3.37542188e+03 3.49959106e+03 3.50730347e+03 3.39899805e+03 3.54179028e+03 3.50416162e+03 3.58648267e+03 3.89186694e+03 3.73780811e+03 3.57258643e+03 3.70748877e+03 3.91589819e+03 4.07800854e+03 4.01960181e+03 3.86489355e+03 3.82030396e+03 3.91064038e+03 4.11708984e+03 4.30433398e+03 4.26431152e+03 4.08128809e+03 4.08108374e+03 4.28364551e+03 4.36990674e+03 4.29192627e+03 4.29240479e+03 4.39199512e+03 4.42455908e+03 4.61299805e+03 4.66724707e+03 4.44561914e+03 4.47559473e+03 4.59480615e+03 4.63663818e+03 4.71480713e+03 4733. 4.86087500e+03 4.80138135e+03 4.67357373e+03 4.84943750e+03 4.74891699e+03 4.91538428e+03 5.26887207e+03 4.98829932e+03 4.72842090e+03 4.92026953e+03 5.19739697e+03 5.35128369e+03 5.38802295e+03 5.10787158e+03 4.93075391e+03 5.09659766e+03 5.39226855e+03 5.62278516e+03 5.51459229e+03 5.22082666e+03 5.20317871e+03 5.40387207e+03 5.50896094e+03 5.62381787e+03 5.64581836e+03 5.39789111e+03 5.41472314e+03 5.66844922e+03 5.74352832e+03 5.64429834e+03 5.63987207e+03 5.62106934e+03 5.63288037e+03 5.89552051e+03 6.00380957e+03 5.77944922e+03 5.73536133e+03 5.74458887e+03 5.76040332e+03 5.91430029e+03 5.92828467e+03 6.12948096e+03 6.14036816e+03 5.92962988e+03 5.84658984e+03 5.80605469e+03 6.08059961e+03 6.40437354e+03 6.28747559e+03 6.01686816e+03 5.85151318e+03 6.13722363e+03 6.51324121e+03 6.21006348e+03 5.93023633e+03 6.10557275e+03 6.28911621e+03 6.45193213e+03 6.61796484e+03 6.52686426e+03 6.15705371e+03 6.08476904e+03 6.38046875e+03 6.49120264e+03 6.49027539e+03 6.45635693e+03 6.44597412e+03 6.40867920e+03 6.58061865e+03 6.47625049e+03 6.33408740e+03 6.39420557e+03 6.47594727e+03 6.73344434e+03 6.74200098e+03 6.55731201e+03 6.67382568e+03 6.64161475e+03 6.64758496e+03 6.53912939e+03 6.35185156e+03 6.71988477e+03 7.04907080e+03 6.77049023e+03 6.48266699e+03 6.51117822e+03 6.87340527e+03 6.96055811e+03 6.85679541e+03 6.72984082e+03 6.55602686e+03 6.57691504e+03 6.84341064e+03 6.86100781e+03 6.72834961e+03 6.57176172e+03 6.52565332e+03 6.87223047e+03 7.23404834e+03 6.85893750e+03 6.61288330e+03 6.80042139e+03 6.82526025e+03 7.02094336e+03 7.00133887e+03 6.56207812e+03 6.64476270e+03 6.88800586e+03 6.84960205e+03 6.86981445e+03 7.00377246e+03 6.76637695e+03 7.37720850e+03 7.37275342e+03 6.80276465e+03 7.78620215e+03 8.17316797e+03 1.83622168e+04 1.18735859e+04 2.00422695e+04 2.00373320e+04 -2.86640450e+06 -2804770. 11531426. -2.06619912e+06 -4.54671750e+06 1.76137875e+06 17449876. 34538408. 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. 0. -249400496. -249400496. -249400496. 0. 0. 3318850. 4221781. 2.21180575e+06 2.00392910e+04 1.63375947e+04 1.07579980e+04 1.03559424e+04 8.23293848e+03 8.06710010e+03 6.64842725e+03 6.59546826e+03 6.41953271e+03 6.20726221e+03 6.34447412e+03 6.36095459e+03 6.17901807e+03 6.19991064e+03 6.21614355e+03 6.13538574e+03 6.12250098e+03 6.05314648e+03 6.00232031e+03 6.00592188e+03 5.98451807e+03 6.02979590e+03 6.04000244e+03 5.79578516e+03 5.78224219e+03 6.02518848e+03 6.00750879e+03 5.88180420e+03 5.84891504e+03 5.80189746e+03 5.78990137e+03 5.74419482e+03 5.73763525e+03 5.69769531e+03 5.66164111e+03 5.57338232e+03 5.51398926e+03 5.68627490e+03 5.70363818e+03 5.54148828e+03 5.48507520e+03 5.47741748e+03 5.47892432e+03 5.41932080e+03 5.39159424e+03 5.37055420e+03 5.24319238e+03 5.18614600e+03 5.22927441e+03 5.18498877e+03 5.36319727e+03 5.33973145e+03 5.13000879e+03 4.97964941e+03 4.92582471e+03 5.18680908e+03 5.19750635e+03 5.00615820e+03 4.85510791e+03 4.82623242e+03 4.89689746e+03 4.85226953e+03 4.92831592e+03 4.91622607e+03 4.60978027e+03 4.49718701e+03 4.70900879e+03 4.88475635e+03 4.69996777e+03 4.57362500e+03 4.53034912e+03 4.47418311e+03 4.43847852e+03 4.42704883e+03 4.38178955e+03 4.31192676e+03 4.31250342e+03 4.28607178e+03 4.23166553e+03 4.18248584e+03 4.27368164e+03 4.24983008e+03 4.09926025e+03 4.03147021e+03 3.99645972e+03 4.03529858e+03 4.00308325e+03 3.89850635e+03 3.87419458e+03 3.74833691e+03 3.65736157e+03 3.78921802e+03 3.73186230e+03 3.51095288e+03 3.51816089e+03 3.67805371e+03 3.76146655e+03 3.59794922e+03 3.44697339e+03 3.37766504e+03 3.33683984e+03 3.32237085e+03 3.27636914e+03 3.23148901e+03 3.18567065e+03 3.24461133e+03 3.20899487e+03 3.07228516e+03 3.02859888e+03 2.90437378e+03 2.88662231e+03 3.01712720e+03 2.94519287e+03 2.83656689e+03 2.73171265e+03 2.64268188e+03 2.73856641e+03 2.74843286e+03 2.62431470e+03 2.50420654e+03 2.45435059e+03 2.46909985e+03 2.42102271e+03 2.45491113e+03 2.42709497e+03 2.29719824e+03 2.22194287e+03 2.17800342e+03 2.18682617e+03 2.14694385e+03 2.06843579e+03 2.01721143e+03 1.97253223e+03 1.91871704e+03 1.82524292e+03 1.80576013e+03 1.85573083e+03 1.78698254e+03 1.70211890e+03 1.61675830e+03 1.56433960e+03 1.60708337e+03 1.55715051e+03 1.46813733e+03 1.38801001e+03 1.33767786e+03 1.33483264e+03 1.27825134e+03 1.23533301e+03 1.16092920e+03 1.13034033e+03 1.15339355e+03 1.07829468e+03 9.97283508e+02 9.54961487e+02 9.09623657e+02 8.56387146e+02 8.09182800e+02 7.56983276e+02 7.08419800e+02 6.62127808e+02 5.97182678e+02 5.59546631e+02 5.44506714e+02 4.77064056e+02 4.14843231e+02 3.79156281e+02 3.31488220e+02 2.92317596e+02 2.40186462e+02 1.84434464e+02 1.43955414e+02 9.64206543e+01 4.67912292e+01 8.04359376e-01 -4.48352470e+01 -9.15287018e+01 -1.39865524e+02 -1.87416214e+02 -2.30644440e+02 -2.87673431e+02 -3.53132324e+02 -3.94555725e+02 -4.31450500e+02 -4.66787506e+02 -5.10443390e+02 -5.88236267e+02 -6.42380432e+02 -6.72956482e+02 -6.99241821e+02 -7.40406799e+02 -8.12543823e+02 -8.62704712e+02 -9.27691406e+02 -9.62716248e+02 -9.82855530e+02 -1.04003540e+03 -1.08626111e+03 -1.17371375e+03 -1.21612012e+03 -1.21972180e+03 -1.27661853e+03 -1.32831946e+03 -1.36389258e+03 -1.36983984e+03 -1.45462170e+03 -1.59309802e+03 -1.59813391e+03 -1.60595312e+03 -1.61953174e+03 -1.65079077e+03 -1.79676123e+03 -1.84819104e+03 -1.84557397e+03 -1.84796204e+03 -1.87812036e+03 -1.98668787e+03 -2.02715308e+03 -2.11971924e+03 -2.15803931e+03 -2.14471265e+03 -2.17447119e+03 -2.20485645e+03 -2.35345752e+03 -2.39466455e+03 -2.37451343e+03 -2.40283594e+03 -2.43466870e+03 -2.56920044e+03 -2.62144043e+03 -2.54421069e+03 -2.58271240e+03 -2.76821997e+03 -2.81688867e+03 -2.71820825e+03 -2.74545630e+03 -2.93412573e+03 -3.00520508e+03 -2.94916138e+03 -2.91645801e+03 -2.96857007e+03 -3.17204785e+03 -3.17181885e+03 -3.12551367e+03 -3.23150195e+03 -3.27566650e+03 -3.27693896e+03 -3.29371582e+03 -3.35324146e+03 -3.31627075e+03 -3.44669604e+03 -3.68488184e+03 -3.61731396e+03 -3.60340479e+03 -3.66161035e+03 -3.67130591e+03 -3.70907642e+03 -3.75469971e+03 -3.79358691e+03 -3.73229614e+03 -3.72406836e+03 -3.86302612e+03 -3.98060669e+03 -4.12439111e+03 -4.03659375e+03 -3.93406250e+03 -4.08646411e+03 -4.17027783e+03 -4.33118408e+03 -4.33208691e+03 -4.24021484e+03 -4.20136621e+03 -4.20367578e+03 -4.35916504e+03 -4.41364502e+03 -4.52735010e+03 -4.58339648e+03 -4.52468701e+03 -4.45859326e+03 -4.37518457e+03 -4.58029248e+03 -4.85192969e+03 -4.84024023e+03 -4.74079346e+03 -4.64334180e+03 -4.60761963e+03 -4.87786572e+03 -5.05049658e+03 -4.93852832e+03 -4.79423682e+03 -4.83107861e+03 -4.98913965e+03 -5.02374365e+03 -5.17587500e+03 -5.22524463e+03 -5.13231201e+03 -5.08474512e+03 -5.08567969e+03 -5.30223145e+03 -5.36004053e+03 -5.14140820e+03 -5.16295654e+03 -5.47369922e+03 -5.46047266e+03 -5.20960693e+03 -5.32411084e+03 -5.62752441e+03 -5.61842725e+03 -5.52638623e+03 -5.40633789e+03 -5.40540771e+03 -5.76682178e+03 -5.80261719e+03 -5.66250732e+03 -5.52835498e+03 -5.51538184e+03 -5.69222510e+03 -5.75840576e+03 -5.79324023e+03 -5.65656445e+03 -5.82049023e+03 -6.11987598e+03 -5.98152588e+03 -5.98138379e+03 -5.99389648e+03 -5.95922217e+03 -5.98647998e+03 -6.01033691e+03 -6.03825049e+03 -6.02504736e+03 -5.98502637e+03 -5.88914600e+03 -6.05226855e+03 -6.33229102e+03 -6.12905420e+03 -5.96262939e+03 -6.16549414e+03 -6.26620166e+03 -6.47707373e+03 -6.38707178e+03 -6.22219141e+03 -6.36769287e+03 -6.35099951e+03 -6.19641748e+03 -6.20597461e+03 -6.47718750e+03 -6.48206299e+03 -6.35999121e+03 -6.27859863e+03 -6.12203369e+03 -6.38116064e+03 -6.82826465e+03 -6.69604492e+03 -6.45373242e+03 -6.36283545e+03 -6.32063916e+03 -6.64822461e+03 -6.82132568e+03 -6.62744580e+03 -6.45426709e+03 -6.42986719e+03 -6.54516113e+03 -6.57213086e+03 -6.80571973e+03 -6.78895508e+03 -6.59708350e+03 -6.63876807e+03 -6.62620850e+03 -6.80112402e+03 -6.82275391e+03 -6.73580811e+03 -6.63629248e+03 -6.65687061e+03 -6.71778320e+03 -6.58976123e+03 -6.61743896e+03 -6.96309668e+03 -6.86745996e+03 -6.79313721e+03 -6.62934570e+03 -6.57998926e+03 -6.99934082e+03 -7.02421484e+03 -6.79411816e+03 -6.68168994e+03 -6.68157324e+03 -6.72549268e+03 -6.73941602e+03 -6.80752197e+03 -6.67371729e+03 -6.83872803e+03 -7.11640039e+03 -6.88359033e+03 -6.93932910e+03 -6.97414795e+03 -6.87491113e+03 -6.82772900e+03 -6.73580908e+03 -6.81134717e+03 -6.85408984e+03 -6.84370166e+03 -6.83080859e+03 -6.90550488e+03 -6.98639209e+03 -6.65600537e+03 -6.56513916e+03 -6.78326611e+03 -6.90119824e+03 -7.08471045e+03 -6.92749902e+03 -6.71504102e+03 -6.92542773e+03 -6.90187891e+03 -6.72208740e+03 -6.81402539e+03 -6.78014062e+03 -6.72903418e+03 -6.69370801e+03 -6.78722412e+03 -6.62709619e+03 -6.76778418e+03 -7.01851660e+03 -6.86691553e+03 -6.78126807e+03 -6.66253223e+03 -6.56233740e+03 -6.83753467e+03 -6.90517725e+03 -6.72736914e+03 -6.54202051e+03 -6.40324414e+03 -6.59854297e+03 -6.73426807e+03 -6.88950928e+03 -6.70583350e+03 -6.47369971e+03 -6.58446582e+03 -6.54412158e+03 -6.79198291e+03 -6.74812598e+03 -6.49668066e+03 -6.48703662e+03 -6.43461816e+03 -6.51876074e+03 -6.36397754e+03 -6.44669385e+03 -6.74567578e+03 -6.59448242e+03 -6.49780615e+03 -6.31007324e+03 -6.20704541e+03 -6.60304541e+03 -6.55019922e+03 -6.31710449e+03 -6.20133154e+03 -6.14775635e+03 -6.30043945e+03 -6.30845654e+03 -6.43928906e+03 -6.41109570e+03 -6.22566943e+03 -6.05993359e+03 -6.02971680e+03 -6.36206006e+03 -6.26428955e+03 -6.07225244e+03 -6.11494043e+03 -6.09533740e+03 -6.02318994e+03 -5.95910303e+03 -6.11215771e+03 -5.97389746e+03 -5.82757861e+03 -6.11404834e+03 -6.14537598e+03 -5.92953369e+03 -5.84289502e+03 -5.85100488e+03 -5.85277148e+03 -5.64286572e+03 -5.57387207e+03 -5.88143701e+03 -5.86861914e+03 -5.49709863e+03 -5.40205225e+03 -5.71099805e+03 -5.91865674e+03 -5.70205615e+03 -5.46848145e+03 -5.43008887e+03 -5.60181738e+03 -5.54259375e+03 -5.39689502e+03 -5.46536279e+03 -5.31950146e+03 -5.11516943e+03 -5.30005957e+03 -5.50972998e+03 -5.44413477e+03 -5.17785742e+03 -5.02069287e+03 -5.27844873e+03 -5.37420361e+03 -5.14880859e+03 -4.98549561e+03 -4.95581055e+03 -4.99063379e+03 -4.94942139e+03 -5.09250098e+03 -5.00372705e+03 -4.77067334e+03 -4.85759961e+03 -4.83061426e+03 -4.86703516e+03 -4.72939551e+03 -4.58019287e+03 -4.74692139e+03 -4.73206787e+03 -4.60868799e+03 -4.47988330e+03 -4.47114258e+03 -4.68369971e+03 -4.50715967e+03 -4.31983057e+03 -4.38024512e+03 -4.35031787e+03 -4.32724170e+03 -4.28624121e+03 -4.35275439e+03 -4.33935645e+03 -4.18370459e+03 -4.02185156e+03 -3.98434473e+03 -4.15796777e+03 -4.07738232e+03 -3.92089038e+03 -3.93398413e+03 -3.91024121e+03 -3.87738062e+03 -3.82247217e+03 -3.85858643e+03 -3.72849292e+03 -3.59925562e+03 -3.72467310e+03 -3.69065918e+03 -3.60521973e+03 -3.56492773e+03 -3.51740967e+03 -3.46718628e+03 -3.33810791e+03 -3.25908594e+03 -3.39364917e+03 -3.42842847e+03 -3.21970752e+03 -3.08374976e+03 -3.17797021e+03 -3.25853540e+03 -3.14209839e+03 -2.98937695e+03 -2.90041260e+03 -2.99284961e+03 -2.97411694e+03 -2.84528564e+03 -2.87698877e+03 -2.83918701e+03 -2.70516992e+03 -2.64692505e+03 -2.68036377e+03 -2.67619141e+03 -2.52691724e+03 -2.43852637e+03 -2.51549194e+03 -2.51532983e+03 -2.40662524e+03 -2.27407202e+03 -2.21191382e+03 -2.29926807e+03 -2.27081519e+03 -2.14585034e+03 -2.09246045e+03 -2.05888989e+03 -2.00233826e+03 -1.94834009e+03 -1.98145471e+03 -1.88881470e+03 -1.77870996e+03 -1.82572742e+03 -1.78802100e+03 -1.72006738e+03 -1.63698413e+03 -1.56186267e+03 -1.58130676e+03 -1.51145886e+03 -1.44328247e+03 -1.44770105e+03 -1.45371912e+03 -1.42039490e+03 -1.23918811e+03 -1.28523926e+03 -1.31399622e+03 -9.88848999e+02 -1.00641980e+03 -1.04727063e+03 -1.04616418e+03 -1.43698340e+03 -1.05126318e+03 -1.02084668e+03 -1.69305591e+03 -2.76005786e+03 1.47612953e+05 940005440. 0. 0. 0. 0. 1381557632. 1381557632. 8.02582875e+05 838171904. 89105472. 5.56289648e+04 5.56289648e+04 833382336. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 469363232. 1.79326781e+05 2.65901406e+05 -9.74267750e+05 1.48940516e+05 3.04350391e+03 2.34339844e+03 1.29185352e+03 1.02443726e+03 1.43161658e+03 1.15092969e+03 1.02772278e+03 1.07634167e+03 1.10845703e+03 1.15132202e+03 1.21540942e+03 1.23899548e+03 1.26931592e+03 1.32042957e+03 1.35507947e+03 1.42412317e+03 1.51419714e+03 1.55636121e+03 1.54935559e+03 1.58650928e+03 1.64951990e+03 1.66401233e+03 1.72742578e+03 1.82307483e+03 1.85460449e+03 1.90162195e+03 1.95373096e+03 1.95865234e+03 1.99948462e+03 2.06603516e+03 2.09641260e+03 2.12764209e+03 2.22653540e+03 2.30556372e+03 2.29133765e+03 2.32289209e+03 2.38504395e+03 2.43155591e+03 2.49744751e+03 2.52151147e+03 2.50824634e+03 2.60606592e+03 2.72917139e+03 2.67731177e+03 2.69341309e+03 2.80637012e+03 2.78264404e+03 2.84020898e+03 2.97938989e+03 2.96822876e+03 2.97363062e+03 3.06688135e+03 3.18093262e+03 3.14178809e+03 3.09904688e+03 3.14868311e+03 3.19610742e+03 3.33994116e+03 3.43796191e+03 3.40029492e+03 3.40081421e+03 3.43718628e+03 3.46827417e+03 3.53877710e+03 3.56144336e+03 3.55174902e+03 3.66998413e+03 3.81128223e+03 3.77920435e+03 3.76261084e+03 3.86599951e+03 3.86647559e+03 3.87923047e+03 3.96853198e+03 4.01471704e+03 4.00654541e+03 4.01172998e+03 4.12994775e+03 4.16006104e+03 4.18414404e+03 4.23134521e+03 4.15209521e+03 4.28250684e+03 4.44932715e+03 4.37446924e+03 4.36600488e+03 4.42301807e+03 4.46415771e+03 4.54107471e+03 4.53010303e+03 4.46919238e+03 4.63994971e+03 4.79268750e+03 4.74015234e+03 4.65287256e+03 4.69612598e+03 4.84549023e+03 4.86929150e+03 4.83863281e+03 4.85949902e+03 4.85254248e+03 5.00144678e+03 5.14201367e+03 5.02021338e+03 4.96755957e+03 4.99542188e+03 5.05328467e+03 5.17387207e+03 5.26658301e+03 5.21423584e+03 5.23131250e+03 5.39732764e+03 5.43485352e+03 5.30837891e+03 5.24024023e+03 5.31352393e+03 5.44402783e+03 5.51839697e+03 5.54932471e+03 5.52695703e+03 5.55447168e+03 5.60147510e+03 5.53524854e+03 5.54159570e+03 5.63102197e+03 5.63554150e+03 5.74993213e+03 5.86191699e+03 5.66028369e+03 5.67295801e+03 5.91933643e+03 5.87211816e+03 5.72142383e+03 5.86745459e+03 6.04096729e+03 6.00477490e+03 5.97307666e+03 5.97334180e+03 5.97227734e+03 5.97587256e+03 5.94635059e+03 6.06167871e+03 6.09925977e+03 6.08598242e+03 6.15554932e+03 6.21435889e+03 6.20459619e+03 6.08221191e+03 6.16661328e+03 6.30442285e+03 6.20234180e+03 6.33180127e+03 6.44762109e+03 6.40671436e+03 6.28095654e+03 6.29919434e+03 6.33670117e+03 6.24621143e+03 6.38123291e+03 6.52651855e+03 6.48525488e+03 6.44483545e+03 6.42195557e+03 6.43068506e+03 6.48772412e+03 6.47569678e+03 6.42697314e+03 6.51009131e+03 6.60708545e+03 6.58041602e+03 6.56772949e+03 6.59372119e+03 6.58145215e+03 6.62738232e+03 6.61797070e+03 6.58398926e+03 6.72257275e+03 6.68152441e+03 6.62143896e+03 6.68576270e+03 6.73509570e+03 6.84146729e+03 6.53333057e+03 6.58850732e+03 6.83816113e+03 6.70712451e+03 6.81965869e+03 6.79435742e+03 6.67968457e+03 6.76095312e+03 6.73432910e+03 6.66275586e+03 6.74444482e+03 6.79777051e+03 6.85700195e+03 6.95921191e+03 6.91506055e+03 6.82099658e+03 6.82987061e+03 6.75796191e+03 6.74554443e+03 6.78024805e+03 6.86789990e+03 7.01304395e+03 6.79537158e+03 6.72644629e+03 6.87012744e+03 6.70816650e+03 6.83961816e+03 6.98638281e+03 6.81287598e+03 6.78310352e+03 6.84923193e+03 6.91690918e+03 6.89099316e+03 6.79249023e+03 6.76063672e+03 6.73197119e+03 6.81037842e+03 6.92066553e+03 6.89869531e+03 6.84219971e+03 6.83946045e+03 6.88786377e+03 6.76919043e+03 6.83635791e+03 6.97161035e+03 6.73591992e+03 6.69537793e+03 6.75663916e+03 6.78721729e+03 6.80352930e+03 6.76758398e+03 6.72502734e+03 6.74231201e+03 6.74689795e+03 6.73241553e+03 6.74564600e+03 6.88917432e+03 6.82595459e+03 6.53665479e+03 6.63308301e+03 6.65114746e+03 6.65921240e+03 6.79390479e+03 6.59164502e+03 6.49394287e+03 6.70352686e+03 6.66940137e+03 6.50518945e+03 6.48942236e+03 6.61312012e+03 6.64070557e+03 6.48474268e+03 6.52949170e+03 6.61961475e+03 6.45727490e+03 6.42270264e+03 6.47721191e+03 6.33530029e+03 6.43711670e+03 6.54506689e+03 6.31314795e+03 6.39785938e+03 6.52019727e+03 6.39364600e+03 6.26195605e+03 6.18094189e+03 6.27097559e+03 6.39859912e+03 6.25219189e+03 6.11904639e+03 6.20280322e+03 6.18530273e+03 6.13056494e+03 6.10889209e+03 6.14036865e+03 6.11959814e+03 6.04592334e+03 6.06311816e+03 6.13032617e+03 6.00762109e+03 5.97394873e+03 6.02073291e+03 5.86008691e+03 5.99865088e+03 6.02442627e+03 5.76856201e+03 5.85303906e+03 5.84139111e+03 5.71873584e+03 5.79296680e+03 5.73566455e+03 5.74877246e+03 5.80653516e+03 5.68467090e+03 5.63085596e+03 5.60147510e+03 5.51117627e+03 5.47858252e+03 5.50919971e+03 5.57527441e+03 5.54376611e+03 5.47381885e+03 5.43955322e+03 5.44888721e+03 5.38146045e+03 5.25316650e+03 5.28459521e+03 5.34405518e+03 5.30746094e+03 5.14537207e+03 5.05959277e+03 5.14227344e+03 5.22228711e+03 5.07627734e+03 4.98679834e+03 5.01626123e+03 4.99110986e+03 5.02202686e+03 4.98877295e+03 4.88603662e+03 4.75795557e+03 4.75829053e+03 4.79036328e+03 4.72486963e+03 4.74276172e+03 4.72746777e+03 4.66534277e+03 4.61389160e+03 4.65549170e+03 4.57956787e+03 4.45871533e+03 4.50075098e+03 4.50594043e+03 4.40889697e+03 4.26323926e+03 4.21414355e+03 4.29364795e+03 4.30914258e+03 4.23709277e+03 4.16408545e+03 4.11930029e+03 4.15191016e+03 4.10952930e+03 3.94360986e+03 3.92530347e+03 3.94998877e+03 3.96060620e+03 3.87543384e+03 3.75061670e+03 3.74942432e+03 3.74703101e+03 3.75391162e+03 3.74568701e+03 3.68648950e+03 3.54626172e+03 3.43539062e+03 3.50146118e+03 3.55502441e+03 3.43892700e+03 3.34936377e+03 3.29226440e+03 3.28893115e+03 3.29711133e+03 3.19871484e+03 3.14382153e+03 3.12740454e+03 3.13783813e+03 3.10028882e+03 2.94884668e+03 2.95715796e+03 2.94207861e+03 2.83727246e+03 2.82646118e+03 2.77777759e+03 2.72089648e+03 2.68276904e+03 2.62903271e+03 2.60459399e+03 2.58877783e+03 2.54246753e+03 2.44425659e+03 2.41957031e+03 2.42363477e+03 2.34711865e+03 2.28428955e+03 2.19697559e+03 2.17272607e+03 2.20732373e+03 2.13662231e+03 2.06215527e+03 1.97670215e+03 1.95837634e+03 1.98611877e+03 1.89469470e+03 1.82701978e+03 1.81056299e+03 1.75386902e+03 1.67220300e+03 1.64648523e+03 1.61838684e+03 1.54937610e+03 1.52220276e+03 1.46872302e+03 1.38215540e+03 1.36254712e+03 1.33650427e+03 1.28667212e+03 1.26041455e+03 1.19572754e+03 1.13927490e+03 1.08676306e+03 1.03602600e+03 1.00006720e+03 9.56253113e+02 9.04985107e+02 8.45772766e+02 8.07196228e+02 7.52289429e+02 7.05292603e+02 6.82527405e+02 6.26511719e+02 5.68032715e+02 5.19241821e+02 4.69645996e+02 4.23141113e+02 3.84462952e+02 3.39243805e+02 2.80468140e+02 2.27839615e+02 1.83905029e+02 1.40507172e+02 9.55381927e+01 4.83159981e+01 -2.81363297e+00 -5.00002747e+01 -9.48689804e+01 -1.39415466e+02 -1.89372406e+02 -2.40002579e+02 -2.90333618e+02 -3.31424530e+02 -3.70933685e+02 -4.32496979e+02 -4.88953613e+02 -5.28811462e+02 -5.68247131e+02 -6.16412903e+02 -6.76651917e+02 -7.30433838e+02 -7.68410522e+02 -8.02211853e+02 -8.51989441e+02 -9.11444763e+02 -9.54570435e+02 -1.00331934e+03 -1.05289941e+03 -1.08162354e+03 -1.13724500e+03 -1.19730591e+03 -1.23980566e+03 -1.29123474e+03 -1.33150659e+03 -1.37839880e+03 -1.42494348e+03 -1.47220312e+03 -1.48974414e+03 -1.53457153e+03 -1.61895251e+03 -1.68265454e+03 -1.73670911e+03 -1.73958215e+03 -1.77753235e+03 -1.82575940e+03 -1.87835413e+03 -1.97174329e+03 -1.97064246e+03 -2.01062549e+03 -2.11367944e+03 -2.09331421e+03 -2.10973853e+03 -2.22787183e+03 -2.28317041e+03 -2.30104932e+03 -2.37489233e+03 -2.37097729e+03 -2.34725000e+03 -2.48292358e+03 -2.56944629e+03 -2.54976855e+03 -2.64630200e+03 -2.70034009e+03 -2.64601611e+03 -2.70736914e+03 -2.76976074e+03 -2.80112793e+03 -2.90482446e+03 -2.93557202e+03 -2.95013208e+03 -3.01069141e+03 -3.05845581e+03 -3.11816406e+03 -3.12331396e+03 -3.13596362e+03 -3.21446973e+03 -3.27109888e+03 -3.25597168e+03 -3.31662012e+03 -3.40863721e+03 -3.41433887e+03 -3.48056396e+03 -3.53470288e+03 -3.55674805e+03 -3.60818481e+03 -3.56556543e+03 -3.61503711e+03 -3.78637939e+03 -3.80497998e+03 -3.77608838e+03 -3.84437646e+03 -3.90958862e+03 -3.92343237e+03 -3.95181323e+03 -3.88059692e+03 -3.91483203e+03 -4.10517920e+03 -4.18168213e+03 -4.19696924e+03 -4.12084717e+03 -4.17258594e+03 -4.29755566e+03 -4.29861328e+03 -4.31076123e+03 -4.36273682e+03 -4.38307422e+03 -4.45923242e+03 -4.49243311e+03 -4.56923926e+03 -4.55696045e+03 -4.52335742e+03 -4.69231543e+03 -4.63947510e+03 -4.61438184e+03 -4.70002588e+03 -4.68985205e+03 -4.79462744e+03 -4.96285010e+03 -4.95350781e+03 -4.81107471e+03 -4.85465137e+03 -4.99588477e+03 -5.04945166e+03 -5.04604736e+03 -5.03336719e+03 -5.10756348e+03 -5.17754053e+03 -5.18336670e+03 -5.23545996e+03 -5.21575391e+03 -5.23923389e+03 -5.34208740e+03 -5.16802490e+03 -5.17513965e+03 -5.45195557e+03 -5.46152051e+03 -5.44956787e+03 -5.46047021e+03 -5.40480127e+03 -5.43940625e+03 -5.64022949e+03 -5.70098340e+03 -5.58656055e+03 -5.56282959e+03 -5.55659473e+03 -5.63416260e+03 -5.75559277e+03 -5.80182471e+03 -5.82454053e+03 -5.75945312e+03 -5.79592041e+03 -5.84224951e+03 -5.75543213e+03 -5.79804639e+03 -5.96376709e+03 -5.98610059e+03 -5.95112695e+03 -5.95685205e+03 -5.98658203e+03 -6.03618896e+03 -5.97623926e+03 -6.11708398e+03 -6.10706006e+03 -6.11834277e+03 -6.13436572e+03 -6.14184717e+03 -6.31775195e+03 -6.20731885e+03 -6.15241943e+03 -6.31458057e+03 -6.24316113e+03 -6.15074121e+03 -6.32036963e+03 -6.34104199e+03 -6.28270117e+03 -6.41285596e+03 -6.46533594e+03 -6.42963232e+03 -6.55140039e+03 -6.45925342e+03 -6.32550391e+03 -6.55205225e+03 -8.53295117e+03 -8.86862305e+03 -9.94960254e+03 -9.94640039e+03 -1.07276689e+04 -9.40586719e+03 -1.91186914e+04 -2.88367031e+04 7554618. 49093276. 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. 0. 0. 0. 0. 0. 0. 0. 0. 7938896. -17083144. 1.68124838e+06 7235108. 4.09605475e+06 -6.14514050e+06 -13922853. -2.00655156e+04 -1.36336973e+04 -9.78537988e+03 -7.83336621e+03 -6.96088770e+03 -6.83350195e+03 -6.98257617e+03 -6.82703857e+03 -6.82531055e+03 -6.83629639e+03 -6.85347656e+03 -6.91509570e+03 -6.88756250e+03 -6.79908203e+03 -6.64035010e+03 -6.81308789e+03 -6.85495508e+03 -6.79468018e+03 -6.80094531e+03 -6.62067041e+03 -6.62057031e+03 -6.91526904e+03 -6.75507959e+03 -6.61139258e+03 -6.51552002e+03 -6.63999023e+03 -6.89208350e+03 -6.91693799e+03 -6.71252344e+03 -6.42754688e+03 -6.44655762e+03 -6.69244482e+03 -6.67908545e+03 -6.65618555e+03 -6542. -6.56462988e+03 -6.64919824e+03 -6.62889209e+03 -6.60461035e+03 -6.35639551e+03 -6.44359277e+03 -6.80331006e+03 -6.51250684e+03 -6.30848926e+03 -6.36163721e+03 -6.31703418e+03 -6.52496924e+03 -6.54875732e+03 -6.34418896e+03 -6.19530420e+03 -6.35996533e+03 -6.46950391e+03 -6.33804883e+03 -6.24299414e+03 -6.14464697e+03 -6.25683057e+03 -6.37356885e+03 -6.18902246e+03 -6.18115479e+03 -6.09766748e+03 -6.02502637e+03 -6.20932227e+03 -6.25371484e+03 -6.10329492e+03 -5.98372607e+03 -6.03750244e+03 -6.05874219e+03 -6.02914111e+03 -6.04043457e+03 -5.82121240e+03 -5.84055762e+03 -6.06840039e+03 -5.91522363e+03 -5.67490771e+03 -5.64972656e+03 -5.82005713e+03 -6.01136816e+03 -5.84645215e+03 -5.72238867e+03 -5.62441943e+03 -5.51964209e+03 -5.61053271e+03 -5.74377100e+03 -5.62884863e+03 -5.45959180e+03 -5.51951514e+03 -5.53024219e+03 -5.51013232e+03 -5.57477295e+03 -5.34372607e+03 -5.27332471e+03 -5.52476660e+03 -5.38453320e+03 -5.25140625e+03 -5.20931445e+03 -5.10642725e+03 -5.29028223e+03 -5.30199512e+03 -5.08711133e+03 -5.04279980e+03 -5.10508691e+03 -5.14200781e+03 -5.04389453e+03 -5.01040479e+03 -4.91516406e+03 -4.87312500e+03 -4.98884521e+03 -4.88475586e+03 -4.73824414e+03 -4.66380957e+03 -4.70688477e+03 -4.85413232e+03 -4.79501123e+03 -4.67358008e+03 -4.50613135e+03 -4.45213135e+03 -4.62856250e+03 -4.59742969e+03 -4.43530518e+03 -4.34657227e+03 -4.36818994e+03 -4.43780420e+03 -4.34304053e+03 -4.24349805e+03 -4.15356885e+03 -4.20690186e+03 -4.32333691e+03 -4.13895264e+03 -4.05982642e+03 -4.06665283e+03 -3.97490405e+03 -4.00960547e+03 -3.99312280e+03 -3.89167847e+03 -3.78571045e+03 -3.78211621e+03 -3.87643457e+03 -3.83593237e+03 -3.73111182e+03 -3.59167407e+03 -3.55160571e+03 -3.65649292e+03 -3.62191382e+03 -3.52076270e+03 -3.39245044e+03 -3.31187402e+03 -3.38754199e+03 -3.41745093e+03 -3.32581738e+03 -3.21529395e+03 -3.17566235e+03 -3.15628760e+03 -3.14405591e+03 -3.14864697e+03 -3.03749609e+03 -2.96787671e+03 -2.99123730e+03 -2.92454932e+03 -2.85606055e+03 -2.80256201e+03 -2.79324512e+03 -2.76140405e+03 -2.66940869e+03 -2.62843506e+03 -2.56857422e+03 -2.56527026e+03 -2.61084009e+03 -2.50502881e+03 -2.37926685e+03 -2.32310645e+03 -2.31767505e+03 -2.33802490e+03 -2.31657788e+03 -2.25525586e+03 -2.12369824e+03 -2.02961816e+03 -2.05249609e+03 -2.07704980e+03 -2.02704565e+03 -1.89536938e+03 -1.83994629e+03 -1.84912134e+03 -1.81492273e+03 -1.77649377e+03 -1.69528577e+03 -1.64415820e+03 -1.62384167e+03 -1.55593713e+03 -1.50715076e+03 -1.46425317e+03 -1.41692175e+03 -1.39452039e+03 -1.33193945e+03 -1.27572095e+03 -1.22399902e+03 -1.18349390e+03 -1.15753125e+03 -1.09559961e+03 -1.03405859e+03 -9.83090942e+02 -9.69995178e+02 -9.37192688e+02 -8.59296021e+02 -8.02890320e+02 -7.43244568e+02 -7.04082397e+02 -6.87477783e+02 -6.37136047e+02 -5.79035339e+02 -5.11591187e+02 -4.62097107e+02 -4.43272675e+02 -3.98530426e+02 -3.34769165e+02 -2.86309937e+02 -2.42898468e+02 -1.93287506e+02 -1.41469208e+02 -8.96045380e+01 -4.15300751e+01 5.95234632e+00 5.27398491e+01 1.02338821e+02 1.44784592e+02 1.82719971e+02 2.36161774e+02 2.91838867e+02 3.38792755e+02 3.87733734e+02 4.29058105e+02 4.88889038e+02 5.36393372e+02 5.56080627e+02 5.95519897e+02 6.54855591e+02 7.34104919e+02 8.10647339e+02 8.38447754e+02 8.38683350e+02 8.59949951e+02 9.25156128e+02 1.02674976e+03 1.11029089e+03 1.13506738e+03 1.10769556e+03 1.14326404e+03 1.27988159e+03 1.32581226e+03 1.31051001e+03 1.35083435e+03 1.40498621e+03 1.45899878e+03 1.55758374e+03 1.57662061e+03 1.56230530e+03 1.65289771e+03 1.67320215e+03 1.75064868e+03 1.83830103e+03 1.80014014e+03 1.88064844e+03 1.97944446e+03 1.98234497e+03 2.02108423e+03 2.07361572e+03 2.12918604e+03 2.17861768e+03 2.19816260e+03 2.19480688e+03 2.24115698e+03 2.39266553e+03 2.51509253e+03 2.49953906e+03 2.41956372e+03 2.40586792e+03 2.50973975e+03 2.66605566e+03 2.78325244e+03 2.76628345e+03 2.66746729e+03 2.72289990e+03 2.85324683e+03 2.88742578e+03 2.89774854e+03 2.93999097e+03 2.99242798e+03 3.04724658e+03 3.17894800e+03 3.13925391e+03 3.11137598e+03 3.22115161e+03 3.16929492e+03 3.29539966e+03 3.43746094e+03 3.36022705e+03 3.49541675e+03 3.49545312e+03 3.38957715e+03 3.54432837e+03 3.50073535e+03 3.58327979e+03 3.88865088e+03 3.75207983e+03 3.56303442e+03 3.67672119e+03 3.91005664e+03 4.09940430e+03 4.02786206e+03 3.86927783e+03 3.82639868e+03 3.94007910e+03 4.10753027e+03 4.28260205e+03 4.26334131e+03 4.07846240e+03 4.08969727e+03 4.23717285e+03 4.34203809e+03 4.31430469e+03 4.31774609e+03 4.39618262e+03 4.42727930e+03 4.62701611e+03 4.64380957e+03 4.41276465e+03 4.42524463e+03 4.61874707e+03 4.68089209e+03 4.72110596e+03 4.73008496e+03 4.86645459e+03 4.80700830e+03 4.67968652e+03 4.84229980e+03 4.74455225e+03 4.91266602e+03 5.26641553e+03 4.97968604e+03 4.75038477e+03 4.93281494e+03 5.20124658e+03 5.37873389e+03 5.36114697e+03 5.09374463e+03 4.94259424e+03 5.11116406e+03 5.37703125e+03 5.57167725e+03 5.47772461e+03 5.21785498e+03 5.22524219e+03 5.45143262e+03 5.50294727e+03 5.59919189e+03 5.64837402e+03 5.39915186e+03 5.40852344e+03 5.72591943e+03 5.77854980e+03 5.54023438e+03 5.55341016e+03 5.70674609e+03 5.67640918e+03 5.91516699e+03 5.98507080e+03 5.76207178e+03 5.74686084e+03 5.77402832e+03 5.80329785e+03 5.89996826e+03 5.90792529e+03 6.09816650e+03 6.20007324e+03 6.01507520e+03 5.84484570e+03 5.74301611e+03 6.05604883e+03 6.39505566e+03 6.30240186e+03 6.02082910e+03 5.83543506e+03 6.11638184e+03 6.48543848e+03 6.28632129e+03 5.93367725e+03 6.09288721e+03 6.30975635e+03 6.45705713e+03 6.63933105e+03 6.52816699e+03 6.13187402e+03 6.12911377e+03 6.35975977e+03 6.43736279e+03 6.46982471e+03 6.45285889e+03 6.50185547e+03 6.44594092e+03 6.56490820e+03 6.54263818e+03 6.39731055e+03 6.41985205e+03 6.38662451e+03 6.62338574e+03 6.73292432e+03 6.57255273e+03 6.63866064e+03 6.67586328e+03 6.65788867e+03 6.52526611e+03 6.39908496e+03 6.66420508e+03 6.99154297e+03 6.84776611e+03 6.51975977e+03 6.48570947e+03 6.79019385e+03 6.94351465e+03 6.82390918e+03 6.74769482e+03 6.55047607e+03 6.57530518e+03 6.85302490e+03 6.86186133e+03 6.69114062e+03 6.55774951e+03 6.52654443e+03 6.89721875e+03 7.20332959e+03 6.80758350e+03 6.62266211e+03 6.80540234e+03 6.83431348e+03 7.04683008e+03 7.01021777e+03 6.59762939e+03 6.68185791e+03 6.89345801e+03 6.86779932e+03 6.89898438e+03 6.96785791e+03 6.73526611e+03 7.20099268e+03 7.27347852e+03 6.69390479e+03 8.52317383e+03 9.11187598e+03 1.09429941e+04 1.06131855e+04 1.01484854e+04 1.04615938e+04 1.03239414e+04 1.08707217e+04 1.14286650e+04 1.06556650e+04 1.84976406e+04 2.84773809e+04 17449876. 34538408. 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. 0. -249400496. -249400496. -249400496. 0. 0. 3318850. 4221781. 2.21180575e+06 2.52339075e+06 -11740239. 4.62016750e+06 2.84509275e+06 1.65851914e+04 1.32200254e+04 7.50664404e+03 6.85979248e+03 6.37655225e+03 6.15638672e+03 6.39952783e+03 6.41092188e+03 6.17728369e+03 6.17980957e+03 6.20985498e+03 6.13868164e+03 6.10939600e+03 6.07878125e+03 5.99291748e+03 6.03381152e+03 6.02416406e+03 6.01991797e+03 6.02092090e+03 5.79094141e+03 5.80665479e+03 6.04706738e+03 6.01439014e+03 5.89411426e+03 5.83882031e+03 5.81372461e+03 5.80734326e+03 5.75299609e+03 5.74033398e+03 5.69686182e+03 5.64206494e+03 5.56493945e+03 5.54403223e+03 5.67585498e+03 5.65747461e+03 5.52350488e+03 5.48615723e+03 5.50315576e+03 5.50018701e+03 5.42346582e+03 5.38643945e+03 5.36628467e+03 5.26433936e+03 5.22534766e+03 5.17065967e+03 5.13825391e+03 5.37381348e+03 5.36739551e+03 5.14861084e+03 4.97731592e+03 4.91389844e+03 5.17866992e+03 5.19441357e+03 4.99429102e+03 4.84273975e+03 4.81344580e+03 4.85126221e+03 4.80960303e+03 4.97069678e+03 4.92250830e+03 4.58873340e+03 4.48748584e+03 4.68892676e+03 4.90393213e+03 4.74795361e+03 4.58884326e+03 4.53973291e+03 4.47877197e+03 4.46975049e+03 4.46110742e+03 4.37304248e+03 4.29414355e+03 4.28765430e+03 4.25209131e+03 4.22015771e+03 4.17574658e+03 4.26469434e+03 4.22388574e+03 4.06504004e+03 4.00555591e+03 3.97786108e+03 4.05992236e+03 4.03416187e+03 3.90604785e+03 3.87223145e+03 3.73944287e+03 3.62257861e+03 3.76310840e+03 3.76787891e+03 3.53323706e+03 3.51811938e+03 3.67868701e+03 3.73763306e+03 3.59412720e+03 3.45211279e+03 3.39965039e+03 3.37736548e+03 3.30666870e+03 3.24345312e+03 3.23168140e+03 3.18718921e+03 3.24585693e+03 3.18559619e+03 3.06601074e+03 3.01864526e+03 2.89691333e+03 2.92311743e+03 3.05017139e+03 2.95459131e+03 2.83401709e+03 2.71692749e+03 2.63575903e+03 2.74626074e+03 2.75993994e+03 2.62706079e+03 2.49603247e+03 2.44911353e+03 2.46150293e+03 2.41431323e+03 2.45135205e+03 2.42701465e+03 2.29079468e+03 2.19683765e+03 2.15909521e+03 2.20332886e+03 2.16319971e+03 2.07050415e+03 2.00677466e+03 1.95438269e+03 1.90597510e+03 1.81392285e+03 1.81909985e+03 1.87751428e+03 1.79005200e+03 1.70254346e+03 1.61698132e+03 1.55777380e+03 1.60420520e+03 1.56197412e+03 1.46842847e+03 1.38630396e+03 1.33706470e+03 1.33249146e+03 1.27949243e+03 1.23401331e+03 1.15727832e+03 1.12869824e+03 1.14006189e+03 1.06386157e+03 1.00114960e+03 9.62293823e+02 9.08401428e+02 8.44824280e+02 7.98171936e+02 7.52658203e+02 7.04118469e+02 6.61285278e+02 5.98666809e+02 5.66423767e+02 5.50578918e+02 4.77656158e+02 4.15432739e+02 3.78085449e+02 3.30413910e+02 2.91213470e+02 2.39398911e+02 1.83519882e+02 1.42071716e+02 9.54900818e+01 4.73031349e+01 -4.42062646e-01 -4.81394844e+01 -9.57441788e+01 -1.44632355e+02 -1.91636871e+02 -2.32462738e+02 -2.87302277e+02 -3.54778748e+02 -3.95645935e+02 -4.28519196e+02 -4.63205688e+02 -5.17550842e+02 -5.97095642e+02 -6.40822937e+02 -6.72544922e+02 -7.01069641e+02 -7.39592407e+02 -8.14042297e+02 -8.62938049e+02 -9.25659912e+02 -9.66967407e+02 -9.86901306e+02 -1.04184338e+03 -1.08758716e+03 -1.17506946e+03 -1.22700378e+03 -1.23466321e+03 -1.27341382e+03 -1.32459448e+03 -1.37298535e+03 -1.37774939e+03 -1.45529944e+03 -1.58309924e+03 -1.60127136e+03 -1.60997498e+03 -1.61506921e+03 -1.65157910e+03 -1.79278394e+03 -1.84414026e+03 -1.84419849e+03 -1.84852368e+03 -1.87886365e+03 -1.98568542e+03 -2.02782361e+03 -2.11659570e+03 -2.15165649e+03 -2.13885669e+03 -2.16558594e+03 -2.20495532e+03 -2.35534766e+03 -2.40561694e+03 -2.38862183e+03 -2.39387622e+03 -2.42528613e+03 -2.56937646e+03 -2.62230273e+03 -2.53456934e+03 -2.58626611e+03 -2.78130664e+03 -2.80888184e+03 -2.71550977e+03 -2.74450952e+03 -2.93480835e+03 -3.00758789e+03 -2.94034644e+03 -2.90421289e+03 -2.96344141e+03 -3.17998193e+03 -3.19860229e+03 -3.15293701e+03 -3.21493091e+03 -3.24208496e+03 -3.23292969e+03 -3.26441064e+03 -3.39500928e+03 -3.34451416e+03 -3.44701099e+03 -3.65598218e+03 -3.59173071e+03 -3.64570435e+03 -3.69301050e+03 -3.66900928e+03 -3.71452954e+03 -3.75314087e+03 -3.78042065e+03 -3.72413062e+03 -3.72525684e+03 -3.86069287e+03 -3.96588354e+03 -4.12535449e+03 -4.02512549e+03 -3.95506396e+03 -4.12038916e+03 -4.14600391e+03 -4.29975244e+03 -4.31811621e+03 -4.23723340e+03 -4.20915381e+03 -4.21597852e+03 -4.36094971e+03 -4.40253223e+03 -4.52805029e+03 -4.57632471e+03 -4.50063477e+03 -4.49789746e+03 -4.42504150e+03 -4.58291992e+03 -4.85250537e+03 -4.82845264e+03 -4.71440088e+03 -4.64133301e+03 -4.64329736e+03 -4.91667676e+03 -5.03036475e+03 -4.90787988e+03 -4.79381055e+03 -4.84002344e+03 -5.00724365e+03 -5.01236426e+03 -5.16837695e+03 -5.17375830e+03 -5.08169727e+03 -5.12536328e+03 -5.12895361e+03 -5.30517334e+03 -5.35705469e+03 -5.13254297e+03 -5.15539014e+03 -5.48896289e+03 -5.41979980e+03 -5.15314209e+03 -5.35361572e+03 -5.66001318e+03 -5.63093701e+03 -5.52226562e+03 -5.38379980e+03 -5.42356006e+03 -5.77004443e+03 -5.77179199e+03 -5.64864551e+03 -5.54099170e+03 -5.52643311e+03 -5.70871582e+03 -5.74855615e+03 -5.80475293e+03 -5.66478564e+03 -5.79962695e+03 -6.09661768e+03 -5.98513135e+03 -5.97960889e+03 -5.94893848e+03 -5.90496533e+03 -5.95974707e+03 -5.99937842e+03 -6.05272168e+03 -6.04519482e+03 -6.04164111e+03 -5.92006055e+03 -6.01714648e+03 -6.36186426e+03 -6.09033691e+03 -5.93105957e+03 -6.14151953e+03 -6.29788672e+03 -6.50987988e+03 -6.42021289e+03 -6.27588477e+03 -6.34599023e+03 -6.30472314e+03 -6.21771094e+03 -6.19775000e+03 -6.49694482e+03 -6.44017188e+03 -6.31816602e+03 -6.33892432e+03 -6.18207959e+03 -6.40498291e+03 -6.79874072e+03 -6.61959180e+03 -6.46851807e+03 -6.31801270e+03 -6.32132275e+03 -6.70310645e+03 -6.84650781e+03 -6.61530615e+03 -6.45287891e+03 -6.43494141e+03 -6.54247217e+03 -6.59010107e+03 -6.82793359e+03 -6.75658545e+03 -6.58917676e+03 -6.60706836e+03 -6.61826807e+03 -6.76019727e+03 -6.75254980e+03 -6.65894336e+03 -6.74589209e+03 -6.75227441e+03 -6.65208838e+03 -6.48807373e+03 -6.65038672e+03 -7.01363232e+03 -6.89319482e+03 -6.73730225e+03 -6.61586475e+03 -6.63614746e+03 -7.05604883e+03 -7.00919824e+03 -6.78427637e+03 -6.68535352e+03 -6.66201709e+03 -6.72823047e+03 -6.74395068e+03 -6.85146875e+03 -6.65998145e+03 -6.79245850e+03 -7.04996191e+03 -6.87107617e+03 -6.93176367e+03 -6.92597607e+03 -6.83523682e+03 -6.89727441e+03 -6.86840332e+03 -6.68934473e+03 -6.70251953e+03 -6.91948975e+03 -6.90570020e+03 -6.91767139e+03 -6.88059033e+03 -6.65719385e+03 -6.60931641e+03 -6.83512451e+03 -6.85847266e+03 -7.03560840e+03 -6.94176172e+03 -6.65790723e+03 -6.84254053e+03 -6.92389844e+03 -6.83193848e+03 -6.72506201e+03 -6.69934180e+03 -6.79842188e+03 -6.76648584e+03 -6.78122363e+03 -6.61175098e+03 -6.75390234e+03 -7.07482227e+03 -6.93850732e+03 -6.74224170e+03 -6.54229492e+03 -6.52824854e+03 -6.92109326e+03 -6.88835254e+03 -6.71200146e+03 -6.51726270e+03 -6.40393994e+03 -6.62249365e+03 -6.75069043e+03 -6.93978076e+03 -6.68281250e+03 -6.41214746e+03 -6.51168066e+03 -6.60422949e+03 -6.80602246e+03 -6.63897070e+03 -6.41360889e+03 -6.56919873e+03 -6.57049365e+03 -6.49492236e+03 -6.33368066e+03 -6.42833789e+03 -6.76469141e+03 -6.67360498e+03 -6.42704199e+03 -6.21980322e+03 -6.26198828e+03 -6.61716309e+03 -6.57595752e+03 -6.37850635e+03 -6.20546924e+03 -6.14105664e+03 -6.31874951e+03 -6.29924121e+03 -6.45346094e+03 -6.42162012e+03 -6.15886816e+03 -6.01749609e+03 -6.09608447e+03 -6.40747998e+03 -6.24455322e+03 -6.04946094e+03 -6.18362451e+03 -6.14284521e+03 -5.96218604e+03 -5.85063574e+03 -6.02607471e+03 -5.98782373e+03 -5.85258154e+03 -6.09972803e+03 -6.11234131e+03 -5.94740332e+03 -5.88102197e+03 -5.83881689e+03 -5.83115186e+03 -5.66637891e+03 -5.57315381e+03 -5.82995605e+03 -5.90530371e+03 -5.59421924e+03 -5.42084814e+03 -5.64455957e+03 -5.83460938e+03 -5.74053516e+03 -5.52920215e+03 -5.38213281e+03 -5.52983838e+03 -5.64111328e+03 -5.51539844e+03 -5.43300293e+03 -5.24867676e+03 -5.11442236e+03 -5.33214502e+03 -5.54885596e+03 -5.40851904e+03 -5.12666699e+03 -5.04158252e+03 -5.29192871e+03 -5.34423584e+03 -5.13294775e+03 -4.97624463e+03 -4.90075830e+03 -4.92173242e+03 -4.94881396e+03 -5.08342285e+03 -5.06758594e+03 -4.84223730e+03 -4.78827783e+03 -4.78563721e+03 -4.87988232e+03 -4.73228564e+03 -4.58593262e+03 -4.77442578e+03 -4.75983691e+03 -4.56466309e+03 -4.41783887e+03 -4.47452539e+03 -4.68221484e+03 -4.47874609e+03 -4.27652930e+03 -4.35196533e+03 -4.39017041e+03 -4.37206055e+03 -4.28315186e+03 -4.35571240e+03 -4.34700635e+03 -4.16922998e+03 -4.00842383e+03 -3.98585620e+03 -4.16858154e+03 -4.07214526e+03 -3.91587891e+03 -3.93244702e+03 -3.91041309e+03 -3.86303882e+03 -3.78903003e+03 -3.80582202e+03 -3.74828760e+03 -3.63710645e+03 -3.68796997e+03 -3.65326709e+03 -3.64572339e+03 -3.60503198e+03 -3.50230225e+03 -3.43577319e+03 -3.30321118e+03 -3.28395337e+03 -3.42729980e+03 -3.43581055e+03 -3.21359668e+03 -3.07478149e+03 -3.14422437e+03 -3.22712842e+03 -3.16422876e+03 -3.00922266e+03 -2.87481763e+03 -2.95952051e+03 -2.99565674e+03 -2.86894873e+03 -2.88277905e+03 -2.81082886e+03 -2.65611060e+03 -2.67100391e+03 -2.72673877e+03 -2.65536597e+03 -2.49560010e+03 -2.41974146e+03 -2.51131616e+03 -2.52295239e+03 -2.39696240e+03 -2.26338110e+03 -2.21121606e+03 -2.29790747e+03 -2.24260278e+03 -2.12916309e+03 -2.12000635e+03 -2.07047192e+03 -2.00218042e+03 -1.94839441e+03 -1.97707422e+03 -1.89555359e+03 -1.78181909e+03 -1.82554980e+03 -1.78748474e+03 -1.71696216e+03 -1.63594885e+03 -1.56328247e+03 -1.59604126e+03 -1.52141284e+03 -1.41267188e+03 -1.41640356e+03 -1.44006604e+03 -1.37579138e+03 -1.21950659e+03 -1.28015210e+03 -1.32893250e+03 -1.14610254e+03 -1.08186597e+03 -9.67339722e+02 -1.01838519e+03 -1.27411365e+03 -9.38010376e+02 -8.74695557e+02 -1.01579028e+03 -1.32305225e+03 -5.27330762e+03 -115786944. 0. 0. 0. 0. 0. 0. -219605696. -219605696. -1.33163477e+03 -3.50749146e+03 -3.50749146e+03 833382336. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 273463104. 7.61380811e+03 1.73774585e+03 1.03364136e+03 1.17995288e+03 1.13745203e+03 1.02586218e+03 1.06075854e+03 1.10947278e+03 1.15443555e+03 1.17840491e+03 1.22895850e+03 1.30020068e+03 1.33719031e+03 1.37540649e+03 1.40810095e+03 1.45303235e+03 1.54066101e+03 1.58132788e+03 1.59821228e+03 1.64389990e+03 1.67781628e+03 1.73893103e+03 1.83992346e+03 1.89394873e+03 1.87552905e+03 1.89817407e+03 1.97587524e+03 2.03316223e+03 2.05871680e+03 2.09310767e+03 2.16282642e+03 2.20571362e+03 2.27769971e+03 2.31754468e+03 2.28001709e+03 2.35344043e+03 2.47849097e+03 2.54685815e+03 2.56991797e+03 2.50842554e+03 2.53051245e+03 2.67628687e+03 2.73268726e+03 2.72905859e+03 2.75531421e+03 2.80101587e+03 2.89911963e+03 2.98381519e+03 2.97765161e+03 2.91998877e+03 2.97105859e+03 3.17804321e+03 3.21908154e+03 3.10961548e+03 3.14077051e+03 3.26019897e+03 3.33379932e+03 3.41547241e+03 3.39345728e+03 3.33984131e+03 3.41121533e+03 3.52482007e+03 3.59391406e+03 3.60592139e+03 3.55538037e+03 3.64963623e+03 3.77442041e+03 3.77686060e+03 3.77383618e+03 3.76475317e+03 3.83187256e+03 3.95026587e+03 3.99790063e+03 4.03941284e+03 4.00851343e+03 3.95953955e+03 4.09377173e+03 4.17324756e+03 4.17936572e+03 4.22255420e+03 4.21141260e+03 4.28039941e+03 4.41774609e+03 4.42146680e+03 4.30225928e+03 4.34337158e+03 4.50848291e+03 4.58477002e+03 4.57530469e+03 4.52065186e+03 4.58711133e+03 4.65444043e+03 4.72862012e+03 4.74316455e+03 4.65803369e+03 4.77148145e+03 4.90843652e+03 4.92634521e+03 4.93226367e+03 4.84938184e+03 4.87530273e+03 5.05717041e+03 5.06439795e+03 4.97298047e+03 4.99728076e+03 5.08031348e+03 5.20864160e+03 5.24058691e+03 5.21749805e+03 5.24171680e+03 5.26738232e+03 5.38003174e+03 5.39788428e+03 5.30812451e+03 5.37197900e+03 5.43457520e+03 5.39797900e+03 5.48978516e+03 5.55344287e+03 5.53707568e+03 5.56043652e+03 5.56741113e+03 5.59346289e+03 5.69530176e+03 5.72492334e+03 5.71510693e+03 5.72507861e+03 5.67906787e+03 5.72838232e+03 5.86831641e+03 5.82569385e+03 5.78397949e+03 5.89737695e+03 6.06286914e+03 6.02764111e+03 5.90107227e+03 5.96340186e+03 6.04898877e+03 5.97534229e+03 5.95141455e+03 5.99545850e+03 6.01913232e+03 6.15392090e+03 6.25859668e+03 6.20879736e+03 6.14047510e+03 6.09425781e+03 6.19815576e+03 6.31184424e+03 6.30320654e+03 6.27444531e+03 6.22903027e+03 6.31867285e+03 6.43622949e+03 6.40768311e+03 6.29348193e+03 6.20664258e+03 6.35238037e+03 6.54192969e+03 6.50337598e+03 6.24487256e+03 6.32400146e+03 6.55529883e+03 6.54505176e+03 6.46264258e+03 6.49609424e+03 6.53163379e+03 6.50764111e+03 6.61360498e+03 6.57724658e+03 6.46993994e+03 6.62389404e+03 6.72073193e+03 6.62839062e+03 6.68691602e+03 6.65256689e+03 6.55058057e+03 6.59946240e+03 6.67057861e+03 6.75500537e+03 6.84592334e+03 6.59377393e+03 6.58516797e+03 6.85241553e+03 6.73316211e+03 6.58243652e+03 6.69149512e+03 6.78123193e+03 6.83446338e+03 6.82192773e+03 6.76626318e+03 6.70362500e+03 6.68707910e+03 6.85872900e+03 6.91303076e+03 6.71872412e+03 6.77676221e+03 6.97597070e+03 6.86994531e+03 6.86364160e+03 6.76319385e+03 6.68534961e+03 6.88969092e+03 6.83389746e+03 6.79312451e+03 6.88282764e+03 6.74990527e+03 6.81378223e+03 7.02105273e+03 6.81295410e+03 6.77981006e+03 6.84351855e+03 6.86199072e+03 6.82611475e+03 6.84250928e+03 6.80554053e+03 6.79457812e+03 6.77780273e+03 6.85343506e+03 6.83000195e+03 6.73449512e+03 6.82184521e+03 6.93636963e+03 6.80555615e+03 6.93830273e+03 6.85530566e+03 6.60552490e+03 6.76800049e+03 6.82818408e+03 6.78195117e+03 6.67616016e+03 6.57212695e+03 6.79341211e+03 6.94497803e+03 6.73515576e+03 6.62437207e+03 6.77993164e+03 6.86009424e+03 6.67464697e+03 6.54385303e+03 6.74693018e+03 6.70586426e+03 6.58793311e+03 6.77434082e+03 6.63571045e+03 6.56045361e+03 6.62425244e+03 6.56207471e+03 6.56112158e+03 6.61849414e+03 6.50349463e+03 6.49793408e+03 6.57059131e+03 6.62469238e+03 6.60696924e+03 6.38131396e+03 6.36056445e+03 6.53268896e+03 6.43837158e+03 6.46824805e+03 6.42427686e+03 6.35689990e+03 6.36210303e+03 6.37358887e+03 6.45943164e+03 6.33073682e+03 6.10293311e+03 6.26625684e+03 6.49821094e+03 6.22370117e+03 6.05866699e+03 6.15092676e+03 6.11915820e+03 6.19644189e+03 6.25210449e+03 6.06850928e+03 6.06393066e+03 6.09464795e+03 6.06272998e+03 6.10048682e+03 6.03074072e+03 6.05700439e+03 6.07084717e+03 5.79935742e+03 5.87794287e+03 5.92932812e+03 5.79259180e+03 5.93647754e+03 5.83947803e+03 5.72805762e+03 5.78756689e+03 5.69455566e+03 5.71917334e+03 5.86057910e+03 5.72075391e+03 5.61175439e+03 5.55731250e+03 5.47897119e+03 5.57736182e+03 5.62282422e+03 5.49271826e+03 5.42789746e+03 5.51613672e+03 5.49045850e+03 5.41645459e+03 5.30053809e+03 5.28916943e+03 5.32713037e+03 5.30833936e+03 5.28687744e+03 5.13921289e+03 5.10613672e+03 5.16877686e+03 5.19581055e+03 5.13254639e+03 5.07408838e+03 4.98632373e+03 4.89833252e+03 5.09091943e+03 5.10079639e+03 4.84524805e+03 4.73502246e+03 4.75527490e+03 4.77662988e+03 4.75853223e+03 4.68343701e+03 4.67526758e+03 4.69916064e+03 4.64417529e+03 4.61858887e+03 4.55166406e+03 4.48405518e+03 4.50187695e+03 4.49533008e+03 4.40951904e+03 4.28530957e+03 4.29839648e+03 4.27959961e+03 4.24465918e+03 4.26739502e+03 4.18040674e+03 4.08927612e+03 4.08984155e+03 4.14230908e+03 4.05867993e+03 3.95038940e+03 3.92669702e+03 3.90535474e+03 3.85883252e+03 3.82304297e+03 3.74832153e+03 3.71480493e+03 3.72025415e+03 3.71083008e+03 3.68986377e+03 3.57495996e+03 3.53842969e+03 3.51120874e+03 3.43222998e+03 3.39203564e+03 3.33734570e+03 3.36160571e+03 3.31658667e+03 3.22731665e+03 3.16356421e+03 3.13073462e+03 3.15406641e+03 3.13999658e+03 3.10800220e+03 3.00641040e+03 2.93982690e+03 2.89990894e+03 2.81079468e+03 2.79509570e+03 2.79872266e+03 2.74489844e+03 2.68573535e+03 2.60335840e+03 2.56969263e+03 2.57829077e+03 2.57307690e+03 2.51751978e+03 2.41751904e+03 2.34324487e+03 2.32699976e+03 2.29702344e+03 2.22563550e+03 2.20832593e+03 2.19610132e+03 2.09766602e+03 2.02945056e+03 1.98801440e+03 1.95606921e+03 1.97622791e+03 1.92501917e+03 1.82142480e+03 1.79427417e+03 1.73844788e+03 1.66046326e+03 1.66372949e+03 1.62455396e+03 1.54052783e+03 1.49293958e+03 1.44456506e+03 1.38559937e+03 1.37432922e+03 1.37178540e+03 1.29081799e+03 1.22207275e+03 1.18425354e+03 1.13087634e+03 1.08733911e+03 1.04057581e+03 9.97143982e+02 9.44844666e+02 8.89204651e+02 8.53120544e+02 8.12848633e+02 7.52494507e+02 7.16339478e+02 6.79328125e+02 6.12288635e+02 5.55576111e+02 5.13660156e+02 4.76970306e+02 4.33119934e+02 3.84689789e+02 3.27578735e+02 2.73324036e+02 2.33543411e+02 1.94645462e+02 1.48904694e+02 9.53211746e+01 4.46961250e+01 -5.94789934e+00 -5.42728119e+01 -9.97399216e+01 -1.42958466e+02 -1.88140320e+02 -2.36626068e+02 -2.93176727e+02 -3.39219208e+02 -3.73893219e+02 -4.31667053e+02 -4.97633209e+02 -5.34272522e+02 -5.68068298e+02 -6.17444275e+02 -6.70715820e+02 -7.24717773e+02 -7.71995361e+02 -8.15747009e+02 -8.47606812e+02 -8.96147400e+02 -9.55144531e+02 -1.00260431e+03 -1.06954834e+03 -1.10202417e+03 -1.13616907e+03 -1.18639038e+03 -1.24191992e+03 -1.29653894e+03 -1.32697607e+03 -1.38866052e+03 -1.44672632e+03 -1.47186938e+03 -1.49014868e+03 -1.53534326e+03 -1.60185583e+03 -1.69327002e+03 -1.73991907e+03 -1.73376257e+03 -1.76950256e+03 -1.81889026e+03 -1.89421265e+03 -1.97236157e+03 -1.98018970e+03 -1.99200073e+03 -2.10062817e+03 -2.13751880e+03 -2.11916309e+03 -2.24130371e+03 -2.30080786e+03 -2.27366040e+03 -2.33964917e+03 -2.34501123e+03 -2.38250317e+03 -2.53141333e+03 -2.55860791e+03 -2.54892969e+03 -2.63478223e+03 -2.66973901e+03 -2.62730469e+03 -2.69070264e+03 -2.79611719e+03 -2.83898608e+03 -2.90252539e+03 -2.89316650e+03 -2.91442822e+03 -3.01411353e+03 -3.07285864e+03 -3.19411328e+03 -3.16831567e+03 -3.07477808e+03 -3.16278149e+03 -3.26221558e+03 -3.31276392e+03 -3.38547119e+03 -3.37574609e+03 -3.34316382e+03 -3.46949072e+03 -3.56401196e+03 -3.53744043e+03 -3.58433618e+03 -3.64224951e+03 -3.60716992e+03 -3.71893457e+03 -3.79080249e+03 -3.73814014e+03 -3.89251392e+03 -3.96180127e+03 -3.90506616e+03 -3.93150098e+03 -3.86298584e+03 -3.91661938e+03 -4.09846387e+03 -4.26080176e+03 -4.22460449e+03 -4.03858398e+03 -4.12590625e+03 -4.29906885e+03 -4.31002051e+03 -4.31739697e+03 -4.35098535e+03 -4.36817236e+03 -4.46429150e+03 -4.49758643e+03 -4.52738281e+03 -4.54612061e+03 -4.58205469e+03 -4.70274219e+03 -4.64996777e+03 -4.60298730e+03 -4.65915283e+03 -4.73201318e+03 -4.82478857e+03 -4.94625244e+03 -4.87914893e+03 -4.77597266e+03 -4.88265088e+03 -4.98541699e+03 -5.12819580e+03 -5.11510400e+03 -4.96420068e+03 -5.02226514e+03 -5.11749023e+03 -5.21282422e+03 -5.32377393e+03 -5.25554395e+03 -5.17148779e+03 -5.25012793e+03 -5.23963330e+03 -5.21229834e+03 -5.41180762e+03 -5.53810107e+03 -5.46945361e+03 -5.39690283e+03 -5.37955273e+03 -5.42217676e+03 -5.64918262e+03 -5.69501660e+03 -5.63818945e+03 -5.58903906e+03 -5.49838428e+03 -5.58907324e+03 -5.71385742e+03 -5.86262842e+03 -5.86171680e+03 -5.68511670e+03 -5.72856055e+03 -5.77638281e+03 -5.85001855e+03 -5.92218164e+03 -5.95709082e+03 -6.01346826e+03 -5.90010938e+03 -5.92647510e+03 -6.00346387e+03 -6.00353809e+03 -6.05053809e+03 -6.11749072e+03 -6.11958643e+03 -6.10505420e+03 -6.06587256e+03 -6.15043359e+03 -6.28955371e+03 -6.26592383e+03 -6.13674219e+03 -6.17473047e+03 -6.21470020e+03 -6.22997461e+03 -6.44089160e+03 -6.42194189e+03 -6.28389893e+03 -6.39107178e+03 -6.32084766e+03 -6.35431299e+03 -6.55909961e+03 -6.55362939e+03 -6.49835742e+03 -6.51957666e+03 -6.23852393e+03 -6.39493506e+03 -6.60656250e+03 -6.39648877e+03 -9.22077344e+03 -8.71612207e+03 -1.91186914e+04 -2.88367031e+04 7554618. 49093276. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -13710447. 2.95389075e+06 3.39485750e+06 -3429949. -2.92355137e+04 -1.99715410e+04 -1.11983955e+04 -7.71975879e+03 -6.89574268e+03 -6.93465869e+03 -7.12446777e+03 -7.00858252e+03 -6.85033496e+03 -6.62774707e+03 -6.71542725e+03 -6.89063818e+03 -6.92417090e+03 -6.88140381e+03 -6.73862988e+03 -6.73247803e+03 -6.74350049e+03 -6.85022510e+03 -6.83003955e+03 -6.60602881e+03 -6.65535742e+03 -6.79900244e+03 -6.77643799e+03 -6.62400732e+03 -6.50321729e+03 -6.70361230e+03 -6.97838281e+03 -6.93308350e+03 -6.56932520e+03 -6.27891553e+03 -6.45490918e+03 -6.73270264e+03 -6.87722168e+03 -6.71566846e+03 -6.45574365e+03 -6.45517578e+03 -6.62527393e+03 -6.75258447e+03 -6.63211719e+03 -6.29846436e+03 -6.30688477e+03 -6.64328223e+03 -6.59636377e+03 -6.35677295e+03 -6.41091602e+03 -6.45630664e+03 -6.49567725e+03 -6.50947363e+03 -6.23232422e+03 -6.10965186e+03 -6.44299365e+03 -6.58523047e+03 -6.41108398e+03 -6.17801904e+03 -5.99524658e+03 -6.29925049e+03 -6.47928955e+03 -6.33277930e+03 -6.11078809e+03 -5.88950977e+03 -5.93455420e+03 -6.23625293e+03 -6.32190723e+03 -6.20810547e+03 -6.05991846e+03 -6.03854932e+03 -5.96691406e+03 -5.96387842e+03 -5.98736719e+03 -5.81093604e+03 -5.85735547e+03 -6.05930859e+03 -5.94521387e+03 -5.66720898e+03 -5.58770605e+03 -5.85964648e+03 -6.01763525e+03 -5.89860205e+03 -5.66417871e+03 -5.50805176e+03 -5.50603613e+03 -5.61731201e+03 -5.86060352e+03 -5.74475781e+03 -5.39743701e+03 -5.41344189e+03 -5.46911475e+03 -5.53425830e+03 -5.59212695e+03 -5.35495898e+03 -5.31097314e+03 -5.44528809e+03 -5.36426660e+03 -5.27009814e+03 -5.20272461e+03 -5.19828418e+03 -5.28429785e+03 -5.24004492e+03 -5.04007959e+03 -4.99211816e+03 -5.12178564e+03 -5.17973242e+03 -5.10724609e+03 -4.98245508e+03 -4.82746777e+03 -4.86353467e+03 -4.98252295e+03 -4.96376367e+03 -4.83169336e+03 -4.59659424e+03 -4.59668164e+03 -4.80743311e+03 -4.85602930e+03 -4.71488232e+03 -4.49727148e+03 -4.49836572e+03 -4.60670947e+03 -4.55391650e+03 -4.41447705e+03 -4.32291406e+03 -4.43428418e+03 -4.46547803e+03 -4.31285352e+03 -4.22464551e+03 -4.13854834e+03 -4.21194824e+03 -4.37381006e+03 -4.22321094e+03 -4.05154150e+03 -3.97103442e+03 -3.95696704e+03 -4.00391138e+03 -4.04104126e+03 -3.94959473e+03 -3.73747168e+03 -3.72296875e+03 -3.87221582e+03 -3.86968848e+03 -3.72125635e+03 -3.59568774e+03 -3.60965869e+03 -3.65157788e+03 -3.60137036e+03 -3.48993359e+03 -3.35058301e+03 -3.34915112e+03 -3.43078003e+03 -3.40590088e+03 -3.29889331e+03 -3.18316797e+03 -3.17254541e+03 -3.20468555e+03 -3.22529419e+03 -3.16121094e+03 -2.96598267e+03 -2.93603271e+03 -2.97805249e+03 -2.94376221e+03 -2.88780469e+03 -2.80984546e+03 -2.76389868e+03 -2.72285376e+03 -2.69094336e+03 -2.63741626e+03 -2.56699854e+03 -2.58761182e+03 -2.60116675e+03 -2.50711401e+03 -2.37499829e+03 -2.31056055e+03 -2.34796411e+03 -2.37668945e+03 -2.32455933e+03 -2.20537817e+03 -2.09049243e+03 -2.03467358e+03 -2.06653809e+03 -2.11318652e+03 -2.01458838e+03 -1.86353967e+03 -1.84810974e+03 -1.85648560e+03 -1.82163818e+03 -1.77926843e+03 -1.69274866e+03 -1.64403931e+03 -1.61298572e+03 -1.54843347e+03 -1.48983289e+03 -1.46119067e+03 -1.43712280e+03 -1.38187622e+03 -1.32785242e+03 -1.27474084e+03 -1.21848901e+03 -1.19257886e+03 -1.16791443e+03 -1.11401941e+03 -1.02507251e+03 -9.57835571e+02 -9.51350647e+02 -9.25436584e+02 -8.66003662e+02 -8.08171570e+02 -7.38168640e+02 -6.91226135e+02 -6.76944641e+02 -6.46154663e+02 -5.86625366e+02 -5.16711792e+02 -4.65464661e+02 -4.30133423e+02 -3.83018463e+02 -3.32498383e+02 -2.87982605e+02 -2.42549118e+02 -1.91195129e+02 -1.39843063e+02 -9.01027069e+01 -4.43741188e+01 1.35992455e+00 4.87838631e+01 9.95202408e+01 1.47415543e+02 1.87206055e+02 2.38884720e+02 2.92367981e+02 3.38329620e+02 3.90205414e+02 4.32485077e+02 4.89963409e+02 5.35349304e+02 5.55319946e+02 5.93222473e+02 6.53629944e+02 7.35591064e+02 8.07964111e+02 8.37924316e+02 8.36997803e+02 8.58746155e+02 9.22951050e+02 1.02728357e+03 1.11101172e+03 1.13048145e+03 1.10646045e+03 1.14370862e+03 1.28345850e+03 1.32257141e+03 1.30478296e+03 1.35517957e+03 1.41234937e+03 1.46313708e+03 1.55881531e+03 1.57122681e+03 1.55864270e+03 1.65053601e+03 1.66602100e+03 1.74892505e+03 1.84315491e+03 1.79122070e+03 1.88211243e+03 1.99245020e+03 1.98410522e+03 2.02010742e+03 2.05705640e+03 2.12724341e+03 2.18349658e+03 2.18582617e+03 2.19537524e+03 2.24833643e+03 2.39533789e+03 2.50528076e+03 2.48516846e+03 2.42183179e+03 2.41654590e+03 2.50566797e+03 2.66435889e+03 2.78563647e+03 2.76117603e+03 2.66562939e+03 2.72307812e+03 2.86297388e+03 2.88446753e+03 2.89353247e+03 2.94839966e+03 2.96644141e+03 3.02869531e+03 3.19587256e+03 3.15067261e+03 3.10149170e+03 3.20005542e+03 3.15936475e+03 3.30804443e+03 3.44674438e+03 3.35735059e+03 3.49409155e+03 3.49424292e+03 3.38765210e+03 3.54783691e+03 3.49963696e+03 3.58799121e+03 3.89109644e+03 3.74403149e+03 3.57601123e+03 3.69276416e+03 3.89580688e+03 4.07621973e+03 4.03180469e+03 3.82660107e+03 3.77513794e+03 3.95772754e+03 4.14298193e+03 4.31155762e+03 4.28025146e+03 4.05563208e+03 4.07769629e+03 4.26918018e+03 4.40030615e+03 4.28490039e+03 4.24511670e+03 4.39721289e+03 4.44211963e+03 4.60317480e+03 4.63260840e+03 4.45742822e+03 4.48343262e+03 4.57618701e+03 4.63638379e+03 4.73592529e+03 4.71863721e+03 4.86401855e+03 4.82890283e+03 4.69510400e+03 4.81061816e+03 4.73993652e+03 4.92301270e+03 5.25755371e+03 5.00802295e+03 4.74073535e+03 4.89514404e+03 5.16831152e+03 5.33864014e+03 5.40272217e+03 5.14233301e+03 4.95957324e+03 5.10343896e+03 5.34082959e+03 5.60870752e+03 5.50780664e+03 5.19559326e+03 5.19663770e+03 5.41965820e+03 5.52772461e+03 5.64933594e+03 5.65838525e+03 5.39015137e+03 5.41600732e+03 5.68970605e+03 5.74760352e+03 5.63044287e+03 5.62109863e+03 5.64224609e+03 5.61745703e+03 5.90996777e+03 5.98039941e+03 5.69483350e+03 5.69851025e+03 5.79512109e+03 5.87299707e+03 5.91239893e+03 5.89207715e+03 6.06939600e+03 6.17651221e+03 5.97585986e+03 5.87297607e+03 5.77694971e+03 6.02123633e+03 6.40080615e+03 6.30798926e+03 5.97143408e+03 5.86928760e+03 6.11534375e+03 6.46735352e+03 6.28635156e+03 5.96978516e+03 6.08430273e+03 6.28550928e+03 6.42522070e+03 6.64423779e+03 6.54041260e+03 6.17636670e+03 6.07140430e+03 6.29711572e+03 6.55479834e+03 6.53429883e+03 6.46178955e+03 6.45121143e+03 6.42091455e+03 6.57141602e+03 6.53232812e+03 6.38801172e+03 6.35703467e+03 6.39969043e+03 6.65349902e+03 6.75217236e+03 6.57054395e+03 6.61806396e+03 6.65419580e+03 6.78147314e+03 6.61516797e+03 6.28883350e+03 6.61021631e+03 7.00365186e+03 6.81631445e+03 6.46935840e+03 6.56080713e+03 6.87376367e+03 6.88820361e+03 6.78221240e+03 6.72593896e+03 6.55401074e+03 6.57210742e+03 6.94807031e+03 6.96607520e+03 6.65768604e+03 6.48246484e+03 6.53746436e+03 6.86102051e+03 7.15991992e+03 6.83632910e+03 6.65576514e+03 6.79722998e+03 6.81166943e+03 7.03920215e+03 7.03141113e+03 6.61937695e+03 6.65385303e+03 6.84567578e+03 6.85509961e+03 6.87898389e+03 6.78013428e+03 6.96747803e+03 7.13179346e+03 7.09669678e+03 7.17377148e+03 8.60697949e+03 8.84256348e+03 1.09429941e+04 1.06131855e+04 1.01484854e+04 1.04615938e+04 1.03239414e+04 1.08707217e+04 1.14286650e+04 1.06556650e+04 1.84976406e+04 2.84773809e+04 17449876. 34538408. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 22249762. -2.53423725e+06 -6.80806950e+06 1.90120195e+04 1.33684854e+04 7.55563184e+03 6.87034961e+03 6.44094629e+03 6.18177344e+03 6.36673340e+03 6.33247803e+03 6.18378516e+03 6.19534619e+03 6.19940088e+03 6.13224902e+03 6.13222070e+03 6.09203809e+03 6.01387354e+03 5.98699121e+03 5.94461182e+03 6.05994775e+03 6.09583057e+03 5.79957324e+03 5.76802051e+03 6.06554785e+03 6.04165430e+03 5.88596436e+03 5.83889404e+03 5.81144336e+03 5.80707764e+03 5.72550146e+03 5.72321826e+03 5.71922998e+03 5.62297900e+03 5.58627881e+03 5.55818408e+03 5.65489990e+03 5.65323145e+03 5.52892969e+03 5.49519922e+03 5.49123340e+03 5.47280273e+03 5.41667627e+03 5.36918848e+03 5.35257031e+03 5.20264111e+03 5.14740674e+03 5.21291943e+03 5.17690771e+03 5.39191895e+03 5.37920850e+03 5.12899854e+03 4.95868701e+03 4.90611475e+03 5.18503467e+03 5.21673828e+03 5.00088623e+03 4.85872998e+03 4.83670801e+03 4.87153955e+03 4.81072070e+03 4.94805811e+03 4.89191016e+03 4.57622754e+03 4.51760400e+03 4.72542725e+03 4.87508643e+03 4.71161768e+03 4.58022070e+03 4.55341357e+03 4.49329395e+03 4.40746973e+03 4.40288672e+03 4.37765918e+03 4.29742578e+03 4.28288086e+03 4.25506836e+03 4.25729590e+03 4.20170557e+03 4.25133789e+03 4.22135840e+03 4.05789795e+03 4.06233032e+03 4.03558740e+03 4.01151196e+03 3.99895825e+03 3.91032861e+03 3.86460669e+03 3.74453589e+03 3.62013257e+03 3.76368774e+03 3.75763550e+03 3.54837109e+03 3.52784839e+03 3.68585693e+03 3.74987964e+03 3.59721948e+03 3.45983325e+03 3.39014404e+03 3.34613159e+03 3.29012793e+03 3.23744849e+03 3.26479053e+03 3.21446045e+03 3.23996069e+03 3.17276318e+03 3.05325781e+03 3.05444287e+03 2.92593799e+03 2.89328247e+03 3.01340356e+03 2.94773999e+03 2.82850342e+03 2.72230029e+03 2.64265430e+03 2.73913184e+03 2.75083984e+03 2.62669702e+03 2.49439111e+03 2.44933203e+03 2.46387329e+03 2.41848340e+03 2.45144434e+03 2.42369287e+03 2.29627759e+03 2.19831641e+03 2.15742529e+03 2.21027222e+03 2.16853735e+03 2.07042603e+03 1.99117786e+03 1.94272900e+03 1.93364880e+03 1.83882251e+03 1.80061621e+03 1.85658569e+03 1.79747766e+03 1.70777649e+03 1.60598889e+03 1.55078040e+03 1.60982654e+03 1.56240393e+03 1.46936646e+03 1.38831421e+03 1.33297375e+03 1.32877271e+03 1.27885071e+03 1.23376221e+03 1.16090637e+03 1.13029407e+03 1.13798914e+03 1.06794763e+03 1.00544781e+03 9.62246216e+02 9.10185791e+02 8.49141724e+02 8.00065125e+02 7.61239929e+02 7.14250793e+02 6.64165955e+02 6.00443848e+02 5.64285522e+02 5.48826294e+02 4.78470642e+02 4.15925720e+02 3.78742188e+02 3.31226776e+02 2.93207458e+02 2.39595947e+02 1.84325104e+02 1.45930374e+02 9.76267548e+01 4.71264915e+01 -2.04108000e+00 -5.07384758e+01 -9.86248322e+01 -1.46150101e+02 -1.93059204e+02 -2.33018051e+02 -2.85442200e+02 -3.52889740e+02 -3.94900879e+02 -4.28487122e+02 -4.59675018e+02 -5.13258972e+02 -5.96591492e+02 -6.41372314e+02 -6.71654663e+02 -7.01345764e+02 -7.39866394e+02 -8.10704468e+02 -8.60005737e+02 -9.28828003e+02 -9.57791321e+02 -9.72487000e+02 -1.04639856e+03 -1.09521521e+03 -1.17137463e+03 -1.21378223e+03 -1.22554211e+03 -1.27528809e+03 -1.32340955e+03 -1.38582581e+03 -1.39253882e+03 -1.45774316e+03 -1.58673413e+03 -1.59783740e+03 -1.60576819e+03 -1.61673975e+03 -1.65231580e+03 -1.79225793e+03 -1.84775000e+03 -1.84189417e+03 -1.83986230e+03 -1.87886475e+03 -1.98355762e+03 -2.03356641e+03 -2.13091724e+03 -2.14422974e+03 -2.13477393e+03 -2.16767017e+03 -2.19965552e+03 -2.35855298e+03 -2.39152466e+03 -2.37078369e+03 -2.41035425e+03 -2.44122876e+03 -2.56362012e+03 -2.61753198e+03 -2.54883130e+03 -2.59040088e+03 -2.75960352e+03 -2.80934082e+03 -2.72351270e+03 -2.74362646e+03 -2.94092480e+03 -3.00080029e+03 -2.94406201e+03 -2.91314771e+03 -2.96230933e+03 -3.18641968e+03 -3.19561865e+03 -3.14950098e+03 -3.20029688e+03 -3.22210815e+03 -3.28819385e+03 -3.31708911e+03 -3.35300171e+03 -3.30557959e+03 -3.44553687e+03 -3.68607959e+03 -3.61069458e+03 -3.59778418e+03 -3.66162378e+03 -3.67333398e+03 -3.72426001e+03 -3.75533618e+03 -3.78317529e+03 -3.72240576e+03 -3.71145044e+03 -3.84591309e+03 -3.97305737e+03 -4.14133838e+03 -4.03934863e+03 -3.93433203e+03 -4.09279663e+03 -4.16755029e+03 -4.31406738e+03 -4.30100928e+03 -4.21459912e+03 -4.21106104e+03 -4.22888721e+03 -4.36814355e+03 -4.41142041e+03 -4.53455566e+03 -4.56093701e+03 -4.50656738e+03 -4.47098193e+03 -4.37574365e+03 -4.59362207e+03 -4.90661768e+03 -4.83744727e+03 -4.71584961e+03 -4.62916211e+03 -4.60201807e+03 -4.88409668e+03 -5.07435693e+03 -4.94728174e+03 -4.78112793e+03 -4.81583691e+03 -4.99189648e+03 -5.02196338e+03 -5.18821973e+03 -5.18183252e+03 -5.06640430e+03 -5.13154980e+03 -5.14404248e+03 -5.29063428e+03 -5.32388672e+03 -5.13235938e+03 -5.17059277e+03 -5.49264453e+03 -5.42112451e+03 -5.15789502e+03 -5.36812646e+03 -5.68658154e+03 -5.61843115e+03 -5.49413232e+03 -5.37797607e+03 -5.43499268e+03 -5.77198828e+03 -5.78494629e+03 -5.64728516e+03 -5.52467676e+03 -5.52592627e+03 -5.74638574e+03 -5.75017627e+03 -5.76778955e+03 -5.66141162e+03 -5.80650928e+03 -6.07335693e+03 -5.92834180e+03 -6.00832178e+03 -5.99285254e+03 -5.88338037e+03 -5.95112646e+03 -6.01708203e+03 -6.05158789e+03 -6.02298193e+03 -5.98594336e+03 -5.90490967e+03 -6.08957520e+03 -6.43366455e+03 -6.15160840e+03 -5.90539209e+03 -6.13125098e+03 -6.26880908e+03 -6.46124561e+03 -6.35422021e+03 -6.22016846e+03 -6.36942920e+03 -6.37384912e+03 -6.13053369e+03 -6.11560156e+03 -6.54530078e+03 -6.55549609e+03 -6.33440088e+03 -6.28755273e+03 -6.10510547e+03 -6.40754199e+03 -6.84635986e+03 -6.65146387e+03 -6.49493457e+03 -6.32795752e+03 -6.26800244e+03 -6.60830469e+03 -6.87997705e+03 -6.70650195e+03 -6.40290381e+03 -6.37615186e+03 -6.56367529e+03 -6.63167480e+03 -6.84939941e+03 -6.73805029e+03 -6.51025439e+03 -6.66384717e+03 -6.68931836e+03 -6.78580371e+03 -6.77254248e+03 -6.63780957e+03 -6.71276562e+03 -6.71857031e+03 -6.70882080e+03 -6.53513037e+03 -6.62774951e+03 -7.05655762e+03 -6.94942822e+03 -6.69363379e+03 -6.53718799e+03 -6.63171875e+03 -7.00502148e+03 -7.02346045e+03 -6.82972070e+03 -6.64149121e+03 -6.60381543e+03 -6.79263672e+03 -6.83104639e+03 -6.87112012e+03 -6.68562158e+03 -6.80934912e+03 -7.07619482e+03 -6.87742188e+03 -6.96455029e+03 -6.95719922e+03 -6.78273779e+03 -6.81537256e+03 -6.77481934e+03 -6.77918945e+03 -6.81172168e+03 -6.81171680e+03 -6.78561230e+03 -6.96096094e+03 -6.95875391e+03 -6.68483203e+03 -6.58618750e+03 -6.76929639e+03 -6.92449902e+03 -7.12894189e+03 -6.91733691e+03 -6.58249170e+03 -6.91200195e+03 -7.03083691e+03 -6.85265381e+03 -6.67707471e+03 -6.64514258e+03 -6.78757666e+03 -6.77573584e+03 -6.77497363e+03 -6.53761914e+03 -6.75940674e+03 -7.05294141e+03 -6.88100146e+03 -6.78958838e+03 -6.64392383e+03 -6.55292383e+03 -6.88558203e+03 -6.93395166e+03 -6.69092725e+03 -6.52192383e+03 -6.38779688e+03 -6.56318750e+03 -6.79392432e+03 -6.97987744e+03 -6.64741211e+03 -6.36277148e+03 -6.56712207e+03 -6.63915283e+03 -6.81800684e+03 -6.67059668e+03 -6.39750830e+03 -6.57772949e+03 -6.59854346e+03 -6.42269385e+03 -6.28487061e+03 -6.45865381e+03 -6.76866064e+03 -6.59714453e+03 -6.47720166e+03 -6.27068848e+03 -6.25066943e+03 -6.60270312e+03 -6.56144238e+03 -6.34555420e+03 -6.17776025e+03 -6.12153418e+03 -6.28558887e+03 -6.26639258e+03 -6.41362988e+03 -6.42788477e+03 -6.18831250e+03 -6.06634082e+03 -6.13851904e+03 -6.35358594e+03 -6.21527686e+03 -6.05517773e+03 -6.10987109e+03 -6.09906250e+03 -5.96477686e+03 -5.86826416e+03 -6.09410791e+03 -6.04534814e+03 -5.88314404e+03 -6.08876367e+03 -6.08376807e+03 -5.94632520e+03 -5.88973389e+03 -5.86510840e+03 -5.82995020e+03 -5.65876172e+03 -5.58832129e+03 -5.81895166e+03 -5.91341357e+03 -5.58114062e+03 -5.36203955e+03 -5.60586182e+03 -5.89906543e+03 -5.79172070e+03 -5.47611621e+03 -5.34811133e+03 -5.58757910e+03 -5.64259717e+03 -5.45030029e+03 -5.46695215e+03 -5.29233154e+03 -5.11064648e+03 -5.27249561e+03 -5.47736719e+03 -5.46216016e+03 -5.16697461e+03 -4.98511084e+03 -5.24959131e+03 -5.38593262e+03 -5.17052051e+03 -4.94557227e+03 -4.85065381e+03 -4.96647656e+03 -4.98042529e+03 -5.06523340e+03 -5.02779785e+03 -4.81077148e+03 -4.82431104e+03 -4.84045068e+03 -4.87098779e+03 -4.72011523e+03 -4.58469629e+03 -4.74034570e+03 -4.70568066e+03 -4.61033643e+03 -4.45999365e+03 -4.48538525e+03 -4.69254004e+03 -4.48335645e+03 -4.28056543e+03 -4.33453320e+03 -4.38202246e+03 -4.37334180e+03 -4.29353613e+03 -4.34103711e+03 -4.33830518e+03 -4.17634180e+03 -4.01744971e+03 -3.99641138e+03 -4.15285986e+03 -4.02297900e+03 -3.88570557e+03 -3.97205273e+03 -3.95155298e+03 -3.84339771e+03 -3.75826660e+03 -3.84215381e+03 -3.78732349e+03 -3.63436768e+03 -3.68639624e+03 -3.65508740e+03 -3.65254297e+03 -3.60836060e+03 -3.50631592e+03 -3.43957617e+03 -3.30865527e+03 -3.24745190e+03 -3.38612207e+03 -3.46429199e+03 -3.24006250e+03 -3.04174438e+03 -3.12227466e+03 -3.26970898e+03 -3.21467505e+03 -3.00530200e+03 -2.86339185e+03 -2.96238599e+03 -2.99853442e+03 -2.87108130e+03 -2.87363867e+03 -2.80955884e+03 -2.66605273e+03 -2.65099707e+03 -2.70169287e+03 -2.66702026e+03 -2.51949219e+03 -2.41872461e+03 -2.48482593e+03 -2.53612573e+03 -2.42343237e+03 -2.27518115e+03 -2.20866943e+03 -2.27276245e+03 -2.28053564e+03 -2.16832422e+03 -2.07840112e+03 -2.03936255e+03 -2.02487158e+03 -1.97238098e+03 -1.98169067e+03 -1.89681323e+03 -1.78531738e+03 -1.80604797e+03 -1.77092297e+03 -1.72594275e+03 -1.64602014e+03 -1.57287280e+03 -1.58530005e+03 -1.50196301e+03 -1.43696924e+03 -1.49216797e+03 -1.43482166e+03 -1.33167102e+03 -1.74361792e+03 -1.86776147e+03 -1.86552222e+03 -1.82656152e+03 -1.72866541e+03 -1.37216797e+03 -1.37789258e+03 -1.35919092e+03 -1.12098840e+03 -8.74695557e+02 -1.01579028e+03 -1.32305225e+03 -5.27330762e+03 -115786944. 0. 0. 0. 0. 0. 0. -219605696. -219605696. -1.33163477e+03 -3.50749146e+03 -3.50749146e+03 833382336. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 391148160. 1.60673500e+05 -1.16610180e+05 2.09380835e+03 1.74053174e+03 1.25825330e+03 8.53561523e+02 1.15941907e+03 1.03147229e+03 1.00982758e+03 1.03317700e+03 1.08781299e+03 1.17193530e+03 1.22777417e+03 1.22816260e+03 1.25579700e+03 1.33548730e+03 1.38869226e+03 1.41968054e+03 1.46819202e+03 1.51021790e+03 1.54913843e+03 1.62810950e+03 1.67673926e+03 1.66632422e+03 1.72188586e+03 1.82705798e+03 1.88174658e+03 1.91639417e+03 1.91820618e+03 1.93059717e+03 2.02592493e+03 2.09570605e+03 2.11656104e+03 2.13878540e+03 2.17774927e+03 2.26936035e+03 2.31800537e+03 2.33411084e+03 2.35964526e+03 2.40125391e+03 2.54166919e+03 2.60140649e+03 2.50965918e+03 2.53542261e+03 2.64930469e+03 2.70075220e+03 2.77671289e+03 2.80913354e+03 2.78760059e+03 2.87744678e+03 2.94176074e+03 2.96196118e+03 3.00884424e+03 3.01274927e+03 3.07887524e+03 3.15440137e+03 3.16119238e+03 3.19114868e+03 3.21799048e+03 3.27555249e+03 3.38470508e+03 3.43355908e+03 3.43883960e+03 3.42156030e+03 3.44016504e+03 3.57903955e+03 3.63286011e+03 3.56617310e+03 3.64236353e+03 3.70378320e+03 3.75563013e+03 3.88240161e+03 3.87846655e+03 3.79089990e+03 3.83982104e+03 4.00623975e+03 4.08436035e+03 3.97699243e+03 3.94369312e+03 4.07212549e+03 4.14887500e+03 4.26839844e+03 4.28750488e+03 4.17833398e+03 4.25760791e+03 4.39835107e+03 4.40761035e+03 4.39221973e+03 4.35216797e+03 4.38094580e+03 4.57582422e+03 4.62907666e+03 4.53950977e+03 4.60310840e+03 4.66361523e+03 4.67536670e+03 4.70050098e+03 4.73866504e+03 4.83165381e+03 4.83015039e+03 4.92360889e+03 4.96793604e+03 4.82461084e+03 4.87480566e+03 5.02052393e+03 5.02500146e+03 5.01521631e+03 5.05718311e+03 5.11347510e+03 5.21515088e+03 5.21037158e+03 5.18066016e+03 5.29106152e+03 5.35668896e+03 5.27478613e+03 5.28910498e+03 5.35091650e+03 5.41348975e+03 5.43463037e+03 5.37715918e+03 5.40956787e+03 5.51180762e+03 5.66510449e+03 5.65185791e+03 5.46487305e+03 5.57019238e+03 5.73540332e+03 5.71186670e+03 5.71517383e+03 5.65318115e+03 5.63588672e+03 5.78823926e+03 5.94804248e+03 5.89311914e+03 5.75465918e+03 5.79314697e+03 5.99424854e+03 6.01824951e+03 6.05774609e+03 5.96409277e+03 5.85661816e+03 5.96278662e+03 6.00878369e+03 6.03355469e+03 6.08108838e+03 6.05024316e+03 6.13428564e+03 6.32968457e+03 6.22805127e+03 6.02358984e+03 6.11271631e+03 6.27801611e+03 6.28433496e+03 6.38667236e+03 6.33027002e+03 6.17804541e+03 6.29098389e+03 6.48952881e+03 6.42652002e+03 6.15454932e+03 6.28594482e+03 6.50011963e+03 6.48419922e+03 6.43437891e+03 6.35943262e+03 6.34512207e+03 6.47906055e+03 6.50218701e+03 6.53779932e+03 6.59318164e+03 6.43993555e+03 6.56618408e+03 6.70456104e+03 6.59764404e+03 6.46861914e+03 6.55081885e+03 6.67207178e+03 6.72309180e+03 6.67828564e+03 6.55296191e+03 6.48813672e+03 6.63358691e+03 6.92359961e+03 6.93957324e+03 6.53923047e+03 6.56158740e+03 6.83542041e+03 6.79715771e+03 6.75045752e+03 6.68293164e+03 6.59248096e+03 6.77910010e+03 6.91989355e+03 6.82926025e+03 6.68925684e+03 6.67209521e+03 6.75153906e+03 6.89743555e+03 6.96185498e+03 6.82770068e+03 6.75225781e+03 6.82688867e+03 6.84009424e+03 6.82211670e+03 6.79291309e+03 6.81152832e+03 6.74155420e+03 6.92741113e+03 7.03817432e+03 6.66240820e+03 6.69848340e+03 6.94192969e+03 6.88376855e+03 6.89528223e+03 6.72032324e+03 6.75633594e+03 7.00218018e+03 6.90565039e+03 6.82191602e+03 6.70502344e+03 6.64686426e+03 6.82365479e+03 6.97526514e+03 6.83967188e+03 6.77952930e+03 6.90580811e+03 6.82107666e+03 6.93420605e+03 6.88848535e+03 6.66705957e+03 6.65713770e+03 6.67289307e+03 6.88525293e+03 6.82946924e+03 6.67807373e+03 6.71531006e+03 6.82097998e+03 6.81184473e+03 6.73030957e+03 6.70234521e+03 6.70166748e+03 6.74074707e+03 6.68237988e+03 6.79974512e+03 6.68732178e+03 6.54329248e+03 6.74180127e+03 6.55732080e+03 6.58666650e+03 6.71931836e+03 6.54983545e+03 6.55229883e+03 6.58906689e+03 6.55570801e+03 6.50884229e+03 6.40255078e+03 6.63981738e+03 6.76710059e+03 6.38633936e+03 6.36718701e+03 6.44539062e+03 6.43913916e+03 6.55143408e+03 6.47428516e+03 6.30373096e+03 6.31349072e+03 6.43413330e+03 6.43063623e+03 6.35486035e+03 6.21968799e+03 6.25079639e+03 6.28700098e+03 6.20891260e+03 6.19827051e+03 6.13430859e+03 6.10804834e+03 6.17019092e+03 6.23617920e+03 6.19896436e+03 6.06070264e+03 5.98786768e+03 6.11919678e+03 6.20861670e+03 5.99556738e+03 6.03229199e+03 5.99722363e+03 5.78688721e+03 5.95052393e+03 5.93385986e+03 5.79334717e+03 5.86101465e+03 5.85328320e+03 5.78014258e+03 5.87732959e+03 5.74591406e+03 5.67033398e+03 5.68787891e+03 5.70989893e+03 5.70508350e+03 5.55159570e+03 5.49349951e+03 5.56496094e+03 5.60212207e+03 5.56308203e+03 5.46852393e+03 5.36767773e+03 5.47605566e+03 5.58352393e+03 5.39164893e+03 5.25036182e+03 5.22621436e+03 5.32541162e+03 5.35439844e+03 5.18787842e+03 5.11734570e+03 5.13521338e+03 5.13481836e+03 5.08257910e+03 5.10594727e+03 5.04306201e+03 4.87169873e+03 4.97414014e+03 5.07827832e+03 4.90841455e+03 4.70106006e+03 4.72456641e+03 4.79825342e+03 4.81740967e+03 4.76151953e+03 4.65646826e+03 4.59874268e+03 4.67191064e+03 4.72110693e+03 4.55018262e+03 4.45192334e+03 4.45580811e+03 4.54114404e+03 4.46606738e+03 4.27066309e+03 4.23504102e+03 4.26662646e+03 4.24790771e+03 4.25096631e+03 4.23079248e+03 4.12529883e+03 4.10172949e+03 4.06668311e+03 3.95361450e+03 3.92843091e+03 3.89015308e+03 3.92300806e+03 3.93015308e+03 3.81051953e+03 3.70774561e+03 3.70688965e+03 3.76053687e+03 3.81239551e+03 3.70664136e+03 3.50954370e+03 3.50437646e+03 3.52601392e+03 3.45282104e+03 3.38554053e+03 3.36570459e+03 3.34066724e+03 3.30418945e+03 3.23732715e+03 3.13578003e+03 3.15035034e+03 3.17475537e+03 3.14687793e+03 3.06454614e+03 2.94027026e+03 2.92831396e+03 2.88965430e+03 2.81774780e+03 2.86621094e+03 2.81951611e+03 2.69012476e+03 2.65539233e+03 2.62791064e+03 2.66147778e+03 2.62267456e+03 2.51564697e+03 2.46528467e+03 2.42306689e+03 2.36761328e+03 2.30170142e+03 2.29551880e+03 2.25624219e+03 2.22770825e+03 2.18650464e+03 2.05559302e+03 2.03401917e+03 2.01329651e+03 1.97197363e+03 1.98274194e+03 1.87461475e+03 1.78334497e+03 1.81158289e+03 1.79117175e+03 1.70840515e+03 1.64681067e+03 1.57772070e+03 1.52770227e+03 1.49621130e+03 1.46758411e+03 1.41470752e+03 1.38506946e+03 1.35943433e+03 1.28459900e+03 1.21969714e+03 1.16707471e+03 1.13809644e+03 1.11182434e+03 1.04691907e+03 9.77832214e+02 9.32192078e+02 8.97329468e+02 8.66537048e+02 8.36075989e+02 7.64545471e+02 6.98771790e+02 6.64333191e+02 6.11337158e+02 5.62512451e+02 5.32088562e+02 4.81578888e+02 4.23666626e+02 3.79745422e+02 3.30008148e+02 2.83843658e+02 2.43030151e+02 1.94160965e+02 1.41521271e+02 9.13286133e+01 4.44989433e+01 -1.68217468e+00 -4.93836517e+01 -9.95679092e+01 -1.47841431e+02 -1.96019943e+02 -2.40218155e+02 -2.90626038e+02 -3.39197205e+02 -3.83341827e+02 -4.35203827e+02 -4.81133667e+02 -5.23367310e+02 -5.73807007e+02 -6.21247192e+02 -6.81209778e+02 -7.31948975e+02 -7.62898254e+02 -8.04724609e+02 -8.47812683e+02 -9.00201294e+02 -9.48530212e+02 -1.00595294e+03 -1.06477271e+03 -1.09631067e+03 -1.13760156e+03 -1.17808093e+03 -1.23840649e+03 -1.31471753e+03 -1.34801416e+03 -1.37162427e+03 -1.41228748e+03 -1.45985461e+03 -1.50374475e+03 -1.57131812e+03 -1.63220264e+03 -1.66501746e+03 -1.70386011e+03 -1.73742053e+03 -1.78420825e+03 -1.85257007e+03 -1.88957935e+03 -1.94933740e+03 -1.99285388e+03 -2.00615613e+03 -2.09996680e+03 -2.10321533e+03 -2.11700635e+03 -2.24230005e+03 -2.26793335e+03 -2.27603296e+03 -2.34744482e+03 -2.37110986e+03 -2.39784131e+03 -2.54750781e+03 -2.59300220e+03 -2.50746338e+03 -2.57923901e+03 -2.66089600e+03 -2.67018311e+03 -2.77247144e+03 -2.80159399e+03 -2.77027759e+03 -2.85050000e+03 -2.89510645e+03 -2.99043921e+03 -3.07241113e+03 -3.05599536e+03 -3.12190454e+03 -3.10785498e+03 -3.06762085e+03 -3.17991260e+03 -3.31681885e+03 -3.31736035e+03 -3.36530493e+03 -3.39313086e+03 -3.31907129e+03 -3.42139282e+03 -3.62822314e+03 -3.62764990e+03 -3.56595312e+03 -3.55098706e+03 -3.58716235e+03 -3.75577124e+03 -3.82509692e+03 -3.77469409e+03 -3.86035938e+03 -3.85894604e+03 -3.90893384e+03 -3.98084229e+03 -3.88015039e+03 -3.96271753e+03 -4.13227490e+03 -4.19436475e+03 -4.14601318e+03 -4.07818921e+03 -4.12422119e+03 -4.26009277e+03 -4.37951807e+03 -4.38870117e+03 -4.30401807e+03 -4.28409033e+03 -4.43189551e+03 -4.53921240e+03 -4.63921875e+03 -4.60320361e+03 -4.50301318e+03 -4.61718896e+03 -4.62392432e+03 -4.63156201e+03 -4.74959814e+03 -4.75507617e+03 -4.78497607e+03 -4.92118799e+03 -4.85886035e+03 -4.84331494e+03 -4.93889355e+03 -4.98049512e+03 -5.05707617e+03 -5.00212842e+03 -4.96218750e+03 -5.02044580e+03 -5.14806445e+03 -5.26586377e+03 -5.29915576e+03 -5.23774121e+03 -5.14711523e+03 -5.21641406e+03 -5.25870605e+03 -5.33958643e+03 -5.43396826e+03 -5.37497119e+03 -5.36960303e+03 -5.40504346e+03 -5.43929248e+03 -5.55320850e+03 -5.72263232e+03 -5.65662256e+03 -5.54636621e+03 -5.56266455e+03 -5.48800635e+03 -5.58899316e+03 -5.77626953e+03 -5.84868604e+03 -5.81806836e+03 -5.70164990e+03 -5.70494971e+03 -5.78203906e+03 -5.90260889e+03 -5.92443652e+03 -5.95592383e+03 -5.92233740e+03 -5.82366016e+03 -5.97364209e+03 -6.15277100e+03 -6.12096338e+03 -5.93042090e+03 -6.02361670e+03 -6.08652783e+03 -6.14437598e+03 -6.18454639e+03 -6.16384863e+03 -6.24680469e+03 -6.16804688e+03 -6.11283105e+03 -6.31083252e+03 -6.29914600e+03 -6.28933203e+03 -6.38387646e+03 -6.23685156e+03 -6.19099316e+03 -6.39335254e+03 -6.39712744e+03 -6.45508838e+03 -6.68471533e+03 -6.64274805e+03 -6.44525439e+03 -6.31905225e+03 -6.44986084e+03 -6.81421045e+03 -8.45103809e+03 -8.21455078e+03 -1.64016699e+04 -1.70681152e+04 -2.72666625e+06 72470784. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -181644528. -4717116. -2.69870801e+04 -1.47211025e+04 -7.33157178e+03 -9.31232715e+03 -1.08827061e+04 -9.48917871e+03 -7.75185645e+03 -7.37528125e+03 -6.81142480e+03 -6.79946191e+03 -7.03434082e+03 -6.90576465e+03 -6.81674219e+03 -6.67664648e+03 -6.64706787e+03 -6.93127979e+03 -7.08086035e+03 -6.81889209e+03 -6.61614307e+03 -6.66987939e+03 -6.77203711e+03 -6.88383789e+03 -6.95888086e+03 -6.70600049e+03 -6.59131738e+03 -6.68188428e+03 -6.71362549e+03 -6.70168555e+03 -6.59464355e+03 -6.55793750e+03 -6.79898877e+03 -6.92048730e+03 -6.76029688e+03 -6.43122217e+03 -6.41069922e+03 -6.68077539e+03 -6.73116553e+03 -6.58882959e+03 -6.39146777e+03 -6.44439258e+03 -6.72629443e+03 -6.82349072e+03 -6.63076758e+03 -6.26047119e+03 -6.35064502e+03 -6.64897900e+03 -6.58578320e+03 -6.55816602e+03 -6.40937158e+03 -6.21253320e+03 -6.31968506e+03 -6.53432861e+03 -6.37757080e+03 -6.23848535e+03 -6.44616699e+03 -6.45132227e+03 -6.34745264e+03 -6.26603174e+03 -6.02233643e+03 -6.18126758e+03 -6.48567041e+03 -6.30705518e+03 -6.07690918e+03 -5.99681348e+03 -5.96460400e+03 -6.22566602e+03 -6.39803027e+03 -6.15957861e+03 -5.96157422e+03 -5.90397607e+03 -5.87517139e+03 -6.01070068e+03 -6.16517578e+03 -5.94270996e+03 -5.78182861e+03 -5.93198975e+03 -5.89053711e+03 -5.74861719e+03 -5.72804492e+03 -5.81735254e+03 -5.90236768e+03 -5.83047070e+03 -5.77718457e+03 -5.60268066e+03 -5.44362988e+03 -5.71941553e+03 -5.89520947e+03 -5.54881055e+03 -5.33451904e+03 -5.41643115e+03 -5.55147998e+03 -5.60541260e+03 -5.62213232e+03 -5.39100439e+03 -5.27075684e+03 -5.37971826e+03 -5.35287305e+03 -5.36183057e+03 -5.28314258e+03 -5.11086914e+03 -5.12098877e+03 -5.23015186e+03 -5.20001367e+03 -5.14465283e+03 -5.14065332e+03 -5.09357666e+03 -5.01925781e+03 -5.00398340e+03 -4.85573633e+03 -4.78802490e+03 -5.01867920e+03 -5.03013184e+03 -4.73022559e+03 -4.59015234e+03 -4.64908203e+03 -4.84598291e+03 -4.89200098e+03 -4.69315820e+03 -4.50316699e+03 -4.46022314e+03 -4.49440625e+03 -4.53004785e+03 -4.50839453e+03 -4.44265088e+03 -4.39909473e+03 -4.34565967e+03 -4.31478223e+03 -4.29687988e+03 -4.16746191e+03 -4.19414844e+03 -4.32362549e+03 -4.18404004e+03 -4.05565723e+03 -4.00473486e+03 -3.91252368e+03 -4.04198804e+03 -4.09090991e+03 -3.86930225e+03 -3.74271533e+03 -3.76351636e+03 -3.89357324e+03 -3.91479419e+03 -3.73891431e+03 -3.58802686e+03 -3.54164917e+03 -3.54371704e+03 -3.59191553e+03 -3.58250293e+03 -3.41576172e+03 -3.29662842e+03 -3.36690503e+03 -3.43236572e+03 -3.35259448e+03 -3.22937817e+03 -3.20208398e+03 -3.17939429e+03 -3.13954419e+03 -3.12591431e+03 -2.97452734e+03 -2.92658154e+03 -3.00465942e+03 -2.95248608e+03 -2.86595215e+03 -2.78321240e+03 -2.74480029e+03 -2.73431396e+03 -2.72004297e+03 -2.69734473e+03 -2.58226416e+03 -2.54568970e+03 -2.56524780e+03 -2.49038501e+03 -2.40811743e+03 -2.35502661e+03 -2.31212036e+03 -2.31492603e+03 -2.33034937e+03 -2.23934692e+03 -2.09723047e+03 -2.04720435e+03 -2.09214648e+03 -2.09687061e+03 -2.01367053e+03 -1.87538062e+03 -1.83137805e+03 -1.83744727e+03 -1.81836987e+03 -1.77777588e+03 -1.67924097e+03 -1.61412781e+03 -1.58898108e+03 -1.57129614e+03 -1.54623315e+03 -1.47612598e+03 -1.41132776e+03 -1.36846631e+03 -1.32480627e+03 -1.28815308e+03 -1.24077124e+03 -1.19345251e+03 -1.13597705e+03 -1.07815088e+03 -1.02014050e+03 -9.69876404e+02 -9.57751953e+02 -9.45349243e+02 -8.82689697e+02 -7.96655945e+02 -7.26368652e+02 -6.90928284e+02 -6.84640198e+02 -6.53085327e+02 -5.83547791e+02 -5.12411560e+02 -4.55242065e+02 -4.21132141e+02 -3.87451904e+02 -3.38868011e+02 -2.88923035e+02 -2.39277115e+02 -1.88294098e+02 -1.40849930e+02 -9.27668076e+01 -4.71017075e+01 -6.32442474e-01 4.83511658e+01 9.95668869e+01 1.49632034e+02 1.86421967e+02 2.34419769e+02 2.91312256e+02 3.39272949e+02 3.87373474e+02 4.31637634e+02 4.90706665e+02 5.39602722e+02 5.63265991e+02 5.92773438e+02 6.50653931e+02 7.32154602e+02 8.03707520e+02 8.38142334e+02 8.42229675e+02 8.65313354e+02 9.20387817e+02 1.01643005e+03 1.10380042e+03 1.13099841e+03 1.11198193e+03 1.14718079e+03 1.27888733e+03 1.31250208e+03 1.30392847e+03 1.36263196e+03 1.41449329e+03 1.46159045e+03 1.55998145e+03 1.57685571e+03 1.56178088e+03 1.64878015e+03 1.66650488e+03 1.74664050e+03 1.83996948e+03 1.80172363e+03 1.88454102e+03 1.98182666e+03 1.98293579e+03 2.02704504e+03 2.05934717e+03 2.13635938e+03 2.18054761e+03 2.17167212e+03 2.18183105e+03 2.24582227e+03 2.41081396e+03 2.51165381e+03 2.48367725e+03 2.42314893e+03 2.41326074e+03 2.50293018e+03 2.65770728e+03 2.78567871e+03 2.75911304e+03 2.64937915e+03 2.72361060e+03 2.87373535e+03 2.87531519e+03 2.90758911e+03 2.96173340e+03 2.95549487e+03 3.02734155e+03 3.20507764e+03 3.14010278e+03 3.09907104e+03 3.20856812e+03 3.15164355e+03 3.30405859e+03 3.46522778e+03 3.35443311e+03 3.48747827e+03 3.49302246e+03 3.38956934e+03 3.53923022e+03 3.49151343e+03 3.61379980e+03 3.90161084e+03 3.72207520e+03 3.57596167e+03 3.68637134e+03 3.89722412e+03 4.07229883e+03 4.05214062e+03 3.86104956e+03 3.79425195e+03 3.92248511e+03 4.09502783e+03 4.31174512e+03 4.27191406e+03 4.07476318e+03 4.11323047e+03 4.26190137e+03 4.37425488e+03 4.28783496e+03 4.28060107e+03 4.37407568e+03 4.41338721e+03 4.60610498e+03 4.66131396e+03 4.45854736e+03 4.44015771e+03 4.57828369e+03 4.63586768e+03 4.71613477e+03 4.71494775e+03 4.88284229e+03 4.82211523e+03 4.66353809e+03 4.84162500e+03 4.75490625e+03 4.89720215e+03 5.26057129e+03 5.02037598e+03 4.74103076e+03 4.89256348e+03 5.19537451e+03 5.34921533e+03 5.34897266e+03 5.10938232e+03 4.97775977e+03 5.11273096e+03 5.32870996e+03 5.59969336e+03 5.48892627e+03 5.18671729e+03 5.19591895e+03 5.42065576e+03 5.50318359e+03 5.66248877e+03 5.71136768e+03 5.38480957e+03 5.39613477e+03 5.64325977e+03 5.72662061e+03 5.63445850e+03 5.63780566e+03 5.67268213e+03 5.60636816e+03 5.92601611e+03 5.94792969e+03 5.69525244e+03 5.71573340e+03 5.79814209e+03 5.83920996e+03 5.87965088e+03 5.89717041e+03 6.08299219e+03 6.15563818e+03 6.00020752e+03 5.88986621e+03 5.78181055e+03 6.05786426e+03 6.37990869e+03 6.27504736e+03 5.97012158e+03 5.87594629e+03 6.09159131e+03 6.43233203e+03 6.28581592e+03 5.94597412e+03 6.11195312e+03 6.34451611e+03 6.38847852e+03 6.64504736e+03 6.53557422e+03 6.16802881e+03 6.07105664e+03 6.27551270e+03 6.51588037e+03 6.55577881e+03 6.44606055e+03 6.43711182e+03 6.44269824e+03 6.58087158e+03 6.52780859e+03 6.39618652e+03 6.43913184e+03 6.35619678e+03 6.62685938e+03 6.82296973e+03 6.57229150e+03 6.62228564e+03 6.67464648e+03 6.67825244e+03 6.51973340e+03 6.41759912e+03 6.68261621e+03 6.97594629e+03 6.78529736e+03 6.48065088e+03 6.54269238e+03 6.85719238e+03 6.95437744e+03 6.84099951e+03 6.78811963e+03 6.55273828e+03 6.54917090e+03 6.84934473e+03 6.88176270e+03 6.74648828e+03 6.60530322e+03 6.52474414e+03 6.85690137e+03 7.12741992e+03 6.81172803e+03 6.64242969e+03 6.82810156e+03 6.75948633e+03 7.02145850e+03 7.03685303e+03 6.68754443e+03 6.58982324e+03 6.78808057e+03 6.82309521e+03 6.88912402e+03 6.82315039e+03 7.00219482e+03 7.13820410e+03 7.06363184e+03 7.31520264e+03 7.85027100e+03 7.25496582e+03 1.08961064e+04 1.03265195e+04 1.56588018e+04 2.18159062e+04 5619526. 2.75342275e+06 2.75369775e+06 -5.51757950e+06 9313138. 1.02738431e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 28241116. 2.45838250e+06 2.74274414e+04 1.73062715e+04 1.13054805e+04 9.22666016e+03 8.39049805e+03 6.85155420e+03 6.69844385e+03 6.40760938e+03 6.17881055e+03 6.32258887e+03 6.30294678e+03 6.18604736e+03 6.21631836e+03 6.16689209e+03 6.12869629e+03 6.10838525e+03 6.09164893e+03 6.03528125e+03 5.96188965e+03 5.92147852e+03 6.08006738e+03 6.09906445e+03 5.77908301e+03 5.75262695e+03 6.06052734e+03 6.06560400e+03 5.87717822e+03 5.82660156e+03 5.82780176e+03 5.78416211e+03 5.69865381e+03 5.74402197e+03 5.71050342e+03 5.63287061e+03 5.51766211e+03 5.49409180e+03 5.70600928e+03 5.71368652e+03 5.50368896e+03 5.48810645e+03 5.48597949e+03 5.46927930e+03 5.39253711e+03 5.34961670e+03 5.36707275e+03 5.27598584e+03 5.20232715e+03 5.19774023e+03 5.15020312e+03 5.35997900e+03 5.35675635e+03 5.13180029e+03 4.96559473e+03 4.91469482e+03 5.18931201e+03 5.19206445e+03 4.97694482e+03 4.86529932e+03 4.85475586e+03 4.88948535e+03 4.80283496e+03 4.93124658e+03 4.89299463e+03 4.59102686e+03 4.51638770e+03 4.70879834e+03 4.86640723e+03 4.71269531e+03 4.56742871e+03 4.53653125e+03 4.48537451e+03 4.44555615e+03 4.40798828e+03 4.41744629e+03 4.37544531e+03 4.26945264e+03 4.23391260e+03 4.21831836e+03 4.16562598e+03 4.27367529e+03 4.21994043e+03 4.06597949e+03 4.01854346e+03 3.98881030e+03 4.05646289e+03 4.04235522e+03 3.89731055e+03 3.85394873e+03 3.75035864e+03 3.65098682e+03 3.79005371e+03 3.73162207e+03 3.50763892e+03 3.52649878e+03 3.67999512e+03 3.75384106e+03 3.60180811e+03 3.46297900e+03 3.37769653e+03 3.33144019e+03 3.31460815e+03 3.27693774e+03 3.24256714e+03 3.18751416e+03 3.22830396e+03 3.17780908e+03 3.05634497e+03 3.02675391e+03 2.89159814e+03 2.91701831e+03 3.05855713e+03 2.94783960e+03 2.82130176e+03 2.71230835e+03 2.65811816e+03 2.76329785e+03 2.72835986e+03 2.60618091e+03 2.50011987e+03 2.44402954e+03 2.45273950e+03 2.41965356e+03 2.45095728e+03 2.41930469e+03 2.29538940e+03 2.22103027e+03 2.18246997e+03 2.18383398e+03 2.14636084e+03 2.07441943e+03 1.99260449e+03 1.95171570e+03 1.92448059e+03 1.81749609e+03 1.81494055e+03 1.87690479e+03 1.79816931e+03 1.70732385e+03 1.60774438e+03 1.55419714e+03 1.60933167e+03 1.56213367e+03 1.46521936e+03 1.38750867e+03 1.33734424e+03 1.33332788e+03 1.27727319e+03 1.23096301e+03 1.16166248e+03 1.13188171e+03 1.14156250e+03 1.06893579e+03 1.00583789e+03 9.65814636e+02 9.11617615e+02 8.47467529e+02 8.01484009e+02 7.59006897e+02 7.07522888e+02 6.67848328e+02 6.03907715e+02 5.62780884e+02 5.49968079e+02 4.79246552e+02 4.14870026e+02 3.78252380e+02 3.31435028e+02 2.93301453e+02 2.42258667e+02 1.87353165e+02 1.45552429e+02 9.72902908e+01 4.70738068e+01 -8.29565942e-01 -4.84331589e+01 -9.49606934e+01 -1.41218979e+02 -1.89359039e+02 -2.32301773e+02 -2.86693054e+02 -3.52222778e+02 -3.94404633e+02 -4.27568176e+02 -4.58296875e+02 -5.11799316e+02 -5.94171692e+02 -6.39849854e+02 -6.68925415e+02 -7.00909180e+02 -7.40331055e+02 -8.07571289e+02 -8.59764221e+02 -9.26877991e+02 -9.65140747e+02 -9.84064331e+02 -1.03588269e+03 -1.08169714e+03 -1.16999207e+03 -1.21262903e+03 -1.22068616e+03 -1.27177673e+03 -1.32043188e+03 -1.36653699e+03 -1.37547156e+03 -1.46510352e+03 -1.60504456e+03 -1.60621362e+03 -1.60437195e+03 -1.61255359e+03 -1.64426013e+03 -1.79136304e+03 -1.85379419e+03 -1.84243689e+03 -1.84027344e+03 -1.88005042e+03 -1.98134192e+03 -2.02810107e+03 -2.12456665e+03 -2.16948364e+03 -2.16255786e+03 -2.14716235e+03 -2.18187109e+03 -2.36057300e+03 -2.39566553e+03 -2.37374902e+03 -2.38342896e+03 -2.40919946e+03 -2.59400366e+03 -2.65158130e+03 -2.53630371e+03 -2.57583374e+03 -2.76604761e+03 -2.81055688e+03 -2.71280591e+03 -2.75335571e+03 -2.93859546e+03 -2.99990625e+03 -2.94720190e+03 -2.91789648e+03 -2.96962402e+03 -3.17303369e+03 -3.17258203e+03 -3.11671411e+03 -3.20906787e+03 -3.24323535e+03 -3.28216504e+03 -3.32853101e+03 -3.36940942e+03 -3.31210400e+03 -3.43592285e+03 -3.64843091e+03 -3.58436011e+03 -3.64439648e+03 -3.70155347e+03 -3.67260742e+03 -3.71586011e+03 -3.75104565e+03 -3.77551929e+03 -3.73284204e+03 -3.76719189e+03 -3.88985156e+03 -3.93033032e+03 -4.10576611e+03 -4.03349414e+03 -3.92430859e+03 -4.08045825e+03 -4.15441406e+03 -4.32639697e+03 -4.30341895e+03 -4.20822461e+03 -4.20580518e+03 -4.23645996e+03 -4.35701465e+03 -4.38929492e+03 -4.53888330e+03 -4.55454834e+03 -4.48577100e+03 -4.50702490e+03 -4.40482324e+03 -4.56932275e+03 -4.87269385e+03 -4.85256104e+03 -4.72716602e+03 -4.62665869e+03 -4.59857080e+03 -4.86538525e+03 -5.06564600e+03 -4.96373682e+03 -4.78604736e+03 -4.82771826e+03 -4.99256494e+03 -5.01830322e+03 -5.16576465e+03 -5.18233008e+03 -5.06278760e+03 -5.09370459e+03 -5.12352051e+03 -5.32877295e+03 -5.38340625e+03 -5.12911914e+03 -5.14584326e+03 -5.47693115e+03 -5.46560889e+03 -5.20652100e+03 -5.32526465e+03 -5.61771631e+03 -5.62630615e+03 -5.54015137e+03 -5.40242578e+03 -5.40245850e+03 -5.73790967e+03 -5.78589355e+03 -5.65730811e+03 -5.53444434e+03 -5.50529150e+03 -5.70071826e+03 -5.77634229e+03 -5.79562695e+03 -5.64792041e+03 -5.79157080e+03 -6.07796143e+03 -5.95577783e+03 -6.00677734e+03 -5.97609229e+03 -5.88735791e+03 -5.95316992e+03 -5.99488965e+03 -6.06487891e+03 -6.04871240e+03 -5.95329980e+03 -5.85691064e+03 -6.06364111e+03 -6.39702246e+03 -6.08870312e+03 -5.89629834e+03 -6.12720312e+03 -6.29791016e+03 -6.52754443e+03 -6.36203174e+03 -6.18186865e+03 -6.35509668e+03 -6.41561230e+03 -6.22894385e+03 -6.16840186e+03 -6.46457861e+03 -6.45868506e+03 -6.30295410e+03 -6.34158008e+03 -6.14202197e+03 -6.40612549e+03 -6.81828418e+03 -6.66101611e+03 -6.49185547e+03 -6.32550049e+03 -6.26126709e+03 -6.60595068e+03 -6.89343506e+03 -6.69826221e+03 -6.42651416e+03 -6.46183740e+03 -6.54343994e+03 -6.53884229e+03 -6.77376416e+03 -6.71602148e+03 -6.53073389e+03 -6.60635596e+03 -6.61047217e+03 -6.82784521e+03 -6.87042480e+03 -6.62987549e+03 -6.66655859e+03 -6.70288232e+03 -6.76728027e+03 -6.64389990e+03 -6.63269043e+03 -6.90436914e+03 -6.86712256e+03 -6.80316455e+03 -6.61515137e+03 -6.63767871e+03 -7.05629834e+03 -7.01532715e+03 -6.81836865e+03 -6.67730225e+03 -6.61356250e+03 -6.69355615e+03 -6.73232373e+03 -6.84989746e+03 -6.70915332e+03 -6.77833984e+03 -7.02326855e+03 -6.80446533e+03 -6.98083936e+03 -7.03583301e+03 -6.83096973e+03 -6.80010986e+03 -6.81098828e+03 -6.81063281e+03 -6.85473926e+03 -6.78338330e+03 -6.77804150e+03 -6.96468799e+03 -6.97055225e+03 -6.64597314e+03 -6.62443994e+03 -6.75936670e+03 -6.87935840e+03 -7.13027588e+03 -6.93845361e+03 -6.61145459e+03 -6.85544678e+03 -6.99189404e+03 -6.80695508e+03 -6.78619482e+03 -6.75554443e+03 -6.67186719e+03 -6.68081787e+03 -6.83202539e+03 -6.65023193e+03 -6.70116797e+03 -7.04518262e+03 -6.86148340e+03 -6.75439941e+03 -6.63329932e+03 -6.57465283e+03 -6.88370020e+03 -6.87274512e+03 -6.70151318e+03 -6.52245947e+03 -6.35771875e+03 -6.55954688e+03 -6.77335254e+03 -6.95918994e+03 -6.71325684e+03 -6.49099512e+03 -6.48736133e+03 -6.55930713e+03 -6.79570312e+03 -6.73598730e+03 -6.49860791e+03 -6.46613818e+03 -6.43303613e+03 -6.52032666e+03 -6.38999854e+03 -6.43557764e+03 -6.71073242e+03 -6.58208447e+03 -6.47240527e+03 -6.30942188e+03 -6.24139160e+03 -6.60477441e+03 -6.57195215e+03 -6.33347070e+03 -6.20246191e+03 -6.16953955e+03 -6.27779395e+03 -6.23023682e+03 -6.45566699e+03 -6.48021533e+03 -6.20273047e+03 -6.03643506e+03 -6.07217139e+03 -6.41060596e+03 -6.30051807e+03 -6.10142236e+03 -6.02766260e+03 -6.00898926e+03 -5.98629688e+03 -5.92785742e+03 -6.06199902e+03 -5.99604590e+03 -5.86566309e+03 -6.05917578e+03 -6.10465137e+03 -5.94237451e+03 -5.90521338e+03 -5.82236768e+03 -5.82069385e+03 -5.65313818e+03 -5.58832812e+03 -5.82528027e+03 -5.88941309e+03 -5.58172559e+03 -5.41890039e+03 -5.65508838e+03 -5.84795605e+03 -5.76439600e+03 -5.49986670e+03 -5.33762646e+03 -5.53815283e+03 -5.61054883e+03 -5.45825439e+03 -5.46876416e+03 -5.27779053e+03 -5.06473975e+03 -5.23648535e+03 -5.54373486e+03 -5.49407812e+03 -5.14033057e+03 -4.97595557e+03 -5.24586719e+03 -5.38599072e+03 -5.18185498e+03 -4.96651270e+03 -4.87980469e+03 -4.92735742e+03 -4.95881543e+03 -5.08202637e+03 -5.07495508e+03 -4.88042920e+03 -4.76462988e+03 -4.73248145e+03 -4.89157080e+03 -4.75779736e+03 -4.60874023e+03 -4.77165967e+03 -4.72135938e+03 -4.62308350e+03 -4.47934229e+03 -4.43820312e+03 -4.65748779e+03 -4.48117676e+03 -4.27993115e+03 -4.36355713e+03 -4.38007129e+03 -4.37557129e+03 -4.29478320e+03 -4.34589502e+03 -4.32831641e+03 -4.18516504e+03 -4.01337231e+03 -3.98414966e+03 -4.16745752e+03 -4.05172217e+03 -3.91993970e+03 -3.91560571e+03 -3.86640723e+03 -3.89892407e+03 -3.83641748e+03 -3.81264819e+03 -3.76018384e+03 -3.63468652e+03 -3.70672095e+03 -3.68968286e+03 -3.62564941e+03 -3.57598242e+03 -3.50070288e+03 -3.43863110e+03 -3.30311450e+03 -3.24169580e+03 -3.39820190e+03 -3.47825488e+03 -3.23995703e+03 -3.06538062e+03 -3.15649756e+03 -3.25273633e+03 -3.17879102e+03 -3.00427222e+03 -2.89330664e+03 -2.99150488e+03 -2.95315332e+03 -2.82789575e+03 -2.90334985e+03 -2.82211597e+03 -2.63352832e+03 -2.63426538e+03 -2.72717676e+03 -2.69839893e+03 -2.52603882e+03 -2.41665405e+03 -2.49015283e+03 -2.54026733e+03 -2.42818457e+03 -2.27728857e+03 -2.20543774e+03 -2.27665967e+03 -2.25842017e+03 -2.14635669e+03 -2.12125049e+03 -2.08976196e+03 -2.00926526e+03 -1.94424048e+03 -1.97162524e+03 -1.89814673e+03 -1.79008545e+03 -1.80414404e+03 -1.77407288e+03 -1.73468689e+03 -1.64463550e+03 -1.56507275e+03 -1.58462854e+03 -1.50426697e+03 -1.43043347e+03 -1.48254309e+03 -1.43198352e+03 -1.39633997e+03 -1.66113928e+03 -1.49052258e+03 -1.74712634e+03 -1.83428809e+03 -1.87897437e+03 -1.32573071e+03 -1.36636646e+03 -1.97811353e+03 -2.16246167e+03 -6.29304750e+05 -2.64252625e+05 -1.97808844e+05 4.81136375e+05 951473920. 0. 0. 0. 0. 0. 0. -219605696. -219605696. -3.08545406e+05 -1175630720. -1175630720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 391148160. 1.60673500e+05 -1.16610180e+05 2.14819971e+03 2.01208521e+03 1.35746497e+03 1.21469116e+03 1.25843103e+03 1.07407800e+03 1.10970630e+03 1.10624097e+03 1.10194739e+03 1.14601843e+03 1.19075537e+03 1.24357703e+03 1.27400073e+03 1.30912866e+03 1.39066809e+03 1.43946252e+03 1.47682898e+03 1.52533118e+03 1.52500403e+03 1.57196045e+03 1.66210022e+03 1.69710278e+03 1.72166626e+03 1.81971875e+03 1.92083228e+03 1.90261206e+03 1.89973303e+03 1.94897839e+03 1.98050708e+03 2.07225806e+03 2.15669580e+03 2.16795410e+03 2.20718921e+03 2.29528491e+03 2.31157349e+03 2.30369116e+03 2.36072290e+03 2.40207861e+03 2.45953442e+03 2.57327686e+03 2.56679663e+03 2.57334912e+03 2.69239526e+03 2.69624316e+03 2.70135645e+03 2.75019751e+03 2.80138965e+03 2.88469897e+03 2.95151733e+03 3.01727271e+03 3.00938672e+03 3.00724048e+03 3.11281909e+03 3.10225098e+03 3.08288330e+03 3.22336597e+03 3.26689917e+03 3.28594800e+03 3.38861133e+03 3.42377759e+03 3.39356787e+03 3.43783643e+03 3.47954688e+03 3.48509204e+03 3.57155884e+03 3.63840161e+03 3.70142383e+03 3.75079102e+03 3.73535132e+03 3.78272485e+03 3.81103149e+03 3.86836255e+03 3.90163818e+03 3.95206934e+03 4.11590967e+03 4.03976978e+03 3.92710205e+03 4.09847656e+03 4.13310010e+03 4.11615039e+03 4.25096436e+03 4.25533887e+03 4.26976465e+03 4.41358936e+03 4.47898340e+03 4.37216406e+03 4.32830078e+03 4.38983252e+03 4.46676123e+03 4.57944873e+03 4.62948438e+03 4.68384131e+03 4.73515430e+03 4.72770898e+03 4.67311572e+03 4.66290039e+03 4.80785596e+03 4.82989551e+03 4.79819629e+03 4.93043896e+03 4.94238525e+03 4.92574268e+03 5.05210498e+03 5.03180078e+03 4.90309180e+03 4.99256689e+03 5.18356641e+03 5.21723047e+03 5.18396631e+03 5.24151318e+03 5.30959717e+03 5.35579883e+03 5.36735400e+03 5.24958301e+03 5.23414258e+03 5.45260205e+03 5.50667188e+03 5.41469385e+03 5.49874805e+03 5.47728564e+03 5.47689648e+03 5.61392822e+03 5.59581787e+03 5.54076465e+03 5.62580322e+03 5.76101172e+03 5.80204492e+03 5.75768164e+03 5.65378223e+03 5.63145703e+03 5.81101953e+03 5.93554492e+03 5.79324512e+03 5.83365137e+03 6.06698877e+03 6.04768213e+03 5.98738232e+03 5.95526611e+03 5.86903223e+03 5.84631592e+03 5.94934424e+03 6.12437354e+03 6.12888379e+03 6.10751562e+03 6.18590967e+03 6.22348438e+03 6.14848584e+03 6.03773096e+03 6.10397705e+03 6.26647412e+03 6.34633594e+03 6.42477002e+03 6.38532666e+03 6.31190430e+03 6.24374707e+03 6.35420459e+03 6.43029395e+03 6.22327734e+03 6.24251807e+03 6.47537061e+03 6.57123828e+03 6.43717773e+03 6.39159424e+03 6.37833740e+03 6.34238135e+03 6.48955615e+03 6.66965137e+03 6.65554883e+03 6.54221045e+03 6.55767529e+03 6.59523242e+03 6.53503174e+03 6.52386377e+03 6.59220410e+03 6.56245850e+03 6.75209570e+03 6.84361279e+03 6.54302734e+03 6.58976221e+03 6.63129102e+03 6.67127197e+03 6.80259033e+03 6.62134277e+03 6.54882666e+03 6.74902246e+03 6.83548242e+03 6.79044434e+03 6.74321924e+03 6.68722949e+03 6.65230762e+03 6.74688428e+03 6.84926465e+03 6.83962598e+03 6.68428125e+03 6.82457324e+03 6.95464893e+03 6.83331396e+03 6.80015771e+03 6.75444189e+03 6.76921191e+03 6.91679688e+03 6.82773779e+03 6.79235498e+03 6.95842529e+03 6.74699365e+03 6.70740137e+03 6.89842578e+03 6.72335889e+03 6.77585693e+03 6.96134033e+03 6.90642529e+03 6.91529590e+03 6.79466650e+03 6.81801172e+03 6.80264111e+03 6.80691357e+03 6.92696973e+03 6.78211475e+03 6.66639062e+03 6.89123828e+03 6.94896436e+03 6.77310352e+03 6.85295166e+03 6.93894922e+03 6.70446826e+03 6.82713379e+03 6.96684912e+03 6.74642725e+03 6.69493701e+03 6.77522998e+03 6.77079492e+03 6.71437500e+03 6.73034277e+03 6.70367529e+03 6.75659473e+03 6.83141113e+03 6.78096924e+03 6.75348145e+03 6.73051758e+03 6.67808398e+03 6.65809863e+03 6.78620508e+03 6.60711426e+03 6.56482373e+03 6.77310742e+03 6.66019434e+03 6.51506836e+03 6.60856543e+03 6.56992236e+03 6.51194336e+03 6.53909863e+03 6.57216699e+03 6.62874121e+03 6.57927881e+03 6.56496289e+03 6.58363330e+03 6.40106104e+03 6.43191455e+03 6.46144287e+03 6.36787793e+03 6.49640967e+03 6.58157764e+03 6.37270312e+03 6.26385986e+03 6.30648682e+03 6.47034326e+03 6.37493945e+03 6.12549219e+03 6.26858301e+03 6.40961084e+03 6.24827197e+03 6.22692188e+03 6.18454883e+03 6.12696191e+03 6.18147705e+03 6.09740918e+03 6.05238330e+03 6.18132275e+03 6.19265967e+03 6.06618799e+03 6.08825732e+03 6.06422510e+03 6.07848096e+03 5.92813037e+03 5.76341943e+03 5.92961523e+03 6.04630762e+03 5.82483740e+03 5.76807080e+03 5.79355078e+03 5.85839795e+03 5.82788428e+03 5.61060352e+03 5.73243750e+03 5.81260547e+03 5.69462012e+03 5.65646631e+03 5.59055811e+03 5.50593018e+03 5.54440674e+03 5.54885010e+03 5.46936475e+03 5.56308301e+03 5.52830713e+03 5.44207129e+03 5.46661182e+03 5.39575293e+03 5.27084619e+03 5.23814990e+03 5.30179102e+03 5.31914355e+03 5.19477930e+03 5.10926660e+03 5.07062012e+03 5.08217432e+03 5.14604443e+03 5.10762744e+03 4.96868799e+03 4.90780566e+03 5.00592383e+03 5.04326416e+03 4.88968604e+03 4.77593750e+03 4.74757227e+03 4.78672754e+03 4.75593701e+03 4.68594482e+03 4.73971533e+03 4.69018750e+03 4.61034326e+03 4.66801562e+03 4.60995410e+03 4.47852197e+03 4.43711035e+03 4.45426123e+03 4.43015381e+03 4.26621240e+03 4.18705811e+03 4.26086963e+03 4.27873633e+03 4.29315625e+03 4.20359814e+03 4.06422363e+03 4.13894775e+03 4.14758643e+03 3.96384888e+03 3.89043628e+03 3.95975122e+03 3.99336890e+03 3.89138818e+03 3.76176978e+03 3.70323120e+03 3.71270581e+03 3.74977441e+03 3.75971191e+03 3.69845215e+03 3.56148657e+03 3.49477759e+03 3.48738989e+03 3.42295435e+03 3.39330762e+03 3.35973169e+03 3.30608545e+03 3.29404370e+03 3.26819141e+03 3.21064990e+03 3.13492554e+03 3.12110278e+03 3.17389990e+03 3.09547388e+03 2.94141479e+03 2.89154370e+03 2.91320630e+03 2.91147241e+03 2.89001587e+03 2.79333691e+03 2.65722266e+03 2.63684424e+03 2.66823413e+03 2.66091113e+03 2.61416211e+03 2.50940356e+03 2.44039282e+03 2.43144629e+03 2.37251782e+03 2.34776099e+03 2.29509521e+03 2.18922900e+03 2.20540918e+03 2.20584570e+03 2.12325269e+03 2.04232349e+03 1.95562695e+03 1.94837793e+03 1.99922229e+03 1.93589453e+03 1.81075964e+03 1.79870288e+03 1.78950537e+03 1.68790295e+03 1.62653821e+03 1.56760083e+03 1.53455896e+03 1.54417822e+03 1.48613440e+03 1.39427698e+03 1.36212158e+03 1.34373901e+03 1.27990527e+03 1.22909705e+03 1.20421497e+03 1.14099084e+03 1.07757935e+03 1.04129297e+03 9.94385437e+02 9.63072632e+02 9.16256104e+02 8.60266174e+02 8.13621033e+02 7.48390015e+02 7.04072266e+02 6.64856873e+02 6.16700195e+02 5.79798706e+02 5.30852417e+02 4.79540192e+02 4.25151978e+02 3.75400604e+02 3.33098541e+02 2.87443115e+02 2.38291000e+02 1.85780655e+02 1.38715775e+02 9.27909088e+01 4.58236580e+01 3.84470403e-01 -4.72328072e+01 -9.48117905e+01 -1.46348251e+02 -1.96114319e+02 -2.41253174e+02 -2.89316711e+02 -3.32131073e+02 -3.77029724e+02 -4.38296875e+02 -4.92012878e+02 -5.17405273e+02 -5.57399963e+02 -6.22650330e+02 -6.80910400e+02 -7.27455750e+02 -7.59930359e+02 -7.96549622e+02 -8.54523315e+02 -9.15312134e+02 -9.57636230e+02 -9.90158875e+02 -1.04243994e+03 -1.09833179e+03 -1.14000232e+03 -1.19672290e+03 -1.24826514e+03 -1.28301672e+03 -1.33440454e+03 -1.38397278e+03 -1.43180859e+03 -1.46590308e+03 -1.49716211e+03 -1.55859021e+03 -1.61805347e+03 -1.66796936e+03 -1.69302258e+03 -1.72621350e+03 -1.80831189e+03 -1.85749036e+03 -1.88894104e+03 -1.95165625e+03 -1.95500659e+03 -1.98345374e+03 -2.11361353e+03 -2.14627246e+03 -2.11460376e+03 -2.21866382e+03 -2.28104712e+03 -2.25295703e+03 -2.35257153e+03 -2.41351343e+03 -2.39017261e+03 -2.49342261e+03 -2.56162207e+03 -2.52916870e+03 -2.59896094e+03 -2.67424756e+03 -2.69340112e+03 -2.75115894e+03 -2.77594727e+03 -2.76183716e+03 -2.83972925e+03 -2.93346045e+03 -3.00048511e+03 -3.05708374e+03 -3.03090747e+03 -3.08405225e+03 -3.11152441e+03 -3.08917139e+03 -3.22572754e+03 -3.29068677e+03 -3.26947412e+03 -3.37276392e+03 -3.38921655e+03 -3.36370142e+03 -3.46982568e+03 -3.55558057e+03 -3.59793750e+03 -3.58705908e+03 -3.60043335e+03 -3.59100391e+03 -3.73209326e+03 -3.88935254e+03 -3.77182349e+03 -3.80726636e+03 -3.82428247e+03 -3.87261230e+03 -4.02778979e+03 -3.95298145e+03 -3.94172803e+03 -4.07112451e+03 -4.15932568e+03 -4.14805908e+03 -4.07262427e+03 -4.18701123e+03 -4.31850781e+03 -4.29970557e+03 -4.34850879e+03 -4.32271143e+03 -4.36323926e+03 -4.49599707e+03 -4.51258398e+03 -4.57708154e+03 -4.51612695e+03 -4.49603955e+03 -4.60777637e+03 -4.65581641e+03 -4.73275439e+03 -4.73942188e+03 -4.67943164e+03 -4.75326270e+03 -4.87517920e+03 -4.91485645e+03 -4.90140771e+03 -4.92180811e+03 -4.94386475e+03 -5.03371777e+03 -5.02458838e+03 -4.97815918e+03 -5.13322559e+03 -5.18336084e+03 -5.13167480e+03 -5.25206055e+03 -5.24097900e+03 -5.17909668e+03 -5.25462207e+03 -5.25238916e+03 -5.31467285e+03 -5.42026709e+03 -5.38529102e+03 -5.34213477e+03 -5.42518750e+03 -5.48081885e+03 -5.51158740e+03 -5.68167480e+03 -5.59905518e+03 -5.49564502e+03 -5.61445801e+03 -5.58078271e+03 -5.63000830e+03 -5.68906006e+03 -5.74573389e+03 -5.84766553e+03 -5.74336377e+03 -5.82958057e+03 -5.82286914e+03 -5.74046289e+03 -5.83750586e+03 -5.97796045e+03 -6.01419287e+03 -5.92769775e+03 -5.93239795e+03 -6.05219629e+03 -6.03187109e+03 -6.00672070e+03 -6.04343896e+03 -6.07024561e+03 -6.20847754e+03 -6.15594482e+03 -6.14544287e+03 -6.22153418e+03 -6.13222998e+03 -6.12974219e+03 -6.34276611e+03 -6.37190039e+03 -6.25979932e+03 -6.26715527e+03 -6.20187256e+03 -6.25803564e+03 -6.54935156e+03 -6.44096826e+03 -6.30762842e+03 -6.58569629e+03 -6.63717139e+03 -6.56763086e+03 -6.37797998e+03 -6.45991357e+03 -6.79737061e+03 -7.46445654e+03 -7.30922412e+03 -1.61196387e+04 -2.11617266e+04 3559672. 3.86196375e+06 20270600. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -181644528. -4717116. -2.69870801e+04 -1.47211025e+04 -7.33157178e+03 -9.31232715e+03 -1.19626475e+04 -1.05661094e+04 -9.33731152e+03 -9.08968750e+03 -6.77585791e+03 -6.87963818e+03 -7.12008594e+03 -6.96239502e+03 -6.82595605e+03 -6.75370117e+03 -6.81221387e+03 -6.97044385e+03 -6.91163672e+03 -6.75066846e+03 -6.59863965e+03 -6.79789160e+03 -6.83713086e+03 -6.78408691e+03 -6.83499170e+03 -6.66323535e+03 -6.63762451e+03 -6.77084180e+03 -6.77528271e+03 -6.74440479e+03 -6.52993213e+03 -6.49695947e+03 -6.81567285e+03 -6.94769189e+03 -6.74481348e+03 -6.42777344e+03 -6.41597314e+03 -6.65204150e+03 -6.68724609e+03 -6.60674170e+03 -6.46735693e+03 -6.62080078e+03 -6.69631299e+03 -6.62611816e+03 -6.56377686e+03 -6.30947559e+03 -6.38608887e+03 -6.73151611e+03 -6.56988477e+03 -6.51284033e+03 -6.42132275e+03 -6.28475488e+03 -6.35284473e+03 -6.56198438e+03 -6.47626562e+03 -6.21128955e+03 -6.36127002e+03 -6.39123535e+03 -6.31266211e+03 -6.30495654e+03 -6.13068604e+03 -6.23837012e+03 -6.35399756e+03 -6.18213477e+03 -6.10892773e+03 -6.01835791e+03 -6.12211377e+03 -6.32633252e+03 -6.25353809e+03 -6.09647119e+03 -5.93853760e+03 -5.97518115e+03 -5.95359424e+03 -6.02947559e+03 -6.08215918e+03 -5.84834326e+03 -5.87253174e+03 -6.02936670e+03 -5.95866943e+03 -5.82773730e+03 -5.64006543e+03 -5.72243994e+03 -5.91025537e+03 -5.86001660e+03 -5.73795166e+03 -5.56732422e+03 -5.54783154e+03 -5.66701807e+03 -5.76018213e+03 -5.55789404e+03 -5.38874512e+03 -5.56880420e+03 -5.54209082e+03 -5.42751221e+03 -5.56552002e+03 -5.39790820e+03 -5.31664990e+03 -5.40204004e+03 -5.36389355e+03 -5.36412793e+03 -5.19532227e+03 -5.11134668e+03 -5.17508398e+03 -5.26787891e+03 -5.25923730e+03 -5.07816748e+03 -5.09104932e+03 -5.07012891e+03 -4.99149463e+03 -5.01597656e+03 -4.89314893e+03 -4.86460986e+03 -4.97580273e+03 -4.94107910e+03 -4.75046777e+03 -4.58607178e+03 -4.71145654e+03 -4.90929590e+03 -4.81370264e+03 -4.65687500e+03 -4.49590674e+03 -4.48072559e+03 -4.55652686e+03 -4.57215869e+03 -4.54118945e+03 -4.38636328e+03 -4.34937109e+03 -4.32398682e+03 -4.31918359e+03 -4.38691650e+03 -4.18825195e+03 -4.14352197e+03 -4.27976123e+03 -4.14515625e+03 -4.06870288e+03 -4.03065991e+03 -4.01050610e+03 -4.05509497e+03 -3.97425195e+03 -3.83156079e+03 -3.73177734e+03 -3.81417310e+03 -3.93614893e+03 -3.83869702e+03 -3.69515918e+03 -3.58121118e+03 -3.57436792e+03 -3.59861865e+03 -3.59999609e+03 -3.54864893e+03 -3.36842236e+03 -3.31580884e+03 -3.39557129e+03 -3.40059863e+03 -3.38823315e+03 -3.24756152e+03 -3.17608301e+03 -3.15117139e+03 -3.11958130e+03 -3.14037915e+03 -3.01059741e+03 -2.96837231e+03 -2.97777026e+03 -2.90895728e+03 -2.88324365e+03 -2.78102734e+03 -2.77344287e+03 -2.78283130e+03 -2.68549756e+03 -2.66451050e+03 -2.59522290e+03 -2.54798560e+03 -2.55351294e+03 -2.50558618e+03 -2.42496973e+03 -2.33379370e+03 -2.30041382e+03 -2.31923608e+03 -2.32669165e+03 -2.24290210e+03 -2.09851953e+03 -2.04132178e+03 -2.07687329e+03 -2.07404395e+03 -2.00606201e+03 -1.87716760e+03 -1.85841174e+03 -1.85581543e+03 -1.79434680e+03 -1.76094116e+03 -1.67641541e+03 -1.63415906e+03 -1.61413049e+03 -1.57582776e+03 -1.53390845e+03 -1.45933704e+03 -1.41715405e+03 -1.37170447e+03 -1.32780994e+03 -1.30700964e+03 -1.23612073e+03 -1.18141809e+03 -1.13685754e+03 -1.07953284e+03 -1.02749487e+03 -9.84699768e+02 -9.67180298e+02 -9.30479736e+02 -8.71147156e+02 -7.99459290e+02 -7.27396057e+02 -7.04479309e+02 -6.91911926e+02 -6.41555603e+02 -5.77325195e+02 -5.11619415e+02 -4.59483276e+02 -4.26204590e+02 -3.92109070e+02 -3.40574158e+02 -2.87440552e+02 -2.41129547e+02 -1.90866638e+02 -1.42494202e+02 -9.37626266e+01 -4.49429779e+01 2.17676497e+00 5.05672493e+01 9.97771072e+01 1.48399170e+02 1.85576416e+02 2.38814224e+02 2.92252289e+02 3.30162231e+02 3.82419739e+02 4.31090149e+02 4.91054657e+02 5.36288208e+02 5.57074280e+02 5.97413940e+02 6.57091064e+02 7.34477478e+02 8.05827881e+02 8.34736206e+02 8.39250488e+02 8.62250000e+02 9.25494446e+02 1.02589673e+03 1.10147400e+03 1.12602588e+03 1.10945581e+03 1.14718750e+03 1.27976562e+03 1.31808142e+03 1.29240723e+03 1.34390674e+03 1.42451208e+03 1.47332104e+03 1.56216248e+03 1.57310083e+03 1.55270361e+03 1.64992554e+03 1.67242773e+03 1.74275232e+03 1.83894641e+03 1.80252783e+03 1.88395276e+03 1.98821777e+03 1.99020215e+03 2.02506787e+03 2.05617407e+03 2.13539136e+03 2.17605420e+03 2.18385059e+03 2.19004883e+03 2.24023755e+03 2.39784399e+03 2.51043848e+03 2.48779468e+03 2.42443188e+03 2.42232471e+03 2.49341772e+03 2.64674365e+03 2.79581616e+03 2.76258643e+03 2.66009204e+03 2.73119067e+03 2.87540601e+03 2.88586060e+03 2.89039478e+03 2.94455981e+03 2.95797754e+03 3.02859888e+03 3.19803687e+03 3.15048682e+03 3.10762500e+03 3.21006323e+03 3.15816870e+03 3.28993848e+03 3.44480786e+03 3.36172632e+03 3.48159204e+03 3.50653149e+03 3.40574731e+03 3.53006909e+03 3.47974512e+03 3.60618457e+03 3.89826660e+03 3.72440942e+03 3.57181006e+03 3.70550391e+03 3.91256494e+03 4.07222241e+03 4.03612183e+03 3.84780762e+03 3.79594287e+03 3.92665894e+03 4.10336035e+03 4.33388525e+03 4.27207568e+03 4.03930884e+03 4.09429346e+03 4.27685840e+03 4.37380469e+03 4.27812061e+03 4.28221094e+03 4.37001172e+03 4.41621533e+03 4.62695264e+03 4.67272998e+03 4.44584033e+03 4.45744531e+03 4.58956885e+03 4.63734766e+03 4.69572705e+03 4.71782617e+03 4.87838916e+03 4.82366406e+03 4.67553516e+03 4.83126660e+03 4.75040283e+03 4.92576318e+03 5.26160400e+03 4.99212012e+03 4.72641211e+03 4.90552295e+03 5.20974365e+03 5.36717139e+03 5.35582324e+03 5.08671777e+03 4.95742676e+03 5.09804297e+03 5.34864355e+03 5.60251953e+03 5.50695850e+03 5.20321631e+03 5.19247070e+03 5.42574023e+03 5.48064893e+03 5.62673486e+03 5.68396924e+03 5.38066553e+03 5.41854688e+03 5.66046387e+03 5.73391113e+03 5.66552246e+03 5.64649170e+03 5.62963330e+03 5.57893311e+03 5.93832617e+03 5.96810547e+03 5.73899316e+03 5.74176562e+03 5.73618994e+03 5.79445020e+03 5.88785938e+03 5.89466992e+03 6.13281494e+03 6.15685791e+03 5.92693213e+03 5.86866846e+03 5.79341748e+03 6.05345801e+03 6.41493408e+03 6.27446533e+03 5.96073242e+03 5.89392285e+03 6.15190430e+03 6.44713525e+03 6.23522266e+03 5.92047314e+03 6.11462598e+03 6.30491357e+03 6.42542627e+03 6.64986865e+03 6.48393701e+03 6.16097070e+03 6.13609912e+03 6.33564697e+03 6.46597705e+03 6.51080713e+03 6.43927588e+03 6.43493066e+03 6.44171826e+03 6.57695508e+03 6.49586377e+03 6.33663672e+03 6.40087158e+03 6.43326904e+03 6.72160254e+03 6.77200391e+03 6.57987939e+03 6.61393457e+03 6.63241162e+03 6.67384375e+03 6.49940430e+03 6.39845459e+03 6.69070215e+03 6.98948828e+03 6.78391846e+03 6.46989160e+03 6.54374121e+03 6.86443359e+03 6.95778271e+03 6.84063086e+03 6.71404443e+03 6.56470898e+03 6.61836768e+03 6.84188184e+03 6.82524365e+03 6.69719238e+03 6.56403955e+03 6.54814893e+03 6.88286230e+03 7.17506445e+03 6.79790137e+03 6.61077734e+03 6.80671680e+03 6.79269678e+03 7.01556299e+03 6.97675293e+03 6.59742090e+03 6.65084863e+03 6.87857861e+03 6.82663721e+03 6.84628418e+03 6.80644287e+03 6.94326172e+03 7.20379297e+03 7.12059082e+03 7.36071387e+03 8.89917188e+03 8.44074023e+03 1.07013555e+04 1.03452393e+04 1.56207451e+04 2.04756777e+04 7.16612050e+06 24705494. 29251180. 3860606. 6.60897950e+06 47075812. 2126702. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 28241116. 2.45838250e+06 2.74274414e+04 1.73062715e+04 1.13054805e+04 1.04599023e+04 8.16789648e+03 7.74105713e+03 6.70285840e+03 6.80478564e+03 6.25902930e+03 6.38321240e+03 6.37096582e+03 6.20773926e+03 6.19655664e+03 6.18896094e+03 6.13172949e+03 6.10474805e+03 6.05147021e+03 5.99126270e+03 6.02975293e+03 5.97685938e+03 6.00635791e+03 6.04624609e+03 5.78549512e+03 5.75919482e+03 6.07995166e+03 6.04264551e+03 5.85042676e+03 5.81567969e+03 5.83521680e+03 5.78320215e+03 5.72708447e+03 5.72145752e+03 5.69473096e+03 5.65712988e+03 5.55623535e+03 5.52974219e+03 5.68269336e+03 5.67967627e+03 5.52799854e+03 5.48879541e+03 5.47625537e+03 5.45746973e+03 5.39991797e+03 5.36033838e+03 5.39007861e+03 5.25920557e+03 5.17787891e+03 5.19771826e+03 5.18186523e+03 5.36826855e+03 5.34631055e+03 5.11729053e+03 4.96691797e+03 4.93408984e+03 5.18740576e+03 5.19686182e+03 4.98533350e+03 4.84963135e+03 4.81039453e+03 4.89406299e+03 4.86072754e+03 4.92392627e+03 4.91285889e+03 4.62118994e+03 4.49662842e+03 4.69871826e+03 4.86116260e+03 4.70777979e+03 4.56403711e+03 4.52707129e+03 4.47569336e+03 4.43388086e+03 4.41890576e+03 4.36620947e+03 4.31025342e+03 4.31171582e+03 4.28219043e+03 4.22692920e+03 4.17422168e+03 4.27229443e+03 4.25085742e+03 4.10251904e+03 4.01797852e+03 3.99820801e+03 4.02174805e+03 3.99328540e+03 3.90419775e+03 3.86656274e+03 3.75655249e+03 3.65219971e+03 3.77807275e+03 3.72620239e+03 3.50651294e+03 3.52231738e+03 3.67219727e+03 3.75260669e+03 3.59647241e+03 3.46189648e+03 3.37548169e+03 3.32917725e+03 3.31844043e+03 3.27692261e+03 3.23617603e+03 3.17598364e+03 3.24565430e+03 3.21210205e+03 3.06414746e+03 3.01600806e+03 2.89903833e+03 2.89538525e+03 3.02005713e+03 2.93730176e+03 2.82439185e+03 2.72643628e+03 2.64977393e+03 2.73163647e+03 2.73666357e+03 2.63099976e+03 2.51059326e+03 2.45320947e+03 2.45693042e+03 2.41850952e+03 2.45585620e+03 2.42667383e+03 2.29807373e+03 2.22123462e+03 2.17254248e+03 2.17799731e+03 2.14803857e+03 2.07372266e+03 2.01091357e+03 1.96951917e+03 1.92330969e+03 1.81874695e+03 1.80013684e+03 1.85871045e+03 1.79194385e+03 1.70058850e+03 1.61006238e+03 1.55826135e+03 1.60497229e+03 1.56014404e+03 1.46481140e+03 1.38858350e+03 1.34005981e+03 1.32935046e+03 1.27374963e+03 1.23287769e+03 1.16050195e+03 1.13300452e+03 1.15319788e+03 1.07645520e+03 9.98299316e+02 9.54480042e+02 9.07686279e+02 8.55865662e+02 8.09505371e+02 7.56179626e+02 7.05118774e+02 6.61219116e+02 5.98514221e+02 5.60809570e+02 5.45922363e+02 4.77090973e+02 4.14829895e+02 3.78250397e+02 3.30407684e+02 2.92830261e+02 2.41101425e+02 1.85270813e+02 1.44194946e+02 9.62876587e+01 4.70006981e+01 1.21247582e-02 -4.68698807e+01 -9.45552826e+01 -1.42514847e+02 -1.88341248e+02 -2.30851196e+02 -2.87617584e+02 -3.51992950e+02 -3.93569427e+02 -4.32529297e+02 -4.65815765e+02 -5.08654938e+02 -5.87506531e+02 -6.42502075e+02 -6.73805847e+02 -6.99356445e+02 -7.38783142e+02 -8.09250916e+02 -8.61100159e+02 -9.28414978e+02 -9.63116699e+02 -9.84198059e+02 -1.04072192e+03 -1.08289270e+03 -1.17041467e+03 -1.21622400e+03 -1.22176514e+03 -1.27828064e+03 -1.32784521e+03 -1.36678882e+03 -1.37257324e+03 -1.45226892e+03 -1.59133496e+03 -1.60401245e+03 -1.60732520e+03 -1.61311304e+03 -1.64513257e+03 -1.79403223e+03 -1.85170898e+03 -1.83959619e+03 -1.84333557e+03 -1.88006738e+03 -1.98030225e+03 -2.02874988e+03 -2.11882764e+03 -2.15042310e+03 -2.14373608e+03 -2.17062329e+03 -2.20416553e+03 -2.35212646e+03 -2.39707251e+03 -2.37186914e+03 -2.39742529e+03 -2.43414966e+03 -2.57290210e+03 -2.62453125e+03 -2.53287598e+03 -2.57624268e+03 -2.76931372e+03 -2.80762354e+03 -2.71329102e+03 -2.75041333e+03 -2.93599072e+03 -3.00386938e+03 -2.94651782e+03 -2.92031445e+03 -2.97187280e+03 -3.17389038e+03 -3.16735986e+03 -3.11931079e+03 -3.23290430e+03 -3.27507739e+03 -3.27927026e+03 -3.29129150e+03 -3.35166382e+03 -3.30544800e+03 -3.43825171e+03 -3.68264331e+03 -3.61104395e+03 -3.59878320e+03 -3.65985620e+03 -3.67326050e+03 -3.71039575e+03 -3.74137183e+03 -3.78674805e+03 -3.73805054e+03 -3.71880737e+03 -3.85590112e+03 -3.98575684e+03 -4.13592578e+03 -4.03572485e+03 -3.92205151e+03 -4.07277466e+03 -4.16112256e+03 -4.34193604e+03 -4.32983154e+03 -4.22899609e+03 -4.18530127e+03 -4.19178516e+03 -4.35774707e+03 -4.40583984e+03 -4.53456396e+03 -4.57680615e+03 -4.51909473e+03 -4.47429688e+03 -4.37665967e+03 -4.56062305e+03 -4.85429590e+03 -4.84441504e+03 -4.74475342e+03 -4.63642334e+03 -4.60843457e+03 -4.87389014e+03 -5.04854541e+03 -4.94051709e+03 -4.80102002e+03 -4.83292578e+03 -4.98299023e+03 -5.02118652e+03 -5.19472412e+03 -5.23054736e+03 -5.10655371e+03 -5.07914502e+03 -5.09355127e+03 -5.28225684e+03 -5.33839697e+03 -5.13986182e+03 -5.16563184e+03 -5.48007617e+03 -5.45732959e+03 -5.20598828e+03 -5.31323877e+03 -5.61749365e+03 -5.61552100e+03 -5.53127734e+03 -5.40806006e+03 -5.39197705e+03 -5.73522852e+03 -5.79636719e+03 -5.66366309e+03 -5.53218750e+03 -5.52538477e+03 -5.69151416e+03 -5.75618799e+03 -5.79673682e+03 -5.64182080e+03 -5.78517090e+03 -6.13004541e+03 -6.00327490e+03 -5.95798145e+03 -5.99900391e+03 -5.95672217e+03 -5955. -5.98871289e+03 -6.03389795e+03 -6.03112109e+03 -5.98235400e+03 -5.84825537e+03 -6.04604492e+03 -6.35565674e+03 -6.09913623e+03 -5.95610547e+03 -6.17392432e+03 -6.26119336e+03 -6.48272510e+03 -6.39578027e+03 -6.18957471e+03 -6.35994824e+03 -6.38873975e+03 -6.20340381e+03 -6.17576025e+03 -6.51482568e+03 -6.47885986e+03 -6.32892236e+03 -6.23918457e+03 -6.12159717e+03 -6.41287549e+03 -6.82547803e+03 -6.67991455e+03 -6.45348389e+03 -6.33218945e+03 -6.29635596e+03 -6.65324854e+03 -6.81617920e+03 -6.64734082e+03 -6.43620068e+03 -6.42985010e+03 -6.51341602e+03 -6.60745459e+03 -6.80024951e+03 -6.76762646e+03 -6.60828711e+03 -6.61835205e+03 -6.60895947e+03 -6.77862842e+03 -6.84362012e+03 -6.72452246e+03 -6.66000830e+03 -6.63261230e+03 -6.74846924e+03 -6.60746729e+03 -6.63244434e+03 -6.93819971e+03 -6.88986377e+03 -6.79522900e+03 -6.66214209e+03 -6.57524414e+03 -7.01066895e+03 -7.00708350e+03 -6.80674219e+03 -6.68104639e+03 -6.63675781e+03 -6.72571826e+03 -6.76473047e+03 -6.80850879e+03 -6.70766992e+03 -6.81968994e+03 -7.07730664e+03 -6.87233350e+03 -6.93373584e+03 -6.98256543e+03 -6.86334814e+03 -6.83404883e+03 -6.74140039e+03 -6.78202783e+03 -6.83468262e+03 -6.83931104e+03 -6.81835889e+03 -6.90323047e+03 -6.94886328e+03 -6.68724170e+03 -6.59448096e+03 -6.75645801e+03 -6.87228174e+03 -7.07043164e+03 -6.89464062e+03 -6.70954053e+03 -6.92949463e+03 -6.88511719e+03 -6.78050488e+03 -6.79912451e+03 -6.77259912e+03 -6.70895752e+03 -6.69710107e+03 -6.77652539e+03 -6.59190234e+03 -6.69982861e+03 -7.00846143e+03 -6.86364844e+03 -6.78618555e+03 -6.67467188e+03 -6.53371094e+03 -6.87503467e+03 -6.87355615e+03 -6.72669873e+03 -6.54362256e+03 -6.40823096e+03 -6.60134814e+03 -6.70421826e+03 -6.90299609e+03 -6.68159326e+03 -6.47859277e+03 -6.56908838e+03 -6.53841162e+03 -6.74766455e+03 -6.70785791e+03 -6.47846436e+03 -6.50717334e+03 -6.46309082e+03 -6.51065332e+03 -6.34260986e+03 -6.43315723e+03 -6.75003613e+03 -6.62798730e+03 -6.50138086e+03 -6.31402783e+03 -6.19787598e+03 -6.56663525e+03 -6.57938721e+03 -6.34231982e+03 -6.17198975e+03 -6.16151904e+03 -6.32556201e+03 -6.29695361e+03 -6.42334863e+03 -6.42235010e+03 -6.23339355e+03 -6.09233447e+03 -6.02343408e+03 -6.34869385e+03 -6.30871338e+03 -6.07896387e+03 -6.09544141e+03 -6.09535205e+03 -5.99432178e+03 -5.97422852e+03 -6.12004102e+03 -5.93685449e+03 -5.79596680e+03 -6.11387158e+03 -6.11733545e+03 -5.92744531e+03 -5.86108154e+03 -5.83072949e+03 -5.83622559e+03 -5.64074072e+03 -5.57880029e+03 -5.86778223e+03 -5.87139551e+03 -5.53391650e+03 -5.42375635e+03 -5.68070068e+03 -5.87568555e+03 -5.72354102e+03 -5.47057666e+03 -5.39977441e+03 -5.59341650e+03 -5.54074805e+03 -5.39581885e+03 -5.45837207e+03 -5.30658203e+03 -5.11547510e+03 -5.29453662e+03 -5.52339893e+03 -5.42472314e+03 -5.15244043e+03 -5.04453711e+03 -5.26249121e+03 -5.35196484e+03 -5.15827197e+03 -4.98408057e+03 -4.94052686e+03 -4.97828662e+03 -4.95404688e+03 -5.08850439e+03 -4.98998486e+03 -4.77353467e+03 -4.84386035e+03 -4.84702344e+03 -4.85501660e+03 -4.71416602e+03 -4.58939551e+03 -4.74665479e+03 -4.72155225e+03 -4.60396436e+03 -4.44822168e+03 -4.47076074e+03 -4.68750684e+03 -4.47495703e+03 -4.32097412e+03 -4.39356543e+03 -4.33659717e+03 -4.33397754e+03 -4.29796680e+03 -4.33822119e+03 -4.33427588e+03 -4.18162305e+03 -4.00834058e+03 -3.98599634e+03 -4.17243018e+03 -4.05131201e+03 -3.90294971e+03 -3.94057397e+03 -3.90028833e+03 -3.87632788e+03 -3.83059741e+03 -3.84564502e+03 -3.73010498e+03 -3.59782812e+03 -3.70909351e+03 -3.67996069e+03 -3.60492285e+03 -3.57235254e+03 -3.50944141e+03 -3.46993945e+03 -3.33291602e+03 -3.25025195e+03 -3.39524390e+03 -3.42512183e+03 -3.20692383e+03 -3.07127271e+03 -3.17973511e+03 -3.26429956e+03 -3.14732812e+03 -2.98939990e+03 -2.90512524e+03 -2.98484937e+03 -2.96035303e+03 -2.84844653e+03 -2.87627295e+03 -2.82595898e+03 -2.69329248e+03 -2.64473926e+03 -2.67986353e+03 -2.67764282e+03 -2.51898462e+03 -2.43179980e+03 -2.51754102e+03 -2.51302222e+03 -2.40000122e+03 -2.26992554e+03 -2.21611890e+03 -2.29728589e+03 -2.26778418e+03 -2.14429810e+03 -2.09026343e+03 -2.06014746e+03 -2.00093933e+03 -1.94598889e+03 -1.97843201e+03 -1.89324402e+03 -1.78213306e+03 -1.81960107e+03 -1.78994873e+03 -1.72262317e+03 -1.63472510e+03 -1.56102368e+03 -1.57344556e+03 -1.50819482e+03 -1.45118542e+03 -1.49007129e+03 -1.41334937e+03 -1.36980408e+03 -1.73552893e+03 -1.60998828e+03 -1.70578394e+03 -1.81845813e+03 -1.94994031e+03 -1.54032568e+03 -1.12939856e+03 -1.29820361e+03 -5.94285938e+03 112373816. 546353984. -18419674. -18419674. 5.39781350e+06 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. 391148160. 1.60673500e+05 -1.16610180e+05 -8.25295625e+04 -1.60373812e+05 -2.17510422e+05 2.02303101e+03 1.57223242e+03 9.56342468e+02 1.02881934e+03 1.03751624e+03 1.05559058e+03 1.18124585e+03 1.39046448e+03 1.21082983e+03 1.21786377e+03 1.35360388e+03 1.28825818e+03 1.37095764e+03 1.59979248e+03 1.62566956e+03 1.55501440e+03 1.59671594e+03 1.65278882e+03 1.67480994e+03 1.73489954e+03 1.82711609e+03 1.86088953e+03 1.89560901e+03 1.95612659e+03 1.96935999e+03 2.00184387e+03 2.06594434e+03 2.09057886e+03 2.11917505e+03 2.22622876e+03 2.31352832e+03 2.29495068e+03 2.31606079e+03 2.38186475e+03 2.42801001e+03 2.49346484e+03 2.52381543e+03 2.51462549e+03 2.61172974e+03 2.72345508e+03 2.67292993e+03 2.69781860e+03 2.80183545e+03 2.77398389e+03 2.84053247e+03 2.97579834e+03 2.96627002e+03 2.98120483e+03 3.06407104e+03 3.16307080e+03 3.15768652e+03 3.10400659e+03 3.13205298e+03 3.18714600e+03 3.33661328e+03 3.44302148e+03 3.40021069e+03 3.39275098e+03 3.42270386e+03 3.48479199e+03 3.53507373e+03 3.54257056e+03 3.55531958e+03 3.67192383e+03 3.81623242e+03 3.75495630e+03 3.74821143e+03 3.86504492e+03 3.87919507e+03 3.88907031e+03 3.94340381e+03 4.01744092e+03 4.00979956e+03 4.00272607e+03 4.13205762e+03 4.15436963e+03 4.18310156e+03 4.22371289e+03 4.16448535e+03 4.28003223e+03 4.44360352e+03 4.36717822e+03 4.33713184e+03 4.41438086e+03 4.46114990e+03 4.53318115e+03 4.54356494e+03 4.48620508e+03 4.62276465e+03 4.79153271e+03 4.73733936e+03 4.63835938e+03 4.68910938e+03 4.83839795e+03 4.86652246e+03 4.85946973e+03 4.85526904e+03 4.85254150e+03 4.99142383e+03 5.14935107e+03 5.03733691e+03 4.93897119e+03 4.99149609e+03 5.05615723e+03 5.17110059e+03 5.26741406e+03 5.21890088e+03 5.21866846e+03 5.40990039e+03 5.43404492e+03 5.27899951e+03 5.23063232e+03 5.30355664e+03 5.43914893e+03 5.51121973e+03 5.53533252e+03 5.52962695e+03 5.55479785e+03 5.61530762e+03 5.50614551e+03 5.51619043e+03 5.63138770e+03 5.64026855e+03 5.74399414e+03 5.83737695e+03 5.69011182e+03 5.69673291e+03 5.86867383e+03 5.85970752e+03 5.74023340e+03 5.86991016e+03 6.04280127e+03 6.00846289e+03 5.96627197e+03 5.94909570e+03 5.97385791e+03 5.98846582e+03 5.93724854e+03 6.03804297e+03 6.11025391e+03 6.11725684e+03 6.14378174e+03 6.18318652e+03 6.20254346e+03 6.02509082e+03 6.15611865e+03 6.28876807e+03 6.25858154e+03 6.32436670e+03 6.43876318e+03 6.39990918e+03 6.25829590e+03 6.26196387e+03 6.31748926e+03 6.24035693e+03 6.35769678e+03 6.50806836e+03 6.44158057e+03 6.45241602e+03 6.46034033e+03 6.42044629e+03 6.43603125e+03 6.44173096e+03 6.45253857e+03 6.52600146e+03 6.60585791e+03 6.59187500e+03 6.50568359e+03 6.62432959e+03 6.60419580e+03 6.61268945e+03 6.58420166e+03 6.57512891e+03 6.70760107e+03 6.62974707e+03 6.64633154e+03 6.67197803e+03 6.69716553e+03 6.78568945e+03 6.55745410e+03 6.62002539e+03 6.81764746e+03 6.73779346e+03 6.82463477e+03 6.82941650e+03 6.70040625e+03 6.71862354e+03 6.64599951e+03 6.65693701e+03 6.72603613e+03 6.81631689e+03 6.86363330e+03 6.87118066e+03 6.88099902e+03 6.86284424e+03 6.80768018e+03 6.75477295e+03 6.67317383e+03 6.71617480e+03 6.91216309e+03 7.02642383e+03 6.77279248e+03 6.70414990e+03 6.92361621e+03 6.72028223e+03 6.82371143e+03 6.97172803e+03 6.79322217e+03 6.76653467e+03 6.85365234e+03 6.90053174e+03 6.88544482e+03 6.81516064e+03 6.78547021e+03 6.66504248e+03 6.73767725e+03 6.87367773e+03 6.85601514e+03 6.80857764e+03 6.80280322e+03 6.87623535e+03 6.75784521e+03 6.82009570e+03 6.87988086e+03 6.73180420e+03 6.66935205e+03 6.74012109e+03 6.76895850e+03 6.80378174e+03 6.76669922e+03 6.70284277e+03 6.75533203e+03 6.73271338e+03 6.72829150e+03 6.70180811e+03 6.84541846e+03 6.83190479e+03 6.53593262e+03 6.65230371e+03 6.67691064e+03 6.62643555e+03 6.76756104e+03 6.56002734e+03 6.47045410e+03 6.73480078e+03 6.70105176e+03 6.47461523e+03 6.48013525e+03 6.60253955e+03 6.63380615e+03 6.47332080e+03 6.55403857e+03 6.62918652e+03 6.42159814e+03 6.40765869e+03 6.50588330e+03 6.30905762e+03 6.41137305e+03 6.51242627e+03 6.30126611e+03 6.39940723e+03 6.50907812e+03 6.38550000e+03 6.26308545e+03 6.23365039e+03 6.29230469e+03 6.36332715e+03 6.24264990e+03 6.13743604e+03 6.18718994e+03 6.18228809e+03 6.12584033e+03 6.09040674e+03 6.12840137e+03 6.10307227e+03 6.06648535e+03 6.09975391e+03 6.11083643e+03 5.98883691e+03 5.99721484e+03 5.99297656e+03 5.83749854e+03 5.98191699e+03 5.99719336e+03 5.77124316e+03 5.84534570e+03 5.85183740e+03 5.74401611e+03 5.80420020e+03 5.70412207e+03 5.74860938e+03 5.80916016e+03 5.68934570e+03 5.61784814e+03 5.59098828e+03 5.51975439e+03 5.47747998e+03 5.48782178e+03 5.57258008e+03 5.59342969e+03 5.47555127e+03 5.41870703e+03 5.46896289e+03 5.36296973e+03 5.23775342e+03 5.27055371e+03 5.34601367e+03 5.33127881e+03 5.16061133e+03 5.06037354e+03 5.15333301e+03 5.18990576e+03 5.07531104e+03 5.01262988e+03 5.00288525e+03 4.98829639e+03 5.02762793e+03 4.95648438e+03 4.86463281e+03 4.77871045e+03 4.73886133e+03 4.77071240e+03 4.73390967e+03 4.71461328e+03 4.75353613e+03 4.65583252e+03 4.61092822e+03 4.69213721e+03 4.57674707e+03 4.43643213e+03 4.48868213e+03 4.53776758e+03 4.40316602e+03 4.24163379e+03 4.21260400e+03 4.29633203e+03 4.31506006e+03 4.24436816e+03 4.17393604e+03 4.09477148e+03 4.14430518e+03 4.11818896e+03 3.93206128e+03 3.90374316e+03 3.95854858e+03 3.95981641e+03 3.85348877e+03 3.74423804e+03 3.74810815e+03 3.75324951e+03 3.75330713e+03 3.74602515e+03 3.68174023e+03 3.54764624e+03 3.44403638e+03 3.50940845e+03 3.56420581e+03 3.43478589e+03 3.33393750e+03 3.26637646e+03 3.27539160e+03 3.31123608e+03 3.20419873e+03 3.13562158e+03 3.11897778e+03 3.13647827e+03 3.09921289e+03 2.94303247e+03 2.94967627e+03 2.93883887e+03 2.84031079e+03 2.83158813e+03 2.75716968e+03 2.71052783e+03 2.69409204e+03 2.63200098e+03 2.60477466e+03 2.58604150e+03 2.53702881e+03 2.45502124e+03 2.42954712e+03 2.40682861e+03 2.34431177e+03 2.28440259e+03 2.19131616e+03 2.17380615e+03 2.19797534e+03 2.13738501e+03 2.06802075e+03 1.97312451e+03 1.94465686e+03 1.97641614e+03 1.89617444e+03 1.82177039e+03 1.80847888e+03 1.75384814e+03 1.67358826e+03 1.64661816e+03 1.62012341e+03 1.54818237e+03 1.51502856e+03 1.46819312e+03 1.38469690e+03 1.36055701e+03 1.33058911e+03 1.28480200e+03 1.26011340e+03 1.20078638e+03 1.14089563e+03 1.08178589e+03 1.02988110e+03 9.99085327e+02 9.62339233e+02 9.02940918e+02 8.42127869e+02 8.08626282e+02 7.59570374e+02 7.05864746e+02 6.75734619e+02 6.22846436e+02 5.67502075e+02 5.19882812e+02 4.70544830e+02 4.27254852e+02 3.83879730e+02 3.35374603e+02 2.80452942e+02 2.31933044e+02 1.87233917e+02 1.40465622e+02 9.43363724e+01 4.70492935e+01 -2.10209513e+00 -4.96782417e+01 -9.56054916e+01 -1.41882309e+02 -1.92295654e+02 -2.42460327e+02 -2.93372253e+02 -3.33624908e+02 -3.72907990e+02 -4.32650665e+02 -4.87941956e+02 -5.27642761e+02 -5.68853577e+02 -6.17536865e+02 -6.69588562e+02 -7.24474854e+02 -7.68663696e+02 -8.00139832e+02 -8.53427612e+02 -9.15278625e+02 -9.55099915e+02 -1.00040186e+03 -1.04508069e+03 -1.08545764e+03 -1.14464331e+03 -1.19396069e+03 -1.24721802e+03 -1.29065002e+03 -1.32264551e+03 -1.38098950e+03 -1.43100549e+03 -1.47733008e+03 -1.48945508e+03 -1.53075610e+03 -1.61819019e+03 -1.68021375e+03 -1.73273633e+03 -1.74343152e+03 -1.78199133e+03 -1.82224438e+03 -1.87228003e+03 -1.96666797e+03 -1.97114172e+03 -2.00313562e+03 -2.10830322e+03 -2.10479785e+03 -2.11559375e+03 -2.22788013e+03 -2.28045435e+03 -2.30358252e+03 -2.37335645e+03 -2.38151294e+03 -2.34742065e+03 -2.46550049e+03 -2.55968359e+03 -2.54389233e+03 -2.66112988e+03 -2.69959814e+03 -2.65530054e+03 -2.70974805e+03 -2.74466846e+03 -2.79730566e+03 -2.90389282e+03 -2.92510815e+03 -2.94728882e+03 -3.01954492e+03 -3.06252295e+03 -3.12073828e+03 -3.12413599e+03 -3.12338574e+03 -3.19996167e+03 -3.26162451e+03 -3.26489526e+03 -3.32572217e+03 -3.39854199e+03 -3.39754370e+03 -3.48160352e+03 -3.54063745e+03 -3.56046753e+03 -3.59497217e+03 -3.57275830e+03 -3.62521655e+03 -3.78005078e+03 -3.81658765e+03 -3.75613330e+03 -3.84009985e+03 -3.90642676e+03 -3.91859082e+03 -3.95317627e+03 -3.87913989e+03 -3.91324341e+03 -4.09978906e+03 -4.19321777e+03 -4.18982715e+03 -4.12190234e+03 -4.14919580e+03 -4.29159180e+03 -4.29260010e+03 -4.30015820e+03 -4.36289551e+03 -4.38162256e+03 -4.44982666e+03 -4.49510938e+03 -4.57496729e+03 -4.54102393e+03 -4.50443506e+03 -4.68268506e+03 -4.64989062e+03 -4.61921680e+03 -4.69857031e+03 -4.67863965e+03 -4.77061670e+03 -4.94972314e+03 -4.95462549e+03 -4.82024756e+03 -4.84848438e+03 -4.98020312e+03 -5.04457324e+03 -5.05580811e+03 -5.02964795e+03 -5.08767578e+03 -5.18390820e+03 -5.19207715e+03 -5.22953467e+03 -5.23791504e+03 -5.25912500e+03 -5.29023877e+03 -5.17059180e+03 -5.22237158e+03 -5.43464355e+03 -5.45380957e+03 -5.42776514e+03 -5.45015332e+03 -5.40969141e+03 -5.42769922e+03 -5.64972461e+03 -5.67166260e+03 -5.54253906e+03 -5.57212695e+03 -5.56306055e+03 -5.64929346e+03 -5.71695264e+03 -5.76659814e+03 -5.84975586e+03 -5.79726221e+03 -5.79551221e+03 -5.80815674e+03 -5.74527734e+03 -5.76659229e+03 -5.98635840e+03 -6.02700537e+03 -5.92220801e+03 -5.94252295e+03 -5.98266016e+03 -6.01422119e+03 -5.99826953e+03 -6.10631934e+03 -6.07531641e+03 -6.09749951e+03 -6.14224854e+03 -6.15334424e+03 -6.28154834e+03 -6.18497754e+03 -6.15104541e+03 -6.32199023e+03 -6.22205566e+03 -6.19521924e+03 -6.30987354e+03 -6.28080957e+03 -6.28711572e+03 -6.42376465e+03 -6.48979736e+03 -6.39175586e+03 -6.46883887e+03 -6.45944434e+03 -6.45127344e+03 -6.45674707e+03 -6.81094873e+03 -6.86757178e+03 -8.23881250e+03 -8.84862305e+03 -1.06168643e+04 -8.99137988e+03 -1.48310088e+04 -8.74486641e+04 20270600. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -181644528. -4717116. 2.81008050e+06 -7779535. 8937507. -3.13485375e+06 -11670611. -5.63130850e+06 -2.03439102e+04 -1.72137949e+04 -9.08920215e+03 -7.24067773e+03 -7.09668115e+03 -8.85985449e+03 -7.26350244e+03 -9.19760840e+03 -6.52477490e+03 -6.32506787e+03 -6.89558838e+03 -6.74795850e+03 -6.56358594e+03 -6.87140918e+03 -7.02807422e+03 -6.92248486e+03 -6.80119434e+03 -6.58790039e+03 -6.65591797e+03 -6.95741650e+03 -6.71465576e+03 -6.57974268e+03 -6.50855664e+03 -6.62994775e+03 -6.92185156e+03 -6.87227051e+03 -6.66510156e+03 -6.39227344e+03 -6.41992773e+03 -6.66952490e+03 -6.67495215e+03 -6.62222168e+03 -6.55562012e+03 -6.57334863e+03 -6.62389453e+03 -6.60003223e+03 -6.62033643e+03 -6.35302148e+03 -6.43661182e+03 -6.78547217e+03 -6.47938330e+03 -6.28839697e+03 -6.34789258e+03 -6.34273828e+03 -6.54588574e+03 -6.55123828e+03 -6.35747217e+03 -6.22056396e+03 -6.36033691e+03 -6.44347168e+03 -6.33163184e+03 -6.24781738e+03 -6.11565723e+03 -6.26481836e+03 -6.39310498e+03 -6.17013672e+03 -6.12724609e+03 -6.09569336e+03 -6.04689453e+03 -6.24175488e+03 -6.26429688e+03 -6.11280078e+03 -5.96015039e+03 -6.03308203e+03 -6.05406982e+03 -6.03025098e+03 -6.01860986e+03 -5.81794287e+03 -5.81620508e+03 -6.07974170e+03 -5.88351025e+03 -5.68153955e+03 -5.63831689e+03 -5.78715820e+03 -6.01419141e+03 -5.86207861e+03 -5.72380176e+03 -5.61987939e+03 -5.51513037e+03 -5.61942822e+03 -5.74352539e+03 -5.59146289e+03 -5.42345947e+03 -5.54050488e+03 -5.55671533e+03 -5.49351270e+03 -5.56050439e+03 -5.35003174e+03 -5.27151709e+03 -5.49357910e+03 -5.39109277e+03 -5.26600293e+03 -5.17691016e+03 -5.11091260e+03 -5.27632080e+03 -5.29226904e+03 -5.09592578e+03 -5.02939551e+03 -5.12024609e+03 -5.13117480e+03 -5.01941211e+03 -5.03375439e+03 -4.93209375e+03 -4.84662842e+03 -4.98534766e+03 -4.90600146e+03 -4.74142480e+03 -4.64612988e+03 -4.68887207e+03 -4.85133545e+03 -4.80824854e+03 -4.69557178e+03 -4.50678271e+03 -4.42278271e+03 -4.61357617e+03 -4.60319775e+03 -4.41259912e+03 -4.35650977e+03 -4.38876123e+03 -4.42507666e+03 -4.32607715e+03 -4.25483887e+03 -4.14886914e+03 -4.19655859e+03 -4.33820801e+03 -4.13595947e+03 -4.05478638e+03 -4.06535693e+03 -3.97239966e+03 -4.00190063e+03 -3.96694653e+03 -3.87218481e+03 -3.78644897e+03 -3.78566309e+03 -3.87084839e+03 -3.83539673e+03 -3.72115991e+03 -3.59662012e+03 -3.55434106e+03 -3.63669556e+03 -3.61636304e+03 -3.52183325e+03 -3.39314771e+03 -3.30140332e+03 -3.39366724e+03 -3.42043750e+03 -3.32727515e+03 -3.19867407e+03 -3.16757300e+03 -3.16999341e+03 -3.13599780e+03 -3.16552197e+03 -3.03001855e+03 -2.96344409e+03 -3.00186597e+03 -2.90744873e+03 -2.84267969e+03 -2.80373096e+03 -2.79686597e+03 -2.76896094e+03 -2.66912671e+03 -2.61362305e+03 -2.56522925e+03 -2.57088281e+03 -2.61097241e+03 -2.50873120e+03 -2.37617236e+03 -2.32949829e+03 -2.31778882e+03 -2.33906689e+03 -2.31936426e+03 -2.24083130e+03 -2.11854053e+03 -2.02847522e+03 -2.05718359e+03 -2.07362524e+03 -2.02538391e+03 -1.89671399e+03 -1.83880884e+03 -1.85388684e+03 -1.81286230e+03 -1.76363586e+03 -1.69529260e+03 -1.64763464e+03 -1.60659558e+03 -1.54510535e+03 -1.51188074e+03 -1.46915076e+03 -1.41498999e+03 -1.39369202e+03 -1.33142407e+03 -1.27178491e+03 -1.22514880e+03 -1.19086829e+03 -1.15605920e+03 -1.08694788e+03 -1.02755164e+03 -9.80553589e+02 -9.69037354e+02 -9.37684509e+02 -8.60338867e+02 -7.98895325e+02 -7.38707581e+02 -7.00416260e+02 -6.84067017e+02 -6.38374207e+02 -5.77569092e+02 -5.09713287e+02 -4.61515411e+02 -4.40588165e+02 -3.96001556e+02 -3.32651947e+02 -2.84855896e+02 -2.42619308e+02 -1.91238007e+02 -1.40545929e+02 -9.13970184e+01 -4.33458328e+01 3.51150966e+00 5.10608177e+01 1.00468285e+02 1.47001236e+02 1.85177429e+02 2.35752106e+02 2.90461273e+02 3.37709351e+02 3.86240753e+02 4.28148315e+02 4.90308441e+02 5.37125549e+02 5.55072449e+02 5.95420410e+02 6.57466675e+02 7.35238586e+02 8.07227539e+02 8.36102417e+02 8.38625793e+02 8.59097900e+02 9.22485657e+02 1.02581750e+03 1.10674023e+03 1.13023389e+03 1.10698633e+03 1.14429199e+03 1.28537769e+03 1.32232312e+03 1.29861475e+03 1.35477063e+03 1.41197644e+03 1.45966467e+03 1.55950720e+03 1.57432178e+03 1.55728235e+03 1.64744958e+03 1.67075671e+03 1.74700549e+03 1.83725134e+03 1.80143860e+03 1.88430750e+03 1.98150330e+03 1.98486890e+03 2.01962561e+03 2.06420630e+03 2.13409155e+03 2.16496924e+03 2.18954028e+03 2.19253442e+03 2.23711841e+03 2.39839917e+03 2.51631055e+03 2.49679199e+03 2.41356543e+03 2.41166064e+03 2.50254761e+03 2.65167139e+03 2.78609839e+03 2.75411426e+03 2.65926416e+03 2.73698096e+03 2.86902344e+03 2.87131836e+03 2.89017456e+03 2.95982202e+03 2.96931372e+03 3.01675439e+03 3.18891064e+03 3.16174756e+03 3.09773975e+03 3.21105420e+03 3.18046069e+03 3.30499170e+03 3.43221606e+03 3.34663745e+03 3.48223047e+03 3.50627979e+03 3.40834839e+03 3.53283716e+03 3.48215601e+03 3.59979199e+03 3.88751587e+03 3.72982983e+03 3.56070679e+03 3.66135767e+03 3.90104932e+03 4.10041211e+03 4.04021167e+03 3.85543066e+03 3.81301172e+03 3.92039771e+03 4.09841846e+03 4.31933252e+03 4.26289551e+03 4.05214014e+03 4.09245068e+03 4.24012744e+03 4.33093799e+03 4.32492578e+03 4.33853711e+03 4.37084521e+03 4.40209229e+03 4.62495508e+03 4.66617969e+03 4.39823926e+03 4.40571143e+03 4.63555713e+03 4.68039697e+03 4.68316455e+03 4.72464844e+03 4.89395605e+03 4.82992822e+03 4.67249561e+03 4.82714697e+03 4.73887842e+03 4.92147314e+03 5.27737012e+03 4.99032471e+03 4.74076514e+03 4.93991699e+03 5.21589404e+03 5.39207910e+03 5.36161230e+03 5.04045459e+03 4.95194775e+03 5.11677246e+03 5.34717773e+03 5.56073389e+03 5.50908984e+03 5.19708545e+03 5.19640674e+03 5.44683936e+03 5.47497510e+03 5.61169385e+03 5.69335156e+03 5.39602051e+03 5.38604492e+03 5.70703760e+03 5.78953613e+03 5.55302393e+03 5.54497314e+03 5.71881152e+03 5.65599365e+03 5.88330176e+03 5.95868457e+03 5.75309424e+03 5.74127441e+03 5.75477295e+03 5.80263916e+03 5.86156152e+03 5.86114502e+03 6.09528027e+03 6.19652246e+03 6.02519092e+03 5.86623047e+03 5.73502588e+03 6.01633887e+03 6.39218555e+03 6.27154639e+03 5.95765430e+03 5.86357568e+03 6.09672021e+03 6.44539209e+03 6.28495996e+03 5.93874072e+03 6.09399902e+03 6.30045996e+03 6.43502441e+03 6.68413916e+03 6.48546533e+03 6.10064355e+03 6.14520459e+03 6.31951123e+03 6.43765088e+03 6.51612939e+03 6.46497021e+03 6.47338721e+03 6.45284229e+03 6.56552881e+03 6.54938330e+03 6.38899561e+03 6.41011768e+03 6.38762012e+03 6.69013623e+03 6.76492383e+03 6.53114551e+03 6.66338428e+03 6.67272412e+03 6.65173633e+03 6.48045166e+03 6.38781006e+03 6.71341992e+03 6.97669727e+03 6.86166162e+03 6.53876465e+03 6.49386572e+03 6.81868750e+03 6.95366016e+03 6.83923633e+03 6.71327197e+03 6.54112061e+03 6.58650342e+03 6.85314941e+03 6.85516797e+03 6.70594775e+03 6.55843604e+03 6.52074561e+03 6.85644287e+03 7.16814795e+03 6.82445166e+03 6.62730127e+03 6.80423047e+03 6.79516211e+03 7.01159326e+03 6.96064795e+03 6.61335938e+03 6.67843750e+03 6.88529443e+03 6.89923584e+03 6.85068457e+03 6.79021338e+03 6.92609619e+03 6.95883643e+03 6.69721875e+03 7.00159033e+03 6.79535205e+03 6.51994531e+03 7.23033105e+03 7.16422656e+03 8.71377832e+03 8.90109277e+03 1.01931445e+04 1.18359209e+04 1.75669570e+04 2.00014980e+04 6.60897950e+06 47075812. 2126702. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 28241116. 2.45838250e+06 5940163. 9734758. 3.73960925e+06 -9.85152750e+05 1.83632715e+04 1.44833916e+04 1.03254697e+04 1.04312842e+04 9.38225391e+03 9.63622559e+03 9.64802930e+03 9.31961914e+03 9.27968359e+03 9.24586816e+03 7.84888867e+03 8.01292432e+03 6.56704443e+03 6.18660205e+03 6.13003418e+03 6.01607324e+03 6.03543262e+03 6.03206006e+03 5.82814795e+03 5.81015820e+03 6.06416553e+03 6.04884131e+03 5.86230811e+03 5.79310938e+03 5.82286133e+03 5.80911377e+03 5.74610156e+03 5.72720117e+03 5.68553418e+03 5.64112305e+03 5.55898633e+03 5.53168506e+03 5.69308447e+03 5.66145703e+03 5.51225635e+03 5.48743213e+03 5.48569385e+03 5.49127490e+03 5.39805371e+03 5.37926953e+03 5.36959082e+03 5.27489404e+03 5.21083447e+03 5.18725098e+03 5.15160352e+03 5.35523389e+03 5.35058057e+03 5.13307227e+03 4.97160791e+03 4.91491016e+03 5.19498242e+03 5.19361963e+03 4.97577002e+03 4.83733545e+03 4.81820264e+03 4.84436670e+03 4.79368555e+03 4.97255176e+03 4.92989941e+03 4.59329736e+03 4.49797021e+03 4.69131982e+03 4.89296045e+03 4.75820166e+03 4.57675098e+03 4.52591504e+03 4.47337354e+03 4.46632959e+03 4.46227832e+03 4.35963672e+03 4.30144287e+03 4.28322021e+03 4.24607764e+03 4.21847266e+03 4.17765479e+03 4.27321582e+03 4.21825439e+03 4.05198730e+03 4.00769189e+03 3.98759741e+03 4.04775952e+03 4.01647974e+03 3.91120630e+03 3.85647363e+03 3.74099902e+03 3.61450635e+03 3.76077393e+03 3.77036084e+03 3.53161182e+03 3.51517017e+03 3.67400659e+03 3.73128125e+03 3.58177783e+03 3.44985205e+03 3.41389453e+03 3.38334912e+03 3.29470435e+03 3.24676562e+03 3.23657031e+03 3.17837134e+03 3.24323242e+03 3.18485303e+03 3.05311597e+03 3.01089087e+03 2.89800293e+03 2.93573804e+03 3.05092407e+03 2.93880591e+03 2.82529761e+03 2.71653418e+03 2.63927002e+03 2.73958130e+03 2.74881079e+03 2.62524829e+03 2.50183813e+03 2.44729761e+03 2.45828638e+03 2.41477271e+03 2.45342554e+03 2.42652686e+03 2.28952930e+03 2.19993311e+03 2.15518872e+03 2.19343750e+03 2.16551636e+03 2.07445020e+03 2.00352625e+03 1.95956653e+03 1.91130078e+03 1.80695044e+03 1.81235815e+03 1.88168298e+03 1.79148315e+03 1.69753015e+03 1.61622754e+03 1.55885059e+03 1.60207861e+03 1.56432666e+03 1.46667590e+03 1.38346692e+03 1.33645801e+03 1.33126831e+03 1.27710645e+03 1.23165967e+03 1.15552832e+03 1.13010742e+03 1.14407703e+03 1.06360583e+03 1.00442645e+03 9.65947754e+02 9.07238892e+02 8.44093872e+02 7.99890991e+02 7.56298157e+02 7.03868835e+02 6.59494446e+02 5.97569946e+02 5.66611816e+02 5.51660645e+02 4.77747772e+02 4.15653442e+02 3.78600586e+02 3.31051727e+02 2.91873444e+02 2.40421173e+02 1.85244217e+02 1.43218094e+02 9.59723587e+01 4.72998810e+01 -4.09079969e-01 -4.81746597e+01 -9.52918777e+01 -1.43436218e+02 -1.89556839e+02 -2.30714310e+02 -2.87418793e+02 -3.53968445e+02 -3.94827209e+02 -4.28326508e+02 -4.61273560e+02 -5.14579773e+02 -5.94789673e+02 -6.40499573e+02 -6.72155212e+02 -6.99901123e+02 -7.39152893e+02 -8.11236633e+02 -8.60968689e+02 -9.25087769e+02 -9.61525330e+02 -9.84348083e+02 -1.04446606e+03 -1.08493616e+03 -1.16943201e+03 -1.22433252e+03 -1.23438782e+03 -1.27083508e+03 -1.31866711e+03 -1.37155383e+03 -1.37960706e+03 -1.45242590e+03 -1.58221448e+03 -1.60541760e+03 -1.61015405e+03 -1.61166260e+03 -1.64878137e+03 -1.79139197e+03 -1.84583667e+03 -1.83910205e+03 -1.84359143e+03 -1.88161438e+03 -1.98075110e+03 -2.03242810e+03 -2.11751880e+03 -2.15001294e+03 -2.14244727e+03 -2.16076196e+03 -2.20025879e+03 -2.35432983e+03 -2.41188794e+03 -2.38502222e+03 -2.38662915e+03 -2.42648462e+03 -2.57436035e+03 -2.62421509e+03 -2.52961548e+03 -2.57576489e+03 -2.78400244e+03 -2.80578052e+03 -2.70674146e+03 -2.74989502e+03 -2.93425635e+03 -3.00615210e+03 -2.93994214e+03 -2.91014404e+03 -2.96341235e+03 -3.17690088e+03 -3.19718701e+03 -3.14017139e+03 -3.22107349e+03 -3.24934351e+03 -3.22535376e+03 -3.25670508e+03 -3.38801123e+03 -3.34381274e+03 -3.43586743e+03 -3.64427100e+03 -3.58348218e+03 -3.64136865e+03 -3.69947949e+03 -3.66639209e+03 -3.70724634e+03 -3.74678442e+03 -3.78677612e+03 -3.73067188e+03 -3.72510010e+03 -3.86150659e+03 -3.97548828e+03 -4.12125146e+03 -4.02361670e+03 -3.94985889e+03 -4.09870947e+03 -4.13114941e+03 -4.30915283e+03 -4.33027783e+03 -4.22858008e+03 -4.19864795e+03 -4.20871631e+03 -4.35062012e+03 -4.40065967e+03 -4.53579688e+03 -4.55190283e+03 -4.48595166e+03 -4.51682764e+03 -4.41781006e+03 -4.56579688e+03 -4.84538818e+03 -4.83764014e+03 -4.73137305e+03 -4.64206201e+03 -4.65140137e+03 -4.91762207e+03 -5.00134326e+03 -4.90998730e+03 -4.79956104e+03 -4.83894287e+03 -4.98904932e+03 -5.00740918e+03 -5.17425732e+03 -5.19094092e+03 -5.07108154e+03 -5.12116162e+03 -5.12985840e+03 -5.28809961e+03 -5.32536523e+03 -5.12247705e+03 -5.16296045e+03 -5.48614062e+03 -5.42646191e+03 -5.15598047e+03 -5.34868311e+03 -5.66124805e+03 -5.63571533e+03 -5.53695410e+03 -5.41523193e+03 -5.40845508e+03 -5.74828955e+03 -5.79021436e+03 -5.65133447e+03 -5.52697949e+03 -5.53176074e+03 -5.70409961e+03 -5.75827734e+03 -5.80488477e+03 -5.67295898e+03 -5.79848584e+03 -6.11984961e+03 -5.98734424e+03 -5.95512158e+03 -5.93852295e+03 -5.90160400e+03 -5.96220654e+03 -5.97884570e+03 -6.04843848e+03 -6.05059326e+03 -6.03815088e+03 -5.89646387e+03 -6.00638330e+03 -6.34295557e+03 -6.11466211e+03 -5.87293457e+03 -6.11892725e+03 -6.31034375e+03 -6.50362695e+03 -6.40862500e+03 -6.25282617e+03 -6.31050488e+03 -6.34031494e+03 -6.21846680e+03 -6.20557080e+03 -6.46216211e+03 -6.44843457e+03 -6.33586768e+03 -6.30514990e+03 -6.15421289e+03 -6.41832227e+03 -6.78162646e+03 -6.63248096e+03 -6.50039795e+03 -6.34408789e+03 -6.31792188e+03 -6.69189258e+03 -6.83092480e+03 -6.64073535e+03 -6.43392480e+03 -6.41353906e+03 -6.52725342e+03 -6.55636035e+03 -6.82430566e+03 -6.76001123e+03 -6.57800146e+03 -6.61527881e+03 -6.59309668e+03 -6.77013525e+03 -6.79149951e+03 -6.64322656e+03 -6.72916260e+03 -6.73751953e+03 -6.62137109e+03 -6.47956543e+03 -6.63305420e+03 -6.98891797e+03 -6.87286768e+03 -6.74433936e+03 -6.60528076e+03 -6.65731885e+03 -7.04905713e+03 -7.02941895e+03 -6.81227344e+03 -6.64233057e+03 -6.61324561e+03 -6.73043750e+03 -6.74474854e+03 -6.85807861e+03 -6.67404688e+03 -6.80630078e+03 -7.04313330e+03 -6.86843848e+03 -6.92596777e+03 -6.97663281e+03 -6.82221045e+03 -6.89167822e+03 -6.89670410e+03 -6.68208350e+03 -6.66236670e+03 -6.91391846e+03 -6.92952832e+03 -6.91252148e+03 -6.88158008e+03 -6.67829785e+03 -6.62736572e+03 -6.84212207e+03 -6.84730859e+03 -7.04015967e+03 -6.95241943e+03 -6.64818652e+03 -6.80612646e+03 -6.95685254e+03 -6.87162061e+03 -6.75001855e+03 -6.66935645e+03 -6.81178857e+03 -6.80649512e+03 -6.75519092e+03 -6.60379102e+03 -6.70711963e+03 -7.08312158e+03 -6.92362744e+03 -6.72280225e+03 -6.57060303e+03 -6.55580029e+03 -6.90543066e+03 -6.87464844e+03 -6.71076514e+03 -6.50956641e+03 -6.41657910e+03 -6.59926123e+03 -6.75120703e+03 -6.91472803e+03 -6.73341455e+03 -6.42150000e+03 -6.49189453e+03 -6.54584473e+03 -6.78568750e+03 -6.63606250e+03 -6.42998340e+03 -6.59608838e+03 -6.59201367e+03 -6.50617041e+03 -6.32969922e+03 -6.42017822e+03 -6.73295459e+03 -6.66650195e+03 -6.41571387e+03 -6.24802539e+03 -6.25717920e+03 -6.56408740e+03 -6.58557373e+03 -6.38675586e+03 -6.18253760e+03 -6.15563330e+03 -6.29819678e+03 -6.26833398e+03 -6.43802002e+03 -6.43030176e+03 -6.18708105e+03 -6.02921680e+03 -6.08210352e+03 -6.41045312e+03 -6.28054443e+03 -6.03610596e+03 -6.15849854e+03 -6.15949658e+03 -5.93986670e+03 -5.85213232e+03 -6.04628223e+03 -5.99253320e+03 -5.82944385e+03 -6.10431494e+03 -6.11029688e+03 -5.94908789e+03 -5.89532715e+03 -5.83223242e+03 -5.81210596e+03 -5.65624121e+03 -5.56940674e+03 -5.83889111e+03 -5.87439795e+03 -5.59752588e+03 -5.43817578e+03 -5.62497949e+03 -5.82682617e+03 -5.76388281e+03 -5.51950391e+03 -5.34823291e+03 -5.52886523e+03 -5.65554297e+03 -5.53439600e+03 -5.40738232e+03 -5.24129443e+03 -5.10471924e+03 -5.31820654e+03 -5.56729541e+03 -5.38843896e+03 -5.11389795e+03 -5.06045654e+03 -5.27900293e+03 -5.33753320e+03 -5.15017090e+03 -4.95470605e+03 -4.87827393e+03 -4.93996973e+03 -4.96289893e+03 -5.08748926e+03 -5.05871387e+03 -4.85942090e+03 -4.79503906e+03 -4.80125635e+03 -4.86386182e+03 -4.69575391e+03 -4.59143018e+03 -4.78528467e+03 -4.75447217e+03 -4.56596680e+03 -4.40127344e+03 -4.48294824e+03 -4.70261475e+03 -4.45049658e+03 -4.26679297e+03 -4.35967139e+03 -4.39066309e+03 -4.37983789e+03 -4.29285840e+03 -4.34675537e+03 -4.34692383e+03 -4.16521924e+03 -3.99818213e+03 -3.96996729e+03 -4.17625146e+03 -4.07138232e+03 -3.91422705e+03 -3.94502368e+03 -3.90447852e+03 -3.86730713e+03 -3.80285864e+03 -3.80596118e+03 -3.75303931e+03 -3.63628101e+03 -3.68923730e+03 -3.65542358e+03 -3.63007666e+03 -3.60334326e+03 -3.50301465e+03 -3.44339990e+03 -3.30733521e+03 -3.28514600e+03 -3.43454443e+03 -3.43728979e+03 -3.20904907e+03 -3.06910571e+03 -3.14849561e+03 -3.22743335e+03 -3.16686987e+03 -3.02142188e+03 -2.87241846e+03 -2.94594238e+03 -2.98700977e+03 -2.86353394e+03 -2.88706104e+03 -2.81107690e+03 -2.65101831e+03 -2.67241260e+03 -2.73105762e+03 -2.66113794e+03 -2.49575488e+03 -2.41408594e+03 -2.50802417e+03 -2.52067651e+03 -2.39846851e+03 -2.26866626e+03 -2.21036035e+03 -2.29515503e+03 -2.24634106e+03 -2.12661621e+03 -2.11661963e+03 -2.07500366e+03 -1.99896240e+03 -1.94823022e+03 -1.97694946e+03 -1.89991467e+03 -1.78298608e+03 -1.81763171e+03 -1.78657336e+03 -1.72049939e+03 -1.63501733e+03 -1.55870166e+03 -1.58742981e+03 -1.51830762e+03 -1.42134204e+03 -1.41716870e+03 -1.39885583e+03 -1.41638049e+03 -1.34066516e+03 -1.22424133e+03 -1.19993665e+03 -1.19657007e+03 -1.21271289e+03 -1.06442285e+03 -9.02391174e+02 -1.02918457e+03 -3.22572095e+03 -1.78577576e+03 -522877888. -1.22315000e+04 -18419674. 5.39781350e+06 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. 0. 0. 0. 2.57731494e+03 1.77520544e+03 9.83858032e+02 1.02794922e+03 1.01481793e+03 1.03339209e+03 1.16814514e+03 1.33284644e+03 1.19727747e+03 1.24580859e+03 1.37238245e+03 1.29976770e+03 1.34379175e+03 1.52035901e+03 1.60314307e+03 1.58132373e+03 1.59977344e+03 1.64633142e+03 1.68841101e+03 1.74367517e+03 1.83727161e+03 1.90018811e+03 1.88198254e+03 1.90146252e+03 1.97992883e+03 2.02959485e+03 2.04836426e+03 2.08671875e+03 2.15886133e+03 2.20302783e+03 2.28064819e+03 2.31553052e+03 2.27418896e+03 2.35189819e+03 2.47611548e+03 2.54079419e+03 2.57552319e+03 2.51974292e+03 2.53496558e+03 2.66105078e+03 2.72321191e+03 2.72967188e+03 2.75007617e+03 2.78922339e+03 2.88557495e+03 2.97619092e+03 2.98442847e+03 2.94072656e+03 2.97301660e+03 3.16424194e+03 3.22254297e+03 3.10115845e+03 3.12924097e+03 3.25621997e+03 3.32960059e+03 3.41589502e+03 3.40809229e+03 3.33192896e+03 3.39265479e+03 3.53434741e+03 3.59782690e+03 3.58100220e+03 3.56373218e+03 3.66409717e+03 3.78143359e+03 3.75397778e+03 3.74305493e+03 3.75837085e+03 3.84997046e+03 3.96287134e+03 3.97731592e+03 4.03501929e+03 4.02800903e+03 3.96857886e+03 4.07225146e+03 4.16821094e+03 4.17106396e+03 4.22933252e+03 4.22633105e+03 4.25643018e+03 4.40533008e+03 4.43501270e+03 4.30991309e+03 4.34152637e+03 4.49312646e+03 4.56513672e+03 4.58987402e+03 4.54498193e+03 4.57429346e+03 4.64803125e+03 4.73122998e+03 4.75209961e+03 4.65743750e+03 4.74040576e+03 4.90618701e+03 4.94916895e+03 4.93269434e+03 4.84036230e+03 4.86177539e+03 5.06239551e+03 5.06598486e+03 4.98390186e+03 5.01614258e+03 5.08172119e+03 5.21463379e+03 5.22681348e+03 5.21677490e+03 5.24792529e+03 5.27983154e+03 5.36552930e+03 5.37404004e+03 5.31012988e+03 5.35979102e+03 5.42669238e+03 5.41812646e+03 5.49152783e+03 5.55712207e+03 5.55003320e+03 5.57592627e+03 5.54882764e+03 5.56958447e+03 5.66828711e+03 5.73831934e+03 5.70723340e+03 5.70846582e+03 5.70826562e+03 5.73346631e+03 5.81332666e+03 5.81170850e+03 5.79168408e+03 5.88845068e+03 6.04976953e+03 6.04065674e+03 5.88761963e+03 5.93274707e+03 6.04715039e+03 5.98512988e+03 5.96061426e+03 5.95679150e+03 6.05579199e+03 6.15078906e+03 6.24199414e+03 6.19654492e+03 6.10157861e+03 6.06962305e+03 6.21097656e+03 6.28761621e+03 6.29102734e+03 6.29073975e+03 6.20892578e+03 6.32525586e+03 6.43608789e+03 6.41837402e+03 6.27266260e+03 6.21137549e+03 6.38238525e+03 6.56913086e+03 6.49044092e+03 6.24627051e+03 6.36639502e+03 6.58998438e+03 6.53728516e+03 6.45734619e+03 6.46461084e+03 6.53371387e+03 6.54091943e+03 6.57488574e+03 6.57767920e+03 6.46056885e+03 6.65911621e+03 6.71148047e+03 6.62886426e+03 6.64483789e+03 6.68643262e+03 6.50816846e+03 6.61520605e+03 6.68619629e+03 6.73815723e+03 6.82362402e+03 6.54730371e+03 6.58239795e+03 6.84440918e+03 6.72095361e+03 6.59041943e+03 6.71483203e+03 6.82233398e+03 6.76089844e+03 6.74180957e+03 6.75036377e+03 6.69404395e+03 6.73402637e+03 6.84068848e+03 6.86993262e+03 6.67327246e+03 6.78564990e+03 6.92138867e+03 6.92676172e+03 6.80373389e+03 6.69517480e+03 6.76451514e+03 6.93228955e+03 6.80498145e+03 6.75433740e+03 6.88300439e+03 6.74321582e+03 6.82088623e+03 6.98956592e+03 6.83766211e+03 6.78003662e+03 6.83600391e+03 6.85284326e+03 6.81497705e+03 6.88025049e+03 6.85313672e+03 6.72791748e+03 6.76571729e+03 6.85525586e+03 6.84481445e+03 6.72017822e+03 6.83004932e+03 6.94917139e+03 6.85540820e+03 6.95004004e+03 6.81102588e+03 6.63909668e+03 6.78375049e+03 6.83529053e+03 6.79112939e+03 6.66845020e+03 6.57765381e+03 6.78350635e+03 6.87158203e+03 6.77648828e+03 6.64366895e+03 6.79028564e+03 6.81175244e+03 6.67672998e+03 6.57459277e+03 6.76706152e+03 6.71745996e+03 6.55992871e+03 6.73121387e+03 6.63192188e+03 6.55764551e+03 6.65360498e+03 6.56326562e+03 6.52888574e+03 6.59234033e+03 6.51876904e+03 6.46372021e+03 6.57444385e+03 6.62567432e+03 6.60871191e+03 6.36741699e+03 6.36169336e+03 6.47896826e+03 6.41418213e+03 6.45964111e+03 6.41306641e+03 6.35666162e+03 6.34989502e+03 6.38862793e+03 6.47020166e+03 6.32414062e+03 6.13739307e+03 6.28771045e+03 6.49938184e+03 6.22436768e+03 6.09014795e+03 6.16516406e+03 6.13061133e+03 6.21838379e+03 6.20095801e+03 6.07308838e+03 6.06258789e+03 6.10586475e+03 6.10924121e+03 6.07712061e+03 5.97353174e+03 6.05165527e+03 6.08066357e+03 5.82851465e+03 5.84728418e+03 5.90352979e+03 5.83178418e+03 5.91927832e+03 5.83878467e+03 5.75454980e+03 5.82047510e+03 5.68596045e+03 5.69696680e+03 5.87207568e+03 5.73595898e+03 5.59736035e+03 5.52922021e+03 5.46605859e+03 5.58160498e+03 5.62634082e+03 5.48268945e+03 5.46539844e+03 5.51458447e+03 5.47903369e+03 5.41423584e+03 5.29047119e+03 5.25275732e+03 5.29731396e+03 5.32084863e+03 5.31951172e+03 5.14435254e+03 5.08681006e+03 5.15869922e+03 5.14614600e+03 5.11962549e+03 5.09854834e+03 4.98212988e+03 4.92991992e+03 5.08290869e+03 5.06458398e+03 4.86576221e+03 4.73467920e+03 4.73678076e+03 4.80112061e+03 4.74805908e+03 4.64857471e+03 4.68336328e+03 4.68385889e+03 4.64522168e+03 4.64667578e+03 4.54862305e+03 4.46808057e+03 4.50418066e+03 4.50311963e+03 4.38562598e+03 4.27080664e+03 4.30324365e+03 4.30356348e+03 4.25477344e+03 4.27368115e+03 4.18170361e+03 4.07684277e+03 4.07041748e+03 4.14325293e+03 4.05104517e+03 3.93153369e+03 3.95456836e+03 3.91167139e+03 3.83550903e+03 3.83084521e+03 3.74703223e+03 3.70607251e+03 3.71055981e+03 3.70000708e+03 3.70304053e+03 3.58738794e+03 3.53484570e+03 3.50833911e+03 3.44720801e+03 3.39723218e+03 3.32833472e+03 3.34183008e+03 3.31248682e+03 3.23524438e+03 3.16556396e+03 3.13474414e+03 3.15859692e+03 3.14275757e+03 3.10153003e+03 3.00354126e+03 2.94107568e+03 2.89789380e+03 2.81573218e+03 2.80753198e+03 2.78964453e+03 2.74029688e+03 2.69635962e+03 2.61642773e+03 2.56647217e+03 2.56711743e+03 2.56915503e+03 2.52811523e+03 2.42041260e+03 2.33604419e+03 2.32674878e+03 2.29391284e+03 2.23548022e+03 2.21248975e+03 2.18251514e+03 2.09895654e+03 2.04098669e+03 1.98703894e+03 1.94779150e+03 1.97342126e+03 1.93070117e+03 1.82701624e+03 1.79665735e+03 1.73872510e+03 1.65504407e+03 1.66433679e+03 1.63240613e+03 1.53947485e+03 1.49640552e+03 1.44828308e+03 1.38854224e+03 1.37804468e+03 1.36433398e+03 1.28793848e+03 1.22613403e+03 1.18457104e+03 1.13435547e+03 1.09091724e+03 1.04078210e+03 9.94590454e+02 9.50380737e+02 8.95273621e+02 8.52782715e+02 8.14349121e+02 7.55001160e+02 7.15041199e+02 6.76957703e+02 6.13918640e+02 5.59562866e+02 5.15414124e+02 4.77106598e+02 4.36341248e+02 3.87095734e+02 3.28335541e+02 2.74055969e+02 2.33126053e+02 1.91860123e+02 1.45837646e+02 9.44249420e+01 4.50626564e+01 -2.87130213e+00 -5.08166122e+01 -9.78537598e+01 -1.45810013e+02 -1.92663132e+02 -2.38206894e+02 -2.91922150e+02 -3.35771698e+02 -3.71198456e+02 -4.32198639e+02 -4.97336548e+02 -5.29744263e+02 -5.63756775e+02 -6.15758728e+02 -6.67287537e+02 -7.23865479e+02 -7.71904236e+02 -8.12799377e+02 -8.46105530e+02 -8.98056030e+02 -9.58431580e+02 -9.99313232e+02 -1.06020789e+03 -1.10629016e+03 -1.14024158e+03 -1.18139868e+03 -1.24448804e+03 -1.29455261e+03 -1.32295728e+03 -1.39221606e+03 -1.44809058e+03 -1.46351196e+03 -1.48715906e+03 -1.53750427e+03 -1.60226514e+03 -1.69077832e+03 -1.73230298e+03 -1.72899622e+03 -1.77230090e+03 -1.82159973e+03 -1.88979724e+03 -1.96604919e+03 -1.98486218e+03 -1.99030151e+03 -2.08710132e+03 -2.14218579e+03 -2.13475830e+03 -2.24579590e+03 -2.29478931e+03 -2.27464185e+03 -2.33202441e+03 -2.34396240e+03 -2.38505200e+03 -2.52030908e+03 -2.54878906e+03 -2.55066333e+03 -2.64361255e+03 -2.66239258e+03 -2.62940210e+03 -2.69428589e+03 -2.78802686e+03 -2.83034570e+03 -2.88703784e+03 -2.89943970e+03 -2.92017480e+03 -3.00800366e+03 -3.07211011e+03 -3.20122388e+03 -3.17572949e+03 -3.08489844e+03 -3.14937476e+03 -3.23314429e+03 -3.32162891e+03 -3.40166797e+03 -3.37365649e+03 -3.33525659e+03 -3.46162695e+03 -3.55657910e+03 -3.54276929e+03 -3.59133032e+03 -3.63461523e+03 -3.62063525e+03 -3.72229199e+03 -3.78170312e+03 -3.73513184e+03 -3.87927197e+03 -3.96407007e+03 -3.90646729e+03 -3.92580444e+03 -3.87117627e+03 -3.92018237e+03 -4.08152319e+03 -4.26095020e+03 -4.23296729e+03 -4.04084302e+03 -4.10187207e+03 -4.29616992e+03 -4.31204834e+03 -4.30288965e+03 -4.35861963e+03 -4.38312109e+03 -4.44531982e+03 -4.48685889e+03 -4.52601221e+03 -4.54700586e+03 -4.57153955e+03 -4.68541406e+03 -4.65701660e+03 -4.61178027e+03 -4.66291406e+03 -4.72027881e+03 -4.81547412e+03 -4.93894678e+03 -4.87040088e+03 -4.79700879e+03 -4.88465820e+03 -4.97021143e+03 -5.13742725e+03 -5.12782764e+03 -4.95155469e+03 -5.00383643e+03 -5.12542432e+03 -5.21990332e+03 -5.33118750e+03 -5.25654492e+03 -5.19119873e+03 -5.22802051e+03 -5.24009961e+03 -5.24319092e+03 -5.40523145e+03 -5.54485693e+03 -5.44947412e+03 -5.38540283e+03 -5.36190088e+03 -5.42828955e+03 -5.66263428e+03 -5.67087207e+03 -5.62339453e+03 -5.58921680e+03 -5.51771094e+03 -5.61385107e+03 -5.68456299e+03 -5.82998242e+03 -5.89104541e+03 -5.70447559e+03 -5.69960986e+03 -5.79517090e+03 -5.87722363e+03 -5.89549170e+03 -5.98118994e+03 -5.99856299e+03 -5.88810449e+03 -5.93616748e+03 -5.98798730e+03 -5.99940918e+03 -6.06033398e+03 -6.13491309e+03 -6.11422119e+03 -6.06546484e+03 -6.05186963e+03 -6.17584033e+03 -6.30016748e+03 -6.21719580e+03 -6.15678760e+03 -6.16220898e+03 -6.23260498e+03 -6.22957861e+03 -6.41979834e+03 -6.41511768e+03 -6.25776709e+03 -6.36121387e+03 -6.36131738e+03 -6.37753369e+03 -6.53522900e+03 -6.50553125e+03 -6.44440283e+03 -6.47917627e+03 -6.53298633e+03 -6.91637305e+03 -6.35920752e+03 -5.94857666e+03 -9.01762109e+03 -8.38649414e+03 -1.48310088e+04 -8.74486641e+04 20270600. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.10336172e+04 -1.32917529e+04 -8.11523193e+03 -7.27760449e+03 -7.19726514e+03 -8.80191211e+03 -7.25979639e+03 -8.58106934e+03 -6.47899072e+03 -6.35531982e+03 -6.91531543e+03 -6.82000879e+03 -6.64598340e+03 -6.79573193e+03 -6.89988086e+03 -6.99310449e+03 -6.83358594e+03 -6.55352197e+03 -6.66538721e+03 -6.83299512e+03 -6.71719434e+03 -6.57149268e+03 -6.50878906e+03 -6.70841797e+03 -7.01972266e+03 -6.91851270e+03 -6.53345361e+03 -6.27288086e+03 -6.44055518e+03 -6.73108887e+03 -6.88424121e+03 -6.74817480e+03 -6.43490088e+03 -6.48043555e+03 -6.56775537e+03 -6.70558398e+03 -6.66021289e+03 -6.29471631e+03 -6.33659863e+03 -6.65249365e+03 -6.56006982e+03 -6.36350635e+03 -6.42370508e+03 -6.44634863e+03 -6.50744482e+03 -6.50573438e+03 -6.25072852e+03 -6.10671582e+03 -6.38687646e+03 -6.55321533e+03 -6.42730615e+03 -6.18227197e+03 -5.99628467e+03 -6.28573535e+03 -6.51996094e+03 -6.31991602e+03 -6.08511816e+03 -5.85372949e+03 -5.96620557e+03 -6.25231543e+03 -6.33857568e+03 -6.21645801e+03 -6.04853760e+03 -6.05720703e+03 -5.95691406e+03 -5.95488184e+03 -5.97124170e+03 -5.80548975e+03 -5.87865430e+03 -6.03370312e+03 -5.93422363e+03 -5.66225391e+03 -5.60150537e+03 -5.84410986e+03 -6.01622559e+03 -5.90346094e+03 -5.67428125e+03 -5.49479785e+03 -5.51758057e+03 -5.62788623e+03 -5.84462109e+03 -5.72461475e+03 -5.36857520e+03 -5.42994141e+03 -5.49948145e+03 -5.52587793e+03 -5.58812549e+03 -5.33880322e+03 -5.32778955e+03 -5.43038379e+03 -5.36431934e+03 -5.27146484e+03 -5.18474609e+03 -5.21730908e+03 -5.28290918e+03 -5.23647217e+03 -5.05906299e+03 -4.98428418e+03 -5.11000732e+03 -5.16798242e+03 -5.12017188e+03 -5.00610400e+03 -4.82895605e+03 -4.85068604e+03 -4.96915967e+03 -4.97404004e+03 -4.82967676e+03 -4.60560791e+03 -4.59911572e+03 -4.79626221e+03 -4.87470117e+03 -4.70766553e+03 -4.49126953e+03 -4.49465820e+03 -4.60523877e+03 -4.53629883e+03 -4.38985498e+03 -4.32545312e+03 -4.44622559e+03 -4.46531299e+03 -4.32249756e+03 -4.22463379e+03 -4.12018701e+03 -4.20764844e+03 -4.36934473e+03 -4.21689746e+03 -4.04884644e+03 -3.97091772e+03 -3.96318018e+03 -3.99780444e+03 -4.02632788e+03 -3.95015991e+03 -3.74082715e+03 -3.72226172e+03 -3.85142749e+03 -3.85268359e+03 -3.72820264e+03 -3.59724829e+03 -3.61205591e+03 -3.64564233e+03 -3.60012866e+03 -3.49765430e+03 -3.34745044e+03 -3.33347852e+03 -3.43920215e+03 -3.40776465e+03 -3.29460156e+03 -3.17337891e+03 -3.16652515e+03 -3.20436548e+03 -3.21973291e+03 -3.16525464e+03 -2.95944189e+03 -2.94238794e+03 -2.97756079e+03 -2.92143970e+03 -2.87950537e+03 -2.80320874e+03 -2.77068286e+03 -2.74827930e+03 -2.68980786e+03 -2.61642334e+03 -2.56570190e+03 -2.58920630e+03 -2.58548340e+03 -2.50888477e+03 -2.38294434e+03 -2.31283984e+03 -2.34618701e+03 -2.37889844e+03 -2.32258130e+03 -2.20158179e+03 -2.08873071e+03 -2.03179968e+03 -2.06991846e+03 -2.10778931e+03 -2.00852417e+03 -1.86512756e+03 -1.84421716e+03 -1.85944836e+03 -1.82426160e+03 -1.77378601e+03 -1.69697729e+03 -1.64855884e+03 -1.60673926e+03 -1.54343579e+03 -1.49352881e+03 -1.46379858e+03 -1.43024426e+03 -1.38093091e+03 -1.33218848e+03 -1.27043542e+03 -1.21483850e+03 -1.19504736e+03 -1.16321228e+03 -1.10871338e+03 -1.02891077e+03 -9.63406494e+02 -9.57798523e+02 -9.29161255e+02 -8.66983643e+02 -8.09072693e+02 -7.37497253e+02 -6.90303406e+02 -6.75312988e+02 -6.47355103e+02 -5.85347107e+02 -5.12331421e+02 -4.64131104e+02 -4.30386749e+02 -3.87005707e+02 -3.35867828e+02 -2.87137390e+02 -2.41392639e+02 -1.90481262e+02 -1.40487518e+02 -9.13859482e+01 -4.44322205e+01 2.04155517e+00 4.99866333e+01 1.00019981e+02 1.48359741e+02 1.86882599e+02 2.35996597e+02 2.89105438e+02 3.37013977e+02 3.88871765e+02 4.30086609e+02 4.89411194e+02 5.36816223e+02 5.55185547e+02 5.94344910e+02 6.56724731e+02 7.36221191e+02 8.07898071e+02 8.35836426e+02 8.34271423e+02 8.58008423e+02 9.22610168e+02 1.02700732e+03 1.10688318e+03 1.12839490e+03 1.11000696e+03 1.14488892e+03 1.28206714e+03 1.32430945e+03 1.29820325e+03 1.35278711e+03 1.41961609e+03 1.46377295e+03 1.55667444e+03 1.56909192e+03 1.55762830e+03 1.64453247e+03 1.66217944e+03 1.74760657e+03 1.84748376e+03 1.80077686e+03 1.87273877e+03 1.98820020e+03 1.99485876e+03 2.01598950e+03 2.06302173e+03 2.12567480e+03 2.16200952e+03 2.20106445e+03 2.19484106e+03 2.23274243e+03 2.39694043e+03 2.51174854e+03 2.49091870e+03 2.41716040e+03 2.41695410e+03 2.50340112e+03 2.65456982e+03 2.78364404e+03 2.75202173e+03 2.66776953e+03 2.73966602e+03 2.87425513e+03 2.87644849e+03 2.88625684e+03 2.95314600e+03 2.96986279e+03 3.00326978e+03 3.18477100e+03 3.18018066e+03 3.09296094e+03 3.18352417e+03 3.17359790e+03 3.31865381e+03 3.44338721e+03 3.34598975e+03 3.48624023e+03 3.50735254e+03 3.40223682e+03 3.54136523e+03 3.48514917e+03 3.59698047e+03 3.88900903e+03 3.71730322e+03 3.57258252e+03 3.68008057e+03 3.89239014e+03 4.08381885e+03 4.04772095e+03 3.83585474e+03 3.76539941e+03 3.93244751e+03 4.14299023e+03 4.33759326e+03 4.26108643e+03 4.04555591e+03 4.08677710e+03 4.27015283e+03 4.36368066e+03 4.30334961e+03 4.29820264e+03 4.38178760e+03 4.43084814e+03 4.61581494e+03 4.63657324e+03 4.43310400e+03 4.46063965e+03 4.58728125e+03 4.63067139e+03 4.71469775e+03 4.73139746e+03 4.87974121e+03 4.83194922e+03 4.68040283e+03 4.80225000e+03 4.73996631e+03 4.92705664e+03 5.28723145e+03 4.99911279e+03 4.72562207e+03 4.89460498e+03 5.18704492e+03 5.37111377e+03 5.38786963e+03 5.11446338e+03 4.96159326e+03 5.08840479e+03 5.32908643e+03 5.59589502e+03 5.52605469e+03 5.20308643e+03 5.16948096e+03 5.41457080e+03 5.48863330e+03 5.64795850e+03 5.67983984e+03 5.36691211e+03 5.39474902e+03 5.67982227e+03 5.76290771e+03 5.62808789e+03 5.62437158e+03 5.65739600e+03 5.62280518e+03 5.90901953e+03 5.93489014e+03 5.70844141e+03 5.67398535e+03 5.78025977e+03 5.86956592e+03 5.88629688e+03 5.85891992e+03 6.07257178e+03 6.15658447e+03 5.98369775e+03 5.87662695e+03 5.75706494e+03 6.01052246e+03 6.41953711e+03 6.30642090e+03 5.97497705e+03 5.85455469e+03 6.11210400e+03 6.48203906e+03 6.27154248e+03 5.94506543e+03 6.06913428e+03 6.26417139e+03 6.43611035e+03 6.68880273e+03 6.48454785e+03 6.17085840e+03 6.08785205e+03 6.28519922e+03 6.49829688e+03 6.55362158e+03 6.48565186e+03 6.40475928e+03 6.38544580e+03 6.57499219e+03 6.55970898e+03 6.37514014e+03 6.36702002e+03 6.38074072e+03 6.73211377e+03 6.76147314e+03 6.54110645e+03 6.59388379e+03 6.66123389e+03 6.79338867e+03 6.58109424e+03 6.28371436e+03 6.64559717e+03 6.99613184e+03 6.80539258e+03 6.48527783e+03 6.56346924e+03 6.91075537e+03 6.88409082e+03 6.75020068e+03 6.76074023e+03 6.55278711e+03 6.59242480e+03 6.93954248e+03 6.89505762e+03 6.64416064e+03 6.48743896e+03 6.50099512e+03 6.83052979e+03 7.16892676e+03 6.83937891e+03 6.63625439e+03 6.84108936e+03 6.78363770e+03 7.03239990e+03 6.97519385e+03 6.62596729e+03 6.61989551e+03 6.82539990e+03 6.84088232e+03 6.86022998e+03 6839. 6.98979102e+03 7.12794629e+03 7.25963477e+03 7.07139746e+03 6.48704395e+03 7.15386572e+03 9.49044922e+03 9.44505859e+03 1.03906250e+04 9.55453418e+03 1.01931445e+04 1.18359209e+04 1.75669570e+04 2.00014980e+04 6.60897950e+06 47075812. 2126702. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.86402012e+04 1.47679941e+04 1.03802920e+04 1.05580664e+04 9.56497559e+03 9.59707910e+03 9.52384668e+03 9.31224414e+03 9.29209473e+03 9.24259180e+03 6.58058838e+03 7.16352637e+03 6.50028320e+03 6.18950000e+03 6.08048486e+03 5.92916064e+03 6.09303760e+03 6.09972607e+03 5.83126221e+03 5.78307129e+03 6.04557275e+03 6.06301855e+03 5.87496045e+03 5.81509863e+03 5.80735254e+03 5.81018555e+03 5.75286670e+03 5.70776904e+03 5.68459717e+03 5.65486523e+03 5.56663867e+03 5.53055664e+03 5.66920264e+03 5.66847363e+03 5.51693213e+03 5.48687695e+03 5.47935254e+03 5.46872217e+03 5.40825146e+03 5.36792285e+03 5.36013721e+03 5.19924805e+03 5.14208252e+03 5.23191064e+03 5.19449463e+03 5.36868311e+03 5.36731250e+03 5.13512695e+03 4.96085986e+03 4.91151270e+03 5.19601660e+03 5.19586865e+03 4.97803027e+03 4.84599316e+03 4.83916455e+03 4.85980127e+03 4.78595264e+03 4.93590039e+03 4.89542676e+03 4.58658789e+03 4.52506006e+03 4.71450195e+03 4.85797949e+03 4.70553564e+03 4.58000098e+03 4.54481934e+03 4.48466309e+03 4.40248633e+03 4.40396973e+03 4.37424316e+03 4.30932080e+03 4.27980518e+03 4.25008838e+03 4.25470068e+03 4.20883203e+03 4.25882715e+03 4.19193311e+03 4.03907129e+03 4.06669580e+03 4.03490625e+03 4.00591772e+03 3.98711719e+03 3.91011548e+03 3.85963940e+03 3.74844165e+03 3.62111768e+03 3.75768652e+03 3.77090405e+03 3.54114307e+03 3.52361133e+03 3.68645068e+03 3.73665063e+03 3.58142529e+03 3.45361963e+03 3.39448096e+03 3.35311011e+03 3.28678564e+03 3.23170996e+03 3.26249683e+03 3.20418188e+03 3.23662378e+03 3.16865991e+03 3.04187158e+03 3.05070483e+03 2.93270215e+03 2.90432349e+03 3.00931348e+03 2.93951709e+03 2.82488110e+03 2.71958350e+03 2.64157568e+03 2.73601074e+03 2.74802148e+03 2.62032812e+03 2.49498877e+03 2.45159424e+03 2.46546094e+03 2.41802930e+03 2.45096533e+03 2.42298145e+03 2.29438940e+03 2.20246045e+03 2.15827539e+03 2.20270874e+03 2.16583789e+03 2.06754126e+03 1.99444275e+03 1.95055603e+03 1.93328174e+03 1.83365942e+03 1.79516345e+03 1.85958276e+03 1.79618250e+03 1.69668750e+03 1.60868665e+03 1.55934961e+03 1.60476904e+03 1.56507715e+03 1.47286194e+03 1.38294641e+03 1.32925500e+03 1.32864014e+03 1.27896326e+03 1.23214502e+03 1.15621692e+03 1.13096533e+03 1.14181702e+03 1.06335022e+03 1.00731494e+03 9.64437805e+02 9.06347534e+02 8.46497314e+02 8.00727173e+02 7.64428955e+02 7.14892212e+02 6.63051147e+02 5.96661255e+02 5.61390930e+02 5.48207703e+02 4.77373108e+02 4.15468323e+02 3.79065521e+02 3.30945801e+02 2.93416138e+02 2.39426575e+02 1.84084702e+02 1.45260666e+02 9.71819153e+01 4.72105446e+01 -8.88646781e-01 -4.85792580e+01 -9.61802673e+01 -1.44260330e+02 -1.91462357e+02 -2.31990250e+02 -2.86332001e+02 -3.52615173e+02 -3.94360046e+02 -4.28280396e+02 -4.60270050e+02 -5.13156067e+02 -5.94377930e+02 -6.40615417e+02 -6.72639893e+02 -7.01460999e+02 -7.39920837e+02 -8.10037354e+02 -8.59074646e+02 -9.26662109e+02 -9.53066162e+02 -9.73184692e+02 -1.05263770e+03 -1.09587378e+03 -1.16734717e+03 -1.21011206e+03 -1.22533655e+03 -1.27218811e+03 -1.31599829e+03 -1.38391528e+03 -1.39356628e+03 -1.45402466e+03 -1.58374585e+03 -1.60462927e+03 -1.60940100e+03 -1.61190454e+03 -1.64963757e+03 -1.79342725e+03 -1.84999854e+03 -1.84095703e+03 -1.83828967e+03 -1.87943774e+03 -1.98249670e+03 -2.03561560e+03 -2.13057983e+03 -2.14529688e+03 -2.13888452e+03 -2.16260767e+03 -2.19543726e+03 -2.35576758e+03 -2.39830396e+03 -2.37105005e+03 -2.39508008e+03 -2.44036279e+03 -2.56567993e+03 -2.61523389e+03 -2.54520093e+03 -2.57896143e+03 -2.76618408e+03 -2.81160669e+03 -2.71492114e+03 -2.74297021e+03 -2.93706860e+03 -2.99751489e+03 -2.94365088e+03 -2.91539404e+03 -2.95869824e+03 -3.18129907e+03 -3.19940967e+03 -3.13979199e+03 -3.19563672e+03 -3.23116333e+03 -3.28745337e+03 -3.31006836e+03 -3.34807153e+03 -3.31343481e+03 -3.43660742e+03 -3.67842505e+03 -3.60233179e+03 -3.59916577e+03 -3.67343335e+03 -3.67584033e+03 -3.71398022e+03 -3.75504565e+03 -3.78620532e+03 -3.72801733e+03 -3.70663892e+03 -3.85589868e+03 -3.99245605e+03 -4.13829395e+03 -4.02933569e+03 -3.92250586e+03 -4.07716479e+03 -4.16277490e+03 -4.33504590e+03 -4.29882715e+03 -4.20080029e+03 -4.22697559e+03 -4.22287500e+03 -4.35249756e+03 -4.41714893e+03 -4.53772705e+03 -4.54400928e+03 -4.48686572e+03 -4.47650342e+03 -4.37392383e+03 -4.58898193e+03 -4.90133789e+03 -4.83455615e+03 -4.72878613e+03 -4.64647559e+03 -4.60542822e+03 -4.87925000e+03 -5.05994727e+03 -4.93777686e+03 -4.79841504e+03 -4.81057080e+03 -4.98746973e+03 -5.01020557e+03 -5.18711133e+03 -5.19301416e+03 -5.06807373e+03 -5.13833252e+03 -5.14979053e+03 -5.28365332e+03 -5.30341406e+03 -5.11722607e+03 -5.17312598e+03 -5.47903320e+03 -5.40537842e+03 -5.17148340e+03 -5.36280908e+03 -5.68921094e+03 -5.62137354e+03 -5.50905127e+03 -5.40315186e+03 -5.42000342e+03 -5.76776318e+03 -5.79414844e+03 -5.64554199e+03 -5.51845557e+03 -5.53487500e+03 -5.72631396e+03 -5.75136084e+03 -5.76950879e+03 -5.66350244e+03 -5.79968262e+03 -6.07803613e+03 -5.93435303e+03 -5.99877197e+03 -5.96415723e+03 -5.87065576e+03 -5.97320068e+03 -6.02385205e+03 -6.03412061e+03 -6.03002148e+03 -6.00020996e+03 -5.88187744e+03 -6.06264746e+03 -6.45107764e+03 -6.16099023e+03 -5.90110645e+03 -6.12545361e+03 -6.25805322e+03 -6.48755811e+03 -6.37623779e+03 -6.21990674e+03 -6.39316309e+03 -6.36961768e+03 -6.16535303e+03 -6.12468018e+03 -6.50611426e+03 -6.54218311e+03 -6.36172119e+03 -6.29895557e+03 -6.08427295e+03 -6.39465283e+03 -6.81678369e+03 -6.62251660e+03 -6.47131885e+03 -6.31564111e+03 -6.26399854e+03 -6.65264111e+03 -6.86136133e+03 -6.68146973e+03 -6.42263770e+03 -6.35797363e+03 -6.52599756e+03 -6.63105029e+03 -6.83128662e+03 -6.71372852e+03 -6.52890039e+03 -6.68329688e+03 -6.65737500e+03 -6.78831250e+03 -6.76036572e+03 -6.63780762e+03 -6.71493896e+03 -6.68838574e+03 -6.67423633e+03 -6.50177686e+03 -6.62513379e+03 -7.08909277e+03 -6.92735205e+03 -6.66437012e+03 -6.53669824e+03 -6.59878809e+03 -7.03433691e+03 -6.98142139e+03 -6.82638672e+03 -6.64336084e+03 -6.62715234e+03 -6.82641016e+03 -6.84123389e+03 -6.82881543e+03 -6.68639795e+03 -6.81182373e+03 -7.06951074e+03 -6.90289844e+03 -6.95539258e+03 -6.96513037e+03 -6.84193018e+03 -6.78181885e+03 -6.79910986e+03 -6.78364258e+03 -6.76982568e+03 -6.83121289e+03 -6.83422656e+03 -6.99770605e+03 -6.95805371e+03 -6.64343750e+03 -6.56957178e+03 -6.75365283e+03 -6.89914111e+03 -7.10938184e+03 -6.86308984e+03 -6.58780078e+03 -6.87361230e+03 -7.03590771e+03 -6.86722803e+03 -6.71225146e+03 -6.67836621e+03 -6.77593604e+03 -6.81120605e+03 -6.74348779e+03 -6.52828271e+03 -6.70566406e+03 -7.11198926e+03 -6.86276709e+03 -6.78864990e+03 -6.60889844e+03 -6.51632373e+03 -6.92899658e+03 -6.87981494e+03 -6.70771387e+03 -6.52704004e+03 -6.36858447e+03 -6.57881201e+03 -6.73984375e+03 -6.95390332e+03 -6.65475977e+03 -6.33179980e+03 -6.56083350e+03 -6.61207959e+03 -6.83061670e+03 -6.68333789e+03 -6.42675000e+03 -6.59802002e+03 -6.59152686e+03 -6.42505518e+03 -6.23980127e+03 -6.46370166e+03 -6.75500732e+03 -6.62204590e+03 -6.45695654e+03 -6.29449512e+03 -6.27462891e+03 -6.57188574e+03 -6.53971875e+03 -6.34813770e+03 -6.20314160e+03 -6.10098047e+03 -6.27616357e+03 -6.29071436e+03 -6.42141406e+03 -6.44222168e+03 -6.20613965e+03 -6.03399854e+03 -6.08308545e+03 -6.38755859e+03 -6.23897607e+03 -6.02570020e+03 -6.13610352e+03 -6.10090137e+03 -5.96941016e+03 -5.88021777e+03 -6.07341309e+03 -6.05935986e+03 -5.86933496e+03 -6.06932764e+03 -6.10286475e+03 -5.93936768e+03 -5.86187354e+03 -5.85347266e+03 -5.84054883e+03 -5.66516943e+03 -5.57201514e+03 -5.83084424e+03 -5.89472363e+03 -5.57363525e+03 -5.36675244e+03 -5.59536670e+03 -5.92244336e+03 -5.80056934e+03 -5.45231934e+03 -5.33095850e+03 -5.59041553e+03 -5.64671680e+03 -5.46822363e+03 -5.45075439e+03 -5.30947168e+03 -5.10492871e+03 -5.27024268e+03 -5.49646631e+03 -5.43127588e+03 -5.18164697e+03 -5.01752686e+03 -5.23283447e+03 -5.36318262e+03 -5.19311035e+03 -4.94216016e+03 -4.84647705e+03 -4.97460059e+03 -4.98027197e+03 -5.06856836e+03 -5.00860449e+03 -4.80763281e+03 -4.83687695e+03 -4.83820898e+03 -4.87436914e+03 -4.69696729e+03 -4.58263574e+03 -4.75216016e+03 -4.69845850e+03 -4.60276709e+03 -4.45800244e+03 -4.47944434e+03 -4.69010840e+03 -4.45707959e+03 -4.26143994e+03 -4.34094189e+03 -4.39176074e+03 -4.36685840e+03 -4.29224951e+03 -4.33996045e+03 -4.35012256e+03 -4.17829932e+03 -4.01744531e+03 -3.98318994e+03 -4.14485156e+03 -4.02866992e+03 -3.87611084e+03 -3.98381250e+03 -3.94798926e+03 -3.84206763e+03 -3.76969263e+03 -3.84456445e+03 -3.78236816e+03 -3.63153638e+03 -3.68720703e+03 -3.65928223e+03 -3.62969604e+03 -3.59093506e+03 -3.51279590e+03 -3.44069336e+03 -3.30869800e+03 -3.25309546e+03 -3.37606348e+03 -3.45917847e+03 -3.23725171e+03 -3.03591626e+03 -3.12947998e+03 -3.26852271e+03 -3.20452686e+03 -3.01349683e+03 -2.86400146e+03 -2.95368335e+03 -2.99053491e+03 -2.86280396e+03 -2.87854077e+03 -2.81910864e+03 -2.66478809e+03 -2.64794507e+03 -2.70040942e+03 -2.67417725e+03 -2.51913354e+03 -2.41134741e+03 -2.48357617e+03 -2.53164941e+03 -2.41653369e+03 -2.28164990e+03 -2.20497827e+03 -2.26880322e+03 -2.28538257e+03 -2.16190918e+03 -2.07394336e+03 -2.03905615e+03 -2.01882153e+03 -1.97058984e+03 -1.98130725e+03 -1.90006848e+03 -1.78407581e+03 -1.80103748e+03 -1.76892700e+03 -1.72742163e+03 -1.64528491e+03 -1.56840820e+03 -1.58109973e+03 -1.50055383e+03 -1.44776233e+03 -1.48911487e+03 -1.41094702e+03 -1.36764136e+03 -1.30919421e+03 -1.67539551e+03 -1.80318469e+03 -1.51271741e+03 -1.56165210e+03 -1.53683411e+03 -9.14234619e+02 -1.28294116e+03 -6.45945312e+03 -1.78577576e+03 -522877888. -1.22315000e+04 -18419674. 5.39781350e+06 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. 61294816. 8.60907617e+03 2.34301807e+03 1.52891809e+03 1.28939417e+03 1.21749109e+03 1.14620386e+03 9.29307922e+02 9.55889648e+02 9.54763428e+02 1.03257007e+03 1.20456848e+03 1.39819055e+03 1.19900037e+03 1.20723926e+03 1.36994983e+03 1.31189197e+03 1.35920837e+03 1.54598010e+03 1.57540881e+03 1.55374695e+03 1.63151172e+03 1.67962085e+03 1.67186975e+03 1.72650366e+03 1.81992407e+03 1.87742163e+03 1.92481067e+03 1.92270654e+03 1.92995984e+03 2.01918628e+03 2.08572461e+03 2.11216968e+03 2.13241943e+03 2.17521045e+03 2.27429761e+03 2.31904028e+03 2.33071899e+03 2.36176636e+03 2.40446631e+03 2.53953613e+03 2.59866675e+03 2.51223096e+03 2.53907031e+03 2.63972095e+03 2.69753516e+03 2.77970581e+03 2.80396851e+03 2.78474878e+03 2.86612427e+03 2.92987256e+03 2.96706885e+03 3.01893872e+03 3.01404199e+03 3.07342285e+03 3.14635205e+03 3.16364697e+03 3.19049438e+03 3.21812573e+03 3.26834131e+03 3.37488940e+03 3.43552344e+03 3.44605737e+03 3.40793628e+03 3.43800684e+03 3.58495386e+03 3.62411572e+03 3.57281909e+03 3.64607715e+03 3.71018921e+03 3.75049194e+03 3.84651050e+03 3.87749878e+03 3.82323608e+03 3.84272168e+03 3.99189478e+03 4.06631274e+03 4.00057349e+03 3.96250610e+03 4.04142676e+03 4.12890332e+03 4.26657324e+03 4.30522754e+03 4.18968018e+03 4.23730176e+03 4.39297266e+03 4.42930469e+03 4.41646875e+03 4.35873193e+03 4.36943701e+03 4.55686768e+03 4.63643066e+03 4.54864551e+03 4.58890479e+03 4.65260400e+03 4.68961621e+03 4.71452588e+03 4.72887988e+03 4.79607227e+03 4.84886426e+03 4.94507275e+03 4.95644922e+03 4.83225781e+03 4.87857715e+03 5.02998682e+03 5.00218066e+03 5.03798926e+03 5.07797949e+03 5.09071338e+03 5.23197070e+03 5.19313379e+03 5.16313281e+03 5.30400586e+03 5.35257471e+03 5.26975928e+03 5.27274414e+03 5.35288281e+03 5.40764258e+03 5.42316699e+03 5.39909961e+03 5.43024756e+03 5.50376123e+03 5.65952588e+03 5.64910254e+03 5.46582861e+03 5.55050977e+03 5.72177686e+03 5.73187744e+03 5.69244336e+03 5.64053223e+03 5.62906396e+03 5.78996680e+03 5.93989014e+03 5.87546875e+03 5.75269189e+03 5.80523340e+03 5.97995312e+03 6.03940723e+03 6.06394873e+03 5.94536230e+03 5.84559082e+03 5.95828223e+03 6.01728760e+03 6.02333789e+03 6.11570801e+03 6.06398389e+03 6.13304688e+03 6.29952246e+03 6.22115283e+03 6.01819238e+03 6.11741553e+03 6.27606738e+03 6.31300488e+03 6.37149072e+03 6.31829688e+03 6.21125098e+03 6.29733496e+03 6.51460107e+03 6.38376611e+03 6.13731445e+03 6.31340234e+03 6.51930762e+03 6.51822021e+03 6.41716406e+03 6.32628271e+03 6.36228174e+03 6.51239258e+03 6.50133252e+03 6.53080713e+03 6.59688477e+03 6.45299268e+03 6.52426318e+03 6.70079199e+03 6.57026270e+03 6.50110498e+03 6.54575195e+03 6.65811035e+03 6.72451514e+03 6.71911719e+03 6.54105908e+03 6.46208008e+03 6.66164551e+03 6.91631250e+03 6.95813135e+03 6.55246680e+03 6.54863135e+03 6.89846582e+03 6.78325684e+03 6.71524268e+03 6.68845166e+03 6.61624902e+03 6.73377979e+03 6.82291260e+03 6.82442041e+03 6.70569287e+03 6.67787695e+03 6.77597314e+03 6.91324756e+03 6.87984717e+03 6.78675098e+03 6.76500537e+03 6.85400049e+03 6.83469531e+03 6.70062598e+03 6.77743896e+03 6.84021729e+03 6.73492236e+03 6.90509229e+03 7.07690039e+03 6.70256348e+03 6.72665527e+03 6.93042041e+03 6.88680762e+03 6.89034229e+03 6.71028223e+03 6.75586084e+03 6.95344482e+03 6.94859229e+03 6.86622705e+03 6.67633203e+03 6.61186816e+03 6.81511670e+03 6.94040527e+03 6.84835498e+03 6.76660693e+03 6.86766260e+03 6.84431982e+03 6.93800537e+03 6.85648438e+03 6.69663086e+03 6.65637256e+03 6.71069189e+03 6.89853223e+03 6.78258008e+03 6.65807812e+03 6.71900537e+03 6.83033984e+03 6.83077734e+03 6.76584961e+03 6.64893896e+03 6.65572217e+03 6.75490430e+03 6.67800586e+03 6.81835010e+03 6.69092578e+03 6.56701660e+03 6.70238574e+03 6.52000635e+03 6.56717529e+03 6.75353760e+03 6.57601025e+03 6.52703662e+03 6.54189355e+03 6.59132227e+03 6.47850000e+03 6.39465479e+03 6.64223340e+03 6.74033252e+03 6.37441846e+03 6.36434766e+03 6.42344385e+03 6.41032861e+03 6.54960449e+03 6.46482275e+03 6.28125977e+03 6.32882666e+03 6.43894092e+03 6.40311865e+03 6.34722656e+03 6.20969922e+03 6.26707324e+03 6.33401904e+03 6.20831445e+03 6.20325098e+03 6.13367090e+03 6.10669775e+03 6.17569043e+03 6.21449121e+03 6.14771924e+03 6.03336914e+03 5.99370117e+03 6.13794727e+03 6.20312891e+03 5.96317383e+03 5.99654199e+03 6.00909717e+03 5.81586328e+03 5.92067725e+03 5.94164600e+03 5.77152783e+03 5.86380664e+03 5.86631348e+03 5.80569873e+03 5.90937793e+03 5.74509570e+03 5.64391406e+03 5.68666650e+03 5.71437451e+03 5.70558154e+03 5.52231348e+03 5.49548291e+03 5.58173682e+03 5.57481055e+03 5.56024170e+03 5.48188135e+03 5.37067871e+03 5.45763672e+03 5.56253516e+03 5.37214404e+03 5.22346631e+03 5.22524707e+03 5.36145605e+03 5.38253662e+03 5.16554932e+03 5.11164551e+03 5.13039844e+03 5.11144531e+03 5.07516992e+03 5.09085547e+03 5.01856641e+03 4.91854443e+03 4.96958398e+03 5.04992822e+03 4.91370898e+03 4.69896484e+03 4.74322119e+03 4.82194287e+03 4.77908008e+03 4.73963330e+03 4.65297461e+03 4.59417822e+03 4.68919824e+03 4.71697705e+03 4.55912012e+03 4.44816309e+03 4.45001758e+03 4.52730518e+03 4.45513086e+03 4.26104297e+03 4.24067773e+03 4.28622266e+03 4.26369043e+03 4.23564844e+03 4.23555859e+03 4.10817041e+03 4.09003052e+03 4.06154712e+03 3.94773120e+03 3.91828882e+03 3.91534399e+03 3.91792676e+03 3.90850537e+03 3.81600684e+03 3.70306055e+03 3.68895874e+03 3.74340845e+03 3.80166089e+03 3.72909766e+03 3.52011255e+03 3.48536523e+03 3.52292944e+03 3.46576782e+03 3.38910938e+03 3.35402661e+03 3.33559155e+03 3.31023999e+03 3.24547998e+03 3.13038623e+03 3.14982788e+03 3.18545435e+03 3.14760229e+03 3.05722388e+03 2.94013208e+03 2.92763184e+03 2.88707764e+03 2.82540771e+03 2.86517627e+03 2.81689478e+03 2.69290039e+03 2.65603296e+03 2.63962085e+03 2.65386255e+03 2.60427246e+03 2.52188184e+03 2.47167603e+03 2.41787354e+03 2.36237793e+03 2.29951733e+03 2.29130103e+03 2.25899121e+03 2.23401685e+03 2.17808862e+03 2.05238086e+03 2.04079749e+03 2.01134375e+03 1.96925940e+03 1.97920117e+03 1.87529504e+03 1.79186353e+03 1.81250146e+03 1.78902271e+03 1.70378430e+03 1.64410229e+03 1.58373450e+03 1.52679553e+03 1.49974597e+03 1.46644153e+03 1.41188586e+03 1.39066882e+03 1.35507434e+03 1.28573181e+03 1.22496680e+03 1.16415540e+03 1.13852429e+03 1.11183215e+03 1.04926868e+03 9.78300903e+02 9.32343933e+02 8.98164062e+02 8.63257690e+02 8.35702820e+02 7.63436157e+02 6.97392883e+02 6.63843994e+02 6.14088745e+02 5.63992249e+02 5.30817139e+02 4.78947266e+02 4.21952911e+02 3.81855591e+02 3.32189362e+02 2.83306488e+02 2.38714920e+02 1.90197845e+02 1.41227463e+02 9.25779114e+01 4.53713875e+01 -2.36771393e+00 -5.00971909e+01 -9.88950882e+01 -1.46408218e+02 -1.93766953e+02 -2.36445435e+02 -2.86975433e+02 -3.35644928e+02 -3.80770538e+02 -4.36884186e+02 -4.83651886e+02 -5.22209167e+02 -5.70245239e+02 -6.20709106e+02 -6.82645203e+02 -7.35519409e+02 -7.63930176e+02 -8.00984131e+02 -8.44483887e+02 -9.00664001e+02 -9.55703125e+02 -1.00572791e+03 -1.05675635e+03 -1.09772449e+03 -1.13654895e+03 -1.17329285e+03 -1.23541516e+03 -1.31384277e+03 -1.35085547e+03 -1.36877612e+03 -1.40948242e+03 -1.45352148e+03 -1.50312500e+03 -1.57535828e+03 -1.63370154e+03 -1.66188428e+03 -1.69643188e+03 -1.73061462e+03 -1.78279749e+03 -1.85714807e+03 -1.89639709e+03 -1.94596521e+03 -1.98973511e+03 -2.00654456e+03 -2.08264697e+03 -2.10052710e+03 -2.13527881e+03 -2.25209155e+03 -2.26150732e+03 -2.26865918e+03 -2.34110791e+03 -2.36425146e+03 -2.40017627e+03 -2.54741553e+03 -2.58338232e+03 -2.50897876e+03 -2.57485205e+03 -2.64370435e+03 -2.67336182e+03 -2.78031689e+03 -2.80782544e+03 -2.76621240e+03 -2.83963525e+03 -2.91394482e+03 -2.99781372e+03 -3.05906934e+03 -3.04801172e+03 -3.12076123e+03 -3.11917407e+03 -3.07977344e+03 -3.17114282e+03 -3.29239551e+03 -3.31811426e+03 -3.37745557e+03 -3.39697119e+03 -3.30355078e+03 -3.41273584e+03 -3.61114185e+03 -3.64033984e+03 -3.58242407e+03 -3.53652661e+03 -3.60294238e+03 -3.76524976e+03 -3.81700024e+03 -3.78800269e+03 -3.85322998e+03 -3.85599512e+03 -3.89875757e+03 -3.97049780e+03 -3.90266968e+03 -3.96514160e+03 -4.11163184e+03 -4.18873242e+03 -4.15555859e+03 -4.07100684e+03 -4.12099707e+03 -4.27670459e+03 -4.38333057e+03 -4.36209375e+03 -4.30710498e+03 -4.29412891e+03 -4.41062744e+03 -4.52981250e+03 -4.64021973e+03 -4.60260107e+03 -4.51007324e+03 -4.60952148e+03 -4.63334131e+03 -4.63798877e+03 -4.74521484e+03 -4.75675195e+03 -4.79883398e+03 -4.90868164e+03 -4.84683984e+03 -4.86414062e+03 -4.95080029e+03 -4.98867822e+03 -5.04475684e+03 -5.01551660e+03 -4.95640283e+03 -5.00883057e+03 -5.15436523e+03 -5.27925195e+03 -5.31028857e+03 -5.21233350e+03 -5.14153076e+03 -5.22806836e+03 -5.24693701e+03 -5.34163721e+03 -5.43665137e+03 -5.39208447e+03 -5.33597412e+03 -5.36959082e+03 -5.42919775e+03 -5.54742725e+03 -5.69258252e+03 -5.65195801e+03 -5.57134473e+03 -5.54972266e+03 -5.47959570e+03 -5.60840332e+03 -5.73780615e+03 -5.81478857e+03 -5.84304248e+03 -5.70511816e+03 -5.66640625e+03 -5.81940479e+03 -5.93300049e+03 -5.87899268e+03 -5.93627734e+03 -5.89675293e+03 -5.81756934e+03 -6.00325732e+03 -6.13858643e+03 -6.08458984e+03 -5.97118799e+03 -6.00965967e+03 -6.09646680e+03 -6.14327734e+03 -6.16408887e+03 -6.16456201e+03 -6.24424756e+03 -6.18474072e+03 -6.11283545e+03 -6.31522754e+03 -6.32661084e+03 -6.24734277e+03 -6.39157617e+03 -6.25329004e+03 -6.17781445e+03 -6.41851660e+03 -6.46687598e+03 -6.43927100e+03 -6.65945410e+03 -6.71139697e+03 -6.11519336e+03 -5.78279297e+03 -6.91359326e+03 -7.97806396e+03 -8.47137012e+03 -7.59697510e+03 -1.61481113e+04 -1.56417324e+04 -39223056. 56004376. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 66855588. 1.62207450e+06 -2.42330430e+04 -1.79677305e+04 -1.16578662e+04 -1.13582129e+04 -1.09664473e+04 -9.97798535e+03 -1.04527500e+04 -9.46057715e+03 -8.83332715e+03 -7.07830957e+03 -6.93380322e+03 -8.89863477e+03 -7.24564893e+03 -8.94785840e+03 -6.41319092e+03 -6.38371387e+03 -7.01829883e+03 -6.80507812e+03 -6.50415332e+03 -6.72833545e+03 -6.92584277e+03 -6.97537451e+03 -6.98141357e+03 -6.71426611e+03 -6.62186426e+03 -6.69792139e+03 -6.68777637e+03 -6.69518896e+03 -6.60268750e+03 -6.57481348e+03 -6.77657324e+03 -6.95555371e+03 -6.75337598e+03 -6.43587646e+03 -6.44696436e+03 -6.70378564e+03 -6.74059277e+03 -6.56581396e+03 -6.38923096e+03 -6.44948096e+03 -6.67143555e+03 -6.77489941e+03 -6.61722559e+03 -6.29430420e+03 -6.38829590e+03 -6.61092578e+03 -6.53509473e+03 -6.55755957e+03 -6.43819531e+03 -6.19096045e+03 -6.31240625e+03 -6.57820020e+03 -6.40711426e+03 -6.24296484e+03 -6.39617139e+03 -6.40568945e+03 -6.33674268e+03 -6.24626416e+03 -6.01828125e+03 -6.17056787e+03 -6.50597070e+03 -6.31734424e+03 -6.07000977e+03 -6.00760547e+03 -5.97956152e+03 -6.24223877e+03 -6.39544580e+03 -6.17604492e+03 -5.95283203e+03 -5.91213965e+03 -5.86523047e+03 -6.00262598e+03 -6.17299951e+03 -5.93276074e+03 -5.81494434e+03 -5.92915234e+03 -5.87579053e+03 -5.76129297e+03 -5.72547754e+03 -5.80262939e+03 -5.87819775e+03 -5.84027197e+03 -5.77290674e+03 -5.57357520e+03 -5.46158203e+03 -5.71704785e+03 -5.86068994e+03 -5.52936475e+03 -5.33033203e+03 -5.44590137e+03 -5.56999219e+03 -5.61808887e+03 -5.61752734e+03 -5.38097803e+03 -5.26866553e+03 -5.35733154e+03 -5.34324805e+03 -5.36738770e+03 -5.27756055e+03 -5.12106445e+03 -5.11704688e+03 -5.21926025e+03 -5.21825586e+03 -5.13762598e+03 -5.09982812e+03 -5.06744434e+03 -5.05443457e+03 -5.03185645e+03 -4.83844238e+03 -4.77816064e+03 -5.01069189e+03 -5.01152490e+03 -4.72408545e+03 -4.61345264e+03 -4.65310547e+03 -4.83451270e+03 -4.90703564e+03 -4.69548682e+03 -4.48761963e+03 -4.45719434e+03 -4.48594482e+03 -4.52335498e+03 -4.51060303e+03 -4.44221533e+03 -4.40716016e+03 -4.34630566e+03 -4.32419922e+03 -4.30468896e+03 -4.15821045e+03 -4.19354248e+03 -4.31558691e+03 -4.19397656e+03 -4.06924976e+03 -4.00203589e+03 -3.91525806e+03 -4.03204053e+03 -4.08699854e+03 -3.87227441e+03 -3.73540479e+03 -3.76856982e+03 -3.88214038e+03 -3.89148438e+03 -3.74290625e+03 -3.60583008e+03 -3.54710254e+03 -3.53894238e+03 -3.59324707e+03 -3.59108105e+03 -3.42076172e+03 -3.29008057e+03 -3.35869824e+03 -3.43559790e+03 -3.35567017e+03 -3.23727588e+03 -3.20125049e+03 -3.16270850e+03 -3.13921631e+03 -3.11883398e+03 -2.98566309e+03 -2.93617065e+03 -2.98532617e+03 -2.94501636e+03 -2.86624731e+03 -2.78082617e+03 -2.74875806e+03 -2.75521118e+03 -2.71512817e+03 -2.67735791e+03 -2.57894312e+03 -2.54286279e+03 -2.55186768e+03 -2.49027905e+03 -2.41998999e+03 -2.35051050e+03 -2.29907861e+03 -2.31902319e+03 -2.33613306e+03 -2.24079590e+03 -2.09303174e+03 -2.04136597e+03 -2.09480835e+03 -2.08588721e+03 -2.01234436e+03 -1.88931885e+03 -1.82452478e+03 -1.83623950e+03 -1.81604871e+03 -1.77934204e+03 -1.68757544e+03 -1.61047107e+03 -1.59321155e+03 -1.57733997e+03 -1.54536267e+03 -1.47549292e+03 -1.40658093e+03 -1.36924744e+03 -1.32931262e+03 -1.28335632e+03 -1.23348291e+03 -1.19264514e+03 -1.13439526e+03 -1.07796570e+03 -1.02621375e+03 -9.73313049e+02 -9.60928101e+02 -9.44274719e+02 -8.81894531e+02 -8.03461426e+02 -7.30316284e+02 -6.91126160e+02 -6.84648743e+02 -6.52032837e+02 -5.83440247e+02 -5.13246277e+02 -4.57338257e+02 -4.21818298e+02 -3.90133423e+02 -3.42477631e+02 -2.88792236e+02 -2.38489517e+02 -1.89224716e+02 -1.41333588e+02 -9.16721115e+01 -4.48099632e+01 2.08375192e+00 4.99719543e+01 1.00434105e+02 1.47403610e+02 1.83879044e+02 2.33552139e+02 2.91210022e+02 3.40952301e+02 3.88042236e+02 4.29831207e+02 4.88673157e+02 5.40340942e+02 5.62772888e+02 5.91768066e+02 6.51958130e+02 7.33296692e+02 8.04399292e+02 8.37171814e+02 8.38140320e+02 8.63431702e+02 9.23698303e+02 1.01894006e+03 1.10168079e+03 1.13011462e+03 1.11756824e+03 1.15031433e+03 1.27304321e+03 1.31460059e+03 1.30079297e+03 1.35961206e+03 1.42017749e+03 1.45847620e+03 1.55472546e+03 1.57274866e+03 1.56118567e+03 1.64573706e+03 1.66453650e+03 1.74918921e+03 1.84230969e+03 1.80399121e+03 1.87755396e+03 1.98192615e+03 1.98912170e+03 2.02201770e+03 2.06877344e+03 2.12177197e+03 2.17305322e+03 2.20491699e+03 2.17384277e+03 2.22444067e+03 2.40948340e+03 2.51900610e+03 2.49213208e+03 2.42331421e+03 2.40842651e+03 2.49994043e+03 2.65747876e+03 2.77271582e+03 2.75827490e+03 2.67270190e+03 2.72455176e+03 2.86267065e+03 2.87650830e+03 2.89101514e+03 2.95820752e+03 2.98636255e+03 3.01067993e+03 3.18384180e+03 3.16674414e+03 3.08740210e+03 3.19240894e+03 3.15973071e+03 3.30488159e+03 3.45201416e+03 3.35249146e+03 3.49751514e+03 3.48988965e+03 3.38677466e+03 3.54687109e+03 3.49946973e+03 3.61034180e+03 3.87919727e+03 3.70820288e+03 3.55675928e+03 3.67623560e+03 3.89503394e+03 4.08895410e+03 4.06059302e+03 3.87757056e+03 3.79865259e+03 3.88455420e+03 4.10397021e+03 4.32061230e+03 4.26103320e+03 4.08694556e+03 4.11465967e+03 4.25393408e+03 4.33680762e+03 4.30541162e+03 4.32299951e+03 4.37281299e+03 4.41083057e+03 4.61085840e+03 4.65752930e+03 4.42077051e+03 4.43508789e+03 4.60015381e+03 4.62919238e+03 4.70457324e+03 4.72116992e+03 4.89960400e+03 4.80916064e+03 4.64797021e+03 4.85115186e+03 4.74725781e+03 4.90018506e+03 5.27981885e+03 5.01179688e+03 4.73071680e+03 4.89852051e+03 5.17438818e+03 5.34900439e+03 5.36592090e+03 5.08456738e+03 4.96147656e+03 5.11698975e+03 5.32717041e+03 5.58265283e+03 5.50744971e+03 5.19927686e+03 5.18636377e+03 5.39646533e+03 5.51201709e+03 5.67985498e+03 5.68223193e+03 5.37599805e+03 5.36270703e+03 5.66986279e+03 5.76511523e+03 5.60194824e+03 5.59651270e+03 5.69207764e+03 5.66102051e+03 5.87246338e+03 5.94058936e+03 5.72604932e+03 5.70537598e+03 5.79520117e+03 5.85499805e+03 5.87934521e+03 5.88906348e+03 6.05927148e+03 6.13830225e+03 6.02405615e+03 5.86609033e+03 5.78342285e+03 6.05267090e+03 6.38623877e+03 6.30483447e+03 6.00774365e+03 5.86581006e+03 6.08263916e+03 6.46376221e+03 6.27229443e+03 5.91611377e+03 6.09068066e+03 6.28201758e+03 6.42563037e+03 6.67033008e+03 6.48613330e+03 6.11929150e+03 6.10706934e+03 6.32075244e+03 6.48237109e+03 6.53246045e+03 6.45976172e+03 6.43866797e+03 6.39897510e+03 6.56140918e+03 6.50054443e+03 6.36669238e+03 6.42940283e+03 6.38008838e+03 6.63561719e+03 6.79517773e+03 6.55120752e+03 6.66938721e+03 6.67875146e+03 6.64859473e+03 6.48354639e+03 6.36812402e+03 6.72629980e+03 6.95195166e+03 6.74751514e+03 6.49330078e+03 6.50542529e+03 6.86932422e+03 6.98821533e+03 6.79026709e+03 6.75377344e+03 6.55479980e+03 6.56833008e+03 6.88783594e+03 6.85194531e+03 6.73070996e+03 6.61740869e+03 6.49750146e+03 6.87290186e+03 7.12225879e+03 6.80048535e+03 6.65675049e+03 6.82089160e+03 6.78437549e+03 7.02083594e+03 7.00500195e+03 6.67710596e+03 6.56732568e+03 6.81124658e+03 6.86561328e+03 6.89566992e+03 6.98662695e+03 7.22014941e+03 7.22459131e+03 7.04433838e+03 6.98716602e+03 6.53672754e+03 7.36217529e+03 7.86972852e+03 7.35234033e+03 9.93486816e+03 1.36135625e+04 1.27680635e+04 2.83094844e+04 1.45392391e+05 45281080. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 50947440. 50947440. -3.28714275e+06 5.60369258e+04 1.62408652e+04 1.27142715e+04 1.08895977e+04 9.65992773e+03 9.30228418e+03 9.11501562e+03 9.62728613e+03 9.63537305e+03 9.29536035e+03 9.49688477e+03 9.42921680e+03 9.28252832e+03 9.32700781e+03 9.31189844e+03 7.81043115e+03 8.00987354e+03 6.58629346e+03 6.22940820e+03 6.06964990e+03 5.91619385e+03 6.08486328e+03 6.09355615e+03 5.81058887e+03 5.80862061e+03 6.04500439e+03 6.05324121e+03 5.87914062e+03 5.80820508e+03 5.80666113e+03 5.79177441e+03 5.76288818e+03 5.73623633e+03 5.68051514e+03 5.63252588e+03 5.51140527e+03 5.46524170e+03 5.71900195e+03 5.72443994e+03 5.49535498e+03 5.47989600e+03 5.48737695e+03 5.46724170e+03 5.39685547e+03 5.34830029e+03 5.36589941e+03 5.25891602e+03 5.21155713e+03 5.20034473e+03 5.15625293e+03 5.35396875e+03 5.34866650e+03 5.13261426e+03 4.96529785e+03 4.92294189e+03 5.20168945e+03 5.17669580e+03 4.97652881e+03 4.86117529e+03 4.85473047e+03 4.89003516e+03 4.78954688e+03 4.91310938e+03 4.89756836e+03 4.59241455e+03 4.51948828e+03 4.71751318e+03 4.86034473e+03 4.69811182e+03 4.56383887e+03 4.52868701e+03 4.47581787e+03 4.44677295e+03 4.41294922e+03 4.41164502e+03 4.37642920e+03 4.27624805e+03 4.23006445e+03 4.20590088e+03 4.17557178e+03 4.28301318e+03 4.20633252e+03 4.04408569e+03 4.02412769e+03 3.99781689e+03 4.05679468e+03 4.03118286e+03 3.89753711e+03 3.84673901e+03 3.75150488e+03 3.65669238e+03 3.78993579e+03 3.74558569e+03 3.50230347e+03 3.51312476e+03 3.68284692e+03 3.75551514e+03 3.59926416e+03 3.44421118e+03 3.37938599e+03 3.33586377e+03 3.31756787e+03 3.27774707e+03 3.23822314e+03 3.17893872e+03 3.23041455e+03 3.17769482e+03 3.04548047e+03 3.02687744e+03 2.89733643e+03 2.92154272e+03 3.05293262e+03 2.95313599e+03 2.82930078e+03 2.71024194e+03 2.65318042e+03 2.76475732e+03 2.73062476e+03 2.60060522e+03 2.49708838e+03 2.44413843e+03 2.45390161e+03 2.41653418e+03 2.45270874e+03 2.41562622e+03 2.29333643e+03 2.22971436e+03 2.18244141e+03 2.17793652e+03 2.14374902e+03 2.07115259e+03 1.99371521e+03 1.95483936e+03 1.91932532e+03 1.81386292e+03 1.81094836e+03 1.87600110e+03 1.80005298e+03 1.69950647e+03 1.60996179e+03 1.56147156e+03 1.60332153e+03 1.56206030e+03 1.47067834e+03 1.38416077e+03 1.33012988e+03 1.33342285e+03 1.28188708e+03 1.22979773e+03 1.15634912e+03 1.13134924e+03 1.14007568e+03 1.06267175e+03 1.00696851e+03 9.65670044e+02 9.07522644e+02 8.44355103e+02 7.98948669e+02 7.58879944e+02 7.07348267e+02 6.67550110e+02 6.02181519e+02 5.61951416e+02 5.50549194e+02 4.78498962e+02 4.13922211e+02 3.78257446e+02 3.31070679e+02 2.92801331e+02 2.40930984e+02 1.85945679e+02 1.44153305e+02 9.63716812e+01 4.72743263e+01 -6.31785095e-01 -4.81419640e+01 -9.56141357e+01 -1.43139038e+02 -1.91096268e+02 -2.32608856e+02 -2.87039734e+02 -3.52867432e+02 -3.93875763e+02 -4.26808258e+02 -4.60275665e+02 -5.15225830e+02 -5.94533020e+02 -6.37999634e+02 -6.69653625e+02 -7.02543945e+02 -7.41630005e+02 -8.09148438e+02 -8.60260071e+02 -9.26196411e+02 -9.63041809e+02 -9.85139771e+02 -1.03916785e+03 -1.08393811e+03 -1.16936987e+03 -1.20992358e+03 -1.22091931e+03 -1.27318335e+03 -1.32135669e+03 -1.36738220e+03 -1.37824304e+03 -1.46412415e+03 -1.60338647e+03 -1.61124890e+03 -1.60568652e+03 -1.60910767e+03 -1.64375195e+03 -1.78985461e+03 -1.85460559e+03 -1.84327002e+03 -1.83737048e+03 -1.87609229e+03 -1.98002026e+03 -2.02926599e+03 -2.12780029e+03 -2.16842871e+03 -2.15842334e+03 -2.14024219e+03 -2.17729346e+03 -2.35771362e+03 -2.39684229e+03 -2.37472900e+03 -2.37657056e+03 -2.40938574e+03 -2.59104077e+03 -2.65078320e+03 -2.53402783e+03 -2.56622217e+03 -2.77289575e+03 -2.82186157e+03 -2.71035962e+03 -2.74797998e+03 -2.93414990e+03 -2.99704956e+03 -2.94736865e+03 -2.91650195e+03 -2.96255981e+03 -3.17041797e+03 -3.18634180e+03 -3.11689160e+03 -3.20503516e+03 -3.24892163e+03 -3.27926489e+03 -3.31825806e+03 -3.36263110e+03 -3.32267285e+03 -3.44208008e+03 -3.63875269e+03 -3.57959717e+03 -3.64884424e+03 -3.70770410e+03 -3.66364771e+03 -3.70813403e+03 -3.74673975e+03 -3.76991089e+03 -3.74174146e+03 -3.76723706e+03 -3.89229663e+03 -3.95027686e+03 -4.09448242e+03 -4.01932642e+03 -3.92812207e+03 -4.07173901e+03 -4.15232324e+03 -4.32410889e+03 -4.31092822e+03 -4.20642920e+03 -4.21349609e+03 -4.22594238e+03 -4.35642480e+03 -4.39253516e+03 -4.53057275e+03 -4.55443164e+03 -4.47827051e+03 -4.51298096e+03 -4.40918506e+03 -4.57126855e+03 -4.86853125e+03 -4.83712939e+03 -4.73577490e+03 -4.63813721e+03 -4.60201855e+03 -4.85786426e+03 -5.05874316e+03 -4.96581494e+03 -4.79824609e+03 -4.82744043e+03 -4.98828662e+03 -5.00720850e+03 -5.16202051e+03 -5.17516162e+03 -5.06975928e+03 -5.09380908e+03 -5.10884961e+03 -5.33797949e+03 -5.38984424e+03 -5.12085303e+03 -5.13656738e+03 -5.46636670e+03 -5.45816602e+03 -5.20758301e+03 -5.31053955e+03 -5.61376904e+03 -5.63647266e+03 -5.52595801e+03 -5.41296924e+03 -5.39710645e+03 -5.72397852e+03 -5.79701025e+03 -5.66499756e+03 -5.54024414e+03 -5.51081641e+03 -5.69484717e+03 -5.76725635e+03 -5.79496387e+03 -5.65014551e+03 -5.81497168e+03 -6.07742773e+03 -5.94743750e+03 -5.99367822e+03 -5.95628516e+03 -5.88280273e+03 -5.97582959e+03 -5.99940283e+03 -6.05654297e+03 -6.02847656e+03 -5.96047217e+03 -5.85352148e+03 -6.09295557e+03 -6.41125146e+03 -6.12498096e+03 -5.86829395e+03 -6.10686621e+03 -6.31543604e+03 -6.53311182e+03 -6.35722998e+03 -6.18710449e+03 -6.38285352e+03 -6.41057520e+03 -6.21812207e+03 -6.15431836e+03 -6.42465674e+03 -6.42676465e+03 -6.35218652e+03 -6.30036279e+03 -6.12287939e+03 -6.40167188e+03 -6.82116016e+03 -6.65405176e+03 -6.48320605e+03 -6.32099902e+03 -6.25950146e+03 -6.63864502e+03 -6.86469385e+03 -6.67263525e+03 -6.46472168e+03 -6.47388037e+03 -6.51751270e+03 -6.53853369e+03 -6.77255762e+03 -6.70652881e+03 -6.54200635e+03 -6.62761572e+03 -6.58616504e+03 -6.83525684e+03 -6.86884277e+03 -6.64619775e+03 -6.67236182e+03 -6.67341309e+03 -6.73295996e+03 -6.60164844e+03 -6.62850684e+03 -6.95194678e+03 -6.89224121e+03 -6.77506592e+03 -6.58149414e+03 -6.62327588e+03 -7.04818945e+03 -7.02533545e+03 -6.81875049e+03 -6.69778467e+03 -6.63450098e+03 -6.72072217e+03 -6.76179004e+03 -6.84328809e+03 -6.68816455e+03 -6.75677783e+03 -7.05319238e+03 -6.82896973e+03 -6.99654395e+03 -7.00078516e+03 -6.82011328e+03 -6.78907520e+03 -6.78853857e+03 -6.81112988e+03 -6.81236328e+03 -6.76501758e+03 -6.79677539e+03 -6.93378125e+03 -6.97814844e+03 -6.65839844e+03 -6.62824414e+03 -6.74898975e+03 -6.86996484e+03 -7.09164258e+03 -6.96526367e+03 -6628. -6.82909277e+03 -6.96201758e+03 -6.85612402e+03 -6.76832275e+03 -6.72643262e+03 -6.67285742e+03 -6.67818457e+03 -6.85740527e+03 -6.62266016e+03 -6.70748291e+03 -7.03387988e+03 -6.88934375e+03 -6.72580078e+03 -6.61783838e+03 -6.57031787e+03 -6.91601074e+03 -6.86551025e+03 -6.69739746e+03 -6.57313330e+03 -6.36840137e+03 -6.50859131e+03 -6.79232715e+03 -6.97541846e+03 -6.70404004e+03 -6.48508545e+03 -6.51980371e+03 -6.54345703e+03 -6.79076221e+03 -6.73727490e+03 -6.49669141e+03 -6.48804785e+03 -6.46240625e+03 -6.49122266e+03 -6.36515771e+03 -6.41515723e+03 -6.66591064e+03 -6.57275830e+03 -6.46572705e+03 -6.33371533e+03 -6.25464697e+03 -6.59360645e+03 -6.57193652e+03 -6.36421045e+03 -6.18897998e+03 -6.14834473e+03 -6.25767334e+03 -6.28714160e+03 -6.42665527e+03 -6.44123291e+03 -6.18089355e+03 -6.01852734e+03 -6.06990674e+03 -6.37892920e+03 -6.28805566e+03 -6.12322998e+03 -6.07257568e+03 -6.01687695e+03 -5.99378467e+03 -5.93077539e+03 -6.05880811e+03 -6.01532373e+03 -5.87228027e+03 -6.05065967e+03 -6.09652441e+03 -5.95120068e+03 -5.87082764e+03 -5.83583594e+03 -5.83018799e+03 -5.67285693e+03 -5.57817529e+03 -5.84554492e+03 -5.88396631e+03 -5.56357178e+03 -5.40460400e+03 -5.66262939e+03 -5.86972266e+03 -5.74430225e+03 -5.49506641e+03 -5.34120654e+03 -5.54025049e+03 -5.60100928e+03 -5.47134326e+03 -5.44018994e+03 -5.29376221e+03 -5.05647510e+03 -5.22260596e+03 -5.52687012e+03 -5.50229639e+03 -5.17858936e+03 -5.00107129e+03 -5.23650830e+03 -5.36873340e+03 -5.17317334e+03 -4.98070068e+03 -4.90112061e+03 -4.92453613e+03 -4.94746240e+03 -5.08070752e+03 -5.06094775e+03 -4.86684473e+03 -4.76737598e+03 -4.72617383e+03 -4.88766309e+03 -4.75999268e+03 -4.60536719e+03 -4.76568311e+03 -4.70800635e+03 -4.61897559e+03 -4.49665723e+03 -4.44235742e+03 -4.64269727e+03 -4.47380762e+03 -4.27304736e+03 -4.34274512e+03 -4.40020117e+03 -4.37253564e+03 -4.28409180e+03 -4.33555176e+03 -4.33801025e+03 -4.18482617e+03 -4.01765259e+03 -3.96937305e+03 -4.17069531e+03 -4.06417236e+03 -3.91579102e+03 -3.92182812e+03 -3.86906860e+03 -3.89823706e+03 -3.84087305e+03 -3.82139404e+03 -3.75094531e+03 -3.62574243e+03 -3.71123315e+03 -3.69501929e+03 -3.60456714e+03 -3.56135229e+03 -3.51115869e+03 -3.43288428e+03 -3.30442236e+03 -3.25646704e+03 -3.38546069e+03 -3.46492017e+03 -3.23392944e+03 -3.05522705e+03 -3.16475122e+03 -3.24278613e+03 -3.16125146e+03 -3.00867383e+03 -2.88894507e+03 -2.99166309e+03 -2.95942432e+03 -2.81543506e+03 -2.89862793e+03 -2.83458447e+03 -2.63235278e+03 -2.62394702e+03 -2.72132104e+03 -2.70245166e+03 -2.52364087e+03 -2.40885596e+03 -2.48645630e+03 -2.53052466e+03 -2.42198975e+03 -2.28582275e+03 -2.20146045e+03 -2.27029443e+03 -2.26079199e+03 -2.14384766e+03 -2.11740039e+03 -2.08404248e+03 -2.00452380e+03 -1.94564624e+03 -1.97527454e+03 -1.90158936e+03 -1.78658716e+03 -1.80055334e+03 -1.76945630e+03 -1.73191016e+03 -1.64528137e+03 -1.56589648e+03 -1.58498315e+03 -1.50068555e+03 -1.44991882e+03 -1.55116760e+03 -1.47720898e+03 -1.38873267e+03 -1.28004919e+03 -2.39839966e+03 -3.69486816e+03 -3.07921826e+03 -2.77122412e+03 -2.92925928e+03 -1.57506555e+03 -4.47582861e+03 -2.74513242e+04 -1.18801138e+06 520358368. 520358368. 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. 61294816. 8.60907617e+03 2.34301807e+03 1.52891809e+03 1.28939417e+03 1.09089758e+03 1.15780029e+03 1.05645288e+03 1.09927393e+03 1.05327441e+03 1.10181140e+03 1.15798352e+03 1.18692664e+03 1.23759753e+03 1.27522864e+03 1.31105774e+03 1.39001428e+03 1.43726697e+03 1.47044324e+03 1.52741626e+03 1.52763049e+03 1.56686108e+03 1.66796252e+03 1.69473303e+03 1.72164734e+03 1.81818945e+03 1.91325024e+03 1.91023474e+03 1.90261377e+03 1.94490479e+03 1.97569971e+03 2.06953247e+03 2.16158740e+03 2.16324048e+03 2.20125195e+03 2.29850635e+03 2.31444238e+03 2.30032983e+03 2.36539844e+03 2.40983838e+03 2.46264795e+03 2.57767749e+03 2.56682056e+03 2.57393848e+03 2.69259180e+03 2.70209009e+03 2.70268311e+03 2.74879688e+03 2.80861475e+03 2.88638940e+03 2.93394824e+03 3.02044458e+03 3.00952466e+03 3.00778979e+03 3.12063550e+03 3.09505469e+03 3.09321460e+03 3.23039526e+03 3.27093774e+03 3.28168823e+03 3.38449829e+03 3.41567456e+03 3.39709570e+03 3.44713965e+03 3.47224878e+03 3.48180737e+03 3.58018066e+03 3.63939502e+03 3.69520190e+03 3.75469482e+03 3.74308203e+03 3.75653125e+03 3.81266650e+03 3.88477490e+03 3.88879126e+03 3.93261963e+03 4.10197314e+03 4.05790283e+03 3.94468872e+03 4.07227271e+03 4.11702002e+03 4.12130908e+03 4.26204541e+03 4.27254785e+03 4.25290088e+03 4.40686621e+03 4.48929395e+03 4.40294971e+03 4.34353857e+03 4.37112842e+03 4.45217773e+03 4.58346436e+03 4.63016064e+03 4.65597656e+03 4.73679346e+03 4.73710645e+03 4.67810645e+03 4.65108057e+03 4.78243994e+03 4.83771875e+03 4.81612549e+03 4.91949805e+03 4.93727490e+03 4.92350928e+03 5.06125195e+03 5.00565576e+03 4.93510400e+03 5.02901318e+03 5.15551611e+03 5.22179004e+03 5.16341846e+03 5.21112305e+03 5.32523193e+03 5.36212891e+03 5.33152393e+03 5.23999658e+03 5.26521240e+03 5.44271777e+03 5.49316455e+03 5.42684424e+03 5.49387598e+03 5.47126953e+03 5.45463574e+03 5.62102930e+03 5.61121924e+03 5.53235840e+03 5.61505176e+03 5.76872412e+03 5.82184766e+03 5.76622559e+03 5.63844922e+03 5.64045459e+03 5.81056348e+03 5.92658789e+03 5.78728271e+03 5.84283545e+03 6.06783594e+03 6.02894629e+03 5.96989844e+03 5.96079541e+03 5.84897559e+03 5.87477100e+03 5.96971924e+03 6.08962256e+03 6.11822803e+03 6.12374072e+03 6.21300293e+03 6.20363086e+03 6.11191504e+03 6.07944434e+03 6.11066943e+03 6.22368994e+03 6.30776660e+03 6.40144678e+03 6.38094971e+03 6.31308789e+03 6.27056689e+03 6.33597314e+03 6.41991602e+03 6.20696094e+03 6.26961719e+03 6.50169238e+03 6.56463721e+03 6.42255957e+03 6.39687646e+03 6.39303125e+03 6.36942822e+03 6.48012891e+03 6.64450830e+03 6.65859717e+03 6.54720068e+03 6.54555713e+03 6.58950732e+03 6.51423193e+03 6.53715869e+03 6.57791504e+03 6.54804443e+03 6.77093066e+03 6.86336670e+03 6.53523047e+03 6.57680908e+03 6.62959912e+03 6.69005371e+03 6.82122217e+03 6.58378271e+03 6.55309619e+03 6.83295752e+03 6.84802100e+03 6.77612695e+03 6.73143506e+03 6.67996094e+03 6.63506689e+03 6.77717432e+03 6.91824902e+03 6.79766748e+03 6.67204980e+03 6.84713867e+03 7.01049072e+03 6.79238525e+03 6.72850879e+03 6.77215234e+03 6.72559570e+03 6.90102979e+03 6.80644482e+03 6.79408105e+03 6.94741309e+03 6.75175977e+03 6.75249951e+03 6.85732471e+03 6.70729736e+03 6.75945508e+03 6.88671289e+03 6.90931641e+03 6.90737939e+03 6.81585059e+03 6.81627295e+03 6.77802832e+03 6.82791650e+03 6.93680127e+03 6.75259131e+03 6.67232422e+03 6.84100830e+03 6.93998682e+03 6.79269482e+03 6.86248291e+03 6.90560156e+03 6.70701514e+03 6.83363330e+03 6.96765723e+03 6.76222607e+03 6.64523193e+03 6.77246484e+03 6.74792871e+03 6.71582617e+03 6.68658936e+03 6.70409033e+03 6.75408838e+03 6.83451367e+03 6.81238818e+03 6.72917725e+03 6.71422266e+03 6.70042871e+03 6.63478418e+03 6.78786475e+03 6.57046680e+03 6.54655469e+03 6.78452100e+03 6.63445459e+03 6.55607861e+03 6.60773242e+03 6.61910742e+03 6.50121533e+03 6.51583936e+03 6.56266846e+03 6.64390625e+03 6.55290430e+03 6.53630811e+03 6.56233301e+03 6.40102002e+03 6.38243066e+03 6.41387207e+03 6.35160938e+03 6.49271240e+03 6.59222070e+03 6.39682861e+03 6.27505469e+03 6.32194678e+03 6.46640039e+03 6.39539648e+03 6.10805957e+03 6.26664307e+03 6.42710107e+03 6.27607324e+03 6.23093359e+03 6.16711133e+03 6.12140625e+03 6.18156689e+03 6.10652588e+03 6.03337158e+03 6.17588037e+03 6.14871729e+03 6.03456494e+03 6.09362158e+03 6.06095557e+03 6.02723242e+03 5.94275293e+03 5.77881104e+03 5.92133643e+03 6.01410254e+03 5.79966357e+03 5.77697412e+03 5.80112207e+03 5.84965576e+03 5.86205371e+03 5.64501855e+03 5.70837402e+03 5.82296436e+03 5.70411670e+03 5.63244971e+03 5.58187109e+03 5.51412158e+03 5.56023389e+03 5.53077344e+03 5.46032227e+03 5.53002588e+03 5.52674023e+03 5.45883984e+03 5.45698975e+03 5.39868018e+03 5.27549072e+03 5.23981494e+03 5.32158789e+03 5.32776807e+03 5.18043652e+03 5.11533105e+03 5.07506641e+03 5.06932275e+03 5.15051318e+03 5.07752393e+03 4.95711621e+03 4.95155615e+03 5.01136328e+03 5.02448389e+03 4.91156445e+03 4.77919971e+03 4.76840234e+03 4.79902246e+03 4.72696582e+03 4.68441357e+03 4.70950146e+03 4.68155322e+03 4.63064014e+03 4.66231006e+03 4.60543896e+03 4.47849805e+03 4.42473096e+03 4.45523730e+03 4.43862988e+03 4.27724609e+03 4.19647559e+03 4.27139844e+03 4.28851562e+03 4.27731494e+03 4.20788428e+03 4.07751465e+03 4.12665430e+03 4.14469824e+03 3.95694531e+03 3.88072876e+03 3.96927515e+03 3.99300073e+03 3.88178223e+03 3.77392236e+03 3.69888623e+03 3.69427808e+03 3.74645605e+03 3.76033008e+03 3.70913696e+03 3.56458862e+03 3.48783594e+03 3.47773853e+03 3.42216846e+03 3.39903198e+03 3.36153833e+03 3.31603906e+03 3.31036157e+03 3.27035107e+03 3.19711353e+03 3.13489819e+03 3.12744604e+03 3.16709717e+03 3.09030078e+03 2.94597925e+03 2.88043921e+03 2.90037646e+03 2.91751123e+03 2.88150977e+03 2.79845728e+03 2.66569507e+03 2.63073486e+03 2.67049097e+03 2.64957983e+03 2.60339941e+03 2.51863794e+03 2.44475513e+03 2.42944873e+03 2.36609473e+03 2.34095532e+03 2.28788110e+03 2.18512158e+03 2.20735547e+03 2.20703149e+03 2.12318872e+03 2.03830750e+03 1.94568994e+03 1.94777856e+03 1.99487866e+03 1.93170837e+03 1.81823462e+03 1.79678040e+03 1.78051746e+03 1.68435303e+03 1.62698938e+03 1.56805261e+03 1.52969421e+03 1.54350049e+03 1.47877124e+03 1.38694775e+03 1.36864075e+03 1.34223633e+03 1.28051184e+03 1.23266931e+03 1.19702454e+03 1.13540881e+03 1.07753491e+03 1.04313037e+03 9.92083191e+02 9.57547302e+02 9.14500427e+02 8.58422180e+02 8.11097900e+02 7.47480103e+02 7.04242249e+02 6.64181824e+02 6.13483521e+02 5.74449890e+02 5.30683472e+02 4.79359863e+02 4.23843140e+02 3.74346497e+02 3.30681305e+02 2.85905762e+02 2.38861221e+02 1.88211227e+02 1.41305832e+02 9.40608444e+01 4.52525063e+01 -2.81993580e+00 -5.08366432e+01 -9.65677567e+01 -1.44578949e+02 -1.92544937e+02 -2.38238312e+02 -2.91481506e+02 -3.36475464e+02 -3.79187622e+02 -4.40465210e+02 -4.94315460e+02 -5.18499451e+02 -5.58988403e+02 -6.26992371e+02 -6.85221558e+02 -7.29726135e+02 -7.58732788e+02 -7.93053772e+02 -8.48049011e+02 -9.15248047e+02 -9.66122620e+02 -9.91710083e+02 -1.03839954e+03 -1.09708276e+03 -1.13762244e+03 -1.19680859e+03 -1.25055823e+03 -1.28472388e+03 -1.33903308e+03 -1.37937622e+03 -1.42926538e+03 -1.46586523e+03 -1.50059534e+03 -1.56954077e+03 -1.61721570e+03 -1.65925586e+03 -1.68837451e+03 -1.72673535e+03 -1.81396362e+03 -1.86193811e+03 -1.89158752e+03 -1.95446765e+03 -1.95364111e+03 -1.98109619e+03 -2.10406543e+03 -2.14090552e+03 -2.12380103e+03 -2.22410669e+03 -2.27538574e+03 -2.25118579e+03 -2.35433984e+03 -2.41083838e+03 -2.39760913e+03 -2.49478735e+03 -2.55417310e+03 -2.53158618e+03 -2.59452612e+03 -2.66515210e+03 -2.69379980e+03 -2.75345581e+03 -2.79430688e+03 -2.75693384e+03 -2.81989722e+03 -2.96058813e+03 -3.01834131e+03 -3.04262598e+03 -3.02375464e+03 -3.07828662e+03 -3.11228418e+03 -3.09987646e+03 -3.21947778e+03 -3.27265186e+03 -3.27445947e+03 -3.38654468e+03 -3.39208911e+03 -3.35435376e+03 -3.45659033e+03 -3.53959814e+03 -3.60221338e+03 -3.60165625e+03 -3.59191919e+03 -3.60112329e+03 -3.72590210e+03 -3.88251855e+03 -3.78799243e+03 -3.79517310e+03 -3.81732446e+03 -3.87370996e+03 -4.02640576e+03 -3.96993091e+03 -3.94055566e+03 -4.04675391e+03 -4.14684521e+03 -4.15750488e+03 -4.07901782e+03 -4.18836182e+03 -4.32351904e+03 -4.29933008e+03 -4.34534326e+03 -4.32066211e+03 -4.36649512e+03 -4.48941846e+03 -4.51092969e+03 -4.57004150e+03 -4.52530615e+03 -4.51480176e+03 -4.61747070e+03 -4.66332520e+03 -4.73300098e+03 -4.72943799e+03 -4.68030078e+03 -4.74801855e+03 -4.87777295e+03 -4.90410596e+03 -4.89698340e+03 -4.92529004e+03 -4.94840918e+03 -5.01065283e+03 -5.01660889e+03 -4.98434180e+03 -5.12168457e+03 -5.16548145e+03 -5.13486377e+03 -5.27580029e+03 -5.22355420e+03 -5.17689209e+03 -5.28600635e+03 -5.25135938e+03 -5.30066455e+03 -5.41632910e+03 -5.40579541e+03 -5.34017139e+03 -5.39550000e+03 -5.48484424e+03 -5.51270752e+03 -5.65225830e+03 -5.62479639e+03 -5.54200830e+03 -5.59873291e+03 -5.56562305e+03 -5.64705518e+03 -5.68320605e+03 -5.75693750e+03 -5.85642529e+03 -5.71780664e+03 -5.79621924e+03 -5.85833789e+03 -5.79204932e+03 -5.85044678e+03 -5.94637402e+03 -5.98773291e+03 -5.92206494e+03 -5.96416895e+03 -6.05071240e+03 -6.04253418e+03 -6.00656982e+03 -6.03883838e+03 -6.06388525e+03 -6.17482764e+03 -6.12834863e+03 -6.14141895e+03 -6.24401221e+03 -6.13039502e+03 -6.13263867e+03 -6.35521973e+03 -6.38248828e+03 -6.21515820e+03 -6.24022119e+03 -6.24403467e+03 -6.21925586e+03 -6.57692432e+03 -6.46926953e+03 -6.28108594e+03 -6.61743115e+03 -6.72018555e+03 -6.22252539e+03 -5.79196191e+03 -6.82560107e+03 -8.00324512e+03 -7.48636768e+03 -6.55883105e+03 -1.67870234e+04 -1.65432871e+04 6.08102250e+06 3.71097275e+06 43397152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 66855588. 1.62207450e+06 -2.42330430e+04 -1.79677305e+04 -1.16578662e+04 -1.13582129e+04 -1.09664473e+04 -9.97798535e+03 -9.46809766e+03 -9.02652246e+03 -6.73670703e+03 -6.96975879e+03 -7.07810547e+03 -6.88873926e+03 -6.81996191e+03 -6.72895410e+03 -6.86062158e+03 -6.95241992e+03 -6.89183789e+03 -6.74685547e+03 -6.59684375e+03 -6.78712158e+03 -6.85917578e+03 -6.82002588e+03 -6.83919775e+03 -6.62029492e+03 -6.63717432e+03 -6.76841504e+03 -6.72332910e+03 -6.75697461e+03 -6.55176123e+03 -6.45828516e+03 -6.84316211e+03 -6.96468359e+03 -6.70343066e+03 -6.43720605e+03 -6.45845752e+03 -6.62603320e+03 -6.68710449e+03 -6.58918066e+03 -6.45405078e+03 -6.64648779e+03 -6.65594873e+03 -6.58498926e+03 -6.55485156e+03 -6.29108203e+03 -6.41200635e+03 -6.71092969e+03 -6.55460645e+03 -6.51922168e+03 -6.39568994e+03 -6.27195996e+03 -6.35721533e+03 -6.56517139e+03 -6.47139697e+03 -6.22596582e+03 -6.35196924e+03 -6.34119531e+03 -6.28842822e+03 -6.29031982e+03 -6.14818506e+03 -6.22974316e+03 -6.35958545e+03 -6.17434424e+03 -6.09245361e+03 -5.99431055e+03 -6.11975488e+03 -6.30077734e+03 -6.21633838e+03 -6.07765723e+03 -5.95721582e+03 -5.95846582e+03 -5.95109863e+03 -6.01726123e+03 -6.09040479e+03 -5.84291016e+03 -5.86769482e+03 -6.00551953e+03 -5.95485449e+03 -5.81873633e+03 -5.65093994e+03 -5.72025684e+03 -5.90649072e+03 -5.85476709e+03 -5.72651904e+03 -5.57707080e+03 -5.54299463e+03 -5.65590723e+03 -5.75621777e+03 -5.56998682e+03 -5.39347363e+03 -5.57247607e+03 -5.55060156e+03 -5.42790332e+03 -5.55769482e+03 -5.39244873e+03 -5.31686133e+03 -5.37916504e+03 -5.36569922e+03 -5.36737158e+03 -5.17458350e+03 -5.10878125e+03 -5.18417236e+03 -5.26826025e+03 -5.26378662e+03 -5.09027393e+03 -5.05940186e+03 -5.04116309e+03 -4.99602588e+03 -5.03423193e+03 -4.88518652e+03 -4.85387158e+03 -4.97695898e+03 -4.92552686e+03 -4.73958643e+03 -4.60176807e+03 -4.73084961e+03 -4.89837207e+03 -4.82076074e+03 -4.64109961e+03 -4.49370752e+03 -4.49185107e+03 -4.54737402e+03 -4.55732812e+03 -4.52791064e+03 -4.38752832e+03 -4.34949268e+03 -4.33116455e+03 -4.32275781e+03 -4.37650146e+03 -4.18218164e+03 -4.14923926e+03 -4.26797510e+03 -4.14313086e+03 -4.07058838e+03 -4.03268359e+03 -4.01012695e+03 -4.03858276e+03 -3.97160474e+03 -3.85630591e+03 -3.73432886e+03 -3.81228076e+03 -3.92815356e+03 -3.82729834e+03 -3.69582739e+03 -3.59451587e+03 -3.57232837e+03 -3.59449365e+03 -3.59928052e+03 -3.55548022e+03 -3.36351245e+03 -3.31118921e+03 -3.37383740e+03 -3.39120532e+03 -3.40116089e+03 -3.26155884e+03 -3.17896069e+03 -3.14252441e+03 -3.12399121e+03 -3.12333032e+03 -3.00994556e+03 -2.98239990e+03 -2.95842432e+03 -2.90074902e+03 -2.88340405e+03 -2.77538916e+03 -2.77616162e+03 -2.79533765e+03 -2.68097583e+03 -2.65761328e+03 -2.60417041e+03 -2.54925464e+03 -2.54101392e+03 -2.50945581e+03 -2.43076953e+03 -2.32502197e+03 -2.29754590e+03 -2.32258081e+03 -2.32372192e+03 -2.24569897e+03 -2.09479883e+03 -2.03095923e+03 -2.07936108e+03 -2.06990747e+03 -2.00533057e+03 -1.88657764e+03 -1.85596985e+03 -1.85721594e+03 -1.79072302e+03 -1.76406506e+03 -1.67644165e+03 -1.62026038e+03 -1.61427710e+03 -1.58114941e+03 -1.53134155e+03 -1.45713062e+03 -1.41791235e+03 -1.37393408e+03 -1.32697266e+03 -1.30091614e+03 -1.23531042e+03 -1.18811133e+03 -1.13629138e+03 -1.07667688e+03 -1.02751611e+03 -9.80986023e+02 -9.64491211e+02 -9.24474121e+02 -8.67846497e+02 -8.05396606e+02 -7.28649963e+02 -7.01374146e+02 -6.89994751e+02 -6.40113098e+02 -5.80444458e+02 -5.14785461e+02 -4.60530548e+02 -4.24638275e+02 -3.89848999e+02 -3.40098755e+02 -2.86939850e+02 -2.40247787e+02 -1.90365479e+02 -1.42336060e+02 -9.28555374e+01 -4.48652611e+01 1.54924488e+00 4.92487640e+01 9.91205215e+01 1.47616837e+02 1.86097549e+02 2.40732086e+02 2.94366608e+02 3.32429779e+02 3.83978912e+02 4.31864075e+02 4.89525085e+02 5.35758484e+02 5.55874695e+02 5.95403259e+02 6.57488037e+02 7.34579773e+02 8.07178772e+02 8.36672607e+02 8.36999634e+02 8.60513306e+02 9.26380249e+02 1.02507373e+03 1.10121655e+03 1.12657458e+03 1.11581653e+03 1.15044043e+03 1.27104871e+03 1.31840588e+03 1.29201831e+03 1.34392786e+03 1.43111145e+03 1.47115881e+03 1.55399658e+03 1.56917371e+03 1.55778394e+03 1.64968164e+03 1.67092444e+03 1.74502039e+03 1.83608252e+03 1.80254614e+03 1.87844141e+03 1.98607715e+03 1.99238391e+03 2.02054614e+03 2.07089331e+03 2.12695386e+03 2.16354321e+03 2.21319067e+03 2.18520972e+03 2.21247290e+03 2.39560791e+03 2.51894824e+03 2.49472925e+03 2.42642041e+03 2.41562769e+03 2.48946118e+03 2.64909595e+03 2.77711011e+03 2.77501196e+03 2.68177075e+03 2.71466675e+03 2.85855786e+03 2.89397534e+03 2.89141919e+03 2.93350171e+03 2.98142432e+03 3.01979053e+03 3.16921997e+03 3.16553027e+03 3.09605493e+03 3.21003394e+03 3.16919946e+03 3.28793945e+03 3.43633838e+03 3.35676709e+03 3.49584009e+03 3.48793408e+03 3.40851318e+03 3.55370923e+03 3.48209399e+03 3.60282910e+03 3.89247974e+03 3.70714722e+03 3.55869507e+03 3.69535889e+03 3.90298877e+03 4.07302075e+03 4.05302905e+03 3.85784155e+03 3.78590869e+03 3.89941382e+03 4.11240967e+03 4.34301953e+03 4.25274951e+03 4.05047778e+03 4.10246484e+03 4.25731885e+03 4.35334766e+03 4.29880420e+03 4.30961279e+03 4.38748486e+03 4.40149414e+03 4.61864453e+03 4.68525635e+03 4.43064795e+03 4.44976807e+03 4.59798242e+03 4.62976025e+03 4.70344141e+03 4.71306250e+03 4.87341357e+03 4.81275586e+03 4.67391455e+03 4.83123633e+03 4.75665723e+03 4.91666797e+03 5.28314746e+03 4.99652295e+03 4.70765918e+03 4.87902344e+03 5.19261914e+03 5.36317090e+03 5.38071875e+03 5.11228467e+03 4.96276025e+03 5.09823242e+03 5.34147607e+03 5.59223242e+03 5.50650391e+03 5.20971191e+03 5.19428564e+03 5.42614697e+03 5.49391748e+03 5.63161084e+03 5.66698926e+03 5.37304932e+03 5.40523779e+03 5.65745361e+03 5.73571875e+03 5.65309766e+03 5.64731592e+03 5.63971484e+03 5.59647656e+03 5.89025049e+03 5.95888428e+03 5.76270459e+03 5.73764551e+03 5.73110059e+03 5.82059814e+03 5.88675879e+03 5.90461182e+03 6.11780664e+03 6.11904590e+03 5.95459326e+03 5.87260010e+03 5.78284326e+03 6.06472266e+03 6.40757227e+03 6.26205420e+03 5.98040430e+03 5.88563867e+03 6.11590234e+03 6.46425488e+03 6.22450049e+03 5.91691992e+03 6.09002002e+03 6.33652148e+03 6.45731396e+03 6.65488232e+03 6.48904590e+03 6.17743164e+03 6.13129199e+03 6.30989551e+03 6.43801172e+03 6.49777734e+03 6.47159082e+03 6.45282861e+03 6.41982910e+03 6.53981641e+03 6.47989453e+03 6.35182520e+03 6.41074854e+03 6.44206006e+03 6.69730518e+03 6.76704639e+03 6.56280176e+03 6.62997656e+03 6.63945557e+03 6.65560059e+03 6.51148633e+03 6.38711670e+03 6.73103906e+03 6.99916992e+03 6.76775635e+03 6.47431885e+03 6.54206592e+03 6.89303369e+03 6.96315039e+03 6.78691943e+03 6.76681787e+03 6.59450879e+03 6.58810010e+03 6.85567285e+03 6.79812646e+03 6.71036426e+03 6.56749805e+03 6.55460107e+03 6.93098047e+03 7.14948877e+03 6.77875977e+03 6.62618262e+03 6.78609424e+03 6.81237451e+03 7.01509473e+03 6.96902734e+03 6.61756982e+03 6.65174658e+03 6.86457568e+03 6.86487646e+03 6.86553564e+03 6.93352246e+03 7.18148682e+03 7.26907373e+03 7.12913916e+03 7.09160449e+03 6.63316357e+03 7.49093750e+03 8.80780859e+03 8.44457324e+03 9.78197266e+03 1.51126201e+04 1.42303359e+04 2.03465586e+04 1.82923164e+04 -2.98607775e+06 -6801838. -2.43777750e+06 -4466672. -49551468. 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. 0. 0. 0. 0. 0. 0. 50947440. 50947440. -3.28714275e+06 5.60369258e+04 1.62408652e+04 1.27142715e+04 9.21920508e+03 8.18072217e+03 6.08438379e+03 6.26822119e+03 7.00401465e+03 6.63268848e+03 6.18499561e+03 6.35013818e+03 6.35820361e+03 6.18522852e+03 6.15770459e+03 6.17319580e+03 6.13850000e+03 6.09042578e+03 6.05039600e+03 6.01646533e+03 6.01723535e+03 5.97536377e+03 6.03683838e+03 6.05375830e+03 5.79893213e+03 5.76293506e+03 6.02514697e+03 6.03437842e+03 5.84859326e+03 5.81885596e+03 5.80543115e+03 5.77969434e+03 5.76795605e+03 5.72644678e+03 5.66936963e+03 5.65924365e+03 5.56043945e+03 5.51330908e+03 5.67639404e+03 5.68205176e+03 5.53366943e+03 5.48333594e+03 5.48467188e+03 5.45151660e+03 5.40592236e+03 5.37903320e+03 5.37646338e+03 5.25852344e+03 5.17558496e+03 5.18599951e+03 5.16628516e+03 5.37596289e+03 5.36300684e+03 5.11563818e+03 4.97127832e+03 4.93371973e+03 5.19479639e+03 5.18677246e+03 4.97467725e+03 4.84443945e+03 4.80537012e+03 4.91038477e+03 4.84321729e+03 4.91405322e+03 4.92516943e+03 4.61887793e+03 4.48757178e+03 4.71026758e+03 4.88378174e+03 4.70137354e+03 4.55776221e+03 4.52673779e+03 4.48170312e+03 4.44389795e+03 4.41964258e+03 4.35740039e+03 4.31178516e+03 4.31616211e+03 4.27175244e+03 4.21779492e+03 4.18493555e+03 4.26623535e+03 4.24192871e+03 4.09267603e+03 4.02869849e+03 3.99874756e+03 4.02251318e+03 3.98686768e+03 3.90206104e+03 3.86467993e+03 3.75110010e+03 3.64708447e+03 3.77891724e+03 3.74152466e+03 3.50797974e+03 3.51506641e+03 3.67743091e+03 3.74462134e+03 3.60075171e+03 3.45447876e+03 3.37180518e+03 3.32431079e+03 3.31878149e+03 3.27442944e+03 3.22765698e+03 3.18022510e+03 3.24610156e+03 3.21015552e+03 3.06269604e+03 3.02437891e+03 2.89902783e+03 2.88880200e+03 3.01875537e+03 2.94974219e+03 2.83137524e+03 2.72626099e+03 2.64419482e+03 2.73390649e+03 2.74232617e+03 2.62348975e+03 2.50541113e+03 2.45268921e+03 2.45782520e+03 2.41815552e+03 2.45440820e+03 2.41692676e+03 2.29581885e+03 2.22989819e+03 2.17940771e+03 2.17833374e+03 2.14343359e+03 2.06943433e+03 2.01347388e+03 1.97014490e+03 1.91552563e+03 1.82089209e+03 1.79964709e+03 1.85347266e+03 1.79455347e+03 1.69606311e+03 1.61175000e+03 1.56403638e+03 1.59945654e+03 1.55850745e+03 1.46974707e+03 1.38839795e+03 1.33460864e+03 1.32724255e+03 1.27909753e+03 1.23391479e+03 1.15573511e+03 1.13326965e+03 1.15311499e+03 1.07507227e+03 1.00082935e+03 9.53576233e+02 9.05623779e+02 8.55686951e+02 8.09235779e+02 7.55958435e+02 7.05268127e+02 6.62698914e+02 5.99760681e+02 5.62904358e+02 5.47331421e+02 4.76987244e+02 4.15593231e+02 3.79629974e+02 3.29994476e+02 2.93311890e+02 2.41630920e+02 1.85584778e+02 1.44510513e+02 9.66297913e+01 4.72378654e+01 -9.12220776e-01 -4.86174965e+01 -9.70130005e+01 -1.44805222e+02 -1.89810135e+02 -2.30957962e+02 -2.86735962e+02 -3.51878204e+02 -3.92570404e+02 -4.30976532e+02 -4.66381866e+02 -5.10548187e+02 -5.87470459e+02 -6.40071594e+02 -6.73030029e+02 -7.00276611e+02 -7.39924316e+02 -8.11812378e+02 -8.61471680e+02 -9.26596436e+02 -9.61812927e+02 -9.82350159e+02 -1.03821484e+03 -1.08365027e+03 -1.17208716e+03 -1.21473120e+03 -1.22009705e+03 -1.28021326e+03 -1.33121692e+03 -1.36691418e+03 -1.37515442e+03 -1.45318860e+03 -1.59076526e+03 -1.60736755e+03 -1.60582312e+03 -1.60943213e+03 -1.64451465e+03 -1.79319165e+03 -1.85335925e+03 -1.83888574e+03 -1.83701367e+03 -1.87574670e+03 -1.98235522e+03 -2.02913977e+03 -2.12034790e+03 -2.15127344e+03 -2.14114062e+03 -2.16578589e+03 -2.20107593e+03 -2.35101392e+03 -2.39868994e+03 -2.37677148e+03 -2.39492871e+03 -2.43223560e+03 -2.56875610e+03 -2.62547510e+03 -2.53525049e+03 -2.57058301e+03 -2.77606689e+03 -2.82331128e+03 -2.71456030e+03 -2.74662427e+03 -2.93156470e+03 -3.00219263e+03 -2.95192578e+03 -2.91306494e+03 -2.96593262e+03 -3.17249561e+03 -3.17931152e+03 -3.12248340e+03 -3.23219897e+03 -3.28010767e+03 -3.27522705e+03 -3.29196582e+03 -3.35151929e+03 -3.31148706e+03 -3.43981323e+03 -3.68080396e+03 -3.60356128e+03 -3.60311499e+03 -3.66641064e+03 -3.67186841e+03 -3.71175977e+03 -3.73312671e+03 -3.78605127e+03 -3.74117969e+03 -3.71285718e+03 -3.84539917e+03 -3.98587842e+03 -4.12734863e+03 -4.03431201e+03 -3.92188403e+03 -4.06705151e+03 -4.16392969e+03 -4.32931689e+03 -4.32823584e+03 -4.23854297e+03 -4.20023096e+03 -4.20015283e+03 -4.35209570e+03 -4.40348975e+03 -4.53763965e+03 -4.58353027e+03 -4.49634082e+03 -4.45264648e+03 -4.39008154e+03 -4.56889258e+03 -4.86447168e+03 -4.83629736e+03 -4.74186230e+03 -4.65035352e+03 -4.60120166e+03 -4.87088428e+03 -5.04209961e+03 -4.94079688e+03 -4.81411523e+03 -4.83310010e+03 -4.97824463e+03 -5.01187109e+03 -5.17638330e+03 -5.23255322e+03 -5.11797607e+03 -5.07626904e+03 -5.08595068e+03 -5.30615088e+03 -5.32855469e+03 -5.13140283e+03 -5.14259473e+03 -5.48365576e+03 -5.46024414e+03 -5.20260059e+03 -5.30944873e+03 -5.59811914e+03 -5.61639551e+03 -5.53848389e+03 -5.39897119e+03 -5.39158301e+03 -5.72153760e+03 -5.80168213e+03 -5.65020459e+03 -5.52300244e+03 -5.51605957e+03 -5.69710156e+03 -5.78124951e+03 -5.79090088e+03 -5.64186377e+03 -5.78685742e+03 -6.13938916e+03 -5.99483008e+03 -5.96372852e+03 -5.99921191e+03 -5.95634814e+03 -5.96250195e+03 -6.00351465e+03 -6.02546436e+03 -6.01709424e+03 -5.96701221e+03 -5.85966602e+03 -6.03656592e+03 -6.36149805e+03 -6.15394580e+03 -5.93409424e+03 -6.14926221e+03 -6.27174756e+03 -6.45739355e+03 -6.38402881e+03 -6.18809961e+03 -6.34906445e+03 -6.41381055e+03 -6.19537354e+03 -6.20505029e+03 -6.46607178e+03 -6.47234912e+03 -6.36873389e+03 -6.26303369e+03 -6.10448096e+03 -6.41112695e+03 -6.82773047e+03 -6.68337109e+03 -6.46275586e+03 -6.33369629e+03 -6.31690283e+03 -6.63833154e+03 -6.80783643e+03 -6.59971094e+03 -6.45228320e+03 -6.43678076e+03 -6.52142480e+03 -6.59011572e+03 -6.78565088e+03 -6.76679395e+03 -6.62524268e+03 -6.65085889e+03 -6.60716211e+03 -6.79868896e+03 -6.83204248e+03 -6.72263428e+03 -6.61422754e+03 -6.59376074e+03 -6.70492334e+03 -6.58273633e+03 -6.62814258e+03 -6.95562891e+03 -6.92063330e+03 -6.82455029e+03 -6.63296338e+03 -6.56033252e+03 -6.98163818e+03 -7.00472754e+03 -6.82898193e+03 -6.70898438e+03 -6.62720703e+03 -6.75751904e+03 -6.72835840e+03 -6.83555518e+03 -6.69365137e+03 -6.83416943e+03 -7.10584814e+03 -6.89984961e+03 -6.96052881e+03 -6.96200781e+03 -6.83619336e+03 -6.78563916e+03 -6.71679736e+03 -6.74687158e+03 -6.81409131e+03 -6.86102197e+03 -6.84678076e+03 -6.88760986e+03 -6.92806201e+03 -6.68400391e+03 -6.57047803e+03 -6.76841064e+03 -6.86789258e+03 -7.07497461e+03 -6.93191064e+03 -6.71205029e+03 -6.91578857e+03 -6.88141602e+03 -6.74486035e+03 -6.77815576e+03 -6.78040723e+03 -6.70701465e+03 -6.70536621e+03 -6.75317627e+03 -6.62022998e+03 -6.72011426e+03 -7.02364307e+03 -6.90689893e+03 -6.77411523e+03 -6.65640820e+03 -6.52586914e+03 -6.91215625e+03 -6.89089795e+03 -6.71703027e+03 -6.51854248e+03 -6.39645557e+03 -6.61943408e+03 -6.72332715e+03 -6.89605127e+03 -6.68517432e+03 -6.48857129e+03 -6.59157715e+03 -6.50518359e+03 -6.72372266e+03 -6.69000146e+03 -6.46949609e+03 -6.48057471e+03 -6.44459473e+03 -6.52045801e+03 -6.31403613e+03 -6.44673633e+03 -6.76262256e+03 -6.57885986e+03 -6.49840381e+03 -6.35015332e+03 -6.21524512e+03 -6.54881689e+03 -6.56827295e+03 -6.33841699e+03 -6.19383838e+03 -6.16426074e+03 -6.27851709e+03 -6.30859326e+03 -6.44807275e+03 -6.42114795e+03 -6.23528760e+03 -6.06778809e+03 -6.01454297e+03 -6.37812061e+03 -6.30904297e+03 -6.07221729e+03 -6.13547607e+03 -6.09464795e+03 -5.99438672e+03 -5.97370752e+03 -6.09539795e+03 -5.95256641e+03 -5.81391211e+03 -6.09419580e+03 -6.14608350e+03 -5.91366260e+03 -5.83639746e+03 -5.84975684e+03 -5.84501318e+03 -5.64855176e+03 -5.58914551e+03 -5.87481299e+03 -5.86594482e+03 -5.49900488e+03 -5.40208691e+03 -5.70505762e+03 -5.90335400e+03 -5.71683643e+03 -5.48145068e+03 -5.41205127e+03 -5.61471729e+03 -5.53931152e+03 -5.38190674e+03 -5.44573389e+03 -5.29998486e+03 -5.11021826e+03 -5.29075049e+03 -5.49239502e+03 -5.42787500e+03 -5.18990137e+03 -5.02734375e+03 -5.26367090e+03 -5.33593164e+03 -5.14162256e+03 -5.00020947e+03 -4.94874951e+03 -4.96330811e+03 -4.95156348e+03 -5.08671289e+03 -4.97712109e+03 -4.76871289e+03 -4.84795605e+03 -4.82418262e+03 -4.84878906e+03 -4.71911426e+03 -4.58497754e+03 -4.74033301e+03 -4.69998096e+03 -4.62383545e+03 -4.46880664e+03 -4.46309912e+03 -4.68763965e+03 -4.47775049e+03 -4.30908936e+03 -4.38497900e+03 -4.35540527e+03 -4.32549316e+03 -4.28961328e+03 -4.34540576e+03 -4.33377881e+03 -4.18161328e+03 -4.01821240e+03 -3.97233105e+03 -4.16173145e+03 -4.05999707e+03 -3.89947412e+03 -3.94268188e+03 -3.90539893e+03 -3.86482104e+03 -3.83177368e+03 -3.85558984e+03 -3.71844141e+03 -3.60325366e+03 -3.71879443e+03 -3.69006885e+03 -3.59875391e+03 -3.56743921e+03 -3.52183301e+03 -3.47110376e+03 -3.33112036e+03 -3.25246753e+03 -3.38652588e+03 -3.41965405e+03 -3.20066895e+03 -3.06993677e+03 -3.19447998e+03 -3.25930005e+03 -3.13251392e+03 -2.98318481e+03 -2.90292725e+03 -2.99577490e+03 -2.97298950e+03 -2.84005957e+03 -2.86777661e+03 -2.82874023e+03 -2.69501611e+03 -2.64018188e+03 -2.67550537e+03 -2.67308789e+03 -2.52132593e+03 -2.42837891e+03 -2.51232568e+03 -2.50248975e+03 -2.39236108e+03 -2.28121094e+03 -2.21691479e+03 -2.29277319e+03 -2.27002002e+03 -2.14545483e+03 -2.09206177e+03 -2.05814551e+03 -2.00229016e+03 -1.94899438e+03 -1.98090918e+03 -1.89355554e+03 -1.77999988e+03 -1.81981189e+03 -1.78764868e+03 -1.71989807e+03 -1.63044885e+03 -1.56482532e+03 -1.58051099e+03 -1.50504663e+03 -1.46722363e+03 -1.55954651e+03 -1.45916016e+03 -1.37008765e+03 -1.27417493e+03 -2.34497021e+03 -3.50586304e+03 -2.69119824e+03 -3.11258789e+03 -3.21375098e+03 -1.69030566e+03 -2.88404736e+03 -9.02785742e+03 -95812040. 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. 0. 0. 61294816. 1.34376325e+06 -8.15503188e+05 -2.48378016e+05 2.23532739e+03 1.64756763e+03 1.19596289e+03 1.08086145e+03 1.10162512e+03 1.07809741e+03 1.10488501e+03 1.15350781e+03 1.20866418e+03 1.23362158e+03 1.26754419e+03 1.31865918e+03 1.35888660e+03 1.42936267e+03 1.50600854e+03 1.57558936e+03 1.55964709e+03 1.56993188e+03 1.67142578e+03 1.67274622e+03 1.66647705e+03 1.78894299e+03 1.89918567e+03 1.93307727e+03 1.95086084e+03 1.94801355e+03 1.99765869e+03 2.07669409e+03 2.10266455e+03 2.12237378e+03 2.22344751e+03 2.30550830e+03 2.29446729e+03 2.31755103e+03 2.38252881e+03 2.43234717e+03 2.49474658e+03 2.52228662e+03 2.51318481e+03 2.61697900e+03 2.72841675e+03 2.67432617e+03 2.69767407e+03 2.79930811e+03 2.78520142e+03 2.84712744e+03 2.96912476e+03 2.97132471e+03 2.97472705e+03 3.06177539e+03 3.16634497e+03 3.14604199e+03 3.09866504e+03 3.13796997e+03 3.19025757e+03 3.34388379e+03 3.44485254e+03 3.39024731e+03 3.40556592e+03 3.43791064e+03 3.47049268e+03 3.52695239e+03 3.54400586e+03 3.56306323e+03 3.67025952e+03 3.81651562e+03 3.76909668e+03 3.73853003e+03 3.85467261e+03 3.87923535e+03 3.88223730e+03 3.94488770e+03 4.01188940e+03 4.01585278e+03 4.01689453e+03 4.12606250e+03 4.15696826e+03 4.18948877e+03 4.22999561e+03 4.16731641e+03 4.27401514e+03 4.43444580e+03 4.38860693e+03 4.35183594e+03 4.42339844e+03 4.44913379e+03 4.51043359e+03 4.53518848e+03 4.49701709e+03 4.61250342e+03 4.78831055e+03 4.73579346e+03 4.62964014e+03 4.69257031e+03 4.82511963e+03 4.86196973e+03 4.85548975e+03 4.87852441e+03 4.84983057e+03 4.98726025e+03 5.13191992e+03 5.01394043e+03 4.95995654e+03 5.00177197e+03 5.04591797e+03 5.18565967e+03 5.24897803e+03 5.19980420e+03 5.25561816e+03 5.40950488e+03 5.40977148e+03 5.30102930e+03 5.27314111e+03 5.30878955e+03 5.40931445e+03 5.51097168e+03 5.55365137e+03 5.50353369e+03 5.55536963e+03 5.61172266e+03 5.51924951e+03 5.53438232e+03 5.64736328e+03 5.64586035e+03 5.75895850e+03 5.85990234e+03 5.67623486e+03 5.70562500e+03 5.87851025e+03 5.83568994e+03 5.74001904e+03 5.84739258e+03 6.04628711e+03 6.01679883e+03 5.97743213e+03 5.95709326e+03 5.95888281e+03 5.99284570e+03 5.96382520e+03 6.03523730e+03 6.12026562e+03 6.11665186e+03 6.12509668e+03 6.22892822e+03 6.20394141e+03 6.03411328e+03 6.14859473e+03 6.31664404e+03 6.23516064e+03 6.31616309e+03 6.41667529e+03 6.40999854e+03 6.26702539e+03 6.27431934e+03 6.32000732e+03 6.24857812e+03 6.39311670e+03 6.53110205e+03 6.47890381e+03 6.42934375e+03 6.41188867e+03 6.43917334e+03 6.49006982e+03 6.45840625e+03 6.40737305e+03 6.50987158e+03 6.62634619e+03 6.54911865e+03 6.52345703e+03 6.62030176e+03 6.57597559e+03 6.66687012e+03 6.58959717e+03 6.57665771e+03 6.69592725e+03 6.66510400e+03 6.67504199e+03 6.64302588e+03 6.69665967e+03 6.81166016e+03 6.55582666e+03 6.60456494e+03 6.84326660e+03 6.73318945e+03 6.80096680e+03 6.77119141e+03 6.70990039e+03 6.70702637e+03 6.68356885e+03 6.67140771e+03 6.69582861e+03 6.80092871e+03 6.89794727e+03 6.99193848e+03 6.88411719e+03 6.82252441e+03 6.81142871e+03 6.71771094e+03 6.68915137e+03 6.74187402e+03 6.89004395e+03 7.01772412e+03 6.78305713e+03 6.73256348e+03 6.87477539e+03 6.69667090e+03 6.81120166e+03 6.94783740e+03 6.81732568e+03 6.79674414e+03 6.86306787e+03 6.91592578e+03 6.88050146e+03 6.77992041e+03 6.80323340e+03 6.69850781e+03 6.77377344e+03 6.86496484e+03 6.91061865e+03 6.83758740e+03 6.85794775e+03 6.87406055e+03 6.76200781e+03 6.82202295e+03 6.91398779e+03 6.76123877e+03 6.64093652e+03 6.77497510e+03 6.78574609e+03 6.82062695e+03 6.74984424e+03 6.65954199e+03 6.77371484e+03 6.71947119e+03 6.76215088e+03 6.73064746e+03 6.81539307e+03 6.79378809e+03 6.54334375e+03 6.63924707e+03 6.66363086e+03 6.60756836e+03 6.77584521e+03 6.60005908e+03 6.49061230e+03 6.73832471e+03 6.73014355e+03 6.45434082e+03 6.42864844e+03 6.63592383e+03 6.62593848e+03 6.46721289e+03 6.53135547e+03 6.66252490e+03 6.45388330e+03 6.40976611e+03 6.44397900e+03 6.31149463e+03 6.43334424e+03 6.50854688e+03 6.34266650e+03 6.41079102e+03 6.48992578e+03 6.35834814e+03 6.26349121e+03 6.22273389e+03 6.28651367e+03 6.38955371e+03 6.22529004e+03 6.14183496e+03 6.18297021e+03 6.20566943e+03 6.12617871e+03 6.10012158e+03 6.12313428e+03 6.11551611e+03 6.05194678e+03 6.09474463e+03 6.14327979e+03 5.98640137e+03 5.97416992e+03 6.00843359e+03 5.84921045e+03 5.99655078e+03 5.97899902e+03 5.74954639e+03 5.87095166e+03 5.83745996e+03 5.73787061e+03 5.82049951e+03 5.73760352e+03 5.72759229e+03 5.80993555e+03 5.66686572e+03 5.62166943e+03 5.59705420e+03 5.50638184e+03 5.49014160e+03 5.48391748e+03 5.54898682e+03 5.56376904e+03 5.49970264e+03 5.43588525e+03 5.44263281e+03 5.36968359e+03 5.24805762e+03 5.27025244e+03 5.38439160e+03 5.32403760e+03 5.14616064e+03 5.08050000e+03 5.16051123e+03 5.19801270e+03 5.07801758e+03 4.98798584e+03 5.00319580e+03 5.01620898e+03 5.04061768e+03 4.95735986e+03 4.84643701e+03 4.77147363e+03 4.75255420e+03 4.77583105e+03 4.72604492e+03 4.73506885e+03 4.74292041e+03 4.64502148e+03 4.63272852e+03 4.68874072e+03 4.58954785e+03 4.43754248e+03 4.47693604e+03 4.55230957e+03 4.43554639e+03 4.24830566e+03 4.20744092e+03 4.29005078e+03 4.31189014e+03 4.22702441e+03 4.17477881e+03 4.13094873e+03 4.15405566e+03 4.11433545e+03 3.93074951e+03 3.90180176e+03 3.95574219e+03 3.96282739e+03 3.85576538e+03 3.74500391e+03 3.76110352e+03 3.73845654e+03 3.73934106e+03 3.75032544e+03 3.68666699e+03 3.54604126e+03 3.43470386e+03 3.50133521e+03 3.55951440e+03 3.44283252e+03 3.33577612e+03 3.27171655e+03 3.28474072e+03 3.31790991e+03 3.19424341e+03 3.13770752e+03 3.13199683e+03 3.13173364e+03 3.09230444e+03 2.94702734e+03 2.93739526e+03 2.92584375e+03 2.84913452e+03 2.82716162e+03 2.76991602e+03 2.71924121e+03 2.68282031e+03 2.63350879e+03 2.59870166e+03 2.58607910e+03 2.54548364e+03 2.45515527e+03 2.43231958e+03 2.40541211e+03 2.33393213e+03 2.28384619e+03 2.18752710e+03 2.16863403e+03 2.20723511e+03 2.14215283e+03 2.05748877e+03 1.97177686e+03 1.94748315e+03 1.96792261e+03 1.89163745e+03 1.83433911e+03 1.81247424e+03 1.74369092e+03 1.67436499e+03 1.65061694e+03 1.61430737e+03 1.54272522e+03 1.51633691e+03 1.46692151e+03 1.38547461e+03 1.36774207e+03 1.33202747e+03 1.28101880e+03 1.25385388e+03 1.19646191e+03 1.13882581e+03 1.08319482e+03 1.03298999e+03 9.98789429e+02 9.57254700e+02 9.05260559e+02 8.50229797e+02 8.08301514e+02 7.57170044e+02 7.06525269e+02 6.73427979e+02 6.20103088e+02 5.65135071e+02 5.21414795e+02 4.75333954e+02 4.27929077e+02 3.82220978e+02 3.33185638e+02 2.80275665e+02 2.36502609e+02 1.91081192e+02 1.40881027e+02 9.28155899e+01 4.55476189e+01 -1.70364511e+00 -4.91051369e+01 -9.61079254e+01 -1.43877792e+02 -1.95372543e+02 -2.44709763e+02 -2.97826538e+02 -3.38044983e+02 -3.73563904e+02 -4.32106995e+02 -4.88180084e+02 -5.28050537e+02 -5.70177673e+02 -6.20246887e+02 -6.71424500e+02 -7.22006897e+02 -7.66918701e+02 -8.01867249e+02 -8.48615112e+02 -9.11878052e+02 -9.59045044e+02 -9.99742920e+02 -1.04137842e+03 -1.08819885e+03 -1.14844360e+03 -1.19514417e+03 -1.24547290e+03 -1.29344690e+03 -1.33235815e+03 -1.37536670e+03 -1.42999365e+03 -1.48178333e+03 -1.49036462e+03 -1.53585327e+03 -1.62060107e+03 -1.67242322e+03 -1.72988037e+03 -1.74672693e+03 -1.78640161e+03 -1.82840100e+03 -1.87184863e+03 -1.96694873e+03 -1.96510449e+03 -2.00249902e+03 -2.10889941e+03 -2.09683398e+03 -2.12300854e+03 -2.23050000e+03 -2.27169141e+03 -2.30964453e+03 -2.37638428e+03 -2.37997852e+03 -2.35476953e+03 -2.46942261e+03 -2.56429663e+03 -2.55034351e+03 -2.65655933e+03 -2.69979980e+03 -2.64902710e+03 -2.70762671e+03 -2.75674561e+03 -2.79888281e+03 -2.89165137e+03 -2.93526221e+03 -2.96788306e+03 -3.01188525e+03 -3.04657056e+03 -3.11317188e+03 -3.13135449e+03 -3.13306616e+03 -3.19581250e+03 -3.25612231e+03 -3.26858594e+03 -3.34063428e+03 -3.40582471e+03 -3.39461499e+03 -3.46630542e+03 -3.53007886e+03 -3.57376074e+03 -3.60998657e+03 -3.55859277e+03 -3.62992822e+03 -3.77891846e+03 -3.80218701e+03 -3.75664087e+03 -3.82991235e+03 -3.90766309e+03 -3.92665674e+03 -3.95742017e+03 -3.88206030e+03 -3.90652051e+03 -4.08019897e+03 -4.17374951e+03 -4.20508740e+03 -4.12877637e+03 -4.16387158e+03 -4.28957959e+03 -4.29471191e+03 -4.31739795e+03 -4.36224023e+03 -4.37115625e+03 -4.43475537e+03 -4.48782324e+03 -4.57437793e+03 -4.54784131e+03 -4.51326660e+03 -4.68375879e+03 -4.66102100e+03 -4.63890186e+03 -4.68049609e+03 -4.67169580e+03 -4.78848242e+03 -4.94578760e+03 -4.94725098e+03 -4.80249316e+03 -4.84301172e+03 -4.99962109e+03 -5.02387500e+03 -5.04703662e+03 -5.04279736e+03 -5.12025439e+03 -5.16687354e+03 -5.16828564e+03 -5.23814453e+03 -5.20220605e+03 -5.25354443e+03 -5.35455469e+03 -5.15752686e+03 -5.19228467e+03 -5.43243506e+03 -5.47271875e+03 -5.42851514e+03 -5.42887061e+03 -5.39995898e+03 -5.44146094e+03 -5.61060889e+03 -5.69562158e+03 -5.59884229e+03 -5.54622998e+03 -5.54233057e+03 -5.63929102e+03 -5.73419287e+03 -5.79825732e+03 -5.83964014e+03 -5.75440967e+03 -5.79005176e+03 -5.85239990e+03 -5.77260059e+03 -5.78857666e+03 -5.97135596e+03 -5.99676660e+03 -5.94648096e+03 -5.96208887e+03 -5.97666699e+03 -6.02635303e+03 -5.99722119e+03 -6.10158887e+03 -6.07862061e+03 -6.12706641e+03 -6.13033350e+03 -6.09687695e+03 -6.34354834e+03 -6.18624561e+03 -6.15127100e+03 -6.35120947e+03 -6.21140918e+03 -6.19086133e+03 -6.31334082e+03 -6.34426611e+03 -6.25535889e+03 -6.42593604e+03 -6.50572754e+03 -6.37828564e+03 -6.56627539e+03 -6.64139355e+03 -6.16783398e+03 -5.86286084e+03 -6.97774365e+03 -7.54365723e+03 -7.99564648e+03 -8.76127832e+03 -1.16990225e+04 -8.78295020e+03 -1.46073623e+04 -1.36412594e+05 43397152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 66855588. 1.62207450e+06 -2.20699225e+06 5557439. 51155096. -1.04991338e+06 -2.68851950e+06 -1.97057441e+04 -1.56897344e+04 -9.15435840e+03 -6.55859570e+03 -7.05949023e+03 -7.15754395e+03 -6.92442139e+03 -6.85365771e+03 -6.85188232e+03 -6.79158447e+03 -6.91357764e+03 -6.96202002e+03 -6.79890820e+03 -6.61245605e+03 -6.74504004e+03 -6.84136865e+03 -6.81530518e+03 -6.79288818e+03 -6.52357520e+03 -6.58550293e+03 -6.90487793e+03 -6.73968213e+03 -6.59183008e+03 -6.52720459e+03 -6.57154736e+03 -6.86049951e+03 -6.89632715e+03 -6.67328027e+03 -6.38685156e+03 -6.48336230e+03 -6.68155615e+03 -6.68658838e+03 -6.60364893e+03 -6.52173193e+03 -6.59704443e+03 -6.62261377e+03 -6.58974121e+03 -6.62252344e+03 -6.34074512e+03 -6.45285303e+03 -6.78483350e+03 -6.49184619e+03 -6.34082715e+03 -6.34406641e+03 -6.31063184e+03 -6.52335059e+03 -6.52088379e+03 -6.31167480e+03 -6.20058105e+03 -6.38284033e+03 -6.47301514e+03 -6.33555762e+03 -6.24431836e+03 -6.12363721e+03 -6.24770068e+03 -6.39200146e+03 -6.16580908e+03 -6.15942334e+03 -6.09531641e+03 -6.03017578e+03 -6.20746240e+03 -6.24215430e+03 -6.10691602e+03 -5.96069873e+03 -6.02173682e+03 -6.03338623e+03 -6.03045068e+03 -6.04155664e+03 -5.81269287e+03 -5.80621875e+03 -6.09406299e+03 -5.90257520e+03 -5.65798389e+03 -5.63933447e+03 -5.82468066e+03 -5.97763770e+03 -5.84744922e+03 -5.73351074e+03 -5.61393604e+03 -5.51966016e+03 -5.62225146e+03 -5.74304346e+03 -5.60599414e+03 -5.43597168e+03 -5.54486621e+03 -5.54267480e+03 -5.48664111e+03 -5.58222803e+03 -5.34647803e+03 -5.26572949e+03 -5.47140039e+03 -5.39917822e+03 -5.25447412e+03 -5.18538281e+03 -5.12369238e+03 -5.27116895e+03 -5.27968945e+03 -5.10239795e+03 -5.04711914e+03 -5.12386572e+03 -5.10753027e+03 -5.01280664e+03 -5.04750000e+03 -4.92666064e+03 -4.83478906e+03 -4.97962939e+03 -4.89373486e+03 -4.71831104e+03 -4.65718262e+03 -4.69792383e+03 -4.84389111e+03 -4.81895361e+03 -4.68701514e+03 -4.49054834e+03 -4.42648145e+03 -4.60783594e+03 -4.59245996e+03 -4.42650879e+03 -4.35287598e+03 -4.38596289e+03 -4.42682861e+03 -4.33314502e+03 -4.25129492e+03 -4.15363037e+03 -4.20347803e+03 -4.32475977e+03 -4.14595654e+03 -4.06822144e+03 -4.06100269e+03 -3.96852393e+03 -4.00038428e+03 -3.98065649e+03 -3.88537280e+03 -3.77561108e+03 -3.77601392e+03 -3.87978198e+03 -3.83394092e+03 -3.73155981e+03 -3.60440601e+03 -3.55318530e+03 -3.63325537e+03 -3.60470166e+03 -3.53244678e+03 -3.39199951e+03 -3.30798486e+03 -3.38117896e+03 -3.40928906e+03 -3.34081274e+03 -3.21296313e+03 -3.17650684e+03 -3.16787012e+03 -3.14344141e+03 -3.13844678e+03 -3.03238745e+03 -2.97258447e+03 -2.97927588e+03 -2.90916772e+03 -2.85247754e+03 -2.79264453e+03 -2.80205542e+03 -2.77778687e+03 -2.66239233e+03 -2.62231396e+03 -2.56718701e+03 -2.57009766e+03 -2.61474072e+03 -2.50566504e+03 -2.38262036e+03 -2.32721680e+03 -2.31445996e+03 -2.33993921e+03 -2.31662158e+03 -2.24421924e+03 -2.11593555e+03 -2.01970007e+03 -2.05752686e+03 -2.07063623e+03 -2.02654858e+03 -1.90137366e+03 -1.83770862e+03 -1.85803589e+03 -1.81026416e+03 -1.76418384e+03 -1.69263074e+03 -1.63085730e+03 -1.60621729e+03 -1.55111707e+03 -1.51070679e+03 -1.46619971e+03 -1.41291150e+03 -1.39476953e+03 -1.32938953e+03 -1.26937720e+03 -1.22914001e+03 -1.19399890e+03 -1.15885034e+03 -1.08959595e+03 -1.02223779e+03 -9.74680847e+02 -9.68573486e+02 -9.34149536e+02 -8.59284241e+02 -8.01693909e+02 -7.35100769e+02 -6.97952759e+02 -6.86028625e+02 -6.37234497e+02 -5.77815735e+02 -5.09847687e+02 -4.59214752e+02 -4.37418427e+02 -3.94151825e+02 -3.33025543e+02 -2.84135071e+02 -2.40458054e+02 -1.90941055e+02 -1.41440475e+02 -9.24877319e+01 -4.58003654e+01 7.52172887e-01 4.98887787e+01 1.01168556e+02 1.48286316e+02 1.87089661e+02 2.36612350e+02 2.89108093e+02 3.35687225e+02 3.86977997e+02 4.28762604e+02 4.88729919e+02 5.37950623e+02 5.55706848e+02 5.95117737e+02 6.58345947e+02 7.34423157e+02 8.05195740e+02 8.38158630e+02 8.39973877e+02 8.55611206e+02 9.22726562e+02 1.02722717e+03 1.10734985e+03 1.12812659e+03 1.10965381e+03 1.14622913e+03 1.27788513e+03 1.32373462e+03 1.29760254e+03 1.35485278e+03 1.41672571e+03 1.46052588e+03 1.55554700e+03 1.57163623e+03 1.56087695e+03 1.64934656e+03 1.67008801e+03 1.75399597e+03 1.83055005e+03 1.78816907e+03 1.88733765e+03 1.98647778e+03 1.98157178e+03 2.02481140e+03 2.06900146e+03 2.11603516e+03 2.17149731e+03 2.21306641e+03 2.18527026e+03 2.22032837e+03 2.39445605e+03 2.52117163e+03 2.50145215e+03 2.41663306e+03 2.40646558e+03 2.49889429e+03 2.65967212e+03 2.77715527e+03 2.75806396e+03 2.68298779e+03 2.72094141e+03 2.83832422e+03 2.88238135e+03 2.89963232e+03 2.94814062e+03 2.98493188e+03 3.02209351e+03 3.18575244e+03 3.16048242e+03 3.09782178e+03 3.22661987e+03 3.18987378e+03 3.30447656e+03 3.40614551e+03 3.33942749e+03 3.51543872e+03 3.49385962e+03 3.38523755e+03 3.54886450e+03 3.49836426e+03 3.57854077e+03 3.88299585e+03 3.73320483e+03 3.54843799e+03 3.66213257e+03 3.91217358e+03 4.10314209e+03 4.04024707e+03 3.85161304e+03 3.81386719e+03 3.90380640e+03 4.10536768e+03 4.31242090e+03 4.26354150e+03 4.06147681e+03 4.08373242e+03 4.24831201e+03 4.32181836e+03 4.32920703e+03 4.35898389e+03 4.39149023e+03 4.40261475e+03 4.60743945e+03 4.65333887e+03 4.39763379e+03 4.42538037e+03 4.62873633e+03 4.67293311e+03 4.70247070e+03 4.71980322e+03 4.88104639e+03 4.81722559e+03 4.66515234e+03 4.83810303e+03 4.74970996e+03 4.90712451e+03 5.27853223e+03 4.99738623e+03 4.72340137e+03 4.91559912e+03 5.19821582e+03 5.36744678e+03 5.36916162e+03 5.07094971e+03 4.94203809e+03 5.11291504e+03 5.36474902e+03 5.55496973e+03 5.48359521e+03 5.20298730e+03 5.20954248e+03 5.44476465e+03 5.50558350e+03 5.62530664e+03 5.67803174e+03 5.39978955e+03 5.38295508e+03 5.69883545e+03 5.75874805e+03 5.54814746e+03 5.55580957e+03 5.70830225e+03 5.65976953e+03 5.88695264e+03 5.95435059e+03 5.74296338e+03 5.73964990e+03 5.74662549e+03 5.82478027e+03 5.89620557e+03 5.85654053e+03 6.06542578e+03 6.19074805e+03 6.01500928e+03 5.85505078e+03 5.73389062e+03 6.04081348e+03 6.44085645e+03 6.28953760e+03 5.94268555e+03 5.85374121e+03 6.08807324e+03 6.46757764e+03 6.31760938e+03 5.95168896e+03 6.07556250e+03 6.27626025e+03 6.48222949e+03 6.64918799e+03 6.47637842e+03 6.13267090e+03 6.15788721e+03 6.33824414e+03 6.43218701e+03 6.46964111e+03 6.46228711e+03 6.47261426e+03 6.44179883e+03 6.53706689e+03 6.49226416e+03 6.41004932e+03 6.43083447e+03 6.36479980e+03 6.63595898e+03 6.71524707e+03 6.54525879e+03 6.68171143e+03 6.70010254e+03 6.62681885e+03 6.50188428e+03 6.36547021e+03 6.69320117e+03 6.99163379e+03 6.84083008e+03 6.54770850e+03 6.46650195e+03 6.83706787e+03 6.97677490e+03 6.78673535e+03 6.73606299e+03 6.55314648e+03 6.54628809e+03 6.87636523e+03 6.83712256e+03 6.70486426e+03 6.57148584e+03 6.50829736e+03 6.90125928e+03 7.15413086e+03 6.74581396e+03 6.62242432e+03 6.82973535e+03 6.83524365e+03 7.04123730e+03 6.96459375e+03 6.57546875e+03 6.66780176e+03 6.91661719e+03 6.82936914e+03 6.85744922e+03 6.90044775e+03 7.15204443e+03 7.02022852e+03 6.51155762e+03 6.78443896e+03 6.82086670e+03 7.13025195e+03 6.82035303e+03 6.62331689e+03 6.61457373e+03 8.66384375e+03 8.55835742e+03 1.03190195e+04 8.60672070e+03 1.27230771e+04 2.24452520e+04 2.97645762e+04 -4466672. -49551468. 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. 0. 0. 0. 0. 0. 0. 50947440. 50947440. -3.28714275e+06 -5.08869550e+06 -4127077. -1.70640425e+06 2.00020371e+04 1.53695664e+04 7.97463574e+03 6.42759570e+03 7.49706689e+03 6.69499219e+03 6.14615039e+03 6.38590918e+03 6.38619922e+03 6.18846631e+03 6.17663428e+03 6.17854736e+03 6.24371875e+03 6.29121777e+03 6.06318555e+03 5.83500732e+03 6.03104785e+03 6.00215479e+03 5.59515967e+03 5.91234961e+03 6.09317139e+03 5.60090283e+03 5.91707520e+03 6.16809961e+03 5.85794189e+03 5.69952393e+03 5.81596436e+03 5.93166113e+03 5.81392578e+03 5.76307275e+03 5.69734521e+03 5.66200098e+03 5.55215137e+03 5.53350439e+03 5.66774707e+03 5.66200049e+03 5.53581445e+03 5.48653955e+03 5.48555127e+03 5.47697266e+03 5.40203223e+03 5.37274707e+03 5.35734277e+03 5.26195508e+03 5.22157666e+03 5.17232080e+03 5.14248584e+03 5.37275000e+03 5.35283398e+03 5.13017871e+03 4.96256592e+03 4.92250684e+03 5.20053516e+03 5.19765283e+03 4.97564893e+03 4.81641357e+03 4.80653369e+03 4.85751709e+03 4.80351904e+03 4.96048877e+03 4.94269629e+03 4.59397705e+03 4.48445508e+03 4.68484814e+03 4.90958154e+03 4.74593799e+03 4.56092529e+03 4.53016553e+03 4.47861182e+03 4.47439111e+03 4.47344141e+03 4.36888232e+03 4.29707861e+03 4.29107959e+03 4.24549805e+03 4.21112939e+03 4.18098535e+03 4.26681494e+03 4.21092090e+03 4.06247144e+03 4.01541724e+03 3.97507764e+03 4.04705469e+03 4.01927075e+03 3.90801538e+03 3.87514331e+03 3.74075732e+03 3.61574316e+03 3.75883252e+03 3.78050854e+03 3.53692383e+03 3.51403271e+03 3.67268872e+03 3.73857104e+03 3.59151855e+03 3.44769189e+03 3.40943311e+03 3.37169653e+03 3.29415894e+03 3.24514038e+03 3.23615820e+03 3.18165967e+03 3.24629077e+03 3.18504956e+03 3.04965210e+03 3.01877490e+03 2.89960303e+03 2.92070142e+03 3.04712305e+03 2.95651465e+03 2.83551001e+03 2.71226123e+03 2.63213086e+03 2.73308862e+03 2.75101489e+03 2.62880273e+03 2.50265112e+03 2.44975488e+03 2.45939648e+03 2.41300928e+03 2.45213916e+03 2.41928467e+03 2.28824316e+03 2.20844360e+03 2.15913257e+03 2.19461768e+03 2.16298706e+03 2.06941284e+03 2.00533582e+03 1.95979309e+03 1.90918420e+03 1.81452991e+03 1.81506909e+03 1.87824597e+03 1.79578809e+03 1.69760718e+03 1.61647083e+03 1.55924890e+03 1.60047986e+03 1.56215784e+03 1.46783386e+03 1.38611255e+03 1.33390100e+03 1.32893591e+03 1.28326672e+03 1.23361792e+03 1.15076782e+03 1.12986072e+03 1.14579797e+03 1.06777625e+03 1.00826721e+03 9.65756775e+02 9.07317688e+02 8.47460205e+02 8.03164917e+02 7.57827576e+02 7.04028625e+02 6.59534119e+02 5.99445740e+02 5.67040710e+02 5.51190613e+02 4.78134918e+02 4.16031219e+02 3.79945312e+02 3.31041534e+02 2.91477905e+02 2.41561096e+02 1.87048828e+02 1.44682495e+02 9.69049530e+01 4.74345894e+01 -5.07889748e-01 -4.82236557e+01 -9.45008240e+01 -1.41703125e+02 -1.88486404e+02 -2.30035461e+02 -2.86789368e+02 -3.54032135e+02 -3.94149597e+02 -4.26587219e+02 -4.59994019e+02 -5.13827698e+02 -5.94014832e+02 -6.38178711e+02 -6.70530640e+02 -6.99764099e+02 -7.40419861e+02 -8.13626221e+02 -8.61369324e+02 -9.24039978e+02 -9.61383240e+02 -9.80194153e+02 -1.03681226e+03 -1.08552429e+03 -1.17155261e+03 -1.22329309e+03 -1.22997900e+03 -1.26890503e+03 -1.32067212e+03 -1.36712708e+03 -1.37698877e+03 -1.45226685e+03 -1.58206494e+03 -1.60754834e+03 -1.60801147e+03 -1.61107874e+03 -1.64952930e+03 -1.79108105e+03 -1.84743542e+03 -1.83768323e+03 -1.84306250e+03 -1.87944312e+03 -1.98225073e+03 -2.03421509e+03 -2.11903198e+03 -2.15268042e+03 -2.14250952e+03 -2.16238647e+03 -2.20364551e+03 -2.35335327e+03 -2.40872656e+03 -2.38606226e+03 -2.38729614e+03 -2.42637329e+03 -2.56732544e+03 -2.62551367e+03 -2.53655200e+03 -2.57326978e+03 -2.78674292e+03 -2.81163037e+03 -2.70856885e+03 -2.75362378e+03 -2.93179858e+03 -3.00250269e+03 -2.94364868e+03 -2.90552563e+03 -2.95927588e+03 -3.17523926e+03 -3.20463843e+03 -3.14156934e+03 -3.22062646e+03 -3.25068213e+03 -3.22152246e+03 -3.26046411e+03 -3.39187280e+03 -3.34401172e+03 -3.44414673e+03 -3.63998584e+03 -3.58004956e+03 -3.65318677e+03 -3.68865820e+03 -3.66792114e+03 -3.71941016e+03 -3.74164502e+03 -3.77393921e+03 -3.74863110e+03 -3.72742749e+03 -3.84713477e+03 -3.96754614e+03 -4.12364453e+03 -4.03103052e+03 -3.94750781e+03 -4.10211963e+03 -4.14381104e+03 -4.29583203e+03 -4.32184326e+03 -4.23338086e+03 -4.20735205e+03 -4.21400781e+03 -4.35383838e+03 -4.39418506e+03 -4.54175000e+03 -4.56677686e+03 -4.46960889e+03 -4.49753906e+03 -4.41971484e+03 -4.57110547e+03 -4.85713818e+03 -4.82430859e+03 -4.73001025e+03 -4.64977637e+03 -4.63925537e+03 -4.89380225e+03 -5.00244287e+03 -4.91229199e+03 -4.81000488e+03 -4.83639600e+03 -4.99608789e+03 -4.99062402e+03 -5.17139404e+03 -5.18014014e+03 -5.06807617e+03 -5.11158936e+03 -5.14185938e+03 -5.31446729e+03 -5.33001221e+03 -5.12000439e+03 -5.16095020e+03 -5.48827295e+03 -5.42205566e+03 -5.15275732e+03 -5.33564893e+03 -5.65286182e+03 -5.63802881e+03 -5.53904932e+03 -5.40486670e+03 -5.40927441e+03 -5.73440967e+03 -5.78632080e+03 -5.64114453e+03 -5.53027344e+03 -5.52726074e+03 -5.70913525e+03 -5.75071680e+03 -5.78294434e+03 -5.67980273e+03 -5.81866602e+03 -6.10288525e+03 -5.99764014e+03 -5.94577979e+03 -5.94232080e+03 -5.93025195e+03 -5.96703320e+03 -6.01904248e+03 -6.03752148e+03 -6.04568457e+03 -6.03491602e+03 -5.90733643e+03 -6.00610986e+03 -6.34731738e+03 -6.14010791e+03 -5.89800293e+03 -6.10419336e+03 -6.30637988e+03 -6.50248779e+03 -6.42358594e+03 -6.27552246e+03 -6.31439551e+03 -6.35210254e+03 -6.20958496e+03 -6.19731348e+03 -6.43668213e+03 -6.45615625e+03 -6.33346484e+03 -6.30680664e+03 -6.14417676e+03 -6.42299219e+03 -6.78767773e+03 -6.60865625e+03 -6.46776465e+03 -6.33758008e+03 -6.35287451e+03 -6.68821777e+03 -6.81340430e+03 -6.63254688e+03 -6.47295605e+03 -6.43798975e+03 -6.48962500e+03 -6.58979297e+03 -6.81149707e+03 -6.75115918e+03 -6.60271338e+03 -6.63307568e+03 -6.62537402e+03 -6.73718604e+03 -6.75819824e+03 -6.63649316e+03 -6.71706934e+03 -6.75379932e+03 -6.64118018e+03 -6.48618018e+03 -6.67260986e+03 -6.99078320e+03 -6.92712402e+03 -6.74940479e+03 -6.61081641e+03 -6.64333203e+03 -7.04946240e+03 -7.01915723e+03 -6.77967334e+03 -6.68349121e+03 -6.63780469e+03 -6.72508008e+03 -6.76859326e+03 -6.81979541e+03 -6.67257568e+03 -6.80330518e+03 -7.12179785e+03 -6.85445312e+03 -6.93297266e+03 -6.96210449e+03 -6.85122852e+03 -6.84158105e+03 -6.86189648e+03 -6.66156592e+03 -6.68420361e+03 -6.91125732e+03 -6.95390820e+03 -6.91797461e+03 -6.91333838e+03 -6.66826514e+03 -6.60064941e+03 -6.81583545e+03 -6.84612012e+03 -7.04852344e+03 -6.96841406e+03 -6.64068652e+03 -6.82618115e+03 -6.92317969e+03 -6.82989746e+03 -6.73480029e+03 -6.70085742e+03 -6.78601611e+03 -6.82003369e+03 -6.75534766e+03 -6.58597021e+03 -6.71358203e+03 -7.06287109e+03 -6.92493115e+03 -6.71168896e+03 -6.55291016e+03 -6.54190869e+03 -6.94934766e+03 -6.85859180e+03 -6.73097949e+03 -6.50852588e+03 -6.38931006e+03 -6.62973389e+03 -6.76356299e+03 -6.92008545e+03 -6.69150195e+03 -6.40765771e+03 -6.51470850e+03 -6.55007422e+03 -6.80137402e+03 -6.62678906e+03 -6.43543506e+03 -6.57960156e+03 -6.57258545e+03 -6.47994141e+03 -6.33221582e+03 -6.41175439e+03 -6.76663037e+03 -6.63071143e+03 -6.41834717e+03 -6.23965381e+03 -6.25670312e+03 -6.56561475e+03 -6.56116895e+03 -6.36651562e+03 -6.21552441e+03 -6.13113184e+03 -6.28433350e+03 -6.30386035e+03 -6.44916455e+03 -6.43671924e+03 -6.16947998e+03 -6.02516211e+03 -6.12512158e+03 -6.37485400e+03 -6.22975293e+03 -6.07665381e+03 -6.17857080e+03 -6.12256445e+03 -5.94609668e+03 -5.84989990e+03 -6.04933252e+03 -5.99635010e+03 -5.86790186e+03 -6.09813916e+03 -6.11950977e+03 -5.93388965e+03 -5.88657910e+03 -5.86271191e+03 -5.80458203e+03 -5.63205029e+03 -5.58520117e+03 -5.82087744e+03 -5.89481152e+03 -5.57222900e+03 -5.41154150e+03 -5.64698096e+03 -5.84729297e+03 -5.75710303e+03 -5.53352490e+03 -5.38009717e+03 -5.53970508e+03 -5.63968555e+03 -5.50904688e+03 -5.41808057e+03 -5.23499121e+03 -5.10158398e+03 -5.33094580e+03 -5.54457715e+03 -5.40337109e+03 -5.14958447e+03 -5.04995166e+03 -5.28425879e+03 -5.32902100e+03 -5.14356055e+03 -4.96654150e+03 -4.88382129e+03 -4.93169775e+03 -4.95258447e+03 -5.09095508e+03 -5.05614746e+03 -4.84515869e+03 -4.79854004e+03 -4.78036816e+03 -4.85210059e+03 -4.71205615e+03 -4.59640039e+03 -4.78807227e+03 -4.74852441e+03 -4.58704395e+03 -4.42115332e+03 -4.46650586e+03 -4.68448438e+03 -4.46654834e+03 -4.26125146e+03 -4.36818311e+03 -4.40026221e+03 -4.37270312e+03 -4.28559033e+03 -4.34628418e+03 -4.34203760e+03 -4.16419678e+03 -3.99532910e+03 -3.97760645e+03 -4.18569189e+03 -4.06859619e+03 -3.91076538e+03 -3.95078076e+03 -3.91710327e+03 -3.84906152e+03 -3.79045190e+03 -3.81771851e+03 -3.75150000e+03 -3.63649707e+03 -3.69265967e+03 -3.65971460e+03 -3.62757007e+03 -3.59584399e+03 -3.51365747e+03 -3.44748975e+03 -3.30021973e+03 -3.28783594e+03 -3.44095386e+03 -3.43876367e+03 -3.20118994e+03 -3.06282202e+03 -3.16422974e+03 -3.23364331e+03 -3.16178979e+03 -3.00982935e+03 -2.86868994e+03 -2.96064282e+03 -3.00639062e+03 -2.86231494e+03 -2.87326465e+03 -2.81154932e+03 -2.65634375e+03 -2.67685986e+03 -2.73175269e+03 -2.66381982e+03 -2.50156982e+03 -2.41048071e+03 -2.50429102e+03 -2.51964209e+03 -2.39525562e+03 -2.27619824e+03 -2.21457837e+03 -2.29562012e+03 -2.25093457e+03 -2.13205371e+03 -2.11745166e+03 -2.06989331e+03 -2.00725806e+03 -1.95502112e+03 -1.98137500e+03 -1.89592419e+03 -1.77612976e+03 -1.82056653e+03 -1.78940186e+03 -1.72186755e+03 -1.63233411e+03 -1.56329211e+03 -1.59729468e+03 -1.51417822e+03 -1.42772522e+03 -1.48353430e+03 -1.46025928e+03 -1.36347290e+03 -1.26078198e+03 -1.64297107e+03 -1.73755017e+03 -1.41150464e+03 -1.70336865e+03 -1.65322144e+03 -1.65091382e+03 -1.43439014e+03 -2.86981714e+03 -5.24811035e+03 4.23644188e+05 128359992. 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. 0. -217353520. -7.14308750e+05 -7.31227875e+05 3.36780713e+03 2.54110791e+03 1.48797119e+03 1.12973792e+03 1.11384985e+03 1.06692932e+03 1.10822620e+03 1.15206799e+03 1.17110010e+03 1.22715149e+03 1.29968616e+03 1.33636084e+03 1.38262439e+03 1.41952625e+03 1.45256262e+03 1.55857800e+03 1.58382007e+03 1.57108728e+03 1.65423279e+03 1.68408533e+03 1.67390479e+03 1.79941699e+03 1.93908386e+03 1.90592712e+03 1.89991711e+03 1.95867456e+03 2.02077051e+03 2.05792188e+03 2.09396606e+03 2.15980859e+03 2.20595776e+03 2.27179932e+03 2.31646387e+03 2.28090137e+03 2.34963330e+03 2.47376831e+03 2.53931641e+03 2.56874829e+03 2.51289160e+03 2.53363013e+03 2.66576733e+03 2.72224951e+03 2.73288525e+03 2.75309375e+03 2.78979126e+03 2.89244556e+03 2.97778223e+03 2.97889917e+03 2.93479712e+03 2.97397437e+03 3.16535376e+03 3.21541357e+03 3.09545801e+03 3.12126367e+03 3.25270605e+03 3.34434497e+03 3.41620044e+03 3.39169287e+03 3.33203442e+03 3.41100293e+03 3.53509790e+03 3.59212134e+03 3.58280884e+03 3.55809424e+03 3.66806128e+03 3.77980859e+03 3.76186011e+03 3.74384375e+03 3.75489429e+03 3.84540625e+03 3.96513892e+03 3.97758545e+03 4.02726318e+03 4.03534033e+03 3.97095605e+03 4.06926270e+03 4.16995996e+03 4.18168457e+03 4.22715771e+03 4.23122998e+03 4.25919092e+03 4.40939600e+03 4.42561328e+03 4.31696631e+03 4.35756885e+03 4.49249414e+03 4.55895312e+03 4.57127686e+03 4.55514697e+03 4.57423340e+03 4.63840479e+03 4.73613867e+03 4.73696289e+03 4.64364453e+03 4.75602295e+03 4.92246191e+03 4.94331152e+03 4.95650732e+03 4.84650195e+03 4.85888721e+03 5.05329102e+03 5.05826416e+03 4.99334424e+03 5.00661768e+03 5.07229199e+03 5.22998145e+03 5.22313721e+03 5.20374902e+03 5.25241748e+03 5.28566455e+03 5.36298584e+03 5.39074121e+03 5.33881299e+03 5.36652246e+03 5.42917041e+03 5.40547266e+03 5.49093262e+03 5.54913184e+03 5.54392383e+03 5.57427148e+03 5.56518018e+03 5.57495947e+03 5.68927344e+03 5.74257178e+03 5.72825146e+03 5.71431982e+03 5.68642090e+03 5.73355273e+03 5.82011084e+03 5.80596533e+03 5.78504883e+03 5.89813281e+03 6.04451367e+03 6.01543213e+03 5.91981006e+03 5.94648779e+03 6.00517041e+03 6.01174219e+03 5.98291455e+03 5.98837061e+03 6.06849707e+03 6.16304590e+03 6.24323047e+03 6.24301953e+03 6.10070654e+03 6.03603223e+03 6.20781201e+03 6.32480127e+03 6.33165137e+03 6.27159814e+03 6.18218701e+03 6.30153906e+03 6.43371240e+03 6.43423047e+03 6.28236963e+03 6.22630566e+03 6.40911768e+03 6.56979053e+03 6.48827295e+03 6.24794971e+03 6.34823633e+03 6.54716748e+03 6.56641211e+03 6.47447363e+03 6.48810400e+03 6.55996484e+03 6.56128711e+03 6.59639062e+03 6.54793066e+03 6.48364160e+03 6.60372412e+03 6.73363281e+03 6.61392041e+03 6.62336963e+03 6.67617578e+03 6.58118457e+03 6.64575049e+03 6.68327588e+03 6.75168262e+03 6.82739160e+03 6.51798975e+03 6.60063477e+03 6.92158105e+03 6.78115137e+03 6.58737158e+03 6.68651270e+03 6.85479004e+03 6.77519238e+03 6.78752002e+03 6.77554492e+03 6.70181250e+03 6.69397461e+03 6.86834082e+03 6.91720068e+03 6.72659375e+03 6.77260889e+03 6.96267871e+03 6.86569482e+03 6.81446533e+03 6.77310352e+03 6.71375049e+03 6.89177979e+03 6.86000537e+03 6.77278418e+03 6.85234961e+03 6.73744580e+03 6.82241406e+03 6.98082422e+03 6.79272314e+03 6.78183398e+03 6.82851416e+03 6.85198584e+03 6.81231982e+03 6.85718750e+03 6.86115674e+03 6.77177832e+03 6.78354736e+03 6.83292578e+03 6.85199414e+03 6.73643555e+03 6.83377148e+03 6.91028760e+03 6.81268701e+03 6.94209375e+03 6.78351318e+03 6.63084082e+03 6.78031641e+03 6.84672461e+03 6.81177002e+03 6.69109570e+03 6.58053125e+03 6.73930811e+03 6.90457080e+03 6.78047070e+03 6.63450146e+03 6.76102637e+03 6.78941992e+03 6.66928906e+03 6.59200977e+03 6.75724805e+03 6.70396240e+03 6.56589209e+03 6.76262402e+03 6.65101367e+03 6.55750537e+03 6.69336523e+03 6.54235059e+03 6.51423682e+03 6.56042285e+03 6.52147070e+03 6.48971533e+03 6.55050488e+03 6.62475928e+03 6.61313379e+03 6.41620605e+03 6.35104346e+03 6.48817188e+03 6.44654492e+03 6.46538477e+03 6.42500049e+03 6.37597559e+03 6.34182129e+03 6.36679346e+03 6.45187207e+03 6.28722852e+03 6.12961084e+03 6.28439844e+03 6.53220508e+03 6.22157422e+03 6.06503467e+03 6.16277734e+03 6.10560498e+03 6.23740332e+03 6.25288818e+03 6.07748682e+03 6.03465186e+03 6.09548145e+03 6.09089990e+03 6.10925391e+03 6.00533838e+03 6.02935986e+03 6.07682031e+03 5.80997021e+03 5.86793164e+03 5.89438379e+03 5.80395801e+03 5.92596924e+03 5.84971533e+03 5.72596631e+03 5.79527734e+03 5.71471631e+03 5.70370068e+03 5.86427490e+03 5.73678516e+03 5.60788965e+03 5.53842529e+03 5.47649268e+03 5.58201855e+03 5.62210254e+03 5.47275928e+03 5.43116748e+03 5.52217822e+03 5.48605908e+03 5.39134717e+03 5.29497705e+03 5.27877393e+03 5.29596240e+03 5.32829834e+03 5.31331982e+03 5.13758789e+03 5.09643848e+03 5.16534326e+03 5.17660059e+03 5.11989404e+03 5.05672510e+03 4.98463770e+03 4.93929980e+03 5.09122021e+03 5.06808447e+03 4.83344482e+03 4.72410645e+03 4.76442041e+03 4.80647656e+03 4.75452832e+03 4.67634277e+03 4.68384131e+03 4.68173584e+03 4.63298389e+03 4.64853369e+03 4.54246533e+03 4.45874268e+03 4.49113184e+03 4.51099951e+03 4.42654688e+03 4.26513770e+03 4.29170850e+03 4.29002979e+03 4.24687891e+03 4.26176953e+03 4.18459814e+03 4.09455396e+03 4.09684570e+03 4.14456201e+03 4.04433716e+03 3.92366284e+03 3.94062939e+03 3.91863184e+03 3.85062476e+03 3.82094482e+03 3.75728906e+03 3.71957544e+03 3.71129883e+03 3.70673120e+03 3.69126855e+03 3.58112207e+03 3.52914209e+03 3.50005640e+03 3.43971582e+03 3.40809058e+03 3.34143677e+03 3.34522705e+03 3.32310620e+03 3.23428516e+03 3.16021558e+03 3.14469751e+03 3.16048633e+03 3.13715527e+03 3.09492432e+03 3.00229102e+03 2.94440405e+03 2.89788428e+03 2.82682300e+03 2.80612720e+03 2.79801758e+03 2.74792603e+03 2.69172046e+03 2.62411792e+03 2.56721704e+03 2.57249487e+03 2.56194336e+03 2.52542920e+03 2.43754712e+03 2.33097241e+03 2.31752368e+03 2.29996338e+03 2.23488721e+03 2.21010522e+03 2.19070825e+03 2.10439551e+03 2.03862097e+03 1.99367627e+03 1.95126575e+03 1.96784570e+03 1.93132520e+03 1.84081067e+03 1.80307471e+03 1.73330078e+03 1.65534802e+03 1.66178357e+03 1.63128271e+03 1.54689502e+03 1.50293359e+03 1.45292029e+03 1.39211084e+03 1.38027710e+03 1.36569434e+03 1.28360754e+03 1.22138049e+03 1.18650732e+03 1.13862598e+03 1.09622607e+03 1.04407520e+03 9.96016663e+02 9.51570068e+02 9.03462585e+02 8.61839783e+02 8.10381592e+02 7.53159241e+02 7.17321594e+02 6.78135803e+02 6.17888123e+02 5.62089111e+02 5.16356262e+02 4.78077393e+02 4.35025055e+02 3.89260803e+02 3.31073395e+02 2.74769897e+02 2.33760162e+02 1.89376007e+02 1.43300171e+02 9.34381943e+01 4.52623405e+01 -2.02044491e-02 -4.75031662e+01 -9.63214645e+01 -1.47676727e+02 -1.96505356e+02 -2.40263107e+02 -2.90563965e+02 -3.32800598e+02 -3.68722351e+02 -4.31043945e+02 -4.95824036e+02 -5.28205444e+02 -5.60770325e+02 -6.12559692e+02 -6.66713257e+02 -7.24195068e+02 -7.76225647e+02 -8.16023804e+02 -8.42753845e+02 -8.95297363e+02 -9.58038086e+02 -9.98668701e+02 -1.05812244e+03 -1.10670532e+03 -1.14144507e+03 -1.18097449e+03 -1.24096924e+03 -1.29452466e+03 -1.33037415e+03 -1.38865466e+03 -1.44217224e+03 -1.46545581e+03 -1.48602710e+03 -1.53857520e+03 -1.60603589e+03 -1.68907422e+03 -1.73293140e+03 -1.72679980e+03 -1.76741736e+03 -1.82614697e+03 -1.89182690e+03 -1.96357617e+03 -1.98182544e+03 -1.99216516e+03 -2.08694116e+03 -2.13743726e+03 -2.14131641e+03 -2.24866504e+03 -2.28636157e+03 -2.27137012e+03 -2.32398804e+03 -2.34774365e+03 -2.39244531e+03 -2.51754297e+03 -2.56258594e+03 -2.56023364e+03 -2.63916431e+03 -2.65883936e+03 -2.61971533e+03 -2.68864282e+03 -2.79685156e+03 -2.84481421e+03 -2.88072803e+03 -2.88605493e+03 -2.93116968e+03 -3.02172168e+03 -3.07712573e+03 -3.19192871e+03 -3.17038672e+03 -3.08354785e+03 -3.14436694e+03 -3.23314551e+03 -3.32774927e+03 -3.40899927e+03 -3.37922998e+03 -3.33532959e+03 -3.45641650e+03 -3.55072046e+03 -3.54791968e+03 -3.60034521e+03 -3.63358618e+03 -3.62857397e+03 -3.72037915e+03 -3.76749365e+03 -3.72279224e+03 -3.87853027e+03 -3.96894800e+03 -3.91149731e+03 -3.92256250e+03 -3.86559985e+03 -3.91824609e+03 -4.08712573e+03 -4.25117529e+03 -4.23901318e+03 -4.04510059e+03 -4.11161182e+03 -4.29002148e+03 -4.29735449e+03 -4.33425146e+03 -4.36377979e+03 -4.35087158e+03 -4.43291504e+03 -4.49339258e+03 -4.52566699e+03 -4.55709521e+03 -4.58084668e+03 -4.67978223e+03 -4.66809619e+03 -4.62531592e+03 -4.64626855e+03 -4.71932373e+03 -4.82656934e+03 -4.94837402e+03 -4.87575000e+03 -4.76288037e+03 -4.88787549e+03 -4.99119824e+03 -5.11645459e+03 -5116. -4.95808740e+03 -5.02850781e+03 -5.11411377e+03 -5.19593701e+03 -5.32223975e+03 -5.25161133e+03 -5.18774463e+03 -5.27095850e+03 -5.23288379e+03 -5.21416992e+03 -5.42173730e+03 -5.54443701e+03 -5.44562793e+03 -5.35912549e+03 -5.37026758e+03 -5.43804834e+03 -5.62264697e+03 -5.67889844e+03 -5.66410010e+03 -5.59564160e+03 -5.48970508e+03 -5.59790869e+03 -5.68371143e+03 -5.85349219e+03 -5.90207617e+03 -5.69810596e+03 -5.70526025e+03 -5.78946143e+03 -5.87596240e+03 -5.91949609e+03 -5.97240332e+03 -5.99522900e+03 -5.87210791e+03 -5.93129736e+03 -5.98213281e+03 -5.98558984e+03 -6.04798682e+03 -6.11448730e+03 -6.11106055e+03 -6.09309326e+03 -6.03732764e+03 -6.13916895e+03 -6.30726367e+03 -6.24232227e+03 -6.12485059e+03 -6.21077686e+03 -6.20379346e+03 -6.23372900e+03 -6.49167676e+03 -6.43798975e+03 -6.22310645e+03 -6.37827197e+03 -6.45035840e+03 -6.52046826e+03 -6.55431250e+03 -6.41399365e+03 -6.57354785e+03 -7.32480469e+03 -8.83269434e+03 -6.57474854e+03 -8.98586133e+03 -8.51084473e+03 -1.16990225e+04 -8.78295020e+03 -1.46073623e+04 -1.36412594e+05 43397152. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -86350792. -4093179. 6.31776650e+06 -16706702. -2.08284082e+04 -1.90429961e+04 -9.86472363e+03 -6.49233838e+03 -7.13689111e+03 -7.27412842e+03 -7.08147461e+03 -6.81975488e+03 -6.66857764e+03 -6.71066455e+03 -6.87452930e+03 -7.03903906e+03 -6.91108887e+03 -6.69026562e+03 -6.66500049e+03 -6.74821875e+03 -6.89797900e+03 -6.83847021e+03 -6.53363770e+03 -6.64459619e+03 -6.82197510e+03 -6.75955811e+03 -6.62016943e+03 -6.49546045e+03 -6.65223633e+03 -6.96547852e+03 -6.92690771e+03 -6.55294531e+03 -6.28991455e+03 -6.47121875e+03 -6.75698438e+03 -6.88477148e+03 -6.72083105e+03 -6.43404688e+03 -6.49575342e+03 -6.60322217e+03 -6.73803125e+03 -6.63017334e+03 -6.26430713e+03 -6.35256738e+03 -6.66437109e+03 -6.56267871e+03 -6.37380322e+03 -6.42892578e+03 -6.41997168e+03 -6.47375879e+03 -6.51145752e+03 -6.20451855e+03 -6.11800049e+03 -6.40968848e+03 -6.55244531e+03 -6.43059424e+03 -6.18388232e+03 -6.01829688e+03 -6.32858496e+03 -6.50671631e+03 -6.32236426e+03 -6.08147852e+03 -5.88810645e+03 -5.97164307e+03 -6.23290869e+03 -6.32912256e+03 -6.18004297e+03 -6.05669482e+03 -6.03470361e+03 -5.95483057e+03 -5.96746387e+03 -5.99696484e+03 -5.79530127e+03 -5.87623633e+03 -6.05969434e+03 -5.93445508e+03 -5.66844238e+03 -5.60320459e+03 -5.85669092e+03 -6.00502881e+03 -5.90820996e+03 -5.66603271e+03 -5.51266846e+03 -5.50104395e+03 -5.63006104e+03 -5.85541211e+03 -5.73897803e+03 -5.38599170e+03 -5.43083984e+03 -5.49346436e+03 -5.52411768e+03 -5.60499902e+03 -5.37054639e+03 -5.31159033e+03 -5.42310791e+03 -5.36433984e+03 -5.29119385e+03 -5.17507617e+03 -5.19478369e+03 -5.30702979e+03 -5.24338916e+03 -5.04654199e+03 -4.99447949e+03 -5.12023730e+03 -5.14632422e+03 -5.10143555e+03 -5.00475342e+03 -4.82932129e+03 -4.85877734e+03 -4.97752100e+03 -4.95072754e+03 -4.81867578e+03 -4.60429541e+03 -4.59864844e+03 -4.79399512e+03 -4.88309619e+03 -4.73232568e+03 -4.48145312e+03 -4.48181201e+03 -4.60030762e+03 -4.55430225e+03 -4.40712500e+03 -4.32636621e+03 -4.43085889e+03 -4.46162012e+03 -4.32021143e+03 -4.21777246e+03 -4.12533594e+03 -4.22187158e+03 -4.37552783e+03 -4.21250146e+03 -4.06520728e+03 -3.98355786e+03 -3.95022583e+03 -3.99002393e+03 -4.03340332e+03 -3.95583594e+03 -3.74342432e+03 -3.72183545e+03 -3.85654272e+03 -3.86736230e+03 -3.72198901e+03 -3.59445776e+03 -3.60876245e+03 -3.64714795e+03 -3.60200708e+03 -3.50770532e+03 -3.34115625e+03 -3.33989429e+03 -3.42797363e+03 -3.40067993e+03 -3.30947437e+03 -3.18225977e+03 -3.16997705e+03 -3.19351562e+03 -3.22506470e+03 -3.15561548e+03 -2.96124561e+03 -2.94915601e+03 -2.96766016e+03 -2.92041602e+03 -2.88977710e+03 -2.80669727e+03 -2.77179907e+03 -2.75160718e+03 -2.68830127e+03 -2.62401489e+03 -2.56384937e+03 -2.58806396e+03 -2.58843311e+03 -2.51070752e+03 -2.38436304e+03 -2.30135278e+03 -2.35240723e+03 -2.38632349e+03 -2.31926807e+03 -2.20384546e+03 -2.08849268e+03 -2.02889453e+03 -2.06565381e+03 -2.10588354e+03 -2.00877637e+03 -1.86535107e+03 -1.84309949e+03 -1.86054858e+03 -1.82617529e+03 -1.77491223e+03 -1.69319751e+03 -1.64674524e+03 -1.61360925e+03 -1.55233179e+03 -1.49400061e+03 -1.45777222e+03 -1.43014014e+03 -1.38566199e+03 -1.32827295e+03 -1.26917383e+03 -1.21518140e+03 -1.19086621e+03 -1.16695203e+03 -1.11558020e+03 -1.02922693e+03 -9.64138306e+02 -9.62360718e+02 -9.31681824e+02 -8.70169861e+02 -8.08360718e+02 -7.34704285e+02 -6.92650146e+02 -6.79578064e+02 -6.46360901e+02 -5.84064087e+02 -5.10122986e+02 -4.60992950e+02 -4.30625000e+02 -3.91575958e+02 -3.38895782e+02 -2.86379517e+02 -2.40525223e+02 -1.91379333e+02 -1.41557037e+02 -9.18995590e+01 -4.42876625e+01 3.04749012e+00 5.16733894e+01 1.02000290e+02 1.48612411e+02 1.86284149e+02 2.33659073e+02 2.86955994e+02 3.34998627e+02 3.88457184e+02 4.29051727e+02 4.88521240e+02 5.38560608e+02 5.56580627e+02 5.95182495e+02 6.57509705e+02 7.34719971e+02 8.05711853e+02 8.38239258e+02 8.38017395e+02 8.54755859e+02 9.26204651e+02 1.03041199e+03 1.10421252e+03 1.12654639e+03 1.10710730e+03 1.14735278e+03 1.28358191e+03 1.32601172e+03 1.29294202e+03 1.34909998e+03 1.41816846e+03 1.46443445e+03 1.56082117e+03 1.56866101e+03 1.56130664e+03 1.65008484e+03 1.66124316e+03 1.75137329e+03 1.84378052e+03 1.78823743e+03 1.88131360e+03 1.98857983e+03 1.98281384e+03 2.02853796e+03 2.06549805e+03 2.11478760e+03 2.17203296e+03 2.20836035e+03 2.19708496e+03 2.23796875e+03 2.39550220e+03 2.50581250e+03 2.49281567e+03 2.41722729e+03 2.41513550e+03 2.50101758e+03 2.66353979e+03 2.79180859e+03 2.75719360e+03 2.67753613e+03 2.72692969e+03 2.85385156e+03 2.89060278e+03 2.88645679e+03 2.94058740e+03 2.97981616e+03 3.01164111e+03 3.19095947e+03 3.17491504e+03 3.09290601e+03 3.21370117e+03 3.18599097e+03 3.30763550e+03 3.41313843e+03 3.34460767e+03 3.52165503e+03 3.49553052e+03 3.38809937e+03 3.53783813e+03 3.50576245e+03 3.58443188e+03 3.87719336e+03 3.73709595e+03 3.56673706e+03 3.67598730e+03 3.89906079e+03 4.08553003e+03 4.03439404e+03 3.83396313e+03 3.76758325e+03 3.91777734e+03 4.14631543e+03 4.33234521e+03 4.27336084e+03 4.06029712e+03 4.07102930e+03 4.26889990e+03 4.38339746e+03 4.30401953e+03 4.29914941e+03 4.38727734e+03 4.41952100e+03 4.60585156e+03 4.64074268e+03 4.44021143e+03 4.48083447e+03 4.57626367e+03 4.63687402e+03 4.72075439e+03 4.72422217e+03 4.86784180e+03 4.82657520e+03 4.68762012e+03 4.80475537e+03 4.74384033e+03 4.90777686e+03 5.28476855e+03 5.03019824e+03 4.70957666e+03 4.89946387e+03 5.15608008e+03 5.33177441e+03 5.38866846e+03 5.13203711e+03 4.95229932e+03 5.06834277e+03 5.36552002e+03 5.60759863e+03 5.49112012e+03 5.19034668e+03 5.17919189e+03 5.41036084e+03 5.50361182e+03 5.64952002e+03 5.69898730e+03 5.39390771e+03 5.40521240e+03 5.64311768e+03 5.72333252e+03 5.66050195e+03 5.62429639e+03 5.63369482e+03 5.62315527e+03 5.90979053e+03 5.96201953e+03 5.70381836e+03 5.71784570e+03 5.79848047e+03 5.85372070e+03 5.92356055e+03 5.86685059e+03 6.05216406e+03 6.15414355e+03 5.96979102e+03 5.86976904e+03 5.76569629e+03 6.02115527e+03 6.43842236e+03 6.29109375e+03 5.95101953e+03 5.85762549e+03 6.11778418e+03 6.47996924e+03 6.29118799e+03 5.96402148e+03 6.07158008e+03 6.26368555e+03 6.49478027e+03 6.65260547e+03 6.52739062e+03 6.15473242e+03 6.07449072e+03 6.28126367e+03 6.50596533e+03 6.52213330e+03 6.45274561e+03 6.44212402e+03 6.42214990e+03 6.58969287e+03 6.54069141e+03 6.39464697e+03 6.39062549e+03 6.38490674e+03 6.65584424e+03 6.76701172e+03 6.54847070e+03 6.61950049e+03 6.66839795e+03 6.73599365e+03 6.61742773e+03 6.32607764e+03 6.62239258e+03 7.01090674e+03 6.80682568e+03 6.46445557e+03 6.53894092e+03 6.90172217e+03 6.89102686e+03 6.74929492e+03 6.77080615e+03 6.58602051e+03 6.55901465e+03 6.95778955e+03 6.97244629e+03 6.63574414e+03 6.50606641e+03 6.51162500e+03 6.83044482e+03 7.15731934e+03 6.82573389e+03 6.64473291e+03 6.84773877e+03 6.82399854e+03 7.01118799e+03 6.97689795e+03 6.57754297e+03 6.63994287e+03 6.84800391e+03 6.84276416e+03 6.87564502e+03 6.81517041e+03 6.95195459e+03 7.14882324e+03 6.46975342e+03 7.02218945e+03 6.75161035e+03 8.30309180e+03 9.97547949e+03 1.04988096e+04 1.02456367e+04 1.03819980e+04 1.11000459e+04 1.04048232e+04 1.01884561e+04 1.27230771e+04 2.24452520e+04 2.97645762e+04 -4466672. -49551468. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -142007024. 11945210. -12088190. 2.16294727e+04 1.28170117e+04 7.27734766e+03 6.50962842e+03 7.50645020e+03 6.75023828e+03 6.24410742e+03 6.33899609e+03 6.34215283e+03 6.19353662e+03 6.18522852e+03 6.17107520e+03 6.23220215e+03 6.31281689e+03 6.06654004e+03 5.84849707e+03 5.96973926e+03 5.94977344e+03 5.65648291e+03 5.97986670e+03 6.10006348e+03 5.56898828e+03 5.90689307e+03 6.17729346e+03 5.87666309e+03 5.73043555e+03 5.84789551e+03 5.94445947e+03 5.78314355e+03 5.73671582e+03 5.72081543e+03 5.66502100e+03 5.57955371e+03 5.54300195e+03 5.66476172e+03 5.66717480e+03 5.53179346e+03 5.48774316e+03 5.47927197e+03 5.46234229e+03 5.40565918e+03 5.37593408e+03 5.36954932e+03 5.19736279e+03 5.13766650e+03 5.23758936e+03 5.19491699e+03 5.37400244e+03 5.35431299e+03 5.13417188e+03 4.96877979e+03 4.91544727e+03 5.20308594e+03 5.20379248e+03 4.97387744e+03 4.83851660e+03 4.82929980e+03 4.87816113e+03 4.81531201e+03 4.94373389e+03 4.90870898e+03 4.58739111e+03 4.50639258e+03 4.71586230e+03 4.87390234e+03 4.71170898e+03 4.55949316e+03 4.55630225e+03 4.48854346e+03 4.40672998e+03 4.40966797e+03 4.38130127e+03 4.31832617e+03 4.27887842e+03 4.24453516e+03 4.25038232e+03 4.20978027e+03 4.25609521e+03 4.19759863e+03 4.04250806e+03 4.06938599e+03 4.03707715e+03 4.00201904e+03 3.98442383e+03 3.91516211e+03 3.87180444e+03 3.74496436e+03 3.61881860e+03 3.76017017e+03 3.76872559e+03 3.54285547e+03 3.52667554e+03 3.68664575e+03 3.73564429e+03 3.58764526e+03 3.45956299e+03 3.39577637e+03 3.34737158e+03 3.28559595e+03 3.23591699e+03 3.26008716e+03 3.20481226e+03 3.23235938e+03 3.17993774e+03 3.04372583e+03 3.05245044e+03 2.93506445e+03 2.89408643e+03 3.00762524e+03 2.93976050e+03 2.83417847e+03 2.72450488e+03 2.63606787e+03 2.72703271e+03 2.74717871e+03 2.62468359e+03 2.49655029e+03 2.45327222e+03 2.47179956e+03 2.41695630e+03 2.44850610e+03 2.42173926e+03 2.29414038e+03 2.20358765e+03 2.16051636e+03 2.20201270e+03 2.15990967e+03 2.06449146e+03 1.99866418e+03 1.95056714e+03 1.92908105e+03 1.83712805e+03 1.79875903e+03 1.85772571e+03 1.79928076e+03 1.70083716e+03 1.60888354e+03 1.55779431e+03 1.60518921e+03 1.56228467e+03 1.47046484e+03 1.38630908e+03 1.33194470e+03 1.32831482e+03 1.28089966e+03 1.23337073e+03 1.15334729e+03 1.13050574e+03 1.14377295e+03 1.06495142e+03 1.00689032e+03 9.63412170e+02 9.07830627e+02 8.48138245e+02 8.01053650e+02 7.63419189e+02 7.14689575e+02 6.62843323e+02 5.95700256e+02 5.59410339e+02 5.45644714e+02 4.76814880e+02 4.14398529e+02 3.78911407e+02 3.31282471e+02 2.92462982e+02 2.39203659e+02 1.83678162e+02 1.44685455e+02 9.71717987e+01 4.71625443e+01 2.26903018e-02 -4.67383080e+01 -9.36690750e+01 -1.41827362e+02 -1.90374283e+02 -2.32095367e+02 -2.86873474e+02 -3.53312561e+02 -3.94026031e+02 -4.28007568e+02 -4.60704102e+02 -5.12572937e+02 -5.96355835e+02 -6.40882874e+02 -6.70284241e+02 -7.00771790e+02 -7.41778564e+02 -8.12785889e+02 -8.60260376e+02 -9.25791321e+02 -9.54777466e+02 -9.72238647e+02 -1.04987476e+03 -1.09922021e+03 -1.16858374e+03 -1.21076660e+03 -1.22170227e+03 -1.26871509e+03 -1.31846729e+03 -1.38199670e+03 -1.38864038e+03 -1.45128040e+03 -1.58210144e+03 -1.60354688e+03 -1.61145386e+03 -1.61674023e+03 -1.65072095e+03 -1.79180737e+03 -1.84995374e+03 -1.84145789e+03 -1.83892847e+03 -1.87975269e+03 -1.98769080e+03 -2.03774585e+03 -2.12514355e+03 -2.14869409e+03 -2.14360620e+03 -2.16544189e+03 -2.19846802e+03 -2.35650317e+03 -2.39687012e+03 -2.36622729e+03 -2.39293774e+03 -2.44040674e+03 -2.56050928e+03 -2.61293408e+03 -2.55120410e+03 -2.58058765e+03 -2.76113940e+03 -2.80817407e+03 -2.71803442e+03 -2.75049902e+03 -2.93512769e+03 -2.99459692e+03 -2.94705933e+03 -2.91640747e+03 -2.95727979e+03 -3.17551465e+03 -3.19629248e+03 -3.13153979e+03 -3.19771167e+03 -3.23203540e+03 -3.27442310e+03 -3.31939893e+03 -3.35645435e+03 -3.30550342e+03 -3.43256494e+03 -3.67613354e+03 -3.61225415e+03 -3.60272021e+03 -3.65780347e+03 -3.68287231e+03 -3.72702197e+03 -3.74949951e+03 -3.77562866e+03 -3.73437720e+03 -3.71194092e+03 -3.85223926e+03 -3.98650903e+03 -4.14778662e+03 -4.03781323e+03 -3.92460767e+03 -4.08286450e+03 -4.17220117e+03 -4.32059912e+03 -4.28635840e+03 -4.20887354e+03 -4.22593408e+03 -4.23375098e+03 -4.36464893e+03 -4.40769189e+03 -4.54184521e+03 -4.56456641e+03 -4.48240479e+03 -4.45256934e+03 -4.37497803e+03 -4.59788477e+03 -4.90714355e+03 -4.83978906e+03 -4.72368848e+03 -4.64913721e+03 -4.60819531e+03 -4.86860156e+03 -5.05173242e+03 -4.95672900e+03 -4.79172559e+03 -4.81767139e+03 -4.98342139e+03 -5.00587646e+03 -5.17876514e+03 -5.18759326e+03 -5.07547900e+03 -5.12807324e+03 -5.15361670e+03 -5.29904590e+03 -5.30532617e+03 -5.11897021e+03 -5.17511768e+03 -5.49037939e+03 -5.41677734e+03 -5.16084668e+03 -5.36735791e+03 -5.69972119e+03 -5.61481006e+03 -5.50438818e+03 -5.41145410e+03 -5.42840234e+03 -5.75698145e+03 -5.78058887e+03 -5.63535840e+03 -5.51470898e+03 -5.53565625e+03 -5.74267725e+03 -5.76047754e+03 -5.74854590e+03 -5.66745996e+03 -5.79950342e+03 -6.06551318e+03 -5.92279492e+03 -5.98360400e+03 -5.97679980e+03 -5.90381641e+03 -5.97448438e+03 -6.01610693e+03 -6.04655615e+03 -6.00494727e+03 -5.96898096e+03 -5.87541064e+03 -6.04274951e+03 -6.40589209e+03 -6.18354150e+03 -5.93464160e+03 -6.14143799e+03 -6.25979199e+03 -6.43301611e+03 -6.38960938e+03 -6.21341162e+03 -6.37733740e+03 -6.41697803e+03 -6.16720605e+03 -6.09901172e+03 -6.51056543e+03 -6.52672803e+03 -6.37734277e+03 -6.27939502e+03 -6.09104346e+03 -6.40656836e+03 -6.80312500e+03 -6.67176221e+03 -6.45917090e+03 -6.33012451e+03 -6.28367969e+03 -6.64153613e+03 -6.85847266e+03 -6.70155420e+03 -6.40984473e+03 -6.36350293e+03 -6.53691016e+03 -6.64462695e+03 -6.83971533e+03 -6.71968066e+03 -6.53755908e+03 -6.68400195e+03 -6.66743066e+03 -6.81392285e+03 -6.76840527e+03 -6.63130566e+03 -6.71781689e+03 -6.75711230e+03 -6.69988623e+03 -6.50727148e+03 -6.60599219e+03 -7.06351025e+03 -6.95882910e+03 -6.68115186e+03 -6.54679492e+03 -6.64393555e+03 -7.03540039e+03 -7.01174561e+03 -6.80338770e+03 -6.66221533e+03 -6.61565674e+03 -6.82716260e+03 -6.81433105e+03 -6.79722949e+03 -6.66545117e+03 -6.82473535e+03 -7.12422412e+03 -6.84823926e+03 -6.91933545e+03 -6.94627832e+03 -6.85009277e+03 -6.80262451e+03 -6.75630371e+03 -6.76310693e+03 -6.76910254e+03 -6.79483057e+03 -6.77804297e+03 -6.98376758e+03 -6.97889453e+03 -6.67262793e+03 -6.55845947e+03 -6.73725586e+03 -6.90429346e+03 -7.14442236e+03 -6.90723193e+03 -6.57022900e+03 -6.90400586e+03 -7.02601611e+03 -6.86699414e+03 -6.72126025e+03 -6.65243701e+03 -6.80294141e+03 -6.81290186e+03 -6.71009326e+03 -6.52054785e+03 -6.76190576e+03 -7.07718750e+03 -6.86052686e+03 -6.77350537e+03 -6.59242627e+03 -6.54534277e+03 -6.94087354e+03 -6.91320605e+03 -6.70277783e+03 -6.49801562e+03 -6.39417529e+03 -6.55767090e+03 -6.77052637e+03 -7.00453516e+03 -6.64001318e+03 -6.36618701e+03 -6.57297510e+03 -6.61829932e+03 -6.77743994e+03 -6.68494873e+03 -6.43797217e+03 -6.58151709e+03 -6.59301709e+03 -6.40879346e+03 -6.24011279e+03 -6.47854395e+03 -6.79729834e+03 -6.58077100e+03 -6.45320459e+03 -6.30725098e+03 -6.23088574e+03 -6.56834619e+03 -6.56103271e+03 -6.36986279e+03 -6.16424512e+03 -6.11730859e+03 -6.28249463e+03 -6.29287451e+03 -6.44809375e+03 -6.41840967e+03 -6.17335791e+03 -6.06225000e+03 -6.12828516e+03 -6.37026855e+03 -6.19958057e+03 -6.05177295e+03 -6.12599609e+03 -6.07906299e+03 -5.97405273e+03 -5.87650928e+03 -6.08064355e+03 -6.07517285e+03 -5.87670850e+03 -6.08098096e+03 -6.10998193e+03 -5.92035400e+03 -5.88083105e+03 -5.89354443e+03 -5.82129053e+03 -5.65653613e+03 -5.58128955e+03 -5.82408594e+03 -5.89301611e+03 -5.56356494e+03 -5.36447803e+03 -5.61395068e+03 -5.90843799e+03 -5.77880566e+03 -5.46727832e+03 -5.33455615e+03 -5.59384863e+03 -5.64967188e+03 -5.44303516e+03 -5.45512158e+03 -5.28824365e+03 -5.09730029e+03 -5.29191699e+03 -5.49902002e+03 -5.44792383e+03 -5.17264502e+03 -4.99186182e+03 -5.23196436e+03 -5.38566895e+03 -5.20185400e+03 -4.93327490e+03 -4.83869385e+03 -4.97033008e+03 -4.98920850e+03 -5.08577930e+03 -5.03514258e+03 -4.82089258e+03 -4.82862158e+03 -4.82657715e+03 -4.86913086e+03 -4.71638574e+03 -4.58296289e+03 -4.74278125e+03 -4.70118066e+03 -4.63190039e+03 -4.46241748e+03 -4.46660352e+03 -4.68959668e+03 -4.46960205e+03 -4.26418945e+03 -4.34036475e+03 -4.39709229e+03 -4.38249512e+03 -4.28922021e+03 -4.34226367e+03 -4.34060010e+03 -4.17963330e+03 -4.00798633e+03 -3.97805640e+03 -4.15906934e+03 -4.03761182e+03 -3.87582056e+03 -3.98836597e+03 -3.96547607e+03 -3.82854590e+03 -3.75176929e+03 -3.85362402e+03 -3.78659790e+03 -3.62738721e+03 -3.69079468e+03 -3.65707275e+03 -3.63198340e+03 -3.59500317e+03 -3.51214795e+03 -3.44371387e+03 -3.30154297e+03 -3.24390186e+03 -3.38032495e+03 -3.46097949e+03 -3.23895483e+03 -3.03700391e+03 -3.12761816e+03 -3.27332642e+03 -3.20816382e+03 -3.00299097e+03 -2.85656714e+03 -2.96171362e+03 -3.00914453e+03 -2.86398706e+03 -2.86287402e+03 -2.81612476e+03 -2.67102319e+03 -2.65357056e+03 -2.71172046e+03 -2.67569214e+03 -2.52414575e+03 -2.40728320e+03 -2.47678613e+03 -2.53560205e+03 -2.42008057e+03 -2.28490479e+03 -2.20575586e+03 -2.26902197e+03 -2.28538965e+03 -2.16662744e+03 -2.07525293e+03 -2.03555347e+03 -2.02312549e+03 -1.97236719e+03 -1.98438074e+03 -1.89640161e+03 -1.77893884e+03 -1.80193018e+03 -1.76901941e+03 -1.73064233e+03 -1.63861108e+03 -1.56466931e+03 -1.59054639e+03 -1.50591736e+03 -1.43036780e+03 -1.42951074e+03 -1.39579614e+03 -1.36471741e+03 -1.31428040e+03 -1.28473523e+03 -1.24088696e+03 -1.19284106e+03 -1.11460254e+03 -9.75226013e+02 -1.05873682e+03 -8.28766357e+02 -1.59225427e+03 -3.52343262e+03 4.23644188e+05 128359992. 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. 466285152. -6.38635938e+05 3.99322607e+03 2.57463623e+03 1.41469275e+03 1.19943115e+03 1.21353711e+03 1.02753271e+03 1.02468237e+03 1.01580133e+03 1.03777795e+03 1.09588721e+03 1.17283984e+03 1.22132080e+03 1.23155200e+03 1.26241553e+03 1.33604028e+03 1.38723474e+03 1.42076404e+03 1.46926343e+03 1.53256116e+03 1.55618726e+03 1.60377625e+03 1.68207043e+03 1.66385034e+03 1.65160938e+03 1.77818408e+03 1.92064380e+03 1.94877307e+03 1.91593018e+03 1.91260364e+03 2.01671997e+03 2.08846484e+03 2.10974780e+03 2.13419971e+03 2.17595508e+03 2.26828027e+03 2.32496753e+03 2.34300708e+03 2.36299194e+03 2.40502563e+03 2.53093311e+03 2.58753638e+03 2.50563257e+03 2.54337329e+03 2.64581714e+03 2.69556641e+03 2.78794604e+03 2.80768848e+03 2.78018701e+03 2.86581836e+03 2.93925366e+03 2.96767163e+03 3.01851807e+03 3.02061377e+03 3.07625171e+03 3.15955835e+03 3.15914282e+03 3.18077979e+03 3.21295190e+03 3.27898779e+03 3.37532739e+03 3.43686108e+03 3.45566650e+03 3.42816748e+03 3.44286865e+03 3.58083789e+03 3.61827295e+03 3.56972632e+03 3.65091943e+03 3.70537720e+03 3.75496704e+03 3.85988232e+03 3.87507837e+03 3.81726318e+03 3.85297168e+03 3.99330151e+03 4.06123584e+03 4.00352539e+03 3.97117749e+03 4.04566162e+03 4.13667334e+03 4.28306104e+03 4.29639160e+03 4.18327588e+03 4.22534521e+03 4.39294434e+03 4.43187891e+03 4.43609131e+03 4.35804688e+03 4.37045020e+03 4.55532617e+03 4.61204639e+03 4.54710596e+03 4.58608252e+03 4.64163232e+03 4.68281445e+03 4.72597559e+03 4.73164893e+03 4.80887354e+03 4.84187158e+03 4.94739014e+03 4.99060303e+03 4.81705029e+03 4.87175635e+03 5.02194580e+03 5.02622998e+03 5.04730811e+03 5.05097607e+03 5.10196338e+03 5.24857715e+03 5.20837500e+03 5.16336963e+03 5.30400928e+03 5.34193701e+03 5.27946631e+03 5.28801123e+03 5.37513281e+03 5.41922119e+03 5.43140137e+03 5.38689941e+03 5.43769727e+03 5.50890039e+03 5.66181885e+03 5.63638525e+03 5.47699854e+03 5.55333350e+03 5.71874902e+03 5.74329150e+03 5.71605957e+03 5.66780957e+03 5.63955225e+03 5.79933643e+03 5.94256934e+03 5.86477197e+03 5.75038721e+03 5.81679004e+03 5.98274707e+03 6.03861816e+03 6.08805664e+03 5.95589111e+03 5.82241895e+03 5.97156592e+03 6.01306055e+03 6.03340088e+03 6.09902197e+03 6.05616406e+03 6.15759766e+03 6.30897314e+03 6.23390039e+03 6.00453809e+03 6.09676562e+03 6.25805518e+03 6.33298877e+03 6.38915723e+03 6.27606152e+03 6.20369629e+03 6.28670312e+03 6.49154785e+03 6.39682715e+03 6.19047607e+03 6.31498975e+03 6.51593555e+03 6.48426904e+03 6.44808398e+03 6.33998096e+03 6.36863916e+03 6.49259326e+03 6.50753857e+03 6.50739453e+03 6.58222314e+03 6.49816992e+03 6.51486475e+03 6.69208350e+03 6.61553125e+03 6.48521240e+03 6.55751416e+03 6.69401465e+03 6.67056689e+03 6.71254297e+03 6.58463721e+03 6.50442969e+03 6.66776172e+03 6.93688086e+03 6.97086426e+03 6.52193994e+03 6.55954785e+03 6.92337646e+03 6.82149951e+03 6.67377881e+03 6.66558545e+03 6.63542334e+03 6.79300342e+03 6.89079883e+03 6.81217578e+03 6.68594971e+03 6.65860596e+03 6.78010254e+03 6.94413232e+03 6.93625830e+03 6.81572412e+03 6.75230225e+03 6.81536768e+03 6.85460303e+03 6.75854199e+03 6.73606104e+03 6.83413232e+03 6.78868652e+03 6.94283398e+03 7.00388623e+03 6.65426221e+03 6.70724170e+03 6.91502930e+03 6.92925000e+03 6.89076514e+03 6.72176416e+03 6.75707373e+03 6.93018408e+03 6.94894092e+03 6.86620020e+03 6.67460449e+03 6.63407617e+03 6.83240234e+03 6.97150049e+03 6.83335938e+03 6.77261621e+03 6.86841797e+03 6.79739551e+03 6.90970410e+03 6.88532764e+03 6.68634668e+03 6.65630859e+03 6.72415430e+03 6.89449023e+03 6.76484570e+03 6.67930078e+03 6.69578809e+03 6.80674170e+03 6.81259473e+03 6.71937891e+03 6.67925781e+03 6.67529297e+03 6.76704492e+03 6.66679443e+03 6.79673633e+03 6.67516211e+03 6.57175439e+03 6.72111865e+03 6.53146436e+03 6.56123340e+03 6.73153369e+03 6.57558203e+03 6.52985449e+03 6.56773340e+03 6.58890820e+03 6.53705957e+03 6.41893262e+03 6.59495850e+03 6.78219141e+03 6.41694336e+03 6.33560254e+03 6.41819092e+03 6.41951758e+03 6.55110791e+03 6.46429590e+03 6.29629004e+03 6.30355420e+03 6.44572900e+03 6.44678320e+03 6.33953955e+03 6.28251953e+03 6.26730615e+03 6.31381055e+03 6.18571826e+03 6.18617139e+03 6.12271191e+03 6.12157178e+03 6.18341992e+03 6.26231885e+03 6.17071973e+03 6.04833887e+03 5.98531592e+03 6.11801367e+03 6.21882031e+03 5.97857178e+03 6.01591064e+03 6.01313965e+03 5.79792822e+03 5.93466455e+03 5.91412598e+03 5.76639697e+03 5.89464893e+03 5.85809375e+03 5.77022168e+03 5.89381396e+03 5.78554346e+03 5.65689307e+03 5.67985059e+03 5.71269434e+03 5.72010596e+03 5.55214551e+03 5.50292725e+03 5.57539697e+03 5.60186182e+03 5.54885889e+03 5.46544971e+03 5.37254492e+03 5.46466357e+03 5.56255908e+03 5.36731104e+03 5.24975439e+03 5.20964453e+03 5.34568066e+03 5.38268408e+03 5.17462256e+03 5.10926904e+03 5.13299707e+03 5.12634961e+03 5.07604102e+03 5.09142236e+03 5.02862891e+03 4.90891895e+03 4.97558789e+03 5.06488672e+03 4.89485986e+03 4.69471484e+03 4.74039111e+03 4.83116260e+03 4.78676611e+03 4.74451855e+03 4.68727588e+03 4.57443799e+03 4.67682666e+03 4.72823975e+03 4.54156006e+03 4.44896680e+03 4.44086963e+03 4.54484863e+03 4.47297705e+03 4.24875586e+03 4.23448779e+03 4.27422754e+03 4.26288379e+03 4.24808740e+03 4.22330615e+03 4.12884082e+03 4.10349951e+03 4.05873291e+03 3.94994067e+03 3.92875024e+03 3.89626733e+03 3.91439038e+03 3.91985669e+03 3.81374048e+03 3.71337427e+03 3.71100391e+03 3.74135962e+03 3.80393774e+03 3.72573682e+03 3.52464526e+03 3.48237842e+03 3.52158740e+03 3.47088110e+03 3.39094458e+03 3.36703394e+03 3.33957446e+03 3.31367676e+03 3.24318384e+03 3.13268091e+03 3.15256348e+03 3.18686377e+03 3.14909448e+03 3.05036328e+03 2.94471143e+03 2.94373169e+03 2.88516797e+03 2.82092554e+03 2.86851709e+03 2.82102441e+03 2.68556421e+03 2.65181470e+03 2.65667505e+03 2.65342603e+03 2.60767432e+03 2.50693262e+03 2.46565894e+03 2.43234155e+03 2.35714551e+03 2.29976123e+03 2.29367554e+03 2.25792188e+03 2.23611060e+03 2.18888965e+03 2.05471118e+03 2.03674536e+03 2.01801282e+03 1.97318237e+03 1.97492725e+03 1.87585022e+03 1.80314929e+03 1.81920020e+03 1.78047510e+03 1.69691553e+03 1.64442810e+03 1.58518140e+03 1.53331116e+03 1.50241504e+03 1.46465039e+03 1.41065930e+03 1.38908435e+03 1.35805676e+03 1.28921521e+03 1.22551416e+03 1.16237476e+03 1.13866016e+03 1.11332837e+03 1.05382007e+03 9.82233582e+02 9.31384094e+02 8.98661682e+02 8.63193237e+02 8.29506348e+02 7.62794556e+02 7.01637939e+02 6.66408203e+02 6.19617615e+02 5.65263367e+02 5.27794006e+02 4.75562500e+02 4.18066101e+02 3.83866577e+02 3.36210358e+02 2.83601868e+02 2.34917007e+02 1.85967545e+02 1.40816223e+02 9.42196655e+01 4.63541565e+01 -3.11184740e+00 -5.12162971e+01 -9.86581268e+01 -1.44710342e+02 -1.91396011e+02 -2.33724945e+02 -2.83295135e+02 -3.33261597e+02 -3.79063385e+02 -4.36347900e+02 -4.84042084e+02 -5.22107849e+02 -5.67609680e+02 -6.19657776e+02 -6.84235413e+02 -7.37852905e+02 -7.67245300e+02 -8.02253601e+02 -8.43645447e+02 -8.97929382e+02 -9.55634460e+02 -1.00794415e+03 -1.05671924e+03 -1.09638147e+03 -1.13452148e+03 -1.17296875e+03 -1.22913416e+03 -1.31545361e+03 -1.35987366e+03 -1.36143164e+03 -1.40659192e+03 -1.45505664e+03 -1.49894751e+03 -1.57648059e+03 -1.63763623e+03 -1.65885205e+03 -1.69319775e+03 -1.72956091e+03 -1.78237329e+03 -1.86470764e+03 -1.90140771e+03 -1.94272180e+03 -1.98578601e+03 -2.01087354e+03 -2.08171338e+03 -2.09770752e+03 -2.14378613e+03 -2.24810425e+03 -2.25181299e+03 -2.26355176e+03 -2.32944531e+03 -2.37359180e+03 -2.41291919e+03 -2.54104272e+03 -2.58939014e+03 -2.51004102e+03 -2.57040479e+03 -2.64857739e+03 -2.66663403e+03 -2.78002368e+03 -2.81235229e+03 -2.77326245e+03 -2.84346289e+03 -2.89515552e+03 -3.00808618e+03 -3.08581958e+03 -3.05679468e+03 -3.10767651e+03 -3.11251636e+03 -3.08173633e+03 -3.16326538e+03 -3.29773999e+03 -3.32493115e+03 -3.37563037e+03 -3.40453369e+03 -3.30631860e+03 -3.41856421e+03 -3.60637769e+03 -3.63729077e+03 -3.58658350e+03 -3.52578003e+03 -3.61345264e+03 -3.78018848e+03 -3.79523804e+03 -3.78428687e+03 -3.86959717e+03 -3.85671606e+03 -3.90873682e+03 -3.96987646e+03 -3.88858472e+03 -3.95991602e+03 -4.11619238e+03 -4.18729590e+03 -4.15855957e+03 -4.06234009e+03 -4.12998682e+03 -4.28562793e+03 -4.35654785e+03 -4.39097412e+03 -4.30551123e+03 -4.28193164e+03 -4.40520215e+03 -4.54038672e+03 -4.64786426e+03 -4.59300537e+03 -4.52658984e+03 -4.60201904e+03 -4.62470166e+03 -4.65215039e+03 -4.74413477e+03 -4.74853418e+03 -4.80745947e+03 -4.91359375e+03 -4.86188721e+03 -4.84784863e+03 -4.95309375e+03 -5.00387598e+03 -5.03686328e+03 -5.00392871e+03 -4.96485840e+03 -5.02718262e+03 -5.16439160e+03 -5.25225635e+03 -5.31073584e+03 -5.20401416e+03 -5.12769482e+03 -5.25972803e+03 -5.26516357e+03 -5.33319629e+03 -5.45251172e+03 -5.38452002e+03 -5.35649854e+03 -5.34979150e+03 -5.43448535e+03 -5589. -5.69128320e+03 -5.61367139e+03 -5.59337988e+03 -5.56049463e+03 -5.47751123e+03 -5.59161621e+03 -5.75027637e+03 -5.84410010e+03 -5.85294727e+03 -5.69965479e+03 -5.67092725e+03 -5.82484277e+03 -5.90864600e+03 -5.91676709e+03 -5.93417480e+03 -5.90144482e+03 -5.83010352e+03 -5.97974121e+03 -6.14521875e+03 -6.06237354e+03 -5.94393018e+03 -6.02384961e+03 -6.08980420e+03 -6.14212354e+03 -6.18946729e+03 -6.18656152e+03 -6.22881934e+03 -6.17538330e+03 -6.12249707e+03 -6.33880029e+03 -6.31631104e+03 -6.23998193e+03 -6.44119922e+03 -6.28779785e+03 -6.20865332e+03 -6.49783838e+03 -6.55365820e+03 -6.24137500e+03 -6.70873828e+03 -6.66665283e+03 -5.95083936e+03 -5.85807422e+03 -1.06712275e+04 -1.01477295e+04 -1.79236309e+04 -2.10968477e+04 60721824. -2819905. -67271688. -41445444. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.98316650e+06 -20910288. -3.07884688e+04 -1.58189316e+04 -9.33458008e+03 -1.11550117e+04 -8.83713867e+03 -9.54229883e+03 -7.56193799e+03 -6.56211963e+03 -6.78235791e+03 -7.07486084e+03 -6.98370459e+03 -6.84071875e+03 -6.74262891e+03 -6.66699316e+03 -6.93005371e+03 -7.13165918e+03 -6.84842725e+03 -6.53899414e+03 -6.62026367e+03 -6.73676367e+03 -6.86318506e+03 -6.96387451e+03 -6.71026465e+03 -6.58258887e+03 -6.69383057e+03 -6.65112500e+03 -6.74046338e+03 -6.63260791e+03 -6.55849463e+03 -6.74407227e+03 -6.93546973e+03 -6.77240576e+03 -6.40986963e+03 -6.44608105e+03 -6.69460449e+03 -6.73840088e+03 -6.57974512e+03 -6.40331348e+03 -6.47601953e+03 -6.68914746e+03 -6.83055420e+03 -6.58927148e+03 -6.27944824e+03 -6.36057227e+03 -6.65355664e+03 -6.58306689e+03 -6.55197119e+03 -6.42366602e+03 -6.20701270e+03 -6.35595361e+03 -6.56316309e+03 -6.36914795e+03 -6.25396826e+03 -6.45340771e+03 -6.46239746e+03 -6.35629541e+03 -6.22935205e+03 -6.09023877e+03 -6.20190381e+03 -6.45935889e+03 -6.32115527e+03 -6.10410986e+03 -6.01248438e+03 -5.99378760e+03 -6.22935938e+03 -6.37466553e+03 -6.15363184e+03 -5.96558643e+03 -5.92518945e+03 -5.86811133e+03 -6.03199023e+03 -6.17761475e+03 -5.92612305e+03 -5.80972559e+03 -5.93653027e+03 -5.86886719e+03 -5.75699121e+03 -5.77109961e+03 -5.82023096e+03 -5.88186572e+03 -5.83849707e+03 -5.78950537e+03 -5.56332275e+03 -5.46085400e+03 -5.72928711e+03 -5.84489160e+03 -5.52715820e+03 -5.34960840e+03 -5.45174805e+03 -5.54284033e+03 -5.59753516e+03 -5.64445605e+03 -5.39087158e+03 -5.26855518e+03 -5.36501660e+03 -5.33990576e+03 -5.37500830e+03 -5.26607617e+03 -5.11633301e+03 -5.14873926e+03 -5.21924072e+03 -5.20331201e+03 -5.14132861e+03 -5.12172363e+03 -5.06610254e+03 -5.03190723e+03 -5.03565967e+03 -4.85051562e+03 -4.78591016e+03 -5.02684277e+03 -5.00489209e+03 -4.73051660e+03 -4.61373877e+03 -4.66317725e+03 -4.82213574e+03 -4.93237158e+03 -4.72129785e+03 -4.47896338e+03 -4.44302100e+03 -4.48687939e+03 -4.52636572e+03 -4.52375781e+03 -4.43973291e+03 -4.39869971e+03 -4.34623242e+03 -4.30972900e+03 -4.28898877e+03 -4.17163477e+03 -4.19810107e+03 -4.30207324e+03 -4.18779688e+03 -4.08934521e+03 -4.00924121e+03 -3.90497437e+03 -4.02758398e+03 -4.09525342e+03 -3.86784912e+03 -3.73435571e+03 -3.77235815e+03 -3.87712817e+03 -3.90141309e+03 -3.73524487e+03 -3.58614038e+03 -3.55362476e+03 -3.55583154e+03 -3.59539941e+03 -3.59626221e+03 -3.41218311e+03 -3.29650586e+03 -3.36133203e+03 -3.42225586e+03 -3.35546777e+03 -3.24260693e+03 -3.20471582e+03 -3.14796582e+03 -3.14918604e+03 -3.13148633e+03 -2.98821973e+03 -2.93432886e+03 -2.96894849e+03 -2.94660059e+03 -2.88405835e+03 -2.78349561e+03 -2.74751807e+03 -2.75110278e+03 -2.71485034e+03 -2.68058887e+03 -2.57547974e+03 -2.54342236e+03 -2.55327563e+03 -2.48887231e+03 -2.42410205e+03 -2.34318530e+03 -2.30388647e+03 -2.31539258e+03 -2.32930957e+03 -2.24920435e+03 -2.09784448e+03 -2.03932617e+03 -2.08914087e+03 -2.09605908e+03 -2.01273010e+03 -1.88938391e+03 -1.82166650e+03 -1.83127185e+03 -1.81727759e+03 -1.77625378e+03 -1.69216577e+03 -1.61925281e+03 -1.59745667e+03 -1.58064282e+03 -1.54608972e+03 -1.47511755e+03 -1.40661987e+03 -1.37191187e+03 -1.33002722e+03 -1.28351636e+03 -1.23587939e+03 -1.18071606e+03 -1.13548340e+03 -1.08653601e+03 -1.02632214e+03 -9.75468628e+02 -9.61391174e+02 -9.45771362e+02 -8.85144348e+02 -8.04268250e+02 -7.31008545e+02 -6.92579834e+02 -6.85970886e+02 -6.51169861e+02 -5.83360901e+02 -5.15311401e+02 -4.58644012e+02 -4.24094177e+02 -3.93221985e+02 -3.43238800e+02 -2.89422791e+02 -2.38977020e+02 -1.91224197e+02 -1.41897232e+02 -8.97840576e+01 -4.22898331e+01 5.15615797e+00 5.16778488e+01 1.01256065e+02 1.45620804e+02 1.81455978e+02 2.32974167e+02 2.93024719e+02 3.42405304e+02 3.88910828e+02 4.28908356e+02 4.89027252e+02 5.42424133e+02 5.61399780e+02 5.90438416e+02 6.50240173e+02 7.32706909e+02 8.04879456e+02 8.39828491e+02 8.41422974e+02 8.59981995e+02 9.27596252e+02 1.02383417e+03 1.09961694e+03 1.12861902e+03 1.11421680e+03 1.15368433e+03 1.27661292e+03 1.31981763e+03 1.29960583e+03 1.35330127e+03 1.41430042e+03 1.45774963e+03 1.56446619e+03 1.57573633e+03 1.55799548e+03 1.64963892e+03 1.66605469e+03 1.75350623e+03 1.84419604e+03 1.79514319e+03 1.88039233e+03 1.97986902e+03 1.97992151e+03 2.03699329e+03 2.06687671e+03 2.11193262e+03 2.18460693e+03 2.20636377e+03 2.18560107e+03 2.24034106e+03 2.40697803e+03 2.50953955e+03 2.48906787e+03 2.42035498e+03 2.41227930e+03 2.49897144e+03 2.66280518e+03 2.79498755e+03 2.75361426e+03 2.66652466e+03 2.72878979e+03 2.85231470e+03 2.87564014e+03 2.88841919e+03 2.94226831e+03 2.98659155e+03 3.03370068e+03 3.19302466e+03 3.15832129e+03 3.09125269e+03 3.21797803e+03 3.16042627e+03 3.30472314e+03 3.42250073e+03 3.34940527e+03 3.53081934e+03 3.50234937e+03 3.37024292e+03 3.51731104e+03 3.51210693e+03 3.60598828e+03 3.87620898e+03 3.73273804e+03 3.56482739e+03 3.67556226e+03 3.89893677e+03 4.09779053e+03 4.03696216e+03 3.86960840e+03 3.82041992e+03 3.88324438e+03 4.10055469e+03 4.30204883e+03 4.27973535e+03 4.10172559e+03 4.08939087e+03 4.26713232e+03 4.34794482e+03 4.30198730e+03 4.31859619e+03 4.37513672e+03 4.41049902e+03 4.60447656e+03 4.63958545e+03 4.43642383e+03 4.46588965e+03 4.57812305e+03 4.62753223e+03 4.70658398e+03 4.72572607e+03 4.90327002e+03 4.79796045e+03 4.65919824e+03 4.86293408e+03 4.74605127e+03 4.88150049e+03 5.30049756e+03 5.02135986e+03 4.70989307e+03 4.92860449e+03 5.18447412e+03 5.34230420e+03 5.36207471e+03 5.09800781e+03 4.93272314e+03 5.07253467e+03 5.39808643e+03 5.62113623e+03 5.48009766e+03 5.18760156e+03 5.19603418e+03 5.39371436e+03 5.49932373e+03 5.68388574e+03 5.71062012e+03 5.40839746e+03 5.38962451e+03 5.62122949e+03 5.74608105e+03 5.62913428e+03 5.59658789e+03 5.66640869e+03 5.65603955e+03 5.88282471e+03 5.93618994e+03 5.72358154e+03 5.73829639e+03 5.80111621e+03 5.81821289e+03 5.91967041e+03 5.90639844e+03 6.02359424e+03 6.16820410e+03 5.99802881e+03 5.87966162e+03 5.78204541e+03 6.04312646e+03 6.41731592e+03 6.32140430e+03 5.98762891e+03 5.85341504e+03 6.08920068e+03 6.46133057e+03 6.27251953e+03 5.96478320e+03 6.11965430e+03 6.28346631e+03 6.45081689e+03 6.65102490e+03 6.54531689e+03 6.17277344e+03 6.07397363e+03 6.31291016e+03 6.49696484e+03 6.52832471e+03 6.41740527e+03 6.46323779e+03 6.42771094e+03 6.57162695e+03 6.48310156e+03 6.36265674e+03 6.44330273e+03 6.39703174e+03 6.61250488e+03 6.79683105e+03 6.57394873e+03 6.64372510e+03 6.67631299e+03 6.62898584e+03 6.48573047e+03 6.37814795e+03 6.69937207e+03 7.00710645e+03 6.79503662e+03 6.48522949e+03 6.48344189e+03 6.85427393e+03 6.97755713e+03 6.83554590e+03 6.77201025e+03 6.52017627e+03 6.52665332e+03 6.86178516e+03 6.87718311e+03 6.75994141e+03 6.59155518e+03 6.48890137e+03 6.83676172e+03 7.16704102e+03 6.79794482e+03 6.64260449e+03 6.80067041e+03 6.81507129e+03 7.01623242e+03 7.05981104e+03 6.61457080e+03 6.59153711e+03 6.79004492e+03 6.79767969e+03 6.85257422e+03 6.85696533e+03 7.22784766e+03 7.28331006e+03 6.55117383e+03 6.84123828e+03 6.43514990e+03 7.75617383e+03 9.36034473e+03 1.07624844e+04 9.74575879e+03 1.14755986e+04 1.90584160e+04 2.13672031e+04 5.61971450e+06 2.03219938e+06 3435410. -23206266. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38534712. -6.24706650e+06 2.60444980e+04 1.65947969e+04 1.07022451e+04 1.02780605e+04 8.55183398e+03 7.85540674e+03 6.28653418e+03 6.79945557e+03 6.50271777e+03 6.23836377e+03 6.32765820e+03 6.30039404e+03 6.17072607e+03 6.18027295e+03 6.19302246e+03 6.23171680e+03 6.30950635e+03 6.11894336e+03 5.87054004e+03 5.96871240e+03 5.93491357e+03 5.66848584e+03 5.98821094e+03 6.07889746e+03 5.57463379e+03 5.90890967e+03 6.18741016e+03 5.87552148e+03 5.74495850e+03 5.81780420e+03 5.91698486e+03 5.79198145e+03 5.74894678e+03 5.71461475e+03 5.67976025e+03 5.51602734e+03 5.47814355e+03 5.74001514e+03 5.70479297e+03 5.51326416e+03 5.47388574e+03 5.47771484e+03 5.47440674e+03 5.39947021e+03 5.36794189e+03 5.37106348e+03 5.25488232e+03 5.18418066e+03 5.21944727e+03 5.18549902e+03 5.34768457e+03 5.35173828e+03 5.15012451e+03 4.99268213e+03 4.91159277e+03 5.17878760e+03 5.18538916e+03 4.97123438e+03 4.85244580e+03 4.84991895e+03 4.89563623e+03 4.80741846e+03 4.92231787e+03 4.90910303e+03 4.60286768e+03 4.51662451e+03 4.70491699e+03 4.86323779e+03 4.70932227e+03 4.55205762e+03 4.52954834e+03 4.48418750e+03 4.44622510e+03 4.42406299e+03 4.42228906e+03 4.36906494e+03 4.26472314e+03 4.23449121e+03 4.22083008e+03 4.17078516e+03 4.26854395e+03 4.21161182e+03 4.04758398e+03 4.03953052e+03 3.99305688e+03 4.05416724e+03 4.03379834e+03 3.89386206e+03 3.85381274e+03 3.74806299e+03 3.65640942e+03 3.78487183e+03 3.74428613e+03 3.50496924e+03 3.51692310e+03 3.68024976e+03 3.75194458e+03 3.59995239e+03 3.45557275e+03 3.38761304e+03 3.33831177e+03 3.31469897e+03 3.27171167e+03 3.23596216e+03 3.18292847e+03 3.22998413e+03 3.17869775e+03 3.04669458e+03 3.02620776e+03 2.90063306e+03 2.91779810e+03 3.04723926e+03 2.95021460e+03 2.83896777e+03 2.71474072e+03 2.64927832e+03 2.75742505e+03 2.73356934e+03 2.60699048e+03 2.50092090e+03 2.44308447e+03 2.46132080e+03 2.41796802e+03 2.44832666e+03 2.41728076e+03 2.28885645e+03 2.22966650e+03 2.18668677e+03 2.17826367e+03 2.14002466e+03 2.06816870e+03 1.99836658e+03 1.95521997e+03 1.91318164e+03 1.81249414e+03 1.81122241e+03 1.87676477e+03 1.80106470e+03 1.70175500e+03 1.61025671e+03 1.56014832e+03 1.60669836e+03 1.56012598e+03 1.46991431e+03 1.38694702e+03 1.33287708e+03 1.33338782e+03 1.28085449e+03 1.22975977e+03 1.15626904e+03 1.13271155e+03 1.14034680e+03 1.06095862e+03 1.00368799e+03 9.62894897e+02 9.08477051e+02 8.44990967e+02 7.96752014e+02 7.55224670e+02 7.06464539e+02 6.68230652e+02 6.02680603e+02 5.61126038e+02 5.49481018e+02 4.79585083e+02 4.13643158e+02 3.78007568e+02 3.31875000e+02 2.92140472e+02 2.40377121e+02 1.84555466e+02 1.42320480e+02 9.56868286e+01 4.70759239e+01 -5.80542743e-01 -4.81643753e+01 -9.63437881e+01 -1.44508804e+02 -1.92610123e+02 -2.34116928e+02 -2.87401489e+02 -3.52823608e+02 -3.93791809e+02 -4.28239655e+02 -4.61750366e+02 -5.16195984e+02 -5.98817139e+02 -6.40708923e+02 -6.68000366e+02 -7.01854614e+02 -7.43750732e+02 -8.10938232e+02 -8.61433228e+02 -9.26766785e+02 -9.65219299e+02 -9.86129822e+02 -1.04071619e+03 -1.08783899e+03 -1.17011255e+03 -1.21174158e+03 -1.22143213e+03 -1.27407385e+03 -1.32680005e+03 -1.37066846e+03 -1.37608423e+03 -1.46272400e+03 -1.60230981e+03 -1.60959448e+03 -1.60868066e+03 -1.61426807e+03 -1.64370654e+03 -1.78903882e+03 -1.85632605e+03 -1.84486292e+03 -1.83854846e+03 -1.87730115e+03 -1.98529272e+03 -2.02846204e+03 -2.12039429e+03 -2.17005200e+03 -2.15778516e+03 -2.14263403e+03 -2.18035645e+03 -2.35650098e+03 -2.39449097e+03 -2.36954077e+03 -2.37865576e+03 -2.41205566e+03 -2.59252051e+03 -2.64881421e+03 -2.53878394e+03 -2.57069043e+03 -2.76692676e+03 -2.80987695e+03 -2.71028809e+03 -2.75321069e+03 -2.93560547e+03 -3.00360645e+03 -2.94898608e+03 -2.92003516e+03 -2.96375708e+03 -3.17108447e+03 -3.18050928e+03 -3.10918799e+03 -3.21533521e+03 -3.25370728e+03 -3.28084814e+03 -3.32493262e+03 -3.35934961e+03 -3.32268311e+03 -3.44252319e+03 -3.63560278e+03 -3.59109888e+03 -3.63932202e+03 -3.69811816e+03 -3.67332642e+03 -3.72138037e+03 -3.74814941e+03 -3.77206274e+03 -3.74157983e+03 -3.76679980e+03 -3.88972974e+03 -3.94814575e+03 -4.10907861e+03 -4.02143335e+03 -3.92050464e+03 -4.09022217e+03 -4.15710840e+03 -4.32416943e+03 -4.30992627e+03 -4.21384277e+03 -4.22844189e+03 -4.24093750e+03 -4.35723438e+03 -4.39638770e+03 -4.53202881e+03 -4.56012354e+03 -4.48357422e+03 -4.49668652e+03 -4.41188232e+03 -4.56287451e+03 -4.87725732e+03 -4.83254346e+03 -4.72002051e+03 -4.64550146e+03 -4.60963281e+03 -4.85962842e+03 -5.05860449e+03 -4.96712061e+03 -4.79549463e+03 -4.83503271e+03 -4.97966162e+03 -5.01279688e+03 -5.17555811e+03 -5.16727686e+03 -5.07573340e+03 -5.09208496e+03 -5.12237061e+03 -5.34045312e+03 -5.37221924e+03 -5.12926416e+03 -5.15043604e+03 -5.47087695e+03 -5.44813232e+03 -5.20204785e+03 -5.33279443e+03 -5.64181396e+03 -5.62659375e+03 -5.51353760e+03 -5.41173438e+03 -5.40508398e+03 -5.71803174e+03 -5.77691357e+03 -5.65572412e+03 -5.54385400e+03 -5.50918457e+03 -5.71573975e+03 -5.78112402e+03 -5.78225586e+03 -5.64718408e+03 -5.80814209e+03 -6.05877881e+03 -5.93838037e+03 -6.00910107e+03 -5.99346191e+03 -5.88045020e+03 -5.98128076e+03 -6.02718506e+03 -6.05043799e+03 -6.01821436e+03 -5.95139160e+03 -5.88174658e+03 -6.05141455e+03 -6.42063672e+03 -6.11351270e+03 -5.90951611e+03 -6.08549854e+03 -6.33282812e+03 -6.50320020e+03 -6.37401221e+03 -6.19883789e+03 -6.39360986e+03 -6.38797119e+03 -6.22732422e+03 -6.17876904e+03 -6.40938330e+03 -6.46065527e+03 -6.33672803e+03 -6.28375977e+03 -6.12709229e+03 -6.40709277e+03 -6.81171582e+03 -6.66145557e+03 -6.48201318e+03 -6.32997998e+03 -6.25014014e+03 -6.60950928e+03 -6.87575391e+03 -6.69738477e+03 -6.45097119e+03 -6.45671680e+03 -6.54385889e+03 -6.54793506e+03 -6.78873633e+03 -6.67640039e+03 -6.51574609e+03 -6.64185645e+03 -6.63540820e+03 -6.83401758e+03 -6.84353857e+03 -6.63140137e+03 -6.68802490e+03 -6.69161914e+03 -6.75268457e+03 -6.63408496e+03 -6.60183740e+03 -6.95453711e+03 -6.89764502e+03 -6.77735791e+03 -6.57517969e+03 -6.64128613e+03 -7.07879736e+03 -7.01494971e+03 -6.79642041e+03 -6.69289404e+03 -6.66178418e+03 -6.75727881e+03 -6.77159229e+03 -6.79190771e+03 -6.64521729e+03 -6.79307373e+03 -7.05101123e+03 -6.81119824e+03 -6.92670996e+03 -7.02913330e+03 -6.85435156e+03 -6.82879297e+03 -6.78536035e+03 -6.82748779e+03 -6.83259912e+03 -6.75934863e+03 -6.77054736e+03 -6.95536133e+03 -6.98192139e+03 -6.65571045e+03 -6.60212207e+03 -6.75852832e+03 -6.89626318e+03 -7.16027441e+03 -6.94602490e+03 -6.61834717e+03 -6.85060938e+03 -6.93251025e+03 -6.81297754e+03 -6.76874609e+03 -6.75956494e+03 -6.68465234e+03 -6.66833984e+03 -6.81934521e+03 -6.68153174e+03 -6.70879492e+03 -6.97794043e+03 -6.85085889e+03 -6.72933643e+03 -6.58628662e+03 -6.60284375e+03 -6.90222998e+03 -6.83210742e+03 -6.70462598e+03 -6.55001416e+03 -6.38377100e+03 -6.52278955e+03 -6.79929102e+03 -6.97100391e+03 -6.68060791e+03 -6.46696680e+03 -6.51695361e+03 -6.55226855e+03 -6.81421729e+03 -6.72954834e+03 -6.51364697e+03 -6.45206934e+03 -6.42944385e+03 -6.48264111e+03 -6.37728418e+03 -6.42981738e+03 -6.71363184e+03 -6.55251025e+03 -6.49224609e+03 -6.32466895e+03 -6.25352002e+03 -6.58631055e+03 -6.60033838e+03 -6.36108008e+03 -6.21112061e+03 -6.12493262e+03 -6.25392627e+03 -6.28363477e+03 -6.43548389e+03 -6.41422363e+03 -6.18917334e+03 -6.04300879e+03 -6.10829004e+03 -6.36255273e+03 -6.27555811e+03 -6.14508447e+03 -6.07054785e+03 -6.00384229e+03 -5.99418799e+03 -5.92466846e+03 -6.05291309e+03 -6.01693652e+03 -5.86810986e+03 -6.07561328e+03 -6.10992334e+03 -5.93804639e+03 -5.88378271e+03 -5.84640869e+03 -5.82856592e+03 -5.63272900e+03 -5.55850928e+03 -5.85119629e+03 -5.89325195e+03 -5.54724023e+03 -5.41152832e+03 -5.66045947e+03 -5.86281250e+03 -5.74919287e+03 -5.49414844e+03 -5.36758838e+03 -5.53949902e+03 -5.61095508e+03 -5.44773730e+03 -5.45761816e+03 -5.28205225e+03 -5.05642139e+03 -5.24485449e+03 -5.53499902e+03 -5.50994141e+03 -5.17170996e+03 -4.97428613e+03 -5.24563525e+03 -5.38328906e+03 -5.17979932e+03 -4.97228906e+03 -4.88330518e+03 -4.92212402e+03 -4.95371045e+03 -5.10338037e+03 -5.07050781e+03 -4.86659668e+03 -4.76693262e+03 -4.72591357e+03 -4.89618848e+03 -4.76185498e+03 -4.59671729e+03 -4.77104932e+03 -4.72657715e+03 -4.63304590e+03 -4.49836182e+03 -4.42371973e+03 -4.64598486e+03 -4.48387646e+03 -4.26789160e+03 -4.36107520e+03 -4.40224316e+03 -4.37868115e+03 -4.27863721e+03 -4.35202100e+03 -4.33933105e+03 -4.17678076e+03 -4.01624072e+03 -3.96289185e+03 -4.16636230e+03 -4.06857788e+03 -3.91601147e+03 -3.91953052e+03 -3.86407812e+03 -3.88206274e+03 -3.83456567e+03 -3.82836890e+03 -3.75776562e+03 -3.62127979e+03 -3.72079932e+03 -3.70417798e+03 -3.60146021e+03 -3.56441455e+03 -3.51956348e+03 -3.43504492e+03 -3.29647388e+03 -3.23906348e+03 -3.37815649e+03 -3.47294189e+03 -3.24218188e+03 -3.05861255e+03 -3.14584326e+03 -3.24661523e+03 -3.17140601e+03 -2.99686768e+03 -2.88224536e+03 -2.99443384e+03 -2.97062158e+03 -2.81739917e+03 -2.89002539e+03 -2.82619409e+03 -2.63460059e+03 -2.62952759e+03 -2.72753589e+03 -2.69972437e+03 -2.52133789e+03 -2.40163745e+03 -2.48102905e+03 -2.53683618e+03 -2.42413745e+03 -2.28368701e+03 -2.19990161e+03 -2.26670972e+03 -2.25525635e+03 -2.14454224e+03 -2.11528809e+03 -2.08062427e+03 -2.00862769e+03 -1.94810632e+03 -1.97542749e+03 -1.89990454e+03 -1.78822705e+03 -1.80270618e+03 -1.76849438e+03 -1.73372083e+03 -1.64301562e+03 -1.56024841e+03 -1.58794080e+03 -1.50559265e+03 -1.41852661e+03 -1.42573242e+03 -1.41292664e+03 -1.40511450e+03 -1.32724670e+03 -1.33305762e+03 -1.18629480e+03 -1.45739478e+03 -1.10777771e+03 -1.27825085e+03 -1.27714343e+03 -8.77022156e+02 -1.99630713e+03 -4.34907617e+03 4.23644188e+05 128359992. 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. 466285152. -6.38635938e+05 3.99322607e+03 2.57463623e+03 1.41469275e+03 1.04683398e+03 1.07503296e+03 9.17897644e+02 1.01292010e+03 9.93297058e+02 1.04242212e+03 1.19804041e+03 1.01675677e+03 1.46275916e+03 1.89129150e+03 1.88253027e+03 1.72086462e+03 1.80561414e+03 1.43468945e+03 1.52286560e+03 1.60986255e+03 1.55583472e+03 1.63164954e+03 1.68181958e+03 1.67033557e+03 1.72498608e+03 1.82162122e+03 1.87902563e+03 1.92358215e+03 1.92526318e+03 1.93284766e+03 2.02143311e+03 2.09675610e+03 2.12217188e+03 2.13071216e+03 2.16689502e+03 2.27488843e+03 2.33081421e+03 2.33338086e+03 2.35768994e+03 2.40582666e+03 2.53193237e+03 2.59613159e+03 2.51571411e+03 2.54308276e+03 2.64766602e+03 2.69630933e+03 2.78653857e+03 2.81284985e+03 2.78591724e+03 2.87400073e+03 2.94075220e+03 2.96180640e+03 3.01247168e+03 3.02373364e+03 3.08172998e+03 3.15678589e+03 3.16196606e+03 3.18809497e+03 3.22139258e+03 3.28235425e+03 3.38800146e+03 3.43380713e+03 3.44932568e+03 3.42628857e+03 3.43888843e+03 3.58537378e+03 3.62559961e+03 3.56667334e+03 3.64939404e+03 3.70836304e+03 3.75041431e+03 3.86813086e+03 3.87837109e+03 3.82389087e+03 3.85437061e+03 3.99379419e+03 4.06224487e+03 4.00131641e+03 3.96722461e+03 4.03449658e+03 4.14151953e+03 4.28870947e+03 4.30704834e+03 4.18318652e+03 4.23449609e+03 4.39567090e+03 4.42579492e+03 4.43197705e+03 4.35484424e+03 4.37222363e+03 4.56809082e+03 4.62641016e+03 4.55300488e+03 4.58503857e+03 4.64671338e+03 4.67895605e+03 4.71739941e+03 4.74127100e+03 4.81019385e+03 4.85140771e+03 4.94813574e+03 4.96844727e+03 4.82712793e+03 4.88936719e+03 5.03544678e+03 5.02498633e+03 5.02776123e+03 5.05587793e+03 5.11172412e+03 5.24315283e+03 5.22001123e+03 5.17392969e+03 5.29808398e+03 5.35300732e+03 5.26357275e+03 5.29310938e+03 5.36637354e+03 5.42779492e+03 5.42785449e+03 5.39950684e+03 5.43975732e+03 5.50802979e+03 5.65210791e+03 5.65810449e+03 5.48194434e+03 5.56156104e+03 5.72348242e+03 5.73872119e+03 5.72230371e+03 5.66000049e+03 5.62240674e+03 5.78756689e+03 5.95696338e+03 5.87048926e+03 5.74385303e+03 5.80712891e+03 5.97382959e+03 6.03664502e+03 6.08510449e+03 5.95868213e+03 5.82407617e+03 5.97229053e+03 6.03131299e+03 6.04321729e+03 6.12804541e+03 6.08658447e+03 6.14737891e+03 6.31612061e+03 6.21893164e+03 6.01817139e+03 6.13449316e+03 6.29931299e+03 6.32154443e+03 6.37260791e+03 6.29371045e+03 6.22662842e+03 6.28078857e+03 6.49521582e+03 6.39545264e+03 6.17614795e+03 6.33724609e+03 6.53249902e+03 6.47804736e+03 6.42701562e+03 6.36794727e+03 6.37516016e+03 6.50541162e+03 6.48512744e+03 6.50772461e+03 6.61025000e+03 6.50467139e+03 6.54346582e+03 6.71328320e+03 6.63116211e+03 6.46900049e+03 6.51831348e+03 6.64801758e+03 6.72550391e+03 6.69357959e+03 6.59675928e+03 6.50684326e+03 6.61315088e+03 6.94751904e+03 6.98051904e+03 6.54111084e+03 6.61843018e+03 6.85402051e+03 6.81326123e+03 6.73017432e+03 6.63545312e+03 6.65830957e+03 6.80815527e+03 6.86787988e+03 6.78732471e+03 6.71152686e+03 6.66535010e+03 6.78144824e+03 6.91637158e+03 6.91353467e+03 6.79749170e+03 6.76144434e+03 6.83636572e+03 6.84037158e+03 6.74867188e+03 6.77261914e+03 6.81587012e+03 6.82141504e+03 6.93290283e+03 7.04066113e+03 6.70779102e+03 6.73311768e+03 6.88504004e+03 6.93098242e+03 6.93898633e+03 6.74123145e+03 6.76422607e+03 6.96544775e+03 6.95639844e+03 6.88869580e+03 6.70076221e+03 6.66254102e+03 6.87000732e+03 6.99257227e+03 6.86448633e+03 6.81616553e+03 6.88047363e+03 6.81647510e+03 6.92555859e+03 6.88972168e+03 6.70238672e+03 6.67380078e+03 6.72260596e+03 6.90641650e+03 6.79111572e+03 6.66984863e+03 6.72473584e+03 6.82926611e+03 6.82320752e+03 6.73320703e+03 6.67135449e+03 6.66783350e+03 6.76914453e+03 6.67031934e+03 6.78759570e+03 6.68674023e+03 6.55507715e+03 6.75175537e+03 6.53156836e+03 6.59093018e+03 6.73551074e+03 6.57796143e+03 6.49768652e+03 6.59355078e+03 6.56769043e+03 6.52043555e+03 6.38986133e+03 6.60610254e+03 6.77486865e+03 6.42055957e+03 6.31994971e+03 6.44368213e+03 6.42777588e+03 6.56701025e+03 6.48027539e+03 6.27775049e+03 6.32501758e+03 6.43633936e+03 6.41115381e+03 6.33130225e+03 6.27684521e+03 6.27907080e+03 6.32198828e+03 6.17171582e+03 6.19791504e+03 6.16098584e+03 6.11299072e+03 6.16773584e+03 6.21867236e+03 6.20369580e+03 6.07155029e+03 5.98519775e+03 6.13084814e+03 6.23424902e+03 5.98344727e+03 6.01001367e+03 6.00868457e+03 5.81391162e+03 5.92547900e+03 5.93807764e+03 5.78462109e+03 5.89046973e+03 5.87025586e+03 5.78167432e+03 5.90508105e+03 5.77175244e+03 5.65328320e+03 5.66805908e+03 5.71237061e+03 5.73326465e+03 5.55829639e+03 5.49942041e+03 5.58762012e+03 5.60348438e+03 5.54849463e+03 5.47483838e+03 5.39022412e+03 5.45359326e+03 5.57281055e+03 5.36793799e+03 5.24269189e+03 5.20919922e+03 5.35857227e+03 5.38263086e+03 5.16529785e+03 5.11503711e+03 5.13479248e+03 5.13571436e+03 5.07666260e+03 5.09516602e+03 5.04121924e+03 4.91642529e+03 4.97807715e+03 5.06241797e+03 4.89902539e+03 4.68367676e+03 4.74191895e+03 4.83133545e+03 4.78076318e+03 4.75952783e+03 4.68297949e+03 4.58311377e+03 4.68320752e+03 4.73229688e+03 4.54125635e+03 4.45454785e+03 4.44896436e+03 4.54609570e+03 4.48267578e+03 4.25432910e+03 4.23288184e+03 4.28103711e+03 4.27607422e+03 4.23531885e+03 4.22348779e+03 4.13065869e+03 4.10286279e+03 4.06443481e+03 3.95517871e+03 3.93018726e+03 3.89721069e+03 3.90945776e+03 3.92656030e+03 3.82103882e+03 3.70701221e+03 3.70982739e+03 3.74065332e+03 3.80393042e+03 3.73094507e+03 3.52346289e+03 3.48455835e+03 3.52391260e+03 3.47619751e+03 3.39634204e+03 3.35787988e+03 3.33617090e+03 3.32281006e+03 3.24021851e+03 3.12990356e+03 3.15254443e+03 3.17956665e+03 3.14854932e+03 3.05537183e+03 2.94720093e+03 2.93694971e+03 2.87536401e+03 2.82108813e+03 2.87176685e+03 2.82308984e+03 2.68723535e+03 2.65292261e+03 2.65136523e+03 2.65822998e+03 2.61366968e+03 2.51469946e+03 2.46111768e+03 2.42400488e+03 2.36354126e+03 2.30403955e+03 2.29592944e+03 2.25586621e+03 2.23063354e+03 2.18745337e+03 2.05813770e+03 2.03960938e+03 2.01750586e+03 1.96835010e+03 1.97204358e+03 1.87600598e+03 1.80156641e+03 1.81877454e+03 1.78098071e+03 1.70191101e+03 1.64812476e+03 1.58262415e+03 1.52888660e+03 1.49673645e+03 1.46408069e+03 1.41182959e+03 1.39254834e+03 1.35848169e+03 1.28562195e+03 1.22206665e+03 1.16125708e+03 1.13760876e+03 1.11134106e+03 1.05069226e+03 9.77676025e+02 9.29092529e+02 8.98795532e+02 8.67734680e+02 8.35016785e+02 7.65815308e+02 7.00774597e+02 6.60827271e+02 6.12932129e+02 5.61539490e+02 5.30863159e+02 4.81744537e+02 4.21956421e+02 3.81548126e+02 3.31236847e+02 2.83511993e+02 2.39783188e+02 1.91469238e+02 1.42826553e+02 9.34632568e+01 4.51971512e+01 -2.67693591e+00 -5.11063881e+01 -9.91937103e+01 -1.46196671e+02 -1.93732971e+02 -2.36314072e+02 -2.88955170e+02 -3.40580963e+02 -3.85108612e+02 -4.36146820e+02 -4.80538391e+02 -5.22442139e+02 -5.71858765e+02 -6.23688965e+02 -6.84897400e+02 -7.32827271e+02 -7.61175537e+02 -8.04126160e+02 -8.49057068e+02 -8.97368713e+02 -9.52040039e+02 -1.00933429e+03 -1.06205969e+03 -1.09811719e+03 -1.13673669e+03 -1.17974219e+03 -1.23178223e+03 -1.31612000e+03 -1.36287744e+03 -1.36394360e+03 -1.40854724e+03 -1.45992517e+03 -1.50250159e+03 -1.58122925e+03 -1.63681116e+03 -1.65425562e+03 -1.69400549e+03 -1.73737732e+03 -1.78983960e+03 -1.86546704e+03 -1.89835181e+03 -1.93984253e+03 -1.98729126e+03 -2.01355017e+03 -2.08453076e+03 -2.09747559e+03 -2.14535181e+03 -2.25419482e+03 -2.25282300e+03 -2.27015259e+03 -2.33915454e+03 -2.36957397e+03 -2.41148853e+03 -2.54580078e+03 -2.59011963e+03 -2.50748022e+03 -2.57410718e+03 -2.65653564e+03 -2.67049683e+03 -2.77972070e+03 -2.81150635e+03 -2.77135645e+03 -2.85108716e+03 -2.90359790e+03 -2.99191577e+03 -3.07454126e+03 -3.06005908e+03 -3.10974609e+03 -3.11404663e+03 -3.08910327e+03 -3.17907397e+03 -3.30241333e+03 -3.32231055e+03 -3.37584912e+03 -3.40746338e+03 -3.31876221e+03 -3.42396338e+03 -3.61761084e+03 -3.63978418e+03 -3.58544043e+03 -3.52597827e+03 -3.60709326e+03 -3.78110156e+03 -3.79063086e+03 -3.78264014e+03 -3.88613501e+03 -3.85964795e+03 -3.91038013e+03 -3.98651221e+03 -3.88300732e+03 -3.96121558e+03 -4.12429980e+03 -4.18495068e+03 -4.15545752e+03 -4.06208154e+03 -4.13403125e+03 -4.28059277e+03 -4.37644043e+03 -4.38141455e+03 -4.30546533e+03 -4.29766162e+03 -4.40102246e+03 -4.53989062e+03 -4.64618701e+03 -4.59781055e+03 -4.52930469e+03 -4.60121191e+03 -4.63182666e+03 -4.66390039e+03 -4.74712305e+03 -4.75572070e+03 -4.79543896e+03 -4.91305371e+03 -4.85470166e+03 -4.85052734e+03 -4.94751562e+03 -4.99794092e+03 -5.03378125e+03 -5.00305322e+03 -4.96632715e+03 -5.03332471e+03 -5.16778613e+03 -5.26163672e+03 -5.33320801e+03 -5.22450635e+03 -5.11073682e+03 -5.24819727e+03 -5.27214941e+03 -5.34277588e+03 -5.45246436e+03 -5.36831494e+03 -5.34583643e+03 -5.37432178e+03 -5.43733496e+03 -5.58909570e+03 -5.69874658e+03 -5.62560449e+03 -5.59106982e+03 -5.56873291e+03 -5.48781738e+03 -5.59581982e+03 -5.76806787e+03 -5.85171387e+03 -5.85170508e+03 -5.70535449e+03 -5.67824365e+03 -5.82246680e+03 -5.91828564e+03 -5.94382861e+03 -5.92778955e+03 -5.88418359e+03 -5.83724561e+03 -5.98825732e+03 -6.15305908e+03 -6.08103906e+03 -5.93570166e+03 -6.02166992e+03 -6.09396582e+03 -6.13412646e+03 -6.19129785e+03 -6.18150000e+03 -6.25508643e+03 -6.16936768e+03 -6.12094580e+03 -6.35866553e+03 -6.32435498e+03 -6.24981885e+03 -6.44313672e+03 -6.26620996e+03 -6.21333154e+03 -6.51665430e+03 -6.52825098e+03 -6.25246484e+03 -6.71710254e+03 -6.66162891e+03 -5.95760693e+03 -5.90863330e+03 -1.23183027e+04 -9.69551562e+03 -1.96037480e+04 -1.88124980e+04 2.99202775e+06 -4489850. 3.35797025e+06 -72840128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.98316650e+06 -20910288. -3.07884688e+04 -1.58189316e+04 -9.33458008e+03 -1.11550117e+04 -1.00423184e+04 -1.02091504e+04 -9.73584961e+03 -5.48282764e+03 -6.18943555e+03 -8.12062793e+03 -6.83592334e+03 -6.35648584e+03 -5.90816992e+03 -6.48022559e+03 -7.06349365e+03 -6.97531396e+03 -6.71632568e+03 -6.67270117e+03 -6.87032959e+03 -6.83040186e+03 -6.93908301e+03 -6.98848633e+03 -6.73843555e+03 -6.63261621e+03 -6.69991162e+03 -6.68338330e+03 -6.75500977e+03 -6.63051758e+03 -6.53655029e+03 -6.74397217e+03 -6.95873242e+03 -6.78287500e+03 -6.41771631e+03 -6439. -6.70343896e+03 -6.76842480e+03 -6.57250781e+03 -6.39837061e+03 -6.47460596e+03 -6.69321484e+03 -6.82835449e+03 -6.60974463e+03 -6.28259766e+03 -6.35208594e+03 -6.67542480e+03 -6.56493652e+03 -6.56839893e+03 -6.44671777e+03 -6.20098584e+03 -6.32857764e+03 -6.53045117e+03 -6.37391797e+03 -6.23784521e+03 -6.44910400e+03 -6.46212793e+03 -6.35939648e+03 -6.22821436e+03 -6.09055078e+03 -6.20111035e+03 -6.46259375e+03 -6.31407178e+03 -6.10925293e+03 -6.01342236e+03 -5.98557666e+03 -6.27523291e+03 -6.36010400e+03 -6.13291309e+03 -5.97333838e+03 -5.92609326e+03 -5.87258203e+03 -6.01249707e+03 -6.16642383e+03 -5.94586133e+03 -5.80334033e+03 -5.93826172e+03 -5.87217969e+03 -5.75515527e+03 -5.75777148e+03 -5.82917969e+03 -5.88725684e+03 -5.84057227e+03 -5.76795117e+03 -5.58149316e+03 -5.46922168e+03 -5.73304834e+03 -5.84010498e+03 -5.52838428e+03 -5.32669971e+03 -5.44100830e+03 -5.53834277e+03 -5.61244971e+03 -5.65285059e+03 -5.37966943e+03 -5.27411719e+03 -5.37729053e+03 -5.34229346e+03 -5.36576953e+03 -5.26013672e+03 -5.10797803e+03 -5.14898535e+03 -5.23383105e+03 -5.20435303e+03 -5.13599170e+03 -5.11960400e+03 -5.06250391e+03 -5.04321045e+03 -5.03012012e+03 -4.84556299e+03 -4.80037598e+03 -5.02645752e+03 -5.01057764e+03 -4.73083252e+03 -4.61015820e+03 -4.65866895e+03 -4.83292822e+03 -4.91977686e+03 -4.71873389e+03 -4.48821387e+03 -4.45260498e+03 -4.49257715e+03 -4.52922705e+03 -4.51905029e+03 -4.45587158e+03 -4.39655566e+03 -4.35241699e+03 -4.31711768e+03 -4.29315869e+03 -4.17616406e+03 -4.20739551e+03 -4.30051855e+03 -4.17789062e+03 -4.08667920e+03 -4.02397754e+03 -3.91413916e+03 -4.02938550e+03 -4.09796875e+03 -3.86455078e+03 -3.74620483e+03 -3.77907495e+03 -3.87585107e+03 -3.90002686e+03 -3.73980005e+03 -3.59074268e+03 -3.54827319e+03 -3.55571411e+03 -3.59304785e+03 -3.59304199e+03 -3.40932129e+03 -3.29900708e+03 -3.36876050e+03 -3.42053564e+03 -3.35440601e+03 -3.24148730e+03 -3.20901270e+03 -3.15806470e+03 -3.15146631e+03 -3.13215015e+03 -2.98445239e+03 -2.93711719e+03 -2.98204199e+03 -2.95235352e+03 -2.86886084e+03 -2.77214478e+03 -2.74909302e+03 -2.75513647e+03 -2.71517285e+03 -2.67978589e+03 -2.59004785e+03 -2.54807568e+03 -2.54984619e+03 -2.48952637e+03 -2.42081421e+03 -2.35021045e+03 -2.31315918e+03 -2.31916260e+03 -2.32411841e+03 -2.24709009e+03 -2.10101367e+03 -2.04221753e+03 -2.09127979e+03 -2.09840820e+03 -2.01188208e+03 -1.89247986e+03 -1.82372742e+03 -1.82623486e+03 -1.81921130e+03 -1.77676599e+03 -1.68440613e+03 -1.61090125e+03 -1.58862292e+03 -1.57812598e+03 -1.54367615e+03 -1.47597107e+03 -1.40863757e+03 -1.36890076e+03 -1.33037146e+03 -1.28365088e+03 -1.23903467e+03 -1.19090051e+03 -1.13809033e+03 -1.08117639e+03 -1.02070532e+03 -9.70340698e+02 -9.58110291e+02 -9.43380310e+02 -8.83442810e+02 -8.01343628e+02 -7.26692871e+02 -6.89191223e+02 -6.82881836e+02 -6.53242676e+02 -5.84219910e+02 -5.14560120e+02 -4.57314575e+02 -4.21201324e+02 -3.87693634e+02 -3.39583069e+02 -2.88322662e+02 -2.37332809e+02 -1.89578049e+02 -1.42545654e+02 -9.25213089e+01 -4.69553490e+01 -4.05822486e-01 4.86493797e+01 1.00368347e+02 1.49380844e+02 1.85034485e+02 2.33881332e+02 2.91296661e+02 3.40563812e+02 3.87712585e+02 4.30348755e+02 4.90478119e+02 5.41651855e+02 5.62310547e+02 5.90044678e+02 6.50607849e+02 7.33927979e+02 8.06032227e+02 8.40997192e+02 8.41015564e+02 8.59863647e+02 9.27188110e+02 1.02219397e+03 1.09900854e+03 1.13063330e+03 1.11310046e+03 1.15489014e+03 1.27722302e+03 1.31735034e+03 1.30459875e+03 1.35511523e+03 1.41609375e+03 1.46207910e+03 1.56605652e+03 1.57599243e+03 1.56001172e+03 1.65097729e+03 1.66601086e+03 1.75453979e+03 1.84836121e+03 1.79914490e+03 1.87686548e+03 1.97845703e+03 1.98122827e+03 2.03038501e+03 2.06890186e+03 2.11879102e+03 2.17865918e+03 2.20489185e+03 2.19411597e+03 2.23402734e+03 2.40032983e+03 2.51310327e+03 2.48803174e+03 2.42145337e+03 2.41259009e+03 2.50096777e+03 2.66436646e+03 2.79325464e+03 2.75410034e+03 2.66306616e+03 2.73374902e+03 2.85879956e+03 2.86856885e+03 2.89116113e+03 2.94380835e+03 2.98427905e+03 3.04399609e+03 3.19314990e+03 3.15306519e+03 3.09148608e+03 3.21229150e+03 3.15738916e+03 3.30988379e+03 3.42874561e+03 3.35561255e+03 3.53008472e+03 3.49810083e+03 3.36814404e+03 3.51264062e+03 3.52161279e+03 3.61075781e+03 3.88840063e+03 3.73368604e+03 3.56865356e+03 3.68365796e+03 3.89084863e+03 4.09136304e+03 4.04172046e+03 3.87345654e+03 3.81297729e+03 3.89162891e+03 4.10123340e+03 4.30855811e+03 4.27973535e+03 4.10777002e+03 4.09651709e+03 4.26454590e+03 4.35212939e+03 4.30134717e+03 4.31484473e+03 4.37371631e+03 4.40347217e+03 4.61408252e+03 4.66037793e+03 4.43726270e+03 4.46046094e+03 4.58039111e+03 4.62309326e+03 4.70507129e+03 4.73215430e+03 4.89918848e+03 4.80663574e+03 4.66038574e+03 4.85674463e+03 4.74992529e+03 4.89458057e+03 5.29508691e+03 5.01266357e+03 4.71942676e+03 4.91162109e+03 5.18187061e+03 5.34610889e+03 5.37633008e+03 5.10258203e+03 4.92795996e+03 5.08422852e+03 5.39328906e+03 5.63278320e+03 5.49721289e+03 5.19049805e+03 5.18644385e+03 5.40690332e+03 5.49120410e+03 5.67755420e+03 5.69942773e+03 5.41091602e+03 5.41220996e+03 5.63898047e+03 5.74848584e+03 5.61166553e+03 5.58416943e+03 5.67670264e+03 5.64907812e+03 5.88806348e+03 5.94458838e+03 5.74492871e+03 5.75511768e+03 5.78774365e+03 5.80935596e+03 5.91206006e+03 5.90096924e+03 6.05629883e+03 6.13325879e+03 5.98942383e+03 5.88851465e+03 5.77617432e+03 6.05014941e+03 6.40003613e+03 6.30660840e+03 6.02712646e+03 5.85623242e+03 6.09489844e+03 6.46047803e+03 6.26602686e+03 5.95793359e+03 6.12685645e+03 6.31081006e+03 6.45710498e+03 6.63404834e+03 6.54740479e+03 6.17613086e+03 6.07078125e+03 6.27262061e+03 6.49247266e+03 6.51608398e+03 6.42880859e+03 6.44075488e+03 6.44609961e+03 6.59901953e+03 6.51723877e+03 6.33722852e+03 6.44701514e+03 6.40079248e+03 6.65467139e+03 6.80260645e+03 6.57879297e+03 6.64962354e+03 6.68608203e+03 6.67585547e+03 6.51483643e+03 6.39059180e+03 6.70003369e+03 7.00209277e+03 6.82618213e+03 6.46037207e+03 6.53812598e+03 6.87274951e+03 6.99195703e+03 6.85862549e+03 6.77666357e+03 6.53386963e+03 6.55922070e+03 6.90084766e+03 6.87536670e+03 6.76661230e+03 6.59577783e+03 6.51196240e+03 6.84297949e+03 7.13828955e+03 6.82265381e+03 6.64807764e+03 6.81773730e+03 6.79743213e+03 6.97654932e+03 7.05882422e+03 6.63973438e+03 6.60532324e+03 6.80762158e+03 6.86170068e+03 6.90686084e+03 6.88455908e+03 7.24230811e+03 7.33766211e+03 6.54421045e+03 6.84314648e+03 6.41744434e+03 8.14904492e+03 1.00161426e+04 1.07336680e+04 9.68785449e+03 1.10530586e+04 1.77676152e+04 2.10090410e+04 -4913675. -1.25274312e+06 -2.09654575e+06 -43805204. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38534712. -6.24706650e+06 2.60444980e+04 1.65947969e+04 1.07022451e+04 1.02780605e+04 9.64592383e+03 9.38255762e+03 9.16236914e+03 9.59276758e+03 9.62842090e+03 9.33626562e+03 9.47612988e+03 9.46471680e+03 9.26023047e+03 9.30188770e+03 9.27801465e+03 9.22134473e+03 8.49934473e+03 8.39120801e+03 6.61245801e+03 6.03053467e+03 5.96007227e+03 6.08891455e+03 6.10669434e+03 5.80437842e+03 5.79015820e+03 6.08109180e+03 6.02875635e+03 5.87738867e+03 5.85313428e+03 5.80823047e+03 5.77177197e+03 5.74973486e+03 5.70933740e+03 5.70830713e+03 5.66166455e+03 5.49492871e+03 5.46497119e+03 5.72747119e+03 5.71612354e+03 5.50446582e+03 5.48809717e+03 5.47730566e+03 5.47466455e+03 5.41912207e+03 5.37932617e+03 5.36326660e+03 5.25617090e+03 5.18922461e+03 5.21642188e+03 5.17468213e+03 5.35431396e+03 5.35165869e+03 5.14156836e+03 4.99159961e+03 4.90892090e+03 5.17808643e+03 5.18249854e+03 4.97958984e+03 4.85753223e+03 4.86216992e+03 4.89934326e+03 4.81290869e+03 4.91328125e+03 4.89561035e+03 4.60741064e+03 4.51547607e+03 4.71290723e+03 4.87685205e+03 4.71152344e+03 4.56354150e+03 4.53915527e+03 4.48304395e+03 4.44303662e+03 4.41946582e+03 4.42629932e+03 4.38496484e+03 4.27257959e+03 4.23657227e+03 4.21631543e+03 4.17384375e+03 4.28000977e+03 4.21342920e+03 4.04722583e+03 4.03259082e+03 3.99296655e+03 4.06409473e+03 4.04429468e+03 3.90235376e+03 3.85454980e+03 3.74888257e+03 3.66530054e+03 3.79147241e+03 3.74722461e+03 3.50378247e+03 3.52036743e+03 3.68664575e+03 3.75267041e+03 3.60424219e+03 3.46246191e+03 3.38075171e+03 3.33584302e+03 3.32536475e+03 3.27687549e+03 3.23715869e+03 3.18286646e+03 3.23289307e+03 3.18960474e+03 3.05449292e+03 3.02616895e+03 2.89676880e+03 2.92455127e+03 3.05343848e+03 2.94456543e+03 2.83619824e+03 2.71690552e+03 2.65220093e+03 2.76015503e+03 2.73032031e+03 2.60633447e+03 2.49472900e+03 2.44710962e+03 2.46358716e+03 2.41389722e+03 2.45031689e+03 2.42183179e+03 2.29488916e+03 2.22948413e+03 2.18918652e+03 2.18410425e+03 2.14394604e+03 2.07074829e+03 1.99924768e+03 1.96032239e+03 1.92155432e+03 1.81416003e+03 1.81177673e+03 1.88142627e+03 1.80219214e+03 1.70021472e+03 1.61207861e+03 1.56190979e+03 1.60801196e+03 1.56267896e+03 1.46883887e+03 1.38439160e+03 1.33178479e+03 1.33451550e+03 1.28241235e+03 1.22809778e+03 1.15742419e+03 1.13746521e+03 1.14331995e+03 1.06472949e+03 1.00873871e+03 9.66450256e+02 9.09762329e+02 8.47761841e+02 8.01568970e+02 7.58654663e+02 7.09505371e+02 6.72114563e+02 6.05602966e+02 5.63850098e+02 5.51655762e+02 4.79985474e+02 4.15071960e+02 3.78746124e+02 3.31867615e+02 2.93146851e+02 2.41848801e+02 1.86430328e+02 1.44425018e+02 9.74315186e+01 4.75825462e+01 -1.35831428e+00 -4.98876495e+01 -9.71182632e+01 -1.43283432e+02 -1.90592484e+02 -2.32749252e+02 -2.86402832e+02 -3.52334930e+02 -3.94635132e+02 -4.27757172e+02 -4.59398071e+02 -5.13098206e+02 -5.96750854e+02 -6.40656860e+02 -6.67453491e+02 -7.00973083e+02 -7.43058289e+02 -8.11627075e+02 -8.62026550e+02 -9.25680542e+02 -9.62331055e+02 -9.83578430e+02 -1.03922363e+03 -1.08616650e+03 -1.16894092e+03 -1.21048010e+03 -1.22286035e+03 -1.27523901e+03 -1.32395264e+03 -1.36853784e+03 -1.37632178e+03 -1.46486572e+03 -1.60385608e+03 -1.60781274e+03 -1.60768628e+03 -1.61456006e+03 -1.64552515e+03 -1.79127759e+03 -1.85679114e+03 -1.84586951e+03 -1.83769202e+03 -1.87864795e+03 -1.98436853e+03 -2.02926318e+03 -2.12447510e+03 -2.17125342e+03 -2.16103662e+03 -2.14553882e+03 -2.17996338e+03 -2.35957568e+03 -2.39737598e+03 -2.37456494e+03 -2.38134741e+03 -2.40932275e+03 -2.59194800e+03 -2.65436377e+03 -2.54268115e+03 -2.57478296e+03 -2.76880640e+03 -2.81508960e+03 -2.71515698e+03 -2.75173071e+03 -2.94435254e+03 -3.00837964e+03 -2.94670630e+03 -2.91781128e+03 -2.96491821e+03 -3.17332275e+03 -3.18340942e+03 -3.11442651e+03 -3.21723853e+03 -3.25777881e+03 -3.27509497e+03 -3.32546118e+03 -3.36025415e+03 -3.32304761e+03 -3.44907959e+03 -3.63703149e+03 -3.59171460e+03 -3.64093652e+03 -3.69969751e+03 -3.67284180e+03 -3.71834473e+03 -3.74921216e+03 -3.77611938e+03 -3.74278125e+03 -3.77031934e+03 -3.89267285e+03 -3.95414258e+03 -4.10890625e+03 -4.02394385e+03 -3.92151489e+03 -4.08956421e+03 -4.16142334e+03 -4.32892871e+03 -4.31396631e+03 -4.22088477e+03 -4.21928027e+03 -4.23769922e+03 -4.36133936e+03 -4.41266504e+03 -4.52649219e+03 -4.56113574e+03 -4.49296582e+03 -4.50601709e+03 -4.39375830e+03 -4.56603955e+03 -4.86953857e+03 -4.83271484e+03 -4.73461572e+03 -4.63876709e+03 -4.60534619e+03 -4.87496045e+03 -5.05218408e+03 -4.97096338e+03 -4.80422852e+03 -4.83321875e+03 -4.98560547e+03 -5.00161865e+03 -5.16213428e+03 -5.17711475e+03 -5.07662646e+03 -5.08747021e+03 -5.12707129e+03 -5.34726270e+03 -5.38239258e+03 -5.14004346e+03 -5.14815820e+03 -5.45690283e+03 -5.45770654e+03 -5.20435889e+03 -5.32671533e+03 -5.65148291e+03 -5.64853711e+03 -5.52531543e+03 -5.39867432e+03 -5.40759375e+03 -5.73324121e+03 -5.78625342e+03 -5.64978467e+03 -5.54213818e+03 -5.53203516e+03 -5.71861670e+03 -5.79013574e+03 -5.76657275e+03 -5.64133545e+03 -5.82587061e+03 -6.07536523e+03 -5.93550977e+03 -6.02675293e+03 -6.00242627e+03 -5.89746387e+03 -5.97113623e+03 -5.99705322e+03 -6.03176660e+03 -6.03007812e+03 -5.94908252e+03 -5.86580713e+03 -6.06818701e+03 -6.42381250e+03 -6.11277100e+03 -5.89218066e+03 -6.12155762e+03 -6.32457764e+03 -6.47545068e+03 -6.38643701e+03 -6.21314551e+03 -6.36312109e+03 -6.39537988e+03 -6.23642627e+03 -6.16472119e+03 -6.42691455e+03 -6.48003027e+03 -6.33801123e+03 -6.32489111e+03 -6.16029932e+03 -6.43428076e+03 -6.83081934e+03 -6.66213428e+03 -6.45391260e+03 -6.35709619e+03 -6.26563623e+03 -6.62829443e+03 -6.89265479e+03 -6.70749463e+03 -6.46073730e+03 -6.46117822e+03 -6.54227148e+03 -6.53864990e+03 -6.78943164e+03 -6.69303955e+03 -6.53039160e+03 -6.61925439e+03 -6.59394238e+03 -6.86129199e+03 -6.83534521e+03 -6.62636035e+03 -6.67123145e+03 -6.68878809e+03 -6.73559131e+03 -6.61028320e+03 -6.61242725e+03 -6.91766943e+03 -6.92054492e+03 -6.79834521e+03 -6.57810742e+03 -6.63587793e+03 -7.04037695e+03 -7.00193994e+03 -6.79530859e+03 -6.68367188e+03 -6.64448340e+03 -6.73625098e+03 -6.77705420e+03 -6.83972168e+03 -6.66784619e+03 -6.79296582e+03 -7.08406982e+03 -6.80911865e+03 -6.95197363e+03 -7.03657471e+03 -6.87342334e+03 -6.84099072e+03 -6.80277246e+03 -6.85168555e+03 -6.83303564e+03 -6.76357910e+03 -6.77643994e+03 -6.94675635e+03 -7.00661670e+03 -6.64040186e+03 -6.57436719e+03 -6.74246094e+03 -6.90045996e+03 -7.10366504e+03 -6.92257275e+03 -6.62826709e+03 -6.84162354e+03 -6.93960889e+03 -6.82772412e+03 -6.77622998e+03 -6.75462891e+03 -6.69828857e+03 -6.67431836e+03 -6.81006006e+03 -6.64240186e+03 -6.69683057e+03 -7.01818799e+03 -6.88442285e+03 -6.75645898e+03 -6.59998486e+03 -6.60739111e+03 -6.93578223e+03 -6.83657812e+03 -6.72435889e+03 -6.54241064e+03 -6.35284277e+03 -6.55142773e+03 -6.77634766e+03 -6.98346191e+03 -6.70176172e+03 -6.45683447e+03 -6.53211426e+03 -6.57494727e+03 -6.80441846e+03 -6.73492871e+03 -6.50938477e+03 -6.47819287e+03 -6.44253223e+03 -6.48735742e+03 -6.38556494e+03 -6.44791016e+03 -6.71054492e+03 -6.56710596e+03 -6.48423096e+03 -6.29168701e+03 -6.23768994e+03 -6.58587939e+03 -6.57492627e+03 -6.37115283e+03 -6.20675488e+03 -6.14691455e+03 -6.25892920e+03 -6.28957129e+03 -6.48114746e+03 -6.44554199e+03 -6.19900049e+03 -6.04887891e+03 -6.10964258e+03 -6.39199316e+03 -6.31228760e+03 -6.12779297e+03 -6.07176172e+03 -6.01534473e+03 -5.99411523e+03 -5.93008496e+03 -6.06671387e+03 -6.02556689e+03 -5.86965039e+03 -6.06667969e+03 -6.10999707e+03 -5.96427441e+03 -5.90254785e+03 -5.84817188e+03 -5.84269824e+03 -5.66241064e+03 -5.57506738e+03 -5.86230371e+03 -5.89022314e+03 -5.56738379e+03 -5.42861475e+03 -5.65803662e+03 -5.85600391e+03 -5.75722949e+03 -5.49811719e+03 -5.35362695e+03 -5.55252588e+03 -5.61813721e+03 -5.46585059e+03 -5.45570459e+03 -5.28334277e+03 -5.04938965e+03 -5.23667871e+03 -5.53341943e+03 -5.50243359e+03 -5.16403857e+03 -4.97560938e+03 -5.25195020e+03 -5.39664307e+03 -5.17644922e+03 -4.97036768e+03 -4.89333350e+03 -4.92573730e+03 -4.95991748e+03 -5.10055273e+03 -5.06873438e+03 -4.87357031e+03 -4.76446045e+03 -4.73694531e+03 -4.90642529e+03 -4.76147070e+03 -4.58779688e+03 -4.76684229e+03 -4.73493164e+03 -4.62959766e+03 -4.49221729e+03 -4.43604492e+03 -4.64997314e+03 -4.47735498e+03 -4.27592822e+03 -4.36127441e+03 -4.41457520e+03 -4.38402832e+03 -4.27988379e+03 -4.35896143e+03 -4.34247021e+03 -4.18068896e+03 -4.02248022e+03 -3.95449585e+03 -4.17585400e+03 -4.07850464e+03 -3.91999829e+03 -3.92401758e+03 -3.86452393e+03 -3.88974170e+03 -3.83928223e+03 -3.83278442e+03 -3.76064453e+03 -3.62828369e+03 -3.72210669e+03 -3.70944238e+03 -3.60418555e+03 -3.56987646e+03 -3.52388403e+03 -3.43651172e+03 -3.30209277e+03 -3.24419434e+03 -3.38143555e+03 -3.47273779e+03 -3.25163184e+03 -3.05894287e+03 -3.14687451e+03 -3.24803101e+03 -3.17517993e+03 -3.00490527e+03 -2.88606055e+03 -2.99591748e+03 -2.97005933e+03 -2.82489185e+03 -2.89530518e+03 -2.83174878e+03 -2.63743530e+03 -2.63089624e+03 -2.73026953e+03 -2.70039771e+03 -2.52274463e+03 -2.40644434e+03 -2.48859766e+03 -2.54277490e+03 -2.43099854e+03 -2.28451660e+03 -2.20080811e+03 -2.27472656e+03 -2.26163208e+03 -2.14910107e+03 -2.11886743e+03 -2.08746436e+03 -2.01014514e+03 -1.94867078e+03 -1.97565466e+03 -1.89736279e+03 -1.79121216e+03 -1.80632031e+03 -1.77271313e+03 -1.73677417e+03 -1.64483411e+03 -1.56250867e+03 -1.58631995e+03 -1.50833484e+03 -1.42200012e+03 -1.42840857e+03 -1.42248682e+03 -1.41776282e+03 -1.33864368e+03 -1.33987390e+03 -1.19706958e+03 -1.45063208e+03 -1.08506689e+03 -1.22343298e+03 -1.31732874e+03 -8.77210205e+02 -1.72585999e+03 -2.75376245e+03 -3.23092500e+05 -126757328. 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. 54902536. 5.77535303e+03 1.39893103e+03 1.29662891e+03 1.20078003e+03 9.77478271e+02 1.05320691e+03 9.21328003e+02 1.01686713e+03 9.98769836e+02 1.03812439e+03 1.18900269e+03 1.01964142e+03 1.34355859e+03 1.65502649e+03 1.88091663e+03 1.47448511e+03 1.62273889e+03 1.43794141e+03 1.53108740e+03 1.61141785e+03 1.55676135e+03 1.63315796e+03 1.68496216e+03 1.67062878e+03 1.72256689e+03 1.82194873e+03 1.88606946e+03 1.93535828e+03 1.92434009e+03 1.93195703e+03 2.02085413e+03 2.08857324e+03 2.12090918e+03 2.13719482e+03 2.17057983e+03 2.28132202e+03 2.33549585e+03 2.33167261e+03 2.36132568e+03 2.40829956e+03 2.53073315e+03 2.59655273e+03 2.52615186e+03 2.55100854e+03 2.64797266e+03 2.69487402e+03 2.78621436e+03 2.81357300e+03 2.79139502e+03 2.88196289e+03 2.94403076e+03 2.96402783e+03 3.02256812e+03 3.01946631e+03 3.07815381e+03 3.15338794e+03 3.16002197e+03 3.19503320e+03 3.21947852e+03 3.28231982e+03 3.39757104e+03 3.43436841e+03 3.44796191e+03 3.43401538e+03 3.43986914e+03 3.58420850e+03 3.63238477e+03 3.57701514e+03 3.65681396e+03 3.71950122e+03 3.75860718e+03 3.86182544e+03 3.88304492e+03 3.82446411e+03 3.84638062e+03 4.00254272e+03 4.08595093e+03 4.00607104e+03 3.96528491e+03 4.04409644e+03 4.15043506e+03 4.27299072e+03 4.30006885e+03 4.18343262e+03 4.23896533e+03 4.40367920e+03 4.43211719e+03 4.44165283e+03 4.36222705e+03 4.37450684e+03 4.55959766e+03 4.63046729e+03 4.55346533e+03 4.58110742e+03 4.64615674e+03 4.68952686e+03 4.73826074e+03 4.74519287e+03 4.80113525e+03 4.85911133e+03 4.94620898e+03 4.97667725e+03 4.83676709e+03 4.88582275e+03 5.03622510e+03 5.03475635e+03 5.02138721e+03 5.04876416e+03 5.12325342e+03 5.24453516e+03 5.22518848e+03 5.17283203e+03 5.28639014e+03 5.36584033e+03 5.26662549e+03 5.28286230e+03 5.38258154e+03 5.42643066e+03 5.43386279e+03 5.40682324e+03 5.45794922e+03 5.50923975e+03 5.65210059e+03 5.66232861e+03 5.48767236e+03 5.56030176e+03 5.72913672e+03 5.76036377e+03 5.72493799e+03 5.67239795e+03 5.63833057e+03 5.79209375e+03 5.93864600e+03 5.87287256e+03 5.75530713e+03 5.82636084e+03 6.00277344e+03 6.05173877e+03 6.09532373e+03 5.95883154e+03 5.82049170e+03 5.97532324e+03 6.03615137e+03 6.04437646e+03 6.10349902e+03 6.05843506e+03 6.16199854e+03 6.36735742e+03 6.26107520e+03 6.02082910e+03 6.11191162e+03 6.27965234e+03 6.31233936e+03 6.40093164e+03 6.31599219e+03 6.23484277e+03 6.29158984e+03 6.47891943e+03 6.41383984e+03 6.18523828e+03 6.30919922e+03 6.51575977e+03 6.47212793e+03 6.40529736e+03 6.37770605e+03 6.40163428e+03 6.48845703e+03 6.49706689e+03 6.50501562e+03 6.61437891e+03 6.51547314e+03 6.55642432e+03 6.67943799e+03 6.62833691e+03 6.51737939e+03 6.53026172e+03 6.65553418e+03 6.76249365e+03 6.68441992e+03 6.57187744e+03 6.50631152e+03 6.66761523e+03 6.94386426e+03 6.96948389e+03 6.56118164e+03 6.62056348e+03 6.88914941e+03 6.80252686e+03 6.72055469e+03 6.68145654e+03 6.64592725e+03 6.81172949e+03 6.88071973e+03 6.74738330e+03 6.71326904e+03 6.69370703e+03 6.79091602e+03 6.94791602e+03 6.88882910e+03 6.77362891e+03 6.76751709e+03 6.88983789e+03 6.85203760e+03 6.78304102e+03 6.79055908e+03 6.85399756e+03 6.75120605e+03 6.95731787e+03 7.00886133e+03 6.66285254e+03 6.68787402e+03 6.88583887e+03 6.93168457e+03 6.90925098e+03 6.67982959e+03 6.77895850e+03 7.01174268e+03 6.92941943e+03 6.90966504e+03 6.72215283e+03 6.63752051e+03 6.85737061e+03 6.98605420e+03 6.89068213e+03 6.80943945e+03 6.85985400e+03 6.80368311e+03 6.93672754e+03 6.88683887e+03 6.70697949e+03 6.63149170e+03 6.71392773e+03 6.90971924e+03 6.82238281e+03 6.70675830e+03 6.70396680e+03 6.82219873e+03 6.85036914e+03 6.73792188e+03 6.70689307e+03 6.68678467e+03 6.75345605e+03 6.69268799e+03 6.78871045e+03 6.67667041e+03 6.57913525e+03 6.73735010e+03 6.54631836e+03 6.60129102e+03 6.72027002e+03 6.57852051e+03 6.51964600e+03 6.56279102e+03 6.59320557e+03 6.52030225e+03 6.39321582e+03 6.60998486e+03 6.77487256e+03 6.42487012e+03 6.34230225e+03 6.45112109e+03 6.44479443e+03 6.55477246e+03 6.47315527e+03 6.29106201e+03 6.34082275e+03 6.45527002e+03 6.45597852e+03 6.37248047e+03 6.27162549e+03 6.29467920e+03 6.31001709e+03 6.20675928e+03 6.19959375e+03 6.14130176e+03 6.12219531e+03 6.21656641e+03 6.21876025e+03 6.19808350e+03 6.06086523e+03 5.97912646e+03 6.13695264e+03 6.22608301e+03 5.97358447e+03 6.00566016e+03 6.01017920e+03 5.82756201e+03 5.93887988e+03 5.92600635e+03 5.79945557e+03 5.90410693e+03 5.86021191e+03 5.79290332e+03 5.91987402e+03 5.77407129e+03 5.64715283e+03 5.66176514e+03 5.70195166e+03 5.73741992e+03 5.55607178e+03 5.50344678e+03 5.58427246e+03 5.59404004e+03 5.56122900e+03 5.50256738e+03 5.38539746e+03 5.46144043e+03 5.59600879e+03 5.38542529e+03 5.26157520e+03 5.21414893e+03 5.33897998e+03 5.38399268e+03 5.16662305e+03 5.11727539e+03 5.13773047e+03 5.13307324e+03 5.08481689e+03 5.08137793e+03 5.03412842e+03 4.93390186e+03 5.00445459e+03 5.07035254e+03 4.90943408e+03 4.69357422e+03 4.74550830e+03 4.81365820e+03 4.77652490e+03 4.76419531e+03 4.69823193e+03 4.60102051e+03 4.68692334e+03 4.72609375e+03 4.54366162e+03 4.46552734e+03 4.44538184e+03 4.54225098e+03 4.48672656e+03 4.28076904e+03 4.23361182e+03 4.28241699e+03 4.30387988e+03 4.24409326e+03 4.22327783e+03 4.13953076e+03 4.09854053e+03 4.07458716e+03 3.96217310e+03 3.94876050e+03 3.89787134e+03 3.91186206e+03 3.93253003e+03 3.81425464e+03 3.71205225e+03 3.71314209e+03 3.74453198e+03 3.81162427e+03 3.73957544e+03 3.53883276e+03 3.48813672e+03 3.51602197e+03 3.47906982e+03 3.40336450e+03 3.35718384e+03 3.34019531e+03 3.32847070e+03 3.24461694e+03 3.13322998e+03 3.16188257e+03 3.18714160e+03 3155. 3.06115234e+03 2.94915234e+03 2.93873877e+03 2.87955005e+03 2.82521240e+03 2.88175806e+03 2.82646338e+03 2.68522510e+03 2.65511743e+03 2.65049219e+03 2.66178174e+03 2.61590747e+03 2.52336377e+03 2.46039404e+03 2.42326978e+03 2.37408594e+03 2.30528296e+03 2.29960571e+03 2.26245630e+03 2.23602075e+03 2.18725708e+03 2.05577466e+03 2.04033508e+03 2.02244385e+03 1.97911743e+03 1.97751978e+03 1.87594861e+03 1.80177148e+03 1.82302600e+03 1.78308789e+03 1.70015405e+03 1.64545386e+03 1.58910205e+03 1.53699683e+03 1.49957349e+03 1.46708484e+03 1.41485193e+03 1.39384814e+03 1.35914172e+03 1.28750806e+03 1.22384412e+03 1.16330273e+03 1.14294763e+03 1.11475354e+03 1.05708704e+03 9.81482971e+02 9.28891052e+02 9.01054565e+02 8.68204102e+02 8.37813049e+02 7.67666931e+02 7.00185669e+02 6.62407104e+02 6.15987671e+02 5.66510010e+02 5.33057312e+02 4.82594696e+02 4.20524567e+02 3.80249573e+02 3.32783691e+02 2.85742218e+02 2.40361374e+02 1.90696228e+02 1.41237183e+02 9.19952774e+01 4.49223938e+01 -1.25257814e+00 -4.84436073e+01 -9.89218140e+01 -1.48521576e+02 -1.97340912e+02 -2.38387360e+02 -2.87379578e+02 -3.37693634e+02 -3.81427246e+02 -4.35357239e+02 -4.83342926e+02 -5.22904602e+02 -5.71235840e+02 -6.21472595e+02 -6.84186584e+02 -7.34443054e+02 -7.60550781e+02 -8.05730408e+02 -8.50882751e+02 -8.96852966e+02 -9.51759705e+02 -1.00962970e+03 -1.06202014e+03 -1.09821448e+03 -1.13869763e+03 -1.17952063e+03 -1.23051794e+03 -1.31759619e+03 -1.35990222e+03 -1.36392700e+03 -1.41451343e+03 -1.46182788e+03 -1.50246729e+03 -1.58043140e+03 -1.64328210e+03 -1.65994873e+03 -1.69274426e+03 -1.73796448e+03 -1.78997571e+03 -1.86801721e+03 -1.90001001e+03 -1.94264990e+03 -1.99153687e+03 -2.01571558e+03 -2.08436816e+03 -2.09480347e+03 -2.15073218e+03 -2.26488354e+03 -2.25465820e+03 -2.27109595e+03 -2.34514990e+03 -2.36807495e+03 -2.40916211e+03 -2.55062500e+03 -2.60205981e+03 -2.51467139e+03 -2.56841699e+03 -2.65281665e+03 -2.67540503e+03 -2.78442554e+03 -2.81228857e+03 -2.77712646e+03 -2.85913574e+03 -2.91015991e+03 -2.99148462e+03 -3.07768311e+03 -3.05760815e+03 -3.11241211e+03 -3.12500439e+03 -3.08737793e+03 -3.17952539e+03 -3.30206250e+03 -3.32434717e+03 -3.38451172e+03 -3.41522974e+03 -3.31651440e+03 -3.42297827e+03 -3.60603784e+03 -3.63585059e+03 -3.58998486e+03 -3.52078857e+03 -3.61250488e+03 -3.79176782e+03 -3.79593311e+03 -3.78571436e+03 -3.88646777e+03 -3.85578882e+03 -3.90914453e+03 -3.98818970e+03 -3.88810962e+03 -3.97017822e+03 -4.13573877e+03 -4.18605566e+03 -4.16112744e+03 -4.06867310e+03 -4.14165430e+03 -4.28672168e+03 -4.37450635e+03 -4.37604736e+03 -4.32205127e+03 -4.31164600e+03 -4.40220898e+03 -4.53458447e+03 -4.64110205e+03 -4.59893066e+03 -4.53578027e+03 -4.60350928e+03 -4.63047607e+03 -4.67070410e+03 -4.75687988e+03 -4.75422754e+03 -4.80339795e+03 -4.91540137e+03 -4.86263672e+03 -4.86385303e+03 -4.95454834e+03 -4.99881104e+03 -5.05249707e+03 -5.02597803e+03 -4.95518408e+03 -5.04112256e+03 -5.17386768e+03 -5.25400195e+03 -5.33742285e+03 -5.22154980e+03 -5.11678613e+03 -5.25822949e+03 -5.27002100e+03 -5.35301123e+03 -5.45303662e+03 -5.35826074e+03 -5.35909668e+03 -5.39061133e+03 -5.44935205e+03 -5.59016895e+03 -5.69666211e+03 -5.63804834e+03 -5.60515625e+03 -5.59258203e+03 -5.50272754e+03 -5.62110205e+03 -5.75629102e+03 -5.84534473e+03 -5.84423438e+03 -5.71728125e+03 -5.69294287e+03 -5.82958398e+03 -5.90825488e+03 -5.92986914e+03 -5.91116602e+03 -5.89375879e+03 -5.85302490e+03 -5.99825439e+03 -6.15629346e+03 -6.07347412e+03 -5.95295557e+03 -6.03680322e+03 -6.09984863e+03 -6.14817041e+03 -6.20767578e+03 -6.18069434e+03 -6.24428467e+03 -6.17708838e+03 -6.15661523e+03 -6.33644678e+03 -6.31004785e+03 -6.25019922e+03 -6.42474365e+03 -6.27862695e+03 -6.21063281e+03 -6.44950781e+03 -6.40650781e+03 -6.14665039e+03 -6.89552979e+03 -6.86129199e+03 -5.86867041e+03 -5.44528027e+03 -8.34679004e+03 -1.07721396e+04 -1.72547402e+04 -1.90573281e+04 2.99202775e+06 -4489850. 3.35797025e+06 -72840128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.98316650e+06 -20910288. -3.10481680e+04 -1.95688477e+04 -1.17609004e+04 -1.10829346e+04 -1.00452959e+04 -9.38457520e+03 -9.67686621e+03 -5.47241602e+03 -6.16661182e+03 -8.13636719e+03 -6.79181641e+03 -6.28763037e+03 -5.92965283e+03 -6.47035742e+03 -7.04144141e+03 -6.96020850e+03 -6.68844238e+03 -6.70661328e+03 -6.85926074e+03 -6.86912207e+03 -6.91835645e+03 -6.94887842e+03 -6.73916748e+03 -6.65344629e+03 -6.70035547e+03 -6.68749707e+03 -6.78173193e+03 -6.64497754e+03 -6.55072656e+03 -6.74478809e+03 -6.94938867e+03 -6.76719189e+03 -6.42371973e+03 -6.45697852e+03 -6.69893994e+03 -6.76989014e+03 -6.57045605e+03 -6.40378027e+03 -6.45547852e+03 -6.70322998e+03 -6.81280957e+03 -6.62672510e+03 -6.31893945e+03 -6.34120215e+03 -6.61709375e+03 -6.55437451e+03 -6.57980078e+03 -6.47277002e+03 -6.22614893e+03 -6.33052832e+03 -6.52945605e+03 -6.38254346e+03 -6.26709277e+03 -6.44707227e+03 -6.46034619e+03 -6.34157520e+03 -6.22581299e+03 -6.07554883e+03 -6.22019971e+03 -6.44220166e+03 -6.28661426e+03 -6.10374854e+03 -6.03056836e+03 -5.99051025e+03 -6.26813525e+03 -6.38295654e+03 -6.13687500e+03 -6.00319727e+03 -5.94517432e+03 -5.87049121e+03 -6.00088428e+03 -6.19104785e+03 -5.93951416e+03 -5.80330518e+03 -5.95616650e+03 -5.89241943e+03 -5.75677637e+03 -5.76359131e+03 -5.81635693e+03 -5.88532861e+03 -5.84406738e+03 -5.79707764e+03 -5.57985645e+03 -5.49590283e+03 -5.75184326e+03 -5.84637109e+03 -5.52855273e+03 -5.33828613e+03 -5.45298926e+03 -5.56058154e+03 -5.62299414e+03 -5.63877881e+03 -5.38604834e+03 -5.27843604e+03 -5.38489404e+03 -5.36043408e+03 -5.37577002e+03 -5.27871777e+03 -5.11959814e+03 -5.14334033e+03 -5.23259375e+03 -5.21648486e+03 -5.14669092e+03 -5.11473047e+03 -5.06899658e+03 -5.05512305e+03 -5.04707520e+03 -4.85317480e+03 -4.80286719e+03 -5.04260840e+03 -5.00792725e+03 -4.72552637e+03 -4.62534717e+03 -4.66099658e+03 -4.84413135e+03 -4.93436328e+03 -4.71252686e+03 -4.49022705e+03 -4.46032861e+03 -4.50258936e+03 -4.52814502e+03 -4.51989990e+03 -4.45360303e+03 -4.40054443e+03 -4.35199170e+03 -4.31888916e+03 -4.30830859e+03 -4.19213184e+03 -4.20480371e+03 -4.30241797e+03 -4.18282227e+03 -4.08957739e+03 -4.02123633e+03 -3.92403760e+03 -4.02748340e+03 -4.10234473e+03 -3.87420215e+03 -3.74508643e+03 -3.79115308e+03 -3.88392139e+03 -3.89500684e+03 -3.74781934e+03 -3.60573584e+03 -3.55614380e+03 -3.55729517e+03 -3.58713770e+03 -3.59494849e+03 -3.42290894e+03 -3.29950806e+03 -3.37530127e+03 -3.44361377e+03 -3.35698438e+03 -3.24843359e+03 -3.20109448e+03 -3.15272119e+03 -3.16076685e+03 -3.13487744e+03 -2.98426318e+03 -2.94115674e+03 -2.99449194e+03 -2.95942017e+03 -2.87291992e+03 -2.77757495e+03 -2.76174707e+03 -2.76031616e+03 -2.72165698e+03 -2.69099146e+03 -2.58803394e+03 -2.54861328e+03 -2.55510645e+03 -2.48166602e+03 -2.42760913e+03 -2.35778857e+03 -2.31145312e+03 -2.31843164e+03 -2.32664526e+03 -2.25325562e+03 -2.10440186e+03 -2.04807642e+03 -2.09344385e+03 -2.10143530e+03 -2.01406592e+03 -1.89602771e+03 -1.83171558e+03 -1.82909033e+03 -1.82040039e+03 -1.78507410e+03 -1.69093884e+03 -1.61370569e+03 -1.59512170e+03 -1.58151868e+03 -1.54534802e+03 -1.47675793e+03 -1.40866882e+03 -1.37006873e+03 -1.33330566e+03 -1.28749304e+03 -1.24104602e+03 -1.18989648e+03 -1.14133716e+03 -1.08669580e+03 -1.02234271e+03 -9.71767761e+02 -9.61210632e+02 -9.48042664e+02 -8.88022766e+02 -8.04963013e+02 -7.30347290e+02 -6.93148621e+02 -6.85607178e+02 -6.54744629e+02 -5.86322571e+02 -5.13250427e+02 -4.56382202e+02 -4.23099609e+02 -3.90536591e+02 -3.43815735e+02 -2.91141174e+02 -2.37020554e+02 -1.89463562e+02 -1.41869476e+02 -9.14936142e+01 -4.48239365e+01 2.38152027e+00 5.02643356e+01 1.01089050e+02 1.47473373e+02 1.83173218e+02 2.34344131e+02 2.92458527e+02 3.40849152e+02 3.87608826e+02 4.31019684e+02 4.90918488e+02 5.41148560e+02 5.63749939e+02 5.91141785e+02 6.51854492e+02 7.34829956e+02 8.05508301e+02 8.41477844e+02 8.42535950e+02 8.61658508e+02 9.29027893e+02 1.02308673e+03 1.10001624e+03 1.13142749e+03 1.11362939e+03 1.15622949e+03 1.27800183e+03 1.32075305e+03 1.30680688e+03 1.35368115e+03 1.41472656e+03 1.46260205e+03 1.56705688e+03 1.57810889e+03 1.56230920e+03 1.65007739e+03 1.66764929e+03 1.75502551e+03 1.84968970e+03 1.80235620e+03 1.87672363e+03 1.98024573e+03 1.98436731e+03 2.03541443e+03 2.06844629e+03 2.11239209e+03 2.19079883e+03 2.21266260e+03 2.18816797e+03 2.23419238e+03 2.40175781e+03 2.51535864e+03 2.49047388e+03 2.42859546e+03 2.41732422e+03 2.50617847e+03 2.66449121e+03 2.78852246e+03 2.75873950e+03 2.66577930e+03 2.73795532e+03 2.87136230e+03 2.87289380e+03 2.89485596e+03 2.94916406e+03 2.99086011e+03 3.04590356e+03 3.19470557e+03 3.15417773e+03 3.08539624e+03 3.21152344e+03 3.16279321e+03 3.32099072e+03 3.44607202e+03 3.35903076e+03 3.53479614e+03 3.51551685e+03 3.37309961e+03 3.51473560e+03 3.51892969e+03 3.61609839e+03 3.90145020e+03 3.74329468e+03 3.57072217e+03 3.69161621e+03 3.90015625e+03 4.09196973e+03 4.04586743e+03 3.87146582e+03 3.81361304e+03 3.91001099e+03 4.10906348e+03 4.29488086e+03 4.28710205e+03 4.11886572e+03 4.10219141e+03 4.26454834e+03 4.35352002e+03 4.30244824e+03 4.33366553e+03 4.37936963e+03 4.40918408e+03 4.62315088e+03 4.65957910e+03 4.44795605e+03 4.46619385e+03 4.58332422e+03 4.63964209e+03 4.71329346e+03 4.72929053e+03 4.89372510e+03 4.81422314e+03 4.66241113e+03 4.84955859e+03 4.75932422e+03 4.89984668e+03 5.31029541e+03 5.02898145e+03 4.71745898e+03 4.91668457e+03 5.19201172e+03 5.33790723e+03 5.40169043e+03 5.11219531e+03 4.92157520e+03 5.09069287e+03 5.41082129e+03 5.61831152e+03 5.50176953e+03 5.20319629e+03 5.19038086e+03 5.39691895e+03 5.51786475e+03 5.70211182e+03 5.71535791e+03 5.40675879e+03 5.41837695e+03 5.65218945e+03 5.75992285e+03 5.63429004e+03 5.59449561e+03 5.67666650e+03 5.65951855e+03 5.89417676e+03 5.95750586e+03 5.72841602e+03 5.74028662e+03 5.79236279e+03 5.82388672e+03 5.93620508e+03 5.91135986e+03 6.05065283e+03 6.15166406e+03 5.97517529e+03 5.89382227e+03 5.79606250e+03 6.06073633e+03 6.39003906e+03 6.30728223e+03 6.01396387e+03 5.86852979e+03 6.09577686e+03 6.44954102e+03 6.28425830e+03 5.93163135e+03 6.15041162e+03 6.34351318e+03 6.44957715e+03 6.62858105e+03 6.55253418e+03 6.18747070e+03 6.08039795e+03 6.29153369e+03 6.53162354e+03 6.53280176e+03 6.43933984e+03 6.43959912e+03 6.43868994e+03 6.60864453e+03 6.53726709e+03 6.37123730e+03 6.43213379e+03 6.42226514e+03 6.62106543e+03 6.81038867e+03 6.59370410e+03 6.63514258e+03 6.68321094e+03 6.65057080e+03 6.52011768e+03 6.35998584e+03 6.69655908e+03 7.04379980e+03 6.81606104e+03 6.47536426e+03 6.53888477e+03 6.89913916e+03 6.99421826e+03 6.84052686e+03 6.77212109e+03 6.53431543e+03 6.52957910e+03 6.89856396e+03 6.92383643e+03 6.76180225e+03 6.59832227e+03 6.53259619e+03 6.85077393e+03 7.17848682e+03 6.83532324e+03 6.65739404e+03 6.77338379e+03 6.78678906e+03 7.01506104e+03 7.06664014e+03 6.66382666e+03 6.58570166e+03 6.82232275e+03 6.82206787e+03 6.91431934e+03 6.87320654e+03 7.17588770e+03 7.03214990e+03 6.76355762e+03 6.64563574e+03 6.45707666e+03 6.94839648e+03 7.47289307e+03 7.22611963e+03 6.48199121e+03 7.19500146e+03 9.96975977e+03 1.11256670e+04 2.42268594e+04 -1.25274312e+06 -2.09654575e+06 -43805204. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38534712. 1.26827328e+05 1.80338301e+04 9.90223438e+03 1.07459443e+04 9.75377051e+03 9.56627344e+03 9.36455859e+03 9.13654492e+03 9.59218066e+03 9.68557910e+03 9.35041602e+03 9.45826562e+03 9.44455273e+03 9.30077832e+03 9.32455859e+03 9.31651465e+03 9.20009668e+03 6.66484668e+03 7.31726709e+03 6.55314600e+03 6.03280078e+03 5.95353662e+03 6.06469531e+03 6.10502051e+03 5.82255615e+03 5.81009668e+03 6.04974902e+03 6.06965771e+03 5.88946631e+03 5.83907324e+03 5.79890186e+03 5.76999268e+03 5.75967334e+03 5.72113428e+03 5.69890283e+03 5.66762549e+03 5.52131152e+03 5.49752148e+03 5.72592676e+03 5.72232422e+03 5.51726465e+03 5.49883887e+03 5.49208936e+03 5.46538379e+03 5.41742383e+03 5.37408545e+03 5.36772852e+03 5.27965674e+03 5.20512842e+03 5.21999023e+03 5.18537402e+03 5.34265381e+03 5.35639258e+03 5.14646777e+03 4.98123535e+03 4.91770947e+03 5.18275488e+03 5.20073291e+03 4.98473584e+03 4.86139990e+03 4.85972607e+03 4.89426074e+03 4.81522119e+03 4.91451904e+03 4.91061670e+03 4.61023535e+03 4.51708252e+03 4.72121191e+03 4.88282861e+03 4.71544385e+03 4.56312500e+03 4.54245605e+03 4.47842871e+03 4.44654785e+03 4.42532959e+03 4.42089258e+03 4.37463428e+03 4.29111377e+03 4.25399707e+03 4.22677930e+03 4.17300635e+03 4.28003662e+03 4.22287549e+03 4.05468530e+03 4.04042993e+03 3.97942432e+03 4.06480908e+03 4.05481665e+03 3.90567725e+03 3.85927148e+03 3.76196582e+03 3.66794971e+03 3.78962231e+03 3.74212476e+03 3.50485889e+03 3.52167432e+03 3.68623291e+03 3.75722925e+03 3.61111523e+03 3.46405103e+03 3.37843140e+03 3.33743823e+03 3.33051880e+03 3.27525513e+03 3.24052539e+03 3.18942651e+03 3.23104907e+03 3.18858252e+03 3.05643652e+03 3.02257544e+03 2.89736792e+03 2.92874634e+03 3.06280347e+03 2.95237524e+03 2.83666406e+03 2.71787939e+03 2.65036597e+03 2.76479028e+03 2.73990601e+03 2.61383496e+03 2.49612378e+03 2.44931689e+03 2.46616553e+03 2.41519312e+03 2.45352319e+03 2.42519263e+03 2.29823389e+03 2.23135620e+03 2.18732227e+03 2.18210718e+03 2.14841992e+03 2.07323169e+03 1.99372302e+03 1.95679126e+03 1.92302710e+03 1.81725171e+03 1.81003674e+03 1.88082593e+03 1.80351758e+03 1.70312561e+03 1.61515112e+03 1.56279370e+03 1.60986780e+03 1.56483459e+03 1.47109644e+03 1.38775879e+03 1.33321448e+03 1.33455457e+03 1.28491882e+03 1.23196265e+03 1.15879700e+03 1.13674011e+03 1.14193311e+03 1.06441565e+03 1.00692542e+03 9.64705933e+02 9.11687744e+02 8.49652893e+02 8.00095337e+02 7.55945618e+02 7.06156372e+02 6.67385315e+02 6.01752319e+02 5.61452942e+02 5.50747803e+02 4.79482361e+02 4.14827332e+02 3.79351746e+02 3.32261505e+02 2.93236572e+02 2.41994965e+02 1.86690399e+02 1.45081085e+02 9.71383438e+01 4.72226982e+01 1.71599776e-01 -4.66206589e+01 -9.34848709e+01 -1.41209396e+02 -1.90386444e+02 -2.33240967e+02 -2.87343109e+02 -3.53011505e+02 -3.94798676e+02 -4.28257568e+02 -4.60825623e+02 -5.15265686e+02 -5.96976013e+02 -6.40614685e+02 -6.68542053e+02 -7.01099426e+02 -7.44134155e+02 -8.12697266e+02 -8.63121887e+02 -9.27815247e+02 -9.63320740e+02 -9.83299011e+02 -1.04002124e+03 -1.08613550e+03 -1.17074182e+03 -1.21195410e+03 -1.22223059e+03 -1.27432800e+03 -1.32382263e+03 -1.36937195e+03 -1.37736633e+03 -1.46690259e+03 -1.60714758e+03 -1.60984851e+03 -1.60926855e+03 -1.61574316e+03 -1.64683057e+03 -1.79483691e+03 -1.85940027e+03 -1.84870398e+03 -1.83675415e+03 -1.88047046e+03 -1.98925757e+03 -2.03050037e+03 -2.12819849e+03 -2.17342310e+03 -2.16251758e+03 -2.14963159e+03 -2.18296924e+03 -2.35886084e+03 -2.39571289e+03 -2.37509644e+03 -2.38703418e+03 -2.41465479e+03 -2.59291211e+03 -2.65434302e+03 -2.54339868e+03 -2.57614331e+03 -2.77220410e+03 -2.82133643e+03 -2.71466772e+03 -2.75071802e+03 -2.94847632e+03 -3.01175659e+03 -2.94610107e+03 -2.91942749e+03 -2.97017017e+03 -3.17724854e+03 -3.19064624e+03 -3.11607178e+03 -3.21490015e+03 -3.25948315e+03 -3.28261548e+03 -3.32609766e+03 -3.36732568e+03 -3.32736230e+03 -3.45836255e+03 -3.63742358e+03 -3.58227881e+03 -3.65585181e+03 -3.70364868e+03 -3.67304810e+03 -3.72078296e+03 -3.74426147e+03 -3.77671899e+03 -3.74033862e+03 -3.76307422e+03 -3.89755127e+03 -3.95767310e+03 -4.10705713e+03 -4.02343872e+03 -3.92604663e+03 -4.08953662e+03 -4.17344775e+03 -4.32371729e+03 -4.33414209e+03 -4.22364795e+03 -4.22073096e+03 -4.23035791e+03 -4.36905127e+03 -4.41916504e+03 -4.54555078e+03 -4.55360693e+03 -4.49239941e+03 -4.50955908e+03 -4.40686572e+03 -4.57241504e+03 -4.86962354e+03 -4.83698633e+03 -4.74045850e+03 -4.63481299e+03 -4.61338428e+03 -4.87826660e+03 -5.05006934e+03 -4.96777246e+03 -4.79925830e+03 -4.83260449e+03 -5.00785889e+03 -5.00699951e+03 -5.16843408e+03 -5.18811621e+03 -5.06804834e+03 -5.09309668e+03 -5.12580713e+03 -5.35254883e+03 -5.40147119e+03 -5.13863721e+03 -5.16444971e+03 -5.48337109e+03 -5.45985107e+03 -5.20831006e+03 -5.33423877e+03 -5.64886523e+03 -5.65733398e+03 -5.55057178e+03 -5.42050146e+03 -5.42276758e+03 -5.74788867e+03 -5.78999854e+03 -5.66693115e+03 -5.56067676e+03 -5.52055811e+03 -5.72333740e+03 -5.79701025e+03 -5.78495410e+03 -5.63655469e+03 -5.82276562e+03 -6.08663232e+03 -5.92443164e+03 -6.02439697e+03 -6.00517578e+03 -5.90558398e+03 -5.98710205e+03 -6.01038623e+03 -6.03295508e+03 -6.02324023e+03 -5.96692041e+03 -5.86596680e+03 -6.08484863e+03 -6.42444434e+03 -6.12232373e+03 -5.89524463e+03 -6.13550439e+03 -6.33265625e+03 -6.49299365e+03 -6.36100732e+03 -6.22395947e+03 -6.38762891e+03 -6.40910449e+03 -6.23895898e+03 -6.16383643e+03 -6.43970508e+03 -6.45766553e+03 -6.34090381e+03 -6.32360693e+03 -6.15044287e+03 -6.39314990e+03 -6.83930420e+03 -6.66067334e+03 -6.47751660e+03 -6.36856006e+03 -6.25480469e+03 -6.64165967e+03 -6.90480566e+03 -6.68274512e+03 -6.46936523e+03 -6.44268408e+03 -6.56128564e+03 -6.57718848e+03 -6.81491016e+03 -6.72536572e+03 -6.54231982e+03 -6.61064062e+03 -6.61867871e+03 -6.87899512e+03 -6.85473828e+03 -6.63644824e+03 -6.67450293e+03 -6.68483691e+03 -6.77130273e+03 -6.59424023e+03 -6.62613184e+03 -6.91332129e+03 -6.90530811e+03 -6.82753418e+03 -6.61072656e+03 -6.64436279e+03 -7.08110889e+03 -6.96893457e+03 -6.81706885e+03 -6.68865625e+03 -6.63330469e+03 -6.75425195e+03 -6.80484326e+03 -6.86580225e+03 -6.67508350e+03 -6.80042041e+03 -7.08992627e+03 -6.80259326e+03 -6.99445312e+03 -7.05785742e+03 -6.87940967e+03 -6.86463086e+03 -6.80064014e+03 -6.83662891e+03 -6.85546582e+03 -6.76718311e+03 -6.79066943e+03 -6.98526660e+03 -6.98160254e+03 -6.64284814e+03 -6.57720459e+03 -6.77228320e+03 -6.91895557e+03 -7.17858350e+03 -6.95964844e+03 -6.64955371e+03 -6.85624121e+03 -6.98273682e+03 -6.86530029e+03 -6.75444336e+03 -6.76873535e+03 -6.70643896e+03 -6.70017383e+03 -6.84603320e+03 -6.66249658e+03 -6.72583838e+03 -7.01136621e+03 -6.87030469e+03 -6.75830127e+03 -6.61717139e+03 -6.62186279e+03 -6.94696826e+03 -6.87967578e+03 -6.74174365e+03 -6.53411475e+03 -6.37387500e+03 -6.56405420e+03 -6.76175244e+03 -6.96872754e+03 -6.73110791e+03 -6.47974316e+03 -6.53891309e+03 -6.55151074e+03 -6.81568408e+03 -6.72253760e+03 -6.51671484e+03 -6.48493945e+03 -6.46598486e+03 -6.49589355e+03 -6.37279639e+03 -6.46724609e+03 -6.71788623e+03 -6.59085107e+03 -6.46001758e+03 -6.33996045e+03 -6.28041846e+03 -6.60244922e+03 -6.58128613e+03 -6.35181885e+03 -6.19174609e+03 -6.13556348e+03 -6.30253467e+03 -6.27380908e+03 -6.48170605e+03 -6.47764111e+03 -6.22129492e+03 -6.04640039e+03 -6.13406592e+03 -6.38418945e+03 -6.29734131e+03 -6.11665723e+03 -6.06090186e+03 -6.02300342e+03 -5.99095557e+03 -5.92584619e+03 -6.05782080e+03 -6.02595459e+03 -5.88680078e+03 -6.06702539e+03 -6.10302441e+03 -5.96961328e+03 -5.89181787e+03 -5.85740869e+03 -5.82963184e+03 -5.66293750e+03 -5.59508154e+03 -5.84864453e+03 -5.88670605e+03 -5.59416943e+03 -5.42908057e+03 -5.66163135e+03 -5.86498975e+03 -5.75606445e+03 -5.50858008e+03 -5.35755469e+03 -5.55995703e+03 -5.60908447e+03 -5.46668066e+03 -5.47799512e+03 -5.28131982e+03 -5.05847852e+03 -5.24753320e+03 -5.54272559e+03 -5.50019873e+03 -5.18451611e+03 -4.97552295e+03 -5.25748193e+03 -5.40082959e+03 -5.17317822e+03 -4.98069629e+03 -4.89456348e+03 -4.92537500e+03 -4.96301367e+03 -5.09823242e+03 -5.07686377e+03 -4.87965674e+03 -4.78329541e+03 -4.75031396e+03 -4.91400586e+03 -4.77467285e+03 -4.59071338e+03 -4.77103662e+03 -4.74031201e+03 -4.62686426e+03 -4.51108545e+03 -4.44788477e+03 -4.65028174e+03 -4.48640479e+03 -4.27408838e+03 -4.36437354e+03 -4.42425098e+03 -4.38335840e+03 -4.28130762e+03 -4.36878125e+03 -4.35305908e+03 -4.18396777e+03 -4.01575806e+03 -3.96364673e+03 -4.17509668e+03 -4.08517334e+03 -3.92113452e+03 -3.92336377e+03 -3.86332788e+03 -3.89147852e+03 -3.84856616e+03 -3.83400171e+03 -3.75641113e+03 -3.64202539e+03 -3.72228564e+03 -3.70343457e+03 -3.60056982e+03 -3.57731592e+03 -3.53039844e+03 -3.43226050e+03 -3.30059912e+03 -3.24212329e+03 -3.38118872e+03 -3.48656470e+03 -3.26061963e+03 -3.06809595e+03 -3.15662280e+03 -3.24736621e+03 -3.17344873e+03 -3.01074170e+03 -2.89779395e+03 -2.99847559e+03 -2.96426880e+03 -2.82091724e+03 -2.90099219e+03 -2.83624561e+03 -2.64308130e+03 -2.63329077e+03 -2.72969263e+03 -2.70587817e+03 -2.52837427e+03 -2.40727173e+03 -2.48914502e+03 -2.54515356e+03 -2.43179370e+03 -2.28266064e+03 -2.20472778e+03 -2.27648535e+03 -2.26175293e+03 -2.15111426e+03 -2.11899170e+03 -2.08760718e+03 -2.01306104e+03 -1.94956433e+03 -1.97778857e+03 -1.89982507e+03 -1.79272925e+03 -1.80740027e+03 -1.77176917e+03 -1.73742798e+03 -1.65327869e+03 -1.56700732e+03 -1.58286853e+03 -1.50560840e+03 -1.42508972e+03 -1.43790906e+03 -1.41615576e+03 -1.38804529e+03 -1.29742114e+03 -1.32589014e+03 -1.18043005e+03 -1.40800195e+03 -1.08200244e+03 -1.42084143e+03 -1.55578125e+03 -1.40623047e+03 -2.02842651e+03 -2.16301074e+03 -3.23092500e+05 -126757328. 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. 234322608. 9.33574316e+03 2.06560791e+03 1.49982385e+03 1.37853308e+03 1.22677234e+03 1.20719531e+03 9.25578674e+02 9.89085571e+02 9.85333008e+02 1.04218604e+03 1.18954236e+03 1.01832745e+03 1.35273047e+03 1.66649878e+03 1.94491528e+03 1.80497168e+03 1.82594299e+03 1.44652673e+03 1.52592590e+03 1.63302661e+03 1.61372949e+03 1.66060510e+03 1.66654700e+03 1.66217065e+03 1.74569043e+03 1.84873328e+03 1.86571606e+03 1.90398193e+03 1.93114075e+03 1.96656543e+03 2.07225830e+03 2.07626587e+03 2.05899194e+03 2.13364868e+03 2.17937573e+03 2.26692065e+03 2.33659326e+03 2.30814966e+03 2.35763867e+03 2.47893945e+03 2.62359839e+03 2.61029785e+03 2.47719531e+03 2.50667871e+03 2.62439478e+03 2.72337549e+03 2.81613892e+03 2.82609424e+03 2.78616382e+03 2.90038086e+03 2.98062817e+03 2.92956372e+03 2.94902661e+03 2.99649414e+03 3.14214331e+03 3.28280493e+03 3.16825806e+03 3.10045850e+03 3.21820776e+03 3.34655200e+03 3.44461792e+03 3.41385156e+03 3.38162036e+03 3.39744531e+03 3.50996362e+03 3.71629858e+03 3.65142822e+03 3.49990918e+03 3.62759131e+03 3.75223828e+03 3.78227197e+03 3.85429004e+03 3.83589941e+03 3.78717310e+03 3.91188818e+03 4.05349561e+03 4.01577954e+03 3.98037671e+03 3.98618311e+03 4.05386108e+03 4.21955664e+03 4.34764795e+03 4.26175439e+03 4.14975635e+03 4.27065674e+03 4.42599170e+03 4.37208545e+03 4.35280566e+03 4.40045312e+03 4.49912354e+03 4.69276416e+03 4.64522852e+03 4.48230957e+03 4.49945654e+03 4.58309180e+03 4.72228369e+03 4.80312061e+03 4.75620508e+03 4.77758154e+03 4.92024414e+03 5.09265820e+03 5.01202734e+03 4.77568262e+03 4.82511865e+03 5.04196338e+03 5.09335059e+03 5.09922412e+03 5.06438037e+03 5.06864160e+03 5.24682275e+03 5.27950928e+03 5.16363330e+03 5.22835059e+03 5.29429980e+03 5.30063721e+03 5.44680957e+03 5.45618945e+03 5.35243506e+03 5.38333105e+03 5.41386768e+03 5.45559912e+03 5.61088330e+03 5.76231836e+03 5.61898242e+03 5.43570166e+03 5.62695703e+03 5.82498584e+03 5.72523535e+03 5.63138818e+03 5.63865527e+03 5.69308008e+03 5.89762891e+03 5.96189160e+03 5.77433057e+03 5.75453320e+03 5.86642236e+03 6.00114258e+03 6.04721289e+03 5.99958643e+03 5.96427637e+03 6.02644434e+03 6.15383301e+03 6.01379443e+03 5.91575000e+03 6.03350000e+03 6.11937842e+03 6.22827637e+03 6.35791553e+03 6.25397900e+03 6.04300439e+03 6.19334619e+03 6.39755957e+03 6.30530664e+03 6.28786377e+03 6.17936768e+03 6.19196045e+03 6.50804883e+03 6.57295166e+03 6.29792090e+03 6.20009082e+03 6.42160400e+03 6.62312695e+03 6.42437305e+03 6.28450732e+03 6.35888379e+03 6.59271973e+03 6.71282666e+03 6.49998486e+03 6.40018604e+03 6.48850830e+03 6.48483545e+03 6.59753174e+03 6.67059863e+03 6.56181201e+03 6.62571875e+03 6.72143750e+03 6.73155371e+03 6.65373877e+03 6.55970898e+03 6.57078027e+03 6.58638135e+03 6.69413672e+03 7.03786523e+03 6.96670117e+03 6.53009521e+03 6.70169727e+03 6.94295850e+03 6.72315186e+03 6.56073145e+03 6.62406787e+03 6.72539746e+03 7.01811426e+03 6.94174170e+03 6.64473633e+03 6.64221289e+03 6.69857715e+03 6.85492773e+03 6.90870850e+03 6.81381982e+03 6.76212207e+03 6.96977881e+03 7.04521777e+03 6.79790967e+03 6.69722461e+03 6.76051758e+03 6.78175391e+03 6.86360547e+03 7.02520654e+03 7.06183545e+03 6.71088525e+03 6.74905908e+03 6.92352197e+03 6.86236133e+03 6.85126660e+03 6.73716309e+03 6.84202246e+03 7.03312256e+03 6.99147266e+03 6.80889209e+03 6.73481592e+03 6.76224854e+03 6.79815283e+03 6.90442285e+03 6.80487158e+03 6.83421191e+03 6.90320801e+03 6.92711426e+03 7.01902295e+03 6.75646338e+03 6.64073047e+03 6.79211621e+03 6.79076221e+03 6.92256543e+03 6.87249609e+03 6.56329346e+03 6.75697363e+03 6.97038135e+03 6.74088623e+03 6.64779150e+03 6.72879443e+03 6.77187354e+03 6.77743311e+03 6.63324170e+03 6.82446533e+03 6.80873145e+03 6.60537500e+03 6.69745703e+03 6.55584619e+03 6.65316211e+03 6.80050000e+03 6.52239844e+03 6.55234082e+03 6.68096436e+03 6.58719238e+03 6.43252734e+03 6.40275000e+03 6.68119482e+03 6.80118750e+03 6.39744482e+03 6.33091260e+03 6.55347461e+03 6.50479346e+03 6.53947266e+03 6.32460059e+03 6.26941553e+03 6.43126221e+03 6.54873975e+03 6.45065186e+03 6.28903467e+03 6.25911230e+03 6.32475244e+03 6.42080078e+03 6.19589453e+03 6.10087402e+03 6.12733643e+03 6.08907910e+03 6.23650586e+03 6.38433203e+03 6.24360010e+03 5.99311230e+03 5.94560059e+03 6.18519922e+03 6.26833105e+03 5.93485205e+03 6.00412988e+03 6.17832910e+03 5.88866699e+03 5.87728076e+03 5.81066455e+03 5.83480713e+03 6.04720947e+03 5.91626270e+03 5.71566455e+03 5.87577344e+03 5.84230078e+03 5.64711816e+03 5.71078564e+03 5.74963037e+03 5.71475928e+03 5.52968750e+03 5.46500195e+03 5.62453564e+03 5.68022559e+03 5.56194434e+03 5.41750195e+03 5.37603857e+03 5.51716113e+03 5.55548779e+03 5.29988232e+03 5.25969824e+03 5.28370068e+03 5.37465820e+03 5.35002930e+03 5.13243213e+03 5.12042090e+03 5.24452148e+03 5.22624756e+03 5.06955664e+03 5.08621729e+03 5.07717480e+03 4.94978809e+03 5.08691943e+03 5.11894873e+03 4.85820459e+03 4.67527100e+03 4.76007910e+03 4.82379346e+03 4.80052881e+03 4.75470410e+03 4.64069922e+03 4.60151660e+03 4.72323438e+03 4.72075098e+03 4.48910498e+03 4.44087793e+03 4.52241016e+03 4.60079492e+03 4.46259033e+03 4.27979053e+03 4.31721777e+03 4.30660205e+03 4.27147705e+03 4.22312207e+03 4.22275195e+03 4.15976123e+03 4.05445947e+03 4.07512231e+03 4.07740918e+03 4.00845557e+03 3.87403662e+03 3.84914380e+03 3.90197070e+03 3.86345264e+03 3.77364282e+03 3.71587646e+03 3.70670459e+03 3.77235986e+03 3.73456421e+03 3.54590479e+03 3.54416821e+03 3.54899121e+03 3.49705322e+03 3.42072900e+03 3.33984326e+03 3.37048755e+03 3.34886230e+03 3.21905884e+03 3.10569312e+03 3.17072021e+03 3.22076880e+03 3.13089941e+03 3.08073584e+03 3.01209253e+03 2.99475464e+03 2.88007690e+03 2.74777588e+03 2.80908960e+03 2.82726587e+03 2.77364111e+03 2.72148291e+03 2.59984058e+03 2.58075562e+03 2.58678027e+03 2.58012012e+03 2.54656860e+03 2.43365527e+03 2.35322339e+03 2.27947217e+03 2.30051929e+03 2.31919971e+03 2.24722632e+03 2.17453296e+03 2.03739001e+03 2.03758704e+03 2.07368359e+03 1.98119397e+03 1.95568152e+03 1.87963635e+03 1.82055493e+03 1.82710046e+03 1.73923523e+03 1.67531116e+03 1.68651257e+03 1.65176917e+03 1.54792627e+03 1.46161926e+03 1.44269543e+03 1.41838525e+03 1.40959473e+03 1.39037671e+03 1.29337732e+03 1.21482532e+03 1.15408777e+03 1.13957556e+03 1.13229810e+03 1.06029541e+03 9.83807556e+02 9.19379395e+02 8.85258667e+02 8.68822083e+02 8.37501770e+02 7.74863037e+02 7.13976868e+02 6.75906372e+02 6.16530273e+02 5.51296204e+02 5.18642456e+02 4.80849518e+02 4.34361786e+02 3.95233704e+02 3.30724640e+02 2.73674347e+02 2.34563828e+02 1.93798874e+02 1.46134506e+02 9.35641479e+01 4.54984245e+01 -2.41116452e+00 -5.03740997e+01 -1.01017380e+02 -1.48503937e+02 -1.93680908e+02 -2.36030273e+02 -2.88772980e+02 -3.38866791e+02 -3.74684479e+02 -4.28217957e+02 -4.87459106e+02 -5.34830505e+02 -5.77326172e+02 -6.12331970e+02 -6.68666382e+02 -7.32720154e+02 -7.78763306e+02 -8.29909241e+02 -8.45072449e+02 -8.79144409e+02 -9.51834961e+02 -1.02355237e+03 -1.08577563e+03 -1.10947607e+03 -1.14028345e+03 -1.16272473e+03 -1.23190576e+03 -1.33043298e+03 -1.34627136e+03 -1.37853076e+03 -1.43103235e+03 -1.46299329e+03 -1.49390088e+03 -1.55397668e+03 -1.63032703e+03 -1.68819604e+03 -1.73798169e+03 -1.74599170e+03 -1.75278955e+03 -1.83180884e+03 -1.90199890e+03 -1.95950281e+03 -2.02562476e+03 -2.02710901e+03 -2.07032544e+03 -2.09806763e+03 -2.16708960e+03 -2.28989136e+03 -2.26825122e+03 -2.29152856e+03 -2.32987280e+03 -2.31100195e+03 -2.40657617e+03 -2.58331104e+03 -2.59966895e+03 -2.54366431e+03 -2.61939868e+03 -2.64197778e+03 -2.61476953e+03 -2.72790015e+03 -2.82271143e+03 -2.86048291e+03 -2.92001611e+03 -2.86790234e+03 -2.91001147e+03 -3.04246240e+03 -3.11393188e+03 -3.23852051e+03 -3.19069580e+03 -3.07441455e+03 -3.10837402e+03 -3.27725610e+03 -3.37717627e+03 -3.40597290e+03 -3.40607300e+03 -3.30851294e+03 -3.42568628e+03 -3.62588159e+03 -3.59025903e+03 -3.59402612e+03 -3.57491504e+03 -3.63902222e+03 -3.78745068e+03 -3.70237915e+03 -3.74261353e+03 -3.97284961e+03 -4.00283398e+03 -3.95715967e+03 -3.90131494e+03 -3.80869727e+03 -3.95929712e+03 -4.17355566e+03 -4.30419971e+03 -4.24152930e+03 -4.06638379e+03 -4.06166919e+03 -4.24994922e+03 -4.38781592e+03 -4.36127686e+03 -4.37379541e+03 -4.31632178e+03 -4.36885693e+03 -4.52383643e+03 -4.61450244e+03 -4.64740039e+03 -4.60298682e+03 -4.68204199e+03 -4.65550732e+03 -4.55239746e+03 -4.69140332e+03 -4.81613965e+03 -4.87140430e+03 -4.99709082e+03 -4.83551953e+03 -4.75767773e+03 -4.93470605e+03 -5.03819629e+03 -5.18766455e+03 -5.12530762e+03 -4.94533496e+03 -4.94586523e+03 -5.13240430e+03 -5.33754297e+03 -5.40793994e+03 -5.27099854e+03 -5.15341797e+03 -5.20595117e+03 -5.23736963e+03 -5.29977393e+03 -5.45461426e+03 -5.52442773e+03 -5.47238818e+03 -5.37070410e+03 -5.35772656e+03 -5.50863281e+03 -5.68845801e+03 -5.71147070e+03 -5.75866455e+03 -5.59641211e+03 -5.44485352e+03 -5.59213867e+03 -5.79822119e+03 -5.92827588e+03 -5.89718066e+03 -5.66930420e+03 -5.61311816e+03 -5.79016162e+03 -6.03593896e+03 -5.98834277e+03 -5.96410547e+03 -5.92107617e+03 -5.80833594e+03 -5.98948340e+03 -6.10159180e+03 -6.04581934e+03 -6.03253174e+03 -6.13732617e+03 -6.16049951e+03 -6.06041992e+03 -6.13286035e+03 -6.17875098e+03 -6.32282812e+03 -6.31079590e+03 -6.11872070e+03 -6.17964697e+03 -6.17816357e+03 -6.28149414e+03 -6.62671973e+03 -6.45638281e+03 -6.19367676e+03 -6.18295898e+03 -6.28814893e+03 -6.53706982e+03 -6.80094824e+03 -6.56661133e+03 -6.35413428e+03 -6.53172656e+03 -6.79962109e+03 -7.04498242e+03 -7.76538232e+03 -6.84805566e+03 -9.79502734e+03 -8.90033789e+03 -2.96201680e+04 15462871. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 36997176. 1961652. -2.56472109e+04 -2.06835977e+04 -1.28871973e+04 -1.08009307e+04 -9.70161719e+03 -5.45703955e+03 -6.23422705e+03 -8.32589355e+03 -7.03514355e+03 -6.38991162e+03 -5.82968457e+03 -6.40933447e+03 -7.05040137e+03 -7.08692725e+03 -6.82685254e+03 -6.83278564e+03 -6.80833838e+03 -6.72364209e+03 -7.05647559e+03 -6.99496436e+03 -6.68117334e+03 -6.65461670e+03 -6.74305664e+03 -6.71907129e+03 -6.58064844e+03 -6.57939404e+03 -6.76066748e+03 -6.96675146e+03 -6.96546143e+03 -6.63164014e+03 -6.28989404e+03 -6.46244238e+03 -6.82006982e+03 -6.97382520e+03 -6.68981104e+03 -6.35264941e+03 -6.33280371e+03 -6.60503223e+03 -6.95557666e+03 -6.70786768e+03 -6.34735254e+03 -6.30511035e+03 -6.63447559e+03 -6.61148145e+03 -6.46863965e+03 -6.46822168e+03 -6.37505078e+03 -6.48949121e+03 -6.50306787e+03 -6.18885400e+03 -6.17850781e+03 -6.48601025e+03 -6.64988232e+03 -6.47429395e+03 -6.14850391e+03 -5.96000391e+03 -6.28307568e+03 -6.62756641e+03 -6.44318311e+03 -6.10011621e+03 -5.91314844e+03 -5.85538135e+03 -6.17147607e+03 -6.47443213e+03 -6.28210205e+03 -6.14019922e+03 -6.02600146e+03 -5.86673047e+03 -5.95804053e+03 -6.09317676e+03 -5.90276953e+03 -5.80511914e+03 -6.02337549e+03 -5.89974072e+03 -5.62627051e+03 -5.68482568e+03 -5.95854492e+03 -6.02802002e+03 -5.87827979e+03 -5.71864990e+03 -5.53910840e+03 -5.46986670e+03 -5.71002783e+03 -5.96347754e+03 -5.70539160e+03 -5.34663672e+03 -5.33197168e+03 -5.52942627e+03 -5.73428955e+03 -5.68836035e+03 -5.36656250e+03 -5.27820703e+03 -5.41996533e+03 -5.35835059e+03 -5.28815137e+03 -5.28794043e+03 -5.22608252e+03 -5.25127197e+03 -5.21530957e+03 -5.03221533e+03 -5.05504688e+03 -5.16418652e+03 -5.19947266e+03 -5.18037695e+03 -5.02589502e+03 -4.81292188e+03 -4.81365137e+03 -5.05941943e+03 -5.05280371e+03 -4.80801953e+03 -4.63091797e+03 -4.55726025e+03 -4.73932275e+03 -4.98753613e+03 -4.79405127e+03 -4.49725977e+03 -4.47796875e+03 -4.55504248e+03 -4.52229102e+03 -4.38264941e+03 -4.39146582e+03 -4.49359570e+03 -4.50737988e+03 -4.33379395e+03 -4.16836719e+03 -4.14065332e+03 -4.29686621e+03 -4.41119385e+03 -4.25967969e+03 -4.07812891e+03 -3.97595264e+03 -3.87606567e+03 -3.98462720e+03 -4.16710010e+03 -3.99646362e+03 -3.75177197e+03 -3.70113818e+03 -3.82022925e+03 -3.93610327e+03 -3.78683667e+03 -3.63270605e+03 -3.59702490e+03 -3.59610352e+03 -3.58670996e+03 -3.54405029e+03 -3.40771582e+03 -3.32279663e+03 -3.43793823e+03 -3.45630469e+03 -3.27207422e+03 -3.17206030e+03 -3.18900049e+03 -3.22467285e+03 -3.27428467e+03 -3.16148438e+03 -2.93465576e+03 -2.91779102e+03 -3.01602588e+03 -2.98533179e+03 -2.87531104e+03 -2.79150098e+03 -2.75584009e+03 -2.73433740e+03 -2.73094629e+03 -2.65602734e+03 -2.56008325e+03 -2.59515112e+03 -2.59996313e+03 -2.48621191e+03 -2.38554492e+03 -2.33584058e+03 -2.36628320e+03 -2.38748022e+03 -2.32913916e+03 -2.21469897e+03 -2.09518677e+03 -2.03822974e+03 -2.08877710e+03 -2.14441724e+03 -2.02141125e+03 -1.87407715e+03 -1.82335767e+03 -1.83768872e+03 -1.85941638e+03 -1.80170398e+03 -1.70218140e+03 -1.63522473e+03 -1.60302332e+03 -1.55256433e+03 -1.50719006e+03 -1.48285864e+03 -1.42470874e+03 -1.38151709e+03 -1.33904810e+03 -1.25688525e+03 -1.21700037e+03 -1.20561267e+03 -1.17301758e+03 -1.11928711e+03 -1.02493042e+03 -9.54637024e+02 -9.57210632e+02 -9.50971191e+02 -8.86970032e+02 -8.11033325e+02 -7.39927063e+02 -6.82960571e+02 -6.72391724e+02 -6.62047058e+02 -5.94839966e+02 -5.12435547e+02 -4.60299164e+02 -4.28908691e+02 -3.87315277e+02 -3.40362793e+02 -2.91564148e+02 -2.39187408e+02 -1.90281479e+02 -1.40822876e+02 -9.03983841e+01 -4.47616501e+01 2.31474733e+00 5.08024445e+01 1.02341576e+02 1.48649826e+02 1.84320450e+02 2.29471634e+02 2.87720703e+02 3.47625824e+02 3.93512207e+02 4.30157013e+02 4.89665955e+02 5.42677246e+02 5.65547485e+02 5.90988464e+02 6.53405823e+02 7.36513367e+02 8.04874268e+02 8.43600769e+02 8.43434204e+02 8.60694031e+02 9.26998474e+02 1.02738538e+03 1.11132690e+03 1.13361804e+03 1.11163977e+03 1.15922290e+03 1.28862231e+03 1.32374902e+03 1.31128540e+03 1.36244873e+03 1.41096350e+03 1.46239600e+03 1.56774475e+03 1.57884851e+03 1.57186670e+03 1.65075293e+03 1.65870996e+03 1.76313989e+03 1.85989197e+03 1.79881555e+03 1.87982898e+03 1.98818530e+03 1.98885876e+03 2.03394434e+03 2.07219141e+03 2.11553857e+03 2.19052734e+03 2.22051587e+03 2.20134888e+03 2.24106079e+03 2.39728564e+03 2.52013135e+03 2.50220020e+03 2.42848340e+03 2.41677100e+03 2.52313916e+03 2.68117456e+03 2.78785107e+03 2.75157983e+03 2.66983301e+03 2.75288916e+03 2.87212842e+03 2.87150171e+03 2.91581519e+03 2.97026514e+03 2.99037427e+03 3.03632397e+03 3.20735059e+03 3.16514917e+03 3.08310132e+03 3.20954199e+03 3.18751709e+03 3.35048999e+03 3.43572192e+03 3.35659375e+03 3.54681665e+03 3.51838306e+03 3.36245215e+03 3.52691406e+03 3.53588379e+03 3.60646362e+03 3.90392505e+03 3.76473755e+03 3.57978149e+03 3.68358447e+03 3.88566357e+03 4.10016162e+03 4.06983472e+03 3.84494678e+03 3.78382300e+03 3.94692285e+03 4.14786230e+03 4.30906104e+03 4.29967725e+03 4.12535254e+03 4.11680762e+03 4.26505664e+03 4.36875000e+03 4.32092285e+03 4.32789453e+03 4.39220752e+03 4.43236719e+03 4.61466748e+03 4.64569092e+03 4.45985107e+03 4.49195605e+03 4.56950391e+03 4.63398193e+03 4.74617383e+03 4.74561426e+03 4.89087500e+03 4.83363232e+03 4.68198633e+03 4.82778516e+03 4.76834131e+03 4.93509814e+03 5.30020117e+03 5.04492920e+03 4.73826660e+03 4.92643945e+03 5.16073535e+03 5.33642822e+03 5.44075732e+03 5.14583350e+03 4.93462549e+03 5.08297119e+03 5.38833643e+03 5.61598486e+03 5.51333447e+03 5.21009619e+03 5.19583691e+03 5.40392285e+03 5.54233545e+03 5.73412842e+03 5.71571094e+03 5.41250195e+03 5.41149609e+03 5.67395654e+03 5.77793311e+03 5.60062891e+03 5.56754834e+03 5.71181299e+03 5.67832666e+03 5.93099268e+03 5.97445508e+03 5.67767529e+03 5.71732715e+03 5.87657031e+03 5.90113672e+03 5.94621729e+03 5.87843555e+03 6.03237402e+03 6.15916357e+03 6.03215527e+03 5.91978223e+03 5.79850342e+03 6.03711768e+03 6.41250146e+03 6.34436670e+03 6.03093262e+03 5.85655713e+03 6.07991602e+03 6.47348975e+03 6.32200098e+03 6.02133789e+03 6.12900195e+03 6.32896729e+03 6.46340430e+03 6.67437061e+03 6.56359863e+03 6.20881738e+03 6.05890723e+03 6.24406836e+03 6.64043408e+03 6.62912158e+03 6.43614893e+03 6.43526855e+03 6.42744189e+03 6.61393262e+03 6.59884619e+03 6.39485400e+03 6.43819189e+03 6.32275488e+03 6.62981006e+03 6.84791504e+03 6.55205322e+03 6.58346729e+03 6.68983105e+03 6.82032422e+03 6.62513818e+03 6.34962695e+03 6.63170801e+03 7.02481250e+03 6.84984277e+03 6.46965527e+03 6.59448975e+03 6.93508643e+03 6.91750244e+03 6.80203271e+03 6.78359424e+03 6.54392236e+03 6.53449512e+03 6.99345459e+03 7.00269873e+03 6.71319238e+03 6.54320654e+03 6.54090967e+03 6.84158008e+03 7.13836279e+03 6.84916113e+03 6.73373486e+03 6.79780469e+03 6.77935547e+03 7.04316602e+03 7.04490771e+03 6.70611426e+03 6.66398145e+03 6.79883496e+03 6.86393750e+03 6.89648193e+03 6.86811182e+03 6.99249023e+03 6.92788867e+03 6.63816602e+03 6.81965576e+03 6.77702100e+03 6.95601562e+03 7.41124609e+03 7.16349170e+03 6.67830469e+03 6.67688232e+03 7.35060938e+03 8.21593652e+03 8.15377197e+03 1.21941885e+04 1.93917324e+04 2.15464629e+04 -12068305. -17693968. 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. 0. 0. 0. 0. 0. 0. 0. 0. 12482699. 4.93358550e+06 -1.27353125e+06 -1.73694238e+06 1.98487598e+04 1.66857930e+04 1.06913545e+04 9.57345312e+03 9.77512793e+03 9.68439844e+03 9.34731152e+03 9.49916113e+03 9.45330273e+03 9.32670996e+03 9.38082324e+03 9.31000781e+03 9.30286035e+03 7.64008643e+03 8.02337842e+03 6.60115479e+03 6.00936865e+03 5.94662793e+03 6.12492676e+03 6.14209229e+03 5.84300635e+03 5.81299072e+03 6.09667139e+03 6.09370215e+03 5.90848291e+03 5.84346484e+03 5.80258740e+03 5.81814404e+03 5.75944141e+03 5.72544922e+03 5.75120850e+03 5.66906885e+03 5.54328467e+03 5.51965918e+03 5.72149463e+03 5.70372949e+03 5.54582910e+03 5.51190918e+03 5.49683984e+03 5.48698486e+03 5.42804736e+03 5.38410449e+03 5.35789502e+03 5.21505566e+03 5.19546289e+03 5.24785205e+03 5.19982031e+03 5.37422266e+03 5.39399756e+03 5.17151416e+03 4.98426807e+03 4.91346582e+03 5.19564600e+03 5.24646582e+03 5.00386230e+03 4.87143262e+03 4.88919531e+03 4.88920459e+03 4.78142236e+03 4.94765479e+03 4.90992529e+03 4.59139209e+03 4.54418506e+03 4.73973340e+03 4.89031592e+03 4.72255420e+03 4.58662109e+03 4.58469189e+03 4.49715625e+03 4.42336621e+03 4.42548242e+03 4.44412207e+03 4.38786670e+03 4.26791553e+03 4.21968262e+03 4.26173047e+03 4.21306641e+03 4.26919287e+03 4.17897363e+03 4.02202881e+03 4.06178613e+03 4.02588818e+03 4.06144019e+03 4.05860815e+03 3.93137158e+03 3.87359033e+03 3.75421167e+03 3.64368726e+03 3.78205054e+03 3.78097510e+03 3.54576123e+03 3.54413721e+03 3.70355542e+03 3.75585791e+03 3.61437207e+03 3.46624634e+03 3.40314795e+03 3.36865430e+03 3.30530591e+03 3.24826343e+03 3.27796924e+03 3.21767261e+03 3.22374634e+03 3.16053589e+03 3.04633398e+03 3.05305469e+03 2.93107837e+03 2.94302026e+03 3.06980420e+03 2.95616406e+03 2.83423169e+03 2.71479883e+03 2.65607886e+03 2.77154395e+03 2.74505615e+03 2.61366357e+03 2.49246680e+03 2.46065894e+03 2.47811304e+03 2.41640796e+03 2.45102710e+03 2.42970996e+03 2.30681860e+03 2.21333521e+03 2.17110596e+03 2.21105225e+03 2.16951416e+03 2.07008105e+03 1.97886023e+03 1.94055359e+03 1.94384949e+03 1.83996460e+03 1.81448889e+03 1.88788123e+03 1.81142383e+03 1.70944873e+03 1.61645459e+03 1.56148010e+03 1.61539185e+03 1.57474390e+03 1.47653503e+03 1.38644556e+03 1.32984021e+03 1.33482874e+03 1.29019482e+03 1.23376123e+03 1.15834607e+03 1.13554431e+03 1.13516382e+03 1.05753210e+03 1.01705536e+03 9.76818298e+02 9.11895081e+02 8.42306030e+02 7.94466675e+02 7.65461182e+02 7.17075012e+02 6.72508484e+02 6.03534790e+02 5.63256042e+02 5.52960144e+02 4.80166565e+02 4.15978149e+02 3.80038849e+02 3.32749023e+02 2.93931244e+02 2.40606384e+02 1.84785385e+02 1.45094421e+02 9.75880966e+01 4.77157516e+01 -5.91901124e-01 -4.82649422e+01 -9.51679230e+01 -1.42547806e+02 -1.93430725e+02 -2.35465271e+02 -2.87471924e+02 -3.55233582e+02 -3.97301056e+02 -4.25490479e+02 -4.56409119e+02 -5.19731201e+02 -6.03870117e+02 -6.41221252e+02 -6.70575745e+02 -7.04457764e+02 -7.45390564e+02 -8.14960144e+02 -8.63789307e+02 -9.28921204e+02 -9.59554138e+02 -9.76708374e+02 -1.05292725e+03 -1.10125696e+03 -1.16885681e+03 -1.21177832e+03 -1.23177258e+03 -1.27109546e+03 -1.31363220e+03 -1.38750537e+03 -1.39942590e+03 -1.47085657e+03 -1.60244604e+03 -1.61013892e+03 -1.61574524e+03 -1.61909009e+03 -1.65667737e+03 -1.79791003e+03 -1.85599390e+03 -1.85435352e+03 -1.84012585e+03 -1.88484827e+03 -1.99547693e+03 -2.04025415e+03 -2.13972119e+03 -2.17469214e+03 -2.16729126e+03 -2.14824390e+03 -2.18262183e+03 -2.37038501e+03 -2.39779663e+03 -2.37657227e+03 -2.38975488e+03 -2.42278540e+03 -2.59327490e+03 -2.65458862e+03 -2564. -2.58478125e+03 -2.76496582e+03 -2.82849121e+03 -2.72414600e+03 -2.75555029e+03 -2.95357446e+03 -3.00408569e+03 -2.94967700e+03 -2.92444385e+03 -2.96488232e+03 -3.19141479e+03 -3.21707056e+03 -3.14264185e+03 -3.18352563e+03 -3.21717334e+03 -3.30251782e+03 -3.36226367e+03 -3.37430322e+03 -3.33020874e+03 -3.45145728e+03 -3.63985156e+03 -3.58635327e+03 -3.66872974e+03 -3.71578247e+03 -3.68424878e+03 -3.73469873e+03 -3.75880566e+03 -3.77451855e+03 -3.74845264e+03 -3.77274854e+03 -3.89653687e+03 -3.96709814e+03 -4.12681982e+03 -4.02621362e+03 -3.94128857e+03 -4.12233105e+03 -4.17248242e+03 -4.31631299e+03 -4.30437305e+03 -4.21287207e+03 -4.24605957e+03 -4.26309131e+03 -4.37122266e+03 -4.44133496e+03 -4.56416016e+03 -4.54114014e+03 -4.45922314e+03 -4.53012012e+03 -4.42636621e+03 -4.61805420e+03 -4.93028711e+03 -4.84909766e+03 -4.73348389e+03 -4.64885352e+03 -4.62186035e+03 -4.88881982e+03 -5.07306299e+03 -4.97952344e+03 -4.80844580e+03 -4.82954199e+03 -5.02137256e+03 -5.02280273e+03 -5.17074023e+03 -5.15552002e+03 -5.02881299e+03 -5.17204004e+03 -5.18444482e+03 -5.34303320e+03 -5.38510498e+03 -5.15126709e+03 -5.18077393e+03 -5.48917139e+03 -5.42350439e+03 -5.17771143e+03 -5.40028613e+03 -5.71412402e+03 -5.64895020e+03 -5.53513721e+03 -5.42360596e+03 -5.44917090e+03 -5.76907959e+03 -5.78002246e+03 -5.65454883e+03 -5.55150732e+03 -5.53278369e+03 -5.76048535e+03 -5.79637988e+03 -5.77575244e+03 -5.67825244e+03 -5.86176416e+03 -6.03453125e+03 -5.92582764e+03 -6.06492627e+03 -5.98383643e+03 -5.85434473e+03 -5.99235254e+03 -6.04613867e+03 -6.04562500e+03 -6.03849365e+03 -6.00491064e+03 -5.89700977e+03 -6.13725244e+03 -6.52262012e+03 -6.16622656e+03 -5.90159766e+03 -6.12515186e+03 -6.33695068e+03 -6.51321533e+03 -6.37806689e+03 -6.21771240e+03 -6.41011719e+03 -6.40920996e+03 -6.18164258e+03 -6.12364990e+03 -6.52425635e+03 -6.53262402e+03 -6.35010547e+03 -6.35095850e+03 -6.16830566e+03 -6.41637500e+03 -6.85414014e+03 -6.65054248e+03 -6.47418750e+03 -6.29765283e+03 -6.25060791e+03 -6.62509082e+03 -6.96987305e+03 -6.78185352e+03 -6.44197314e+03 -6.42987891e+03 -6.55679150e+03 -6.62841309e+03 -6.84096094e+03 -6.66557324e+03 -6.46246436e+03 -6.67171289e+03 -6.64955322e+03 -6.86050391e+03 -6.82170215e+03 -6.58813916e+03 -6.76686963e+03 -6.78044873e+03 -6.75808838e+03 -6.56190723e+03 -6.65141504e+03 -7.07002979e+03 -6.97741895e+03 -6.71511035e+03 -6.54409082e+03 -6.70405078e+03 -7.10071777e+03 -6.97595605e+03 -6.82701318e+03 -6.65979590e+03 -6.60490967e+03 -6.85532422e+03 -6.90368848e+03 -6.85848145e+03 -6.70557812e+03 -6.81449512e+03 -7.08243701e+03 -6.85938965e+03 -6.98889014e+03 -7.03037939e+03 -6.85328223e+03 -6.87130225e+03 -6.83093994e+03 -6.81835889e+03 -6.81138184e+03 -6.75430908e+03 -6.74197021e+03 -7.01218457e+03 -7.03342529e+03 -6.62444043e+03 -6.62275635e+03 -6.75615479e+03 -6.93504395e+03 -7.20377881e+03 -6.96024756e+03 -6.54119922e+03 -6.85198633e+03 -7.15863232e+03 -6.96416895e+03 -6.66706641e+03 -6.64717920e+03 -6.76031201e+03 -6.78265625e+03 -6.84351221e+03 -6.60275000e+03 -6.76387842e+03 -7.10717285e+03 -6.91387500e+03 -6.71841064e+03 -6.58321338e+03 -6.64537842e+03 -6.94861279e+03 -6.91562695e+03 -6.70474951e+03 -6.59359033e+03 -6.36380322e+03 -6.50606299e+03 -6.84914502e+03 -7.05172217e+03 -6.67038135e+03 -6.39830176e+03 -6.57532861e+03 -6.68269580e+03 -6.90047168e+03 -6.71265234e+03 -6.44502051e+03 -6.61076123e+03 -6.58481250e+03 -6.44066455e+03 -6.31417627e+03 -6.47870312e+03 -6.77094336e+03 -6.61921338e+03 -6.46081592e+03 -6.34706348e+03 -6.29784961e+03 -6.60648096e+03 -6.58191455e+03 -6.39577539e+03 -6.21093896e+03 -6.13614209e+03 -6.27315137e+03 -6.25965771e+03 -6.46955078e+03 -6.52314893e+03 -6.16670068e+03 -6.02982324e+03 -6.20796924e+03 -6.45350244e+03 -6.27301660e+03 -6.12335010e+03 -6.05732178e+03 -6.05279932e+03 -5.98195703e+03 -5.85679590e+03 -6.06826270e+03 -6.14883545e+03 -5.95762061e+03 -6.05718652e+03 -6.07653809e+03 -5.99671875e+03 -5.95627148e+03 -5.87422705e+03 -5.83792676e+03 -5.69305957e+03 -5.61341553e+03 -5.82239307e+03 -5.92150732e+03 -5.64107520e+03 -5.41495264e+03 -5.58425293e+03 -5.87116553e+03 -5.85370947e+03 -5.53043262e+03 -5.28903760e+03 -5.56336719e+03 -5.72734375e+03 -5.56526904e+03 -5.48283252e+03 -5.27862939e+03 -5.06630518e+03 -5.24835156e+03 -5.53704102e+03 -5.52661768e+03 -5.18832812e+03 -4.96228418e+03 -5.24849023e+03 -5.44174219e+03 -5.23276807e+03 -4.94670312e+03 -4.80378369e+03 -4.95415967e+03 -4.99214795e+03 -5.09578027e+03 -5.13193359e+03 -4.92818115e+03 -4.77323047e+03 -4.75568896e+03 -4.93371533e+03 -4.77925049e+03 -4.58812500e+03 -4.77190576e+03 -4.73791504e+03 -4.64486084e+03 -4.50556445e+03 -4.46424805e+03 -4.67715576e+03 -4.49212158e+03 -4.23393262e+03 -4.33419189e+03 -4.46479199e+03 -4.43583496e+03 -4.29134229e+03 -4.36488037e+03 -4.36589648e+03 -4.19894531e+03 -4.02590796e+03 -3.97792017e+03 -4.18298633e+03 -4.05911987e+03 -3.89502173e+03 -3.97000977e+03 -3.92280176e+03 -3.86288306e+03 -3.77968652e+03 -3.83367480e+03 -3.83332031e+03 -3.68480811e+03 -3.70534253e+03 -3.67253711e+03 -3.64517188e+03 -3.61747583e+03 -3.52888037e+03 -3.41285645e+03 -3.28102637e+03 -3.25091333e+03 -3.38942480e+03 -3.51515308e+03 -3.28623486e+03 -3.03551489e+03 -3.10874902e+03 -3.26031201e+03 -3.24415015e+03 -3.04145361e+03 -2.86876123e+03 -2.96879028e+03 -2.99238086e+03 -2.84763672e+03 -2.91098242e+03 -2.82918481e+03 -2.62179126e+03 -2.64479736e+03 -2.75568140e+03 -2.71361719e+03 -2.53514941e+03 -2.39632227e+03 -2.46281714e+03 -2.57266968e+03 -2.46069531e+03 -2.29166406e+03 -2.19479663e+03 -2.25856519e+03 -2.28909351e+03 -2.17621924e+03 -2.10717407e+03 -2.06860913e+03 -2.03226270e+03 -1.97741882e+03 -1.98475793e+03 -1.90647278e+03 -1.79313733e+03 -1.79204517e+03 -1.75838989e+03 -1.74726062e+03 -1.66221680e+03 -1.57380212e+03 -1.59409766e+03 -1.49993848e+03 -1.41481372e+03 -1.43377844e+03 -1.41811536e+03 -1.35896094e+03 -1.28266052e+03 -1.27828735e+03 -1.23126367e+03 -1.12860486e+03 -1.06453772e+03 -1.03143835e+03 -1.10683594e+03 -1.06934387e+03 -1.04002673e+03 -9.76973938e+02 -2.50667603e+03 -1.54946396e+04 -281374080. 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. 94908496. 1.10996289e+04 1.71637354e+03 1.00691724e+03 8.97523254e+02 8.67064636e+02 8.54788635e+02 8.88082214e+02 9.25685547e+02 9.73343323e+02 1.00709003e+03 1.02728149e+03 1.10396643e+03 1.18512634e+03 1.19629248e+03 1.22910303e+03 1.30403455e+03 1.36799744e+03 1.41784326e+03 1.42213892e+03 1.42732434e+03 1.49943457e+03 1.59013220e+03 1.64667017e+03 1.67971619e+03 1.69003711e+03 1.73519568e+03 1.84751086e+03 1.93326526e+03 1.91628955e+03 1.88200781e+03 1.95360962e+03 2.06413867e+03 2.08254053e+03 2.12265747e+03 2.19008203e+03 2.17746143e+03 2.26365698e+03 2.35897754e+03 2.30764307e+03 2.34884058e+03 2.46842090e+03 2.60460742e+03 2.66904395e+03 2.53339844e+03 2.49030103e+03 2.60422510e+03 2.75571069e+03 2.84102197e+03 2.78134229e+03 2.81721875e+03 2.95151074e+03 2.96979883e+03 2.99958179e+03 2.99705420e+03 2.95027344e+03 3.10297583e+03 3.23913696e+03 3.17252612e+03 3.20092676e+03 3.30708423e+03 3.30901367e+03 3.39991675e+03 3.45889893e+03 3.39617065e+03 3.42156543e+03 3.51932300e+03 3.68580078e+03 3.70447729e+03 3.59391650e+03 3.66861646e+03 3.70486426e+03 3.77763184e+03 3.90503076e+03 3.80420728e+03 3.80551025e+03 3.95163940e+03 4.06125513e+03 4.12207812e+03 4.03004663e+03 3.94335205e+03 4.02923315e+03 4.19350732e+03 4.29640430e+03 4.32196289e+03 4.26938916e+03 4.26840576e+03 4.40155566e+03 4.50495801e+03 4.43625391e+03 4.33541406e+03 4.44054541e+03 4.63912500e+03 4.72627148e+03 4.64769189e+03 4.55552148e+03 4.54219971e+03 4.73530762e+03 4.87180566e+03 4.72875342e+03 4.75954248e+03 4.93890283e+03 5.06872559e+03 5.10176953e+03 4.87058057e+03 4.77147412e+03 4.97735547e+03 5.11235107e+03 5.10133545e+03 5.10966943e+03 5.20015186e+03 5.31040088e+03 5.21849023e+03 5.21162793e+03 5.34155029e+03 5.27518018e+03 5.25791943e+03 5.41799268e+03 5.50088867e+03 5.54188477e+03 5.47629883e+03 5.32802930e+03 5.43032666e+03 5.60432764e+03 5.70795703e+03 5.66532959e+03 5.54827393e+03 5.64805029e+03 5.83136523e+03 5.89873438e+03 5.71227686e+03 5.57328711e+03 5.68764600e+03 5.86994287e+03 5.92838867e+03 5.86123193e+03 5.83443701e+03 5.87718359e+03 6.04759229e+03 6.10501562e+03 6.03644189e+03 6.01212842e+03 5.95212061e+03 6.05362549e+03 6.07717676e+03 6.02545410e+03 6.07843848e+03 6.12459082e+03 6.31303711e+03 6.42908740e+03 6.20796924e+03 6.08465088e+03 6.20898486e+03 6.32930225e+03 6.43088672e+03 6.40965967e+03 6.15544873e+03 6.18054492e+03 6.49848389e+03 6.68493359e+03 6.45432422e+03 6.21257227e+03 6.33907568e+03 6.60689795e+03 6.60643359e+03 6.27530859e+03 6.32772168e+03 6.54648389e+03 6.60859033e+03 6.59469141e+03 6.65328027e+03 6.66981006e+03 6.43402295e+03 6.61419531e+03 6.79082031e+03 6.51685889e+03 6.56350488e+03 6.68307275e+03 6.71928369e+03 6.87217090e+03 6.68694336e+03 6.47639014e+03 6.55114893e+03 6.71610059e+03 7.03535547e+03 6.97753271e+03 6.56660254e+03 6.63958496e+03 6.99654590e+03 6.85222754e+03 6.55487598e+03 6.60234814e+03 6.78085840e+03 6.98244434e+03 6.97021143e+03 6.91304297e+03 6.74804492e+03 6.63604199e+03 6.84348389e+03 6.98497168e+03 6.77386084e+03 6.75761377e+03 6.95126855e+03 7.03782666e+03 7.03392676e+03 6.81639697e+03 6.66565283e+03 6.74887207e+03 6.84989746e+03 7.08978223e+03 7.07751709e+03 6.73481885e+03 6.73909717e+03 6.96441064e+03 7.00114746e+03 6.95752197e+03 6.72123291e+03 6.79258496e+03 6.95331787e+03 7.03356201e+03 6.98189062e+03 6.79406836e+03 6.71703564e+03 6.84508789e+03 6.99201611e+03 6.79743506e+03 6.86263037e+03 6.97100879e+03 6.90704688e+03 7.06249023e+03 6.80666992e+03 6.64965576e+03 6.81908740e+03 6.83077148e+03 6.92189795e+03 6.75470898e+03 6.56285840e+03 6.79058105e+03 7.04692480e+03 6.88780029e+03 6.75393896e+03 6.77373730e+03 6.68440576e+03 6.62461963e+03 6.80664111e+03 6.99420361e+03 6.81116260e+03 6.57219238e+03 6.74790479e+03 6.67422217e+03 6.71699463e+03 6.69026807e+03 6.45703076e+03 6.61831396e+03 6.77446631e+03 6.53242432e+03 6.45000098e+03 6.51885010e+03 6.71274170e+03 6.82461426e+03 6.39414648e+03 6.34981934e+03 6.55998926e+03 6.58827002e+03 6.65775684e+03 6.41796777e+03 6.36552148e+03 6.33479688e+03 6.36179688e+03 6.58870068e+03 6.45093262e+03 6.18918701e+03 6.33304980e+03 6.48573486e+03 6.25318311e+03 6.17078564e+03 6.11322363e+03 6.07002441e+03 6.29935596e+03 6.38521387e+03 6.16775293e+03 6.03440039e+03 6.07816943e+03 6.16239551e+03 6.25497119e+03 6.02146094e+03 6.11028809e+03 6.12295557e+03 5.83729785e+03 5.84840186e+03 5.88680176e+03 5.90163867e+03 6.00236182e+03 5.87385498e+03 5.82034717e+03 5.94912402e+03 5.78025830e+03 5.64537793e+03 5.74004932e+03 5.81380371e+03 5.75859473e+03 5.52714648e+03 5.49195654e+03 5.74261865e+03 5.76056250e+03 5.49237305e+03 5.41040869e+03 5.44253418e+03 5.55958301e+03 5.58911182e+03 5.36270996e+03 5.30787012e+03 5.27404541e+03 5.34772803e+03 5.38490186e+03 5.20097021e+03 5.18270166e+03 5.17366455e+03 5.12711523e+03 5.17175488e+03 5.19903564e+03 5.04322510e+03 4.90606641e+03 5.08775146e+03 5.21421191e+03 4.91860449e+03 4.69469434e+03 4.79130029e+03 4.88036914e+03 4.84324707e+03 4.73017432e+03 4.64306348e+03 4.64921777e+03 4.74220264e+03 4.71858447e+03 4.55195605e+03 4.51455615e+03 4.47149268e+03 4.51993848e+03 4.50850732e+03 4.33467090e+03 4.32348975e+03 4.29137305e+03 4.25997070e+03 4.30339502e+03 4.26520459e+03 4.14017236e+03 4.06466040e+03 4.11803516e+03 4.11575244e+03 4.01265771e+03 3.90138062e+03 3.89093506e+03 3.94561963e+03 3.90879517e+03 3.73416040e+03 3.70302148e+03 3.72593848e+03 3.79393164e+03 3.77057104e+03 3.58377905e+03 3.62950903e+03 3.54889697e+03 3.37739331e+03 3.37644971e+03 3.38135498e+03 3.43744873e+03 3.37835742e+03 3.19495312e+03 3.12165063e+03 3.18407031e+03 3.23902173e+03 3.18075073e+03 3.08733765e+03 3.02179126e+03 2.95436182e+03 2.87601196e+03 2.82146851e+03 2.87873730e+03 2.86736548e+03 2.72095508e+03 2.68041504e+03 2.65293457e+03 2.63664185e+03 2.61741602e+03 2.56481689e+03 2.55984351e+03 2.44742383e+03 2.32298047e+03 2.28638037e+03 2.30904883e+03 2.33370508e+03 2.30186426e+03 2.18732007e+03 2.02488379e+03 2.02101758e+03 2.05778662e+03 1.99303040e+03 1.98959351e+03 1.93024731e+03 1.81103064e+03 1.81989636e+03 1.78283521e+03 1.69405713e+03 1.67092761e+03 1.61310779e+03 1.54216443e+03 1.49112170e+03 1.46453235e+03 1.42633728e+03 1.41380518e+03 1.40794153e+03 1.29791394e+03 1.19803101e+03 1.16072339e+03 1.14257227e+03 1.13274597e+03 1.07849719e+03 9.82078857e+02 9.26033997e+02 8.99838318e+02 8.78176514e+02 8.41330811e+02 7.70751282e+02 7.15181763e+02 6.66794312e+02 6.15311646e+02 5.64981934e+02 5.30379761e+02 4.88257233e+02 4.33151398e+02 3.88620911e+02 3.29008423e+02 2.80386414e+02 2.40102997e+02 1.92385773e+02 1.46075211e+02 9.41583786e+01 4.48211136e+01 -2.47306514e+00 -5.10544319e+01 -1.01561012e+02 -1.51205719e+02 -1.94450989e+02 -2.32895508e+02 -2.85367981e+02 -3.38310089e+02 -3.80809418e+02 -4.38656219e+02 -4.94556305e+02 -5.27140259e+02 -5.69974731e+02 -6.21522827e+02 -6.82755493e+02 -7.41939453e+02 -7.76924561e+02 -8.24905151e+02 -8.46523071e+02 -8.85997192e+02 -9.60436157e+02 -1.01833728e+03 -1.08409351e+03 -1.12593066e+03 -1.14116187e+03 -1.16545813e+03 -1.24100806e+03 -1.33218140e+03 -1.36136047e+03 -1.38814697e+03 -1.43826038e+03 -1.45621350e+03 -1.51085461e+03 -1.58965747e+03 -1.63238086e+03 -1.68616406e+03 -1.70908191e+03 -1.73459985e+03 -1.78126294e+03 -1.87649365e+03 -1.93285645e+03 -1.95362427e+03 -2.01721655e+03 -2.01270020e+03 -2.07827881e+03 -2.15344580e+03 -2.17784229e+03 -2.28749683e+03 -2.28280396e+03 -2.25026514e+03 -2.31197534e+03 -2.36025366e+03 -2.46833105e+03 -2.61669531e+03 -2.60783594e+03 -2.54365625e+03 -2.56992090e+03 -2.62072754e+03 -2.66753320e+03 -2.78886084e+03 -2.87099683e+03 -2.82582617e+03 -2.86588110e+03 -2.89070947e+03 -2.97181274e+03 -3.09927197e+03 -3.10481055e+03 -3.21151514e+03 -3.18702002e+03 -3.05609717e+03 -3.14015283e+03 -3.30954175e+03 -3.40348926e+03 -3.47276929e+03 -3.41271216e+03 -3.27403418e+03 -3.42714087e+03 -3.65637646e+03 -3.63046436e+03 -3.60552612e+03 -3.63859814e+03 -3.62982251e+03 -3.74336743e+03 -3.79587964e+03 -3.78458496e+03 -3.95745459e+03 -3.94575366e+03 -3.92934717e+03 -3.98084814e+03 -3.90559204e+03 -4.00133130e+03 -4.14661865e+03 -4.29856689e+03 -4.22074805e+03 -4.02876147e+03 -4.11352637e+03 -4.30288037e+03 -4.41008545e+03 -4.41724609e+03 -4.34206152e+03 -4.32191943e+03 -4.45652295e+03 -4.57886523e+03 -4.63190820e+03 -4.64865869e+03 -4.62169287e+03 -4.62628760e+03 -4.67844922e+03 -4.69154443e+03 -4.75938379e+03 -4.83341455e+03 -4.84719482e+03 -4.92931348e+03 -4.82970459e+03 -4.85974121e+03 -5.02996045e+03 -5.01682275e+03 -5.18728564e+03 -5.12323926e+03 -4.90829150e+03 -4.98898438e+03 -5.15977393e+03 -5.33171240e+03 -5.44790137e+03 -5.26601416e+03 -5.11727686e+03 -5.22406592e+03 -5.35635547e+03 -5.41955176e+03 -5.46060645e+03 -5.51056787e+03 -5.40352832e+03 -5.35212158e+03 -5.46399268e+03 -5.62927637e+03 -5.73702637e+03 -5.65133301e+03 -5.72502588e+03 -5.65733838e+03 -5.46475537e+03 -5.63576709e+03 -5.77821777e+03 -5.89732129e+03 -5.94721191e+03 -5.67419824e+03 -5.64365576e+03 -5.85131885e+03 -6.09012695e+03 -6.06678076e+03 -5.96491602e+03 -5.96588525e+03 -5.81014453e+03 -6.01112842e+03 -6.19367285e+03 -6.09302148e+03 -6.07022510e+03 -6.10791113e+03 -6.15343945e+03 -6.16940332e+03 -6.14679980e+03 -6.22942578e+03 -6.27724756e+03 -6.30630273e+03 -6.14515234e+03 -6.23896826e+03 -6.34672852e+03 -6.34780664e+03 -6.59121777e+03 -6.39328564e+03 -6.20063037e+03 -6.32871533e+03 -6.26201709e+03 -6.46857764e+03 -6.85686670e+03 -6.73913037e+03 -6.36125781e+03 -6.39509424e+03 -6.76435742e+03 -7.37194092e+03 -8.45338281e+03 -8.15692725e+03 -1.16493408e+04 -1.92436426e+04 -9.16756016e+04 -44345160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -20479820. 31591046. -3.24172637e+04 -2.04293906e+04 -8.17122119e+03 -8.58199121e+03 -7.78544775e+03 -7.43655713e+03 -7.17313379e+03 -6.75743994e+03 -6.85119727e+03 -7.19731641e+03 -7.14942090e+03 -6.83809814e+03 -6.59080029e+03 -6.61013818e+03 -7.00039844e+03 -7.23015820e+03 -6.94123682e+03 -6.69796777e+03 -6.63599268e+03 -6.73212256e+03 -7.00700244e+03 -7.04412939e+03 -6.78208252e+03 -6.66808691e+03 -6.65104590e+03 -6.72873047e+03 -6.77109229e+03 -6.63898242e+03 -6.64131689e+03 -6.91606787e+03 -7.05257910e+03 -6.68922510e+03 -6.35872412e+03 -6.50126758e+03 -6.81415967e+03 -7.02375732e+03 -6.71763379e+03 -6.34180615e+03 -6.39589160e+03 -6.67935889e+03 -6.98129883e+03 -6.68267920e+03 -6.29023926e+03 -6.31103809e+03 -6.58260547e+03 -6.70219824e+03 -6.68449512e+03 -6.56570703e+03 -6.36177295e+03 -6.37426514e+03 -6.54866211e+03 -6.35202441e+03 -6.20726318e+03 -6.52838525e+03 -6.56065527e+03 -6.45962451e+03 -6.24162500e+03 -5.98905664e+03 -6.32530273e+03 -6.63873242e+03 -6.46183301e+03 -6.06384863e+03 -5.86233496e+03 -5.94731299e+03 -6.30426270e+03 -6.48986523e+03 -6.28984375e+03 -6.14042871e+03 -6.00076074e+03 -5.83908447e+03 -5.98922266e+03 -6.16137109e+03 -5.95793555e+03 -5.89139307e+03 -5.95520361e+03 -5.96478760e+03 -5.80206885e+03 -5.72887402e+03 -5.91898779e+03 -5.95391064e+03 -5.95135938e+03 -5.74129639e+03 -5.50183008e+03 -5.50505469e+03 -5.78670166e+03 -5.99563916e+03 -5.68862207e+03 -5.33195508e+03 -5.38021484e+03 -5.55233887e+03 -5.69959375e+03 -5.69192676e+03 -5.43945996e+03 -5.36205518e+03 -5.35274316e+03 -5.36849170e+03 -5.42580859e+03 -5.31249072e+03 -5.24432812e+03 -5.19615625e+03 -5.21212646e+03 -5.20852783e+03 -5.11700830e+03 -5.13525684e+03 -5.15500879e+03 -5.18600488e+03 -5.03763574e+03 -4.78043457e+03 -4.83649219e+03 -5.07098828e+03 -5.12614258e+03 -4.84262891e+03 -4.60033643e+03 -4.59290625e+03 -4.81104688e+03 -5.02408350e+03 -4.77898877e+03 -4.51817529e+03 -4.55456934e+03 -4.50945020e+03 -4.51274121e+03 -4.52547607e+03 -4.44295459e+03 -4.47915137e+03 -4.40183594e+03 -4.34733301e+03 -4.32229395e+03 -4.18353369e+03 -4.25958350e+03 -4.36250244e+03 -4.29077393e+03 -4.11710059e+03 -3.95799683e+03 -3.92790698e+03 -4.04549658e+03 -4.17452148e+03 -3.97531323e+03 -3.72515430e+03 -3.75548828e+03 -3.89351562e+03 -3.95867920e+03 -3.77334204e+03 -3.63637134e+03 -3.63154199e+03 -3.57463062e+03 -3.59021851e+03 -3.58825195e+03 -3.40430957e+03 -3.34791870e+03 -3.43307178e+03 -3.44661377e+03 -3.34408179e+03 -3.24317993e+03 -3.20881421e+03 -3.20839111e+03 -3.27015869e+03 -3.15938818e+03 -2.92665479e+03 -2.93554712e+03 -3.00301440e+03 -2.98970068e+03 -2.93216577e+03 -2.79811914e+03 -2.73939014e+03 -2.75271655e+03 -2.76757617e+03 -2.71336572e+03 -2.59893579e+03 -2.58551367e+03 -2.54948486e+03 -2.49857739e+03 -2.45020386e+03 -2.34663354e+03 -2.35305493e+03 -2.37750952e+03 -2.35011304e+03 -2.22907422e+03 -2.08169067e+03 -2.06048657e+03 -2.11804272e+03 -2.14884155e+03 -2.01319543e+03 -1.86764575e+03 -1.85011157e+03 -1.85081580e+03 -1.84125464e+03 -1.80394751e+03 -1.69817432e+03 -1.63687512e+03 -1.61667249e+03 -1.58658655e+03 -1.53785229e+03 -1.47868909e+03 -1.43530762e+03 -1.37018726e+03 -1.33954980e+03 -1.29796204e+03 -1.23132507e+03 -1.19848425e+03 -1.15776904e+03 -1.11562585e+03 -1.02967786e+03 -9.62863647e+02 -9.58911804e+02 -9.45957336e+02 -9.00015625e+02 -8.17169312e+02 -7.35484436e+02 -6.90103821e+02 -6.81406433e+02 -6.66871643e+02 -5.98166199e+02 -5.19347107e+02 -4.62674805e+02 -4.18134918e+02 -3.85947998e+02 -3.48786041e+02 -2.94962646e+02 -2.40274750e+02 -1.90706924e+02 -1.42565369e+02 -9.19398193e+01 -4.47793007e+01 2.59403276e+00 5.04857140e+01 1.01116905e+02 1.48703491e+02 1.84874481e+02 2.35309525e+02 2.92784729e+02 3.43106415e+02 3.92464935e+02 4.34801086e+02 4.91493073e+02 5.44533691e+02 5.69804993e+02 5.95315918e+02 6.55174744e+02 7.38489502e+02 8.08218811e+02 8.44999451e+02 8.47735168e+02 8.68470459e+02 9.35407104e+02 1.03150696e+03 1.10856042e+03 1.13699109e+03 1.12054602e+03 1.16540039e+03 1.28980652e+03 1.33049670e+03 1.30764172e+03 1.35553052e+03 1.43219885e+03 1.47882385e+03 1.57474915e+03 1.58498547e+03 1.57459790e+03 1.65943994e+03 1.66596533e+03 1.75908679e+03 1.87349292e+03 1.81815955e+03 1.88382495e+03 1.99443799e+03 2.00348462e+03 2.05374756e+03 2.07587988e+03 2.12279761e+03 2.21060254e+03 2.22761743e+03 2.20074805e+03 2.26093066e+03 2.40986206e+03 2.51601855e+03 2.50740186e+03 2.44989771e+03 2.43394849e+03 2.52396265e+03 2.68587964e+03 2.80093433e+03 2.78676294e+03 2.68589819e+03 2.74216870e+03 2.90140112e+03 2.90313013e+03 2.90813013e+03 2.96548169e+03 3.00876196e+03 3.05255347e+03 3.22323193e+03 3.17678906e+03 3.09631030e+03 3.21676294e+03 3.18040405e+03 3.34970337e+03 3.47745166e+03 3.38993872e+03 3.55863037e+03 3.52834888e+03 3.39698047e+03 3.53975610e+03 3.52995874e+03 3.63427271e+03 3.91472607e+03 3.76223755e+03 3.61111426e+03 3.73222021e+03 3.91072266e+03 4.09643945e+03 4.07025342e+03 3.87165161e+03 3.78627100e+03 3.93893286e+03 4.18751611e+03 4.35020264e+03 4.31984814e+03 4.13383447e+03 4.10961621e+03 4.30411035e+03 4.42826660e+03 4.32022266e+03 4.31055469e+03 4.41537158e+03 4.44806006e+03 4.63330811e+03 4.67470557e+03 4.53160107e+03 4.55270410e+03 4.56197998e+03 4.62224854e+03 4.77927734e+03 4.76874561e+03 4.89897217e+03 4.86503467e+03 4.70110352e+03 4.84387793e+03 4.79295312e+03 4.95362354e+03 5.33560449e+03 5.07329395e+03 4.73589014e+03 4.91238818e+03 5.19296973e+03 5.34019189e+03 5.46332617e+03 5.20571631e+03 4.96242480e+03 5.09839111e+03 5.40550244e+03 5.69066064e+03 5.53769336e+03 5.22129102e+03 5.21186816e+03 5.41378955e+03 5.56853369e+03 5.76518311e+03 5.74710352e+03 5.43468555e+03 5.43095947e+03 5.65272021e+03 5.76072070e+03 5.76630859e+03 5.71517188e+03 5.64839990e+03 5.64907422e+03 5.95526270e+03 5.99840430e+03 5.70538232e+03 5.73864697e+03 5.88947266e+03 5.92826562e+03 5.97670215e+03 5.93647852e+03 6.09236377e+03 6.17731885e+03 5.98974072e+03 5.94316064e+03 5.90213281e+03 6.09879346e+03 6.41726025e+03 6.37631787e+03 6.05479639e+03 5.90245068e+03 6.15068750e+03 6.52802344e+03 6.32947705e+03 5.99136865e+03 6.13263037e+03 6.35479980e+03 6.49690869e+03 6.65279150e+03 6.56052002e+03 6.23845850e+03 6.06648145e+03 6.28468457e+03 6.69575977e+03 6.70718701e+03 6.43564844e+03 6.42393652e+03 6.47974512e+03 6.63985791e+03 6.56920117e+03 6.37914795e+03 6.43666553e+03 6.42336865e+03 6.68337939e+03 6.88332861e+03 6.63989014e+03 6.60865137e+03 6.69883496e+03 6.85911035e+03 6.69191357e+03 6.34522754e+03 6.70069971e+03 7.09312207e+03 6.78234619e+03 6.45219824e+03 6.66345020e+03 7.04373828e+03 6.95978271e+03 6.78194434e+03 6.83560889e+03 6.58514111e+03 6.57622119e+03 7.00746045e+03 7.01605664e+03 6.73085742e+03 6.59559717e+03 6.54322217e+03 6.87411475e+03 7.18562744e+03 6.90578125e+03 6.70171436e+03 6.80986914e+03 6.84441504e+03 7.09138330e+03 7.10795654e+03 6.70252002e+03 6.66436035e+03 6.81896045e+03 6.85715381e+03 6.94905176e+03 6.92578809e+03 7.08873779e+03 7.00675635e+03 6.72551611e+03 6.78931885e+03 6.73394238e+03 6.96057227e+03 7.39505322e+03 7.20847998e+03 6.68971826e+03 6.74833643e+03 7.55360693e+03 9.01122363e+03 9.19102246e+03 1.26416436e+04 1.06695186e+04 1.62886494e+04 8.06232344e+04 -17693968. 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. 0. 0. 0. 0. 0. 0. 0. -99286584. 2.78277051e+04 9.92599902e+03 1.07324170e+04 1.10006348e+04 7.32247656e+03 7.78855615e+03 6.78444775e+03 6.31315625e+03 6.48226855e+03 6.52522070e+03 6.29184863e+03 6.34280713e+03 6.32759375e+03 6.25124365e+03 6.26777148e+03 6.21692334e+03 6.18916406e+03 6.17486475e+03 6.14257568e+03 6.09614600e+03 5.94288379e+03 5.88852881e+03 6.15571289e+03 6.16948291e+03 5.82870850e+03 5.80684814e+03 6.11959180e+03 6.12048633e+03 5.93789502e+03 5.88730420e+03 5.83829053e+03 5.83248291e+03 5.78196191e+03 5.73968652e+03 5.75609424e+03 5.69774414e+03 5.57962305e+03 5.53775928e+03 5.73552588e+03 5.76077197e+03 5.58091260e+03 5.53635791e+03 5.51577490e+03 5.49272949e+03 5.45628223e+03 5.41019922e+03 5.39335498e+03 5.23354688e+03 5.16738916e+03 5.30272803e+03 5.25377100e+03 5.39253027e+03 5.40427930e+03 5.18133984e+03 5.00901514e+03 4.94723730e+03 5.22668311e+03 5.24932178e+03 5.01937842e+03 4.91227734e+03 4.93428955e+03 4.94550342e+03 4.84807031e+03 4.93891016e+03 4.91754346e+03 4.64174951e+03 4.56017383e+03 4.78447754e+03 4.87034229e+03 4.68905029e+03 4.59941846e+03 4.58544482e+03 4.52132031e+03 4.42575635e+03 4.40763818e+03 4.46427246e+03 4.41479785e+03 4.30606689e+03 4.27312646e+03 4.28076709e+03 4.23562891e+03 4.29764746e+03 4.22992773e+03 4.06443945e+03 4.10218262e+03 4.05847314e+03 4.05134741e+03 4.04645215e+03 3.94329102e+03 3.89040674e+03 3.78319507e+03 3.69101685e+03 3.80776392e+03 3.76758398e+03 3.54038940e+03 3.55422510e+03 3.72604883e+03 3.78927148e+03 3.63309595e+03 3.49110083e+03 3.38551318e+03 3.33895508e+03 3.34054785e+03 3.28585059e+03 3.29287524e+03 3.23355566e+03 3.24024097e+03 3.19372559e+03 3.07072876e+03 3.07570312e+03 2.94517139e+03 2.92078125e+03 3.05155054e+03 2.96380786e+03 2.84719141e+03 2.74203760e+03 2.67593164e+03 2.78051245e+03 2.74606152e+03 2.61832227e+03 2.51314453e+03 2.47385425e+03 2.49449316e+03 2.43672095e+03 2.46075464e+03 2.43837524e+03 2.31779541e+03 2.24731128e+03 2.20442285e+03 2.20378418e+03 2.15677734e+03 2.07783496e+03 1.99656201e+03 1.95659436e+03 1.96186462e+03 1.85876770e+03 1.80882776e+03 1.86990894e+03 1.81584998e+03 1.72202539e+03 1.61934021e+03 1.56878381e+03 1.62288220e+03 1.57475867e+03 1.48314893e+03 1.39770166e+03 1.34040674e+03 1.33934741e+03 1.28988367e+03 1.24274902e+03 1.16879993e+03 1.14061169e+03 1.14894299e+03 1.07229724e+03 1.01444318e+03 9.68966492e+02 9.15215332e+02 8.54689697e+02 8.03057190e+02 7.68308594e+02 7.22852539e+02 6.77419250e+02 6.06048340e+02 5.60321045e+02 5.51357666e+02 4.82402435e+02 4.16803223e+02 3.81000397e+02 3.34146576e+02 2.96694794e+02 2.41704315e+02 1.85084869e+02 1.46046188e+02 9.80931320e+01 4.76077347e+01 -6.36467874e-01 -4.80242691e+01 -9.65625839e+01 -1.44891525e+02 -1.94714478e+02 -2.37009811e+02 -2.89005219e+02 -3.54366089e+02 -3.96947601e+02 -4.31290985e+02 -4.63870148e+02 -5.18166626e+02 -5.99773376e+02 -6.45554077e+02 -6.75271790e+02 -7.07682007e+02 -7.49877502e+02 -8.16274353e+02 -8.66927795e+02 -9.36238220e+02 -9.65509827e+02 -9.80992920e+02 -1.05531909e+03 -1.10599292e+03 -1.17387036e+03 -1.20820862e+03 -1.22632471e+03 -1.28608606e+03 -1.33081689e+03 -1.39074902e+03 -1.40029480e+03 -1.47649243e+03 -1.61880701e+03 -1.61674255e+03 -1.61895947e+03 -1.62814465e+03 -1.66012329e+03 -1.80457349e+03 -1.87013696e+03 -1.86449036e+03 -1.84380615e+03 -1.89101172e+03 -2.00650037e+03 -2.04649121e+03 -2.14667480e+03 -2.18301709e+03 -2.17444580e+03 -2.16000537e+03 -2.19223291e+03 -2.37760181e+03 -2.39921777e+03 -2.37815381e+03 -2.40871924e+03 -2.44580981e+03 -2.60803906e+03 -2.65966211e+03 -2.57414453e+03 -2.59431201e+03 -2.76553125e+03 -2.84465234e+03 -2.74279810e+03 -2.76887256e+03 -2.95923169e+03 -3.01288867e+03 -2.97515796e+03 -2.95373975e+03 -2.98446191e+03 -3.19437451e+03 -3.19928125e+03 -3.13760059e+03 -3.20622925e+03 -3.25174756e+03 -3.37288892e+03 -3.41824829e+03 -3.35338647e+03 -3.31368530e+03 -3.46138013e+03 -3.69587646e+03 -3.63926318e+03 -3.63606812e+03 -3.69471265e+03 -3.71431396e+03 -3.75401538e+03 -3.77930615e+03 -3.80093262e+03 -3.76809302e+03 -3.77541870e+03 -3.90019873e+03 -3.99022144e+03 -4.15604248e+03 -4.05731006e+03 -3.92994629e+03 -4.11507373e+03 -4.21417090e+03 -4.36279053e+03 -4.32188086e+03 -4.23087305e+03 -4.27084912e+03 -4.28839355e+03 -4.38376660e+03 -4.44637500e+03 -4.58806641e+03 -4.58152539e+03 -4.49577051e+03 -4.50150146e+03 -4.41229688e+03 -4.63300439e+03 -4.97439209e+03 -4.86971826e+03 -4.75574316e+03 -4.67893018e+03 -4.60610107e+03 -4.86842773e+03 -5.13997705e+03 -5.03956250e+03 -4.83054785e+03 -4.83724365e+03 -5.03026221e+03 -5.06597412e+03 -5.19422949e+03 -5.21781934e+03 -5.10467871e+03 -5.14384717e+03 -5.15594922e+03 -5.36820801e+03 -5.40417871e+03 -5.17001709e+03 -5.21307227e+03 -5.53076270e+03 -5.48205371e+03 -5.24990967e+03 -5.38394629e+03 -5.70139746e+03 -5.65648584e+03 -5.54526904e+03 -5.45738525e+03 -5.46564355e+03 -5.79647412e+03 -5.81338623e+03 -5.72338623e+03 -5.56608936e+03 -5.53885840e+03 -5.74855371e+03 -5.83166650e+03 -5.81686621e+03 -5.68460205e+03 -5.87262598e+03 -6.09726611e+03 -5.94318896e+03 -6.08125293e+03 -6.05829053e+03 -5.92728613e+03 -6.02771338e+03 -6.08485107e+03 -6.07882715e+03 -6.05320752e+03 -5.96846973e+03 -5.89629785e+03 -6.15887549e+03 -6.55147900e+03 -6.19140967e+03 -5.96586572e+03 -6.19292676e+03 -6.28077539e+03 -6.49177051e+03 -6.38596094e+03 -6.16655176e+03 -6.50862988e+03 -6.49487207e+03 -6.17646533e+03 -6.16639209e+03 -6.54724561e+03 -6.60254199e+03 -6.43806641e+03 -6.33353125e+03 -6.13781445e+03 -6.43518604e+03 -6.92868750e+03 -6.73236865e+03 -6.48112061e+03 -6.32949219e+03 -6.26389111e+03 -6.60562793e+03 -7.01931836e+03 -6.80523877e+03 -6.48823828e+03 -6.43075781e+03 -6.59284424e+03 -6.68252930e+03 -6.84499951e+03 -6.71019727e+03 -6.53064209e+03 -6.72509180e+03 -6.68928711e+03 -6.93506641e+03 -6.92632324e+03 -6.67826514e+03 -6.71459473e+03 -6.70083496e+03 -6.88443359e+03 -6.71053223e+03 -6.62722998e+03 -7.05712500e+03 -7.01888867e+03 -6.78993896e+03 -6.61247119e+03 -6.67714502e+03 -7.06893018e+03 -7.02797461e+03 -6.87631738e+03 -6.70594531e+03 -6.67410693e+03 -6.83853125e+03 -6.89754883e+03 -6.87708789e+03 -6.70020068e+03 -6.82672119e+03 -7.10554102e+03 -6.91583643e+03 -7.00278418e+03 -7.10116699e+03 -6.87806836e+03 -6.75375928e+03 -6.76054004e+03 -6.99941064e+03 -6.96882568e+03 -6.74102930e+03 -6.68168408e+03 -7.08294922e+03 -7.07600342e+03 -6.68214844e+03 -6.57835889e+03 -6.73643506e+03 -6.95907520e+03 -7.24107568e+03 -6.97642285e+03 -6.61896191e+03 -6.97312256e+03 -7.10439014e+03 -6.94077490e+03 -6.76643115e+03 -6.79003174e+03 -6.71214209e+03 -6.76082031e+03 -6.83747021e+03 -6.63134326e+03 -6.76655762e+03 -7.09295264e+03 -6.88080859e+03 -6.85933594e+03 -6.71763379e+03 -6.64031592e+03 -6.94060156e+03 -6.93917627e+03 -6.76429248e+03 -6.63014404e+03 -6.38307080e+03 -6.53476318e+03 -6.87686572e+03 -7.05448096e+03 -6.69760889e+03 -6.47034766e+03 -6.63152832e+03 -6.64320361e+03 -6.88945801e+03 -6.82481250e+03 -6.56512988e+03 -6.50739355e+03 -6.47921631e+03 -6.46935840e+03 -6.35080029e+03 -6.53199316e+03 -6.77834131e+03 -6.56578027e+03 -6.58509863e+03 -6.43563721e+03 -6.30820654e+03 -6.64220850e+03 -6.63540234e+03 -6.37729297e+03 -6.23890723e+03 -6.17492139e+03 -6.34988184e+03 -6.31162012e+03 -6.47689844e+03 -6.55859082e+03 -6.27549951e+03 -6.06121436e+03 -6.16621484e+03 -6.44821191e+03 -6.32378711e+03 -6.16235547e+03 -6.04327588e+03 -6.02764697e+03 -6.06697412e+03 -6.00406543e+03 -6.16478906e+03 -6.13878809e+03 -5.93745752e+03 -6.11885693e+03 -6.13892578e+03 -5.98872998e+03 -5.92222510e+03 -5.90542920e+03 -5.89049268e+03 -5.71242383e+03 -5.61108594e+03 -5.88398389e+03 -5.91656104e+03 -5.61323535e+03 -5.42375244e+03 -5.66255811e+03 -5.95356836e+03 -5.84515674e+03 -5.49764600e+03 -5.37166504e+03 -5.65790186e+03 -5.64827441e+03 -5.43593359e+03 -5.53701904e+03 -5.35576953e+03 -5.10342773e+03 -5.24449072e+03 -5.50582422e+03 -5.58128418e+03 -5.26373682e+03 -4.97762988e+03 -5.23183154e+03 -5.46945264e+03 -5.24902246e+03 -4.98658057e+03 -4.89032568e+03 -5.01721045e+03 -5.00793799e+03 -5.11293311e+03 -5.07150635e+03 -4.86996631e+03 -4.84460742e+03 -4.80690381e+03 -4.94007812e+03 -4.80236914e+03 -4.62655664e+03 -4.75524414e+03 -4.70548145e+03 -4.71811475e+03 -4.58900391e+03 -4.46509082e+03 -4.68718359e+03 -4.54136865e+03 -4.30147266e+03 -4.37150635e+03 -4.43552637e+03 -4.41732178e+03 -4.31836182e+03 -4.36578564e+03 -4.36864062e+03 -4.22485840e+03 -4.07073730e+03 -4.00334204e+03 -4.17966895e+03 -4.06242920e+03 -3.91061670e+03 -3.98528540e+03 -3.94344507e+03 -3.89067578e+03 -3.83252368e+03 -3.88946680e+03 -3.81446704e+03 -3.66615771e+03 -3.75103711e+03 -3.72108740e+03 -3.62344824e+03 -3.59880981e+03 -3.55095093e+03 -3.46135767e+03 -3.32570020e+03 -3.23303076e+03 -3.35769312e+03 -3.52615552e+03 -3.30417773e+03 -3.05673853e+03 -3.15532324e+03 -3.30598730e+03 -3.23445679e+03 -3.02232373e+03 -2.90677588e+03 -3.02012915e+03 -2.97682544e+03 -2.83507227e+03 -2.91451562e+03 -2.85687427e+03 -2.67288428e+03 -2.62184180e+03 -2.71288892e+03 -2.74293726e+03 -2.57054321e+03 -2.41934399e+03 -2.47517944e+03 -2.57369678e+03 -2.46968481e+03 -2.30731177e+03 -2.20603003e+03 -2.26178369e+03 -2.32265576e+03 -2.20275488e+03 -2.09006543e+03 -2.06409570e+03 -2.03998425e+03 -1.98538501e+03 -1.99599207e+03 -1.91398853e+03 -1.80195129e+03 -1.79568738e+03 -1.76427295e+03 -1.75512402e+03 -1.66857422e+03 -1.57797009e+03 -1.58246350e+03 -1.49732581e+03 -1.45148950e+03 -1.46464868e+03 -1.40352087e+03 -1.34625317e+03 -1.29114771e+03 -1.28893896e+03 -1.23624207e+03 -1.13323767e+03 -1.06728320e+03 -1.03358716e+03 -1.10477979e+03 -1.06783557e+03 -1.17219153e+03 -1.27118604e+03 -2.53193823e+03 -1.33733701e+04 -281374080. 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. 94908496. 9.21878320e+03 1.18080408e+03 9.94295898e+02 8.73475403e+02 8.54785583e+02 8.68706360e+02 9.18965698e+02 9.28751404e+02 9.46060120e+02 1.00729132e+03 1.05597632e+03 1.11227380e+03 1.19494202e+03 1.23274988e+03 1.23664062e+03 1.30947327e+03 1.38779749e+03 1.39633691e+03 1.42109827e+03 1.47119836e+03 1.54175977e+03 1.62874561e+03 1.67734302e+03 1.68289014e+03 1.67851575e+03 1.76547559e+03 1.87767847e+03 1.88748071e+03 1.92706250e+03 1.95856628e+03 1.99064954e+03 2.10561060e+03 2.10968481e+03 2.08925732e+03 2.16506836e+03 2.21604956e+03 2.29607227e+03 2.36052026e+03 2.34563525e+03 2.38787329e+03 2.51297168e+03 2.67586987e+03 2.65066040e+03 2.50103125e+03 2.54405688e+03 2.66185938e+03 2.75245215e+03 2.86338037e+03 2.86161157e+03 2.82691162e+03 2.93672559e+03 3.01918335e+03 2.98558398e+03 2.98975464e+03 3.02817358e+03 3.18568823e+03 3.34022803e+03 3.21426001e+03 3.14484766e+03 3.27670166e+03 3.38420483e+03 3.48055371e+03 3.47205933e+03 3.42752100e+03 3.43905713e+03 3.55184106e+03 3.77565649e+03 3.72138281e+03 3.55368994e+03 3.67354614e+03 3.79239746e+03 3.83768579e+03 3.93357910e+03 3.89787793e+03 3.82890430e+03 3.97258228e+03 4.12225000e+03 4.05965625e+03 4.02848926e+03 4.05877930e+03 4.11675439e+03 4.26821973e+03 4.41201123e+03 4.33900977e+03 4.21130566e+03 4.33666553e+03 4.47684961e+03 4.43693945e+03 4.43468750e+03 4.45622461e+03 4.57406348e+03 4.74940332e+03 4.70763525e+03 4.54433301e+03 4.56153271e+03 4.65351855e+03 4.77942773e+03 4.86680615e+03 4.81467432e+03 4.84215723e+03 4.99603906e+03 5.17954834e+03 5.07574561e+03 4.84169873e+03 4.89083496e+03 5.09061914e+03 5.18544189e+03 5.20153711e+03 5.14392236e+03 5.12795459e+03 5.30921826e+03 5.34861426e+03 5.24836621e+03 5.31716357e+03 5.38183154e+03 5.37658203e+03 5.53456006e+03 5.54645996e+03 5.42959180e+03 5.45242920e+03 5.47639111e+03 5.51371045e+03 5.71017139e+03 5.85234912e+03 5.69839648e+03 5.52634912e+03 5.69784717e+03 5.90276318e+03 5.81797705e+03 5.71613867e+03 5.71938574e+03 5.77371289e+03 5.97352930e+03 6.04994531e+03 5.88200391e+03 5.84940088e+03 5.95462549e+03 6.08397705e+03 6.09764844e+03 6.07635889e+03 6.05563330e+03 6.12113525e+03 6.23185254e+03 6.11729004e+03 6.01239844e+03 6.12663428e+03 6.19503271e+03 6.29148047e+03 6.46843213e+03 6.31220752e+03 6.11413330e+03 6.27249170e+03 6.46274902e+03 6.39143848e+03 6.36010205e+03 6.28826025e+03 6.27287549e+03 6.61237305e+03 6.69661230e+03 6.38058887e+03 6.28978955e+03 6.53085889e+03 6.72010059e+03 6.56489648e+03 6.34454785e+03 6.43401758e+03 6.68283301e+03 6.80629492e+03 6.58098193e+03 6.49886084e+03 6.62925098e+03 6.59098975e+03 6.66976953e+03 6.82993262e+03 6.67742383e+03 6.64291699e+03 6.83168213e+03 6.90268799e+03 6.67459814e+03 6.64892041e+03 6.64580029e+03 6.68744189e+03 6.81074121e+03 7.12368945e+03 7.04430078e+03 6.63773096e+03 6.75936279e+03 7.04432080e+03 6.82128174e+03 6.68901904e+03 6.73714258e+03 6.84778271e+03 7.12030420e+03 7.02809375e+03 6.73612500e+03 6.72395654e+03 6.78770508e+03 6.91565723e+03 7.02050293e+03 6.91810254e+03 6.91670996e+03 7.04839307e+03 7.12832812e+03 6.92025000e+03 6.78657422e+03 6.83637256e+03 6.86776660e+03 6.93636621e+03 7.14673486e+03 7.17277490e+03 6.81798047e+03 6.82571436e+03 7.04147461e+03 6.99986182e+03 6.88771436e+03 6.86592822e+03 6.93206396e+03 7.13875879e+03 7.11599268e+03 6.87536523e+03 6.80262695e+03 6.86018115e+03 6.90014600e+03 7.02775098e+03 6.89744971e+03 6.90650830e+03 6.99569775e+03 7.05180469e+03 7.12031006e+03 6.85294971e+03 6.76391699e+03 6.90963232e+03 6.87219434e+03 7.00826953e+03 6.91990967e+03 6.66752344e+03 6.87661133e+03 7.04880811e+03 6.84607910e+03 6.76614502e+03 6.80550928e+03 6.86598926e+03 6.86347559e+03 6.70371680e+03 6.89628955e+03 6.90369580e+03 6.71416748e+03 6.86576172e+03 6.68083740e+03 6.71322266e+03 6.87074756e+03 6.62865527e+03 6.67765186e+03 6.75690576e+03 6.64564648e+03 6.45781592e+03 6.49652539e+03 6.83244141e+03 6.92661035e+03 6.48996533e+03 6.44241064e+03 6.66596143e+03 6.61688672e+03 6.61568555e+03 6.45202344e+03 6.38996973e+03 6.49362793e+03 6.58240088e+03 6.55442139e+03 6.36953760e+03 6.33060352e+03 6.42155176e+03 6.51329883e+03 6.32129248e+03 6.16479297e+03 6.20637793e+03 6.19332959e+03 6.29951904e+03 6.47530078e+03 6.31472705e+03 6.04569873e+03 6.05517480e+03 6.27503418e+03 6.35437402e+03 6.01739941e+03 6.10723975e+03 6.23310303e+03 5.95986621e+03 5.99538428e+03 5.88247412e+03 5.91452100e+03 6.14756982e+03 5.97941406e+03 5.77694580e+03 5.97452637e+03 5.94536572e+03 5.71823926e+03 5.80535254e+03 5.85352930e+03 5.80800977e+03 5.60148340e+03 5.52945410e+03 5.70761914e+03 5.77556885e+03 5.63534082e+03 5.48608984e+03 5.46989111e+03 5.59671240e+03 5.64344971e+03 5.38270020e+03 5.31580518e+03 5.37005713e+03 5.46205615e+03 5.41329443e+03 5.19173242e+03 5.20287061e+03 5.31848096e+03 5.30007910e+03 5.14288574e+03 5.17075586e+03 5.15438525e+03 4.99743604e+03 5.15906787e+03 5.19645557e+03 4.90903223e+03 4.74071484e+03 4.80339941e+03 4.91360840e+03 4.90649658e+03 4.82032178e+03 4.68968311e+03 4.66193506e+03 4.80012305e+03 4.78691357e+03 4.56813135e+03 4.50446777e+03 4.57320557e+03 4.67534033e+03 4.51817676e+03 4.34034131e+03 4.38791504e+03 4.36922949e+03 4.32270898e+03 4.27707080e+03 4.27303662e+03 4.21835889e+03 4.10721680e+03 4.12493701e+03 4.14283154e+03 4.07056836e+03 3.92804175e+03 3.89898218e+03 3.94655591e+03 3.91676465e+03 3.82337720e+03 3.77167725e+03 3.76009546e+03 3.82717847e+03 3.78702100e+03 3.59064844e+03 3.61261670e+03 3.61072974e+03 3.54529321e+03 3.45248584e+03 3.38767383e+03 3.43650269e+03 3.38573486e+03 3.26530542e+03 3.15070605e+03 3.20455737e+03 3.26313940e+03 3.17787720e+03 3.12607446e+03 3.05370459e+03 3.03170190e+03 2.93151440e+03 2.79470801e+03 2.84875269e+03 2.86731250e+03 2.80243384e+03 2.75612061e+03 2.64367773e+03 2.60860132e+03 2.62827930e+03 2.61494019e+03 2.59210864e+03 2.47842163e+03 2.38336328e+03 2.31105371e+03 2.32789478e+03 2.35432788e+03 2.27510571e+03 2.20582275e+03 2.07137158e+03 2.06818188e+03 2.09746191e+03 2.00515210e+03 1.98211963e+03 1.90962109e+03 1.84482385e+03 1.85507019e+03 1.76262354e+03 1.69984534e+03 1.71619946e+03 1.67390015e+03 1.56668274e+03 1.48281494e+03 1.46522937e+03 1.43576001e+03 1.43191248e+03 1.41088977e+03 1.31124902e+03 1.23220459e+03 1.17128638e+03 1.15534924e+03 1.14794421e+03 1.07604614e+03 9.96640381e+02 9.35882935e+02 9.00686523e+02 8.76740356e+02 8.43858154e+02 7.87583984e+02 7.24964966e+02 6.83532959e+02 6.27350220e+02 5.60631531e+02 5.25246094e+02 4.86144501e+02 4.42359406e+02 4.00816193e+02 3.34327759e+02 2.77621155e+02 2.38508453e+02 1.96901459e+02 1.47763184e+02 9.45804062e+01 4.57248154e+01 -2.50275564e+00 -5.13495674e+01 -1.01970161e+02 -1.49745682e+02 -1.96444809e+02 -2.39299286e+02 -2.94166077e+02 -3.43051910e+02 -3.78654755e+02 -4.35299957e+02 -4.93404297e+02 -5.42412659e+02 -5.87754700e+02 -6.22293396e+02 -6.77820801e+02 -7.42332825e+02 -7.93475647e+02 -8.40527527e+02 -8.51366760e+02 -8.92071045e+02 -9.66959351e+02 -1.03943481e+03 -1.09828101e+03 -1.12468921e+03 -1.16034290e+03 -1.17614392e+03 -1.25098633e+03 -1.35056799e+03 -1.36582715e+03 -1.39914148e+03 -1.44982251e+03 -1.48483459e+03 -1.51484729e+03 -1.57591406e+03 -1.64923071e+03 -1.71025854e+03 -1.76857031e+03 -1.77295276e+03 -1.77460803e+03 -1.85768091e+03 -1.93171167e+03 -1.99077820e+03 -2.05384619e+03 -2.04868115e+03 -2.09906177e+03 -2.13746143e+03 -2.19487305e+03 -2.31009155e+03 -2.30770581e+03 -2.32800854e+03 -2.35793408e+03 -2.34870239e+03 -2.44635938e+03 -2.62403003e+03 -2.62932568e+03 -2.57845581e+03 -2.66660889e+03 -2.67950464e+03 -2.65050391e+03 -2.76980469e+03 -2.86964648e+03 -2.89820679e+03 -2.95000928e+03 -2.90399438e+03 -2.95277271e+03 -3.09245361e+03 -3.16387134e+03 -3.28036206e+03 -3.23151538e+03 -3.12296704e+03 -3.15408472e+03 -3.31725513e+03 -3.42575000e+03 -3.45298584e+03 -3.45542310e+03 -3.35772314e+03 -3.47925342e+03 -3.67463843e+03 -3.62768408e+03 -3.64121582e+03 -3.65048462e+03 -3.69322290e+03 -3.82472266e+03 -3.76999585e+03 -3.78832275e+03 -4.02673340e+03 -4.06784229e+03 -3.99958667e+03 -3.94916724e+03 -3.87639282e+03 -4.00976465e+03 -4.21135986e+03 -4.36249414e+03 -4.30594922e+03 -4.12940918e+03 -4.12175195e+03 -4.30403467e+03 -4.45961670e+03 -4.42609717e+03 -4.41795508e+03 -4.37561621e+03 -4.43399854e+03 -4.59382764e+03 -4.68095264e+03 -4.71070117e+03 -4.68010498e+03 -4.74571924e+03 -4.72982227e+03 -4.62589209e+03 -4.74956396e+03 -4.87919971e+03 -4.93205762e+03 -5.06093848e+03 -4.90909033e+03 -4.81364404e+03 -4.99249609e+03 -5.10919043e+03 -5.24634131e+03 -5.20819287e+03 -5.02516357e+03 -5.01506201e+03 -5.20293506e+03 -5.41914062e+03 -5.45292578e+03 -5.31140039e+03 -5.25939062e+03 -5.30609619e+03 -5.31036621e+03 -5.37890039e+03 -5.53836328e+03 -5.62019287e+03 -5.52734912e+03 -5.43277686e+03 -5.43641699e+03 -5.57422314e+03 -5.76252441e+03 -5.82471191e+03 -5.82431152e+03 -5.65329541e+03 -5.51123975e+03 -5.68257178e+03 -5.87049268e+03 -6.02160938e+03 -5.98396289e+03 -5.75990186e+03 -5.66299609e+03 -5.87747900e+03 -6.15731592e+03 -6.04511279e+03 -6.08497852e+03 -6.01881055e+03 -5.88070996e+03 -6.09600342e+03 -6.17237354e+03 -6.13676465e+03 -6.12606104e+03 -6.24066113e+03 -6.23994873e+03 -6.14270459e+03 -6.21495117e+03 -6.27413721e+03 -6.40027051e+03 -6.38726758e+03 -6.20539502e+03 -6.29178467e+03 -6.21426758e+03 -6.38629980e+03 -6.70704590e+03 -6.57556201e+03 -6.30449365e+03 -6.29047070e+03 -6.35688721e+03 -6.58095410e+03 -6.79121973e+03 -6.60341260e+03 -6.38706250e+03 -6.55913428e+03 -6.67341162e+03 -6.62398291e+03 -6.72108887e+03 -6.95007861e+03 -7.56592969e+03 -8.75945117e+03 -1.42817754e+04 -2.06449668e+04 -14077006. 38653256. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -20479820. 31591046. -76856240. -2.58431172e+04 -1.05352744e+04 -9.29955957e+03 -8.24848145e+03 -7.62806250e+03 -7.10853857e+03 -6.77306885e+03 -6.96608545e+03 -7.27120312e+03 -7.19295312e+03 -6.97068994e+03 -6.66479150e+03 -6.60653760e+03 -6.97584229e+03 -7.36117578e+03 -7.07833301e+03 -6.81859424e+03 -6.70135303e+03 -6.75771973e+03 -7.07779541e+03 -7.04717578e+03 -6.75230029e+03 -6.68043750e+03 -6.87024561e+03 -6.81532471e+03 -6.67305762e+03 -6.66595508e+03 -6.90490723e+03 -7.10221973e+03 -7.04813135e+03 -6.68435791e+03 -6.39958105e+03 -6.56633545e+03 -6.91262891e+03 -7.03853369e+03 -6.82044922e+03 -6.50019629e+03 -6.45004980e+03 -6.71535742e+03 -7.01604980e+03 -6.79109619e+03 -6.39895312e+03 -6.39690674e+03 -6.73895801e+03 -6.72291357e+03 -6.57680518e+03 -6.57604785e+03 -6.46021240e+03 -6.56868115e+03 -6.56984766e+03 -6.27361865e+03 -6.27270508e+03 -6.58704248e+03 -6.69871191e+03 -6.56446729e+03 -6.26403857e+03 -6.04289941e+03 -6.39097559e+03 -6.75677344e+03 -6.52596387e+03 -6.20374268e+03 -5.99926465e+03 -5.91326709e+03 -6.26060986e+03 -6.58838525e+03 -6.35928467e+03 -6.22477148e+03 -6.13060498e+03 -5.97356934e+03 -6.02788184e+03 -6.15741113e+03 -5.97796924e+03 -5.88101562e+03 -6.08384766e+03 -5.97392432e+03 -5.70700244e+03 -5.78091846e+03 -6.03651465e+03 -6.12841895e+03 -5.98318457e+03 -5.78271191e+03 -5.60484766e+03 -5.51742578e+03 -5.79997070e+03 -6.05982666e+03 -5.79503662e+03 -5.43536963e+03 -5.40287939e+03 -5.60830859e+03 -5.81260107e+03 -5.76318262e+03 -5.45606934e+03 -5.35445068e+03 -5.49452979e+03 -5.44158740e+03 -5.36883984e+03 -5.36019531e+03 -5.30218115e+03 -5.34282812e+03 -5.29044092e+03 -5.11074658e+03 -5.10896729e+03 -5.23012305e+03 -5.29831201e+03 -5.26206152e+03 -5.07781885e+03 -4.87860205e+03 -4.88090430e+03 -5.11468262e+03 -5.13665674e+03 -4.88540186e+03 -4.69228125e+03 -4.61894287e+03 -4.81520850e+03 -5.06458984e+03 -4.84995068e+03 -4.55124072e+03 -4.54459668e+03 -4.61831348e+03 -4.58360547e+03 -4.45905273e+03 -4.44035449e+03 -4.55660889e+03 -4.56417480e+03 -4.40827441e+03 -4.22755029e+03 -4.18803564e+03 -4.36578076e+03 -4.46141895e+03 -4.32662939e+03 -4.14520654e+03 -4.02504590e+03 -3.93249146e+03 -4.03485449e+03 -4.22112744e+03 -4.06220386e+03 -3.81365918e+03 -3.74943213e+03 -3.88533447e+03 -4.00843384e+03 -3.84516406e+03 -3.68745239e+03 -3.63861963e+03 -3.64710791e+03 -3.65204956e+03 -3.59712256e+03 -3.45992822e+03 -3.37420801e+03 -3.47604419e+03 -3.49643652e+03 -3.32791504e+03 -3.21807837e+03 -3.23011157e+03 -3.27741504e+03 -3.31256445e+03 -3.20788501e+03 -2.97601050e+03 -2.96002686e+03 -3.05354761e+03 -3.02399976e+03 -2.92904883e+03 -2.83536987e+03 -2.78112915e+03 -2.76639771e+03 -2.77792603e+03 -2.69247241e+03 -2.59320972e+03 -2.62954126e+03 -2.64247266e+03 -2.53455151e+03 -2.41552295e+03 -2.37235107e+03 -2.39083667e+03 -2.41818994e+03 -2.37241235e+03 -2.24804321e+03 -2.12484497e+03 -2.06237183e+03 -2.11490674e+03 -2.17545337e+03 -2.05650488e+03 -1.89664807e+03 -1.84684167e+03 -1.86981543e+03 -1.88289014e+03 -1.82601270e+03 -1.73110925e+03 -1.66170227e+03 -1.62459094e+03 -1.57062646e+03 -1.53125867e+03 -1.50388831e+03 -1.44768384e+03 -1.40630139e+03 -1.35534460e+03 -1.27575793e+03 -1.23574902e+03 -1.22293433e+03 -1.18864539e+03 -1.13474487e+03 -1.03849255e+03 -9.67630981e+02 -9.72338806e+02 -9.64002686e+02 -8.97026672e+02 -8.22745789e+02 -7.51876526e+02 -6.93244141e+02 -6.82272034e+02 -6.69452698e+02 -6.02376099e+02 -5.21233276e+02 -4.66760559e+02 -4.34821960e+02 -3.93882721e+02 -3.43942230e+02 -2.94546997e+02 -2.42986053e+02 -1.92563828e+02 -1.42369568e+02 -9.18046722e+01 -4.54686623e+01 2.29243708e+00 5.14485703e+01 1.03804733e+02 1.50753448e+02 1.87712753e+02 2.33065979e+02 2.91593231e+02 3.52509521e+02 3.98168152e+02 4.36037384e+02 4.95559418e+02 5.50907593e+02 5.75095032e+02 6.00708313e+02 6.61299561e+02 7.45597778e+02 8.18791199e+02 8.52961304e+02 8.55223877e+02 8.71823547e+02 9.38631592e+02 1.04528577e+03 1.13000818e+03 1.14929199e+03 1.12880750e+03 1.17595105e+03 1.30363721e+03 1.34441211e+03 1.32821594e+03 1.37726685e+03 1.43691223e+03 1.48507959e+03 1.58636719e+03 1.60093213e+03 1.59309778e+03 1.67380042e+03 1.68434399e+03 1.78369897e+03 1.88324841e+03 1.82495532e+03 1.90904395e+03 2.01784436e+03 2.01980579e+03 2.05777930e+03 2.10322754e+03 2.15836377e+03 2.21854956e+03 2.25081030e+03 2.22878516e+03 2.27561108e+03 2.43617969e+03 2.54763550e+03 2.53540723e+03 2.46538306e+03 2.45425098e+03 2.56113867e+03 2.72023877e+03 2.81530103e+03 2.80448901e+03 2.71526074e+03 2.77617529e+03 2.90328906e+03 2.91376733e+03 2.96738818e+03 3.01333325e+03 3.03334814e+03 3.08102930e+03 3.25022900e+03 3.20721851e+03 3.13082837e+03 3.25483862e+03 3.22365186e+03 3.40115918e+03 3.47962598e+03 3.40204272e+03 3.61986792e+03 3.54138452e+03 3.42763354e+03 3.59718994e+03 3.57142090e+03 3.66394409e+03 3.95927417e+03 3.81407031e+03 3.63395605e+03 3.73305762e+03 3.94214648e+03 4.17425830e+03 4.10874170e+03 3.91472876e+03 3.85275635e+03 3.96994556e+03 4.20751221e+03 4.39149365e+03 4.35150977e+03 4.18371191e+03 4.17206104e+03 4.31999512e+03 4.42750732e+03 4.39869287e+03 4.38232568e+03 4.45471631e+03 4.51572168e+03 4.67372705e+03 4.71301465e+03 4.54128223e+03 4.55231836e+03 4.63042578e+03 4.69638770e+03 4.80965527e+03 4.80419629e+03 4.96169971e+03 4.92229297e+03 4.75038330e+03 4.89448926e+03 4.83489941e+03 4.99569531e+03 5.36133643e+03 5.12116650e+03 4.84319141e+03 4.98664502e+03 5.26719971e+03 5.42707471e+03 5.48196826e+03 5.21613721e+03 5.02139404e+03 5.16960205e+03 5.45558496e+03 5.71159180e+03 5.57571924e+03 5.27514014e+03 5.29131641e+03 5.48636279e+03 5.61062549e+03 5.81694580e+03 5.82447266e+03 5.49445654e+03 5.46901465e+03 5.75821191e+03 5.85658008e+03 5.68582520e+03 5.65518311e+03 5.79948584e+03 5.77289258e+03 5.97571924e+03 6.06105176e+03 5.75361963e+03 5.77144727e+03 5.97362744e+03 5.97992188e+03 6.00976172e+03 5.95498682e+03 6.11614746e+03 6.27610498e+03 6.13600586e+03 5.98917139e+03 5.88945508e+03 6.14736572e+03 6.48541943e+03 6.41964062e+03 6.10625342e+03 5.95018750e+03 6.19274219e+03 6.57464404e+03 6.41588867e+03 6.10490430e+03 6.19877441e+03 6.39127393e+03 6.56536768e+03 6.75698096e+03 6.62433252e+03 6.28267822e+03 6.12549609e+03 6.33346484e+03 6.71594043e+03 6.73263721e+03 6.49924365e+03 6.53191797e+03 6.55102295e+03 6.74324707e+03 6.67744824e+03 6.54082861e+03 6.54111377e+03 6.40348438e+03 6.72168262e+03 6.94503369e+03 6.66133691e+03 6.70502197e+03 6.76363184e+03 6.88750391e+03 6.74198877e+03 6.45784619e+03 6.74274658e+03 7.08000635e+03 6.93149561e+03 6.57458301e+03 6.67260889e+03 7.06213037e+03 7.02019580e+03 6.87372559e+03 6.90678223e+03 6.64204492e+03 6.65872900e+03 7.09709570e+03 7.07011621e+03 6.79325195e+03 6.64262793e+03 6.63368359e+03 6.94802051e+03 7.24599121e+03 6.94949268e+03 6.81228223e+03 6.95265234e+03 6.89143066e+03 7.17784473e+03 7.19658350e+03 6.75907080e+03 6.74341064e+03 6.90101709e+03 6.91937109e+03 6.95047461e+03 6.94014355e+03 7.15021289e+03 7.01552100e+03 6.79838135e+03 6.85164404e+03 6.75913281e+03 7.00807861e+03 7.42636328e+03 7.19704199e+03 6.76620654e+03 6.72495117e+03 6.94688770e+03 7.06644043e+03 7.63344482e+03 7.97342139e+03 7.42510059e+03 8.55613867e+03 1.66207305e+04 1.61790359e+05 -35459156. 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. 0. 0. 0. 0. 0. 0. -99286584. -2554518. 1.22419199e+04 1.94144453e+04 1.07023027e+04 8.55853320e+03 8.63184863e+03 6.87133838e+03 6.43444189e+03 6.57114062e+03 6.49421191e+03 6.32297266e+03 6.44796582e+03 6.39857471e+03 6.29525830e+03 6.29968896e+03 6.26369189e+03 6.24143213e+03 6.21506592e+03 6.22131836e+03 6.16801172e+03 6.01319043e+03 5.99449219e+03 6.21837500e+03 6.18385645e+03 5.91087012e+03 5.88886426e+03 6.19568408e+03 6.17017627e+03 5.96277979e+03 5.92930811e+03 5.88312646e+03 5.89054297e+03 5.85648291e+03 5.81788770e+03 5.80489551e+03 5.72711768e+03 5.62235938e+03 5.60244922e+03 5.80075293e+03 5.79172754e+03 5.60862500e+03 5.60195996e+03 5.58717773e+03 5.57461133e+03 5.51074609e+03 5.47498633e+03 5.44864648e+03 5.28386670e+03 5.25200195e+03 5.31739453e+03 5.28329883e+03 5.45036572e+03 5.44686182e+03 5.26052197e+03 5.06134912e+03 4.97307617e+03 5.29399512e+03 5.31086523e+03 5.06660742e+03 4.94565039e+03 4.97220508e+03 4.93863281e+03 4.83694580e+03 5.04479199e+03 4.98490967e+03 4.65133691e+03 4.59910596e+03 4.81210840e+03 4.95020850e+03 4.78289355e+03 4.66369580e+03 4.65464258e+03 4.56059717e+03 4.49241309e+03 4.50115820e+03 4.50167871e+03 4.44812744e+03 4.32518408e+03 4.27022021e+03 4.32096973e+03 4.28266992e+03 4.33692090e+03 4.25109131e+03 4.07376538e+03 4.11342090e+03 4.09005176e+03 4.13037891e+03 4.11056982e+03 3.98295532e+03 3.92755005e+03 3.81500562e+03 3.68717627e+03 3.82935571e+03 3.84805884e+03 3.60335889e+03 3.59486011e+03 3.76044727e+03 3.80216626e+03 3.65588989e+03 3.51004321e+03 3.45549243e+03 3.42620312e+03 3.34583301e+03 3.29830981e+03 3.32083472e+03 3.26259497e+03 3.27518506e+03 3.20078320e+03 3.09006787e+03 3.10269507e+03 2.97776611e+03 2.98495020e+03 3.10469409e+03 2.99858911e+03 2.87556494e+03 2.75678320e+03 2.70140234e+03 2.81532520e+03 2.78219189e+03 2.64299854e+03 2.53185229e+03 2.49135742e+03 2.51473608e+03 2.45852954e+03 2.48093604e+03 2.46094727e+03 2.33360767e+03 2.24515747e+03 2.20931323e+03 2.24724854e+03 2.19353882e+03 2.09499512e+03 2.01164319e+03 1.96726221e+03 1.97073645e+03 1.86985815e+03 1.84391443e+03 1.91201794e+03 1.83501184e+03 1.73735449e+03 1.63743311e+03 1.58380762e+03 1.63921387e+03 1.59458203e+03 1.49890076e+03 1.40745935e+03 1.35052637e+03 1.35369519e+03 1.30523547e+03 1.25226184e+03 1.17724634e+03 1.14974695e+03 1.15072449e+03 1.07318347e+03 1.03433911e+03 9.92090210e+02 9.22608398e+02 8.52788391e+02 8.04940796e+02 7.77383911e+02 7.28580750e+02 6.82716797e+02 6.12802429e+02 5.71637146e+02 5.60482361e+02 4.86811768e+02 4.21814148e+02 3.85623932e+02 3.37795044e+02 2.97924438e+02 2.44042877e+02 1.87688187e+02 1.46845642e+02 9.89285202e+01 4.82850266e+01 -5.89477360e-01 -4.89412651e+01 -9.65504227e+01 -1.44810425e+02 -1.96171341e+02 -2.38921158e+02 -2.91808197e+02 -3.59404053e+02 -4.02515656e+02 -4.31788239e+02 -4.63001526e+02 -5.27560913e+02 -6.12697998e+02 -6.49505066e+02 -6.80384827e+02 -7.15982483e+02 -7.56524536e+02 -8.24893921e+02 -8.74341797e+02 -9.42916382e+02 -9.75547546e+02 -9.90304443e+02 -1.06547998e+03 -1.11957141e+03 -1.18629895e+03 -1.22666418e+03 -1.24966003e+03 -1.29076501e+03 -1.33074707e+03 -1.40608325e+03 -1.42060571e+03 -1.48974170e+03 -1.62394397e+03 -1.63270325e+03 -1.63898523e+03 -1.64379761e+03 -1.67958801e+03 -1.82169653e+03 -1.88333154e+03 -1.88303076e+03 -1.86788708e+03 -1.91007922e+03 -2.02249377e+03 -2.07015454e+03 -2.16835498e+03 -2.20566724e+03 -2.19810596e+03 -2.17627026e+03 -2.21576978e+03 -2.40478931e+03 -2.43462231e+03 -2.41491553e+03 -2.42109888e+03 -2.45591138e+03 -2.63005737e+03 -2.69171631e+03 -2.60029590e+03 -2.62240820e+03 -2.80557739e+03 -2.86246143e+03 -2.76310059e+03 -2.79960596e+03 -2.99033130e+03 -3.04061938e+03 -2.99682715e+03 -2.97500146e+03 -3.00718677e+03 -3.23377881e+03 -3.25926221e+03 -3.19363477e+03 -3.22966553e+03 -3.25407251e+03 -3.35280200e+03 -3.41589331e+03 -3.43086890e+03 -3.37933496e+03 -3.49447583e+03 -3.68979688e+03 -3.64344873e+03 -3.70478784e+03 -3.78010181e+03 -3.75405591e+03 -3.79601733e+03 -3.81582764e+03 -3.83232886e+03 -3.79791187e+03 -3.82769556e+03 -3.95012769e+03 -4.01670435e+03 -4.18053223e+03 -4.09003442e+03 -4.00485474e+03 -4.17497119e+03 -4.23764258e+03 -4.37458984e+03 -4.33963477e+03 -4.27227539e+03 -4.33665918e+03 -4.32978027e+03 -4.43456250e+03 -4.49294775e+03 -4.62231787e+03 -4.61447998e+03 -4.52041895e+03 -4.58064941e+03 -4.49353223e+03 -4.68782080e+03 -5.00588916e+03 -4.90750928e+03 -4.79579883e+03 -4.72287500e+03 -4.68596875e+03 -4.95421094e+03 -5.15300049e+03 -5.05561426e+03 -4.88437500e+03 -4.90058252e+03 -5.08759863e+03 -5.09783154e+03 -5.24226855e+03 -5.22163623e+03 -5.12064062e+03 -5.22703125e+03 -5.25257666e+03 -5.43648096e+03 -5.45498682e+03 -5.20521875e+03 -5.26645996e+03 -5.57370898e+03 -5.49991992e+03 -5.25407666e+03 -5.48159766e+03 -5.79000928e+03 -5.71372412e+03 -5.59660352e+03 -5.50609082e+03 -5.52959521e+03 -5.84905566e+03 -5.86645508e+03 -5.75016846e+03 -5.62630908e+03 -5.61663867e+03 -5.83004395e+03 -5.89733105e+03 -5.87578320e+03 -5.75784570e+03 -5.92343555e+03 -6.13075146e+03 -5.99401123e+03 -6.11810303e+03 -6.06206641e+03 -5.91521973e+03 -6.07720654e+03 -6.11836426e+03 -6.16320215e+03 -6.13840479e+03 -6.08459668e+03 -5.97545361e+03 -6.18994189e+03 -6.60578955e+03 -6.26462939e+03 -5.98684375e+03 -6.18136719e+03 -6.43805908e+03 -6.63051709e+03 -6.48352100e+03 -6.29282666e+03 -6.48154834e+03 -6.49022852e+03 -6.27336768e+03 -6.19873779e+03 -6.60836133e+03 -6.61547412e+03 -6.42760547e+03 -6.46522217e+03 -6.24004053e+03 -6.49114941e+03 -6.93056299e+03 -6.72310645e+03 -6.58420752e+03 -6.41555322e+03 -6.33370020e+03 -6.72596631e+03 -7.07624756e+03 -6.90930225e+03 -6.54693311e+03 -6.51967871e+03 -6.66398340e+03 -6.76095215e+03 -6.92495117e+03 -6.76728809e+03 -6.55915479e+03 -6.82120117e+03 -6.76849609e+03 -6.94622266e+03 -6.89817529e+03 -6.67843945e+03 -6.87897510e+03 -6.89354053e+03 -6.83556494e+03 -6.65370947e+03 -6.77584668e+03 -7.13478564e+03 -7.09015625e+03 -6.79067773e+03 -6.63498730e+03 -6.80794092e+03 -7.18458252e+03 -7.14855176e+03 -6.89892383e+03 -6.73251318e+03 -6.71475000e+03 -6.90756543e+03 -6.99196631e+03 -6.95226025e+03 -6.75629053e+03 -6.91993652e+03 -7.14710449e+03 -6.95400977e+03 -7.09044043e+03 -7.10468750e+03 -6.89589648e+03 -6.92430322e+03 -6.93265234e+03 -6.93364355e+03 -6.94719434e+03 -6.88442285e+03 -6.83013574e+03 -7.14587891e+03 -7.12047314e+03 -6.75333789e+03 -6.74512598e+03 -6.88305762e+03 -7.01313477e+03 -7.31246631e+03 -7.04252197e+03 -6.64569727e+03 -6.94492383e+03 -7.26564307e+03 -7.07689014e+03 -6.74953955e+03 -6.75594385e+03 -6.82743213e+03 -6.90208496e+03 -6.90134717e+03 -6.71035498e+03 -6.85820117e+03 -7.18521240e+03 -7.01757129e+03 -6.85661914e+03 -6.67756348e+03 -6.70846387e+03 -7.10096777e+03 -6.99589404e+03 -6.80301367e+03 -6.69644385e+03 -6.42843604e+03 -6.57255469e+03 -6.93829785e+03 -7.19505957e+03 -6.77350684e+03 -6.46166064e+03 -6.64090186e+03 -6.73622656e+03 -6.96875391e+03 -6.83491895e+03 -6.55426172e+03 -6.69602197e+03 -6.66750977e+03 -6.55187451e+03 -6.43756104e+03 -6.55824365e+03 -6.81110352e+03 -6.68616553e+03 -6.56177734e+03 -6.45345801e+03 -6.40012744e+03 -6.68854688e+03 -6.68282275e+03 -6.50414697e+03 -6.30851709e+03 -6.21381885e+03 -6.37687500e+03 -6.36567773e+03 -6.56994434e+03 -6.60825684e+03 -6.27732031e+03 -6.09910059e+03 -6.30793994e+03 -6.55388770e+03 -6.33943701e+03 -6.17924512e+03 -6.15874561e+03 -6.15046143e+03 -6.09199707e+03 -5.93942480e+03 -6.16556348e+03 -6.23089551e+03 -6.02360303e+03 -6.14666357e+03 -6.18767334e+03 -6.07324805e+03 -6.04487744e+03 -5.97000586e+03 -5.93307080e+03 -5.77062842e+03 -5.66953223e+03 -5.89712207e+03 -6.00608398e+03 -5.75157520e+03 -5.48708350e+03 -5.64577441e+03 -5.95680566e+03 -5.94907178e+03 -5.59399023e+03 -5.36902734e+03 -5.64121338e+03 -5.81025830e+03 -5.63406885e+03 -5.56826416e+03 -5.37152246e+03 -5.13697021e+03 -5.32377393e+03 -5.61123584e+03 -5.59977783e+03 -5.25878711e+03 -5.03366113e+03 -5.31932324e+03 -5.50980762e+03 -5.31157031e+03 -5.01750146e+03 -4.87295801e+03 -5.01128857e+03 -5.06336621e+03 -5.15942676e+03 -5.20001758e+03 -4.98827148e+03 -4.84785791e+03 -4.82057422e+03 -4.98738770e+03 -4.85387939e+03 -4.67776123e+03 -4.83293018e+03 -4.78918457e+03 -4.71957520e+03 -4.56723779e+03 -4.51969092e+03 -4.74726514e+03 -4.56954443e+03 -4.30894580e+03 -4.37434961e+03 -4.52564990e+03 -4.50141748e+03 -4.36167334e+03 -4.41645996e+03 -4.40755176e+03 -4.26007520e+03 -4.10697070e+03 -4.03847412e+03 -4.22598779e+03 -4.11184229e+03 -3.94777075e+03 -4.03706177e+03 -3.98668652e+03 -3.91517163e+03 -3.83663696e+03 -3.87916895e+03 -3.87777759e+03 -3.73803003e+03 -3.74851294e+03 -3.72594775e+03 -3.70245264e+03 -3.65446753e+03 -3.57400977e+03 -3.46842456e+03 -3.32931323e+03 -3.30560571e+03 -3.44160669e+03 -3.56368311e+03 -3.32716943e+03 -3.07704102e+03 -3.16264917e+03 -3.30832397e+03 -3.29378052e+03 -3.07624487e+03 -2.90017090e+03 -3.01330054e+03 -3.02964478e+03 -2.89162256e+03 -2.96240625e+03 -2.85744189e+03 -2.65506348e+03 -2.68621411e+03 -2.79513843e+03 -2.75684326e+03 -2.56990063e+03 -2.42828979e+03 -2.49632178e+03 -2.61081226e+03 -2.49868140e+03 -2.32322607e+03 -2.22120776e+03 -2.28688623e+03 -2.32611035e+03 -2.20942651e+03 -2.13302441e+03 -2.09508984e+03 -2.06530029e+03 -2.01198572e+03 -2.01244104e+03 -1.93363538e+03 -1.81680603e+03 -1.81213721e+03 -1.78410510e+03 -1.77529443e+03 -1.68233496e+03 -1.59169165e+03 -1.61729199e+03 -1.52255725e+03 -1.43665857e+03 -1.45248438e+03 -1.43052588e+03 -1.37799304e+03 -1.30652722e+03 -1.29317517e+03 -1.25014990e+03 -1.14817981e+03 -1.07207092e+03 -1.03016504e+03 -1.05645776e+03 -9.81149170e+02 -8.87952148e+02 -1.00033698e+03 -1.35038953e+03 -4.80988916e+03 -278286944. 0. 0. 0. 0. 0. 0. 0. 0. 263891712. -6.62446562e+04 -6.62446562e+04 -2.91143757e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -432891424. 8.82789125e+05 2.64674756e+03 1.37485706e+03 8.79393616e+02 7.64877808e+02 7.77234192e+02 7.86933777e+02 8.62010986e+02 9.16401978e+02 9.52455078e+02 1.00326691e+03 1.03993298e+03 1.05526221e+03 1.13360315e+03 1.22391565e+03 1.23385669e+03 1.26685510e+03 1.34109985e+03 1.40581042e+03 1.46325476e+03 1.46693335e+03 1.47222253e+03 1.55098267e+03 1.64218799e+03 1.69501062e+03 1.72480762e+03 1.73838440e+03 1.79526013e+03 1.90679883e+03 1.98906580e+03 1.97831580e+03 1.94123157e+03 2.01097888e+03 2.12651587e+03 2.15362817e+03 2.19562109e+03 2.25640796e+03 2.23852979e+03 2.32757446e+03 2.43311035e+03 2.38499780e+03 2.41695752e+03 2.54228223e+03 2.69096704e+03 2.75336963e+03 2.60779736e+03 2.56560327e+03 2.68604785e+03 2.84315308e+03 2.93858911e+03 2.86375830e+03 2.89822876e+03 3.04101172e+03 3.05288135e+03 3.09295923e+03 3.09409180e+03 3.04267041e+03 3.19652417e+03 3.34814697e+03 3.27619214e+03 3.30521045e+03 3.41770312e+03 3.39601855e+03 3.50237402e+03 3.58007056e+03 3.49788452e+03 3.50998535e+03 3.63000635e+03 3.79840967e+03 3.82124170e+03 3.70811450e+03 3.78028735e+03 3.81287207e+03 3.89715137e+03 4.03794873e+03 3.92378052e+03 3.92315649e+03 4.07116162e+03 4.20431787e+03 4.25637402e+03 4.15168555e+03 4.06503369e+03 4.15719873e+03 4.32486328e+03 4.41784766e+03 4.45928857e+03 4.41396875e+03 4.40164014e+03 4.53623340e+03 4.65945752e+03 4.57388867e+03 4.45891943e+03 4.57703613e+03 4.76953369e+03 4.85275195e+03 4.79424561e+03 4.70135938e+03 4.69072070e+03 4.89098389e+03 5.00831104e+03 4.87928223e+03 4.90500635e+03 5.08676660e+03 5.23603809e+03 5.25710693e+03 5.00905908e+03 4.92144629e+03 5.14302930e+03 5.26348389e+03 5.27940234e+03 5.26090918e+03 5.33528418e+03 5.46181201e+03 5.36648633e+03 5.37747607e+03 5.51374121e+03 5.44380420e+03 5.41243750e+03 5.59466699e+03 5.67072217e+03 5.70130322e+03 5.64380176e+03 5.51142871e+03 5.57444043e+03 5.78586182e+03 5.88501270e+03 5.80930859e+03 5.73929834e+03 5.80877588e+03 5.99404346e+03 6.07998438e+03 5.90794141e+03 5.73393555e+03 5.84618018e+03 6.05893457e+03 6.10766992e+03 6.05506934e+03 6.02703613e+03 6.06530029e+03 6.21551367e+03 6.29364502e+03 6.21009180e+03 6.20108496e+03 6.15198730e+03 6.24669824e+03 6.24668359e+03 6.20006299e+03 6.29098145e+03 6.34676367e+03 6.48312109e+03 6.59956543e+03 6.38028076e+03 6.26197705e+03 6.38098975e+03 6.52414014e+03 6.63550146e+03 6.60329932e+03 6.33404834e+03 6.37501074e+03 6.68614990e+03 6.86703760e+03 6.61584277e+03 6.41719336e+03 6.53520020e+03 6.79628174e+03 6.79528809e+03 6.47754883e+03 6.50847363e+03 6.77355518e+03 6.81873242e+03 6.71987354e+03 6.84489014e+03 6.86462256e+03 6.61249219e+03 6.80756348e+03 7.01800342e+03 6.73566943e+03 6.72573877e+03 6.85942773e+03 6.97777100e+03 7.04200342e+03 6.90909082e+03 6.65379297e+03 6.72856348e+03 7.00207080e+03 7.23319434e+03 7.20164551e+03 6.82270752e+03 6.87686816e+03 7.17075098e+03 7.07329736e+03 6.79238721e+03 6.82698486e+03 6.97334521e+03 7.15697998e+03 7.23137354e+03 7.18257080e+03 6.96967334e+03 6.80637305e+03 7.03532959e+03 7.20150586e+03 6.98923193e+03 7.01133301e+03 7.15896826e+03 7.22430957e+03 7.27985986e+03 7.03856494e+03 6.83904736e+03 6.96829150e+03 7.05944043e+03 7.29861230e+03 7.30051172e+03 6.96786426e+03 6.94704443e+03 7.14713135e+03 7.24407324e+03 7.21221240e+03 6.95639697e+03 6.97475293e+03 7.18327246e+03 7.22345996e+03 7.17140820e+03 6.99444531e+03 6.91481250e+03 7.07672559e+03 7.25968213e+03 7.04439355e+03 7.06205908e+03 7.16210254e+03 7.16616748e+03 7.25027637e+03 7.02278418e+03 6.85744824e+03 6.99846387e+03 7.04676660e+03 7.12937646e+03 6.93418994e+03 6.78047314e+03 7.03166211e+03 7.23163525e+03 7.10058057e+03 6.94813477e+03 6.97120312e+03 6.85487256e+03 6.87326611e+03 7.02403125e+03 7.24508447e+03 6.99358594e+03 6.77798828e+03 6.96439697e+03 6.87015771e+03 6.93182666e+03 6.88110742e+03 6.68522900e+03 6.82310254e+03 6.97501465e+03 6.69388379e+03 6.62940723e+03 6.73828076e+03 6.92896533e+03 6.97642578e+03 6.61457080e+03 6.54514307e+03 6.71156494e+03 6.75541406e+03 6.84159473e+03 6.59693066e+03 6.58599170e+03 6.50836572e+03 6.53418750e+03 6.74048242e+03 6.63773877e+03 6.39380762e+03 6.50054053e+03 6.70270801e+03 6.46510498e+03 6.37741357e+03 6.32372754e+03 6.29717188e+03 6.51513232e+03 6.58113330e+03 6.36009180e+03 6.21302881e+03 6.28308008e+03 6.37433984e+03 6.43672412e+03 6.21680957e+03 6.29075732e+03 6.31177490e+03 6.00622803e+03 6.04778320e+03 6.08595312e+03 6.07015039e+03 6.16047949e+03 6.05319922e+03 6.01239160e+03 6.13378223e+03 5.96894189e+03 5.82016064e+03 5.92088232e+03 5.99746484e+03 5.95131348e+03 5.72157959e+03 5.65236377e+03 5.89430225e+03 5.95057715e+03 5.67169287e+03 5.55389014e+03 5.61501807e+03 5.72726416e+03 5.75853027e+03 5.51480127e+03 5.48230762e+03 5.43499316e+03 5.50992578e+03 5.56916162e+03 5.33991455e+03 5.33272119e+03 5.34210107e+03 5.28183887e+03 5.32504492e+03 5.38343994e+03 5.20501123e+03 5.03229590e+03 5.25826807e+03 5.38405078e+03 5.05377490e+03 4.83036230e+03 4.90661475e+03 5.05738525e+03 5.01737305e+03 4.86888379e+03 4.78295068e+03 4.79554053e+03 4.89225293e+03 4.86435938e+03 4.69023291e+03 4.64014648e+03 4.61106250e+03 4.66757812e+03 4.63524902e+03 4.46033350e+03 4.47756152e+03 4.43466797e+03 4.38881006e+03 4.42580176e+03 4.38736426e+03 4.26092529e+03 4.18742383e+03 4.25727881e+03 4.23644043e+03 4.12223975e+03 4.03403198e+03 4.01933740e+03 4.06678076e+03 4.02839087e+03 3.85020703e+03 3.81581128e+03 3.84250049e+03 3.91380249e+03 3.88201025e+03 3.69349634e+03 3.73792065e+03 3.65760132e+03 3.48507397e+03 3.47427612e+03 3.48209277e+03 3.56104321e+03 3.48975635e+03 3.29154272e+03 3.21792065e+03 3.27847681e+03 3.33691479e+03 3.27783252e+03 3.18849512e+03 3.11277295e+03 3.03778784e+03 2.96718530e+03 2.91448193e+03 2.96666943e+03 2.95566650e+03 2.80245703e+03 2.76203687e+03 2.73691333e+03 2.71330566e+03 2.70838794e+03 2.64091260e+03 2.63368823e+03 2.52757837e+03 2.38773755e+03 2.36038452e+03 2.38975146e+03 2.40336084e+03 2.36263745e+03 2.25339307e+03 2.10403271e+03 2.09392847e+03 2.09951440e+03 2.04432727e+03 2.05532520e+03 1.99207715e+03 1.86611157e+03 1.87744446e+03 1.83628418e+03 1.74906567e+03 1.72675110e+03 1.66082788e+03 1.58962634e+03 1.53880103e+03 1.50774292e+03 1.47013293e+03 1.46239392e+03 1.44920081e+03 1.33666675e+03 1.23588770e+03 1.19545251e+03 1.17702441e+03 1.16453186e+03 1.11067444e+03 1.01344214e+03 9.54123657e+02 9.29521362e+02 9.06949036e+02 8.64973877e+02 7.92710938e+02 7.37686157e+02 6.88262085e+02 6.34978699e+02 5.82240479e+02 5.45063965e+02 5.02455414e+02 4.47822296e+02 4.00457336e+02 3.38785797e+02 2.89549255e+02 2.48117508e+02 1.98573318e+02 1.50364700e+02 9.73608322e+01 4.62572975e+01 -2.48820210e+00 -5.24008026e+01 -1.04069351e+02 -1.55249527e+02 -2.00718979e+02 -2.40071762e+02 -2.94822113e+02 -3.49380829e+02 -3.92262177e+02 -4.52366913e+02 -5.09575439e+02 -5.43224548e+02 -5.87306885e+02 -6.42829773e+02 -7.05132202e+02 -7.61603333e+02 -8.01952698e+02 -8.51969055e+02 -8.69642761e+02 -9.13215210e+02 -9.91608643e+02 -1.05173425e+03 -1.11684729e+03 -1.16001819e+03 -1.17909082e+03 -1.20316089e+03 -1.27735876e+03 -1.36908838e+03 -1.40517505e+03 -1.43279138e+03 -1.47847571e+03 -1.50048145e+03 -1.55906799e+03 -1.63963220e+03 -1.68032263e+03 -1.73654504e+03 -1.76335413e+03 -1.78714673e+03 -1.84017297e+03 -1.93556641e+03 -1.98883740e+03 -2.01686975e+03 -2.08719263e+03 -2.07274170e+03 -2.13782324e+03 -2.22066528e+03 -2.24258569e+03 -2.35071411e+03 -2.36065894e+03 -2.32724121e+03 -2.38068213e+03 -2.43127539e+03 -2.54443433e+03 -2.70740674e+03 -2.68978979e+03 -2.61384448e+03 -2.65303589e+03 -2.70404419e+03 -2.74315771e+03 -2.87682910e+03 -2.96052881e+03 -2.91466016e+03 -2.94363501e+03 -2.97681226e+03 -3.07000684e+03 -3.19656592e+03 -3.19587183e+03 -3.32159497e+03 -3.28547046e+03 -3.14947876e+03 -3.24984888e+03 -3.40880713e+03 -3.50531494e+03 -3.58618896e+03 -3.51465527e+03 -3.38241919e+03 -3.54398315e+03 -3.75996143e+03 -3.73668848e+03 -3.73097314e+03 -3.76012744e+03 -3.73280518e+03 -3.85714868e+03 -3.92321216e+03 -3.90428027e+03 -4.08473706e+03 -4.06343286e+03 -4.02829858e+03 -4.09741211e+03 -4.03866040e+03 -4.12161914e+03 -4.27283545e+03 -4.42761621e+03 -4.35181201e+03 -4.15496338e+03 -4.24939795e+03 -4.44464697e+03 -4.55816797e+03 -4.55876709e+03 -4.46635107e+03 -4.45333105e+03 -4.57940186e+03 -4.71581104e+03 -4.78052539e+03 -4.78669385e+03 -4.78004248e+03 -4.77733789e+03 -4.81477832e+03 -4.84451074e+03 -4.88242773e+03 -4.97471240e+03 -5.01213477e+03 -5.08199072e+03 -4.99487939e+03 -4.98501172e+03 -5.17408643e+03 -5.18625879e+03 -5.34215283e+03 -5.27918457e+03 -5.06493115e+03 -5.14560547e+03 -5.31365576e+03 -5.50515088e+03 -5.60755908e+03 -5.41567773e+03 -5.29119629e+03 -5.39594287e+03 -5.52225293e+03 -5.57467139e+03 -5.62264355e+03 -5.65653320e+03 -5.55250537e+03 -5.50943115e+03 -5.63531445e+03 -5.78648291e+03 -5.90717236e+03 -5.84957031e+03 -5.91387109e+03 -5.79450879e+03 -5.62969775e+03 -5.80078711e+03 -5.94898682e+03 -6.11553027e+03 -6.13494678e+03 -5.86263379e+03 -5.79416113e+03 -6.01275928e+03 -6.29958740e+03 -6.22847949e+03 -6.16319238e+03 -6.13259521e+03 -5.99256250e+03 -6.19342676e+03 -6.37146826e+03 -6.25794727e+03 -6.27305176e+03 -6.29106543e+03 -6.32915576e+03 -6.34960547e+03 -6.37620947e+03 -6.45521680e+03 -6.47220898e+03 -6.45127295e+03 -6.32984375e+03 -6.42367676e+03 -6.50434912e+03 -6.52766016e+03 -6.79006543e+03 -6.62243359e+03 -6.40042627e+03 -6.51170312e+03 -6.43654541e+03 -6.68734570e+03 -6.99644775e+03 -6.86966553e+03 -6.51100781e+03 -6.47197363e+03 -6.76269482e+03 -6.88905762e+03 -6.76468652e+03 -7.15863818e+03 -7.49419922e+03 -9.20158008e+03 -1.03443594e+04 -1.79733770e+04 -6.99361641e+04 38653256. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -59734588. -1.03065508e+05 -2.06793477e+04 -1.38177119e+04 -9.56430469e+03 -8.71972559e+03 -7.45895605e+03 -7.33872754e+03 -7.30347510e+03 -7.24594336e+03 -6.87395459e+03 -7.03237695e+03 -7.40807812e+03 -7.38523877e+03 -7.00312695e+03 -6.72635889e+03 -6.83604443e+03 -7.23084326e+03 -7.43787256e+03 -7.16028125e+03 -6.91384180e+03 -6.81155957e+03 -6.91439111e+03 -7.26672949e+03 -7.24963623e+03 -6.93839502e+03 -6.83880127e+03 -6.85785498e+03 -6.95307227e+03 -6.96580176e+03 -6.84113574e+03 -6.88722266e+03 -7.11318506e+03 -7.23419922e+03 -6.89170410e+03 -6.54200781e+03 -6.70354395e+03 -7.02512109e+03 -7.24015918e+03 -6.93722461e+03 -6.58174414e+03 -6.56701514e+03 -6.92155176e+03 -7.15467871e+03 -6.90653418e+03 -6.47371582e+03 -6.49247461e+03 -6.76435938e+03 -6.93010254e+03 -6.92700439e+03 -6.76500342e+03 -6.56769727e+03 -6.53648389e+03 -6.74847656e+03 -6.51675537e+03 -6.41650049e+03 -6.73288574e+03 -6.72974658e+03 -6.67657471e+03 -6.41371143e+03 -6.17946924e+03 -6.50474902e+03 -6.86363037e+03 -6.65861914e+03 -6.24289648e+03 -6.04778027e+03 -6.14422559e+03 -6.49869385e+03 -6.68916846e+03 -6.46957422e+03 -6.32277832e+03 -6.20733887e+03 -6.02318652e+03 -6.16839355e+03 -6.35178809e+03 -6.13050098e+03 -6.08836523e+03 -6.11358740e+03 -6.15534766e+03 -5.99891016e+03 -5.90416846e+03 -6.07454834e+03 -6.16760498e+03 -6.12941064e+03 -5.93081592e+03 -5.65699072e+03 -5.65947559e+03 -5.95786182e+03 -6.18852051e+03 -5.89863477e+03 -5.50766504e+03 -5.55101172e+03 -5.72662988e+03 -5.85524902e+03 -5.85777539e+03 -5.61327295e+03 -5.52610254e+03 -5.50846924e+03 -5.55443115e+03 -5.60261426e+03 -5.47301562e+03 -5.41007373e+03 -5.36480371e+03 -5.38996875e+03 -5.37383984e+03 -5.26577148e+03 -5.30354688e+03 -5.32812158e+03 -5.35682080e+03 -5.17707324e+03 -4.91875244e+03 -4.98855420e+03 -5.20921924e+03 -5.28922314e+03 -5.01681055e+03 -4.73512354e+03 -4.72175146e+03 -4.96863135e+03 -5.19862939e+03 -4.92456982e+03 -4.63230664e+03 -4.69267383e+03 -4.65670361e+03 -4.65741846e+03 -4.67306787e+03 -4.57005518e+03 -4.61491064e+03 -4.53980029e+03 -4.47877539e+03 -4.45035986e+03 -4.30714990e+03 -4.38025879e+03 -4.50483984e+03 -4.43673145e+03 -4.23687598e+03 -4.07645337e+03 -4.04704297e+03 -4.17036670e+03 -4.30836865e+03 -4.09587402e+03 -3.83572510e+03 -3.86093091e+03 -4.01445117e+03 -4.08917944e+03 -3.89286060e+03 -3.74615747e+03 -3.73095190e+03 -3.67664966e+03 -3.70932031e+03 -3.70653125e+03 -3.51232788e+03 -3.45697363e+03 -3.53472266e+03 -3.54630200e+03 -3.46019189e+03 -3.33499414e+03 -3.31268799e+03 -3.31822461e+03 -3.36139233e+03 -3.24823462e+03 -3.02356445e+03 -3.02938354e+03 -3.08895581e+03 -3.08522290e+03 -3.02918140e+03 -2.88764160e+03 -2.82459741e+03 -2.82707031e+03 -2.85302783e+03 -2.79682666e+03 -2.67565552e+03 -2.66149707e+03 -2.63274561e+03 -2.58322876e+03 -2.51551050e+03 -2.42543604e+03 -2.42153223e+03 -2.44893481e+03 -2.43376758e+03 -2.29900928e+03 -2.14638574e+03 -2.12495947e+03 -2.17827930e+03 -2.20922583e+03 -2.07754541e+03 -1.92479407e+03 -1.90270374e+03 -1.90638037e+03 -1.90246118e+03 -1.86477759e+03 -1.75122925e+03 -1.68442603e+03 -1.66494507e+03 -1.63339392e+03 -1.58709558e+03 -1.52605835e+03 -1.47884326e+03 -1.41405859e+03 -1.38091187e+03 -1.33827771e+03 -1.27139648e+03 -1.23390674e+03 -1.19181982e+03 -1.15334131e+03 -1.06243579e+03 -9.91356995e+02 -9.87255249e+02 -9.73850342e+02 -9.28398682e+02 -8.41975891e+02 -7.57842773e+02 -7.13098389e+02 -7.03605103e+02 -6.85059143e+02 -6.14556030e+02 -5.37298950e+02 -4.77286865e+02 -4.31039001e+02 -3.98981903e+02 -3.59092285e+02 -3.03176575e+02 -2.47884140e+02 -1.96534088e+02 -1.46161377e+02 -9.46343384e+01 -4.65694733e+01 2.17322350e+00 5.20429611e+01 1.04253708e+02 1.53046997e+02 1.90502075e+02 2.42585693e+02 3.02029449e+02 3.53086182e+02 4.03693726e+02 4.48557495e+02 5.06265747e+02 5.60216125e+02 5.86995422e+02 6.14130493e+02 6.74266174e+02 7.61242676e+02 8.36902954e+02 8.71243530e+02 8.73040955e+02 8.94201355e+02 9.61874634e+02 1.06465991e+03 1.14483081e+03 1.17216882e+03 1.15573218e+03 1.20071558e+03 1.32695947e+03 1.37273193e+03 1.35200916e+03 1.39611353e+03 1.47742896e+03 1.52624426e+03 1.62113953e+03 1.63269592e+03 1.62263574e+03 1.71106140e+03 1.72158936e+03 1.81371143e+03 1.92356519e+03 1.87156165e+03 1.94620178e+03 2.06077246e+03 2.06607983e+03 2.10480151e+03 2.13850684e+03 2.20146997e+03 2.27988037e+03 2.29507373e+03 2.26258447e+03 2.33331177e+03 2.49491040e+03 2.58514160e+03 2.57864209e+03 2.53054565e+03 2.51561108e+03 2.60498193e+03 2.76994116e+03 2.88064453e+03 2.88016406e+03 2.77339380e+03 2.81706909e+03 2.97849683e+03 2.99720605e+03 3.00931421e+03 3.05946118e+03 3.10260327e+03 3.14576392e+03 3.30769849e+03 3.28384937e+03 3.19997412e+03 3.30320142e+03 3.27242603e+03 3.45565283e+03 3.59021143e+03 3.49307935e+03 3.66610083e+03 3.62749390e+03 3.51214282e+03 3.66334229e+03 3.64263867e+03 3.75432031e+03 4.03726123e+03 3.87962036e+03 3.72026807e+03 3.83638477e+03 4.02505127e+03 4.23190430e+03 4.17139600e+03 4.00336499e+03 3.92853857e+03 4.02891382e+03 4.30564111e+03 4.51325195e+03 4.44267188e+03 4.25388477e+03 4.24513525e+03 4.44706250e+03 4.55147119e+03 4.44681982e+03 4.43616357e+03 4.55562842e+03 4.61314014e+03 4.76699902e+03 4.81573877e+03 4.67076025e+03 4.69182080e+03 4.69971973e+03 4.76249121e+03 4.90796094e+03 4.90491309e+03 5.07097705e+03 5.01884570e+03 4.85108691e+03 5.00871582e+03 4.93250586e+03 5.10596338e+03 5.47361426e+03 5.22384961e+03 4.91640234e+03 5.05844336e+03 5.38275391e+03 5.54166797e+03 5.58440723e+03 5.35627441e+03 5.14705908e+03 5.26183057e+03 5.57570264e+03 5.88894434e+03 5.70715332e+03 5.38579590e+03 5.35642139e+03 5.58079492e+03 5.75247754e+03 5.92990039e+03 5.92407812e+03 5.62129541e+03 5.58412842e+03 5.81993262e+03 5.95402734e+03 5.90883740e+03 5.90152930e+03 5.84082910e+03 5.83853613e+03 6.11404346e+03 6.18099463e+03 5.89267969e+03 5.90597852e+03 6.09124023e+03 6.09723828e+03 6.15597266e+03 6.11999756e+03 6.28179785e+03 6.35830957e+03 6.18051660e+03 6.09401855e+03 6.06566553e+03 6.30075928e+03 6.63745557e+03 6.53955469e+03 6.24108789e+03 6.08097461e+03 6.36126611e+03 6.73377197e+03 6.48571289e+03 6.19488330e+03 6.33669922e+03 6.51588330e+03 6.67856445e+03 6.88758301e+03 6.81299365e+03 6.42795020e+03 6.26758936e+03 6.50202441e+03 6.87801562e+03 6.89833887e+03 6.68090625e+03 6.61912646e+03 6.67988281e+03 6.82294873e+03 6.75682520e+03 6.61764551e+03 6.64298096e+03 6.59643066e+03 6.87324219e+03 7.10177588e+03 6.81112109e+03 6.82942676e+03 6.90426514e+03 7.07005273e+03 6.89553076e+03 6.58192529e+03 6.93204492e+03 7.32104053e+03 7.02365576e+03 6.67804541e+03 6.85808350e+03 7.25137695e+03 7.18993066e+03 7.01197168e+03 7.05131689e+03 6.80741309e+03 6.80377002e+03 7.21267285e+03 7.19166162e+03 6.93670996e+03 6.78643457e+03 6.77697217e+03 7.10675195e+03 7.41488867e+03 7.14992090e+03 6.94536914e+03 7.05263672e+03 7.06841455e+03 7.35214502e+03 7.35041455e+03 6.92568750e+03 6.89015430e+03 7.02653320e+03 7.09575391e+03 7.15959424e+03 7.14243164e+03 7.28577051e+03 7.22097461e+03 6.98867334e+03 6.95038379e+03 6.84502295e+03 7.11282666e+03 7.55412305e+03 7.35554785e+03 6.93456348e+03 6.87745312e+03 7.11230859e+03 7.16687695e+03 7.90474658e+03 8.17160352e+03 7.41129248e+03 9.12690820e+03 1.48466367e+04 1.56483938e+05 -35459156. 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. 0. 0. 0. 0. 0. 0. 21068432. 2.24740176e+04 6.61003418e+03 9.16948047e+03 7.14927930e+03 6.93711475e+03 6.75155078e+03 6.49505469e+03 6.41729492e+03 6.65317383e+03 6.67189307e+03 6.50609277e+03 6.54766504e+03 6.50644043e+03 6.43898340e+03 6.46125684e+03 6.41429395e+03 6.35572363e+03 6.35696826e+03 6.36625049e+03 6.29210840e+03 6.11879736e+03 6.06697510e+03 6.36636719e+03 6.35888428e+03 6.00940674e+03 5.97112207e+03 6.29118799e+03 6.30596045e+03 6.10374365e+03 6.05972900e+03 6.03608545e+03 5.99874121e+03 5.96746826e+03 5.93702930e+03 5.90936035e+03 5.87508984e+03 5.74246631e+03 5.69127002e+03 5.93215820e+03 5.92573682e+03 5.73129736e+03 5.71120166e+03 5.67813037e+03 5.66211230e+03 5.62690381e+03 5.56345654e+03 5.57848340e+03 5.38939600e+03 5.32391455e+03 5.46906641e+03 5.41944238e+03 5.55240234e+03 5.57640332e+03 5.34544141e+03 5.16160059e+03 5.11193457e+03 5.40338428e+03 5.42781445e+03 5.17318896e+03 5.06425781e+03 5.08661133e+03 5.08144043e+03 4.99573535e+03 5.10317139e+03 5.06316602e+03 4.77306592e+03 4.70408936e+03 4.92056836e+03 5.01317334e+03 4.84371436e+03 4.74971680e+03 4.73373682e+03 4.67458154e+03 4.56084033e+03 4.53421777e+03 4.59905322e+03 4.56071631e+03 4.43426953e+03 4.39732812e+03 4.41200098e+03 4.35673975e+03 4.43595752e+03 4.37753613e+03 4.19579199e+03 4.22579883e+03 4.18057715e+03 4.18404492e+03 4.17184521e+03 4.05424927e+03 4.00993506e+03 3.90685425e+03 3.80634863e+03 3.92260400e+03 3.88724609e+03 3.65398657e+03 3.66738940e+03 3.84358643e+03 3.90269141e+03 3.73188257e+03 3.59884253e+03 3.49152271e+03 3.44173535e+03 3.43562207e+03 3.38642920e+03 3.38942871e+03 3.33796899e+03 3.34784277e+03 3.28418091e+03 3.16271362e+03 3.17507764e+03 3.04508813e+03 3.00866455e+03 3.13928516e+03 3.06031738e+03 2.93637524e+03 2.82444067e+03 2.76406348e+03 2.87253027e+03 2.83838770e+03 2.69613916e+03 2.58440356e+03 2.54316455e+03 2.56993652e+03 2.51597900e+03 2.53547925e+03 2.51039380e+03 2.38759058e+03 2.31236548e+03 2.27325464e+03 2.27730859e+03 2.22047241e+03 2.14071167e+03 2.06331714e+03 2.02055688e+03 2.02111377e+03 1.91569031e+03 1.86809241e+03 1.92642334e+03 1.86884888e+03 1.77479175e+03 1.66907239e+03 1.61805042e+03 1.67297766e+03 1.62109387e+03 1.53064575e+03 1.44050134e+03 1.38280957e+03 1.38284790e+03 1.32867993e+03 1.27932031e+03 1.20623975e+03 1.17822949e+03 1.18363696e+03 1.10413965e+03 1.04653601e+03 1.00063245e+03 9.43072693e+02 8.80295410e+02 8.27453613e+02 7.92317688e+02 7.45679138e+02 6.98053223e+02 6.24990112e+02 5.78694092e+02 5.67585266e+02 4.96877441e+02 4.29897430e+02 3.92991486e+02 3.44943756e+02 3.05459015e+02 2.49062576e+02 1.90881088e+02 1.50523087e+02 1.01340988e+02 4.90208359e+01 -7.29663968e-01 -4.96423454e+01 -9.97276917e+01 -1.49837357e+02 -2.00566803e+02 -2.43965286e+02 -2.98155243e+02 -3.65038513e+02 -4.09476776e+02 -4.45220886e+02 -4.78416901e+02 -5.34058289e+02 -6.19337524e+02 -6.64447205e+02 -6.95666504e+02 -7.30926636e+02 -7.72907104e+02 -8.39978943e+02 -8.91509521e+02 -9.66093872e+02 -9.95173340e+02 -1.01080560e+03 -1.08751855e+03 -1.14207593e+03 -1.21254944e+03 -1.24367859e+03 -1.26204138e+03 -1.32657581e+03 -1.37073596e+03 -1.43398328e+03 -1.44598755e+03 -1.52201685e+03 -1.66603137e+03 -1.66376538e+03 -1.67227014e+03 -1.68033484e+03 -1.70830261e+03 -1.86178552e+03 -1.93117651e+03 -1.92266357e+03 -1.90419519e+03 -1.94755566e+03 -2.06451001e+03 -2.11007617e+03 -2.21204858e+03 -2.24926855e+03 -2.24425000e+03 -2.22994360e+03 -2.25963574e+03 -2.45136035e+03 -2.47638940e+03 -2.45133740e+03 -2.48238452e+03 -2.52177930e+03 -2.68382788e+03 -2.73972510e+03 -2.65471948e+03 -2.67809009e+03 -2.85228638e+03 -2.92774756e+03 -2.82793335e+03 -2.85583301e+03 -3.04917139e+03 -3.10493457e+03 -3.06491382e+03 -3.04981982e+03 -3.08010181e+03 -3.28926733e+03 -3.29738354e+03 -3.23419653e+03 -3.31005127e+03 -3.34965576e+03 -3.47633813e+03 -3.51535181e+03 -3.46133960e+03 -3.41162158e+03 -3.56883374e+03 -3.82170215e+03 -3.75008301e+03 -3.73381396e+03 -3.82177246e+03 -3.83136670e+03 -3.87242603e+03 -3.90072534e+03 -3.91671729e+03 -3.87500098e+03 -3.89255005e+03 -4.03179639e+03 -4.12029883e+03 -4.27036865e+03 -4.18886572e+03 -4.07477637e+03 -4.22605615e+03 -4.35204395e+03 -4.49491943e+03 -4.43821143e+03 -4.35415283e+03 -4.41772119e+03 -4.42262646e+03 -4.51755029e+03 -4.57410547e+03 -4.71623340e+03 -4.73829785e+03 -4.65239258e+03 -4.64208545e+03 -4.55745508e+03 -4.76929199e+03 -5.10866553e+03 -5.01944092e+03 -4.91498682e+03 -4.83157471e+03 -4.74739648e+03 -5.02061182e+03 -5.29334229e+03 -5.18730713e+03 -4.98705713e+03 -4.98898242e+03 -5.16877539e+03 -5.22055762e+03 -5.38173340e+03 -5.39277393e+03 -5.27751123e+03 -5.27542529e+03 -5.30073535e+03 -5.54979688e+03 -5.57091846e+03 -5.31974463e+03 -5.36341602e+03 -5.69410693e+03 -5.63802344e+03 -5.41313477e+03 -5.54928760e+03 -5.88830713e+03 -5.82829248e+03 -5.70714062e+03 -5.61801904e+03 -5.64337354e+03 -5.97117188e+03 -6.00664551e+03 -5.89297266e+03 -5.75567432e+03 -5.72360986e+03 -5.94750195e+03 -6.00892969e+03 -5.99170215e+03 -5.87063525e+03 -6.03626660e+03 -6.29116357e+03 -6.11967480e+03 -6.27141895e+03 -6.25471729e+03 -6.07959863e+03 -6.20718506e+03 -6.26607471e+03 -6.26706055e+03 -6.25651709e+03 -6.16051025e+03 -6.06111035e+03 -6.33577588e+03 -6.75047559e+03 -6.43018213e+03 -6.12412939e+03 -6.35648486e+03 -6.49288672e+03 -6.70895996e+03 -6.57635693e+03 -6.37749414e+03 -6.66525537e+03 -6.68344092e+03 -6.39808740e+03 -6.33573926e+03 -6.73015234e+03 -6.79492578e+03 -6.62813232e+03 -6.53081543e+03 -6.29240674e+03 -6.63735059e+03 -7.14040479e+03 -6.89857373e+03 -6.71045850e+03 -6.55918164e+03 -6.42565869e+03 -6.81954932e+03 -7.19752783e+03 -7.03063867e+03 -6.68001611e+03 -6.63567773e+03 -6.81344434e+03 -6.89083740e+03 -7.10579932e+03 -6.91200439e+03 -6.72834375e+03 -6.94237842e+03 -6.87916064e+03 -7.14193262e+03 -7.12579834e+03 -6.86441455e+03 -6.91377588e+03 -6.96322070e+03 -7.09346729e+03 -6.90906152e+03 -6.85986572e+03 -7.21582178e+03 -7.19774805e+03 -6.96998193e+03 -6.82352002e+03 -6.91088672e+03 -7.29357275e+03 -7.29740576e+03 -7.06365332e+03 -6.91590723e+03 -6.85085840e+03 -7.04936768e+03 -7.07961279e+03 -7.09576904e+03 -6.91872021e+03 -7.04211523e+03 -7.34571436e+03 -7.10433691e+03 -7.25126318e+03 -7.32101904e+03 -7.07511426e+03 -7.01345508e+03 -6.97984717e+03 -7.16608057e+03 -7.20816455e+03 -6.93085254e+03 -6.91630469e+03 -7.32672266e+03 -7.37326123e+03 -6.91013867e+03 -6.78910352e+03 -6.96241211e+03 -7.20724902e+03 -7.44824707e+03 -7.17868213e+03 -6.84261719e+03 -7.15207471e+03 -7.35977100e+03 -7.13844922e+03 -6.97967969e+03 -6.99827930e+03 -6.92511133e+03 -6.96912451e+03 -7.03813086e+03 -6.81608496e+03 -7.02225244e+03 -7.35303271e+03 -7.08882275e+03 -7.10035645e+03 -6.94621338e+03 -6.83860059e+03 -7.15561914e+03 -7.12901025e+03 -6.97512012e+03 -6.83322656e+03 -6.60486670e+03 -6.73680908e+03 -7.06280518e+03 -7.33834814e+03 -6.90530908e+03 -6.66096289e+03 -6.80734717e+03 -6.88582080e+03 -7.05977197e+03 -7.04511328e+03 -6.77884619e+03 -6.75129248e+03 -6.68839258e+03 -6.71319238e+03 -6.55689502e+03 -6.69234717e+03 -6.94196191e+03 -6.75496777e+03 -6.81316211e+03 -6.64773779e+03 -6.50050244e+03 -6.84551465e+03 -6.85069238e+03 -6.58504248e+03 -6.41104150e+03 -6.36016602e+03 -6.51435693e+03 -6.50383887e+03 -6.67679736e+03 -6.74606055e+03 -6.45272119e+03 -6.28870117e+03 -6.35246826e+03 -6.61685107e+03 -6.50965137e+03 -6.35717432e+03 -6.24138770e+03 -6.21081738e+03 -6.28642236e+03 -6.18678809e+03 -6.34412744e+03 -6.34164990e+03 -6.11232764e+03 -6.28601270e+03 -6.34594629e+03 -6.16095264e+03 -6.12545312e+03 -6.09770801e+03 -6.07099170e+03 -5.86978711e+03 -5.77749023e+03 -6.07622803e+03 -6.12712891e+03 -5.80131055e+03 -5.57121582e+03 -5.82931934e+03 -6.17011963e+03 -6.02134082e+03 -5.65511426e+03 -5.51294580e+03 -5.81536816e+03 -5.83156445e+03 -5.60803174e+03 -5.72231836e+03 -5.55890039e+03 -5.26738867e+03 -5.40219043e+03 -5.66836523e+03 -5.75147168e+03 -5.41916699e+03 -5.11932764e+03 -5.39284668e+03 -5.63843555e+03 -5.43695703e+03 -5.15413721e+03 -5.05551025e+03 -5.16296484e+03 -5.16086572e+03 -5.27817578e+03 -5.21539307e+03 -5.01092188e+03 -4.99592480e+03 -4.97017383e+03 -5.07986133e+03 -4.96029346e+03 -4.77278564e+03 -4.89831152e+03 -4.84800879e+03 -4.85151465e+03 -4.73228125e+03 -4.60897607e+03 -4.84198926e+03 -4.68403906e+03 -4.43139600e+03 -4.48725977e+03 -4.56950146e+03 -4.56275391e+03 -4.45110205e+03 -4.49699023e+03 -4.49404150e+03 -4.35911035e+03 -4.20823535e+03 -4.12262158e+03 -4.30346533e+03 -4.18867432e+03 -4.03810327e+03 -4.11308105e+03 -4.06282886e+03 -4.01698901e+03 -3.95544800e+03 -4.00660986e+03 -3.92991406e+03 -3.77180469e+03 -3.86037085e+03 -3.84178906e+03 -3.75122119e+03 -3.70469678e+03 -3.64220581e+03 -3.56324878e+03 -3.43309326e+03 -3.34094946e+03 -3.47512842e+03 -3.63272461e+03 -3.38986426e+03 -3.15084619e+03 -3.25179492e+03 -3.40928955e+03 -3.33349121e+03 -3.10966138e+03 -2.99210620e+03 -3.11098120e+03 -3.06437524e+03 -2.92943262e+03 -3.01158447e+03 -2.93425366e+03 -2.75434863e+03 -2.70873267e+03 -2.79737207e+03 -2.83004077e+03 -2.64524194e+03 -2.48836792e+03 -2.54885034e+03 -2.65823071e+03 -2.55315405e+03 -2.38146338e+03 -2.27384131e+03 -2.32995386e+03 -2.39065552e+03 -2.26909302e+03 -2.15156494e+03 -2.12817847e+03 -2.10966431e+03 -2.05001929e+03 -2.05761743e+03 -1.96981006e+03 -1.85439868e+03 -1.85292090e+03 -1.82041687e+03 -1.80680457e+03 -1.71877051e+03 -1.62632556e+03 -1.62714636e+03 -1.54517395e+03 -1.49913818e+03 -1.50539624e+03 -1.44376672e+03 -1.38881104e+03 -1.33067761e+03 -1.32165955e+03 -1.27754724e+03 -1.17942786e+03 -1.09877002e+03 -1.05512646e+03 -1.07488989e+03 -9.98079529e+02 -9.51977905e+02 -1.13141565e+03 -2.05281592e+03 -7.55900244e+03 430693024. 0. 0. 0. 0. -812645376. -3.29115562e+05 6.50518688e+05 1.07055766e+05 -5.01078522e+02 -1.66338110e+03 -5.04398584e+03 -2.91143757e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -432891424. 8.82789125e+05 6.19429938e+05 2.22280859e+03 1.50225720e+03 7.84663757e+02 8.52851562e+02 8.05383240e+02 8.72021667e+02 9.40140808e+02 9.47127197e+02 9.72956360e+02 1.04017297e+03 1.08367834e+03 1.14217212e+03 1.23360730e+03 1.26780481e+03 1.26708289e+03 1.33932983e+03 1.42220300e+03 1.43969641e+03 1.46872742e+03 1.51538208e+03 1.58555835e+03 1.67302698e+03 1.71962280e+03 1.71847668e+03 1.71777454e+03 1.81571973e+03 1.92440869e+03 1.93384375e+03 1.98526001e+03 2.01992603e+03 2.04143542e+03 2.15336206e+03 2.16618726e+03 2.14508887e+03 2.22116870e+03 2.26935059e+03 2.35520728e+03 2.43224585e+03 2.41483325e+03 2.44843066e+03 2.57292139e+03 2.74720093e+03 2.72347559e+03 2.56583008e+03 2.60802881e+03 2.73470215e+03 2.83440015e+03 2.94534180e+03 2.93005127e+03 2.89454688e+03 3.01845776e+03 3.09358667e+03 3.05960620e+03 3.08533447e+03 3.11881006e+03 3.26562891e+03 3.43204321e+03 3.30106323e+03 3.23511230e+03 3.36424292e+03 3.47309155e+03 3.57677002e+03 3.56976221e+03 3.51349341e+03 3.53570239e+03 3.66269067e+03 3.87150854e+03 3.81740918e+03 3.64926001e+03 3.77235864e+03 3.90114429e+03 3.93329199e+03 4.03435840e+03 4.00625024e+03 3.93802051e+03 4.06552026e+03 4.24745264e+03 4.19281250e+03 4.13580176e+03 4.15942139e+03 4.22849121e+03 4.38141797e+03 4.51172314e+03 4.44649854e+03 4.33989990e+03 4.44594092e+03 4.59969482e+03 4.57110352e+03 4.54489648e+03 4.56555225e+03 4.68905713e+03 4.87847461e+03 4.81982812e+03 4.67715479e+03 4.69954150e+03 4.79248438e+03 4.91595166e+03 4.99100049e+03 4.95179248e+03 4.97000635e+03 5.12661914e+03 5.30658496e+03 5.21732959e+03 4.96459082e+03 5.03487500e+03 5.24002197e+03 5.31242578e+03 5.35229199e+03 5.27702930e+03 5.24459033e+03 5.44565039e+03 5.50539453e+03 5.38886230e+03 5.47029785e+03 5.52312354e+03 5.51020605e+03 5.68359131e+03 5.69833301e+03 5.53606055e+03 5.61351904e+03 5.66434912e+03 5.64346777e+03 5.86831982e+03 6.01261768e+03 5.83259277e+03 5.67042139e+03 5.84144971e+03 6.04030029e+03 5.97784326e+03 5.89956885e+03 5.87136230e+03 5.92323975e+03 6.13481982e+03 6.22291406e+03 6.04182275e+03 6.01613818e+03 6.10226318e+03 6.22102051e+03 6.28480469e+03 6.23836230e+03 6.22519580e+03 6.31051416e+03 6.40314258e+03 6.25171436e+03 6.15110547e+03 6.33250146e+03 6.37691650e+03 6.46784326e+03 6.64135938e+03 6.48493799e+03 6.29307275e+03 6.46265576e+03 6.65833154e+03 6.59616895e+03 6.53691406e+03 6.43834473e+03 6.47496680e+03 6.80572852e+03 6.86124316e+03 6.52867139e+03 6.48572168e+03 6.72334277e+03 6.87823535e+03 6.70314502e+03 6.51550781e+03 6.62818262e+03 6.84988037e+03 7.00274756e+03 6.76043945e+03 6.65843896e+03 6.77893164e+03 6.76512207e+03 6.84745361e+03 6.99974072e+03 6.86763965e+03 6.80462354e+03 6.96596680e+03 7.08641455e+03 6.86926611e+03 6.82403223e+03 6.84594922e+03 6.87542139e+03 7.01405518e+03 7.28513477e+03 7.21382422e+03 6.84488086e+03 6.92942090e+03 7.19872314e+03 6.95980469e+03 6.86531396e+03 6.91012988e+03 7.00142285e+03 7.26869043e+03 7.25324121e+03 6.97977783e+03 6885. 6.98055908e+03 7.13126025e+03 7.18389160e+03 7.04819971e+03 7.09873096e+03 7.24260645e+03 7.27211328e+03 7.11766064e+03 7.02662061e+03 7.04400537e+03 7.06452490e+03 7.15598633e+03 7.33204590e+03 7.32667188e+03 6.99219287e+03 7.06214160e+03 7.22821045e+03 7.11820215e+03 7.15551709e+03 7.06430176e+03 7.11192041e+03 7.36843164e+03 7.27515479e+03 7.07180273e+03 7.00835889e+03 7.03062158e+03 7.15032666e+03 7.23762305e+03 7.12486963e+03 7.05742578e+03 7.16024561e+03 7.25877539e+03 7.29178076e+03 7.03659180e+03 6.88399072e+03 7.05773242e+03 7.06936230e+03 7.21239990e+03 7.10928955e+03 6.86302002e+03 7.03227686e+03 7.22530762e+03 7.03928613e+03 6.95936475e+03 7.02293018e+03 7.01577441e+03 7.07536963e+03 6.91240723e+03 7.09978906e+03 7.07144043e+03 6.89048584e+03 7.04774219e+03 6.87852051e+03 6.87726318e+03 7.06901758e+03 6.82550537e+03 6.85673242e+03 6.95957227e+03 6.82057178e+03 6.63328076e+03 6.69415381e+03 6.99546631e+03 7.03127393e+03 6.68824902e+03 6.63156152e+03 6.78322559e+03 6.78313721e+03 6.79519678e+03 6.59327148e+03 6.59976660e+03 6.65627295e+03 6.76081543e+03 6.68791504e+03 6.55586621e+03 6.55177441e+03 6.55612695e+03 6.66295557e+03 6.48726758e+03 6.33199512e+03 6.39779834e+03 6.37459912e+03 6.46197998e+03 6.62891895e+03 6.49027637e+03 6.20263672e+03 6.21089990e+03 6.48091113e+03 6.52873975e+03 6.16128369e+03 6.26279199e+03 6.40778027e+03 6.11921094e+03 6.13374512e+03 6.04850244e+03 6.05423340e+03 6.29430664e+03 6.13282227e+03 5.94071387e+03 6.12482129e+03 6.11723193e+03 5.86960596e+03 5.93700293e+03 6.01671387e+03 5.98602783e+03 5.78048438e+03 5.67971924e+03 5.83231201e+03 5.95251270e+03 5.80460547e+03 5.60292725e+03 5.60770068e+03 5.75549756e+03 5.79253613e+03 5.51419385e+03 5.46295410e+03 5.51487061e+03 5.59764502e+03 5.56773584e+03 5.32611768e+03 5.33512354e+03 5.47173682e+03 5.43169531e+03 5.28456006e+03 5.32137451e+03 5.27689893e+03 5.10526514e+03 5.31773291e+03 5.35481396e+03 5.04542969e+03 4.85526709e+03 4.92240088e+03 5.05628271e+03 5.05981836e+03 4.95498682e+03 4.82085400e+03 4.79167676e+03 4.91482715e+03 4.91836865e+03 4.69222119e+03 4.59901318e+03 4.69536035e+03 4.80925928e+03 4.64135010e+03 4.44764014e+03 4.51840332e+03 4.50391992e+03 4.44906641e+03 4.39040430e+03 4.37976758e+03 4.32793506e+03 4.22951172e+03 4.26170801e+03 4.23906689e+03 4.16013721e+03 4.04361255e+03 4.02126050e+03 4.05440283e+03 4.02129565e+03 3.93546973e+03 3.87414966e+03 3.85180103e+03 3.93375195e+03 3.88376514e+03 3.69459180e+03 3.69465869e+03 3.70232031e+03 3.64867261e+03 3.54760889e+03 3.47591699e+03 3.55012378e+03 3.48670776e+03 3.33740527e+03 3.23535669e+03 3.29647803e+03 3.36161377e+03 3.26987524e+03 3.21762061e+03 3.13760181e+03 3.11346924e+03 3.01220508e+03 2.87490405e+03 2.92580493e+03 2.94377368e+03 2.88472876e+03 2.83224365e+03 2.71224707e+03 2.67664331e+03 2.71127148e+03 2.67696826e+03 2.65099756e+03 2.55266626e+03 2.43889429e+03 2.38148901e+03 2.40952881e+03 2.41180591e+03 2.32772803e+03 2.25674194e+03 2.14574365e+03 2.14341846e+03 2.13667578e+03 2.05842041e+03 2.04411890e+03 1.95432336e+03 1.89280139e+03 1.90729211e+03 1.80898132e+03 1.74470569e+03 1.75889941e+03 1.72051685e+03 1.61810327e+03 1.52914697e+03 1.50245911e+03 1.47774097e+03 1.47497583e+03 1.44414856e+03 1.34733508e+03 1.26850708e+03 1.20239160e+03 1.19136157e+03 1.17953442e+03 1.10657507e+03 1.02934265e+03 9.60170227e+02 9.27497437e+02 9.03345154e+02 8.65087891e+02 8.05002991e+02 7.45991516e+02 7.08789978e+02 6.47315369e+02 5.78063599e+02 5.38231079e+02 4.97583588e+02 4.52604218e+02 4.11634064e+02 3.45999176e+02 2.86668854e+02 2.43923859e+02 2.00063858e+02 1.49929993e+02 9.69377518e+01 4.77469025e+01 -1.53495514e+00 -5.04089851e+01 -1.04275528e+02 -1.54617783e+02 -2.04006348e+02 -2.46310959e+02 -2.99112061e+02 -3.48893555e+02 -3.85415985e+02 -4.45925659e+02 -5.09877594e+02 -5.56991943e+02 -5.99682861e+02 -6.37233154e+02 -6.96020691e+02 -7.62032715e+02 -8.16299561e+02 -8.64214539e+02 -8.70560120e+02 -9.16370605e+02 -9.95804443e+02 -1.06622461e+03 -1.12525049e+03 -1.15161548e+03 -1.19302063e+03 -1.20942834e+03 -1.28052966e+03 -1.38090076e+03 -1.39968628e+03 -1.44037585e+03 -1.48813000e+03 -1.52344080e+03 -1.55431311e+03 -1.61544238e+03 -1.69829736e+03 -1.75918652e+03 -1.81426465e+03 -1.81591309e+03 -1.82459021e+03 -1.90812146e+03 -1.97769165e+03 -2.04967285e+03 -2.12136206e+03 -2.10222266e+03 -2.14892554e+03 -2.19182520e+03 -2.25602148e+03 -2.37576025e+03 -2.37742188e+03 -2.39211255e+03 -2.41648535e+03 -2.41490454e+03 -2.50595190e+03 -2.70286792e+03 -2.71021411e+03 -2.64573022e+03 -2.73562207e+03 -2.74858398e+03 -2.71889551e+03 -2.83835742e+03 -2.94299780e+03 -2.98868848e+03 -3.02175146e+03 -2.97760522e+03 -3.04617798e+03 -3.17046729e+03 -3.23789160e+03 -3.37594336e+03 -3.32268750e+03 -3.19607983e+03 -3.24720850e+03 -3.40322021e+03 -3.52060376e+03 -3.54181860e+03 -3.54551733e+03 -3.45424927e+03 -3.57629492e+03 -3.75959058e+03 -3.72598096e+03 -3.75990796e+03 -3.74484692e+03 -3.79237158e+03 -3.93207031e+03 -3.87778931e+03 -3.90067163e+03 -4.14329785e+03 -4.17059863e+03 -4.10011865e+03 -4.05535010e+03 -3.98058423e+03 -4.11942188e+03 -4.33691162e+03 -4.48379395e+03 -4.41867139e+03 -4.24493701e+03 -4.23719873e+03 -4.42844580e+03 -4.57666748e+03 -4.54223975e+03 -4.54327344e+03 -4.49985889e+03 -4.53885889e+03 -4.71774170e+03 -4.80352197e+03 -4.83456689e+03 -4.83377881e+03 -4.88219336e+03 -4.84736719e+03 -4.75134766e+03 -4.86318359e+03 -5.01347070e+03 -5.09278320e+03 -5.20698877e+03 -5.05377881e+03 -4.92613428e+03 -5.11730859e+03 -5.27721289e+03 -5.38081250e+03 -5.34422314e+03 -5.16940820e+03 -5.13832422e+03 -5.33796436e+03 -5.56773730e+03 -5.59278223e+03 -5.46754590e+03 -5.41415039e+03 -5.45005664e+03 -5.46302441e+03 -5.51113672e+03 -5.65215771e+03 -5.76614258e+03 -5.69483740e+03 -5.58532373e+03 -5.58170898e+03 -5.71339258e+03 -5.89229297e+03 -6.00553027e+03 -5.99853027e+03 -5.78459033e+03 -5.65234961e+03 -5.81775586e+03 -6.04324170e+03 -6.21219727e+03 -6.15789893e+03 -5.90218311e+03 -5.79817236e+03 -6.04795068e+03 -6.34076465e+03 -6.20668213e+03 -6.22967383e+03 -6.16665430e+03 -6.02868018e+03 -6.25572412e+03 -6.32202051e+03 -6.30306299e+03 -6.33187012e+03 -6.39605029e+03 -6.40734863e+03 -6.27917041e+03 -6.40081104e+03 -6.48264990e+03 -6.59444629e+03 -6.52552246e+03 -6.40104443e+03 -6.46822363e+03 -6.36995996e+03 -6.51741650e+03 -6.89755322e+03 -6.77932031e+03 -6.45807422e+03 -6.43178516e+03 -6.53362061e+03 -6.79062695e+03 -6.96856299e+03 -6.72528564e+03 -6.58576660e+03 -6.67884229e+03 -6.77854199e+03 -6.76527246e+03 -6.86563379e+03 -6.98247998e+03 -7.14701611e+03 -7.13983740e+03 -7.96508105e+03 -9.65920508e+03 -3.51845078e+04 19326628. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -59734588. -14162799. 1.66975175e+06 3.73615225e+06 -2.41036250e+04 -1.53163965e+04 -7.83487988e+03 -7.83620898e+03 -7.51992090e+03 -7.15181250e+03 -6.87733887e+03 -7.08489551e+03 -7.51976807e+03 -7.43061328e+03 -7.06252588e+03 -6.83632520e+03 -6.79257080e+03 -7.17860742e+03 -7.53424365e+03 -7.22867578e+03 -6.99330127e+03 -6.88336914e+03 -6.94604736e+03 -7.29658057e+03 -7.25310693e+03 -6.90236182e+03 -6.89249316e+03 -7.10155811e+03 -7.02362354e+03 -6.80277832e+03 -6.90399121e+03 -7.10117188e+03 -7.27225488e+03 -7.22812402e+03 -6.89705908e+03 -6.53148486e+03 -6.75016309e+03 -7.13555859e+03 -7.24876270e+03 -7.00070508e+03 -6.68399561e+03 -6.59922656e+03 -6.90483447e+03 -7.21766260e+03 -6.97685059e+03 -6.54831201e+03 -6.55634277e+03 -6.87491162e+03 -6.88866357e+03 -6.73976709e+03 -6.71699023e+03 -6.63774951e+03 -6.74850879e+03 -6.76886963e+03 -6.43041406e+03 -6.43650635e+03 -6.77989844e+03 -6.86688672e+03 -6.72464795e+03 -6.39676562e+03 -6.18408545e+03 -6.52701953e+03 -6.92392139e+03 -6.71617334e+03 -6.37370312e+03 -6.16714502e+03 -6.10225684e+03 -6.41688965e+03 -6.76223145e+03 -6.53511914e+03 -6.38745117e+03 -6.27951123e+03 -6.14806494e+03 -6.22303076e+03 -6.33385107e+03 -6.14970166e+03 -6.05747363e+03 -6.25346338e+03 -6.13107520e+03 -5.86307812e+03 -5.93137305e+03 -6.18745264e+03 -6.29476318e+03 -6.14291602e+03 -5.95878711e+03 -5.75493164e+03 -5.67335645e+03 -5.94860352e+03 -6.21313818e+03 -5.97000293e+03 -5.57601709e+03 -5.55470020e+03 -5.75828809e+03 -5.95015479e+03 -5.89746045e+03 -5.60146875e+03 -5.49975000e+03 -5.63054932e+03 -5.60661963e+03 -5.51718994e+03 -5.50641064e+03 -5.44113623e+03 -5.48407227e+03 -5.44728467e+03 -5.24680518e+03 -5.24456982e+03 -5.38021777e+03 -5.44659229e+03 -5.39563184e+03 -5.21423340e+03 -5.00825684e+03 -5.00694434e+03 -5.23890186e+03 -5.28071875e+03 -5.04773779e+03 -4.82819531e+03 -4.72858203e+03 -4.94930713e+03 -5.21594824e+03 -4.96356494e+03 -4.66644287e+03 -4.65536914e+03 -4.75486230e+03 -4.70129053e+03 -4.57371777e+03 -4.56027344e+03 -4.68140674e+03 -4.68739307e+03 -4.52148926e+03 -4.33985498e+03 -4.30061328e+03 -4.47075000e+03 -4.59861035e+03 -4.44609766e+03 -4.25630225e+03 -4.13709717e+03 -4.03867603e+03 -4.15361182e+03 -4.34580762e+03 -4.15291211e+03 -3.90366382e+03 -3.84672168e+03 -3.99007251e+03 -4.12712549e+03 -3.95537231e+03 -3.77981470e+03 -3.73101221e+03 -3.73769165e+03 -3.74942676e+03 -3.69310156e+03 -3.56133081e+03 -3.47643750e+03 -3.57088647e+03 -3.58933374e+03 -3.42064868e+03 -3.30108081e+03 -3.31559985e+03 -3.36919165e+03 -3.40192700e+03 -3.28721997e+03 -3.06237451e+03 -3.04487231e+03 -3.13182568e+03 -3.10522021e+03 -3.01339819e+03 -2.92328271e+03 -2.86467944e+03 -2.83248462e+03 -2.85598877e+03 -2.76355273e+03 -2.65450464e+03 -2.69679492e+03 -2.71651660e+03 -2.60209839e+03 -2.47242334e+03 -2.44346851e+03 -2.45351270e+03 -2.48452954e+03 -2.44446484e+03 -2.30925537e+03 -2.18547095e+03 -2.12276465e+03 -2.16768213e+03 -2.23060400e+03 -2.11348218e+03 -1.95049438e+03 -1.89331812e+03 -1.91564075e+03 -1.94453052e+03 -1.88711682e+03 -1.77867883e+03 -1.70958276e+03 -1.67655273e+03 -1.61529639e+03 -1.57237158e+03 -1.54450012e+03 -1.48519763e+03 -1.44874133e+03 -1.39435059e+03 -1.30789062e+03 -1.26730530e+03 -1.25241052e+03 -1.22002368e+03 -1.17195996e+03 -1.07186365e+03 -9.94890686e+02 -9.99689636e+02 -9.93213135e+02 -9.26327576e+02 -8.47722534e+02 -7.74044861e+02 -7.16734985e+02 -7.05563232e+02 -6.86867554e+02 -6.17231323e+02 -5.34687256e+02 -4.79599976e+02 -4.49523315e+02 -4.10019928e+02 -3.57434723e+02 -3.04086548e+02 -2.50515930e+02 -1.98981033e+02 -1.45078278e+02 -9.22829666e+01 -4.35410347e+01 6.28192186e+00 5.55911789e+01 1.07580421e+02 1.52237411e+02 1.90076004e+02 2.38888443e+02 3.01235016e+02 3.63267273e+02 4.08731659e+02 4.47947266e+02 5.09084076e+02 5.63918640e+02 5.89866882e+02 6.17052124e+02 6.78375488e+02 7.67169739e+02 8.44988220e+02 8.76209473e+02 8.77500305e+02 8.95492798e+02 9.63587463e+02 1.07607874e+03 1.16123682e+03 1.17832996e+03 1.16008337e+03 1.20937207e+03 1.33502063e+03 1.38147827e+03 1.36798694e+03 1.41366089e+03 1.47389734e+03 1.52511523e+03 1.62839893e+03 1.64411633e+03 1.63594373e+03 1.71894446e+03 1.73366809e+03 1.83454248e+03 1.92448547e+03 1.86874353e+03 1.96623279e+03 2.08080396e+03 2.07349878e+03 2.09750049e+03 2.15806689e+03 2.23195386e+03 2.27967261e+03 2.30995581e+03 2.28541211e+03 2.33906177e+03 2.51145020e+03 2.61149072e+03 2.59661548e+03 2.53696729e+03 2.52702051e+03 2.63271533e+03 2.79130371e+03 2.88998926e+03 2.87828296e+03 2.79636377e+03 2.84970166e+03 2.97047095e+03 3.00478076e+03 3.05884326e+03 3.09198560e+03 3.11820532e+03 3.15509619e+03 3.32470898e+03 3.30645605e+03 3.21707739e+03 3.32278247e+03 3.31452710e+03 3.49453735e+03 3.57793042e+03 3.49047070e+03 3.71346191e+03 3.63818677e+03 3.53094189e+03 3.70668994e+03 3.66514380e+03 3.76550171e+03 4.07209521e+03 3.93377759e+03 3.73249487e+03 3.82335205e+03 4.04670874e+03 4.28804980e+03 4.20907764e+03 4.01903003e+03 3.97596631e+03 4.05513086e+03 4.30737354e+03 4.54015869e+03 4.45766309e+03 4.27877539e+03 4.29480566e+03 4.45870752e+03 4.54062500e+03 4.51105469e+03 4.49575293e+03 4.56301953e+03 4.65866797e+03 4.79794336e+03 4.82439307e+03 4.65312939e+03 4.67768555e+03 4.76047607e+03 4.82886914e+03 4.92342139e+03 4.94333789e+03 5.11143555e+03 5.03205469e+03 4.87742139e+03 5.04035596e+03 4.95547363e+03 5.14589893e+03 5.48339404e+03 5.25071826e+03 4.98772363e+03 5.12906055e+03 5.40322705e+03 5.61821240e+03 5.60619824e+03 5.33007080e+03 5.18594238e+03 5.30731494e+03 5.60249121e+03 5.88447168e+03 5.72051953e+03 5.40111719e+03 5.42430859e+03 5.61940918e+03 5.77477393e+03 5.97094678e+03 5.97327588e+03 5.65986670e+03 5.57764160e+03 5.92909424e+03 6.04697510e+03 5.81176074e+03 5.81937158e+03 5.97816992e+03 5.94710742e+03 6.13796191e+03 6.22142627e+03 5.89995947e+03 5.92577246e+03 6.12892773e+03 6.15127979e+03 6.19749170e+03 6.11797754e+03 6.25834473e+03 6.44775488e+03 6.31267236e+03 6.11825000e+03 6.00491406e+03 6.30506885e+03 6.70716064e+03 6.57244141e+03 6.27172705e+03 6.10847656e+03 6.34456396e+03 6.76313916e+03 6.60891406e+03 6.27116162e+03 6.35420361e+03 6.53364014e+03 6.71855420e+03 6.93899414e+03 6.82305566e+03 6.45546631e+03 6.32389648e+03 6.54917334e+03 6.85895117e+03 6.88198926e+03 6.68811182e+03 6.68853369e+03 6.71198877e+03 6.88668457e+03 6.88233154e+03 6.74610156e+03 6.72567578e+03 6.53760449e+03 6.85749512e+03 7.12311084e+03 6.83333496e+03 6.93022705e+03 6.97645312e+03 7.05296289e+03 6.88450537e+03 6.63361816e+03 6.93905859e+03 7.29589209e+03 7.12416016e+03 6.75308936e+03 6.81649219e+03 7.20794336e+03 7.23790137e+03 7.06747803e+03 7.09864062e+03 6.81552295e+03 6.81793213e+03 7.27619678e+03 7.24128369e+03 6.96112549e+03 6.82426270e+03 6.82048828e+03 7.15280176e+03 7.40742676e+03 7.15813623e+03 6.97646582e+03 7.11854932e+03 7.08758350e+03 7.34827100e+03 7.33817969e+03 6.95674219e+03 6.97179590e+03 7.10973877e+03 7.10019971e+03 7.14974902e+03 7.12292236e+03 7.33767334e+03 7.23114307e+03 6.99972705e+03 7.06785791e+03 6.91160352e+03 7.15928564e+03 7.60448438e+03 7.37939795e+03 7.01690234e+03 6.90477393e+03 7.02292139e+03 7.24009375e+03 7.56728564e+03 7.68129688e+03 8.13762305e+03 7.43974268e+03 1.08677480e+04 7.84219531e+04 -17729578. 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. 0. 0. 0. 0. 0. 0. -160556896. 30361858. 2.43834863e+04 1.47821328e+04 7.32767188e+03 7.20819092e+03 6.89386279e+03 6.55131104e+03 6.51950732e+03 6.66298291e+03 6.63217188e+03 6.49791846e+03 6.64484277e+03 6.58337598e+03 6.48360449e+03 6.48620361e+03 6.45458789e+03 6.39167041e+03 6.39663867e+03 6.42869629e+03 6.33686133e+03 6.18508008e+03 6.16281250e+03 6.41079688e+03 6.37627832e+03 6.04934229e+03 6.05724121e+03 6.34132373e+03 6.34871631e+03 6.12059375e+03 6.10225684e+03 6.04939893e+03 6.04197314e+03 6.01328613e+03 6.00783740e+03 5.96321094e+03 5.88182031e+03 5.77478906e+03 5.75711328e+03 5.96140039e+03 5.93950391e+03 5.75490576e+03 5.74851807e+03 5.73196045e+03 5.72628027e+03 5.65590576e+03 5.60526465e+03 5.60146826e+03 5.43251855e+03 5.39246582e+03 5.47082764e+03 5.42610547e+03 5.59182861e+03 5.59353662e+03 5.40112695e+03 5.18843506e+03 5.11405518e+03 5.43806787e+03 5.46230566e+03 5.19120898e+03 5.08461328e+03 5.12785889e+03 5.05956885e+03 4.96680176e+03 5.18125732e+03 5.11576123e+03 4.78042627e+03 4.72158008e+03 4.93698584e+03 5.08153662e+03 4.92961426e+03 4.79322461e+03 4.76733057e+03 4.69259180e+03 4.61372998e+03 4.61127051e+03 4.63154004e+03 4.57396875e+03 4.43962256e+03 4.38136963e+03 4.42815576e+03 4.38657715e+03 4.45690527e+03 4.36680127e+03 4.18967822e+03 4.23140088e+03 4.19245312e+03 4.24295459e+03 4.22201514e+03 4.07975488e+03 4.03433350e+03 3.91346851e+03 3.79180737e+03 3.92708154e+03 3.94289697e+03 3.70016724e+03 3.69752393e+03 3.87286230e+03 3.90351123e+03 3.75232910e+03 3.60791650e+03 3.54861865e+03 3.51757031e+03 3.43628345e+03 3.38467993e+03 3.41162549e+03 3.36073535e+03 3.36432715e+03 3.27560864e+03 3.16719360e+03 3.18157300e+03 3.06328784e+03 3.06601489e+03 3.18321973e+03 3.08277002e+03 2.95394751e+03 2.83117383e+03 2.77829956e+03 2.89366431e+03 2.86864600e+03 2.71635718e+03 2.59233154e+03 2.55081812e+03 2.57736792e+03 2.52839014e+03 2.55242065e+03 2.52827368e+03 2.39548145e+03 2.29943115e+03 2.26228076e+03 2.30980688e+03 2.25227539e+03 2.15215088e+03 2.06871509e+03 2.02226270e+03 2.01611157e+03 1.91527234e+03 1.89447522e+03 1.96147583e+03 1.88364990e+03 1.77989990e+03 1.68201868e+03 1.62915674e+03 1.68235864e+03 1.63599060e+03 1.54160742e+03 1.44538611e+03 1.38768311e+03 1.39157605e+03 1.34014343e+03 1.28487964e+03 1.21037402e+03 1.18383325e+03 1.17780798e+03 1.09670679e+03 1.06000085e+03 1.01829639e+03 9.46930481e+02 8.74208862e+02 8.24310852e+02 7.95272339e+02 7.44758057e+02 6.95899902e+02 6.25278015e+02 5.85528137e+02 5.73709839e+02 4.99030945e+02 4.32695343e+02 3.96245697e+02 3.47548065e+02 3.05124176e+02 2.49977554e+02 1.92171188e+02 1.50458145e+02 1.00865479e+02 4.87544823e+01 3.75764817e-01 -4.76415215e+01 -9.65524292e+01 -1.47986710e+02 -2.01843567e+02 -2.45650742e+02 -3.00339020e+02 -3.69724335e+02 -4.13463104e+02 -4.44086975e+02 -4.76837982e+02 -5.43321838e+02 -6.31467529e+02 -6.65894043e+02 -6.97922485e+02 -7.36735596e+02 -7.77006042e+02 -8.46009949e+02 -8.96190186e+02 -9.70223206e+02 -1.00205341e+03 -1.01736810e+03 -1.09494885e+03 -1.14997363e+03 -1.22219470e+03 -1.25960583e+03 -1.27875647e+03 -1.32309229e+03 -1.36565991e+03 -1.44723108e+03 -1.46091638e+03 -1.52862610e+03 -1.66444788e+03 -1.67506482e+03 -1.68885010e+03 -1.68793652e+03 -1.71996130e+03 -1.87316089e+03 -1.93618091e+03 -1.93586389e+03 -1.91907275e+03 -1.96017407e+03 -2.07429102e+03 -2.12495435e+03 -2.22689258e+03 -2.26643286e+03 -2.25977856e+03 -2.23788135e+03 -2.27489722e+03 -2.46544849e+03 -2.49979541e+03 -2.47764966e+03 -2.48495874e+03 -2.52427100e+03 -2.69560645e+03 -2.76167310e+03 -2.67092700e+03 -2.69649414e+03 -2.88371265e+03 -2.93497388e+03 -2.83574170e+03 -2.87095386e+03 -3.07064624e+03 -3.12481079e+03 -3.07033984e+03 -3.05435083e+03 -3.09234766e+03 -3.31937427e+03 -3.34699121e+03 -3.27142603e+03 -3.31936401e+03 -3.34323413e+03 -3.43708276e+03 -3.50092822e+03 -3.52589282e+03 -3.47454834e+03 -3.57894189e+03 -3.79396680e+03 -3.74736133e+03 -3.80642334e+03 -3.88151831e+03 -3.84747876e+03 -3.89476733e+03 -3.92597705e+03 -3.92504492e+03 -3.88626050e+03 -3.93366431e+03 -4.06146313e+03 -4.12922998e+03 -4.28307031e+03 -4.21341260e+03 -4.12100342e+03 -4.28697900e+03 -4.34529688e+03 -4.49193066e+03 -4.46217041e+03 -4.37866357e+03 -4.44724268e+03 -4.43911475e+03 -4.55421387e+03 -4.60683154e+03 -4.73134521e+03 -4.73457422e+03 -4.65258203e+03 -4.70623242e+03 -4.62239697e+03 -4.80963770e+03 -5.12898486e+03 -5.04703076e+03 -4.93481348e+03 -4.84601416e+03 -4.81909180e+03 -5.09522559e+03 -5.29867725e+03 -5.17816797e+03 -5.01698340e+03 -5.02989160e+03 -5.20010547e+03 -5.24103809e+03 -5.39901904e+03 -5.36774072e+03 -5.24605420e+03 -5.36548633e+03 -5.39574609e+03 -5.58004541e+03 -5.61801758e+03 -5.34141309e+03 -5.39532764e+03 -5.71846143e+03 -5.65532129e+03 -5.40431787e+03 -5.61070264e+03 -5.95240576e+03 -5.86776172e+03 -5.75577930e+03 -5.66718115e+03 -5.69159082e+03 -5.99761768e+03 -6.02983252e+03 -5.91374561e+03 -5.79052295e+03 -5.79518311e+03 -6.02334424e+03 -6.02141699e+03 -6.02358203e+03 -5.92532227e+03 -6.06432617e+03 -6.32548145e+03 -6.16755127e+03 -6.29027295e+03 -6.21996240e+03 -6.06191748e+03 -6.24738135e+03 -6.30435986e+03 -6.31412402e+03 -6.30069629e+03 -6.24560449e+03 -6.14260938e+03 -6.34196094e+03 -6.80441309e+03 -6.43961035e+03 -6.12484424e+03 -6.33001514e+03 -6.59379639e+03 -6.79590771e+03 -6.64556494e+03 -6.49504443e+03 -6.67021729e+03 -6.66218213e+03 -6.44219238e+03 -6.35416650e+03 -6.73703516e+03 -6.79537451e+03 -6.58720361e+03 -6.63481543e+03 -6.43979590e+03 -6.69003027e+03 -7.10392188e+03 -6.90906201e+03 -6.76790967e+03 -6.56966113e+03 -6.51301904e+03 -6.92901953e+03 -7.24331348e+03 -7.08237500e+03 -6.74093408e+03 -6.67229150e+03 -6.84501904e+03 -6.90325195e+03 -7.12586523e+03 -6.92958789e+03 -6.76330664e+03 -7.01194580e+03 -6.92630664e+03 -7.11803711e+03 -7.10218213e+03 -6.84415820e+03 -7.09145752e+03 -7.09548779e+03 -7.00602588e+03 -6.83729004e+03 -6.91809619e+03 -7.30572949e+03 -7.26844678e+03 -6.94003223e+03 -6.82152051e+03 -7.01968750e+03 -7.39538721e+03 -7.29769238e+03 -7.10239404e+03 -6.94503320e+03 -6.92541650e+03 -7.11789258e+03 -7.18185498e+03 -7.15768652e+03 -6.98133447e+03 -7.06875000e+03 -7.34703613e+03 -7.15306299e+03 -7.32486816e+03 -7.30552686e+03 -7.07883545e+03 -7.14872510e+03 -7.17444580e+03 -7.09445801e+03 -7.13524854e+03 -7.04788184e+03 -7.04674170e+03 -7.33502148e+03 -7.29842285e+03 -6.93942139e+03 -6.89203516e+03 -7.03702441e+03 -7.21270459e+03 -7.48237402e+03 -7.22742578e+03 -6.82555469e+03 -7.09450488e+03 -7.48250781e+03 -7.27432031e+03 -6.94326660e+03 -6.93409082e+03 -7.02592920e+03 -7.06685791e+03 -7.10805566e+03 -6.88614600e+03 -7.05208838e+03 -7.38967188e+03 -7.17927734e+03 -7.01896631e+03 -6.85119189e+03 -6.87344141e+03 -7.27358740e+03 -7.17911377e+03 -7.01645557e+03 -6.88616211e+03 -6.58773145e+03 -6.76694482e+03 -7.16962061e+03 -7.38148779e+03 -6.96081836e+03 -6.62811768e+03 -6.82616992e+03 -6.95026123e+03 -7.18214209e+03 -6.97253418e+03 -6.75231006e+03 -6.86805518e+03 -6.86052295e+03 -6.75059424e+03 -6.58356152e+03 -6.70157617e+03 -6.98334814e+03 -6.86435547e+03 -6.75826514e+03 -6.62644287e+03 -6.56993555e+03 -6.84979834e+03 -6.88293262e+03 -6.66973242e+03 -6.50162109e+03 -6.40120312e+03 -6.54421240e+03 -6.54689893e+03 -6.73220752e+03 -6.76218848e+03 -6.41054297e+03 -6.29472803e+03 -6.47033350e+03 -6.70095020e+03 -6.50645068e+03 -6.35164893e+03 -6.30622656e+03 -6.29550635e+03 -6.27163525e+03 -6.10040869e+03 -6.31677637e+03 -6.40192188e+03 -6.18649512e+03 -6.31529639e+03 -6.36757666e+03 -6.22644092e+03 -6.22156982e+03 -6.17130518e+03 -6.05720947e+03 -5.88176807e+03 -5.82307666e+03 -6.07200732e+03 -6.19044531e+03 -5.90438477e+03 -5.62783203e+03 -5.81325000e+03 -6.13950635e+03 -6.09472510e+03 -5.73644336e+03 -5.49047168e+03 -5.75373877e+03 -5.97491406e+03 -5.79675928e+03 -5.74978613e+03 -5.54795410e+03 -5.27878662e+03 -5.46715186e+03 -5.76565723e+03 -5.76475391e+03 -5.40543750e+03 -5.16588428e+03 -5.46362549e+03 -5.68481348e+03 -5.46939355e+03 -5.17678760e+03 -5.01104492e+03 -5.13440332e+03 -5.20123389e+03 -5.30827588e+03 -5.33891064e+03 -5.11252686e+03 -4.98600586e+03 -4.95668896e+03 -5.13212451e+03 -4.98523193e+03 -4.79751074e+03 -4.98117676e+03 -4.93600391e+03 -4.83512988e+03 -4.69491162e+03 -4.65824365e+03 -4.88348779e+03 -4.68699414e+03 -4.41143213e+03 -4.48609521e+03 -4.63539600e+03 -4.61933252e+03 -4.48086328e+03 -4.52828467e+03 -4.51304785e+03 -4.37507666e+03 -4.21656299e+03 -4.13234521e+03 -4.33798047e+03 -4.22252051e+03 -4.06438086e+03 -4.14677295e+03 -4.09356494e+03 -4.02110669e+03 -3.94543994e+03 -3.98715137e+03 -3.97486255e+03 -3.83432812e+03 -3.83992993e+03 -3.83076001e+03 -3.82492065e+03 -3.76013940e+03 -3.64639673e+03 -3.56002881e+03 -3.42159570e+03 -3.39515601e+03 -3.54092700e+03 -3.66581006e+03 -3.41847485e+03 -3.16362109e+03 -3.24673511e+03 -3.39992749e+03 -3.37274927e+03 -3.15803784e+03 -2.97903442e+03 -3.08971509e+03 -3.10891235e+03 -2.97404077e+03 -3.04254541e+03 -2.92594067e+03 -2.72730176e+03 -2.76675708e+03 -2.87234351e+03 -2.83120825e+03 -2.63270801e+03 -2.48819800e+03 -2.56279004e+03 -2.68331494e+03 -2.57263306e+03 -2.38528882e+03 -2.28185840e+03 -2.34712915e+03 -2.37817480e+03 -2.26205029e+03 -2.18604077e+03 -2.15178613e+03 -2.12790137e+03 -2.06457593e+03 -2.06544531e+03 -1.98404736e+03 -1.86387500e+03 -1.86215637e+03 -1.83068384e+03 -1.81868335e+03 -1.73282141e+03 -1.63733728e+03 -1.65700061e+03 -1.56678455e+03 -1.47732898e+03 -1.48539343e+03 -1.46513440e+03 -1.41597864e+03 -1.33900452e+03 -1.32555188e+03 -1.28845715e+03 -1.18827881e+03 -1.10520642e+03 -1.05590149e+03 -1.07571765e+03 -1.00674335e+03 -9.41422974e+02 -1.01231812e+03 -1.52320117e+03 -8.42224805e+03 215346512. 0. 0. 0. 0. -812645376. -3.29115562e+05 6.50518688e+05 1.07055766e+05 -5.01183594e+02 -1.15254187e+03 -2.52186987e+03 -1455718784. 0. 0.
================================================ FILE: config/m2dgr/ring32_M_4.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.17365791e+10 6.06541484e+04 3.37838555e+04 2.42433047e+04 1.63886289e+04 1.52145908e+04 1.49927559e+04 1.58251670e+04 1.54524727e+04 1.54396943e+04 1.52174033e+04 1.47430713e+04 1.51803477e+04 1.57048711e+04 1.51684121e+04 1.49901318e+04 1.52815840e+04 1.54398906e+04 1.55334863e+04 1.50642480e+04 1.45812559e+04 1.48320840e+04 1.52213711e+04 1.53481211e+04 1.52111797e+04 1.48689141e+04 1.48540059e+04 1.53289434e+04 1.57014502e+04 1.51668438e+04 1.45011104e+04 1.46950010e+04 1.51249482e+04 1.49873965e+04 1.49363496e+04 1.50468945e+04 1.46080830e+04 1.48389873e+04 1.51972100e+04 1.45576758e+04 1.44757549e+04 1.49089502e+04 1.54420371e+04 1.55446221e+04 1.44849883e+04 1.39615049e+04 1.43678076e+04 1.49755225e+04 1.51235928e+04 1.45134834e+04 1.44589824e+04 1.49021992e+04 1.47145879e+04 1.46994033e+04 1.44834189e+04 1.39652861e+04 1.44118135e+04 1.48823848e+04 1.43873574e+04 1.42978818e+04 1.45682510e+04 1.42659521e+04 1.44980029e+04 1.46313018e+04 1.40420459e+04 1.38990400e+04 1.41872910e+04 1.46424561e+04 1.44931309e+04 1.39914814e+04 1.40639678e+04 1.39541924e+04 1.40558682e+04 1.43464395e+04 1.38039980e+04 1.36728252e+04 1.40666777e+04 1.42241758e+04 1.42479014e+04 1.38642988e+04 1.33001230e+04 1.34313945e+04 1.38204297e+04 1.40206045e+04 1.39614600e+04 1.36652217e+04 1.34423359e+04 1.37438271e+04 1.39584834e+04 1.34637334e+04 1.30546172e+04 1.32410938e+04 1.36594639e+04 1.37350840e+04 1.35261260e+04 1.31608076e+04 1.28843105e+04 1.32818105e+04 1.35657930e+04 1.30087861e+04 1.29744639e+04 1.33198740e+04 1.35112344e+04 1.34301992e+04 1.27801133e+04 1.23856494e+04 1.27557783e+04 1.30123701e+04 1.29194854e+04 1.27870049e+04 1.27956963e+04 1.29559492e+04 1.26537393e+04 1.25484639e+04 1.27866982e+04 1.24217988e+04 1.22895479e+04 1.25537578e+04 1.26312314e+04 1.26152998e+04 1.23535898e+04 1.19680977e+04 1.20161348e+04 1.22734131e+04 1.24446670e+04 1.22607744e+04 1.21287734e+04 1.29480049e+04 1.64641367e+04 1.80410605e+04 4.87999281e+05 -5.37879500e+05 -7.75995688e+05 1.22942662e+06 1.70922324e+04 1.62068584e+04 1.36544805e+04 1.27865332e+04 1.21272754e+04 1.53600850e+04 1.65442441e+04 -4.40988650e+06 20237230. -5.90333125e+05 -10195032. -464239. 650373. -1.96809525e+06 1.36638162e+06 6.44093500e+05 -7.60221812e+05 1.54942832e+04 1.43916104e+04 1.20570156e+04 1.18727129e+04 1.09891631e+04 1.03050742e+04 1.02032744e+04 1.08816768e+04 1.10384902e+04 1.05355156e+04 1.01074805e+04 1.02482822e+04 1.05556670e+04 1.04637412e+04 9.93011621e+03 9.90182910e+03 1.01831133e+04 1.01656660e+04 1.00650049e+04 1.01162842e+04 1.00889482e+04 9.62956934e+03 9.81714941e+03 1.00474209e+04 9.53243555e+03 9.44711328e+03 9.65639551e+03 9.67431543e+03 9.69192578e+03 9.46162012e+03 9.06303027e+03 9.09718555e+03 9.31035352e+03 9.61096680e+03 9.52119727e+03 8.93360938e+03 8.93257617e+03 9.34085547e+03 9.09070996e+03 8.64045215e+03 8.63530566e+03 8.83213672e+03 8.90581836e+03 8.95446289e+03 8.86683594e+03 8.56656055e+03 8.28899609e+03 8.50217480e+03 8.64737988e+03 8.31856738e+03 8.24060742e+03 8.38469824e+03 8.45489941e+03 8.38700879e+03 8.11518457e+03 7.83857178e+03 7.87061475e+03 8.00987451e+03 8.19216602e+03 8.09946191e+03 7.63759277e+03 7.61800049e+03 7.75461133e+03 7.74416553e+03 7.63238281e+03 7.42337549e+03 7.36079053e+03 7.52634863e+03 7.58038574e+03 7.43828125e+03 7.20846289e+03 7.05226025e+03 7.17504932e+03 7.25026416e+03 7.01219189e+03 7.00776172e+03 7.08530420e+03 7.00003516e+03 7.07727783e+03 6.76621924e+03 6.55130029e+03 6.67089551e+03 6.65016846e+03 6.69809912e+03 6.45515479e+03 6.24559326e+03 6.46099512e+03 6.60326221e+03 6.44524219e+03 6.23222803e+03 6.24548682e+03 6.07786230e+03 6.01679834e+03 6.11826367e+03 6.25466406e+03 6.01327930e+03 5.80749023e+03 5.93924658e+03 5.79037256e+03 5.78742334e+03 5.73844189e+03 5.49607812e+03 5.61181738e+03 5.67581201e+03 5.43210107e+03 5.27968750e+03 5.34995068e+03 5.49814844e+03 5.47912891e+03 5.14571924e+03 5.05493018e+03 5.13631641e+03 5.15630371e+03 5.17039307e+03 4.97035205e+03 4.90082227e+03 4.81385449e+03 4.77687109e+03 4.92900586e+03 4.80377246e+03 4.55431445e+03 4.60937891e+03 4.73638623e+03 4.51925684e+03 4.44152441e+03 4.34595654e+03 4.27851904e+03 4.42535254e+03 4.45056152e+03 4.24127734e+03 4.12980664e+03 4.13229443e+03 4.16665381e+03 4.17283447e+03 4.00314038e+03 4.01574731e+03 3.99501978e+03 3.77269067e+03 3.76557593e+03 3.76091064e+03 3.72479956e+03 3.73892212e+03 3.66291162e+03 3.59979419e+03 3.62762891e+03 3.50861133e+03 3.39390015e+03 3.42105078e+03 3.44173071e+03 3.38353760e+03 3.21978809e+03 3.17279297e+03 3.26722632e+03 3.26561621e+03 3.08552124e+03 2.99617334e+03 2.99432617e+03 3.03709253e+03 3.03127026e+03 2.88560229e+03 2.83859033e+03 2.78137305e+03 2.79258423e+03 2.80557373e+03 2.67686450e+03 2.63889014e+03 2.61430347e+03 2.56096973e+03 2.55729785e+03 2.56829517e+03 2.46343335e+03 2.35182373e+03 2.41972339e+03 2.45899023e+03 2.28962500e+03 2.16993896e+03 2.20309326e+03 2.21739746e+03 2.17507739e+03 2.10101099e+03 2.04377356e+03 2.02693689e+03 2.04101831e+03 2.01931262e+03 1.92967615e+03 1.88724792e+03 1.85177405e+03 1.86185583e+03 1.82277185e+03 1.73335010e+03 1.71938696e+03 1.68469690e+03 1.64219861e+03 1.64235022e+03 1.61454456e+03 1.54612439e+03 1.50996252e+03 1.51445972e+03 1.48462036e+03 1.41742639e+03 1.38000671e+03 1.36601648e+03 1.36506921e+03 1.32889697e+03 1.25442517e+03 1.22938220e+03 1.22188623e+03 1.22565808e+03 1.20319897e+03 1.13506543e+03 1.13049268e+03 1.08905286e+03 1.01812665e+03 1.00538892e+03 9.94724976e+02 9.99455627e+02 9.68234680e+02 8.98679626e+02 8.66818970e+02 8.69734985e+02 8.73604492e+02 8.43993713e+02 8.04005676e+02 7.75712891e+02 7.44630371e+02 7.15170898e+02 6.91732117e+02 6.91421753e+02 6.80632263e+02 6.37368347e+02 6.13926941e+02 5.94509399e+02 5.81552307e+02 5.68370361e+02 5.44945801e+02 5.36028992e+02 5.00917908e+02 4.62379944e+02 4.50710266e+02 4.46105133e+02 4.39235840e+02 4.26186829e+02 3.95454041e+02 3.59084351e+02 3.50091644e+02 3.45368500e+02 3.27147156e+02 3.20020203e+02 3.03034790e+02 2.77158875e+02 2.71284607e+02 2.60142273e+02 2.41305099e+02 2.30545074e+02 2.14464294e+02 1.99197479e+02 1.87817154e+02 1.77709625e+02 1.68422531e+02 1.62111053e+02 1.55411774e+02 1.38201828e+02 1.22661713e+02 1.14331718e+02 1.07950310e+02 1.02656494e+02 9.35798798e+01 8.16289215e+01 7.33925018e+01 6.83250351e+01 6.36907654e+01 5.73612328e+01 4.97082787e+01 4.36562042e+01 3.80197411e+01 3.26431541e+01 2.79679508e+01 2.45381603e+01 2.10016232e+01 1.72005062e+01 1.40518007e+01 1.08508120e+01 8.49374676e+00 6.70541477e+00 5.04967213e+00 3.75970340e+00 2.77302456e+00 2.20712566e+00 2.04157877e+00 2.26139903e+00 2.85335708e+00 3.81022620e+00 5.04542112e+00 6.57223463e+00 8.83188152e+00 1.14750929e+01 1.41378269e+01 1.75577164e+01 2.13629875e+01 2.46093636e+01 2.87623978e+01 3.38931923e+01 3.94551697e+01 4.52434235e+01 5.03914948e+01 5.66147614e+01 6.14974747e+01 6.78966217e+01 7.73182297e+01 8.55762177e+01 9.49427185e+01 1.03359749e+02 1.08934807e+02 1.15478210e+02 1.28047089e+02 1.42448120e+02 1.51419464e+02 1.59390656e+02 1.69901321e+02 1.78301605e+02 1.91364609e+02 2.07405762e+02 2.18009750e+02 2.31663574e+02 2.43019806e+02 2.53471725e+02 2.67464539e+02 2.88632996e+02 3.04746094e+02 3.15316254e+02 3.33217621e+02 3.40023163e+02 3.60056824e+02 3.82706024e+02 3.94805389e+02 4.22078766e+02 4.30946014e+02 4.33876587e+02 4.56949402e+02 4.76762573e+02 5.06275940e+02 5.47135498e+02 5.54671997e+02 5.50414124e+02 5.68175354e+02 5.90822876e+02 6.11614197e+02 6.50893555e+02 6.81360413e+02 6.81022278e+02 6.99104065e+02 7.24112244e+02 7.61339844e+02 7.97734314e+02 8.10190186e+02 8.55722351e+02 8.60140564e+02 8.34803406e+02 8.74819336e+02 9.33715637e+02 9.74757996e+02 1.01130609e+03 1.00080280e+03 9.78326660e+02 1.03975085e+03 1.12119910e+03 1.13318640e+03 1.14305847e+03 1.15981665e+03 1.17280566e+03 1.22609302e+03 1.26346106e+03 1.27431665e+03 1.34048767e+03 1.35507947e+03 1.36868335e+03 1.40853064e+03 1.40545105e+03 1.44957324e+03 1.51154932e+03 1.58751685e+03 1.58059180e+03 1.52974817e+03 1.58550647e+03 1.66924316e+03 1.73352197e+03 1.76162805e+03 1.74081165e+03 1.74408289e+03 1.81952161e+03 1.89282629e+03 1.94425818e+03 1.96453601e+03 1.97990637e+03 1.99713037e+03 2.04399524e+03 2.07877979e+03 2.10536328e+03 2.16889478e+03 2.20871118e+03 2.26432300e+03 2.23245264e+03 2.27168262e+03 2.37902368e+03 2.39634937e+03 2.48669849e+03 2.48715771e+03 2.41763379e+03 2.47015942e+03 2.56736646e+03 2.69128369e+03 2.78494263e+03 2.71655908e+03 2.66634644e+03 2.74216821e+03 2.82935522e+03 2.88057471e+03 2.93225024e+03 2.98461108e+03 2.96218677e+03 2.96554956e+03 3.05866431e+03 3.15315137e+03 3.23658008e+03 3.24934766e+03 3.29656860e+03 3.27239746e+03 3.21336328e+03 3.32528271e+03 3.43033521e+03 3.56154370e+03 3.61026270e+03 3.46369873e+03 3.47349243e+03 3.63931982e+03 3.82970166e+03 3.82514917e+03 3.80559424e+03 3.83560083e+03 3.77745752e+03 3.91057251e+03 4.06984668e+03 4.04208276e+03 4.06705786e+03 4.09439941e+03 4.16897217e+03 4.23077637e+03 4.25364795e+03 4.32438379e+03 4.38832471e+03 4.42347900e+03 4.37610059e+03 4.46970264e+03 4.59159912e+03 4.60364990e+03 4.81969385e+03 4.73426416e+03 4.61040479e+03 4.73441504e+03 4.73064160e+03 4.94314551e+03 5.21799854e+03 5.12660449e+03 4.89644873e+03 4.89897998e+03 5.14303076e+03 5.24354297e+03 5.43114111e+03 5.32844189e+03 6.08814502e+03 5.89907715e+03 1.01232959e+04 1.69032383e+04 6025358. 87204568. 3.07887225e+06 2.33708775e+06 -80622096. 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. 0. 0. 0. 0. 0. 0. 0. 126740496. 8.08213750e+04 1.40874375e+04 9.36300977e+03 8.29434863e+03 7.85533301e+03 8.18015527e+03 8.19993359e+03 8.21459766e+03 7.88190527e+03 8.09210205e+03 8.63179980e+03 8.63904297e+03 8.28204980e+03 8.04696875e+03 8.20239746e+03 8.67743555e+03 9.03168945e+03 8.76614258e+03 8.49344629e+03 8.51938672e+03 8.61763184e+03 9.05815039e+03 9.19371973e+03 8.91340723e+03 8.80294238e+03 8.85371289e+03 9.07200195e+03 9.20119434e+03 9.10831055e+03 9.16483496e+03 9.57670996e+03 9.81408398e+03 9.39180664e+03 8.98225488e+03 9.23894043e+03 9.79656641e+03 1.01903193e+04 9.78441895e+03 9.32584180e+03 9.46598730e+03 9.95838281e+03 1.04323857e+04 1.01396328e+04 9.54427832e+03 9.68771484e+03 1.01311914e+04 1.04187656e+04 1.04964697e+04 1.03720986e+04 1.00745820e+04 1.01305986e+04 1.05642598e+04 1.02678936e+04 1.01616680e+04 1.07403740e+04 1.09070068e+04 1.08305059e+04 1.05158867e+04 1.01456279e+04 1.07511279e+04 1.15299346e+04 1.13054854e+04 1.06681455e+04 1.03237266e+04 1.05944590e+04 1.12996553e+04 1.17787578e+04 1.14637920e+04 1.12467490e+04 1.11160225e+04 1.08546670e+04 1.12861396e+04 1.17541406e+04 1.14088418e+04 1.13654551e+04 1.15234453e+04 1.16690078e+04 1.15410459e+04 1.14625264e+04 1.18629658e+04 1.19855850e+04 1.20889863e+04 1.18603809e+04 1.14024551e+04 1.14975615e+04 1.21892246e+04 1.27704570e+04 1.22673994e+04 1.15646064e+04 1.17818896e+04 1.22123945e+04 1.25775762e+04 1.27330801e+04 1.23199844e+04 1.22451826e+04 1.22717520e+04 1.24849619e+04 1.27681953e+04 1.25553320e+04 1.25055557e+04 1.24831914e+04 1.26721318e+04 1.27971641e+04 1.26829521e+04 1.28451709e+04 1.29831123e+04 1.32260732e+04 1.29186455e+04 1.23916680e+04 1.26780488e+04 1.34296787e+04 1.37411396e+04 1.31121318e+04 1.25050430e+04 1.26319551e+04 1.34240859e+04 1.41379678e+04 1.35190352e+04 1.29269072e+04 1.32126113e+04 1.32210059e+04 1.33361611e+04 1.35610586e+04 1.34272900e+04 1.37061328e+04 1.35814238e+04 1.35486514e+04 1.36775674e+04 1.33745996e+04 1.36567666e+04 1.42425898e+04 1.42777822e+04 1.37862070e+04 1.33304609e+04 1.34247197e+04 1.40433174e+04 1.46631787e+04 1.41071699e+04 1.33654697e+04 1.36239102e+04 1.43446748e+04 1.47724668e+04 1.42380371e+04 1.38762236e+04 1.40387129e+04 1.40304346e+04 1.43608232e+04 1.45186123e+04 1.39323789e+04 1.39378740e+04 1.44868320e+04 1.47059707e+04 1.45417354e+04 1.42568213e+04 1.43149443e+04 1.45417441e+04 1.49843262e+04 1.47139541e+04 1.39531719e+04 1.41978379e+04 1.46096074e+04 1.48645625e+04 1.48919902e+04 1.44020645e+04 1.43645322e+04 1.46501533e+04 1.49701191e+04 1.49744863e+04 1.46264375e+04 1.48217197e+04 1.48355703e+04 1.48679551e+04 1.48590020e+04 1.44937881e+04 1.48074307e+04 1.53705459e+04 1.54913848e+04 1.49165908e+04 1.43266602e+04 1.44832773e+04 1.52015352e+04 1.58127549e+04 1.51915645e+04 1.44046807e+04 1.46014365e+04 1.50674033e+04 1.54438154e+04 1.54914795e+04 1.49026094e+04 1.47940693e+04 1.51101445e+04 1.52550371e+04 1.52821504e+04 15149. 1.52361445e+04 1.50406230e+04 1.51645986e+04 1.53172891e+04 1.51239385e+04 1.52340410e+04 1.53142188e+04 1.54200596e+04 1.49095439e+04 1.46337227e+04 1.52552832e+04 1.58464697e+04 1.59661016e+04 1.52906260e+04 1.46096709e+04 1.47303457e+04 1.55774082e+04 1.62996104e+04 1.58130322e+04 1.50916045e+04 1.47685645e+04 1.47635273e+04 1.54926543e+04 1.60497861e+04 1.56289990e+04 1.52715654e+04 1.52527676e+04 1.51986855e+04 1.48396660e+04 1.48840176e+04 1.53410029e+04 1.54289062e+04 1.58829307e+04 1.56011885e+04 1.46333838e+04 1.49324043e+04 1.54588838e+04 1.54301455e+04 1.54828301e+04 1.53417861e+04 1.56506904e+04 1.57425010e+04 1.50386631e+04 1.45312275e+04 1.48311064e+04 1.56148467e+04 1.61033066e+04 1.58065020e+04 1.49180713e+04 1.45295273e+04 1.48683115e+04 1.55456260e+04 1.59601855e+04 1.56658135e+04 1.48943545e+04 1.47985957e+04 1.56186885e+04 1.56444893e+04 1.48768350e+04 1.48156064e+04 1.51321045e+04 1.51274023e+04 1.55746826e+04 1.51864609e+04 1.47075078e+04 1.50732256e+04 1.46594971e+04 1.50325322e+04 1.55242305e+04 1.47102578e+04 1.49273994e+04 1.54437783e+04 1.50616709e+04 1.49746836e+04 1.49295527e+04 1.49722471e+04 1.51512021e+04 1.49319463e+04 1.44300059e+04 1.45410146e+04 1.52384912e+04 1.55413945e+04 1.51388447e+04 1.45276162e+04 1.41801074e+04 1.44305566e+04 1.50875703e+04 1.54639854e+04 1.51379482e+04 1.43204443e+04 1.42754902e+04 1.48173164e+04 1.47379111e+04 1.45081787e+04 1.44718623e+04 1.44932627e+04 1.44581650e+04 1.50007197e+04 1.46427109e+04 1.40416611e+04 1.43017139e+04 1.39485000e+04 1.44527471e+04 1.47885322e+04 1.42808135e+04 1.47659805e+04 1.43874160e+04 1.37641904e+04 1.41660127e+04 1.38711621e+04 1.41187861e+04 1.50090791e+04 1.42115059e+04 1.34306016e+04 1.37045146e+04 1.42257832e+04 1.46905137e+04 1.44311582e+04 1.36364434e+04 1.31105879e+04 1.33979053e+04 1.42075752e+04 1.45976133e+04 1.42546045e+04 1.34665830e+04 1.32751650e+04 1.38113936e+04 1.40154775e+04 1.34998564e+04 1.32716807e+04 1.34891104e+04 1.34966699e+04 1.38087295e+04 1.37330039e+04 1.31928545e+04 1.32772725e+04 1.31620371e+04 1.31107686e+04 1.33625615e+04 1.32438848e+04 1.34968730e+04 1.31986270e+04 1.26712207e+04 1.29788896e+04 1.26562236e+04 1.29084482e+04 1.37874424e+04 1.30647861e+04 1.21458008e+04 1.23385088e+04 1.29584268e+04 1.32843818e+04 1.33251816e+04 1.26297422e+04 1.19988271e+04 1.21399092e+04 1.27523545e+04 1.33244180e+04 1.28394951e+04 1.20348232e+04 1.18931152e+04 1.22068447e+04 1.24925127e+04 1.28109541e+04 1.26612832e+04 1.18752451e+04 1.16772080e+04 1.21442490e+04 1.22724658e+04 1.20982383e+04 1.19678789e+04 1.17531621e+04 1.15930518e+04 1.20869834e+04 1.21316152e+04 1.14828262e+04 1.13737637e+04 1.16450166e+04 1.16123242e+04 1.15730400e+04 1.14176289e+04 1.16203701e+04 1.16345645e+04 1.12335000e+04 1.11244736e+04 1.09066270e+04 1.12410039e+04 1.16935303e+04 1.14801484e+04 1.08613496e+04 1.05145205e+04 1.08860195e+04 1.14340195e+04 1.09590156e+04 1.03612861e+04 1.05181709e+04 1.07484639e+04 1.09346719e+04 1.11886611e+04 1.09524961e+04 1.02804111e+04 9.92850586e+03 1.02638555e+04 1.06985977e+04 1.06071416e+04 1.02511377e+04 1.01819072e+04 1.01533086e+04 1.02783105e+04 1.00722363e+04 9.78738867e+03 9.81991016e+03 9.71803125e+03 1.00116611e+04 1.02227461e+04 9.79407324e+03 9.71437598e+03 9.68411230e+03 9.87886719e+03 9.60733496e+03 9.05648438e+03 9.40170605e+03 9.87839648e+03 9.47307812e+03 8.92973438e+03 9.11798535e+03 9.56377246e+03 9.40474316e+03 9.14587891e+03 9.13526855e+03 8.79690918e+03 8.68576465e+03 9.11457520e+03 9.15920020e+03 8.72947656e+03 8.42350586e+03 8.26916406e+03 8.65415723e+03 9.03926953e+03 8.59589355e+03 8.28499512e+03 8.41456152e+03 8.35598438e+03 8.55782324e+03 8.55512109e+03 8.00046338e+03 7.87786572e+03 8.01938379e+03 8.02337646e+03 8.02902930e+03 7.98359570e+03 8.10353027e+03 7.99671094e+03 7.60133057e+03 7.53798535e+03 7.37363281e+03 7.62796240e+03 8.02189062e+03 7.74428320e+03 7.25736328e+03 7.14420947e+03 7.33252051e+03 7.76262500e+03 8.21262988e+03 8.95621582e+03 7.80160059e+03 1.47423975e+04 1.02254156e+05 -25335056. 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. 0. 0. 0. 0. 0. 0. -5383558. 3.26159453e+04 7.14658496e+03 5.74185400e+03 5.02198682e+03 4.90313232e+03 4.95135107e+03 4.83032373e+03 4.63217432e+03 4.57211377e+03 4.72250000e+03 4.71847900e+03 4.54416895e+03 4.54001172e+03 4.50322119e+03 4.40387402e+03 4.37666992e+03 4.31373730e+03 4.26031689e+03 4.22417480e+03 4.16845020e+03 4.11342383e+03 3.98597339e+03 3.90097021e+03 4.06805469e+03 4.03673438e+03 3.79251318e+03 3.72406274e+03 3.88298047e+03 3.86703003e+03 3.71112793e+03 3.66928345e+03 3.60777173e+03 3.55623047e+03 3.51459595e+03 3.45877710e+03 3.42086353e+03 3.36465601e+03 3.24709741e+03 3.19233887e+03 3.32359741e+03 3.29506616e+03 3.16427832e+03 3.11048975e+03 3.07382251e+03 3.04006445e+03 2.98401538e+03 2.93125537e+03 2.91336597e+03 2.78972974e+03 2.71975293e+03 2.77939014e+03 2.74230933e+03 2.77783667e+03 2.75412012e+03 2.61683203e+03 2.50376758e+03 2.45163208e+03 2.56908398e+03 2.55403564e+03 2.41389380e+03 2.34910449e+03 2.32634985e+03 2.30484619e+03 2.24356055e+03 2.26828003e+03 2.22608667e+03 2.08102075e+03 2.03371436e+03 2.10919043e+03 2.12051758e+03 2.02894617e+03 1.96886951e+03 1.93443689e+03 1.89379346e+03 1.83286707e+03 1.80001978e+03 1.80665857e+03 1.76992444e+03 1.69933118e+03 1.67121716e+03 1.66248059e+03 1.62216272e+03 1.62739087e+03 1.58808435e+03 1.50902283e+03 1.50099683e+03 1.46755994e+03 1.44567944e+03 1.42808765e+03 1.37461475e+03 1.34038049e+03 1.28724316e+03 1.24220837e+03 1.26526147e+03 1.23389014e+03 1.14755383e+03 1.13567834e+03 1.16904785e+03 1.18123291e+03 1.11399866e+03 1.05614087e+03 1.01290405e+03 9.81147217e+02 9.66318848e+02 9.41100586e+02 9.28231445e+02 8.98475464e+02 8.88130249e+02 8.58803162e+02 8.14074219e+02 8.08663757e+02 7.61285583e+02 7.36766724e+02 7.56941467e+02 7.27624451e+02 6.87394043e+02 6.48573792e+02 6.22555420e+02 6.36270996e+02 6.17953613e+02 5.78601318e+02 5.44457153e+02 5.24956116e+02 5.20052246e+02 5.00379364e+02 4.94910858e+02 4.79051086e+02 4.46599762e+02 4.25080048e+02 4.08660461e+02 3.98931183e+02 3.82015991e+02 3.60143127e+02 3.39521912e+02 3.24862610e+02 3.15574219e+02 2.92300415e+02 2.77947235e+02 2.78897247e+02 2.63624512e+02 2.43189240e+02 2.22996887e+02 2.10308899e+02 2.10377548e+02 1.97762100e+02 1.81000107e+02 1.65216568e+02 1.53392334e+02 1.48146057e+02 1.37354828e+02 1.27242226e+02 1.15589211e+02 1.08602806e+02 1.04875397e+02 9.41352158e+01 8.49617844e+01 7.73986588e+01 6.96761398e+01 6.20250244e+01 5.53663864e+01 5.00287666e+01 4.43962669e+01 3.91439972e+01 3.29158249e+01 2.82980824e+01 2.55966301e+01 2.07539139e+01 1.66195602e+01 1.38515224e+01 1.10631628e+01 8.92616653e+00 6.72570229e+00 4.91192532e+00 3.73694015e+00 2.80447817e+00 2.22656274e+00 2.04100466e+00 2.24814701e+00 2.83491254e+00 3.76874495e+00 5.08501196e+00 6.65172005e+00 8.78893852e+00 1.17259350e+01 1.44236622e+01 1.71301365e+01 2.00293045e+01 2.41063442e+01 3.00270023e+01 3.46988869e+01 3.87347412e+01 4.33133316e+01 4.86775398e+01 5.59682884e+01 6.26048813e+01 7.11670685e+01 7.71198273e+01 8.23029633e+01 9.25515976e+01 1.00900970e+02 1.11772163e+02 1.19748352e+02 1.25968323e+02 1.37493408e+02 1.47535400e+02 1.59425766e+02 1.66018814e+02 1.80491837e+02 2.04072952e+02 2.09978699e+02 2.16836884e+02 2.24363510e+02 2.35113083e+02 2.63151672e+02 2.79670197e+02 2.85268585e+02 2.90405396e+02 3.05142670e+02 3.31414642e+02 3.46685852e+02 3.71607758e+02 3.86549805e+02 3.94126373e+02 4.00422791e+02 4.14486572e+02 4.59311584e+02 4.73034271e+02 4.76723785e+02 4.94694763e+02 5.12276550e+02 5.54855225e+02 5.77302002e+02 5.69445129e+02 5.84954712e+02 6.34277893e+02 6.62877380e+02 6.50394958e+02 6.67915527e+02 7.26405884e+02 7.51973145e+02 7.53732910e+02 7.61110779e+02 7.80726562e+02 8.48221069e+02 8.64054626e+02 8.58971436e+02 8.91542664e+02 9.19002014e+02 9.68966980e+02 9.90953613e+02 9.83707092e+02 9.88141785e+02 1.04863232e+03 1.13628149e+03 1.13158252e+03 1.14176648e+03 1.18363501e+03 1.20097339e+03 1.22920032e+03 1.25458948e+03 1.27923840e+03 1.27842932e+03 1.30246838e+03 1.36756519e+03 1.40826782e+03 1.48447290e+03 1.47029993e+03 1.44007068e+03 1.51277600e+03 1.58179675e+03 1.65855933e+03 1.65384143e+03 1.63984985e+03 1.67414258e+03 1.69717236e+03 1.76817517e+03 1.80225000e+03 1.86595288e+03 1.89964197e+03 1.89206714e+03 1.90211853e+03 1.88366345e+03 2.00097009e+03 2.16586719e+03 2.15308325e+03 2.12209717e+03 2.09750269e+03 2.09295557e+03 2.23544360e+03 2.38942163e+03 2.35676880e+03 2.27997974e+03 2.30897607e+03 2.41589746e+03 2.47309521e+03 2.55778662e+03 2.58391919e+03 2.56520654e+03 2.59167847e+03 2.61815918e+03 2.75773730e+03 2.80522192e+03 2.70198120e+03 2.74170068e+03 2.94314648e+03 2.96097241e+03 2.85230811e+03 2.94186377e+03 3.14187842e+03 3.16181250e+03 3.11640210e+03 3.08548096e+03 3.12841431e+03 3.34522119e+03 3.39925269e+03 3.34969849e+03 3.30542603e+03 3.31858618e+03 3.45966382e+03 3.52758618e+03 3.55023755e+03 3.50846143e+03 3.64150269e+03 3.82321289e+03 3.75431836e+03 3.87266260e+03 3.90294775e+03 3.82768286e+03 3.93615869e+03 3.99806885e+03 4.03540845e+03 4.02461572e+03 4.00545728e+03 4.00425317e+03 4.23417725e+03 4.50958057e+03 4.32770947e+03 4.18200195e+03 4.36186279e+03 4.48381787e+03 4.68356250e+03 4.60383398e+03 4.49427393e+03 4.75393604e+03 4.80881885e+03 4.60360400e+03 4.61872656e+03 4.96523926e+03 5.05534814e+03 4.93323828e+03 4.90636523e+03 4.75489062e+03 5.05009863e+03 5.47218896e+03 5.34108496e+03 5.22641602e+03 5.13805469e+03 5.10979199e+03 5.42832617e+03 5.76868164e+03 5.66834375e+03 5.42831592e+03 5.44181738e+03 5.63779248e+03 5.72685059e+03 5.93322070e+03 5.84858740e+03 5.73148779e+03 5.91587939e+03 5.96698193e+03 6.19514990e+03 6.21783643e+03 6.06442773e+03 6.13771289e+03 6.16681494e+03 6.35369385e+03 6.27135498e+03 6.26024951e+03 6.66271826e+03 6.67437646e+03 6.48988525e+03 6.39190186e+03 6.49323389e+03 6.95996045e+03 6.94919971e+03 6.81523096e+03 6.70425098e+03 6.69931885e+03 6.94301807e+03 7.01995264e+03 7.07948975e+03 6.96375293e+03 7.15252246e+03 7.47806348e+03 7.30642725e+03 7.54719824e+03 7.60441113e+03 7.45398828e+03 7.41024170e+03 7.39388135e+03 7.72615723e+03 7.79974609e+03 7.54789990e+03 7.53563965e+03 8.02495020e+03 8.18563867e+03 7.73574561e+03 7.60295166e+03 7.85912793e+03 8.23603906e+03 8.56734863e+03 8.31035059e+03 7.95846924e+03 8.39575000e+03 8.65143750e+03 8.49847559e+03 8.38732520e+03 8.44035547e+03 8.41062500e+03 8.48718555e+03 8.70317969e+03 8.49457031e+03 8.76170117e+03 9.24429785e+03 8.98080469e+03 9.02262598e+03 8.89457324e+03 8.83730469e+03 9.33966602e+03 9.37278809e+03 9.22412793e+03 9.04278418e+03 8.84738379e+03 9.10370605e+03 9.62278027e+03 1.00096211e+04 9.56129980e+03 9.28925879e+03 9.54414355e+03 9.67939648e+03 1.00361729e+04 1.00584785e+04 9.79752539e+03 9.78666113e+03 9.79974902e+03 9.86117285e+03 9.71085059e+03 1.00507920e+04 1.05049883e+04 1.02307168e+04 1.03690244e+04 1.02803496e+04 1.00575244e+04 1.07074951e+04 1.08134258e+04 1.04869316e+04 1.03059180e+04 1.02026826e+04 1.06028506e+04 1.06385605e+04 1.10288662e+04 1.11916279e+04 1.08169688e+04 1.06167744e+04 1.07937334e+04 1.13547217e+04 1.12256143e+04 1.10462754e+04 1.09138066e+04 1.09430928e+04 1.11572021e+04 1.11547324e+04 1.14806201e+04 1.15683682e+04 1.12439668e+04 1.16460234e+04 1.18484160e+04 1.16054600e+04 1.16006992e+04 1.16653350e+04 1.17226309e+04 1.14651377e+04 1.13672285e+04 1.20185449e+04 1.22025303e+04 1.16045273e+04 1.12986240e+04 1.19491758e+04 1.27387520e+04 1.25615449e+04 1.18561641e+04 1.17205957e+04 1.24615186e+04 1.25175254e+04 1.21587148e+04 1.25220850e+04 1.22561250e+04 1.17237578e+04 1.21663311e+04 1.28970400e+04 1.32071250e+04 1.25429238e+04 1.19697764e+04 1.27275830e+04 1.33910723e+04 1.30509766e+04 1.24732959e+04 1.23251113e+04 1.27428838e+04 1.29063311e+04 1.32596719e+04 1.32611875e+04 1.28447812e+04 1.29598340e+04 1.29960273e+04 1.34439082e+04 1.32215996e+04 1.28927949e+04 1.34009854e+04 1.33755537e+04 1.35204551e+04 1.33271934e+04 1.30922646e+04 1.38661143e+04 1.35795889e+04 1.30186182e+04 1.33778164e+04 1.36745879e+04 1.37884512e+04 1.36324834e+04 1.39672197e+04 1.41301221e+04 1.38288027e+04 1.34360547e+04 1.33986992e+04 1.41275928e+04 1.38957500e+04 1.35564658e+04 1.39764590e+04 1.39976621e+04 1.39851357e+04 1.39534072e+04 1.43670859e+04 1.42524268e+04 1.38326660e+04 1.43663096e+04 1.44671523e+04 1.42524307e+04 1.43082080e+04 1.42901553e+04 1.41821631e+04 1.38421699e+04 1.36272441e+04 1.43496406e+04 1.52383027e+04 1.44984287e+04 1.36456104e+04 1.43019248e+04 1.52576377e+04 1.50954688e+04 1.43015977e+04 1.39870752e+04 1.48058691e+04 1.48454346e+04 1.43385459e+04 1.49782705e+04 1.49706025e+04 1.42240508e+04 1.42118926e+04 1.49720508e+04 1.54065889e+04 1.47153867e+04 1.41259189e+04 1.47055205e+04 1.55787568e+04 1.52921230e+04 1.45874453e+04 1.42305996e+04 1.48679639e+04 1.55933125e+04 1.51388867e+04 1.46860586e+04 1.48394990e+04 1.50293906e+04 1.49653779e+04 1.54056943e+04 1.50854863e+04 1.46380449e+04 1.50438574e+04 1.51115176e+04 1.54432373e+04 1.51298320e+04 1.47320439e+04 1.52054365e+04 1.48382920e+04 1.48966943e+04 1.54729150e+04 1.53078271e+04 1.52224268e+04 1.51228262e+04 1.56528408e+04 1.57450322e+04 1.51685225e+04 1.48140752e+04 1.48579844e+04 1.57545215e+04 1.52979141e+04 1.45975381e+04 1.52090898e+04 1.66432031e+04 1.80799043e+04 1.37333379e+04 1.50674863e+04 3.85481758e+04 5.06335820e+04 2.69668031e+05 -6.62653440e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.34731581e+10 1.21308297e+05 6.75652422e+04 2.84502012e+04 2.12904902e+04 1.52820908e+04 1.54158145e+04 1.67680820e+04 1.53074326e+04 1.46685762e+04 1.48428945e+04 1.48198271e+04 1.49791543e+04 1.54728203e+04 1.53096641e+04 1.47447295e+04 1.50042402e+04 1.53620791e+04 1.49431826e+04 1.47104746e+04 1.47112139e+04 1.48849326e+04 1.52309258e+04 1.53097705e+04 1.49096963e+04 1.44235518e+04 1.47515752e+04 1.52420996e+04 1.50047617e+04 1.49288955e+04 1.47475645e+04 1.46402598e+04 1.51043281e+04 1.47962539e+04 1.43178369e+04 1.45481201e+04 1.45406240e+04 1.47213740e+04 1.48683291e+04 1.44435830e+04 1.44002627e+04 1.48531094e+04 1.54721924e+04 1.50404609e+04 1.40027764e+04 1.39716973e+04 1.43735039e+04 1.46476318e+04 1.48879971e+04 1.45983398e+04 1.41755615e+04 1.45047090e+04 1.46857100e+04 1.42501396e+04 1.40978018e+04 1.40548779e+04 1.44858770e+04 1.49731621e+04 1.42245967e+04 1.37031504e+04 1.40341826e+04 1.43235703e+04 1.45459404e+04 1.43112236e+04 1.39148018e+04 1.37300391e+04 1.40359502e+04 1.46403574e+04 1.42070908e+04 1.35181230e+04 1.37572266e+04 1.39883311e+04 1.39483740e+04 1.40961992e+04 1.38571201e+04 1.34858154e+04 1.37937354e+04 1.40499766e+04 1.37565898e+04 1.35219141e+04 1.33675117e+04 1.34121357e+04 1.37783662e+04 1.40878574e+04 1.36937832e+04 1.31443838e+04 1.33501611e+04 1.36740322e+04 1.33882314e+04 1.31584209e+04 1.31373418e+04 1.33399658e+04 1.37024268e+04 1.34503477e+04 1.29198369e+04 1.28391338e+04 1.28780596e+04 1.31426816e+04 1.32110303e+04 1.29551484e+04 1.28974180e+04 1.32020762e+04 1.34778369e+04 1.31075117e+04 1.23830117e+04 1.23940977e+04 1.27882744e+04 1.28851543e+04 1.28486250e+04 1.25616172e+04 1.23383799e+04 1.27084873e+04 1.27348809e+04 1.23294600e+04 1.23652598e+04 1.23982549e+04 1.23150605e+04 1.25390674e+04 1.24383271e+04 1.20842920e+04 1.20373994e+04 1.20087979e+04 1.19984268e+04 1.22297773e+04 1.24551084e+04 1.20931729e+04 1.17949482e+04 1.27732354e+04 1.60121436e+04 1.62109238e+04 1.67237148e+04 1.63326426e+04 1.64813438e+04 1.68807402e+04 1.57465088e+04 1.52859678e+04 1.32893027e+04 1.26478887e+04 1.19311445e+04 1.47663359e+04 1.55324170e+04 1.61082051e+04 1.59835439e+04 1.61728330e+04 1.59439609e+04 1.55731768e+04 1.57183350e+04 1.57954619e+04 1.59289023e+04 1.60749072e+04 1.55298506e+04 1.41318887e+04 1.39156904e+04 1.19971396e+04 1.14608418e+04 1.07033428e+04 1.02620156e+04 1.01595488e+04 1.07839814e+04 1.07636064e+04 1.01994141e+04 9.99966602e+03 1.03497236e+04 1.04832051e+04 1.01476357e+04 9.80041016e+03 9.83494141e+03 1.01195361e+04 1.02667939e+04 9.85032031e+03 9.66569727e+03 9.71249707e+03 9.61533789e+03 9.75274219e+03 9.79341406e+03 9.49482617e+03 9.48607812e+03 9.63741016e+03 9.60898145e+03 9.32289844e+03 9.16098828e+03 9.11167383e+03 9.08755176e+03 9.23366895e+03 9.47125684e+03 9.44461133e+03 8.78299902e+03 8.86242285e+03 9.23340234e+03 8.84398730e+03 8.59515820e+03 8.64026660e+03 8.64017090e+03 8.84915234e+03 8.84144336e+03 8.46055176e+03 8.29018750e+03 8.32520312e+03 8.44562988e+03 8.45777637e+03 8.21995410e+03 8.18572021e+03 8.36458594e+03 8.37674414e+03 8.01931006e+03 7.88121387e+03 7.82191455e+03 7.88509375e+03 7.93971143e+03 8.04979150e+03 8.02399268e+03 7.57678027e+03 7.55824805e+03 7.70642725e+03 7.54693652e+03 7.44318750e+03 7.40983252e+03 7.36432373e+03 7.50565625e+03 7.47721729e+03 7.16428809e+03 7.08984473e+03 7.03657275e+03 7.05277100e+03 7.12460010e+03 6.95278418e+03 6.90206641e+03 6.93049805e+03 6.97525342e+03 6.96752881e+03 6.60540283e+03 6.45977148e+03 6.58633203e+03 6.57884521e+03 6.61514990e+03 6.48085742e+03 6.22986719e+03 6.34669580e+03 6.51204980e+03 6.24890234e+03 6.10922461e+03 6.15908301e+03 6.09424902e+03 6.05292822e+03 5.94777539e+03 6.04211963e+03 5.98242236e+03 5.77302148e+03 5.86579541e+03 5.67702637e+03 5.64457178e+03 5.74065332e+03 5.50455371e+03 5.49635742e+03 5.55528613e+03 5.42651074e+03 5.20862939e+03 5.20373828e+03 5.42743750e+03 5.46243018e+03 5.10117578e+03 5.00130566e+03 5.13169775e+03 5.05144629e+03 5.03896582e+03 4.85416553e+03 4.78004492e+03 4.83318848e+03 4.88568066e+03 4.79512939e+03 4.65610645e+03 4.56491504e+03 4.58302783e+03 4.62627783e+03 4.46024902e+03 4.33791846e+03 4.30928223e+03 4.26357129e+03 4.32165381e+03 4.39167041e+03 4.25405518e+03 4.05376221e+03 4.00119873e+03 4.14794043e+03 4.13232129e+03 3.87746460e+03 3.93449658e+03 4.00459595e+03 3.76552710e+03 3.73241162e+03 3.67680200e+03 3.63738062e+03 3.74754346e+03 3.64240576e+03 3.49124268e+03 3.54904834e+03 3.51684009e+03 3.37672534e+03 3.38577539e+03 3.37239258e+03 3.31749341e+03 3.19160205e+03 3.12652515e+03 3.18071899e+03 3.19363062e+03 3.10532275e+03 2.96980322e+03 2.93155420e+03 2.99498267e+03 2.98616016e+03 2.83761035e+03 2.77893677e+03 2.76842310e+03 2.77857129e+03 2.76952368e+03 2.61706152e+03 2.58379199e+03 2.62548218e+03 2.59183325e+03 2.48400513e+03 2.48836670e+03 2.45456201e+03 2.35293945e+03 2.39645386e+03 2.38819312e+03 2.24252368e+03 2.14181470e+03 2.15548389e+03 2.17895801e+03 2.15174585e+03 2.09686743e+03 2.02266284e+03 1.98876135e+03 2.02192297e+03 2.00034729e+03 1.89025574e+03 1.83849292e+03 1.85707068e+03 1.87416431e+03 1.78417896e+03 1.69956885e+03 1.70544531e+03 1.67177844e+03 1.62919458e+03 1.60352649e+03 1.58292542e+03 1.54728223e+03 1.49588403e+03 1.48085376e+03 1.45538452e+03 1.41279932e+03 1.35836511e+03 1.33522913e+03 1.33170691e+03 1.30517993e+03 1.25523169e+03 1.22527551e+03 1.20552747e+03 1.20782483e+03 1.18075281e+03 1.10990576e+03 1.09465918e+03 1.07839758e+03 1.04471851e+03 1.00790259e+03 9.74057617e+02 9.73687317e+02 9.48596497e+02 8.99551941e+02 8.55229370e+02 8.58462402e+02 8.61152161e+02 8.24655396e+02 7.95546814e+02 7.66769836e+02 7.50741760e+02 7.12647339e+02 6.68125183e+02 6.68347351e+02 6.62503601e+02 6.42823853e+02 6.17708435e+02 5.77573425e+02 5.63421143e+02 5.55302551e+02 5.42037292e+02 5.29190674e+02 4.94144806e+02 4.64785461e+02 4.44251190e+02 4.38747040e+02 4.33613678e+02 4.12361847e+02 3.89353363e+02 3.56927979e+02 3.49033997e+02 3.45023773e+02 3.22672913e+02 3.11156250e+02 2.91933167e+02 2.75607697e+02 2.69813843e+02 2.50449234e+02 2.34498611e+02 2.29508240e+02 2.18146713e+02 1.98415421e+02 1.81716949e+02 1.73241440e+02 1.65217056e+02 1.59195251e+02 1.51085953e+02 1.35620361e+02 1.22862572e+02 1.12058868e+02 1.06237991e+02 1.01287971e+02 9.08592987e+01 8.06892166e+01 7.18302078e+01 6.59528809e+01 6.11147804e+01 5.54049034e+01 4.87728729e+01 4.23025818e+01 3.74224854e+01 3.18592930e+01 2.64353085e+01 2.29185009e+01 1.94700623e+01 1.60888844e+01 1.32283545e+01 9.96556568e+00 7.36765909e+00 5.57274246e+00 4.05957699e+00 2.76746154e+00 1.80283046e+00 1.26197505e+00 1.09597850e+00 1.30152822e+00 1.89243388e+00 2.82804704e+00 4.10312986e+00 5.67427731e+00 7.83227539e+00 1.02686977e+01 1.26944056e+01 1.60982647e+01 2.00374374e+01 2.38356590e+01 2.79370327e+01 3.19905949e+01 3.72399254e+01 4.35703621e+01 4.94330063e+01 5.54517021e+01 5.96190186e+01 6.59491730e+01 7.50038071e+01 8.40704117e+01 9.31002197e+01 9.97467499e+01 1.07257523e+02 1.13110283e+02 1.24841080e+02 1.40288818e+02 1.46704361e+02 1.55906250e+02 1.66891510e+02 1.76490173e+02 1.86807556e+02 1.99768723e+02 2.14786560e+02 2.30156708e+02 2.44938828e+02 2.51335968e+02 2.58402283e+02 2.77856110e+02 2.97028687e+02 3.13823029e+02 3.31114929e+02 3.37779327e+02 3.54514771e+02 3.69636597e+02 3.88591431e+02 4.17082306e+02 4.24925415e+02 4.38970459e+02 4.54428802e+02 4.60757507e+02 4.89050659e+02 5.35272827e+02 5.47980164e+02 5.46725159e+02 5.74005371e+02 5.87560547e+02 5.92523376e+02 6.30454224e+02 6.64358215e+02 6.83055847e+02 7.05774109e+02 7.09718994e+02 7.37637451e+02 7.76828918e+02 8.05148865e+02 8.53850952e+02 8.54822937e+02 8.32031494e+02 8.55173828e+02 9.13699646e+02 9.60466675e+02 9.80906372e+02 9.92603271e+02 9.78281189e+02 1.02885596e+03 1.10055115e+03 1.10509363e+03 1.12687952e+03 1.13812292e+03 1.16671094e+03 1.22559460e+03 1.22252954e+03 1.24503894e+03 1.33810046e+03 1.36815881e+03 1.36583911e+03 1.36150525e+03 1.35628943e+03 1.42112256e+03 1.50908008e+03 1.57988855e+03 1.57801794e+03 1.52733008e+03 1.54859924e+03 1.63700745e+03 1.71267932e+03 1.71817847e+03 1.73241479e+03 1.72936121e+03 1.77343494e+03 1.85879932e+03 1.91868872e+03 1.94751440e+03 1.95442957e+03 2.00485339e+03 2.01878430e+03 1.99389258e+03 2.06805029e+03 2.14794043e+03 2.19843164e+03 2.26819409e+03 2.22547241e+03 2.20232422e+03 2.30832520e+03 2.38095630e+03 2.47260303e+03 2.47632104e+03 2.41271411e+03 2.42217505e+03 2.53714917e+03 2.67704321e+03 2.72746851e+03 2.67684668e+03 2.66921216e+03 2.71817358e+03 2.74307568e+03 2.80467358e+03 2.90425732e+03 2.98537524e+03 2.96473608e+03 2.93520630e+03 2.96038281e+03 3.06060986e+03 3.18699561e+03 3.26084302e+03 3.27884521e+03 3.20627319e+03 3.16337793e+03 3.27532666e+03 3.41695166e+03 3.54893384e+03 3.54660547e+03 3.44676685e+03 3.41670972e+03 3.57863257e+03 3.77206689e+03 3.72997681e+03 3.78593970e+03 3.78171411e+03 3.73358545e+03 3.86942261e+03 3.96513208e+03 3.99631079e+03 4.00285449e+03 4.08641138e+03 4.14075391e+03 4.11928467e+03 4.18611182e+03 4.24492676e+03 4.38430273e+03 4.41499854e+03 4.33775000e+03 4.38772949e+03 4.39656885e+03 4.51556836e+03 4.80960938e+03 4.73878174e+03 4.57541895e+03 4.59756445e+03 4.71897803e+03 4.93826074e+03 5.09065869e+03 4.98138232e+03 4.86717041e+03 4.97572754e+03 5.12552246e+03 5.09437158e+03 5.25261963e+03 5.27258545e+03 5.99183203e+03 5.77213037e+03 6.52446191e+03 1.23257295e+04 1.78918145e+04 87204568. 3.07887225e+06 2.33708775e+06 -80622096. 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. 0. 0. 0. 0. 0. 0. 0. 253480992. 1.62584078e+05 2.55655820e+04 1.11718555e+04 1.07633545e+04 8.74144238e+03 8.27052148e+03 8.12594434e+03 8.19182568e+03 7.69515234e+03 7.96850928e+03 8.50539355e+03 8.47945410e+03 8.18519678e+03 8.02309082e+03 8.04551807e+03 8.47998145e+03 8.95442188e+03 8.68768652e+03 8.42458203e+03 8.39836719e+03 8.53180176e+03 8.97950586e+03 9.00704102e+03 8.73835352e+03 8.69566113e+03 8.97664648e+03 8.95414062e+03 8.79775098e+03 8.93179102e+03 9.23859863e+03 9.56926562e+03 9.61215527e+03 9.17650684e+03 8.82502637e+03 9.13634375e+03 9.74233301e+03 1.00090361e+04 9.67431641e+03 9.30780859e+03 9.26060547e+03 9.74060254e+03 1.03155889e+04 1.00594766e+04 9.51058203e+03 9.60904688e+03 1.01780576e+04 1.01936406e+04 1.00154209e+04 1.01125840e+04 1.00559990e+04 1.03011660e+04 1.04022666e+04 9.96334277e+03 1.00352910e+04 1.06317578e+04 1.09638027e+04 1.07574609e+04 1.02693965e+04 9.99009082e+03 1.06433867e+04 1.13753027e+04 1.11612051e+04 1.06407197e+04 1.03292656e+04 1.02979170e+04 1.10104619e+04 1.16612695e+04 1.13857354e+04 1.11074062e+04 1.10641025e+04 1.08488066e+04 1.10863418e+04 1.15083711e+04 1.11936816e+04 1.10817188e+04 1.15251992e+04 1.14225176e+04 1.10229619e+04 1.12660205e+04 1.18408809e+04 1.20542598e+04 1.19591826e+04 1.17220615e+04 1.13792051e+04 1.12718145e+04 1.19250811e+04 1.26389609e+04 1.21672734e+04 1.15014961e+04 1.15009463e+04 1.20542461e+04 1.26186064e+04 1.26127080e+04 1.20779277e+04 1.19431289e+04 1.23267783e+04 1.23435918e+04 1.23304072e+04 1.24214668e+04 1.23857793e+04 1.25430869e+04 1.25630439e+04 1.22363574e+04 1.24135918e+04 1.27770576e+04 1.30374580e+04 1.30508662e+04 1.27841797e+04 1.23520957e+04 1.24746338e+04 1.32279287e+04 1.34617393e+04 1.29083447e+04 1.25174297e+04 1.24070283e+04 1.31169668e+04 1.39026934e+04 1.34298047e+04 1.27881953e+04 1.28849346e+04 1.32551494e+04 1.32777051e+04 1.30677402e+04 1.31380469e+04 1.36533604e+04 1.37800537e+04 1.34307402e+04 1.30934854e+04 1.30991846e+04 1.37227354e+04 1.42811025e+04 1.40570566e+04 1.35597988e+04 1.32791855e+04 1.31267578e+04 1.37284111e+04 1.44864443e+04 1.40044033e+04 1.33807217e+04 1.33581104e+04 1.39796270e+04 1.45839902e+04 1.41844629e+04 1.37582334e+04 1.37988086e+04 1.40114932e+04 1.42556855e+04 1.42057656e+04 1.38123320e+04 1.37092246e+04 1.43314463e+04 1.45980342e+04 1.41048232e+04 1.38359268e+04 1.40973457e+04 1.45091719e+04 1.48793750e+04 1.46289580e+04 1.38710840e+04 1.39813506e+04 1.45530078e+04 1.47030361e+04 1.44943047e+04 1.43096699e+04 1.42844736e+04 1.43712461e+04 1.46832246e+04 1.45218652e+04 1.42758604e+04 1.47528066e+04 1.50294297e+04 1.47062998e+04 1.43176445e+04 1.43181250e+04 1.47753135e+04 1.52691250e+04 1.52204805e+04 1.47458359e+04 1.42798896e+04 1.41821641e+04 1.48669482e+04 1.56543564e+04 1.51308857e+04 1.43005049e+04 1.42854775e+04 1.48924590e+04 1.54356377e+04 1.52801523e+04 1.48542256e+04 1.47466406e+04 1.48214453e+04 1.47502256e+04 1.48671104e+04 1.50281260e+04 1.50015342e+04 1.50934834e+04 1.50174736e+04 1.46989951e+04 1.48058994e+04 1.51962227e+04 1.53795986e+04 1.53596826e+04 1.47247627e+04 1.43705479e+04 1.51315273e+04 1.58294609e+04 1.55590938e+04 1.50328877e+04 1.46063428e+04 1.44176006e+04 1.52040078e+04 1.60804854e+04 1.56110557e+04 1.47490068e+04 1.45686797e+04 1.50785898e+04 1.54554170e+04 1.54194092e+04 1.52608018e+04 1.51236025e+04 1.50890869e+04 1.48727783e+04 1.44730742e+04 1.46823906e+04 1.51153486e+04 1.53941152e+04 1.59170771e+04 1.55090557e+04 1.45311377e+04 1.44421758e+04 1.50097520e+04 1.54974463e+04 1.54193789e+04 1.50654453e+04 1.54372734e+04 1.55624873e+04 1.48286572e+04 1.43301816e+04 1.46625059e+04 1.54406934e+04 1.59132676e+04 1.56203955e+04 1.47149229e+04 1.42836494e+04 1.46027158e+04 1.53546279e+04 1.58747256e+04 1.55121045e+04 1.46634668e+04 1.45830010e+04 1.54776250e+04 1.54689990e+04 1.47834609e+04 1.47524062e+04 1.48024727e+04 1.48109785e+04 1.53498965e+04 1.50327129e+04 1.45701406e+04 1.48507451e+04 1.44707139e+04 1.49173125e+04 1.52880566e+04 1.44617197e+04 1.47848311e+04 1.52269922e+04 1.48064521e+04 1.47521191e+04 1.47937832e+04 1.48174180e+04 1.48755508e+04 1.47433115e+04 1.43068057e+04 1.43304209e+04 1.50286377e+04 1.53998027e+04 1.49798818e+04 1.42873115e+04 1.39620947e+04 1.43083193e+04 1.49353584e+04 1.52330039e+04 1.48833486e+04 1.41182549e+04 1.41476553e+04 1.46061143e+04 1.44692480e+04 1.43671064e+04 1.43755742e+04 1.42991025e+04 1.42760625e+04 1.48423799e+04 1.44256318e+04 1.38513418e+04 1.41808252e+04 1.38453164e+04 1.42933154e+04 1.45767041e+04 1.40586768e+04 1.45879717e+04 1.41770996e+04 1.35802764e+04 1.40156650e+04 1.36765518e+04 1.39069990e+04 1.48279570e+04 1.40577930e+04 1.32066895e+04 1.34333564e+04 1.40013154e+04 1.45775713e+04 1.43072637e+04 1.34809453e+04 1.29919238e+04 1.32436621e+04 1.39504551e+04 1.43412949e+04 1.40618623e+04 1.33132285e+04 1.31538145e+04 1.35349160e+04 1.36839658e+04 1.34275752e+04 1.31967139e+04 1.33070527e+04 1.33549482e+04 1.36572422e+04 1.35834795e+04 1.29334443e+04 1.29583252e+04 1.30432686e+04 1.30411797e+04 1.31641221e+04 1.31086660e+04 1.33822129e+04 1.30492139e+04 1.25268145e+04 1.28409521e+04 1.24885146e+04 1.27386338e+04 1.35679609e+04 1.28900684e+04 1.20695547e+04 1.22256641e+04 1.27839453e+04 1.31647393e+04 1.30793555e+04 1.24033945e+04 1.18666533e+04 1.20289346e+04 1.26216846e+04 1.30213320e+04 1.25975488e+04 1.19002939e+04 1.17910137e+04 1.20957422e+04 1.22889385e+04 1.25832100e+04 1.25350938e+04 1.17093252e+04 1.15369512e+04 1.21017734e+04 1.22124736e+04 1.16921084e+04 1.16165322e+04 1.17284355e+04 1.15745654e+04 1.19184111e+04 1.20090400e+04 1.12947773e+04 1.12570303e+04 1.15174443e+04 1.14798604e+04 1.14202783e+04 1.12246230e+04 1.13908535e+04 1.15683184e+04 1.12693945e+04 1.09379863e+04 1.06365908e+04 1.10429395e+04 1.15749639e+04 1.13369326e+04 10726. 1.03823115e+04 1.06448340e+04 1.12677656e+04 1.09450273e+04 1.02763252e+04 1.03143623e+04 1.05689609e+04 1.08096357e+04 1.11284941e+04 1.07534541e+04 1.01338369e+04 9.86712305e+03 1.01378955e+04 1.05572822e+04 1.04685762e+04 1.01898525e+04 1.00573213e+04 1.00288926e+04 1.01930645e+04 1.00679102e+04 9.76809570e+03 9.70023145e+03 9.46500781e+03 9.84630469e+03 1.01151162e+04 9.66623828e+03 9.58962695e+03 9.60406738e+03 9.72796680e+03 9.42780957e+03 8.97722949e+03 9.30273535e+03 9.73594043e+03 9.43543555e+03 8.92660938e+03 8.93823926e+03 9.37727344e+03 9.29035938e+03 9.04408301e+03 8.99922461e+03 8.61535449e+03 8.53322266e+03 9.07980859e+03 8.99102344e+03 8.60699512e+03 8.32267676e+03 8.22588965e+03 8.55143555e+03 8.89833594e+03 8.47122266e+03 8.21284668e+03 8.31236719e+03 8.22925195e+03 8.48156836e+03 8.39799414e+03 7.89568359e+03 7.80653809e+03 7.98351367e+03 7.95068750e+03 7.89945996e+03 7.83906152e+03 7.97857422e+03 7.79591064e+03 7.47431689e+03 7.53561475e+03 7.32212012e+03 7.56438428e+03 7.93507373e+03 7.66761133e+03 7.13614746e+03 7.07870752e+03 7.32376367e+03 7.46696680e+03 7.56567188e+03 8.35259277e+03 7.90620752e+03 9.33116699e+03 4.20578086e+04 -15530591. 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. 0. 0. 0. 0. 0. 0. -11147687. 5.07625508e+04 8.04401758e+03 6.90854248e+03 5.50770215e+03 5.29539062e+03 4.84410352e+03 4.73276953e+03 4.69648730e+03 4.52010059e+03 4.64734619e+03 4.59589062e+03 4.44082178e+03 4.50236621e+03 4.46634229e+03 4.35253320e+03 4.31282666e+03 4.25292627e+03 4.20759229e+03 4.17454053e+03 4.11964453e+03 4.05135303e+03 3.93753540e+03 3.88752881e+03 3.99909106e+03 3.97669751e+03 3.74650830e+03 3.68339990e+03 3.83907935e+03 3.80313550e+03 3.66635278e+03 3.61960156e+03 3.55417383e+03 3.52546045e+03 3.47598877e+03 3.42328540e+03 3.37717358e+03 3.31943799e+03 3.21320410e+03 3.16759814e+03 3.27267432e+03 3.23666431e+03 3.11656616e+03 3.07700342e+03 3.04035156e+03 3.00776636e+03 2.95198853e+03 2.89934570e+03 2.87040991e+03 2.75095190e+03 2.70522729e+03 2.73381323e+03 2.68728003e+03 2.74236157e+03 2.72049683e+03 2.59337354e+03 2.46383789e+03 2.40587305e+03 2.53952881e+03 2.52327515e+03 2.38539307e+03 2.31358252e+03 2.29622290e+03 2.25256641e+03 2.19246289e+03 2.25690771e+03 2.20873389e+03 2.04289185e+03 2.00526526e+03 2.07487573e+03 2.11080176e+03 2.01800525e+03 1.94278467e+03 1.91754749e+03 1.87173340e+03 1.82156433e+03 1.79731323e+03 1.78283411e+03 1.74306189e+03 1.66957117e+03 1.63556665e+03 1.63757080e+03 1.60038318e+03 1.60822864e+03 1.55269629e+03 1.47948694e+03 1.47289502e+03 1.44152942e+03 1.43906982e+03 1.41946460e+03 1.35925122e+03 1.32258313e+03 1.26436682e+03 1.21062439e+03 1.24300012e+03 1.22914673e+03 1.13831177e+03 1.11944043e+03 1.15529663e+03 1.15884424e+03 1.09802917e+03 1.04046997e+03 1.00828485e+03 9.82256042e+02 9.48550537e+02 9.22265503e+02 9.15298523e+02 8.86172485e+02 8.75648682e+02 8.41677734e+02 7.99703186e+02 7.93738770e+02 7.48813843e+02 7.36537354e+02 7.54435547e+02 7.18963989e+02 6.78820862e+02 6.37084167e+02 6.12808350e+02 6.27945435e+02 6.11311462e+02 5.70973755e+02 5.36139648e+02 5.16479248e+02 5.11468658e+02 4.92367004e+02 4.87832367e+02 4.72368286e+02 4.38707245e+02 4.13905914e+02 3.98409912e+02 3.95720673e+02 3.78672241e+02 3.54330353e+02 3.32444305e+02 3.16863312e+02 3.08982330e+02 2.86511780e+02 2.75336151e+02 2.77852905e+02 2.59945282e+02 2.39176208e+02 2.19780334e+02 2.06468460e+02 2.06724823e+02 1.95106873e+02 1.78078674e+02 1.61902954e+02 1.50251938e+02 1.45312607e+02 1.35077881e+02 1.24688721e+02 1.12866966e+02 1.06021744e+02 1.01573792e+02 9.07719193e+01 8.32991180e+01 7.63365784e+01 6.78149033e+01 5.95221863e+01 5.30880775e+01 4.82416801e+01 4.25786705e+01 3.73520088e+01 3.12973824e+01 2.70544071e+01 2.43973465e+01 1.95391045e+01 1.55003080e+01 1.27688198e+01 1.00106964e+01 7.84779406e+00 5.70160913e+00 3.92720342e+00 2.75881290e+00 1.83941925e+00 1.27662838e+00 1.09547150e+00 1.28542674e+00 1.83875024e+00 2.76114440e+00 4.10032701e+00 5.65550804e+00 7.77506924e+00 1.07117462e+01 1.33400021e+01 1.58561239e+01 1.87252846e+01 2.31555901e+01 2.91034870e+01 3.32569046e+01 3.72127151e+01 4.18726196e+01 4.71841621e+01 5.45081711e+01 6.09304352e+01 6.91893234e+01 7.53844147e+01 8.04072266e+01 9.04818268e+01 9.89472046e+01 1.09562439e+02 1.18161209e+02 1.24514206e+02 1.33525681e+02 1.43428909e+02 1.56909851e+02 1.63392014e+02 1.77115448e+02 1.99559265e+02 2.06769379e+02 2.13477844e+02 2.20425781e+02 2.31971588e+02 2.58905670e+02 2.74350739e+02 2.80786377e+02 2.86550964e+02 3.00910278e+02 3.26086945e+02 3.41750641e+02 3.66096405e+02 3.80923157e+02 3.88455902e+02 3.93117065e+02 4.08571411e+02 4.54026825e+02 4.68136261e+02 4.71739441e+02 4.85157562e+02 5.02059570e+02 5.46289062e+02 5.69621765e+02 5.61054321e+02 5.76631897e+02 6.28061829e+02 6.51377563e+02 6.39342651e+02 6.58724976e+02 7.17748169e+02 7.42060059e+02 7.40390747e+02 7.47092224e+02 7.68650757e+02 8.37717896e+02 8.59202393e+02 8.53205261e+02 8.76720215e+02 8.97178772e+02 9.39034790e+02 9.69438110e+02 9.84613770e+02 9.85921021e+02 1.03566187e+03 1.10959253e+03 1.10391150e+03 1.13854858e+03 1.18077454e+03 1.18378027e+03 1.21274756e+03 1.24115479e+03 1.25922986e+03 1.26361963e+03 1.28846399e+03 1.35031677e+03 1.38675391e+03 1.45977686e+03 1.44720569e+03 1.43249182e+03 1.50342578e+03 1.54615466e+03 1.62508997e+03 1.63348950e+03 1.61938879e+03 1.65294678e+03 1.67894104e+03 1.73841809e+03 1.77393250e+03 1.84425916e+03 1.86300244e+03 1.84885449e+03 1.89554065e+03 1.87707385e+03 1.97594263e+03 2.13392529e+03 2.10968481e+03 2.08805713e+03 2.07430884e+03 2.07653564e+03 2.22656714e+03 2.33737329e+03 2.30527026e+03 2.25530518e+03 2.27960449e+03 2.38825049e+03 2.42555249e+03 2.51974780e+03 2.53522437e+03 2.50531885e+03 2.58080518e+03 2.61625366e+03 2.72664478e+03 2.77306396e+03 2.66195337e+03 2.70943799e+03 2.90029272e+03 2.89688135e+03 2.78821045e+03 2.92133594e+03 3.12626318e+03 3.12045264e+03 3.07813599e+03 3.03983203e+03 3.09104834e+03 3.30807935e+03 3.34903149e+03 3.29776685e+03 3.24937451e+03 3.27021289e+03 3.44002271e+03 3.47614380e+03 3.51312744e+03 3.47748877e+03 3.60366943e+03 3.76900415e+03 3.70482056e+03 3.81565820e+03 3.79972144e+03 3.74467871e+03 3.86909521e+03 3.94592358e+03 3.98898999e+03 3.99579492e+03 3.99324536e+03 3.98701416e+03 4.14980518e+03 4.45200293e+03 4.26607373e+03 4.09535205e+03 4.28057617e+03 4.46771143e+03 4.63309521e+03 4.56741309e+03 4.49244189e+03 4.64885889e+03 4.71098877e+03 4.57628906e+03 4.55742529e+03 4.86450146e+03 4.94748633e+03 4.82190771e+03 4.88377100e+03 4.75866553e+03 4.98873926e+03 5.34297900e+03 5.23549756e+03 5.18379834e+03 5.06994678e+03 5.05173682e+03 5.40352539e+03 5.70891211e+03 5.58703809e+03 5.34104639e+03 5.37380420e+03 5.56061377e+03 5.62862842e+03 5.85617236e+03 5.74547363e+03 5.64606787e+03 5.87354834e+03 5.89006885e+03 6.08750684e+03 6.09187158e+03 5.93158740e+03 6.14689209e+03 6.21058984e+03 6.20094434e+03 6.07324219e+03 6.20822852e+03 6.63500635e+03 6.58466504e+03 6.37599463e+03 6.29731494e+03 6.48439893e+03 6.91878467e+03 6.87893018e+03 6.69817578e+03 6.60123535e+03 6.64617871e+03 6.87284326e+03 7.01244873e+03 7.01172705e+03 6.89644141e+03 7.06741992e+03 7.39604248e+03 7.20164209e+03 7.40046631e+03 7.49051318e+03 7.33768848e+03 7.36517432e+03 7.45775098e+03 7.50633301e+03 7.54879688e+03 7.51891895e+03 7.55771387e+03 7.92536670e+03 8.03743750e+03 7.62694336e+03 7.60386475e+03 7.80957080e+03 8.06196045e+03 8.39649023e+03 8.24036426e+03 7.81293262e+03 8.18000928e+03 8.59457617e+03 8.49054004e+03 8.17304590e+03 8.20666406e+03 8.33397070e+03 8.46845898e+03 8.56487305e+03 8.37200098e+03 8.61836914e+03 9.09887988e+03 8.96449414e+03 8.77574023e+03 8.68064941e+03 8.75325098e+03 9.27694141e+03 9.27470410e+03 9.09647168e+03 8.97849902e+03 8.74102930e+03 8.95037109e+03 9.55523438e+03 9.92970703e+03 9.40658887e+03 9.06087695e+03 9.38224707e+03 9.62327637e+03 9.99968262e+03 9.85834668e+03 9.54911816e+03 9.79217090e+03 9.82853027e+03 9.77518262e+03 9.60561719e+03 9.87187598e+03 1.03568105e+04 1.02331982e+04 1.01501826e+04 9.98807031e+03 1.00247197e+04 1.05949785e+04 1.06430127e+04 1.04260840e+04 1.01745068e+04 1.01021113e+04 1.04672988e+04 1.04869648e+04 1.08746338e+04 1.10411094e+04 1.05569600e+04 1.03840850e+04 1.08139160e+04 1.12451543e+04 1.09950508e+04 1.08697119e+04 1.08683623e+04 1.08968037e+04 1.09102490e+04 1.07658516e+04 1.12311768e+04 1.14958838e+04 1.11677686e+04 1.15034736e+04 1.16351455e+04 1.15553555e+04 1.15399004e+04 1.15018311e+04 1.15139092e+04 1.13161055e+04 1.12248672e+04 1.17695020e+04 1.21168213e+04 1.15867451e+04 1.11840781e+04 1.17145439e+04 1.24320947e+04 1.24566250e+04 1.18450283e+04 1.14575527e+04 1.21253926e+04 1.26206270e+04 1.23426035e+04 1.23142158e+04 1.19784170e+04 1.15553789e+04 1.20948604e+04 1.28765576e+04 1.29676318e+04 1.22768994e+04 1.18608096e+04 1.26136074e+04 1.31873975e+04 1.28491680e+04 1.22800830e+04 1.19870596e+04 1.24798887e+04 1.27744209e+04 1.31214043e+04 1.33079580e+04 1.29118057e+04 1.26711602e+04 1.27030527e+04 1.33164932e+04 1.30382285e+04 1.27115596e+04 1.33361143e+04 1.33183115e+04 1.32057891e+04 1.29417988e+04 1.29648643e+04 1.37188691e+04 1.33545010e+04 1.27251055e+04 1.31134639e+04 1.36569170e+04 1.37172559e+04 1.34764062e+04 1.37927822e+04 1.39509287e+04 1.36190020e+04 1.32435381e+04 1.32039150e+04 1.40027305e+04 1.37753623e+04 1.33891992e+04 1.38133457e+04 1.38173848e+04 1.37954932e+04 1.36432227e+04 1.39982305e+04 1.41447539e+04 1.38182939e+04 1.40742471e+04 1.41147793e+04 1.42435742e+04 1.42502617e+04 1.40757285e+04 1.38692578e+04 1.35278447e+04 1.35930957e+04 1.43629375e+04 1.51020820e+04 1.43066621e+04 1.34407139e+04 1.40063369e+04 1.49135137e+04 1.50111602e+04 1.42596426e+04 1.36698877e+04 1.44272305e+04 1.47801270e+04 1.42961250e+04 1.48536045e+04 1.46572188e+04 1.38182549e+04 1.42252578e+04 1.50948975e+04 1.51198271e+04 1.43976885e+04 1.38883584e+04 1.45163818e+04 1.54502373e+04 1.51157900e+04 1.43580215e+04 1.40102520e+04 1.46977236e+04 1.52552842e+04 1.48345967e+04 1.46893936e+04 1.47513584e+04 1.48426035e+04 1.48035996e+04 1.51903584e+04 1.49168311e+04 1.44488438e+04 1.48567207e+04 1.49302148e+04 1.52566982e+04 1.49518506e+04 1.45604688e+04 1.51938359e+04 1.47415605e+04 1.43981943e+04 1.50106250e+04 1.52714443e+04 1.52001650e+04 1.49622061e+04 1.54471172e+04 1.55283828e+04 1.49825469e+04 1.46507256e+04 1.46119951e+04 1.54955986e+04 1.52249746e+04 1.43399609e+04 1.49915254e+04 1.64207617e+04 1.65706328e+04 1.54631309e+04 1.62937803e+04 3.39552070e+04 4.94632188e+04 2.69668031e+05 -6.62653440e+09 0. 0. 0. 0. 0. -2.48822792e+11 8.42352562e+05 7.75989375e+04 1.27741852e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.34731581e+10 1.21308297e+05 6.74733984e+04 3.33985547e+04 1.78618496e+04 1.51231064e+04 1.52498906e+04 1.52446660e+04 1.45834883e+04 1.44024102e+04 1.42224580e+04 1.37829219e+04 1.41630703e+04 1.46602314e+04 1.41922539e+04 1.39952656e+04 1.42785449e+04 1.44440508e+04 1.44796631e+04 1.40365098e+04 1.36378496e+04 1.38859561e+04 1.42302949e+04 1.43274424e+04 1.41847012e+04 1.38625049e+04 1.38938242e+04 1.43588926e+04 1.46126689e+04 1.41461621e+04 1.35805566e+04 1.37316123e+04 1.41357783e+04 1.40026963e+04 1.39116016e+04 1.40201025e+04 1.36552451e+04 1.38565166e+04 1.41695869e+04 1.35882588e+04 1.35369873e+04 1.39421299e+04 1.44358369e+04 1.44828145e+04 1.35064170e+04 1.30542559e+04 1.34329521e+04 1.39863271e+04 1.41369521e+04 1.35684404e+04 1.34739141e+04 1.39075938e+04 1.37745635e+04 1.37010713e+04 1.35004268e+04 1.30609150e+04 1.34745615e+04 1.39224932e+04 1.34317100e+04 1.32979268e+04 1.35897422e+04 1.33530518e+04 1.35482373e+04 1.36252031e+04 1.31343184e+04 1.30244443e+04 1.32566621e+04 1.36645654e+04 1.35369355e+04 1.30403018e+04 1.31106963e+04 1.30378389e+04 1.31381318e+04 1.34195869e+04 1.29406641e+04 1.27752988e+04 1.31077607e+04 1.32618516e+04 1.33126680e+04 1.29322080e+04 1.24473018e+04 1.25405107e+04 1.29312217e+04 1.31319717e+04 1.30262803e+04 1.27410449e+04 1.25545645e+04 1.28155762e+04 1.30323975e+04 1.25921328e+04 1.22017676e+04 1.24016201e+04 1.28179531e+04 1.28194268e+04 1.25893359e+04 1.22344043e+04 1.20435488e+04 1.24296533e+04 1.26225391e+04 1.21393809e+04 1.20968574e+04 1.24070762e+04 1.26450957e+04 1.25727266e+04 1.19302764e+04 1.15850625e+04 1.19484004e+04 1.20950498e+04 1.20228125e+04 1.19073193e+04 1.19556289e+04 1.21227607e+04 1.18625439e+04 1.17132061e+04 1.19158721e+04 1.16149658e+04 1.14974932e+04 1.17919785e+04 1.17588711e+04 1.17566406e+04 1.15206572e+04 1.11727900e+04 1.12827949e+04 1.14681162e+04 1.16289043e+04 1.14448545e+04 1.11417725e+04 1.12174902e+04 1.14571064e+04 1.14708877e+04 1.10622881e+04 1.07097344e+04 1.08424678e+04 1.10893848e+04 1.10884902e+04 1.09022100e+04 1.07802998e+04 1.07116064e+04 1.09472314e+04 1.10255947e+04 1.07764004e+04 1.06226045e+04 1.04262217e+04 1.04941953e+04 1.05148750e+04 1.03015391e+04 1.03571104e+04 1.03896191e+04 1.05457578e+04 1.06568906e+04 1.02171006e+04 9.92947461e+03 1.00684434e+04 1.02075752e+04 1.02946289e+04 1.01513154e+04 9.69228418e+03 9.67048145e+03 1.01002480e+04 1.02952744e+04 9.80633984e+03 9.46513672e+03 9.58073828e+03 9.88377344e+03 9.72729590e+03 9.27193359e+03 9.27477539e+03 9.53602246e+03 9.50077734e+03 9.40034180e+03 9.40418555e+03 9.39956641e+03 9.00492773e+03 9.18824219e+03 9.34050391e+03 8.88207324e+03 8.88279492e+03 9.04347168e+03 9.01972266e+03 9.04099902e+03 8.81822266e+03 8.48433789e+03 8.47961914e+03 8.71028223e+03 8.95087793e+03 8.91599512e+03 8.33120410e+03 8.32869336e+03 8.74150195e+03 8.46000098e+03 8.10103223e+03 8.09503467e+03 8.20734570e+03 8.29089551e+03 8.40856152e+03 8.27268555e+03 7.97502295e+03 7.71948877e+03 7.96639844e+03 8.05621143e+03 7.78623975e+03 7.71518311e+03 7.81035059e+03 7.89707715e+03 7.82816748e+03 7.55482031e+03 7.30093506e+03 7.33314404e+03 7.46754004e+03 7.59276758e+03 7.58953955e+03 7.14560645e+03 7.11985693e+03 7.31866357e+03 7.28707178e+03 7.11312939e+03 6.95262988e+03 6.93085791e+03 7.06836914e+03 7.06418164e+03 6.93957129e+03 6.72628418e+03 6.57443164e+03 6.65412549e+03 6.74448877e+03 6.54566602e+03 6.55935742e+03 6.56980664e+03 6.55709033e+03 6.61474268e+03 6.30089502e+03 6.10601465e+03 6.24937256e+03 6.20586035e+03 6.24640527e+03 6.01242725e+03 5.85620752e+03 6.03837891e+03 6.15350049e+03 6.01575928e+03 5.80338525e+03 5.81413037e+03 5.67331396e+03 5.61397217e+03 5.71715820e+03 5.83303711e+03 5.64612695e+03 5.39166406e+03 5.53331396e+03 5.41739795e+03 5.37503418e+03 5.35616455e+03 5.13627783e+03 5.24383740e+03 5.30793652e+03 5.08757764e+03 4.91777490e+03 4.98299219e+03 5.13484961e+03 5.12097510e+03 4.81014893e+03 4.71153271e+03 4.80392090e+03 4.81815625e+03 4.80589453e+03 4.63097998e+03 4.58484912e+03 4.49465234e+03 4.46304834e+03 4.58993652e+03 4.48347559e+03 4.26125195e+03 4.32304639e+03 4.41829883e+03 4.23026709e+03 4.15217285e+03 4.06734326e+03 3.99640381e+03 4.13130908e+03 4.16348926e+03 3.95921704e+03 3.85348145e+03 3.85547339e+03 3.89957031e+03 3.89296899e+03 3.72458447e+03 3.75885425e+03 3.73075269e+03 3.51637231e+03 3.50843213e+03 3.50800830e+03 3.46894922e+03 3.49784668e+03 3.42707251e+03 3.35796777e+03 3.39146802e+03 3.28147290e+03 3.17737915e+03 3.20829077e+03 3.20633960e+03 3.14704663e+03 3.00636621e+03 2.95631738e+03 3.04598804e+03 3.05142261e+03 2.88867993e+03 2.79380151e+03 2.79632178e+03 2.83533032e+03 2.82610254e+03 2.69810278e+03 2.64239038e+03 2.60167358e+03 2.60892017e+03 2.61899341e+03 2.49855566e+03 2.45743774e+03 2.43436377e+03 2.39416870e+03 2.38721411e+03 2.39379443e+03 2.30466479e+03 2.19943726e+03 2.25644263e+03 2.28824365e+03 2.15073584e+03 2.03073926e+03 2.04862476e+03 2.06928467e+03 2.03490063e+03 1.96361108e+03 1.91337000e+03 1.89336523e+03 1.90266943e+03 1.87941443e+03 1.79616553e+03 1.75839282e+03 1.73667786e+03 1.74266821e+03 1.69051111e+03 1.61865503e+03 1.61298779e+03 1.57170642e+03 1.53682288e+03 1.53785010e+03 1.50775891e+03 1.44393970e+03 1.41021448e+03 1.41211121e+03 1.38873730e+03 1.32785278e+03 1.28826624e+03 1.27390515e+03 1.27481506e+03 1.24162231e+03 1.17036255e+03 1.14749890e+03 1.14206970e+03 1.14625342e+03 1.12460242e+03 1.05676831e+03 1.05192151e+03 1.01603192e+03 9.55146362e+02 9.41750732e+02 9.31014099e+02 9.31250122e+02 9.03995483e+02 8.43288208e+02 8.11110229e+02 8.12941345e+02 8.17167664e+02 7.89310120e+02 7.51227051e+02 7.24251404e+02 6.97146912e+02 6.69559814e+02 6.46922180e+02 6.46082031e+02 6.34395386e+02 5.96698120e+02 5.75141235e+02 5.55107300e+02 5.42847351e+02 5.29221497e+02 5.09026489e+02 5.00978241e+02 4.67444763e+02 4.32949127e+02 4.21275848e+02 4.16895355e+02 4.10997375e+02 3.97831940e+02 3.69691833e+02 3.35866180e+02 3.28246948e+02 3.23781921e+02 3.06214355e+02 2.98779968e+02 2.83267792e+02 2.59703613e+02 2.53727493e+02 2.42934891e+02 2.24883545e+02 2.15043945e+02 2.01099182e+02 1.87166031e+02 1.76095276e+02 1.66356339e+02 1.57625641e+02 1.51701172e+02 1.45105499e+02 1.29251160e+02 1.15041664e+02 1.07129662e+02 1.01604683e+02 9.65103378e+01 8.79039078e+01 7.68132401e+01 6.89062271e+01 6.41280746e+01 5.95372314e+01 5.36003189e+01 4.66525345e+01 4.09997559e+01 3.59233589e+01 3.09531956e+01 2.65181503e+01 2.30858555e+01 1.96616058e+01 1.61379223e+01 1.33363266e+01 1.04223156e+01 8.13659573e+00 6.38886356e+00 4.85255146e+00 3.65918136e+00 2.75404096e+00 2.23991513e+00 2.08473110e+00 2.27732801e+00 2.83593273e+00 3.74919772e+00 4.93172359e+00 6.34433794e+00 8.32908630e+00 1.07183571e+01 1.31868401e+01 1.64980698e+01 2.01890030e+01 2.32191086e+01 2.69229717e+01 3.15100842e+01 3.69162292e+01 4.26064529e+01 4.73996735e+01 5.30624771e+01 5.73974800e+01 6.33948593e+01 7.24108124e+01 7.98569870e+01 8.85753250e+01 9.66895370e+01 1.01870468e+02 1.07733810e+02 1.19152664e+02 1.33135361e+02 1.41206467e+02 1.48712769e+02 1.58730820e+02 1.66573334e+02 1.78847427e+02 1.93444305e+02 2.04221741e+02 2.17405792e+02 2.27531967e+02 2.36159088e+02 2.48501740e+02 2.69177490e+02 2.84978912e+02 2.95400391e+02 3.12362915e+02 3.18099426e+02 3.35764557e+02 3.57050110e+02 3.69486908e+02 3.95277985e+02 4.02921570e+02 4.06257782e+02 4.26558624e+02 4.43894958e+02 4.72171265e+02 5.11141754e+02 5.19214111e+02 5.14980774e+02 5.31527283e+02 5.51149597e+02 5.69593933e+02 6.07363464e+02 6.36176636e+02 6.37612854e+02 6.53691406e+02 6.75262390e+02 7.11621338e+02 7.43147461e+02 7.56235291e+02 8.01616516e+02 8.04119141e+02 7.77739502e+02 8.16174988e+02 8.72616394e+02 9.10425659e+02 9.42533142e+02 9.35011292e+02 9.15135925e+02 9.68902283e+02 1.04482593e+03 1.06151575e+03 1.06715234e+03 1.08646826e+03 1.09470581e+03 1.14357104e+03 1.18317578e+03 1.18613074e+03 1.25484607e+03 1.26748425e+03 1.27870483e+03 1.31652844e+03 1.30837830e+03 1.35671765e+03 1.41637817e+03 1.48279407e+03 1.48023889e+03 1.42760486e+03 1.47701965e+03 1.55679822e+03 1.61975439e+03 1.64275842e+03 1.62221423e+03 1.63164258e+03 1.69930322e+03 1.76881006e+03 1.81465955e+03 1.83636914e+03 1.84958728e+03 1.86533838e+03 1.90679004e+03 1.93950964e+03 1.97245679e+03 2.02621887e+03 2.06948389e+03 2.11969824e+03 2.08912793e+03 2.11484814e+03 2.21615015e+03 2.23821973e+03 2.32706250e+03 2.32564014e+03 2.26055615e+03 2.30900708e+03 2.39888550e+03 2.51171338e+03 2.60415601e+03 2.53406567e+03 2.49075684e+03 2.56321362e+03 2.64077612e+03 2.69191089e+03 2.73795312e+03 2.79381885e+03 2.76595361e+03 2.75932227e+03 2.84706982e+03 2.94024902e+03 3.03276489e+03 3.04674268e+03 3.08789526e+03 3.04681592e+03 2.99544409e+03 3.10439453e+03 3.20997925e+03 3.33355444e+03 3.37115259e+03 3.23029810e+03 3.24795581e+03 3.40281812e+03 3.57145288e+03 3.55973120e+03 3.55402661e+03 3.59046924e+03 3.51259619e+03 3.64779688e+03 3.80172876e+03 3.77391455e+03 3.78792236e+03 3.81862305e+03 3.90138354e+03 3.94930347e+03 3.96184888e+03 4.04581738e+03 4.11471240e+03 4.13198633e+03 4.08406006e+03 4.16773145e+03 4.26984814e+03 4.30969971e+03 4.49151709e+03 4.41978857e+03 4.31358203e+03 4.42117236e+03 4.41712109e+03 4.64433301e+03 4.86472217e+03 4.74905566e+03 4.60150830e+03 4.59919775e+03 4.84043994e+03 5.09272119e+03 4.99428271e+03 4.85786719e+03 7.45018945e+03 7.49602734e+03 1.28563779e+04 8.33385234e+04 13955498. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 253480992. 1.69346016e+05 2.47994785e+04 9.48497852e+03 9.17135938e+03 8.11412744e+03 7.62058643e+03 7.65069336e+03 7.88253906e+03 7.33572607e+03 7.54317725e+03 8.01689453e+03 8.02219482e+03 7.76441846e+03 7.51918799e+03 7.67742432e+03 8.12725928e+03 8.46701074e+03 8211. 7.92494141e+03 7.95016699e+03 8.05832178e+03 8.47058398e+03 8.59589746e+03 8.30728027e+03 8.25470312e+03 8.27297168e+03 8.45924707e+03 8.54827637e+03 8.45448145e+03 8.55337891e+03 8.93563867e+03 9.15549316e+03 8.77310352e+03 8.37204004e+03 8.66484570e+03 9.15208496e+03 9.47508691e+03 9.12459668e+03 8.72321387e+03 8.82764258e+03 9.26634180e+03 9.77908203e+03 9.44984277e+03 8.91393848e+03 9.05517188e+03 9.51051758e+03 9.75259277e+03 9.78249121e+03 9.67780957e+03 9.39421484e+03 9.53961328e+03 9.87740039e+03 9.55760840e+03 9.50396875e+03 1.00438066e+04 1.01870088e+04 1.01290820e+04 9.79187793e+03 9.49427246e+03 1.00743320e+04 1.07407793e+04 1.05597451e+04 9.93127734e+03 9.63214844e+03 9.87498438e+03 1.05814736e+04 1.10112773e+04 1.07075879e+04 1.05066475e+04 1.03433545e+04 1.01211855e+04 1.05051504e+04 1.09680342e+04 1.06861025e+04 1.06134639e+04 1.07821533e+04 1.08870020e+04 1.07181914e+04 1.06819297e+04 1.10549316e+04 1.12364277e+04 1.13282129e+04 1.11125469e+04 1.06807500e+04 1.07290840e+04 1.13769453e+04 1.19454463e+04 1.14114727e+04 1.07892236e+04 1.09726133e+04 1.14141465e+04 1.17435439e+04 1.18902949e+04 1.15181318e+04 1.14319785e+04 1.14703242e+04 1.16398877e+04 1.18972314e+04 1.17354570e+04 1.16973145e+04 1.16817490e+04 1.18167246e+04 1.19138604e+04 1.18259590e+04 1.19895557e+04 1.21442197e+04 1.23331006e+04 1.20674043e+04 1.15945107e+04 1.18470527e+04 1.25144492e+04 1.28097197e+04 1.22354814e+04 1.16881816e+04 1.17757715e+04 1.25223574e+04 1.31599824e+04 1.26631045e+04 1.20698857e+04 1.23099551e+04 1.23315869e+04 1.25002773e+04 1.26647295e+04 1.25118213e+04 1.28044531e+04 1.27385801e+04 1.26513721e+04 1.27587129e+04 1.24748135e+04 1.28023750e+04 1.33340195e+04 1.33102939e+04 1.28597070e+04 1.24877900e+04 1.25558672e+04 1.30893848e+04 1.36929160e+04 1.31575312e+04 1.24956426e+04 1.27324336e+04 1.33752783e+04 1.38051943e+04 1.33232773e+04 1.29488467e+04 1.31066768e+04 1.31132490e+04 1.34156934e+04 1.35522021e+04 1.30106084e+04 1.30097930e+04 1.35231875e+04 1.37368691e+04 1.35733691e+04 1.32938877e+04 1.33719062e+04 1.35819121e+04 1.40051484e+04 1.37419951e+04 1.30520352e+04 1.32418945e+04 1.36451328e+04 1.39082500e+04 1.38971201e+04 1.34488682e+04 1.34071514e+04 1.36674434e+04 1.39875332e+04 1.39738350e+04 1.36404600e+04 1.38471543e+04 1.38953262e+04 1.38833721e+04 1.38543936e+04 1.35450488e+04 1.38351221e+04 1.43570430e+04 1.44562100e+04 1.39489229e+04 1.34031953e+04 1.35223838e+04 1.41851660e+04 1.47623848e+04 1.41887979e+04 1.34488125e+04 1.36266631e+04 1.40845146e+04 1.44505488e+04 1.44625156e+04 1.39176172e+04 1.38115645e+04 1.41072539e+04 1.42418506e+04 1.42389834e+04 1.41457881e+04 1.42242725e+04 1.40535029e+04 1.41722793e+04 1.42758887e+04 1.41102441e+04 1.42267725e+04 1.43178779e+04 1.44173447e+04 1.39271377e+04 1.36669463e+04 1.42514238e+04 1.48125107e+04 1.48948760e+04 1.42678174e+04 1.36482812e+04 1.37344014e+04 1.45315479e+04 1.52219570e+04 1.47804482e+04 1.40932393e+04 1.37924658e+04 1.38259121e+04 1.44656914e+04 1.49446836e+04 1.45915771e+04 1.42730391e+04 1.42532959e+04 1.41796406e+04 1.38334043e+04 1.38992207e+04 1.43255781e+04 1.44203350e+04 1.48571182e+04 1.45775244e+04 1.36702686e+04 1.39143701e+04 1.44078008e+04 1.44358789e+04 1.44858271e+04 1.43228779e+04 1.45958506e+04 1.46948193e+04 1.40558359e+04 1.35803809e+04 1.38511357e+04 1.45871455e+04 1.50473135e+04 1.47645205e+04 1.39264229e+04 1.35614141e+04 1.38796455e+04 1.45248008e+04 1.49185244e+04 1.46409365e+04 1.38979512e+04 1.38127070e+04 1.45970684e+04 1.46208711e+04 1.39037383e+04 1.38460107e+04 1.41278721e+04 1.41163301e+04 1.45404805e+04 1.41920039e+04 1.37401250e+04 1.40742012e+04 1.36856748e+04 1.40365693e+04 1.44959854e+04 1.37398066e+04 1.39525264e+04 1.44249678e+04 1.40559209e+04 1.39663105e+04 1.39541562e+04 1.40009443e+04 1.41446035e+04 1.39491211e+04 1.34694941e+04 1.35777930e+04 1.42323223e+04 1.45090791e+04 1.41449785e+04 1.35783301e+04 1.32353232e+04 1.34745195e+04 1.40985771e+04 1.44399365e+04 1.41281104e+04 1.33748730e+04 1.33318760e+04 1.38553184e+04 1.37787148e+04 1.35397832e+04 1.35136016e+04 1.35327969e+04 1.35107285e+04 1.40045488e+04 1.36554365e+04 1.31237041e+04 1.33624385e+04 1.30091768e+04 1.34835752e+04 1.38425391e+04 1.33611670e+04 1.37825312e+04 1.34380732e+04 1.28454355e+04 1.32240713e+04 1.29440840e+04 1.31868652e+04 1.40118672e+04 1.32740430e+04 1.25441523e+04 1.27834072e+04 1.32782158e+04 1.37031523e+04 1.34922061e+04 1.27493594e+04 1.22530596e+04 1.25094141e+04 1.32390635e+04 1.36306094e+04 1.32916514e+04 1.25950244e+04 1.24162939e+04 1.28955361e+04 1.30755439e+04 1.25880654e+04 1.23812617e+04 1.25726973e+04 1.26168896e+04 1.29210098e+04 1.28989072e+04 1.23395859e+04 1.23441660e+04 1.22855791e+04 1.22203926e+04 1.24844814e+04 1.24033271e+04 1.26351602e+04 1.23266592e+04 1.18431279e+04 1.21490410e+04 1.18225635e+04 1.20458066e+04 1.28737529e+04 1.22242510e+04 1.13478936e+04 1.15285635e+04 1.20948262e+04 1.24201055e+04 1.24409102e+04 1.17964199e+04 1.11982871e+04 1.13414121e+04 1.19194854e+04 1.24306396e+04 1.19820449e+04 1.12451797e+04 1.10817500e+04 1.13635986e+04 1.16535889e+04 1.19778047e+04 1.18098867e+04 1.11019092e+04 1.09226787e+04 1.13573047e+04 1.14786357e+04 1.12782295e+04 1.11902363e+04 1.09858564e+04 1.08427744e+04 1.13072178e+04 1.13353799e+04 1.07082744e+04 1.06567754e+04 1.08507441e+04 1.08520938e+04 1.08279023e+04 1.06728398e+04 1.08268408e+04 1.08980029e+04 1.05334570e+04 1.03237188e+04 1.01479072e+04 1.04827324e+04 1.09620195e+04 1.07405518e+04 1.01335830e+04 9.83506152e+03 1.01650527e+04 1.06446514e+04 1.02445928e+04 9.69567871e+03 9.80932715e+03 1.00476357e+04 1.02147148e+04 1.04435156e+04 1.02210215e+04 9.61992090e+03 9.29866699e+03 9.56825488e+03 1.00097129e+04 9.92116309e+03 9.55885352e+03 9.49598535e+03 9.45893652e+03 9.59387109e+03 9.46197461e+03 9.14700879e+03 9.15075391e+03 9.03047070e+03 9.40716309e+03 9.54407129e+03 9.12768262e+03 9.03110547e+03 9.03644238e+03 9.20636816e+03 8.94279199e+03 8.48875000e+03 8.77686328e+03 9.25195508e+03 8.87035938e+03 8.37284277e+03 8.50080371e+03 8.93130176e+03 8.77382422e+03 8.58876855e+03 8.49389062e+03 8.20230957e+03 8.09637354e+03 8.54436426e+03 8.50398438e+03 8.10799023e+03 7.85414014e+03 7.78052246e+03 8.11515820e+03 8.43247656e+03 8.03244385e+03 7.72855713e+03 7.83294971e+03 7.77793262e+03 8.01603223e+03 7.94613916e+03 7.45391943e+03 7.38274658e+03 7.48472021e+03 7.50544580e+03 7.52150000e+03 7.42609619e+03 7.53799805e+03 7.41818750e+03 7.08162695e+03 7.06695166e+03 6.93560156e+03 7.17528857e+03 7.43687744e+03 7.20515088e+03 6.82429834e+03 6.70365576e+03 7.16039600e+03 7.21438867e+03 7.11289062e+03 7.91623730e+03 9.10410156e+03 1.18359277e+04 9.83755234e+04 138469296. 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. 0. 0. 0. 0. 0. 0. -78582576. 9.33957266e+04 1.16249160e+04 6.26088232e+03 5.16650537e+03 5.05041016e+03 4.75705518e+03 4.49423340e+03 4.42492334e+03 4.27498633e+03 4.41429102e+03 4.38764893e+03 4.24699609e+03 4.23107178e+03 4.19332910e+03 4.12385498e+03 4.09618311e+03 4.03023193e+03 3.97976489e+03 3.94789136e+03 3.88830371e+03 3.84542480e+03 3.72294458e+03 3.64622412e+03 3.78504785e+03 3.76907690e+03 3.52829736e+03 3.48338721e+03 3.61627734e+03 3.60638452e+03 3.47315869e+03 3.42932520e+03 3.36236450e+03 3.32689868e+03 3.28201855e+03 3.23305737e+03 3.20686768e+03 3.15301270e+03 3.04458374e+03 2.99435425e+03 3.09540552e+03 3.07191919e+03 2.95395923e+03 2.90692261e+03 2.87708154e+03 2.84914331e+03 2.78780688e+03 2.73376562e+03 2.71691382e+03 2.60206128e+03 2.53667114e+03 2.60236157e+03 2.55883521e+03 2.58978516e+03 2.56983350e+03 2.44761523e+03 2.33588794e+03 2.28604272e+03 2.39888086e+03 2.38331885e+03 2.25484717e+03 2.19060522e+03 2.17163403e+03 2.14816504e+03 2.09681274e+03 2.12293726e+03 2.08114355e+03 1.94422864e+03 1.90254565e+03 1.97023157e+03 1.98350244e+03 1.89435803e+03 1.83651831e+03 1.80791907e+03 1.77108569e+03 1.71432678e+03 1.68230310e+03 1.68460352e+03 1.65318481e+03 1.58977979e+03 1.56515759e+03 1.55088782e+03 1.51544031e+03 1.52318469e+03 1.48356946e+03 1.41205505e+03 1.39978198e+03 1.36554333e+03 1.35133276e+03 1.33468188e+03 1.28468921e+03 1.25138440e+03 1.20188977e+03 1.15950757e+03 1.18193848e+03 1.15101123e+03 1.07112024e+03 1.05914941e+03 1.09370239e+03 1.10211072e+03 1.03909302e+03 9.84715271e+02 9.47305359e+02 9.18522156e+02 9.03190552e+02 8.78406494e+02 8.67128723e+02 8.39000916e+02 8.29363220e+02 8.02427673e+02 7.60884705e+02 7.53196106e+02 7.09273621e+02 6.89285522e+02 7.08312256e+02 6.80673645e+02 6.43130737e+02 6.06517456e+02 5.81912415e+02 5.94734009e+02 5.78354858e+02 5.41217102e+02 5.09281677e+02 4.90570892e+02 4.85417877e+02 4.66904785e+02 4.61984619e+02 4.47920654e+02 4.16900848e+02 3.96387054e+02 3.81213501e+02 3.71998077e+02 3.56131409e+02 3.36303650e+02 3.16564362e+02 3.02380280e+02 2.94536316e+02 2.72439362e+02 2.59289795e+02 2.60961761e+02 2.46787796e+02 2.27144928e+02 2.08365646e+02 1.96491425e+02 1.96665070e+02 1.85088089e+02 1.69412781e+02 1.54608978e+02 1.43529877e+02 1.38614029e+02 1.28534302e+02 1.19044189e+02 1.08092430e+02 1.01500778e+02 9.77890091e+01 8.76288757e+01 7.92029953e+01 7.24095154e+01 6.51775208e+01 5.78876343e+01 5.15941849e+01 4.65412483e+01 4.13698616e+01 3.64397316e+01 3.05992661e+01 2.63947506e+01 2.39280243e+01 1.95045757e+01 1.56747408e+01 1.31089745e+01 1.05083542e+01 8.49650860e+00 6.44035101e+00 4.75386238e+00 3.66022563e+00 2.78731227e+00 2.25435567e+00 2.08431053e+00 2.26106262e+00 2.79212332e+00 3.67314053e+00 4.92759323e+00 6.40968513e+00 8.41378689e+00 1.11438322e+01 1.36194057e+01 1.61589565e+01 1.89656162e+01 2.28189831e+01 2.83006172e+01 3.25585556e+01 3.63477516e+01 4.06428757e+01 4.56587830e+01 5.25423317e+01 5.86771889e+01 6.66642532e+01 7.23283920e+01 7.70679016e+01 8.66815033e+01 9.46090851e+01 1.04742836e+02 1.12040703e+02 1.17676300e+02 1.28321350e+02 1.37863968e+02 1.49230042e+02 1.55173569e+02 1.68689972e+02 1.90652802e+02 1.96266464e+02 2.02836014e+02 2.09947876e+02 2.19852325e+02 2.45551300e+02 2.61392609e+02 2.66806213e+02 2.71271515e+02 2.85419983e+02 3.09912598e+02 3.24080811e+02 3.46966370e+02 3.60918976e+02 3.68750824e+02 3.74050659e+02 3.86975922e+02 4.29486725e+02 4.41627563e+02 4.45142792e+02 4.61771820e+02 4.78179840e+02 5.17616821e+02 5.38516541e+02 5.31756531e+02 5.46284363e+02 5.93131897e+02 6.18584167e+02 6.06678345e+02 6.23727112e+02 6.79243042e+02 7.01768799e+02 7.02912048e+02 7.10215149e+02 7.29230103e+02 7.92877380e+02 8.06829712e+02 8.01875977e+02 8.33341675e+02 8.55779846e+02 9.02711792e+02 9.26364319e+02 9.20720703e+02 9.24324158e+02 9.80636719e+02 1.06356921e+03 1.05385120e+03 1.06459692e+03 1.10675757e+03 1.12252075e+03 1.14770752e+03 1.17376489e+03 1.19535144e+03 1.19590735e+03 1.21738123e+03 1.27462085e+03 1.31808325e+03 1.38500110e+03 1.37465515e+03 1.34707837e+03 1.41529065e+03 1.47277747e+03 1.54933765e+03 1.54727771e+03 1.53234668e+03 1.56502087e+03 1.59029089e+03 1.65032617e+03 1.68014807e+03 1.74526685e+03 1.77548193e+03 1.76399097e+03 1.77617932e+03 1.76104810e+03 1.86815344e+03 2.02056042e+03 2.00463867e+03 1.98438513e+03 1.96137415e+03 1.95260999e+03 2.08653931e+03 2.22503149e+03 2.19620264e+03 2.12685571e+03 2.15613086e+03 2.25826099e+03 2.29612769e+03 2.38744971e+03 2.42133496e+03 2.38963672e+03 2.42208594e+03 2.45628784e+03 2.57542676e+03 2.62579614e+03 2.52825220e+03 2.55964429e+03 2.74900488e+03 2.76004004e+03 2.66428149e+03 2.75366333e+03 2.94124463e+03 2.94404004e+03 2.90658911e+03 2.87881543e+03 2.91893579e+03 3.12400586e+03 3.16761743e+03 3.12781616e+03 3.08099634e+03 3.09344824e+03 3.23472339e+03 3.29183105e+03 3.32085986e+03 3.27937134e+03 3.40464380e+03 3.56277563e+03 3.50407275e+03 3.61134839e+03 3.64788721e+03 3.57524170e+03 3.66887817e+03 3.73055469e+03 3.76409937e+03 3.77715430e+03 3.74301147e+03 3.74247729e+03 3.93843652e+03 4.19947510e+03 4.03775000e+03 3.90644214e+03 4.08397974e+03 4.19480029e+03 4.35893799e+03 4.29846631e+03 4.20159521e+03 4.42764111e+03 4.49280566e+03 4.30659277e+03 4.31849219e+03 4.64088037e+03 4.68394824e+03 4.59794141e+03 4.56654395e+03 4.46367920e+03 4.71566992e+03 5.09978857e+03 5.01659033e+03 4.88576221e+03 4.78927100e+03 4.76276953e+03 5.06147217e+03 5.41480029e+03 5.30295312e+03 5.06496436e+03 5.07435303e+03 5.26530420e+03 5.34736719e+03 5.51283447e+03 5.44452002e+03 5.35278613e+03 5.55944141e+03 5.56075195e+03 5.77857764e+03 5.79209961e+03 5.66366162e+03 5.73573389e+03 5.75711670e+03 5.94063574e+03 5.86221045e+03 5.84521777e+03 6.18067285e+03 6.25643311e+03 6.09013281e+03 5.97025000e+03 6.06586133e+03 6.47531787e+03 6.50191309e+03 6.37849365e+03 6.24314209e+03 6.29158496e+03 6.52441748e+03 6.59198340e+03 6.66319531e+03 6.48355713e+03 6.69960498e+03 7.01661621e+03 6.80670996e+03 7.04079883e+03 7.12823926e+03 6.93299316e+03 6.88482178e+03 6.92575342e+03 7.20060156e+03 7.26091113e+03 7.05888965e+03 7.09194238e+03 7.52484229e+03 7.64223145e+03 7.24766797e+03 7.10938867e+03 7.31975635e+03 7.69121436e+03 8.04711963e+03 7.78883887e+03 7.46465430e+03 7.82359619e+03 8.07117432e+03 7.90521973e+03 7.83274463e+03 7.86470410e+03 7.85383887e+03 7.95853271e+03 8.13476025e+03 7.95815088e+03 8.17861768e+03 8.61610840e+03 8.35106543e+03 8.41794727e+03 8.31149609e+03 8.22188672e+03 8.69044824e+03 8.76786914e+03 8.59250781e+03 8.45697852e+03 8.26843164e+03 8.49806738e+03 9.02236523e+03 9.37345605e+03 8.94865625e+03 8.60622461e+03 8.94710059e+03 9.06884375e+03 9.41374414e+03 9.40559863e+03 9.13789355e+03 9.09688477e+03 9.15820508e+03 9.25149414e+03 9.11301367e+03 9.37512793e+03 9.83524414e+03 9.61897852e+03 9.65231543e+03 9.52752246e+03 9.37454785e+03 1.00282549e+04 1.00459180e+04 9.75942480e+03 9.60190137e+03 9.56155371e+03 9.90551855e+03 9.95936621e+03 1.02707803e+04 1.04227295e+04 1.00882432e+04 9.88711914e+03 1.01018477e+04 1.06149775e+04 1.05299883e+04 1.03237861e+04 1.02247842e+04 1.02372754e+04 1.03866084e+04 1.03851680e+04 1.07325430e+04 1.08094297e+04 1.04863506e+04 1.08810039e+04 1.10572031e+04 1.08343184e+04 1.08711387e+04 1.08763242e+04 1.09444785e+04 1.06895000e+04 1.06062451e+04 1.12270469e+04 1.14090469e+04 1.08184678e+04 1.05471445e+04 1.11698535e+04 1.18786357e+04 1.17023398e+04 1.10773867e+04 1.09162734e+04 1.15880332e+04 1.17192676e+04 1.13711523e+04 1.17284189e+04 1.14356660e+04 1.09668330e+04 1.13607363e+04 1.20566162e+04 1.23305449e+04 1.17065283e+04 1.11812666e+04 1.18832305e+04 1.25018184e+04 1.21919902e+04 1.16547764e+04 1.15034443e+04 1.18929707e+04 1.20350557e+04 1.24191514e+04 1.24035615e+04 1.20140840e+04 1.20841201e+04 1.21167041e+04 1.25625498e+04 1.23434736e+04 1.20319893e+04 1.25212832e+04 1.24963086e+04 1.25958477e+04 1.24116631e+04 1.22178047e+04 1.29440869e+04 1.26552520e+04 1.21636338e+04 1.24851348e+04 1.27876309e+04 1.28929053e+04 1.27490879e+04 1.30500166e+04 1.31943672e+04 1.29108975e+04 1.25450049e+04 1.25107510e+04 1.32258545e+04 1.29760625e+04 1.26760088e+04 1.30769932e+04 1.30850381e+04 1.30717031e+04 1.30113672e+04 1.33763252e+04 1.33021650e+04 1.29093623e+04 1.34063418e+04 1.34932822e+04 1.33515215e+04 1.33669521e+04 1.33474521e+04 1.32114551e+04 1.29215439e+04 1.27451094e+04 1.34275557e+04 1.42440527e+04 1.35195713e+04 1.27289082e+04 1.33422354e+04 1.42460439e+04 1.41012480e+04 1.33570664e+04 1.30456592e+04 1.38027578e+04 1.38615596e+04 1.34107100e+04 1.39859453e+04 1.39685254e+04 1.32698857e+04 1.32838213e+04 1.39963447e+04 1.43777012e+04 1.37430059e+04 1.31937002e+04 1.37265332e+04 1.45655469e+04 1.43051816e+04 1.36178301e+04 1.32698896e+04 1.38798799e+04 1.45672842e+04 1.41250469e+04 1.37441846e+04 1.38763223e+04 1.40113086e+04 1.39637705e+04 1.43984512e+04 1.41041543e+04 1.36711553e+04 1.40528066e+04 1.41083164e+04 1.44314473e+04 1.41297744e+04 1.37450508e+04 1.42350557e+04 1.38647305e+04 1.38676357e+04 1.44730664e+04 1.43534678e+04 1.42222354e+04 1.40405059e+04 1.45929990e+04 1.47611289e+04 1.41867324e+04 1.38408750e+04 1.39540361e+04 1.48649512e+04 1.43531475e+04 1.37646299e+04 1.57140068e+04 2.06799180e+04 1.94717227e+04 2.25917656e+04 2.24890605e+04 9.16930469e+04 2.18889446e+09 0. 0. 0. 0. 0. 7.37560986e+10 7.37560986e+10 -2.76790682e+09 8.42352562e+05 7.75989375e+04 1.27741852e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -5.03211008e+09 9.37572188e+04 2.82538730e+04 1.59695635e+04 1.49370664e+04 1.59273398e+04 1.44882705e+04 1.38142773e+04 1.38038496e+04 1.37464219e+04 1.39132822e+04 1.43572734e+04 1.41999131e+04 1.36818818e+04 1.39265811e+04 1.42630791e+04 1.38595566e+04 1.36195049e+04 1.36364248e+04 1.38309707e+04 1.41280908e+04 1.41996836e+04 1.38395986e+04 1.33678730e+04 1.36942881e+04 1.41774424e+04 1.38818857e+04 1.38203975e+04 1.37053164e+04 1.35866650e+04 1.40179707e+04 1.37385469e+04 1.32743545e+04 1.34679541e+04 1.35007393e+04 1.36487480e+04 1.37639688e+04 1.33883350e+04 1.33751699e+04 1.38064551e+04 1.43634678e+04 1.39432822e+04 1.29752920e+04 1.29649834e+04 1.33287812e+04 1.35725469e+04 1.38068281e+04 1.35391826e+04 1.31358213e+04 1.34634727e+04 1.36467734e+04 1.32088467e+04 1.30621006e+04 1.30361328e+04 1.34304072e+04 1.39121924e+04 1.31845059e+04 1.27041885e+04 1.30261719e+04 1.32887969e+04 1.34909580e+04 1.32335811e+04 1.29104229e+04 1.27505215e+04 1.30410830e+04 1.35733857e+04 1.31826514e+04 1.25269775e+04 1.27683506e+04 1.29705420e+04 1.29668408e+04 1.30809268e+04 1.28810586e+04 1.25130957e+04 1.27750986e+04 1.30334160e+04 1.27822842e+04 1.25362529e+04 1.23962266e+04 1.24254062e+04 1.27784541e+04 1.30886494e+04 1.26883662e+04 1.22020928e+04 1.23670391e+04 1.26957168e+04 1.24214629e+04 1.22284756e+04 1.22032344e+04 1.23981943e+04 1.27597246e+04 1.24937393e+04 1.19345537e+04 1.18430234e+04 1.19528721e+04 1.21814053e+04 1.22371621e+04 1.19927246e+04 1.19408701e+04 1.22221514e+04 1.25256758e+04 1.21684170e+04 1.14808799e+04 1.15002295e+04 1.18725420e+04 1.19219639e+04 1.18684023e+04 1.16377598e+04 1.14726133e+04 1.17984590e+04 1.18241162e+04 1.14379160e+04 1.15123301e+04 1.15312109e+04 1.14042080e+04 1.16326934e+04 1.15529014e+04 1.12055234e+04 1.11682412e+04 1.11467764e+04 1.11260859e+04 1.13643232e+04 1.15686104e+04 1.12015322e+04 1.07813125e+04 1.09778828e+04 1.12419043e+04 1.09874092e+04 1.07608125e+04 1.06679580e+04 1.06922754e+04 1.09645137e+04 1.09921885e+04 1.05906094e+04 1.04502959e+04 1.05284346e+04 1.07145850e+04 1.07361436e+04 1.05168691e+04 1.03995537e+04 1.04345254e+04 1.05484883e+04 1.02715166e+04 9.99430762e+03 1.01312803e+04 1.01872939e+04 1.02573398e+04 1.04150674e+04 1.01381250e+04 9.69024707e+03 9.88781543e+03 1.00977275e+04 9.95616406e+03 9.78265332e+03 9.55720898e+03 9.57759863e+03 9.94920312e+03 1.00111992e+04 9.45999902e+03 9.23419531e+03 9.59792090e+03 9.72669922e+03 9.44975586e+03 9.11532227e+03 9.14338770e+03 9.42598145e+03 9.51540234e+03 9.15015527e+03 8.97682715e+03 9.03903125e+03 8.93260547e+03 9.06354004e+03 9.11254199e+03 8.82802832e+03 8.81275879e+03 8.94385547e+03 8.87133203e+03 8.67045312e+03 8.52425293e+03 8.47600977e+03 8.44463574e+03 8.58374219e+03 8.81749316e+03 8.75126562e+03 8.16571143e+03 8.21440625e+03 8.56581445e+03 8.17417432e+03 7.99742578e+03 8.03556250e+03 8.04022461e+03 8.23476172e+03 8.20785254e+03 7.79564160e+03 7.66971094e+03 7.71225195e+03 7.81715625e+03 7.84545410e+03 7.64464355e+03 7.60637012e+03 7.80807715e+03 7.71068457e+03 7.45462744e+03 7.29921533e+03 7.30402637e+03 7.28052344e+03 7.40234229e+03 7.43344238e+03 7.38895996e+03 7.00939355e+03 7.02418164e+03 7.17609717e+03 6.99363086e+03 6.87945605e+03 6.88502490e+03 6.84726123e+03 7.00512012e+03 6.97209766e+03 6.64927441e+03 6.58125684e+03 6.52434082e+03 6.56257666e+03 6.61453125e+03 6.44894336e+03 6.43619092e+03 6.41479443e+03 6.46855859e+03 6.49932861e+03 6.10688135e+03 6.00675439e+03 6.13520117e+03 6.10373779e+03 6.13741113e+03 6.00116211e+03 5.78414844e+03 5.89648877e+03 6.04149365e+03 5.78505713e+03 5.67996582e+03 5.71424268e+03 5.66570068e+03 5.62629980e+03 5.53982031e+03 5.64064893e+03 5.55795361e+03 5.36056738e+03 5.43846338e+03 5.25471777e+03 5.23550879e+03 5.31584326e+03 5.12017334e+03 5.09194482e+03 5.14183740e+03 5.00666260e+03 4.82772803e+03 4.82485107e+03 5.02102051e+03 5.07046240e+03 4.72613623e+03 4.64012207e+03 4.74901221e+03 4.71140088e+03 4.67030713e+03 4.49093701e+03 4.45096777e+03 4.50617383e+03 4.53428369e+03 4.43015576e+03 4.31649609e+03 4.26659033e+03 4.24823047e+03 4.29769092e+03 4.13193750e+03 4.03308276e+03 3.99537256e+03 3.95196436e+03 4.00075439e+03 4.07995215e+03 3.95575830e+03 3.73751904e+03 3.71798462e+03 3.85439429e+03 3.84624561e+03 3.61003687e+03 3.65259814e+03 3.70069604e+03 3.49694385e+03 3.48331201e+03 3.41735986e+03 3.37602661e+03 3.47647754e+03 3.38850073e+03 3.23257715e+03 3.30482715e+03 3.27893848e+03 3.13615161e+03 3.15618115e+03 3.13137256e+03 3.06283350e+03 2.95784155e+03 2.90343433e+03 2.94961890e+03 2.97203931e+03 2.88445728e+03 2.76277222e+03 2.72057031e+03 2.78220850e+03 2.77063794e+03 2.63039111e+03 2.57216382e+03 2.55832080e+03 2.58721069e+03 2.56316431e+03 2.42452490e+03 2.39309375e+03 2.43082568e+03 2.39418945e+03 2.30847192e+03 2.31366846e+03 2.27997998e+03 2.18556396e+03 2.22025854e+03 2.22177222e+03 2.09211816e+03 1.99282715e+03 1.99595190e+03 2.01640540e+03 2.00026660e+03 1.94791833e+03 1.88215186e+03 1.84753003e+03 1.87133679e+03 1.85513550e+03 1.75402393e+03 1.70926379e+03 1.72901013e+03 1.73970605e+03 1.64703662e+03 1.58174792e+03 1.59423352e+03 1.55341736e+03 1.51313550e+03 1.48843494e+03 1.47364099e+03 1.43433240e+03 1.38676953e+03 1.37437451e+03 1.35410803e+03 1.31384973e+03 1.26184082e+03 1.24146387e+03 1.24078064e+03 1.21583374e+03 1.16657336e+03 1135. 1.11761560e+03 1.12500134e+03 1.09624927e+03 1.02945764e+03 1.01743854e+03 1.00457098e+03 9.73374146e+02 9.38197510e+02 9.08325562e+02 9.01658264e+02 8.80526001e+02 8.38143860e+02 7.95645935e+02 7.97600037e+02 8.02007996e+02 7.66367859e+02 7.39922485e+02 7.12735962e+02 6.97325378e+02 6.63455566e+02 6.21276184e+02 6.22205383e+02 6.18386414e+02 5.99640259e+02 5.74747375e+02 5.37037598e+02 5.24404785e+02 5.17257812e+02 5.06079254e+02 4.94496704e+02 4.58975220e+02 4.32980591e+02 4.14733948e+02 4.09279144e+02 4.05132172e+02 3.83961731e+02 3.63226715e+02 3.33736694e+02 3.26460175e+02 3.22642303e+02 3.01183105e+02 2.90722076e+02 2.73600311e+02 2.58214783e+02 2.52169754e+02 2.34600937e+02 2.19899643e+02 2.14920395e+02 2.04602875e+02 1.86457275e+02 1.70963562e+02 1.63144608e+02 1.55509491e+02 1.49921768e+02 1.42613098e+02 1.28204544e+02 1.16193367e+02 1.06308411e+02 1.01022850e+02 9.64770966e+01 8.66296768e+01 7.70734558e+01 6.88778687e+01 6.34828300e+01 5.91117783e+01 5.38604546e+01 4.76395645e+01 4.15435867e+01 3.70502434e+01 3.19507923e+01 2.69116554e+01 2.36332226e+01 2.04581432e+01 1.73499775e+01 1.46678915e+01 1.16249857e+01 9.20703697e+00 7.55831814e+00 6.15587950e+00 4.95983219e+00 4.06602383e+00 3.56761479e+00 3.41208982e+00 3.60123253e+00 4.14569235e+00 5.00930071e+00 6.19292021e+00 7.65431261e+00 9.66444111e+00 1.19338579e+01 1.41720066e+01 1.73319721e+01 2.09863968e+01 2.45038929e+01 2.82670708e+01 3.19988441e+01 3.69869308e+01 4.28359337e+01 4.82461357e+01 5.38123741e+01 5.76672783e+01 6.35451698e+01 7.19828491e+01 8.03422318e+01 8.87209702e+01 9.50855942e+01 1.01813629e+02 1.07377548e+02 1.18480904e+02 1.32278748e+02 1.38360260e+02 1.47167526e+02 1.57039291e+02 1.65904602e+02 1.75553589e+02 1.87457870e+02 2.01582062e+02 2.16310928e+02 2.29822250e+02 2.35576843e+02 2.41886124e+02 2.59830750e+02 2.77475311e+02 2.93336975e+02 3.10053802e+02 3.16236908e+02 3.31379059e+02 3.44901703e+02 3.62742645e+02 3.89532043e+02 3.95819519e+02 4.10019257e+02 4.24272156e+02 4.30559479e+02 4.55628021e+02 4.97448120e+02 5.11235748e+02 5.09025909e+02 5.34941833e+02 5.47538574e+02 5.51303101e+02 5.86613831e+02 6.18140869e+02 6.35947083e+02 6.56470764e+02 6.61028259e+02 6.85823059e+02 7.21134460e+02 7.48702576e+02 7.94870544e+02 7.95317627e+02 7.72727966e+02 7.95802124e+02 8.50820618e+02 8.93648865e+02 9.12091858e+02 9.22011414e+02 9.10385742e+02 9.54891724e+02 1.02350983e+03 1.03097754e+03 1.04903613e+03 1.05931421e+03 1.08301721e+03 1.13783923e+03 1.13987610e+03 1.15729370e+03 1.24264673e+03 1.27505444e+03 1.27467932e+03 1.26717017e+03 1.25841150e+03 1.31970862e+03 1.40080432e+03 1.46766699e+03 1.46737964e+03 1.41946497e+03 1.43284570e+03 1.51744165e+03 1.59114783e+03 1.59565491e+03 1.60751257e+03 1.60407507e+03 1.65003760e+03 1.72522266e+03 1.77721777e+03 1.81283911e+03 1.81508936e+03 1.86024585e+03 1.87078723e+03 1.85212183e+03 1.91674524e+03 1.99060205e+03 2.04173975e+03 2.11482031e+03 2.06576318e+03 2.04128247e+03 2.13742261e+03 2.21185205e+03 2.29584204e+03 2.30114453e+03 2.23723169e+03 2.25424316e+03 2.35635718e+03 2.48247021e+03 2.52842993e+03 2.48431494e+03 2.47853735e+03 2.51892456e+03 2.54471191e+03 2.60285718e+03 2.70299780e+03 2.76968286e+03 2.75337524e+03 2.72436279e+03 2.74161182e+03 2.84103418e+03 2.96390991e+03 3.02694263e+03 3.04178101e+03 2.97861523e+03 2.93055664e+03 3.03595654e+03 3.18301318e+03 3.28454321e+03 3.29456274e+03 3.19031689e+03 3.16514380e+03 3.33341870e+03 3.51260840e+03 3.45243848e+03 3.49515405e+03 3.51061084e+03 3.45407495e+03 3.59096582e+03 3.69895532e+03 3.69489893e+03 3.70052271e+03 3.79062183e+03 3.85092310e+03 3.81228516e+03 3.88134497e+03 3.94696680e+03 4.08003979e+03 4.10248877e+03 4.01188110e+03 4.07461670e+03 4.08058740e+03 4.20018262e+03 4.44281738e+03 4.39869189e+03 4.23399902e+03 4.28321826e+03 4.37419092e+03 4.62649316e+03 4.72494629e+03 4.55616650e+03 4.51273242e+03 4.61961475e+03 4.76873193e+03 4.91261816e+03 4.89933838e+03 4.83849121e+03 6.73356738e+03 6.58447217e+03 1.27065840e+04 8.33867734e+04 13955498. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 71704640. -2.16288875e+06 2.58536055e+04 1.95231445e+04 1.26726719e+04 9.85960645e+03 9.89483594e+03 8.03993701e+03 7.35185645e+03 7.49364404e+03 7.92957031e+03 7.86755859e+03 7.61256201e+03 7.51317334e+03 7.43264160e+03 7.86874854e+03 8.35396680e+03 8.12125732e+03 7.86675439e+03 7.81030078e+03 7.90828125e+03 8.32032520e+03 8.37872559e+03 8.07860645e+03 8.05265088e+03 8.27732520e+03 8.32071680e+03 8.18730615e+03 8.28631348e+03 8.54073242e+03 8.83253418e+03 8.92496094e+03 8.50079395e+03 8.15213965e+03 8.49048145e+03 9.03312402e+03 9.31776367e+03 9.00151660e+03 8.64011035e+03 8.56325195e+03 9.01307422e+03 9.56479004e+03 9.27936133e+03 8.81563965e+03 8.92516016e+03 9.42502832e+03 9.41399512e+03 9.28746387e+03 9.39338672e+03 9.33132031e+03 9.55139551e+03 9.67032422e+03 9.22589746e+03 9.32601172e+03 9.83938086e+03 1.01282900e+04 9.99878320e+03 9.55671973e+03 9.29648633e+03 9.84541895e+03 1.05585215e+04 1.03415586e+04 9.87096289e+03 9.56651660e+03 9.54436328e+03 1.02038721e+04 1.08097871e+04 1.05146055e+04 1.03266973e+04 1.02610430e+04 1.00731807e+04 1.02958584e+04 1.06486221e+04 1.04062480e+04 1.02729180e+04 1.07409131e+04 1.05945361e+04 1.01965332e+04 1.04212510e+04 1.09760215e+04 1.11740654e+04 1.10950439e+04 1.08587852e+04 1.05560498e+04 1.04638418e+04 1.10400820e+04 1.17006074e+04 1.12889121e+04 1.06373096e+04 1.06968145e+04 1.11762031e+04 1.16378584e+04 1.16811729e+04 1.12101016e+04 1.10871865e+04 1.14448447e+04 1.14456758e+04 1.13944443e+04 1.15057012e+04 1.14914785e+04 1.16764639e+04 1.16549795e+04 1.13540908e+04 1.14852979e+04 1.18885879e+04 1.21060283e+04 1.21139795e+04 1.18492832e+04 1.14691670e+04 1.15846172e+04 1.22672402e+04 1.24823223e+04 1.19710869e+04 1.16059795e+04 1.15216240e+04 1.21284844e+04 1.28984199e+04 1.25192432e+04 1.18460664e+04 1.19354531e+04 1.22826143e+04 1.23261719e+04 1.20965801e+04 1.21548213e+04 1.26873379e+04 1.28045049e+04 1.24441436e+04 1.21302539e+04 1.21458555e+04 1.27053779e+04 1.32540068e+04 1.30103721e+04 1.25714736e+04 1.23430088e+04 1.21824502e+04 1.27273408e+04 1.34371074e+04 1.30046045e+04 1.24195596e+04 1.23938574e+04 1.29532148e+04 1.35401426e+04 1.31594365e+04 1.27629678e+04 1.28042686e+04 1.30114834e+04 1.32168936e+04 1.31512773e+04 1.28403408e+04 1.27302607e+04 1.33071895e+04 1.35329336e+04 1.30864297e+04 1.28316426e+04 1.30866436e+04 1.34607510e+04 1.38047598e+04 1.35573887e+04 1.28679775e+04 1.29573574e+04 1.34926787e+04 1.36176250e+04 1.34614502e+04 1.32926074e+04 1.32232480e+04 1.33280645e+04 1.36241406e+04 1.34711494e+04 1.32354844e+04 1.36823369e+04 1.39546816e+04 1.36418145e+04 1.32783770e+04 1.32737461e+04 1.37105332e+04 1.41624795e+04 1.41095459e+04 1.36948486e+04 1.32607217e+04 1.31644912e+04 1.37855371e+04 1.45021562e+04 1.40409551e+04 1.32611826e+04 1.32595059e+04 1.38207021e+04 1.43189512e+04 1.41726309e+04 1.37765186e+04 1.36705713e+04 1.37539629e+04 1.37087129e+04 1.37680439e+04 1.39273838e+04 1.39086982e+04 1.39910449e+04 1.39331455e+04 1.36348887e+04 1.37189102e+04 1.40979268e+04 1.42872197e+04 1.42501113e+04 1.36537480e+04 1.33312627e+04 1.40318877e+04 1.46822373e+04 1.44323066e+04 1.39335020e+04 1.35474639e+04 1.33692021e+04 1.40957480e+04 1.49172090e+04 1.44899033e+04 1.36798770e+04 1.35111357e+04 1.39935273e+04 1.43285303e+04 1.42976729e+04 1.41570557e+04 1.40380283e+04 1.40012158e+04 1.37776621e+04 1.34101943e+04 1.36207939e+04 1.40248877e+04 1.42967900e+04 1.47711377e+04 1.43777969e+04 1.34764561e+04 1.33818125e+04 1.39071035e+04 1.43849785e+04 1.43289854e+04 1.39778389e+04 1.42951846e+04 1.44205977e+04 1.37629844e+04 1.33079189e+04 1.36097812e+04 1.43125938e+04 1.47534775e+04 1.44866182e+04 1.36492852e+04 1.32454717e+04 1.35328359e+04 1.42346279e+04 1.47399238e+04 1.44026338e+04 1.35939062e+04 1.35211436e+04 1.43585410e+04 1.43519766e+04 1.37129111e+04 1.36835205e+04 1.37422002e+04 1.37398398e+04 1.42326875e+04 1.39431309e+04 1.35081221e+04 1.37658975e+04 1.34308174e+04 1.38048008e+04 1.41791094e+04 1.34395410e+04 1.37173203e+04 1.41160508e+04 1.37184277e+04 1.36834473e+04 1.37431289e+04 1.37475576e+04 1.37871572e+04 1.36842881e+04 1.32855293e+04 1.32963105e+04 1.39186504e+04 1.42694502e+04 1.39065479e+04 1.32608643e+04 1.29513428e+04 1.32486943e+04 1.38463672e+04 1.41231807e+04 1.38288594e+04 1.30685889e+04 1.31043018e+04 1.35890898e+04 1.34480801e+04 1.33200996e+04 1.33281357e+04 1.32713867e+04 1.32398535e+04 1.37422441e+04 1.33731553e+04 1.28501855e+04 1.31458682e+04 1.28428477e+04 1.32516621e+04 1.35025732e+04 1.30458057e+04 1.35292354e+04 1.31519600e+04 1.25908232e+04 1.29906514e+04 1.27006992e+04 1.28843740e+04 1.37402148e+04 1.30386348e+04 1.22728691e+04 1.24666045e+04 1.29953115e+04 1.35058721e+04 1.32495957e+04 1.25141865e+04 1.20348174e+04 1.23051582e+04 1.29433408e+04 1.33067920e+04 1.30215361e+04 1.23611426e+04 1.22321709e+04 1.25861719e+04 1.26755107e+04 1.24221523e+04 1.22540488e+04 1.23204951e+04 1.23871777e+04 1.26726318e+04 1.26477119e+04 1.20007295e+04 1.19790195e+04 1.20810068e+04 1.20890586e+04 1.22341172e+04 1.21434883e+04 1.24438076e+04 1.21066201e+04 1.16262598e+04 1.19216865e+04 1.15721387e+04 1.18223066e+04 1.25927041e+04 1.19679004e+04 1.11850801e+04 1.13225068e+04 1.18701885e+04 1.21958828e+04 1.21722275e+04 1.14987910e+04 1.09844326e+04 1.11518750e+04 1.16953965e+04 1.20766553e+04 1.17125586e+04 1.10211064e+04 1.08926133e+04 1.11978145e+04 1.14031602e+04 1.17064561e+04 1.16365674e+04 1.08689775e+04 1.07127725e+04 1.12804521e+04 1.13330967e+04 1.08160205e+04 1.07877930e+04 1.08877559e+04 1.07595244e+04 1.10818662e+04 1.11112529e+04 1.04891797e+04 1.04227002e+04 1.06644502e+04 1.06104814e+04 1.06024414e+04 1.03963574e+04 1.05831387e+04 1.07709023e+04 1.04903613e+04 1.01335781e+04 9.87622852e+03 1.02189463e+04 1.07438701e+04 1.05106221e+04 9.94378809e+03 9.60934570e+03 9.89179395e+03 1.04253115e+04 1.01309873e+04 9.54594629e+03 9.57237500e+03 9.80619629e+03 1.00067559e+04 1.03069365e+04 1.00043496e+04 9.42543848e+03 9.12587793e+03 9.37680176e+03 9.77972070e+03 9.74657812e+03 9.42793652e+03 9.31104004e+03 9.26480566e+03 9.43914453e+03 9.34704688e+03 9.10228320e+03 8.94987598e+03 8.74760547e+03 9.14460547e+03 9.40517871e+03 8.94910645e+03 8.92094531e+03 8.91669824e+03 9.03573242e+03 8.78420508e+03 8.32035352e+03 8.58717285e+03 9.05288770e+03 8.77268164e+03 8.28315820e+03 8.27848047e+03 8.69779004e+03 8.64923242e+03 8.35268457e+03 8.30960547e+03 7.99945654e+03 7.90948096e+03 8.39142969e+03 8.36149219e+03 7.97859766e+03 7.70989502e+03 7.64085889e+03 7.92544531e+03 8.21445410e+03 7.84678369e+03 7.61912793e+03 7.72408643e+03 7.66491748e+03 7.83178076e+03 7.76825879e+03 7.31184082e+03 7.25315918e+03 7.40689844e+03 7.36354297e+03 7.35821680e+03 7.25016943e+03 7.38925195e+03 7.26589502e+03 6.94412646e+03 7.00836426e+03 6.89002295e+03 7.01767188e+03 7.27166455e+03 7.05545215e+03 6.74298975e+03 6.63749951e+03 6.96706738e+03 6.99397754e+03 6.85431543e+03 7.22651562e+03 8.27579590e+03 8.82018066e+03 5.29952109e+04 -7.88935350e+06 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. 0. 0. 0. 0. 0. 0. 0. -5923267. 7.84163984e+04 1.44055479e+04 8.33054492e+03 7.89903320e+03 7.05056738e+03 5.43443701e+03 5.49428760e+03 4.49677588e+03 4.48155713e+03 4.29774219e+03 4.13058789e+03 4.20310449e+03 4.17706982e+03 4.02285962e+03 3.99713672e+03 3.95580566e+03 3.90160596e+03 3.87123169e+03 3.82043994e+03 3.75645703e+03 3.65579980e+03 3.60991309e+03 3.70801514e+03 3.68399536e+03 3.47674805e+03 3.41831226e+03 3.55605957e+03 3.53892603e+03 3.41128418e+03 3.35897632e+03 3.28839893e+03 3.26193506e+03 3.22483472e+03 3.17285620e+03 3.13638574e+03 3.08112183e+03 2.98867480e+03 2.94913110e+03 3.02813135e+03 2.99589160e+03 2.88934204e+03 2.85139087e+03 2.82773438e+03 2.79372144e+03 2.73830859e+03 2.68596582e+03 2.65408765e+03 2.55416357e+03 2.51617749e+03 2.53492188e+03 2.48516309e+03 2.53667920e+03 2.52688354e+03 2.40452319e+03 2.28725928e+03 2.23527710e+03 2.35438818e+03 2.33424609e+03 2.20639258e+03 2.14687500e+03 2.12762231e+03 2.09053394e+03 2.03647644e+03 2.09474463e+03 2.05155981e+03 1.89756543e+03 1.86085645e+03 1.92601038e+03 1.96059937e+03 1.87741553e+03 1.80049475e+03 1.78277979e+03 1.73970813e+03 1.69008203e+03 1.66410547e+03 1.65470923e+03 1.61424854e+03 1.55193018e+03 1.52497046e+03 1.52443896e+03 1.48542188e+03 1.49235449e+03 1.44745117e+03 1.37273779e+03 1.36671448e+03 1.33898572e+03 1.33707690e+03 1.31855591e+03 1.26556262e+03 1.22825000e+03 1.17432349e+03 1.12800195e+03 1.15659766e+03 1.14435547e+03 1.05851807e+03 1.04012695e+03 1.07594263e+03 1.07765564e+03 1.01928821e+03 9.65871826e+02 9.39081360e+02 9.14921143e+02 8.81638794e+02 8.56124756e+02 8.50622070e+02 8.25429199e+02 8.13003784e+02 7.83147156e+02 7.45627930e+02 7.38300720e+02 6.96030884e+02 6.85992493e+02 7.02414124e+02 6.67434814e+02 6.31407104e+02 5.93563293e+02 5.70476990e+02 5.84964905e+02 5.69997681e+02 5.31414734e+02 4.99204254e+02 4.82367157e+02 4.76408203e+02 4.58237030e+02 4.54124969e+02 4.40297272e+02 4.09828400e+02 3.86459106e+02 3.71921600e+02 3.69440063e+02 3.53660431e+02 3.31451111e+02 3.10161957e+02 2.95772308e+02 2.89378265e+02 2.68102783e+02 2.57766205e+02 2.60527893e+02 2.43693802e+02 2.23965714e+02 2.06063126e+02 1.93787964e+02 1.94017349e+02 1.83463638e+02 1.67520874e+02 1.52533386e+02 1.41955078e+02 1.37267456e+02 1.27622757e+02 1.18008530e+02 1.07071167e+02 1.00582245e+02 9.64431763e+01 8.65614624e+01 7.96373978e+01 7.32602234e+01 6.53157806e+01 5.74967461e+01 5.16148338e+01 4.71031647e+01 4.19067116e+01 3.70657425e+01 3.13977146e+01 2.74547062e+01 2.49822903e+01 2.05179043e+01 1.67706490e+01 1.42405891e+01 1.16811495e+01 9.67463779e+00 7.68334532e+00 6.03792048e+00 4.95750284e+00 4.10363913e+00 3.58054423e+00 3.41172600e+00 3.58935571e+00 4.10390568e+00 4.95793676e+00 6.19930696e+00 7.64656925e+00 9.61569595e+00 1.23569546e+01 1.47900648e+01 1.70886650e+01 1.97649250e+01 2.38801785e+01 2.93412724e+01 3.32557182e+01 3.69618301e+01 4.11937141e+01 4.61022034e+01 5.29209938e+01 5.88766594e+01 6.66269379e+01 7.23410034e+01 7.67892227e+01 8.62174759e+01 9.43015289e+01 1.04068192e+02 1.11870224e+02 1.17875778e+02 1.26335258e+02 1.35548141e+02 1.47980896e+02 1.54026550e+02 1.66721100e+02 1.87113220e+02 1.94000977e+02 2.00594498e+02 2.07018570e+02 2.17449524e+02 2.41990265e+02 2.57017761e+02 2.62996307e+02 2.67876221e+02 2.81813416e+02 3.04773285e+02 3.18823486e+02 3.41943115e+02 3.55732544e+02 3.62725952e+02 3.66930389e+02 3.81271973e+02 4.23542938e+02 4.36253235e+02 4.39652985e+02 4.52693665e+02 4.68345520e+02 5.08303772e+02 5.30588257e+02 5.22241699e+02 5.36948547e+02 5.85769653e+02 6.06304993e+02 5.95330566e+02 6.13183411e+02 6.68226074e+02 6.90736328e+02 6.89227905e+02 6.95004089e+02 7.13664856e+02 7.81031555e+02 7.98410461e+02 7.92221619e+02 8.17635864e+02 8.32916687e+02 8.70374390e+02 9.00997070e+02 9.14988098e+02 9.16882751e+02 9.63752930e+02 1.03319788e+03 1.02529199e+03 1.05807373e+03 1.09678735e+03 1.09840063e+03 1.12849548e+03 1.15295654e+03 1.17058081e+03 1.17585242e+03 1.19826807e+03 1.25321082e+03 1.28939612e+03 1.35717676e+03 1.34594189e+03 1.33202173e+03 1.39698291e+03 1.43513611e+03 1.51100220e+03 1.51598254e+03 1.50128455e+03 1.53767639e+03 1.56295581e+03 1.61965186e+03 1.64778613e+03 1.71803040e+03 1.73334314e+03 1.71613232e+03 1.76216711e+03 1.74017334e+03 1.83250061e+03 1.97954639e+03 1.96483728e+03 1.93796680e+03 1.91916797e+03 1.93363928e+03 2.06483032e+03 2.16398315e+03 2.13746899e+03 2.09037305e+03 2.12383105e+03 2.22364722e+03 2.24765552e+03 2.33365649e+03 2.35501074e+03 2.32265649e+03 2.39747632e+03 2.42809985e+03 2.53729858e+03 2.58160620e+03 2.47632837e+03 2.51312329e+03 2.69737842e+03 2.68829321e+03 2.58941919e+03 2.71466943e+03 2.90693359e+03 2.89003760e+03 2.84876343e+03 2.82306714e+03 2.86910864e+03 3.06713306e+03 3.10089746e+03 3.06270801e+03 3.02798389e+03 3.04396484e+03 3.18199365e+03 3.23301318e+03 3.25634888e+03 3.23058130e+03 3.34480225e+03 3.49159644e+03 3.44709985e+03 3.53977686e+03 3.52836401e+03 3.47374976e+03 3.59366675e+03 3.66021948e+03 3.70594116e+03 3.70721924e+03 3.72045752e+03 3.69473047e+03 3.83884277e+03 4.13158740e+03 3.95327563e+03 3.80980884e+03 3.96493555e+03 4.15187842e+03 4.30289209e+03 4.22403125e+03 4.16558447e+03 4.30818213e+03 4.37360693e+03 4.23971094e+03 4.23709814e+03 4.52964795e+03 4.56277686e+03 4.45827783e+03 4.53047168e+03 4.42729492e+03 4.62440039e+03 4.97658398e+03 4.89096631e+03 4.80152344e+03 4.70912451e+03 4.69859131e+03 5.00775635e+03 5.32320850e+03 5.18092139e+03 4.96236523e+03 4.98434521e+03 5.15478564e+03 5.22206104e+03 5.42850342e+03 5.33572852e+03 5.23316406e+03 5.45041309e+03 5.45412988e+03 5.65837012e+03 5.66103564e+03 5.47505225e+03 5.72222803e+03 5.76556738e+03 5.74479834e+03 5.63494385e+03 5.75699561e+03 6.12856982e+03 6.10107324e+03 5.89530127e+03 5.82697314e+03 6.03188184e+03 6.41233252e+03 6.38840771e+03 6.24348047e+03 6.10401074e+03 6.13069727e+03 6.37787744e+03 6.45840625e+03 6.51615088e+03 6.36840039e+03 6.56199951e+03 6.82620605e+03 6.67992383e+03 6.89663623e+03 6.91414893e+03 6.78662598e+03 6.86851318e+03 6.92909180e+03 6.94241992e+03 6.97315576e+03 6.95496533e+03 7.00795947e+03 7.33895068e+03 7.38640967e+03 7.10211279e+03 7.04512012e+03 7.24681152e+03 7.52266162e+03 7.81749365e+03 7.60721143e+03 7.25331592e+03 7.59788086e+03 7.98840625e+03 7.88418945e+03 7.58387842e+03 7.64733350e+03 7.80474121e+03 7.88694971e+03 7.96365137e+03 7.81405664e+03 8.03393066e+03 8.43977734e+03 8.29579395e+03 8.19223730e+03 8.05794336e+03 8.16313379e+03 8.58124219e+03 8.59528125e+03 8.47893555e+03 8.32042773e+03 8.12284961e+03 8.33449121e+03 8.85476562e+03 9.22583301e+03 8.74096582e+03 8.41148438e+03 8.69469922e+03 8.93357324e+03 9.31844531e+03 9.16125098e+03 8.84780469e+03 9.06359766e+03 9.07905859e+03 9.10102734e+03 8.94594141e+03 9.12743164e+03 9.62145020e+03 9.52377441e+03 9.42328613e+03 9.25166602e+03 9.27529883e+03 9.82904492e+03 9.89655859e+03 9.64695898e+03 9.43432715e+03 9.40424609e+03 9.73175781e+03 9.76309668e+03 1.00996768e+04 1.02557158e+04 9.79345117e+03 9.61850391e+03 1.00237217e+04 1.04680342e+04 1.01986104e+04 1.00890566e+04 1.00960215e+04 1.01318887e+04 1.01081455e+04 9.94796484e+03 1.04081865e+04 1.06475898e+04 1.03699990e+04 1.06344219e+04 1.07610381e+04 1.06921426e+04 1.07343428e+04 1.06828672e+04 1.07286445e+04 1.05236191e+04 1.04260215e+04 1.09419316e+04 1.12294404e+04 1.07684648e+04 1.03606719e+04 1.08639014e+04 1.15556973e+04 1.15394385e+04 1.09938994e+04 1.06332598e+04 1.12180527e+04 1.16806416e+04 1.14528398e+04 1.14395879e+04 1.10851807e+04 1.07315176e+04 1.12027939e+04 1.19537939e+04 1.19912412e+04 1.13472422e+04 1.10266309e+04 1.17399453e+04 1.22140049e+04 1.18863428e+04 1.13905723e+04 1.11544033e+04 1.15736123e+04 1.18223340e+04 1.21496680e+04 1.23756260e+04 1.19887393e+04 1.17212451e+04 1.17975498e+04 1.23402236e+04 1.20637383e+04 1.17876396e+04 1.23514365e+04 1.23611260e+04 1.22564922e+04 1.20007383e+04 1.20207041e+04 1.27440010e+04 1.23818945e+04 1.18055635e+04 1.21587344e+04 1.26530742e+04 1.27431377e+04 1.24753633e+04 1.27920391e+04 1.29464180e+04 1.26295537e+04 1.22757061e+04 1.22332715e+04 1.30060791e+04 1.27979395e+04 1.24171230e+04 1.28521289e+04 1.28224062e+04 1.27684014e+04 1.26581348e+04 1.29783115e+04 1.31274746e+04 1.28246797e+04 1.30243789e+04 1.30957598e+04 1.32117158e+04 1.32374287e+04 1.30776270e+04 1.28829219e+04 1.25347764e+04 1.26207139e+04 1.33362686e+04 1.40047539e+04 1.32655645e+04 1.24692500e+04 1.29806035e+04 1.38044639e+04 1.39168438e+04 1.32235176e+04 1.26633594e+04 1.33808701e+04 1.37166943e+04 1.32723887e+04 1.37644365e+04 1.35898887e+04 1.28416562e+04 1.31871748e+04 1.39947129e+04 1.40388652e+04 1.33697617e+04 1.28707695e+04 1.34402041e+04 1.43499336e+04 1.40306162e+04 1.33069561e+04 1.29854443e+04 1.36506445e+04 1.41476250e+04 1.37237988e+04 1.36414629e+04 1.37019580e+04 1.37519443e+04 1.37258887e+04 1.40798389e+04 1.38516934e+04 1.34159785e+04 1.37602119e+04 1.38457559e+04 1.41575693e+04 1.38562959e+04 1.35102402e+04 1.41251113e+04 1.36752959e+04 1.33279404e+04 1.39462236e+04 1.42182363e+04 1.40985430e+04 1.37872471e+04 1.43019922e+04 1.44626445e+04 1.39397656e+04 1.36256426e+04 1.36331660e+04 1.45276260e+04 1.41138789e+04 1.33528525e+04 1.52144775e+04 1.89346602e+04 1.82290977e+04 4.56708281e+04 5.06801680e+04 1.30137797e+05 3.55368294e+09 0. 0. 0. 0. 0. 7.37560986e+10 -2.54300877e+10 6.50914336e+04 8.42903938e+05 7.75989375e+04 1.27741852e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.09421988e+10 4.97235562e+05 2.74865527e+04 1.73384023e+04 1.62216387e+04 1.44624189e+04 1.48665791e+04 1.43054443e+04 1.42217871e+04 1.38470322e+04 1.33765908e+04 1.37936445e+04 1.42493213e+04 1.37845410e+04 1.36285654e+04 1.38722109e+04 1.40216719e+04 1.40863633e+04 1.36317588e+04 1.32204023e+04 1.34967197e+04 1.38244863e+04 1.39285869e+04 1.37926387e+04 1.34483799e+04 1.35034971e+04 1.39771318e+04 1.41691943e+04 1.37288574e+04 1.32152324e+04 1.33527930e+04 1.37383447e+04 1.35893662e+04 1.35346611e+04 1.36377715e+04 1.32524678e+04 1.34589590e+04 1.37565059e+04 1.31957588e+04 1.31625215e+04 1.35645215e+04 1.40397012e+04 1.40692207e+04 1.31229238e+04 1.26741455e+04 1.30429326e+04 1.35667090e+04 1.37341807e+04 1.31773037e+04 1.31134424e+04 1.35274102e+04 1.33915166e+04 1.33304600e+04 1.31200166e+04 1.26906191e+04 1.30960371e+04 1.35213994e+04 1.30407422e+04 1.29570332e+04 13191. 1.29690195e+04 1.31610205e+04 1.32411787e+04 1.27715557e+04 1.26403193e+04 1.28952568e+04 1.32751045e+04 1.31603193e+04 1.26532285e+04 1.27426562e+04 1.26760254e+04 1.27857129e+04 1.30297812e+04 1.25534307e+04 1.24303975e+04 1.27086133e+04 1.28791240e+04 1.29404072e+04 1.25742246e+04 1.20815361e+04 1.21721377e+04 1.25797266e+04 1.27648535e+04 1.26648535e+04 1.23776162e+04 1.21888330e+04 1.24606846e+04 1.26445400e+04 1.22298662e+04 1.18417871e+04 1.20587529e+04 1.24557266e+04 1.24856758e+04 1.21874053e+04 1.18766494e+04 1.17206738e+04 1.20647344e+04 1.22480322e+04 1.18232441e+04 1.17377754e+04 1.20301162e+04 1.22915908e+04 1.22339922e+04 1.15991123e+04 1.12486807e+04 1.15783965e+04 1.17939072e+04 1.16966299e+04 1.16012715e+04 1.16273457e+04 1.17866914e+04 1.14887549e+04 1.13813506e+04 1.15992764e+04 1.12961504e+04 1.11660713e+04 1.14119463e+04 1.14663203e+04 1.14651426e+04 1.11965205e+04 1.08565752e+04 1.09213867e+04 1.11420352e+04 1.13080312e+04 1.11569082e+04 1.08472783e+04 1.08835098e+04 1.11284004e+04 1.11717373e+04 1.07511445e+04 1.04175381e+04 1.05119072e+04 1.07606982e+04 1.07932910e+04 1.06286387e+04 1.04725664e+04 1.04222168e+04 1.06289619e+04 1.06890225e+04 1.04462461e+04 1.03497441e+04 1.01522939e+04 1.02176201e+04 1.02063691e+04 1.00320869e+04 1.00651094e+04 1.00793662e+04 1.02502432e+04 1.03794395e+04 9.93087988e+03 9.61345117e+03 9.74569727e+03 9.90947266e+03 1.00321045e+04 9.86061816e+03 9.42283789e+03 9.41547461e+03 9.82349023e+03 9.97351758e+03 9.55757812e+03 9.15816504e+03 9.29907715e+03 9.60760742e+03 9.48230371e+03 8.99800098e+03 8.99208105e+03 9.21580176e+03 9.24352930e+03 9.12398438e+03 9.17734570e+03 9.07032715e+03 8.69776465e+03 8.94116699e+03 9.04168457e+03 8.62133496e+03 8.62412500e+03 8.80230859e+03 8.75939453e+03 8.79247559e+03 8.57457422e+03 8.24061230e+03 8.24438281e+03 8.48429785e+03 8.73627832e+03 8.70828223e+03 8.08056982e+03 8.08781934e+03 8.48377051e+03 8.22861133e+03 7.84552734e+03 7.84759033e+03 7.97612500e+03 8.11021924e+03 8.14355615e+03 8.01714062e+03 7.71766846e+03 7.49575977e+03 7.72792285e+03 7.81364453e+03 7.51909668e+03 7.50468457e+03 7.63217822e+03 7.65123584e+03 7.63889893e+03 7.33351709e+03 7.08310400e+03 7.16866553e+03 7.24977295e+03 7.40118359e+03 7.34505518e+03 6.96780811e+03 6.92994873e+03 7.06732080e+03 7.04231152e+03 6.94215967e+03 6.72784424e+03 6.68303223e+03 6.86312988e+03 6.88421924e+03 6.70709473e+03 6.56633447e+03 6.39188916e+03 6.51550879e+03 6.56193994e+03 6.33329541e+03 6.37622559e+03 6.37709863e+03 6.36964404e+03 6.47809131e+03 6.11555371e+03 5.95240869e+03 6.06398438e+03 6.04721826e+03 6.09256982e+03 5.85053174e+03 5.69766211e+03 5.86441943e+03 5.95095752e+03 5.86610010e+03 5.64388574e+03 5.65077686e+03 5.54179980e+03 5.45171582e+03 5.55019336e+03 5.67475391e+03 5.48606201e+03 5.22576123e+03 5.35457812e+03 5.24866992e+03 5.24540625e+03 5.20120801e+03 4.99229541e+03 5.08640820e+03 5.15225732e+03 4.90866943e+03 4.81685352e+03 4.86186035e+03 4.95141748e+03 4.97841260e+03 4.65983643e+03 4.57933105e+03 4.70040625e+03 4.69126221e+03 4.69218604e+03 4.48562256e+03 4.42690967e+03 4.38155713e+03 4.34839551e+03 4.43941406e+03 4.36119922e+03 4.16135938e+03 4.19929004e+03 4.27833301e+03 4.09581055e+03 4.01860596e+03 3.95889746e+03 3.90012036e+03 4.00735938e+03 4.04943457e+03 3.86167944e+03 3.74991260e+03 3.75784155e+03 3.76928491e+03 3.78118457e+03 3.63965161e+03 3.64744922e+03 3.62261182e+03 3.41515894e+03 3.41677271e+03 3.41076904e+03 3.37522388e+03 3.39486938e+03 3.33891724e+03 3.25615991e+03 3.29809204e+03 3.19678735e+03 3.08483691e+03 3.12295312e+03 3.12682031e+03 3.05880688e+03 2.92888672e+03 2.87788867e+03 2.96562769e+03 2.97161987e+03 2.82367188e+03 2.71284131e+03 2.72505713e+03 2.76469629e+03 2.75519458e+03 2.62056616e+03 2.57557642e+03 2.52048950e+03 2.53219092e+03 2.54233911e+03 2.43300073e+03 2.39872998e+03 2.37101294e+03 2.32573145e+03 2.32343359e+03 2.32941479e+03 2.23795435e+03 2.13198584e+03 2.19644678e+03 2.23541553e+03 2.09556445e+03 1.98017322e+03 1.98746765e+03 2.00311255e+03 1.98229199e+03 1.90633765e+03 1.86520935e+03 1.84518396e+03 1.85319995e+03 1.82511145e+03 1.75306738e+03 1.71014172e+03 1.68900403e+03 1.69638208e+03 1.64085364e+03 1.57740796e+03 1.57369153e+03 1.53295984e+03 1.49226929e+03 1.49587109e+03 1.47264209e+03 1.40819141e+03 1.37035461e+03 1.37650073e+03 1.35119812e+03 1.29250684e+03 1.25365002e+03 1.24052539e+03 1.24127576e+03 1.20992249e+03 1.13992444e+03 1.11617078e+03 1.10992102e+03 1.11768274e+03 1.09471985e+03 1.03052368e+03 1.02513538e+03 9.89884888e+02 9.31510254e+02 9.20395447e+02 9.11237366e+02 9.06128845e+02 8.79121399e+02 8.20723938e+02 7.90554810e+02 7.92569519e+02 7.97198853e+02 7.69626892e+02 7.32929932e+02 7.08356689e+02 6.79364624e+02 6.52428345e+02 6.30965515e+02 6.30520752e+02 6.21260193e+02 5.82439087e+02 5.60302124e+02 5.41363220e+02 5.29758728e+02 5.17999207e+02 4.98616302e+02 4.90787933e+02 4.55366272e+02 4.23014313e+02 4.13531677e+02 4.08596588e+02 4.02768768e+02 3.88370026e+02 3.61824371e+02 3.29705231e+02 3.21582855e+02 3.17971161e+02 3.00390259e+02 2.93431702e+02 2.79017578e+02 2.54985458e+02 2.48805878e+02 2.39171310e+02 2.21585724e+02 2.11574371e+02 1.98562134e+02 1.84869766e+02 1.74219879e+02 1.65046143e+02 1.55978638e+02 1.50189987e+02 1.44251556e+02 1.28681168e+02 1.14623550e+02 1.07259796e+02 1.01705544e+02 9.69331131e+01 8.85572128e+01 7.75876617e+01 7.00318985e+01 6.54122391e+01 6.09850769e+01 5.52360687e+01 4.82864380e+01 4.28304062e+01 3.79997597e+01 3.31906052e+01 2.88622646e+01 2.54753056e+01 2.21404991e+01 1.87694874e+01 1.59734764e+01 1.31579857e+01 1.09535131e+01 9.26544189e+00 7.76695061e+00 6.60342646e+00 5.72399282e+00 5.22386169e+00 5.07523298e+00 5.26385260e+00 5.80391502e+00 6.69330120e+00 7.83992243e+00 9.20805264e+00 1.11445370e+01 1.34643478e+01 1.58572569e+01 1.91080112e+01 2.27063618e+01 2.56099815e+01 2.92153416e+01 3.36618309e+01 3.88870811e+01 4.44208908e+01 4.90610924e+01 5.46089516e+01 5.88914986e+01 6.46271667e+01 7.32278214e+01 8.07558975e+01 8.93074951e+01 9.69600677e+01 1.01660828e+02 1.07960136e+02 1.19513329e+02 1.31842331e+02 1.39834488e+02 1.47994873e+02 1.57331497e+02 1.64529678e+02 1.76392685e+02 1.90947006e+02 2.01807999e+02 2.14298645e+02 2.23682755e+02 2.32321014e+02 2.44654770e+02 2.64749634e+02 2.79573975e+02 2.89457184e+02 3.06482239e+02 3.12093658e+02 3.29857208e+02 3.50154724e+02 3.61739899e+02 3.87572235e+02 3.93299957e+02 3.97425964e+02 4.17773163e+02 4.34748871e+02 4.62037201e+02 4.98422638e+02 5.07581329e+02 5.03163147e+02 5.19262085e+02 5.38269470e+02 5.56334473e+02 5.92723328e+02 6.21695374e+02 6.22646606e+02 6.36698914e+02 6.59313416e+02 6.93912354e+02 7.23598572e+02 7.37947388e+02 7.82171509e+02 7.83408264e+02 7.57724426e+02 7.96203735e+02 8.51881104e+02 8.88036194e+02 9.17647217e+02 9.12883240e+02 8.91733704e+02 9.42932251e+02 1.01924805e+03 1.03526306e+03 1.03863672e+03 1.05687561e+03 1.06511621e+03 1.11603320e+03 1.15335718e+03 1.15705493e+03 1.22239429e+03 1.23832654e+03 1.24533545e+03 1.27888611e+03 1.27144727e+03 1.31852869e+03 1.38076599e+03 1.44477539e+03 1.43886353e+03 1.39076318e+03 1.43509619e+03 1.51506299e+03 1.57941187e+03 1.59820752e+03 1.57636792e+03 1.58667847e+03 1.65291052e+03 1.72342419e+03 1.76075964e+03 1.78406982e+03 1.80327881e+03 1.81504541e+03 1.85119458e+03 1.88485754e+03 1.92468762e+03 1.97227649e+03 2.00810327e+03 2.06740552e+03 2.03044775e+03 2.05743091e+03 2.15504370e+03 2.17538403e+03 2.26718530e+03 2.26705835e+03 2.19105420e+03 2.24826050e+03 2.33412061e+03 2.44161401e+03 2.52645703e+03 2.46543677e+03 2.42650439e+03 2.48246655e+03 2.56122754e+03 2.62540259e+03 2.66730786e+03 2.71248364e+03 2.68582910e+03 2.69391187e+03 2.75966528e+03 2.86079834e+03 2.95604712e+03 2.95260742e+03 2.99069751e+03 2.97456543e+03 2.91775439e+03 3.02180371e+03 3.12783350e+03 3.24122095e+03 3.26754883e+03 3.14277051e+03 3.14995386e+03 3.31417700e+03 3.48514453e+03 3.46798657e+03 3.45187305e+03 3.48536694e+03 3.41407983e+03 3.55105151e+03 3.69078369e+03 3.66809497e+03 3.68038086e+03 3.69891431e+03 3.79423071e+03 3.83502002e+03 3.85822656e+03 3.94004639e+03 4.01186768e+03 4.03456348e+03 3.95590063e+03 4.05147559e+03 4.15631055e+03 4.18305078e+03 4.36032617e+03 4.30068652e+03 4.18175293e+03 4.29821143e+03 4.32645508e+03 4.54644971e+03 4.75920020e+03 4.59603516e+03 4.48059131e+03 4.48436719e+03 4.72335596e+03 5.08197852e+03 5.02925000e+03 4.68037012e+03 8.67236523e+03 9.96821777e+03 2.08580312e+06 -164669536. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -13163047. 6.31924766e+04 1.34800146e+04 1.17842812e+04 1.10197744e+04 8.32975098e+03 9.18574219e+03 7.91155957e+03 7.35911328e+03 7.47888721e+03 7.83054053e+03 7.79006201e+03 7.54334131e+03 7.36530420e+03 7.44079639e+03 7.87009473e+03 8.20744336e+03 7.97457031e+03 7.75308789e+03 7.75196094e+03 7.84020947e+03 8.22075000e+03 8.32317188e+03 8.09866162e+03 7.98450635e+03 8.05929736e+03 8.25895898e+03 8.33320020e+03 8.22565039e+03 8.33782812e+03 8.65493457e+03 8.90460645e+03 8.53752246e+03 8.11104834e+03 8.40695996e+03 8.91754785e+03 9.21970117e+03 8.87535938e+03 8.42625977e+03 8.57916504e+03 9.04005957e+03 9.49313965e+03 9.14892383e+03 8.63267773e+03 8.79041699e+03 9.26208789e+03 9.43391211e+03 9.46573438e+03 9.33687988e+03 9.14983984e+03 9.25666211e+03 9.60143945e+03 9.31380859e+03 9.25736035e+03 9.74433594e+03 9.88197266e+03 9.87519238e+03 9.52400586e+03 9.19013965e+03 9.76885449e+03 1.04470947e+04 1.02039307e+04 9.66299316e+03 9.35849121e+03 9.59113770e+03 1.02770527e+04 1.06812324e+04 1.03841162e+04 1.02003135e+04 1.00483428e+04 9.83890918e+03 1.02677402e+04 1.06204238e+04 1.03439033e+04 1.02766152e+04 1.04867588e+04 1.05820186e+04 1.03861035e+04 1.03528545e+04 1.07181797e+04 1.09232666e+04 1.10312275e+04 1.07888154e+04 1.03558838e+04 1.04173340e+04 1.10626846e+04 1.16213916e+04 1.11267520e+04 1.04860234e+04 1.06686074e+04 1.10529600e+04 1.14167832e+04 1.15577959e+04 1.12037705e+04 1.11102490e+04 1.11424883e+04 1.13325498e+04 1.15566543e+04 1.14185361e+04 1.13750732e+04 1.13520986e+04 1.14935127e+04 1.15844473e+04 1.14723926e+04 1.16541533e+04 1.18315400e+04 1.19840166e+04 1.17578213e+04 1.12475732e+04 1.15122422e+04 1.21832451e+04 1.24170186e+04 1.18902539e+04 1.13516572e+04 1.14885811e+04 1.21632207e+04 1.27978311e+04 1.23396787e+04 1.17143164e+04 1.19669902e+04 1.20018457e+04 1.21173789e+04 1.22747256e+04 1.21571123e+04 1.24530273e+04 1.23564209e+04 1.23039082e+04 1.23955303e+04 1.21239668e+04 1.24339990e+04 1.29488682e+04 1.29235234e+04 1.24942178e+04 1.21119395e+04 1.22113477e+04 1.27625889e+04 1.32954863e+04 1.28335479e+04 1.21744707e+04 1.23379893e+04 1.29849258e+04 1.34129014e+04 1.29025752e+04 1.25897510e+04 1.27441904e+04 1.27632686e+04 1.30446377e+04 1.31527129e+04 1.26395137e+04 1.26634639e+04 1.31696143e+04 1.33428174e+04 1.31695020e+04 1.29191221e+04 1.29911221e+04 1.32185615e+04 1.36154932e+04 1.33420049e+04 1.26771904e+04 1.28737568e+04 1.32479580e+04 1.34782959e+04 1.35094141e+04 1.30827207e+04 1.30287012e+04 1.32805791e+04 1.35823359e+04 1.35840557e+04 1.32569873e+04 1.34509609e+04 1.35023086e+04 1.34882373e+04 1.34526748e+04 1.31479287e+04 1.34435938e+04 1.39457666e+04 1.40322754e+04 1.35558809e+04 1.30279229e+04 1.31509219e+04 1.37933477e+04 1.43226895e+04 1.37860283e+04 1.30648076e+04 1.32432158e+04 1.36930771e+04 1.40395898e+04 1.40483398e+04 1.35054238e+04 1.34191787e+04 1.37211289e+04 1.38512246e+04 1.38345117e+04 1.37417373e+04 1.38084727e+04 1.36522363e+04 1.37699141e+04 1.38838604e+04 1.37094365e+04 1.38124443e+04 1.39076572e+04 1.40111348e+04 1.35453643e+04 1.32712822e+04 1.38347930e+04 1.43812158e+04 1.44701982e+04 1.38589268e+04 1.32592451e+04 1.33507383e+04 1.41363379e+04 1.47974521e+04 1.43558369e+04 1.36840938e+04 1.33990127e+04 1.34297656e+04 1.40350752e+04 1.45327783e+04 1.41687979e+04 1.38682178e+04 1.38582705e+04 1.37661074e+04 1.34492471e+04 1.35121328e+04 1.39192402e+04 1.40231270e+04 1.44249502e+04 1.41509482e+04 1.32813311e+04 1.35176777e+04 1.40103096e+04 1.40257891e+04 1.40724951e+04 1.39232549e+04 1.41829355e+04 1.42745615e+04 1.36548350e+04 1.31980254e+04 1.34734600e+04 1.41735381e+04 1.45966182e+04 1.43341885e+04 1.35304971e+04 1.31757725e+04 1.34900840e+04 1.40748252e+04 1.44875459e+04 1.42695488e+04 1.35137842e+04 1.34100566e+04 1.41772754e+04 1.42084561e+04 1.35115283e+04 1.34464863e+04 1.37317646e+04 1.37288604e+04 1.41383936e+04 1.37904727e+04 1.33234326e+04 1.36698447e+04 1.33097822e+04 1.36172129e+04 1.40858545e+04 1.33668877e+04 1.35583018e+04 1.39768467e+04 1.36508115e+04 1.36211543e+04 1.35577988e+04 1.35912812e+04 1.37399766e+04 1.35615264e+04 1.31055469e+04 1.31951865e+04 1.38127471e+04 1.40880615e+04 1.37729092e+04 1.32175674e+04 1.28521924e+04 1.30585596e+04 1.36778037e+04 1.40339316e+04 1.37629795e+04 1.29385566e+04 1.29290645e+04 1.35183125e+04 1.33993164e+04 1.31436074e+04 1.31318262e+04 1.31667920e+04 1.31313691e+04 1.35988398e+04 1.32486465e+04 1.27448369e+04 1.29912314e+04 1.26714307e+04 1.31181709e+04 1.34163965e+04 1.30040996e+04 1.33852139e+04 1.30274199e+04 1.25184414e+04 1.28303740e+04 1.25552715e+04 1.27967764e+04 1.36146396e+04 1.28993457e+04 1.21841855e+04 1.24549434e+04 1.29073975e+04 1.33235273e+04 1.31115537e+04 1.24013145e+04 1.19033203e+04 1.21278389e+04 1.28685869e+04 1.32383125e+04 1.29166680e+04 1.22064453e+04 1.20708525e+04 1.25509717e+04 1.26634551e+04 1.22138564e+04 1.20398672e+04 1.21988252e+04 1.22300322e+04 1.25850137e+04 1.25409746e+04 1.20139961e+04 1.19583594e+04 1.19032891e+04 1.18982578e+04 1.21207861e+04 1.20502705e+04 1.22707734e+04 1.19850859e+04 1.15089912e+04 1.18162852e+04 1.14931260e+04 1.17007490e+04 1.24780977e+04 1.18762695e+04 1.10300449e+04 1.11974307e+04 1.17527109e+04 1.20091816e+04 1.20788350e+04 1.14732363e+04 1.09047412e+04 1.10326875e+04 1.15833643e+04 1.20797080e+04 1.16777979e+04 1.09049014e+04 1.07787793e+04 1.10487451e+04 1.13430332e+04 1.16536445e+04 1.14606484e+04 1.07504268e+04 1.06090693e+04 1.10686250e+04 1.11303535e+04 1.09235566e+04 1.08715137e+04 1.06649238e+04 1.05195186e+04 1.09714824e+04 1.10195303e+04 1.04274287e+04 1.03274160e+04 1.05136924e+04 1.05442158e+04 1.05007324e+04 1.03631104e+04 1.05247686e+04 1.06449385e+04 1.02820088e+04 1.00475518e+04 9.85327637e+03 1.01777441e+04 1.06657236e+04 1.04006436e+04 9.84750977e+03 9.54977637e+03 9.86793652e+03 1.03617676e+04 9.95858789e+03 9.38764551e+03 9.51376953e+03 9.75933887e+03 9.92861426e+03 1.01798936e+04 9.93569043e+03 9.31483789e+03 9.04096387e+03 9.27610547e+03 9.72748730e+03 9.64538574e+03 9.34921387e+03 9.20622852e+03 9.19551660e+03 9.39289160e+03 9.23265527e+03 8.87684277e+03 8.82790723e+03 8.77232422e+03 9.12365820e+03 9.28427148e+03 8.91537207e+03 8.79232422e+03 8.78817969e+03 8.97565918e+03 8.73888672e+03 8.22761426e+03 8.53442090e+03 8.98934180e+03 8.60120703e+03 8.15894141e+03 8.27075293e+03 8.67099219e+03 8.59230859e+03 8.31317969e+03 8.24231934e+03 7.93944434e+03 7.90074805e+03 8.30916309e+03 8.24964551e+03 7.89899902e+03 7.62227979e+03 7.58725098e+03 7.85702246e+03 8.21052832e+03 7.81683789e+03 7.55413623e+03 7.64174268e+03 7.57474756e+03 7.76695264e+03 7.69215967e+03 7.23650879e+03 7.15857764e+03 7.27995361e+03 7.28455273e+03 7.29196875e+03 7.23232764e+03 7.37623730e+03 7.24096631e+03 6.88803027e+03 6.84042090e+03 6.75600391e+03 6.98069434e+03 7.18203857e+03 6.99446143e+03 6.69942334e+03 6.55631348e+03 6.94373486e+03 7.01971582e+03 7.11124072e+03 7.51206445e+03 8.73189844e+03 11914. 1.14984023e+05 18452610. 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. 0. 0. 0. 0. 0. 0. 0. -5923267. 7.33474766e+04 1.39245088e+04 7.97674365e+03 7.19197510e+03 6.96394189e+03 4.92706348e+03 4.97195410e+03 4.46468555e+03 4.47423486e+03 4.33042627e+03 4.10888965e+03 4.12897998e+03 4.10603809e+03 3.99653345e+03 3.98075122e+03 3.91386353e+03 3.87383374e+03 3.84103638e+03 3.78634082e+03 3.72317944e+03 3.61756152e+03 3.54816016e+03 3.68322437e+03 3.65464331e+03 3.42256421e+03 3.37886743e+03 3.52519629e+03 3.50067017e+03 3.37820825e+03 3.33421533e+03 3.26704443e+03 3.24275903e+03 3.18545361e+03 3.14268115e+03 3.11556592e+03 3.07184814e+03 2.96686792e+03 2.90709082e+03 3.01100830e+03 2.98752075e+03 2.86805396e+03 2.82267871e+03 2.78829175e+03 2.76311157e+03 2.71135815e+03 2.65962939e+03 2.63510669e+03 2.53074658e+03 2.47748169e+03 2.52059961e+03 2.47249634e+03 2.51647070e+03 2.50655908e+03 2.38130176e+03 2.27419971e+03 2.22099780e+03 2.33677368e+03 2.31887183e+03 2.19331982e+03 2.12915039e+03 2.11421851e+03 2.09031885e+03 2.03795813e+03 2.06379688e+03 2.02602783e+03 1.89090393e+03 1.84863135e+03 1.91158447e+03 1.92653369e+03 1.84292346e+03 1.78538782e+03 1.76155481e+03 1.72386804e+03 1.66591797e+03 1.63573608e+03 1.63700903e+03 1.60571899e+03 1.54913733e+03 1.52305408e+03 1.51270520e+03 1.47278870e+03 1.48135034e+03 1.44371277e+03 1.37099146e+03 1.36370312e+03 1.33374146e+03 1.31421179e+03 1.29525977e+03 1.25230969e+03 1.21577466e+03 1.16952368e+03 1.12926575e+03 1.15100500e+03 1.12216028e+03 1.04212634e+03 1.03181909e+03 1.06633826e+03 1.07559204e+03 1.01290411e+03 9.59156677e+02 9.21619324e+02 8.95671509e+02 8.80142578e+02 8.57059082e+02 8.46311218e+02 8.18943726e+02 8.07806396e+02 7.83275757e+02 7.41775940e+02 7.34437317e+02 6.91298218e+02 6.73099854e+02 6.91044739e+02 6.62184509e+02 6.27098450e+02 5.92746765e+02 5.67804565e+02 5.80937866e+02 5.65766174e+02 5.27507080e+02 4.97144531e+02 4.80458069e+02 4.75138336e+02 4.56544708e+02 4.51783356e+02 4.37695190e+02 4.08799500e+02 3.88580688e+02 3.72922516e+02 3.64594604e+02 3.49401733e+02 3.30201111e+02 3.10075470e+02 2.96513916e+02 2.89188354e+02 2.67401550e+02 2.55079636e+02 2.56781830e+02 2.42580673e+02 2.23589798e+02 2.05521225e+02 1.94042099e+02 1.94181000e+02 1.82977692e+02 1.67435074e+02 1.53236572e+02 1.42703644e+02 1.37651993e+02 1.27879738e+02 1.18700615e+02 1.08028328e+02 1.01603310e+02 9.80263824e+01 8.81436157e+01 8.00067444e+01 7.33732452e+01 6.63758011e+01 5.92138367e+01 5.31574745e+01 4.82941742e+01 4.32238045e+01 3.84460983e+01 3.27553825e+01 2.86670761e+01 2.62727585e+01 2.20188828e+01 1.82791843e+01 1.57881737e+01 1.32645521e+01 1.13012447e+01 9.30336952e+00 7.65946531e+00 6.60417032e+00 5.75654888e+00 5.24029636e+00 5.07486248e+00 5.24582624e+00 5.76289845e+00 6.61818457e+00 7.83791447e+00 9.27327919e+00 1.12150249e+01 1.38878918e+01 1.63037357e+01 1.87340069e+01 2.14599781e+01 2.52028179e+01 3.04605045e+01 3.47157135e+01 3.84246750e+01 4.25304718e+01 4.74030952e+01 5.39980774e+01 6.00349083e+01 6.79465256e+01 7.33545151e+01 7.77878189e+01 8.71019745e+01 9.49428177e+01 1.04822922e+02 1.11725479e+02 1.17296913e+02 1.27847153e+02 1.37102783e+02 1.48032059e+02 1.53951172e+02 1.66983398e+02 1.87959167e+02 1.93783051e+02 2.00252747e+02 2.06910187e+02 2.16641800e+02 2.41466202e+02 2.56898468e+02 2.62483673e+02 2.66832214e+02 2.80404053e+02 3.03850281e+02 3.17618896e+02 3.40390198e+02 3.53840729e+02 3.60998444e+02 3.66237854e+02 3.79208557e+02 4.20708344e+02 4.31789886e+02 4.35166077e+02 4.51952942e+02 4.67506836e+02 5.05607025e+02 5.26358643e+02 5.19310120e+02 5.33273071e+02 5.79520630e+02 6.04131714e+02 5.92526001e+02 6.08725586e+02 6.63008179e+02 6.85933777e+02 6.86405396e+02 6.92996826e+02 7.10738098e+02 7.74072144e+02 7.86260864e+02 7.81856079e+02 8.14638428e+02 8.35399170e+02 8.77039490e+02 9.02834412e+02 8.97387451e+02 9.01039490e+02 9.55497681e+02 1.03451562e+03 1.03008813e+03 1.03855737e+03 1.07557019e+03 1.09099475e+03 1.11956018e+03 1.14378113e+03 1.16442029e+03 1.16617224e+03 1.18616272e+03 1.23805774e+03 1.28403650e+03 1.35129529e+03 1.34014429e+03 1.31234619e+03 1.37747534e+03 1.43473206e+03 1.51005774e+03 1.50713855e+03 1.48825488e+03 1.51811292e+03 1.54812122e+03 1.60631165e+03 1.63034924e+03 1.70106323e+03 1.73046545e+03 1.71667957e+03 1.73056824e+03 1.71112744e+03 1.82047144e+03 1.96709119e+03 1.95396497e+03 1.92580188e+03 1.90314905e+03 1.90010022e+03 2.03021936e+03 2.16717798e+03 2.13642676e+03 2.07219727e+03 2.10280249e+03 2.19737549e+03 2.22989673e+03 2.32136255e+03 2.34787256e+03 2.32140137e+03 2.35418408e+03 2.38552441e+03 2.50999927e+03 2.55983008e+03 2.46022046e+03 2.48621655e+03 2.66544043e+03 2.68537183e+03 2.58606885e+03 2.67974658e+03 2.85933667e+03 2.86974707e+03 2.82728809e+03 2.79922021e+03 2.83333691e+03 3.04338135e+03 3.07579468e+03 3.03978906e+03 3.01088623e+03 3.01246826e+03 3.14114453e+03 3.21323535e+03 3.22146899e+03 3.18171753e+03 3.31319604e+03 3.46131396e+03 3.40798608e+03 3.50945679e+03 3.52661035e+03 3.48302222e+03 3.56757349e+03 3.62939844e+03 3.67792334e+03 3.68272095e+03 3.64736914e+03 3.63701587e+03 3.82899121e+03 4.10615674e+03 3.93491895e+03 3.78929565e+03 3.95492480e+03 4.09018579e+03 4.24657861e+03 4.17340625e+03 4.07569141e+03 4.31351367e+03 4.38602002e+03 4.19246387e+03 4.20768555e+03 4.50643311e+03 4.55846484e+03 4.45205029e+03 4.44377051e+03 4.32068750e+03 4.57434033e+03 4.94228125e+03 4.86186670e+03 4.74632373e+03 4.66046387e+03 4.63387939e+03 4.91829053e+03 5.27081934e+03 5.13787646e+03 4.92260156e+03 4.93312939e+03 5.13671533e+03 5.20836719e+03 5.38912402e+03 5.30312549e+03 5.20369287e+03 5.38247314e+03 5.41300488e+03 5.64104932e+03 5.64445312e+03 5.50376465e+03 5.56921191e+03 5.58856982e+03 5.77206543e+03 5.65036035e+03 5.63716846e+03 6.04469336e+03 6.06452197e+03 5.87914746e+03 5.78821436e+03 5.92737939e+03 6.29865918e+03 6.33728711e+03 6.20340869e+03 6.07852930e+03 6.09101025e+03 6.33331543e+03 6.35500342e+03 6.44512549e+03 6.32052783e+03 6.50626367e+03 6.82107715e+03 6.59925879e+03 6.82497070e+03 6.90145410e+03 6.78140967e+03 6.70290576e+03 6.69078809e+03 7.01260693e+03 7.06670703e+03 6.83179736e+03 6.84543018e+03 7.26951611e+03 7.38372998e+03 7.03580127e+03 6.89249707e+03 7.13278125e+03 7.45525732e+03 7.80244482e+03 7.51240576e+03 7.24150391e+03 7.58471143e+03 7.80685791e+03 7.70843555e+03 7.60517578e+03 7.62678271e+03 7.65998145e+03 7.71821924e+03 7.89149219e+03 7.69648926e+03 7.94517139e+03 8.37188086e+03 8.19481445e+03 8.18418018e+03 8.06786182e+03 8.00246045e+03 8.45146191e+03 8.49485938e+03 8.36899316e+03 8.22460059e+03 8.02065771e+03 8.23630273e+03 8.72636719e+03 9.06968164e+03 8.68004004e+03 8.39738477e+03 8.66345312e+03 8.78809180e+03 9.18645020e+03 9.13694922e+03 8.88041211e+03 8.88005469e+03 8.89785742e+03 8.94338477e+03 8.80944531e+03 9.11932617e+03 9.53459668e+03 9.31370508e+03 9.41203906e+03 9.28912012e+03 9.11726855e+03 9.73199219e+03 9.75498633e+03 9.50444336e+03 9.34488867e+03 9.28451172e+03 9.64054102e+03 9.67982715e+03 1.00001924e+04 1.01441748e+04 9.79504395e+03 9.64361133e+03 9.81871777e+03 1.03318252e+04 1.02010293e+04 1.00289541e+04 9.95119824e+03 9.96077637e+03 1.00892754e+04 1.00976865e+04 1.04098271e+04 1.04799697e+04 1.02314834e+04 1.05843838e+04 1.07283652e+04 1.05488359e+04 1.05474941e+04 1.06034023e+04 1.06380312e+04 1.04149492e+04 1.03148701e+04 1.09280645e+04 1.10822188e+04 1.05046992e+04 1.02480479e+04 1.08217441e+04 1.15614297e+04 1.13758281e+04 1.07603027e+04 1.06004043e+04 1.12708105e+04 1.13967656e+04 1.10824639e+04 1.13993477e+04 1.11026416e+04 1.06592949e+04 1.10122861e+04 1.16988662e+04 1.19627393e+04 1.13687061e+04 1.08907139e+04 1.15787480e+04 1.21300986e+04 1.17924326e+04 1.13275801e+04 1.11954795e+04 1.16008447e+04 1.16973301e+04 1.20457168e+04 1.20354492e+04 1.16890439e+04 1.17381367e+04 1.17703486e+04 1.22027881e+04 1.19534531e+04 1.16613779e+04 1.21552959e+04 1.21180859e+04 1.22378047e+04 1.20394375e+04 1.18800098e+04 1.25975215e+04 1.22749834e+04 1.18241094e+04 1.21502207e+04 1.23956924e+04 1.25135312e+04 1.23761523e+04 1.26611934e+04 1.28056230e+04 1.25173447e+04 1.22028975e+04 1.21385186e+04 1.28308496e+04 1.26322676e+04 1.23054512e+04 1.27018496e+04 1.26937979e+04 1.26830127e+04 1.26459990e+04 1.29910820e+04 1.29415029e+04 1.25918154e+04 1.30128828e+04 1.30992139e+04 12959. 1.30118398e+04 1.29847344e+04 1.28510195e+04 1.25269463e+04 1.23709131e+04 1.30248516e+04 1.38383662e+04 1.31415293e+04 1.23795889e+04 1.29631543e+04 1.38011299e+04 1.36857930e+04 1.30022822e+04 1.26622139e+04 1.34107607e+04 1.34866162e+04 1.30528906e+04 1.35696396e+04 1.35503115e+04 1.29061631e+04 1.28922227e+04 1.36024365e+04 1.39901592e+04 1.33690859e+04 1.28080762e+04 1.33135547e+04 1.41477754e+04 1.38886240e+04 1.32263535e+04 1.29114727e+04 1.35016514e+04 1.41562109e+04 1.37010391e+04 1.33371426e+04 1.34769463e+04 1.36234443e+04 1.35821348e+04 1.39798721e+04 1.37145654e+04 1.33037109e+04 1.36179746e+04 1.37080137e+04 1.40095469e+04 1.36992236e+04 1.33715508e+04 1.38636191e+04 1.34792080e+04 1.34741348e+04 1.40558867e+04 1.39234277e+04 1.38013613e+04 1.36562949e+04 1.41828770e+04 1.43865098e+04 1.38202578e+04 1.34307217e+04 1.35521875e+04 1.45590781e+04 1.44678223e+04 1.39607998e+04 1.31376367e+04 1.74192246e+04 3.28474805e+04 2.19040047e+05 -2.74779520e+09 0. 0. 0. 0. 0. -4.64683213e+10 2.00708188e+05 4.34830508e+04 4.87046953e+04 1.51165078e+05 4.54435308e+10 0. 0. 7.89500238e+12 7.89500238e+12 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.09421988e+10 3.06599281e+05 4.98376484e+04 2.40693105e+04 2.11386074e+04 1.41805547e+04 1.41947109e+04 1.43132441e+04 1.46165117e+04 1.39871777e+04 1.38066299e+04 1.39049639e+04 1.39113447e+04 1.35722891e+04 1.36168115e+04 1.38817568e+04 1.37654492e+04 1.37123877e+04 1.36115576e+04 1.34624023e+04 1.37701025e+04 1.37645078e+04 1.35421250e+04 1.35456318e+04 1.33979512e+04 1.34990508e+04 1.39633447e+04 1.39521475e+04 1.34997344e+04 1.33959971e+04 1.35617480e+04 1.35417695e+04 1.33918047e+04 1.33821992e+04 1.34818076e+04 1.34240166e+04 1.36219707e+04 1.35718301e+04 1.30532979e+04 1.32119609e+04 1.36530166e+04 1.37212812e+04 1.36142480e+04 1.30827734e+04 1.29333496e+04 1.33619326e+04 1.34289883e+04 1.32343809e+04 1.30856826e+04 1.30721045e+04 1.33028086e+04 1.34586074e+04 1.32763125e+04 1.28414072e+04 1.28022588e+04 1.34546719e+04 1.34516533e+04 1.27031543e+04 1.27060898e+04 1.30487168e+04 1.31758428e+04 1.32856504e+04 1.29964277e+04 1.25375732e+04 1.26561943e+04 1.29693008e+04 1.30184854e+04 1.28125010e+04 1.25626357e+04 1.27911846e+04 1.29730186e+04 1.27488945e+04 1.25753320e+04 1.24828896e+04 1.25618662e+04 1.27350020e+04 1.26597832e+04 1.27331143e+04 1.25550439e+04 1.21956055e+04 1.23587354e+04 1.25357510e+04 1.24275225e+04 1.24019932e+04 1.22530576e+04 1.22584775e+04 1.25560283e+04 1.24388467e+04 1.19822920e+04 1.19881387e+04 1.22207783e+04 1.22929365e+04 1.21788799e+04 1.19614795e+04 1.19201934e+04 1.20114229e+04 1.21406562e+04 1.19731816e+04 1.16568467e+04 1.17768398e+04 1.20634736e+04 1.20103145e+04 1.18764287e+04 1.15670176e+04 1.14852275e+04 1.17930498e+04 1.17335088e+04 1.14336709e+04 1.13829512e+04 1.14169756e+04 1.16214639e+04 1.15842686e+04 1.14000566e+04 1.13818320e+04 1.13014902e+04 1.13939131e+04 1.13946523e+04 1.11655068e+04 1.11619102e+04 1.11341006e+04 1.10179590e+04 1.11132373e+04 1.11077207e+04 1.10270781e+04 1.10432363e+04 1.08873486e+04 1.07744258e+04 1.08806855e+04 1.09214160e+04 1.08055449e+04 1.06802568e+04 1.05422510e+04 1.05260996e+04 1.06456104e+04 1.05426162e+04 1.03932607e+04 1.04452158e+04 1.06513730e+04 1.06189707e+04 1.02485752e+04 1.02820693e+04 1.03118838e+04 1.01780615e+04 1.00911113e+04 9.98051172e+03 1.00065801e+04 1.00991211e+04 1.02274912e+04 1.01279805e+04 9.81239648e+03 9.65215430e+03 9.72826758e+03 9.91956543e+03 9.82642578e+03 9.70713379e+03 9.55103125e+03 9.64390234e+03 9.72825586e+03 9.60755859e+03 9.40650195e+03 9.23459277e+03 9.30216309e+03 9.59616309e+03 9.39068164e+03 8.94434180e+03 9.02763867e+03 9.27854297e+03 9.15616992e+03 8.97513086e+03 9.00813379e+03 8.95280566e+03 8.85250586e+03 8.97693652e+03 8.78720605e+03 8.63538184e+03 8.79624219e+03 8.84220996e+03 8.64030762e+03 8.58367090e+03 8.58456934e+03 8.33739648e+03 8.46004199e+03 8.39818945e+03 8.36926172e+03 8.48346973e+03 8.06032227e+03 8.07418994e+03 8.35890332e+03 8.13937500e+03 7.91325879e+03 7.97627930e+03 8.02608301e+03 7.95552979e+03 7.91860059e+03 7.84481641e+03 7.63801172e+03 7.61058887e+03 7.81125732e+03 7.84147266e+03 7.45999414e+03 7.50205371e+03 7.65712744e+03 7.48479346e+03 7.39568799e+03 7.27174707e+03 7.17648145e+03 7.32581836e+03 7.25773047e+03 7.15626709e+03 7.11153320e+03 6.97895850e+03 6.99664014e+03 7.11284619e+03 6.90432422e+03 6.84242480e+03 6.83140820e+03 6.76145752e+03 6.75274365e+03 6.71193506e+03 6.58827588e+03 6.53894971e+03 6.51622607e+03 6.50738330e+03 6.46666455e+03 6.32106152e+03 6.39003613e+03 6.38553857e+03 6.27630615e+03 6.32341895e+03 6.15296240e+03 5.94045898e+03 6.05537695e+03 6.05235059e+03 5.95933398e+03 5.83403857e+03 5.76139746e+03 5.82245166e+03 5.87068359e+03 5.76729834e+03 5.63769385e+03 5.67776025e+03 5.66821289e+03 5.48572510e+03 5.39233008e+03 5.50265283e+03 5.42888477e+03 5.26799902e+03 5.40277930e+03 5.29256982e+03 5.13441895e+03 5.18090381e+03 5.07676025e+03 5.00453418e+03 5.02351221e+03 4.94960498e+03 4.86677197e+03 4.89590039e+03 4.88271094e+03 4.87181152e+03 4.68722412e+03 4.59457324e+03 4.69361279e+03 4.60003369e+03 4.57498340e+03 4.52124902e+03 4.43524707e+03 4.41304883e+03 4.37886768e+03 4.40474902e+03 4.27671436e+03 4.13437598e+03 4.21157324e+03 4.28680127e+03 4.07931470e+03 3.96233398e+03 3.97649341e+03 3.93112866e+03 3.96902466e+03 3.94891602e+03 3.82083691e+03 3.75518457e+03 3.77840820e+03 3.73284717e+03 3.71337817e+03 3.64034570e+03 3.62111646e+03 3.59973950e+03 3.41837109e+03 3.42105054e+03 3.43683398e+03 3.35040796e+03 3.37381787e+03 3.30494067e+03 3.21791406e+03 3.23935156e+03 3.15734277e+03 3.11015869e+03 3.17670728e+03 3.09466504e+03 2.98924194e+03 2.93780933e+03 2.86612476e+03 2.89629175e+03 2.90594800e+03 2.81189111e+03 2.75085840e+03 2.76693848e+03 2.74078101e+03 2.68925977e+03 2.60568262e+03 2.55687109e+03 2.53307104e+03 2.53674951e+03 2.51243481e+03 2.40044165e+03 2.36742480e+03 2.37441748e+03 2.35141675e+03 2.31103003e+03 2.27663696e+03 2.21510425e+03 2.16275610e+03 2.20135449e+03 2.18064233e+03 2.06541919e+03 2.00720581e+03 1.98494824e+03 1.98263220e+03 1.95305310e+03 1.89538025e+03 1.88231641e+03 1.86521826e+03 1.82252747e+03 1.80399121e+03 1.75402893e+03 1.70818335e+03 1.69930383e+03 1.68234241e+03 1.61674121e+03 1.56471851e+03 1.55914014e+03 1.52726697e+03 1.49643176e+03 1.48556897e+03 1.44554211e+03 1.39614392e+03 1.38077563e+03 1.38596692e+03 1.33724890e+03 1.28217041e+03 1.26992371e+03 1.25152527e+03 1.21969006e+03 1.18692163e+03 1.14908875e+03 1.12729834e+03 1.10911414e+03 1.09794592e+03 1.07902319e+03 1.03272180e+03 1.00909705e+03 9.81913818e+02 9.49335754e+02 9.29182678e+02 8.98887573e+02 8.85395569e+02 8.66023560e+02 8.32802307e+02 8.04685852e+02 7.84903687e+02 7.79370667e+02 7.63487671e+02 7.40605408e+02 7.09229431e+02 6.80776123e+02 6.61162598e+02 6.35718018e+02 6.22331543e+02 6.11547546e+02 5.88938538e+02 5.66383728e+02 5.39060242e+02 5.20209595e+02 5.16226135e+02 5.03429413e+02 4.86828064e+02 4.56695618e+02 4.31313721e+02 4.23256012e+02 4.09003204e+02 3.90657837e+02 3.76017212e+02 3.63764496e+02 3.44636047e+02 3.26553986e+02 3.12198303e+02 2.97291168e+02 2.92441986e+02 2.82290161e+02 2.61508545e+02 2.51051636e+02 2.36236938e+02 2.19443939e+02 2.14460007e+02 2.03919693e+02 1.87175156e+02 1.77203354e+02 1.67094513e+02 1.55056549e+02 1.48810806e+02 1.42436630e+02 1.29131393e+02 1.18661858e+02 1.11848671e+02 1.03652222e+02 9.60706024e+01 8.78027573e+01 8.02428207e+01 7.40373764e+01 6.83616638e+01 6.25669060e+01 5.59966278e+01 4.96200142e+01 4.47535629e+01 4.02400398e+01 3.52747192e+01 3.08221455e+01 2.71914558e+01 2.42091427e+01 2.11305542e+01 1.80684032e+01 1.51609001e+01 1.28719120e+01 1.12140026e+01 9.74217987e+00 8.57246304e+00 7.71352673e+00 7.22907257e+00 7.07441092e+00 7.23581314e+00 7.74326420e+00 8.69012356e+00 9.93263531e+00 1.13986120e+01 1.33613596e+01 1.54188976e+01 1.76133003e+01 2.08415165e+01 2.44541359e+01 2.73298244e+01 3.09221878e+01 3.54774628e+01 4.00869370e+01 4.53556290e+01 5.10764427e+01 5.63408890e+01 6.13043747e+01 6.74818497e+01 7.45886307e+01 8.15873795e+01 9.01289368e+01 9.81902466e+01 1.04295357e+02 1.11382408e+02 1.22295052e+02 1.30832397e+02 1.38820648e+02 1.50711060e+02 1.60716721e+02 1.67857498e+02 1.75248413e+02 1.86757172e+02 2.00865082e+02 2.16896240e+02 2.28815125e+02 2.34905228e+02 2.45731094e+02 2.60320251e+02 2.75329895e+02 2.93129272e+02 3.04892242e+02 3.12052979e+02 3.33791229e+02 3.50902222e+02 3.58420715e+02 3.83206146e+02 3.98401764e+02 4.04155243e+02 4.23668060e+02 4.35616943e+02 4.49233856e+02 4.83309601e+02 5.02170624e+02 5.11322601e+02 5.35422363e+02 5.47868408e+02 5.50929688e+02 5.75961060e+02 6.08994141e+02 6.28653687e+02 6.49573242e+02 6.63084473e+02 6.79430725e+02 7.08840698e+02 7.34858215e+02 7.78981995e+02 7.86128357e+02 7.72720886e+02 8.03490845e+02 8.37605591e+02 8.68573120e+02 9.06827209e+02 9.12186218e+02 9.12823547e+02 9.56963806e+02 9.97024170e+02 1.01404370e+03 1.04110022e+03 1.06104932e+03 1.06974670e+03 1.11478491e+03 1.14586914e+03 1.14655420e+03 1.21275073e+03 1.25105396e+03 1.24881287e+03 1.26862793e+03 1.26093848e+03 1.29483606e+03 1.36885278e+03 1.43771692e+03 1.45124084e+03 1.40671069e+03 1.44097742e+03 1.52524963e+03 1.54512000e+03 1.56360022e+03 1.59674268e+03 1.61471704e+03 1.65563306e+03 1.69790771e+03 1.73177393e+03 1.75609521e+03 1.78983215e+03 1.84700134e+03 1.85057825e+03 1.86132080e+03 1.89546875e+03 1.93326550e+03 1.99568884e+03 2.07837988e+03 2.07006738e+03 2.03599500e+03 2.10296436e+03 2.16737012e+03 2.25574072e+03 2.27504321e+03 2.21832568e+03 2.27697827e+03 2.33450732e+03 2.39504492e+03 2.47079810e+03 2.46081738e+03 2.47446924e+03 2.50457764e+03 2.51480396e+03 2.55851953e+03 2.65574194e+03 2.73686401e+03 2.71026270e+03 2.71886328e+03 2.72878638e+03 2.78018213e+03 2.91243848e+03 2.96281885e+03 2.96592847e+03 2.97769360e+03 2.95266577e+03 3.02033618e+03 3.09666724e+03 3.19918799e+03 3.26270654e+03 3.16939941e+03 3.18557568e+03 3.29167236e+03 3.35906714e+03 3.39651147e+03 3.46763135e+03 3.52517798e+03 3.47271460e+03 3.52890894e+03 3.58363184e+03 3.62563525e+03 3.69149365e+03 3.74792627e+03 3.78680469e+03 3.79042969e+03 3.80253101e+03 3.89031348e+03 4.03232983e+03 4.03109082e+03 3.98268774e+03 4.03219043e+03 4.08944580e+03 4.11620654e+03 4.31008105e+03 4.33841162e+03 4.20394287e+03 4.35299854e+03 4.33700879e+03 4.45606396e+03 4.62414062e+03 4.53870557e+03 4.52844434e+03 4.59671924e+03 4.70317041e+03 4.76756885e+03 4.90277051e+03 4.80533496e+03 6.13233057e+03 6.39933496e+03 1.24922441e+04 2.27030137e+04 4.65230450e+06 -93729688. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 62249224. 4.02128425e+06 -21384962. 4.01282575e+06 -4.18297498e+09 1.15398711e+04 1.29863379e+04 8.36082520e+03 7.52433398e+03 7.44070020e+03 7.80001172e+03 7.69488721e+03 7.57338184e+03 7.42121582e+03 7.51882129e+03 7.78594775e+03 7.97151953e+03 7.92458057e+03 7.78047119e+03 7.81234180e+03 7.89399414e+03 8.11882178e+03 8.12449512e+03 7.86649219e+03 7.99412549e+03 8.27250781e+03 8.29218945e+03 8.13476904e+03 8.01827295e+03 8.34963477e+03 8.77883594e+03 8.79165137e+03 8.38317285e+03 8.05044922e+03 8.36827441e+03 8.82520703e+03 9.05421191e+03 8.91562012e+03 8.58770215e+03 8.69367188e+03 8.92059375e+03 9.18289355e+03 9.08351270e+03 8.68118359e+03 8.88846680e+03 9.42567871e+03 9.27693750e+03 9.05659180e+03 9.19218359e+03 9.25684375e+03 9.49599121e+03 9.52147656e+03 9.20450293e+03 9.10757422e+03 9.60769238e+03 9.87353711e+03 9.81151562e+03 9.51156934e+03 9.32390332e+03 9.82386230e+03 1.01923232e+04 9.97032324e+03 9.72663184e+03 9.40175781e+03 9.63842676e+03 1.01896729e+04 1.03870947e+04 1.02841211e+04 1.01830879e+04 1.01916074e+04 1.00454512e+04 1.02297148e+04 1.03729541e+04 1.00819609e+04 1.02393232e+04 1.06898994e+04 1.05622344e+04 1.01503320e+04 1.01307461e+04 1.06931377e+04 1.10662686e+04 1.09498965e+04 1.06299502e+04 1.03680605e+04 1.04706611e+04 1.07976104e+04 1.13268359e+04 1.11807842e+04 1.06138662e+04 1.07953730e+04 1.09880293e+04 1.11178027e+04 1.13853408e+04 1.10742676e+04 1.10255977e+04 1.13642783e+04 1.13933691e+04 1.12376758e+04 1.11388906e+04 1.13235449e+04 1.16113604e+04 1.15739238e+04 1.13113047e+04 1.11539062e+04 1.15540869e+04 1.19453281e+04 1.18689268e+04 1.16679697e+04 1.13992080e+04 1.16161719e+04 1.19951641e+04 1.20232861e+04 1.18443750e+04 1.14339736e+04 1.15339443e+04 1.21128906e+04 1.24586230e+04 1.22483994e+04 1.17046230e+04 1.18327256e+04 1.22697520e+04 1.22238330e+04 1.19852676e+04 1.18633145e+04 1.23648379e+04 1.25849375e+04 1.22707109e+04 1.21764004e+04 1.20107041e+04 1.23985850e+04 1.29364707e+04 1.26969395e+04 1.24004033e+04 1.22133076e+04 1.23288242e+04 1.25877744e+04 1.28633428e+04 1.27655566e+04 1.22797842e+04 1.23337383e+04 1.28944941e+04 1.31026670e+04 1.28222383e+04 1.25328291e+04 1.27122773e+04 1.30498838e+04 1.30740840e+04 1.28685986e+04 1.24538750e+04 1.26536855e+04 1.32095850e+04 1.32055742e+04 1.30113906e+04 1.27208848e+04 1.28163721e+04 1.31848691e+04 1.35293027e+04 1.33908945e+04 1.28318047e+04 1.29465283e+04 1.32120723e+04 1.32661904e+04 1.33348018e+04 1.31081953e+04 1.32233164e+04 1.33111904e+04 1.32030273e+04 1.31732969e+04 1.31416348e+04 1.35161387e+04 1.37318232e+04 1.35454033e+04 1.31612793e+04 1.29619893e+04 1.34616143e+04 1.39866602e+04 1.38353145e+04 1.34951201e+04 1.31252998e+04 1.29690791e+04 1.34890781e+04 1.41510273e+04 1.37719043e+04 1.30850596e+04 1.32955547e+04 1.37706367e+04 1.39008193e+04 1.38400312e+04 1.35337832e+04 1.35701201e+04 1.37682861e+04 1.35666104e+04 1.34528574e+04 1.35801865e+04 1.38147246e+04 1.38360078e+04 1.37165137e+04 1.36395996e+04 1.35447715e+04 1.37767402e+04 14089. 1.40591699e+04 1.35363242e+04 1.32499473e+04 1.38376240e+04 1.41676602e+04 1.40129932e+04 1.37773965e+04 1.33475830e+04 1.34040859e+04 1.40623096e+04 1.44235205e+04 1.41577920e+04 1.35260225e+04 1.34221221e+04 1.38864512e+04 1.40826816e+04 1.39992930e+04 1.38858057e+04 1.39744219e+04 1.39022422e+04 1.36799639e+04 1.34094209e+04 1.33397803e+04 1.36983916e+04 1.39809531e+04 1.43749521e+04 1.41291377e+04 1.34001279e+04 1.36223125e+04 1.38704023e+04 1.38124141e+04 1.39569775e+04 1.38272256e+04 1.41467266e+04 1.41038242e+04 1.33852314e+04 1.32001465e+04 1.35380596e+04 1.41537520e+04 1.45821553e+04 1.42416221e+04 1.34127490e+04 1.30219678e+04 1.34036875e+04 1.41040117e+04 1.44986641e+04 1.41813389e+04 1.33842705e+04 1.33110244e+04 1.41509443e+04 1.41730264e+04 1.34399189e+04 1.33640752e+04 1.36166543e+04 1.36542314e+04 1.40657168e+04 1.37168086e+04 1.32307324e+04 1.36023711e+04 1.32857051e+04 1.35651318e+04 1.39767598e+04 1.32445811e+04 1.35398350e+04 1.39383174e+04 1.35583271e+04 1.35443164e+04 1.34959590e+04 1.35301855e+04 1.35851924e+04 1.35064307e+04 1.31407344e+04 1.30894170e+04 1.36460879e+04 1.40570771e+04 1.37594414e+04 1.30997773e+04 1.27813750e+04 1.29971533e+04 1.36003545e+04 1.39895537e+04 1.37102754e+04 1.28798271e+04 1.28751279e+04 1.34284746e+04 1.32992031e+04 1.30967080e+04 1.30720078e+04 1.30974902e+04 1.30841533e+04 1.34970039e+04 1.31558535e+04 1.27040576e+04 1.29912852e+04 1.26784854e+04 1.30534688e+04 1.32603057e+04 1.29455166e+04 1.33243125e+04 1.28902725e+04 1.24804834e+04 1.27994336e+04 1.24871787e+04 1.27086992e+04 1.35534688e+04 1.28277334e+04 1.20888379e+04 1.23452998e+04 1.28704121e+04 1.33367422e+04 1.30359492e+04 1.22773760e+04 1.18530869e+04 1.21460664e+04 1.28094248e+04 1.31698291e+04 1.28336758e+04 1.21028350e+04 1.19728652e+04 1.23960703e+04 1.25654258e+04 1.22294844e+04 1.20387607e+04 1.21849551e+04 1.22134863e+04 1.25341387e+04 1.24646807e+04 1.18505293e+04 1.18263076e+04 1.19092412e+04 1.19342500e+04 1.20399521e+04 1.19815225e+04 1.22041270e+04 1.19332236e+04 1.15029658e+04 1.17148398e+04 1.14179062e+04 1.17057080e+04 1.24254688e+04 1.17173701e+04 1.09842969e+04 1.11692041e+04 1.17040420e+04 1.20424355e+04 1.19752021e+04 1.13110996e+04 1.08171992e+04 1.10006338e+04 1.15533057e+04 1.19799297e+04 1.15795820e+04 1.09373115e+04 1.07879434e+04 1.10591602e+04 1.12080811e+04 1.14756494e+04 1.13630176e+04 1.06941885e+04 1.06233145e+04 1.11386064e+04 1.11705303e+04 1.07320625e+04 1.06702646e+04 1.06472549e+04 1.05567500e+04 1.09675596e+04 1.09853936e+04 1.04027188e+04 1.02981084e+04 1.03705146e+04 1.04315029e+04 1.04514932e+04 1.02947549e+04 1.05166602e+04 1.06034961e+04 1.02375586e+04 9.97095312e+03 9.75671387e+03 1.00736738e+04 1.06027119e+04 1.03632568e+04 9.78262793e+03 9.45858496e+03 9.83996875e+03 1.03372793e+04 9.91802637e+03 9.33798926e+03 9.42404980e+03 9.67577441e+03 9.89169922e+03 1.01121113e+04 9.85140234e+03 9.26013477e+03 9.06225391e+03 9.30370898e+03 9.56911914e+03 9.55795703e+03 9.33056836e+03 9.17139551e+03 9.15799512e+03 9.32817969e+03 9.19548047e+03 8.87203516e+03 8.77997559e+03 8.71857031e+03 9.08885645e+03 9.14753809e+03 8.79654980e+03 8.77578711e+03 8.79196973e+03 8.92022168e+03 8.64986133e+03 8.16033887e+03 8.52616113e+03 8.93259961e+03 8.65704590e+03 8.16742480e+03 8.19968359e+03 8.54027148e+03 8.50922559e+03 8.27357129e+03 8.20476367e+03 7.93667334e+03 7.84747021e+03 8.21886621e+03 8.21204883e+03 7.75698242e+03 7.55606104e+03 7.52778076e+03 7.88869385e+03 8.15797900e+03 7.76485986e+03 7.44941162e+03 7.59424268e+03 7.55575439e+03 7.75933838e+03 7.62768896e+03 7.14215137e+03 7.20693408e+03 7.37404199e+03 7.24642236e+03 7.23748096e+03 7.11239697e+03 7.21742285e+03 7.18859473e+03 6.90381055e+03 6.88850879e+03 6.77906641e+03 6.88226855e+03 7.10858691e+03 6.93874609e+03 6.57366992e+03 6.53119287e+03 6.73960693e+03 6.93741650e+03 7.21390332e+03 7.26434814e+03 6.50499902e+03 7.74461621e+03 1.38378701e+04 1.06380695e+05 45702096. 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. 0. 0. 0. 0. 0. 0. 0. -103585272. -8899590. -2.22294725e+06 -7057037. 1.23589736e+04 7.14957910e+03 5.94837988e+03 4.64470654e+03 4.46778564e+03 4.31732227e+03 4.05940698e+03 4.15614990e+03 4.15885693e+03 3.98857373e+03 3.94972998e+03 3.89840820e+03 3.84567456e+03 3.81828247e+03 3.75135547e+03 3.67836719e+03 3.64101074e+03 3.59654614e+03 3.62655298e+03 3.59894580e+03 3.41777930e+03 3.37764746e+03 3.49971582e+03 3.47470825e+03 3.34715381e+03 3.30733350e+03 3.25479663e+03 3.22562280e+03 3.16999927e+03 3.12659570e+03 3.08915479e+03 3.04856372e+03 2.98181177e+03 2.93742871e+03 2.97377368e+03 2.94715015e+03 2.86189893e+03 2.82121655e+03 2.78993359e+03 2.74792847e+03 2.70087549e+03 2.65882935e+03 2.62845654e+03 2.51535107e+03 2.47502637e+03 2.49624194e+03 2.46093408e+03 2.51458252e+03 2.48870728e+03 2.36513354e+03 2.25952856e+03 2.21615186e+03 2.33017456e+03 2.31228442e+03 2.18702002e+03 2.11322119e+03 2.08099316e+03 2.06918579e+03 2.02768726e+03 2.06584448e+03 2.03567664e+03 1.88397729e+03 1.82929431e+03 1.89651794e+03 1.94093750e+03 1.85276160e+03 1.77869287e+03 1.75836792e+03 1.71938147e+03 1.66811365e+03 1.64639441e+03 1.61129260e+03 1.57148804e+03 1.54918066e+03 1.51714197e+03 1.50704565e+03 1.47108179e+03 1.47033191e+03 1.44138794e+03 1.37216699e+03 1.35868774e+03 1.33543762e+03 1.30920569e+03 1.28709363e+03 1.24853271e+03 1.21744592e+03 1.16415381e+03 1.11495923e+03 1.14074170e+03 1.12964941e+03 1.04606006e+03 1.02948755e+03 1.06250891e+03 1.06303162e+03 1.00586969e+03 9.55323120e+02 9.26336548e+02 9.02056580e+02 8.71683777e+02 8.45906982e+02 8.39879395e+02 8.13573181e+02 8.09599060e+02 7.83973694e+02 7.42190125e+02 7.32662598e+02 6.93394104e+02 6.74264771e+02 6.87025513e+02 6.58747070e+02 6.24426880e+02 5.92022095e+02 5.63026489e+02 5.74897583e+02 5.67205994e+02 5.29761780e+02 4.96497772e+02 4.80779480e+02 4.74944946e+02 4.56333649e+02 4.53114227e+02 4.38427124e+02 4.08367615e+02 3.84909760e+02 3.69176849e+02 3.68314484e+02 3.53451233e+02 3.30782623e+02 3.12721191e+02 2.99426819e+02 2.90045044e+02 2.69212280e+02 2.57389984e+02 2.58558685e+02 2.43046600e+02 2.24431335e+02 2.07051605e+02 1.94605576e+02 1.94720108e+02 1.84208618e+02 1.68364838e+02 1.54436966e+02 1.43949051e+02 1.38370178e+02 1.29176285e+02 1.20179329e+02 1.08918869e+02 1.02983627e+02 1.00078941e+02 9.03760910e+01 8.23080673e+01 7.55278015e+01 6.81034622e+01 6.12584267e+01 5.55966911e+01 5.07819519e+01 4.54278603e+01 4.01845741e+01 3.46451530e+01 3.08288097e+01 2.82776394e+01 2.38929272e+01 2.02177658e+01 1.77224998e+01 1.51917200e+01 1.32425022e+01 1.12720070e+01 9.64471722e+00 8.59175396e+00 7.75445557e+00 7.23998594e+00 7.07411242e+00 7.25231838e+00 7.75119066e+00 8.56141090e+00 9.72916317e+00 1.11623955e+01 1.31730919e+01 1.58718719e+01 1.83127575e+01 2.06557217e+01 2.32651997e+01 2.68898964e+01 3.21965599e+01 3.65568924e+01 4.02417374e+01 4.41593285e+01 4.90415344e+01 5.59194794e+01 6.17010574e+01 6.93629456e+01 7.47793350e+01 7.92580566e+01 8.88475418e+01 9.65774841e+01 1.06359344e+02 1.14141655e+02 1.19610817e+02 1.28397903e+02 1.37451691e+02 1.48534607e+02 1.54627411e+02 1.66593628e+02 1.86507935e+02 1.94640579e+02 2.01391388e+02 2.07749741e+02 2.18151398e+02 2.42716476e+02 2.56724396e+02 2.62516357e+02 2.68307190e+02 2.81325073e+02 3.04229034e+02 3.18503967e+02 3.40586182e+02 3.51925140e+02 3.58792816e+02 3.70418854e+02 3.83590271e+02 4.19958191e+02 4.34265259e+02 4.37476746e+02 4.52586700e+02 4.69351349e+02 5.00664459e+02 5.20736023e+02 5.18022461e+02 5.34244934e+02 5.81625732e+02 6.00898804e+02 5.90729370e+02 6.06788147e+02 6.61686584e+02 6.84891418e+02 6.83158020e+02 6.88408813e+02 7.08691772e+02 7.73194214e+02 7.88803223e+02 7.86533325e+02 8.15300598e+02 8.33707397e+02 8.55308228e+02 8.78969604e+02 9.03104187e+02 9.05669800e+02 9.52519348e+02 1.03026636e+03 1.02364130e+03 1.03469250e+03 1.06945715e+03 1.08705176e+03 1.11350891e+03 1.13901428e+03 1.16244434e+03 1.16131152e+03 1.16948608e+03 1.22608301e+03 1.28771118e+03 1.35727588e+03 1.33539502e+03 1.31524500e+03 1.37856604e+03 1.42404980e+03 1.49585339e+03 1.50546631e+03 1.49006006e+03 1.51020923e+03 1.53427820e+03 1.59729968e+03 1.62562427e+03 1.69620715e+03 1.72190796e+03 1.70777747e+03 1.72102148e+03 1.70633789e+03 1.81402466e+03 1.95402698e+03 1.94664429e+03 1.92227197e+03 1.90138672e+03 1.91135913e+03 2.04194275e+03 2.13941919e+03 2.10804272e+03 2.06285669e+03 2.09748218e+03 2.19726099e+03 2.21979980e+03 2.31508008e+03 2.34225122e+03 2.30878784e+03 2.35267627e+03 2.38505640e+03 2.47700977e+03 2.52444214e+03 2.44999756e+03 2.48523193e+03 2.66241187e+03 2.65107251e+03 2.55264429e+03 2.67457666e+03 2.86496460e+03 2.86182471e+03 2.81239380e+03 2.79013086e+03 2.83155981e+03 3.03543530e+03 3.06908447e+03 3.00610010e+03 2.98888306e+03 3.00450806e+03 3.13207227e+03 3.17417090e+03 3.21472510e+03 3.18408813e+03 3.29286938e+03 3.47493530e+03 3.43015601e+03 3.47686377e+03 3.49542261e+03 3.47274463e+03 3.54504517e+03 3.60062402e+03 3.64388086e+03 3.67570117e+03 3.67254028e+03 3.64252490e+03 3.77087451e+03 4.03314282e+03 3.91509546e+03 3.78860400e+03 3.95246240e+03 4.05661035e+03 4.22625244e+03 4.20865869e+03 4.10880566e+03 4.25464404e+03 4.30063428e+03 4.16668457e+03 4.19141309e+03 4.50307031e+03 4.53397168e+03 4.44344189e+03 4.43155859e+03 4.33455029e+03 4.57229541e+03 4.91525586e+03 4.80164209e+03 4.73665527e+03 4.64664014e+03 4.67094482e+03 4.93963574e+03 5.15819287e+03 5.07368359e+03 4.87336768e+03 4.88022314e+03 5.07276562e+03 5.20166553e+03 5.38980078e+03 5.33879492e+03 5.20975000e+03 5.37001416e+03 5.38445410e+03 5.55145557e+03 5.55831641e+03 5.47135352e+03 5.59132666e+03 5.61471045e+03 5.66495410e+03 5.52197607e+03 5.65562012e+03 6.08997266e+03 6.00726025e+03 5.83338965e+03 5.76907812e+03 5.88420703e+03 6.25934863e+03 6.30267236e+03 6.17409619e+03 6.05693604e+03 6.07471826e+03 6.29045117e+03 6.32454492e+03 6.41176611e+03 6.28898438e+03 6.46666455e+03 6.81938574e+03 6.64184717e+03 6.74692773e+03 6.80983154e+03 6.68839600e+03 6.74286621e+03 6.79438770e+03 6.84851367e+03 6.88556982e+03 6.96556787e+03 6.97802539e+03 7.18078125e+03 7.27365186e+03 6.98515137e+03 6.90844678e+03 7.14101514e+03 7.39064941e+03 7.63472314e+03 7.47933984e+03 7.20868799e+03 7.55515430e+03 7.79146436e+03 7.66276953e+03 7.52593896e+03 7.55883984e+03 7.71643359e+03 7.82767139e+03 7.81658643e+03 7.64560449e+03 7.92620850e+03 8.37293457e+03 8.21348340e+03 8.11409717e+03 7.94888135e+03 7.97541309e+03 8.46716504e+03 8.51525781e+03 8.33266309e+03 8.17249805e+03 8.03192725e+03 8.29473438e+03 8.64900391e+03 8.93904199e+03 8.64199414e+03 8.29446777e+03 8.59133008e+03 8.77063281e+03 9.08501562e+03 8.96389258e+03 8.68632129e+03 8.99631348e+03 9.02437891e+03 8.86487598e+03 8.68443066e+03 9.06725781e+03 9.59405176e+03 9.38002441e+03 9.28040820e+03 9.08645020e+03 9.08802344e+03 9.66292090e+03 9.70731641e+03 9.47872461e+03 9.27720996e+03 9.23225000e+03 9.59257324e+03 9.63272559e+03 9.95569824e+03 1.00566455e+04 9.69858008e+03 9.58543262e+03 9.73611621e+03 1.02355830e+04 1.00540342e+04 9.84050781e+03 1.00551279e+04 1.01231650e+04 9.97889160e+03 9.89325098e+03 1.03688838e+04 1.03868604e+04 1.01253193e+04 1.05750234e+04 1.06925264e+04 1.04952500e+04 1.04832549e+04 1.05052539e+04 1.05852529e+04 1.03751289e+04 1.02663320e+04 1.08493623e+04 1.10190322e+04 1.05112754e+04 1.02020723e+04 1.07599795e+04 1.14743457e+04 1.13019424e+04 1.07661191e+04 1.05951572e+04 1.11930703e+04 1.14091025e+04 1.11395273e+04 1.12565928e+04 1.09651475e+04 1.06861143e+04 1.11649453e+04 1.16773076e+04 1.16944805e+04 1.12566504e+04 1.09728906e+04 1.15877363e+04 1.19732236e+04 1.16543486e+04 1.12487158e+04 1.11532764e+04 1.15209912e+04 1.16577119e+04 1.19855439e+04 1.19977354e+04 1.15647178e+04 1.17576172e+04 1.18794951e+04 1.21109932e+04 1.17674570e+04 1.15650703e+04 1.21273184e+04 1.21626475e+04 1.20395938e+04 1.17844688e+04 1.19365430e+04 1.26687246e+04 1.21878398e+04 1.17281602e+04 1.20934072e+04 1.23786309e+04 1.24179824e+04 1.23109180e+04 1.26337920e+04 1.27623965e+04 1.24333711e+04 1.21015840e+04 1.20790967e+04 1.27889082e+04 1.25937266e+04 1.22387422e+04 1.27289092e+04 1.27562959e+04 1.25220947e+04 1.24406025e+04 1.29052988e+04 1.28679941e+04 1.25279043e+04 1.28500156e+04 1.28791064e+04 1.29828184e+04 1.30398467e+04 1.29308643e+04 1.28035264e+04 1.24743115e+04 1.24579209e+04 1.31428174e+04 1.36312910e+04 1.29439170e+04 1.23558418e+04 1.29037773e+04 1.36500303e+04 1.36013467e+04 1.29872139e+04 1.25284746e+04 1.31804541e+04 1.36008164e+04 1.32351416e+04 1.34462197e+04 1.33885293e+04 1.29393281e+04 1.30380068e+04 1.35681953e+04 1.36902793e+04 1.31490430e+04 1.28027246e+04 1.33826543e+04 1.39958691e+04 1.36591982e+04 1.31078691e+04 1.29045322e+04 1.35713945e+04 1.40061777e+04 1.35360791e+04 1.32417441e+04 1.33283398e+04 1.35742490e+04 1.35485361e+04 1.39121328e+04 1.36326377e+04 1.32084463e+04 1.36871689e+04 1.37499873e+04 1.38440430e+04 1.35493477e+04 1.33219570e+04 1.38702607e+04 1.35425674e+04 1.33617227e+04 1.37858467e+04 1.37752773e+04 1.37707041e+04 1.37353018e+04 1.41265146e+04 1.42230068e+04 1.37728135e+04 1.33983369e+04 1.33982959e+04 1.42875830e+04 1.43872852e+04 1.38028467e+04 1.22502598e+04 1.33704189e+04 2.20832793e+04 1.17673492e+05 2.74640850e+06 0. 0. 0. 0. 0. -4.64683213e+10 2.00708188e+05 4.62339883e+04 3.32044062e+04 5.77052578e+04 4.24488047e+04 1.65340938e+05 -7.86057462e+11 7.89500238e+12 7.89500238e+12 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.09421988e+10 3.06599281e+05 7.21443047e+04 3.75423164e+04 3.79713008e+04 1.65305000e+04 1.21479414e+04 1.50239990e+04 1.44130518e+04 1.39893262e+04 1.38539824e+04 1.38454834e+04 1.38661914e+04 1.35433184e+04 1.35550654e+04 1.38228828e+04 1.37127832e+04 1.36722559e+04 1.35740254e+04 1.34335137e+04 1.37309834e+04 1.37229297e+04 1.35031348e+04 1.35614492e+04 1.33733105e+04 1.33858506e+04 1.38818984e+04 1.39518750e+04 1.34656875e+04 1.33357178e+04 1.34841787e+04 1.35651416e+04 1.33512656e+04 1.32288936e+04 1.34224365e+04 1.34053408e+04 1.36182354e+04 1.35461865e+04 1.30237002e+04 1.31464492e+04 1.36037910e+04 1.36943779e+04 1.35502383e+04 1.30454609e+04 1.28895264e+04 1.33040547e+04 1.33919287e+04 1.31824199e+04 1.30532715e+04 1.30360898e+04 1.32854736e+04 1.34160127e+04 1.32090830e+04 1.27948887e+04 1.27800498e+04 1.34142510e+04 1.34066982e+04 1.26924688e+04 1.26465547e+04 1.29917559e+04 1.31179199e+04 1.32441777e+04 1.29509512e+04 1.25122051e+04 1.26142979e+04 1.29117295e+04 1.29713428e+04 1.27629697e+04 1.25160527e+04 1.27355674e+04 1.29120850e+04 1.26901807e+04 1.25453408e+04 1.24489355e+04 1.25211904e+04 1.27172100e+04 1.26232891e+04 1.26458398e+04 1.25167363e+04 1.21812451e+04 1.23228994e+04 1.24645059e+04 1.23987363e+04 1.23729971e+04 1.22271426e+04 1.22284834e+04 1.24893467e+04 1.23995020e+04 1.19369795e+04 1.19673223e+04 1.21598906e+04 1.22636670e+04 1.21460400e+04 1.19141348e+04 1.18668047e+04 1.19766807e+04 1.20840225e+04 1.19575234e+04 1.16172959e+04 1.17414209e+04 1.20215967e+04 1.19910332e+04 1.18580684e+04 1.15224668e+04 1.14474941e+04 1.17613965e+04 1.16900674e+04 1.13830234e+04 1.13629287e+04 1.14126836e+04 1.15860762e+04 1.15352520e+04 1.13678994e+04 1.13356084e+04 1.12859453e+04 1.13987051e+04 1.13608311e+04 1.11149365e+04 1.11081162e+04 1.10954971e+04 1.09769639e+04 1.10540703e+04 1.10561055e+04 1.09985088e+04 1.10193223e+04 1.08525098e+04 1.07228105e+04 1.08516123e+04 1.09006152e+04 1.07320527e+04 1.06491846e+04 1.05159160e+04 1.04715488e+04 1.06265908e+04 1.04965908e+04 1.03838545e+04 1.04165029e+04 1.06242969e+04 1.05723770e+04 1.02131572e+04 1.02425430e+04 1.02937900e+04 1.01566836e+04 1.00127236e+04 9.99061914e+03 1.00252812e+04 1.00751172e+04 1.01901855e+04 1.00378682e+04 9.81802734e+03 9.64893848e+03 9.72983203e+03 9.87200977e+03 9.82571973e+03 9.69300781e+03 9.51217285e+03 9.57441895e+03 9.70710938e+03 9.57442383e+03 9.36182129e+03 9.20730762e+03 9.32357129e+03 9.48545508e+03 9.33247070e+03 8.94599902e+03 9.00639062e+03 9.24590430e+03 9.17868262e+03 8.97661621e+03 8.92403027e+03 8.93001270e+03 8.86908984e+03 8.89861719e+03 8.77851855e+03 8.54171387e+03 8.71283984e+03 8.86713379e+03 8.65726367e+03 8.56139844e+03 8.51412891e+03 8.33611328e+03 8.43184863e+03 8.37767383e+03 8.36201758e+03 8.45299707e+03 8.07982275e+03 8.04295654e+03 8.33938281e+03 8.11376904e+03 7.86517627e+03 7.94927344e+03 8.05035596e+03 7.97030029e+03 7.89800342e+03 7.81508691e+03 7.63585254e+03 7.54078223e+03 7.77397119e+03 7.80927930e+03 7.42847363e+03 7.42190479e+03 7.60902734e+03 7.45724365e+03 7.41640918e+03 7.23471875e+03 7.15119678e+03 7.27267529e+03 7.19707666e+03 7.14638818e+03 7.12101660e+03 6.96077539e+03 6.96421387e+03 7.03948926e+03 6.90703223e+03 6.81070361e+03 6.77717627e+03 6.77805859e+03 6.71225439e+03 6.64821191e+03 6.57985352e+03 6.51926904e+03 6.45993994e+03 6.49642969e+03 6.43822266e+03 6.32290527e+03 6.35306738e+03 6.38080713e+03 6.23883105e+03 6.34312256e+03 6.14616406e+03 5.91205225e+03 6.00274756e+03 6.02338965e+03 5.95253125e+03 5.81333936e+03 5.72899756e+03 5.80169629e+03 5.87273682e+03 5.74789111e+03 5.60163818e+03 5.65058252e+03 5.67472705e+03 5.46969141e+03 5.38998242e+03 5.48583936e+03 5.40690820e+03 5.23647656e+03 5.36808203e+03 5.24632324e+03 5.12344824e+03 5.15372461e+03 5.07784326e+03 5.00183936e+03 4.98730078e+03 4.93904248e+03 4.85179004e+03 4.87507910e+03 4.89044434e+03 4.86435791e+03 4.65692969e+03 4.58734961e+03 4.68518848e+03 4.59062305e+03 4.56431152e+03 4.50488965e+03 4.40198389e+03 4.37829443e+03 4.38873877e+03 4.39280420e+03 4.25896875e+03 4.11925684e+03 4.18704248e+03 4.28365674e+03 4.07431226e+03 3.94737866e+03 3.97927051e+03 3.92441772e+03 3.94256030e+03 3.93739722e+03 3.81133691e+03 3.76139648e+03 3.75447583e+03 3.71344287e+03 3.69928247e+03 3.63657935e+03 3.60290601e+03 3.59950439e+03 3.40932568e+03 3.42038257e+03 3.42760693e+03 3.33043921e+03 3.36404492e+03 3.30377124e+03 3.20696753e+03 3.22245142e+03 3.15102124e+03 3.10597388e+03 3.16753174e+03 3.09088892e+03 2.98953003e+03 2.92464185e+03 2.87036768e+03 2.88914307e+03 2.89203955e+03 2.79384326e+03 2.74623193e+03 2.76994702e+03 2.73529785e+03 2.67075635e+03 2.59463257e+03 2.55892358e+03 2.52261548e+03 2.51691699e+03 2.50252051e+03 2.39382422e+03 2.35912085e+03 2.37233789e+03 2.34648584e+03 2.30679053e+03 2.27013672e+03 2.20724292e+03 2.15801074e+03 2.19838721e+03 2.17816528e+03 2.06393994e+03 2.00011462e+03 1.97913892e+03 1.97292749e+03 1.94320178e+03 1.88951904e+03 1.88035449e+03 1.85535181e+03 1.81622620e+03 1.79863293e+03 1.74960828e+03 1.69655823e+03 1.68959387e+03 1.68196814e+03 1.62123535e+03 1.56017603e+03 1.55517053e+03 1.52759497e+03 1.50094043e+03 1.49027563e+03 1.44286975e+03 1.39611243e+03 1.38255200e+03 1.38551160e+03 1.33467273e+03 1.27945496e+03 1.26577869e+03 1.24445337e+03 1.21305396e+03 1.18093567e+03 1.14276624e+03 1.12652649e+03 1.11188171e+03 1.09494250e+03 1.07650012e+03 1.02814380e+03 1.00408063e+03 9.78755127e+02 9.49547791e+02 9.28436768e+02 9.01581726e+02 8.90741028e+02 8.67388123e+02 8.35539673e+02 8.06667175e+02 7.86981262e+02 7.80370789e+02 7.65214111e+02 7.42053589e+02 7.08833984e+02 6.83583923e+02 6.64564819e+02 6.36864990e+02 6.20191650e+02 6.07549438e+02 5.86544800e+02 5.66658691e+02 5.40118408e+02 5.19649597e+02 5.13394531e+02 5.01617828e+02 4.84619232e+02 4.57241455e+02 4.32029724e+02 4.22704254e+02 4.09919189e+02 3.90989563e+02 3.78367188e+02 3.65466675e+02 3.43722534e+02 3.26688599e+02 3.13876404e+02 3.00768097e+02 2.95686066e+02 2.83034271e+02 2.60882263e+02 2.50322128e+02 2.36289230e+02 2.18729813e+02 2.14061920e+02 2.06100067e+02 1.90205444e+02 1.79349075e+02 1.67969238e+02 1.55886047e+02 1.50104401e+02 1.43839294e+02 1.31284958e+02 1.20898903e+02 1.13362900e+02 1.05518875e+02 9.81741714e+01 9.01965485e+01 8.28132248e+01 7.58318253e+01 6.92654037e+01 6.30403671e+01 5.72277222e+01 5.12565117e+01 4.66070404e+01 4.25475769e+01 3.75002365e+01 3.28604469e+01 2.87452545e+01 2.54211197e+01 2.24365711e+01 1.97227764e+01 1.70941525e+01 1.46874495e+01 1.28563719e+01 1.14211721e+01 1.03175526e+01 9.49501419e+00 9.01888943e+00 8.86274815e+00 9.02616501e+00 9.55093861e+00 1.04542656e+01 1.16855659e+01 1.31186647e+01 1.48971720e+01 1.68852310e+01 1.90509701e+01 2.25418243e+01 2.66006126e+01 2.93526726e+01 3.25977821e+01 3.68684502e+01 4.17514458e+01 4.74268608e+01 5.27834129e+01 5.77653046e+01 6.23061562e+01 6.86767731e+01 7.63923798e+01 8.29763565e+01 9.11865845e+01 9.90656738e+01 1.05122292e+02 1.12552071e+02 1.22820862e+02 1.31697769e+02 1.39826553e+02 1.51394730e+02 1.62035065e+02 1.69203354e+02 1.77109726e+02 1.88610077e+02 2.03542297e+02 2.18514908e+02 2.28758377e+02 2.34914459e+02 2.45543747e+02 2.61042450e+02 2.77445557e+02 2.95496338e+02 3.06794403e+02 3.11922852e+02 3.32324432e+02 3.51569122e+02 3.60286713e+02 3.85981964e+02 3.99429474e+02 4.03744049e+02 4.23673950e+02 4.33083191e+02 4.49135864e+02 4.86020813e+02 5.04275391e+02 5.12371582e+02 5.34041260e+02 5.46473572e+02 5.50941284e+02 5.76370361e+02 6.11612183e+02 6.28966553e+02 6.48047607e+02 6.61487244e+02 6.79198853e+02 7.09443787e+02 7.36206909e+02 7.78274597e+02 7.82938293e+02 7.69386780e+02 8.00823914e+02 8.33193726e+02 8.67664917e+02 9.05477173e+02 9.10416138e+02 9.11009155e+02 9.54127686e+02 9.93700684e+02 1.01005414e+03 1.03945654e+03 1.05863501e+03 1.06795264e+03 1.11667651e+03 1.14042175e+03 1.14705566e+03 1.21749036e+03 1.24502844e+03 1.23880273e+03 1.26248621e+03 1.25876672e+03 1.29530566e+03 1.36551038e+03 1.43456628e+03 1.44792651e+03 1.39626099e+03 1.43199463e+03 1.51950159e+03 1.54170850e+03 1.55729614e+03 1.59104724e+03 1.60873376e+03 1.65250391e+03 1.69806055e+03 1.73234583e+03 1.74957080e+03 1.78676099e+03 1.83955457e+03 1.84476562e+03 1.85476770e+03 1.89732642e+03 1.93834741e+03 1.99263818e+03 2.06503784e+03 2.05465845e+03 2.03704260e+03 2.10553394e+03 2.16590942e+03 2.24601489e+03 2.26338745e+03 2.21167285e+03 2.27285083e+03 2.32993555e+03 2.38415332e+03 2.46392114e+03 2.45428418e+03 2.45902295e+03 2.49440112e+03 2.50530469e+03 2.53954346e+03 2.64993774e+03 2.73529517e+03 2.70619800e+03 2.70380396e+03 2.71765674e+03 2.77566162e+03 2.91012134e+03 2.94746875e+03 2.95479370e+03 2.96012598e+03 2.93230737e+03 3.00535498e+03 3.09000562e+03 3.19085278e+03 3.24679785e+03 3.15963940e+03 3.18685815e+03 3.28329980e+03 3.34737354e+03 3.39112866e+03 3.45486133e+03 3.50617456e+03 3.46754297e+03 3.50155859e+03 3.55994165e+03 3.61537427e+03 3.69089600e+03 3.74384204e+03 3.77278003e+03 3.78065747e+03 3.80703760e+03 3.87181299e+03 4.00683008e+03 4.01366943e+03 3.96035034e+03 4.00488843e+03 4.06714380e+03 4.09779346e+03 4.31078760e+03 4.31247070e+03 4.19779346e+03 4.33674902e+03 4.31889941e+03 4.42166602e+03 4.60772656e+03 4.52076367e+03 4.52065869e+03 4.57518213e+03 4.71032568e+03 4.78993652e+03 4.89443115e+03 4.77145459e+03 6.61918652e+03 7.13349121e+03 1.14705068e+04 2.10582188e+04 4.65230450e+06 -93729688. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 62249224. 4.02128425e+06 2.79057988e+04 1.89238125e+04 9.87325586e+03 7.78834180e+03 9.95376465e+03 8.35547266e+03 7.38113330e+03 7.42528613e+03 7.73616846e+03 7.71202051e+03 7.52898145e+03 7.39895166e+03 7.52562744e+03 7.79574854e+03 7.94794043e+03 7.90311133e+03 7.75421289e+03 7.77391748e+03 7.83753076e+03 8.07499512e+03 8.11402393e+03 7.80557812e+03 7.99258008e+03 8.27166992e+03 8.27318750e+03 8.14293506e+03 8.06333105e+03 8.33483105e+03 8.70047852e+03 8.77204395e+03 8.30375586e+03 8.02316748e+03 8.35990430e+03 8.77659473e+03 9.02064941e+03 8.87885352e+03 8.55293262e+03 8.68711426e+03 8.89861914e+03 9.12247559e+03 9.09507520e+03 8.65831445e+03 8.84973145e+03 9.35556250e+03 9.28710254e+03 9.05114062e+03 9.20101758e+03 9.27807324e+03 9.46955664e+03 9.49855566e+03 9.18001367e+03 9.09371777e+03 9.59184570e+03 9.85726953e+03 9.81343164e+03 9.46567578e+03 9.27708008e+03 9.76359375e+03 1.01562246e+04 9.97509766e+03 9.70722461e+03 9.41640820e+03 9.62636230e+03 1.01740713e+04 1.03454648e+04 1.02600645e+04 1.01287422e+04 1.01653174e+04 1.00564551e+04 1.01427236e+04 1.03252129e+04 1.00499717e+04 1.02520605e+04 1.07002832e+04 1.05685820e+04 1.01220400e+04 1.01003984e+04 1.06609961e+04 1.10265479e+04 1.09265498e+04 1.06006553e+04 1.03494102e+04 1.04489014e+04 1.07722021e+04 1.12709443e+04 1.11541084e+04 1.05846582e+04 1.07481016e+04 1.09817432e+04 1.11049219e+04 1.13493291e+04 1.10012734e+04 1.09918779e+04 1.13207803e+04 1.13416807e+04 1.12145508e+04 1.10939844e+04 1.12860303e+04 1.15533428e+04 1.15582656e+04 1.13051592e+04 1.11346191e+04 1.15066787e+04 1.19199375e+04 1.18501289e+04 1.16334424e+04 1.13199600e+04 1.16100869e+04 1.19682646e+04 1.20079072e+04 1.18027324e+04 1.13682500e+04 1.14970996e+04 1.20966299e+04 1.24227344e+04 1.21511729e+04 1.16519453e+04 1.18184238e+04 1.22181455e+04 1.21834082e+04 1.19618877e+04 1.18503984e+04 1.23245850e+04 1.25553477e+04 1.22383789e+04 1.21101260e+04 1.19723701e+04 1.23759043e+04 1.29161123e+04 1.26785537e+04 1.23272812e+04 1.21707373e+04 1.22924727e+04 1.25363330e+04 1.28249189e+04 1.27501230e+04 1.22161475e+04 1.22871670e+04 1.28588643e+04 1.30476426e+04 1.27746553e+04 1.25072393e+04 1.26646289e+04 1.29862363e+04 1.30431875e+04 1.28377715e+04 1.24100322e+04 1.26049492e+04 1.31434082e+04 1.31440488e+04 1.29595938e+04 1.27183008e+04 1.27758740e+04 1.31426602e+04 1.34880361e+04 1.33401777e+04 1.27967139e+04 1.28873467e+04 1.31650771e+04 1.32424189e+04 1.32536514e+04 1.30545498e+04 1.32364473e+04 1.32667920e+04 1.31491201e+04 1.31493271e+04 1.31007070e+04 1.34932002e+04 1.36913779e+04 1.34813301e+04 1.31276836e+04 1.29407646e+04 1.34223516e+04 1.39241543e+04 1.37929072e+04 1.34500371e+04 1.30906729e+04 1.29373252e+04 1.34282002e+04 1.41127568e+04 1.37233516e+04 1.30381611e+04 1.32440381e+04 1.37162959e+04 1.38536348e+04 1.38003945e+04 1.34945859e+04 1.35182881e+04 1.37476543e+04 1.35368584e+04 1.34029980e+04 1.35341338e+04 1.37666357e+04 1.37900654e+04 1.36680273e+04 1.35711230e+04 1.35173105e+04 1.37582031e+04 1.40326338e+04 1.39848779e+04 1.34908662e+04 1.32325498e+04 1.38037197e+04 1.41264551e+04 1.39547246e+04 1.37312520e+04 1.33123750e+04 1.33611572e+04 1.40278643e+04 1.43819531e+04 1.41023770e+04 1.34767275e+04 1.33763506e+04 1.38499775e+04 1.40528916e+04 1.39443271e+04 1.38331855e+04 1.39277129e+04 1.38689443e+04 1.36357510e+04 1.33618896e+04 1.33087402e+04 1.36579619e+04 1.39312822e+04 1.43382803e+04 1.40831914e+04 1.33618174e+04 1.35928721e+04 1.38198789e+04 1.37567510e+04 1.38961592e+04 1.37708301e+04 1.41114424e+04 1.40652607e+04 1.33402881e+04 1.31621641e+04 1.34830869e+04 1.41126367e+04 1.45452490e+04 1.41886152e+04 1.33781240e+04 1.29907617e+04 1.33651807e+04 1.40632832e+04 1.44301787e+04 1.41224619e+04 1.33571562e+04 1.32408740e+04 1.40789238e+04 1.41627910e+04 1.34068799e+04 1.33292598e+04 1.35823555e+04 1.35996455e+04 1.40274248e+04 1.36835332e+04 1.31771787e+04 1.35506074e+04 1.32485469e+04 1.35346240e+04 1.39352266e+04 1.31973984e+04 1.34814219e+04 1.39017100e+04 1.35328896e+04 1.35108926e+04 1.34393887e+04 1.34631562e+04 1.35423330e+04 1.34802910e+04 1.30910625e+04 1.30440332e+04 1.36285459e+04 1.40049209e+04 1.37184707e+04 1.30658350e+04 1.27407559e+04 1.29505410e+04 1.35553828e+04 1.39419551e+04 1.36523955e+04 1.28610693e+04 1.28612529e+04 1.33554219e+04 1.32496562e+04 1.30596006e+04 1.30199648e+04 1.30490283e+04 1.30478135e+04 1.34534736e+04 1.31235195e+04 1.26825156e+04 1.29524414e+04 1.26451064e+04 1.29858477e+04 1.32337969e+04 1.29080537e+04 1.32570273e+04 1.28420977e+04 1.24307334e+04 1.27888916e+04 1.24404990e+04 1.26752803e+04 1.35263887e+04 1.28091641e+04 1.20433662e+04 1.22865391e+04 1.28340811e+04 1.32986250e+04 1.29665781e+04 1.22262949e+04 1.18430654e+04 1.21135078e+04 1.27390791e+04 1.31234512e+04 1.27774727e+04 1.20807676e+04 1.19578008e+04 1.23649355e+04 1.25201357e+04 1.22019121e+04 1.19805195e+04 1.21528604e+04 1.21767354e+04 1.24507041e+04 1.24266211e+04 1.18154502e+04 1.17633047e+04 1.18702285e+04 1.19059863e+04 1.20271504e+04 1.19370527e+04 1.21548574e+04 1.19064062e+04 1.14774121e+04 1.16800332e+04 1.13939053e+04 1.16868467e+04 1.23823623e+04 1.17037793e+04 1.09323203e+04 1.11562588e+04 1.17056113e+04 1.20282295e+04 1.19549727e+04 1.12683770e+04 1.07847676e+04 1.09437402e+04 1.14956680e+04 1.19462881e+04 1.15657393e+04 1.08737627e+04 1.07634258e+04 1.10385352e+04 1.11509551e+04 1.14377832e+04 1.13247842e+04 1.06800449e+04 1.05690762e+04 1.10976787e+04 1.11348350e+04 1.07025605e+04 1.06181123e+04 1.06162490e+04 1.04988711e+04 1.09146250e+04 1.09723857e+04 1.03808428e+04 1.02665605e+04 1.03405381e+04 1.04029678e+04 1.04342959e+04 1.02838584e+04 1.04984199e+04 1.06058545e+04 1.02042725e+04 9.95922461e+03 9.69958984e+03 1.00527744e+04 1.05808320e+04 1.03072676e+04 9.74993164e+03 9.45553223e+03 9.78103223e+03 1.02712500e+04 9.91147656e+03 9.32332910e+03 9.45761816e+03 9.63403418e+03 9.89449805e+03 1.00964404e+04 9.84487305e+03 9.22550977e+03 9.01758887e+03 9.26521680e+03 9.53799121e+03 9.48242969e+03 9.30754980e+03 9.22666113e+03 9.13443164e+03 9.27420605e+03 9.17541895e+03 8.85739551e+03 8.73432129e+03 8.73542480e+03 9.10536035e+03 9.11625293e+03 8.81204102e+03 8.78173535e+03 8.78325781e+03 8.84674414e+03 8.64809375e+03 8.15107715e+03 8.48984082e+03 8.91952637e+03 8.62468652e+03 8.13764404e+03 8.11852930e+03 8.50078223e+03 8.48973926e+03 8.27977637e+03 8.17682324e+03 7.90777881e+03 7.86760938e+03 8.21958203e+03 8.18081104e+03 7.76922998e+03 7.56551758e+03 7.55099023e+03 7.85203174e+03 8.11192725e+03 7.70169434e+03 7.42859473e+03 7.54135303e+03 7.53786816e+03 7.71421533e+03 7.62189307e+03 7.09537695e+03 7.17212207e+03 7.35442725e+03 7.25745264e+03 7.22470166e+03 7.10831250e+03 7.23205420e+03 7.15427832e+03 6.89108203e+03 6.87069922e+03 6.69441113e+03 6.89125635e+03 7.15792383e+03 6.92036133e+03 6.58192676e+03 6.44600879e+03 6.72895898e+03 6.90449609e+03 7.19437598e+03 7.54506738e+03 6.66394385e+03 7.84491504e+03 1.21136123e+04 1.13393438e+05 45702096. 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. 0. 0. 0. 0. 0. 0. 0. -103585272. -8899590. -2.22294725e+06 -7057037. 1.23589736e+04 9.99571777e+03 5.64268750e+03 5.52163916e+03 4.52908301e+03 4.39251172e+03 4.15994824e+03 4.20230518e+03 4.09433545e+03 3.90491870e+03 3.95243066e+03 3.90713062e+03 3.98783862e+03 3.97456348e+03 3.58999219e+03 3.49263525e+03 3.52732007e+03 3.57246680e+03 3.47609937e+03 3.37039722e+03 3.57408008e+03 3.44459351e+03 3.31243457e+03 3.42042700e+03 3.36538721e+03 3.21109302e+03 3.27880225e+03 3.34818774e+03 3.22295190e+03 3.13700732e+03 3.09146631e+03 3.03708398e+03 2.97261768e+03 2.94178296e+03 2.98295728e+03 2.94553320e+03 2.86015039e+03 2.81369214e+03 2.77655884e+03 2.74086328e+03 2.69506299e+03 2.65282031e+03 2.62242285e+03 2.51167236e+03 2.46366357e+03 2.49640381e+03 2.45998364e+03 2.50978491e+03 2.48026782e+03 2.35874829e+03 2.25480786e+03 2.21395654e+03 2.31949048e+03 2.30629565e+03 2.18270532e+03 2.10353979e+03 2.07642944e+03 2.06817603e+03 2.02296985e+03 2.05818091e+03 2.02421667e+03 1.87824194e+03 1.82452747e+03 1.88846118e+03 1.92880457e+03 1.84700757e+03 1.77196448e+03 1.75062988e+03 1.71459277e+03 1.66304297e+03 1.64330090e+03 1.61668628e+03 1.57579700e+03 1.54648877e+03 1.51417212e+03 1.50320984e+03 1.46726611e+03 1.47067358e+03 1.43567078e+03 1.36202393e+03 1.35345984e+03 1.32672119e+03 1.30421313e+03 1.28176172e+03 1.24566211e+03 1.21707715e+03 1.16287585e+03 1.10793481e+03 1.13498389e+03 1.12477869e+03 1.04326636e+03 1.02653076e+03 1.05914758e+03 1.06279248e+03 1.00496002e+03 9.52236145e+02 9.25173828e+02 9.02265930e+02 8.73665710e+02 8.46921204e+02 8.38992676e+02 8.13536621e+02 8.09746277e+02 7.82416260e+02 7.38997314e+02 7.29529297e+02 6.89274719e+02 6.71549194e+02 6.86812561e+02 6.61076172e+02 6.26528687e+02 5.92455688e+02 5.63873413e+02 5.76909424e+02 5.68476868e+02 5.30230164e+02 4.97884796e+02 4.81985840e+02 4.76185760e+02 4.56160950e+02 4.52579041e+02 4.39082977e+02 4.07547882e+02 3.83531372e+02 3.68024109e+02 3.67286285e+02 3.53072693e+02 3.30338654e+02 3.12394653e+02 2.98794373e+02 2.87895996e+02 2.67388367e+02 2.56419769e+02 2.58210114e+02 2.43874496e+02 2.25632767e+02 2.08501053e+02 1.95731735e+02 1.95765732e+02 1.85734940e+02 1.70077438e+02 1.56104614e+02 1.45335800e+02 1.39658615e+02 1.30742706e+02 1.21799332e+02 1.10405777e+02 1.04352089e+02 1.00954308e+02 9.07228546e+01 8.28375854e+01 7.64926147e+01 6.95327759e+01 6.23795929e+01 5.63600960e+01 5.13431702e+01 4.60917702e+01 4.10068932e+01 3.56664619e+01 3.21735420e+01 2.97698441e+01 2.55664120e+01 2.19394989e+01 1.94791698e+01 1.69745331e+01 1.49947042e+01 1.30339994e+01 1.14168997e+01 1.03758526e+01 9.53384495e+00 9.02398491e+00 8.86270332e+00 9.00730228e+00 9.48715496e+00 1.03480549e+01 1.15782709e+01 1.30081282e+01 1.49862146e+01 1.76331844e+01 1.99592800e+01 2.24567280e+01 2.53161945e+01 2.90093212e+01 3.41878319e+01 3.82364769e+01 4.19378967e+01 4.58738556e+01 5.07805901e+01 5.76311760e+01 6.34377708e+01 7.09795914e+01 7.64559555e+01 8.09982986e+01 9.05611420e+01 9.82244415e+01 1.08049240e+02 1.15549957e+02 1.20829445e+02 1.29681046e+02 1.38913116e+02 1.50683502e+02 1.56481308e+02 1.68078293e+02 1.88047745e+02 1.95918991e+02 2.02654587e+02 2.09010696e+02 2.19153717e+02 2.43681564e+02 2.57557831e+02 2.63494202e+02 2.69287628e+02 2.81848114e+02 3.05086853e+02 3.19615570e+02 3.40781769e+02 3.51504456e+02 3.58993927e+02 3.70315460e+02 3.83492859e+02 4.20526001e+02 4.34086731e+02 4.36863190e+02 4.52104950e+02 4.69739777e+02 5.01903503e+02 5.21043091e+02 5.17987610e+02 5.33730591e+02 5.80455261e+02 6.00126892e+02 5.90556763e+02 6.07250793e+02 6.60639160e+02 6.84519409e+02 6.81983337e+02 6.87903503e+02 7.09211365e+02 7.72684814e+02 7.87410583e+02 7.85690186e+02 8.11244507e+02 8.31810852e+02 8.58460876e+02 8.81395691e+02 9.04703247e+02 9.04919556e+02 9.52030334e+02 1.03186230e+03 1.02653430e+03 1.03718677e+03 1.07077405e+03 1.08762524e+03 1.11276685e+03 1.13636768e+03 1.16105786e+03 1.15906775e+03 1.16705505e+03 1.22151831e+03 1.28146790e+03 1.35115210e+03 1.33165112e+03 1.31161865e+03 1.37486365e+03 1.42069067e+03 1.49373804e+03 1.50412219e+03 1.48984668e+03 1.50839465e+03 1.52834778e+03 1.59287585e+03 1.62462952e+03 1.68872705e+03 1.71821167e+03 1.70966907e+03 1.72230725e+03 1.70443262e+03 1.80727185e+03 1.94473108e+03 1.94039429e+03 1.91502209e+03 1.89489209e+03 1.90637964e+03 2.03782971e+03 2.12606885e+03 2.10119873e+03 2.05995483e+03 2.09497559e+03 2.18604199e+03 2.21753516e+03 2.31607495e+03 2.34254980e+03 2.30755884e+03 2.35696899e+03 2.38617480e+03 2.46665869e+03 2.51533179e+03 2.44715356e+03 2.48011304e+03 2.66086035e+03 2.64556055e+03 2.54719067e+03 2.67443457e+03 2.85530054e+03 2.84568848e+03 2.81040576e+03 2.78032568e+03 2.82551514e+03 3.03144360e+03 3.05223242e+03 3.00419702e+03 2.97484692e+03 2.99749927e+03 3.13055762e+03 3.16971729e+03 3.19784692e+03 3.17338208e+03 3.28531323e+03 3.46767358e+03 3.41180591e+03 3.45753027e+03 3.48813184e+03 3.46255298e+03 3.54015723e+03 3.58661475e+03 3.64277710e+03 3.66365967e+03 3.67108423e+03 3.63959521e+03 3.76747876e+03 4.03172485e+03 3.89341064e+03 3.75921899e+03 3.92400488e+03 4.06594824e+03 4.22431006e+03 4.17595850e+03 4.09325708e+03 4.24033154e+03 4.29417188e+03 4.16259277e+03 4.16086084e+03 4.45841992e+03 4.52615820e+03 4.44355225e+03 4.41008984e+03 4.32080469e+03 4.54773193e+03 4.89202588e+03 4.80445898e+03 4.72418018e+03 4.64252148e+03 4.64389844e+03 4.94197949e+03 5.15226465e+03 5.05415527e+03 4.85999951e+03 4.88550586e+03 5.06462012e+03 5.19198145e+03 5.35044971e+03 5.30610889e+03 5.20063770e+03 5.34644531e+03 5.37141455e+03 5.50905957e+03 5.51596826e+03 5.47927344e+03 5.57050928e+03 5.59652295e+03 5.61855078e+03 5.51189941e+03 5.67599902e+03 6.07658643e+03 5.99062158e+03 5.82214502e+03 5.75923828e+03 5.88253467e+03 6.27190967e+03 6.28439355e+03 6.15782617e+03 6.04396436e+03 6.06825049e+03 6.26045654e+03 6.32359863e+03 6.36611572e+03 6.26350488e+03 6.43619141e+03 6.77590820e+03 6.60901270e+03 6.71232324e+03 6.79217969e+03 6.67703857e+03 6.72227051e+03 6.76456836e+03 6.78620557e+03 6.84302295e+03 6.91539062e+03 6.95431396e+03 7.17456787e+03 7.25772949e+03 6.94105225e+03 6.91280518e+03 7.15818848e+03 7.39145605e+03 7.63899316e+03 7.43360986e+03 7.17026562e+03 7.55893018e+03 7.77472168e+03 7.62241211e+03 7.49323535e+03 7.51591162e+03 7.73584766e+03 7.80820264e+03 7.77676953e+03 7.61346387e+03 7.89879639e+03 8.33453613e+03 8.19885254e+03 8.09249414e+03 7.96187061e+03 7.90639160e+03 8.43265625e+03 8.44807520e+03 8.29089551e+03 8.16588770e+03 7.97456641e+03 8.25508789e+03 8.64150195e+03 8.94621973e+03 8.61442188e+03 8.27709375e+03 8.56638965e+03 8.75883887e+03 9.05367969e+03 8.92459180e+03 8.69146875e+03 8.98575781e+03 8.99919336e+03 8.86567480e+03 8.66621094e+03 9.00790234e+03 9.54598535e+03 9.37102734e+03 9.29219434e+03 9.07862793e+03 9.09067383e+03 9.61109766e+03 9.68959473e+03 9.42306055e+03 9.23109473e+03 9.22364355e+03 9.58419043e+03 9.61360059e+03 9.93397363e+03 9.97591016e+03 9.67401074e+03 9.54972266e+03 9.71514648e+03 1.01840479e+04 9.99942090e+03 9.83069434e+03 1.00194453e+04 1.00986064e+04 9.93395312e+03 9.85972168e+03 1.03290264e+04 1.03398857e+04 1.00842490e+04 1.05472012e+04 1.06647910e+04 1.04946406e+04 1.04921982e+04 1.04894639e+04 1.05363633e+04 1.03059570e+04 1.02390508e+04 1.08071582e+04 1.10255234e+04 1.04787119e+04 1.01914424e+04 1.07136650e+04 1.13900020e+04 1.12741611e+04 1.07512822e+04 1.05657578e+04 1.11519893e+04 1.13813076e+04 1.10832061e+04 1.12144717e+04 1.09320137e+04 1.06605566e+04 1.11242148e+04 1.16509727e+04 1.16677305e+04 1.12369277e+04 1.09344248e+04 1.15302539e+04 1.19380762e+04 1.16230938e+04 1.12117002e+04 1.10959043e+04 1.14951396e+04 1.16078027e+04 1.19308760e+04 1.19352988e+04 1.15201611e+04 1.17274531e+04 1.18473428e+04 1.20650381e+04 1.17508887e+04 1.15255977e+04 1.21014229e+04 1.21533535e+04 1.20234463e+04 1.17570459e+04 1.18848857e+04 1.26131182e+04 1.21671299e+04 1.16821592e+04 1.20287080e+04 1.23369502e+04 1.23892090e+04 1.22701182e+04 1.25777969e+04 1.27065215e+04 1.23578271e+04 1.20491660e+04 1.20584814e+04 1.27417754e+04 1.25473428e+04 1.22123711e+04 1.26783955e+04 1.27102627e+04 1.25074785e+04 1.24111953e+04 1.28625176e+04 1.28094863e+04 1.24736875e+04 1.28298975e+04 1.28621641e+04 1.29438193e+04 1.29938311e+04 1.28606875e+04 1.27941660e+04 1.24730312e+04 1.24136592e+04 1.30711709e+04 1.36008945e+04 1.29252061e+04 1.22984551e+04 1.28441660e+04 1.36450889e+04 1.35708926e+04 1.29290605e+04 1.25069326e+04 1.31445752e+04 1.35740488e+04 1.31679053e+04 1.34040488e+04 1.33686211e+04 1.28731318e+04 1.30115781e+04 1.35256572e+04 1.36347832e+04 1.31041914e+04 1.27655947e+04 1.33553555e+04 1.39546240e+04 1.36191514e+04 1.30752861e+04 1.28709941e+04 1.35047607e+04 1.39700635e+04 1.35220117e+04 1.31957627e+04 1.32743584e+04 1.35378359e+04 1.35044590e+04 1.38705684e+04 1.35946846e+04 1.31539795e+04 1.36548906e+04 1.37129248e+04 1.37885518e+04 1.35012256e+04 1.32585332e+04 1.38280254e+04 1.35192471e+04 1.33296221e+04 1.37574590e+04 1.37370098e+04 1.37249424e+04 1.36823018e+04 1.40943154e+04 1.42024150e+04 1.36852070e+04 1.32870781e+04 1.33403555e+04 1.42349766e+04 1.43553691e+04 1.38520322e+04 1.23660850e+04 1.35886064e+04 2.29258145e+04 1.26030570e+05 5093668. 0. 0. 0. 0. 0. -4.64683213e+10 2.00708188e+05 4.62339883e+04 1.43835609e+05 1.74280734e+05 4.20238828e+04 1.65340938e+05 -7.86057462e+11 7.89500238e+12 7.89500238e+12 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.06972160e+09 1.70592578e+05 3.53237461e+04 3.73138242e+04 3.19668184e+04 1.68461270e+04 1.21395850e+04 1.50583262e+04 1.43899551e+04 1.39509287e+04 1.38249727e+04 1.38169902e+04 1.38466680e+04 1.35291582e+04 1.35205684e+04 1.37940752e+04 1.36750781e+04 1.36082061e+04 1.35574316e+04 1.34209854e+04 1.36927246e+04 1.36673633e+04 1.34636846e+04 1.35698613e+04 1.33820176e+04 1.33527578e+04 1.38224014e+04 1.39348535e+04 1.34306318e+04 1.32990088e+04 1.34851377e+04 1.35174404e+04 1.32958037e+04 1.32066182e+04 1.33759990e+04 1.33641709e+04 1.35931455e+04 1.35154902e+04 1.30010576e+04 1.31215703e+04 1.36008203e+04 1.36733555e+04 1.34998711e+04 1.30021738e+04 1.28548027e+04 1.32654502e+04 1.33701465e+04 1.31390508e+04 1.30219082e+04 1.30215615e+04 1.32532314e+04 1.33835020e+04 1.31825615e+04 1.27735322e+04 1.27340898e+04 1.33790283e+04 1.33934238e+04 1.26726396e+04 1.26230830e+04 1.29539502e+04 1.31040791e+04 1.32098740e+04 1.29335742e+04 1.24776182e+04 1.25924072e+04 1.29027500e+04 1.29236465e+04 1.27385205e+04 1.25304023e+04 1.27061426e+04 1.28292617e+04 1.26934199e+04 1.25370430e+04 1.23997988e+04 1.24864561e+04 1.26883262e+04 1.25932334e+04 1.26249062e+04 1.25183457e+04 1.21567109e+04 1.23253105e+04 1.24277695e+04 1.23684062e+04 1.23597686e+04 1.22004590e+04 1.21851396e+04 1.24832080e+04 1.23765811e+04 1.19120449e+04 1.19349854e+04 1.21427871e+04 1.22459688e+04 1.21245342e+04 1.18633115e+04 1.18384609e+04 1.19534980e+04 1.20394248e+04 1.19306387e+04 1.16072246e+04 1.17316973e+04 1.20412969e+04 1.19445947e+04 1.18209648e+04 1.14847539e+04 1.13952256e+04 1.17787842e+04 1.16363486e+04 1.13903760e+04 1.13465430e+04 1.13908174e+04 1.15812734e+04 1.15202100e+04 1.13194434e+04 1.12800195e+04 1.12538799e+04 1.13780449e+04 1.13471572e+04 1.11052598e+04 1.10959844e+04 1.10739385e+04 1.09573643e+04 1.10463047e+04 1.10346436e+04 1.09557246e+04 1.09501445e+04 1.08189502e+04 1.06972344e+04 1.08265830e+04 1.09241133e+04 1.07256826e+04 1.06228750e+04 1.04612852e+04 1.04650479e+04 1.06094336e+04 1.04820225e+04 1.03922705e+04 1.03770449e+04 1.05528125e+04 1.05360781e+04 1.02483516e+04 1.02596162e+04 1.02551045e+04 1.01362646e+04 9.97428418e+03 9.94952930e+03 9.98870898e+03 1.00717002e+04 1.01278291e+04 1.00592812e+04 9.79940137e+03 9.61212988e+03 9.77183008e+03 9.81953906e+03 9.74071680e+03 9.68849805e+03 9.51349512e+03 9.56201270e+03 9.65072168e+03 9.55182324e+03 9.34036914e+03 9.15522461e+03 9.32444531e+03 9.49591992e+03 9.35021582e+03 8.94569434e+03 8.97663281e+03 9.21955762e+03 9.16018848e+03 8.94628418e+03 8.93307324e+03 8.92463184e+03 8.80950391e+03 8.87800098e+03 8.74033008e+03 8.51204688e+03 8.68385254e+03 8.80127148e+03 8.61060254e+03 8.55137207e+03 8.52191309e+03 8.31527637e+03 8.34180664e+03 8.35790234e+03 8.37775293e+03 8.44421289e+03 8.03997314e+03 8.02981787e+03 8.29563672e+03 8.10342627e+03 7.84114502e+03 7.92183691e+03 8.02381641e+03 7.92510254e+03 7.88258252e+03 7.81033105e+03 7.66465820e+03 7.58354199e+03 7.76325342e+03 7.81775879e+03 7.45362012e+03 7.43262402e+03 7.61698828e+03 7.45407031e+03 7.36155664e+03 7.24715869e+03 7.10613428e+03 7.25632471e+03 7.16294141e+03 7.09087402e+03 7.10749414e+03 6.93156689e+03 6.92989062e+03 7.03041846e+03 6.83864404e+03 6.78472168e+03 6.80438525e+03 6.74651074e+03 6.66056299e+03 6.66164648e+03 6.60272314e+03 6.50829541e+03 6.46550244e+03 6.50762744e+03 6.43280908e+03 6.29187061e+03 6.34287793e+03 6.36771533e+03 6.23110547e+03 6.28812354e+03 6.13117285e+03 5.93654199e+03 6.02310645e+03 5.98763086e+03 5.94535400e+03 5.82011768e+03 5.73264697e+03 5.82379199e+03 5.88745410e+03 5.73043604e+03 5.59480957e+03 5.62240479e+03 5.63069629e+03 5.46426807e+03 5.36314307e+03 5.49332910e+03 5.41695996e+03 5.23032031e+03 5.33215820e+03 5.23453906e+03 5.15440625e+03 5.15860303e+03 5.03072217e+03 4.99067822e+03 4.99695801e+03 4.92800781e+03 4.86545654e+03 4.86742285e+03 4.86055518e+03 4.83940674e+03 4.63698096e+03 4.56306104e+03 4.64464258e+03 4.58222217e+03 4.56067578e+03 4.49801221e+03 4.39352002e+03 4.38643604e+03 4.37112451e+03 4.40367676e+03 4.26279980e+03 4.09484106e+03 4.16386719e+03 4.29799854e+03 4.07484009e+03 3.94062720e+03 3.95461816e+03 3.90927954e+03 3.92598096e+03 3.93023779e+03 3.79368823e+03 3.74826758e+03 3.74162720e+03 3.70830713e+03 3.71082983e+03 3.61394385e+03 3.59662500e+03 3.59815552e+03 3.40706763e+03 3.40763745e+03 3.41325854e+03 3.32461084e+03 3.35939038e+03 3.29431689e+03 3.20253247e+03 3.21912378e+03 3.13821509e+03 3.10352148e+03 3.16286230e+03 3.07669019e+03 2.97445679e+03 2.91674438e+03 2.85840088e+03 2.88810669e+03 2.88952539e+03 2.80854248e+03 2.75393652e+03 2.75808594e+03 2.72896045e+03 2.67264136e+03 2.58989014e+03 2.54438745e+03 2.53080249e+03 2.52172729e+03 2.49954175e+03 2.39781836e+03 2.35780005e+03 2.36512524e+03 2.34092163e+03 2.30036914e+03 2.26836475e+03 2.21029492e+03 2.15443555e+03 2.18297314e+03 2.17500562e+03 2.06941504e+03 1.99311035e+03 1.97374036e+03 1.97703894e+03 1.94456348e+03 1.89069824e+03 1.88347485e+03 1.85413940e+03 1.81155249e+03 1.79923279e+03 1.74896497e+03 1.69926929e+03 1.68852087e+03 1.68059985e+03 1.61487378e+03 1.55549219e+03 1.55452173e+03 1.52569971e+03 1.49885535e+03 1.48681323e+03 1.44206836e+03 1.39257202e+03 1.37966345e+03 1.38019031e+03 1.33307898e+03 1.27767456e+03 1.25931140e+03 1.23721350e+03 1.20941284e+03 1.17991626e+03 1.14336218e+03 1.12536829e+03 1.10576160e+03 1.09180652e+03 1.07470923e+03 1.02832874e+03 1.00431195e+03 9.78738831e+02 9.48306091e+02 9.23936768e+02 8.92267700e+02 8.84787476e+02 8.67864258e+02 8.32771484e+02 8.00561584e+02 7.79795959e+02 7.74488647e+02 7.61675293e+02 7.39958313e+02 7.04921143e+02 6.78205994e+02 6.57861145e+02 6.27915344e+02 6.15006409e+02 6.05684448e+02 5.83639404e+02 5.60325745e+02 5.34784119e+02 5.18448914e+02 5.12174988e+02 5.00540741e+02 4.83594391e+02 4.55384216e+02 4.29155975e+02 4.17591980e+02 4.03867554e+02 3.87776062e+02 3.77902893e+02 3.64834290e+02 3.41821075e+02 3.23401886e+02 3.08525665e+02 2.96553711e+02 2.93631165e+02 2.80363342e+02 2.58383057e+02 2.47512848e+02 2.33845215e+02 2.18258835e+02 2.14074280e+02 2.04220566e+02 1.86638367e+02 1.75079544e+02 1.64452423e+02 1.53361450e+02 1.48647293e+02 1.43834717e+02 1.31490555e+02 1.19917984e+02 1.11243271e+02 1.02607681e+02 9.59427872e+01 8.88045654e+01 8.15050354e+01 7.39677505e+01 6.68392715e+01 6.13901863e+01 5.63402939e+01 5.08163834e+01 4.59397125e+01 4.12906189e+01 3.59881401e+01 3.12505016e+01 2.78124638e+01 2.48892651e+01 2.19612217e+01 1.89339523e+01 1.61208801e+01 1.39504776e+01 1.23509245e+01 1.10114193e+01 9.84715652e+00 8.94548321e+00 8.41429424e+00 8.26762199e+00 8.49528980e+00 9.00541306e+00 9.74788284e+00 1.08205862e+01 1.23323736e+01 1.45417242e+01 1.68488503e+01 1.89816074e+01 2.21396885e+01 2.59431591e+01 2.89741592e+01 3.25440331e+01 3.70907974e+01 4.14312439e+01 4.66108246e+01 5.17676086e+01 5.68266678e+01 6.15951843e+01 6.83132553e+01 7.63027878e+01 8.27933960e+01 9.06901245e+01 9.82588196e+01 1.04564438e+02 1.12128311e+02 1.23164322e+02 1.31897049e+02 1.39310257e+02 1.50311325e+02 1.61272049e+02 1.69800613e+02 1.77646927e+02 1.87888153e+02 2.00689240e+02 2.16140060e+02 2.28566910e+02 2.36156677e+02 2.47246506e+02 2.60049347e+02 2.75667206e+02 2.93006989e+02 3.05054657e+02 3.12007111e+02 3.30878479e+02 3.48668243e+02 3.57236053e+02 3.82496735e+02 3.97945221e+02 4.02573578e+02 4.25132477e+02 4.36056061e+02 4.48520111e+02 4.81929535e+02 4.98695831e+02 5.07649902e+02 5.32039734e+02 5.48386963e+02 5.53448853e+02 5.75690430e+02 6.07226685e+02 6.25566711e+02 6.47360535e+02 6.62236755e+02 6.79288452e+02 7.07973938e+02 7.29867859e+02 7.72542725e+02 7.81094177e+02 7.69735229e+02 8.02390564e+02 8.32992371e+02 8.65469910e+02 8.99244263e+02 9.04561218e+02 9.07892273e+02 9.54944519e+02 9.90913147e+02 1.00639014e+03 1.03581836e+03 1.05291858e+03 1.06326917e+03 1.11164929e+03 1.14006140e+03 1.14131165e+03 1.21187769e+03 1.24220251e+03 1.23703540e+03 1.26521191e+03 1.25774829e+03 1.28992932e+03 1.35967810e+03 1.43089844e+03 1.44428357e+03 1.39183508e+03 1.42978442e+03 1.51821155e+03 1.53715295e+03 1.55216565e+03 1.58815283e+03 1.60541699e+03 1.65280005e+03 1.69336914e+03 1.72763049e+03 1.75062488e+03 1.78187463e+03 1.83505042e+03 1.83849658e+03 1.85300806e+03 1.88695251e+03 1.92429089e+03 1.97999976e+03 2.05458276e+03 2.05134375e+03 2.02729980e+03 2.09783813e+03 2.15570605e+03 2.23379297e+03 2.25400366e+03 2.20093945e+03 2.26368774e+03 2.32791919e+03 2.38288940e+03 2.45710571e+03 2.44602319e+03 2.44654468e+03 2.49656812e+03 2.50925732e+03 2.52065234e+03 2.63957983e+03 2.72886133e+03 2.69190576e+03 2.69884741e+03 2.72070483e+03 2.77283276e+03 2.89933691e+03 2.93881104e+03 2.94487598e+03 2.95800659e+03 2.92488867e+03 3.01133765e+03 3.07944507e+03 3.18130737e+03 3.24156860e+03 3.15949902e+03 3.19084399e+03 3.28423438e+03 3.34219385e+03 3.38259863e+03 3.44728418e+03 3.49623486e+03 3.45738989e+03 3.50638281e+03 3.56311133e+03 3.60554736e+03 3.67224756e+03 3.73652783e+03 3.76307104e+03 3.78548877e+03 3.79879858e+03 3.87266699e+03 3.99850928e+03 3.99697070e+03 3.95708838e+03 4.00232129e+03 4.06808301e+03 4.10317090e+03 4.30019092e+03 4.35383691e+03 4.20397900e+03 4.27965625e+03 4.29208203e+03 4.38805420e+03 4.59784375e+03 4.66618164e+03 4.44795654e+03 4.18969629e+03 5.70330273e+03 6.32728467e+03 7.18611377e+03 7.42832422e+03 7.87763965e+03 7.45674023e+03 1.14705068e+04 2.10582188e+04 4.65230450e+06 -93729688. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -31759844. 3.06536660e+04 1.14017871e+04 1.08005889e+04 9.26095703e+03 1.10024502e+04 8.36713770e+03 7.27788965e+03 7.35274561e+03 7.74749463e+03 7.68228027e+03 7.49606104e+03 7.38325781e+03 7.47150439e+03 7.76750049e+03 7.92113184e+03 7.88856250e+03 7.72671875e+03 7.72001514e+03 7.80120166e+03 8.07326807e+03 8.05940527e+03 7.81389014e+03 7.96948926e+03 8.26543262e+03 8.23992871e+03 8.11065576e+03 8.02988037e+03 8.33493164e+03 8.76320605e+03 8.76732812e+03 8.28053809e+03 8.00438525e+03 8.32399414e+03 8.75564355e+03 8.98145117e+03 8.89280273e+03 8.51350098e+03 8.64885938e+03 8.84662500e+03 9.13840430e+03 9.05093066e+03 8.63310449e+03 8.80694238e+03 9.32906641e+03 9.23391504e+03 9.05990039e+03 9.16715234e+03 9.26275098e+03 9.39462793e+03 9.44937109e+03 9.17248438e+03 9.10735254e+03 9.54945312e+03 9.89413672e+03 9.75617188e+03 9.47272461e+03 9.23363965e+03 9.72195996e+03 1.01393037e+04 9.97571680e+03 9.66547070e+03 9.37353711e+03 9.59611816e+03 1.01861787e+04 1.03483701e+04 1.02498877e+04 1.00936768e+04 1.01303936e+04 1.00491709e+04 1.01744580e+04 1.03042959e+04 1.00416133e+04 1.02546787e+04 1.06672168e+04 1.05579922e+04 1.00954600e+04 1.00860332e+04 1.06542783e+04 1.10491816e+04 1.08854854e+04 1.05898320e+04 1.03574072e+04 1.03981562e+04 1.07342031e+04 1.12451953e+04 1.11186182e+04 1.05622949e+04 1.07398467e+04 1.09790996e+04 1.10977266e+04 1.13286895e+04 1.09712715e+04 1.09675596e+04 1.13342363e+04 1.13515693e+04 1.11620762e+04 1.10516230e+04 1.12882295e+04 1.15421523e+04 1.15250654e+04 1.12662275e+04 1.11132588e+04 1.14866182e+04 1.18788428e+04 1.18116104e+04 1.15866221e+04 1.13122686e+04 1.15694805e+04 1.19587842e+04 1.19867324e+04 1.17537051e+04 1.13591084e+04 1.14892568e+04 1.20645566e+04 1.23730420e+04 1.21541143e+04 1.16148350e+04 1.18085117e+04 1.22295938e+04 1.21631143e+04 1.19376367e+04 1.18029307e+04 1.22947461e+04 1.25605693e+04 1.22002627e+04 1.20597139e+04 1.19595869e+04 1.23396416e+04 1.28673506e+04 1.26602432e+04 1.22917031e+04 1.21504355e+04 1.22814121e+04 1.25002217e+04 1.28005771e+04 1.27147598e+04 1.21805684e+04 1.22578213e+04 1.28278262e+04 1.30177373e+04 1.27527178e+04 1.24915107e+04 1.26549932e+04 1.29639990e+04 1.29903008e+04 1.28053662e+04 1.23971963e+04 1.25619648e+04 1.31069062e+04 1.31206250e+04 1.29298740e+04 1.26578604e+04 1.27564941e+04 1.31203896e+04 1.34647246e+04 1.33272627e+04 1.27644629e+04 1.28355811e+04 1.31296279e+04 1.32294150e+04 1.32305029e+04 1.30175068e+04 1.32217197e+04 1.32446191e+04 1.31160127e+04 1.31277207e+04 1.30630361e+04 1.34583564e+04 1.36685342e+04 1.34362988e+04 1.31036367e+04 1.29115303e+04 1.33825117e+04 1.38812803e+04 1.37648291e+04 1.34427852e+04 1.30583350e+04 1.28921035e+04 1.33916602e+04 1.40869258e+04 1.37293926e+04 1.30084775e+04 1.31968525e+04 1.37007129e+04 1.38104023e+04 1.37498564e+04 1.34884893e+04 1.34883945e+04 1.36781543e+04 1.35130156e+04 1.33776826e+04 1.35132129e+04 1.37562119e+04 1.37499463e+04 1.36366475e+04 1.35340674e+04 1.34716670e+04 1.37495186e+04 1.40240898e+04 1.39354990e+04 1.34306533e+04 1.32236846e+04 1.38036064e+04 1.40925176e+04 1.39165928e+04 1.36945273e+04 1.32747500e+04 1.33411338e+04 1.40002842e+04 1.43464326e+04 1.40771836e+04 1.34611777e+04 1.33368311e+04 1.38084014e+04 1.40406260e+04 1.38904287e+04 1.38100723e+04 1.39254346e+04 1.38219863e+04 1.36085889e+04 1.33351719e+04 1.32695967e+04 1.36251338e+04 1.38964854e+04 1.43209707e+04 1.40558848e+04 1.33228125e+04 1.35627246e+04 1.37771445e+04 1.37323340e+04 1.38807051e+04 1.37328730e+04 1.40700879e+04 1.40352129e+04 1.33144600e+04 1.31438438e+04 1.34522168e+04 1.40679062e+04 1.45101357e+04 1.41605234e+04 1.33699307e+04 1.29678330e+04 1.33164043e+04 1.40604678e+04 1.44193594e+04 1.40411396e+04 1.33175410e+04 1.32264658e+04 1.40513057e+04 1.41329561e+04 1.33557842e+04 1.33206699e+04 1.35636055e+04 1.35453340e+04 1.39876035e+04 1.36464287e+04 1.31554521e+04 1.35201055e+04 1.32206592e+04 1.35079111e+04 1.38942734e+04 1.31776729e+04 1.34579385e+04 1.38697988e+04 1.35018379e+04 1.34541270e+04 1.34277539e+04 1.34680693e+04 1.35121035e+04 1.34200361e+04 1.30582129e+04 1.30135488e+04 1.35839736e+04 1.39811162e+04 1.36800088e+04 1.30403301e+04 1.27220488e+04 1.29262686e+04 1.35319834e+04 1.39090371e+04 1.36003984e+04 1.28612012e+04 1.28409395e+04 1.33142959e+04 1.32279395e+04 1.30481045e+04 1.29874609e+04 1.29827939e+04 1.30107715e+04 1.34348955e+04 1.30788564e+04 1.26622227e+04 1.29521641e+04 1.26009893e+04 1.29568594e+04 1.32043232e+04 1.28437412e+04 1.32510898e+04 1.28394434e+04 1.23796436e+04 1.27591201e+04 1.24319824e+04 1.26563350e+04 1.34772959e+04 1.27399365e+04 1.20372861e+04 1.22661836e+04 1.28079189e+04 1.32769482e+04 1.29534258e+04 1.21536807e+04 1.18333193e+04 1.21379014e+04 1.26871846e+04 1.31091650e+04 1.27583848e+04 1.20391719e+04 1.19307559e+04 1.23369355e+04 1.24793438e+04 1.21546406e+04 1.19564863e+04 1.21298428e+04 1.21818643e+04 1.24303887e+04 1.24202715e+04 1.17699414e+04 1.17448555e+04 1.18727930e+04 1.18913799e+04 1.19991367e+04 1.19013613e+04 1.20969287e+04 1.18992393e+04 1.14772422e+04 1.16377148e+04 1.13584385e+04 1.16713994e+04 1.23653320e+04 1.16541934e+04 1.08964990e+04 1.11429521e+04 1.16766426e+04 1.19907236e+04 1.19048340e+04 1.12629434e+04 1.07668535e+04 1.09199746e+04 1.14735830e+04 1.18990742e+04 1.15455625e+04 1.08636738e+04 1.07092959e+04 1.09621758e+04 1.11719229e+04 1.14070215e+04 1.13074883e+04 1.06787891e+04 1.05528564e+04 1.10525020e+04 1.11276904e+04 1.06893535e+04 1.06148994e+04 1.05501895e+04 1.04770078e+04 1.09206348e+04 1.09370137e+04 1.03480967e+04 1.02317217e+04 1.03441445e+04 1.03520996e+04 1.04110371e+04 1.02774600e+04 1.05044775e+04 1.05562861e+04 1.01535342e+04 9.91314355e+03 9.67576074e+03 1.00265088e+04 1.05796670e+04 1.03121992e+04 9.69771289e+03 9.43491309e+03 9.77948633e+03 1.02926914e+04 9.89697559e+03 9.27290625e+03 9.41842383e+03 9.60403906e+03 9.81387109e+03 1.00800352e+04 9.78429688e+03 9.21704492e+03 8.95421289e+03 9.25621484e+03 9.53894434e+03 9.48953027e+03 9.26773047e+03 9.15478125e+03 9.09450488e+03 9.25192480e+03 9.12589062e+03 8.81116406e+03 8.70062598e+03 8.67731348e+03 9.04831055e+03 9.12720996e+03 8.75441309e+03 8.74695215e+03 8.73938574e+03 8.83178613e+03 8.62283887e+03 8.14702637e+03 8.44236035e+03 8.83004199e+03 8.58891602e+03 8.11272803e+03 8.10615479e+03 8.51351270e+03 8.49593066e+03 8.20188574e+03 8.15336768e+03 7.88003809e+03 7.85504932e+03 8.21451855e+03 8.14458887e+03 7.73446631e+03 7.53714355e+03 7.50290869e+03 7.82823486e+03 8.12081152e+03 7.71191797e+03 7.43975098e+03 7.54859912e+03 7.51317529e+03 7.69848828e+03 7.59816406e+03 7.08460742e+03 7.18014648e+03 7.32728613e+03 7.21876270e+03 7.20768018e+03 7.11407227e+03 7.30755273e+03 7.38009326e+03 7.11043994e+03 6.96447705e+03 6.35222900e+03 8.65831543e+03 1.00044287e+04 1.04039102e+04 9.83125977e+03 9.62101367e+03 9.94904980e+03 1.02684189e+04 1.06915752e+04 1.09417061e+04 9.68762793e+03 9.50835938e+03 1.86100059e+04 1.13393438e+05 45702096. 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. 0. 0. 0. 0. 0. 0. 0. 0. -89117784. 4.86425950e+06 2.94627025e+06 1.52269688e+04 1.09427314e+04 4.82855029e+03 5.03779004e+03 4.53197852e+03 4.40317139e+03 4.18235010e+03 4.22614600e+03 4.07090601e+03 3.89723413e+03 3.95936694e+03 3.90583081e+03 3.96752344e+03 3.96593823e+03 3.57909814e+03 3.49060132e+03 3.51964722e+03 3.56449097e+03 3.47860156e+03 3.37801733e+03 3.56883813e+03 3.44829492e+03 3.31202197e+03 3.42260669e+03 3.35977051e+03 3.21526953e+03 3.27833496e+03 3.34640381e+03 3.22027734e+03 3.14857202e+03 3.08465063e+03 3.03958203e+03 2.97103540e+03 2.93544873e+03 2.96215894e+03 2.93364502e+03 2.84845093e+03 2.80471216e+03 2.77462891e+03 2.73535815e+03 2.68390112e+03 2.64638892e+03 2.61337842e+03 2.50362378e+03 2.45719800e+03 2.48628101e+03 2.44746875e+03 2.50131665e+03 2.47093164e+03 2.34999023e+03 2.24653809e+03 2.20445801e+03 2.31454736e+03 2.29767847e+03 2.17709229e+03 2.09519067e+03 2.06866968e+03 2.07264990e+03 2.02128540e+03 2.05431104e+03 2.02030542e+03 1.87282361e+03 1.82164014e+03 1.89057764e+03 1.92726880e+03 1.84376257e+03 1.77036914e+03 1.74588000e+03 1.71028430e+03 1.65453625e+03 1.63270166e+03 1.60614722e+03 1.56375684e+03 1.54273352e+03 1.51294580e+03 1.49651331e+03 1.46471753e+03 1.46610840e+03 1.43134387e+03 1.35960547e+03 1.34880908e+03 1.32559741e+03 1.30772876e+03 1.27995508e+03 1.24144836e+03 1.21382275e+03 1.16070215e+03 1.10715027e+03 1.13769543e+03 1.12614368e+03 1.04209998e+03 1.02580847e+03 1.05761768e+03 1.05985559e+03 1.00216089e+03 9.51281921e+02 9.24909119e+02 9.00111023e+02 8.68235474e+02 8.42331909e+02 8.37877991e+02 8.12222290e+02 8.08911682e+02 7.80906128e+02 7.39219116e+02 7.29263489e+02 6.88940369e+02 6.69103760e+02 6.84541504e+02 6.58175049e+02 6.23442993e+02 5.90254700e+02 5.62262451e+02 5.74917175e+02 5.66405579e+02 5.29315674e+02 4.95811493e+02 4.79307068e+02 4.73562317e+02 4.53655792e+02 4.50642181e+02 4.37633820e+02 4.05810455e+02 3.82676361e+02 3.68782471e+02 3.68388306e+02 3.53177094e+02 3.29089691e+02 3.11083130e+02 2.97639435e+02 2.88094971e+02 2.67964783e+02 2.55808365e+02 2.56720123e+02 2.42452316e+02 2.24518814e+02 2.07171600e+02 1.94383881e+02 1.94602371e+02 1.84748444e+02 1.69022476e+02 1.54870209e+02 1.44264404e+02 1.38857224e+02 1.29987000e+02 1.20928635e+02 1.09719528e+02 1.03835533e+02 1.00670151e+02 9.07049255e+01 8.26120148e+01 7.58799744e+01 6.88697891e+01 6.18222504e+01 5.58642197e+01 5.10445976e+01 4.58998985e+01 4.10295067e+01 3.58138924e+01 3.21802330e+01 2.95407715e+01 2.51100044e+01 2.14733086e+01 1.89314060e+01 1.63936443e+01 1.44515858e+01 1.24879675e+01 1.08578405e+01 9.79561996e+00 8.94795609e+00 8.42939949e+00 8.26476765e+00 8.45811749e+00 9.00106239e+00 9.86228752e+00 1.10359840e+01 1.24064007e+01 1.43128014e+01 1.69675331e+01 1.93250923e+01 2.17929420e+01 2.44824600e+01 2.81731930e+01 3.34497108e+01 3.76209488e+01 4.12860832e+01 4.51492500e+01 5.00090141e+01 5.69360619e+01 6.27525215e+01 7.01939850e+01 7.54967499e+01 7.99814301e+01 8.94177933e+01 9.71836853e+01 1.06937096e+02 1.15087120e+02 1.21146461e+02 1.30139069e+02 1.39158096e+02 1.50333359e+02 1.56544434e+02 1.67934525e+02 1.87146973e+02 1.94424622e+02 2.01252335e+02 2.07849915e+02 2.17947571e+02 2.42103302e+02 2.56442078e+02 2.61848602e+02 2.67259125e+02 2.80356232e+02 3.03580383e+02 3.18130463e+02 3.39587555e+02 3.50151611e+02 3.56502991e+02 3.67887115e+02 3.81713379e+02 4.18800690e+02 4.33263855e+02 4.36640930e+02 4.51972870e+02 4.69877808e+02 5.02009918e+02 5.20028748e+02 5.17072693e+02 5.33813599e+02 5.78892212e+02 5.97476379e+02 5.90621704e+02 6.07315735e+02 6.59661194e+02 6.83496033e+02 6.81291748e+02 6.86464111e+02 7.06631042e+02 7.69999207e+02 7.86883423e+02 7.85697144e+02 8.13492188e+02 8.33565796e+02 8.57500488e+02 8.77394836e+02 8.99014771e+02 9.01389587e+02 9.49873901e+02 1.02679932e+03 1.02120490e+03 1.03372034e+03 1.06799280e+03 1.08492224e+03 1.11030200e+03 1.13358325e+03 1.15620288e+03 1.15381213e+03 1.16541760e+03 1.22060376e+03 1.27528296e+03 1.34729700e+03 1.32937756e+03 1.30996509e+03 1.37258398e+03 1.41846021e+03 1.48924707e+03 1.49418860e+03 1.48712219e+03 1.50677405e+03 1.52171350e+03 1.58524194e+03 1.62288354e+03 1.68383032e+03 1.71208813e+03 1.70523083e+03 1.71509595e+03 1.69742554e+03 1.80127759e+03 1.93626050e+03 1.93239771e+03 1.90727856e+03 1.89167883e+03 1.89794897e+03 2.03136108e+03 2.12737769e+03 2.10162354e+03 2.05134839e+03 2.08725684e+03 2.17709863e+03 2.21015259e+03 2.31056763e+03 2.33172656e+03 2.29822046e+03 2.34636523e+03 2.37977319e+03 2.46234448e+03 2.51054541e+03 2.43749097e+03 2.47774072e+03 2.65759863e+03 2.63404492e+03 2.53576587e+03 2.66533203e+03 2.85478467e+03 2.83912842e+03 2.79645874e+03 2.77018823e+03 2.81513330e+03 3.01438306e+03 3.05188135e+03 2.99806763e+03 2.96807739e+03 2.98923486e+03 3.11749878e+03 3.16558643e+03 3.20358789e+03 3.16560156e+03 3.27774048e+03 3.46986475e+03 3.41289575e+03 3.45254736e+03 3.48808618e+03 3.44985181e+03 3.53171533e+03 3.59008203e+03 3.62035181e+03 3.63911255e+03 3.65483838e+03 3.63219385e+03 3.76552271e+03 4.02026758e+03 3.87226245e+03 3.76663696e+03 3.91889697e+03 4.03142676e+03 4.20845850e+03 4.16617188e+03 4.09114429e+03 4.24727539e+03 4.31011328e+03 4.13923633e+03 4.16731543e+03 4.43683545e+03 4.52603906e+03 4.44076074e+03 4.39113672e+03 4.31100049e+03 4.56033887e+03 4.87492139e+03 4.81035645e+03 4.69629688e+03 4.62447656e+03 4.65366406e+03 4.91724951e+03 5.16076025e+03 5.02681006e+03 4.86204346e+03 4.86285059e+03 5.03866992e+03 5.15826709e+03 5.35408789e+03 5.27182812e+03 5.17894971e+03 5.35232422e+03 5.38000244e+03 5.51237549e+03 5.52276758e+03 5.47174072e+03 5.55858594e+03 5.58081055e+03 5.61395459e+03 5.49799414e+03 5.63518652e+03 6.06567627e+03 5.98733838e+03 5.81820020e+03 5.74088086e+03 5.83537109e+03 6.24575293e+03 6.25005713e+03 6.11383398e+03 6.02826514e+03 6.00697070e+03 6.28466748e+03 6.31681543e+03 6.38320068e+03 6.27660400e+03 6.42939697e+03 6.74717578e+03 6.63949023e+03 6.70381055e+03 6.76108545e+03 6.66541455e+03 6.69223730e+03 6.73086719e+03 6.78646289e+03 6.83809326e+03 6.91364355e+03 6.96354883e+03 7.15984521e+03 7.23553076e+03 6.96949561e+03 6.88918311e+03 7.17348730e+03 7.38009033e+03 7.57142529e+03 7.46568604e+03 7.12562402e+03 7.53114111e+03 7.77926416e+03 7.59439209e+03 7.48271045e+03 7.49621484e+03 7.69128369e+03 7.79959717e+03 7.76397266e+03 7.56219092e+03 7.82975000e+03 8.31478711e+03 8.16449805e+03 8.09370264e+03 7.93054688e+03 7.92704053e+03 8.43869238e+03 8.43252344e+03 8.26539844e+03 8.13147607e+03 7.99199951e+03 8.27918555e+03 8.59764453e+03 8.95932422e+03 8.58918066e+03 8.26556445e+03 8.59707227e+03 8.74163867e+03 9.03921875e+03 8.93202734e+03 8.63152441e+03 8.93262012e+03 8.98595312e+03 8.83834961e+03 8.67383984e+03 9.02680859e+03 9.49196777e+03 9.32333496e+03 9.25895117e+03 9.09956934e+03 9.04290430e+03 9.59511523e+03 9.67334766e+03 9.40956543e+03 9.24838672e+03 9.23317773e+03 9.55211621e+03 9.58129883e+03 9.84123438e+03 9.95513574e+03 9.65900586e+03 9.53628418e+03 9.69812598e+03 1.02410439e+04 1.00152363e+04 9.77672070e+03 1.00226484e+04 1.00789717e+04 9.94978711e+03 9.84475684e+03 1.02935977e+04 1.03225762e+04 1.00802256e+04 1.05352090e+04 1.06542578e+04 1.04457842e+04 1.04288047e+04 1.04558281e+04 1.04971455e+04 1.02991455e+04 1.02090488e+04 1.07934277e+04 1.10089131e+04 1.04412529e+04 1.01670400e+04 1.06927832e+04 1.13698184e+04 1.12654932e+04 1.07456621e+04 1.05329756e+04 1.11250508e+04 1.13354473e+04 1.10597959e+04 1.11779375e+04 1.09182588e+04 1.06140010e+04 1.11208135e+04 1.16416143e+04 1.16231357e+04 1.12059873e+04 1.09182100e+04 1.15150654e+04 1.19388818e+04 1.16046650e+04 1.11550732e+04 1.10710010e+04 1.14789268e+04 1.15722119e+04 1.19123428e+04 1.19233633e+04 1.14982344e+04 1.16789893e+04 1.18294111e+04 1.20435654e+04 1.17257607e+04 1.15231875e+04 1.20718154e+04 1.20943916e+04 1.20114443e+04 1.17285742e+04 1.18686016e+04 1.25789795e+04 1.21286621e+04 1.16777520e+04 1.20004287e+04 1.23133008e+04 1.23600127e+04 1.22398428e+04 1.25424453e+04 1.26854961e+04 1.23533770e+04 1.20328135e+04 1.20339111e+04 1.27226729e+04 1.25392100e+04 1.21763223e+04 1.26499160e+04 1.27021465e+04 1.24992832e+04 1.23809561e+04 1.28244453e+04 1.27637061e+04 1.24304492e+04 1.27940156e+04 1.28345586e+04 1.29386865e+04 1.29744453e+04 1.28247549e+04 1.27412607e+04 1.24470527e+04 1.24066631e+04 1.30408594e+04 1.35601875e+04 1.29242236e+04 1.23030293e+04 1.28214277e+04 1.36160430e+04 1.35373408e+04 1.28925898e+04 1.24746641e+04 1.31113965e+04 1.35457441e+04 1.31387227e+04 1.33827422e+04 1.33331846e+04 1.28340635e+04 1.29870332e+04 1.34969717e+04 1.36146104e+04 1.30487588e+04 1.27409893e+04 1.33495029e+04 1.39381729e+04 1.35950801e+04 1.30508086e+04 1.28226826e+04 1.34827871e+04 1.39387490e+04 1.34702686e+04 1.31669844e+04 1.32527676e+04 1.35155010e+04 1.34523623e+04 1.38213701e+04 1.35778652e+04 1.31217324e+04 1.36280459e+04 1.36972646e+04 1.37701582e+04 1.34756416e+04 1.32236191e+04 1.38106982e+04 1.38503643e+04 1.41526650e+04 1.35205537e+04 1.36348633e+04 1.81499648e+04 1.80454961e+04 2.11001777e+04 2.11955605e+04 1.84217773e+04 1.55386270e+04 1.32109336e+04 1.57871924e+04 1.81467969e+04 1.80643340e+04 2.14112715e+04 2.43048242e+04 2.95538105e+04 1.39315500e+05 2.50134042e+09 0. 0. 0. 0. 0. 0. 0. 0. 8.51706184e+11 1.75052938e+05 4.20238828e+04 1.65340938e+05 -7.86057462e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.34501181e+10 2.07796906e+05 4.87555664e+04 3.41279297e+04 2.30865742e+04 2.12355020e+04 2.06659727e+04 1.70006895e+04 1.23987344e+04 1.47782197e+04 1.36994805e+04 1.36981865e+04 1.35246602e+04 1.36018701e+04 1.40363594e+04 1.40864346e+04 1.35283135e+04 1.33600537e+04 1.36689561e+04 1.36579180e+04 1.35711914e+04 1.35894736e+04 1.34895000e+04 1.33814316e+04 1.36960420e+04 1.38129922e+04 1.32288047e+04 1.32005459e+04 1.36693389e+04 1.37682334e+04 1.37108516e+04 1.33834238e+04 1.31120342e+04 1.34561787e+04 1.35046943e+04 1.32972812e+04 1.32272812e+04 1.32109414e+04 1.35535791e+04 1.35105166e+04 1.32679082e+04 1.31524238e+04 1.31922021e+04 1.36684258e+04 1.35852910e+04 1.29402188e+04 1.29226328e+04 1.31394277e+04 1.31969326e+04 1.33663164e+04 1.32461367e+04 1.29608184e+04 1.31385986e+04 1.31827051e+04 1.31135898e+04 1.31365488e+04 1.28838330e+04 1.29628340e+04 1.31053652e+04 1.29029307e+04 1.28411729e+04 1.27788574e+04 1.28274229e+04 1.30305293e+04 1.30455039e+04 1.29382168e+04 1.26578340e+04 1.25017100e+04 1.28354834e+04 1.28680957e+04 1.25382764e+04 1.25838818e+04 1.26001445e+04 1.26723291e+04 1.28824229e+04 1.27404023e+04 1.23660527e+04 1.23254111e+04 1.26452441e+04 1.27174883e+04 1.23560449e+04 1.21074844e+04 1.22201582e+04 1.23496182e+04 1.26174297e+04 1.25430361e+04 1.20458721e+04 1.20740156e+04 1.23881553e+04 1.23346943e+04 1.22081826e+04 1.19329795e+04 1.18231670e+04 1.21799980e+04 1.22165078e+04 1.18585059e+04 1.18628018e+04 1.19394531e+04 1.19072461e+04 1.18529658e+04 1.17886152e+04 1.18702285e+04 1.18261709e+04 1.19198506e+04 1.18902480e+04 1.14339453e+04 1.13967207e+04 1.16560234e+04 1.15166885e+04 1.14801074e+04 1.14390312e+04 1.14212852e+04 1.15765771e+04 1.14150938e+04 1.12378906e+04 1.13753994e+04 1.14592061e+04 1.11784199e+04 1.10950586e+04 1.11635508e+04 1.11646768e+04 1.10573447e+04 1.09058291e+04 1.09302812e+04 1.09608457e+04 1.11699258e+04 1.10695420e+04 1.06154121e+04 1.06443564e+04 1.08956465e+04 1.08379541e+04 1.06785215e+04 1.05308857e+04 1.03705703e+04 1.05622979e+04 1.07684775e+04 1.05479238e+04 1.03071621e+04 1.02562588e+04 1.04673955e+04 1.05108174e+04 1.05017666e+04 1.02231699e+04 9.92528809e+03 1.00631738e+04 1.00476055e+04 9.99845020e+03 1.00744639e+04 9.88441895e+03 9.94525391e+03 1.01811045e+04 9.96985742e+03 9.53428809e+03 9.54298535e+03 9.71025391e+03 9.75855469e+03 9.79868164e+03 9.63285254e+03 9.38055469e+03 9.41584277e+03 9.67579980e+03 9.40882129e+03 9.07540723e+03 9.21881250e+03 9.41305273e+03 9.34379297e+03 9.14087109e+03 8.98356152e+03 8.94122656e+03 9.00016113e+03 8.94582910e+03 8.95024219e+03 9.02425000e+03 8.78550195e+03 8.80077637e+03 8.93741016e+03 8.70060156e+03 8.53161035e+03 8.57957910e+03 8.66735156e+03 8.60884180e+03 8.53514160e+03 8.33113184e+03 8.20800879e+03 8.29992871e+03 8.61635449e+03 8.56300879e+03 8.00622119e+03 7.97421680e+03 8.27592383e+03 8.18896045e+03 7.96641162e+03 7.88011816e+03 7.80165430e+03 7.89651172e+03 7.96178516e+03 7.78351367e+03 7.66289062e+03 7.52939600e+03 7.62130615e+03 7.74628711e+03 7.68707910e+03 7.46790625e+03 7.38560938e+03 7.43014453e+03 7.39623047e+03 7.28725879e+03 7.18851562e+03 7.17444238e+03 7.12515186e+03 7.24119873e+03 7.26124023e+03 6.87125293e+03 6.83749805e+03 6.97160107e+03 6.95593262e+03 6.89839111e+03 6.67764307e+03 6.71019824e+03 6.84091992e+03 6.65487354e+03 6.62192920e+03 6.44101953e+03 6.30414844e+03 6.44253418e+03 6.53771729e+03 6.37340479e+03 6.31113281e+03 6.31171973e+03 6.20300391e+03 6.26095215e+03 6.20034863e+03 5.97526904e+03 5.88890527e+03 5.88036621e+03 5.99508203e+03 5.92255176e+03 5.78297852e+03 5.73740234e+03 5.80140771e+03 5.77258643e+03 5.62170117e+03 5.51676270e+03 5.49931445e+03 5.53505371e+03 5.45565576e+03 5.55405713e+03 5.36676416e+03 5.22272461e+03 5.30637549e+03 5.15067529e+03 5.15241992e+03 5.17740381e+03 5.03996094e+03 4.98607129e+03 4.93486035e+03 4.93110791e+03 4.90074414e+03 4.74559961e+03 4.88695264e+03 4.92267090e+03 4.64886621e+03 4.57502051e+03 4.59670068e+03 4.56942334e+03 4.61099463e+03 4.51249268e+03 4.36130029e+03 4.36015039e+03 4.42423682e+03 4.34500049e+03 4.27090088e+03 4.18101709e+03 4.14327295e+03 4.15913281e+03 4.06425317e+03 4.00703271e+03 3.95761694e+03 3.90610718e+03 3.90217554e+03 3.92491626e+03 3.84794873e+03 3.74204810e+03 3.67639087e+03 3.72841382e+03 3.75973828e+03 3.57742676e+03 3.57561548e+03 3.56057983e+03 3.39859912e+03 3.44398267e+03 3.43538159e+03 3.33318750e+03 3.32854565e+03 3.29491211e+03 3.22694043e+03 3.25245654e+03 3.16813989e+03 3.07400317e+03 3.06419580e+03 3.05954785e+03 3.03690405e+03 2.90998315e+03 2.87597803e+03 2.88717114e+03 2.87223047e+03 2.83178247e+03 2.75348511e+03 2.68343286e+03 2.71705957e+03 2.74005493e+03 2.62363525e+03 2.53786279e+03 2.50102148e+03 2.52978711e+03 2.53003979e+03 2.42045508e+03 2.36460107e+03 2.35090039e+03 2.32670288e+03 2.27955396e+03 2.27713647e+03 2.21776587e+03 2.13693579e+03 2.15245874e+03 2.16503345e+03 2.08351416e+03 1.97436304e+03 1.96470776e+03 1.98844580e+03 1.96035120e+03 1.92497241e+03 1.87364392e+03 1.81942017e+03 1.83424609e+03 1.83389307e+03 1.75190710e+03 1.70020032e+03 1.67738525e+03 1.69039612e+03 1.63941492e+03 1.55355908e+03 1.52864050e+03 1.52140527e+03 1.50144055e+03 1.47528650e+03 1.45401245e+03 1.40631677e+03 1.38295996e+03 1.35635120e+03 1.30335767e+03 1.27546826e+03 1.24493347e+03 1.24160620e+03 1.23630725e+03 1.17870923e+03 1.13381946e+03 1.12264551e+03 1.11742480e+03 1.11949097e+03 1.08546973e+03 1.01423639e+03 9.91290710e+02 9.81435303e+02 9.54520935e+02 9.21127441e+02 8.98370117e+02 8.83341858e+02 8.64001709e+02 8.33501343e+02 7.94118347e+02 7.85585876e+02 7.84295959e+02 7.64323364e+02 7.31183167e+02 6.91095398e+02 6.75933838e+02 6.52269043e+02 6.28334473e+02 6.35889648e+02 6.17105103e+02 5.74449158e+02 5.52903320e+02 5.42685425e+02 5.40417786e+02 5.25153259e+02 4.96602600e+02 4.73797363e+02 4.55291412e+02 4.37033997e+02 4.18408783e+02 4.07845490e+02 3.94101379e+02 3.81488495e+02 3.64573761e+02 3.36313019e+02 3.26696564e+02 3.16058044e+02 3.01377686e+02 2.95878967e+02 2.75076538e+02 2.56295898e+02 2.52991730e+02 2.44281937e+02 2.27814590e+02 2.14665146e+02 2.00223053e+02 1.86405045e+02 1.77844360e+02 1.70396149e+02 1.60501953e+02 1.52930496e+02 1.44414795e+02 1.32354156e+02 1.21260445e+02 1.12546074e+02 1.06499382e+02 1.00683578e+02 9.17455215e+01 8.24755478e+01 7.58009109e+01 7.05736542e+01 6.61220093e+01 6.11009369e+01 5.39508553e+01 4.74125824e+01 4.28626442e+01 3.83295364e+01 3.41952820e+01 3.15411434e+01 2.82713470e+01 2.44921074e+01 2.14341927e+01 1.87800121e+01 1.68795033e+01 1.53685579e+01 1.38033466e+01 1.24413443e+01 1.15629654e+01 1.10959530e+01 1.09579811e+01 1.11362858e+01 1.16744413e+01 1.25804186e+01 1.38336287e+01 1.52951269e+01 1.73398018e+01 1.96313000e+01 2.19256439e+01 2.47671356e+01 2.78005390e+01 3.12594452e+01 3.54880638e+01 3.97583237e+01 4.45046959e+01 4.92368774e+01 5.35606880e+01 5.91327667e+01 6.47574692e+01 7.10320969e+01 7.75911484e+01 8.50731277e+01 9.30115356e+01 1.00612831e+02 1.08321281e+02 1.14916054e+02 1.24592537e+02 1.35996246e+02 1.44899109e+02 1.51231323e+02 1.60558685e+02 1.71461380e+02 1.81635696e+02 1.94242996e+02 2.06100708e+02 2.15211243e+02 2.26931763e+02 2.39522812e+02 2.51521774e+02 2.66569366e+02 2.77984863e+02 2.91766724e+02 3.07169312e+02 3.17346619e+02 3.34205078e+02 3.43884399e+02 3.59819427e+02 3.87360596e+02 3.95758575e+02 4.06527435e+02 4.29940277e+02 4.40355408e+02 4.52551697e+02 4.89056458e+02 5.08119446e+02 5.04305511e+02 5.23436951e+02 5.49000244e+02 5.63072510e+02 5.92419250e+02 6.09690247e+02 6.12216187e+02 6.40245483e+02 6.66811279e+02 6.95427734e+02 7.17847168e+02 7.25301270e+02 7.57404907e+02 7.72982178e+02 7.75905945e+02 8.08067871e+02 8.51337952e+02 8.67801453e+02 8.94610413e+02 9.17747314e+02 9.04822876e+02 9.44539551e+02 1.00589886e+03 1.02982227e+03 1.03643909e+03 1.02368518e+03 1.06119885e+03 1.13246863e+03 1.14706506e+03 1.15617603e+03 1.20035962e+03 1.21280615e+03 1.24052393e+03 1.28029004e+03 1.26484131e+03 1.29862415e+03 1.36598132e+03 1.41168225e+03 1.42293726e+03 1.40852246e+03 1.43838403e+03 1.50668530e+03 1.55957312e+03 1.57348584e+03 1.56868799e+03 1.58076221e+03 1.63654175e+03 1.69988318e+03 1.75865662e+03 1.76526147e+03 1.75257068e+03 1.80347534e+03 1.83132507e+03 1.86292053e+03 1.91765503e+03 1.92977380e+03 1.97605542e+03 2.04089709e+03 2.03979932e+03 2.06133521e+03 2.11901538e+03 2.14609814e+03 2.19833203e+03 2.21836255e+03 2.21474243e+03 2.25726489e+03 2.33097583e+03 2.40536230e+03 2.44721509e+03 2.43085010e+03 2.42059863e+03 2.49062573e+03 2.51944458e+03 2.56746094e+03 2.65875244e+03 2.64702612e+03 2.64883716e+03 2.70043848e+03 2.75668848e+03 2.83294678e+03 2.91954077e+03 2.92857178e+03 2.92975830e+03 2.93696094e+03 2.91737573e+03 3.00456592e+03 3.11127612e+03 3.17553198e+03 3.20910767e+03 3.16024390e+03 3.18278833e+03 3.28379980e+03 3.36363281e+03 3.38377197e+03 3.42801611e+03 3.43699341e+03 3.42188428e+03 3.53121509e+03 3.64544849e+03 3.65099805e+03 3.61055273e+03 3.67813574e+03 3.74155615e+03 3.81354858e+03 3.87243066e+03 3.86367334e+03 3.97345117e+03 3.94639282e+03 3.95467505e+03 4.08718335e+03 4.11693896e+03 4.12716113e+03 4.26690820e+03 4.26253857e+03 4.20472021e+03 4.31687646e+03 4.41705029e+03 4.46160645e+03 4.95675049e+03 4.94224951e+03 5.19806445e+03 4.76282080e+03 9.92969727e+03 1.30326846e+04 -8.30591750e+06 -3.42624325e+06 -1.93987275e+06 -2.19383075e+06 -11513898. 26795030. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 49187952. 2.34669375e+06 2.67535293e+04 1.30520352e+04 7.55102637e+03 7.04804639e+03 6.79559033e+03 7.89439990e+03 7.82729541e+03 7.19034912e+03 7.31931787e+03 7.65653906e+03 7.59645703e+03 7.47675879e+03 7.44945801e+03 7.37758008e+03 7.78778369e+03 8.06619971e+03 7.78912207e+03 7.53634473e+03 7.64160303e+03 7.85955127e+03 8.01370166e+03 8.18953613e+03 7.95614600e+03 7.86493213e+03 8.13319727e+03 8.20091504e+03 8.24544629e+03 8.15455713e+03 8.14165723e+03 8.50127930e+03 8.73874609e+03 8.56531348e+03 8.16516504e+03 8.29205566e+03 8.66085156e+03 8.79377539e+03 8.69338281e+03 8.50967871e+03 8.62337402e+03 8.94514062e+03 9.18977637e+03 9.03552637e+03 8.63664551e+03 8.84147070e+03 9.28586914e+03 9.20595312e+03 9.31345312e+03 9.21016113e+03 8.90401270e+03 9.18700977e+03 9.46260742e+03 9.37254199e+03 9.31249219e+03 9.57305566e+03 9.65009375e+03 9.66371680e+03 9.54612988e+03 9.23364746e+03 9.52152246e+03 1.01316973e+04 9.93715625e+03 9.62964453e+03 9.55858496e+03 9.61678711e+03 1.01525967e+04 1.04179297e+04 1.01223008e+04 9.92305566e+03 9.95138965e+03 9.95160449e+03 1.02421816e+04 1.05999531e+04 1.02561523e+04 1.01317588e+04 1.04568818e+04 1.04063975e+04 1.02599717e+04 1.03439258e+04 1.05798770e+04 1.08074346e+04 1.07239580e+04 1.07494385e+04 1.05082734e+04 1.02825186e+04 1.08908828e+04 1.12527568e+04 1.07350742e+04 1.04266143e+04 1.07737793e+04 1.10847559e+04 1.12285039e+04 1.13925176e+04 1.10362432e+04 1.08769443e+04 1.12043994e+04 1.12510830e+04 1.12900439e+04 1.12493252e+04 1.10872695e+04 1.11771660e+04 1.14607197e+04 1.15813203e+04 1.14501611e+04 1.15215381e+04 1.16335342e+04 1.16085137e+04 1.16375391e+04 1.13666133e+04 1.13811357e+04 1.20387412e+04 1.21289609e+04 1.15247080e+04 1.13585146e+04 1.15762734e+04 1.21589697e+04 1.24768916e+04 1.20647236e+04 1.16061934e+04 1.16810811e+04 1.19124180e+04 1.20862412e+04 1.21986953e+04 1.21048750e+04 1.21582080e+04 1.21589141e+04 1.21714883e+04 1.22663105e+04 1.20592422e+04 1.22272832e+04 1.26844521e+04 1.25720322e+04 1.23245059e+04 1.22106699e+04 1.21203711e+04 1.26359150e+04 1.29830850e+04 1.24366562e+04 1.21608506e+04 1.23785762e+04 1.28962744e+04 1.31319541e+04 1.27413271e+04 1.24482725e+04 1.24577627e+04 1.26022744e+04 1.29437861e+04 1.31135879e+04 1.26595283e+04 1.23681846e+04 1.28031553e+04 1.32169082e+04 1.31150127e+04 1.28948926e+04 1.28898721e+04 1.29411104e+04 1.31067578e+04 1.31394053e+04 1.28451396e+04 1.27713232e+04 1.31127910e+04 1.33253662e+04 1.31765508e+04 1.28706934e+04 1.30465732e+04 1.32636445e+04 13267. 1.34198574e+04 1.31012080e+04 1.31964443e+04 1.34666631e+04 1.33018760e+04 1.32907344e+04 1.31131797e+04 1.31264551e+04 1.34851914e+04 1.38176299e+04 1.37091846e+04 1.30548457e+04 1.29369639e+04 1.35318828e+04 1.39594160e+04 1.37496094e+04 1.31302725e+04 1.30418857e+04 1.34548643e+04 1.37272568e+04 1.37972539e+04 1.33999160e+04 1.32000352e+04 1.34831592e+04 1.37340732e+04 1.38455303e+04 1.36414414e+04 1.34899727e+04 1.35807930e+04 1.36234814e+04 1.36783613e+04 1.36687627e+04 1.37149717e+04 1.36400498e+04 1.34581221e+04 1.33562754e+04 1.33710664e+04 1.38248154e+04 1.43270352e+04 1.41327891e+04 1.35364209e+04 1.31337197e+04 1.33212061e+04 1.41237998e+04 1.44456123e+04 13995. 1.34583936e+04 1.31673184e+04 1.35427666e+04 1.41213340e+04 1.40969023e+04 1.38606221e+04 1.37601758e+04 1.37175195e+04 1.36272178e+04 1.33229229e+04 1.33614541e+04 1.37196836e+04 1.38296992e+04 1.42778135e+04 1.39724482e+04 1.31085918e+04 1.34178789e+04 1.38840225e+04 1.38714453e+04 1.38567178e+04 1.36982939e+04 1.40298682e+04 1.41175020e+04 1.34605850e+04 1.30663564e+04 1.33110527e+04 1.39803008e+04 1.44630928e+04 1.41733994e+04 1.34315811e+04 1.30407725e+04 1.32808223e+04 1.39286514e+04 1.43411836e+04 1.40347676e+04 1.33452842e+04 1.32452295e+04 1.39737793e+04 1.40699395e+04 1.33810518e+04 1.33406758e+04 1.35268311e+04 1.34697520e+04 1.39534688e+04 1.36868447e+04 1.31680205e+04 1.34942236e+04 1.32071797e+04 1.34779180e+04 1.38611113e+04 1.32315098e+04 1.34265117e+04 1.37730469e+04 1.34814609e+04 1.34471299e+04 1.34492393e+04 1.34858203e+04 1.35243789e+04 1.33541279e+04 1.29451494e+04 1.29889561e+04 1.36673789e+04 1.39929502e+04 1.36378643e+04 1.30466201e+04 1.26734316e+04 1.28884150e+04 1.34979551e+04 1.38513564e+04 1.35506006e+04 1.28442949e+04 1.28197783e+04 1.32572148e+04 1.31693535e+04 1.30536523e+04 1.29995732e+04 1.29778418e+04 1.30201982e+04 1.34365664e+04 1.30414648e+04 1.26485332e+04 1.29222695e+04 1.25056328e+04 1.29078164e+04 1.32966738e+04 1.28258584e+04 1.31917197e+04 1.28494756e+04 1.23253945e+04 1.27198691e+04 1.24533555e+04 1.26400352e+04 1.34521162e+04 1.27416953e+04 1.20138359e+04 1.22265820e+04 1.27923809e+04 1.32655723e+04 1.29604277e+04 1.22448027e+04 1.19286396e+04 1.20344688e+04 1.25459326e+04 1.30096387e+04 1.27243643e+04 1.21064961e+04 1.19379766e+04 1.23095439e+04 1.23829365e+04 1.21439863e+04 1.20416953e+04 1.20554248e+04 1.20954941e+04 1.24374912e+04 1.24460029e+04 1.17564004e+04 1.16455264e+04 1.18572070e+04 1.18485303e+04 1.19258350e+04 1.18536621e+04 1.21530225e+04 1.18230547e+04 1.13869707e+04 1.17587363e+04 1.13843613e+04 1.15886895e+04 1.23292803e+04 1.16620400e+04 1.08997705e+04 1.11665684e+04 1.16824521e+04 1.19507559e+04 1.18353936e+04 1.11867754e+04 1.07408164e+04 1.09445586e+04 1.14821572e+04 1.18621338e+04 1.15085957e+04 1.08114854e+04 1.07072471e+04 1.10371934e+04 1.11623369e+04 1.13947100e+04 1.13524502e+04 1.06555195e+04 1.05020840e+04 1.09682256e+04 1.10588789e+04 1.06672324e+04 1.05820713e+04 1.06240820e+04 1.05054717e+04 1.08737793e+04 1.09076338e+04 1.03497969e+04 1.03000820e+04 1.03866055e+04 1.03052695e+04 1.03536934e+04 1.02629346e+04 1.04588203e+04 1.05004277e+04 1.01680117e+04 9.89392871e+03 9.67366016e+03 1.00665088e+04 1.05321934e+04 1.02757451e+04 9.73513184e+03 9.45721582e+03 9.75761426e+03 1.02168154e+04 9.86019141e+03 9.25992871e+03 9.41366113e+03 9.66705762e+03 9.80486230e+03 1.01039717e+04 9.83055078e+03 9.22719727e+03 8.97774023e+03 9.21186133e+03 9.47757422e+03 9.43606641e+03 9.23810840e+03 9.13498145e+03 9.11919727e+03 9.24330273e+03 9.08727930e+03 8.77558496e+03 8.80962207e+03 8.69462891e+03 9.01362305e+03 9.16354395e+03 8.78774023e+03 8.75930762e+03 8.75673242e+03 8.67651953e+03 8.49573633e+03 8.19193994e+03 8.53185547e+03 8.87658496e+03 8.57894629e+03 8.11883838e+03 8.06580713e+03 8.44980859e+03 8.51972461e+03 8.29151855e+03 8.16453125e+03 7.85110010e+03 7.77673877e+03 8.11952051e+03 8.08544531e+03 7.82678906e+03 7.59541553e+03 7.47115479e+03 7.87943750e+03 8.09066309e+03 7.61319678e+03 7.40853564e+03 7.52574707e+03 7.50311865e+03 7.65063965e+03 7.63449707e+03 7.16625391e+03 7.08808301e+03 7.19630615e+03 7.21237793e+03 7.31571191e+03 7.40990283e+03 7.44932617e+03 7.15179004e+03 6.90120947e+03 6.85409766e+03 8.25131934e+03 1.57082295e+04 2.26099922e+04 5999636. -1.60664088e+06 2309853. 9645361. 10889608. 30837616. 1.86620038e+06 -2.85816775e+06 3.39023250e+06 -3.03435125e+06 -27607692. 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. 0. 0. 0. 0. 0. 0. 0. 23285380. 6714477. 1.93052129e+04 1.32658457e+04 7.94057764e+03 7.04716504e+03 6.71912109e+03 6.07560645e+03 5.68631494e+03 4.61636719e+03 4.37766064e+03 4.19100098e+03 4.22019727e+03 4.06216797e+03 3.90904321e+03 3.96910571e+03 3.93401245e+03 3.96294824e+03 3.94694458e+03 3.57628198e+03 3.49850513e+03 3.52906860e+03 3.56707178e+03 3.53203955e+03 3.41999609e+03 3.59756201e+03 3.47168677e+03 3.34715259e+03 3.45849878e+03 3.40622510e+03 3.23889429e+03 3.29134619e+03 3.34616895e+03 3.21986304e+03 3.14701978e+03 3.08862598e+03 3.03750439e+03 2.93162036e+03 2.89061816e+03 2.98428320e+03 2.96260571e+03 2.83323975e+03 2.79978003e+03 2.76425049e+03 2.73597021e+03 2.68197827e+03 2.63512842e+03 2.61718335e+03 2.53052979e+03 2.48410962e+03 2.47753979e+03 2.43354102e+03 2.48855176e+03 2.46645386e+03 2.35807764e+03 2.25223755e+03 2.20518555e+03 2.30232300e+03 2.28892871e+03 2.17581396e+03 2.09619189e+03 2.07598950e+03 2.07245923e+03 2.02515002e+03 2.05410693e+03 2.01842847e+03 1.87629700e+03 1.82185498e+03 1.88819678e+03 1.92562805e+03 1.84269495e+03 1.77079517e+03 1.73911621e+03 1.69975354e+03 1.67083752e+03 1.64261182e+03 1.62553528e+03 1.58993933e+03 1.53756689e+03 1.50887073e+03 1.48937988e+03 1.45464636e+03 1.47209131e+03 1.44021375e+03 1.36896533e+03 1.34027002e+03 1.31037036e+03 1.32400549e+03 1.30091638e+03 1.23814819e+03 1.21326489e+03 1.16213757e+03 1.11968201e+03 1.14734656e+03 1.11738623e+03 1.03377185e+03 1.02246350e+03 1.05626562e+03 1.06593323e+03 1.00948083e+03 9.51163940e+02 9.19126770e+02 8.96547791e+02 8.77480042e+02 8.54730347e+02 8.34917603e+02 8.07021057e+02 8.06669739e+02 7.83338440e+02 7.42574402e+02 7.24991577e+02 6.81921692e+02 6.75112854e+02 6.94505615e+02 6.60331787e+02 6.24860352e+02 5.88341492e+02 5.66087280e+02 5.81354248e+02 5.63523865e+02 5.27081421e+02 4.98677582e+02 4.79788300e+02 4.73491028e+02 4.55114868e+02 4.52407806e+02 4.39801514e+02 4.08649750e+02 3.89615143e+02 3.75540955e+02 3.66700226e+02 3.51676086e+02 3.32135986e+02 3.14148682e+02 3.01964233e+02 2.89874817e+02 2.68411743e+02 2.60904785e+02 2.61812042e+02 2.45272156e+02 2.27206268e+02 2.10114365e+02 1.97627396e+02 1.97064240e+02 1.86693756e+02 1.70916122e+02 1.56894226e+02 1.46946243e+02 1.42236176e+02 1.32325760e+02 1.23159538e+02 1.12534988e+02 1.06536652e+02 1.03548027e+02 9.41284103e+01 8.59304504e+01 7.90471802e+01 7.18056107e+01 6.48376465e+01 5.91275787e+01 5.39803162e+01 4.85479584e+01 4.38638878e+01 3.85088997e+01 3.46903000e+01 3.22130356e+01 2.77937679e+01 2.41180477e+01 2.15855713e+01 1.90667877e+01 1.71045914e+01 1.52238035e+01 1.36226206e+01 1.25063877e+01 1.16449604e+01 1.11216564e+01 1.09579725e+01 1.11376562e+01 1.16287327e+01 1.24168930e+01 1.35742760e+01 1.50149889e+01 1.70203686e+01 1.96453114e+01 2.20177288e+01 2.43590603e+01 2.68712006e+01 3.05169754e+01 3.58622971e+01 4.01568565e+01 4.37575264e+01 4.77656174e+01 5.26105537e+01 5.93980827e+01 6.52832947e+01 7.26189804e+01 7.84473724e+01 8.29646072e+01 9.05984497e+01 9.83219604e+01 1.09281685e+02 1.17262680e+02 1.22671776e+02 1.31599136e+02 1.40506454e+02 1.49781708e+02 1.56300034e+02 1.70668320e+02 1.91257202e+02 1.97753143e+02 2.03366928e+02 2.09918640e+02 2.20007599e+02 2.44278809e+02 2.59304504e+02 2.64810760e+02 2.70194427e+02 2.82735870e+02 3.05607605e+02 3.19741455e+02 3.41192719e+02 3.57298706e+02 3.63431732e+02 3.67329651e+02 3.81410645e+02 4.21571594e+02 4.36476532e+02 4.39727814e+02 4.50100800e+02 4.65582794e+02 5.07632721e+02 5.27395874e+02 5.17072510e+02 5.34306946e+02 5.81440552e+02 6.00816284e+02 5.91652100e+02 6.09971191e+02 6.60703918e+02 6.85037231e+02 6.83656433e+02 6.87851685e+02 7.10485168e+02 7.68532043e+02 7.82955078e+02 7.82339355e+02 8.16548645e+02 8.34969055e+02 8.56571655e+02 8.80634094e+02 9.00826355e+02 9.04468018e+02 9.50023987e+02 1.01742090e+03 1.01527423e+03 1.04474902e+03 1.07514941e+03 1.08276978e+03 1.10944739e+03 1.13076355e+03 1.15149341e+03 1.15952637e+03 1.18394153e+03 1.23503784e+03 1.26619312e+03 1.33131995e+03 1.32125757e+03 1.30767212e+03 1.37403552e+03 1.41792517e+03 1.49146802e+03 1.49746423e+03 1.48109998e+03 1.50046204e+03 1.52417090e+03 1.58927112e+03 1.61993884e+03 1.68187537e+03 1.71155396e+03 1.70134790e+03 1.72552258e+03 1.70912244e+03 1.79207312e+03 1.92759644e+03 1.93251440e+03 1.91544897e+03 1.89248279e+03 1.89610168e+03 2.02302075e+03 2.12090552e+03 2.10249878e+03 2.05647998e+03 2.08791211e+03 2.16576733e+03 2.21092236e+03 2.30297925e+03 2.32106909e+03 2.30223218e+03 2.32620166e+03 2.35439404e+03 2.49535620e+03 2.53634058e+03 2.43148804e+03 2.46604834e+03 2.64694775e+03 2.65422412e+03 2.55197510e+03 2.63990283e+03 2.81788989e+03 2.84027026e+03 2.81124048e+03 2.77039014e+03 2.80943262e+03 3.00363843e+03 3.04820483e+03 3.00659082e+03 2.98433838e+03 2.98050439e+03 3.08795190e+03 3.18494556e+03 3.21153247e+03 3.14899023e+03 3.26524487e+03 3.45776099e+03 3.39735742e+03 3.44397119e+03 3.48221606e+03 3.45317114e+03 3.51930078e+03 3.58417920e+03 3.62584131e+03 3.63846777e+03 3.63065112e+03 3.59872827e+03 3.77346094e+03 4.00913257e+03 3.84153833e+03 3.72946948e+03 3.91380957e+03 4.06823315e+03 4.22849609e+03 4.17112646e+03 4.09404688e+03 4.22367871e+03 4.27778320e+03 4.18666699e+03 4.17919482e+03 4.40463232e+03 4.46374805e+03 4.39430615e+03 4.40557715e+03 4.32596533e+03 4.52944287e+03 4.87154297e+03 4.78839697e+03 4.68804688e+03 4.62417627e+03 4.62513232e+03 4.90223096e+03 5.14339307e+03 5.04451123e+03 4.89455420e+03 4.92547119e+03 5.03139258e+03 5.09912207e+03 5.27657715e+03 5.27573584e+03 5.16509180e+03 5.28334912e+03 5.28653613e+03 5.55443213e+03 5.56042041e+03 5.45188232e+03 5.51435254e+03 5.56546094e+03 5.65395703e+03 5.56774609e+03 5.61825293e+03 5.92448389e+03 5.95818506e+03 5.88647705e+03 5.76659570e+03 5.84242285e+03 6.24872705e+03 6.26289697e+03 6.11804980e+03 6.04708057e+03 6.07438770e+03 6.19488135e+03 6.25377686e+03 6.39189111e+03 6.28928076e+03 6.41072266e+03 6.68543066e+03 6.55948340e+03 6.74253857e+03 6.82367920e+03 6.68687207e+03 6.72035742e+03 6.69427148e+03 6.83961182e+03 6.86202588e+03 6.85143018e+03 6.86206641e+03 7.16915186e+03 7.23879346e+03 6.92285547e+03 6.88581250e+03 7.13682373e+03 7.31540674e+03 7.56646533e+03 7.49610303e+03 7.23418115e+03 7.46591357e+03 7.68413281e+03 7.59324707e+03 7.54560254e+03 7.57848535e+03 7.59165527e+03 7.58844580e+03 7.81853467e+03 7.71284131e+03 7.81187305e+03 8.24139648e+03 8.16051758e+03 8.04489697e+03 7.90591553e+03 7.94575635e+03 8.36851367e+03 8.38169824e+03 8.31695312e+03 8.17336475e+03 7.99372803e+03 8.23247949e+03 8.59240430e+03 8.93453027e+03 8.66498242e+03 8.39890430e+03 8.51751758e+03 8.64238965e+03 9.01853516e+03 9.00567676e+03 8.73637109e+03 8.75067871e+03 8.74865234e+03 8.93145215e+03 8.85172461e+03 8.94699414e+03 9.38856836e+03 9.29010938e+03 9.23552344e+03 9.08126562e+03 9.02678223e+03 9.62491797e+03 9.65720508e+03 9.40411523e+03 9.24416895e+03 9.21872168e+03 9.50604102e+03 9.55117676e+03 9.92978613e+03 1.00037207e+04 9.68692480e+03 9.43016406e+03 9.66225977e+03 1.02470537e+04 1.01158838e+04 9.88100098e+03 9.89065039e+03 9.89120996e+03 9.96486035e+03 9.89695312e+03 1.01873955e+04 1.02156797e+04 1.00610361e+04 1.04925527e+04 1.06493760e+04 1.04709453e+04 1.04178301e+04 1.04044014e+04 1.04830469e+04 1.02553779e+04 1.01966689e+04 1.07940479e+04 1.09772354e+04 1.03993545e+04 1.02437812e+04 1.08014834e+04 1.12378467e+04 1.11342861e+04 1.07451279e+04 1.05368818e+04 1.10255322e+04 1.12856943e+04 1.11093691e+04 1.11710752e+04 1.09012988e+04 1.04983047e+04 1.10075488e+04 1.17318301e+04 1.17282988e+04 1.11405898e+04 1.08397598e+04 1.15133652e+04 1.19125703e+04 1.15721426e+04 1.12413135e+04 1.11497656e+04 1.13624863e+04 1.15039023e+04 1.19401670e+04 1.19939600e+04 1.16338740e+04 1.15234443e+04 1.15813994e+04 1.20661270e+04 1.18530273e+04 1.15654082e+04 1.21154307e+04 1.21316602e+04 1.20038652e+04 1.17965889e+04 1.17192314e+04 1.24051357e+04 1.21081299e+04 1.16990332e+04 1.20298867e+04 1.22791992e+04 1.23528740e+04 1.22320850e+04 1.25359541e+04 1.26569551e+04 1.23329521e+04 1.20066836e+04 1.19917178e+04 1.27250439e+04 1.26057529e+04 1.22788281e+04 1.24014893e+04 1.23998076e+04 1.26634209e+04 1.26332383e+04 1.27216182e+04 1.26524336e+04 1.24100986e+04 1.28694541e+04 1.29459863e+04 1.28168115e+04 1.28500791e+04 1.28014043e+04 1.27174209e+04 1.24046377e+04 1.23758643e+04 1.30395283e+04 1.35441934e+04 1.29177510e+04 1.23509512e+04 1.29241992e+04 1.35027705e+04 1.33710283e+04 1.28470859e+04 1.25753008e+04 1.32442383e+04 1.33284268e+04 1.28972969e+04 1.34561963e+04 1.33722959e+04 1.26819424e+04 1.28722539e+04 1.35780586e+04 1.37326943e+04 1.30370605e+04 1.26844951e+04 1.33738535e+04 1.39169883e+04 1.35576357e+04 1.30197412e+04 1.27956641e+04 1.34990381e+04 1.37682734e+04 1.33109248e+04 1.34265469e+04 1.35503730e+04 1.33659619e+04 1.32576162e+04 1.37670107e+04 1.35797686e+04 1.31152002e+04 1.35931895e+04 1.37154961e+04 1.37623857e+04 1.34807305e+04 1.32199062e+04 1.41445908e+04 1.45643828e+04 1.37869531e+04 1.38060938e+04 1.85759922e+04 3.45338047e+04 4.05207539e+04 6.56753750e+04 1.17667139e+04 4.09002656e+04 2.76277949e+04 1.97557871e+04 2.53163984e+04 3.37654648e+04 3.86626445e+04 5.48370273e+04 -4.06674492e+04 1.28111969e+05 2.88030250e+05 7.38144922e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.34501181e+10 2.07796906e+05 4.87555664e+04 3.41279297e+04 2.30865742e+04 1.77122969e+04 1.96046992e+04 1.53971484e+04 1.10654053e+04 1.35880244e+04 1.49249307e+04 1.39707549e+04 1.37791104e+04 1.37336006e+04 1.37222285e+04 1.36337852e+04 1.36063271e+04 1.35343047e+04 1.34228252e+04 1.36654248e+04 1.37199951e+04 1.36018379e+04 1.36403730e+04 1.32229268e+04 1.32306250e+04 1.36346113e+04 1.34259785e+04 1.32545723e+04 1.36586318e+04 1.39924775e+04 1.35731494e+04 1.32645518e+04 1.32680479e+04 1.31447324e+04 1.33673389e+04 1.36797656e+04 1.34186797e+04 1.33318662e+04 1.36421045e+04 1.34529736e+04 1.30769453e+04 1.31817061e+04 1.32145605e+04 1.32373604e+04 1.34577314e+04 1.31709268e+04 1.30786729e+04 1.33574619e+04 1.31967139e+04 1.30372393e+04 1.29518438e+04 1.30223984e+04 1.31718877e+04 1.31925996e+04 1.33691094e+04 1.30875020e+04 1.28017295e+04 1.31362305e+04 1.28674092e+04 1.26416924e+04 1.29999033e+04 1.29579453e+04 1.28529912e+04 1.30569590e+04 1.29997266e+04 1.27244053e+04 1.26911963e+04 1.26061523e+04 1.25035869e+04 1.26910645e+04 1.27701582e+04 1.27659316e+04 1.27711943e+04 1.26552959e+04 1.25200928e+04 1.24558486e+04 1.25710234e+04 1.24858506e+04 1.24634160e+04 1.28318818e+04 1.25270889e+04 1.20209229e+04 1.23302168e+04 1.23177334e+04 1.21574824e+04 1.24108203e+04 1.22832686e+04 1.21166074e+04 1.24278057e+04 1.25081221e+04 1.21305371e+04 1.18486738e+04 1.18207441e+04 1.19106387e+04 1.20554141e+04 1.20505771e+04 1.20882197e+04 1.21209512e+04 1.20106592e+04 1.17338037e+04 1.15664912e+04 1.18251846e+04 1.18205498e+04 1.15709424e+04 1.17702529e+04 1.16428848e+04 1.15289521e+04 1.17549053e+04 1.14972275e+04 1.11929033e+04 1.12867275e+04 1.15437803e+04 1.15607715e+04 1.13197158e+04 1.13628877e+04 1.14345596e+04 1.13890371e+04 1.13140146e+04 1.10226855e+04 1.09307744e+04 1.12314355e+04 1.11901260e+04 1.09614238e+04 1.10542295e+04 1.08695420e+04 1.07670303e+04 1.09788242e+04 1.08725957e+04 1.05978623e+04 1.06741289e+04 1.09042168e+04 1.08827852e+04 1.06784824e+04 1.03908857e+04 1.02986406e+04 1.05472051e+04 1.06398330e+04 1.03639092e+04 1.02734395e+04 1.05478926e+04 1.05364414e+04 1.03389092e+04 1.02198809e+04 9.91353809e+03 9.84381055e+03 9.98827344e+03 1.01336992e+04 1.00637939e+04 9.97360547e+03 1.00778398e+04 1.00152236e+04 9.78083887e+03 9.60038477e+03 9.57480664e+03 9.67969531e+03 9.80986719e+03 9.89126855e+03 9.73799023e+03 9.57765527e+03 9.33004883e+03 9.42679102e+03 9.46763574e+03 9.13302734e+03 9.14142871e+03 9.36723828e+03 9.44816797e+03 9.17585840e+03 9.04019531e+03 9.00151074e+03 8.84955957e+03 8.98276660e+03 9.14414258e+03 9.04694531e+03 8.86029590e+03 8.80412012e+03 8.80203027e+03 8.62905371e+03 8.55833984e+03 8.56537402e+03 8.52148340e+03 8.74393555e+03 8.75273633e+03 8.34377344e+03 8.25197363e+03 8.29511816e+03 8.37695898e+03 8.41583496e+03 8.02756006e+03 7.93758545e+03 8.20524609e+03 8.23172266e+03 8.00254639e+03 7.96419531e+03 7.87761133e+03 7.73119873e+03 7.84435645e+03 7.94757812e+03 7.70181982e+03 7.55511328e+03 7.71723779e+03 7.80987646e+03 7.59592480e+03 7.47181104e+03 7.39331934e+03 7.32934668e+03 7.47436182e+03 7.33376953e+03 7.19432324e+03 7.28206885e+03 7.17620752e+03 7.01713428e+03 7.06546338e+03 6.90892139e+03 6.89850635e+03 7.00639209e+03 6.93978174e+03 6.90381055e+03 6.75584131e+03 6.72892432e+03 6.64260352e+03 6.54788477e+03 6.63572070e+03 6.52719092e+03 6.35739160e+03 6.49194189e+03 6.46148779e+03 6.32250293e+03 6.29966943e+03 6.32512256e+03 6.17440039e+03 6.19881885e+03 6.25484277e+03 6.05167285e+03 5.91480518e+03 5.93158496e+03 5.85325195e+03 5.83437305e+03 5.81150830e+03 5.76725781e+03 5.75724902e+03 5.76326562e+03 5.66783789e+03 5.57126367e+03 5.56381543e+03 5.48450391e+03 5.44889160e+03 5.50304639e+03 5.29624902e+03 5.20268555e+03 5.32278467e+03 5.24254443e+03 5.12997021e+03 5.12549219e+03 5.08531152e+03 4.98063721e+03 4.92663477e+03 4.93213965e+03 4.97803076e+03 4.87149365e+03 4.84559131e+03 4.82438965e+03 4.63457764e+03 4.61244531e+03 4.59640869e+03 4.51497949e+03 4.59425732e+03 4.57949707e+03 4.43376514e+03 4.33266455e+03 4.33806104e+03 4.37737939e+03 4.30955518e+03 4.07335498e+03 4.14178613e+03 4.24868506e+03 4.09436670e+03 4.01865210e+03 3.96768848e+03 3.93631152e+03 3.91449072e+03 3.85741968e+03 3.76809521e+03 3.80779883e+03 3.78546924e+03 3.69218335e+03 3.68789233e+03 3.64675757e+03 3.58306714e+03 3.51689551e+03 3.37974878e+03 3.44849194e+03 3.50823511e+03 3.34177368e+03 3.29815991e+03 3.26975488e+03 3.25957373e+03 3.24444336e+03 3.10241992e+03 3.11296973e+03 3.14275464e+03 3.07314380e+03 3.00541455e+03 2.92217456e+03 2.88480615e+03 2.89188062e+03 2.84379199e+03 2.79338672e+03 2.78725903e+03 2.75728149e+03 2.71410352e+03 2.69743701e+03 2.63855786e+03 2.55373535e+03 2.50636011e+03 2.51555835e+03 2.51268921e+03 2.41645312e+03 2.35906250e+03 2.32368555e+03 2.30689355e+03 2.31891821e+03 2.26679883e+03 2.18335962e+03 2.15153149e+03 2.16854761e+03 2.15841162e+03 2.08814160e+03 1.99412415e+03 1.98580347e+03 1.98898242e+03 1.93126599e+03 1.89704370e+03 1.90015564e+03 1.85883948e+03 1.81242065e+03 1.80422534e+03 1.77347571e+03 1.71777820e+03 1.66814795e+03 1.65834814e+03 1.63431421e+03 1.56169580e+03 1.52071899e+03 1.51811877e+03 1.51639587e+03 1.49717688e+03 1.44677209e+03 1.39057007e+03 1.39788831e+03 1.38600159e+03 1.31093396e+03 1.27205005e+03 1.27836523e+03 1.27992847e+03 1.23620410e+03 1.17166040e+03 1.13973572e+03 1.13281702e+03 1.12894324e+03 1.11510400e+03 1.08527490e+03 1.03294885e+03 9.93959595e+02 9.75618591e+02 9.49601929e+02 9.33072571e+02 9.10586426e+02 8.86054504e+02 8.69821167e+02 8.47356506e+02 8.21538086e+02 7.94735779e+02 7.80158630e+02 7.78364319e+02 7.46756775e+02 7.02475586e+02 6.79363098e+02 6.73423157e+02 6.65672607e+02 6.52312622e+02 6.20550537e+02 5.77776489e+02 5.62466431e+02 5.63500122e+02 5.49057007e+02 5.30028564e+02 5.02150055e+02 4.77442322e+02 4.65066925e+02 4.48609741e+02 4.39407898e+02 4.20549438e+02 3.93440399e+02 3.86555450e+02 3.76673157e+02 3.56951935e+02 3.39415710e+02 3.18861572e+02 3.10238190e+02 3.09134552e+02 2.93591248e+02 2.71563110e+02 2.63381134e+02 2.55064743e+02 2.33568741e+02 2.19769058e+02 2.08485687e+02 1.99139603e+02 1.96187729e+02 1.83575546e+02 1.68113907e+02 1.59973831e+02 1.51563828e+02 1.39939819e+02 1.31273193e+02 1.26358574e+02 1.18212486e+02 1.08337456e+02 1.00665359e+02 9.32442932e+01 8.82531052e+01 8.30769806e+01 7.59544296e+01 6.90495834e+01 6.18551445e+01 5.68829422e+01 5.29812889e+01 4.88782043e+01 4.51364517e+01 4.09619522e+01 3.72096558e+01 3.35790634e+01 3.08933735e+01 2.86166573e+01 2.63173962e+01 2.43283901e+01 2.26761665e+01 2.15748119e+01 2.08266792e+01 2.03894711e+01 2.02359982e+01 2.03512726e+01 2.08484688e+01 2.18914700e+01 2.32754040e+01 2.46825390e+01 2.62503510e+01 2.80305767e+01 3.04652081e+01 3.39127655e+01 3.73329048e+01 3.98371544e+01 4.32105789e+01 4.80082817e+01 5.35189934e+01 5.86557541e+01 6.32246552e+01 6.82387314e+01 7.43429718e+01 8.11245041e+01 8.72272797e+01 9.28689041e+01 1.00355820e+02 1.09569595e+02 1.16782906e+02 1.25148621e+02 1.32988159e+02 1.41382843e+02 1.52743149e+02 1.61432236e+02 1.70935898e+02 1.79117874e+02 1.87880325e+02 2.01231781e+02 2.14677704e+02 2.26227020e+02 2.34246902e+02 2.43985626e+02 2.60143829e+02 2.74715088e+02 2.87397736e+02 3.03406647e+02 3.10431610e+02 3.22828033e+02 3.47904083e+02 3.59318329e+02 3.66047180e+02 3.92128662e+02 4.08567474e+02 4.09662537e+02 4.33906097e+02 4.53667542e+02 4.59226318e+02 4.88928314e+02 5.15041748e+02 5.20664917e+02 5.34676147e+02 5.56901428e+02 5.69750549e+02 5.94100220e+02 6.16996094e+02 6.20591675e+02 6.46630737e+02 6.80120972e+02 7.04743652e+02 7.26356323e+02 7.33561768e+02 7.58614258e+02 7.75837158e+02 7.83494019e+02 8.25427673e+02 8.53129944e+02 8.61596558e+02 9.04808228e+02 9.23894653e+02 9.26027771e+02 9.61180664e+02 9.92588074e+02 1.03050488e+03 1.04832080e+03 1.05247388e+03 1.06786340e+03 1.12246997e+03 1.17577454e+03 1.16815613e+03 1.19131702e+03 1.20221619e+03 1.23785864e+03 1.30270789e+03 1.28824304e+03 1.30612659e+03 1.36326306e+03 1.40935681e+03 1.42639673e+03 1.41513867e+03 1.46879272e+03 1.52860449e+03 1.53706274e+03 1.57218738e+03 1.58348804e+03 1.61208997e+03 1.66730286e+03 1.70220947e+03 1.74470703e+03 1.74806689e+03 1.76424683e+03 1.81592261e+03 1.84810742e+03 1.90348877e+03 1.91971985e+03 1.91862610e+03 1.96938367e+03 2.03573572e+03 2.07125220e+03 2.09042725e+03 2.12174976e+03 2.15433350e+03 2.21125342e+03 2.23040039e+03 2.23593726e+03 2.31196387e+03 2.34353638e+03 2.35158032e+03 2.43942529e+03 2.44152124e+03 2.44395728e+03 2.51531982e+03 2.52583618e+03 2.55929834e+03 2.65624023e+03 2.66984399e+03 2.64778735e+03 2.71067993e+03 2.77999341e+03 2.81186035e+03 2.90855298e+03 2.91166846e+03 2.90740503e+03 2.96118335e+03 2.96241553e+03 3.03739966e+03 3.07174463e+03 3.13449023e+03 3.22285205e+03 3.17290430e+03 3.24441895e+03 3.29240430e+03 3.26591089e+03 3.34559619e+03 3.44060645e+03 3.50143188e+03 3.48896802e+03 3.50517554e+03 3.60350928e+03 3.63476660e+03 3.64892358e+03 3.68937500e+03 3.73906958e+03 3.83823804e+03 3.83509155e+03 3.90080933e+03 3.97948828e+03 3.91889673e+03 3.95661377e+03 4.12680273e+03 4.17278418e+03 4.10508057e+03 4.18802002e+03 4.26456787e+03 4.26308105e+03 4.41878223e+03 4.44971924e+03 4.39591992e+03 4.94147119e+03 4.94970264e+03 4.90494092e+03 4.51985303e+03 1.04403389e+04 1.43208193e+04 -12897263. -39629616. -3.18180750e+06 -12347168. 37589468. -1.85608550e+06 -12360666. -13550051. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 49187952. 2.34669375e+06 2.67535293e+04 1.31254287e+04 7.60907129e+03 9.53005469e+03 7.72993750e+03 8.23041602e+03 7.80330371e+03 7.32477246e+03 7.42693311e+03 7.61999707e+03 7.50326514e+03 7.44532080e+03 7.52153125e+03 7.64223926e+03 7.77801367e+03 7.79424951e+03 7.73125781e+03 7.60352002e+03 7.86853223e+03 7.97370557e+03 7.97700439e+03 8.04968262e+03 7.89029150e+03 7.90664893e+03 8.13116553e+03 8.20518457e+03 8.27031934e+03 8.04198975e+03 8.09388330e+03 8.52905078e+03 8.76280859e+03 8.50057031e+03 8.18880127e+03 8.26625684e+03 8.58892480e+03 8.71203418e+03 8.71175781e+03 8.54432617e+03 8.82663867e+03 8.92808789e+03 8.92968555e+03 8.97077734e+03 8.65674316e+03 8.89522852e+03 9.35845020e+03 9.20099609e+03 9.21292871e+03 9.12863379e+03 8.98520801e+03 9.17455176e+03 9.46731836e+03 9.46383398e+03 9.20685254e+03 9.50273340e+03 9.57243555e+03 9.56972852e+03 9.62336621e+03 9.43009473e+03 9.61387012e+03 9.89694238e+03 9.67847754e+03 9.61195020e+03 9.60619727e+03 9.87104492e+03 1.02706455e+04 1.01944844e+04 9.97559863e+03 9.88184961e+03 1.00420859e+04 1.00275830e+04 1.02225391e+04 1.04053350e+04 1.01097041e+04 1.01991250e+04 1.05713096e+04 1.04984023e+04 1.03823125e+04 1.01589912e+04 1.04051680e+04 1.08130830e+04 1.07593906e+04 1.06702793e+04 1.04647012e+04 1.04489404e+04 1.08078125e+04 1.10659219e+04 1.07606455e+04 1.05357871e+04 1.10073672e+04 1.10072920e+04 1.08299102e+04 1.12488477e+04 1.10281201e+04 1.09810996e+04 1.12699424e+04 1.12981260e+04 1.13121904e+04 1.10519180e+04 1.11161436e+04 1.13108936e+04 1.15560068e+04 1.16374531e+04 1.12960342e+04 1.14477793e+04 1.15300947e+04 1.14854463e+04 1.16336729e+04 1.14483447e+04 1.15226660e+04 1.19077461e+04 1.18977012e+04 1.15674385e+04 1.13191367e+04 1.17428652e+04 1.22664092e+04 1.22326289e+04 1.19906719e+04 1.16145547e+04 1.16917451e+04 1.20322773e+04 1.21813486e+04 1.22750537e+04 1.19686348e+04 1.20316943e+04 1.20852744e+04 1.21228838e+04 1.24911328e+04 1.21317764e+04 1.21228438e+04 1.25341025e+04 1.24215244e+04 1.23529932e+04 1.22887393e+04 1.24200156e+04 1.26596436e+04 1.25979336e+04 1.23776455e+04 1.21399219e+04 1.25381816e+04 1.30045537e+04 1.28961533e+04 1.26277227e+04 1.23877383e+04 1.25128945e+04 1.27966436e+04 1.29586367e+04 1.29545098e+04 1.24515146e+04 1.24177852e+04 1.28446943e+04 1.30805352e+04 1.32427617e+04 1.29377295e+04 1.28205225e+04 1.28466758e+04 1.30114521e+04 1.31994521e+04 1.29070986e+04 1.29350879e+04 1.30435762e+04 1.31273271e+04 1.32415293e+04 1.28649766e+04 1.31341572e+04 1.34153291e+04 1.31079795e+04 1.32974561e+04 1.31746064e+04 1.31786963e+04 1.34341582e+04 1.34314121e+04 1.33070908e+04 1.29608379e+04 1.30861709e+04 1.34737949e+04 1.37752549e+04 1.37171777e+04 1.30437051e+04 1.28928555e+04 1.34366064e+04 1.37906543e+04 1.36866445e+04 1.31328096e+04 1.32495596e+04 1.35620049e+04 1.35125762e+04 1.36892822e+04 1.33354932e+04 1.32513750e+04 1.36198428e+04 1.37645928e+04 1.36978926e+04 1.34801504e+04 1.35862256e+04 1.35927939e+04 1.36226201e+04 1.38839316e+04 1.36386396e+04 1.35983115e+04 1.36626562e+04 1.34370430e+04 1.33906748e+04 1.34619150e+04 1.38204580e+04 1.40245059e+04 1.39120723e+04 1.35645889e+04 1.30995791e+04 1.35288516e+04 1.42510312e+04 1.41548828e+04 1.38752070e+04 1.35157031e+04 1.32673516e+04 1.35940820e+04 1.40662930e+04 1.39842354e+04 1.37987812e+04 1.39008535e+04 1.38123105e+04 1.37008145e+04 1.34516914e+04 1.32319375e+04 1.35829287e+04 1.36878867e+04 1.40844297e+04 1.39255830e+04 1.31952373e+04 1.38712041e+04 1.40173965e+04 1.35073955e+04 1.37206406e+04 1.37400693e+04 1.40400332e+04 1.39684541e+04 1.32844297e+04 1.31366826e+04 1.34012275e+04 1.39983887e+04 1.45086553e+04 1.41232686e+04 1.33611201e+04 1.29959580e+04 1.32921191e+04 1.39975830e+04 1.43456406e+04 1.39830918e+04 1.32869004e+04 1.32510869e+04 1.40161719e+04 1.40580537e+04 1.32585000e+04 1.31914912e+04 1.35788779e+04 1.35623340e+04 1.39506875e+04 1.36404043e+04 1.31027646e+04 1.35065791e+04 1.32486680e+04 1.34146533e+04 1.38232705e+04 1.32189502e+04 1.34332852e+04 1.37885859e+04 1.34703115e+04 1.34288535e+04 1.33994170e+04 1.34939473e+04 1.35048857e+04 1.33671475e+04 1.29632949e+04 1.29528672e+04 1.36059443e+04 1.39519072e+04 1.36275586e+04 1.30450801e+04 1.26822793e+04 1.28425439e+04 1.34529434e+04 1.38734287e+04 1.35991865e+04 1.28504375e+04 1.27750283e+04 1.32644316e+04 1.32601758e+04 1.29579395e+04 1.28965947e+04 1.29961094e+04 1.30099961e+04 1.33601963e+04 1.30436533e+04 1.26538428e+04 1.29130752e+04 1.25129102e+04 1.28562920e+04 1.32185791e+04 1.28552822e+04 1.31947793e+04 1.28617588e+04 1.23273438e+04 1.27076123e+04 1.24243447e+04 1.26074307e+04 1.34245264e+04 1.27349219e+04 1.19907783e+04 1.22632520e+04 1.28340713e+04 1.32123652e+04 1.29070264e+04 1.21840439e+04 1.19083584e+04 1.20551465e+04 1.25535273e+04 1.30586309e+04 1.27116387e+04 1.20090234e+04 1.18873477e+04 1.23404531e+04 1.24467842e+04 1.20496094e+04 1.19838428e+04 12094. 1.20727666e+04 1.24506328e+04 1.24343418e+04 1.17113818e+04 1.16693057e+04 1.18609238e+04 1.18586230e+04 1.19036289e+04 1.18459238e+04 1.20800586e+04 1.18264092e+04 1.14158848e+04 1.16949668e+04 1.13756191e+04 1.16073037e+04 1.23377432e+04 1.15843320e+04 1.08352871e+04 1.11512695e+04 1.17181582e+04 1.19811719e+04 1.18535635e+04 1.11971982e+04 1.07020566e+04 1.09427490e+04 1.15155771e+04 1.19013760e+04 1.14962061e+04 1.08710605e+04 1.07273994e+04 1.09948320e+04 1.11398408e+04 1.13270234e+04 1.12416768e+04 1.06534053e+04 1.05602021e+04 1.09602178e+04 1.10115596e+04 1.07610254e+04 1.06550039e+04 1.05237822e+04 1.04754580e+04 1.08479502e+04 1.09065557e+04 1.04653691e+04 1.03124023e+04 1.02242930e+04 1.02203027e+04 1.03824941e+04 1.03360088e+04 1.05196885e+04 1.04860195e+04 1.00589678e+04 9.88775781e+03 9.68435938e+03 1.00816924e+04 1.05359268e+04 1.02653613e+04 9.67662988e+03 9.42172949e+03 9.78325684e+03 1.02668369e+04 9.79677930e+03 9.24988965e+03 9.43368555e+03 9.68230371e+03 9.78389648e+03 1.00565674e+04 9.73926562e+03 9.18169824e+03 9.00374219e+03 9.29696973e+03 9.38404004e+03 9.35996094e+03 9.26728906e+03 9.17769531e+03 9.07335938e+03 9.19475000e+03 9.07178516e+03 8.71369531e+03 8.79170508e+03 8.78246387e+03 9.08520996e+03 9.04386719e+03 8.73735938e+03 8.80483789e+03 8.70221191e+03 8.66117285e+03 8.48771875e+03 8.16866504e+03 8.54053809e+03 8.84278223e+03 8.51171484e+03 8.09056006e+03 8.09638330e+03 8.43560742e+03 8.50062012e+03 8.33492188e+03 8.12382861e+03 7.85168604e+03 7.85439502e+03 8.06193994e+03 8.01149561e+03 7.81729492e+03 7.58700293e+03 7.49839111e+03 7.91076123e+03 8.15573682e+03 7.64058887e+03 7.34786182e+03 7.52923145e+03 7.49501221e+03 7.64349463e+03 7.59513770e+03 7.08584326e+03 7.11505322e+03 7.25662988e+03 7.24003467e+03 7.30828271e+03 7.32781055e+03 7.39342920e+03 7.13913184e+03 6.88488867e+03 6.86161377e+03 7.84841748e+03 1.28641045e+04 2.07262578e+04 3.84064725e+06 2.01626850e+06 10989510. 1.78849788e+06 23114118. -23041946. -3834643. 2.60641975e+06 -1.58770312e+06 -4.08372825e+06 -8588070. 42812980. 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. 0. 0. 0. 0. 0. 0. 23285380. 6714477. 1.93052129e+04 1.32658457e+04 7.94057764e+03 5.40121240e+03 5.47113428e+03 4.51240137e+03 4.27808789e+03 4.38796777e+03 4.23864160e+03 4.03774365e+03 4.13155225e+03 4.07325781e+03 3.98010352e+03 3.93579590e+03 3.89630640e+03 3.82982910e+03 3.77918823e+03 3.71911572e+03 3.66170654e+03 3.63485840e+03 3.57409204e+03 3.58940918e+03 3.56913916e+03 3.38878760e+03 3.35628101e+03 3.50017090e+03 3.46213965e+03 3.32505078e+03 3.27603174e+03 3.23206079e+03 3.19629541e+03 3.16746680e+03 3.12354810e+03 3.07744995e+03 3.03931006e+03 2.96556934e+03 2.91481226e+03 2.97162036e+03 2.95261157e+03 2.84116455e+03 2.80251221e+03 2.78053906e+03 2.74724780e+03 2.68715845e+03 2.64598877e+03 2.63162939e+03 2.53867578e+03 2.48136572e+03 2.47973145e+03 2.44975024e+03 2.50226538e+03 2.47648364e+03 2.35346606e+03 2.26613965e+03 2.21964185e+03 2.31505444e+03 2.30142944e+03 2.17987720e+03 2.10196753e+03 2.06432739e+03 2.08480396e+03 2.04868433e+03 2.05404663e+03 2.02556897e+03 1.88898621e+03 1.81457483e+03 1.88255042e+03 1.93063525e+03 1.84621948e+03 1.77860400e+03 1.74338525e+03 1.70708459e+03 1.67860156e+03 1.65385083e+03 1.61361377e+03 1.57601318e+03 1.55830566e+03 1.53465552e+03 1.49383093e+03 1.46193591e+03 1.47653772e+03 1.45441077e+03 1.38781128e+03 1.34550647e+03 1.31806653e+03 1.32001514e+03 1.29114636e+03 1.24475305e+03 1.22265710e+03 1.16766919e+03 1.12118005e+03 1.14597095e+03 1.11781152e+03 1.04155334e+03 1.03104639e+03 1.06085315e+03 1.07204358e+03 1.01255994e+03 9.55216248e+02 9.25500366e+02 9.04289124e+02 8.86014465e+02 8.60940308e+02 8.39362305e+02 8.13621521e+02 8.18852600e+02 7.98236755e+02 7.52352722e+02 7.30971985e+02 6.91075867e+02 6.77656616e+02 6.95266479e+02 6.67220459e+02 6.33105225e+02 6.01169189e+02 5.72357605e+02 5.82075500e+02 5.74451782e+02 5.40438843e+02 5.08684418e+02 4.89749542e+02 4.83145447e+02 4.64983032e+02 4.62790619e+02 4.49918610e+02 4.18353546e+02 3.96939911e+02 3.80605042e+02 3.72884766e+02 3.59407776e+02 3.41107239e+02 3.25832886e+02 3.12914337e+02 2.97788940e+02 2.77304993e+02 2.67853607e+02 2.67924957e+02 2.53842331e+02 2.36209702e+02 2.18744125e+02 2.06675171e+02 2.05967361e+02 1.95388412e+02 1.80238922e+02 1.66435547e+02 1.56283249e+02 1.50984482e+02 1.41008713e+02 1.32247574e+02 1.21354263e+02 1.15338142e+02 1.12880051e+02 1.03139000e+02 9.37087784e+01 8.70249405e+01 8.09342499e+01 7.43441238e+01 6.84204102e+01 6.27509727e+01 5.74113121e+01 5.23276367e+01 4.69437370e+01 4.33084030e+01 4.08968239e+01 3.67214699e+01 3.31351967e+01 3.06996098e+01 2.82292824e+01 2.62976437e+01 2.43658962e+01 2.27579441e+01 2.16984081e+01 2.08877277e+01 2.03931713e+01 2.02335014e+01 2.03733006e+01 2.08270283e+01 2.16277428e+01 2.27955551e+01 2.42648525e+01 2.63742237e+01 2.89958572e+01 3.13155804e+01 3.38729630e+01 3.66229973e+01 3.99555054e+01 4.50323181e+01 4.94661331e+01 5.31194725e+01 5.69524841e+01 6.18154106e+01 6.87176361e+01 7.45940628e+01 8.19950714e+01 8.79209366e+01 9.27971268e+01 1.00892311e+02 1.08078461e+02 1.18676949e+02 1.26408234e+02 1.30996262e+02 1.40659760e+02 1.49838058e+02 1.58335419e+02 1.64074387e+02 1.77644135e+02 1.98482788e+02 2.06978088e+02 2.12890915e+02 2.19250259e+02 2.29014572e+02 2.53520844e+02 2.67981873e+02 2.73739197e+02 2.79941315e+02 2.91679749e+02 3.14875641e+02 3.28451935e+02 3.48982758e+02 3.63498138e+02 3.69563324e+02 3.81767975e+02 3.94936890e+02 4.27308075e+02 4.43401215e+02 4.47407318e+02 4.60098022e+02 4.75304382e+02 5.09434540e+02 5.28713989e+02 5.23533936e+02 5.42119019e+02 5.88869446e+02 6.07545166e+02 5.98894287e+02 6.15235657e+02 6.65404358e+02 6.92452942e+02 6.91484070e+02 6.95143066e+02 7.17849731e+02 7.77557800e+02 7.88328979e+02 7.86698486e+02 8.26014832e+02 8.46996643e+02 8.58875793e+02 8.80856262e+02 9.09256775e+02 9.12520691e+02 9.58905762e+02 1.03674390e+03 1.03206763e+03 1.04196033e+03 1.06887878e+03 1.08977368e+03 1.11580127e+03 1.13645471e+03 1.16328442e+03 1.16897949e+03 1.17778784e+03 1.23508301e+03 1.29115466e+03 1.35217334e+03 1.33350159e+03 1.31283105e+03 1.37913159e+03 1.42538232e+03 1.50051685e+03 1.51406873e+03 1.49950195e+03 1.50108215e+03 1.51573767e+03 1.59484290e+03 1.62914001e+03 1.68810132e+03 1.73440161e+03 1.72055066e+03 1.71614307e+03 1.70551978e+03 1.79783691e+03 1.93164709e+03 1.94233643e+03 1.92398572e+03 1.90307593e+03 1.90541077e+03 2.02919861e+03 2.11930835e+03 2.10531299e+03 2.06631885e+03 2.09350537e+03 2.17344287e+03 2.21896851e+03 2.31728784e+03 2.35193506e+03 2.32362378e+03 2.32757202e+03 2.34708813e+03 2.46801270e+03 2.51809473e+03 2.44422021e+03 2.47492798e+03 2.65011694e+03 2.66547461e+03 2.56631836e+03 2.64936328e+03 2.82746387e+03 2.84352344e+03 2.81664478e+03 2.77553687e+03 2.81416553e+03 3.01261548e+03 3.05466650e+03 3.01097363e+03 2.97670288e+03 2.98153955e+03 3.09251221e+03 3.16425171e+03 3.22496680e+03 3.15825366e+03 3.27510547e+03 3.48183496e+03 3.42810815e+03 3.43167627e+03 3.49359131e+03 3.49798364e+03 3.53272803e+03 3.57202515e+03 3.62882007e+03 3.64122021e+03 3.62579199e+03 3.60009180e+03 3.75232300e+03 3.96692407e+03 3.86425513e+03 3.77588232e+03 3.94646338e+03 4.02201880e+03 4.18688965e+03 4.19198975e+03 4.08822339e+03 4.22510059e+03 4.26498730e+03 4.17446924e+03 4.21954443e+03 4.44396436e+03 4.47578857e+03 4.42463623e+03 4.37953369e+03 4.29011279e+03 4.53593213e+03 4.89910693e+03 4.80021143e+03 4.68302441e+03 4.63910693e+03 4.66151172e+03 4.95787207e+03 5.06810303e+03 4.99100684e+03 4.88626611e+03 4.91127490e+03 5.04245361e+03 5.09953809e+03 5.30458154e+03 5.34233252e+03 5.21153613e+03 5.25060498e+03 5.30148877e+03 5.47518018e+03 5.55593604e+03 5.49626367e+03 5.49899219e+03 5.51547217e+03 5.62171924e+03 5.53966064e+03 5.64007861e+03 5.96908887e+03 5.93124902e+03 5.92152197e+03 5.82419873e+03 5.78943799e+03 6.23405566e+03 6.24774219e+03 6.10316016e+03 6.06885400e+03 6.07193213e+03 6.19702002e+03 6.22097217e+03 6.36499512e+03 6.27181348e+03 6.45435107e+03 6.76698975e+03 6.57120898e+03 6.67092578e+03 6.80480566e+03 6.71040674e+03 6.66604004e+03 6.69404004e+03 6.79437012e+03 6.87392432e+03 6.90342578e+03 6.93943408e+03 7.05968848e+03 7.18000391e+03 6.93826221e+03 6.86636865e+03 7.12766943e+03 7.32334619e+03 7.55753906e+03 7.46577246e+03 7.26330225e+03 7.56654004e+03 7.55563330e+03 7.47505518e+03 7.61179688e+03 7.64586523e+03 7.63256592e+03 7.60696143e+03 7.74011865e+03 7.67882080e+03 7.80337793e+03 8.19484570e+03 8.15122119e+03 8.07987744e+03 7.93359326e+03 7.84798535e+03 8.35570801e+03 8.43143555e+03 8.27441309e+03 8.10123047e+03 8.02388379e+03 8.31844434e+03 8.48137695e+03 8.83638086e+03 8.62261719e+03 8.39207324e+03 8.59951172e+03 8.60221484e+03 8.90214453e+03 8.92912305e+03 8.72502344e+03 8.76855176e+03 8.83764941e+03 8.90445898e+03 8.75553418e+03 8.97263770e+03 9.49245312e+03 9.34542383e+03 9.26300781e+03 9.05244727e+03 8.95652148e+03 9.58309570e+03 9.60617578e+03 9.36432031e+03 9.23560938e+03 9.21826465e+03 9.48625586e+03 9.57214062e+03 9.92050000e+03 9.93775684e+03 9.69497559e+03 9.55802832e+03 9.53922656e+03 1.01605234e+04 1.01284551e+04 9.83107617e+03 9.98411035e+03 1.00227412e+04 9.95415039e+03 9.95107812e+03 1.03136279e+04 1.00929639e+04 9.91450879e+03 1.05573164e+04 1.06948135e+04 1.03454268e+04 1.03404678e+04 1.03877891e+04 1.05201357e+04 1.02412764e+04 1.01888740e+04 1.08732168e+04 1.09426045e+04 1.03255195e+04 1.02095527e+04 1.08377080e+04 1.13253828e+04 1.10739395e+04 1.07140713e+04 1.06920957e+04 1.11479883e+04 1.11356064e+04 1.09216543e+04 1.11333926e+04 1.08809844e+04 1.06133633e+04 1.11549629e+04 1.16284590e+04 1.15847715e+04 1.11666377e+04 1.09312656e+04 1.15367676e+04 1.18478916e+04 1.14931680e+04 1.12340342e+04 1.13033076e+04 1.14454395e+04 1.14776494e+04 1.19248740e+04 1.17582686e+04 1.14107969e+04 1.17003496e+04 1.17544951e+04 1.19628633e+04 1.17186904e+04 1.15227861e+04 1.20393457e+04 1.20859961e+04 1.19586709e+04 1.17163574e+04 1.17862549e+04 1.25274189e+04 1.21239580e+04 1.17707295e+04 1.21143760e+04 1.21328936e+04 1.22045195e+04 1.22395332e+04 1.25475225e+04 1.26545303e+04 1.23178340e+04 1.20017363e+04 1.20053184e+04 1.27113389e+04 1.25728779e+04 1.22324658e+04 1.24515801e+04 1.25150957e+04 1.25746992e+04 1.25707061e+04 1.28294980e+04 1.25271846e+04 1.22579062e+04 1.28697725e+04 1.29424697e+04 1.27932109e+04 1.28673936e+04 1.28122949e+04 1.28097549e+04 1.25078828e+04 1.23786592e+04 1.30401279e+04 1.33450283e+04 1.27682188e+04 1.24188574e+04 1.30203037e+04 1.35577861e+04 1.32237676e+04 1.27468594e+04 1.26063105e+04 1.32140020e+04 1.33655459e+04 1.30120186e+04 1.33158633e+04 1.33620537e+04 1.29751465e+04 1.29203242e+04 1.33251992e+04 1.35749277e+04 1.29860566e+04 1.27732168e+04 1.35010859e+04 1.37984951e+04 1.33931572e+04 1.29609150e+04 1.28740508e+04 1.36024238e+04 1.38165605e+04 1.32994541e+04 1.32195586e+04 1.33766299e+04 1.33421807e+04 1.32493545e+04 1.37923574e+04 1.35257676e+04 1.30567773e+04 1.37117656e+04 1.38351016e+04 1.36575508e+04 1.33796709e+04 1.31919541e+04 1.40693633e+04 1.45676973e+04 1.39572705e+04 1.38374297e+04 1.69489551e+04 2.64750664e+04 4.14681016e+04 7.25566016e+04 6.53525352e+04 4.10464336e+04 2.76412422e+04 1.97561172e+04 2.51191816e+04 3.39607344e+04 4.21615703e+04 5.46899961e+04 1.56053250e+05 2.64747094e+05 -1265534080. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.17923768e+10 -2.17923768e+10 -1.08961884e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.34501181e+10 2.07796906e+05 5.66802969e+04 1.02930498e+04 4.40683516e+04 2.77774336e+04 1.94421582e+04 1.74611211e+04 1.08284951e+04 1.46194053e+04 1.44779736e+04 1.38231416e+04 1.40682422e+04 1.37593574e+04 1.36994697e+04 1.38567227e+04 1.35010928e+04 1.34668047e+04 1.35482930e+04 1.33319824e+04 1.35774883e+04 1.38921602e+04 1.38412803e+04 1.34202256e+04 1.33507373e+04 1.35166426e+04 1.31762031e+04 1.33028975e+04 1.37455469e+04 1.35684502e+04 1.35595137e+04 1.36318789e+04 1.33321592e+04 1.32831943e+04 1.34016523e+04 1.32672471e+04 1.31302715e+04 1.34564443e+04 1.37078027e+04 1.33069482e+04 1.31389658e+04 1.32478516e+04 1.33063623e+04 1.34054883e+04 1.32537578e+04 1.29261016e+04 1.32347354e+04 1.35086582e+04 1.30653115e+04 1.29971465e+04 1.31805059e+04 1.29115068e+04 1.29663574e+04 1.33087324e+04 1.31274629e+04 1.29067627e+04 1.30481309e+04 1.33695752e+04 1.30781475e+04 1.26477939e+04 1.26166250e+04 1.26558643e+04 1.30481074e+04 1.32510225e+04 1.28757725e+04 1.27068945e+04 1.26469209e+04 1.26196416e+04 1.26559814e+04 1.26253350e+04 1.24922061e+04 1.26431992e+04 1.29700098e+04 1.27034180e+04 1.24257578e+04 1.26088721e+04 1.25538389e+04 1.24395947e+04 1.25172861e+04 1.25101338e+04 1.23634717e+04 1.22212637e+04 1.24383574e+04 1.23744902e+04 1.23426123e+04 1.23446758e+04 1.19862861e+04 1.21863936e+04 1.24848867e+04 1.21532461e+04 1.19983545e+04 1.20707783e+04 1.19994775e+04 1.20407822e+04 1.19770215e+04 1.17674121e+04 1.19620762e+04 1.22345469e+04 1.19768916e+04 1.15950176e+04 1.16152373e+04 1.18889121e+04 1.18264932e+04 1.16608711e+04 1.16110654e+04 1.14801172e+04 1.17113770e+04 1.19675869e+04 1.15288135e+04 1.12558945e+04 1.12413057e+04 1.12966025e+04 1.14384648e+04 1.15132383e+04 1.13099248e+04 1.12215020e+04 1.14999004e+04 1.14364150e+04 1.11211016e+04 1.08866406e+04 1.08610312e+04 1.10562031e+04 1.11642285e+04 1.11392461e+04 1.09432676e+04 1.09365986e+04 1.09784980e+04 1.06959453e+04 1.06054131e+04 1.06860674e+04 1.06297676e+04 1.07639268e+04 1.08623906e+04 1.04550352e+04 1.03672334e+04 1.06274902e+04 1.05184414e+04 1.02052451e+04 1.03014854e+04 1.05494893e+04 1.04519141e+04 1.03016162e+04 1.02050195e+04 1.01098701e+04 1.01034961e+04 9.96156348e+03 9.98791699e+03 1.00264795e+04 9.96191309e+03 9.96096973e+03 9.97253320e+03 9.91183203e+03 9.52705859e+03 9.63010156e+03 9.83930273e+03 9.68148633e+03 9.73371875e+03 9.82162500e+03 9.65491895e+03 9.38721289e+03 9.37513770e+03 9.26493652e+03 9.16014844e+03 9.29167676e+03 9.38616895e+03 9.27258203e+03 9.15288184e+03 9.06841211e+03 8.97685449e+03 8.96337988e+03 8.91157812e+03 8.85456738e+03 8.90969629e+03 8.95870801e+03 8.78943848e+03 8.69892285e+03 8.68264551e+03 8.68841406e+03 8.62996582e+03 8.56137402e+03 8.51039062e+03 8.53162402e+03 8.44151465e+03 8.37051367e+03 8.30179297e+03 8.34465918e+03 8.39129297e+03 8.03208643e+03 8.00784375e+03 8.24189648e+03 8.06684131e+03 8.04192139e+03 8.00982080e+03 7.81723047e+03 7.77270557e+03 7.79632324e+03 7.67431836e+03 7.60378516e+03 7.66230176e+03 7.75112158e+03 7.76367334e+03 7.59864111e+03 7.47914746e+03 7.42582568e+03 7.30216309e+03 7.25143213e+03 7.22550586e+03 7.28758740e+03 7.39395801e+03 7.12571240e+03 6.96339404e+03 7.08608447e+03 6.89619629e+03 6.94462158e+03 7.03860742e+03 6.82459912e+03 6.79062598e+03 6.76817529e+03 6.77363379e+03 6.71111572e+03 6.58416211e+03 6.49040723e+03 6.41402051e+03 6.43834326e+03 6.47129443e+03 6.43294385e+03 6.36344531e+03 6.32154346e+03 6.28368506e+03 6.20559082e+03 6.21029053e+03 6.17398486e+03 6.00761572e+03 5.89311768e+03 5.92672559e+03 5.93327051e+03 5.89829883e+03 5.80783789e+03 5.75409570e+03 5.72452441e+03 5.65581201e+03 5.65544824e+03 5.61277197e+03 5.63764258e+03 5.56708740e+03 5.32285303e+03 5.36270703e+03 5.33507129e+03 5.28774219e+03 5.31697314e+03 5.15795557e+03 5.07152637e+03 5.20931348e+03 5.16998535e+03 4.92798242e+03 4.87590137e+03 4.98602832e+03 4.95328223e+03 4.79635400e+03 4.79993750e+03 4.84511768e+03 4.66659668e+03 4.61895703e+03 4.61707764e+03 4.50360889e+03 4.52641309e+03 4.53676416e+03 4.37176367e+03 4.40518945e+03 4.44138330e+03 4.33957422e+03 4.22077002e+03 4.11294727e+03 4.17736328e+03 4.20778955e+03 4.05637695e+03 3.97863306e+03 3.99310327e+03 3.95177368e+03 3.87977612e+03 3.84886353e+03 3.83302612e+03 3.78191724e+03 3.70404272e+03 3.69683569e+03 3.71304663e+03 3.60014331e+03 3.53945190e+03 3.53884521e+03 3.41725049e+03 3.46870264e+03 3.46171216e+03 3.30104541e+03 3.32597754e+03 3.28737598e+03 3.19189233e+03 3.20787207e+03 3.15372070e+03 3.12282227e+03 3.14071582e+03 3.04032544e+03 2.98736475e+03 2.93130542e+03 2.87019873e+03 2.85250073e+03 2.82645483e+03 2.82150513e+03 2.80097168e+03 2.73870312e+03 2.69924463e+03 2.68733423e+03 2.61610156e+03 2.53274023e+03 2.50173779e+03 2.51909546e+03 2.50952979e+03 2.38823047e+03 2.31963794e+03 2.34811499e+03 2.35465210e+03 2.28234985e+03 2.22732178e+03 2.20331006e+03 2.17394409e+03 2.17913647e+03 2.12963208e+03 2.06629517e+03 1.99434790e+03 1.97526868e+03 1.97546777e+03 1.93060376e+03 1.91627930e+03 1.89863745e+03 1.84023645e+03 1.80842554e+03 1.81305579e+03 1.75492957e+03 1.69203906e+03 1.68191968e+03 1.67646216e+03 1.62534668e+03 1.55164062e+03 1.51921069e+03 1.52735022e+03 1.52260596e+03 1.47887939e+03 1.43221875e+03 1.40212158e+03 1.39821191e+03 1.36494226e+03 1.29848987e+03 1.28182434e+03 1.27105249e+03 1.26045068e+03 1.21637109e+03 1.15667554e+03 1.14960266e+03 1.13765283e+03 1.12148596e+03 1.10666809e+03 1.07070203e+03 1.02033142e+03 9.77532166e+02 9.80141357e+02 9.86183899e+02 9.42358643e+02 9.00874634e+02 8.74453552e+02 8.63848694e+02 8.58888733e+02 8.15630737e+02 7.87192322e+02 7.73912537e+02 7.64511780e+02 7.46570129e+02 6.97883484e+02 6.89959290e+02 6.78604004e+02 6.45169373e+02 6.30149170e+02 6.03794250e+02 5.83275574e+02 5.69020386e+02 5.49567017e+02 5.32849670e+02 5.18192200e+02 5.00556244e+02 4.74544922e+02 4.62701752e+02 4.52606079e+02 4.31184814e+02 4.11497192e+02 3.87518799e+02 3.79052124e+02 3.76877808e+02 3.55836853e+02 3.35572845e+02 3.16714508e+02 3.07039825e+02 3.02946228e+02 2.83684296e+02 2.68551605e+02 2.59750031e+02 2.44222610e+02 2.26037537e+02 2.17152588e+02 2.10700119e+02 1.98309509e+02 1.88871353e+02 1.75593307e+02 1.60976166e+02 1.55487991e+02 1.48545715e+02 1.38795868e+02 1.31534348e+02 1.21454239e+02 1.12882988e+02 1.03968277e+02 9.63640976e+01 9.10486221e+01 8.38304901e+01 7.63332214e+01 6.94272079e+01 6.43529892e+01 5.86473312e+01 5.37338791e+01 5.04861984e+01 4.57574463e+01 4.07662811e+01 3.63749313e+01 3.26084290e+01 2.97504654e+01 2.76011562e+01 2.52181644e+01 2.25395813e+01 2.04825516e+01 1.91102543e+01 1.81808300e+01 1.74249554e+01 1.69151287e+01 1.67412834e+01 1.69344139e+01 1.74149017e+01 1.81729202e+01 1.92911148e+01 2.08011780e+01 2.26352310e+01 2.46009293e+01 2.69645271e+01 3.03954124e+01 3.39728737e+01 3.71112938e+01 4.03540344e+01 4.45186844e+01 5.00821686e+01 5.57365456e+01 6.02453842e+01 6.45642700e+01 7.01669312e+01 7.72845917e+01 8.47604828e+01 9.12337036e+01 9.76374207e+01 1.03497162e+02 1.11686836e+02 1.21882721e+02 1.29295242e+02 1.38521225e+02 1.47461884e+02 1.56513580e+02 1.66637558e+02 1.76239960e+02 1.83794739e+02 1.95187515e+02 2.10969330e+02 2.23348236e+02 2.34911758e+02 2.41953049e+02 2.54452133e+02 2.67205170e+02 2.82413879e+02 3.02660095e+02 3.08300110e+02 3.21065826e+02 3.43083252e+02 3.49319580e+02 3.61877594e+02 3.86629547e+02 4.00725006e+02 4.13198883e+02 4.34589447e+02 4.43201996e+02 4.49692108e+02 4.82447479e+02 5.07355469e+02 5.14108276e+02 5.40956177e+02 5.59510742e+02 5.59216736e+02 5.84538208e+02 6.09461365e+02 6.25017883e+02 6.55493530e+02 6.74862122e+02 6.91378357e+02 7.17591125e+02 7.37628723e+02 7.60889587e+02 7.70712585e+02 7.83206604e+02 8.17194031e+02 8.45034241e+02 8.57193909e+02 8.83358765e+02 9.15755859e+02 9.28069702e+02 9.62657776e+02 9.91744019e+02 1.01230688e+03 1.04433752e+03 1.03973340e+03 1.07165845e+03 1.13362378e+03 1.14830627e+03 1.16438330e+03 1.19968066e+03 1.22168213e+03 1.24478064e+03 1.27577917e+03 1.26366382e+03 1.29319373e+03 1.37134058e+03 1.41330005e+03 1.43139758e+03 1.41995642e+03 1.44533362e+03 1.51880481e+03 1.53868103e+03 1.54978088e+03 1.59112708e+03 1.61695435e+03 1.65150415e+03 1.69536975e+03 1.74485767e+03 1.75526843e+03 1.75571643e+03 1.83795032e+03 1.84744409e+03 1.85450183e+03 1.90152759e+03 1.91537732e+03 1.97810876e+03 2.05505322e+03 2.07361206e+03 2.05269653e+03 2.08667773e+03 2.16228369e+03 2.20682837e+03 2.23296826e+03 2.23732178e+03 2.29982495e+03 2.34590552e+03 2.36787354e+03 2.41652783e+03 2.43748120e+03 2.47234058e+03 2.52575952e+03 2.47505151e+03 2.51504834e+03 2.66865552e+03 2.68391504e+03 2.68288013e+03 2.71253394e+03 2.72649731e+03 2.76409546e+03 2.89335181e+03 2.95142749e+03 2.91712451e+03 2.92571143e+03 2.94850122e+03 3.01836182e+03 3.10602368e+03 3.14809375e+03 3.18976050e+03 3.18444312e+03 3.24930444e+03 3.28016992e+03 3.25761841e+03 3.31846094e+03 3.43783154e+03 3.48891016e+03 3.47423169e+03 3.51050073e+03 3.56573975e+03 3.61100122e+03 3.61184521e+03 3.70898804e+03 3.75342847e+03 3.77374805e+03 3.81366211e+03 3.84786353e+03 4.00635278e+03 3.94136108e+03 3.94924854e+03 4.09931348e+03 4.05938452e+03 4.07642993e+03 4.19808936e+03 4.26260596e+03 4.23835156e+03 4.41801123e+03 4.51655615e+03 4.46615234e+03 4.86137549e+03 4.76878906e+03 5.80918066e+03 6.39157910e+03 6.94052832e+03 6.91204736e+03 7.09926123e+03 7.39457617e+03 7.98302441e+03 7.13240137e+03 1.25417061e+04 2.09168418e+04 -12360666. -13550051. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 49187952. 2.34669375e+06 -12577004. 3262850. 2.54608906e+04 1.74142461e+04 1.11089971e+04 8.94672168e+03 7.91552930e+03 7.45133887e+03 7.51432373e+03 7.64951709e+03 7.46321729e+03 7.44409668e+03 7.57202441e+03 7.57439258e+03 7.76221436e+03 7.80550098e+03 7.67389062e+03 7.62956250e+03 7.86270703e+03 7.96795557e+03 7.96955273e+03 8.03868164e+03 7.83954639e+03 7.89202539e+03 8.32871484e+03 8.19374219e+03 8.03916064e+03 8.00282031e+03 8.22378125e+03 8.58508105e+03 8.69864453e+03 8.46353418e+03 8.19695312e+03 8.31612500e+03 8.60909277e+03 8.67516797e+03 8.68059863e+03 8.63000098e+03 8.74296289e+03 8.87012500e+03 8.94231641e+03 8.96492480e+03 8.69589160e+03 8.87389648e+03 9.50429883e+03 9.10953906e+03 8.91353027e+03 9.05133691e+03 9.03797656e+03 9.46049609e+03 9.52445898e+03 9.24955859e+03 9.22177539e+03 9.52198828e+03 9.77263867e+03 9.55099609e+03 9.50042773e+03 9.38376660e+03 9.65435547e+03 9.95455371e+03 9.66481250e+03 9.75002734e+03 9.71951953e+03 9.71755859e+03 1.00871084e+04 1.01706016e+04 1.00167812e+04 9.88722852e+03 1.01040449e+04 1.02175527e+04 1.01887666e+04 1.03191953e+04 9.99716895e+03 1.00898135e+04 1.06927773e+04 1.04309346e+04 1.00820117e+04 1.00817744e+04 1.05782217e+04 1.09901934e+04 1.06863818e+04 1.06365098e+04 1.05376035e+04 1.03819336e+04 1.07098926e+04 1.10347119e+04 1.08210195e+04 1.05874951e+04 1.09360996e+04 1.09975430e+04 1.09532236e+04 1.12806680e+04 1.09054385e+04 1.08931016e+04 1.14600654e+04 1.12630068e+04 1.10642217e+04 1.10563574e+04 1.10620146e+04 1.14795098e+04 1.15889414e+04 1.12686416e+04 1.12202910e+04 1.15703311e+04 1.16785645e+04 1.15142549e+04 1.16459004e+04 1.15506016e+04 1.14765840e+04 1.18865361e+04 1.18239863e+04 1.15118496e+04 1.14426934e+04 1.16831592e+04 1.21347061e+04 1.22308457e+04 1.20064092e+04 1.16214980e+04 1.15620576e+04 1.22016689e+04 1.22554209e+04 1.19737705e+04 1.18793691e+04 1.20897549e+04 1.23502207e+04 1.21369873e+04 1.21389229e+04 1.20343340e+04 1.22779785e+04 1.26879854e+04 1.23661338e+04 1.23107959e+04 1.23805898e+04 1.22550771e+04 1.25366914e+04 1.25903330e+04 1.24286543e+04 1.23126934e+04 1.24545225e+04 1.28633359e+04 1.28508984e+04 1.27469824e+04 1.24699668e+04 1.24257637e+04 1.29130889e+04 1.30297354e+04 1.28315859e+04 1.25099248e+04 1.24174688e+04 1.28718672e+04 1.31250811e+04 1.29809756e+04 1.27387959e+04 1.27943838e+04 1.29395508e+04 1.30709883e+04 1.32642988e+04 1.29381230e+04 1.28796250e+04 1.32115225e+04 1.31369424e+04 1.30175225e+04 1.29521494e+04 1.31889502e+04 1.32992705e+04 1.30788125e+04 1.30601826e+04 1.30032031e+04 1.32746777e+04 1.37362627e+04 1.34592354e+04 1.29875664e+04 1.29659424e+04 1.32456846e+04 1.35588184e+04 1.36830820e+04 1.37067686e+04 1.31867178e+04 1.27773340e+04 1.33050273e+04 1.38155605e+04 1.37541963e+04 1.32149004e+04 1.31644404e+04 1.35232432e+04 1.36392539e+04 1.37309102e+04 1.34702334e+04 1.33612148e+04 1.35408086e+04 1.34970742e+04 1.34965430e+04 1.34987295e+04 1.35252803e+04 1.37922725e+04 1.36399932e+04 1.35136074e+04 1.35220283e+04 1.37345898e+04 1.38740049e+04 1.35242021e+04 1.34233232e+04 1.33885586e+04 1.38392402e+04 1.41585723e+04 1.37372061e+04 1.35061396e+04 1.32724453e+04 1.34123672e+04 1.40836084e+04 1.41434707e+04 1.38409336e+04 1.33636240e+04 1.32607256e+04 1.40360752e+04 1.41795479e+04 1.36337881e+04 1.36553564e+04 1.39480107e+04 1.38228691e+04 1.35514473e+04 1.32894395e+04 1.32249219e+04 1.35649443e+04 1.37980420e+04 1.42487764e+04 1.40035986e+04 1.32579082e+04 1.36083164e+04 1.37894268e+04 1.37149111e+04 1.38276816e+04 1.36458174e+04 1.40197344e+04 1.39695049e+04 1.32429307e+04 1.31098721e+04 1.34017832e+04 1.40054756e+04 1.45150557e+04 1.41178613e+04 1.33204385e+04 1.29539404e+04 1.32179463e+04 1.39695947e+04 1.44421826e+04 1.40411250e+04 1.32340469e+04 1.31985508e+04 1.40831504e+04 1.40192637e+04 1.33326680e+04 1.32925439e+04 1.34590752e+04 1.34686934e+04 1.38903057e+04 1.36786006e+04 1.31273291e+04 1.34360684e+04 1.32530381e+04 1.35102598e+04 1.37953857e+04 1.31568105e+04 1.34303291e+04 1.37681875e+04 1.34302012e+04 1.33861523e+04 1.34065498e+04 1.34618008e+04 1.34490293e+04 1.33388291e+04 1.29983809e+04 1.29545352e+04 1.35872314e+04 1.39818613e+04 1.36362441e+04 1.29799336e+04 1.26558877e+04 1.28906006e+04 1.34682461e+04 1.38533633e+04 1.35173105e+04 1.28009277e+04 1.28374775e+04 1.32167715e+04 1.31481357e+04 1.29874199e+04 1.29858711e+04 1.30178262e+04 1.29619766e+04 1.33410107e+04 1.30351201e+04 1.26703232e+04 1.29286152e+04 1.25849844e+04 1.28834980e+04 1.31699268e+04 1.27845176e+04 1.31978818e+04 1.28529395e+04 1.22960312e+04 1.27274395e+04 1.24222197e+04 1.25760430e+04 1.34358301e+04 1.27687139e+04 1.19462588e+04 1.21460430e+04 1.27875039e+04 1.32808633e+04 1.29143623e+04 1.22139893e+04 1.19115684e+04 1.20577041e+04 1.25393135e+04 1.29879570e+04 1.26729805e+04 1.20008281e+04 1.19580713e+04 1.22830811e+04 1.22916006e+04 1.21317705e+04 1.20556943e+04 1.20896777e+04 1.20690107e+04 1.24332432e+04 1.24165479e+04 1.16096348e+04 1.15656553e+04 1.19705400e+04 1.19268145e+04 1.18869248e+04 1.18575205e+04 1.21273994e+04 1.18246660e+04 1.14009912e+04 1.16782627e+04 1.13101904e+04 1.16070811e+04 1.22885576e+04 1.15614590e+04 1.08995645e+04 1.11898262e+04 1.17059189e+04 1.20231982e+04 1.18377139e+04 1.11117129e+04 1.07140312e+04 1.09714561e+04 1.15000596e+04 1.17977295e+04 1.14403037e+04 1.08021396e+04 1.07804619e+04 1.10775186e+04 1.11044580e+04 1.12403330e+04 1.12565986e+04 1.06510332e+04 1.05433525e+04 1.10422715e+04 1.10722422e+04 1.05295215e+04 1.04137158e+04 1.06468682e+04 1.05749365e+04 1.08160957e+04 1.08937744e+04 1.04065791e+04 1.03072764e+04 1.02481016e+04 1.02058672e+04 1.03572266e+04 1.02545459e+04 1.04739668e+04 1.05871172e+04 1.01884639e+04 9.84185156e+03 9.62476660e+03 1.00276943e+04 1.05338799e+04 1.02127734e+04 9.70598730e+03 9.36412500e+03 9.68320996e+03 1.02018418e+04 9.86872559e+03 9.28376270e+03 9.34788086e+03 9.60568262e+03 9.83100195e+03 1.01196113e+04 9.77681934e+03 9.15348145e+03 9.05362109e+03 9.29796387e+03 9.33827832e+03 9.36809473e+03 9.27120020e+03 9.19538281e+03 9.05569922e+03 9.21396387e+03 9.13809668e+03 8.82834082e+03 8.79553223e+03 8.67665625e+03 8.97565332e+03 9.05815332e+03 8.71328125e+03 8.82360547e+03 8.74233594e+03 8.62515625e+03 8.43384277e+03 8.23876758e+03 8.50475293e+03 8.86280762e+03 8.62072461e+03 8.18662305e+03 8.02398535e+03 8.35916602e+03 8.52214160e+03 8.32831836e+03 8.15968555e+03 7.83243359e+03 7.79639062e+03 8.05836572e+03 8.04084863e+03 7.76133789e+03 7.58526611e+03 7.49722852e+03 7.89317432e+03 8.09842969e+03 7.61508545e+03 7.37402881e+03 7.57316064e+03 7.53101318e+03 7.66789160e+03 7.56783154e+03 7.10819189e+03 7.12909717e+03 7.31169043e+03 7.23737500e+03 7.25847119e+03 7.29354199e+03 7.20283936e+03 6.86761230e+03 6.61735938e+03 6.87359521e+03 8.70944824e+03 9.12428125e+03 1.07823447e+04 1.04171484e+04 9.83601953e+03 9.71737305e+03 1.00132061e+04 1.08151143e+04 1.03682266e+04 1.02686289e+04 1.01279209e+04 1.67815195e+04 2.59542832e+04 -8588070. 42812980. 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. 0. 0. 0. 0. 0. 0. 23285380. 6714477. -2.74762575e+06 -2.40671625e+06 -49063760. 1.11817402e+04 1.03157471e+04 6.38937939e+03 4.67497656e+03 4.43600049e+03 4.15754688e+03 3.97958936e+03 4.14684521e+03 4.10340332e+03 3.95464624e+03 3.92679102e+03 3.87095459e+03 3.81830347e+03 3.78544385e+03 3.72921191e+03 3.66519556e+03 3.65014087e+03 3.58330200e+03 3.57783984e+03 3.55007422e+03 3.39829980e+03 3.36703687e+03 3.49176978e+03 3.44825073e+03 3.32802075e+03 3.26860718e+03 3.23459473e+03 3.20053345e+03 3.18301904e+03 3.13180005e+03 3.06633643e+03 3.02539478e+03 2.95552515e+03 2.91202612e+03 2.96942554e+03 2.93592114e+03 2.84300098e+03 2.80354980e+03 2.77638257e+03 2.74491602e+03 2.68489722e+03 2.64394434e+03 2.61611792e+03 2.54192163e+03 2.49484595e+03 2.46520801e+03 2.42419067e+03 2.50081885e+03 2.47607056e+03 2.36059448e+03 2.24959131e+03 2.20798120e+03 2.31130151e+03 2.28905005e+03 2.17395410e+03 2.09234595e+03 2.06246338e+03 2.06849536e+03 2.02434924e+03 2.06459082e+03 2.02619409e+03 1.87142200e+03 1.80884583e+03 1.87132922e+03 1.94537097e+03 1.85797351e+03 1.77466077e+03 1.74420251e+03 1.69850659e+03 1.68228687e+03 1.66325110e+03 1.60934412e+03 1.56821582e+03 1.54454626e+03 1.51348120e+03 1.48882520e+03 1.45691785e+03 1.46889392e+03 1.43835876e+03 1.37018018e+03 1.33087488e+03 1.30774585e+03 1.32054150e+03 1.29461401e+03 1.24039026e+03 1.21759033e+03 1.15909436e+03 1.10503613e+03 1.13506531e+03 1.12555298e+03 1.04322705e+03 1.02651562e+03 1.05988550e+03 1.06373999e+03 1.00804108e+03 9.52495911e+02 9.32025208e+02 9.13819458e+02 8.78078430e+02 8.50658020e+02 8.36300354e+02 8.10005249e+02 8.15614990e+02 7.89560425e+02 7.45008789e+02 7.22637146e+02 6.86606445e+02 6.83617554e+02 6.98859863e+02 6.66401367e+02 6.30556396e+02 5.95389160e+02 5.68669373e+02 5.81768616e+02 5.73413574e+02 5.36815186e+02 5.03664520e+02 4.84664795e+02 4.78073334e+02 4.60936646e+02 4.58435913e+02 4.45482605e+02 4.13219971e+02 3.88751221e+02 3.73220825e+02 3.72230530e+02 3.58500702e+02 3.37299805e+02 3.20458130e+02 3.05123993e+02 2.90452209e+02 2.71276520e+02 2.65808685e+02 2.66783234e+02 2.50139954e+02 2.32077301e+02 2.14935150e+02 2.02582458e+02 2.02187729e+02 1.92367325e+02 1.77088226e+02 1.62653519e+02 1.52418869e+02 1.47232651e+02 1.37687515e+02 1.28752411e+02 1.17609756e+02 1.11630898e+02 1.08223396e+02 9.78313141e+01 8.97156448e+01 8.36081772e+01 7.70475388e+01 6.95123215e+01 6.35777397e+01 5.83352890e+01 5.32967377e+01 4.89734001e+01 4.38579102e+01 4.03988304e+01 3.77755699e+01 3.33389549e+01 2.97173195e+01 2.72376251e+01 2.47549362e+01 2.28079605e+01 2.08494701e+01 1.92167950e+01 1.81592770e+01 1.73840828e+01 1.69046021e+01 1.67399750e+01 1.69075565e+01 1.74296036e+01 1.83126431e+01 1.94979935e+01 2.08652878e+01 2.28405495e+01 2.55212803e+01 2.78103123e+01 3.02996254e+01 3.32049828e+01 3.70191231e+01 4.20843697e+01 4.59886284e+01 4.96657181e+01 5.36134758e+01 5.83967819e+01 6.52448425e+01 7.11890717e+01 7.85928726e+01 8.47797089e+01 8.98848801e+01 9.81537399e+01 1.04995926e+02 1.15326393e+02 1.24279343e+02 1.29723846e+02 1.38112625e+02 1.47401917e+02 1.57231659e+02 1.62731903e+02 1.74918091e+02 1.94481567e+02 2.03208755e+02 2.09253067e+02 2.15324326e+02 2.25790878e+02 2.50085297e+02 2.63261017e+02 2.69093994e+02 2.76533539e+02 2.87928162e+02 3.10595551e+02 3.24304199e+02 3.44612305e+02 3.58170776e+02 3.63112152e+02 3.75091278e+02 3.90233093e+02 4.23478333e+02 4.41267365e+02 4.45914825e+02 4.56343903e+02 4.71864288e+02 5.06761078e+02 5.26574829e+02 5.19249756e+02 5.37517273e+02 5.88656677e+02 6.04283447e+02 5.93601501e+02 6.11082397e+02 6.62504761e+02 6.89740112e+02 6.86126343e+02 6.89516846e+02 7.13766663e+02 7.76133240e+02 7.91790833e+02 7.91350098e+02 8.23045776e+02 8.40779846e+02 8.45233643e+02 8.69585938e+02 9.15292236e+02 9.17824219e+02 9.55522766e+02 1.01955792e+03 1.02223993e+03 1.05373718e+03 1.07663184e+03 1.08335510e+03 1.11183191e+03 1.13244897e+03 1.15847388e+03 1.16341406e+03 1.17617480e+03 1.22738684e+03 1.28054651e+03 1.34526404e+03 1.32569922e+03 1.31778186e+03 1.38597974e+03 1.41247717e+03 1.48239954e+03 1.50867175e+03 1.49780139e+03 1.49998328e+03 1.51859558e+03 1.59179895e+03 1.62189062e+03 1.68407947e+03 1.71829285e+03 1.70712085e+03 1.73011633e+03 1.71914526e+03 1.79838159e+03 1.92520618e+03 1.92959302e+03 1.91072644e+03 1.89802551e+03 1.92460925e+03 2.04640723e+03 2.09650977e+03 2.08460571e+03 2.06474219e+03 2.08839893e+03 2.16981006e+03 2.21358496e+03 2.30813696e+03 2.33255176e+03 2.31029980e+03 2.34602710e+03 2.36855957e+03 2.46662329e+03 2.51832544e+03 2.43596655e+03 2.46954761e+03 2.65370166e+03 2.63939087e+03 2.53863989e+03 2.65927686e+03 2.83868921e+03 2.85084985e+03 2.81611035e+03 2.76489941e+03 2.81334424e+03 3.01223096e+03 3.03973242e+03 2.99303296e+03 2.97201636e+03 2.98462793e+03 3.09425879e+03 3.16157568e+03 3.20986499e+03 3.16852026e+03 3.26611206e+03 3.47388354e+03 3.43431714e+03 3.42476660e+03 3.45390430e+03 3.46591650e+03 3.53053198e+03 3.57299707e+03 3.63305640e+03 3.65450122e+03 3.68146143e+03 3.63993726e+03 3.71825195e+03 3.96607251e+03 3.84498218e+03 3.75420898e+03 3.89512305e+03 4.06538428e+03 4.21392969e+03 4.18877295e+03 4.12859082e+03 4.19952734e+03 4.20939697e+03 4.17588672e+03 4.21138623e+03 4.40101953e+03 4.45998438e+03 4.39032129e+03 4.40966162e+03 4.34510547e+03 4.53007178e+03 4.85814746e+03 4.75933447e+03 4.69952295e+03 4.63197412e+03 4.67122705e+03 4.97631592e+03 5.09114453e+03 4.97284766e+03 4.89107861e+03 4.91432178e+03 5.03499219e+03 5.10001416e+03 5.30331250e+03 5.31285547e+03 5.20661621e+03 5.26664111e+03 5.31145312e+03 5.47646826e+03 5.53222266e+03 5.43365869e+03 5.58117920e+03 5.62762305e+03 5.56187207e+03 5.45559570e+03 5.67681494e+03 6.00556738e+03 5.96004883e+03 5.87790576e+03 5.77619092e+03 5.82800830e+03 6.22692188e+03 6.27513135e+03 6.09259717e+03 6.03696143e+03 6.04309521e+03 6.18536768e+03 6.21959375e+03 6.34508643e+03 6.28344531e+03 6.44521826e+03 6.74953613e+03 6.56362891e+03 6.67575342e+03 6.77323779e+03 6.66306592e+03 6.76923193e+03 6.78168115e+03 6.64847559e+03 6.71559229e+03 6.96399902e+03 7.06272559e+03 7.10712695e+03 7.13419482e+03 6.94119189e+03 6.93298584e+03 7.21394824e+03 7.28659814e+03 7.51456592e+03 7.46393262e+03 7.24462891e+03 7.45889014e+03 7.62380029e+03 7.59791943e+03 7.51393457e+03 7.51499316e+03 7.70853418e+03 7.73923730e+03 7.71145410e+03 7.65262256e+03 7.80726904e+03 8.22918750e+03 8.21855859e+03 8.00616748e+03 7.82023926e+03 7.93990967e+03 8.36199219e+03 8.40161621e+03 8.27156934e+03 8.10574707e+03 8.00435303e+03 8.31458691e+03 8.54221973e+03 8.87862695e+03 8.62287402e+03 8.30251660e+03 8.51694434e+03 8.66181738e+03 8.96079004e+03 8.83498828e+03 8.62783203e+03 8.91551660e+03 8.94282617e+03 8.95281836e+03 8.78510938e+03 8.88593164e+03 9.44526172e+03 9.41391016e+03 9.16536426e+03 8.96325488e+03 9.07659863e+03 9.61269531e+03 9.60778320e+03 9.41648438e+03 9.23270020e+03 9.20741113e+03 9.51934082e+03 9.56217969e+03 9.95667578e+03 9.92105859e+03 9.59352051e+03 9.45476562e+03 9.61564844e+03 1.01787578e+04 1.00085459e+04 9.80756543e+03 1.00405146e+04 1.01372666e+04 9.85802148e+03 9.75487305e+03 1.02086689e+04 1.01625215e+04 9.96612109e+03 1.05178105e+04 1.06834092e+04 1.04120918e+04 1.03820869e+04 1.03867979e+04 1.04682510e+04 1.02594775e+04 1.02293389e+04 1.07565400e+04 1.09443594e+04 1.04276758e+04 1.02455898e+04 1.07481904e+04 1.11965820e+04 1.11416787e+04 1.08157705e+04 1.05842607e+04 1.09862588e+04 1.13219873e+04 1.11769297e+04 1.10618516e+04 1.07844648e+04 1.05580557e+04 1.11722539e+04 1.17479180e+04 1.15150850e+04 1.10638125e+04 1.09782803e+04 1.16019766e+04 1.17961240e+04 1.14330605e+04 1.11640156e+04 1.11326699e+04 1.13323271e+04 1.14822773e+04 1.19484023e+04 1.19555781e+04 1.15778994e+04 1.16119180e+04 1.16343799e+04 1.19405176e+04 1.17287910e+04 1.15255381e+04 1.21158545e+04 1.22085127e+04 1.18527334e+04 1.15150557e+04 1.17895576e+04 1.25369531e+04 1.20774268e+04 1.16177939e+04 1.20119766e+04 1.22838945e+04 1.23124053e+04 1.22094951e+04 1.25499180e+04 1.27038105e+04 1.23027393e+04 1.19465137e+04 1.20066807e+04 1.27230742e+04 1.25864453e+04 1.22433848e+04 1.24590254e+04 1.25094492e+04 1.24916533e+04 1.24312412e+04 1.26919521e+04 1.25960283e+04 1.23959590e+04 1.27704082e+04 1.28096807e+04 1.29048545e+04 1.29442910e+04 1.27944785e+04 1.27079912e+04 1.23655303e+04 1.25171240e+04 1.32133232e+04 1.33764062e+04 1.27456836e+04 1.23881875e+04 1.29019238e+04 1.34318818e+04 1.33164229e+04 1.28524775e+04 1.24826162e+04 1.30742744e+04 1.34658164e+04 1.30908789e+04 1.33770723e+04 1.32546689e+04 1.27722207e+04 1.30853076e+04 1.35871133e+04 1.34836914e+04 1.28817744e+04 1.27117217e+04 1.34581562e+04 1.38440068e+04 1.33840654e+04 1.29019688e+04 1.28402451e+04 1.36270957e+04 1.36790605e+04 1.31977812e+04 1.33658926e+04 1.34527461e+04 1.33462256e+04 1.32619492e+04 1.37708848e+04 1.35285371e+04 1.30344775e+04 1.37156348e+04 1.38477715e+04 1.36364639e+04 1.33782773e+04 1.32066514e+04 1.41808486e+04 1.43026680e+04 1.28655684e+04 1.38143691e+04 1.84171367e+04 1.80546758e+04 2.05954141e+04 2.08830137e+04 2.09692500e+04 2.05376406e+04 1.99722383e+04 1.98046270e+04 2.13661465e+04 2.13515840e+04 2.10248027e+04 2.30058301e+04 1.96771680e+04 3.29228320e+04 3.70119875e+05 4.02860401e+10 0. 0. 0. 0. 0. 0. 0. -4.20160881e+10 7.30711016e+04 2.89728613e+04 4.52383672e+04 1.14269875e+05 1.01335253e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.22940477e+10 1.16487055e+05 2.87390859e+04 2.68388770e+04 1.99567168e+04 1.79384707e+04 1.09647471e+04 1.47657529e+04 1.47483564e+04 1.37890830e+04 1.38429414e+04 1.38241553e+04 1.37520215e+04 1.34179766e+04 1.34150488e+04 1.37707490e+04 1.36762539e+04 1.35476475e+04 1.35130791e+04 1.33597900e+04 1.36427100e+04 1.36681328e+04 1.34050703e+04 1.34388369e+04 1.32962227e+04 1.33430215e+04 1.37956172e+04 1.38316260e+04 1.34067256e+04 1.32675078e+04 1.34207803e+04 1.34330654e+04 1.32639648e+04 1.32423760e+04 1.33447139e+04 1.33310879e+04 1.34700049e+04 1.34027090e+04 1.29496572e+04 1.30948867e+04 1.35302256e+04 1.36022715e+04 1.35197539e+04 1.29747324e+04 1.27959014e+04 1.31711064e+04 1.33083877e+04 1.31794531e+04 1.29459990e+04 1.29573564e+04 1.31836699e+04 1.32864531e+04 1.31563105e+04 1.27523965e+04 1.26726436e+04 1.33094121e+04 1.33195947e+04 1.26185273e+04 1.25477822e+04 1.28888623e+04 1.30571172e+04 1.32193477e+04 1.28709541e+04 1.24106748e+04 1.25236631e+04 1.28250283e+04 1.29117773e+04 1.27532510e+04 1.24910156e+04 1.26055674e+04 1.27643184e+04 1.26544590e+04 1.24836396e+04 1.22882344e+04 1.24416182e+04 1.26716367e+04 1.25786562e+04 1.25674648e+04 1.24160762e+04 1.20884629e+04 1.22822383e+04 1.24065352e+04 1.23279268e+04 1.23502939e+04 1.21808232e+04 1.21120654e+04 1.23769971e+04 1.23052666e+04 1.18975400e+04 1.19023096e+04 1.21021426e+04 1.21449492e+04 1.20934971e+04 1.18762480e+04 1.18177344e+04 1.19043760e+04 1.19690137e+04 1.18727930e+04 1.15537275e+04 1.16900195e+04 1.19497324e+04 1.18337002e+04 1.17254609e+04 1.14740547e+04 1.14308877e+04 1.17464199e+04 1.15989922e+04 1.13250088e+04 1.12939502e+04 1.13572305e+04 1.15377959e+04 1.14579053e+04 1.12746914e+04 1.12947637e+04 1.12525020e+04 1.13052070e+04 1.12923506e+04 1.10480596e+04 1.10503408e+04 1.10745518e+04 1.09131172e+04 1.10161768e+04 1.09830498e+04 1.09275127e+04 1.08743350e+04 1.07396016e+04 1.07129375e+04 1.07924580e+04 1.07964268e+04 1.07182109e+04 1.05835850e+04 1.04465137e+04 1.04258623e+04 1.05435889e+04 1.04575996e+04 1.03037285e+04 1.03112334e+04 1.05326953e+04 1.05023174e+04 1.01683916e+04 1.01972295e+04 1.02093428e+04 1.01246338e+04 9.99651367e+03 9.91007910e+03 9.90537598e+03 1.00071279e+04 1.01095908e+04 1.00260176e+04 9.79505078e+03 9.55982812e+03 9.66569238e+03 9.77563477e+03 9.74065137e+03 9.62803223e+03 9.46051465e+03 9.48779004e+03 9.58284961e+03 9.55053711e+03 9.26069043e+03 9.11131152e+03 9.23437988e+03 9.45676758e+03 9.33981738e+03 8.93059570e+03 8.91169434e+03 9.15121875e+03 9.10760059e+03 8.95335938e+03 8.93204590e+03 8.94135352e+03 8.81637988e+03 8.81807715e+03 8.71699707e+03 8.52080566e+03 8.67777832e+03 8.71722559e+03 8.56761621e+03 8.55220703e+03 8.48654004e+03 8.31763965e+03 8.28200391e+03 8.35185547e+03 8.37217383e+03 8.36968750e+03 8.04247852e+03 7.97942285e+03 8.31529980e+03 8.05814355e+03 7.80956592e+03 7.92428516e+03 7.93498828e+03 7.90490234e+03 7.82846924e+03 7.77671338e+03 7.62763525e+03 7.52537988e+03 7.70852246e+03 7.76746826e+03 7.37230176e+03 7.41480322e+03 7.56569824e+03 7.40781396e+03 7.35330469e+03 7.20580811e+03 7.09365186e+03 7.22051172e+03 7.22432568e+03 7.03096289e+03 7.05601660e+03 6.89893701e+03 6.93416553e+03 7.01757861e+03 6.84079541e+03 6.78750342e+03 6.77042090e+03 6.76095557e+03 6.64005225e+03 6.60701611e+03 6.56693848e+03 6.45712012e+03 6.41798975e+03 6.47710596e+03 6.39609131e+03 6.28440771e+03 6.35716113e+03 6.33567529e+03 6.24209473e+03 6.27404688e+03 6056. 5.91253076e+03 6.01175000e+03 5.99122021e+03 5.90097412e+03 5.77637939e+03 5.67448389e+03 5.76540234e+03 5.85445605e+03 5.67694043e+03 5.58249463e+03 5.64254541e+03 5.56302588e+03 5.43287793e+03 5.34267725e+03 5.46483057e+03 5.38971533e+03 5.23396533e+03 5.32744727e+03 5.22577295e+03 5.13007129e+03 5.14535156e+03 5.04560449e+03 4.96219238e+03 4.98623828e+03 4.91048438e+03 4.84126025e+03 4.88277344e+03 4.84240137e+03 4.79704199e+03 4.65011572e+03 4.56543018e+03 4.62669141e+03 4.55214160e+03 4.54678857e+03 4.48163623e+03 4.40056592e+03 4.35251562e+03 4.33734424e+03 4.38654004e+03 4.25068799e+03 4.04071240e+03 4.17125732e+03 4.30191895e+03 4.06900586e+03 3.92994580e+03 3.94588477e+03 3.89841650e+03 3.94020386e+03 3.90813721e+03 3.77619678e+03 3.72005737e+03 3.74372070e+03 3.71073267e+03 3.69755615e+03 3.61288794e+03 3.57747656e+03 3.57894434e+03 3.39395947e+03 3.39861499e+03 3.42825024e+03 3.31691772e+03 3.35376904e+03 3.29026196e+03 3.18252759e+03 3.20821777e+03 3.14113135e+03 3.11283154e+03 3.15485400e+03 3.06396680e+03 2.97478589e+03 2.90873340e+03 2.84187524e+03 2.89127881e+03 2.89951001e+03 2.78529810e+03 2.74185669e+03 2.75661377e+03 2.70992261e+03 2.66509863e+03 2.58868921e+03 2.55065356e+03 2.52142578e+03 2.50976880e+03 2.49773218e+03 2.39573486e+03 2.34173291e+03 2.36103394e+03 2.33889355e+03 2.29428149e+03 2.26309888e+03 2.20506689e+03 2.14887378e+03 2.18579688e+03 2.17612915e+03 2.06648486e+03 1.97236328e+03 1.97440015e+03 1.98001868e+03 1.93859351e+03 1.89484351e+03 1.87720764e+03 1.85069617e+03 1.81624414e+03 1.79869287e+03 1.74604626e+03 1.69907092e+03 1.69049744e+03 1.66946448e+03 1.61583301e+03 1.56063940e+03 1.55097144e+03 1.52282117e+03 1.49809375e+03 1.48653198e+03 1.43846582e+03 1.39286169e+03 1.37992383e+03 1.37426379e+03 1.33334619e+03 1.28590198e+03 1.26085327e+03 1.23485693e+03 1.20962817e+03 1.18160693e+03 1.14337573e+03 1.12075098e+03 1.10786572e+03 1.09150928e+03 1.07399585e+03 1.03199634e+03 1.00372650e+03 9.80301086e+02 9.50460938e+02 9.25238708e+02 8.95072876e+02 8.86483643e+02 8.69935242e+02 8.33563354e+02 8.00543579e+02 7.82349426e+02 7.74773926e+02 7.62564941e+02 7.43726135e+02 7.06038757e+02 6.80625488e+02 6.61293152e+02 6.30099976e+02 6.16579651e+02 6.06591980e+02 5.86154175e+02 5.63082825e+02 5.36755737e+02 5.21743591e+02 5.14073303e+02 5.04668640e+02 4.86376404e+02 4.58329437e+02 4.34130035e+02 4.22121460e+02 4.06982544e+02 3.88613525e+02 3.81634003e+02 3.71015625e+02 3.45529907e+02 3.25637329e+02 3.12281738e+02 3.01580719e+02 2.97997589e+02 2.84663574e+02 2.61930176e+02 2.50825821e+02 2.37913925e+02 2.22850403e+02 2.17664948e+02 2.07682343e+02 1.91474670e+02 1.79668930e+02 1.68263962e+02 1.57292862e+02 1.54003540e+02 1.49416641e+02 1.36196930e+02 1.24804535e+02 1.15904175e+02 1.07678589e+02 1.00620445e+02 9.35073395e+01 8.68372803e+01 7.89584427e+01 7.13335114e+01 6.62399826e+01 6.15755386e+01 5.58175697e+01 5.11977844e+01 4.65811691e+01 4.09908257e+01 3.62776108e+01 3.30338707e+01 3.01139488e+01 2.72277164e+01 2.42169113e+01 2.14026546e+01 1.92335091e+01 1.76958332e+01 1.64076176e+01 1.52369499e+01 1.43092813e+01 1.37720356e+01 1.36315336e+01 1.38757792e+01 1.43885155e+01 1.50972061e+01 1.61287575e+01 1.76821499e+01 1.99688969e+01 2.23278522e+01 2.44300442e+01 2.74796600e+01 3.11678219e+01 3.45888824e+01 3.81059303e+01 4.22105751e+01 4.68337669e+01 5.18429565e+01 5.64727859e+01 6.20791969e+01 6.68109894e+01 7.31693420e+01 8.16469574e+01 8.81795120e+01 9.63125000e+01 1.02615227e+02 1.09068153e+02 1.18147438e+02 1.27797127e+02 1.36809265e+02 1.44349319e+02 1.55072662e+02 1.66246521e+02 1.74218399e+02 1.82861313e+02 1.93581802e+02 2.04437103e+02 2.20552704e+02 2.32714447e+02 2.40426178e+02 2.53107300e+02 2.63960938e+02 2.80529907e+02 2.96937469e+02 3.05391785e+02 3.16540131e+02 3.36951569e+02 3.51251892e+02 3.61311737e+02 3.85732025e+02 4.00179871e+02 4.07491058e+02 4.28754089e+02 4.38077698e+02 4.54733856e+02 4.86868866e+02 4.99531586e+02 5.10080139e+02 5.35468018e+02 5.52888855e+02 5.56255554e+02 5.77488342e+02 6.09195984e+02 6.26108643e+02 6.50565613e+02 6.66298706e+02 6.80110291e+02 7.10221924e+02 7.37481201e+02 7.73315552e+02 7.77945312e+02 7.71214294e+02 8.05910889e+02 8.38503357e+02 8.68792175e+02 8.98532166e+02 9.03483521e+02 9.06526001e+02 9.60661987e+02 9.99536133e+02 9.96509033e+02 1.03432874e+03 1.05998120e+03 1.06784131e+03 1.11091699e+03 1.13926086e+03 1.14475647e+03 1.20717908e+03 1.23483423e+03 1.23775781e+03 1.26429846e+03 1.25473169e+03 1.28947900e+03 1.36194446e+03 1.42907434e+03 1.43729272e+03 1.39207373e+03 1.43070898e+03 1.51675635e+03 1.53627563e+03 1.54794458e+03 1.58132373e+03 1.60296057e+03 1.65218445e+03 1.69092749e+03 1.72577148e+03 1.74097192e+03 1.77142261e+03 1.83408618e+03 1.84376038e+03 1.84960889e+03 1.88372815e+03 1.92162598e+03 1.97687244e+03 2.04069128e+03 2.04090088e+03 2.02166187e+03 2.09313721e+03 2.15036523e+03 2.23141455e+03 2.24735718e+03 2.18831421e+03 2.26250830e+03 2.32578027e+03 2.37804712e+03 2.44879468e+03 2.45062964e+03 2.43483911e+03 2.48209497e+03 2.50177295e+03 2.51608032e+03 2.64480640e+03 2.72634204e+03 2.69540894e+03 2.68899365e+03 2.71408545e+03 2.76569629e+03 2.89247534e+03 2.93169629e+03 2.93392163e+03 2.93912695e+03 2.91485425e+03 2.99800244e+03 3.07810645e+03 3.17687329e+03 3.22039868e+03 3.15228442e+03 3.21208301e+03 3.25534277e+03 3.31672021e+03 3.39205054e+03 3.43237231e+03 3.50153149e+03 3.45095483e+03 3.48180176e+03 3.56122583e+03 3.58852954e+03 3.64188696e+03 3.72455933e+03 3.77494238e+03 3.78986890e+03 3.77879736e+03 3.85578687e+03 3.98638184e+03 3.99431030e+03 3.94612939e+03 4.00101270e+03 4.05728198e+03 4.06808252e+03 4.26630908e+03 4.28250244e+03 4.18550732e+03 4.32797363e+03 4.30538037e+03 4.33965771e+03 4.57045459e+03 4.51552246e+03 4.56466357e+03 4.68277588e+03 4.69516016e+03 4.98049365e+03 6.05781152e+03 6.12691553e+03 7.98302441e+03 7.13240137e+03 1.25417061e+04 2.09168418e+04 -12360666. -13550051. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -333500896. 1.06845945e+05 1.45894717e+04 9.95967480e+03 9.10916797e+03 7.82474902e+03 7.33877637e+03 7.51518945e+03 7.72855859e+03 7.57374658e+03 7.49551562e+03 7.36698730e+03 7.45993994e+03 7.73223340e+03 7.91387842e+03 7.79874170e+03 7.73105908e+03 7.74841260e+03 7.83602637e+03 8.07497363e+03 8.02249902e+03 7.79633057e+03 7.91061230e+03 8.18604443e+03 8.21574316e+03 8.05468262e+03 7.98848682e+03 8.29801074e+03 8.70595117e+03 8.72011133e+03 8.31201270e+03 8.03567871e+03 8.30556152e+03 8.70627051e+03 8.96715527e+03 8.83311035e+03 8.52497461e+03 8.60902539e+03 8.81546191e+03 9.13166699e+03 9.03392383e+03 8.63078320e+03 8.80952246e+03 9.33402539e+03 9.19870703e+03 8.94681934e+03 9.10121680e+03 9.19183301e+03 9.38546094e+03 9.45330957e+03 9.09814062e+03 9.02619043e+03 9.56135352e+03 9.87549414e+03 9.75664453e+03 9.39126367e+03 9.20258691e+03 9.76163770e+03 1.01183896e+04 9.86760352e+03 9.64940234e+03 9.39059570e+03 9.58413770e+03 1.01067783e+04 1.02962910e+04 1.01737207e+04 1.00491221e+04 1.01200820e+04 1.00701094e+04 1.01241660e+04 1.02642930e+04 9.97304492e+03 1.01501230e+04 1.06187090e+04 1.04975439e+04 1.00973691e+04 1.00325303e+04 1.06039375e+04 1.09998057e+04 1.07897344e+04 1.05364844e+04 1.03147705e+04 1.03616572e+04 1.07339346e+04 1.12338135e+04 1.10744512e+04 1.05265576e+04 1.06924092e+04 1.08816279e+04 1.10242471e+04 1.12867217e+04 1.09005273e+04 1.10031836e+04 1.13710938e+04 1.12375244e+04 1.11121641e+04 1.10559424e+04 1.11923037e+04 1.15336104e+04 1.14851426e+04 1.11676416e+04 1.11077480e+04 1.15151748e+04 1.17443164e+04 1.17369004e+04 1.15888232e+04 1.12787588e+04 1.14597764e+04 1.19503369e+04 1.19666719e+04 1.17411738e+04 1.13327188e+04 1.14234473e+04 1.20062949e+04 1.23567305e+04 1.20647451e+04 1.15916592e+04 1.17168877e+04 1.21674697e+04 1.21368682e+04 1.19025957e+04 1.17913115e+04 1.21992070e+04 1.24604893e+04 1.21034189e+04 1.20744658e+04 1.19845293e+04 1.22929502e+04 1.27987168e+04 1.25836689e+04 1.22855801e+04 1.20925439e+04 1.21953311e+04 1.24782236e+04 1.27437598e+04 1.26696260e+04 1.21457959e+04 1.22236934e+04 1.28137324e+04 1.29712822e+04 1.27145537e+04 1.24375293e+04 1.25702061e+04 1.28953564e+04 1.29669727e+04 1.27755957e+04 1.23296191e+04 1.25281357e+04 1.30508398e+04 1.30784424e+04 1.28615850e+04 1.26276680e+04 1.27458311e+04 1.30402129e+04 1.34105156e+04 1.33176582e+04 1.26158203e+04 1.27757646e+04 1.31939326e+04 1.31495723e+04 1.31514062e+04 1.30217539e+04 1.30577607e+04 1.31285703e+04 1.32026826e+04 1.30889971e+04 1.29924502e+04 1.33808643e+04 1.36024912e+04 1.34514326e+04 1.29745293e+04 1.28265645e+04 1.34108838e+04 1.38744922e+04 1.37256035e+04 1.33687275e+04 1.29767676e+04 1.28427354e+04 1.33840605e+04 1.39947070e+04 1.36408428e+04 1.29908984e+04 1.31785078e+04 1.35558799e+04 1.37387051e+04 1.38070527e+04 1.34882422e+04 1.34116182e+04 1.35564600e+04 1.34923516e+04 1.33335068e+04 1.34213672e+04 1.37097979e+04 1.36705986e+04 1.36066670e+04 1.35061582e+04 1.33510859e+04 1.37092451e+04 1.39962139e+04 1.38468877e+04 1.34376748e+04 1.31972148e+04 1.36929590e+04 1.39966885e+04 1.38645830e+04 1.36630703e+04 1.32265459e+04 1.32750869e+04 1.39529971e+04 1.43333018e+04 1.40211504e+04 1.34062197e+04 1.33068271e+04 1.37557051e+04 1.39518857e+04 1.38063018e+04 1.37655293e+04 1.39271416e+04 1.37805215e+04 1.35327148e+04 1.32789355e+04 1.32107119e+04 1.35851133e+04 1.37593447e+04 1.41957695e+04 1.40603955e+04 1.32813408e+04 1.35371650e+04 1.37370264e+04 1.36936758e+04 1.38636260e+04 1.36692109e+04 1.40009512e+04 1.39577793e+04 1.32533008e+04 1.31024941e+04 1.33856318e+04 1.40081504e+04 1.44695420e+04 1.40866191e+04 1.32964082e+04 1.29535947e+04 1.32226807e+04 1.39646816e+04 1.44085518e+04 1.40430625e+04 1.32259941e+04 1.31868418e+04 1.41266094e+04 1.39854443e+04 1.32761279e+04 1.32724590e+04 1.34897627e+04 1.35095762e+04 1.39012119e+04 1.36322988e+04 1.31131357e+04 1.34173555e+04 1.31868721e+04 1.35123232e+04 1.38391328e+04 1.31222305e+04 1.33701924e+04 1.37880059e+04 1.34784873e+04 1.34017246e+04 1.33300518e+04 1.34029873e+04 1.34939805e+04 1.33076074e+04 1.29738770e+04 1.30223340e+04 1.35923438e+04 1.38976133e+04 1.35763037e+04 1.29964023e+04 1.26957441e+04 1.28959199e+04 13466. 1.38624385e+04 1.34825039e+04 1.28014775e+04 1.28564883e+04 1.32707090e+04 1.31509473e+04 1.29501709e+04 1.29758125e+04 1.29424482e+04 1.29067295e+04 1.33805498e+04 1.30590586e+04 1.26441377e+04 1.28741064e+04 1.25533701e+04 1.29446729e+04 1.31948828e+04 1.27555879e+04 1.31653760e+04 1.28710234e+04 1.23157686e+04 1.27213730e+04 1.23927080e+04 1.25610420e+04 1.34215781e+04 1.27556064e+04 1.20042363e+04 1.21990430e+04 1.27570811e+04 1.32329082e+04 1.28912090e+04 1.21458936e+04 1.17821777e+04 1.20770137e+04 1.26540195e+04 1.30466035e+04 1.26916279e+04 1.19500146e+04 1.19124043e+04 1.23165537e+04 1.24356348e+04 1.20904629e+04 1.18959160e+04 1.21052217e+04 1.20784443e+04 1.23752256e+04 1.23918613e+04 1.17382656e+04 1.16838926e+04 1.18265488e+04 1.18306768e+04 1.19124678e+04 1.18303770e+04 1.20780811e+04 1.18730361e+04 1.14100566e+04 1.15748379e+04 1.12881064e+04 1.16275957e+04 1.23119824e+04 1.15913477e+04 1.08619336e+04 1.11164580e+04 1.16296807e+04 1.19263398e+04 1.18954346e+04 1.12414863e+04 1.07285215e+04 1.09092539e+04 1.14418906e+04 1.18710811e+04 1.14824141e+04 1.07988018e+04 1.06978467e+04 1.09686543e+04 1.11368311e+04 1.13013809e+04 1.12274785e+04 1.06226631e+04 1.05299297e+04 1.09486348e+04 1.10540469e+04 1.07115195e+04 1.05925264e+04 1.05439014e+04 1.04493789e+04 1.08082305e+04 1.09043662e+04 1.03595684e+04 1.02096406e+04 1.02761230e+04 1.02909434e+04 1.03624414e+04 1.02169707e+04 1.04464785e+04 1.05575830e+04 1.00919834e+04 9.84547656e+03 9.66056641e+03 1.00245664e+04 1.05575674e+04 1.02500371e+04 9.65708301e+03 9.40075195e+03 9.70327051e+03 1.02126650e+04 9.87159473e+03 9.29015234e+03 9.39254785e+03 9.55510547e+03 9.79680371e+03 1.00794521e+04 9.74418848e+03 9.15815039e+03 8.94992480e+03 9.24874609e+03 9.46890332e+03 9.45318066e+03 9.26765918e+03 9.15102734e+03 9.04416211e+03 9.20818555e+03 9.14009766e+03 8.81421289e+03 8.73775195e+03 8.66824707e+03 9.01648633e+03 9.09787695e+03 8.71487012e+03 8.71655664e+03 8.71804785e+03 8.82794824e+03 8.56061621e+03 8.09378418e+03 8.44642188e+03 8.84310645e+03 8.54529395e+03 8.07257080e+03 8.08898096e+03 8.44815234e+03 8.43489355e+03 8.23053809e+03 8.13324561e+03 7.81887012e+03 7.79709570e+03 8.15987158e+03 8.12538086e+03 7.73213818e+03 7.50554932e+03 7.49628223e+03 7.79279688e+03 8.07891748e+03 7.68833398e+03 7.36767480e+03 7.55806592e+03 7.50197656e+03 7.65954199e+03 7.60056543e+03 7.12923535e+03 7.11413916e+03 7.28202490e+03 7.19470361e+03 7.21450391e+03 7.08554248e+03 7.19997412e+03 7.26330469e+03 6.90048193e+03 7.05470068e+03 6.64680371e+03 6.88011426e+03 9.72324707e+03 7.49272021e+03 9.79983301e+03 8.53184961e+03 1.00132061e+04 1.08151143e+04 1.03682266e+04 1.02686289e+04 1.01279209e+04 1.67815195e+04 2.59542832e+04 -8588070. 42812980. 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. 0. 0. 0. 0. 0. 0. 0. 0. 15353035. 5.42871650e+06 -2850929. 1.60619697e+04 9.37695703e+03 5.96937549e+03 4.75037354e+03 4.47867627e+03 4.21025342e+03 4.02818799e+03 4.12604102e+03 4.07881641e+03 3.94665234e+03 3.93845459e+03 3.87680420e+03 3.80448096e+03 3.79967676e+03 3.73350586e+03 3.66428540e+03 3.61836230e+03 3.54595117e+03 3.60353320e+03 3.59329590e+03 3.39641821e+03 3.35177905e+03 3.46988916e+03 3.45213257e+03 3.34059644e+03 3.28486597e+03 3.23756543e+03 3.19673340e+03 3.15624585e+03 3.11889062e+03 3.07203223e+03 3.03193433e+03 2.95972852e+03 2.90935986e+03 2.95740161e+03 2.93021509e+03 2.83783423e+03 2.80042822e+03 2.76503955e+03 2.73068311e+03 2.67581812e+03 2.63423413e+03 2.60497314e+03 2.50836621e+03 2.45434619e+03 2.48038623e+03 2.44263428e+03 2.49917798e+03 2.46270654e+03 2.34266602e+03 2.23527222e+03 2.19934717e+03 2.31302539e+03 2.29188843e+03 2.16840234e+03 2.09648608e+03 2.07046216e+03 2.07167676e+03 2.02198047e+03 2.05123267e+03 2.01431042e+03 1.86657544e+03 1.81919971e+03 1.88789490e+03 1.92320190e+03 1.84243652e+03 1.77226379e+03 1.74514136e+03 1.70129028e+03 1.65066882e+03 1.63182678e+03 1.60544116e+03 1.56713489e+03 1.54166284e+03 1.50928882e+03 1.49623987e+03 1.46458301e+03 1.46356335e+03 1.42793677e+03 1.36140405e+03 1.34927759e+03 1.32580273e+03 1.30278687e+03 1.28036475e+03 1.24179773e+03 1.21650708e+03 1.16290930e+03 1.10697302e+03 1.13837634e+03 1.12660425e+03 1.04403918e+03 1.02555811e+03 1.05789868e+03 1.06183167e+03 1.00303796e+03 9.53512451e+02 9.27584290e+02 9.01276367e+02 8.68536743e+02 8.45435486e+02 8.41923279e+02 8.15413452e+02 8.10755066e+02 7.82598328e+02 7.39044617e+02 7.29782959e+02 6.91813721e+02 6.72536316e+02 6.86957092e+02 6.60740784e+02 6.25585754e+02 5.93110596e+02 5.65736450e+02 5.77995361e+02 5.69009399e+02 5.32427063e+02 4.98971527e+02 4.81458405e+02 4.75763458e+02 4.57818848e+02 4.54543915e+02 4.41200287e+02 4.09649811e+02 3.85856018e+02 3.72503967e+02 3.72943298e+02 3.56975800e+02 3.33024261e+02 3.15967285e+02 3.01165070e+02 2.91280396e+02 2.72136444e+02 2.59976807e+02 2.60664764e+02 2.46707397e+02 2.28573608e+02 2.10900467e+02 1.99244919e+02 2.00054764e+02 1.89232803e+02 1.73826691e+02 1.59099426e+02 1.48582779e+02 1.44085373e+02 1.34674042e+02 1.25923714e+02 1.14803085e+02 1.08728958e+02 1.05766693e+02 9.57499695e+01 8.74954605e+01 8.10385361e+01 7.41719513e+01 6.68768539e+01 6.09482231e+01 5.61410065e+01 5.09340477e+01 4.62437782e+01 4.11932068e+01 3.75353470e+01 3.48326683e+01 3.04265194e+01 2.67518158e+01 2.42553482e+01 2.17297421e+01 1.97913380e+01 1.78278599e+01 1.62053280e+01 1.51580572e+01 1.43177776e+01 1.37966976e+01 1.36262531e+01 1.38247099e+01 1.43800354e+01 1.52528982e+01 1.64103374e+01 1.77417603e+01 1.96199226e+01 2.22653389e+01 2.46416187e+01 2.70621204e+01 2.97495098e+01 3.34521790e+01 3.86861343e+01 4.28563843e+01 4.65158730e+01 5.04631653e+01 5.52787132e+01 6.18872223e+01 6.78349991e+01 7.54705124e+01 8.04126358e+01 8.49884338e+01 9.46811981e+01 1.02195885e+02 1.11916130e+02 1.19926430e+02 1.26042473e+02 1.35181702e+02 1.44049088e+02 1.55185211e+02 1.61493820e+02 1.72956635e+02 1.92193512e+02 1.98681610e+02 2.04965744e+02 2.12395096e+02 2.22674515e+02 2.46952789e+02 2.60097534e+02 2.65695251e+02 2.72690308e+02 2.84615906e+02 3.07362701e+02 3.21543732e+02 3.43358063e+02 3.54432343e+02 3.58993988e+02 3.71351410e+02 3.86118988e+02 4.21283325e+02 4.36047485e+02 4.41108582e+02 4.57159454e+02 4.73578003e+02 5.04847473e+02 5.24245850e+02 5.20386475e+02 5.36170105e+02 5.82362305e+02 6.02883301e+02 5.92968628e+02 6.08477478e+02 6.60367126e+02 6.86100220e+02 6.85624023e+02 6.88946716e+02 7.08564270e+02 7.72087769e+02 7.88944458e+02 7.89457520e+02 8.18374023e+02 8.35522461e+02 8.55523560e+02 8.78058899e+02 8.99942017e+02 9.02157776e+02 9.50939880e+02 1.02659509e+03 1.02467273e+03 1.03472571e+03 1.06724438e+03 1.08174463e+03 1.11009460e+03 1.13356116e+03 1.15707532e+03 1.15598999e+03 1.16513599e+03 1.22176135e+03 1.27638171e+03 1.34122107e+03 1.32652917e+03 1.30818396e+03 1.37589502e+03 1.41621997e+03 1.48697388e+03 1.49885803e+03 1.48264832e+03 1.50188904e+03 1.52222766e+03 1.58497595e+03 1.62170630e+03 1.68369263e+03 1.71259351e+03 1.70209106e+03 1.71047852e+03 1.69597461e+03 1.79956567e+03 1.94188904e+03 1.93167249e+03 1.90767322e+03 1.89115588e+03 1.90090125e+03 2.03204102e+03 2.11930493e+03 2.10016479e+03 2.05267358e+03 2.07563013e+03 2.17086646e+03 2.20888525e+03 2.30454077e+03 2.33186841e+03 2.30067090e+03 2.34544434e+03 2.37119287e+03 2.46091528e+03 2.50182520e+03 2.42890112e+03 2.47112378e+03 2.64032251e+03 2.63023633e+03 2.53538623e+03 2.65380151e+03 2.84591064e+03 2.83683081e+03 2.79246777e+03 2.76331006e+03 2.81512524e+03 3.01809863e+03 3.03838330e+03 2.99654248e+03 2.95915430e+03 2.97623389e+03 3.11221729e+03 3.13953442e+03 3.19469409e+03 3.15447754e+03 3.26460938e+03 3.44525415e+03 3.40360132e+03 3.44672070e+03 3.46817944e+03 3.44337231e+03 3.51490137e+03 3.56850977e+03 3.62283691e+03 3.64073828e+03 3.64629077e+03 3.61567773e+03 3.73196533e+03 4.01631299e+03 3.88204468e+03 3.75451318e+03 3.91160254e+03 4.01655029e+03 4.19592334e+03 4.16626514e+03 4.07464819e+03 4.22131543e+03 4.26801172e+03 4.14138232e+03 4.15745801e+03 4.46051514e+03 4.49494336e+03 4.40662256e+03 4.38609082e+03 4.30039502e+03 4.52753857e+03 4.85835742e+03 4.77919482e+03 4.69734619e+03 4.63795898e+03 4.62132471e+03 4.91271240e+03 5.13412646e+03 5.03566064e+03 4.83601270e+03 4.85054834e+03 5.04524805e+03 5.14231299e+03 5.34059131e+03 5.26789746e+03 5.16266016e+03 5.33769482e+03 5.36540527e+03 5.48771729e+03 5.51709521e+03 5.44986914e+03 5.52283740e+03 5.59316748e+03 5.62144824e+03 5.48343018e+03 5.64824316e+03 6.04954346e+03 5.98340430e+03 5.78534229e+03 5.70395801e+03 5.82559131e+03 6.22641504e+03 6.21673242e+03 6.09930029e+03 5.98595410e+03 6.03175879e+03 6.25960547e+03 6.29384277e+03 6.35389844e+03 6.22182812e+03 6.44339795e+03 6.75433398e+03 6.58685156e+03 6.68421729e+03 6.73887891e+03 6.68745361e+03 6.68733008e+03 6.67996094e+03 6.77742432e+03 6.79552539e+03 6.88342822e+03 6.90763184e+03 7.13677686e+03 7.20241309e+03 6.95077832e+03 6.88201123e+03 7.10129492e+03 7.30342822e+03 7.60924365e+03 7.40965576e+03 7.14551660e+03 7.51592285e+03 7.74962891e+03 7.59781104e+03 7.44747070e+03 7.47475049e+03 7.63413135e+03 7.70644434e+03 7.70254102e+03 7.54841699e+03 7.84534473e+03 8.28823633e+03 8.13838037e+03 8.02321533e+03 7.92271484e+03 7.88643701e+03 8.36907910e+03 8.44597461e+03 8237. 8.07439209e+03 7.93832373e+03 8.22200586e+03 8.58169043e+03 8.91030762e+03 8.58435645e+03 8.24793555e+03 8.55640039e+03 8.68179883e+03 9.02496484e+03 8.86317285e+03 8.63337598e+03 8.91143945e+03 8.94663867e+03 8.78968359e+03 8.66996680e+03 9.00039258e+03 9.50087598e+03 9.35024316e+03 9.22292969e+03 9.03012988e+03 9.01620215e+03 9.54168457e+03 9.61776953e+03 9.39718652e+03 9.19387500e+03 9.14774316e+03 9.48453809e+03 9.60471484e+03 9.85415527e+03 9.94611035e+03 9.64730469e+03 9.48909473e+03 9.63283496e+03 1.01790674e+04 1.00081094e+04 9.77401465e+03 9.97531641e+03 1.00557188e+04 9.88532227e+03 9.78613086e+03 1.02693613e+04 1.02670801e+04 1.00154268e+04 1.04899873e+04 1.06068105e+04 1.04097021e+04 1.03957451e+04 1.04172871e+04 1.04486465e+04 1.02597891e+04 1.02140176e+04 1.07577285e+04 1.08937979e+04 1.03849365e+04 1.01147207e+04 1.06848896e+04 1.13255859e+04 1.12297725e+04 1.07013506e+04 1.04956621e+04 1.10978867e+04 1.13129619e+04 1.10045029e+04 1.11384756e+04 1.08973594e+04 1.06059033e+04 1.10522686e+04 1.15913506e+04 1.15719688e+04 1.11400293e+04 1.08701172e+04 1.14974404e+04 1.18746768e+04 1.15413369e+04 1.11114102e+04 1.10194053e+04 1.14487764e+04 1.15501875e+04 1.18731162e+04 1.18870801e+04 1.14744629e+04 1.16895693e+04 1.17281094e+04 1.19482598e+04 1.17287676e+04 1.14817266e+04 1.20177520e+04 1.20808555e+04 1.19288604e+04 1.16430605e+04 1.17994434e+04 1.25488408e+04 1.21084648e+04 1.16164277e+04 1.19272227e+04 1.22329668e+04 1.22966426e+04 1.21855957e+04 1.25126416e+04 1.26714912e+04 1.23193652e+04 1.19534346e+04 1.20100801e+04 1.26795156e+04 1.24649355e+04 1.21005693e+04 1.25594521e+04 1.26782715e+04 1.24416484e+04 1.23123018e+04 1.28135312e+04 1.27082588e+04 1.23669854e+04 1.27283359e+04 1.27925596e+04 1.28852275e+04 1.28965996e+04 1.27908057e+04 1.27197051e+04 1.23617002e+04 1.23645205e+04 1.30133887e+04 1.34706855e+04 1.28639639e+04 1.22373311e+04 1.27722344e+04 1.35524189e+04 1.34846426e+04 1.28562090e+04 1.24215840e+04 1.30516475e+04 1.34680225e+04 1.30586133e+04 1.33488223e+04 1.32865498e+04 1.28067598e+04 1.29729609e+04 1.34333525e+04 1.35075381e+04 1.30312080e+04 1.27185215e+04 1.32607500e+04 1.38813984e+04 1.35376143e+04 1.29646924e+04 1.27720068e+04 1.34603086e+04 1.38934385e+04 1.34106074e+04 1.30749248e+04 1.31937705e+04 1.34713828e+04 1.34133789e+04 1.38006865e+04 1.35049541e+04 1.30444404e+04 1.35826406e+04 1.36790625e+04 1.36874609e+04 1.34038281e+04 1.31845635e+04 1.37381309e+04 1.34291367e+04 1.32218086e+04 1.37263301e+04 1.39313047e+04 1.42423574e+04 1.39588232e+04 1.40651240e+04 1.40183643e+04 1.20185244e+04 1.24269014e+04 1.39283623e+04 1.48161846e+04 1.48781035e+04 1.33745127e+04 1.35744141e+04 1.68543223e+04 2.54606641e+04 3.70119875e+05 4.02860401e+10 0. 0. 0. 0. -4.32443351e+10 -4.32443351e+10 8.42669766e+04 4.49461504e+09 6.28439648e+04 2.89728613e+04 4.52383672e+04 1.14269875e+05 1.01335253e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.81452820e+10 1.55116234e+05 3.98284805e+04 3.33826094e+04 1.55270811e+04 1.76788594e+04 1.37757549e+04 1.75319785e+04 1.33455684e+04 1.49672520e+04 1.37917266e+04 1.35683262e+04 1.34228193e+04 1.36354111e+04 1.40007656e+04 1.39656455e+04 1.34726172e+04 1.33169268e+04 1.36419355e+04 1.36343477e+04 1.35775605e+04 1.35614961e+04 1.34025244e+04 1.33916465e+04 1.36652871e+04 1.36802119e+04 1.31897246e+04 1.32034375e+04 1.36383555e+04 1.37119053e+04 1.37179453e+04 1.33525791e+04 1.30450498e+04 1.33576230e+04 1.34978027e+04 1.33827393e+04 1.31896191e+04 1.31658828e+04 1.34188584e+04 1.33899053e+04 1.32769600e+04 1.31283848e+04 1.31079766e+04 1.35788467e+04 1.36330732e+04 1.29625361e+04 1.28123320e+04 1.30695049e+04 1.31853643e+04 1.33730684e+04 1.32120635e+04 1.28864238e+04 1.30260586e+04 1.31332812e+04 1.31035635e+04 1.31438838e+04 1.28946406e+04 1.28988105e+04 1.30029355e+04 1.28587803e+04 1.28145557e+04 1.27421758e+04 1.27901475e+04 1.30686982e+04 1.30055850e+04 1.28166826e+04 1.25672480e+04 1.25121465e+04 1.28814609e+04 1.28656914e+04 1.24707100e+04 1.25310508e+04 1.25478223e+04 1.26284824e+04 1.28909072e+04 1.26692051e+04 1.23181016e+04 1.23296631e+04 1.26351934e+04 1.26423320e+04 1.23199873e+04 1.20624580e+04 1.21583145e+04 1.23208164e+04 1.26001855e+04 1.25593262e+04 1.20324336e+04 1.20057705e+04 1.23236484e+04 1.22897061e+04 1.21804082e+04 1.18917549e+04 1.17579668e+04 1.21389482e+04 1.22041064e+04 1.18761016e+04 1.18646152e+04 1.18917969e+04 1.18406982e+04 1.18203369e+04 1.17512480e+04 1.18014785e+04 1.17557891e+04 1.18535293e+04 1.18169551e+04 1.14217939e+04 1.14319355e+04 1.16195762e+04 1.14541045e+04 1.14676133e+04 1.13960684e+04 1.13695908e+04 1.15367588e+04 1.13981504e+04 1.11873193e+04 1.13883281e+04 1.13984531e+04 1.11188281e+04 1.10584697e+04 1.11184707e+04 1.11639990e+04 1.10493604e+04 1.08631660e+04 1.08572949e+04 1.09327471e+04 1.11859629e+04 1.10195010e+04 1.05834111e+04 1.06858486e+04 1.08350957e+04 1.07755967e+04 1.06800479e+04 1.05074404e+04 1.03838047e+04 1.05325762e+04 1.07065479e+04 1.05400098e+04 1.02269268e+04 1.01945771e+04 1.04180342e+04 1.04946357e+04 1.04733633e+04 1.01923711e+04 9.89165820e+03 1.00344727e+04 1.00209541e+04 9.98929297e+03 1.00189707e+04 9.86711523e+03 9.90072656e+03 1.01576982e+04 9.89407617e+03 9.50756543e+03 9.56241309e+03 9.71232031e+03 9.70406445e+03 9.77345312e+03 9.57082812e+03 9.35984961e+03 9.39749512e+03 9.65851660e+03 9.42438867e+03 9.06316797e+03 9.14888574e+03 9.39446094e+03 9.28713379e+03 9.14377539e+03 8.90949219e+03 8.92234863e+03 8.99919531e+03 8.99665527e+03 8.93665723e+03 8.96869238e+03 8.74377930e+03 8.72304688e+03 8.94249414e+03 8.71154590e+03 8.47394824e+03 8.52717969e+03 8.61665137e+03 8.63671387e+03 8.51761816e+03 8.28354297e+03 8.21157324e+03 8.31306250e+03 8.55444336e+03 8.52744336e+03 7.99259473e+03 7.94428369e+03 8.28334375e+03 8.11846582e+03 7.90907227e+03 7.82243896e+03 7.75099170e+03 7.87845898e+03 7.92034180e+03 7.77341943e+03 7.68566797e+03 7.46974463e+03 7.58732422e+03 7.70969824e+03 7.61938672e+03 7.45473096e+03 7.36188330e+03 7.40678760e+03 7.39848535e+03 7.24692236e+03 7.16500781e+03 7.14793555e+03 7.14422217e+03 7.22888379e+03 7.23149463e+03 6.84911084e+03 6.83376953e+03 6.95073340e+03 6.90989502e+03 6.87824902e+03 6.66007715e+03 6.65870020e+03 6.80471973e+03 6.68594922e+03 6.61474268e+03 6.40161768e+03 6.29835352e+03 6.47058398e+03 6.48627588e+03 6.37745752e+03 6.27938721e+03 6.25791504e+03 6.20196533e+03 6.25019971e+03 6.15455127e+03 5.97709717e+03 5.86017139e+03 5.87426074e+03 5.99415430e+03 5.87919189e+03 5.72717480e+03 5.72997119e+03 5.79773096e+03 5.73630371e+03 5.64360742e+03 5.55260986e+03 5.45952148e+03 5.47060303e+03 5.44855859e+03 5.48872998e+03 5.35366650e+03 5.22931006e+03 5.32002002e+03 5.13585889e+03 5.10806348e+03 5.18054688e+03 4.98631934e+03 4.95648730e+03 4.96882520e+03 4.92539795e+03 4.82693018e+03 4.74828467e+03 4.86834619e+03 4.88195117e+03 4.63180713e+03 4.57609912e+03 4.58791260e+03 4.54988330e+03 4.58407471e+03 4.49299072e+03 4.36211035e+03 4.33403516e+03 4.39287061e+03 4.35976562e+03 4.25486865e+03 4.14673779e+03 4.15994482e+03 4.16734912e+03 4.04513184e+03 4.00548535e+03 3.93732715e+03 3.89572876e+03 3.90207129e+03 3.90822461e+03 3.84968188e+03 3.74168286e+03 3.67473999e+03 3.73772217e+03 3.75399585e+03 3.59429590e+03 3.55545142e+03 3.54112915e+03 3.37823975e+03 3.42834253e+03 3.45167041e+03 3.30737891e+03 3.30696948e+03 3.30338110e+03 3.21563428e+03 3.23964380e+03 3.16881812e+03 3.08325000e+03 3.06091431e+03 3.04741870e+03 3.03321484e+03 2.92357275e+03 2.84909692e+03 2.86907593e+03 2.88613379e+03 2.82348364e+03 2.74726392e+03 2.68137842e+03 2.69390625e+03 2.73874072e+03 2.62721460e+03 2.53357056e+03 2.49381396e+03 2.52589038e+03 2.53596313e+03 2.42076929e+03 2.34311133e+03 2.34882300e+03 2.32577905e+03 2.26942749e+03 2.26986646e+03 2.21772852e+03 2.13213403e+03 2.14225513e+03 2.16481738e+03 2.08040771e+03 1.95534729e+03 1.96330115e+03 1.99407263e+03 1.95304675e+03 1.91502490e+03 1.86386340e+03 1.81610022e+03 1.82595520e+03 1.82823193e+03 1.74392676e+03 1.69409241e+03 1.67500598e+03 1.67374646e+03 1.63332471e+03 1.55295215e+03 1.52323682e+03 1.51928296e+03 1.49803894e+03 1.47567151e+03 1.44808472e+03 1.40032520e+03 1.38115918e+03 1.34582642e+03 1.29876013e+03 1.27504810e+03 1.24103674e+03 1.23588806e+03 1.23320190e+03 1.17858252e+03 1.12849487e+03 1.11348914e+03 1.11519373e+03 1.11692603e+03 1.08085669e+03 1.01424371e+03 9.84362854e+02 9.78521484e+02 9.52825623e+02 9.17927002e+02 8.98885193e+02 8.80765747e+02 8.60528809e+02 8.28347778e+02 7.90954346e+02 7.87453857e+02 7.81275513e+02 7.61335693e+02 7.30117493e+02 6.87984924e+02 6.74632446e+02 6.53278564e+02 6.26836426e+02 6.32038452e+02 6.15594666e+02 5.74743958e+02 5.52097656e+02 5.39443787e+02 5.39244690e+02 5.23313049e+02 4.94179260e+02 4.71969635e+02 4.53637817e+02 4.36911041e+02 4.16889435e+02 4.06258820e+02 3.92466339e+02 3.79282623e+02 3.63942932e+02 3.35633911e+02 3.24788635e+02 3.14708344e+02 3.01634430e+02 2.95898468e+02 2.74093842e+02 2.54851974e+02 2.51446640e+02 2.43665894e+02 2.27233521e+02 2.13651932e+02 1.98694977e+02 1.86095474e+02 1.77885086e+02 1.69614532e+02 1.59300583e+02 1.52884888e+02 1.44465317e+02 1.31648163e+02 1.20895027e+02 1.11742661e+02 1.06317047e+02 1.00438080e+02 9.13812180e+01 8.22085876e+01 7.54374161e+01 7.02105103e+01 6.57369461e+01 6.09297676e+01 5.35506096e+01 4.71847916e+01 4.26753578e+01 3.79368095e+01 3.39515152e+01 3.13290501e+01 2.79739456e+01 2.42311096e+01 2.11619186e+01 1.85510635e+01 1.66707668e+01 1.51634274e+01 1.36011620e+01 1.22169704e+01 1.13530703e+01 1.08941040e+01 1.07599144e+01 1.09353209e+01 1.14795485e+01 1.24061079e+01 1.36647434e+01 1.51412201e+01 1.71465378e+01 1.94113770e+01 2.17096348e+01 2.44837303e+01 2.74223270e+01 3.10274849e+01 3.53174171e+01 3.92786522e+01 4.41869888e+01 4.88283463e+01 5.28498650e+01 5.89979286e+01 6.45233688e+01 7.04511337e+01 7.71000977e+01 8.45151749e+01 9.30667191e+01 9.97901459e+01 1.07313431e+02 1.14669769e+02 1.24056969e+02 1.35525070e+02 1.44172318e+02 1.51142654e+02 1.59742523e+02 1.69532608e+02 1.81637650e+02 1.95057190e+02 2.05309845e+02 2.15020660e+02 2.26274765e+02 2.37750961e+02 2.51072495e+02 2.65882599e+02 2.76588135e+02 2.89374481e+02 3.04365509e+02 3.18011292e+02 3.34235229e+02 3.41653046e+02 3.58928162e+02 3.85352722e+02 3.94567078e+02 4.06906036e+02 4.28612518e+02 4.37471100e+02 4.52390015e+02 4.89416992e+02 5.05463806e+02 5.00915588e+02 5.22062195e+02 5.47893188e+02 5.60787964e+02 5.90573792e+02 6.07044617e+02 6.10684021e+02 6.39039673e+02 6.64017029e+02 6.92231079e+02 7.15286621e+02 7.26195435e+02 7.55052979e+02 7.66641052e+02 7.73333679e+02 8.08400208e+02 8.48374573e+02 8.65998657e+02 8.90392029e+02 9.13981567e+02 8.99819885e+02 9.43965942e+02 1.00978418e+03 1.02045587e+03 1.02892090e+03 1.02563037e+03 1.06016113e+03 1.12415454e+03 1.14258228e+03 1.15228381e+03 1.19410852e+03 1.21001270e+03 1.23910547e+03 1.27427295e+03 1.26618127e+03 1.29615930e+03 1.36390063e+03 1.40602637e+03 1.41039417e+03 1.40360400e+03 1.43303528e+03 1.50212878e+03 1.55619922e+03 1.56758569e+03 1.56172058e+03 1.57340637e+03 1.63472803e+03 1.69915405e+03 1.75948132e+03 1.75554236e+03 1.74389075e+03 1.79707874e+03 1.82888110e+03 1.85612427e+03 1.91292749e+03 1.92968726e+03 1.97020386e+03 2.03676892e+03 2.02720874e+03 2.05211670e+03 2.11192334e+03 2.14461865e+03 2.19328223e+03 2.20259595e+03 2.19077197e+03 2.25207520e+03 2.33056494e+03 2.39600464e+03 2.44675928e+03 2.43270288e+03 2.41111890e+03 2.47949902e+03 2.50527271e+03 2.55875171e+03 2.66128027e+03 2.64268262e+03 2.65225732e+03 2.68237061e+03 2.73129688e+03 2.83328076e+03 2.91906274e+03 2.91538647e+03 2.91238940e+03 2.92779688e+03 2.90392163e+03 2.99364258e+03 3.11216162e+03 3.17996826e+03 3.18986792e+03 3.14564087e+03 3.17620679e+03 3.25766382e+03 3.34078833e+03 3.37785327e+03 3.42319263e+03 3.43358643e+03 3.41837158e+03 3.52256665e+03 3.63771167e+03 3.64760083e+03 3.58185986e+03 3.66638232e+03 3.74566626e+03 3.80101294e+03 3.84690674e+03 3.85857861e+03 3.94854614e+03 3.95406958e+03 3.93616772e+03 4.07464307e+03 4.10223242e+03 4.09021777e+03 4.22528271e+03 4.20080225e+03 4.14942041e+03 4.32926074e+03 4.35446240e+03 4.40410645e+03 4.63320605e+03 4.60540186e+03 4.44137109e+03 4.57760986e+03 6.14283936e+03 7.20002002e+03 1.18426895e+04 1.35523789e+04 -16104623. -3.91262925e+06 6.70686350e+06 26788356. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 603420288. -16902752. 1.71963850e+06 7155243. 4.09413875e+06 2.11521035e+04 1.77040703e+04 9.65924512e+03 9.27129199e+03 8.06818945e+03 7.72201855e+03 7.20645752e+03 7.33341113e+03 7.61118750e+03 7.53301807e+03 7.43070459e+03 7.37885498e+03 7.37405518e+03 7.80033447e+03 7.97802100e+03 7.68593262e+03 7.51491602e+03 7.67620166e+03 7.86899316e+03 8.03251025e+03 8.17632275e+03 7.97852734e+03 7.84236230e+03 8.01054834e+03 8.11745654e+03 8.21663867e+03 8.10063428e+03 8.06522510e+03 8.46883984e+03 8.75393164e+03 8.55220117e+03 8.21665625e+03 8.25420801e+03 8.65734473e+03 8.79143164e+03 8.63234668e+03 8.49149609e+03 8.57669434e+03 8.94650000e+03 9.18466309e+03 8.96604492e+03 8.59154785e+03 8.79693750e+03 9.28692090e+03 9.19274219e+03 9.21116504e+03 9.19973633e+03 8.91613477e+03 9.16729590e+03 9.53657715e+03 9.35388184e+03 9.24696582e+03 9.52093359e+03 9.68212695e+03 9.61908496e+03 9.55550098e+03 9.27875488e+03 9.51752344e+03 1.00203203e+04 9.89603418e+03 9.65036133e+03 9.56285156e+03 9.62044141e+03 1.00982051e+04 1.04077148e+04 1.01147354e+04 9.89130762e+03 9.90459766e+03 9.92880371e+03 1.02114600e+04 1.05141182e+04 1.01607510e+04 1.00647051e+04 1.03937725e+04 1.03661777e+04 1.02650537e+04 1.02683271e+04 1.05105723e+04 1.07603027e+04 1.07106855e+04 1.07036123e+04 1.04344326e+04 1.02949326e+04 1.08866904e+04 1.11915986e+04 1.07103916e+04 1.04333242e+04 1.06934619e+04 1.10158975e+04 1.12296660e+04 1.13180479e+04 1.09555908e+04 1.09014316e+04 1.11962559e+04 1.11549121e+04 1.12858291e+04 1.12763750e+04 1.09626455e+04 1.11507080e+04 1.14239746e+04 1.14987666e+04 1.14916016e+04 1.15068359e+04 1.15438916e+04 1.15984805e+04 1.16171611e+04 1.12938125e+04 1.13303379e+04 1.20366709e+04 1.20753877e+04 1.15169209e+04 1.13342656e+04 1.15520947e+04 1.21029229e+04 1.24325176e+04 1.20090361e+04 1.16088691e+04 1.16403203e+04 1.18855869e+04 1.20479639e+04 1.21993027e+04 1.20830547e+04 1.20474043e+04 1.20956133e+04 1.21419834e+04 1.22830420e+04 1.20276367e+04 1.21928994e+04 1.26548584e+04 1.25138164e+04 1.23178428e+04 1.21737178e+04 1.20547900e+04 1.25724873e+04 1.29379111e+04 1.23986250e+04 1.21358936e+04 1.23249414e+04 1.28806162e+04 1.31227666e+04 1.27362520e+04 1.24236221e+04 1.23694854e+04 1.25612129e+04 1.28956279e+04 1.30704111e+04 1.26090752e+04 1.23412900e+04 1.27795283e+04 1.31846289e+04 1.30459561e+04 1.28512666e+04 1.28789346e+04 1.28470146e+04 1.30533301e+04 1.31576621e+04 1.27433770e+04 1.27363027e+04 1.32094580e+04 1.32425732e+04 1.30866797e+04 1.28930488e+04 1.29364463e+04 1.31598525e+04 1.33104932e+04 1.33809766e+04 1.30619434e+04 1.31667705e+04 1.33874951e+04 1.32697725e+04 1.32157871e+04 1.30518076e+04 1.31456162e+04 1.35229922e+04 1.37648262e+04 1.35903506e+04 1.30112500e+04 1.29233408e+04 1.35146377e+04 1.38785518e+04 1.36576592e+04 1.31057393e+04 1.30311377e+04 1.33720977e+04 1.37019365e+04 1.38303438e+04 1.33870176e+04 1.31576045e+04 1.34129717e+04 1.36922129e+04 1.38090674e+04 1.35679395e+04 1.34477529e+04 1.35168154e+04 1.35826318e+04 1.36830713e+04 1.35878984e+04 1.36072656e+04 1.35802480e+04 1.34583408e+04 1.33873311e+04 1.33575127e+04 1.37575371e+04 1.42189756e+04 1.40695537e+04 1.35226113e+04 1.30864570e+04 1.32791826e+04 1.41137373e+04 1.44374326e+04 1.39640488e+04 1.33917568e+04 1.31299697e+04 1.35186455e+04 1.40588750e+04 1.40358398e+04 1.38350049e+04 1.37437900e+04 1.36508232e+04 1.35837578e+04 1.33070078e+04 1.33188438e+04 1.36957734e+04 1.37547090e+04 1.41729668e+04 1.39437803e+04 1.30768994e+04 1.33739756e+04 1.38642627e+04 1.38692139e+04 1.38305918e+04 1.36355615e+04 1.39905049e+04 1.40934385e+04 1.34135234e+04 1.30226201e+04 1.32519854e+04 1.39385635e+04 1.44231406e+04 1.41140723e+04 1.33753643e+04 1.30272041e+04 1.32261797e+04 1.38355537e+04 1.43014277e+04 1.41116680e+04 1.32749941e+04 1.31540459e+04 1.40240879e+04 1.39352002e+04 1.33552031e+04 1.33143154e+04 1.34605762e+04 1.34705117e+04 1.38907783e+04 1.36606748e+04 1.31409463e+04 1.34078955e+04 1.31886816e+04 1.35243828e+04 1.38299688e+04 1.31755967e+04 1.33164414e+04 1.36932676e+04 1.34954648e+04 1.34120205e+04 1.33638457e+04 1.34053291e+04 1.35328271e+04 1.32467334e+04 1.28625625e+04 1.30442324e+04 1.36550928e+04 1.39238311e+04 1.35767334e+04 1.30066025e+04 1.26546621e+04 1.28835498e+04 1.34459678e+04 1.38294307e+04 1.34335283e+04 1.27659150e+04 1.28647754e+04 1.32313828e+04 1.31170322e+04 1.29668057e+04 1.29745234e+04 1.29605508e+04 1.29769609e+04 1.33924268e+04 1.30109736e+04 1.26377412e+04 1.28857617e+04 1.24977441e+04 1.28700889e+04 1.32724609e+04 1.27444092e+04 1.31047285e+04 1.28984141e+04 1.22716953e+04 1.26699189e+04 1.24088467e+04 1.25636025e+04 1.33795986e+04 1.27309639e+04 1.19960117e+04 1.21951719e+04 1.27836436e+04 1.31918662e+04 1.28635938e+04 1.22461436e+04 1.19052471e+04 1.20199902e+04 1.25270625e+04 1.29425576e+04 1.27078994e+04 1.20298428e+04 1.19367803e+04 1.23028477e+04 1.23411084e+04 1.20862939e+04 1.19680625e+04 1.20418096e+04 1.20153594e+04 1.23853965e+04 1.24178467e+04 1.17318691e+04 1.16168730e+04 1.18279268e+04 1.18310781e+04 1.19015469e+04 1.18477119e+04 1.21034844e+04 1.17917207e+04 1.12988252e+04 1.16840586e+04 1.13186846e+04 1.15536924e+04 1.23228623e+04 1.16040459e+04 1.09129971e+04 1.11171787e+04 1.16503330e+04 1.19295703e+04 1.18376895e+04 1.11706289e+04 1.07427256e+04 1.09310771e+04 1.14218564e+04 1.18151260e+04 1.14561758e+04 1.07625371e+04 1.06937285e+04 1.10023506e+04 1.11332656e+04 1.13259541e+04 1.12530361e+04 1.06251387e+04 1.04587012e+04 1.09154062e+04 1.10337646e+04 1.06910967e+04 1.05738281e+04 1.05998652e+04 1.04506348e+04 1.08256699e+04 1.08962480e+04 1.03474863e+04 1.02851514e+04 1.03580596e+04 1.02465420e+04 1.03128203e+04 1.02296943e+04 1.04377568e+04 1.05114736e+04 1.01326328e+04 9.86620801e+03 9.68050293e+03 1.00453174e+04 1.04866299e+04 1.02454717e+04 9.73233789e+03 9.41444141e+03 9.70601074e+03 1.01852471e+04 9.82086816e+03 9.27250488e+03 9.38363086e+03 9.60539551e+03 9.75942480e+03 1.00172432e+04 9.74304980e+03 9.18191699e+03 8.97274316e+03 9.24918359e+03 9.48351953e+03 9.40295410e+03 9.21692383e+03 9.12884180e+03 9.07474805e+03 9.22784668e+03 9.06031055e+03 8.75109180e+03 8.82037207e+03 8.64660645e+03 8.95679004e+03 9.16533887e+03 8.73868848e+03 8.77485156e+03 8.69778320e+03 8.66094727e+03 8.42253320e+03 8.17944141e+03 8.49927148e+03 8.87134961e+03 8.57407910e+03 8.09108105e+03 8.04412354e+03 8.45956738e+03 8.47977246e+03 8.23735352e+03 8.15150146e+03 7.83463330e+03 7.73674365e+03 8.08988672e+03 8.02127783e+03 7.78826562e+03 7.60810986e+03 7.45897412e+03 7.77828271e+03 8.09511621e+03 7.66465381e+03 7.34229834e+03 7.51115625e+03 7.49347559e+03 7.64815527e+03 7.63513916e+03 7.13402734e+03 7.06005518e+03 7.24136572e+03 7.17314551e+03 7.19495361e+03 7.27002881e+03 7.04887842e+03 7.56939941e+03 7.43447314e+03 6.90633496e+03 8.71826855e+03 9.80716406e+03 1.91072676e+04 1.19183945e+04 2.01118164e+04 2.11386836e+04 3.23181550e+06 6.45249850e+06 -2.91332125e+06 3.85683950e+06 -6.89170650e+06 -2239083. 57006492. 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. 0. 0. -125313584. -125313584. -125313584. 0. 0. -20887132. -6.01617750e+06 -3.10240275e+06 1.48833740e+04 1.17201816e+04 7.45747754e+03 7.10475439e+03 5.95333447e+03 5.61665674e+03 4.45586963e+03 4.37079492e+03 4.19026611e+03 4.02712769e+03 4.12351416e+03 4.05356934e+03 3.93601978e+03 3.92645410e+03 3.88149927e+03 3.81624707e+03 3.78991064e+03 3.74097388e+03 3.66826562e+03 3.59315283e+03 3.53878027e+03 3.61030591e+03 3.59173315e+03 3.38056982e+03 3.34417725e+03 3.46458569e+03 3.44406470e+03 3.33820215e+03 3.28061279e+03 3.23052466e+03 3.17762793e+03 3.14872412e+03 3.11924512e+03 3.07354126e+03 3.02392871e+03 2.91541504e+03 2.86112354e+03 2.97619263e+03 2.95166943e+03 2.81768359e+03 2.78234131e+03 2.75309766e+03 2.73225439e+03 2.67575903e+03 2.62552051e+03 2.60018848e+03 2.53018042e+03 2.48986646e+03 2.46741162e+03 2.42377344e+03 2.48090259e+03 2.46135474e+03 2.34467700e+03 2.24341479e+03 2.19687500e+03 2.29724023e+03 2.27496045e+03 2.16559082e+03 2.09705029e+03 2.07337573e+03 2.07013867e+03 2.01704175e+03 2.03932068e+03 2.01024634e+03 1.86950256e+03 1.81802429e+03 1.87935583e+03 1.91783081e+03 1.83963293e+03 1.76985901e+03 1.73252405e+03 1.69214050e+03 1.66191248e+03 1.63863928e+03 1.62600208e+03 1.58777002e+03 1.53105420e+03 1.50449243e+03 1.48059705e+03 1.45296838e+03 1.46363818e+03 1.43128430e+03 1.36522168e+03 1.33804297e+03 1.30737366e+03 1.31695801e+03 1.29606738e+03 1.23716064e+03 1.20857837e+03 1.15974414e+03 1.11551367e+03 1.14497986e+03 1.11304700e+03 1.03040601e+03 1.02097473e+03 1.05227832e+03 1.06353259e+03 1.00208972e+03 9.50793213e+02 9.20135071e+02 8.93528198e+02 8.75558228e+02 8.52732849e+02 8.30970154e+02 8.04196350e+02 8.03808594e+02 7.79501953e+02 7.38723450e+02 7.22220215e+02 6.80561768e+02 6.72440552e+02 6.92938538e+02 6.59457458e+02 6.22776855e+02 5.86464539e+02 5.64359863e+02 5.78958435e+02 5.62395325e+02 5.26196045e+02 4.96844849e+02 4.77562683e+02 4.71556519e+02 4.55052612e+02 4.51304749e+02 4.37387787e+02 4.07043976e+02 3.87375214e+02 3.73603333e+02 3.66370575e+02 3.50722961e+02 3.30594666e+02 3.14110138e+02 3.00470459e+02 2.88242676e+02 2.67274414e+02 2.59779663e+02 2.61004761e+02 2.43733566e+02 2.25917816e+02 2.08834778e+02 1.97218307e+02 1.97162109e+02 1.85971619e+02 1.70194855e+02 1.55884598e+02 1.46030258e+02 1.41862991e+02 1.31913757e+02 1.23059708e+02 1.12104492e+02 1.05893784e+02 1.03280510e+02 9.35611877e+01 8.52120361e+01 7.88267975e+01 7.14749298e+01 6.42444687e+01 5.87224693e+01 5.35957298e+01 4.80920753e+01 4.35240135e+01 3.82338562e+01 3.43653641e+01 3.18860455e+01 2.75362415e+01 2.38525925e+01 2.13778782e+01 1.88755665e+01 1.68870506e+01 1.50151300e+01 1.34202747e+01 1.23181667e+01 1.14503746e+01 1.09238510e+01 1.07599773e+01 1.09320431e+01 1.14168129e+01 1.22116203e+01 1.33732128e+01 1.47970610e+01 1.67814236e+01 1.94082718e+01 2.18330002e+01 2.41393356e+01 2.66603584e+01 3.02848949e+01 3.55435715e+01 3.98771820e+01 4.34513397e+01 4.74541321e+01 5.23035774e+01 5.88928642e+01 6.49006500e+01 7.22308121e+01 7.77897263e+01 8.24641113e+01 9.01814651e+01 9.78702774e+01 1.08976128e+02 1.16628281e+02 1.21822525e+02 1.30661682e+02 1.39650970e+02 1.48957916e+02 1.55450989e+02 1.70696823e+02 1.91280029e+02 1.96265869e+02 2.01881073e+02 2.09236099e+02 2.19190704e+02 2.44275040e+02 2.58109192e+02 2.63737274e+02 2.70670044e+02 2.81862152e+02 3.04037933e+02 3.17891876e+02 3.40151672e+02 3.56267639e+02 3.61824615e+02 3.66617035e+02 3.80521576e+02 4.19659790e+02 4.33919067e+02 4.38147949e+02 4.48780670e+02 4.63537445e+02 5.06482239e+02 5.26705322e+02 5.15191711e+02 5.32063660e+02 5.81079773e+02 5.99323486e+02 5.88509033e+02 6.06330750e+02 6.57132874e+02 6.82292603e+02 6.81502075e+02 6.85827942e+02 7.07362488e+02 7.65447144e+02 7.80938599e+02 7.80313660e+02 8.14259460e+02 8.34361023e+02 8.51833435e+02 8.76166260e+02 9.00101807e+02 9.02301941e+02 9.46525574e+02 1.01085773e+03 1.01383740e+03 1.04371045e+03 1.07382214e+03 1.07575867e+03 1.10278967e+03 1.13052380e+03 1.15062415e+03 1.15399622e+03 1.17957141e+03 1.23238184e+03 1.26312695e+03 1.32440088e+03 1.32002246e+03 1.30633337e+03 1.37396680e+03 1.41354797e+03 1.48019775e+03 1.49383728e+03 1.47436829e+03 1.49789233e+03 1.51864355e+03 1.58145764e+03 1.61424792e+03 1.67810828e+03 1.70708875e+03 1.69887488e+03 1.71971423e+03 1.70301965e+03 1.78824902e+03 1.91925378e+03 1.93153003e+03 1.90504675e+03 1.88382336e+03 1.89017969e+03 2.02000964e+03 2.11250391e+03 2.09679004e+03 2.05161914e+03 2.08088501e+03 2.16648560e+03 2.20923438e+03 2.28909375e+03 2.31498608e+03 2.29329590e+03 2.32041260e+03 2.35224463e+03 2.47997876e+03 2.53123828e+03 2.42477612e+03 2.45916968e+03 2.62904053e+03 2.65353931e+03 2.54797754e+03 2.62236743e+03 2.81197705e+03 2.83434839e+03 2.80673706e+03 2.76454565e+03 2.79619775e+03 3.00247314e+03 3.03552612e+03 2.99232495e+03 2.96137915e+03 2.96845605e+03 3.08405273e+03 3.15413672e+03 3.21587744e+03 3.14928516e+03 3.26041113e+03 3.44257397e+03 3.39544873e+03 3.44647266e+03 3.45744629e+03 3.43380322e+03 3.51811963e+03 3.57315088e+03 3.62026392e+03 3.62855078e+03 3.61746655e+03 3.59459399e+03 3.74035889e+03 3.97885449e+03 3.84831274e+03 3.72885571e+03 3.89928467e+03 4.04187720e+03 4.23436475e+03 4.16131934e+03 4.07455225e+03 4.21309717e+03 4.25188623e+03 4.17963428e+03 4.18347559e+03 4.39383154e+03 4.42169727e+03 4.39322119e+03 4.41225537e+03 4.32774316e+03 4.51481104e+03 4.85808789e+03 4.76717383e+03 4.67511865e+03 4.60663965e+03 4.59746191e+03 4.88813574e+03 5.15775928e+03 5.02921875e+03 4.86746729e+03 4.91736816e+03 5.01241797e+03 5.07778223e+03 5.29068701e+03 5.25857568e+03 5.15206934e+03 5.25508643e+03 5.28639795e+03 5.51461963e+03 5.54616406e+03 5.42053076e+03 5.47840283e+03 5.54214014e+03 5.66321582e+03 5.56922021e+03 5.61018262e+03 5.91100732e+03 5.91456055e+03 5.85942139e+03 5.74373389e+03 5.80309473e+03 6.25814355e+03 6.26385449e+03 6.09274316e+03 6.02082764e+03 6.02966943e+03 6.15677881e+03 6.25160059e+03 6.35662988e+03 6.26319043e+03 6.39189600e+03 6.70998047e+03 6.52384912e+03 6.69517480e+03 6.79764209e+03 6.65798584e+03 6.66747559e+03 6.67738721e+03 6.80988623e+03 6.86216211e+03 6.81948828e+03 6.87422119e+03 7.09600586e+03 7.23061572e+03 6.92017041e+03 6.89366748e+03 7.12492285e+03 7.33486426e+03 7.61358301e+03 7.47307373e+03 7.20951172e+03 7.44250098e+03 7.66432959e+03 7.59361572e+03 7.54538379e+03 7.55795215e+03 7.52205908e+03 7.56876221e+03 7.76187451e+03 7.66987158e+03 7.79333398e+03 8.18565186e+03 8.12865039e+03 7.97693213e+03 7.91977979e+03 7.96024854e+03 8.35880176e+03 8.40145703e+03 8.24454395e+03 8.08959424e+03 7.95870752e+03 8.18318066e+03 8.59755859e+03 8.87570996e+03 8.61527832e+03 8.34525195e+03 8.46594629e+03 8.56777148e+03 8.99073242e+03 8.95445703e+03 8.71721875e+03 8.72640137e+03 8.72912695e+03 8.94296680e+03 8.85520215e+03 8.90316797e+03 9.34104688e+03 9.28738965e+03 9.17980664e+03 9.01495898e+03 9.01672949e+03 9.59564355e+03 9.63307422e+03 9.35170508e+03 9.23027637e+03 9.17904395e+03 9.45818457e+03 9.59751270e+03 9.92678809e+03 9.91451270e+03 9.64205469e+03 9.40640234e+03 9.62016406e+03 1.02066504e+04 1.00796914e+04 9.87047461e+03 9.84815625e+03 9.89648145e+03 9.91614551e+03 9.86999219e+03 1.01755635e+04 1.01959199e+04 1.00287295e+04 1.04356279e+04 1.06029980e+04 1.04305479e+04 1.03677881e+04 1.03656367e+04 1.04534287e+04 1.02383828e+04 1.01839756e+04 1.07582334e+04 1.08798262e+04 1.03385391e+04 1.02015518e+04 1.07978301e+04 1.12420273e+04 1.11106172e+04 1.07352021e+04 1.05484336e+04 1.09910078e+04 1.11861953e+04 1.10310752e+04 1.11168008e+04 1.09064795e+04 1.05167451e+04 1.09587939e+04 1.16765781e+04 1.16890977e+04 11084. 1.08161855e+04 1.15122900e+04 1.18842939e+04 1.15404033e+04 1.11922393e+04 1.10779678e+04 1.13104883e+04 1.14387148e+04 1.19068682e+04 1.19716162e+04 1.15914326e+04 1.15063877e+04 1.15229912e+04 1.19947490e+04 1.18348525e+04 1.15381855e+04 1.20551191e+04 1.20935791e+04 1.19446318e+04 1.17399756e+04 1.17043750e+04 1.24060078e+04 1.21121475e+04 1.16282207e+04 1.19573203e+04 1.22485088e+04 1.22998076e+04 1.21776113e+04 1.25103291e+04 1.26133232e+04 1.23018965e+04 1.19734268e+04 1.19709463e+04 1.26839619e+04 1.25645439e+04 1.22553174e+04 1.23610781e+04 1.23717451e+04 1.25931738e+04 1.25449678e+04 1.27147119e+04 1.25997207e+04 1.23787754e+04 1.28231436e+04 1.29346895e+04 1.27673408e+04 1.27513447e+04 1.27870098e+04 1.27016152e+04 1.23470498e+04 1.23484160e+04 1.30215322e+04 1.35131289e+04 1.28652441e+04 1.23318008e+04 1.28656543e+04 1.34398467e+04 1.33062422e+04 1.28540527e+04 1.25455771e+04 1.32081924e+04 1.32635332e+04 1.28329180e+04 1.34597510e+04 1.33514209e+04 1.26648047e+04 1.28457490e+04 1.35149248e+04 1.36340293e+04 1.30406865e+04 1.26967871e+04 1.32887666e+04 1.38507461e+04 1.35386201e+04 1.29472363e+04 1.27403164e+04 1.34933926e+04 1.37156016e+04 1.32594951e+04 1.33765391e+04 1.35000957e+04 1.33153916e+04 1.32231904e+04 1.37532148e+04 1.35022793e+04 1.30651045e+04 1.35906875e+04 1.36735703e+04 1.37104551e+04 1.34214424e+04 1.31379424e+04 1.37385596e+04 1.34578789e+04 1.31254268e+04 1.37271279e+04 1.45236611e+04 1.47380127e+04 1.32682598e+04 1.43015176e+04 1.53185723e+04 1.18488691e+04 1.22118076e+04 1.28672490e+04 1.40905615e+04 2.05572148e+04 1.77976465e+04 1.96842539e+04 2.57840254e+04 3.78276875e+04 3.23764094e+05 4.02860401e+10 0. 0. 0. 0. -4.32443351e+10 -4.32443351e+10 8.42669766e+04 4.49461504e+09 6.28439648e+04 2.89728613e+04 4.47524648e+04 1.13304047e+05 9.50585344e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.81452820e+10 1.55116234e+05 3.98284805e+04 3.33826094e+04 1.84539727e+04 1.76787305e+04 2.01323340e+04 1.88140664e+04 1.63009238e+04 1.40480557e+04 1.53919014e+04 1.39420723e+04 1.36712812e+04 1.37839736e+04 1.37117217e+04 1.35423447e+04 1.36278389e+04 1.34730459e+04 1.33403691e+04 1.36746875e+04 1.37190146e+04 1.35824189e+04 1.35543867e+04 1.32073086e+04 1.32397871e+04 1.35647490e+04 1.34104111e+04 1.32372373e+04 1.36110166e+04 1.39638936e+04 1.35763389e+04 1.32078516e+04 1.31772148e+04 1.31122012e+04 1.33768916e+04 1.36548945e+04 1.33888477e+04 1.33413408e+04 1.35647031e+04 1.33430869e+04 1.30929424e+04 1.31531328e+04 1.31273174e+04 1.31682656e+04 1.34885039e+04 1.32339121e+04 1.30029189e+04 1.33267236e+04 1.31788857e+04 1.29730693e+04 1.29733389e+04 1.29646377e+04 1.30907627e+04 1.31972354e+04 1.33321543e+04 1.30961484e+04 1.28178486e+04 1.30478828e+04 1.27727002e+04 1.25986514e+04 1.30160840e+04 1.29214551e+04 1.28094619e+04 1.30224141e+04 1.29594248e+04 1.26753594e+04 1.26379951e+04 1.25802656e+04 1.25433965e+04 1.26956162e+04 1.26953838e+04 1.26925918e+04 1.27061709e+04 1.26036855e+04 1.25554912e+04 1.24855820e+04 1.25330947e+04 1.24691094e+04 1.24644326e+04 1.27768457e+04 1.24782539e+04 1.19744805e+04 1.22299062e+04 1.22503555e+04 1.21492480e+04 1.24327041e+04 1.22240410e+04 1.20569395e+04 1.23705352e+04 1.25114619e+04 1.21445439e+04 1.17944971e+04 1.17740664e+04 1.18704707e+04 1.20389766e+04 1.20297266e+04 1.20358828e+04 1.20681562e+04 1.19743193e+04 1.17547031e+04 1.15282617e+04 1.17664678e+04 1.17911631e+04 1.15179375e+04 1.17021875e+04 1.16504619e+04 1.15258242e+04 1.16763076e+04 1.14694238e+04 1.12282715e+04 1.12888428e+04 1.14848018e+04 1.15280742e+04 1.13458828e+04 1.13266943e+04 1.13753740e+04 1.13555820e+04 1.12683770e+04 1.09935537e+04 1.08581689e+04 1.12283594e+04 1.11925996e+04 1.08659170e+04 1.09894287e+04 1.08536953e+04 1.07343027e+04 1.09351064e+04 1.08569766e+04 1.06143896e+04 1.06681738e+04 1.08875771e+04 1.08616279e+04 1.06774971e+04 1.03239805e+04 1.02680684e+04 1.05619365e+04 1.05997373e+04 1.02890234e+04 1.03095918e+04 1.05532373e+04 1.04691055e+04 1.03297363e+04 1.01896982e+04 9.90515332e+03 9.83433984e+03 9.95499219e+03 1.01232520e+04 1.00451230e+04 9.91938672e+03 1.00429814e+04 9.96671094e+03 9.73023145e+03 9.60963379e+03 9.60240527e+03 9.61688477e+03 9.71582031e+03 9.83734961e+03 9.69936426e+03 9.55215137e+03 9.33917773e+03 9.46899414e+03 9.45081152e+03 9.08024902e+03 9.04930762e+03 9.31311133e+03 9.44017090e+03 9.09140625e+03 8.97052246e+03 8.92068750e+03 8.85780469e+03 8.99082812e+03 9.10995410e+03 8.99811523e+03 8.81590332e+03 8.79046875e+03 8.78989648e+03 8.60002637e+03 8.54199609e+03 8.54311719e+03 8.48071289e+03 8.67364453e+03 8.70766504e+03 8.30923730e+03 8.25822070e+03 8.29337695e+03 8.28255664e+03 8.37239551e+03 7.99532324e+03 7.88466016e+03 8.20458594e+03 8.21045020e+03 7.97722168e+03 7.87448633e+03 7.84906055e+03 7.74957568e+03 7.76130713e+03 7.86167969e+03 7.77155615e+03 7.54920020e+03 7.62357666e+03 7.77831836e+03 7.55428125e+03 7.43259619e+03 7.36395020e+03 7.30665576e+03 7.46936133e+03 7.29797656e+03 7.17175488e+03 7.32633203e+03 7.06481494e+03 6.98527393e+03 7.08784814e+03 6.88572705e+03 6.85532764e+03 6.98781348e+03 6.93314258e+03 6.86797705e+03 6.70907520e+03 6.73271875e+03 6.61608740e+03 6.53352148e+03 6.65871387e+03 6.43106250e+03 6.33665674e+03 6.47126611e+03 6.46151465e+03 6.30876855e+03 6.32247803e+03 6.34088379e+03 6.11660303e+03 6.17136133e+03 6.29376318e+03 6.00286377e+03 5.88361572e+03 5.91487305e+03 5.89243896e+03 5.77862793e+03 5.72845850e+03 5.72665479e+03 5.73497852e+03 5.75089795e+03 5.68391260e+03 5.55504980e+03 5.51849658e+03 5.46294434e+03 5.38362402e+03 5.45073242e+03 5.28671387e+03 5.23844189e+03 5.35108643e+03 5.19157959e+03 5.08576465e+03 5.09806250e+03 5.05420459e+03 4.94826611e+03 4.92564404e+03 4.93309131e+03 4.93536621e+03 4.86898145e+03 4.78512598e+03 4.78386523e+03 4.63216748e+03 4.58392920e+03 4.57870459e+03 4.47427979e+03 4.56161084e+03 4.59347852e+03 4.40263965e+03 4.30148584e+03 4.30306934e+03 4.39754785e+03 4.29802344e+03 4.06306226e+03 4.14028027e+03 4.22364062e+03 4.07023779e+03 3.99222729e+03 3.94831787e+03 3.92009009e+03 3.89143750e+03 3.83375610e+03 3.75036304e+03 3.81557324e+03 3.77362695e+03 3.66628589e+03 3.67750098e+03 3.63463062e+03 3.55587891e+03 3.50874683e+03 3.36236621e+03 3.43145581e+03 3.50531738e+03 3.31965601e+03 3.25251685e+03 3.25221484e+03 3.24002930e+03 3.21060791e+03 3.09500977e+03 3.10631934e+03 3.12679565e+03 3.04840869e+03 3.00160571e+03 2.93096021e+03 2.86397021e+03 2.85556494e+03 2.84192212e+03 2.77884253e+03 2.76993896e+03 2.75047119e+03 2.67819531e+03 2.67065332e+03 2.62635400e+03 2.53894556e+03 2.49718555e+03 2.50375366e+03 2.49400171e+03 2.40213599e+03 2.34012036e+03 2.30776929e+03 2.30194092e+03 2.30125415e+03 2.25077881e+03 2.16967847e+03 2.14072754e+03 2.14954639e+03 2.15467603e+03 2.07748901e+03 1.97984375e+03 1.98083911e+03 1.97534839e+03 1.91525464e+03 1.88635095e+03 1.87720862e+03 1.84492371e+03 1.79705859e+03 1.78760132e+03 1.76100195e+03 1.69797327e+03 1.65964697e+03 1.63665015e+03 1.61998914e+03 1.55144812e+03 1.50248425e+03 1.50976685e+03 1.50023596e+03 1.48331738e+03 1.43595300e+03 1.37947778e+03 1.38443823e+03 1.36980859e+03 1.29781335e+03 1.26320398e+03 1.26289648e+03 1.25712256e+03 1.22101709e+03 1.16244836e+03 1.12455823e+03 1.11269556e+03 1.11413928e+03 1.09956750e+03 1.07442407e+03 1.02214856e+03 9.78549866e+02 9.64100464e+02 9.36331665e+02 9.16813171e+02 9.00456360e+02 8.74921326e+02 8.56983948e+02 8.31597839e+02 8.07086243e+02 7.82690247e+02 7.65262817e+02 7.63496643e+02 7.32899292e+02 6.88312439e+02 6.67933105e+02 6.60776733e+02 6.49584839e+02 6.34442627e+02 6.07117615e+02 5.67078247e+02 5.48515564e+02 5.47425476e+02 5.35699402e+02 5.16920288e+02 4.89756256e+02 4.63383148e+02 4.52372620e+02 4.37543579e+02 4.24703033e+02 4.06360596e+02 3.79941803e+02 3.73505737e+02 3.64654266e+02 3.43689972e+02 3.25029144e+02 3.05993591e+02 2.97843079e+02 2.97094391e+02 2.80623016e+02 2.57261383e+02 2.48994019e+02 2.42307571e+02 2.21905655e+02 2.07712921e+02 1.95409744e+02 1.86306290e+02 1.83322281e+02 1.70920395e+02 1.55436386e+02 1.47425110e+02 1.39746414e+02 1.28448395e+02 1.19806854e+02 1.13396156e+02 1.05078033e+02 9.59210510e+01 8.86324387e+01 8.09819260e+01 7.56372147e+01 7.02059402e+01 6.33197670e+01 5.68877754e+01 4.97418861e+01 4.49191666e+01 4.08921013e+01 3.64978294e+01 3.28109856e+01 2.88771973e+01 2.52166672e+01 2.15703716e+01 1.87908173e+01 1.65139523e+01 1.43164215e+01 1.23550739e+01 1.07477036e+01 9.62947083e+00 8.87728405e+00 8.42377281e+00 8.26546574e+00 8.40176201e+00 8.90819931e+00 9.88322067e+00 1.11992216e+01 1.26097546e+01 1.42835741e+01 1.62327061e+01 1.86822205e+01 2.20589542e+01 2.53606148e+01 2.80327568e+01 3.15099163e+01 3.62516212e+01 4.17338982e+01 4.66468506e+01 5.08912849e+01 5.60095863e+01 6.21985550e+01 6.87640762e+01 7.48448944e+01 8.08796768e+01 8.88268890e+01 9.73031921e+01 1.04301193e+02 1.13146759e+02 1.21113297e+02 1.29490082e+02 1.40458084e+02 1.49314240e+02 1.58268127e+02 1.66591339e+02 1.76632874e+02 1.89723724e+02 2.02232834e+02 2.14273560e+02 2.22346451e+02 2.31565933e+02 2.48716537e+02 2.63226654e+02 2.75429382e+02 2.89519501e+02 2.96873779e+02 3.11836884e+02 3.34602417e+02 3.45524719e+02 3.53379120e+02 3.78383453e+02 3.94833862e+02 3.97529358e+02 4.23587036e+02 4.40437073e+02 4.46318298e+02 4.78170135e+02 5.00764679e+02 5.04630188e+02 5.21287964e+02 5.45877441e+02 5.60317810e+02 5.83089294e+02 6.02547302e+02 6.07468506e+02 6.33301941e+02 6.67849060e+02 6.89846130e+02 7.10436157e+02 7.22568909e+02 7.45245178e+02 7.63010376e+02 7.72267029e+02 8.13288208e+02 8.40250061e+02 8.46347839e+02 8.88491943e+02 9.13144287e+02 9.12638245e+02 9.52981750e+02 9.86510803e+02 1.00819653e+03 1.03164246e+03 1.03847559e+03 1.05214807e+03 1.11224402e+03 1.16259985e+03 1.15437000e+03 1.17719470e+03 1.19214917e+03 1.22301672e+03 1.28717432e+03 1.28384058e+03 1.29070898e+03 1.34983838e+03 1.39627490e+03 1.40946570e+03 1.39605017e+03 1.45779089e+03 1.51492126e+03 1.51773364e+03 1.55866028e+03 1.56739514e+03 1.59716052e+03 1.66088831e+03 1.68492651e+03 1.73084070e+03 1.72761902e+03 1.74311169e+03 1.80074622e+03 1.82705127e+03 1.88707007e+03 1.90559485e+03 1.90104382e+03 1.95956604e+03 2.02755237e+03 2.05253589e+03 2.06623535e+03 2.10286499e+03 2.14085449e+03 2.18624707e+03 2.20850610e+03 2.20634131e+03 2.30101172e+03 2.33033008e+03 2.34041650e+03 2.42589771e+03 2.42579712e+03 2.41999194e+03 2.51251562e+03 2.50784180e+03 2.53698535e+03 2.64356104e+03 2.64464551e+03 2.64665137e+03 2.69693311e+03 2.75784985e+03 2.80272754e+03 2.89172095e+03 2.89277661e+03 2.89025977e+03 2.94587988e+03 2.94550415e+03 3.00854004e+03 3.05876978e+03 3.12535352e+03 3.20371118e+03 3.15023242e+03 3.23579419e+03 3.27862646e+03 3.25149316e+03 3.34107593e+03 3.40763867e+03 3.48666577e+03 3.47986377e+03 3.47546997e+03 3.58220801e+03 3.61134790e+03 3.63130298e+03 3.66601465e+03 3.72217700e+03 3.83561694e+03 3.82246167e+03 3.84639233e+03 3.94115161e+03 3.90838696e+03 3.92555298e+03 4.08174463e+03 4.14653027e+03 4.07141284e+03 4.15677393e+03 4.18083740e+03 4.17149219e+03 4.43259033e+03 4.39297656e+03 4.32218896e+03 4.60812012e+03 4.59575488e+03 4.51353906e+03 4.57935889e+03 5.91014795e+03 6.45466602e+03 1.21970635e+04 1.49668018e+04 1.94678625e+06 -9529158. 5717872. -6.87238550e+06 10173138. -142376032. 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. 0. 0. 0. 0. 0. 0. 0. 0. 603420288. -16902752. 1.71963850e+06 7155243. 4.09413875e+06 2.11521035e+04 1.77040703e+04 1.13196357e+04 9.36728320e+03 9.80048828e+03 8.03878711e+03 7.34582422e+03 7.28832324e+03 7.51641846e+03 7.48408740e+03 7.45563135e+03 7.47221533e+03 7.59715918e+03 7.74573828e+03 7.79740332e+03 7.67806641e+03 7.55387988e+03 7.84729248e+03 7.99502539e+03 7.93923242e+03 8.04602246e+03 7.89593018e+03 7.93123828e+03 8.09545068e+03 8.19522754e+03 8.28796777e+03 8.05502832e+03 7.99816260e+03 8.46879883e+03 8.71537207e+03 8.53151270e+03 8.17312158e+03 8.24540430e+03 8.61452051e+03 8.73417090e+03 8.63009668e+03 8.50450879e+03 8.76701270e+03 8.98901660e+03 8.93435742e+03 8.93380078e+03 8.61214844e+03 8.83277246e+03 9.29850684e+03 9.15837598e+03 9.14446680e+03 9.13573926e+03 8.95681738e+03 9.19106152e+03 9.54083691e+03 9.44465625e+03 9.15823047e+03 9.44032812e+03 9.58453418e+03 9.50022168e+03 9.60012891e+03 9.40203125e+03 9.68217480e+03 9.82812598e+03 9.68786914e+03 9.61553223e+03 9.55100391e+03 9.84665820e+03 1.01938770e+04 1.01436035e+04 9.99139844e+03 9.83244238e+03 9.97972461e+03 1.00487373e+04 1.02237520e+04 1.03455088e+04 1.00479951e+04 1.02094932e+04 1.04907188e+04 1.04488936e+04 1.04069385e+04 1.01690420e+04 1.03703096e+04 1.07456846e+04 1.07362715e+04 1.06133252e+04 1.03982852e+04 1.04728125e+04 1.07965645e+04 1.10059092e+04 1.07713242e+04 1.05559453e+04 1.09652178e+04 1.09648643e+04 1.08655967e+04 1.12000703e+04 1.09545801e+04 1.09979424e+04 1.12641475e+04 1.11969873e+04 1.13016836e+04 1.10898975e+04 1.09182822e+04 1.12760234e+04 1.15356836e+04 1.15627461e+04 1.13474424e+04 1.13699043e+04 1.14828066e+04 1.15549414e+04 1.16007715e+04 1.13393564e+04 1.15102510e+04 1.19286758e+04 1.18689619e+04 1.15590791e+04 1.13335205e+04 1.16842295e+04 1.22703604e+04 1.21806797e+04 1.18906797e+04 1.16185264e+04 1.17033428e+04 1.19936455e+04 1.21694346e+04 1.23010469e+04 1.19563232e+04 1.19452646e+04 1.20596699e+04 1.21516250e+04 1.24698389e+04 1.20859102e+04 1.20808213e+04 1.25142393e+04 1.23587734e+04 1.22709883e+04 1.22710156e+04 1.23646064e+04 1.26042090e+04 1.25747344e+04 1.23215469e+04 1.21040479e+04 1.24994854e+04 1.30300967e+04 1.28704893e+04 1.25755273e+04 1.23534541e+04 1.24907158e+04 1.27679658e+04 1.28864795e+04 1.28998242e+04 1.24310742e+04 1.24188594e+04 1.27914590e+04 1.30771025e+04 1.32049297e+04 1.29666748e+04 1.28157529e+04 1.27309717e+04 1.29384277e+04 1.31800195e+04 1.29177529e+04 1.29177373e+04 1.30655947e+04 1.30649053e+04 1.31905332e+04 1.29059043e+04 1.30311162e+04 1.33183867e+04 1.31081436e+04 1.32764941e+04 1.31621680e+04 1.31664209e+04 1.33600381e+04 1.33611211e+04 1.32951533e+04 1.29067930e+04 1.30601006e+04 1.35206436e+04 1.37490723e+04 1.36002949e+04 1.29905127e+04 1.29341885e+04 1.34248633e+04 1.37146758e+04 1.36258916e+04 1.31216504e+04 1.32259307e+04 1.35042646e+04 1.34890645e+04 1.36925830e+04 1.33043652e+04 1.32306172e+04 1.36151201e+04 1.37222637e+04 1.36406201e+04 1.34328809e+04 1.35631162e+04 1.35238408e+04 1.35660371e+04 1.39034189e+04 1.35845732e+04 1.34772754e+04 1.36219541e+04 1.34768154e+04 1.33906025e+04 1.34514414e+04 1.37938037e+04 1.39351641e+04 1.38246152e+04 1.35430439e+04 1.30777510e+04 1.35075908e+04 1.42524951e+04 1.41312559e+04 1.38430791e+04 1.34370479e+04 1.32266895e+04 1.36013779e+04 1.40524395e+04 1.39704590e+04 1.37585830e+04 1.38216055e+04 1.37650293e+04 1.36750605e+04 1.34475410e+04 1.32222627e+04 1.35329385e+04 1.36826494e+04 1.40098926e+04 1.38417256e+04 1.31846084e+04 1.38210664e+04 1.40072559e+04 1.34887666e+04 1.36831250e+04 1.37051895e+04 1.40150938e+04 1.39687559e+04 1.32578682e+04 1.30944453e+04 1.33415332e+04 1.39633428e+04 1.44751689e+04 1.40892842e+04 1.33289756e+04 1.29674355e+04 1.32642334e+04 1.39365928e+04 1.42695557e+04 1.40639580e+04 1.32187842e+04 1.31180869e+04 1.40198867e+04 1.39997988e+04 1.32892949e+04 1.31652832e+04 1.34986123e+04 1.35433779e+04 1.39189150e+04 1.36118447e+04 1.30716494e+04 1.34768652e+04 1.32303955e+04 1.34370850e+04 1.38039277e+04 1.31657246e+04 1.33250908e+04 1.37290732e+04 1.34866113e+04 1.34000781e+04 1.33391797e+04 1.33885361e+04 1.35213896e+04 1.33040254e+04 1.28944668e+04 1.30003652e+04 1.35905635e+04 1.39180879e+04 1.35734766e+04 1.29888447e+04 1.26513936e+04 1.28434756e+04 1.34055723e+04 1.38505117e+04 1.34952119e+04 1.28224209e+04 1.28178242e+04 1.32247354e+04 1.31724072e+04 1.28799062e+04 1.28986240e+04 1.29811230e+04 1.29975215e+04 1.33274619e+04 1.30114316e+04 1.26682275e+04 1.29010410e+04 1.24698203e+04 1.27878770e+04 1.32344590e+04 1.27744404e+04 1.30597119e+04 1.29088994e+04 1.23414209e+04 1.26874863e+04 1.23856680e+04 1.25073896e+04 1.33963008e+04 1.27016191e+04 1.19854336e+04 1.22767568e+04 1.28049551e+04 1.31742900e+04 1.28305830e+04 1.21874570e+04 1.19019277e+04 1.20394707e+04 1.25280713e+04 1.29457510e+04 1.26787715e+04 1.19940488e+04 1.18557812e+04 1.22986494e+04 1.24060029e+04 1.20491738e+04 1.19214492e+04 1.20668037e+04 1.20282051e+04 1.24094082e+04 1.24234727e+04 1.17053330e+04 1.16562139e+04 1.18432783e+04 1.18326084e+04 1.19139072e+04 1.18396621e+04 1.20379082e+04 1.17726494e+04 1.13467295e+04 1.16570996e+04 1.13021846e+04 1.15839707e+04 1.22987666e+04 1.15328457e+04 1.08270713e+04 1.11589238e+04 1.16778760e+04 1.19151533e+04 1.18876904e+04 1.11662578e+04 1.06774570e+04 1.09344443e+04 1.14643096e+04 1.18479209e+04 1.15166982e+04 1.08060840e+04 1.06755166e+04 1.09909189e+04 1.11074395e+04 1.12383438e+04 1.11829873e+04 1.05985986e+04 1.05417412e+04 1.09454473e+04 1.10003467e+04 1.07173008e+04 1.06130791e+04 1.04863027e+04 1.04220293e+04 1.08200811e+04 1.09294512e+04 1.04374424e+04 1.02736631e+04 1.02046729e+04 1.01469609e+04 1.03319805e+04 1.02731885e+04 1.05380840e+04 1.04752461e+04 1.00383047e+04 9.81844922e+03 9.67025391e+03 1.00445400e+04 1.04963057e+04 1.02258408e+04 9.70996582e+03 9.36818457e+03 9.74800586e+03 1.02661826e+04 9.71566406e+03 9.20755469e+03 9.40559180e+03 9.61304395e+03 9.78760059e+03 9.96582910e+03 9.75635938e+03 9.13422949e+03 8.96009961e+03 9.32508691e+03 9.41608398e+03 9.34196289e+03 9.22329980e+03 9.14181738e+03 9.02360840e+03 9.19843164e+03 8.98727539e+03 8.72658887e+03 8.74441406e+03 8.79200195e+03 9.07491309e+03 9.02028027e+03 8.70816699e+03 8.79835840e+03 8.69372754e+03 8.63962891e+03 8.43710547e+03 8.13588086e+03 8.54476855e+03 8.89983887e+03 8.48986719e+03 8.07293896e+03 8.05023828e+03 8.43557324e+03 8.48088281e+03 8.29585547e+03 8.08475879e+03 7.82046533e+03 7.78987939e+03 8.04844141e+03 8.01177783e+03 7.80052246e+03 7.56361035e+03 7.45685986e+03 7.79824854e+03 8.15355322e+03 7.67793066e+03 7.35061084e+03 7.50535986e+03 7.48025146e+03 7.64165527e+03 7.56556396e+03 7.04032178e+03 7.07849658e+03 7.28816357e+03 7.19916211e+03 7.17040527e+03 7.25821631e+03 6.96125635e+03 7.53326318e+03 7.47490771e+03 6.84601416e+03 7.78943018e+03 8.11335742e+03 1.78970840e+04 1.15692373e+04 1.93388457e+04 1.87970098e+04 3.03429775e+06 2.99278325e+06 -12152901. 2221401. 4.89029250e+06 -1.84002962e+06 -18437276. 4238268. 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. 0. -125313584. -125313584. -125313584. 0. 0. -20887132. -6.01617750e+06 -3.10240275e+06 1.48833740e+04 1.17201816e+04 7.45747754e+03 7.10475439e+03 5.41944922e+03 5.31298047e+03 4.40849170e+03 4.35171289e+03 4.20594092e+03 4.03561694e+03 4.09359692e+03 4.07386621e+03 3.92848071e+03 3.91136792e+03 3.89144482e+03 3.81145093e+03 3.77391187e+03 3.70150635e+03 3.64100952e+03 3.61526025e+03 3.57543262e+03 3.57446460e+03 3.55112280e+03 3.37979736e+03 3.34517358e+03 3.45779346e+03 3.41978247e+03 3.32117505e+03 3.27536475e+03 3.22250513e+03 3.18970215e+03 3.13902441e+03 3.10977954e+03 3.06248804e+03 3.01742310e+03 2.94627173e+03 2.89121582e+03 2.95642700e+03 2.93980225e+03 2.83161914e+03 2.77881885e+03 2.75127710e+03 2.72827295e+03 2.67553223e+03 2.63877856e+03 2.60550879e+03 2.52146924e+03 2.47174316e+03 2.46932251e+03 2.42588477e+03 2.48622876e+03 2.45332935e+03 2.33600098e+03 2.24654590e+03 2.20142188e+03 2.29596680e+03 2.27944971e+03 2.17542896e+03 2.08963257e+03 2.05636328e+03 2.06526270e+03 2.02618091e+03 2.03842603e+03 2.01414697e+03 1.87065674e+03 1.80613708e+03 1.87113525e+03 1.92138306e+03 1.83092566e+03 1.76428516e+03 1.72950635e+03 1.69028992e+03 1.65945093e+03 1.63827380e+03 1.60374890e+03 1.56045972e+03 1.54282861e+03 1.51684241e+03 1.48152466e+03 1.44799365e+03 1.46286218e+03 1.43837146e+03 1.37210938e+03 1.33387000e+03 1.30674292e+03 1.30359558e+03 1.27781982e+03 1.22978455e+03 1.20744067e+03 1.15400574e+03 1.11164673e+03 1.13641492e+03 1.10539087e+03 1.02737402e+03 1.01643060e+03 1.04810754e+03 1.05759912e+03 9.98499756e+02 9.44011230e+02 9.12773132e+02 8.89711426e+02 8.73549438e+02 8.49118347e+02 8.25087097e+02 8.01631714e+02 8.04466309e+02 7.84225220e+02 7.40091980e+02 7.18418457e+02 6.78500610e+02 6.63649231e+02 6.82319641e+02 6.55512329e+02 6.21400085e+02 5.88760132e+02 5.59907898e+02 5.69645447e+02 5.61817810e+02 5.27657654e+02 4.95046997e+02 4.76397186e+02 4.70225616e+02 4.52455536e+02 4.49904633e+02 4.36292603e+02 4.05241180e+02 3.83934723e+02 3.68299072e+02 3.61888885e+02 3.48008759e+02 3.28513092e+02 3.13473541e+02 2.99737732e+02 2.84865631e+02 2.64749390e+02 2.55481415e+02 2.55821899e+02 2.40336182e+02 2.23340057e+02 2.06754791e+02 1.94721741e+02 1.94085754e+02 1.82817291e+02 1.67685226e+02 1.54063843e+02 1.44012741e+02 1.38959244e+02 1.28906540e+02 1.20504013e+02 1.09627922e+02 1.02958267e+02 1.00841019e+02 9.11148071e+01 8.14344788e+01 7.50065002e+01 6.86505661e+01 6.21490669e+01 5.63800735e+01 5.06239319e+01 4.53928604e+01 4.05262680e+01 3.51803513e+01 3.15061607e+01 2.90311832e+01 2.48391800e+01 2.12333050e+01 1.87954006e+01 1.63186169e+01 1.43463755e+01 1.24225903e+01 1.08141069e+01 9.75356770e+00 8.92688560e+00 8.42438793e+00 8.26477909e+00 8.41245842e+00 8.87824345e+00 9.69406509e+00 1.08621407e+01 1.23069210e+01 1.43542175e+01 1.69577808e+01 1.93232994e+01 2.18343163e+01 2.46007080e+01 2.79267521e+01 3.29868889e+01 3.74744682e+01 4.11630783e+01 4.49282913e+01 4.97239265e+01 5.66392593e+01 6.26380806e+01 6.99246597e+01 7.56707916e+01 8.05393753e+01 8.84603271e+01 9.58607559e+01 1.06968460e+02 1.14634041e+02 1.19037422e+02 1.28622696e+02 1.38172668e+02 1.46496536e+02 1.51947052e+02 1.66162979e+02 1.87056992e+02 1.93410385e+02 1.99994171e+02 2.07341919e+02 2.17047852e+02 2.41869644e+02 2.55075409e+02 2.61284821e+02 2.68234436e+02 2.79218048e+02 3.01970490e+02 3.15177124e+02 3.36677612e+02 3.50551758e+02 3.56375702e+02 3.69007141e+02 3.81739716e+02 4.15023804e+02 4.30564758e+02 4.35363983e+02 4.48837769e+02 4.63316406e+02 4.97825226e+02 5.17482422e+02 5.12126282e+02 5.29088440e+02 5.76486938e+02 5.96440247e+02 5.85760315e+02 6.01761475e+02 6.53274841e+02 6.79789917e+02 6.77983582e+02 6.81539551e+02 7.04733276e+02 7.64134705e+02 7.75381226e+02 7.75265015e+02 8.12894958e+02 8.35911072e+02 8.49142212e+02 8.66635681e+02 8.95158752e+02 8.97737976e+02 9.45132629e+02 1.02361658e+03 1.01821460e+03 1.02782312e+03 1.05815527e+03 1.07487610e+03 1.09999390e+03 1.12763367e+03 1.15359375e+03 1.14941833e+03 1.16177783e+03 1.22040686e+03 1.27268652e+03 1.33373401e+03 1.32059265e+03 1.30219312e+03 1.36791638e+03 1.41187463e+03 1.48297632e+03 1.50005579e+03 1.48461841e+03 1.48774109e+03 1.50562646e+03 1.57858704e+03 1.61569885e+03 1.67474805e+03 1.71338440e+03 1.70923621e+03 1.70228601e+03 1.68819934e+03 1.78555371e+03 1.91037976e+03 1.92535938e+03 1.90514490e+03 1.88512659e+03 1.88909058e+03 2.01856812e+03 2.11013159e+03 2.08410620e+03 2.04395654e+03 2.07949341e+03 2.16787939e+03 2.20359790e+03 2.29154810e+03 2.33494922e+03 2.31475537e+03 2.31447485e+03 2.33608008e+03 2.45769458e+03 2.50763672e+03 2.42820996e+03 2.46065869e+03 2.63137427e+03 2.64878979e+03 2.55068457e+03 2.63022437e+03 2.80364014e+03 2.82273584e+03 2.80063330e+03 2.76387427e+03 2.78741357e+03 2.99840747e+03 3.04248047e+03 2.99439380e+03 2.94889795e+03 2.96688013e+03 3.08746924e+03 3.14932446e+03 3.19468628e+03 3.14523877e+03 3.26246411e+03 3.45714062e+03 3.40584937e+03 3.43327173e+03 3.46859424e+03 3.47673853e+03 3.52067285e+03 3.56316431e+03 3.60851587e+03 3.62907886e+03 3.63251831e+03 3.60188940e+03 3.73045752e+03 3.93413135e+03 3.83869165e+03 3.76399463e+03 3.92192480e+03 4.01645728e+03 4.18306396e+03 4.15578516e+03 4.07812134e+03 4.20478516e+03 4.22632812e+03 4.15657568e+03 4.19458301e+03 4.41055762e+03 4.44657520e+03 4.39567578e+03 4.37229443e+03 4.29553369e+03 4.51010107e+03 4.86077246e+03 4.80165283e+03 4.66251221e+03 4.63098047e+03 4.63330078e+03 4.90712744e+03 5.07126514e+03 4.96414258e+03 4.87142529e+03 4.88879443e+03 5.01318213e+03 5.07021387e+03 5.28761279e+03 5.31072070e+03 5.19674268e+03 5.26608398e+03 5.29400293e+03 5.47365918e+03 5.53154395e+03 5.50151074e+03 5.45800977e+03 5.51296191e+03 5.60436816e+03 5.53987354e+03 5.60426514e+03 5.93693652e+03 5.89492236e+03 5.87235010e+03 5.77167041e+03 5.76984326e+03 6.18035449e+03 6.24604834e+03 6.08405225e+03 6.02597461e+03 6.06874805e+03 6.15216260e+03 6.20859521e+03 6.31521484e+03 6.23486572e+03 6.43338379e+03 6.73989844e+03 6.56341992e+03 6.66255762e+03 6.74395752e+03 6.69602979e+03 6.69525342e+03 6.64967822e+03 6.77300244e+03 6.86663770e+03 6.90421143e+03 6.93534424e+03 7.05751270e+03 7.19131836e+03 6.90171924e+03 6.85501123e+03 7.13056396e+03 7.30494922e+03 7.55177637e+03 7.43764990e+03 7.26000586e+03 7.53961084e+03 7.56680176e+03 7.42154736e+03 7.57766260e+03 7.59480908e+03 7.58938623e+03 7.59988721e+03 7.75846240e+03 7.63097021e+03 7.84935498e+03 8.19571191e+03 8.07322656e+03 8.02821924e+03 7.94564453e+03 7.88435449e+03 8.27291504e+03 8.41352637e+03 8.25438574e+03 8.08612891e+03 7.97121338e+03 8.27174805e+03 8.50170605e+03 8.75991895e+03 8.59065625e+03 8.35486816e+03 8.56057031e+03 8.56953711e+03 8.95710645e+03 8.96658008e+03 8.69929004e+03 8.74947363e+03 8.73846094e+03 8.91375977e+03 8.76780469e+03 8.94956738e+03 9.43173633e+03 9.28515723e+03 9.21598145e+03 9.01865625e+03 8.94093164e+03 9.58233105e+03 9.57647852e+03 9.30486328e+03 9.20391602e+03 9.19403223e+03 9.49320410e+03 9.57593652e+03 9.84739258e+03 9.87981348e+03 9.66905469e+03 9.48568164e+03 9.51198047e+03 1.01130381e+04 1.00374512e+04 9.80830371e+03 9.95203418e+03 9.99261523e+03 9.94900781e+03 9.92483105e+03 1.02637373e+04 1.01143086e+04 9.94653906e+03 1.05187686e+04 1.06561406e+04 1.03640840e+04 1.02965127e+04 1.03946621e+04 1.04833584e+04 1.01915361e+04 1.01526709e+04 1.08019434e+04 1.08679180e+04 1.02637373e+04 1.01718994e+04 1.08459785e+04 1.13366748e+04 1.10151543e+04 1.06532236e+04 1.06689639e+04 1.11003721e+04 1.10760312e+04 1.08763174e+04 1.11108994e+04 1.09135674e+04 1.05895713e+04 1.10655703e+04 1.16023076e+04 1.15688711e+04 1.11076055e+04 1.08692256e+04 1.15288125e+04 1.18458438e+04 1.14578281e+04 1.12020176e+04 1.12419131e+04 1.14291572e+04 1.14439551e+04 1.18872314e+04 1.17933516e+04 1.13563262e+04 1.16763213e+04 1.17233389e+04 1.19261094e+04 1.17081895e+04 1.14584639e+04 1.19968340e+04 1.20789316e+04 1.18887715e+04 1.16846064e+04 1.17879746e+04 1.24764727e+04 1.21303701e+04 1.17534014e+04 1.20475137e+04 1.20970869e+04 1.21654209e+04 1.21854131e+04 1.25122705e+04 1.26132910e+04 1.22997383e+04 1.19628398e+04 1.19924746e+04 1.26609053e+04 1.25612861e+04 1.22242256e+04 1.24105283e+04 1.24826797e+04 1.25306035e+04 1.25134092e+04 1.27969434e+04 1.25258311e+04 1.22481230e+04 1.28442705e+04 1.28990801e+04 1.27667695e+04 1.27886250e+04 1.27844629e+04 1.27760137e+04 1.24743252e+04 1.23458799e+04 1.30311318e+04 1.33524941e+04 1.27288906e+04 1.23802363e+04 1.29517871e+04 1.34828057e+04 1.32026992e+04 1.27585811e+04 1.25825488e+04 1.32007432e+04 1.33283926e+04 1.29511436e+04 1.33079365e+04 1.33618115e+04 1.29529697e+04 1.28871494e+04 1.32764170e+04 1.35003936e+04 1.30004180e+04 1.27907324e+04 1.34439824e+04 1.37023018e+04 1.33770547e+04 1.29143330e+04 1.28247764e+04 1.36065303e+04 1.37263682e+04 1.32605537e+04 1.32322666e+04 1.33244961e+04 1.32691689e+04 1.32286348e+04 1.37796816e+04 1.34709209e+04 1.30183506e+04 1.37106729e+04 1.37825840e+04 1.36199434e+04 1.33443896e+04 1.31183555e+04 1.36794492e+04 1.34745928e+04 1.32858867e+04 1.37902842e+04 1.43647158e+04 1.45978135e+04 1.32662910e+04 1.43510010e+04 1.52656484e+04 1.17883525e+04 1.23584043e+04 1.32767520e+04 1.40180986e+04 2.00943691e+04 1.55128975e+04 1.60767676e+04 3.10572383e+04 5.85647734e+04 2.76090188e+05 -4.88527421e+10 0. 0. 0. 0. -4.32443351e+10 -4.32443351e+10 8.42669766e+04 -7.50941133e+09 9.00082483e+09 1.36508250e+05 1.36508250e+05 -1.87401339e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.81452820e+10 1.55116234e+05 2.85628574e+04 9.43519297e+04 4.47185781e+04 4.36032500e+04 3.54162773e+04 2.18949375e+04 1.52507041e+04 1.94205430e+04 1.61571875e+04 1.39202471e+04 1.39262598e+04 1.37334502e+04 1.36816660e+04 1.38531230e+04 1.35667305e+04 1.33935029e+04 1.34612070e+04 1.33461387e+04 1.35318652e+04 1.38852256e+04 1.38292881e+04 1.33770723e+04 1.33255664e+04 1.34566602e+04 1.31781934e+04 1.33072773e+04 1.36833857e+04 1.35606113e+04 1.35393428e+04 1.35554424e+04 1.32738086e+04 1.32568467e+04 1.33842617e+04 1.32569434e+04 1.31356953e+04 1.34377119e+04 1.36204805e+04 1.32495342e+04 1.31499033e+04 1.32279912e+04 1.32335518e+04 1.33608672e+04 1.32494326e+04 1.29266289e+04 1.31636064e+04 1.35237930e+04 1.30332969e+04 1.28884980e+04 1.32056221e+04 1.28710117e+04 1.29231748e+04 1.33385371e+04 1.30703652e+04 1.28680166e+04 1.30458330e+04 1.33262285e+04 1.29872578e+04 1.26296309e+04 1.26345303e+04 1.26219756e+04 1.30005137e+04 1.32014961e+04 1.28735576e+04 1.26869482e+04 1.26357734e+04 1.25792559e+04 1.26767725e+04 1.25983955e+04 1.23943623e+04 1.26306660e+04 1.29451699e+04 1.26773066e+04 1.24631865e+04 1.26404678e+04 1.24797178e+04 1.23699180e+04 1.25047646e+04 1.24986484e+04 1.23201182e+04 1.21890254e+04 1.24050771e+04 1.23575117e+04 1.22935508e+04 1.22917119e+04 1.19233691e+04 1.21579141e+04 1.24938496e+04 1.21446104e+04 1.19807861e+04 1.20026201e+04 1.19932793e+04 1.20857461e+04 1.19365566e+04 1.16488623e+04 1.19574268e+04 1.22151846e+04 1.19561914e+04 1.16195596e+04 1.16110586e+04 1.18605098e+04 1.18044844e+04 1.16244863e+04 1.15665859e+04 1.14356338e+04 1.16657686e+04 1.18776064e+04 1.14899023e+04 1.12668838e+04 1.12237676e+04 1.12432285e+04 1.14020771e+04 1.15002900e+04 1.12830762e+04 1.12142715e+04 1.14595771e+04 1.14353457e+04 1.10754736e+04 1.08418887e+04 1.08954092e+04 1.10594824e+04 1.11086504e+04 1.10739932e+04 1.09381650e+04 1.09030059e+04 1.09031943e+04 1.06797402e+04 1.06007314e+04 1.06833135e+04 1.06026592e+04 1.07236904e+04 1.08371357e+04 1.03779609e+04 1.03193018e+04 1.06812217e+04 1.05076299e+04 1.01526006e+04 1.03261162e+04 1.05478809e+04 1.03995215e+04 1.02589990e+04 1.01766191e+04 1.00987510e+04 1.00332334e+04 9.90845117e+03 1.00172109e+04 9.99457812e+03 9.89331055e+03 9.92997559e+03 9.94925391e+03 9.85719922e+03 9.58873828e+03 9.64956250e+03 9.79279688e+03 9.56225879e+03 9.68410742e+03 9.77948633e+03 9.64107324e+03 9.38442090e+03 9.34529688e+03 9.33018359e+03 9.12568262e+03 9.25490527e+03 9.40014355e+03 9.27163477e+03 9.14148047e+03 9.03750000e+03 8.98640723e+03 9.00665430e+03 8.92774121e+03 8.79291895e+03 8.83560059e+03 8.89925977e+03 8.79917090e+03 8.71832031e+03 8.68882324e+03 8.61149609e+03 8.61298926e+03 8.54297949e+03 8.43587305e+03 8.54765527e+03 8.43152344e+03 8.29666699e+03 8.31937500e+03 8.32255957e+03 8.39536230e+03 7.96065625e+03 7.97235400e+03 8.21662305e+03 8.00171191e+03 8.07450684e+03 7.98480322e+03 7.79525684e+03 7.83824072e+03 7.75541357e+03 7.61832666e+03 7.65414307e+03 7.65862891e+03 7.67139258e+03 7.73104541e+03 7.62534863e+03 7.46837695e+03 7.42950879e+03 7.30365186e+03 7.24018506e+03 7.22399121e+03 7.26384668e+03 7.36468701e+03 7.08692822e+03 6.96764941e+03 7.06809375e+03 6.85333057e+03 6.93988086e+03 7.04090430e+03 6.81733496e+03 6.73806543e+03 6.75485156e+03 6.77468701e+03 6.70475781e+03 6.56384229e+03 6.48697607e+03 6.41369336e+03 6.44285205e+03 6.50300537e+03 6.43615234e+03 6.33697363e+03 6.28912842e+03 6.28917773e+03 6.14079346e+03 6.16030273e+03 6.23767334e+03 5.98218994e+03 5.90373633e+03 5.91735107e+03 5.90422900e+03 5.87661035e+03 5.80334863e+03 5.72647314e+03 5.70225146e+03 5.66619922e+03 5.61173096e+03 5.58197607e+03 5.66180469e+03 5.57220410e+03 5.29700439e+03 5.33604297e+03 5.31264795e+03 5.28211475e+03 5.35078662e+03 5.15387158e+03 5.04196289e+03 5.16778711e+03 5.10485205e+03 4.94411523e+03 4.89682080e+03 4.95418311e+03 4.93654590e+03 4.78488232e+03 4.78276123e+03 4.81519873e+03 4.66257861e+03 4.60340674e+03 4.60868457e+03 4.47575732e+03 4.51442432e+03 4.55399805e+03 4.35919531e+03 4.38469385e+03 4.43714258e+03 4.31918799e+03 4.19846094e+03 4.11196533e+03 4.13988818e+03 4.19312598e+03 4.06579834e+03 3.94823096e+03 3.96987354e+03 3.92764893e+03 3.86335840e+03 3.82118481e+03 3.81225244e+03 3.76912061e+03 3.69345020e+03 3.67436694e+03 3.68635938e+03 3.58370654e+03 3.53576636e+03 3.53619897e+03 3.41600195e+03 3.46863550e+03 3.45335913e+03 3.27977148e+03 3.30158960e+03 3.26994824e+03 3.17463184e+03 3.18846997e+03 3.13068042e+03 3.11245581e+03 3.11845020e+03 3.02776660e+03 2.97415674e+03 2.93258936e+03 2.86044629e+03 2.81928564e+03 2.81155957e+03 2.82117188e+03 2.78042676e+03 2.72101758e+03 2.68044409e+03 2.66155737e+03 2.60429126e+03 2.51887842e+03 2.51133203e+03 2.51732324e+03 2.47762280e+03 2.37949634e+03 2.31812866e+03 2.33476562e+03 2.35065186e+03 2.26441992e+03 2.20394995e+03 2.19556934e+03 2.16406006e+03 2.15756763e+03 2.12344580e+03 2.06027637e+03 1.98606653e+03 1.96617615e+03 1.95917993e+03 1.91333899e+03 1.90111938e+03 1.87568323e+03 1.83196667e+03 1.79349329e+03 1.79116077e+03 1.74323218e+03 1.67904395e+03 1.67725903e+03 1.66224890e+03 1.60939282e+03 1.53962402e+03 1.50592029e+03 1.51787427e+03 1.50668701e+03 1.46428174e+03 1.42287781e+03 1.39152734e+03 1.38594189e+03 1.35597534e+03 1.28665784e+03 1.26664014e+03 1.25956592e+03 1.24689807e+03 1.20455164e+03 1.15156140e+03 1.13744104e+03 1.12302380e+03 1.11063684e+03 1.09364282e+03 1.06209973e+03 1.00842773e+03 9.64577942e+02 9.70157349e+02 9.72218811e+02 9.27805054e+02 8.91281555e+02 8.64067139e+02 8.50944275e+02 8.40925110e+02 8.03408325e+02 7.77970947e+02 7.62226379e+02 7.53166321e+02 7.33031616e+02 6.87139648e+02 6.79209229e+02 6.65122986e+02 6.30566040e+02 6.16587952e+02 5.95284302e+02 5.73970398e+02 5.57162842e+02 5.36614502e+02 5.21251160e+02 5.07751923e+02 4.89837891e+02 4.63219147e+02 4.50388306e+02 4.42318451e+02 4.19601074e+02 4.00391144e+02 3.77686371e+02 3.65963165e+02 3.63834198e+02 3.44415833e+02 3.25308502e+02 3.05162506e+02 2.95569183e+02 2.92529938e+02 2.72402344e+02 2.56475220e+02 2.47832092e+02 2.33648788e+02 2.16726685e+02 2.07645859e+02 1.99198288e+02 1.85904892e+02 1.77223694e+02 1.65492096e+02 1.50922958e+02 1.44092468e+02 1.37010483e+02 1.27725937e+02 1.20894302e+02 1.10608643e+02 1.01686020e+02 9.34852676e+01 8.58096619e+01 7.96105423e+01 7.28897934e+01 6.60760803e+01 5.89987297e+01 5.37648048e+01 4.79287148e+01 4.29798393e+01 3.96036758e+01 3.47214966e+01 2.99722176e+01 2.58886585e+01 2.22657166e+01 1.92518368e+01 1.68677864e+01 1.44650335e+01 1.19516029e+01 9.96456909e+00 8.58215332e+00 7.56422853e+00 6.78708553e+00 6.28865957e+00 6.12133837e+00 6.30414963e+00 6.79037285e+00 7.57220745e+00 8.73994160e+00 1.02798195e+01 1.21401939e+01 1.41454363e+01 1.64691448e+01 1.98230591e+01 2.33704815e+01 2.65195923e+01 2.99177246e+01 3.41343079e+01 3.94351730e+01 4.47956505e+01 4.94002113e+01 5.38721161e+01 5.97455597e+01 6.68120499e+01 7.32475815e+01 8.01435318e+01 8.72785339e+01 9.31300430e+01 1.01461273e+02 1.10920166e+02 1.18940315e+02 1.28288544e+02 1.36760788e+02 1.46206299e+02 1.55847885e+02 1.65768143e+02 1.73114243e+02 1.83886322e+02 1.99765930e+02 2.13194351e+02 2.25542542e+02 2.31680420e+02 2.43161484e+02 2.56661163e+02 2.70968506e+02 2.91020203e+02 2.97505188e+02 3.10445923e+02 3.33526520e+02 3.37967773e+02 3.48031006e+02 3.75041077e+02 3.92085999e+02 4.02972717e+02 4.24356476e+02 4.32792206e+02 4.37527374e+02 4.71538086e+02 4.96794006e+02 5.01944489e+02 5.29798828e+02 5.50009277e+02 5.49260559e+02 5.72742371e+02 5.96381165e+02 6.12664734e+02 6.44798828e+02 6.62287476e+02 6.77229370e+02 7.03126953e+02 7.25234497e+02 7.49550964e+02 7.61071106e+02 7.75384521e+02 8.07382202e+02 8.34328186e+02 8.42590942e+02 8.70153381e+02 9.06632812e+02 9.21335754e+02 9.52156006e+02 9.80159058e+02 1.00002722e+03 1.02815271e+03 1.02957654e+03 1.05680261e+03 1.12104724e+03 1.14180237e+03 1.14847046e+03 1.18349268e+03 1.21679089e+03 1.23469995e+03 1.25917761e+03 1.25312683e+03 1.28044019e+03 1.35831091e+03 1.39827576e+03 1.41834912e+03 1.40822961e+03 1.44318066e+03 1.50367749e+03 1.52141162e+03 1.54250037e+03 1.57801929e+03 1.60282703e+03 1.64815686e+03 1.67902478e+03 1.72613647e+03 1.73983826e+03 1.74451685e+03 1.82676062e+03 1.82442944e+03 1.83411230e+03 1.88859546e+03 1.90402930e+03 1.96508252e+03 2.05251514e+03 2.06884399e+03 2.03010535e+03 2.07003857e+03 2.15091284e+03 2.19333984e+03 2.21119971e+03 2.22591748e+03 2.28110718e+03 2.33512378e+03 2.35940967e+03 2.40413623e+03 2.41583276e+03 2.44869800e+03 2.51955005e+03 2.46045581e+03 2.48734399e+03 2.64378516e+03 2.67095142e+03 2.68653882e+03 2.71462964e+03 2.71189624e+03 2.75486548e+03 2.88222266e+03 2.93738550e+03 2.90164429e+03 2.91343091e+03 2.93556104e+03 3.00290723e+03 3.09321411e+03 3.14308276e+03 3.18038306e+03 3.17091626e+03 3.21863159e+03 3.27234326e+03 3.24997900e+03 3.30003589e+03 3.42003052e+03 3.46073218e+03 3.46816309e+03 3.50032837e+03 3.54673901e+03 3.60518530e+03 3.59815430e+03 3.71055225e+03 3.73276733e+03 3.76951123e+03 3.81051001e+03 3.84617310e+03 3.98577124e+03 3.94490576e+03 3.93921826e+03 4.07553101e+03 4.06351196e+03 4.03534497e+03 4.17646826e+03 4.21841992e+03 4.20929395e+03 4.33001709e+03 4.40044971e+03 4.41063184e+03 4.52871436e+03 4.49986914e+03 4.44003955e+03 4.63239014e+03 6.13099463e+03 6.45670605e+03 7.19087012e+03 7.23429004e+03 7.85542578e+03 6.95914551e+03 1.40136055e+04 2.10181348e+04 10173138. -142376032. 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. 0. 0. 0. 0. 0. 0. 0. 0. 603420288. -16902752. 1.71963850e+06 7155243. 4.09413875e+06 -5986565. -13457735. 2.15235664e+04 1.45313105e+04 1.03420479e+04 8.30863965e+03 7.43059375e+03 7.34348486e+03 7.55222266e+03 7.43073047e+03 7.47902881e+03 7.54518945e+03 7.62105713e+03 7.74607275e+03 7.76842285e+03 7.71951221e+03 7.58821826e+03 7.84062646e+03 7.94579785e+03 7.93255322e+03 7.99632520e+03 7.84035938e+03 7.89821680e+03 8.30579590e+03 8.17069971e+03 8.05719141e+03 8.00074561e+03 8.20991992e+03 8.57540723e+03 8.66382520e+03 8.47189648e+03 8.17672461e+03 8.26401855e+03 8.63937109e+03 8.67808496e+03 8.70576465e+03 8.61648730e+03 8.71436719e+03 8.89464844e+03 8.93217383e+03 8.96053809e+03 8.68499023e+03 8.87131641e+03 9.43599805e+03 9.10102344e+03 8.88370020e+03 9.02704492e+03 9.02902930e+03 9.38838477e+03 9.49199316e+03 9.27024512e+03 9.12861621e+03 9.44356348e+03 9.67224219e+03 9.54125684e+03 9.47009863e+03 9.39720410e+03 9.64413574e+03 9.89473047e+03 9.67470898e+03 9.73447656e+03 9.68052051e+03 9.64848242e+03 1.00271357e+04 1.01775020e+04 1.00052119e+04 9.87985059e+03 1.00429521e+04 1.01564199e+04 1.01897441e+04 1.02944482e+04 1.00046904e+04 1.01211846e+04 1.05997715e+04 1.04173184e+04 1.00814141e+04 1.01253955e+04 1.05164717e+04 1.09439531e+04 1.07263916e+04 1.05867383e+04 1.04961953e+04 1.03938174e+04 1.06577949e+04 1.10004961e+04 1.08640098e+04 1.06238496e+04 1.08387295e+04 1.09607246e+04 1.10150303e+04 1.12372939e+04 1.08655879e+04 1.08202383e+04 1.14361504e+04 1.12454121e+04 1.10691250e+04 1.10828242e+04 1.09617881e+04 1.14515430e+04 1.15814502e+04 1.12240303e+04 1.12420811e+04 1.14919775e+04 1.16757217e+04 1.15538691e+04 1.15832266e+04 1.14750107e+04 1.14901436e+04 1.18792666e+04 1.17431074e+04 1.14984590e+04 1.14292109e+04 1.16576514e+04 1.21541729e+04 1.21308135e+04 1.19408037e+04 1.16294004e+04 1.16100938e+04 1.21927422e+04 1.22388496e+04 1.19419951e+04 1.18410576e+04 1.20288975e+04 1.23397109e+04 1.22034619e+04 1.20652939e+04 1.19563115e+04 1.22488076e+04 1.27185146e+04 1.23054004e+04 1.22073623e+04 1.23775234e+04 1.22513652e+04 1.25135039e+04 1.26103691e+04 1.24296611e+04 1.22342783e+04 1.23825625e+04 1.28624492e+04 1.28919756e+04 1.26966455e+04 1.23774150e+04 1.23986328e+04 1.29271025e+04 1.29726465e+04 1.27851748e+04 1.24970029e+04 1.23739727e+04 1.28265254e+04 1.31202051e+04 1.29595771e+04 1.27338799e+04 1.27775820e+04 1.28865127e+04 1.30110039e+04 1.32163027e+04 1.29534404e+04 1.28688135e+04 1.31846904e+04 1.30958701e+04 1.30019092e+04 1.29663750e+04 1.31497256e+04 1.32286055e+04 1.30239844e+04 1.30668154e+04 1.30105576e+04 1.32392363e+04 1.37088496e+04 1.33957402e+04 1.29841807e+04 1.29462422e+04 1.31777861e+04 1.35423193e+04 1.36891455e+04 1.36201348e+04 1.31235762e+04 1.28396973e+04 1.32871641e+04 1.37534424e+04 1.37378428e+04 1.31629316e+04 1.31201377e+04 1.35267285e+04 1.36170234e+04 1.36769600e+04 1.33971523e+04 1.33533066e+04 1.35669561e+04 1.34204590e+04 1.34461338e+04 1.35091836e+04 1.35086133e+04 1.37306777e+04 1.35832773e+04 1.35253994e+04 1.35191846e+04 1.36131816e+04 1.38218652e+04 1.35858535e+04 1.33764785e+04 1.33473691e+04 1.38650654e+04 1.41125771e+04 1.36460938e+04 1.34846836e+04 1.32454160e+04 1.34133174e+04 1.40831406e+04 1.40792949e+04 1.38160625e+04 1.33027373e+04 1.32111992e+04 1.40442900e+04 1.41705254e+04 1.36227480e+04 1.36496377e+04 1.38630469e+04 1.37617744e+04 1.35326533e+04 1.32679639e+04 1.32232803e+04 1.35073398e+04 1.38089854e+04 1.42191562e+04 1.39231387e+04 1.32452871e+04 1.35460176e+04 1.37662480e+04 1.36929307e+04 1.38011738e+04 1.36441758e+04 1.39890420e+04 1.39485068e+04 1.32454756e+04 1.30751709e+04 1.33408486e+04 1.39623379e+04 1.44710605e+04 1.41028008e+04 1.33170225e+04 1.29197109e+04 1.31725137e+04 1.39263643e+04 1.43914072e+04 1.40982324e+04 1.31783408e+04 1.30461406e+04 1.40484189e+04 1.40170449e+04 1.33731006e+04 1.33091367e+04 1.33790752e+04 1.34343955e+04 1.38813096e+04 1.36231621e+04 1.30988311e+04 1.34554697e+04 1.32310986e+04 1.34666426e+04 1.37633828e+04 1.31281865e+04 1.33672783e+04 1.37248936e+04 1.34177998e+04 1.33552412e+04 1.33813330e+04 1.34333184e+04 1.34378115e+04 1.32656465e+04 1.29611396e+04 1.29611680e+04 1.35577197e+04 1.39701494e+04 1.36156553e+04 1.29242275e+04 1.26041270e+04 1.29009805e+04 1.34577822e+04 1.37997500e+04 1.34777363e+04 1.27653125e+04 1.28072510e+04 1.31896299e+04 1.31276455e+04 1.29611641e+04 1.29415088e+04 1.29613076e+04 1.29880645e+04 1.33401230e+04 1.29755996e+04 1.26680293e+04 1.29160381e+04 1.25218789e+04 1.28347012e+04 1.32000498e+04 1.27219424e+04 1.30495215e+04 1.28678154e+04 1.23092666e+04 1.26952236e+04 1.23708428e+04 1.24951865e+04 1.33848691e+04 1.27519697e+04 1.19558359e+04 1.21774717e+04 1.27866328e+04 1.32414629e+04 1.28570479e+04 1.21998564e+04 1.19151543e+04 1.21200986e+04 1.24887812e+04 1.28768574e+04 1.26731914e+04 1.19861553e+04 1.18800146e+04 1.21677949e+04 1.23326475e+04 1.21194551e+04 1.19973330e+04 1.20809629e+04 1.20368555e+04 1.24473809e+04 1.23599805e+04 1.16214004e+04 1.15313691e+04 1.19099482e+04 1.19455215e+04 1.19267666e+04 1.18290518e+04 1.20496104e+04 1.17851250e+04 1.13609365e+04 1.16383623e+04 1.12895352e+04 1.15749600e+04 1.22898242e+04 1.15117188e+04 1.08776396e+04 1.11860449e+04 1.16814844e+04 1.19667217e+04 1.18201064e+04 1.11292080e+04 1.07021943e+04 1.09644609e+04 1.14294072e+04 1.17362451e+04 1.14362441e+04 1.07961094e+04 1.07139346e+04 1.10782734e+04 1.10857412e+04 1.11828984e+04 1.11854307e+04 1.06005332e+04 1.05277393e+04 1.10494795e+04 1.10579131e+04 1.05120332e+04 1.04480967e+04 1.06458711e+04 1.05008955e+04 1.08529863e+04 1.08904590e+04 1.03982881e+04 1.02826670e+04 1.02476523e+04 1.02180332e+04 1.03063955e+04 1.02356680e+04 1.04787061e+04 1.05691387e+04 1.01743906e+04 9.80954297e+03 9.56091504e+03 1.00003711e+04 1.04770332e+04 1.02461309e+04 9.71312500e+03 9.33972461e+03 9.71108496e+03 1.02170244e+04 9.82957617e+03 9.20958789e+03 9.38447461e+03 9.64282129e+03 9.79318457e+03 9.99530762e+03 9.75598633e+03 9.09582520e+03 9.02188281e+03 9.28886133e+03 9.33229199e+03 9.31126562e+03 9.22049805e+03 9.22184277e+03 9.07445410e+03 9.17373340e+03 9.07688574e+03 8.81308203e+03 8.77984375e+03 8.66817383e+03 8.92164746e+03 9.00299023e+03 8.72583105e+03 8.74852051e+03 8.73358398e+03 8.65019727e+03 8.42020605e+03 8.19856641e+03 8.47403027e+03 8.82452441e+03 8.58187500e+03 8.11320410e+03 8.01440674e+03 8.33147949e+03 8.45900488e+03 8.25375391e+03 8.10301074e+03 7.81045703e+03 7.78425977e+03 8.05738184e+03 8.01392871e+03 7.76018604e+03 7.55026172e+03 7.45900439e+03 7.82618408e+03 8.11584082e+03 7.61673145e+03 7.35925488e+03 7.50988916e+03 7.48943896e+03 7.66856055e+03 7.57591895e+03 7.08108936e+03 7.12119580e+03 7.29516846e+03 7.21753711e+03 7.20011621e+03 7.21792432e+03 6.93268652e+03 7.34915283e+03 7.36672998e+03 6.72258105e+03 8.42988281e+03 8.90919434e+03 1.08083213e+04 1.04154600e+04 9.89759668e+03 1.01430156e+04 9.93659082e+03 1.03759668e+04 1.08447305e+04 1.00691074e+04 1.77436680e+04 2.76071035e+04 -18437276. 4238268. 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. 0. -125313584. -125313584. -125313584. 0. 0. -20887132. -6.01617750e+06 -3.10240275e+06 -3.59801425e+06 17027194. -6720882. -4.12573050e+06 1.07475830e+04 8.66454785e+03 4.96776709e+03 4.52057178e+03 4.17579395e+03 4.00155103e+03 4.12792139e+03 4.10394580e+03 3.92459106e+03 3.89592554e+03 3.88439771e+03 3.81012842e+03 3.76260693e+03 3.71523218e+03 3.63428174e+03 3.63017432e+03 3.59508081e+03 3.56443604e+03 3.53730103e+03 3.37589941e+03 3.35783960e+03 3.46864575e+03 3.42269385e+03 3.32778955e+03 3.26993530e+03 3.22954395e+03 3.19980322e+03 3.14385864e+03 3.11094092e+03 3.06150830e+03 3.00664136e+03 2.94084546e+03 2.90524023e+03 2.94923584e+03 2.91433984e+03 2.82102686e+03 2.77795947e+03 2.76277466e+03 2.73743237e+03 2.67586719e+03 2.63426709e+03 2.60110742e+03 2.52846875e+03 2.48675928e+03 2.43825342e+03 2.40121240e+03 2.48858496e+03 2.46332129e+03 2.34187964e+03 2.24297827e+03 2.19340649e+03 2.28962842e+03 2.27531885e+03 2.16770020e+03 2.08200024e+03 2.04967139e+03 2.04530518e+03 2.00756470e+03 2.05415723e+03 2.01414160e+03 1.85930981e+03 1.79972705e+03 1.86137427e+03 1.92704822e+03 1.84716980e+03 1.76735156e+03 1.73070947e+03 1.68991858e+03 1.66863025e+03 1.64750525e+03 1.59761877e+03 1.55199377e+03 1.53228748e+03 1.50232263e+03 1.47450098e+03 1.44286951e+03 1.45725659e+03 1.42642480e+03 1.35675293e+03 1.32137695e+03 1.29727686e+03 1.30863757e+03 1.28494482e+03 1.22934802e+03 1.20415576e+03 1.14857068e+03 1.09852905e+03 1.12609460e+03 1.11330359e+03 1.03138574e+03 1.01400244e+03 1.04635999e+03 1.04909753e+03 9.95753357e+02 9.43637573e+02 9.16915833e+02 8.98530396e+02 8.67267761e+02 8.38321289e+02 8.23142517e+02 8.00359497e+02 8.03251099e+02 7.76322083e+02 7.35886719e+02 7.13495789e+02 6.74556213e+02 6.70081787e+02 6.87862305e+02 6.55844849e+02 6.19014465e+02 5.83623535e+02 5.56572144e+02 5.69640137e+02 5.62516724e+02 5.26274048e+02 4.91157990e+02 4.73036438e+02 4.66415741e+02 4.48885162e+02 4.46905670e+02 4.33889282e+02 4.01704010e+02 3.77323151e+02 3.62928650e+02 3.62349060e+02 3.48391205e+02 3.26565521e+02 3.09317627e+02 2.94188080e+02 2.80204041e+02 2.60573242e+02 2.54927750e+02 2.56294983e+02 2.38427261e+02 2.21188461e+02 2.04571838e+02 1.91681442e+02 1.91501694e+02 1.81188431e+02 1.65649719e+02 1.51801453e+02 1.41838638e+02 1.36577133e+02 1.26859451e+02 1.18210106e+02 1.07141800e+02 1.00636673e+02 9.74838486e+01 8.75563126e+01 7.92732925e+01 7.31623993e+01 6.63329849e+01 5.90900383e+01 5.32879524e+01 4.79597206e+01 4.28689766e+01 3.83792496e+01 3.31971321e+01 2.97438755e+01 2.71698341e+01 2.27264671e+01 1.91060181e+01 1.66015835e+01 1.41264210e+01 1.21713772e+01 1.02507801e+01 8.63536644e+00 7.57434034e+00 6.77214193e+00 6.28345585e+00 6.12057447e+00 6.28942776e+00 6.79877281e+00 7.66686344e+00 8.84409428e+00 1.02365866e+01 1.21961241e+01 1.48496380e+01 1.71943607e+01 1.96302910e+01 2.24260941e+01 2.61788120e+01 3.12882862e+01 3.52821274e+01 3.90686760e+01 4.29529037e+01 4.75772057e+01 5.46176910e+01 6.05901680e+01 6.77683563e+01 7.39954529e+01 7.89295578e+01 8.66682892e+01 9.39346313e+01 1.04980110e+02 1.13667473e+02 1.18644684e+02 1.26786819e+02 1.36396179e+02 1.45982666e+02 1.51194946e+02 1.64358673e+02 1.83851135e+02 1.91510513e+02 1.98203522e+02 2.04531631e+02 2.14893402e+02 2.39072159e+02 2.52240524e+02 2.58776550e+02 2.66020111e+02 2.77022949e+02 2.99567139e+02 3.12911865e+02 3.33779602e+02 3.46784912e+02 3.52362640e+02 3.64591980e+02 3.79079987e+02 4.12987000e+02 4.30246765e+02 4.35766876e+02 4.45410278e+02 4.59928040e+02 4.96274017e+02 5.15848145e+02 5.07988190e+02 5.27563477e+02 5.77015930e+02 5.92871033e+02 5.83319214e+02 5.99608459e+02 6.51456482e+02 6.78463623e+02 6.74119263e+02 6.76860107e+02 7.01588440e+02 7.64097595e+02 7.79981628e+02 7.80178833e+02 8.07575623e+02 8.26949646e+02 8.37138794e+02 8.57338623e+02 9.03783447e+02 9.03031250e+02 9.43461975e+02 1.01401031e+03 1.00963879e+03 1.03831494e+03 1.06554675e+03 1.07238672e+03 1.09947009e+03 1.12491968e+03 1.14731409e+03 1.14479541e+03 1.15970483e+03 1.21681482e+03 1.26509070e+03 1.33126001e+03 1.31443359e+03 1.30679077e+03 1.37728943e+03 1.40185034e+03 1.47033472e+03 1.49374585e+03 1.48274988e+03 1.48964148e+03 1.50838135e+03 1.57700916e+03 1.60922632e+03 1.67272778e+03 1.70872205e+03 1.69868567e+03 1.71590833e+03 1.70628223e+03 1.78510596e+03 1.90878918e+03 1.91807776e+03 1.89193567e+03 1.88177722e+03 1.90177148e+03 2.03324768e+03 2.10038965e+03 2.06914062e+03 2.04124268e+03 2.08123608e+03 2.17397827e+03 2.19709302e+03 2.28653979e+03 2.31096899e+03 2.29161353e+03 2.33278662e+03 2.35532031e+03 2.45776465e+03 2.50460864e+03 2.42221802e+03 2.45508716e+03 2.63691846e+03 2.62738525e+03 2.52142798e+03 2.64266089e+03 2.81724316e+03 2.82628125e+03 2.79607178e+03 2.75019580e+03 2.79443457e+03 2.99779883e+03 3.02393140e+03 2.98458154e+03 2.95293042e+03 2.96993604e+03 3.09309180e+03 3.14048853e+03 3.19755103e+03 3.14699121e+03 3.24821411e+03 3.44269434e+03 3.40773926e+03 3.43219434e+03 3.44242554e+03 3.44490576e+03 3.50554248e+03 3.55713037e+03 3.61698267e+03 3.64100610e+03 3.66723950e+03 3.62210522e+03 3.70966187e+03 3.95126123e+03 3.81108374e+03 3.74038428e+03 3.90374609e+03 4.03424341e+03 4.20171436e+03 4.17536475e+03 4.11275098e+03 4.19017920e+03 4.19439697e+03 4.16874609e+03 4.18827344e+03 4.42360596e+03 4.41762158e+03 4.36574316e+03 4.41293555e+03 4.33630713e+03 4.52538379e+03 4.83922168e+03 4.74627783e+03 4.67248584e+03 4.59802295e+03 4.63517139e+03 4.95177979e+03 5.09326416e+03 4.95591016e+03 4.86928516e+03 4.89255615e+03 5.01083447e+03 5.08350879e+03 5.30339307e+03 5.28672363e+03 5.19377588e+03 5.24571143e+03 5.29168701e+03 5.44286133e+03 5.47668799e+03 5.44055029e+03 5.55058740e+03 5.59392822e+03 5.54912305e+03 5.45236426e+03 5.62932373e+03 5.97736035e+03 5.91437646e+03 5.82202197e+03 5.75976025e+03 5.81941064e+03 6.23031592e+03 6.23150293e+03 6.07398633e+03 6.02878467e+03 6.05153906e+03 6.15467041e+03 6.21061719e+03 6.35234082e+03 6.21853369e+03 6.38706738e+03 6.67564990e+03 6.55138135e+03 6.65480566e+03 6.69552832e+03 6.65468896e+03 6.76219922e+03 6.78015479e+03 6.64966309e+03 6.70999609e+03 6.97721338e+03 7.01253906e+03 7.07306396e+03 7.08385156e+03 6.90144043e+03 6.90045508e+03 7.18600830e+03 7.26046338e+03 7.49881738e+03 7.45074121e+03 7.19903125e+03 7.45239453e+03 7.59184375e+03 7.53993262e+03 7.47434180e+03 7.50135742e+03 7.66731494e+03 7.68341846e+03 7.75336914e+03 7.61463916e+03 7.83435156e+03 8.26375879e+03 8.16001270e+03 7.98564600e+03 7.80504199e+03 7.84473730e+03 8.37472656e+03 8.39279004e+03 8.23588965e+03 8.05496729e+03 7.97409082e+03 8.30713574e+03 8.52866992e+03 8.82779688e+03 8.56201855e+03 8.27797852e+03 8.47017188e+03 8.65170312e+03 8.97676465e+03 8.81987305e+03 8.58416113e+03 8.85550000e+03 8.91903320e+03 8.87993652e+03 8.72619922e+03 8.92359570e+03 9.45875781e+03 9.39867578e+03 9.11977148e+03 8.89265234e+03 9.02066992e+03 9.60203516e+03 9.61230371e+03 9.39212891e+03 9.20655957e+03 9.18078613e+03 9.51941895e+03 9.56386133e+03 9.87273438e+03 9.89894238e+03 9.56727832e+03 9.42105664e+03 9.61736621e+03 1.01849082e+04 1.00024219e+04 9.76726855e+03 1.00622432e+04 1.00739219e+04 9.85629004e+03 9.75306738e+03 1.01278281e+04 1.01422549e+04 9.98858398e+03 1.04921348e+04 1.05991982e+04 1.03964209e+04 1.03618516e+04 1.03696826e+04 1.04401777e+04 1.02295332e+04 1.01456963e+04 1.07034209e+04 1.09313945e+04 1.04412021e+04 1.02037695e+04 1.07195732e+04 1.11766299e+04 1.10867832e+04 1.07677539e+04 1.05751787e+04 1.09621162e+04 1.12768008e+04 1.11154854e+04 1.10418232e+04 1.07634688e+04 1.05836201e+04 1.11356699e+04 1.16918613e+04 1.14985127e+04 1.09985225e+04 1.09180205e+04 1.15670693e+04 1.17885898e+04 1.14247998e+04 1.11827246e+04 1.11246533e+04 1.12840049e+04 1.14560010e+04 1.18790391e+04 1.19534795e+04 1.15311758e+04 1.15125293e+04 1.16216152e+04 1.19674590e+04 1.17222139e+04 1.14746719e+04 1.20692998e+04 1.21549033e+04 1.17780537e+04 1.15201592e+04 1.17908994e+04 1.24679766e+04 1.20529639e+04 1.16383057e+04 1.19777998e+04 1.22160400e+04 1.22955908e+04 1.21764004e+04 1.25207969e+04 1.26367715e+04 1.22578340e+04 1.19221377e+04 1.19942744e+04 1.26918281e+04 1.25485303e+04 1.22161660e+04 1.24156523e+04 1.24927510e+04 1.24926230e+04 1.24150986e+04 1.26325479e+04 1.25977090e+04 1.23741230e+04 1.27110244e+04 1.27622383e+04 1.29035771e+04 1.29267119e+04 1.27242832e+04 1.26610107e+04 1.23496807e+04 1.24577734e+04 1.31888623e+04 1.34036357e+04 1.27158643e+04 1.23496650e+04 1.28325244e+04 1.33750908e+04 1.33065391e+04 1.28431533e+04 1.24690977e+04 1.30555215e+04 1.34327949e+04 1.30733916e+04 1.33494531e+04 1.32444326e+04 1.27421064e+04 1.30444326e+04 1.35509404e+04 1.34294639e+04 1.28569668e+04 1.27125459e+04 1.34563066e+04 1.37828936e+04 1.33491348e+04 1.28538115e+04 1.28269346e+04 1.36191787e+04 1.35801787e+04 1.31716768e+04 1.34116738e+04 1.34108359e+04 1.32742119e+04 1.32222812e+04 1.37357920e+04 1.35016279e+04 1.30195703e+04 1.37025879e+04 1.37936689e+04 1.36240723e+04 1.33536553e+04 1.31316182e+04 1.38129980e+04 1.35839229e+04 1.30347969e+04 1.35254229e+04 1.42714482e+04 1.41630479e+04 1.30005195e+04 1.42022061e+04 15389. 1.38537949e+04 1.36247158e+04 1.25690381e+04 1.37746826e+04 1.91836152e+04 1.60004414e+04 1.48796475e+04 1.86776504e+04 2.68694258e+04 1.11585188e+05 2.60690125e+09 0. 0. 0. 0. 0. 0. -1.98056489e+10 -1.98056489e+10 3.39065391e+04 1.35750828e+05 1.35750828e+05 -1.87401339e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.83709338e+09 1.32642562e+05 3.16411777e+04 1.77232520e+04 1.79108652e+04 1.64696230e+04 1.40075342e+04 1.37732383e+04 1.37351436e+04 1.36916602e+04 1.34391846e+04 1.34829424e+04 1.37232031e+04 1.36185166e+04 1.35456445e+04 1.34165498e+04 1.33752490e+04 1.36988037e+04 1.36175127e+04 1.33670742e+04 1.33750850e+04 1.32762451e+04 1.33788369e+04 1.37752773e+04 1.38243232e+04 1.33547793e+04 1.31753057e+04 1.33646152e+04 1.34198887e+04 1.32813574e+04 1.32112021e+04 1.33535947e+04 1.33127998e+04 1.34433467e+04 1.33887305e+04 1.29098662e+04 1.30573193e+04 1.34732744e+04 1.35866309e+04 1.34683496e+04 1.29116963e+04 1.27730049e+04 1.32411016e+04 1.32766533e+04 1.30401748e+04 1.29502725e+04 1.29479561e+04 1.31781133e+04 1.33420127e+04 1.30996602e+04 1.26426055e+04 1.26581318e+04 1.33172871e+04 1.32769766e+04 1.26360059e+04 1.25844658e+04 1.28771172e+04 1.29744893e+04 1.30964541e+04 1.28256143e+04 1.24518369e+04 1.25433740e+04 1.27819902e+04 1.28613096e+04 1.27399355e+04 1.24032627e+04 1.25648799e+04 1.28159590e+04 1.26578652e+04 1.24914756e+04 1.23132744e+04 1.23743770e+04 1.25938350e+04 1.25941826e+04 1.25803359e+04 1.23387295e+04 1.20405088e+04 1.22940098e+04 1.23855498e+04 1.22647500e+04 1.22595889e+04 1.20944365e+04 1.21542852e+04 1.24032822e+04 1.22796172e+04 1.18226279e+04 1.18054434e+04 1.21172812e+04 1.21900352e+04 1.20428926e+04 1.17827773e+04 1.18332617e+04 1.18764688e+04 1.19366445e+04 1.18518604e+04 1.15272598e+04 1.16913154e+04 1.19065166e+04 1.18362666e+04 1.17416572e+04 1.14359102e+04 1.13804551e+04 1.16832344e+04 1.15842725e+04 1.12697607e+04 1.12224160e+04 1.13078193e+04 1.14894346e+04 1.14529219e+04 1.12967363e+04 1.12465430e+04 1.11988691e+04 1.13308760e+04 1.12624141e+04 1.09792959e+04 1.10204551e+04 1.10535605e+04 1.08803242e+04 1.09618604e+04 1.09900312e+04 1.08664170e+04 1.08219639e+04 1.07433125e+04 1.07015137e+04 1.08066904e+04 1.07772490e+04 1.06683887e+04 1.05930186e+04 1.04154316e+04 1.04190479e+04 1.05892119e+04 1.04291758e+04 1.02703613e+04 1.03852256e+04 1.05882910e+04 1.04421211e+04 1.01442324e+04 1.01706992e+04 1.02326094e+04 1.00258545e+04 9.90654199e+03 9.90240234e+03 9.86322266e+03 1.00030498e+04 1.00944805e+04 9.93907910e+03 9.75627539e+03 9.60858887e+03 9.69437207e+03 9.79582129e+03 9.70906934e+03 9.59360352e+03 9.45038867e+03 9.50823438e+03 9.60948438e+03 9.49901758e+03 9.26514062e+03 9.06980371e+03 9.21058496e+03 9.41337891e+03 9.28916016e+03 8.85375488e+03 8.89750586e+03 9.15218848e+03 9.07060547e+03 8.89202441e+03 8.87633789e+03 8.86224707e+03 8.76406250e+03 8.84120801e+03 8.72921777e+03 8.52691992e+03 8.66481641e+03 8.72429785e+03 8.54329395e+03 8.55903516e+03 8.45574219e+03 8.26388086e+03 8.26142578e+03 8.28876660e+03 8.33651953e+03 8.39307715e+03 8.02931494e+03 7.96128369e+03 8.22641602e+03 8.02693457e+03 7.79155273e+03 7.86175391e+03 7.90774854e+03 7.91392725e+03 7.84662061e+03 7.73270264e+03 7.60917139e+03 7.53570020e+03 7.67173438e+03 7.67637256e+03 7.40876514e+03 7.41963721e+03 7.58331689e+03 7.41685498e+03 7.36119727e+03 7.20561377e+03 7.07146387e+03 7.23324414e+03 7.12258887e+03 7.03318408e+03 7.08038086e+03 6.89652734e+03 6.91143115e+03 7.06984326e+03 6.81388916e+03 6.73554102e+03 6.75084814e+03 6.71982568e+03 6.63721729e+03 6.60903662e+03 6.53060449e+03 6.47536768e+03 6.41266309e+03 6.43731299e+03 6.37077344e+03 6.23868848e+03 6.27557178e+03 6.33566895e+03 6.17394287e+03 6.25184033e+03 6.13384424e+03 5.86862500e+03 5.96889795e+03 5.97908105e+03 5.89779150e+03 5.76490381e+03 5.63526123e+03 5.78256201e+03 5.87121338e+03 5.65513672e+03 5.52344092e+03 5.61237939e+03 5.63576270e+03 5.44327686e+03 5.29884521e+03 5.42773486e+03 5.35776855e+03 5.22633838e+03 5.33414893e+03 5.18724219e+03 5.09261182e+03 5.10511035e+03 5.01983984e+03 4.98225098e+03 4.99045752e+03 4.86898438e+03 4.82789795e+03 4.84419141e+03 4.84910449e+03 4.80223584e+03 4.60510840e+03 4.55578711e+03 4.64332031e+03 4.54405420e+03 4.53237207e+03 4.46920068e+03 4.38883252e+03 4.35816846e+03 4.33270117e+03 4.35766650e+03 4.24018750e+03 4.05757520e+03 4.13486768e+03 4.25436768e+03 4.04354932e+03 3.90652295e+03 3.93496216e+03 3.88388135e+03 3.90216748e+03 3.90856470e+03 3.76542139e+03 3.73320386e+03 3.72155054e+03 3.67340747e+03 3.66795776e+03 3.59818994e+03 3.58592700e+03 3.56533716e+03 3.37904590e+03 3.39600830e+03 3.39741699e+03 3.29176611e+03 3.34622437e+03 3.26530127e+03 3.17750073e+03 3.18523120e+03 3.10873853e+03 3.09604565e+03 3.14457031e+03 3.04386621e+03 2.96121240e+03 2.90812671e+03 2.84239844e+03 2.86902808e+03 2.86907764e+03 2.77952490e+03 2.72239062e+03 2.74091138e+03 2.70409253e+03 2.64501978e+03 2.56653003e+03 2.53842505e+03 2.53291455e+03 2.50131177e+03 2.46856299e+03 2.37877393e+03 2.34212988e+03 2.34913452e+03 2.33874658e+03 2.28858545e+03 2.24203979e+03 2.18326440e+03 2.12392334e+03 2.18540112e+03 2.16904468e+03 2.04126111e+03 1.97533215e+03 1.96347571e+03 1.95283032e+03 1.92694641e+03 1.87803101e+03 1.85558191e+03 1.84501123e+03 1.80506042e+03 1.77697754e+03 1.73364648e+03 1.68977979e+03 1.67806360e+03 1.65804688e+03 1.60907239e+03 1.54750818e+03 1.53535498e+03 1.51175281e+03 1.48242749e+03 1.47351355e+03 1.42760425e+03 1.38094592e+03 1.36500024e+03 1.36584497e+03 1.32262146e+03 1.27215381e+03 1.24914160e+03 1.22688953e+03 1.19777246e+03 1.17276453e+03 1.13565967e+03 1.11104041e+03 1.09802405e+03 1.08184692e+03 1.06210583e+03 1.01592090e+03 9.92573303e+02 9.71886353e+02 9.36994873e+02 9.12475586e+02 8.85121887e+02 8.79522461e+02 8.56010193e+02 8.20852966e+02 7.92218445e+02 7.72035767e+02 7.66468994e+02 7.51972656e+02 7.32933655e+02 6.97936462e+02 6.71464478e+02 6.51434875e+02 6.20782227e+02 6.07270203e+02 5.98222046e+02 5.76912170e+02 5.54586975e+02 5.27957642e+02 5.12347839e+02 5.04905243e+02 4.94824677e+02 4.75094208e+02 4.47680389e+02 4.25370239e+02 4.13465698e+02 3.99763000e+02 3.79866058e+02 3.69800873e+02 3.60147156e+02 3.36132782e+02 3.17520020e+02 3.03897949e+02 2.92464783e+02 2.88673340e+02 2.74365845e+02 2.53078308e+02 2.42876434e+02 2.29442749e+02 2.13848038e+02 2.08422409e+02 1.97649460e+02 1.81917801e+02 1.70842636e+02 1.60338562e+02 1.49151306e+02 1.43465332e+02 1.38755920e+02 1.26422256e+02 1.15447289e+02 1.07430367e+02 9.86064682e+01 9.13207016e+01 8.41496811e+01 7.73127518e+01 6.99238052e+01 6.27364616e+01 5.74488335e+01 5.23215866e+01 4.62807961e+01 4.17678070e+01 3.73352089e+01 3.18584843e+01 2.72971859e+01 2.38288994e+01 2.07948036e+01 1.77908115e+01 1.49138794e+01 1.21653204e+01 9.92807293e+00 8.31411266e+00 6.99646759e+00 5.84394360e+00 4.93569088e+00 4.42042542e+00 4.27479839e+00 4.48739481e+00 4.99868059e+00 5.76166725e+00 6.85983801e+00 8.38957119e+00 1.04954805e+01 1.27207975e+01 1.48792896e+01 1.79673042e+01 2.17895336e+01 2.49873714e+01 2.83230419e+01 3.25968246e+01 3.72858315e+01 4.24094810e+01 4.75016632e+01 5.27992821e+01 5.77449417e+01 6.40399094e+01 7.14479904e+01 7.82559967e+01 8.68162460e+01 9.30351639e+01 9.97630463e+01 1.08329796e+02 1.17749397e+02 1.27217789e+02 1.34587875e+02 1.45420242e+02 1.56588364e+02 1.64710419e+02 1.72030685e+02 1.82389709e+02 1.95443344e+02 2.12301178e+02 2.24447479e+02 2.30065811e+02 2.41199646e+02 2.53977615e+02 2.70964813e+02 2.88773163e+02 2.96950104e+02 3.05792267e+02 3.29686493e+02 3.43193787e+02 3.47739166e+02 3.75461609e+02 3.93620239e+02 3.97428009e+02 4.17774872e+02 4.27397675e+02 4.42506989e+02 4.78219025e+02 4.91881805e+02 4.99326385e+02 5.26301453e+02 5.43692322e+02 5.44929260e+02 5.67293335e+02 5.98943604e+02 6.18249939e+02 6.43052551e+02 6.52232483e+02 6.67526123e+02 7.00879822e+02 7.25161377e+02 7.65143005e+02 7.70821411e+02 7.60040161e+02 7.94053223e+02 8.30997925e+02 8.55501709e+02 8.85931946e+02 8.95872986e+02 9.00472229e+02 9.48267395e+02 9.87169312e+02 9.92342529e+02 1.01840649e+03 1.04878760e+03 1.05293286e+03 1.09969128e+03 1.13542700e+03 1.13369421e+03 1.19491577e+03 1.23146753e+03 1.22876538e+03 1.25243262e+03 1.24523303e+03 1.27741736e+03 1.35188074e+03 1.42124133e+03 1.42576611e+03 1.37942017e+03 1.42623010e+03 1.50315894e+03 1.52338147e+03 1.54207800e+03 1.57103882e+03 1.59540466e+03 1.64904651e+03 1.67908142e+03 1.70738684e+03 1.73153589e+03 1.76320569e+03 1.82880530e+03 1.82752185e+03 1.82779724e+03 1.86818542e+03 1.91588623e+03 1.97236621e+03 2.04217468e+03 2.03543262e+03 2.01196411e+03 2.07668481e+03 2.13987183e+03 2.22201172e+03 2.23772437e+03 2.19306641e+03 2.24125244e+03 2.30578271e+03 2.37026831e+03 2.44162939e+03 2.43184644e+03 2.41582397e+03 2.47616162e+03 2.49376270e+03 2.50183936e+03 2.61965723e+03 2.70481299e+03 2.69618188e+03 2.68498779e+03 2.70018652e+03 2.74428442e+03 2.88231567e+03 2.93014966e+03 2.92580908e+03 2.92572241e+03 2.90339526e+03 2.97728857e+03 3.06949390e+03 3.17510254e+03 3.20041064e+03 3.13036548e+03 3.18176953e+03 3.23580884e+03 3.30280396e+03 3.36893286e+03 3.41505200e+03 3.47618115e+03 3.44011768e+03 3.48377490e+03 3.55627637e+03 3.58289331e+03 3.63939502e+03 3.70982812e+03 3.74087476e+03 3.76135083e+03 3.76543604e+03 3.84733813e+03 3.96498315e+03 3.98104980e+03 3.93025122e+03 3.98489673e+03 4.04147974e+03 4.08064990e+03 4.24946338e+03 4.26920117e+03 4.20997705e+03 4.31584082e+03 4.30147168e+03 4.35668848e+03 4.52844971e+03 4.55483301e+03 4.54830908e+03 4.59751807e+03 4.43650684e+03 4.58262500e+03 4.77128076e+03 4.65455615e+03 6.69827881e+03 6.34759180e+03 1.40136055e+04 2.10181348e+04 10173138. -142376032. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 21767450. 2.97087250e+06 3.35743775e+06 -3.32081650e+06 2.93622832e+04 2.05096016e+04 1.16688418e+04 8.16036914e+03 7.34745557e+03 7.44306543e+03 7.70016309e+03 7.62545312e+03 7.50495801e+03 7.31360742e+03 7.46672070e+03 7.71533301e+03 7.80481055e+03 7.80782861e+03 7.70017871e+03 7.75086719e+03 7.82152246e+03 8.00208301e+03 8.03236572e+03 7.82026123e+03 7.93415576e+03 8.16609961e+03 8.20018555e+03 8.07319873e+03 7.98072900e+03 8.28559473e+03 8.68824219e+03 8.69316992e+03 8.29455371e+03 7.98389404e+03 8.26773535e+03 8.68538281e+03 8.93412988e+03 8.78693555e+03 8.51079590e+03 8.57696484e+03 8.86760156e+03 9.10030273e+03 8.99984473e+03 8.61015723e+03 8.68889453e+03 9.22292090e+03 9.22466895e+03 8.95082715e+03 9.08889941e+03 9.22203027e+03 9.35290820e+03 9.44531738e+03 9.11199707e+03 8.99745410e+03 9.55873828e+03 9.84208008e+03 9.65317676e+03 9.37442871e+03 9.16951953e+03 9.71187500e+03 1.00641289e+04 9.90796582e+03 9.63349414e+03 9.36032227e+03 9.51075000e+03 1.00721104e+04 1.02870273e+04 1.01765361e+04 1.00100645e+04 1.00576514e+04 1.00229385e+04 1.01019590e+04 1.02208496e+04 9.99438672e+03 1.01538926e+04 1.05920840e+04 1.04793184e+04 1.00711543e+04 1.00074395e+04 1.05802881e+04 1.09560742e+04 1.08299443e+04 1.04861777e+04 1.02837969e+04 1.03700049e+04 1.06673896e+04 1.12187842e+04 1.10878945e+04 1.05119160e+04 1.06417910e+04 1.08466719e+04 1.10691445e+04 1.12772314e+04 1.08901816e+04 1.08963135e+04 1.12759434e+04 1.12115146e+04 1.11131650e+04 1.10642393e+04 1.11526514e+04 1.14469795e+04 1.14605576e+04 1.11264961e+04 1.11168604e+04 1.15095654e+04 1.17499199e+04 1.16960068e+04 1.15210059e+04 1.12733789e+04 1.14746387e+04 1.18695107e+04 1.19355547e+04 1.17283535e+04 1.12713301e+04 1.13919033e+04 1.20361689e+04 1.22765283e+04 1.20378623e+04 1.15982422e+04 1.17246514e+04 1.21399795e+04 1.21336396e+04 1.18902939e+04 1.17611426e+04 1.21914482e+04 1.24143115e+04 1.21253652e+04 1.20104424e+04 1.18954121e+04 1.22448311e+04 1.28601582e+04 1.25564678e+04 1.21844434e+04 1.20859775e+04 1.21959160e+04 1.24890859e+04 1.27500762e+04 1.26084268e+04 1.20806338e+04 1.21924512e+04 1.28399932e+04 1.29879844e+04 1.26458926e+04 1.23751504e+04 1.25929561e+04 1.29174180e+04 1.29176689e+04 1.26879404e+04 1.23435547e+04 1.25108018e+04 1.29994531e+04 1.30883418e+04 1.28576357e+04 1.25852627e+04 1.27268379e+04 1.30472422e+04 1.33277598e+04 1.32678125e+04 1.26522920e+04 1.27368633e+04 1.31330059e+04 1.31892559e+04 1.31470996e+04 1.30097080e+04 1.30264580e+04 1.30659717e+04 1.31363809e+04 1.30926250e+04 1.29662305e+04 1.33152461e+04 1.36534473e+04 1.34198955e+04 1.29640869e+04 1.28562998e+04 1.33314141e+04 1.37760029e+04 1.37570977e+04 1.33345713e+04 1.29252432e+04 1.28701797e+04 1.33635537e+04 1.39700498e+04 1.36353516e+04 1.29318730e+04 1.31651660e+04 1.35800312e+04 1.36791602e+04 1.37214092e+04 1.34176934e+04 1.34239834e+04 1.35771514e+04 1.34274824e+04 1.33020547e+04 1.34474561e+04 1.36685078e+04 1.36209102e+04 1.35654980e+04 1.35109424e+04 1.33910322e+04 1.36370420e+04 1.39283994e+04 1.38905244e+04 1.33863564e+04 1.31193105e+04 1.37103564e+04 1.40229385e+04 1.38056475e+04 1.36073076e+04 1.32183750e+04 1.32658096e+04 1.39323379e+04 1.42765479e+04 1.39732490e+04 1.33699443e+04 1.32876045e+04 1.37560537e+04 1.39004854e+04 1.37777129e+04 1.37854512e+04 1.38756182e+04 1.37409961e+04 1.34992480e+04 1.32328672e+04 1.32202119e+04 1.35317676e+04 1.37537783e+04 1.41616455e+04 1.40224893e+04 1.32870957e+04 1.34626992e+04 1.36993789e+04 1.36636777e+04 1.38620186e+04 1.36867676e+04 1.39714033e+04 1.39119033e+04 1.32606367e+04 1.30655605e+04 1.33448838e+04 1.39885449e+04 1.44131787e+04 1.40751689e+04 1.32847148e+04 1.29154336e+04 1.31769629e+04 1.39629521e+04 1.44100645e+04 1.40338076e+04 1.31659395e+04 1.30622402e+04 1.40921660e+04 1.39765664e+04 1.32930684e+04 1.33243711e+04 1.34249619e+04 1.34589033e+04 1.38941689e+04 1.35777910e+04 1.30714102e+04 1.34364629e+04 1.31767461e+04 1.34513789e+04 1.38020791e+04 1.30668691e+04 1.33835586e+04 1.38176699e+04 1.34330283e+04 1.33576152e+04 1.32862217e+04 1.34318037e+04 1.34830723e+04 1.32048838e+04 1.29729893e+04 1.30058252e+04 1.35778955e+04 1.39236113e+04 1.35431934e+04 1.29428477e+04 1.26676592e+04 1.28884258e+04 1.34529355e+04 1.38159893e+04 1.34540244e+04 1.27615107e+04 1.28102500e+04 1.32419941e+04 1.31201543e+04 1.29485625e+04 1.29807314e+04 1.28502275e+04 1.29112676e+04 1.34155498e+04 1.30264648e+04 1.26313164e+04 1.28335879e+04 1.24803203e+04 1.28769727e+04 1.32282598e+04 1.27066377e+04 1.30426992e+04 1.28627480e+04 1.22996035e+04 1.27052217e+04 1.23636924e+04 1.25111914e+04 1.33926289e+04 1.27228662e+04 1.19963721e+04 1.22305918e+04 1.27416533e+04 1.31688818e+04 1.28692256e+04 1.20663867e+04 1.17582812e+04 1.21766182e+04 1.25951152e+04 1.29588682e+04 1.27188486e+04 1.19161855e+04 1.18444600e+04 1.22638613e+04 1.25029180e+04 1.20407803e+04 1.17954883e+04 1.20819883e+04 1.20731885e+04 1.23771592e+04 1.23256191e+04 1.17384922e+04 1.16861865e+04 1.18026807e+04 1.18317471e+04 1.19603555e+04 1.17960400e+04 1.20393320e+04 1.18330273e+04 1.13916016e+04 1.15554297e+04 1.12742549e+04 1.15962754e+04 1.22661240e+04 1.15744932e+04 1.08525859e+04 1.10971787e+04 1.16045957e+04 1.18747822e+04 1.19090137e+04 1.12314443e+04 1.07348018e+04 1.09432578e+04 1.13478125e+04 1.18111826e+04 1.14978125e+04 1.07502363e+04 1.06541123e+04 1.10105146e+04 1.11318008e+04 1.12813174e+04 1.12045723e+04 1.05824326e+04 1.05402793e+04 1.09748262e+04 1.09911924e+04 1.06778896e+04 1.05749170e+04 1.05269111e+04 1.03916787e+04 1.08412812e+04 1.08795547e+04 1.02745488e+04 1.01946455e+04 1.02834766e+04 1.03382256e+04 1.03254531e+04 1.02066670e+04 1.04300098e+04 1.05284062e+04 1.01057881e+04 9.85299414e+03 9.61575098e+03 9.94367285e+03 1.04884424e+04 1.02568818e+04 9.63467773e+03 9.39578320e+03 9.71350098e+03 1.01937568e+04 9.83244824e+03 9.26482812e+03 9.36997559e+03 9.60591992e+03 9.74579004e+03 1.00025322e+04 9.77342676e+03 9.16117676e+03 8.93577637e+03 9.19646289e+03 9.50145312e+03 9.40379590e+03 9.23229590e+03 9.14823047e+03 9.03754492e+03 9.18105664e+03 9.05897559e+03 8.79333398e+03 8.68608105e+03 8.67949316e+03 8.95810156e+03 9.02575000e+03 8.72146777e+03 8.72147754e+03 8.70541211e+03 8.80849805e+03 8.53099609e+03 8.05189111e+03 8.40176953e+03 8.83839746e+03 8.54026172e+03 8.04685449e+03 8.10195361e+03 8.42931641e+03 8.38880762e+03 8.20221094e+03 8.07705615e+03 7.81474121e+03 7.78042725e+03 8.16709961e+03 8.13128223e+03 7.71766113e+03 7.46213574e+03 7.47193408e+03 7.78572363e+03 8.06733594e+03 7.64943018e+03 7.39588428e+03 7.49994092e+03 7.46309814e+03 7.65864600e+03 7.59860498e+03 7.10529590e+03 7.09221973e+03 7.24368994e+03 7.20155469e+03 7.17627637e+03 7.02490967e+03 7.17064355e+03 7.29384863e+03 7.21590039e+03 7.25382324e+03 8.72564844e+03 8.95304688e+03 1.08083213e+04 1.04154600e+04 9.89759668e+03 1.01430156e+04 9.93659082e+03 1.03759668e+04 1.08447305e+04 1.00691074e+04 1.77436680e+04 2.76071035e+04 -18437276. 4238268. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -22629050. 3.92844950e+06 10170959. 1.30766504e+04 9.04053809e+03 5.02996875e+03 4.53485791e+03 4.21905225e+03 4.01954810e+03 4.10814844e+03 4.05441724e+03 3.92851489e+03 3.90581763e+03 3.87844751e+03 3.80682007e+03 3.77725757e+03 3.72367285e+03 3.64759033e+03 3.60215283e+03 3.54731396e+03 3.58726855e+03 3.58062720e+03 3.38023413e+03 3.33431494e+03 3.47781543e+03 3.43656421e+03 3.32160938e+03 3.26842944e+03 3.22661353e+03 3.19760376e+03 3.12642334e+03 3.09915674e+03 3.07124634e+03 2.99456250e+03 2.94943604e+03 2.90913306e+03 2.93454810e+03 2.90916870e+03 2.82140869e+03 2.77994775e+03 2.75369800e+03 2.72061206e+03 2.66902271e+03 2.62223560e+03 2.59093408e+03 2.49581885e+03 2.44711523e+03 2.45583423e+03 2.41692310e+03 2.49464722e+03 2.46616357e+03 2.33022974e+03 2.23195288e+03 2.18751147e+03 2.29000781e+03 2.28233740e+03 2.16744409e+03 2.08586841e+03 2.05682056e+03 2.05200830e+03 2.00695618e+03 2.04376941e+03 2.00042126e+03 1.85272546e+03 1.81076355e+03 1.87492480e+03 1.91453601e+03 1.83134937e+03 1.76175818e+03 1.73326025e+03 1.69251160e+03 1.64243115e+03 1.62273682e+03 1.59635083e+03 1.55072388e+03 1.52904834e+03 1.50228589e+03 1.48608215e+03 1.45030627e+03 1.45082983e+03 1.42434009e+03 1.35361072e+03 1.33943799e+03 1.31505762e+03 1.29194568e+03 1.27264478e+03 1.22954822e+03 1.20036902e+03 1.14880298e+03 1.09710791e+03 1.12640442e+03 1.11009753e+03 1.03479773e+03 1.01502911e+03 1.04660522e+03 1.05094373e+03 9.95240234e+02 9.44679626e+02 9.12785645e+02 8.88101929e+02 8.60798035e+02 8.35119629e+02 8.30297974e+02 8.05637207e+02 8.00066040e+02 7.71686218e+02 7.31466675e+02 7.20471069e+02 6.79463867e+02 6.61249268e+02 6.77451599e+02 6.52170166e+02 6.15703430e+02 5.82685852e+02 5.56170410e+02 5.66488403e+02 5.58964050e+02 5.24334900e+02 4.88888519e+02 4.71173859e+02 4.64887115e+02 4.47658203e+02 4.44907837e+02 4.31295593e+02 4.00658386e+02 3.76013062e+02 3.61491272e+02 3.62333862e+02 3.47711029e+02 3.24679413e+02 3.05171997e+02 2.90813934e+02 2.82560730e+02 2.62377502e+02 2.50622940e+02 2.51648254e+02 2.37539810e+02 2.19926208e+02 2.01328354e+02 1.88962860e+02 1.90299957e+02 1.79383041e+02 1.63831558e+02 1.50076584e+02 1.39520218e+02 1.34394409e+02 1.24988243e+02 1.16399551e+02 1.05658096e+02 9.90284195e+01 9.57046280e+01 8.63601685e+01 7.80399704e+01 7.14946518e+01 6.46738129e+01 5.76282806e+01 5.17162361e+01 4.67355461e+01 4.16290436e+01 3.67588844e+01 3.15671043e+01 2.79403801e+01 2.53541279e+01 2.09628525e+01 1.73266869e+01 1.48056011e+01 1.23170128e+01 1.03824053e+01 8.43445778e+00 6.83263016e+00 5.79007721e+00 4.94827414e+00 4.43475580e+00 4.27246714e+00 4.46140718e+00 4.99075365e+00 5.84645891e+00 7.01024294e+00 8.38014126e+00 1.02795420e+01 1.29334764e+01 1.53253574e+01 1.77600651e+01 2.03592930e+01 2.40574169e+01 2.93524704e+01 3.34570122e+01 3.71642761e+01 4.10744705e+01 4.57001381e+01 5.25346260e+01 5.85058517e+01 6.60829697e+01 7.13199463e+01 7.57327805e+01 8.48458862e+01 9.24634857e+01 1.02710358e+02 1.10619072e+02 1.16062286e+02 1.25174866e+02 1.34420425e+02 1.45424194e+02 1.51101074e+02 1.63024033e+02 1.82479706e+02 1.89114487e+02 1.95629532e+02 2.02742355e+02 2.13091446e+02 2.37152374e+02 2.50863235e+02 2.56497925e+02 2.62824341e+02 2.75069275e+02 2.97342834e+02 3.11979004e+02 3.34230927e+02 3.43754272e+02 3.49670959e+02 3.62894043e+02 3.76283447e+02 4.11815796e+02 4.26156586e+02 4.31082062e+02 4.47183563e+02 4.61869263e+02 4.93962280e+02 5.13524414e+02 5.09117859e+02 5.26936951e+02 5.71177002e+02 5.91687988e+02 5.83669128e+02 5.97995056e+02 6.51423828e+02 6.75526306e+02 6.73533081e+02 6.77220032e+02 6.99485107e+02 7.63813477e+02 7.77958740e+02 7.78646240e+02 8.03332825e+02 8.20871033e+02 8.49362122e+02 8.68587402e+02 8.90166626e+02 8.90328674e+02 9.41137451e+02 1.02026093e+03 1.01297046e+03 1.02273517e+03 1.05459180e+03 1.07168335e+03 1.10053296e+03 1.12394446e+03 1.14673657e+03 1.14269824e+03 1.15339697e+03 1.20951855e+03 1.26458606e+03 1.33391272e+03 1.31693518e+03 1.29821326e+03 1.36661072e+03 1.40771008e+03 1.47345215e+03 1.48561072e+03 1.47241528e+03 1.48788660e+03 1.51066394e+03 1.57735962e+03 1.61026770e+03 1.67294751e+03 1.70071838e+03 1.69840881e+03 1.70294507e+03 1.68459741e+03 1.78681592e+03 1.92782996e+03 1.91961743e+03 1.89018359e+03 1.87446570e+03 1.88286365e+03 2.01865015e+03 2.11770459e+03 2.08440820e+03 2.03378369e+03 2.06875269e+03 2.16517773e+03 2.19907007e+03 2.29303271e+03 2.31175073e+03 2.28159302e+03 2.33286304e+03 2.36055640e+03 2.44991382e+03 2.48726855e+03 2.41944678e+03 2.45969653e+03 2.63641138e+03 2.62508374e+03 2.51963135e+03 2.64544922e+03 2.82693335e+03 2.81775464e+03 2.77925830e+03 2.74447583e+03 2.79763916e+03 2.99659351e+03 3.02868896e+03 2.98157837e+03 2.94154590e+03 2.96737695e+03 3.11169629e+03 3.13981787e+03 3.17546973e+03 3.14322217e+03 3.25042212e+03 3.42785742e+03 3.37352075e+03 3.44643530e+03 3.46502686e+03 3.42882251e+03 3.49627441e+03 3.56306470e+03 3.61175171e+03 3.62328540e+03 3.63051074e+03 3.61075830e+03 3.75301855e+03 3.99489868e+03 3.84902612e+03 3.72402515e+03 3.89670801e+03 4.01487036e+03 4.16928223e+03 4.13197852e+03 4.07658545e+03 4.20624023e+03 4.24040430e+03 4.10877930e+03 4.13023877e+03 4.45349463e+03 4.49382324e+03 4.37456250e+03 4.37513379e+03 4.28079443e+03 4.52666602e+03 4.87205664e+03 4.76764014e+03 4.68936719e+03 4.60307715e+03 4.59439648e+03 4.88044482e+03 5.11761426e+03 5.02364648e+03 4.83038525e+03 4.84544434e+03 5.02420850e+03 5.11307373e+03 5.31873047e+03 5.27115234e+03 5.13045410e+03 5.29042725e+03 5.34892578e+03 5.46363818e+03 5.49086035e+03 5.41884668e+03 5.52006787e+03 5.56504395e+03 5.59563525e+03 5.48815137e+03 5.60454980e+03 6.01009668e+03 5.96163867e+03 5.78262598e+03 5.68800879e+03 5.81113232e+03 6.18121924e+03 6.24029004e+03 6.11029736e+03 5.98400928e+03 5.99230811e+03 6.20742090e+03 6.28658447e+03 6.36786328e+03 6.23979785e+03 6.39992432e+03 6.69768066e+03 6.55600586e+03 6.68472900e+03 6.72344092e+03 6.59926416e+03 6.67874219e+03 6.68690381e+03 6.73709277e+03 6.81457764e+03 6.86251172e+03 6.88710352e+03 7.11593555e+03 7.16210352e+03 6.92729736e+03 6.87434521e+03 7.11699121e+03 7.33135059e+03 7.59918604e+03 7.42389648e+03 7.11457568e+03 7.52323877e+03 7.70570166e+03 7.56273242e+03 7.42001562e+03 7.43604004e+03 7.65061426e+03 7.69354150e+03 7.74842676e+03 7.52945947e+03 7.83898096e+03 8.23784082e+03 8.09432715e+03 8.04337500e+03 7.92603467e+03 7.87213184e+03 8.33051660e+03 8.44848242e+03 8.21054199e+03 8.06036963e+03 7.95291748e+03 8.23190332e+03 8.58272070e+03 8.87944922e+03 8.51575293e+03 8.20928516e+03 8.53444824e+03 8.69068457e+03 8.98955273e+03 8.85654688e+03 8.55338965e+03 8.85911621e+03 8.95528711e+03 8.78334668e+03 8.65846973e+03 8.96247656e+03 9.46256250e+03 9.29211523e+03 9.19055859e+03 8.96315723e+03 9.00012402e+03 9.57734961e+03 9.58824414e+03 9.34182715e+03 9.16429980e+03 9.15038574e+03 9.46807422e+03 9.51250488e+03 9.81001562e+03 9.90593848e+03 9.60826074e+03 9.49152930e+03 9.67861328e+03 1.00952021e+04 9.94988477e+03 9.76709375e+03 9.93441992e+03 9.99908496e+03 9.85894824e+03 9.77489453e+03 1.02289697e+04 1.02269326e+04 1.00316260e+04 1.04653213e+04 1.05408555e+04 1.03859814e+04 1.03704326e+04 1.04118154e+04 1.04342031e+04 1.02123740e+04 1.01689307e+04 1.06768281e+04 1.09399834e+04 1.04133555e+04 1.00906826e+04 1.06390850e+04 1.12888115e+04 1.11760449e+04 1.06589902e+04 1.05020625e+04 1.10685654e+04 1.12766592e+04 1.09891270e+04 1.11202363e+04 1.08594316e+04 1.05815986e+04 1.10197891e+04 1.15532129e+04 1.16221641e+04 1.10913916e+04 1.08010459e+04 1.14821436e+04 1.18886182e+04 1.15159033e+04 1.11170898e+04 1.10082891e+04 1.13799922e+04 1.15220762e+04 1.18305957e+04 1.18564434e+04 1.14541426e+04 1.16012188e+04 1.17582832e+04 1.19516201e+04 1.16963506e+04 1.14734795e+04 1.19844775e+04 1.20210371e+04 1.18965264e+04 1.16259336e+04 1.18130947e+04 1.24911621e+04 1.20638682e+04 1.16418760e+04 1.19186250e+04 1.21818408e+04 1.22923330e+04 1.22018447e+04 1.24742246e+04 1.26074219e+04 1.22740566e+04 1.19441660e+04 1.20198506e+04 1.26384570e+04 1.23902227e+04 1.21121934e+04 1.25344854e+04 1.26247451e+04 1.24304229e+04 1.23041172e+04 1.27322012e+04 1.27094033e+04 1.23536416e+04 1.26918984e+04 1.27465068e+04 1.29057305e+04 1.29233740e+04 1.27319980e+04 1.26625781e+04 1.23528291e+04 1.23049395e+04 1.30208857e+04 1.35133369e+04 1.28190537e+04 1.22129209e+04 1.27283721e+04 1.35304922e+04 1.35022285e+04 1.28205645e+04 1.24087725e+04 1.30420801e+04 1.34197363e+04 1.30697910e+04 1.33071436e+04 1.32310342e+04 1.27762842e+04 1.29412764e+04 1.34320986e+04 1.34976670e+04 1.29780400e+04 1.26952031e+04 1.32997441e+04 1.38397324e+04 1.34822656e+04 1.29080645e+04 1.27973076e+04 1.34547637e+04 1.37921211e+04 1.33978057e+04 1.31272617e+04 1.31772979e+04 1.33926592e+04 1.33597461e+04 1.37555693e+04 1.34987471e+04 1.30343037e+04 1.35461816e+04 1.36522227e+04 1.36797803e+04 1.34169033e+04 1.31966963e+04 1.37138154e+04 1.34123252e+04 1.32463154e+04 1.41594785e+04 1.40348447e+04 1.34643008e+04 1.74725703e+04 1.88776367e+04 2.12443750e+04 2.14900723e+04 2.11567285e+04 1.91657422e+04 1.93476191e+04 1.77897344e+04 1.49010938e+04 1.48796475e+04 1.86776504e+04 2.68694258e+04 1.11585188e+05 2.60690125e+09 0. 0. 0. 0. 0. 0. -1.98056489e+10 -1.98056489e+10 3.39065391e+04 1.35750828e+05 1.35750828e+05 -1.87401339e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 8.03682662e+09 2.06699203e+05 5.72183750e+04 4.58152383e+04 3.33570195e+04 2.07753320e+04 1.37819717e+04 1.83024355e+04 1.48116914e+04 1.37375742e+04 1.34146895e+04 1.34980879e+04 1.39323857e+04 1.40267305e+04 1.35029570e+04 1.32837881e+04 1.35963506e+04 1.36391250e+04 1.34913896e+04 1.35230312e+04 1.34695654e+04 1.33745273e+04 1.36179023e+04 1.36189375e+04 1.31632939e+04 1.32274785e+04 1.36552930e+04 1.37018428e+04 1.36129531e+04 1.32962285e+04 1.30507617e+04 1.33549775e+04 1.34944385e+04 1.33327539e+04 1.31869258e+04 1.31424980e+04 1.34065625e+04 1.34148311e+04 1.32394541e+04 1.31170391e+04 1.30772490e+04 1.35558252e+04 1.36042002e+04 1.28850625e+04 1.27904551e+04 1.31313564e+04 1.31485752e+04 1.32808311e+04 1.32009287e+04 1.28806494e+04 1.30724883e+04 1.31429814e+04 1.30233926e+04 1.30296562e+04 1.28530371e+04 1.29296719e+04 1.30295938e+04 1.28540205e+04 1.27864795e+04 1.27120039e+04 1.27502744e+04 1.29811006e+04 1.29837734e+04 1.28301777e+04 1.25961504e+04 1.24899805e+04 1.28084277e+04 1.28214971e+04 1.24223672e+04 1.25285566e+04 1.25769219e+04 1.25887363e+04 1.28506133e+04 1.26825791e+04 1.22484902e+04 1.22525977e+04 1.26258232e+04 1.27192812e+04 1.22415869e+04 1.19971387e+04 1.22399902e+04 1.23227979e+04 1.25302725e+04 1.24440127e+04 1.19935586e+04 1.20869746e+04 1.23485664e+04 1.22431699e+04 1.20736084e+04 1.18359238e+04 1.17810703e+04 1.21653857e+04 1.21744648e+04 1.18177314e+04 1.18664980e+04 1.19055576e+04 1.18166396e+04 1.17584561e+04 1.17332510e+04 1.18447295e+04 1.17223604e+04 1.18270342e+04 1.18132588e+04 1.13629746e+04 1.13739688e+04 1.16033457e+04 1.15020049e+04 1.13679512e+04 1.13544277e+04 1.13756787e+04 1.14970146e+04 1.13806768e+04 1.12119717e+04 1.13488740e+04 1.13907598e+04 1.11169111e+04 1.10439287e+04 1.10687725e+04 1.10992871e+04 1.10478096e+04 1.08376855e+04 1.08076943e+04 1.09135332e+04 1.11181318e+04 1.09966191e+04 1.05436699e+04 1.06550752e+04 1.08760098e+04 1.07405566e+04 1.06597705e+04 1.04587422e+04 1.03398564e+04 1.05287051e+04 1.07295059e+04 1.05454922e+04 1.02152500e+04 1.02004980e+04 1.04680791e+04 1.04266943e+04 1.04142285e+04 1.01723643e+04 9.90640820e+03 9.99981738e+03 9.99396094e+03 9.95859277e+03 9.96218164e+03 9.83583496e+03 9.89412305e+03 1.01293135e+04 9.89018359e+03 9.49144434e+03 9.55564453e+03 9.73646973e+03 9.67200977e+03 9.75836523e+03 9.60401758e+03 9.30407617e+03 9.39948340e+03 9.62046289e+03 9.45615527e+03 8.98951660e+03 9.11117188e+03 9.34810156e+03 9.25666895e+03 9.12124512e+03 8.95134180e+03 8.86286719e+03 8.97793750e+03 8.94095703e+03 8.92669531e+03 8.94080664e+03 8.67159766e+03 8.77726270e+03 8.89768555e+03 8.69351855e+03 8.46112305e+03 8.50415234e+03 8.59601074e+03 8.60128320e+03 8.48553125e+03 8.26923047e+03 8.12791602e+03 8.24927344e+03 8.54767969e+03 8.50693262e+03 7.95944678e+03 7.92898633e+03 8.19976953e+03 8.09723730e+03 7.98782666e+03 7.85459766e+03 7.69285645e+03 7.85180811e+03 7.95632861e+03 7.79775293e+03 7.58614600e+03 7.51467188e+03 7.55082373e+03 7.66057324e+03 7.68036182e+03 7481. 7.34470605e+03 7.37121289e+03 7.33288525e+03 7.26414258e+03 7.18439795e+03 7.15466455e+03 7.03122900e+03 7.17423242e+03 7.23774268e+03 6.80405371e+03 6.79235547e+03 6.98892236e+03 6.88341553e+03 6.84867236e+03 6.62918066e+03 6.61781104e+03 6.80945361e+03 6.66904639e+03 6.54309863e+03 6.38624658e+03 6.28612988e+03 6.40679736e+03 6.50450342e+03 6.33508984e+03 6.23669727e+03 6.30854443e+03 6.18594043e+03 6.24368408e+03 6.15959912e+03 5.92192969e+03 5.87171240e+03 5.84298877e+03 5.98511816e+03 5.89530273e+03 5.72504150e+03 5.71612061e+03 5.76406787e+03 5.71557520e+03 5.60897217e+03 5.54696533e+03 5.50626123e+03 5.49810889e+03 5.41254053e+03 5.46923047e+03 5.34005762e+03 5.18745947e+03 5.30605176e+03 5.12432275e+03 5.10954199e+03 5.17447949e+03 5.00772803e+03 4.97307812e+03 4.96427393e+03 4.90328955e+03 4.83441846e+03 4.72132520e+03 4.86063965e+03 4.91666699e+03 4.60665527e+03 4.55921680e+03 4.58066309e+03 4.54164697e+03 4.58645459e+03 4.50037354e+03 4.35028271e+03 4.32446924e+03 4.37285498e+03 4.33781055e+03 4.25504980e+03 4.13383105e+03 4.12300439e+03 4.11437256e+03 4.03268701e+03 3.99570972e+03 3.92538379e+03 3.87894556e+03 3.88775513e+03 3.89821289e+03 3.84433301e+03 3.72996655e+03 3.65705884e+03 3.70829858e+03 3.73262695e+03 3.57681860e+03 3.57038794e+03 3.52065186e+03 3.36904370e+03 3.43630249e+03 3.40055444e+03 3.29373535e+03 3.30452319e+03 3.27212354e+03 3.20540479e+03 3.23320068e+03 3.13510254e+03 3.06791943e+03 3.05114771e+03 3.03753784e+03 3.00934106e+03 2.90437109e+03 2.84982397e+03 2.86222339e+03 2.85609253e+03 2.81159521e+03 2.74054102e+03 2.66705469e+03 2.69722192e+03 2.72604785e+03 2.61030444e+03 2.51989697e+03 2.48566479e+03 2.50964746e+03 2.50057104e+03 2.40153589e+03 2.34740283e+03 2.33341235e+03 2.31065308e+03 2.26553101e+03 2.25462012e+03 2.20615186e+03 2.11080859e+03 2.13393921e+03 2.15729395e+03 2.06498071e+03 1.95908813e+03 1.94965332e+03 1.96057617e+03 1.94867761e+03 1.90698706e+03 1.84640588e+03 1.80523914e+03 1.81510388e+03 1.81540137e+03 1.73214221e+03 1.67739417e+03 1.66083240e+03 1.67414380e+03 1.62891626e+03 1.54082568e+03 1.51063916e+03 1.50450879e+03 1.48107532e+03 1.46612109e+03 1.44285022e+03 1.39100317e+03 1.36751880e+03 1.34008032e+03 1.28729028e+03 1.26313501e+03 1.23562244e+03 1.23160315e+03 1.21934070e+03 1.16778552e+03 1.12172900e+03 1.10696252e+03 1.10890698e+03 1.11033240e+03 1.06608740e+03 9.96367004e+02 9.81246948e+02 9.73758301e+02 9.40323853e+02 9.09382690e+02 8.91475464e+02 8.72189392e+02 8.50319885e+02 8.21049744e+02 7.84224670e+02 7.76214539e+02 7.70510132e+02 7.52224426e+02 7.21289185e+02 6.80989746e+02 6.66777283e+02 6.47250732e+02 6.21365051e+02 6.22378967e+02 6.02372070e+02 5.64589294e+02 5.46965759e+02 5.31718445e+02 5.29522705e+02 5.13079895e+02 4.83061859e+02 4.63946472e+02 4.46973511e+02 4.28270416e+02 4.08448517e+02 3.99008453e+02 3.83928253e+02 3.71002411e+02 3.56337769e+02 3.28042389e+02 3.17299896e+02 3.06731781e+02 2.93305298e+02 2.87885315e+02 2.65809692e+02 2.46580200e+02 2.43946243e+02 2.35151993e+02 2.18704483e+02 2.05063187e+02 1.90521759e+02 1.78835876e+02 1.69998215e+02 1.61935944e+02 1.51371429e+02 1.43332596e+02 1.35756241e+02 1.23842957e+02 1.13400688e+02 1.04661835e+02 9.81493683e+01 9.20308075e+01 8.30859222e+01 7.42903671e+01 6.77593536e+01 6.22295609e+01 5.72720032e+01 5.24479790e+01 4.55087433e+01 3.93031693e+01 3.50498390e+01 3.02857304e+01 2.61886711e+01 2.32019711e+01 1.96450748e+01 1.60889511e+01 1.32760305e+01 1.07194700e+01 8.67714787e+00 7.04803658e+00 5.51218271e+00 4.24181128e+00 3.39032245e+00 2.91945076e+00 2.77447534e+00 2.95258880e+00 3.49003053e+00 4.36600542e+00 5.58641911e+00 7.05889797e+00 8.99157715e+00 1.12207241e+01 1.36186724e+01 1.65267105e+01 1.96191959e+01 2.29917736e+01 2.70232601e+01 3.11852989e+01 3.61788940e+01 4.11036911e+01 4.54254494e+01 5.07456169e+01 5.63434181e+01 6.27530136e+01 6.91587601e+01 7.67500381e+01 8.49503326e+01 9.13469925e+01 9.87795486e+01 1.06230278e+02 1.15890160e+02 1.27393524e+02 1.35274490e+02 1.42467056e+02 1.51660522e+02 1.61982544e+02 1.71981888e+02 1.84952118e+02 1.97563416e+02 2.07439133e+02 2.18527359e+02 2.29192398e+02 2.41480133e+02 2.56868988e+02 2.68416138e+02 2.83800873e+02 2.97408203e+02 3.06646057e+02 3.28375549e+02 3.36331299e+02 3.46161743e+02 3.74644867e+02 3.87211334e+02 3.96997437e+02 4.17739899e+02 4.30087494e+02 4.43268066e+02 4.79878601e+02 4.97915833e+02 4.90807587e+02 5.14445740e+02 5.40506836e+02 5.51655579e+02 5.82112732e+02 5.98106506e+02 6.02054688e+02 6.30507141e+02 6.51040161e+02 6.82718811e+02 7.11857117e+02 7.19292786e+02 7.46942993e+02 7.55917358e+02 7.57911377e+02 7.96949646e+02 8.42994263e+02 8.55381592e+02 8.80383423e+02 9.00482605e+02 8.93102661e+02 9.33463013e+02 1.00318793e+03 1.01624640e+03 1.01227448e+03 1.02151215e+03 1.04604871e+03 1.10916992e+03 1.14348401e+03 1.14202087e+03 1.18269788e+03 1.19812683e+03 1.22934717e+03 1.26701318e+03 1.24904297e+03 1.29026233e+03 1.36131262e+03 1.39865063e+03 1.39935913e+03 1.39281824e+03 1.42412927e+03 1.48726807e+03 1.54560413e+03 1.56598157e+03 1.55291003e+03 1.56270178e+03 1.63414539e+03 1.69104932e+03 1.74617114e+03 1.75089099e+03 1.73125879e+03 1.79461536e+03 1.81622070e+03 1.83738416e+03 1.90241956e+03 1.92360632e+03 1.95567761e+03 2.03220703e+03 2.02628247e+03 2.03901892e+03 2.09856909e+03 2.13658887e+03 2.19114502e+03 2.18910986e+03 2.19287305e+03 2.23890747e+03 2.31652271e+03 2.39140918e+03 2.42926904e+03 2.42387842e+03 2.40396411e+03 2.45857275e+03 2.50077783e+03 2.56122705e+03 2.62957935e+03 2.62479785e+03 2.64697705e+03 2.68858838e+03 2.72858252e+03 2.80872607e+03 2.91833936e+03 2.90999634e+03 2.87871509e+03 2.91258398e+03 2.89785278e+03 2.97541553e+03 3.10105591e+03 3.16675513e+03 3.17710059e+03 3.13952051e+03 3.16636060e+03 3.23495850e+03 3.32961328e+03 3.37004810e+03 3.41632422e+03 3.42450854e+03 3.39462964e+03 3.50965869e+03 3.64297949e+03 3.65245923e+03 3.56668823e+03 3.65248169e+03 3.72045117e+03 3.78490674e+03 3.83836084e+03 3.85433398e+03 3.93714673e+03 3.91872778e+03 3.91440161e+03 4.07106567e+03 4.09249121e+03 4.11607617e+03 4.21085889e+03 4.14785107e+03 4.15028906e+03 4.31758984e+03 4.35109424e+03 4.42261572e+03 4.61370654e+03 4.61830273e+03 4.51316602e+03 4.45936035e+03 4.58245801e+03 4.87452002e+03 6.03896240e+03 5.89247412e+03 1.18555635e+04 1.22075537e+04 -3.60436775e+06 -185715120. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9226059. -4320898. 2.70772930e+04 1.49163018e+04 7.51893750e+03 9.55595312e+03 1.11296553e+04 9.82045898e+03 8.12826514e+03 7.79757617e+03 7.25332812e+03 7.29251074e+03 7.59931494e+03 7.51546631e+03 7.47159375e+03 7.36923486e+03 7.38626562e+03 7.75471240e+03 7.97743750e+03 7.73801318e+03 7.56409814e+03 7.67992871e+03 7.85212305e+03 8.03701660e+03 8.18165283e+03 7.94024756e+03 7.85906592e+03 8.02522266e+03 8.12096924e+03 8.16229004e+03 8.08815771e+03 8.10253809e+03 8.46479199e+03 8.67938672e+03 8.53615137e+03 8.17607080e+03 8.20711914e+03 8.61624316e+03 8.74775684e+03 8.62809570e+03 8.43263770e+03 8.56163086e+03 8.99869531e+03 9.19425098e+03 9.00179297e+03 8.56391406e+03 8.75025293e+03 9.22853613e+03 9.20622070e+03 9.23322070e+03 9.08992090e+03 8.87819531e+03 9.10397559e+03 9.48365918e+03 9.32174316e+03 9.18228027e+03 9.55843555e+03 9.64233398e+03 9.56251953e+03 9.51162598e+03 9.20933496e+03 9.52370312e+03 1.00719785e+04 9.87419336e+03 9.58902344e+03 9.53519238e+03 9.55340039e+03 1.00455020e+04 1.04034297e+04 1.00966836e+04 9.85407324e+03 9.84000781e+03 9.87235742e+03 1.01789121e+04 1.05204561e+04 1.02195078e+04 1.00220850e+04 1.03669961e+04 1.03777432e+04 1.02072803e+04 1.02515195e+04 1.04979072e+04 1.07439590e+04 1.07041885e+04 1.06935098e+04 1.04560420e+04 1.02427344e+04 1.08513359e+04 1.12811074e+04 1.07134541e+04 1.03921113e+04 1.06410225e+04 1.09973887e+04 1.12009941e+04 1.13343398e+04 1.09649756e+04 1.08142939e+04 1.11379277e+04 1.11816152e+04 1.12986592e+04 1.12323779e+04 1.09674307e+04 1.10971465e+04 1.14389619e+04 1.14725469e+04 1.14482100e+04 1.15436094e+04 1.15512227e+04 1.14965752e+04 1.15737070e+04 1.13387295e+04 1.12879102e+04 1.19467539e+04 1.20921963e+04 1.14872988e+04 1.12622275e+04 1.15195674e+04 1.21221240e+04 1.23582070e+04 1.19786299e+04 1.16156260e+04 1.16271074e+04 1.18435312e+04 1.20643730e+04 1.21287910e+04 1.20733604e+04 1.20851309e+04 1.20788398e+04 1.21298809e+04 1.22088301e+04 1.19670674e+04 1.21794307e+04 1.27062021e+04 1.24442129e+04 1.22042793e+04 1.21912344e+04 1.20470068e+04 1.25902881e+04 1.28981074e+04 1.23554316e+04 1.21061816e+04 1.23227373e+04 1.29009268e+04 1.31317725e+04 1.27042021e+04 1.23540273e+04 1.23594414e+04 1.25384561e+04 1.28830195e+04 1.30206758e+04 1.25814775e+04 1.23136289e+04 1.27615566e+04 1.31978467e+04 1.30697021e+04 1.27616279e+04 1.28336602e+04 1.29402422e+04 1.29857637e+04 1.31382129e+04 1.26975010e+04 1.26857959e+04 1.32325615e+04 1.32192402e+04 1.30455928e+04 1.28899775e+04 1.29285771e+04 1.31038789e+04 1.32606865e+04 1.33784404e+04 1.30389971e+04 1.30922119e+04 1.34541387e+04 1.33178584e+04 1.31250068e+04 1.30863174e+04 1.31156660e+04 1.34211162e+04 1.38028467e+04 1.35425322e+04 1.29573027e+04 1.29311992e+04 1.35222041e+04 1.38752363e+04 1.36461035e+04 1.30266143e+04 1.30349951e+04 1.34232441e+04 1.36430410e+04 1.37133730e+04 1.33310742e+04 1.31962061e+04 1.33885000e+04 1.36306230e+04 1.38098369e+04 1.35969590e+04 1.34358477e+04 1.34980361e+04 1.35389521e+04 1.36374551e+04 1.36197627e+04 1.36144521e+04 1.35331104e+04 1.34496953e+04 1.33379248e+04 1.32839629e+04 1.37563701e+04 1.42764717e+04 1.40658350e+04 1.34548984e+04 1.30675596e+04 1.32648818e+04 1.40530107e+04 1.44042012e+04 1.39497051e+04 1.33785508e+04 1.31105957e+04 1.35208633e+04 14014. 1.39711729e+04 1.38518838e+04 1.37672041e+04 1.35815586e+04 1.35129199e+04 1.32850029e+04 1.33244434e+04 1.36672178e+04 1.36854189e+04 1.41101777e+04 1.40274736e+04 1.30893105e+04 1.32546533e+04 1.38284941e+04 1.38599678e+04 1.38063789e+04 1.36493164e+04 1.39910527e+04 1.40116914e+04 1.34142520e+04 1.30184023e+04 1.32576885e+04 1.39230498e+04 1.43442412e+04 1.40916084e+04 1.33808770e+04 1.30168613e+04 1.31505088e+04 1.38251592e+04 1.43336113e+04 1.40479971e+04 1.32351133e+04 1.31045459e+04 1.40445049e+04 1.38790303e+04 1.32860684e+04 1.33924121e+04 1.34327598e+04 1.34319385e+04 1.38971182e+04 1.36191084e+04 1.30892676e+04 1.34158213e+04 1.31793916e+04 1.34359795e+04 1.37770625e+04 1.31410342e+04 1.34007607e+04 1.37439131e+04 1.34226621e+04 1.33985049e+04 1.32999561e+04 1.34868633e+04 1.34621943e+04 1.31178984e+04 1.28944590e+04 1.29926416e+04 1.36609941e+04 1.39540420e+04 1.35321240e+04 1.29500928e+04 1.26494082e+04 1.28710049e+04 1.34127334e+04 1.38101270e+04 1.34392637e+04 1.26817568e+04 1.28097676e+04 1.32890635e+04 1.30754902e+04 1.30061113e+04 1.30315713e+04 1.27974570e+04 1.29029873e+04 1.34513838e+04 1.29774111e+04 1.26157236e+04 1.28673564e+04 1.24516807e+04 1.28627812e+04 1.32958740e+04 1.26904844e+04 1.30110566e+04 1.28523174e+04 1.23024922e+04 1.26719395e+04 1.23321123e+04 1.25967588e+04 1.34249053e+04 1.26445195e+04 1.19909346e+04 1.22037920e+04 1.27413926e+04 1.31533174e+04 1.29303838e+04 1.21743340e+04 1.18205332e+04 1.20727441e+04 1.24530352e+04 1.29593184e+04 1.26934873e+04 1.19705977e+04 1.19457705e+04 1.22388955e+04 1.24207275e+04 1.20408672e+04 1.18883291e+04 1.20152988e+04 1.19912021e+04 1.23821719e+04 1.24009736e+04 1.17381406e+04 1.15664131e+04 1.18014336e+04 1.18274492e+04 1.19095186e+04 1.17854268e+04 1.20836846e+04 1.18144375e+04 1.13124316e+04 1.16284756e+04 1.13081182e+04 1.15343193e+04 1.22716689e+04 1.16005518e+04 1.08495596e+04 1.10890576e+04 1.16656064e+04 1.19026875e+04 1.17932734e+04 1.11606328e+04 1.07711611e+04 1.09607070e+04 1.13210645e+04 1.17917598e+04 1.14574795e+04 1.07310088e+04 1.06542998e+04 1.10168574e+04 1.10857197e+04 1.13085850e+04 1.13079375e+04 1.05703916e+04 1.05005840e+04 1.08867295e+04 1.09539521e+04 1.06876201e+04 1.06046152e+04 1.05805986e+04 1.03690254e+04 1.08694141e+04 1.08206689e+04 1.02776084e+04 1.02313389e+04 1.02932334e+04 1.02801006e+04 1.02653301e+04 1.02137354e+04 1.04531426e+04 1.04951777e+04 1.01489092e+04 9.88171973e+03 9.62287793e+03 1.00033154e+04 1.04540332e+04 1.02034521e+04 9.63196484e+03 9.40583105e+03 9.67567676e+03 1.01389805e+04 9.83162695e+03 9.22700098e+03 9.41071094e+03 9.69460840e+03 9.68882324e+03 1.00029795e+04 9.76462598e+03 9.14628906e+03 8.93466211e+03 9.16658301e+03 9.44642480e+03 9.43337598e+03 9.20586523e+03 9.12541992e+03 9.06596777e+03 9.19299609e+03 9.05110449e+03 8.80231055e+03 8.79541895e+03 8.61953809e+03 8.92273242e+03 9.12106348e+03 8.72310938e+03 8.72689062e+03 8.73280371e+03 8.67310352e+03 8.40374805e+03 8.21190234e+03 8.49106836e+03 8.80259668e+03 8.50188379e+03 8.06203174e+03 8.07973633e+03 8.40721777e+03 8.46695312e+03 8.27187402e+03 8.15097852e+03 7.81247363e+03 7.75280371e+03 8.04950098e+03 8.02926904e+03 7.81599268e+03 7.59921777e+03 7.45434277e+03 7.77901074e+03 8.03006934e+03 7.62139600e+03 7.37922559e+03 7.53159912e+03 7.40355273e+03 7.63715869e+03 7.60082422e+03 7.17316504e+03 7.01849023e+03 7.17878174e+03 7.16552295e+03 7.18462842e+03 7.06595947e+03 7.20125586e+03 7.29118359e+03 7.16658691e+03 7.37483057e+03 7.86724023e+03 7.21801514e+03 1.07470635e+04 1.01065879e+04 1.53531016e+04 2.14002246e+04 -5847065. -2.86437025e+06 -2.87168275e+06 5.92517150e+06 -9805365. 38827180. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 38177792. -3.17001075e+06 1.94457090e+04 1.20618711e+04 7.72733496e+03 6.31074756e+03 5.67006934e+03 4.56459766e+03 4.42218213e+03 4.19598242e+03 4.01544751e+03 4.07751196e+03 4.03391211e+03 3.92919995e+03 3.91820898e+03 3.85732861e+03 3.80377808e+03 3.76165381e+03 3.72164575e+03 3.65823853e+03 3.58539771e+03 3.53333057e+03 3.59909351e+03 3.58138403e+03 3.36596387e+03 3.32341138e+03 3.47291309e+03 3.44795801e+03 3.31389819e+03 3.25856177e+03 3.23255786e+03 3.18188599e+03 3.10905493e+03 3.10775952e+03 3.06407910e+03 2.99718848e+03 2.91089600e+03 2.87367041e+03 2.95911279e+03 2.93833936e+03 2.80652319e+03 2.77444116e+03 2.74918286e+03 2.71694165e+03 2.65526147e+03 2.61092969e+03 2.59634814e+03 2.53008130e+03 2.47279419e+03 2.44842773e+03 2.40378882e+03 2.47880396e+03 2.45470557e+03 2.33016089e+03 2.23370215e+03 2.19012402e+03 2.29077417e+03 2.27053369e+03 2.15595825e+03 2.08733765e+03 2.06248022e+03 2.05719531e+03 2.00121228e+03 2.03478833e+03 1.99935205e+03 1.85754712e+03 1.80887415e+03 1.86645264e+03 1.90926917e+03 1.83039734e+03 1.75579016e+03 1.72551331e+03 1.68802490e+03 1.65543408e+03 1.62411499e+03 1.61014062e+03 1.57753650e+03 1.52273462e+03 1.49373230e+03 1.47156592e+03 1.43675769e+03 1.45720508e+03 1.42302905e+03 1.35590308e+03 1.32445715e+03 1.29899219e+03 1.30521924e+03 1.28530615e+03 1.22446240e+03 1.19596777e+03 1.14952136e+03 1.10521204e+03 1.13299915e+03 1.10128748e+03 1.02173358e+03 1.01334180e+03 1.04329565e+03 1.05029956e+03 9.94624451e+02 9.43597290e+02 9.07604553e+02 8.82565063e+02 8.65820740e+02 8.44009583e+02 8.23165161e+02 7.97138245e+02 7.95265686e+02 7.71424194e+02 7.31016418e+02 7.12693726e+02 6.69951294e+02 6.64870483e+02 6.85843811e+02 6.50482361e+02 6.12468079e+02 5.78952209e+02 5.57745117e+02 5.69639648e+02 5.52606262e+02 5.18599243e+02 4.88532715e+02 4.68739624e+02 4.61445831e+02 4.46476440e+02 4.43476593e+02 4.29172638e+02 3.99168243e+02 3.78474609e+02 3.64232544e+02 3.56610107e+02 3.42743988e+02 3.23834045e+02 3.04168396e+02 2.91128113e+02 2.80214783e+02 2.58141113e+02 2.51177078e+02 2.52996902e+02 2.36196640e+02 2.18350967e+02 2.00055801e+02 1.87940231e+02 1.88839676e+02 1.77863708e+02 1.61837784e+02 1.48457214e+02 1.38467850e+02 1.33364807e+02 1.23366287e+02 1.14661774e+02 1.04231445e+02 9.76779099e+01 9.45808487e+01 8.51241302e+01 7.67679596e+01 7.03880081e+01 6.33555450e+01 5.61626396e+01 5.04971771e+01 4.52799416e+01 3.98496017e+01 3.53735962e+01 3.01207199e+01 2.62961216e+01 2.38560524e+01 1.94856071e+01 1.57900791e+01 1.33064394e+01 1.08378019e+01 8.89478493e+00 6.99567080e+00 5.39694977e+00 4.30089855e+00 3.45217252e+00 2.93623757e+00 2.77433872e+00 2.94658351e+00 3.43899441e+00 4.24772930e+00 5.41544342e+00 6.84413195e+00 8.81279564e+00 1.14146910e+01 1.38152323e+01 1.62081757e+01 1.87548943e+01 2.24189701e+01 2.76913128e+01 3.18543797e+01 3.54821205e+01 3.95086174e+01 4.42032318e+01 5.08308372e+01 5.69397659e+01 6.43813629e+01 7.02352600e+01 7.49387589e+01 8.23997040e+01 8.98070374e+01 1.01073105e+02 1.08874893e+02 1.13839233e+02 1.22916298e+02 1.32120972e+02 1.41484482e+02 1.47419785e+02 1.62144821e+02 1.82971710e+02 1.88665009e+02 1.94053375e+02 2.00829239e+02 2.10646606e+02 2.35631668e+02 2.50270416e+02 2.55220749e+02 2.61526581e+02 2.73896973e+02 2.95621277e+02 3.09832794e+02 3.32012421e+02 3.46700531e+02 3.53283569e+02 3.58501373e+02 3.72167419e+02 4.10899719e+02 4.25517273e+02 4.30120972e+02 4.40511200e+02 4.54065155e+02 4.97961792e+02 5.18423828e+02 5.05180664e+02 5.22568054e+02 5.71010132e+02 5.90278870e+02 5.79678650e+02 5.98464722e+02 6.49308594e+02 6.73631470e+02 6.72599060e+02 6.76626587e+02 6.99571960e+02 7.58927490e+02 7.70679993e+02 7.68870605e+02 8.03387939e+02 8.23584229e+02 8.45365051e+02 8.69792786e+02 8.93222534e+02 8.90659485e+02 9.36751282e+02 1.00820142e+03 1.00384607e+03 1.03418640e+03 1.06423486e+03 1.06976477e+03 1.09651147e+03 1.12121985e+03 1.14294189e+03 1.14432483e+03 1.16925879e+03 1.22215540e+03 1.24993848e+03 1.32131531e+03 1.31369153e+03 1.29348059e+03 1.36083459e+03 1.40168567e+03 1.47609216e+03 1.48459509e+03 1.46780481e+03 1.48366504e+03 1.51145361e+03 1.57195361e+03 1.60097095e+03 1.67326270e+03 1.69684302e+03 1.68875208e+03 1.71467688e+03 1.69356958e+03 1.77543359e+03 1.91286511e+03 1.92452405e+03 1.89363293e+03 1.87219482e+03 1.87969727e+03 2.00871655e+03 2.11187817e+03 2.08967163e+03 2.03456848e+03 2.07220801e+03 2.16359668e+03 2.19552441e+03 2.28132959e+03 2.30975879e+03 2.27733691e+03 2.31286206e+03 2.34860815e+03 2.46542041e+03 2.51322656e+03 2.41626343e+03 2.44639258e+03 2.62711719e+03 2.64481250e+03 2.54163232e+03 2.62287891e+03 2.79167993e+03 2.82069409e+03 2.80128174e+03 2.75529395e+03 2.77940210e+03 2.97753394e+03 3.02799121e+03 2.98553320e+03 2.94547656e+03 2.95512158e+03 3.08625073e+03 3.15338330e+03 3.19007202e+03 3.13457056e+03 3.24091602e+03 3.42848560e+03 3.38623071e+03 3.44258911e+03 3.45252222e+03 3.42840332e+03 3.49420557e+03 3.54686987e+03 3.61704541e+03 3.63601172e+03 3.60744263e+03 3.57754907e+03 3.73358130e+03 3.96993213e+03 3.80884546e+03 3.71766797e+03 3.89333813e+03 4.03242627e+03 4.21088770e+03 4.13526074e+03 4.04877100e+03 4.19405029e+03 4.26617041e+03 4.17311084e+03 4.16329834e+03 4.39577637e+03 4.42482471e+03 4.35086377e+03 4.41070801e+03 4.30446143e+03 4.52352783e+03 4.84964404e+03 4.77231543e+03 4.68491211e+03 4.59855811e+03 4.58548730e+03 4.87290039e+03 5.12231738e+03 5.01379883e+03 4.84582422e+03 4.90740527e+03 5.00562061e+03 5.03881885e+03 5.25806250e+03 5.25022266e+03 5.14147998e+03 5.23847998e+03 5.28012891e+03 5.49322168e+03 5.56613623e+03 5.40871729e+03 5.47779639e+03 5.54809229e+03 5.64206299e+03 5.57834131e+03 5.60814844e+03 5.87989990e+03 5.89028662e+03 5.87599365e+03 5.75315186e+03 5.81324072e+03 6.22362646e+03 6.23098438e+03 6.09796631e+03 6.01354248e+03 5.99790137e+03 6.11403467e+03 6.19408203e+03 6.34751123e+03 6.26112207e+03 6.36974805e+03 6.64590137e+03 6.48389014e+03 6.69816113e+03 6.79769971e+03 6.64508740e+03 6.66154639e+03 6.71966162e+03 6.76666309e+03 6.85796143e+03 6.83333594e+03 6.87557373e+03 7.11457275e+03 7.17057129e+03 6.88550977e+03 6.91168115e+03 7.10259863e+03 7.27959912e+03 7.59782275e+03 7.44495557e+03 7.14243506e+03 7.45705713e+03 7.66001318e+03 7.51181738e+03 7.54168066e+03 7.55874609e+03 7.51743750e+03 7.58206592e+03 7.80908887e+03 7.65466162e+03 7.76744531e+03 8.22387402e+03 8.06660010e+03 7.99619238e+03 7.90884131e+03 7.89464844e+03 8.32503027e+03 8.37169824e+03 8.22092285e+03 8.05908887e+03 7.91143555e+03 8.22113574e+03 8.55003320e+03 8.84795215e+03 8.59642969e+03 8.36963477e+03 8.42474023e+03 8.58100098e+03 8.95657227e+03 8.94208105e+03 8.68858301e+03 8.70961621e+03 8.73075391e+03 8.91507910e+03 8.80006641e+03 8.92730371e+03 9.37776953e+03 9.26614844e+03 9.17810156e+03 9.01361816e+03 8.98335645e+03 9.57782715e+03 9.60173340e+03 9.32296680e+03 9.20009473e+03 9.22070508e+03 9.45376465e+03 9.45303027e+03 9.86889453e+03 9.98139062e+03 9.62576758e+03 9.44036426e+03 9.57092578e+03 1.01833857e+04 1.00854736e+04 9.84127246e+03 9.79867773e+03 9.84563770e+03 9.88565039e+03 9.86470117e+03 1.01665967e+04 1.01375830e+04 9.99966504e+03 1.04134688e+04 1.05748057e+04 1.03758555e+04 1.03960508e+04 1.03350391e+04 1.04176172e+04 1.02024932e+04 1.01698340e+04 1.06884951e+04 1.08958975e+04 1.04144229e+04 1.01973086e+04 1.07298037e+04 1.11881572e+04 1.11222939e+04 1.07048311e+04 1.04782646e+04 1.09658311e+04 1.12075430e+04 1.10016709e+04 1.11221904e+04 1.08293838e+04 1.04865859e+04 1.09396709e+04 1.16844688e+04 1.16824268e+04 1.10296523e+04 1.07757871e+04 1.14649014e+04 1.18796621e+04 1.15363955e+04 1.11601885e+04 1.10666797e+04 1.12798115e+04 1.14611377e+04 1.18591025e+04 1.19583613e+04 1.16129482e+04 1.14515635e+04 1.14874062e+04 1.19924902e+04 1.17828809e+04 1.15298018e+04 1.20584473e+04 1.20528896e+04 1.19229307e+04 1.16740830e+04 1.16899180e+04 1.23977881e+04 1.20561523e+04 1.16365498e+04 1.19912744e+04 1.21683193e+04 1.22918711e+04 1.22017344e+04 1.24843203e+04 1.25741631e+04 1.22959746e+04 1.19297559e+04 1.19824521e+04 1.26812188e+04 1.24724658e+04 1.22084990e+04 1.23456104e+04 1.23434424e+04 1.26017832e+04 1.25491367e+04 1.26243848e+04 1.26120215e+04 1.23540146e+04 1.27629043e+04 1.28687178e+04 1.28123984e+04 1.28096602e+04 1.27130137e+04 1.26569883e+04 1.23275000e+04 1.22696279e+04 1.30459512e+04 1.35488154e+04 1.28075967e+04 1.22998037e+04 1.28502764e+04 1.34401631e+04 1.33400088e+04 1.28120273e+04 1.25361553e+04 1.31659189e+04 1.32099805e+04 1.28626943e+04 1.34321895e+04 1.32768447e+04 1.26025420e+04 1.28317080e+04 1.35262197e+04 1.36294678e+04 1.29966621e+04 1.26683164e+04 1.33029736e+04 1.38354551e+04 1.34900049e+04 1.29178799e+04 1.27712109e+04 1.34613096e+04 1.36416885e+04 1.32541826e+04 1.33953691e+04 1.34934219e+04 1.32803877e+04 1.31692275e+04 1.36922939e+04 1.35170156e+04 1.30793057e+04 1.35297764e+04 1.36597031e+04 1.37235596e+04 1.33901562e+04 1.31300664e+04 1.37064844e+04 1.34241816e+04 1.31755537e+04 1.41057139e+04 1.40912021e+04 1.41710957e+04 1.73444180e+04 1.61387256e+04 1.98942285e+04 2.18453555e+04 2.32166445e+04 1.71864844e+04 1.84321641e+04 2.60305293e+04 2.73723828e+04 -1.06300234e+04 1.95560645e+04 3.88627539e+04 2.17780484e+05 4.80331059e+09 0. 0. 0. 0. 0. 0. -1.98056489e+10 -1.98056489e+10 2.82703652e+04 1.52388026e+11 1.52388026e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 8.03682662e+09 2.06699203e+05 5.72183750e+04 5.36991016e+04 4.11257109e+04 2.34823320e+04 1.74535410e+04 1.76098340e+04 1.49437656e+04 1.48788242e+04 1.42798506e+04 1.36846123e+04 1.36420205e+04 1.35930801e+04 1.36445986e+04 1.34656748e+04 1.33331133e+04 1.36598525e+04 1.36562725e+04 1.35703789e+04 1.35980996e+04 1.31872529e+04 1.31788760e+04 1.35155732e+04 1.34065332e+04 1.32307031e+04 1.36162871e+04 1.40010557e+04 1.35164961e+04 1.31679580e+04 1.31902979e+04 1.30896094e+04 1.33749678e+04 1.35983213e+04 1.33661914e+04 1.33199746e+04 1.35672070e+04 1.33841895e+04 1.30626172e+04 1.31173584e+04 1.30875352e+04 1.31376758e+04 1.34765039e+04 1.31868711e+04 1.29876768e+04 1.33576797e+04 1.31437070e+04 1.29321006e+04 1.29318369e+04 1.29451533e+04 1.31078984e+04 1.31932539e+04 1.32722061e+04 1.30274717e+04 1.28157373e+04 1.30687617e+04 1.28305801e+04 1.25554482e+04 1.29232852e+04 1.29002559e+04 1.27906729e+04 1.30068613e+04 1.29604053e+04 1.26634561e+04 1.26501211e+04 1.26296367e+04 1.24769102e+04 1.26114121e+04 1.26728740e+04 1.27268779e+04 1.27383730e+04 1.25274541e+04 1.25241416e+04 1.24549189e+04 1.24880225e+04 1.24453379e+04 1.24534297e+04 1.28122637e+04 1.24251035e+04 1.19388398e+04 1.23192090e+04 1.22817402e+04 1.20899648e+04 1.23392676e+04 1.22102461e+04 1.21165732e+04 1.23893291e+04 1.24361445e+04 1.20061279e+04 1.17576465e+04 1.17994297e+04 1.18799316e+04 1.20485322e+04 1.20494248e+04 1.20652090e+04 1.20776895e+04 1.19405254e+04 1.16834766e+04 1.15372002e+04 1.17762656e+04 1.17139082e+04 1.15212217e+04 1.17195537e+04 1.16322734e+04 1.14844814e+04 1.16723584e+04 1.15179941e+04 1.11160234e+04 1.12086670e+04 1.15255273e+04 1.14912812e+04 1.13139023e+04 1.13358711e+04 1.13791191e+04 1.13758154e+04 1.13015039e+04 1.09571904e+04 1.08253760e+04 1.11724463e+04 1.11824170e+04 1.09015947e+04 1.09791260e+04 1.08435664e+04 1.07480791e+04 1.09207510e+04 1.07923418e+04 1.05952676e+04 1.06650859e+04 1.08265459e+04 1.08133174e+04 1.06449609e+04 1.03694570e+04 1.02425508e+04 1.04796143e+04 1.06151143e+04 1.02762998e+04 1.02649961e+04 1.05911016e+04 1.04739893e+04 1.02853701e+04 1.01477090e+04 9.92199023e+03 9.80602832e+03 9.89955566e+03 1.01096064e+04 1.00379502e+04 9.92636621e+03 9.97588281e+03 9.95803125e+03 9.76091309e+03 9.51035254e+03 9.54183105e+03 9.72116602e+03 9.76990137e+03 9.81479883e+03 9.68229492e+03 9.50244336e+03 9.33060449e+03 9.42197754e+03 9.46022363e+03 9.08651953e+03 9.04785742e+03 9.31646191e+03 9.38453711e+03 9.12544238e+03 8.99523730e+03 8.91162988e+03 8.79628711e+03 8.93319141e+03 9.11195312e+03 9.02552246e+03 8.80849121e+03 8.76595703e+03 8.75193555e+03 8.60811426e+03 8.53213379e+03 8.56170117e+03 8.46126172e+03 8.64255078e+03 8.69614258e+03 8.25645703e+03 8.25855176e+03 8.25214160e+03 8.24153516e+03 8.34122949e+03 8.05976660e+03 7.91520166e+03 8.09875195e+03 8.14429395e+03 8.03410840e+03 7.92405273e+03 7.80492627e+03 7.70907422e+03 7.76163135e+03 7.82113232e+03 7.75450439e+03 7.52626807e+03 7.63226709e+03 7.72468457e+03 7.53694873e+03 7.44862305e+03 7.34721338e+03 7.31156836e+03 7.41687988e+03 7.26867090e+03 7.18144189e+03 7.30841406e+03 7.03827979e+03 6.94679736e+03 7.09209180e+03 6.86307715e+03 6.86952295e+03 7.00967725e+03 6.90578320e+03 6.86567725e+03 6.69931104e+03 6.67680908e+03 6.61563281e+03 6.57270996e+03 6.64037354e+03 6.45592578e+03 6.30204199e+03 6.47006787e+03 6.47896777e+03 6.27065430e+03 6.30025781e+03 6.33525098e+03 6.07796387e+03 6.14526221e+03 6.22719141e+03 5.98844775e+03 5.90176025e+03 5.93080176e+03 5.88482812e+03 5.79475830e+03 5.76755469e+03 5.70476074e+03 5.70867334e+03 5.73040479e+03 5.64777881e+03 5.58563574e+03 5.52909668e+03 5.44814014e+03 5.39315723e+03 5.45577051e+03 5.27287695e+03 5.20145752e+03 5.32892627e+03 5.20305811e+03 5.05275732e+03 5.08843994e+03 5.02272998e+03 4.94277441e+03 4.92675732e+03 4.91525439e+03 4.92276953e+03 4.85180957e+03 4.80602100e+03 4.78381396e+03 4.61668506e+03 4.60524707e+03 4.59289404e+03 4.49219336e+03 4.54838574e+03 4.57335986e+03 4.39591650e+03 4.28939160e+03 4.28664746e+03 4.36535352e+03 4.26800684e+03 4.06968628e+03 4.13310449e+03 4.19485986e+03 4.05863525e+03 4.01399707e+03 3.95624438e+03 3.88967969e+03 3.89422021e+03 3.81058667e+03 3.75244385e+03 3.80255908e+03 3.78083813e+03 3.67485742e+03 3.65885425e+03 3.61518433e+03 3.59470288e+03 3.47812061e+03 3.35436450e+03 3.42397534e+03 3.46363672e+03 3.31029419e+03 3.25133765e+03 3.23874268e+03 3.24789624e+03 3.20387231e+03 3.05860547e+03 3.09925928e+03 3.11736621e+03 3.02895264e+03 2.98324072e+03 2.92335498e+03 2.85470312e+03 2.84985132e+03 2.82671143e+03 2.76191235e+03 2.78543921e+03 2.74513623e+03 2.67909326e+03 2.66724902e+03 2.60892700e+03 2.52570483e+03 2.48783496e+03 2.49545728e+03 2.48128760e+03 2.40086450e+03 2.33950049e+03 2.30019995e+03 2.28440723e+03 2.29176636e+03 2.25311841e+03 2.17081201e+03 2.12409668e+03 2.14631030e+03 2.14149707e+03 2.05602124e+03 1.98864990e+03 1.95763440e+03 1.95416479e+03 1.92168640e+03 1.87424170e+03 1.87677759e+03 1.83886304e+03 1.78909314e+03 1.79268115e+03 1.75190295e+03 1.68430310e+03 1.65132544e+03 1.63992517e+03 1.61350098e+03 1.53652075e+03 1.49126868e+03 1.50072083e+03 1.49052856e+03 1.47906433e+03 1.43178687e+03 1.36833740e+03 1.37752429e+03 1.36477869e+03 1.28920398e+03 1.25027026e+03 1.25740979e+03 1.25315833e+03 1.20628271e+03 1.15134363e+03 1.11914172e+03 1.10803882e+03 1.10516101e+03 1.09361902e+03 1.06181995e+03 1.00903638e+03 9.76814514e+02 9.61520203e+02 9.31061218e+02 9.10782166e+02 8.89292480e+02 8.62371216e+02 8.46619812e+02 8.27995972e+02 8.01995422e+02 7.71679443e+02 7.56480347e+02 7.57367371e+02 7.27432800e+02 6.80629028e+02 6.58592896e+02 6.52927795e+02 6.42152161e+02 6.26859375e+02 5.95528015e+02 5.56776367e+02 5.42942261e+02 5.39817322e+02 5.28441895e+02 5.09637085e+02 4.80083130e+02 4.58160126e+02 4.47688843e+02 4.28470703e+02 4.15898407e+02 3.98414154e+02 3.71963898e+02 3.66286530e+02 3.58356232e+02 3.37808929e+02 3.18034546e+02 2.97567505e+02 2.89201111e+02 2.89434906e+02 2.73595184e+02 2.49785645e+02 2.41838531e+02 2.34151276e+02 2.14721054e+02 2.01131104e+02 1.88406250e+02 1.79168060e+02 1.74992249e+02 1.63233337e+02 1.48249741e+02 1.39830994e+02 1.33022446e+02 1.22216141e+02 1.13222290e+02 1.06974648e+02 9.75484467e+01 8.83242035e+01 8.15902939e+01 7.44959335e+01 6.89875259e+01 6.26290550e+01 5.58481789e+01 4.99072914e+01 4.33106804e+01 3.83634949e+01 3.40531502e+01 2.95880737e+01 2.59333878e+01 2.19841423e+01 1.83322544e+01 1.49345589e+01 1.20813704e+01 9.74808121e+00 7.60801888e+00 5.73550987e+00 4.15836096e+00 3.02689290e+00 2.24086571e+00 1.76780987e+00 1.61399782e+00 1.77696705e+00 2.28225398e+00 3.18876052e+00 4.42983484e+00 5.89796257e+00 7.70348740e+00 9.72764683e+00 1.21587610e+01 1.54402962e+01 1.88392658e+01 2.15049896e+01 2.49818401e+01 2.99076920e+01 3.49938850e+01 3.98535843e+01 4.42771912e+01 4.91351585e+01 5.55729637e+01 6.25624390e+01 6.86603012e+01 7.44215546e+01 8.20208282e+01 9.02862854e+01 9.76672974e+01 1.06541748e+02 1.15322159e+02 1.23042770e+02 1.32723099e+02 1.42530655e+02 1.52317123e+02 1.60891571e+02 1.69590073e+02 1.82145691e+02 1.94981964e+02 2.06855286e+02 2.15798340e+02 2.25981445e+02 2.42952347e+02 2.56282562e+02 2.67370148e+02 2.83242828e+02 2.90739166e+02 3.02079803e+02 3.29382935e+02 3.41970490e+02 3.44565338e+02 3.69482941e+02 3.87983765e+02 3.91154297e+02 4.16545074e+02 4.35849640e+02 4.40439423e+02 4.68842865e+02 4.91295898e+02 4.94200867e+02 5.16772095e+02 5.40922241e+02 5.54399048e+02 5.76606262e+02 5.92329529e+02 5.99590149e+02 6.26648682e+02 6.57693054e+02 6.83705627e+02 7.07985107e+02 7.13351440e+02 7.37229431e+02 7.55183777e+02 7.60974548e+02 8.06234009e+02 8.34718262e+02 8.41807861e+02 8.81344666e+02 8.98349548e+02 9.03838013e+02 9.44835876e+02 9.81549011e+02 1.00709802e+03 1.01785474e+03 1.03507910e+03 1.04577319e+03 1.10078210e+03 1.16167188e+03 1.14105823e+03 1.16638135e+03 1.18616211e+03 1.21585181e+03 1.27977759e+03 1.27149646e+03 1.28335071e+03 1.34156592e+03 1.38686829e+03 1.39895032e+03 1.38920667e+03 1.44411292e+03 1.50613525e+03 1.51663074e+03 1.55129797e+03 1.55926855e+03 1.59054785e+03 1.65614099e+03 1.68007812e+03 1.72255176e+03 1.71823950e+03 1.72881396e+03 1.79010986e+03 1.82717285e+03 1.87621777e+03 1.89844006e+03 1.89386133e+03 1.94355688e+03 2.01308777e+03 2.04888428e+03 2.06328345e+03 2.09238477e+03 2.12275488e+03 2.18219751e+03 2.19885376e+03 2.19895679e+03 2.28798315e+03 2.33166919e+03 2.33007568e+03 2.40745068e+03 2.42481592e+03 2.41754443e+03 2.47458350e+03 2.49599414e+03 2.54930371e+03 2.62373535e+03 2.62981738e+03 2.63112183e+03 2.69496387e+03 2.74647437e+03 2.78663770e+03 2.89815283e+03 2.88087036e+03 2.85187769e+03 2.93828003e+03 2.94530322e+03 2.99591455e+03 3.05293872e+03 3.10937109e+03 3.19111377e+03 3.15982129e+03 3.23290552e+03 3.25536719e+03 3.23642627e+03 3.31921631e+03 3.42721021e+03 3.47512134e+03 3.45166528e+03 3.48203198e+03 3.58140259e+03 3.59894556e+03 3.61260352e+03 3.66281372e+03 3.70774243e+03 3.82172217e+03 3.81977100e+03 3.84301270e+03 3.92074072e+03 3.89414453e+03 3.92212744e+03 4.08963574e+03 4.13979980e+03 4.09897607e+03 4.13587549e+03 4.12409033e+03 4.19261572e+03 4.41958350e+03 4.37856250e+03 4.32007373e+03 4.54528271e+03 4.61659131e+03 4.60257275e+03 4.50291211e+03 4.59184033e+03 4.86634766e+03 5.37736377e+03 5.30405518e+03 1.18355098e+04 1.56989502e+04 4842013. 5211962. 3048284. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9226059. -4320898. 2.70772930e+04 1.49163018e+04 7.51893750e+03 9.55595312e+03 1.23418711e+04 1.10095459e+04 9.91300488e+03 9.68438965e+03 7.22805811e+03 7.38836670e+03 7.69755371e+03 7.57803223e+03 7.48057910e+03 7.45293994e+03 7.56814795e+03 7.79816602e+03 7.78761914e+03 7.66161084e+03 7.54212549e+03 7.82294238e+03 7.92199756e+03 7.91534863e+03 8.03285303e+03 7.88915430e+03 7.91544678e+03 8.12988428e+03 8.19104395e+03 8.21174316e+03 8.00967627e+03 8.02669434e+03 8.47949805e+03 8.70470898e+03 8.51175293e+03 8.17216455e+03 8.21672559e+03 8.58147656e+03 8.68970605e+03 8.64724316e+03 8.52500684e+03 8.78773535e+03 8.95243652e+03 8.92466699e+03 8.90739062e+03 8.62572070e+03 8.79305176e+03 9.33484082e+03 9.17773145e+03 9.16786035e+03 9.10981641e+03 8.98250098e+03 9.14475293e+03 9.51417969e+03 9.45962793e+03 9.14277441e+03 9.43512207e+03 9.55200586e+03 9.50607520e+03 9.56610352e+03 9.37187695e+03 9.60755566e+03 9.86161523e+03 9.67043750e+03 9.63092969e+03 9.56108105e+03 9.79924902e+03 1.02050596e+04 1.01670508e+04 9.99173047e+03 9.81096777e+03 9.94788379e+03 9.98800684e+03 1.01933877e+04 1.03661943e+04 1.00513047e+04 1.01757939e+04 1.05301377e+04 1.04892158e+04 1.03427266e+04 1.00958506e+04 1.03291260e+04 1.07554326e+04 1.07503242e+04 1.06138867e+04 1.03854355e+04 1.04360674e+04 1.07523115e+04 1.10237627e+04 1.07287578e+04 1.04898037e+04 1.09302861e+04 1.09718457e+04 1.08398438e+04 1.12159219e+04 1.09766426e+04 1.09074219e+04 1.11796387e+04 1.11975078e+04 1.12991865e+04 1.10472705e+04 1.09703604e+04 1.12068613e+04 1.15093926e+04 1.15963633e+04 1.13059199e+04 1.14430996e+04 1.15041143e+04 1.14327920e+04 1.15982090e+04 1.14218965e+04 1.14622725e+04 1.18394131e+04 1.18750225e+04 1.15326660e+04 1.12460352e+04 1.16672148e+04 1.22792979e+04 1.21633994e+04 1.18892441e+04 1.16003232e+04 1.16821191e+04 1.20017471e+04 1.21665244e+04 1.22117686e+04 1.19283066e+04 1.19590264e+04 1.20183506e+04 1.21358047e+04 1.24625771e+04 1.20350801e+04 1.20414795e+04 1.25799609e+04 1.23262266e+04 1.22407676e+04 1.22691387e+04 1.23473203e+04 1.26341025e+04 1.25354609e+04 1.22370693e+04 1.20672734e+04 1.24847168e+04 1.30461729e+04 1.28866904e+04 1.25663262e+04 1.23414951e+04 1.24785439e+04 1.27263730e+04 1.28971826e+04 1.28861631e+04 1.24062461e+04 1.23861846e+04 1.28628545e+04 1.30655742e+04 1.32055205e+04 1.28476045e+04 1.27537383e+04 1.28482363e+04 1.29133770e+04 1.31974609e+04 1.28469150e+04 1.28612910e+04 1.31096631e+04 1.30182100e+04 1.31230967e+04 1.28732988e+04 1.30529404e+04 1.33202998e+04 1.30839199e+04 1.32256807e+04 1.31255615e+04 1.31265625e+04 1.33945664e+04 1.33907773e+04 1.32144287e+04 1.29800176e+04 1.30586357e+04 1.34371045e+04 1.37640264e+04 1.35520381e+04 1.29601445e+04 1.28950908e+04 1.34324033e+04 1.37376592e+04 1.36061436e+04 1.30457031e+04 1.32370928e+04 1.35585820e+04 1.34551553e+04 1.35688857e+04 1.32822949e+04 1.33133369e+04 1.35337695e+04 1.36212881e+04 1.36922764e+04 1.34634619e+04 1.35137588e+04 1.35237158e+04 1.35563369e+04 1.38389883e+04 1.36084785e+04 1.35263066e+04 1.35533955e+04 1.34193311e+04 1.33519629e+04 1.34091445e+04 1.38177139e+04 1.39973877e+04 1.38492998e+04 1.34797959e+04 1.30441992e+04 1.34620332e+04 1.41691943e+04 1.41537773e+04 1.38227979e+04 1.34033633e+04 1.32463213e+04 1.36041162e+04 1.40069150e+04 1.39031299e+04 1.37624688e+04 1.38751748e+04 1.36897900e+04 1.35889932e+04 1.34515439e+04 1.32281123e+04 1.35460508e+04 1.36025947e+04 1.39150586e+04 1.39732109e+04 1.32087480e+04 1.36787734e+04 1.39600889e+04 1.35063105e+04 1.36534062e+04 1.36739902e+04 1.40360186e+04 1.39306201e+04 1.32463389e+04 1.30940303e+04 1.33682734e+04 1.39700742e+04 1.43895244e+04 1.40483916e+04 1.33366865e+04 1.29591230e+04 1.31969775e+04 1.39317637e+04 1.42950391e+04 1.39908057e+04 1.32039131e+04 1.30958887e+04 1.40453359e+04 1.39373643e+04 1.31782549e+04 1.32225508e+04 1.35395430e+04 1.35485322e+04 1.39168652e+04 1.35870635e+04 1.30104395e+04 1.34234619e+04 1.32214658e+04 1.34037227e+04 1.37659014e+04 1.31430889e+04 1.33884062e+04 1.37819531e+04 1.34654453e+04 1.33773086e+04 1.32695000e+04 1.34707129e+04 1.34226309e+04 1.31805967e+04 1.29357266e+04 1.29573672e+04 1.35824404e+04 1.39408008e+04 1.35484355e+04 1.29507139e+04 1.26898662e+04 1.28148516e+04 1.33532656e+04 13855. 1.34521758e+04 1.27283027e+04 1.28433145e+04 1.32922842e+04 1.31196553e+04 1.29251523e+04 1.29539053e+04 1.28050156e+04 1.29043086e+04 1.34168184e+04 1.30163262e+04 1.26467207e+04 1.28698018e+04 1.24763359e+04 1.28094639e+04 1.32198740e+04 1.27186553e+04 1.29883506e+04 1.29016904e+04 1.23611572e+04 1.26395254e+04 1.22908682e+04 1.25687959e+04 1.34115449e+04 1.26512607e+04 1.19774883e+04 1.22657920e+04 1.27892646e+04 1.31502559e+04 1.28776904e+04 1.21286357e+04 1.18201230e+04 1.20799609e+04 1.24755957e+04 1.30258770e+04 1.26943096e+04 1.18648721e+04 1.18869951e+04 1.22753350e+04 1.24130713e+04 1.20085781e+04 1.18898145e+04 1.20026650e+04 1.19988740e+04 1.24391172e+04 1.24315225e+04 1.17027656e+04 1.16081465e+04 1.18276191e+04 1.18295986e+04 1.18579043e+04 1.17929961e+04 1.20730059e+04 1.18194150e+04 1.13433672e+04 1.16049639e+04 1.12974844e+04 1.16012998e+04 1.22741016e+04 1.15348828e+04 1.08155674e+04 1.11176836e+04 1.16974121e+04 1.19419287e+04 1.18085938e+04 1.11118633e+04 1.07278105e+04 1.09298906e+04 1.13636113e+04 1.17973545e+04 1.14943506e+04 1.07636445e+04 1.06465830e+04 1.10270625e+04 1.10410801e+04 1.12364775e+04 1.12522090e+04 1.05598242e+04 1.05428516e+04 1.09203555e+04 1.09700957e+04 1.07473545e+04 1.06194150e+04 1.04978467e+04 1.03167168e+04 1.08914092e+04 1.08566982e+04 1.03560117e+04 1.02765107e+04 1.01818740e+04 1.02004600e+04 1.02795615e+04 1.02083623e+04 1.05363564e+04 1.04949424e+04 1.00239473e+04 9.84602441e+03 9.64097656e+03 9.99335059e+03 1.05075576e+04 1.01988984e+04 9.61366699e+03 9.43092871e+03 9.76666504e+03 1.01574102e+04 9.74908887e+03 9.18602051e+03 9.41331543e+03 9.63164746e+03 9.74221094e+03 1.00081074e+04 9.68589160e+03 9.13397461e+03 9.02880273e+03 9.25271777e+03 9.37233398e+03 9.36641797e+03 9.19453613e+03 9.12125586e+03 9.06356445e+03 9.18643066e+03 9.00670996e+03 8.72205859e+03 8.74512305e+03 8.72504297e+03 9.04995508e+03 9.05232031e+03 8.73182910e+03 8.71344043e+03 8.67505566e+03 8.66664355e+03 8.37904590e+03 8.18893994e+03 8.50120117e+03 8.81785449e+03 8.49908691e+03 8.04856006e+03 8.08216309e+03 8.41691211e+03 8.47090625e+03 8.26981348e+03 8.05956934e+03 7.82422119e+03 7.83214990e+03 8.03956982e+03 7.96359766e+03 7.75879834e+03 7.54994971e+03 7.47798291e+03 7.80519336e+03 8.08089453e+03 7.60311475e+03 7.34195947e+03 7.50613574e+03 7.43849072e+03 7.62956348e+03 7.53396143e+03 7.07382373e+03 7.08074805e+03 7.27276514e+03 7.16848145e+03 7.13921338e+03 7.04765088e+03 7.13876318e+03 7.35308301e+03 7.21426855e+03 7.40156934e+03 8.85023242e+03 8.31732324e+03 1.05547402e+04 1.01413848e+04 1.50984600e+04 1.95364199e+04 -7576427. -25924366. -30948142. -4065213. -7034017. -50936644. -2.05908050e+06 6.71785150e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 38177792. -3.17001075e+06 1.94457090e+04 1.20618711e+04 7.72733496e+03 7.07926904e+03 5.40319287e+03 5.09740967e+03 4.41058398e+03 4.44729492e+03 4.06313794e+03 4.11314697e+03 4.07474072e+03 3.94072729e+03 3.90336475e+03 3.86848315e+03 3.80297412e+03 3.75677271e+03 3.69461182e+03 3.62882422e+03 3.62370337e+03 3.56409180e+03 3.55346802e+03 3.54829321e+03 3.36770264e+03 3.32550244e+03 3.48246362e+03 3.43346265e+03 3.29744873e+03 3.25103491e+03 3.23525024e+03 3.18017285e+03 3.12363940e+03 3.09471558e+03 3.05471777e+03 3.00911011e+03 2.93086475e+03 2.89247070e+03 2.94725562e+03 2.92051611e+03 2.81814624e+03 2.77416016e+03 2.74399585e+03 2.71087134e+03 2.65890454e+03 2.61627808e+03 2.60753979e+03 2.52166333e+03 2.46034375e+03 2.44728003e+03 2.41753296e+03 2.48176147e+03 2.44926733e+03 2.32304443e+03 2.23375073e+03 2.19811182e+03 2.28923779e+03 2.27204736e+03 2.15922192e+03 2.08018896e+03 2.04307178e+03 2.05794678e+03 2.02380273e+03 2.03024158e+03 2.00599402e+03 1.86836658e+03 1.79938171e+03 1.86087769e+03 1.90578625e+03 1.82734534e+03 1.75366772e+03 1.72136450e+03 1.68391296e+03 1.65062329e+03 1.62772083e+03 1.59079529e+03 1.55302893e+03 1.53621863e+03 1.50892017e+03 1.47304138e+03 1.43832971e+03 1.45563220e+03 1.43190967e+03 1.36624524e+03 1.32245007e+03 1.30044885e+03 1.29249646e+03 1.26803662e+03 1.22484155e+03 1.19833484e+03 1.14983289e+03 1.10365710e+03 1.12701355e+03 1.09747314e+03 1.01964886e+03 1.01090381e+03 1.03990686e+03 1.04867749e+03 9.91705811e+02 9.41706787e+02 9.05703796e+02 8.81025696e+02 8.65779358e+02 8.42639771e+02 8.19913452e+02 7.92875244e+02 7.98326294e+02 7.78392517e+02 7.31454529e+02 7.08781738e+02 6.70583618e+02 6.58999756e+02 6.76323608e+02 6.47148315e+02 6.12104309e+02 5.80895935e+02 5.54779358e+02 5.61793518e+02 5.52961365e+02 5.22320618e+02 4.89488556e+02 4.69407379e+02 4.61201996e+02 4.45231079e+02 4.43330811e+02 4.29440308e+02 3.98613312e+02 3.77211304e+02 3.61013977e+02 3.54085632e+02 3.41660767e+02 3.22597015e+02 3.05764282e+02 2.92508606e+02 2.78826965e+02 2.57143280e+02 2.48034973e+02 2.49476761e+02 2.34252853e+02 2.16384354e+02 1.99189804e+02 1.87280914e+02 1.87173157e+02 1.76508423e+02 1.60689194e+02 1.47475159e+02 1.37600952e+02 1.31779449e+02 1.21834099e+02 1.13633583e+02 1.02925720e+02 9.65467911e+01 9.42223816e+01 8.43649063e+01 7.48994598e+01 6.83423004e+01 6.18886986e+01 5.54467659e+01 4.97026024e+01 4.38880806e+01 3.85466232e+01 3.38746910e+01 2.86659737e+01 2.49859772e+01 2.24823093e+01 1.82061481e+01 1.45944729e+01 1.21241856e+01 9.64100552e+00 7.71175098e+00 5.79522324e+00 4.18253422e+00 3.10990047e+00 2.27801847e+00 1.77571261e+00 1.61399734e+00 1.77557325e+00 2.26766062e+00 3.09798193e+00 4.24637461e+00 5.66948223e+00 7.69311476e+00 1.02692223e+01 1.26403084e+01 1.52215405e+01 1.79099903e+01 2.12001858e+01 2.62989540e+01 3.08326321e+01 3.45798454e+01 3.82930794e+01 4.29776077e+01 4.97847939e+01 5.58852348e+01 6.33519630e+01 6.90566559e+01 7.39896774e+01 8.18265839e+01 8.88877029e+01 1.00013298e+02 1.08066391e+02 1.12743034e+02 1.22361755e+02 1.31725327e+02 1.40388672e+02 1.45850540e+02 1.59446976e+02 1.80248398e+02 1.87354019e+02 1.93381760e+02 1.99824600e+02 2.09629562e+02 2.34821411e+02 2.48849335e+02 2.53741455e+02 2.60858276e+02 2.72765411e+02 2.94299408e+02 3.08707733e+02 3.29862274e+02 3.42502106e+02 3.49186066e+02 3.61345703e+02 3.74785583e+02 4.08145782e+02 4.24412933e+02 4.28372101e+02 4.41543488e+02 4.57037231e+02 4.92330353e+02 5.11691650e+02 5.03251221e+02 5.21239014e+02 5.70211365e+02 5.88159058e+02 5.78334656e+02 5.96430115e+02 6.47271912e+02 6.73096558e+02 6.70986145e+02 6.75910767e+02 6.98924377e+02 7.58004150e+02 7.67968994e+02 7.67639160e+02 8.07383850e+02 8.29929260e+02 8.43495239e+02 8.59228027e+02 8.87743713e+02 8.87952087e+02 9.36275208e+02 1.01647571e+03 1.01004602e+03 1.02011646e+03 1.05118542e+03 1.06893518e+03 1.09377917e+03 1.11713000e+03 1.14501733e+03 1.14468201e+03 1.15337854e+03 1.21104187e+03 1.26712646e+03 1.33032727e+03 1.31348425e+03 1.29162354e+03 1.35702063e+03 1.40254810e+03 1.48016565e+03 1.49275647e+03 1.47426282e+03 1.47556152e+03 1.49458618e+03 1.57118237e+03 1.60599707e+03 1.67065161e+03 1.70419873e+03 1.70051392e+03 1.70162939e+03 1.68221606e+03 1.77135876e+03 1.90477905e+03 1.92025293e+03 1.89979907e+03 1.87532861e+03 1.88271313e+03 2.01066882e+03 2.10320630e+03 2.07852173e+03 2.04000793e+03 2.07353418e+03 2.15859497e+03 2.19600098e+03 2.29329761e+03 2.33069043e+03 2.29660034e+03 2.30548413e+03 2.33346582e+03 2.44222339e+03 2.49109595e+03 2.42077905e+03 2.45518579e+03 2.62791504e+03 2.64050122e+03 2.54182056e+03 2.61739673e+03 2.79139746e+03 2.81435669e+03 2.79618237e+03 2.75782300e+03 2.77355493e+03 2.97526685e+03 3.03239746e+03 2.98798657e+03 2.94366992e+03 2.96506665e+03 3.08003369e+03 3.14109863e+03 3.18950537e+03 3.13019727e+03 3.23609082e+03 3.45659375e+03 3.41208350e+03 3.41364624e+03 3.46511816e+03 3.46857642e+03 3.49538696e+03 3.54341357e+03 3.59887549e+03 3.62583154e+03 3.62467529e+03 3.57130396e+03 3.72128833e+03 3.94274512e+03 3.81342334e+03 3.75311450e+03 3.92081006e+03 4.00694727e+03 4.18023340e+03 4.15523877e+03 4.05139136e+03 4.19458984e+03 4.24586475e+03 4.15467432e+03 4.16761963e+03 4.42954834e+03 4.43804053e+03 4.36780762e+03 4.33838867e+03 4.28885938e+03 4.52645605e+03 4.85301416e+03 4.78429004e+03 4.65610010e+03 4.60261475e+03 4.61010596e+03 4.90654346e+03 5.06308154e+03 4.97386865e+03 4.85179590e+03 4.88274756e+03 4.98258203e+03 5.09126416e+03 5.27728320e+03 5.28894141e+03 5.20091211e+03 5.24587061e+03 5.27607666e+03 5.45092529e+03 5.54300146e+03 5.48601611e+03 5.47179248e+03 5.48798389e+03 5.62426758e+03 5.54748047e+03 5.60883984e+03 5.90840088e+03 5.90774316e+03 5.86755420e+03 5.79368799e+03 5.75899707e+03 6.18361670e+03 6.22377979e+03 6.08808643e+03 6.01815527e+03 6.02079736e+03 6.14479102e+03 6.22406689e+03 6.30838428e+03 6.25901367e+03 6.40807520e+03 6.69624561e+03 6.54685596e+03 6.65127588e+03 6.74527783e+03 6.67699219e+03 6.69448096e+03 6.64935791e+03 6.73710010e+03 6.83861133e+03 6.89119971e+03 6.91657178e+03 7.05029053e+03 7.14699854e+03 6.92714209e+03 6.87911621e+03 7.09722461e+03 7.26953125e+03 7.53135742e+03 7.39606445e+03 7.24784375e+03 7.53789062e+03 7.54243994e+03 7.47993408e+03 7.55417236e+03 7.57824365e+03 7.55928027e+03 7.59798340e+03 7.74170361e+03 7.58519727e+03 7.76478809e+03 8.17903564e+03 8.06572119e+03 8.03043945e+03 7.95569922e+03 7.84428320e+03 8.31297266e+03 8.36995215e+03 8.24878320e+03 8.08251318e+03 7.97228076e+03 8.27146289e+03 8.46064355e+03 8.77367676e+03 8.55419629e+03 8.35462793e+03 8.53351562e+03 8.55551465e+03 8.89276660e+03 8.90582227e+03 8.66525391e+03 8.76735449e+03 8.77003418e+03 8.89812109e+03 8.73335156e+03 8.92427148e+03 9.43199121e+03 9.32783594e+03 9.21692285e+03 9.01916602e+03 8.92101660e+03 9.52263770e+03 9.61221680e+03 9.33497656e+03 9.15327344e+03 9.20749219e+03 9.52468359e+03 9.55331445e+03 9.81847949e+03 9.89173340e+03 9.67442871e+03 9.52937402e+03 9.49545898e+03 1.00854336e+04 1.01003242e+04 9.80896289e+03 9.91193945e+03 9.98721289e+03 9.89804688e+03 9.94459473e+03 1.02698672e+04 1.00431113e+04 9.88415234e+03 1.05100605e+04 1.05998887e+04 1.03528428e+04 1.03204912e+04 1.03507031e+04 1.04457148e+04 1.01798242e+04 1.01527822e+04 1.07677598e+04 1.08640049e+04 1.03250518e+04 1.02059658e+04 1.07807793e+04 1.12456738e+04 1.10469219e+04 1.06487383e+04 1.06014648e+04 1.10768037e+04 1.10669453e+04 1.08704170e+04 1.10932812e+04 1.08819893e+04 1.05853838e+04 1.10523291e+04 1.16319863e+04 1.15274463e+04 1.10507256e+04 1.09189883e+04 1.14943008e+04 1.17971943e+04 1.14770166e+04 1.11955879e+04 1.12037930e+04 1.13979727e+04 1.14510801e+04 1.18743066e+04 1.17573340e+04 1.13579307e+04 1.16388857e+04 1.17602041e+04 1.18956182e+04 1.16681885e+04 1.14769648e+04 1.19916973e+04 1.20491133e+04 1.18718066e+04 1.15941094e+04 1.17777402e+04 1.24778848e+04 1.20378252e+04 1.17498486e+04 1.20782490e+04 1.20522383e+04 1.21776357e+04 1.22115586e+04 1.24630801e+04 1.25912910e+04 1.22861455e+04 1.19149531e+04 1.19892041e+04 1.26973809e+04 1.24744951e+04 1.21617432e+04 1.24267744e+04 1.24491299e+04 1.25253105e+04 1.25349922e+04 1.27444688e+04 1.25204492e+04 1.22326836e+04 1.27775566e+04 1.28460840e+04 1.27509834e+04 1.28043799e+04 1.27477285e+04 1.27777295e+04 1.24457773e+04 1.23073936e+04 1.30374824e+04 1.33407500e+04 1.26758477e+04 1.23248213e+04 1.29536064e+04 1.35007305e+04 1.32169160e+04 1.27502930e+04 1.25921553e+04 1.31503291e+04 1.32553066e+04 1.29614375e+04 1.33050635e+04 1.32973809e+04 1.28936689e+04 1.28812871e+04 1.32842520e+04 1.35161465e+04 1.29594688e+04 1.27523135e+04 1.34553916e+04 1.36926895e+04 1.33390752e+04 1.28811465e+04 1.28401953e+04 1.35901748e+04 1.37034697e+04 1.32437939e+04 1.32075527e+04 1.33214863e+04 1.32472744e+04 1.31967334e+04 1.37456328e+04 1.34869922e+04 1.30269189e+04 1.36511602e+04 1.37898408e+04 1.36365859e+04 1.33205488e+04 1.31044688e+04 1.36139570e+04 1.34574043e+04 1.33720137e+04 1.42165264e+04 1.39751797e+04 1.40357129e+04 1.88146504e+04 1.83900645e+04 1.95830820e+04 2.16352715e+04 2.42356387e+04 1.92856348e+04 1.51906250e+04 1.96356270e+04 9.41205000e+04 -1.02358170e+10 -2.39732864e+09 -8.55866500e+05 -8.55866500e+05 -5.74428211e+09 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. 8.03682662e+09 2.06699203e+05 5.72183750e+04 5.79879805e+04 5.67727969e+04 5.21080078e+04 2.92605801e+04 2.25478867e+04 1.36398740e+04 1.38920713e+04 1.33632334e+04 1.29226406e+04 1.39008535e+04 1.57742930e+04 1.32530469e+04 1.28435439e+04 1.37433086e+04 1.26147158e+04 1.29437627e+04 1.46103008e+04 1.44200146e+04 1.34107568e+04 1.33751611e+04 1.34486455e+04 1.32418682e+04 1.33431875e+04 1.36844199e+04 1.35778945e+04 1.34795771e+04 1.35643467e+04 1.33311963e+04 1.32390176e+04 1.33480117e+04 1.31951807e+04 1.30715977e+04 1.34308438e+04 1.36635801e+04 1.32718711e+04 1.31180625e+04 1.32186533e+04 1.32144180e+04 1.33199707e+04 1.32319434e+04 1.29351377e+04 1.31817510e+04 1.34948516e+04 1.30112354e+04 1.29047773e+04 1.31744561e+04 1.28207520e+04 1.29104434e+04 1.33046211e+04 1.30483604e+04 1.29009980e+04 1.30465869e+04 1.32623242e+04 1.30465742e+04 1.26351494e+04 1.25564854e+04 1.25838193e+04 1.29839688e+04 1.32111523e+04 1.28646035e+04 1.26543076e+04 1.25856924e+04 1.26397783e+04 1.26543750e+04 1.25154473e+04 1.23929385e+04 1.26293906e+04 1.29570811e+04 1.25887178e+04 1.24077061e+04 1.26326367e+04 1.25202832e+04 1.24002207e+04 1.24226914e+04 1.25043965e+04 1.23309434e+04 1.21638213e+04 1.24116533e+04 1.23365361e+04 1.22822178e+04 1.22617949e+04 1.19526826e+04 1.21462314e+04 1.24716396e+04 1.21225312e+04 1.19062207e+04 1.19866318e+04 1.19867617e+04 1.20560996e+04 1.19587812e+04 1.16831348e+04 1.19106025e+04 1.22159189e+04 1.19545059e+04 1.15871318e+04 1.15967012e+04 1.18461963e+04 1.17986328e+04 1.16690459e+04 1.15472266e+04 1.14275527e+04 1.16394512e+04 1.18930469e+04 1.15252715e+04 1.11953066e+04 1.12075850e+04 1.12453037e+04 1.13930410e+04 1.14991670e+04 1.12895908e+04 1.11854238e+04 1.14887002e+04 1.14366309e+04 1.10131494e+04 1.08166855e+04 1.08696680e+04 1.10475605e+04 1.10949531e+04 1.10472314e+04 1.09420430e+04 1.08990166e+04 1.09239766e+04 1.06193916e+04 1.05480078e+04 1.06779951e+04 1.06050986e+04 1.07088506e+04 1.07912773e+04 1.04319277e+04 1.03591045e+04 1.05848652e+04 1.04815029e+04 1.01832314e+04 1.03282305e+04 1.05476318e+04 1.04037949e+04 1.02471445e+04 1.01357188e+04 1.00983428e+04 1.00455312e+04 9.88209473e+03 9.96932031e+03 1.00076543e+04 9.94037988e+03 9.90641797e+03 9.89349902e+03 9.84792773e+03 9.49224805e+03 9.62477930e+03 9.75774805e+03 9.63745508e+03 9.66331250e+03 9.76173828e+03 9.62912305e+03 9.34686133e+03 9.28337793e+03 9.29502734e+03 9.11191113e+03 9.21454395e+03 9.36417969e+03 9.19996484e+03 9.14578125e+03 9.08793848e+03 8.96637305e+03 8.92450488e+03 8.86809961e+03 8.81679980e+03 8.85025000e+03 8.89249316e+03 8.80949512e+03 8.63103809e+03 8.72458887e+03 8.63571387e+03 8.58596387e+03 8.48883398e+03 8.41558594e+03 8.52242578e+03 8.36198340e+03 8.32345801e+03 8.29646387e+03 8.26954688e+03 8.31976562e+03 7.98282959e+03 8.00190430e+03 8.18278662e+03 8.02951758e+03 8.07464404e+03 8.02208350e+03 7.81578662e+03 7.78301318e+03 7.64544775e+03 7.60335742e+03 7.62708887e+03 7.67463135e+03 7.67407666e+03 7.62878174e+03 7.58553174e+03 7.51237988e+03 7.40098340e+03 7.29384717e+03 7.15548828e+03 7.15039844e+03 7.30635889e+03 7.37564990e+03 7.06009717e+03 6.94030908e+03 7.11760059e+03 6.86046191e+03 6.91795459e+03 7.01933203e+03 6.79174854e+03 6.71723047e+03 6.75585840e+03 6.75497900e+03 6.69388916e+03 6.57979395e+03 6.50530029e+03 6.34505957e+03 6.36922607e+03 6.45285254e+03 6.39113184e+03 6.30208936e+03 6.25248584e+03 6.27597900e+03 6.12584131e+03 6.13971387e+03 6.14999268e+03 5.97461816e+03 5.87735693e+03 5.89853418e+03 5.88279346e+03 5.87147266e+03 5.79783887e+03 5.70273340e+03 5.70727246e+03 5.64822021e+03 5.60406250e+03 5.54206299e+03 5.62133447e+03 5.57092871e+03 5.29144629e+03 5.34700244e+03 5.32865186e+03 5.25100439e+03 5.32481201e+03 5.12415479e+03 5.01810400e+03 5.18562109e+03 5.12281396e+03 4.91424365e+03 4.88288867e+03 4.93907715e+03 4.92570996e+03 4.77131592e+03 4.79562598e+03 4.81592725e+03 4.63089551e+03 4.58683398e+03 4.62292188e+03 4.45030908e+03 4.48912695e+03 4.52535010e+03 4.34566846e+03 4.38041064e+03 4.42298975e+03 4.30685352e+03 4.19246484e+03 4.14092627e+03 4.14831641e+03 4.16398584e+03 4.05390210e+03 3.95483936e+03 3.95559448e+03 3.92188574e+03 3.85631323e+03 3.80480127e+03 3.79917456e+03 3.75374292e+03 3.70170630e+03 3.69276733e+03 3.67072241e+03 3.56877100e+03 3.54542969e+03 3.51503662e+03 3.39704663e+03 3.45324072e+03 3.43358643e+03 3.27734155e+03 3.29274316e+03 3.27001440e+03 3.18344141e+03 3.19008228e+03 3.10909399e+03 3.10756470e+03 3.11447607e+03 3.02488965e+03 2.96191016e+03 2.92246094e+03 2.86042114e+03 2.81408936e+03 2.79539893e+03 2.81429004e+03 2.80034595e+03 2.71738940e+03 2.66571021e+03 2.66677368e+03 2.59158057e+03 2.50823047e+03 2.50127710e+03 2.51450586e+03 2.48509229e+03 2.38343604e+03 2.31557324e+03 2.33648804e+03 2.33180566e+03 2.25932788e+03 2.21054736e+03 2.18525317e+03 2.15830298e+03 2.15488232e+03 2.10427661e+03 2.04536389e+03 1.98920447e+03 1.95297290e+03 1.94650330e+03 1.91231335e+03 1.88533752e+03 1.88160938e+03 1.82410449e+03 1.78811340e+03 1.80087549e+03 1.73821814e+03 1.66709204e+03 1.66897083e+03 1.66956213e+03 1.60274573e+03 1.52713635e+03 1.50019397e+03 1.51327417e+03 1.50316797e+03 1.46178210e+03 1.42126257e+03 1.37825098e+03 1.37873389e+03 1.35412024e+03 1.27791589e+03 1.25389124e+03 1.25629041e+03 1.24125757e+03 1.19299219e+03 1.14484790e+03 1.13186523e+03 1.11925500e+03 1.10492444e+03 1.08850098e+03 1.05586829e+03 1.00409296e+03 9.61907532e+02 9.67051453e+02 9.69020813e+02 9.21093567e+02 8.81586670e+02 8.51489990e+02 8.41625854e+02 8.38564392e+02 7.99349670e+02 7.70603577e+02 7.54922913e+02 7.47683228e+02 7.27487366e+02 6.80171875e+02 6.71190125e+02 6.57969177e+02 6.25336243e+02 6.12638184e+02 5.86272949e+02 5.66707031e+02 5.53734131e+02 5.31447205e+02 5.16161499e+02 5.02772919e+02 4.84182892e+02 4.59981110e+02 4.46630066e+02 4.33769684e+02 4.13935333e+02 3.95180298e+02 3.71265411e+02 3.60544617e+02 3.56668823e+02 3.39109375e+02 3.20750092e+02 2.99027374e+02 2.87828278e+02 2.85458313e+02 2.67101959e+02 2.50216080e+02 2.41985764e+02 2.28373230e+02 2.11860718e+02 2.02620575e+02 1.93859680e+02 1.79953323e+02 1.70709137e+02 1.60080399e+02 1.46032944e+02 1.38699951e+02 1.31052368e+02 1.22104202e+02 1.15377548e+02 1.05706993e+02 9.64758453e+01 8.77089844e+01 7.99412766e+01 7.40718613e+01 6.79680634e+01 6.06203957e+01 5.35805168e+01 4.86434288e+01 4.30969543e+01 3.76748314e+01 3.37938728e+01 2.90545273e+01 2.45253887e+01 2.06407337e+01 1.70761566e+01 1.41074581e+01 1.14728994e+01 8.96697903e+00 6.61510515e+00 4.75746727e+00 3.33442736e+00 2.22195506e+00 1.42523110e+00 9.36569691e-01 7.77402341e-01 9.58212674e-01 1.45856762e+00 2.27928448e+00 3.47871017e+00 5.02782822e+00 6.92870045e+00 8.93917942e+00 1.12280092e+01 1.44604959e+01 1.79248734e+01 2.11205788e+01 2.46639481e+01 2.88861084e+01 3.36659698e+01 3.89466438e+01 4.39426537e+01 4.84438362e+01 5.45969849e+01 6.17403297e+01 6.78053970e+01 7.44718018e+01 8.13773117e+01 8.82478867e+01 9.69946365e+01 1.05393242e+02 1.14434280e+02 1.22967110e+02 1.30642303e+02 1.41218918e+02 1.51321625e+02 1.61329971e+02 1.68000061e+02 1.78174561e+02 1.94166458e+02 2.07450546e+02 2.19851883e+02 2.27269272e+02 2.38696289e+02 2.50778198e+02 2.64422791e+02 2.84694275e+02 2.92232269e+02 3.04068115e+02 3.27492920e+02 3.34549042e+02 3.43809235e+02 3.69940002e+02 3.86690399e+02 3.98720337e+02 4.19323883e+02 4.29528900e+02 4.32085449e+02 4.62754089e+02 4.89593292e+02 4.95662628e+02 5.27924805e+02 5.45228394e+02 5.46117737e+02 5.67530823e+02 5.85064392e+02 6.06302673e+02 6.39687256e+02 6.55017395e+02 6.71074890e+02 6.98959717e+02 7.20095215e+02 7.44821716e+02 7.56741028e+02 7.67966125e+02 7.98934082e+02 8.26674438e+02 8.39692688e+02 8.67606018e+02 8.99171936e+02 9.11772156e+02 9.47326843e+02 9.76733398e+02 9.95607971e+02 1.01884137e+03 1.02606311e+03 1.05465869e+03 1.11401233e+03 1.13943713e+03 1.13600391e+03 1.17594397e+03 1.21061389e+03 1.22890820e+03 1.25503064e+03 1.24704382e+03 1.27357422e+03 1.35018054e+03 1.39666711e+03 1.41126514e+03 1.40426245e+03 1.43011182e+03 1.49618408e+03 1.51352185e+03 1.53309338e+03 1.57260107e+03 1.59668933e+03 1.63912537e+03 1.67393994e+03 1.72190515e+03 1.72722693e+03 1.73112134e+03 1.81790771e+03 1.82373474e+03 1.83054883e+03 1.88156177e+03 1.89278479e+03 1.94915027e+03 2.04192859e+03 2.06403516e+03 2.02812903e+03 2.06047314e+03 2.13710376e+03 2.18508252e+03 2.21035059e+03 2.21963818e+03 2.26690869e+03 2.33187744e+03 2.35726294e+03 2.39579565e+03 2.42141504e+03 2.45340820e+03 2.49049878e+03 2.45653491e+03 2.50401587e+03 2.62928613e+03 2.66164844e+03 2.67166821e+03 2.70610254e+03 2.71012524e+03 2.74355908e+03 2.88093359e+03 2.91666382e+03 2.87417090e+03 2.91398926e+03 2.93427588e+03 3.00546948e+03 3.06717139e+03 3.11936841e+03 3.19029590e+03 3.18777783e+03 3.21369263e+03 3.24767749e+03 3.23887646e+03 3.27728467e+03 3.42935498e+03 3.48065698e+03 3.44763501e+03 3.48755273e+03 3.53955591e+03 3.58686914e+03 3.60593945e+03 3.69936597e+03 3.70933081e+03 3.75226880e+03 3.81001050e+03 3.84702295e+03 3.95717578e+03 3.92599316e+03 3.93423853e+03 4.07532202e+03 4.04271216e+03 4.05672852e+03 4.16272314e+03 4.17377393e+03 4.20890820e+03 4.33330273e+03 4.41150586e+03 4.37770068e+03 4.46366504e+03 4.49058496e+03 4.51866016e+03 4.55524219e+03 4.84126562e+03 4.91824854e+03 5.95842383e+03 6.45368311e+03 7.76278760e+03 6.63071387e+03 1.09443848e+04 6.49086602e+04 3048284. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9226059. -4320898. 2862480. -7669407. 8808082. -3.02039150e+06 -11311646. -5.34199350e+06 2.18828867e+04 1.84433535e+04 9.74396484e+03 7.77971680e+03 7.67533203e+03 9.60522070e+03 7.95869531e+03 1.01809648e+04 7.24523926e+03 7.07697314e+03 7.77409180e+03 7.66177002e+03 7.50397266e+03 7.91166748e+03 8.14773047e+03 8.08012500e+03 7.99342676e+03 7.79794629e+03 7.93509424e+03 8.35272168e+03 8.11826709e+03 8.01303027e+03 7.98457666e+03 8.19107617e+03 8.61047363e+03 8.60810840e+03 8.40957422e+03 8.12579980e+03 8.22176758e+03 8.60282715e+03 8.66985547e+03 8.66175586e+03 8.63623340e+03 8.72425488e+03 8.85679004e+03 8.88921777e+03 8.98044238e+03 8.68056836e+03 8.86040430e+03 9.40943555e+03 9.05187109e+03 8.85095996e+03 9.00232324e+03 9.06151367e+03 9.41902441e+03 9.49659863e+03 9.28647363e+03 9.15774902e+03 9.43489062e+03 9.62823926e+03 9.53054004e+03 9.47607910e+03 9.34856152e+03 9.65059277e+03 9.92199219e+03 9.64719824e+03 9.65353809e+03 9.68006445e+03 9.68015430e+03 1.00719795e+04 1.01868818e+04 1.00166416e+04 9.84159277e+03 1.00396006e+04 1.01540029e+04 1.01950693e+04 1.02582920e+04 9.99770605e+03 1.00765752e+04 1.06177373e+04 1.03588477e+04 1.00870186e+04 1.00955967e+04 1.04476201e+04 1.09445127e+04 1.07535898e+04 1.05877080e+04 1.04842910e+04 1.03781221e+04 1.06653486e+04 1.09923916e+04 1.07903652e+04 1.05550400e+04 1.08778203e+04 1.10063623e+04 1.09752754e+04 1.12050811e+04 1.08758770e+04 1.08125332e+04 1.13680791e+04 1.12556787e+04 1.10944971e+04 1.10073037e+04 1.09661182e+04 1.14218828e+04 1.15613779e+04 1.12384531e+04 1.11996436e+04 1.15111318e+04 1.16420332e+04 1.14936387e+04 1.16350439e+04 1.15109766e+04 1.14228135e+04 1.18648770e+04 1.17899502e+04 1.15056279e+04 1.13873281e+04 1.16105508e+04 1.21378584e+04 1.21524883e+04 1.19872490e+04 1.16240215e+04 1.15277061e+04 1.21508721e+04 1.22517754e+04 1.18724785e+04 1.18522354e+04 1.20698467e+04 1.22981914e+04 1.21533291e+04 1.20893936e+04 1.19262334e+04 1.22012041e+04 1.27527168e+04 1.22938740e+04 1.21918389e+04 1.23696104e+04 1.22341582e+04 1.24754639e+04 1.25154795e+04 1.23624111e+04 1.22365186e+04 1.23900518e+04 1.28325146e+04 1.28773203e+04 1.26527344e+04 1.23876553e+04 1.24029014e+04 1.28568818e+04 1.29553037e+04 1.27888828e+04 1.24947842e+04 1.23289160e+04 1.28508477e+04 1.31355811e+04 1.29648701e+04 1.26532998e+04 1.27218359e+04 1.29224062e+04 1.29724902e+04 1.32913975e+04 1.29222734e+04 1.28434443e+04 1.32220596e+04 1.30146338e+04 1.29361826e+04 1.29734766e+04 1.31648125e+04 1.32607803e+04 1.30117803e+04 1.29760088e+04 1.29740312e+04 1.32462607e+04 1.37005996e+04 1.34131611e+04 1.29574814e+04 1.29640918e+04 1.31630459e+04 1.35513027e+04 1.37153848e+04 1.35373721e+04 1.30867676e+04 1.28203369e+04 1.33046621e+04 1.37249814e+04 1.37237715e+04 1.31690791e+04 1.30975176e+04 1.35495537e+04 1.35983438e+04 1.35824355e+04 1.34154844e+04 1.34106113e+04 1.34620254e+04 1.33513838e+04 1.34882070e+04 1.35415254e+04 1.34816309e+04 1.37306045e+04 1.35883975e+04 1.34703027e+04 1.34937041e+04 1.36491670e+04 1.37897891e+04 1.35099238e+04 1.33464541e+04 1.33558047e+04 1.38715684e+04 1.41303857e+04 1.36783320e+04 1.34449189e+04 1.32121514e+04 1.33790117e+04 1.40189072e+04 1.40898467e+04 1.37912295e+04 1.32813291e+04 1.32366221e+04 1.40351729e+04 1.41714043e+04 1.36050986e+04 1.36089561e+04 1.39064697e+04 1.36875908e+04 1.34570127e+04 1.33166602e+04 1.32107432e+04 1.35237607e+04 1.37861006e+04 1.41288057e+04 1.39972275e+04 1.32469365e+04 1.34382920e+04 1.37483838e+04 1.37127285e+04 1.37618174e+04 1.35816660e+04 1.40090391e+04 1.39554688e+04 1.32208447e+04 1.30713262e+04 1.33897920e+04 1.39791748e+04 1.44087520e+04 1.40608789e+04 1.33169453e+04 1.29072949e+04 1.31491699e+04 1.39253447e+04 1.43536699e+04 1.40354883e+04 1.31705166e+04 1.30600938e+04 1.41046719e+04 1.39768369e+04 1.32404092e+04 1.33327656e+04 1.34261543e+04 1.34264453e+04 1.38925215e+04 1.35973887e+04 1.30502490e+04 1.34043154e+04 1.32072119e+04 1.34340059e+04 1.37526787e+04 1.31359229e+04 1.33906631e+04 1.37342988e+04 1.34285371e+04 1.33422832e+04 1.33209189e+04 1.34609893e+04 1.33542842e+04 1.32137793e+04 1.29492119e+04 1.29360830e+04 1.35866094e+04 1.39745059e+04 1.35982139e+04 1.28908672e+04 1.26329551e+04 1.28615820e+04 1.33798701e+04 1.38089570e+04 1.34114629e+04 1.27237598e+04 1.28700088e+04 1.32630518e+04 1.30528271e+04 1.29227217e+04 1.30207891e+04 1.28543379e+04 1.28540186e+04 1.33787139e+04 1.30638877e+04 1.26079375e+04 1.28725928e+04 1.25615410e+04 1.28658047e+04 1.31714287e+04 1.26626104e+04 1.29932295e+04 1.29029863e+04 1.23714961e+04 1.26497256e+04 1.23005322e+04 1.25489717e+04 1.33758262e+04 1.26697607e+04 1.19405322e+04 1.21201455e+04 1.27515020e+04 1.32404424e+04 1.28901025e+04 1.21516045e+04 1.18707539e+04 1.20582012e+04 1.24580234e+04 1.29801074e+04 1.26653438e+04 1.19017646e+04 1.18824102e+04 1.21713896e+04 1.22943623e+04 1.21425391e+04 1.20479072e+04 1.20058096e+04 1.19619570e+04 1.24345449e+04 1.24133525e+04 1.15772949e+04 1.14747500e+04 1.19474756e+04 1.19391455e+04 1.18250430e+04 1.18095293e+04 1.21113613e+04 1.18342949e+04 1.13353633e+04 1.15939521e+04 1.12690469e+04 1.15894463e+04 1.23092959e+04 1.15299512e+04 1.08487920e+04 1.11960713e+04 1.17097686e+04 1.19940684e+04 1.18181650e+04 1.10089014e+04 1.07153242e+04 1.09693330e+04 1.13589023e+04 1.17078809e+04 1.14972100e+04 1.07497168e+04 1.06519961e+04 1.10653379e+04 1.10257109e+04 1.12037422e+04 1.12699336e+04 1.05890010e+04 1.04781865e+04 1.10078652e+04 1.10736992e+04 1.05314912e+04 1.04268145e+04 1.06628350e+04 1.04581699e+04 1.07893525e+04 1.08379561e+04 1.03781396e+04 1.02707715e+04 1.02104912e+04 1.02120879e+04 1.02332178e+04 1.01493418e+04 1.04700225e+04 1.05593320e+04 1.01872402e+04 9.84011328e+03 9.54282422e+03 9.93086914e+03 1.04689463e+04 1.01924766e+04 9.60739453e+03 9.38099902e+03 9.67735547e+03 1.01524355e+04 9.82494238e+03 9.21310156e+03 9.38097266e+03 9.62402441e+03 9.75564258e+03 1.00586016e+04 9.68762500e+03 9.04436621e+03 9.04054004e+03 9.22628320e+03 9.32869434e+03 9.37303906e+03 9.23145801e+03 9.17550098e+03 9.07875488e+03 9.16970312e+03 9.08033496e+03 8.79395117e+03 8.75797656e+03 8.66261719e+03 9.00631738e+03 9.04095312e+03 8.66569043e+03 8.77709180e+03 8.72615820e+03 8.63740625e+03 8.35508203e+03 8.17591943e+03 8.52993457e+03 8.80090918e+03 8.59508203e+03 8.13231689e+03 8.01887988e+03 8.36035547e+03 8.46581152e+03 8.26770508e+03 8.05769043e+03 7.79504736e+03 7.79306641e+03 8.05185352e+03 7.99841797e+03 7.76962500e+03 7.54418604e+03 7.44686768e+03 7.77476318e+03 8.07179834e+03 7.63132666e+03 7.35948633e+03 7.50292529e+03 7.44082959e+03 7.62475488e+03 7.51690088e+03 7.09209766e+03 7.11140918e+03 7.28026025e+03 7.24425830e+03 7.14347070e+03 7.03117383e+03 7.12232178e+03 7.10595459e+03 6.79099951e+03 7.04889551e+03 6.79283789e+03 6.47311621e+03 7.12995557e+03 7.02002783e+03 8.46217090e+03 8.57221094e+03 9.77468262e+03 1.12808613e+04 1.67560508e+04 1.91163379e+04 -7034017. -50936644. -2.05908050e+06 6.71785150e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 38177792. -3.17001075e+06 -8538725. -14167671. -5494078. 1.50015712e+06 1.19600010e+04 9.46792969e+03 6.78527686e+03 6.81276709e+03 6.09084082e+03 6.21071289e+03 6.17231104e+03 5.91769043e+03 5.84708447e+03 5.78071094e+03 4.81639941e+03 4.89524609e+03 4.00123975e+03 3.74407617e+03 3.68168530e+03 3.58516382e+03 3.56848462e+03 3.53847339e+03 3.39197144e+03 3.35439209e+03 3.47309351e+03 3.43662842e+03 3.30403125e+03 3.23843481e+03 3.22848828e+03 3.19445728e+03 3.13386523e+03 3.09772485e+03 3.04954297e+03 3.00037476e+03 2.93177441e+03 2.89262402e+03 2.95180273e+03 2.91040259e+03 2.80951807e+03 2.77271191e+03 2.74791968e+03 2.72688184e+03 2.65724243e+03 2.62472241e+03 2.59671948e+03 2.52792139e+03 2.47456372e+03 2.44098315e+03 2.40225049e+03 2.47467456e+03 2.45014795e+03 2.32924658e+03 2.23488623e+03 2.18852759e+03 2.29146045e+03 2.26948242e+03 2.15394946e+03 2.07390430e+03 2.04579248e+03 2.03667493e+03 1.99552551e+03 2.04965479e+03 2.01205579e+03 1.85600745e+03 1.79890088e+03 1.85717175e+03 1.91751746e+03 1.84591052e+03 1.75743384e+03 1.71993848e+03 1.68215454e+03 1.66167090e+03 1.64237036e+03 1.58732581e+03 1.54911731e+03 1.52548169e+03 1.49534448e+03 1.46903931e+03 1.43851196e+03 1.45495032e+03 1.41971814e+03 1.34797021e+03 1.31762378e+03 1.29568799e+03 1.29975781e+03 1.27434009e+03 1.22601758e+03 1.19417151e+03 1.14401611e+03 1.09130017e+03 1.12094458e+03 1.10953052e+03 1.02604395e+03 1.00797186e+03 1.03965527e+03 1.04203455e+03 9.87037537e+02 9.37812988e+02 9.15299866e+02 8.94557129e+02 8.58739014e+02 8.34002808e+02 8.19239136e+02 7.92799988e+02 7.97102844e+02 7.70909790e+02 7.27751587e+02 7.06541626e+02 6.69442383e+02 6.67427979e+02 6.82478516e+02 6.46821655e+02 6.11619385e+02 5.78094177e+02 5.51904053e+02 5.62834900e+02 5.54842957e+02 5.20522522e+02 4.86947296e+02 4.67371429e+02 4.60502380e+02 4.43620392e+02 4.41954315e+02 4.28460876e+02 3.96174927e+02 3.72668549e+02 3.57224152e+02 3.55698364e+02 3.43553711e+02 3.21857422e+02 3.03634918e+02 2.89909485e+02 2.75927185e+02 2.54433929e+02 2.48744049e+02 2.51587677e+02 2.33308670e+02 2.15171463e+02 1.99108704e+02 1.86486511e+02 1.85962723e+02 1.76141678e+02 1.60086868e+02 1.46114822e+02 1.36390121e+02 1.31118149e+02 1.21317581e+02 1.12704849e+02 1.01671089e+02 9.54581528e+01 9.25868835e+01 8.24030075e+01 7.43725815e+01 6.82091370e+01 6.09795418e+01 5.37935791e+01 4.81775360e+01 4.29351196e+01 3.75758362e+01 3.29625816e+01 2.78195000e+01 2.44225903e+01 2.18831558e+01 1.74025364e+01 1.37899303e+01 1.12950239e+01 8.81772900e+00 6.85598946e+00 4.94250631e+00 3.33625674e+00 2.25661469e+00 1.43750441e+00 9.40069914e-01 7.77092874e-01 9.46404397e-01 1.44836926e+00 2.29435492e+00 3.44874048e+00 4.84100151e+00 6.84603214e+00 9.47762585e+00 1.18305559e+01 1.42621775e+01 1.69497662e+01 2.06417713e+01 2.57976475e+01 2.99144592e+01 3.36818237e+01 3.75086594e+01 4.21744804e+01 4.90715828e+01 5.50585480e+01 6.23170319e+01 6.81440201e+01 7.32202072e+01 8.13367538e+01 8.82400436e+01 9.90996857e+01 1.08001747e+02 1.13194458e+02 1.21036560e+02 1.30256882e+02 1.40298782e+02 1.45977478e+02 1.58737274e+02 1.78427872e+02 1.86637589e+02 1.92842957e+02 1.98762375e+02 2.09211517e+02 2.33591156e+02 2.47170807e+02 2.52754654e+02 2.59978363e+02 2.72079559e+02 2.93493195e+02 3.08339386e+02 3.28669159e+02 3.41324371e+02 3.47759979e+02 3.58580994e+02 3.73084290e+02 4.07605347e+02 4.26145599e+02 4.29918823e+02 4.38875763e+02 4.54991699e+02 4.91989044e+02 5.10950958e+02 5.01744934e+02 5.20279480e+02 5.72384094e+02 5.86998535e+02 5.76183228e+02 5.95511902e+02 6.46108459e+02 6.72871643e+02 6.68759644e+02 6.72834290e+02 6.96187805e+02 7.57991028e+02 7.74460632e+02 7.72070557e+02 8.03961670e+02 8.23253479e+02 8.29363953e+02 8.49626831e+02 8.96471130e+02 8.97373657e+02 9.34918457e+02 1.00522308e+03 1.00181866e+03 1.03157300e+03 1.06189648e+03 1.06616162e+03 1.09203479e+03 1.11785730e+03 1.14416052e+03 1.14159998e+03 1.15435693e+03 1.21160547e+03 1.26262659e+03 1.32453735e+03 1.30864587e+03 1.29988647e+03 1.36483948e+03 1.39164551e+03 1.46822314e+03 1.49231177e+03 1.47381812e+03 1.47997803e+03 1.50010876e+03 1.56775989e+03 1.60316833e+03 1.67012891e+03 1.69416187e+03 1.68745361e+03 1.71724438e+03 1.69751074e+03 1.77266162e+03 1.90043250e+03 1.91645288e+03 1.89335474e+03 1.87662207e+03 1.89952234e+03 2.02824011e+03 2.08302954e+03 2.06489160e+03 2.03838867e+03 2.07532104e+03 2.16052490e+03 2.18931421e+03 2.28357446e+03 2.31268726e+03 2.28055322e+03 2.32462598e+03 2.35003442e+03 2.44459521e+03 2.48439868e+03 2.41172339e+03 2.45302002e+03 2.62998828e+03 2.62478540e+03 2.51658545e+03 2.63397729e+03 2.81208276e+03 2.82336060e+03 2.79797534e+03 2.76052100e+03 2.78109619e+03 2.98103320e+03 3.02819165e+03 2.98052637e+03 2.93998975e+03 2.96752954e+03 3.08574487e+03 3.14105396e+03 3.19280469e+03 3.14637378e+03 3.24239380e+03 3.45017578e+03 3.40291602e+03 3.41195874e+03 3.43009961e+03 3.43644971e+03 3.49996094e+03 3.53783081e+03 3.60743164e+03 3.63743970e+03 3.65862231e+03 3.60124170e+03 3.69709351e+03 3.93440552e+03 3.82200830e+03 3.69963501e+03 3.88501953e+03 4.03759058e+03 4.19287744e+03 4.16298535e+03 4.09259839e+03 4.16179785e+03 4.21313721e+03 4.16396338e+03 4.18743408e+03 4.39363770e+03 4.41715332e+03 4.37224023e+03 4.38375049e+03 4.31122070e+03 4.52971338e+03 4.82155713e+03 4.74990576e+03 4.68964990e+03 4.61107227e+03 4.62641260e+03 4.93647363e+03 5.07522803e+03 4.96924756e+03 4.84958545e+03 4.87007861e+03 4.99287305e+03 5.05152246e+03 5.29530615e+03 5.28335303e+03 5.17829102e+03 5.24546875e+03 5.26533496e+03 5.44512402e+03 5.50168701e+03 5.42033545e+03 5.52955908e+03 5.57535205e+03 5.51806445e+03 5.43921631e+03 5.60818408e+03 5.95040381e+03 5.89212451e+03 5.82292627e+03 5.74435596e+03 5.83112061e+03 6.21740918e+03 6.24298389e+03 6.09240820e+03 5.98290430e+03 5.99938184e+03 6.14888721e+03 6.20492578e+03 6.35297803e+03 6.22634131e+03 6.39435498e+03 6.66323242e+03 6.54303125e+03 6.64367188e+03 6.73909033e+03 6.63617090e+03 6.75071436e+03 6.80258496e+03 6.63720996e+03 6.66440430e+03 6.96513379e+03 7.02980469e+03 7.06102783e+03 7.07832031e+03 6.91732910e+03 6.91328320e+03 7.18764307e+03 7.24346143e+03 7.49894678e+03 7.45726758e+03 7.18172998e+03 7.40478613e+03 7.62117334e+03 7.57928320e+03 7.49763574e+03 7.46157373e+03 7.67524268e+03 7.72281836e+03 7.71836328e+03 7.59968457e+03 7.77361768e+03 8.26700391e+03 8.13691357e+03 7.95677979e+03 7.83275732e+03 7.87139551e+03 8.34996191e+03 8.37109570e+03 8.22937891e+03 8.04030615e+03 7.98350928e+03 8.27088965e+03 8.52224023e+03 8.78987891e+03 8.62082910e+03 8.28206641e+03 8.43504980e+03 8.56679004e+03 8.94339844e+03 8.80961328e+03 8.59855566e+03 8.88508594e+03 8.94344727e+03 8.89135547e+03 8.71513379e+03 8.90594727e+03 9.40826660e+03 9.38321289e+03 9.09699414e+03 8.92596973e+03 9.00641309e+03 9.51858008e+03 9.62025977e+03 9.39904395e+03 9.16745215e+03 9.19769531e+03 9.48302344e+03 9.51034863e+03 9.84163574e+03 9.90468750e+03 9.60322656e+03 9.43116602e+03 9.58754883e+03 1.01825439e+04 1.00534150e+04 9.73800391e+03 1.00134355e+04 1.00935645e+04 9.81097949e+03 9.74483887e+03 1.01491465e+04 1.01390361e+04 9.94077930e+03 1.04925049e+04 1.05870889e+04 1.03906084e+04 1.03798096e+04 1.03523408e+04 1.04010078e+04 1.02060068e+04 1.01335059e+04 1.07129297e+04 1.08676523e+04 1.04417109e+04 1.02311758e+04 1.06742979e+04 1.11515225e+04 1.11233848e+04 1.07423076e+04 1.05006631e+04 1.09505146e+04 1.12977070e+04 1.11498721e+04 1.09886660e+04 1.07464336e+04 1.05614814e+04 1.11032471e+04 1.17279951e+04 1.14529395e+04 1.09683770e+04 1.09546348e+04 1.15337109e+04 1.17690303e+04 1.14601855e+04 1.11300654e+04 1.10652412e+04 1.13144990e+04 1.14768105e+04 1.18772441e+04 1.19232266e+04 1.15640635e+04 1.15228643e+04 1.16526250e+04 1.19219033e+04 1.16258770e+04 1.14832861e+04 1.20908242e+04 1.21357148e+04 1.17751182e+04 1.14704043e+04 1.18068242e+04 1.25160400e+04 1.19711963e+04 1.16031064e+04 1.19877256e+04 1.22056982e+04 1.23083281e+04 1.21969902e+04 1.24878535e+04 1.26288916e+04 1.22385254e+04 1.18845225e+04 1.19401084e+04 1.27086162e+04 1.25377227e+04 1.21992832e+04 1.24444053e+04 1.24659297e+04 1.24993604e+04 1.24479404e+04 1.26165586e+04 1.25994512e+04 1.23625039e+04 1.27066143e+04 1.27570010e+04 1.28363301e+04 1.29117031e+04 1.27214512e+04 1.26796309e+04 1.23518594e+04 1.24460059e+04 1.31986670e+04 1.33963799e+04 1.26883818e+04 1.23178809e+04 1.28329277e+04 1.33567969e+04 1.33037441e+04 1.28880928e+04 1.24505781e+04 1.29799971e+04 1.33776318e+04 1.30352920e+04 1.33609111e+04 1.32334111e+04 1.26998066e+04 1.30317061e+04 1.35554531e+04 1.34464561e+04 1.28458184e+04 1.26669766e+04 1.34178086e+04 1.37491504e+04 1.33398428e+04 1.28737734e+04 1.28094893e+04 1.35860664e+04 1.35849219e+04 1.31418291e+04 1.33762979e+04 1.34200303e+04 1.32344531e+04 1.32091211e+04 1.37293691e+04 1.35272686e+04 1.30247676e+04 1.36355449e+04 1.37724023e+04 1.36328057e+04 1.33296953e+04 1.30831621e+04 1.37312139e+04 1.35478848e+04 1.30990361e+04 1.35051348e+04 1.37917578e+04 1.44753857e+04 1.42204277e+04 1.34727148e+04 1.36913242e+04 1.41902461e+04 1.50241504e+04 1.37879414e+04 1.22709932e+04 1.47869434e+04 4.73383945e+04 2.83856113e+04 8.38194944e+09 1.91129594e+05 -8.55866500e+05 -5.74428211e+09 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. 0. 0. 0. 4.07714492e+04 2.66336270e+04 1.40839150e+04 13976. 1.31483398e+04 1.27715215e+04 1.38458008e+04 1.51867920e+04 1.31285889e+04 1.31515371e+04 1.39656230e+04 1.27706953e+04 1.27564668e+04 1.39591758e+04 1.42573545e+04 1.36383369e+04 1.33923896e+04 1.33884482e+04 1.33466396e+04 1.34059492e+04 1.37512861e+04 1.38587803e+04 1.33827598e+04 1.31854727e+04 1.33942217e+04 1.34049092e+04 1.32173984e+04 1.31621816e+04 1.33161494e+04 1.32925596e+04 1.34681416e+04 1.33892422e+04 1.28822422e+04 1.30538945e+04 1.34718711e+04 1.35617354e+04 1.34930977e+04 1.29573594e+04 1.27929277e+04 1.31812383e+04 1.32497109e+04 1.30524141e+04 1.29263818e+04 1.28891055e+04 1.31129736e+04 1.33036943e+04 1.31267314e+04 1.27279258e+04 1.26641592e+04 1.32675703e+04 1.33060439e+04 1.26133457e+04 1.25398447e+04 1.28576934e+04 1.29566621e+04 1.31025947e+04 1.28881504e+04 1.24251436e+04 1.24761396e+04 1.28192148e+04 1.28752100e+04 1.26466270e+04 1.24210518e+04 1.26042021e+04 1.28384619e+04 1.25830801e+04 1.23887393e+04 1.22850439e+04 1.24282314e+04 1.26355713e+04 1.25291113e+04 1.25606572e+04 1.23908525e+04 1.20634121e+04 1.22319258e+04 1.23746982e+04 1.22426016e+04 1.22751426e+04 1.21297393e+04 1.20798516e+04 1.23642471e+04 1.23123877e+04 1.18360576e+04 1.17936875e+04 1.20736191e+04 1.21373311e+04 1.20767031e+04 1.18354629e+04 1.17884590e+04 1.18537969e+04 1.19422969e+04 1.18741045e+04 1.15213701e+04 1.16094883e+04 1.18963799e+04 1.18845020e+04 1.17315527e+04 1.14008701e+04 1.13394902e+04 1.16927471e+04 1.15891543e+04 1.12944082e+04 1.12611016e+04 1.13027520e+04 1.14917842e+04 1.14127842e+04 1.12867158e+04 1.12506797e+04 1.12165967e+04 1.12954893e+04 1.12117002e+04 1.09803896e+04 1.09863691e+04 1.10261670e+04 1.09118105e+04 1.09620537e+04 1.09963135e+04 1.08885791e+04 1.08463477e+04 1.07017412e+04 1.06503223e+04 1.07481387e+04 1.07908477e+04 1.06430322e+04 1.05556719e+04 1.04664219e+04 1.04255684e+04 1.04845566e+04 1.03963154e+04 1.02760977e+04 1.03626152e+04 1.05607051e+04 1.04603330e+04 1.01145049e+04 1.01108555e+04 1.02234189e+04 1.00380449e+04 9.91766602e+03 9.83312988e+03 9.91786426e+03 9.99452539e+03 1.00644824e+04 9.91458691e+03 9.68770508e+03 9.56246094e+03 9.70938672e+03 9.75376758e+03 9.68527344e+03 9.61174316e+03 9.41449023e+03 9.51724512e+03 9.61083496e+03 9.51371680e+03 9.22907812e+03 9.07016992e+03 9.24946094e+03 9.44933301e+03 9.26749219e+03 8.85263672e+03 8.95547461e+03 9.20119238e+03 9.06088477e+03 8.88488086e+03 8.83040918e+03 8.86011133e+03 8.80500879e+03 8.78637793e+03 8.72639746e+03 8.50929785e+03 8.70722949e+03 8.71182910e+03 8.54307129e+03 8.50267969e+03 8.49511133e+03 8.20878516e+03 8.28307520e+03 8.31158203e+03 8.31732129e+03 8.36422852e+03 7.96885498e+03 7.95453662e+03 8.21259570e+03 8.00788281e+03 7.79664062e+03 7.88684180e+03 7.95598975e+03 7.82896875e+03 7.75268262e+03 7.70887305e+03 7.59111816e+03 7.58240039e+03 7.64799658e+03 7.62687500e+03 7.35671973e+03 7.42806348e+03 7.52356006e+03 7.47740039e+03 7.29417920e+03 7.12799072e+03 7.15104883e+03 7.27649658e+03 7.09274072e+03 6.99146924e+03 7.07573633e+03 6.88389990e+03 6.91432275e+03 7.03565088e+03 6.83525977e+03 6.73081006e+03 6.73895898e+03 6.70817627e+03 6.62456787e+03 6.64201611e+03 6.57033496e+03 6.40541357e+03 6.39596387e+03 6.43502002e+03 6.38045361e+03 6.22067773e+03 6.27834033e+03 6.34312988e+03 6.21420703e+03 6.25646484e+03 6.08852393e+03 5.89316895e+03 5.97882031e+03 5.98190186e+03 5.90172363e+03 5.75424756e+03 5.63563525e+03 5.77066016e+03 5.80474219e+03 5.68450146e+03 5.53389697e+03 5.61587646e+03 5.59329639e+03 5.44325439e+03 5.32181543e+03 5.43935156e+03 5.36133691e+03 5.19834033e+03 5.29564893e+03 5.18003906e+03 5.08552441e+03 5.12276221e+03 5.01661572e+03 4.95414404e+03 4.96625342e+03 4.87536670e+03 4.79872852e+03 4.84495996e+03 4.84735156e+03 4.80012305e+03 4.59108105e+03 4.55304102e+03 4.60238916e+03 4.52304785e+03 4.52171191e+03 4.45604980e+03 4.38397461e+03 4.34626172e+03 4.34001270e+03 4.36256689e+03 4.23244629e+03 4.07642041e+03 4.14462500e+03 4.25161768e+03 4.04093506e+03 3.92360303e+03 3.94120483e+03 3.88875391e+03 3.91398022e+03 3.87324951e+03 3.76418994e+03 3.72838989e+03 3.72535767e+03 3.69831665e+03 3.65020312e+03 3.55980981e+03 3.57803149e+03 3.56660571e+03 3.39143286e+03 3.37475293e+03 3.37950610e+03 3.31137549e+03 3.33386133e+03 3.26183179e+03 3.18861523e+03 3.19884131e+03 3.09917896e+03 3.07935205e+03 3.14734619e+03 3.04879785e+03 2.95026611e+03 2.88961011e+03 2.83214062e+03 2.86735522e+03 2.86594775e+03 2.76888599e+03 2.73611035e+03 2.73638770e+03 2.69501514e+03 2.63992676e+03 2.55689380e+03 2.51606567e+03 2.51447144e+03 2.50298120e+03 2.47975000e+03 2.37643750e+03 2.32835571e+03 2.33942480e+03 2.31203320e+03 2.27866602e+03 2.24821069e+03 2.17625513e+03 2.13287378e+03 2.17795361e+03 2.14946436e+03 2.04533313e+03 1.97070703e+03 1.95197034e+03 1.95883948e+03 1.91805310e+03 1.85902869e+03 1.85387354e+03 1.83501880e+03 1.80128955e+03 1.78339417e+03 1.72768591e+03 1.67925208e+03 1.67481775e+03 1.65664734e+03 1.59611353e+03 1.53750293e+03 1.53222144e+03 1.51537756e+03 1.48152405e+03 1.47140527e+03 1.42356396e+03 1.37203711e+03 1.35397852e+03 1.36206030e+03 1.31614185e+03 1.26218445e+03 1.25431641e+03 1.22557532e+03 1.18708228e+03 1.17110144e+03 1.13116943e+03 1.10458301e+03 1.09167041e+03 1.07472705e+03 1.06177063e+03 1.01519019e+03 9.87100769e+02 9.66494202e+02 9.36687378e+02 9.10183228e+02 8.79209595e+02 8.70410217e+02 8.50535583e+02 8.18646301e+02 7.89068726e+02 7.69657349e+02 7.63911377e+02 7.48630371e+02 7.27474670e+02 6.93447693e+02 6.68182434e+02 6.47651306e+02 6.18854553e+02 6.06778870e+02 5.92798950e+02 5.72378235e+02 5.53354431e+02 5.27369324e+02 5.08032715e+02 4.98886200e+02 4.90076172e+02 4.73188202e+02 4.44324707e+02 4.20336761e+02 4.10127747e+02 3.96043915e+02 3.78021057e+02 3.66365509e+02 3.53647888e+02 3.32483978e+02 3.15879639e+02 3.00367676e+02 2.87535919e+02 2.84347992e+02 2.71357208e+02 2.50274399e+02 2.39716110e+02 2.25830154e+02 2.09154465e+02 2.04435699e+02 1.94709122e+02 1.78148315e+02 1.67802460e+02 1.57258682e+02 1.45867447e+02 1.39962738e+02 1.33859955e+02 1.21896545e+02 1.11720734e+02 1.03689171e+02 9.52797318e+01 8.78387299e+01 8.02071152e+01 7.31616364e+01 6.65361557e+01 5.95087852e+01 5.37289505e+01 4.85179672e+01 4.23895531e+01 3.76623573e+01 3.32836342e+01 2.80502129e+01 2.36124611e+01 1.99708176e+01 1.68463402e+01 1.39206038e+01 1.10345497e+01 8.24946880e+00 5.97234488e+00 4.30447197e+00 2.92876148e+00 1.78954196e+00 9.26859915e-01 4.28554296e-01 2.78211057e-01 4.66368884e-01 9.79722619e-01 1.82171428e+00 2.98438430e+00 4.46314383e+00 6.44403839e+00 8.55820370e+00 1.07326670e+01 1.39563131e+01 1.77454109e+01 2.07323837e+01 2.40274506e+01 2.83900661e+01 3.30620117e+01 3.83496437e+01 4.35495377e+01 4.86802788e+01 5.36589241e+01 6.01133842e+01 6.75344238e+01 7.39023743e+01 8.20740051e+01 8.94737015e+01 9.62076111e+01 1.03870003e+02 1.13815720e+02 1.22917175e+02 1.30217804e+02 1.41895844e+02 1.52703552e+02 1.59551163e+02 1.67405029e+02 1.78499023e+02 1.91630310e+02 2.08159286e+02 2.19430527e+02 2.25182159e+02 2.37183136e+02 2.50226028e+02 2.66286957e+02 2.83959961e+02 2.93713654e+02 3.01631622e+02 3.23734161e+02 3.39975098e+02 3.46402100e+02 3.72384705e+02 3.88703278e+02 3.93485962e+02 4.11915527e+02 4.22579926e+02 4.38574554e+02 4.72384918e+02 4.86764343e+02 4.96331573e+02 5.24133301e+02 5.37665344e+02 5.40662231e+02 5.63769653e+02 5.93433838e+02 6.12735474e+02 6.35627625e+02 6.49118530e+02 6.64447449e+02 6.95417358e+02 7.21421021e+02 7.63363892e+02 7.68963196e+02 7.58460632e+02 7.86201477e+02 8.19179016e+02 8.53828247e+02 8.86836853e+02 8.92062683e+02 8.94565491e+02 9.41637695e+02 9.80787598e+02 9.90110046e+02 1.01709271e+03 1.04312256e+03 1.05291675e+03 1.09661279e+03 1.12848853e+03 1.12874939e+03 1.18699268e+03 1.22807654e+03 1.22511755e+03 1.24633813e+03 1.24392761e+03 1.27485950e+03 1.34306079e+03 1.41833020e+03 1.42535986e+03 1.37649915e+03 1.41361792e+03 1.49750452e+03 1.51982178e+03 1.53330640e+03 1.57034155e+03 1.59666504e+03 1.63709045e+03 1.67016443e+03 1.70257202e+03 1.72841541e+03 1.75592944e+03 1.81845715e+03 1.82622485e+03 1.82718164e+03 1.86626233e+03 1.90830139e+03 1.96617883e+03 2.03661816e+03 2.02837610e+03 2.01752258e+03 2.07453320e+03 2.13120801e+03 2.22392041e+03 2.24095117e+03 2.18465063e+03 2.22903369e+03 2.30487451e+03 2.36911792e+03 2.44164136e+03 2.42942651e+03 2.42138062e+03 2.46113940e+03 2.48931665e+03 2.51314624e+03 2.61384009e+03 2.70519214e+03 2.68236035e+03 2.67445898e+03 2.68638574e+03 2.74331763e+03 2.88626343e+03 2.91519287e+03 2.91544507e+03 2.92264209e+03 2.91004663e+03 2.98615942e+03 3.04941748e+03 3.15341284e+03 3.21282471e+03 3.13699756e+03 3.16069751e+03 3.24053174e+03 3.31311401e+03 3.35022046e+03 3.42618823e+03 3.46418237e+03 3.42815063e+03 3.48411157e+03 3.54255029e+03 3.57729346e+03 3.64230054e+03 3.71646240e+03 3.73320947e+03 3.73261206e+03 3.75332764e+03 3.86006738e+03 3.96830396e+03 3.94630664e+03 3.93838477e+03 3.97225146e+03 4.04853809e+03 4.07729346e+03 4.23339990e+03 4.26246875e+03 4.18946729e+03 4.29134375e+03 4.32387988e+03 4.36739355e+03 4.50837158e+03 4.52081592e+03 4.51146826e+03 4.56991553e+03 4.64219531e+03 4.94920557e+03 4.58409521e+03 4.32072607e+03 6.58176416e+03 6.15834424e+03 1.09443848e+04 6.49086602e+04 3048284. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.20964238e+04 1.40728535e+04 8.65398340e+03 7.80856641e+03 7.77616016e+03 9.56677832e+03 7.95207227e+03 9.47220801e+03 7.19720605e+03 7.11045801e+03 7.79181934e+03 7.73808984e+03 7.59391504e+03 7.82085693e+03 7.99717529e+03 8.16190723e+03 8.03117871e+03 7.75604492e+03 7.94470996e+03 8.20320898e+03 8.12206836e+03 8.00286426e+03 7.98326270e+03 8.28726562e+03 8.73370020e+03 8.66849414e+03 8.24443164e+03 7.97312744e+03 8.24637402e+03 8.68080371e+03 8.94141406e+03 8.82761914e+03 8.47932617e+03 8.60293652e+03 8.78270898e+03 9.03145605e+03 9.03500488e+03 8.60219922e+03 8.72448340e+03 9.22777637e+03 9.16636816e+03 8.95641992e+03 9.10737793e+03 9.20776953e+03 9.36534863e+03 9.43320215e+03 9.13175586e+03 8.98861230e+03 9.47208203e+03 9.79164844e+03 9.67523828e+03 9.37752734e+03 9.16598047e+03 9.68322559e+03 1.01202109e+04 9.88353809e+03 9.58963184e+03 9.29829297e+03 9.55281738e+03 1.00893896e+04 1.03072793e+04 1.01864756e+04 9.98880957e+03 1.00831299e+04 9.99648438e+03 1.00736963e+04 1.01821445e+04 9.97840332e+03 1.01857578e+04 1.05396279e+04 1.04502812e+04 1.00532520e+04 1.00272500e+04 1.05481162e+04 1.09482441e+04 1.08315576e+04 1.04978057e+04 1.02519385e+04 1.03829248e+04 1.06804805e+04 1.11845020e+04 1.10472803e+04 1.04501953e+04 1.06631973e+04 1.08945586e+04 1.10414658e+04 1.12622334e+04 1.08539629e+04 1.09277334e+04 1.12387441e+04 1.12018525e+04 1.11072295e+04 1.10227158e+04 1.11930547e+04 1.14387441e+04 1.14433682e+04 1.11586143e+04 1.10958994e+04 1.14827324e+04 1.17226807e+04 1.17238818e+04 1.15723652e+04 1.12716758e+04 1.14345215e+04 1.18283447e+04 1.19545391e+04 1.17213018e+04 1.12902842e+04 1.13904209e+04 1.19997549e+04 1.23183633e+04 1.20167910e+04 1.15829395e+04 1.17140342e+04 1.21300430e+04 1.20759707e+04 1.18117734e+04 1.17634736e+04 1.22227676e+04 1.24099600e+04 1.21455635e+04 1.20035859e+04 1.18392119e+04 1.22283008e+04 1.28426348e+04 1.25352578e+04 1.21754648e+04 1.20832021e+04 1.22060928e+04 1.24610205e+04 1.26998086e+04 1.26100527e+04 1.20904561e+04 1.21835928e+04 1.27661572e+04 1.29306055e+04 1.26723223e+04 1.23859189e+04 1.26024766e+04 1.28906084e+04 1.29016006e+04 1.27046836e+04 1.23269316e+04 1.24487451e+04 1.30265752e+04 1.30911582e+04 1.28384512e+04 1.25475869e+04 1.27073105e+04 1.30531904e+04 1.33138037e+04 1.32905596e+04 1.26231875e+04 1.27540713e+04 1.31173174e+04 1.30800361e+04 1.31054160e+04 1.29741670e+04 1.30460488e+04 1.31684287e+04 1.31157480e+04 1.29857002e+04 1.29664023e+04 1.33295752e+04 1.35646035e+04 1.34164629e+04 1.29941826e+04 1.28650029e+04 1.33183281e+04 1.37839668e+04 1.37391602e+04 1.33039160e+04 1.29040840e+04 1.28410869e+04 1.33845078e+04 1.39457266e+04 1.36067451e+04 1.29501514e+04 1.31352461e+04 1.35911475e+04 1.36873906e+04 1.36686709e+04 1.34429434e+04 1.34392119e+04 1.34917305e+04 1.33559268e+04 1.33291250e+04 1.34857920e+04 1.36194775e+04 1.36098252e+04 1.36024248e+04 1.34574727e+04 1.33647021e+04 1.36771650e+04 1.38718613e+04 1.37994541e+04 1.33962832e+04 1.31498340e+04 1.37375449e+04 1.40252578e+04 1.38015674e+04 1.36308906e+04 1.32111572e+04 1.32118242e+04 1.38573818e+04 1.42895830e+04 1.39731641e+04 1.33318516e+04 1.33058389e+04 1.37439961e+04 1.39247363e+04 1.37993330e+04 1.37326875e+04 1.38413086e+04 1.36760371e+04 1.34818672e+04 1.32754277e+04 1.32003018e+04 1.35652852e+04 1.37536475e+04 1.41095811e+04 1.40570547e+04 1.32855879e+04 1.33974404e+04 1.36706211e+04 1.36902158e+04 1.38474971e+04 1.36270195e+04 1.39725527e+04 1.39463486e+04 1.32266943e+04 1.30545010e+04 1.33792910e+04 1.39959922e+04 1.44164531e+04 1.40515215e+04 1.32466104e+04 1.28950781e+04 1.31589844e+04 1.39488682e+04 1.43564238e+04 1.40094551e+04 1.32052705e+04 1.30702295e+04 1.40709219e+04 1.39977051e+04 1.32303311e+04 1.33054609e+04 1.34923662e+04 1.34598691e+04 1.38672666e+04 1.35509893e+04 1.30532559e+04 1.33799785e+04 1.31404756e+04 1.34381113e+04 1.38294395e+04 1.31314453e+04 1.33105176e+04 1.37822891e+04 1.34973438e+04 1.33201475e+04 1.33164102e+04 1.34115244e+04 1.33395918e+04 1.32870977e+04 1.29654561e+04 1.29123564e+04 1.35791504e+04 1.39499648e+04 1.35669824e+04 1.29116328e+04 1.26625850e+04 1.28680234e+04 1.33949453e+04 1.37973936e+04 1.34023955e+04 1.27655928e+04 1.28830605e+04 1.32877637e+04 1.30774756e+04 1.29076221e+04 1.29926572e+04 1.28581992e+04 1.27976484e+04 1.33630547e+04 1.31407432e+04 1.25889082e+04 1.27626680e+04 1.25338018e+04 1.29168926e+04 1.32118223e+04 1.26584902e+04 1.30068564e+04 1.29049648e+04 1.23479746e+04 1.26784385e+04 1.23093262e+04 1.25375732e+04 1.33803867e+04 1.26266152e+04 1.19792627e+04 1.21817422e+04 1.27236123e+04 1.31871602e+04 1.29139473e+04 1.20906006e+04 1.17236553e+04 1.20956641e+04 1.25928857e+04 1.30341631e+04 1.26589277e+04 1.18821289e+04 1.18659883e+04 1.22590674e+04 1.23888213e+04 1.20828525e+04 1.19356133e+04 1.20347881e+04 1.20383535e+04 1.24084531e+04 1.23334678e+04 1.16692090e+04 1.16187266e+04 1.18237998e+04 1.18123496e+04 1.19038994e+04 1.18254160e+04 1.20752588e+04 1.18379033e+04 1.13531523e+04 1.15330615e+04 1.12709736e+04 1.16021904e+04 1.23317246e+04 1.15498301e+04 1.08134258e+04 1.10920947e+04 1.16435068e+04 1.19455967e+04 1.18741846e+04 1.11686201e+04 1.07349980e+04 1.09071328e+04 1.13193506e+04 1.17807939e+04 1.15317871e+04 1.07615156e+04 1.05959570e+04 1.09994111e+04 1.10522920e+04 1.12759053e+04 1.12428730e+04 1.05320986e+04 1.04947539e+04 1.09541201e+04 1.10204326e+04 1.06724316e+04 1.05764287e+04 1.05491240e+04 1.03967822e+04 1.08354990e+04 1.07938398e+04 1.02967900e+04 1.01500264e+04 1.02553896e+04 1.03294014e+04 1.02754209e+04 1.01452236e+04 1.04313574e+04 1.04916738e+04 1.01164395e+04 9.85617090e+03 9.57850781e+03 9.92108984e+03 1.05140918e+04 1.02495605e+04 9.63562891e+03 9.36716797e+03 9.70284668e+03 1.02113447e+04 9.80455078e+03 9.22261621e+03 9.34228223e+03 9.56854785e+03 9.75737793e+03 1.00651592e+04 9.68569629e+03 9.14807910e+03 8.95617090e+03 9.17628320e+03 9.41676172e+03 9.42735547e+03 9.26106641e+03 9.07786328e+03 8.98335059e+03 9.18224316e+03 9.09364941e+03 8.77291992e+03 8.69687891e+03 8.65132715e+03 9.06159668e+03 9.03562012e+03 8.67860645e+03 8.68539941e+03 8.71074023e+03 8.82026758e+03 8.48324512e+03 8.04136572e+03 8.44294824e+03 8.82520020e+03 8.52382617e+03 8.06454590e+03 8.10310742e+03 8.47172070e+03 8.37998730e+03 8.15948975e+03 8.11447314e+03 7.80897168e+03 7.80029590e+03 8.15304492e+03 8.04430176e+03 7.69736963e+03 7.46244531e+03 7.42454932e+03 7.74570557e+03 8.07292969e+03 7.64839209e+03 7.36949512e+03 7.54353613e+03 7.42794434e+03 7.64701758e+03 7.53250146e+03 7.10573779e+03 7.04916309e+03 7.21665479e+03 7.18222998e+03 7.15252197e+03 7.08093848e+03 7.18750439e+03 7.27992432e+03 7.36661865e+03 7.12799609e+03 6.49427344e+03 7.11343164e+03 9.39658105e+03 9.30604590e+03 1.01133066e+04 9.23128320e+03 9.77468262e+03 1.12808613e+04 1.67560508e+04 1.91163379e+04 -7034017. -50936644. -2.05908050e+06 6.71785150e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.24761172e+04 9.80944629e+03 6.84297363e+03 6.90791455e+03 6.21127637e+03 6.18484814e+03 6.09083057e+03 5.90987354e+03 5.85180420e+03 5.77575586e+03 4.07431909e+03 4.40098779e+03 3.96621582e+03 3.74812744e+03 3.65320874e+03 3.53402051e+03 3.60300073e+03 3.57856592e+03 3.39391382e+03 3.33859937e+03 3.46204053e+03 3.44423291e+03 3.31065430e+03 3.25030103e+03 3.21944141e+03 3.19455103e+03 3.13692212e+03 3.08653638e+03 3.04837256e+03 3.00702271e+03 2.93499878e+03 2.89110449e+03 2.93846460e+03 2.91323022e+03 2.81125220e+03 2.77181152e+03 2.74397632e+03 2.71482910e+03 2.66127393e+03 2.61816870e+03 2.59122607e+03 2.49088721e+03 2.44124146e+03 2.46133130e+03 2.42156494e+03 2.48023901e+03 2.45712085e+03 2.32944458e+03 2.22934253e+03 2.18632642e+03 2.29126245e+03 2.26974341e+03 2.15414478e+03 2.07686084e+03 2.05396362e+03 2.04271985e+03 1.99204077e+03 2.03433521e+03 1.99773254e+03 1.85300220e+03 1.80954004e+03 1.86616699e+03 1.90353064e+03 1.82508691e+03 1.75807434e+03 1.72641235e+03 1.68565747e+03 1.63715588e+03 1.62006311e+03 1.59180481e+03 1.55122290e+03 1.52376794e+03 1.49639819e+03 1.48126660e+03 1.44882031e+03 1.44953748e+03 1.41050500e+03 1.34345044e+03 1.33687170e+03 1.31088110e+03 1.28613196e+03 1.26482690e+03 1.22544275e+03 1.19483630e+03 1.14599744e+03 1.09314563e+03 1.12005432e+03 1.10964331e+03 1.02854456e+03 1.00992566e+03 1.04270020e+03 1.04310706e+03 9.86596863e+02 9.38562561e+02 9.09700195e+02 8.85973206e+02 8.56091736e+02 8.29659180e+02 8.25453003e+02 7.98778992e+02 7.94982422e+02 7.66570496e+02 7.24724060e+02 7.15556519e+02 6.77024841e+02 6.59760376e+02 6.72585144e+02 6.46354675e+02 6.10923767e+02 5.78151611e+02 5.51863220e+02 5.61632629e+02 5.54192871e+02 5.19010681e+02 4.85053619e+02 4.67646606e+02 4.61296448e+02 4.43686432e+02 4.40969879e+02 4.27291168e+02 3.96460510e+02 3.72668518e+02 3.57455933e+02 3.56929688e+02 3.43239471e+02 3.20292450e+02 3.01806427e+02 2.88160339e+02 2.78698181e+02 2.57775574e+02 2.45949783e+02 2.48162094e+02 2.33415253e+02 2.14538101e+02 1.97673187e+02 1.86034225e+02 1.85773346e+02 1.75706299e+02 1.60233200e+02 1.45541504e+02 1.35165863e+02 1.30374237e+02 1.21000473e+02 1.12251808e+02 1.01244125e+02 9.50599136e+01 9.19752350e+01 8.19844589e+01 7.41756744e+01 6.76561432e+01 6.04378777e+01 5.34862976e+01 4.77936172e+01 4.29521294e+01 3.76923141e+01 3.26727333e+01 2.73256016e+01 2.37504120e+01 2.12856102e+01 1.69087334e+01 1.32989435e+01 1.08177271e+01 8.31978607e+00 6.39472437e+00 4.43428946e+00 2.83165026e+00 1.78481030e+00 9.49282229e-01 4.40542817e-01 2.77663291e-01 4.51560080e-01 9.60475445e-01 1.80585957e+00 2.97337532e+00 4.35928059e+00 6.31470680e+00 8.93741894e+00 1.13176136e+01 1.37557230e+01 1.63888969e+01 2.00545750e+01 2.52571316e+01 2.94153595e+01 3.31970749e+01 3.70773277e+01 4.17046814e+01 4.84936333e+01 5.44297752e+01 6.19102516e+01 6.70066147e+01 7.18276901e+01 8.13903427e+01 8.85723267e+01 9.83986816e+01 1.06249786e+02 1.11891205e+02 1.20679619e+02 1.29476318e+02 1.41025757e+02 1.46966049e+02 1.58450653e+02 1.78098068e+02 1.86005295e+02 1.92195358e+02 1.98259018e+02 2.08812622e+02 2.33359146e+02 2.47218262e+02 2.52471954e+02 2.58710693e+02 2.71256592e+02 2.93253174e+02 3.08353394e+02 3.30249512e+02 3.40124390e+02 3.46680939e+02 3.58369324e+02 3.71773987e+02 4.07401794e+02 4.23334015e+02 4.27018951e+02 4.40074158e+02 4.57275452e+02 4.89989227e+02 5.08820038e+02 5.04391266e+02 5.20542053e+02 5.68379883e+02 5.87872253e+02 5.77543701e+02 5.93613831e+02 6.46351440e+02 6.70554138e+02 6.69216187e+02 6.73597717e+02 6.94574341e+02 7.58522705e+02 7.74609009e+02 7.71767090e+02 7.97435303e+02 8.18346191e+02 8.44740295e+02 8.62807068e+02 8.85169678e+02 8.88603943e+02 9.34594482e+02 1.01405518e+03 1.00647003e+03 1.01899707e+03 1.05384595e+03 1.06835388e+03 1.09348047e+03 1.11982568e+03 1.14351355e+03 1.14029333e+03 1.14805151e+03 1.20915820e+03 1.26729907e+03 1.32934875e+03 1.30988513e+03 1.29039258e+03 1.35726599e+03 1.40193945e+03 1.47655444e+03 1.48083313e+03 1.46340796e+03 1.48924268e+03 1.50446313e+03 1.56782654e+03 1.60856445e+03 1.67026245e+03 1.69051953e+03 1.68701343e+03 1.70111621e+03 1.67991919e+03 1.78102722e+03 1.92177893e+03 1.91469592e+03 1.89172656e+03 1.87779272e+03 1.88027026e+03 2.01214343e+03 2.10714771e+03 2.07618701e+03 2.03731885e+03 2.06258691e+03 2.15926440e+03 2.18996240e+03 2.28866138e+03 2.31286157e+03 2.27830688e+03 2.33163306e+03 2.35862671e+03 2.44218848e+03 2.47363428e+03 2.40856665e+03 2.45717798e+03 2.62595093e+03 2.61376440e+03 2.52299146e+03 2.63972949e+03 2.82499731e+03 2.81556689e+03 2.78318408e+03 2.75360303e+03 2.78628271e+03 2.99052075e+03 3.02968237e+03 2.97684106e+03 2.93470020e+03 2.96851807e+03 3.09722412e+03 3.13677979e+03 3.17279712e+03 3.14055005e+03 3.24261816e+03 3.42616504e+03 3.37232080e+03 3.43639062e+03 3.44413135e+03 3.41738184e+03 3.50515674e+03 3.56315479e+03 3.59760791e+03 3.62377563e+03 3.63470532e+03 3.59165771e+03 3.73130664e+03 4.00106787e+03 3.85071680e+03 3.71712769e+03 3.88877881e+03 4.00370898e+03 4.18207275e+03 4.14172803e+03 4.07109351e+03 4.21641260e+03 4.23259277e+03 4.12790283e+03 4.13211572e+03 4.42263623e+03 4.48047021e+03 4.38925635e+03 4.37875732e+03 4.26171484e+03 4.51280469e+03 4.84620020e+03 4.74232324e+03 4.66802637e+03 4.58967725e+03 4.58629932e+03 4.90697363e+03 5.09758301e+03 4.99951318e+03 4.84073145e+03 4.82724512e+03 4.99114600e+03 5.10838574e+03 5.30038379e+03 5.24687939e+03 5.13927197e+03 5.29904248e+03 5.31648340e+03 5.45952197e+03 5.47574707e+03 5.41456104e+03 5.51686328e+03 5.53441260e+03 5.56195654e+03 5.45689697e+03 5.60002100e+03 6.03471680e+03 5.93852393e+03 5.75326025e+03 5.68350537e+03 5.77841699e+03 6.20318896e+03 6.19941602e+03 6.10401807e+03 5.98256934e+03 6.01039941e+03 6.23511523e+03 6.29265967e+03 6.32528711e+03 6.23721777e+03 6.39884766e+03 6.68751709e+03 6.57541895e+03 6.67138232e+03 6.72714893e+03 6.65393994e+03 6.64200586e+03 6.70598633e+03 6.73760791e+03 6.77066504e+03 6.88000293e+03 6.93194629e+03 7.14757568e+03 7.15645850e+03 6.88056055e+03 6.85255322e+03 7.09481006e+03 7.29860547e+03 7.57290674e+03 7.36137695e+03 7.11580859e+03 7.47692334e+03 7.70683350e+03 7.57443408e+03 7.45556445e+03 7.47042236e+03 7.63365332e+03 7.72800635e+03 7.70555859e+03 7.51284814e+03 7.77161035e+03 8.30071973e+03 8.06602881e+03 8.03512158e+03 7.87827588e+03 7.82329004e+03 8.37796094e+03 8.37730078e+03 8.22563965e+03 8.06177295e+03 7.92345361e+03 8.24482129e+03 8.50753613e+03 8.83979688e+03 8.51991504e+03 8.16499951e+03 8.52222070e+03 8.65124219e+03 9.00140039e+03 8.87066016e+03 8.59157617e+03 8.88539258e+03 8.94226172e+03 8.78104785e+03 8.59140137e+03 8.96545605e+03 9.43865039e+03 9.32080273e+03 9.15542578e+03 8.99175781e+03 9.03042578e+03 9.52884961e+03 9.55273535e+03 9.34197852e+03 9.19815430e+03 9.11582520e+03 9.44955176e+03 9.54390625e+03 9.81598633e+03 9.92248828e+03 9.63157422e+03 9.43713379e+03 9.58786328e+03 1.01455117e+04 9.98573145e+03 9.71907520e+03 9.97525684e+03 9.99690332e+03 9.85935840e+03 9.78938672e+03 1.01908984e+04 1.02482197e+04 1.00060029e+04 1.04300137e+04 1.05717207e+04 1.03712705e+04 1.03190625e+04 1.03886562e+04 1.04506748e+04 1.02210605e+04 1.01370615e+04 1.06964131e+04 1.09034287e+04 1.03962227e+04 1.00965215e+04 1.06168154e+04 1.13321338e+04 1.11919150e+04 1.06104043e+04 1.04651055e+04 1.10702979e+04 1.12790273e+04 1.10180010e+04 1.10794473e+04 1.08883945e+04 1.05635205e+04 1.10054248e+04 1.15816504e+04 1.15461992e+04 1.11151055e+04 1.08629355e+04 1.14347139e+04 1.18276982e+04 1.15577002e+04 1.11026973e+04 1.09921494e+04 1.13915645e+04 1.15145791e+04 1.18309238e+04 1.18040625e+04 1.14406055e+04 1.16243076e+04 1.17435801e+04 1.19489795e+04 1.16300391e+04 1.14617490e+04 1.20077451e+04 1.19942461e+04 1.18707197e+04 1.16178174e+04 1.17964014e+04 1.24821133e+04 1.19885977e+04 1.15864541e+04 1.19325898e+04 1.22050273e+04 1.22694932e+04 1.21939990e+04 1.24670938e+04 1.26370518e+04 1.22755918e+04 1.19404111e+04 1.19781094e+04 1.26113164e+04 1.24039102e+04 1.20775664e+04 1.25650459e+04 1.26047139e+04 1.24178701e+04 1.23363213e+04 1.27387236e+04 1.26925244e+04 1.23433262e+04 1.26960547e+04 1.27649570e+04 1.28292129e+04 1.28631367e+04 1.27547930e+04 1.26660518e+04 1.23523418e+04 1.23204590e+04 1.29712412e+04 1.34814883e+04 1.27999844e+04 1.21839678e+04 1.27512949e+04 1.35202422e+04 1.34569404e+04 1.28527578e+04 1.24115693e+04 1.30075479e+04 1.33862744e+04 1.30277578e+04 1.33206406e+04 1.32682686e+04 1.27613359e+04 1.29096221e+04 1.34041299e+04 1.35146113e+04 1.29662471e+04 1.26491992e+04 1.32823701e+04 1.38041611e+04 1.34365654e+04 1.29445273e+04 1.27742578e+04 1.34255107e+04 1.38157656e+04 1.33551875e+04 1.31009961e+04 1.31794072e+04 1.33578096e+04 1.33543389e+04 1.37570596e+04 1.35267363e+04 1.30306562e+04 1.35084453e+04 1.36318359e+04 1.36832285e+04 1.34085723e+04 1.31613135e+04 1.36756592e+04 1.33916016e+04 1.33395000e+04 1.41687705e+04 1.38782959e+04 1.39129473e+04 1.38129619e+04 1.80744277e+04 2.00345352e+04 1.85066973e+04 1.96517422e+04 1.95486680e+04 1.22852559e+04 1.79531035e+04 9.07938438e+04 2.83856113e+04 8.38194944e+09 1.91129594e+05 -8.55866500e+05 -5.74428211e+09 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. 7.91520512e+09 1.60519312e+05 4.24728672e+04 2.69814492e+04 2.15475664e+04 1.90663320e+04 1.70815859e+04 1.32677236e+04 1.29736191e+04 1.23603574e+04 1.27595342e+04 1.42765156e+04 1.59326611e+04 1.31506152e+04 1.27480332e+04 1.39387471e+04 1.28824854e+04 1.28951592e+04 1.41918086e+04 1.40147988e+04 1.34055273e+04 1.36606475e+04 1.36598838e+04 1.32154717e+04 1.32731904e+04 1.36191709e+04 1.36881533e+04 1.36823135e+04 1.33304463e+04 1.30564570e+04 1.33361787e+04 1.34578467e+04 1.33216611e+04 1.31510996e+04 1.31233525e+04 1.34302217e+04 1.34105996e+04 1.32042275e+04 1.31113994e+04 1.30854414e+04 1.35556426e+04 1.36111592e+04 1.29141260e+04 1.28115039e+04 1.30775664e+04 1.31273887e+04 1.32927461e+04 1.31797480e+04 1.28683125e+04 1.30238359e+04 1.30951436e+04 1.30484258e+04 1.30656289e+04 1.28399424e+04 1.28901758e+04 1.29948174e+04 1.28698291e+04 1.27861572e+04 1.27069307e+04 1.27178916e+04 1.29450791e+04 1.29927520e+04 1.28520107e+04 1.25342119e+04 1.24717236e+04 1.28294883e+04 1.27975713e+04 1.24504160e+04 1.25399141e+04 1.25956641e+04 1.25708008e+04 1.27308750e+04 1.26745537e+04 1.23429551e+04 1.22538008e+04 1.25754082e+04 1.26575146e+04 1.23055781e+04 1.20446025e+04 1.21402217e+04 1.22594512e+04 1.25244160e+04 1.24960586e+04 1.20244766e+04 1.20254141e+04 1.23295840e+04 1.22965273e+04 1.21286162e+04 1.18407871e+04 1.17422773e+04 1.21161543e+04 1.21988906e+04 1.18437227e+04 1.18248818e+04 1.18657119e+04 1.18384609e+04 1.17809551e+04 1.16982314e+04 1.17462139e+04 1.17582637e+04 1.18746484e+04 1.17865703e+04 1.13798584e+04 1.13777812e+04 1.16184551e+04 1.14444521e+04 1.14177803e+04 1.14001104e+04 1.13223105e+04 1.15289814e+04 1.13383643e+04 1.11698232e+04 1.13703486e+04 1.13712178e+04 1.10948154e+04 1.10016201e+04 1.10692021e+04 1.10836914e+04 1.10177734e+04 1.08727734e+04 1.08400010e+04 1.08914795e+04 1.11039424e+04 1.09890625e+04 1.05418447e+04 1.06138135e+04 1.08488408e+04 1.07771758e+04 1.06138369e+04 1.04292451e+04 1.03211582e+04 1.05283232e+04 1.07126211e+04 1.05103125e+04 1.02067188e+04 1.02159453e+04 1.04384141e+04 1.04579717e+04 1.04171748e+04 1.01321006e+04 9.88251367e+03 9.99268652e+03 1.00115762e+04 9.94273926e+03 1.00160322e+04 9.85372852e+03 9.88856738e+03 1.00787178e+04 9.87695117e+03 9.48089355e+03 9.56274121e+03 9.73531641e+03 9.71831641e+03 9.73418945e+03 9.58009961e+03 9.34651562e+03 9.40452344e+03 9.65628711e+03 9.39175586e+03 8.96139160e+03 9.14922363e+03 9.37731836e+03 9.30669727e+03 9.09479199e+03 8.89957812e+03 8.88393164e+03 9.02657715e+03 8.94518750e+03 8.92020996e+03 8.94487109e+03 8.68597754e+03 8.71814551e+03 8.88928027e+03 8.65337598e+03 8.50038867e+03 8.49674902e+03 8.58039355e+03 8.60404785e+03 8.53591504e+03 8.25006445e+03 8.09177686e+03 8.28170117e+03 8.53758008e+03 8.52899512e+03 7.97483105e+03 7.91342969e+03 8.27692090e+03 8.08149561e+03 7.94418262e+03 7.85639941e+03 7.71655566e+03 7.79813428e+03 7.84591650e+03 7.79275830e+03 7.60337207e+03 7.51846924e+03 7.57526074e+03 7.67481055e+03 7.58463721e+03 7.42985107e+03 7.35423047e+03 7.39899951e+03 7.32676318e+03 7.13287012e+03 7.16415576e+03 7.18003223e+03 7.02012402e+03 7.14763818e+03 7.27476562e+03 6.84207764e+03 6.81863281e+03 6.97604785e+03 6.88419434e+03 6.84000244e+03 6.61477930e+03 6.61324902e+03 6.75926514e+03 6.70793652e+03 6.58251562e+03 6.35569775e+03 6.25001123e+03 6.39693555e+03 6.46930420e+03 6.33917725e+03 6.21990771e+03 6.26870752e+03 6.20383008e+03 6.24506396e+03 6.12863379e+03 5.94390332e+03 5.86638770e+03 5.87253760e+03 5.99454150e+03 5.85247217e+03 5.70456201e+03 5.71603857e+03 5.76981543e+03 5.72963770e+03 5.63524023e+03 5.49859131e+03 5.46513135e+03 5.50713770e+03 5.40581201e+03 5.48043896e+03 5.33970264e+03 5.20349658e+03 5.27266504e+03 5.09229492e+03 5.09231299e+03 5.19912891e+03 5.02612695e+03 4.95261865e+03 4.92787012e+03 4.92912598e+03 4.80947559e+03 4.71247705e+03 4.85934814e+03 4.89542383e+03 4.59592822e+03 4.55489453e+03 4.56303467e+03 4.52016211e+03 4.58432471e+03 4.49160059e+03 4.33163037e+03 4.33176367e+03 4.37424902e+03 4.31747168e+03 4.24781006e+03 4.12436621e+03 4.13101367e+03 4.14344824e+03 4.03040161e+03 3.99633569e+03 3.92111987e+03 3.87378027e+03 3.88728638e+03 3.88160742e+03 3.81023120e+03 3.71028467e+03 3.65693579e+03 3.71565942e+03 3.72576807e+03 3.55349146e+03 3.54515942e+03 3.52424780e+03 3.38365356e+03 3.41693237e+03 3.40139819e+03 3.27730737e+03 3.30266357e+03 3.27713745e+03 3.21685596e+03 3.24754590e+03 3.13126660e+03 3.05063306e+03 3.04799976e+03 3.03730200e+03 3.00720288e+03 2.88598608e+03 2.84746875e+03 2.86738477e+03 2.83935522e+03 2.80763550e+03 2.74415625e+03 2.66500903e+03 2.68449780e+03 2.71219165e+03 2.59635913e+03 2.50201636e+03 2.48028516e+03 2.52210352e+03 2.50924365e+03 2.38629956e+03 2.33970508e+03 2.32657275e+03 2.29647388e+03 2.25892017e+03 2.24470825e+03 2.19195776e+03 2.12783691e+03 2.12934180e+03 2.14307764e+03 2.06516626e+03 1.95553589e+03 1.95437903e+03 1.96706421e+03 1.93022400e+03 1.89513623e+03 1.84166760e+03 1.79981592e+03 1.81823950e+03 1.81025671e+03 1.73159851e+03 1.67169897e+03 1.65463367e+03 1.66549878e+03 1.62140991e+03 1.53394141e+03 1.50977002e+03 1.50906287e+03 1.48443750e+03 1.45818115e+03 1.44171680e+03 1.38238403e+03 1.36043335e+03 1.33517908e+03 1.28247632e+03 1.25769556e+03 1.24160938e+03 1.22739185e+03 1.20952441e+03 1.16634814e+03 1.11763110e+03 1.09924463e+03 1.10123389e+03 1.10415442e+03 1.06916162e+03 9.96012512e+02 9.72992554e+02 9.70183167e+02 9.41463684e+02 9.07929260e+02 8.85965820e+02 8.68623596e+02 8.49725769e+02 8.21028625e+02 7.80232422e+02 7.73352356e+02 7.70331055e+02 7.49679504e+02 7.16943726e+02 6.78645752e+02 6.64951294e+02 6.45082703e+02 6.20921082e+02 6.19195496e+02 5.98513611e+02 5.62365173e+02 5.44939697e+02 5.31934875e+02 5.25221619e+02 5.06022919e+02 4.80951752e+02 4.62441010e+02 4.43648071e+02 4.24917664e+02 4.05287537e+02 3.95576874e+02 3.81877380e+02 3.69698975e+02 3.52659149e+02 3.24933807e+02 3.15756958e+02 3.03952881e+02 2.90587250e+02 2.85024963e+02 2.63406342e+02 2.45292877e+02 2.41662430e+02 2.32218323e+02 2.15159439e+02 2.01799789e+02 1.88754501e+02 1.76527405e+02 1.68064316e+02 1.59137207e+02 1.48230469e+02 1.41117996e+02 1.32759964e+02 1.21475639e+02 1.11425102e+02 1.01778793e+02 9.55293198e+01 8.93941345e+01 8.07059479e+01 7.18063812e+01 6.51457977e+01 5.95896530e+01 5.42616577e+01 4.96350746e+01 4.26941338e+01 3.65674896e+01 3.24762001e+01 2.78941479e+01 2.36510830e+01 2.04149342e+01 1.67611599e+01 1.33076115e+01 1.07184563e+01 8.17735481e+00 6.00332785e+00 4.24230003e+00 2.74127364e+00 1.57135940e+00 7.44381189e-01 2.62568355e-01 1.11528188e-01 2.94799566e-01 8.19398344e-01 1.66735137e+00 2.84708405e+00 4.27751589e+00 6.17441416e+00 8.38093472e+00 1.08246346e+01 1.39287462e+01 1.70937786e+01 2.02715416e+01 2.41275139e+01 2.84302368e+01 3.36309853e+01 3.87804451e+01 4.29313774e+01 4.78209267e+01 5.33941345e+01 6.01111031e+01 6.71395340e+01 7.41681595e+01 8.16286469e+01 8.86343765e+01 9.57650986e+01 1.03002670e+02 1.12808022e+02 1.24566124e+02 1.32796310e+02 1.39367020e+02 1.48499237e+02 1.58298004e+02 1.69032700e+02 1.82721222e+02 1.95242950e+02 2.04470871e+02 2.14730774e+02 2.25220764e+02 2.38358887e+02 2.54896286e+02 2.67014465e+02 2.80889709e+02 2.94292145e+02 3.03936707e+02 3.22894470e+02 3.33208466e+02 3.46366547e+02 3.73375580e+02 3.83020935e+02 3.92377716e+02 4.13351318e+02 4.25984711e+02 4.41139160e+02 4.77340240e+02 4.93344452e+02 4.88198120e+02 5.10402527e+02 5.33709167e+02 5.49429138e+02 5.81502563e+02 5.97467407e+02 5.98733704e+02 6.25071106e+02 6.52148132e+02 6.81846924e+02 7.06955139e+02 7.15544434e+02 7.44071167e+02 7.55220154e+02 7.57140259e+02 7.91457336e+02 8.33948486e+02 8.52760437e+02 8.80495972e+02 8.98244629e+02 8.85979675e+02 9.28142029e+02 9.95630981e+02 1.01719281e+03 1.01442664e+03 1.01485303e+03 1.04765344e+03 1.10911597e+03 1.13876965e+03 1.14445093e+03 1.17880042e+03 1.19440210e+03 1.22253967e+03 1.26029968e+03 1.25383264e+03 1.28927856e+03 1.35281592e+03 1.39426904e+03 1.39928516e+03 1.38672302e+03 1.41998645e+03 1.49041833e+03 1.54466333e+03 1.55420142e+03 1.55159180e+03 1.56400439e+03 1.62399866e+03 1.68584033e+03 1.74519116e+03 1.74927185e+03 1.73211609e+03 1.78884375e+03 1.81678784e+03 1.83733435e+03 1.89901477e+03 1.92292542e+03 1.95938672e+03 2.02417920e+03 2.01844092e+03 2.04557642e+03 2.10241577e+03 2.13902075e+03 2.18385840e+03 2.19199146e+03 2.18687817e+03 2.23109448e+03 2.31754004e+03 2.39572437e+03 2.43189795e+03 2.40898364e+03 2.39811792e+03 2.46088940e+03 2.49229590e+03 2.56015967e+03 2.62901636e+03 2.63065991e+03 2.62645581e+03 2.66648462e+03 2.71986890e+03 2.80334644e+03 2.90145410e+03 2.90542773e+03 2.88847363e+03 2.90200586e+03 2.88995557e+03 2.98313892e+03 3.07775635e+03 3.14504102e+03 3.18655884e+03 3.13721973e+03 3.14189648e+03 3.25347778e+03 3.34413745e+03 3.34073389e+03 3.40062158e+03 3.40547217e+03 3.38695532e+03 3.52328784e+03 3.63142505e+03 3.62802271e+03 3.58872705e+03 3.64055981e+03 3.72240723e+03 3.78041284e+03 3.82288867e+03 3.85291724e+03 3.93296143e+03 3.92569189e+03 3.91008521e+03 4.07063672e+03 4.10917139e+03 4.08864160e+03 4.21483496e+03 4.15513135e+03 4.13622754e+03 4.33004883e+03 4.39541602e+03 4.40933398e+03 4.59377881e+03 4.66365137e+03 4.28121875e+03 4.07962451e+03 4.91337598e+03 5.70949072e+03 6.09845459e+03 5.50582373e+03 1.17802168e+04 1.14573955e+04 -52843072. 105425464. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -59475064. 1.86131262e+06 2.46392148e+04 1.83145859e+04 1.19227783e+04 1.16893857e+04 1.13643682e+04 1.04101836e+04 1.09810859e+04 1.00286318e+04 9.42259277e+03 7.59490869e+03 7.49164014e+03 9.67094727e+03 7.93708984e+03 9.87881152e+03 7.12355713e+03 7.14154834e+03 7.90739160e+03 7.72112549e+03 7.43208350e+03 7.74323877e+03 8.02678223e+03 8.14063330e+03 8.20456836e+03 7.94641797e+03 7.89291553e+03 8.04079688e+03 8.08600146e+03 8.15278174e+03 8.09798291e+03 8.12180371e+03 8.43105762e+03 8.71506738e+03 8.52191602e+03 8.18005029e+03 8.25400488e+03 8.64519238e+03 8.75518555e+03 8.58980176e+03 8.41989746e+03 8.56174414e+03 8.92099707e+03 9.12479492e+03 8.97709570e+03 8.60210645e+03 8.79541406e+03 9.16924512e+03 9.13060254e+03 9.22921973e+03 9.12855371e+03 8.84379980e+03 9.08528125e+03 9.53861230e+03 9.35999316e+03 9.18881348e+03 9.48537207e+03 9.57109180e+03 9.53939648e+03 9.47488867e+03 9.19952832e+03 9.50510449e+03 1.00983281e+04 9.88033887e+03 9.56675098e+03 9.54282422e+03 9.57311816e+03 1.00717354e+04 1.03988594e+04 1.01200889e+04 9.83132715e+03 9.84217773e+03 9.84261719e+03 1.01537305e+04 1.05250566e+04 1.01964072e+04 1.00748115e+04 1.03563037e+04 1.03467861e+04 1.02283223e+04 1.02488809e+04 1.04728057e+04 1.06967295e+04 1.07154482e+04 1.06798555e+04 1.03981426e+04 1.02761357e+04 1.08482617e+04 1.12146885e+04 1.06707188e+04 1.03759785e+04 1.06938281e+04 1.10327959e+04 1.12243906e+04 1.13204590e+04 1.09392354e+04 1.08061943e+04 1.10869014e+04 1.11568818e+04 1.13080459e+04 1.12195596e+04 1.09867002e+04 1.10797041e+04 1.14056045e+04 1.15089570e+04 1.14365547e+04 1.14590117e+04 1.14938945e+04 1.15732949e+04 1.16317129e+04 1.12931904e+04 1.12618906e+04 1.19254912e+04 1.20439141e+04 1.14652529e+04 1.13099863e+04 1.15235684e+04 1.20939482e+04 1.23988916e+04 1.19848945e+04 1.15733545e+04 1.16164141e+04 1.18156230e+04 1.20408428e+04 1.21350859e+04 1.20796914e+04 1.21145039e+04 1.20784639e+04 1.21498184e+04 1.22300566e+04 1.19475020e+04 1.21861309e+04 1.26837744e+04 1.24675117e+04 1.22373496e+04 1.21778652e+04 1.20568945e+04 1.25655586e+04 1.28902500e+04 1.23616309e+04 1.20735156e+04 1.23345518e+04 1.28663691e+04 1.30597109e+04 1.27214180e+04 1.24154111e+04 1.23758311e+04 1.25132998e+04 1.28766680e+04 1.30430771e+04 1.25959043e+04 1.22856016e+04 1.27209854e+04 1.31979395e+04 1.30761006e+04 1.27993613e+04 1.28454521e+04 1.28827393e+04 1.29820156e+04 1.30971777e+04 1.27355693e+04 1.27254404e+04 1.31484824e+04 1.31830830e+04 1.30434883e+04 1.28699756e+04 1.29410430e+04 1.31984990e+04 1.32363047e+04 1.32865195e+04 1.30332520e+04 1.30908057e+04 1.33866953e+04 1.33147520e+04 1.31933496e+04 1.30725762e+04 1.30497197e+04 1.34370068e+04 1.38208701e+04 1.35407861e+04 1.29289824e+04 1.28984492e+04 1.35436709e+04 1.38019414e+04 1.36332051e+04 1.31174463e+04 1.29915938e+04 1.34180527e+04 1.36232920e+04 1.37103057e+04 1.33683467e+04 1.31282471e+04 1.33768975e+04 1.36489775e+04 1.37910400e+04 1.35939932e+04 1.33945596e+04 1.34937344e+04 1.35720371e+04 1.35910840e+04 1.35685811e+04 1.36462852e+04 1.35249365e+04 1.34153271e+04 1.33607646e+04 1.32843809e+04 1.37757734e+04 1.42444531e+04 1.40331016e+04 1.35352861e+04 1.30843936e+04 1.32235938e+04 1.40400117e+04 1.43858604e+04 1.39293174e+04 1.33692832e+04 1.31247471e+04 1.34714404e+04 1.40214111e+04 1.40523740e+04 1.38094346e+04 1.36813223e+04 1.35806436e+04 1.35497432e+04 1.32883418e+04 1.32921963e+04 1.36435264e+04 1.37170869e+04 1.41587998e+04 1.39627803e+04 1.30744463e+04 1.32675664e+04 1.37847090e+04 1.38617139e+04 1.38231592e+04 1.36204600e+04 1.39516201e+04 1.40365391e+04 1.34046699e+04 1.29953779e+04 1.32807471e+04 1.39411514e+04 1.43544473e+04 1.40746309e+04 1.33090361e+04 1.29766816e+04 1.31749121e+04 1.38389775e+04 1.42907373e+04 1.40323408e+04 1.32968857e+04 1.31323936e+04 1.39723516e+04 1.38951689e+04 1.32575176e+04 1.33730762e+04 1.34980752e+04 1.34109092e+04 1.38493086e+04 1.35822227e+04 1.30825068e+04 1.33896895e+04 1.31593428e+04 1.34513809e+04 1.37911221e+04 1.31546348e+04 1.33445098e+04 1.37387842e+04 1.34586172e+04 1.33592676e+04 1.33528223e+04 1.33863125e+04 1.34075107e+04 1.33101387e+04 1.28413057e+04 1.28640859e+04 1.36498047e+04 1.39899932e+04 1.35736914e+04 1.29447793e+04 1.26178271e+04 1.28498496e+04 1.34091455e+04 1.37425508e+04 1.34323047e+04 1.27888848e+04 1.28117178e+04 1.32332266e+04 1.30763848e+04 1.29273379e+04 1.30137178e+04 1.29283955e+04 1.28285977e+04 1.33585752e+04 1.30847002e+04 1.25656113e+04 1.27981445e+04 1.24794824e+04 1.28638477e+04 1.32449697e+04 1.26828936e+04 1.30485977e+04 1.28406113e+04 1.22915303e+04 1.26979277e+04 1.23596494e+04 1.25837793e+04 1.33462178e+04 1.25954629e+04 1.19259160e+04 1.21684473e+04 1.27314668e+04 1.32032979e+04 1.29546494e+04 1.22220234e+04 1.18277109e+04 1.19492051e+04 1.24749961e+04 1.29831074e+04 1.26587139e+04 1.20034229e+04 1.19466641e+04 1.22117227e+04 1.23113037e+04 1.20875303e+04 1.20038857e+04 1.20099980e+04 1.19837910e+04 1.23947881e+04 1.23891172e+04 1.16361445e+04 1.15510459e+04 1.18558252e+04 1.18079678e+04 1.18781514e+04 1.17995186e+04 1.21240400e+04 1.17817119e+04 1.12741240e+04 1.16502129e+04 1.12881455e+04 1.15389170e+04 1.23143398e+04 1.15788330e+04 1.08247070e+04 1.11008848e+04 1.16155723e+04 1.18973877e+04 1.18266143e+04 1.11037041e+04 1.07345664e+04 1.09684658e+04 1.13154834e+04 1.17531816e+04 1.14929287e+04 1.07534785e+04 1.06306611e+04 1.09629668e+04 1.10998438e+04 1.13396465e+04 1.12474238e+04 1.05496357e+04 1.04323906e+04 1.09352979e+04 1.10253574e+04 1.06231582e+04 1.05235479e+04 1.06131885e+04 1.04671230e+04 1.07685605e+04 1.08042324e+04 1.03289482e+04 1.02069023e+04 1.02825352e+04 1.03040430e+04 1.02631924e+04 1.01972471e+04 1.04084121e+04 1.04606299e+04 1.01850898e+04 9.83895117e+03 9.62263672e+03 9.99079883e+03 1.04596143e+04 1.02470166e+04 9.68839648e+03 9.38507227e+03 9.65592871e+03 1.01823809e+04 9.80555273e+03 9.17756738e+03 9.37529883e+03 9.59568848e+03 9.74138574e+03 1.00374150e+04 9.68794531e+03 9.07141895e+03 8.98439746e+03 9.22840332e+03 9.39382812e+03 9.39659473e+03 9.22353223e+03 9.12558887e+03 9.00227344e+03 9.16324121e+03 9.01150684e+03 8.76129492e+03 8.78229004e+03 8.65081738e+03 8.93200391e+03 9.08075391e+03 8.69194043e+03 8.78499414e+03 8.73401758e+03 8.63237988e+03 8.35717773e+03 8.14886865e+03 8.54520312e+03 8.76936328e+03 8.45147656e+03 8.07489453e+03 8.03176367e+03 8.42087012e+03 8.50653027e+03 8.20779980e+03 8.10615430e+03 7.81129346e+03 7.77165674e+03 8.09199463e+03 7.99339990e+03 7.79697559e+03 7.61132666e+03 7.42021436e+03 7.79359619e+03 8.02038184e+03 7.60487646e+03 7.39206543e+03 7.52097363e+03 7.42842676e+03 7.63412646e+03 7.56426807e+03 7.15999512e+03 6.99262793e+03 7.20129980e+03 7.20806152e+03 7.18943994e+03 7.23384717e+03 7.42477979e+03 7.37875439e+03 7.14601953e+03 7.03935645e+03 6.53967871e+03 7.31577295e+03 7.77123682e+03 7.21121240e+03 9.66078125e+03 1.31677646e+04 1.22481738e+04 2.69980645e+04 1.38442453e+05 70205760. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -599992064. -599992064. 4.74704250e+06 3.85645352e+04 1.11388945e+04 8.69262793e+03 7.39504834e+03 6.51450488e+03 6.22630029e+03 6.05465576e+03 6.34659521e+03 6.30424561e+03 6.03620166e+03 6.12028076e+03 6.03031494e+03 5.89101562e+03 5.87378955e+03 5.81906396e+03 4.83005176e+03 4.91907275e+03 4.01841577e+03 3.77195728e+03 3.64647900e+03 3.52624268e+03 3.59811035e+03 3.57475854e+03 3.38153906e+03 3.35309009e+03 3.46149707e+03 3.43849365e+03 3.31277954e+03 3.24616650e+03 3.21874780e+03 3.18410474e+03 3.14210913e+03 3.10165771e+03 3.04594580e+03 2.99489966e+03 2.90565723e+03 2.85674438e+03 2.96403662e+03 2.94173169e+03 2.80000366e+03 2.76802856e+03 2.74779297e+03 2.71391040e+03 2.65551782e+03 2.60844727e+03 2.59384180e+03 2.51941724e+03 2.47428320e+03 2.44656812e+03 2.40374243e+03 2.47333472e+03 2.44846265e+03 2.32815698e+03 2.23118335e+03 2.19128613e+03 2.29363232e+03 2.26124829e+03 2.15336499e+03 2.08320483e+03 2.06032617e+03 2.05509302e+03 1.99316748e+03 2.02461121e+03 1.99833594e+03 1.85514197e+03 1.80706042e+03 1.86703625e+03 1.90415674e+03 1.82197742e+03 1.75173254e+03 1.72010291e+03 1.68214124e+03 1.65349280e+03 1.62337024e+03 1.60545447e+03 1.57537732e+03 1.52245056e+03 1.48931177e+03 1.46421509e+03 1.43727246e+03 1.45764868e+03 1.41527466e+03 1.34507092e+03 1.32276270e+03 1.29862927e+03 1.30221851e+03 1.27860620e+03 1.22135632e+03 1.19070520e+03 1.14678857e+03 1.10370361e+03 1.12946021e+03 1.10200256e+03 1.01708527e+03 1.00674158e+03 1.04146753e+03 1.04814343e+03 9.91262329e+02 9.35752502e+02 9.05428650e+02 8.81242371e+02 8.63971436e+02 8.41362183e+02 8.19151306e+02 7.92311951e+02 7.93247437e+02 7.68586365e+02 7.25429749e+02 7.09783569e+02 6.68630005e+02 6.63428711e+02 6.82129639e+02 6.49192993e+02 6.11732422e+02 5.76015259e+02 5.54120483e+02 5.67350159e+02 5.50509033e+02 5.14949768e+02 4.85328918e+02 4.66097168e+02 4.58997620e+02 4.43254089e+02 4.41126190e+02 4.25842651e+02 3.96128845e+02 3.77110443e+02 3.61260834e+02 3.52714172e+02 3.39538025e+02 3.20668701e+02 3.01536865e+02 2.88653870e+02 2.76529999e+02 2.54803787e+02 2.47907639e+02 2.50173325e+02 2.33758926e+02 2.14734756e+02 1.97672562e+02 1.86134506e+02 1.85452286e+02 1.75207687e+02 1.59826416e+02 1.45499039e+02 1.35084747e+02 1.30680222e+02 1.21115692e+02 1.11877388e+02 1.01091164e+02 9.49273682e+01 9.16712723e+01 8.17721558e+01 7.39909210e+01 6.75863266e+01 6.03576660e+01 5.31936340e+01 4.75288124e+01 4.24770432e+01 3.71187820e+01 3.26980476e+01 2.73800087e+01 2.35870590e+01 2.11981125e+01 1.67785664e+01 1.30824804e+01 1.06289215e+01 8.15665627e+00 6.21382999e+00 4.29417753e+00 2.69270968e+00 1.60874689e+00 7.77586222e-01 2.74142951e-01 1.11142054e-01 2.81645387e-01 7.85123825e-01 1.62117815e+00 2.79731631e+00 4.20210266e+00 6.16515589e+00 8.77709770e+00 1.11360712e+01 1.35397844e+01 1.62201195e+01 1.99631100e+01 2.50924206e+01 2.91247311e+01 3.28824959e+01 3.69668961e+01 4.16355515e+01 4.82735786e+01 5.43349609e+01 6.17090645e+01 6.75272980e+01 7.25194168e+01 8.01648941e+01 8.74348602e+01 9.84036713e+01 1.06045578e+02 1.11282051e+02 1.20547272e+02 1.29773178e+02 1.39127884e+02 1.45150009e+02 1.59372238e+02 1.80134628e+02 1.86611679e+02 1.91594269e+02 1.97755981e+02 2.07908401e+02 2.32736237e+02 2.47682892e+02 2.52648209e+02 2.58431061e+02 2.70620728e+02 2.92725647e+02 3.07243896e+02 3.29680054e+02 3.43663422e+02 3.49734894e+02 3.54543915e+02 3.68574097e+02 4.07591309e+02 4.22909637e+02 4.27492645e+02 4.36468018e+02 4.51270782e+02 4.94632812e+02 5.15540161e+02 5.02007660e+02 5.17801453e+02 5.69575684e+02 5.89818420e+02 5.76377625e+02 5.94513672e+02 6.45519775e+02 6.70246094e+02 6.69862366e+02 6.73657410e+02 6.95308960e+02 7.55756287e+02 7.71256531e+02 7.65921448e+02 7.99507019e+02 8.22534668e+02 8.42413513e+02 8.64826599e+02 8.88955688e+02 8.90958374e+02 9.35893188e+02 1.00297900e+03 9.99987854e+02 1.03292676e+03 1.06349902e+03 1.06461804e+03 1.09158691e+03 1.11718127e+03 1.13843518e+03 1.14432190e+03 1.16664832e+03 1.22041187e+03 1.25376880e+03 1.31513708e+03 1.30648889e+03 1.29205444e+03 1.35522546e+03 1.39818030e+03 1.47263330e+03 1.48481409e+03 1.46513843e+03 1.48425635e+03 1.50535925e+03 1.56908960e+03 1.59947400e+03 1.66750269e+03 1.69428101e+03 1.68364587e+03 1.71480322e+03 1.69321021e+03 1.77390027e+03 1.90870752e+03 1.91558118e+03 1.89439404e+03 1.87427600e+03 1.87864624e+03 2.00300562e+03 2.10634863e+03 2.08776416e+03 2.03710974e+03 2.06960742e+03 2.15937134e+03 2.18838647e+03 2.27735889e+03 2.30467163e+03 2.27883691e+03 2.31119653e+03 2.33965723e+03 2.46706299e+03 2.51371167e+03 2.41005762e+03 2.43961011e+03 2.61967944e+03 2.63910229e+03 2.54046924e+03 2.61390723e+03 2.78749292e+03 2.82305615e+03 2.79163867e+03 2.75847070e+03 2.77437744e+03 2.96770215e+03 3.03107544e+03 2.98700562e+03 2.94618408e+03 2.95552124e+03 3.08012964e+03 3.14538257e+03 3.18672607e+03 3.13304102e+03 3.25104785e+03 3.42559424e+03 3.37940015e+03 3.43313232e+03 3.43931470e+03 3.42425659e+03 3.50648145e+03 3.54849976e+03 3.61084814e+03 3.62269482e+03 3.61036768e+03 3.57396582e+03 3.74959155e+03 3.97616040e+03 3.82814722e+03 3.69648169e+03 3.87704883e+03 4.04045435e+03 4.21140918e+03 4.12917383e+03 4.04926392e+03 4.20925000e+03 4.25955420e+03 4.16306934e+03 4.15181396e+03 4.36695264e+03 4.40123779e+03 4.38267139e+03 4.37970312e+03 4.28860645e+03 4.51749805e+03 4.84905566e+03 4.76471533e+03 4.67643408e+03 4.59338184e+03 4.58264355e+03 4.89605762e+03 5.09942969e+03 4.99242676e+03 4.87209717e+03 4.91477881e+03 4.98417920e+03 5.03670459e+03 5.25451660e+03 5.24078857e+03 5.14898242e+03 5.25420557e+03 5.25902979e+03 5.49687109e+03 5.56326465e+03 5.42120361e+03 5.48156104e+03 5.52162598e+03 5.61059229e+03 5.54062549e+03 5.60291455e+03 5.91799805e+03 5.90844434e+03 5.84882764e+03 5.72232520e+03 5.79965137e+03 6.21517627e+03 6.23815381e+03 6.09691406e+03 6.03119873e+03 6.01664404e+03 6.13817871e+03 6.21936475e+03 6.33858838e+03 6.23878369e+03 6.34700195e+03 6.67191357e+03 6.50478320e+03 6.71068848e+03 6.76151221e+03 6.63277295e+03 6.64895703e+03 6.69514795e+03 6.76462305e+03 6.81335449e+03 6.81354932e+03 6.89372217e+03 7.08176660e+03 7.17676709e+03 6.89599170e+03 6.91349316e+03 7.08938135e+03 7.26714453e+03 7.55358691e+03 7.47064111e+03 7.15874854e+03 7.42798926e+03 7.62565967e+03 7.56216846e+03 7.51788867e+03 7.52417529e+03 7.51728662e+03 7.57671924e+03 7.83513623e+03 7.62080811e+03 7.77308008e+03 8.20881641e+03 8.09648096e+03 7.95997803e+03 7.88837891e+03 7.88779883e+03 8.36194727e+03 8.35961914e+03 8.21268457e+03 8.11844434e+03 7.92278271e+03 8.15621387e+03 8.57307031e+03 8.86650195e+03 8.58247852e+03 8.36202344e+03 8.46838086e+03 8.56105371e+03 8.94869727e+03 8.94232520e+03 8.68541406e+03 8.73768066e+03 8.76722754e+03 8.87120117e+03 8.76344336e+03 8.89762598e+03 9.31356348e+03 9.25075098e+03 9.16711523e+03 9.04725488e+03 9.00141504e+03 9.56015332e+03 9.59957129e+03 9.36542676e+03 9.17683203e+03 9.18623438e+03 9.42123340e+03 9.53785449e+03 9.82323145e+03 9.92018359e+03 9.59173926e+03 9.41248145e+03 9.56676660e+03 1.01315244e+04 1.00640547e+04 9.87620801e+03 9.87150098e+03 9.85825000e+03 9.89839062e+03 9.87254688e+03 1.01658525e+04 1.01736074e+04 1.00112549e+04 1.03981787e+04 1.05609141e+04 1.03919102e+04 1.03348457e+04 1.03573477e+04 1.04322822e+04 1.02351836e+04 1.01485801e+04 1.07237822e+04 1.08839219e+04 1.03777090e+04 1.01675537e+04 1.07439971e+04 1.12310186e+04 1.10834629e+04 1.06935596e+04 1.04848057e+04 1.09704902e+04 1.11872969e+04 1.10235078e+04 1.10571631e+04 1.08556230e+04 1.04631084e+04 1.09052529e+04 1.16444287e+04 1.16959639e+04 1.11078340e+04 1.08265586e+04 1.14414082e+04 1.18384795e+04 1.15124668e+04 1.11887070e+04 1.11152744e+04 1.12761348e+04 1.14380146e+04 1.18587461e+04 1.19264541e+04 1.15803652e+04 1.14560898e+04 1.14705947e+04 1.19808076e+04 1.17853994e+04 1.15180723e+04 1.20409199e+04 1.20170049e+04 1.19110986e+04 1.17177627e+04 1.16987139e+04 1.23558369e+04 1.20334531e+04 1.16179209e+04 1.19373809e+04 1.22282119e+04 1.22850811e+04 1.21705449e+04 1.24540400e+04 1.26014590e+04 1.22943857e+04 1.19409844e+04 1.19366025e+04 1.26899375e+04 1.25124863e+04 1.21999355e+04 1.23680557e+04 1.23516260e+04 1.25985459e+04 1.25683047e+04 1.26613369e+04 1.25869248e+04 1.23239990e+04 1.27792998e+04 1.28904590e+04 1.27412354e+04 1.27579229e+04 1.27493604e+04 1.26377207e+04 1.23367373e+04 1.23325186e+04 1.30054033e+04 1.35013311e+04 1.27851143e+04 1.22600400e+04 1.28930273e+04 1.34118945e+04 1.32742305e+04 1.28317012e+04 1.25193262e+04 1.31746797e+04 1.32467266e+04 1.28114189e+04 1.34121523e+04 1.33401504e+04 1.26052041e+04 1.27907686e+04 1.35046709e+04 1.36539326e+04 1.29874102e+04 1.26347324e+04 1.32954443e+04 1.37955430e+04 1.34648682e+04 1.29681436e+04 1.27532725e+04 1.34328096e+04 1.36658867e+04 1.32438623e+04 1.33762109e+04 1.34693867e+04 1.32617568e+04 1.31849746e+04 1.37155566e+04 1.35382520e+04 1.30500547e+04 1.35043955e+04 1.36337705e+04 1.37153115e+04 1.34063408e+04 1.31396084e+04 1.37080039e+04 1.33898926e+04 1.33571748e+04 1.47602695e+04 1.45303994e+04 1.41313623e+04 1.35102695e+04 2.59541250e+04 4.10922461e+04 3.78268008e+04 3.47824805e+04 3.72602656e+04 2.11456426e+04 6.30593828e+04 386753. -4.74222383e+04 -1.86798141e+10 -1.86798141e+10 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. 7.91520512e+09 1.60519312e+05 4.24728672e+04 2.69814492e+04 2.15475664e+04 1.74292754e+04 1.74822109e+04 1.50957783e+04 1.49539053e+04 1.36612422e+04 1.36608896e+04 1.37591768e+04 1.35443477e+04 1.35798477e+04 1.34686221e+04 1.33512197e+04 1.36694932e+04 1.36644678e+04 1.35235850e+04 1.35980400e+04 1.31787510e+04 1.31158330e+04 1.35619082e+04 1.33949170e+04 1.32343711e+04 1.36042266e+04 1.39500029e+04 1.35812803e+04 1.31926758e+04 1.31551338e+04 1.30441055e+04 1.33486826e+04 1.36312920e+04 1.33425439e+04 1.32823105e+04 1.35737627e+04 1.33836865e+04 1.30320557e+04 1.31310830e+04 1.31121172e+04 1.31419258e+04 1.34999014e+04 1.31958848e+04 1.29886074e+04 1.33378711e+04 1.31472578e+04 1.29230264e+04 1.29191982e+04 1.29779678e+04 1.31155508e+04 1.31135234e+04 1.32840527e+04 1.30263223e+04 1.28146865e+04 1.30869434e+04 1.27794150e+04 1.25795117e+04 1.29442031e+04 1.29162109e+04 1.27704756e+04 1.29812129e+04 1.29158965e+04 1.26684014e+04 1.26779658e+04 1.25950557e+04 1.24592354e+04 1.26418008e+04 1.26832578e+04 1.27107793e+04 1.27475078e+04 1.25460479e+04 1.24328896e+04 1.24627988e+04 1.25415586e+04 1.23999805e+04 1.23885088e+04 1.27694941e+04 1.24838457e+04 1.19919541e+04 1.22328926e+04 1.22230391e+04 1.20963086e+04 1.23695889e+04 1.22622422e+04 1.20700332e+04 1.23688057e+04 1.24638965e+04 1.20932344e+04 1.18010791e+04 1.17467793e+04 1.18365107e+04 1.20586191e+04 1.20565186e+04 1.19993828e+04 1.20817334e+04 1.19590547e+04 1.16907627e+04 1.15068613e+04 1.17137324e+04 1.17313750e+04 1.15650488e+04 1.16995000e+04 1.16287686e+04 1.14838174e+04 1.16907178e+04 1.14514697e+04 1.11835840e+04 1.12896064e+04 1.14668809e+04 1.15078867e+04 1.12745986e+04 1.12746406e+04 1.14170322e+04 1.13928359e+04 1.12254326e+04 1.09329111e+04 1.08876533e+04 1.11564502e+04 1.11617969e+04 1.09304111e+04 1.09678086e+04 1.08271445e+04 1.07016104e+04 1.09340928e+04 1.08222812e+04 1.05793662e+04 1.06470762e+04 1.08477930e+04 1.08569131e+04 1.06631602e+04 1.03390752e+04 1.02566240e+04 1.04794395e+04 1.06020527e+04 1.02687646e+04 1.02828994e+04 1.05924873e+04 1.04404932e+04 1.02567021e+04 1.01596201e+04 9.88885254e+03 9.85246387e+03 9.93185742e+03 1.00517930e+04 1.00200684e+04 9.95075000e+03 1.00177217e+04 9.92572656e+03 9.70398633e+03 9.57776660e+03 9.55217188e+03 9.65385352e+03 9.71015625e+03 9.78042383e+03 9.67563184e+03 9.49965820e+03 9.36398730e+03 9.39141016e+03 9.44557617e+03 9.06383887e+03 9.08595410e+03 9.35167188e+03 9.37283398e+03 9.10240625e+03 8.99879297e+03 8.92626465e+03 8.82747852e+03 8.91503027e+03 9.07521875e+03 9.02911621e+03 8.81338281e+03 8.74707129e+03 8.74212012e+03 8.58012793e+03 8.54779395e+03 8.53807812e+03 8.43806934e+03 8.66342871e+03 8.71974512e+03 8.24322266e+03 8.23524316e+03 8.24124219e+03 8.25766895e+03 8.36084082e+03 8.01278857e+03 7.91862012e+03 8.19813672e+03 8.15870654e+03 8.01619873e+03 7.90667920e+03 7.79017285e+03 7.68306982e+03 7.79279736e+03 7.90018359e+03 7.70852197e+03 7.51271924e+03 7.65524609e+03 7.78306934e+03 7.48849854e+03 7.36612793e+03 7.36161084e+03 7.25999658e+03 7.39811621e+03 7.24623486e+03 7.18250781e+03 7.29267432e+03 7.03756055e+03 6.98968262e+03 7.04932520e+03 6.84723340e+03 6.85191113e+03 6.93184570e+03 6.90673145e+03 6.85734229e+03 6.71936475e+03 6.67262207e+03 6.58867578e+03 6.59143066e+03 6.65052148e+03 6.42891309e+03 6.30771436e+03 6.42158740e+03 6.46927881e+03 6.28811279e+03 6.30853418e+03 6.30374121e+03 6.07974268e+03 6.15156348e+03 6.22851807e+03 6.00276465e+03 5.85708350e+03 5.92706104e+03 5.86411328e+03 5.79511670e+03 5.72910498e+03 5.70322021e+03 5.70544775e+03 5.73304980e+03 5.67450684e+03 5.56555371e+03 5.51335303e+03 5.46261035e+03 5.37069385e+03 5.45626025e+03 5.24409863e+03 5.18770459e+03 5.33747266e+03 5.18200879e+03 5.08421436e+03 5.08732617e+03 5.05917383e+03 4.93295752e+03 4.90835254e+03 4.90785205e+03 4.93240186e+03 4.82909473e+03 4.78201611e+03 4.76629834e+03 4.61522754e+03 4.56783936e+03 4.55603564e+03 4.47868311e+03 4.54454688e+03 4.58045264e+03 4.41175537e+03 4.29516406e+03 4.29464746e+03 4.35986865e+03 4.27999512e+03 4.05688062e+03 4.13070801e+03 4.20417090e+03 4.07439331e+03 4.01427588e+03 3.94263672e+03 3.88316968e+03 3.89100732e+03 3.81429590e+03 3.73946899e+03 3.79806128e+03 3.75166528e+03 3.65334839e+03 3.66025586e+03 3.61211328e+03 3.56378809e+03 3.48580371e+03 3.36243213e+03 3.41741260e+03 3.44294360e+03 3.29336890e+03 3.25384473e+03 3.24074023e+03 3.24129736e+03 3.22178784e+03 3.07699780e+03 3.08560913e+03 3.12101050e+03 3.03183447e+03 2.96868970e+03 2.91717578e+03 2.85718384e+03 2.85653271e+03 2.81731372e+03 2.75758252e+03 2.76851831e+03 2.74256714e+03 2.68524878e+03 2.66097119e+03 2.60951758e+03 2.52734814e+03 2.48754272e+03 2.50365039e+03 2.48392798e+03 2.39350684e+03 2.34181030e+03 2.30182739e+03 2.27768555e+03 2.29251831e+03 2.23903101e+03 2.16545215e+03 2.14233618e+03 2.14731982e+03 2.13240649e+03 2.06451440e+03 1.98927625e+03 1.96508557e+03 1.95809167e+03 1.90959912e+03 1.87346619e+03 1.86436218e+03 1.83429968e+03 1.79579028e+03 1.78955310e+03 1.74949719e+03 1.68343726e+03 1.64551477e+03 1.63917554e+03 1.61552356e+03 1.53994226e+03 1.49423999e+03 1.50401697e+03 1.49318164e+03 1.47266467e+03 1.43249756e+03 1.37231860e+03 1.37278430e+03 1.36264722e+03 1.28562817e+03 1.24581641e+03 1.25889050e+03 1.25106287e+03 1.20148743e+03 1.15377661e+03 1.11663586e+03 1.10101331e+03 1.10221997e+03 1.09229639e+03 1.06363611e+03 1.00885004e+03 9.74028809e+02 9.58067383e+02 9.29820740e+02 9.10598206e+02 8.87907959e+02 8.63610474e+02 8.49900085e+02 8.27435730e+02 7.96925903e+02 7.69696838e+02 7.56385925e+02 7.54425415e+02 7.24832214e+02 6.80117126e+02 6.54255981e+02 6.48030945e+02 6.41103699e+02 6.22795105e+02 5.94772339e+02 5.56826904e+02 5.39820801e+02 5.38175232e+02 5.24502747e+02 5.06065796e+02 4.80548828e+02 4.57600525e+02 4.45924927e+02 4.25692566e+02 4.12639893e+02 3.95012695e+02 3.69486633e+02 3.65459686e+02 3.57554688e+02 3.36308594e+02 3.15462494e+02 2.94099091e+02 2.87485107e+02 2.87384369e+02 2.71476532e+02 2.49040222e+02 2.39700912e+02 2.31259750e+02 2.12912338e+02 1.99908585e+02 1.87019699e+02 1.76941711e+02 1.73013443e+02 1.60562469e+02 1.45728149e+02 1.39029694e+02 1.31685715e+02 1.21172188e+02 1.12284897e+02 1.04770958e+02 9.53615646e+01 8.67560043e+01 8.03688583e+01 7.29555283e+01 6.70293503e+01 6.07859726e+01 5.41050568e+01 4.83466721e+01 4.19819679e+01 3.70946541e+01 3.26373482e+01 2.80025101e+01 2.42198277e+01 2.05668163e+01 1.69487057e+01 1.35425205e+01 1.06730814e+01 8.29486275e+00 6.21863747e+00 4.41507816e+00 2.88755465e+00 1.74371505e+00 9.22812164e-01 4.28424478e-01 2.78186053e-01 4.66073185e-01 9.70928133e-01 1.81185639e+00 2.98983598e+00 4.47223473e+00 6.44781017e+00 8.58931828e+00 1.09667854e+01 1.42155247e+01 1.76317024e+01 2.03015099e+01 2.38418331e+01 2.89157104e+01 3.39346008e+01 3.86306534e+01 4.27902298e+01 4.75068932e+01 5.37930832e+01 6.12603798e+01 6.80531921e+01 7.33251953e+01 8.03958969e+01 8.87583923e+01 9.60309525e+01 1.05247688e+02 1.14398491e+02 1.22003593e+02 1.31818100e+02 1.40614777e+02 1.50754272e+02 1.59860870e+02 1.68948120e+02 1.82219055e+02 1.93385147e+02 2.04274811e+02 2.13915237e+02 2.24970978e+02 2.42801132e+02 2.55744232e+02 2.66479431e+02 2.82233643e+02 2.89093536e+02 3.00253662e+02 3.26393341e+02 3.39775665e+02 3.44639832e+02 3.68832214e+02 3.85493378e+02 3.89542786e+02 4.15952087e+02 4.34671112e+02 4.40867279e+02 4.67579803e+02 4.87790588e+02 4.92652588e+02 5.14487610e+02 5.38331848e+02 5.53947693e+02 5.76088745e+02 5.94666748e+02 5.96819580e+02 6.20920532e+02 6.62872070e+02 6.86729431e+02 7.03256958e+02 7.09939453e+02 7.34064575e+02 7.53741516e+02 7.62320618e+02 8.03791565e+02 8.29208435e+02 8.41723511e+02 8.82951233e+02 8.97024048e+02 8.99724121e+02 9.40313782e+02 9.76132751e+02 1.00670587e+03 1.01998041e+03 1.03084399e+03 1.04729395e+03 1.09771924e+03 1.15851282e+03 1.14455664e+03 1.16111792e+03 1.18264722e+03 1.21500830e+03 1.27839478e+03 1.27561462e+03 1.28132910e+03 1.33146899e+03 1.38034387e+03 1.40007971e+03 1.38969067e+03 1.44350879e+03 1.50704651e+03 1.51528125e+03 1.54836072e+03 1.55662207e+03 1.59055310e+03 1.65327600e+03 1.67896533e+03 1.71891565e+03 1.71995789e+03 1.73400549e+03 1.79212048e+03 1.82876978e+03 1.87519080e+03 1.89271375e+03 1.89193579e+03 1.93852124e+03 2.01141638e+03 2.04242493e+03 2.05946753e+03 2.09154956e+03 2.12160303e+03 2.16895825e+03 2.19242310e+03 2.19925439e+03 2.28151953e+03 2.32273633e+03 2.33038721e+03 2.41624170e+03 2.41426929e+03 2.41480859e+03 2.48852954e+03 2.49470654e+03 2.54062500e+03 2.61911157e+03 2.63735986e+03 2.62877612e+03 2.67977441e+03 2.74814551e+03 2.78596509e+03 2.88083179e+03 2.89144629e+03 2.87333154e+03 2.92779321e+03 2.93546167e+03 3.00385303e+03 3.04870239e+03 3.11399341e+03 3.19414404e+03 3.14454956e+03 3.21432812e+03 3.27577368e+03 3.26506738e+03 3.32470483e+03 3.40651465e+03 3.45817456e+03 3.44816357e+03 3.50070996e+03 3.57972314e+03 3.60302051e+03 3.60999170e+03 3.65842871e+03 3.70275513e+03 3.80009741e+03 3.80079492e+03 3.83844897e+03 3.93295801e+03 3.89141382e+03 3.92322437e+03 4.09676367e+03 4.14561182e+03 4.06743335e+03 4.11476758e+03 4.14901855e+03 4.16412158e+03 4.43711768e+03 4.39717432e+03 4.30112793e+03 4.56471533e+03 4.66934814e+03 4.35580029e+03 4.08592700e+03 4.85084277e+03 5.72640869e+03 5.38992969e+03 4.75815576e+03 1.22462900e+04 1.21177168e+04 8272864. 5374565. -54726096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -59475064. 1.86131262e+06 2.46392148e+04 1.83145859e+04 1.19227783e+04 1.16893857e+04 1.13643682e+04 1.04101836e+04 9.93753809e+03 9.54240137e+03 7.17507227e+03 7.47558203e+03 7.64553662e+03 7.49295117e+03 7.47023145e+03 7.42283398e+03 7.62205127e+03 7.77823145e+03 7.76393604e+03 7.65360938e+03 7.53675049e+03 7.80986621e+03 7.94922314e+03 7.95952539e+03 8.03771387e+03 7.83503027e+03 7.91089258e+03 8.12573730e+03 8.12965869e+03 8.22855859e+03 8.03547217e+03 7.97803613e+03 8.51453809e+03 8.72728125e+03 8.45936914e+03 8.18185205e+03 8.26879883e+03 8.54506250e+03 8.68578516e+03 8.62059863e+03 8.50573047e+03 8824. 8.90083301e+03 8.86919336e+03 8.89265723e+03 8.59807520e+03 8.82889648e+03 9.30933789e+03 9.15900684e+03 9.17559082e+03 9.06754980e+03 8.95884473e+03 9.15010547e+03 9.52039746e+03 9.45446484e+03 9.16363965e+03 9.41961914e+03 9.47485645e+03 9.46683887e+03 9.54204688e+03 9.39828711e+03 9.59686719e+03 9.87174219e+03 9.65709473e+03 9.60262891e+03 9.52265039e+03 9.79888477e+03 1.01672158e+04 1.01081787e+04 9.95925977e+03 9.83893848e+03 9.92019922e+03 9.98839941e+03 1.01807070e+04 1.03863486e+04 1.00432686e+04 1.01670811e+04 1.04909277e+04 1.04870566e+04 1.03309521e+04 1.01150332e+04 1.03238750e+04 1.07485596e+04 1.07428359e+04 1.05949043e+04 1.04055586e+04 1.04302793e+04 1.07328896e+04 1.10148730e+04 1.07492568e+04 1.04995312e+04 1.09434941e+04 1.09956133e+04 1.08456143e+04 1.12010498e+04 1.09633633e+04 1.09053770e+04 1.11331025e+04 1.12050146e+04 1.13092803e+04 1.10008252e+04 1.09602168e+04 1.12259746e+04 1.15140371e+04 1.16103428e+04 1.13307490e+04 1.13673232e+04 1.14342100e+04 1.14397705e+04 1.16379648e+04 1.14032520e+04 1.14419814e+04 1.18468916e+04 1.18382305e+04 1.15035762e+04 1.12820830e+04 1.17172529e+04 1.22545957e+04 1.21811211e+04 1.18464082e+04 1.15892373e+04 1.17067812e+04 1.19781299e+04 1.21323564e+04 1.21827051e+04 1.19305811e+04 1.19552305e+04 1.20370420e+04 1.21469824e+04 1.24347969e+04 1.20156680e+04 1.20566211e+04 1.25441152e+04 1.23167520e+04 1.22419814e+04 1.22718428e+04 1.23502041e+04 1.25866758e+04 1.25259912e+04 1.23105068e+04 1.20705449e+04 1.24785752e+04 1.30193975e+04 1.28438672e+04 1.25611445e+04 1.23760938e+04 1.24638887e+04 1.27106670e+04 1.28998174e+04 1.29155547e+04 1.23861533e+04 1.23654121e+04 1.27799277e+04 1.30290283e+04 1.32542344e+04 1.28946729e+04 1.27541182e+04 1.27988047e+04 1.29175645e+04 1.31158535e+04 1.28397842e+04 1.29274619e+04 1.30325586e+04 1.29873467e+04 1.31233574e+04 1.28464014e+04 1.30725146e+04 1.33943867e+04 1.30722021e+04 1.31884414e+04 1.31583145e+04 1.31211377e+04 1.33302881e+04 1.34194307e+04 1.32536357e+04 1.29300566e+04 1.30400986e+04 1.34584258e+04 1.37482891e+04 1.35717793e+04 1.29414727e+04 1.28345088e+04 1.34444463e+04 1.36946895e+04 1.35853252e+04 1.30995059e+04 1.32174609e+04 1.35735576e+04 1.34358545e+04 1.35961357e+04 1.32850254e+04 1.32146396e+04 1.35627012e+04 1.36877002e+04 1.36680381e+04 1.34234150e+04 1.35008477e+04 1.35425020e+04 1.35508330e+04 1.37794229e+04 1.35851426e+04 1.35908994e+04 1.35486270e+04 1.34050625e+04 1.33867305e+04 1.33969023e+04 1.38372773e+04 1.39568496e+04 1.38181572e+04 1.35734834e+04 1.30599951e+04 1.34290713e+04 1.41595156e+04 1.41263887e+04 1.38569277e+04 1.33986992e+04 1.32082979e+04 1.35697197e+04 1.40403555e+04 1.39832197e+04 1.37282441e+04 1.37818135e+04 1.36755742e+04 1.36556582e+04 1.34470547e+04 1.31996768e+04 1.35004580e+04 1.36062031e+04 1.39886523e+04 1.39596689e+04 1.32098213e+04 1.36607021e+04 1.39302715e+04 1.35151807e+04 1.36753311e+04 1.36805596e+04 1.39745791e+04 1.39186016e+04 1.32430264e+04 1.30786660e+04 1.33960283e+04 1.39658877e+04 1.44037578e+04 1.40656201e+04 1.32905400e+04 1.29338818e+04 1.32148457e+04 1.39245020e+04 1.42844053e+04 1.39872979e+04 1.32752998e+04 1.31350371e+04 1.39511123e+04 1.39354902e+04 1.31660312e+04 1.32164160e+04 1.36001143e+04 1.35268252e+04 1.38437061e+04 1.35515566e+04 1.30544385e+04 1.34216230e+04 1.32099053e+04 1.34186406e+04 1.37444199e+04 1.31442695e+04 1.33514600e+04 1.37680449e+04 1.34812812e+04 1.33505801e+04 1.33677412e+04 1.34201572e+04 1.33499092e+04 1.33613770e+04 1.29096025e+04 1.27958574e+04 1.35718477e+04 1.39901904e+04 1.35881162e+04 1.29619521e+04 1.26563330e+04 1.27969307e+04 1.33673359e+04 1.37648115e+04 1.35144668e+04 1.28329922e+04 1.27658535e+04 1.32151396e+04 1.31570518e+04 1.29308037e+04 1.29061211e+04 1.29081055e+04 1.28681611e+04 1.32981914e+04 1.30804375e+04 1.26015439e+04 1.28692227e+04 1.25166113e+04 1.27970947e+04 1.31841094e+04 1.26987695e+04 1.30422754e+04 1.28331504e+04 1.23704111e+04 1.27221963e+04 1.22980859e+04 1.25574658e+04 1.33921611e+04 1.25920352e+04 1.19324932e+04 1.22321465e+04 1.27582021e+04 1.31524326e+04 1.29308896e+04 1.21602363e+04 1.17882246e+04 1.19946768e+04 1.25002441e+04 1.30503721e+04 1.26340879e+04 1.18965293e+04 1.19115244e+04 1.22223857e+04 1.23594795e+04 1.20699814e+04 1.19670605e+04 1.20502041e+04 1.19581963e+04 1.24156582e+04 1.24627871e+04 1.16626426e+04 1.15903389e+04 1.18512998e+04 1.18100352e+04 1.18753984e+04 1.17793398e+04 1.20593652e+04 1.17905166e+04 1.13370859e+04 1.16024287e+04 1.13106025e+04 1.15778594e+04 1.23222588e+04 1.15438242e+04 1.07721064e+04 1.10564990e+04 1.16560391e+04 1.19280967e+04 1.18585449e+04 1.11637188e+04 1.07372881e+04 1.09280537e+04 1.13456553e+04 1.17731826e+04 1.14910342e+04 1.07752822e+04 1.06469297e+04 1.10232891e+04 1.10632061e+04 1.12434541e+04 1.12174326e+04 1.05441680e+04 1.05151816e+04 1.09110283e+04 1.09683721e+04 1.07198965e+04 1.06196943e+04 1.05163730e+04 1.03482236e+04 1.08011133e+04 1.08375400e+04 1.03949277e+04 1.02644512e+04 1.01686504e+04 1.02434766e+04 1.02761709e+04 1.02244688e+04 1.05094180e+04 1.04281367e+04 1.00674883e+04 9.84945117e+03 9.62147852e+03 1.00107969e+04 1.04948174e+04 1.01777764e+04 9.64464160e+03 9.41723535e+03 9.70933008e+03 1.01838496e+04 9.73137500e+03 9.17908691e+03 9.37446875e+03 9.67918848e+03 9.78971484e+03 1.00142314e+04 9.69243164e+03 9.15783398e+03 9.02032227e+03 9.21277051e+03 9.32982617e+03 9.34726074e+03 9.24101270e+03 9.14601367e+03 9.03179395e+03 9.13318359e+03 8.98290918e+03 8.74045312e+03 8.75619824e+03 8.73425195e+03 9.01475293e+03 9.04315039e+03 8.70747559e+03 8.73316504e+03 8.68254883e+03 8.64136523e+03 8.39317383e+03 8.17328760e+03 8.55134082e+03 8.82912891e+03 8.47675098e+03 8.05095410e+03 8.07657324e+03 8.44975391e+03 8.47603418e+03 8.20383691e+03 8.12192920e+03 7.85882471e+03 7.79537598e+03 8.05448486e+03 7.93096240e+03 7.77373584e+03 7.55436768e+03 7.48582861e+03 7.85982715e+03 8.05138232e+03 7.58097559e+03 7.35850928e+03 7.48299414e+03 7.45941650e+03 7.62820166e+03 7.52584277e+03 7.09668750e+03 7.08302490e+03 7.25802979e+03 7.20737354e+03 7.15804785e+03 7.17902686e+03 7.38544775e+03 7.42550781e+03 7.23560645e+03 7.14970508e+03 6.64166113e+03 7.45061963e+03 8.72218457e+03 8.32062793e+03 9.50453516e+03 1.46847402e+04 1.36630146e+04 1.94706543e+04 1.76275723e+04 3.19044375e+06 7.30316350e+06 2.65459025e+06 4893892. 6.71785150e+06 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. 0. 0. 0. 0. 0. 0. -599992064. -599992064. 4.74704250e+06 3.85645352e+04 1.11388945e+04 8.69262793e+03 6.26840820e+03 5.52178223e+03 4.07390405e+03 4.16491846e+03 4.61823486e+03 4.34002539e+03 4.01651709e+03 4.09240234e+03 4.06634277e+03 3.92542725e+03 3.87794092e+03 3.85773486e+03 3.80636841e+03 3.74720459e+03 3.69355835e+03 3.64412622e+03 3.61573096e+03 3.56196924e+03 3.57011401e+03 3.55184302e+03 3.37516113e+03 3.32700562e+03 3.45033154e+03 3.42796802e+03 3.29575586e+03 3.25234106e+03 3.21828467e+03 3.17768774e+03 3.14504785e+03 3.09652539e+03 3.04011377e+03 3.00925439e+03 2.93162280e+03 2.88195752e+03 2.94202832e+03 2.92007227e+03 2.81968457e+03 2.76994751e+03 2.74656030e+03 2.70619043e+03 2.66001245e+03 2.62345166e+03 2.59899365e+03 2.51924219e+03 2.45718311e+03 2.43978613e+03 2.40843384e+03 2.48358838e+03 2.45513013e+03 2.32055200e+03 2.23397339e+03 2.19617700e+03 2.29069971e+03 2.26573120e+03 2.15263965e+03 2.07613696e+03 2.03952271e+03 2.06391309e+03 2.01584363e+03 2.02533813e+03 2.00989148e+03 1.86608850e+03 1.79461487e+03 1.86452710e+03 1.91364685e+03 1.82347546e+03 1.74952551e+03 1.71947998e+03 1.68446362e+03 1.65248328e+03 1.62580078e+03 1.58566370e+03 1.55210095e+03 1.53674548e+03 1.50411462e+03 1.46850720e+03 1.44065527e+03 1.45208472e+03 1.42742334e+03 1.36142944e+03 1.32452893e+03 1.29922815e+03 1.29151355e+03 1.26481482e+03 1.22299365e+03 1.19645667e+03 1.14687415e+03 1.10107471e+03 1.12651111e+03 1.10111462e+03 1.01896991e+03 1.00747815e+03 1.04012781e+03 1.04532214e+03 9.91923218e+02 9.38817810e+02 9.03617676e+02 8.78326721e+02 8.64399780e+02 8.40643433e+02 8.16676453e+02 7.92812134e+02 7.97288147e+02 7.76632935e+02 7.29745239e+02 7.09440186e+02 6.69261047e+02 6.56196838e+02 6.74651245e+02 6.48562561e+02 6.12301086e+02 5.79547485e+02 5.52397949e+02 5.61194763e+02 5.53034607e+02 5.19626282e+02 4.87081085e+02 4.67868195e+02 4.59875763e+02 4.43706024e+02 4.41581696e+02 4.26220703e+02 3.96705750e+02 3.77335419e+02 3.61007080e+02 3.53032166e+02 3.39712555e+02 3.20581268e+02 3.04706177e+02 2.91098328e+02 2.76190887e+02 2.56011993e+02 2.46574661e+02 2.47356979e+02 2.33211060e+02 2.14458252e+02 1.98052582e+02 1.86598007e+02 1.85166519e+02 1.74968277e+02 1.59886185e+02 1.46108170e+02 1.35708481e+02 1.30241241e+02 1.21015244e+02 1.12413467e+02 1.01204575e+02 9.52624817e+01 9.29048538e+01 8.29202805e+01 7.37319870e+01 6.69193115e+01 6.03981018e+01 5.40803337e+01 4.83232422e+01 4.25035286e+01 3.71990585e+01 3.26563988e+01 2.74679260e+01 2.38179493e+01 2.12575226e+01 1.68993149e+01 1.33065567e+01 1.08361511e+01 8.29789829e+00 6.39327097e+00 4.47487879e+00 2.85631442e+00 1.77988064e+00 9.46525812e-01 4.40667003e-01 2.77666658e-01 4.51745629e-01 9.65567172e-01 1.80896544e+00 2.94686365e+00 4.33885622e+00 6.32195187e+00 8.91763592e+00 1.12670574e+01 1.38374386e+01 1.65931015e+01 1.99412270e+01 2.49574299e+01 2.93876247e+01 3.32136879e+01 3.70111084e+01 4.17013474e+01 4.85968208e+01 5.45763435e+01 6.19005699e+01 6.76006165e+01 7.24714050e+01 8.02482834e+01 8.75696106e+01 9.87917023e+01 1.06643127e+02 1.11401283e+02 1.21413078e+02 1.30931137e+02 1.39259277e+02 1.45010681e+02 1.58363129e+02 1.78883316e+02 1.86313690e+02 1.91755753e+02 1.97948425e+02 2.08165726e+02 2.33332794e+02 2.47673401e+02 2.52190765e+02 2.58530762e+02 2.70724701e+02 2.93231445e+02 3.07391296e+02 3.28694092e+02 3.41108459e+02 3.47080170e+02 3.58919220e+02 3.72750183e+02 4.06599884e+02 4.23425629e+02 4.28072754e+02 4.40067200e+02 4.55780090e+02 4.90596222e+02 5.10826019e+02 5.02436157e+02 5.18884705e+02 5.70447876e+02 5.90350159e+02 5.77487549e+02 5.94427002e+02 6.45165527e+02 6.71615051e+02 6.71109741e+02 6.73058472e+02 6.96269958e+02 7.56422302e+02 7.69768555e+02 7.67563660e+02 8.06583069e+02 8.30704834e+02 8.41530151e+02 8.58031494e+02 8.86054260e+02 8.88066895e+02 9.35445740e+02 1.01468414e+03 1.00677094e+03 1.02007184e+03 1.05179541e+03 1.06717517e+03 1.09281567e+03 1.11329224e+03 1.14347791e+03 1.14431921e+03 1.14996228e+03 1.20584253e+03 1.26518884e+03 1.32581189e+03 1.31147888e+03 1.29017822e+03 1.35389392e+03 1.40232825e+03 1.47458350e+03 1.49089600e+03 1.47643933e+03 1.47970544e+03 1.49628650e+03 1.56765039e+03 1.60357629e+03 1.67022705e+03 1.70518152e+03 1.69050146e+03 1.69195642e+03 1.68601770e+03 1.77316394e+03 1.90729614e+03 1.91540454e+03 1.89696069e+03 1.87934302e+03 1.87852539e+03 2.00868176e+03 2.09972070e+03 2.07747070e+03 2.04398608e+03 2.07220605e+03 2.15521265e+03 2.19062769e+03 2.28387573e+03 2.33035767e+03 2.30057300e+03 2.30333569e+03 2.32932422e+03 2.45257935e+03 2.48531079e+03 2.41516968e+03 2.44261011e+03 2.62811841e+03 2.64019360e+03 2.53801294e+03 2.61330957e+03 2.77970093e+03 2.81309766e+03 2.79806494e+03 2.75144775e+03 2.77164014e+03 2.96655566e+03 3.03363330e+03 2.97930005e+03 2.93707471e+03 2.95840869e+03 3.08144727e+03 3.15312061e+03 3.18459033e+03 3.12857471e+03 3.23549854e+03 3.46072461e+03 3.40657642e+03 3.41620068e+03 3.46423584e+03 3.46707300e+03 3.49860718e+03 3.55084741e+03 3.59221826e+03 3.61577344e+03 3.61441772e+03 3.57792065e+03 3.71515820e+03 3.94549927e+03 3.84641064e+03 3.73803564e+03 3.90399463e+03 4.01255518e+03 4.16268262e+03 4.14684521e+03 4.05032275e+03 4.18740283e+03 4.26203809e+03 4.14799854e+03 4.18619141e+03 4.39522607e+03 4.43249561e+03 4.39403711e+03 4.35375635e+03 4.27585498e+03 4.52446045e+03 4.85395801e+03 4.78586719e+03 4.66177295e+03 4.60271826e+03 4.62487988e+03 4.89617480e+03 5.05763477e+03 4.93826025e+03 4.86303564e+03 4.88691162e+03 4.98744775e+03 5.07670508e+03 5.26496436e+03 5.28823242e+03 5.21488281e+03 5.27304395e+03 5.27619434e+03 5.46778125e+03 5.53360254e+03 5.48345605e+03 5.43386084e+03 5.45603662e+03 5.58756348e+03 5.52476904e+03 5.60242139e+03 5.92108252e+03 5.93290674e+03 5.89155957e+03 5.76698193e+03 5.74443408e+03 6.15647998e+03 6.21995898e+03 6.10615967e+03 6.04136279e+03 6.01003516e+03 6.17182031e+03 6.18867480e+03 6.33153076e+03 6.24398877e+03 6.41980859e+03 6.72184619e+03 6.57247607e+03 6.67624658e+03 6.72405176e+03 6.64819482e+03 6.64557471e+03 6.62473389e+03 6.70105811e+03 6.81493994e+03 6.90986279e+03 6.94446875e+03 7.03493506e+03 7.12548779e+03 6.92253955e+03 6.85344727e+03 7.11029541e+03 7.26559424e+03 7.53635547e+03 7.43525684e+03 7.24979199e+03 7.52235352e+03 7.53741406e+03 7.43965869e+03 7.52900879e+03 7.58443750e+03 7.55573877e+03 7.60784717e+03 7.71664258e+03 7.61853564e+03 7.78816211e+03 8.19747461e+03 8.11790479e+03 8.01783594e+03 7.93474854e+03 7.83452881e+03 8.35745703e+03 8.39078613e+03 8.23705859e+03 8.05125293e+03 7.95795801e+03 8.29542871e+03 8.48638770e+03 8.76615039e+03 8.55875391e+03 8.36664844e+03 8.56137793e+03 8.51069824e+03 8.86024219e+03 8.87925000e+03 8.64836523e+03 8.72701953e+03 8.74305664e+03 8.91164258e+03 8.69361230e+03 8.94171777e+03 9.44915332e+03 9.25994727e+03 9.21399805e+03 9.07099902e+03 8.94471973e+03 9.49523438e+03 9.59445117e+03 9.32776367e+03 9.18451367e+03 9.21041113e+03 9.45305664e+03 9.57084863e+03 9.85649805e+03 9.88969727e+03 9.67636719e+03 9.48954004e+03 9.47957031e+03 1.01304736e+04 1.00977666e+04 9.79373926e+03 9.97379395e+03 9.98625488e+03 9.90011230e+03 9.94409766e+03 1.02265947e+04 1.00666113e+04 9.91101953e+03 1.04723887e+04 1.06461465e+04 1.03258975e+04 1.02739160e+04 1.03819004e+04 1.04585947e+04 1.01911123e+04 1.01682383e+04 1.07769502e+04 1.08500410e+04 1.02570918e+04 1.01630977e+04 1.08246543e+04 1.12950889e+04 1.10300283e+04 1.06669805e+04 1.06237793e+04 1.11176699e+04 1.10640977e+04 1.08442754e+04 1.10698418e+04 1.08695088e+04 1.05750420e+04 1.10486807e+04 1.15734375e+04 1.15392773e+04 1.11332041e+04 1.08844043e+04 1.15021201e+04 1.17676445e+04 1.14434854e+04 1.12333623e+04 1.12235791e+04 1.13647383e+04 1.14471094e+04 1.18723809e+04 1.17291729e+04 1.13476104e+04 1.16508770e+04 1.17095303e+04 1.18863311e+04 1.16849160e+04 1.14675977e+04 1.19777061e+04 1.19979941e+04 1.19248525e+04 1.16458203e+04 1.17533613e+04 1.24755859e+04 1.20442266e+04 1.17154834e+04 1.20526016e+04 1.21029463e+04 1.21526670e+04 1.21863047e+04 1.24824727e+04 1.25892588e+04 1.22849805e+04 1.19424775e+04 1.19451670e+04 1.26623369e+04 1.24995889e+04 1.21492344e+04 1.24343018e+04 1.24682695e+04 1.24911133e+04 1.25383232e+04 1.27734004e+04 1.24764912e+04 1.22466318e+04 1.28043320e+04 1.28714971e+04 1.27190010e+04 1.27785811e+04 1.27876885e+04 1.27775254e+04 1.24350732e+04 1.23165967e+04 1.30096846e+04 1.33262148e+04 1.26546826e+04 1.23198867e+04 1.30142744e+04 1.34795625e+04 1.31528799e+04 1.27230273e+04 1.25796201e+04 1.31912529e+04 1.33057744e+04 1.29228057e+04 1.32699990e+04 1.33124258e+04 1.29044150e+04 1.28698730e+04 1.32790430e+04 1.35080410e+04 1.29768027e+04 1.27369570e+04 1.34335859e+04 1.36424512e+04 1.33000791e+04 1.29413623e+04 1.28420684e+04 1.35652646e+04 1.37204033e+04 1.32518633e+04 1.32140869e+04 1.33006064e+04 1.32462881e+04 1.32067422e+04 1.37542568e+04 1.34806953e+04 1.30013779e+04 1.36487109e+04 1.37740488e+04 1.36208525e+04 1.32854414e+04 1.31302207e+04 1.36701475e+04 1.34314746e+04 1.35166035e+04 1.48282295e+04 1.43341816e+04 1.39144023e+04 1.34240889e+04 2.50735723e+04 3.81181250e+04 3.40162461e+04 3.94151562e+04 4.05184961e+04 2.26927246e+04 4.06333125e+04 1.27191250e+05 2.93514598e+09 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. 0. 0. 7.91520512e+09 9.16553438e+04 9.66020859e+04 6.68936250e+04 3.90838203e+04 2.65150332e+04 1.78614062e+04 1.53934648e+04 1.49469209e+04 1.39799248e+04 1.37044756e+04 1.37100781e+04 1.37993428e+04 1.35476934e+04 1.33976650e+04 1.34241455e+04 1.33464785e+04 1.35744922e+04 1.38513682e+04 1.40347773e+04 1.34573574e+04 1.31313652e+04 1.35743545e+04 1.32062607e+04 1.28032451e+04 1.33806523e+04 1.38419932e+04 1.37333398e+04 1.35214375e+04 1.31733125e+04 1.31823438e+04 1.33859287e+04 1.32528340e+04 1.30866895e+04 1.34157480e+04 1.36172480e+04 1.32742891e+04 1.31375820e+04 1.32358418e+04 1.32430059e+04 1.33115293e+04 1.31989141e+04 1.29080195e+04 1.32018760e+04 1.35219375e+04 1.30198857e+04 1.29028525e+04 1.31558877e+04 1.28690332e+04 1.29350244e+04 1.32674268e+04 1.30648096e+04 1.28765996e+04 1.30518213e+04 1.32895850e+04 1.29969014e+04 1.26041221e+04 1.25742451e+04 1.25987031e+04 1.30139727e+04 1.32133389e+04 1.28218770e+04 1.27035264e+04 1.26501074e+04 1.25944316e+04 1.26211270e+04 1.25096094e+04 1.24117090e+04 1.26215596e+04 1.29572080e+04 1.26331865e+04 1.23733604e+04 1.26010078e+04 1.25273906e+04 1.23832383e+04 1.24290977e+04 1.24896299e+04 1.23555107e+04 1.22140967e+04 1.23990938e+04 1.23458848e+04 1.22990176e+04 1.22767295e+04 1.19599453e+04 1.21304277e+04 1.24471270e+04 1.21860449e+04 1.19557891e+04 1.20224404e+04 1.19604678e+04 1.19926348e+04 1.19296250e+04 1.17069189e+04 1.18865381e+04 1.22170850e+04 1.19621934e+04 1.15748291e+04 1.16128477e+04 1.18219375e+04 1.17941885e+04 1.16602236e+04 1.15988887e+04 1.14191123e+04 1.16322559e+04 1.18573027e+04 1.14744570e+04 1.12419932e+04 1.12288027e+04 1.12229053e+04 1.14275527e+04 1.14607070e+04 1.12494932e+04 1.12683086e+04 1.14964990e+04 1.13949414e+04 1.10645361e+04 1.09055889e+04 1.08814805e+04 1.09908652e+04 1.11010312e+04 1.10902461e+04 1.08942285e+04 1.09008418e+04 1.09165762e+04 1.06456758e+04 1.05839141e+04 1.07072607e+04 1.06141494e+04 1.07377744e+04 1.08370967e+04 1.04104834e+04 1.03763086e+04 1.06019727e+04 1.04398096e+04 1.01855332e+04 1.02919668e+04 1.05556191e+04 1.04208770e+04 1.02713252e+04 1.01549766e+04 1.00757178e+04 1.00497480e+04 9.92045703e+03 9.96117773e+03 1.00239375e+04 9.94060352e+03 9.87640137e+03 9.96558789e+03 9.84924707e+03 9.50549902e+03 9.61076953e+03 9.79668457e+03 9.59643066e+03 9.64843945e+03 9.73060449e+03 9.64897363e+03 9.36180469e+03 9.30071680e+03 9.29782520e+03 9.12437891e+03 9.26503320e+03 9.39314453e+03 9.24955859e+03 9.11250684e+03 9.02218262e+03 8.99257812e+03 8.99462598e+03 8.88366797e+03 8.74969727e+03 8.82640234e+03 8.91990625e+03 8.75215820e+03 8.65512598e+03 8.72046777e+03 8.59923828e+03 8.65409668e+03 8.49074121e+03 8.41398926e+03 8.50668066e+03 8.40841211e+03 8.36076367e+03 8.26040332e+03 8.26726953e+03 8.34920996e+03 7.97837305e+03 7.98022119e+03 8.20927441e+03 8.02067529e+03 8.04589844e+03 7.95553906e+03 7.82768604e+03 7.76750293e+03 7.68467871e+03 7.61698340e+03 7.59195703e+03 7.65754590e+03 7.71241113e+03 7.76353076e+03 7.59164941e+03 7.47186719e+03 7.40674121e+03 7.25225977e+03 7.17037207e+03 7.17658789e+03 7.28447754e+03 7.36848096e+03 7.07252539e+03 6.97043896e+03 7.06747656e+03 6.83638623e+03 6.90450781e+03 6.99360205e+03 6.81501904e+03 6.74793457e+03 6.76674268e+03 6.77143555e+03 6.68928760e+03 6.54552881e+03 6.52233838e+03 6.37705859e+03 6.40356104e+03 6.44411084e+03 6.44238818e+03 6.33055176e+03 6.30553662e+03 6.27638574e+03 6.13002734e+03 6.14074219e+03 6.18035693e+03 6.00253613e+03 5.85448242e+03 5.92990576e+03 5.89694678e+03 5.88579541e+03 5.78406934e+03 5.66649854e+03 5.72234473e+03 5.63642725e+03 5.63278467e+03 5.56735938e+03 5.59745996e+03 5.53992139e+03 5.29818262e+03 5.33759961e+03 5.31854053e+03 5.23594482e+03 5.33070898e+03 5.15539941e+03 5.03307373e+03 5.18745410e+03 5.14417676e+03 4.89766553e+03 4.84235645e+03 4.96192529e+03 4.91929932e+03 4.76695166e+03 4.77927930e+03 4.83924707e+03 4.65361279e+03 4.58794629e+03 4.57818311e+03 4.45045605e+03 4.50262646e+03 4.52227002e+03 4.37481299e+03 4.38906543e+03 4.40952979e+03 4.28786182e+03 4.19225342e+03 4.13367480e+03 4.14449561e+03 4.18009033e+03 4.04192017e+03 3.95748926e+03 3.95399683e+03 3.93823364e+03 3.85770190e+03 3.81107568e+03 3.79538745e+03 3.76145776e+03 3.69370703e+03 3.69089673e+03 3.69088574e+03 3.56855298e+03 3.53310620e+03 3.52475586e+03 3.40337402e+03 3.46119360e+03 3.42396973e+03 3.26631250e+03 3.30783545e+03 3.26156006e+03 3.17992334e+03 3.19951392e+03 3.12807056e+03 3.09668628e+03 3.11482739e+03 3.01281128e+03 2.96357690e+03 2.92593774e+03 2.85426538e+03 2.82146460e+03 2.79366675e+03 2.80230029e+03 2.78576929e+03 2.73014062e+03 2675. 2.65495923e+03 2.59669214e+03 2.51548145e+03 2.50336255e+03 2.53449609e+03 2.48362280e+03 2.37909106e+03 2.32714429e+03 2.34174072e+03 2.33650806e+03 2.26121802e+03 2.20021021e+03 2.18608081e+03 2.17088916e+03 2.16045752e+03 2.10430151e+03 2.03724634e+03 1.98635095e+03 1.95907544e+03 1.94915454e+03 1.90949695e+03 1.89404211e+03 1.87816492e+03 1.82088843e+03 1.79744580e+03 1.80049768e+03 1.74439563e+03 1.66909338e+03 1.66597034e+03 1.67572839e+03 1.61527417e+03 1.53028491e+03 1.49859119e+03 1.51086938e+03 1.50160315e+03 1.45590491e+03 1.42170361e+03 1.39073975e+03 1.38262048e+03 1.35353174e+03 1.27781396e+03 1.25288708e+03 1.25484668e+03 1.24224646e+03 1.19421692e+03 1.14555298e+03 1.13580518e+03 1.11451196e+03 1.10074854e+03 1.09007874e+03 1.05798157e+03 1.00426434e+03 9.59559753e+02 9.64780579e+02 9.67314697e+02 9.22805786e+02 8.81657776e+02 8.52383972e+02 8.43511475e+02 8.39710510e+02 7.96856140e+02 7.71152100e+02 7.58134705e+02 7.46576172e+02 7.25829163e+02 6.80811462e+02 6.67443726e+02 6.53998230e+02 6.26669983e+02 6.11917969e+02 5.89606018e+02 5.68691589e+02 5.50996216e+02 5.31268555e+02 5.15123718e+02 5.03574554e+02 4.86436981e+02 4.60052063e+02 4.46836884e+02 4.33254639e+02 4.12210815e+02 3.95154663e+02 3.70480377e+02 3.59356415e+02 3.57791016e+02 3.39806549e+02 3.19082703e+02 2.98655609e+02 2.87925720e+02 2.83923889e+02 2.66325043e+02 2.51728653e+02 2.42303833e+02 2.27085815e+02 2.12290756e+02 2.03404144e+02 1.92988800e+02 1.78843918e+02 1.70508224e+02 1.59944702e+02 1.46287048e+02 1.39542145e+02 1.31114563e+02 1.21584068e+02 1.14608925e+02 1.05289627e+02 9.62730408e+01 8.77789917e+01 8.00703659e+01 7.39037170e+01 6.75623550e+01 6.08053818e+01 5.42271576e+01 4.87581825e+01 4.30405388e+01 3.76956367e+01 3.35487862e+01 2.87666969e+01 2.43501701e+01 2.07696133e+01 1.73771744e+01 1.41979532e+01 1.13780785e+01 8.84188175e+00 6.60995579e+00 4.90239096e+00 3.44104147e+00 2.23287582e+00 1.40584040e+00 9.27273095e-01 7.77292669e-01 9.53815281e-01 1.46444821e+00 2.31863666e+00 3.56601405e+00 5.12166214e+00 7.10469103e+00 9.13458252e+00 1.13043070e+01 1.44322805e+01 1.78910732e+01 2.11582680e+01 2.48169060e+01 2.90902691e+01 3.37135315e+01 3.86589890e+01 4.37147522e+01 4.85640602e+01 5.43658600e+01 6.15269356e+01 6.79532471e+01 7.43140488e+01 8.11101303e+01 8.86237259e+01 9.75791779e+01 1.05656029e+02 1.14432350e+02 1.23320335e+02 1.31706512e+02 1.40796677e+02 1.51419586e+02 1.62153061e+02 1.68322983e+02 1.78803284e+02 1.94281174e+02 2.06421188e+02 2.19729477e+02 2.28168396e+02 2.39572067e+02 2.51552628e+02 2.64057709e+02 2.84443787e+02 2.91317780e+02 3.04054535e+02 3.27734436e+02 3.33293823e+02 3.45101746e+02 3.70624146e+02 3.85671021e+02 4.00461792e+02 4.20466888e+02 4.29500519e+02 4.33350342e+02 4.63362427e+02 4.90488647e+02 4.97111877e+02 5.27501953e+02 5.45920105e+02 5.45104797e+02 5.66752319e+02 5.86986267e+02 6.06423584e+02 6.37353088e+02 6.57680420e+02 6.75505798e+02 6.96240540e+02 7.15501526e+02 7.42960144e+02 7.59264099e+02 7.71452454e+02 7.98510315e+02 8.25453552e+02 8.40776917e+02 8.71860901e+02 9.01662598e+02 9.11257935e+02 9.43491455e+02 9.74014709e+02 9.99273987e+02 1.02289246e+03 1.02178796e+03 1.05629321e+03 1.11388794e+03 1.13481104e+03 1.13514294e+03 1.17189539e+03 1.21114709e+03 1.23241272e+03 1.25711719e+03 1.24775391e+03 1.27046570e+03 1.34278650e+03 1.39005725e+03 1.41708875e+03 1.40763647e+03 1.43557031e+03 1.49544238e+03 1.51384229e+03 1.53878870e+03 1.57205115e+03 1.59253394e+03 1.63323376e+03 1.67029285e+03 1.72040027e+03 1.72856311e+03 1.73371765e+03 1.81844104e+03 1.82851086e+03 1.83824597e+03 1.87331055e+03 1.88870728e+03 1.95569617e+03 2.04045129e+03 2.06109814e+03 2.02017285e+03 2.05673047e+03 2.14382764e+03 2.17545117e+03 2.20688867e+03 2.22623999e+03 2.28137671e+03 2.32334229e+03 2.34560815e+03 2.39951855e+03 2.40536694e+03 2.45137402e+03 2.52128735e+03 2.45049438e+03 2.48907056e+03 2.62750879e+03 2.67082446e+03 2.67331079e+03 2.69733447e+03 2.70621875e+03 2.75043652e+03 2.86013306e+03 2.92860449e+03 2.90384180e+03 2.90151367e+03 2.92421680e+03 3.00028979e+03 3.07645996e+03 3.13705420e+03 3.18604541e+03 3.16567847e+03 3.21111963e+03 3.27209814e+03 3.25411011e+03 3.29037085e+03 3.42238794e+03 3.46475659e+03 3.46324072e+03 3.50008936e+03 3.53641357e+03 3.59414893e+03 3.60516724e+03 3.69742847e+03 3.71295093e+03 3.77166479e+03 3.80289429e+03 3.81118555e+03 3.99640942e+03 3.92797266e+03 3.93610718e+03 4.09475977e+03 4.03417432e+03 4.05124048e+03 4.16353711e+03 4.21720117e+03 4.19032959e+03 4.33646924e+03 4.42220459e+03 4.36775342e+03 4.52966992e+03 4.61472461e+03 4.31832373e+03 4.13885010e+03 4.96167773e+03 5.39876514e+03 5.73174707e+03 6.31042773e+03 8.56675977e+03 6.48956689e+03 1.09427822e+04 1.02584922e+05 -54726096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -59475064. 1.86131262e+06 -2.15324925e+06 5.55218650e+06 50698256. -9.74110500e+05 -2.54279475e+06 2.04643262e+04 1.64558340e+04 9.68916016e+03 6.98644238e+03 7.57162646e+03 7.73135010e+03 7.53344775e+03 7.50941846e+03 7.56016504e+03 7.54493115e+03 7.73368066e+03 7.84254150e+03 7.71404395e+03 7.55702246e+03 7.76306934e+03 7.92875439e+03 7.95381836e+03 7.98367188e+03 7.72189551e+03 7.85029883e+03 8.29012305e+03 8.14950098e+03 8.02653955e+03 8.00459082e+03 8.11763525e+03 8.53729004e+03 8.64375977e+03 8.42250195e+03 8.11796436e+03 8.29971387e+03 8.61639746e+03 8.68709961e+03 8.64302344e+03 8.59873535e+03 8.75965723e+03 8.85653320e+03 8.87646973e+03 8.98697168e+03 8.66897266e+03 8.88653027e+03 9.41194434e+03 9.07099414e+03 8.92492969e+03 8.99627734e+03 9.01666016e+03 9.39235449e+03 9.45871973e+03 9.22173730e+03 9.12563574e+03 9.46421094e+03 9.67246094e+03 9.54050098e+03 9.47471973e+03 9.36167090e+03 9.62371680e+03 9.92293555e+03 9.64758008e+03 9.71297266e+03 9.68607324e+03 9.65477734e+03 1.00144053e+04 1.01487900e+04 1.00081172e+04 9.84815234e+03 1.00295029e+04 1.01297637e+04 1.02044814e+04 1.03033594e+04 9.99189355e+03 1.00611641e+04 1.06461172e+04 1.03950732e+04 1.00443105e+04 1.00930654e+04 1.05111553e+04 1.08782197e+04 1.07305107e+04 1.06084785e+04 1.04739209e+04 1.03840508e+04 1.06663857e+04 1.09890508e+04 1.08207441e+04 1.05847363e+04 1.08889180e+04 1.09773809e+04 1.09609980e+04 1.12501094e+04 1.08708936e+04 1.08013994e+04 1.13243486e+04 1.12743711e+04 1.10698682e+04 1.10234521e+04 1.09934238e+04 1.14169238e+04 1.15408096e+04 1.12536523e+04 1.12323584e+04 1.15092334e+04 1.15834297e+04 1.14795381e+04 1.16704277e+04 1.15007344e+04 1.13950039e+04 1.18512324e+04 1.17620420e+04 1.14548145e+04 1.14218438e+04 1.16366436e+04 1.21158984e+04 1.21743252e+04 1.19630029e+04 1.15824805e+04 1.15377832e+04 1.21385898e+04 1.22257900e+04 1.19067617e+04 1.18322822e+04 1.20524844e+04 1.23026162e+04 1.21771807e+04 1.20776924e+04 1.19302393e+04 1.22101348e+04 1.27095830e+04 1.23280098e+04 1.22386768e+04 1.23601777e+04 1.22191748e+04 1.24624424e+04 1.25522754e+04 1.24051719e+04 1.22080518e+04 1.23601475e+04 1.28556465e+04 1.28629531e+04 1.26809424e+04 1.24111982e+04 1.23985312e+04 1.28499658e+04 1.29210752e+04 1.28321719e+04 1.24908975e+04 1.23531318e+04 1.28096592e+04 1.31020625e+04 1.30208643e+04 1.27002568e+04 1.27388477e+04 1.28986357e+04 1.30010762e+04 1.31857061e+04 1.29397188e+04 1.28829512e+04 1.31191348e+04 1.30215146e+04 1.29814795e+04 1.29280723e+04 1.31932119e+04 1.33058027e+04 1.29763955e+04 1.30091279e+04 1.29687852e+04 1.32248770e+04 1.37130996e+04 1.33950879e+04 1.29844805e+04 1.29355361e+04 1.31321826e+04 1.35604736e+04 1.37125039e+04 1.35650078e+04 1.30702363e+04 1.27575850e+04 1.33001855e+04 1.37034121e+04 1.37333408e+04 1.32050801e+04 1.30814639e+04 1.35734756e+04 1.35794717e+04 1.36002754e+04 1.34227070e+04 1.33118652e+04 1.35057070e+04 1.34348779e+04 1.34857275e+04 1.35094600e+04 1.34562285e+04 1.37520449e+04 1.35785166e+04 1.34405957e+04 1.35103027e+04 1.36433242e+04 1.38098672e+04 1.35697393e+04 1.33296494e+04 1.33180146e+04 1.38872031e+04 1.40910820e+04 1.36790762e+04 1.35211172e+04 1.31944258e+04 1.33668975e+04 1.40660254e+04 1.40488643e+04 1.38030039e+04 1.33035605e+04 1.32060781e+04 1.39980059e+04 1.41885430e+04 1.36797510e+04 1.36037539e+04 1.38185205e+04 1.37235205e+04 1.35281250e+04 1.32605986e+04 1.31915244e+04 1.34374463e+04 1.38163447e+04 1.42556143e+04 1.39604678e+04 1.32438623e+04 1.34438486e+04 1.37357520e+04 1.36960586e+04 1.37978838e+04 1.35834727e+04 1.39515088e+04 1.39718535e+04 1.32286445e+04 1.30636904e+04 1.34085156e+04 1.39645703e+04 1.43705215e+04 1.40929287e+04 1.33404141e+04 1.28616465e+04 1.31672500e+04 1.39578232e+04 1.43709014e+04 1.40115322e+04 1.32077490e+04 1.30911875e+04 1.40298740e+04 1.39935254e+04 1.32226201e+04 1.33213701e+04 1.34611318e+04 1.34274805e+04 1.38572158e+04 1.35722373e+04 1.30792520e+04 1.34189502e+04 1.32049189e+04 1.34904980e+04 1.37044336e+04 1.30394443e+04 1.34153359e+04 1.37720020e+04 1.34096367e+04 1.33785381e+04 1.33560752e+04 1.33523818e+04 1.34014512e+04 1.33631289e+04 1.29119463e+04 1.28425352e+04 1.35655352e+04 1.40031475e+04 1.36261787e+04 1.29121221e+04 1.26100127e+04 1.28466621e+04 1.34205967e+04 1.37641436e+04 1.34319453e+04 1.28397949e+04 1.27964053e+04 1.31209209e+04 1.31033262e+04 1.29664736e+04 1.29696553e+04 1.29222344e+04 1.28780654e+04 1.33677363e+04 1.30593652e+04 1.26080596e+04 1.29364531e+04 1.25999297e+04 1.28628047e+04 1.30684883e+04 1.26333086e+04 1.31153760e+04 1.28548330e+04 1.22854121e+04 1.27046670e+04 1.23555859e+04 1.24726885e+04 1.33595068e+04 1.26808193e+04 1.18981104e+04 1.21219248e+04 1.27878672e+04 1.32498145e+04 1.28903428e+04 1.21415439e+04 1.18777158e+04 1.20109014e+04 1.24811074e+04 1.29593965e+04 1.26670488e+04 1.19291914e+04 1.18570234e+04 1.21954600e+04 1.22680537e+04 1.21535596e+04 1.21033760e+04 1.20610898e+04 1.19610371e+04 1.23849971e+04 1.23785840e+04 1.15757461e+04 1.15260205e+04 1.19294463e+04 1.19201377e+04 1.18736572e+04 1.17965225e+04 1.20783320e+04 1.18015068e+04 1.13156475e+04 1.16189941e+04 1.12944854e+04 1.15564531e+04 1.23123076e+04 1.15461807e+04 1.08079502e+04 1.11396348e+04 1.16698760e+04 1.19399189e+04 1.18352871e+04 1.10746924e+04 1.06928467e+04 1.09604287e+04 1.13963350e+04 1.16961934e+04 1.14442012e+04 1.07622900e+04 1.06795879e+04 1.10631562e+04 1.10889893e+04 1.12322041e+04 1.12397070e+04 1.05966982e+04 1.04725742e+04 1.09924658e+04 1.10145986e+04 1.05224883e+04 1.04481484e+04 1.06446650e+04 1.04659297e+04 1.07960449e+04 1.08302705e+04 1.03615342e+04 1.02713848e+04 1.01991006e+04 1.02525312e+04 1.02930625e+04 1.01418984e+04 1.04205156e+04 1.05520127e+04 1.01715527e+04 9.82163770e+03 9.54146875e+03 9.97273926e+03 1.05507969e+04 1.02237568e+04 9.58484473e+03 9.36729590e+03 9.66644531e+03 1.01903799e+04 9.87795703e+03 9.23373242e+03 9.35281641e+03 9.58797461e+03 9.82842578e+03 1.00068555e+04 9.67411816e+03 9.09197852e+03 9.06050684e+03 9.25607812e+03 9.32296777e+03 9.30722754e+03 9.22741406e+03 9.17429590e+03 9.06340039e+03 9.13001953e+03 9.00028809e+03 8.82065234e+03 8.78414551e+03 8.63061426e+03 8.93357227e+03 8.97505273e+03 8.68511523e+03 8.80266504e+03 8.76367480e+03 8.60493652e+03 8.38058887e+03 8.14501074e+03 8.50348730e+03 8.82036719e+03 8.56936133e+03 8.14355371e+03 7.98440332e+03 8.38159375e+03 8.49293164e+03 8.20418945e+03 8.08605225e+03 7.81044482e+03 7.74686523e+03 8.07925732e+03 7.97591260e+03 7.76652734e+03 7.55826660e+03 7.43307666e+03 7.82686768e+03 8.05784473e+03 7.54532715e+03 7.35499512e+03 7.53145508e+03 7.48467822e+03 7.65685254e+03 7.52101953e+03 7.05108057e+03 7.09961377e+03 7.31293994e+03 7.17053418e+03 7.15035596e+03 7.14592090e+03 7.35756104e+03 7.17393555e+03 6.60786914e+03 6.83649707e+03 6.82451953e+03 7.08772900e+03 6.72933008e+03 6.48899023e+03 6.42861133e+03 8.39776172e+03 8.21421387e+03 9.85039648e+03 8.21369727e+03 1.19093262e+04 2.07223848e+04 2.71029062e+04 4893892. 6.71785150e+06 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. 0. 0. 0. 0. 0. 0. -599992064. -599992064. 4.74704250e+06 7.55347850e+06 5966827. 2.52368150e+06 1.37184990e+04 1.04129746e+04 5.35389941e+03 4.27152930e+03 4.94409912e+03 4.38129004e+03 3.99174292e+03 4.11570801e+03 4.08469165e+03 3.92815381e+03 3.89050122e+03 3.86172900e+03 3.87198193e+03 3.87046362e+03 3.70051782e+03 3.53350146e+03 3.62370654e+03 3.57830737e+03 3.31016260e+03 3.47040454e+03 3.54762012e+03 3.23464014e+03 3.38985278e+03 3.50574951e+03 3.30219873e+03 3.18698096e+03 3.22529004e+03 3.26216943e+03 3.17059155e+03 3.11664893e+03 3.05540576e+03 3.01092480e+03 2.92749048e+03 2.89274707e+03 2.93775610e+03 2.90995532e+03 2.82102222e+03 2.77184375e+03 2.74737769e+03 2.71918115e+03 2.65849316e+03 2.62074243e+03 2.59015039e+03 2.52156274e+03 2.48000928e+03 2.43438086e+03 2.39819604e+03 2.48273022e+03 2.45106372e+03 2.32763721e+03 2.23053589e+03 2.19173145e+03 2.29380103e+03 2.27105176e+03 2.15358618e+03 2.06458569e+03 2.04026440e+03 2.04185229e+03 1.99947083e+03 2.04476501e+03 2.01743799e+03 1.85654785e+03 1.79381445e+03 1.85477405e+03 1.92406787e+03 1.84121057e+03 1.75131958e+03 1.72121655e+03 1.68368579e+03 1.66432239e+03 1.64637183e+03 1.59064661e+03 1.54749646e+03 1.52845129e+03 1.49564233e+03 1.46692358e+03 1.43995020e+03 1.45287073e+03 1.41780359e+03 1.35235425e+03 1.32103711e+03 1.29221570e+03 1.29992676e+03 1.27568628e+03 1.22551184e+03 1.20035400e+03 1.14437500e+03 1.09225879e+03 1.12115466e+03 1.11321326e+03 1.02793188e+03 1.00768109e+03 1.03920166e+03 1.04403906e+03 9.89757019e+02 9.37356628e+02 9.14074158e+02 8.91256897e+02 8.58490479e+02 8.33726868e+02 8.19357910e+02 7.93627136e+02 7.97708618e+02 7.71100159e+02 7.27273132e+02 7.08713928e+02 6.69825745e+02 6.63783264e+02 6.81370972e+02 6.50493469e+02 6.13663025e+02 5.77049683e+02 5.50346191e+02 5.61462463e+02 5.55212097e+02 5.21149902e+02 4.87080750e+02 4.67871796e+02 4.60711334e+02 4.43267670e+02 4.41685852e+02 4.27168854e+02 3.95945282e+02 3.74260132e+02 3.58187592e+02 3.56178009e+02 3.43284485e+02 3.21064575e+02 3.04050507e+02 2.90226868e+02 2.75906738e+02 2.55662964e+02 2.49174622e+02 2.51173706e+02 2.33895508e+02 2.15158203e+02 1.99148178e+02 1.86554764e+02 1.85811905e+02 1.75883118e+02 1.60153931e+02 1.46350311e+02 1.36125900e+02 1.30917175e+02 1.21916382e+02 1.12893585e+02 1.01274704e+02 9.54912033e+01 9.28562241e+01 8.29321823e+01 7.48475113e+01 6.83257980e+01 6.10361443e+01 5.41043320e+01 4.85192451e+01 4.31539230e+01 3.76407280e+01 3.29618988e+01 2.79097080e+01 2.44600220e+01 2.18916283e+01 1.74350548e+01 1.38177862e+01 1.13454390e+01 8.82309532e+00 6.85229874e+00 4.97562933e+00 3.38376784e+00 2.28767967e+00 1.45027685e+00 9.40856755e-01 7.77099848e-01 9.46859360e-01 1.43786240e+00 2.25993824e+00 3.41349316e+00 4.81401300e+00 6.82387638e+00 9.46786404e+00 1.18098593e+01 1.41886196e+01 1.68471050e+01 2.05350437e+01 2.57075386e+01 2.97885551e+01 3.35830765e+01 3.74761429e+01 4.22270699e+01 4.91975441e+01 5.50538063e+01 6.22103462e+01 6.80234833e+01 7.27348251e+01 8.05616913e+01 8.81773682e+01 9.92350464e+01 1.07832863e+02 1.12709496e+02 1.20697708e+02 1.30225021e+02 1.39624176e+02 1.45598389e+02 1.58734100e+02 1.78391113e+02 1.86837067e+02 1.92521057e+02 1.98665756e+02 2.09317169e+02 2.33581924e+02 2.47415009e+02 2.52576370e+02 2.59914520e+02 2.71794434e+02 2.93739441e+02 3.08719696e+02 3.29075623e+02 3.41964569e+02 3.47971680e+02 3.58999298e+02 3.73795929e+02 4.07576813e+02 4.25733887e+02 4.30238007e+02 4.39098663e+02 4.55118561e+02 4.90768585e+02 5.11303070e+02 5.03219086e+02 5.19963928e+02 5.73159119e+02 5.88371094e+02 5.76667297e+02 5.96411621e+02 6.45697632e+02 6.72123474e+02 6.69673157e+02 6.71745422e+02 6.95176392e+02 7.57542603e+02 7.76363342e+02 7.72711670e+02 8.04018921e+02 8.23427612e+02 8.28002502e+02 8.50302246e+02 8.97344666e+02 8.97332642e+02 9.37044434e+02 1.00389459e+03 1.00062994e+03 1.03467053e+03 1.05857385e+03 1.06643896e+03 1.09554297e+03 1.11633533e+03 1.14033545e+03 1.14708337e+03 1.15497266e+03 1.20693823e+03 1.25995496e+03 1.32519019e+03 1.31093237e+03 1.29906677e+03 1.36594055e+03 1.39595276e+03 1.46361951e+03 1.48905444e+03 1.47482043e+03 1.48238855e+03 1.50155103e+03 1.56877014e+03 1.60073340e+03 1.67228552e+03 1.69946045e+03 1.68085535e+03 1.70933655e+03 1.69760779e+03 1.77432507e+03 1.90484546e+03 1.91127393e+03 1.89279810e+03 1.87962109e+03 1.89441284e+03 2.01836243e+03 2.08350757e+03 2.06595728e+03 2.04280615e+03 2.07402393e+03 2.16323657e+03 2.18160352e+03 2.28197266e+03 2.30717822e+03 2.27819238e+03 2.31939746e+03 2.35512280e+03 2.45674341e+03 2.48630884e+03 2.41012354e+03 2.45169263e+03 2.63070288e+03 2.62207910e+03 2.51401880e+03 2.62660303e+03 2.80747852e+03 2.82461182e+03 2.79895215e+03 2.75491846e+03 2.78121094e+03 2.97382227e+03 3.02621777e+03 2.97514209e+03 2.94150415e+03 2.96503638e+03 3.08868433e+03 3.13721606e+03 3.18095142e+03 3.15025269e+03 3.25394556e+03 3.44049316e+03 3.40814697e+03 3.40590723e+03 3.43143701e+03 3.45194824e+03 3.50111865e+03 3.55990576e+03 3.59950366e+03 3.63296826e+03 3.65546582e+03 3.60676196e+03 3.69635205e+03 3.93706763e+03 3.83856885e+03 3.71625464e+03 3.87627124e+03 4.03550000e+03 4.19244336e+03 4.17298242e+03 4.10770410e+03 4.16470166e+03 4.22145361e+03 4.15800244e+03 4.18104834e+03 4.37516895e+03 4.42148975e+03 4.37019482e+03 4.38470703e+03 4.30408057e+03 4.53321777e+03 4.82573584e+03 4.73267188e+03 4.66564648e+03 4.60571240e+03 4.65097314e+03 4.93212939e+03 5.06109131e+03 4.96261816e+03 4.87874707e+03 4.88761621e+03 4.96286377e+03 5.07636621e+03 5.28527197e+03 5.27573877e+03 5.19640381e+03 5.25789795e+03 5.28996631e+03 5.41804639e+03 5.47347021e+03 5.41294287e+03 5.51795264e+03 5.58824854e+03 5.53469971e+03 5.44420215e+03 5.64059570e+03 5.95166162e+03 5.93931885e+03 5.82729785e+03 5.74779736e+03 5.81693262e+03 6.21629736e+03 6.23294922e+03 6.06218750e+03 6.01817432e+03 6.01912207e+03 6.14176758e+03 6.22590625e+03 6.31768115e+03 6.22510938e+03 6.39139062e+03 6.73732568e+03 6.52947266e+03 6.65011719e+03 6.72455566e+03 6.66332227e+03 6.70050488e+03 6.76774805e+03 6.61670898e+03 6.68622852e+03 6.96149121e+03 7.05304834e+03 7.06540918e+03 7.11019189e+03 6.90681055e+03 6.88509326e+03 7.15980176e+03 7.24225439e+03 7.50837207e+03 7.47486621e+03 7.17242725e+03 7.42409375e+03 7.58308496e+03 7.53439746e+03 7.48204883e+03 7.49607324e+03 7.64469336e+03 7.73786719e+03 7.71880664e+03 7.57857422e+03 7.78003174e+03 8.24255859e+03 8.13849854e+03 7.94318457e+03 7.81077539e+03 7.85349463e+03 8.40229102e+03 8.35159863e+03 8.25418066e+03 8.03905615e+03 7.94867139e+03 8.30739941e+03 8.53602832e+03 8.79594727e+03 8.56645312e+03 8.26116602e+03 8.46021777e+03 8.56845508e+03 8.96250879e+03 8.79585938e+03 8.60365625e+03 8.86147461e+03 8.91779199e+03 8.85682617e+03 8.71849121e+03 8.89291113e+03 9.45428906e+03 9.33239062e+03 9.09964062e+03 8.91258496e+03 9.00417480e+03 9.51963867e+03 9.58436426e+03 9.36973145e+03 9.21721387e+03 9.16130176e+03 9.46177246e+03 9.56311328e+03 9.85727051e+03 9.91276172e+03 9.57333203e+03 9.42220703e+03 9.65374609e+03 1.01256504e+04 9.97145703e+03 9.80128223e+03 1.00435732e+04 1.00307422e+04 9.81826074e+03 9.73557715e+03 1.01471611e+04 1.01394248e+04 1.00032949e+04 1.04796982e+04 1.06003018e+04 1.03610439e+04 1.03625713e+04 1.04055508e+04 1.03871992e+04 1.01625898e+04 1.01623213e+04 1.06792158e+04 1.09046475e+04 1.03950557e+04 1.01817314e+04 1.07141729e+04 1.11874209e+04 1.11082109e+04 1.07690586e+04 1.05606738e+04 1.09680449e+04 1.12639453e+04 1.11003037e+04 1.10142549e+04 1.07370352e+04 1.05582871e+04 1.11322578e+04 1.16820820e+04 1.14860830e+04 1.10466338e+04 1.09327646e+04 1.15451562e+04 1.17503340e+04 1.14473330e+04 1.11575459e+04 1.10746094e+04 1.12897021e+04 1.14466309e+04 1.18799590e+04 1.19131797e+04 1.15280938e+04 1.15309746e+04 1.16017949e+04 1.18932979e+04 1.16667002e+04 1.14959385e+04 1.20973672e+04 1.21201133e+04 1.18286006e+04 1.15212725e+04 1.17631123e+04 1.24676934e+04 1.20142959e+04 1.15849111e+04 1.20048887e+04 1.22259287e+04 1.22843086e+04 1.21747051e+04 1.24846367e+04 1.26129531e+04 1.22335977e+04 1.18748145e+04 1.19614434e+04 1.27355469e+04 1.25247207e+04 1.21816260e+04 1.24567100e+04 1.25035352e+04 1.24386436e+04 1.24000654e+04 1.26445498e+04 1.25854346e+04 1.23600840e+04 1.27154199e+04 1.27666094e+04 1.28219492e+04 1.28819209e+04 1.27596650e+04 1.26909844e+04 1.23190508e+04 1.24469473e+04 1.32128408e+04 1.33951377e+04 1.26539043e+04 1.22891055e+04 1.28855693e+04 1.33668936e+04 1.32720273e+04 1.28358379e+04 1.24305254e+04 1.30347754e+04 1.34523516e+04 1.30207197e+04 1.32920088e+04 1.32282129e+04 1.27149854e+04 1.30412197e+04 1.35493008e+04 1.34536865e+04 1.28711934e+04 1.26386055e+04 1.33826289e+04 1.37276670e+04 1.33103076e+04 1.29127070e+04 1.28261045e+04 1.35765186e+04 1.35987549e+04 1.31659424e+04 1.33725771e+04 1.33715312e+04 1.32741416e+04 1.32459424e+04 1.37590107e+04 1.34999922e+04 1.29767207e+04 1.36536748e+04 1.37812793e+04 1.36270049e+04 1.32953076e+04 1.31166182e+04 1.38149297e+04 1.35086641e+04 1.31456426e+04 1.40910635e+04 1.43193418e+04 1.38195771e+04 1.32619277e+04 1.75529629e+04 1.90549258e+04 1.77954824e+04 2.14664434e+04 2.07832148e+04 2.20241172e+04 1.99140039e+04 3.92066523e+04 7.16372812e+04 2.30180812e+05 -4.52047258e+09 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. 0. 570249472. 3.54371219e+05 9.90525859e+04 4.30811055e+04 3.50523086e+04 2.07828496e+04 1.57977842e+04 1.49805840e+04 1.38222578e+04 1.37666152e+04 1.37167539e+04 1.33688018e+04 1.34615371e+04 1.37327461e+04 1.36088682e+04 1.35791582e+04 1.34638760e+04 1.33417793e+04 1.38943652e+04 1.36999375e+04 1.31803428e+04 1.34615010e+04 1.33120918e+04 1.28697939e+04 1.34672451e+04 1.41365918e+04 1.35430488e+04 1.31711787e+04 1.32576055e+04 1.33577373e+04 1.32852695e+04 1.32040186e+04 1.33158418e+04 1.33115293e+04 1.34283252e+04 1.34116191e+04 1.29308906e+04 1.30524258e+04 1.34766797e+04 1.35674072e+04 1.34575068e+04 1.29130059e+04 1.27864258e+04 1.32245918e+04 1.32699639e+04 1.30837129e+04 1.29457754e+04 1.28927109e+04 1.31450400e+04 1.33136699e+04 1.31052500e+04 1.27042295e+04 1.26713135e+04 1.32866592e+04 1.32978164e+04 1.26073125e+04 1.25141982e+04 1.28441299e+04 1.30185869e+04 1.31146523e+04 1.28397070e+04 1.24330498e+04 1.25495723e+04 1.28303379e+04 1.28611318e+04 1.26529482e+04 1.23953271e+04 1.26124990e+04 1.28370469e+04 1.26165068e+04 1.23959336e+04 1.22715469e+04 1.24127773e+04 1.26470635e+04 1.25328770e+04 1.25353525e+04 1.24098232e+04 1.20705693e+04 1.22301816e+04 1.23907510e+04 1.22821836e+04 1.22699570e+04 1.21405459e+04 1.20857080e+04 1.23766113e+04 1.22864297e+04 1.18525625e+04 1.18353008e+04 1.20744102e+04 1.21253057e+04 1.20277881e+04 1.18561963e+04 1.17822295e+04 1.18293682e+04 1.19598037e+04 1.18417939e+04 1.14884531e+04 1.16485195e+04 1.19374844e+04 1.18695283e+04 1.17820615e+04 1.14069922e+04 1.13288877e+04 1.16749199e+04 1.15784062e+04 1.13207500e+04 1.12404961e+04 1.12782725e+04 1.15193242e+04 1.13990986e+04 1.12537900e+04 1.12555498e+04 1.12254316e+04 1.12907178e+04 1.12509785e+04 1.10420312e+04 1.09968848e+04 1.10251777e+04 1.08825625e+04 1.09629062e+04 1.09854170e+04 1.08792998e+04 1.08431885e+04 1.07328018e+04 1.06603008e+04 1.07854180e+04 1.07919492e+04 1.06756582e+04 1.05640850e+04 1.04284443e+04 1.04278135e+04 1.04959102e+04 1.03831084e+04 1.02610088e+04 1.03777793e+04 1.05515107e+04 1.04175742e+04 1.01682949e+04 1.01316201e+04 1.01514951e+04 1.00838301e+04 9.95645117e+03 9.88590723e+03 9.93920312e+03 1.00163037e+04 1.00681611e+04 9.98952051e+03 9.68532812e+03 9.50832520e+03 9.70488281e+03 9.81270898e+03 9.74803125e+03 9.58140039e+03 9.37421680e+03 9.48656055e+03 9.61440332e+03 9.54109082e+03 9.24300391e+03 9.09108691e+03 9.28942480e+03 9.45296777e+03 9.26669824e+03 8.85732520e+03 8.93359082e+03 9.14711719e+03 9.10775195e+03 8.91381641e+03 8.86506738e+03 8.89632812e+03 8.83453320e+03 8.81827148e+03 8.68961816e+03 8.54054590e+03 8.63658789e+03 8.74557617e+03 8.52871191e+03 8.47885156e+03 8.48412598e+03 8.30447070e+03 8.32846875e+03 8.31681934e+03 8.34104492e+03 8.37186914e+03 7.93439502e+03 7.97808350e+03 8.30655957e+03 8.08001221e+03 7.79396484e+03 7.85675635e+03 7.99953906e+03 7.85078271e+03 7.80839893e+03 7.73719482e+03 7.59835254e+03 7.53644482e+03 7.68051611e+03 7.68245898e+03 7.41875098e+03 7.41773682e+03 7.57332764e+03 7.41563428e+03 7.30758936e+03 7.21090869e+03 7.09868701e+03 7.23818994e+03 7.15595410e+03 7.01447119e+03 7.04497510e+03 6.87747852e+03 6.91681982e+03 7.02949219e+03 6.79214551e+03 6.73294043e+03 6.73224658e+03 6.70988867e+03 6.62517529e+03 6.62127490e+03 6.57712939e+03 6.44591309e+03 6.41271924e+03 6.41525244e+03 6.38823340e+03 6.23628564e+03 6.28249463e+03 6.30914746e+03 6.17638428e+03 6.24910059e+03 6.06352295e+03 5.88568457e+03 5.97681445e+03 5.99326562e+03 5.92062012e+03 5.77481104e+03 5.63903320e+03 5.73499561e+03 5.83361768e+03 5.68794629e+03 5.52577100e+03 5.59173291e+03 5.57734766e+03 5.44074268e+03 5.33922021e+03 5.43214111e+03 5.34995654e+03 5.20227637e+03 5.32058008e+03 5.19580225e+03 5.08564746e+03 5.15366357e+03 5.00170166e+03 4.94458203e+03 4.94301172e+03 4.87757324e+03 4.81950684e+03 4.83049609e+03 4.84954297e+03 4.80518896e+03 4.62758154e+03 4.54726318e+03 4.61193750e+03 4.54777881e+03 4.52696533e+03 4.46474121e+03 4.39821875e+03 4.34289990e+03 4.32792676e+03 4.35337061e+03 4.20977832e+03 4.07281885e+03 4.14373730e+03 4.27523730e+03 4.04129712e+03 3.90956836e+03 3.94191699e+03 3.87565625e+03 3.92905371e+03 3.90762280e+03 3.76811230e+03 3.71231836e+03 3.72113013e+03 3.68916650e+03 3.67106323e+03 3.57985498e+03 3.56560400e+03 3.56533032e+03 3.38154492e+03 3.38852246e+03 3.37648706e+03 3.29802173e+03 3.33991797e+03 3.26989648e+03 3.17438501e+03 3.18560767e+03 3.11504053e+03 3.08347998e+03 3.14509155e+03 3.05140894e+03 2.95767773e+03 2.89594458e+03 2.83915869e+03 2.86884937e+03 2.86380933e+03 2.76345557e+03 2.71907202e+03 2.74165015e+03 2.70028516e+03 2.63012598e+03 2.55970703e+03 2.52902661e+03 2.51499634e+03 2.50771924e+03 2.47824902e+03 2.37402441e+03 2.33315845e+03 2.34283691e+03 2.32670166e+03 2.28006274e+03 2.23053662e+03 2.17758618e+03 2.13750244e+03 2.18285815e+03 2.15208862e+03 2.03246289e+03 1.96695703e+03 1.96439392e+03 1.96203137e+03 1.92102100e+03 1.87024841e+03 1.85449109e+03 1.83533911e+03 1.79770374e+03 1.78506897e+03 1.72600806e+03 1.67656396e+03 1.67102856e+03 1.66056201e+03 1.61208276e+03 1.53616565e+03 1.52863867e+03 1.51110376e+03 1.47959961e+03 1.46821167e+03 1.42524866e+03 1.37843469e+03 1.36347864e+03 1.36373901e+03 1.31533740e+03 1.26103857e+03 1.25142334e+03 1.22971753e+03 1.19357788e+03 1.16945337e+03 1.13556946e+03 1.11018445e+03 1.09385205e+03 1.07816541e+03 1.05965833e+03 1.01443842e+03 9.86277222e+02 9.64878113e+02 9.35564087e+02 9.14683899e+02 8.84433044e+02 8.72567749e+02 8.54127441e+02 8.19524658e+02 7.89411743e+02 7.74097656e+02 7.65994385e+02 7.48645691e+02 7.27324280e+02 6.94737427e+02 6.70738647e+02 6.49658264e+02 6.23634460e+02 6.08692444e+02 5.96452026e+02 5.75732727e+02 5.54312988e+02 5.31002197e+02 5.09835541e+02 5.01381287e+02 4.90006378e+02 4.74050385e+02 4.48908997e+02 4.21061859e+02 4.10607147e+02 3.99260681e+02 3.79687469e+02 3.67083099e+02 3.55961578e+02 3.34848511e+02 3.17437866e+02 3.03288483e+02 2.89627106e+02 2.84962952e+02 2.72954071e+02 2.53930115e+02 2.42461365e+02 2.26858856e+02 2.10559708e+02 2.05383545e+02 1.95996811e+02 1.80646103e+02 1.70409622e+02 1.59616257e+02 1.47997147e+02 1.41655655e+02 1.35201202e+02 1.22601120e+02 1.12559227e+02 1.05426125e+02 9.73531265e+01 8.98244705e+01 8.18158188e+01 7.46343155e+01 6.81801147e+01 6.17677727e+01 5.59286728e+01 4.97142334e+01 4.35751648e+01 3.90607681e+01 3.47233009e+01 2.96787834e+01 2.52084293e+01 2.14165840e+01 1.82527027e+01 1.52221432e+01 1.24697285e+01 9.70601463e+00 7.34408998e+00 5.64894867e+00 4.20172596e+00 3.07638431e+00 2.24697614e+00 1.76669109e+00 1.61399078e+00 1.77858829e+00 2.29298997e+00 3.19838452e+00 4.42828560e+00 5.87389946e+00 7.72044802e+00 9.73406506e+00 1.19273357e+01 1.52264910e+01 1.89957447e+01 2.19223728e+01 2.51150761e+01 2.94434624e+01 3.43082352e+01 3.97080536e+01 4.52069893e+01 5.02927628e+01 5.48230667e+01 6.12382164e+01 6.87166748e+01 7.50622177e+01 8.32188721e+01 9.09292297e+01 9.77374954e+01 1.05119995e+02 1.14615395e+02 1.24094200e+02 1.32286896e+02 1.42977310e+02 1.53384277e+02 1.60811325e+02 1.68332962e+02 1.79845917e+02 1.93594940e+02 2.09467422e+02 2.20799133e+02 2.25984909e+02 2.37459610e+02 2.52039108e+02 2.67872528e+02 2.85036041e+02 2.94710632e+02 3.03357880e+02 3.25180115e+02 3.40539246e+02 3.48895691e+02 3.74466400e+02 3.88897583e+02 3.94294617e+02 4.11462189e+02 424. 4.40900085e+02 4.73427338e+02 4.91476776e+02 5.00211517e+02 5.24633057e+02 5.37713745e+02 5.39223633e+02 5.63606812e+02 5.96848877e+02 6.17545715e+02 6.35554993e+02 6.46986938e+02 6.67950684e+02 6.99896729e+02 7.24236572e+02 7.62850342e+02 7.69249023e+02 7.59404175e+02 7.85860291e+02 8.20140137e+02 8.56790039e+02 8.90738464e+02 8.95615967e+02 8.96165894e+02 9.41164001e+02 9.80211487e+02 9.93148621e+02 1.02160339e+03 1.04453076e+03 1.05656909e+03 1.09724963e+03 1.12533948e+03 1.12635571e+03 1.18830359e+03 1.23094104e+03 1.22792395e+03 1.24623804e+03 1.24344971e+03 1.27581677e+03 1.34696899e+03 1.41743408e+03 1.42940735e+03 1.37956592e+03 1.41790417e+03 1.49608826e+03 1.51574548e+03 1.54623694e+03 1.57403503e+03 1.58606970e+03 1.63296472e+03 1.67317151e+03 1.70350659e+03 1.73410010e+03 1.76154224e+03 1.81801135e+03 1.83188171e+03 1.83358386e+03 1.86125964e+03 1.91013586e+03 1.97360559e+03 2.04326440e+03 2.03256934e+03 2.00516821e+03 2.07817603e+03 2.14328809e+03 2.21802246e+03 2.23873901e+03 2.18988818e+03 2.24125586e+03 2.30061914e+03 2.35936011e+03 2.43966821e+03 2.42971729e+03 2.42153149e+03 2.48214404e+03 2.48659326e+03 2.50111011e+03 2.62454419e+03 2.70745581e+03 2.68180615e+03 2.66186743e+03 2.69091943e+03 2.74955127e+03 2.86832617e+03 2.92208008e+03 2.93917114e+03 2.92816528e+03 2.89705127e+03 2.97884937e+03 3.05007104e+03 3.16758813e+03 3.22060376e+03 3.13483228e+03 3.16415674e+03 3.23700391e+03 3.31292529e+03 3.36575195e+03 3.42372412e+03 3.46393213e+03 3.41907959e+03 3.48123975e+03 3.53986206e+03 3.57127026e+03 3.63729541e+03 3.70567163e+03 3.73237720e+03 3.75050562e+03 3.74609424e+03 3.83920020e+03 3.97471631e+03 3.96380640e+03 3.91868311e+03 4.00463843e+03 4.03112817e+03 4.08262061e+03 4.28439941e+03 4.28089160e+03 4.16885107e+03 4.30410449e+03 4.38585303e+03 4.46781885e+03 4.52573047e+03 4.46240137e+03 4.60722363e+03 5.17690674e+03 6.31566309e+03 4.72510010e+03 6.50321729e+03 6.24526074e+03 8.56675977e+03 6.48956689e+03 1.09427822e+04 1.02584922e+05 -54726096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 75724720. -3.94824175e+06 6157412. -16127423. 2.25362324e+04 2.03148418e+04 1.05150361e+04 6.92591895e+03 7.66609375e+03 7.86368066e+03 7.70708936e+03 7.47365918e+03 7.35899512e+03 7.45556104e+03 7.69127734e+03 7.93109375e+03 7.84322705e+03 7.64596143e+03 7.66933936e+03 7.81858398e+03 8.04807617e+03 8.03680225e+03 7.73583105e+03 7.92408496e+03 8.19161328e+03 8.17209766e+03 8.06077637e+03 7.96786230e+03 8.21902539e+03 8.66587988e+03 8.67824023e+03 8.26945996e+03 7.99694727e+03 8.28772754e+03 8.71679688e+03 8.94574414e+03 8.79553418e+03 8.47999902e+03 8.62127539e+03 8.82796289e+03 9.07527051e+03 8.99680078e+03 8.56301367e+03 8.74625098e+03 9.24121094e+03 9.16718750e+03 8.97195898e+03 9.12045312e+03 9.17542969e+03 9.31761426e+03 9.43996875e+03 9.06266504e+03 9.00632715e+03 9.50791211e+03 9.79301367e+03 9.68314160e+03 9.38204688e+03 9.20040234e+03 9.74676074e+03 1.00984404e+04 9.88883496e+03 9.58654785e+03 9.35333008e+03 9.55829980e+03 1.00547900e+04 1.02904316e+04 1.01283271e+04 1.00052139e+04 1.00454893e+04 9.98856543e+03 1.00872666e+04 1.02197871e+04 9.95945117e+03 1.01818877e+04 1.05825234e+04 1.04456006e+04 1.00594219e+04 1.00302227e+04 1.05722393e+04 1.09281592e+04 1.08383848e+04 1.04807266e+04 1.02834541e+04 1.03486318e+04 1.06833408e+04 1.12069248e+04 1.10782637e+04 1.04836084e+04 1.06591016e+04 1.08755811e+04 1.10325156e+04 1.12952832e+04 1.09200264e+04 1.08968604e+04 1.12223301e+04 1.11984492e+04 1.11453955e+04 1.10045459e+04 1.11493018e+04 1.14914844e+04 1.14547256e+04 1.11272568e+04 1.11204443e+04 1.15099961e+04 1.16774561e+04 1.16841201e+04 1.15715381e+04 1.12725869e+04 1.14487617e+04 1.18433760e+04 1.18979160e+04 1.16974883e+04 1.12899600e+04 1.13878330e+04 1.19917656e+04 1.23398154e+04 1.20824941e+04 1.15633604e+04 1.16852285e+04 1.21169541e+04 1.21186895e+04 1.18519443e+04 1.17666963e+04 1.21850322e+04 1.24012305e+04 1.21383242e+04 1.19826162e+04 1.18561221e+04 1.22714639e+04 1.28620957e+04 1.25256670e+04 1.22286133e+04 1.21244561e+04 1.21618633e+04 1.24333955e+04 1.27238428e+04 1.26342236e+04 1.21036035e+04 1.21821689e+04 1.27833867e+04 1.29844199e+04 1.26580781e+04 1.23866045e+04 1.25974658e+04 1.28967139e+04 1.29035928e+04 1.27371406e+04 1.23063311e+04 1.24762568e+04 1.29855312e+04 1.30645312e+04 1.28986924e+04 1.25900889e+04 1.27320010e+04 1.30225742e+04 1.33499971e+04 1.32602119e+04 1.26356152e+04 1.27791016e+04 1.30660254e+04 1.30698037e+04 1.31524629e+04 1.29911895e+04 1.30444639e+04 1.31703164e+04 1.30976260e+04 1.30251299e+04 1.29681924e+04 1.33337764e+04 1.35773262e+04 1.34162197e+04 1.29933877e+04 1.28016650e+04 1.33562354e+04 1.38245693e+04 1.37177344e+04 1.33137764e+04 1.28981436e+04 1.28183389e+04 1.33619463e+04 1.39514551e+04 1.36259336e+04 1.29658418e+04 1.31310840e+04 1.35965645e+04 1.36949248e+04 1.36734434e+04 1.34101641e+04 1.34119795e+04 1.35245127e+04 1.34140938e+04 1.33320820e+04 1.34495654e+04 1.36398232e+04 1.36621240e+04 1.35624453e+04 1.34421562e+04 1.33829395e+04 1.36416182e+04 1.39130225e+04 1.38622939e+04 1.33635527e+04 1.31206729e+04 1.37449287e+04 1.40149619e+04 1.38331074e+04 1.36279219e+04 1.31688262e+04 1.32312568e+04 1.39133477e+04 1.42640664e+04 1.39794355e+04 1.33600225e+04 1.32785771e+04 1.37420254e+04 1.39818027e+04 1.38313096e+04 1.37023145e+04 1.38358359e+04 1.37191699e+04 1.35091885e+04 1.32216748e+04 1.31634473e+04 1.35348037e+04 1.38117139e+04 1.41784521e+04 1.40323271e+04 1.32639111e+04 1.33853955e+04 1.36930430e+04 1.36924688e+04 1.38677598e+04 1.36121680e+04 1.39618350e+04 1.39844082e+04 1.32274375e+04 1.30389531e+04 1.33732588e+04 1.39718115e+04 1.43859629e+04 1.41042490e+04 1.33141895e+04 1.28456035e+04 1.32059697e+04 1.39923018e+04 1.43310352e+04 1.39981279e+04 1.31792568e+04 1.30980303e+04 1.40886729e+04 1.40199609e+04 1.31851191e+04 1.32748594e+04 1.34812764e+04 1.34681816e+04 1.39045439e+04 1.35479043e+04 1.30821758e+04 1.34250918e+04 1.31342646e+04 1.34708789e+04 1.38024121e+04 1.30380146e+04 1.33674883e+04 1.37833203e+04 1.34151504e+04 1.34018994e+04 1.33311318e+04 1.33417559e+04 1.33993555e+04 1.33303291e+04 1.29783994e+04 1.29426855e+04 1.35678135e+04 1.39136738e+04 1.35750791e+04 1.29106660e+04 1.26515059e+04 1.28537520e+04 1.34386123e+04 1.38352471e+04 1.34256748e+04 1.28114580e+04 1.28232061e+04 1.31920986e+04 1.31403682e+04 1.29068643e+04 1.29371045e+04 1.29002588e+04 1.28323945e+04 1.33868506e+04 1.31169004e+04 1.25868008e+04 1.28843350e+04 1.25869736e+04 1.28801309e+04 1.31004639e+04 1.26550752e+04 1.31391445e+04 1.28620361e+04 1.22976689e+04 1.26685215e+04 1.23843848e+04 1.24948818e+04 1.33394785e+04 1.26941992e+04 1.19604297e+04 1.21680820e+04 1.27452861e+04 1.31935371e+04 1.28729746e+04 1.20849512e+04 1.17311123e+04 1.20521279e+04 1.26061045e+04 1.30212715e+04 1.26976113e+04 1.19259756e+04 1.18193809e+04 1.22521162e+04 1.24404590e+04 1.20811777e+04 1.19369512e+04 1.20506670e+04 1.20088916e+04 1.23833242e+04 1.23462764e+04 1.16880703e+04 1.16692070e+04 1.17933701e+04 1.18281064e+04 1.19212734e+04 1.18096104e+04 1.20473613e+04 1.18268965e+04 1.13729277e+04 1.15412930e+04 1.12822275e+04 1.15590439e+04 1.23286113e+04 1.16234785e+04 1.07781406e+04 1.11051689e+04 1.15769902e+04 1.18625088e+04 1.18807344e+04 1.12111670e+04 1.07178525e+04 1.08672627e+04 1.14001982e+04 1.18081777e+04 1.14607930e+04 1.07366387e+04 1.06186807e+04 1.09947725e+04 1.10870010e+04 1.12820811e+04 1.12824746e+04 1.05859072e+04 1.05171777e+04 1.08870410e+04 1.09500957e+04 1.07375635e+04 1.05778516e+04 1.05053789e+04 1.03985996e+04 1.08389727e+04 1.08454707e+04 1.02921182e+04 1.02327197e+04 1.02914551e+04 1.03041309e+04 1.03418574e+04 1.01600176e+04 1.03974521e+04 1.04897754e+04 1.00964385e+04 9.84836816e+03 9.59526758e+03 9.94022266e+03 1.05461738e+04 1.02259932e+04 9.59790332e+03 9.37229688e+03 9.71191797e+03 1.02082871e+04 9.83596289e+03 9.25320312e+03 9.34705859e+03 9.56878516e+03 9.84747168e+03 1.00123408e+04 9.75090234e+03 9.12474121e+03 8.93794043e+03 9.17272656e+03 9.42983789e+03 9.38220312e+03 9.21349414e+03 9.13103320e+03 9.03594531e+03 9.20383496e+03 9.06858984e+03 8.80226465e+03 8.73203516e+03 8.66032422e+03 8.96181055e+03 9.04554395e+03 8.69012402e+03 8.72053613e+03 8.72195215e+03 8.74738770e+03 8.53157812e+03 8.09682666e+03 8.41488281e+03 8.84498633e+03 8.52793457e+03 8.04182031e+03 8.07638037e+03 8.46316113e+03 8.39007715e+03 8.15978955e+03 8.12777393e+03 7.84988965e+03 7.76197803e+03 8.17613477e+03 8.13553613e+03 7.68801221e+03 7.48330029e+03 7.43623389e+03 7.74579785e+03 8.06081348e+03 7.63407275e+03 7.37952881e+03 7.55134961e+03 7.47285107e+03 7.62490674e+03 7.53428174e+03 7.05267334e+03 7.06928271e+03 7.24065332e+03 7.18571143e+03 7.17017773e+03 7.05707861e+03 7.14786865e+03 7.29661426e+03 6.55880957e+03 7.06559717e+03 6.74864062e+03 8.20854883e+03 9.78132324e+03 1.02849326e+04 9.96693262e+03 1.00268760e+04 1.06512568e+04 9.91084180e+03 9.63145410e+03 1.19093262e+04 2.07223848e+04 2.71029062e+04 4893892. 6.71785150e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -86807896. -17598636. 17335314. 1.44377852e+04 8.53958008e+03 4.84983545e+03 4.31172656e+03 4.93910156e+03 4.41417090e+03 4.05441626e+03 4.08493921e+03 4.05645532e+03 3.93169019e+03 3.89623291e+03 3.85731519e+03 3.86544141e+03 3.88531445e+03 3.70446802e+03 3.54302759e+03 3.58808911e+03 3.54819653e+03 3.34636865e+03 3.50893823e+03 3.55058130e+03 3.21563428e+03 3.38314941e+03 3.50928833e+03 3.31184839e+03 3.20299097e+03 3.24181665e+03 3.26837842e+03 3.15398877e+03 3.10293970e+03 3.06874048e+03 3.01328931e+03 2.94320972e+03 2.89945312e+03 2.93812036e+03 2.91423560e+03 2.82019507e+03 2.77372852e+03 2.74558813e+03 2.71338184e+03 2.66190991e+03 2.62407837e+03 2.59787402e+03 2.49214258e+03 2.44134546e+03 2.46602832e+03 2.42358789e+03 2.48440601e+03 2.45298584e+03 2.33081323e+03 2.23459058e+03 2.18979688e+03 2.29612744e+03 2.27511182e+03 2.15429736e+03 2.07545117e+03 2.05112622e+03 2.05132471e+03 2.00493701e+03 2.03850085e+03 2.00436316e+03 1.85476550e+03 1.80323145e+03 1.86765271e+03 1.91083118e+03 1.82891772e+03 1.75195789e+03 1.73252087e+03 1.68882288e+03 1.64062146e+03 1.62439172e+03 1.59635449e+03 1.55592249e+03 1.52447961e+03 1.49556555e+03 1.48115576e+03 1.45050781e+03 1.45006799e+03 1.41386987e+03 1.34614648e+03 1.33925647e+03 1.31302844e+03 1.28614185e+03 1.26519556e+03 1.22824829e+03 1.19999512e+03 1.14630591e+03 1.09357874e+03 1.12156091e+03 1.10984814e+03 1.03013196e+03 1.01215948e+03 1.04403149e+03 1.04395361e+03 9.89286560e+02 9.41080872e+02 9.11169495e+02 8.85866577e+02 8.57237244e+02 8.32076172e+02 8.25900452e+02 8.00055664e+02 7.95096130e+02 7.70596619e+02 7.26500977e+02 7.17249573e+02 6.78853821e+02 6.58712830e+02 6.73535339e+02 6.47730591e+02 6.14276306e+02 5.80557434e+02 5.51936829e+02 5.60834900e+02 5.55058838e+02 5.21079468e+02 4.86750244e+02 4.69401855e+02 4.63946625e+02 4.44952057e+02 4.42016418e+02 4.28571960e+02 3.97925568e+02 3.74186188e+02 3.58953735e+02 3.57903259e+02 3.43508026e+02 3.21180298e+02 3.03869476e+02 2.89611755e+02 2.79533112e+02 2.59650330e+02 2.47814682e+02 2.49324356e+02 2.35188553e+02 2.16426422e+02 1.99050339e+02 1.87217606e+02 1.87175568e+02 1.76739319e+02 1.61304947e+02 1.47244675e+02 1.36782425e+02 1.31680908e+02 1.22518799e+02 1.13700821e+02 1.02322708e+02 9.63295441e+01 9.34379959e+01 8.34480515e+01 7.54990158e+01 6.89446487e+01 6.18836823e+01 5.49492683e+01 4.91817131e+01 4.42685738e+01 3.90304527e+01 3.39423523e+01 2.85316105e+01 2.49214153e+01 2.24654484e+01 1.81868420e+01 1.45720530e+01 1.21384783e+01 9.66032028e+00 7.70263100e+00 5.75784540e+00 4.15571404e+00 3.11241984e+00 2.28317237e+00 1.77634466e+00 1.61399162e+00 1.77495944e+00 2.26223898e+00 3.09392810e+00 4.27771521e+00 5.69259405e+00 7.67639399e+00 1.03020525e+01 1.26527357e+01 1.50819836e+01 1.77408180e+01 2.13623447e+01 2.66792469e+01 3.07617874e+01 3.44121170e+01 3.83758621e+01 4.31543198e+01 4.99982758e+01 5.58329964e+01 6.31712608e+01 6.84732819e+01 7.31235352e+01 8.25578461e+01 9.02253494e+01 9.98618011e+01 1.07584427e+02 1.12748718e+02 1.21482689e+02 1.30853745e+02 1.41969147e+02 1.47564041e+02 1.59337357e+02 1.79207092e+02 1.87291748e+02 1.93882904e+02 2.00278519e+02 2.10342636e+02 2.34523987e+02 2.48599243e+02 2.53992783e+02 2.60252136e+02 2.72752594e+02 2.95435608e+02 3.10079712e+02 3.30818665e+02 3.42197388e+02 3.49141541e+02 3.60481110e+02 3.73785309e+02 4.08874481e+02 4.24344879e+02 4.27332825e+02 4.40678833e+02 4.58170929e+02 4.89953339e+02 5.09450317e+02 5.06876068e+02 5.22070068e+02 5.68474976e+02 5.88215698e+02 5.79306580e+02 5.96380249e+02 6.47035339e+02 6.70980286e+02 6.71093567e+02 6.74993835e+02 6.95486816e+02 7.58376282e+02 7.74905823e+02 7.70561523e+02 7.98558472e+02 8.19093750e+02 8.42364563e+02 8.66677124e+02 8.89075684e+02 8.87979919e+02 9.34723206e+02 1.01469592e+03 1.01044794e+03 1.02127966e+03 1.05063660e+03 1.07170239e+03 1.09865234e+03 1.11951086e+03 1.14165002e+03 1.14354529e+03 1.15124121e+03 1.20988220e+03 1.26738452e+03 1.33422144e+03 1.31421545e+03 1.29249353e+03 1.36031482e+03 1.40622778e+03 1.47288672e+03 1.47787549e+03 1.46739551e+03 1.49004163e+03 1.50966211e+03 1.57372083e+03 1.60665454e+03 1.67327002e+03 1.69962207e+03 1.68675122e+03 1.69345105e+03 1.68170215e+03 1.78589355e+03 1.92547644e+03 1.91832581e+03 1.89128162e+03 1.88043054e+03 1.88259033e+03 2.00851611e+03 2.10455786e+03 2.08533911e+03 2.03601941e+03 2.06700708e+03 2.15879541e+03 2.18928589e+03 2.28617676e+03 2.31155835e+03 2.28269849e+03 2.32774438e+03 2.36100903e+03 2.44995947e+03 2.47566382e+03 2.41090137e+03 2.45969629e+03 2.63281665e+03 2.62093311e+03 2.51983423e+03 2.64417847e+03 2.83231714e+03 2.81396655e+03 2.78251611e+03 2.75947803e+03 2.79226465e+03 2.98655396e+03 3.02414258e+03 2.97311719e+03 2.93445874e+03 2.97065967e+03 3.10778735e+03 3.14348560e+03 3.16305933e+03 3.14436377e+03 3.24402393e+03 3.42020801e+03 3.36645728e+03 3.42842212e+03 3.45240308e+03 3.43795532e+03 3.50710889e+03 3.55987183e+03 3.60661108e+03 3.61020923e+03 3.61669995e+03 3.58804175e+03 3.71941797e+03 3.97401367e+03 3.86619214e+03 3.73954370e+03 3.90002466e+03 4.00582764e+03 4.14799707e+03 4.15104688e+03 4.06687744e+03 4.20590674e+03 4.26453076e+03 4.13047363e+03 4.11605615e+03 4.42686182e+03 4.47092578e+03 4.40123633e+03 4.36646387e+03 4.26754102e+03 4.52207764e+03 4.83719043e+03 4.77851807e+03 4.66032520e+03 4.60115039e+03 4.60092725e+03 4.89800928e+03 5.09456396e+03 5.01437012e+03 4.83183203e+03 4.83241455e+03 5.00063477e+03 5.11994482e+03 5.30781982e+03 5.25151514e+03 5.14541211e+03 5.29813525e+03 5.32297168e+03 5.47926270e+03 5.48209375e+03 5.41003613e+03 5.51948438e+03 5.59096484e+03 5.58356738e+03 5.46322363e+03 5.58642041e+03 6.01503809e+03 5.96655518e+03 5.76886084e+03 5.69342139e+03 5.81939746e+03 6.20562793e+03 6.22820557e+03 6.08528369e+03 6.00146240e+03 6.00181982e+03 6.23767627e+03 6.26977881e+03 6.29803027e+03 6.21974414e+03 6.41290283e+03 6.74050928e+03 6.52376172e+03 6.63736816e+03 6.71019482e+03 6.66412256e+03 6.66369482e+03 6.66394482e+03 6.71829688e+03 6.77301611e+03 6.84662842e+03 6.87577051e+03 7.13275098e+03 7.17809082e+03 6.91219189e+03 6.84174268e+03 7.07719189e+03 7.30348291e+03 7.61025586e+03 7.40972412e+03 7.09775439e+03 7.51068359e+03 7.69696729e+03 7.57515625e+03 7.46740771e+03 7.44401025e+03 7.66565918e+03 7.72966211e+03 7.66611035e+03 7.50342480e+03 7.83707764e+03 8.25945801e+03 8.06188965e+03 8.01542432e+03 7.85779590e+03 7.85858203e+03 8.39272852e+03 8.41802148e+03 8.21931348e+03 8.02627930e+03 7.95522119e+03 8.21727734e+03 8.54463379e+03 8.90268164e+03 8.50096289e+03 8.20996973e+03 8.53933008e+03 8.66082227e+03 8.93271191e+03 8.87584668e+03 8.61148047e+03 8.86758105e+03 8.94605762e+03 8.75859863e+03 8.59205176e+03 8.98741016e+03 9.49805859e+03 9.26157031e+03 9.14881738e+03 9.00977051e+03 8.96867188e+03 9.52516992e+03 9.58524121e+03 9.37547363e+03 9.14171582e+03 9.14146777e+03 9.45988574e+03 9.54745508e+03 9.85675977e+03 9.88621191e+03 9.58188770e+03 9.48285742e+03 9.66085352e+03 1.01194814e+04 9.92559277e+03 9.76549707e+03 9.96204102e+03 9.96088770e+03 9.86496680e+03 9.78287207e+03 1.02049590e+04 1.02781807e+04 1.00221533e+04 1.04535977e+04 1.05871768e+04 1.03409111e+04 1.03554580e+04 1.04621816e+04 1.04189688e+04 1.02082549e+04 1.01573135e+04 1.06875400e+04 1.09039209e+04 1.03804658e+04 1.00943809e+04 1.06545596e+04 1.13088047e+04 1.11539131e+04 1.06423516e+04 1.04739551e+04 1.10780957e+04 1.12848457e+04 1.09653262e+04 1.10862217e+04 1.08438818e+04 1.05469033e+04 1.10460684e+04 1.15799209e+04 1.15758662e+04 1.10930410e+04 1.08040078e+04 1.14268936e+04 1.18707002e+04 1.15727764e+04 1.10804570e+04 1.09729258e+04 1.13801777e+04 1.15333877e+04 1.18689287e+04 1.18647539e+04 1.14712109e+04 1.16024268e+04 1.17108369e+04 1.19305566e+04 1.16741504e+04 1.14613359e+04 1.19825566e+04 1.19979668e+04 1.19443359e+04 1.16309375e+04 1.17660840e+04 1.24829766e+04 1.20229238e+04 1.15953467e+04 1.19323262e+04 1.22210410e+04 1.23145371e+04 1.21870020e+04 1.24752197e+04 1.26103906e+04 1.22812490e+04 1.19148164e+04 1.19660732e+04 1.26575664e+04 1.24333232e+04 1.20786973e+04 1.25787461e+04 1.26571846e+04 1.23707061e+04 1.22772734e+04 1.27728994e+04 1.27119834e+04 1.23343926e+04 1.27154229e+04 1.27672949e+04 1.28480664e+04 1.28861406e+04 1.27572188e+04 1.26812139e+04 1.23293994e+04 1.22849814e+04 1.29819951e+04 1.34812734e+04 1.28031650e+04 1.21878721e+04 1.27427324e+04 1.35395410e+04 1.34731289e+04 1.28088535e+04 1.23823389e+04 1.30498467e+04 1.34747598e+04 1.30327432e+04 1.32435342e+04 1.32523203e+04 1.27886348e+04 1.29258496e+04 1.34431826e+04 1.35074600e+04 1.29862676e+04 1.26245654e+04 1.32393428e+04 1.38186299e+04 1.34536436e+04 1.29674424e+04 1.27817529e+04 1.34250488e+04 1.38125850e+04 1.33828799e+04 1.31125518e+04 1.31626475e+04 1.33942363e+04 1.33750352e+04 1.37838242e+04 1.35075508e+04 1.30017510e+04 1.35199170e+04 1.36302275e+04 1.37037363e+04 1.33553232e+04 1.31361182e+04 1.37596943e+04 1.34345488e+04 1.31773086e+04 1.36168242e+04 1.37644551e+04 1.39486797e+04 1.39564453e+04 1.41849268e+04 1.42650566e+04 1.43132666e+04 1.39301133e+04 1.26570410e+04 1.42419912e+04 1.15586201e+04 2.28503086e+04 5.19793867e+04 2.30180812e+05 -4.52047258e+09 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. 1.06926203e+10 3.16328812e+05 5.62827734e+04 3.96921523e+04 2.40370840e+04 1.76103770e+04 1.76501836e+04 1.51166201e+04 1.45093730e+04 1.37731416e+04 1.34405146e+04 1.35841787e+04 1.39407832e+04 1.39284971e+04 1.34958770e+04 1.33245996e+04 1.36155225e+04 1.36578516e+04 1.35103252e+04 1.34963857e+04 1.36514668e+04 1.34611670e+04 1.34892334e+04 1.37399473e+04 1.32011816e+04 1.27209883e+04 1.33186367e+04 1.40066475e+04 1.38679541e+04 1.32960205e+04 1.29552051e+04 1.33482656e+04 1.35062607e+04 1.33255586e+04 1.31691270e+04 1.31299297e+04 1.33964941e+04 1.34415752e+04 1.32640137e+04 1.31075020e+04 1.30864922e+04 1.35279873e+04 1.35813203e+04 1.29022988e+04 1.28412803e+04 1.31074189e+04 1.31178047e+04 1.33360117e+04 1.32061221e+04 1.28536777e+04 1.30311230e+04 1.31480635e+04 1.30601963e+04 1.30634004e+04 1.28559795e+04 1.28924297e+04 1.30539639e+04 1.28639189e+04 1.27551621e+04 1.26859561e+04 1.27602900e+04 1.29547451e+04 1.30059990e+04 1.28897256e+04 1.26035098e+04 1.24863936e+04 1.28217979e+04 1.27902227e+04 1.24495176e+04 1.25598203e+04 1.25819756e+04 1.25906729e+04 1.27801006e+04 1.26663438e+04 1.23187461e+04 1.22832783e+04 1.25799961e+04 1.26416240e+04 1.23112041e+04 1.20656348e+04 1.21489443e+04 1.22829854e+04 1.25776094e+04 1.24766162e+04 1.20093086e+04 1.19924541e+04 1.23314912e+04 1.23027256e+04 1.21761943e+04 1.18300684e+04 1.17414229e+04 1.21170244e+04 1.21438916e+04 1.18463369e+04 1.18177646e+04 1.18317266e+04 1.18129531e+04 1.18030283e+04 1.17000498e+04 1.17719580e+04 1.17369971e+04 1.18818223e+04 1.18739287e+04 1.13490459e+04 1.13618975e+04 1.15971621e+04 1.14981279e+04 1.14411514e+04 1.13432666e+04 1.13489902e+04 1.15656025e+04 1.13720176e+04 1.11713828e+04 1.13690088e+04 1.13426533e+04 1.11085781e+04 1.10303799e+04 1.11169082e+04 1.11090928e+04 1.10337188e+04 1.08447510e+04 1.08513184e+04 1.09005430e+04 1.11105088e+04 1.09679619e+04 1.05653379e+04 1.06212275e+04 1.08470703e+04 1.08027842e+04 1.06593828e+04 1.04782119e+04 1.03392402e+04 1.05469961e+04 1.07205625e+04 1.04926836e+04 1.02026465e+04 1.02355898e+04 1.04436602e+04 1.04558906e+04 1.04557773e+04 1.01467871e+04 9.84340039e+03 1.00207637e+04 1.00130605e+04 9.96554785e+03 9.99165527e+03 9.84307715e+03 9.93131348e+03 1.00983906e+04 9.90142578e+03 9.46365820e+03 9.53544629e+03 9.71464941e+03 9.75717969e+03 9.76717578e+03 9.51701367e+03 9.33356934e+03 9.38919238e+03 9.62573438e+03 9.41456152e+03 9.04134473e+03 9.15492773e+03 9.37931055e+03 9.26464355e+03 9.14227637e+03 8.91945117e+03 8.89568945e+03 9.00658301e+03 8.96386523e+03 8.89657812e+03 8.92984668e+03 8.74982129e+03 8.70831738e+03 8.87978613e+03 8.71405664e+03 8.48145312e+03 8.51661523e+03 8.63454785e+03 8.54160449e+03 8.53134473e+03 8.30637598e+03 8.14653271e+03 8.29219727e+03 8.56703223e+03 8.54944434e+03 7.94232568e+03 7.93185205e+03 8.31320703e+03 8.13301074e+03 7.89831494e+03 7.83019824e+03 7.74057471e+03 7.87158838e+03 7.93109326e+03 7.78465918e+03 7.58473828e+03 7.49895264e+03 7.58226270e+03 7.71086279e+03 7.64691357e+03 7.46092773e+03 7.34165723e+03 7.36140771e+03 7.35274268e+03 7.19801660e+03 7.12164697e+03 7.17412842e+03 7.07678516e+03 7.18857764e+03 7.20271924e+03 6.79574023e+03 6.80261670e+03 6.96480811e+03 6.92995020e+03 6.84201318e+03 6.62711084e+03 6.61592432e+03 6.73942090e+03 6.71139697e+03 6.58511182e+03 6.35659570e+03 6.27352344e+03 6.41648584e+03 6.50072021e+03 6.32640674e+03 6.22582715e+03 6.26949316e+03 6.16341113e+03 6.22285498e+03 6.15720605e+03 5.93565967e+03 5.86681299e+03 5.88615479e+03 5.99417969e+03 5.84026367e+03 5.72502148e+03 5.69857275e+03 5.75325684e+03 5.71779932e+03 5.59885303e+03 5.52499561e+03 5.48333008e+03 5.51960596e+03 5.39862012e+03 5.46462988e+03 5.32935107e+03 5.21003906e+03 5.29060400e+03 5.10404785e+03 5.09127979e+03 5.18597803e+03 5.02945410e+03 4.95850098e+03 4.95157568e+03 4.93192432e+03 4.85601660e+03 4.73285107e+03 4.82694775e+03 4.92921973e+03 4.62966699e+03 4.53732715e+03 4.56273193e+03 4.53096973e+03 4.59007275e+03 4.49431445e+03 4.34427734e+03 4.31670117e+03 4.38245801e+03 4.35071533e+03 4.24587158e+03 4.17535352e+03 4.13352734e+03 4.13367920e+03 4.01885840e+03 3.98801587e+03 3.91558862e+03 3.88425293e+03 3.89342651e+03 3.91375562e+03 3.82757422e+03 3.72202417e+03 3.65351880e+03 3.70490845e+03 3.73707202e+03 3.56405322e+03 3.55802979e+03 3.52858423e+03 3.37630737e+03 3.42807471e+03 3.38743506e+03 3.27573315e+03 3.32189062e+03 3.27561841e+03 3.19983960e+03 3.24107495e+03 3.15499683e+03 3.05969409e+03 3.04693921e+03 3.03901025e+03 3.01774634e+03 2.90377490e+03 2.85319360e+03 2.86580786e+03 2.85546387e+03 2.80453418e+03 2.73820605e+03 2.66777856e+03 2.68969092e+03 2.71376465e+03 2.59477173e+03 2.51493066e+03 2.47339722e+03 2.51544214e+03 2.51006396e+03 2.39078979e+03 2.33882422e+03 2.32833911e+03 2.30470996e+03 2.26117773e+03 2.24693945e+03 2.19819653e+03 2.12581372e+03 2.13465015e+03 2.15245581e+03 2.06030249e+03 1.95620959e+03 1.95538684e+03 1.97295178e+03 1.93567725e+03 1.89930127e+03 1.85723450e+03 1.79374927e+03 1.81511768e+03 1.81627222e+03 1.72622375e+03 1.67297717e+03 1.65239563e+03 1.67370166e+03 1.62986865e+03 1.53149536e+03 1.51001367e+03 1.50761707e+03 1.48709253e+03 1.46483289e+03 1.43986157e+03 1.39163232e+03 1.36697107e+03 1.33633484e+03 1.28558447e+03 1.26409778e+03 1.23872607e+03 1.22891846e+03 1.21517297e+03 1.16782227e+03 1.12337085e+03 1.10881689e+03 1.10345569e+03 1.10722742e+03 1.07023193e+03 9.99342224e+02 9.74537292e+02 9.72484131e+02 9.45865417e+02 9.11468811e+02 8.92446045e+02 8.72837036e+02 8.53751038e+02 8.23605286e+02 7.83483826e+02 7.76685425e+02 7.73336670e+02 7.52705505e+02 7.18045105e+02 6.82621643e+02 6.72169128e+02 6.48319885e+02 6.23172913e+02 6.22302307e+02 6.01387756e+02 5.63303101e+02 5.47162476e+02 5.38487305e+02 5.27593140e+02 5.08499634e+02 4.80098969e+02 4.63882599e+02 4.49260040e+02 4.26871124e+02 4.07825134e+02 3.98455322e+02 3.84392700e+02 3.72960815e+02 3.57382019e+02 3.27973053e+02 3.17810425e+02 3.07783020e+02 2.94125305e+02 2.87348358e+02 2.66252716e+02 2.49703964e+02 2.45424454e+02 2.33714218e+02 2.16599960e+02 2.04204910e+02 1.91764877e+02 1.80398788e+02 1.71351288e+02 1.61601013e+02 1.50589447e+02 1.43518372e+02 1.35821823e+02 1.24643875e+02 1.14331238e+02 1.04301689e+02 9.82013092e+01 9.22078705e+01 8.38225479e+01 7.49232788e+01 6.77949524e+01 6.22683525e+01 5.67953415e+01 5.18080101e+01 4.52468452e+01 3.94593697e+01 3.53972511e+01 3.09734192e+01 2.64503536e+01 2.28938675e+01 1.91719894e+01 1.57831583e+01 1.34873266e+01 1.10102921e+01 8.66942310e+00 6.77594233e+00 5.29466867e+00 4.22569942e+00 3.42638206e+00 2.93237376e+00 2.77499247e+00 2.96591067e+00 3.47985125e+00 4.29563379e+00 5.43536329e+00 6.84423923e+00 8.68471050e+00 1.09010048e+01 1.33826714e+01 1.65882072e+01 1.98136883e+01 2.29088268e+01 2.65792770e+01 3.09615841e+01 3.64156075e+01 4.17293243e+01 4.59036446e+01 5.05218086e+01 5.59188004e+01 6.25755882e+01 6.99386215e+01 7.71053009e+01 8.42791595e+01 9.10332565e+01 9.80071945e+01 1.05493401e+02 1.14758698e+02 1.27304787e+02 1.36223053e+02 1.41135147e+02 1.50660599e+02 1.60806915e+02 1.70999374e+02 1.85458328e+02 1.98540298e+02 2.06834702e+02 2.16756882e+02 2.27287216e+02 2.40677338e+02 2.58652466e+02 2.70671295e+02 2.83359772e+02 2.96404205e+02 3.07180054e+02 3.25281281e+02 3.35436310e+02 3.50323639e+02 3.75153625e+02 3.83625336e+02 3.93555817e+02 4.13434296e+02 4.30148193e+02 4.46288239e+02 4.78972626e+02 4.97135254e+02 4.90853424e+02 5.11685944e+02 5.36701904e+02 5.50430603e+02 5.84466614e+02 6.01782593e+02 6.03155518e+02 6.28295288e+02 6.50267822e+02 6.87112366e+02 7.16709961e+02 7.21100708e+02 7.43672424e+02 7.55475952e+02 7.59171082e+02 7.91567993e+02 8.37815796e+02 8.57039490e+02 8.82289551e+02 9.02335327e+02 8.89107971e+02 9.32119568e+02 9.96809326e+02 1.01910449e+03 1.01844849e+03 1.01462433e+03 1.05307483e+03 1.11593726e+03 1.13524426e+03 1.14699597e+03 1.18740247e+03 1.19711658e+03 1.22732324e+03 1.26199402e+03 1.25217053e+03 1.29114880e+03 1.35792578e+03 1.39661194e+03 1.40231213e+03 1.38540833e+03 1.42533472e+03 1.49627478e+03 1.53839233e+03 1.56757520e+03 1.55389929e+03 1.56249023e+03 1.62499829e+03 1.69339050e+03 1.75205029e+03 1.74961572e+03 1.74196924e+03 1.78848706e+03 1.81556201e+03 1.84565198e+03 1.90225977e+03 1.92359827e+03 1.96631812e+03 2.02861597e+03 2.02712183e+03 2.04185791e+03 2.10754248e+03 2.14990356e+03 2.18377637e+03 2.18925391e+03 2.19248022e+03 2.24193457e+03 2.32551172e+03 2.38698633e+03 2.43513672e+03 2.40750513e+03 2.39388623e+03 2.47788208e+03 2.50347021e+03 2.55949365e+03 2.64034448e+03 2.62982373e+03 2.63802710e+03 2.65766724e+03 2.72431323e+03 2.82726196e+03 2.90444702e+03 2.88892114e+03 2.90201123e+03 2.90913525e+03 2.89065991e+03 2.97684424e+03 3.08712427e+03 3.16301416e+03 3.19341504e+03 3.13564282e+03 3.14681323e+03 3.25964331e+03 3.33326245e+03 3.36421533e+03 3.40038623e+03 3.40918188e+03 3.39529175e+03 3.51097437e+03 3.63748438e+03 3.61732007e+03 3.57502466e+03 3.65087964e+03 3.71941577e+03 3.78107935e+03 3.84087573e+03 3.86980713e+03 3.92576221e+03 3.92138062e+03 3.91731274e+03 4.08811084e+03 4.10688965e+03 4.08922778e+03 4.25177490e+03 4.17970117e+03 4.15780859e+03 4.38659229e+03 4.45983691e+03 4.27691504e+03 4.63150684e+03 4.63594922e+03 4.16937891e+03 4.12400830e+03 7.60123682e+03 7.31336475e+03 1.30788643e+04 1.58349668e+04 83249152. -3.80585650e+06 -89428832. 18929290. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -41794592. -19494640. 3.20008223e+04 1.64387773e+04 9.62565332e+03 1.16109609e+04 9.37623535e+03 1.01233066e+04 8.01640869e+03 6.99731445e+03 7.28562451e+03 7.64956885e+03 7.59959229e+03 7.49402490e+03 7.43885010e+03 7.41005029e+03 7.75796582e+03 8.03855762e+03 7.77016455e+03 7.46925342e+03 7.61662012e+03 7.80780664e+03 8.01070898e+03 8.18529248e+03 7.94322900e+03 7.84932031e+03 8.03798828e+03 8.04345752e+03 8.21168359e+03 8.14023047e+03 8.10591699e+03 8.39078320e+03 8.68786426e+03 8.54663086e+03 8.15107178e+03 8.25915234e+03 8.63830566e+03 8.75316797e+03 8.60554492e+03 8.43424316e+03 8.59587598e+03 8.94588574e+03 9.20134668e+03 8.93838477e+03 8.57948633e+03 8.75637402e+03 9.22783887e+03 9.19855664e+03 9.22370996e+03 9.11094434e+03 8.86818555e+03 9.14500684e+03 9.51347461e+03 9.30504199e+03 9.21022070e+03 9.57687793e+03 9.65845605e+03 9.56751367e+03 9.44790234e+03 9.31115820e+03 9.55632812e+03 1.00258867e+04 9.88124121e+03 9.61422852e+03 9.54617773e+03 9.59700488e+03 1.00558018e+04 1.03700166e+04 1.00847549e+04 9.84909766e+03 9.85764062e+03 9.83978027e+03 1.01969199e+04 1.05291533e+04 1.01842998e+04 1.00664971e+04 1.03688057e+04 1.03345703e+04 1.02241934e+04 1.03373623e+04 1.05111338e+04 1.07057627e+04 1.07113535e+04 1.07106289e+04 1.03808896e+04 1.02798086e+04 1.08785107e+04 1.11896865e+04 1.06666562e+04 1.04103271e+04 1.07051152e+04 1.09826094e+04 1.11869150e+04 1.13757480e+04 1.09595918e+04 1.08073232e+04 1.11032090e+04 1.11506924e+04 1.13270947e+04 1.11998408e+04 1.09794697e+04 1.11451992e+04 1.14017295e+04 1.14779795e+04 1.14547725e+04 1.15204707e+04 1.14980830e+04 1.15227646e+04 1.16396494e+04 1.13213770e+04 1.12825723e+04 1.19663857e+04 1.20290957e+04 1.14784619e+04 1.13063457e+04 1.15477021e+04 1.20689785e+04 1.24706836e+04 1.20558584e+04 1.15531416e+04 1.15814639e+04 1.18175322e+04 1.20482764e+04 1.21761475e+04 1.20855420e+04 1.21037646e+04 1.20812100e+04 1.21080664e+04 1.21899844e+04 1.19989150e+04 1.22136016e+04 1.26502852e+04 1.24470205e+04 1.22933477e+04 1.21986240e+04 1.20307422e+04 1.25627178e+04 1.29252227e+04 1.23488604e+04 1.20659600e+04 1.23479668e+04 1.28593438e+04 1.31053779e+04 1.27045518e+04 1.23525244e+04 1.24006631e+04 1.25700889e+04 1.28800654e+04 1.30604434e+04 1.25672549e+04 1.23122227e+04 1.27280625e+04 1.31401904e+04 1.30751338e+04 1.28322500e+04 1.28810781e+04 1.28401426e+04 1.30277148e+04 1.31449355e+04 1.27419043e+04 1.27203955e+04 1.30822900e+04 1.31946660e+04 1.31270361e+04 1.28806064e+04 1.29342939e+04 1.31801572e+04 1.32406270e+04 1.33153477e+04 1.30331934e+04 1.31121758e+04 1.34034404e+04 1.33104775e+04 1.32266709e+04 1.30506436e+04 1.30919463e+04 1.34144941e+04 1.37687920e+04 1.35852988e+04 1.29613545e+04 1.28963428e+04 1.35194014e+04 1.38765957e+04 1.36401562e+04 1.31214268e+04 1.29854502e+04 1.33935947e+04 1.36347285e+04 1.36760791e+04 1.33805176e+04 1.31672646e+04 1.33719971e+04 1.36513301e+04 1.37937715e+04 1.35996768e+04 1.34013271e+04 1.35112900e+04 1.35688975e+04 1.36002393e+04 1.36279795e+04 1.35564365e+04 1.35570674e+04 1.34975430e+04 1.33146328e+04 1.32757627e+04 1.37666318e+04 1.42578896e+04 1.40712891e+04 1.35261689e+04 1.30581875e+04 1.32248721e+04 1.40647559e+04 1.43867852e+04 1.39236611e+04 1.34109756e+04 1.31326973e+04 1.34951953e+04 1.40547783e+04 1.40222734e+04 1.37994746e+04 1.36544258e+04 1.36489238e+04 1.35954873e+04 1.32213984e+04 1.32985225e+04 1.36601934e+04 1.37530879e+04 1.42064609e+04 1.39518818e+04 1.30396885e+04 1.32780322e+04 1.38180459e+04 1.38519697e+04 1.38435000e+04 1.36058604e+04 1.39734717e+04 1.40957480e+04 1.33840420e+04 1.29744287e+04 1.32546377e+04 1.39352598e+04 1.43649082e+04 1.41211631e+04 1.33636816e+04 1.29238008e+04 1.32213105e+04 1.38948447e+04 1.42606543e+04 1.40151514e+04 1.32557598e+04 1.31637891e+04 1.40089590e+04 1.39513271e+04 1.32554434e+04 1.33234922e+04 1.34540020e+04 1.34130723e+04 1.39384121e+04 1.36112803e+04 1.30594717e+04 1.34251230e+04 1.31725283e+04 1.34857588e+04 1.38061377e+04 1.30901562e+04 1.33635244e+04 1.37231553e+04 1.33969414e+04 1.34579902e+04 1.33393926e+04 1.33203877e+04 1.34737656e+04 1.33132295e+04 1.29085625e+04 1.29551309e+04 1.36360088e+04 1.39368135e+04 1.35561045e+04 1.29269131e+04 1.26361504e+04 1.28427812e+04 1.34372354e+04 1.38548145e+04 1.34104150e+04 1.27593096e+04 1.28319141e+04 1.31861543e+04 1.30724971e+04 1.29154902e+04 1.29457031e+04 1.29310479e+04 1.29275850e+04 1.33972900e+04 1.30516064e+04 1.25838496e+04 1.29021807e+04 1.24853135e+04 1.28684678e+04 1.31377334e+04 1.26753193e+04 1.31767207e+04 1.28911016e+04 1.22366738e+04 1.25978848e+04 1.24101201e+04 1.25735527e+04 1.33389160e+04 1.26813750e+04 1.19559551e+04 1.21690449e+04 1.27459688e+04 1.32341680e+04 1.28817354e+04 1.21980664e+04 1.18939434e+04 1.19439941e+04 1.24651523e+04 1.29300010e+04 1.27174258e+04 1.20499043e+04 1.18763721e+04 1.22524434e+04 1.23466523e+04 1.20823457e+04 1.19959121e+04 1.20211143e+04 1.19878174e+04 1.23829434e+04 1.23439111e+04 1.16796426e+04 1.16336982e+04 1.18022119e+04 1.18065791e+04 1.18861543e+04 1.18143701e+04 1.21366279e+04 1.17581309e+04 1.13060791e+04 1.16829707e+04 1.12892061e+04 1.14976455e+04 1.23658486e+04 1.16044424e+04 1.07813906e+04 1.11732773e+04 1.16408994e+04 1.18844902e+04 1.18196074e+04 1.11365996e+04 1.06762285e+04 1.08773818e+04 1.14690879e+04 1.18364053e+04 1.14373535e+04 1.07307432e+04 1.06514404e+04 1.09580986e+04 1.10748408e+04 1.13492256e+04 1.13062559e+04 1.06163320e+04 1.04873799e+04 1.08437520e+04 1.09908447e+04 1.06766367e+04 1.05251572e+04 1.05669316e+04 1.04596152e+04 1.07902520e+04 1.07986387e+04 1.03248760e+04 1.02641387e+04 1.02918086e+04 1.02403994e+04 1.03368057e+04 1.02294590e+04 1.03481133e+04 1.05118398e+04 1.01421475e+04 9.86389551e+03 9.62189160e+03 9.97593750e+03 1.05111719e+04 1.02749766e+04 9.65711914e+03 9.36571289e+03 9.66620020e+03 1.01783291e+04 9.80685938e+03 9.25535352e+03 9.42237891e+03 9.59949219e+03 9.78086133e+03 1.00098232e+04 9.77858008e+03 9.15254297e+03 8.93681250e+03 9.21701074e+03 9.41566016e+03 9.39265234e+03 9.16619238e+03 9.16330469e+03 9.04541406e+03 9.18042090e+03 8.99136328e+03 8.76105566e+03 8.80670605e+03 8.67799707e+03 8.90356543e+03 9.08507227e+03 8.72384473e+03 8.75226953e+03 8.73170410e+03 8.60944434e+03 8.36449512e+03 8.16660254e+03 8.51434863e+03 8.84087793e+03 8.51312109e+03 8.06745557e+03 8.00776367e+03 8.40604004e+03 8.49681738e+03 8.26524121e+03 8.12967725e+03 7.77159863e+03 7.72362549e+03 8.06392041e+03 8.02713281e+03 7.83554639e+03 7.58555762e+03 7.41285791e+03 7.75430420e+03 8.07156689e+03 7.60284912e+03 7.37798291e+03 7.50105713e+03 7.46485596e+03 7.63206885e+03 7.62623975e+03 7.09594727e+03 7.02151318e+03 7.18209521e+03 7.13984814e+03 7.14742480e+03 7.10192676e+03 7.43207324e+03 7.43556055e+03 6.63833057e+03 6.88660840e+03 6.43379346e+03 7.71113721e+03 9.23912109e+03 1.05384541e+04 9.47988379e+03 1.10790430e+04 1.81771270e+04 2.01088965e+04 -5942834. -2.08809350e+06 -3446233. -20889166. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 67853944. 8939442. 1.73995762e+04 1.11886104e+04 7.30634717e+03 6.97955615e+03 5.68310693e+03 5.20165381e+03 4.16742920e+03 4.47704395e+03 4.25462207e+03 4.05215479e+03 4.07922510e+03 4.03082861e+03 3.91776343e+03 3.89367090e+03 3.87157202e+03 3.86675098e+03 3.88695312e+03 3.74191699e+03 3.56137036e+03 3.59144116e+03 3.54161182e+03 3.35293750e+03 3.51227075e+03 3.53702124e+03 3.21800171e+03 3.38280005e+03 3.51247754e+03 3.31050146e+03 3.20962915e+03 3.22422363e+03 3.25292261e+03 3.15994312e+03 3.11106934e+03 3.06713940e+03 3.02316260e+03 2.91146680e+03 2.86698047e+03 2.97845361e+03 2.93494434e+03 2.81224194e+03 2.76809009e+03 2.74613965e+03 2.72077905e+03 2.66019995e+03 2.62150464e+03 2.59959424e+03 2.52029907e+03 2.46363647e+03 2.45779785e+03 2.41982129e+03 2.47310010e+03 2.45264160e+03 2.33904419e+03 2.24633008e+03 2.18898950e+03 2.28629175e+03 2.26801172e+03 2.15420801e+03 2.08251416e+03 2.06147144e+03 2.06036353e+03 2.00336646e+03 2.03100513e+03 2.00565979e+03 1.86191370e+03 1.80840442e+03 1.86459070e+03 1.90794507e+03 1.82894421e+03 1.74984546e+03 1.72334497e+03 1.68830225e+03 1.65629749e+03 1.63021606e+03 1.61204285e+03 1.57548669e+03 1.52093359e+03 1.49310706e+03 1.47169360e+03 1.43804773e+03 1.45530872e+03 1.41917480e+03 1.34801501e+03 1.32962244e+03 1.29913770e+03 1.30362439e+03 1.28165552e+03 1.22240686e+03 1.19519165e+03 1.14797266e+03 1.10569678e+03 1.12978833e+03 1.10356458e+03 1.02016614e+03 1.01045587e+03 1.04346765e+03 1.04982751e+03 9.94077515e+02 9.41392212e+02 9.10347168e+02 8.84768066e+02 8.65990295e+02 8.42348450e+02 8.21075745e+02 7.96003174e+02 7.95961426e+02 7.71346985e+02 7.28018372e+02 7.11979614e+02 6.72039917e+02 6.65462158e+02 6.83738708e+02 6.51398865e+02 6.16624390e+02 5.79764221e+02 5.56028076e+02 5.68555542e+02 5.53829163e+02 5.18943542e+02 4.88770355e+02 4.68573639e+02 4.63094238e+02 4.46264893e+02 4.43045502e+02 4.28825226e+02 3.98020569e+02 3.79621399e+02 3.64323853e+02 3.55143646e+02 3.41467316e+02 3.22843292e+02 3.04716766e+02 2.91029968e+02 2.77966827e+02 2.57072723e+02 2.50538055e+02 2.52894577e+02 2.36527023e+02 2.17708588e+02 2.00383911e+02 1.88633255e+02 1.88484772e+02 1.77656799e+02 1.62448639e+02 1.48482315e+02 1.38029419e+02 1.33312027e+02 1.23672821e+02 1.14536644e+02 1.03738243e+02 9.76515503e+01 9.42270050e+01 8.41058731e+01 7.62371368e+01 6.99383774e+01 6.30417747e+01 5.58077621e+01 4.99268990e+01 4.48157845e+01 3.96810188e+01 3.53997383e+01 3.00670757e+01 2.62107067e+01 2.38062344e+01 1.94695511e+01 1.57261772e+01 1.32780266e+01 1.08353682e+01 8.85936642e+00 6.93474483e+00 5.31548977e+00 4.23678255e+00 3.42891645e+00 2.93589783e+00 2.77431607e+00 2.94482303e+00 3.45911336e+00 4.31645107e+00 5.50425196e+00 6.90975285e+00 8.84524441e+00 1.14478006e+01 1.37962780e+01 1.62664089e+01 1.89949818e+01 2.27409000e+01 2.79942875e+01 3.19386883e+01 3.54909210e+01 3.96263237e+01 4.44386902e+01 5.10662422e+01 5.71034317e+01 6.44457626e+01 7.04428635e+01 7.54290848e+01 8.31295624e+01 9.05266495e+01 1.01178238e+02 1.08934959e+02 1.14064308e+02 1.23429955e+02 1.33182983e+02 1.42327499e+02 1.47671921e+02 1.61856125e+02 1.82693146e+02 1.89127411e+02 1.94676773e+02 2.01062881e+02 2.10548767e+02 2.35258560e+02 2.50562073e+02 2.55537933e+02 2.61268402e+02 2.73447510e+02 2.96134918e+02 3.09694580e+02 3.31050140e+02 3.46400208e+02 3.52110931e+02 3.57456451e+02 3.71609772e+02 4.09896515e+02 4.24997253e+02 4.29105804e+02 4.39432159e+02 4.54316193e+02 4.97473358e+02 5.17733826e+02 5.05517426e+02 5.21202515e+02 5.70837097e+02 5.89879639e+02 5.78936523e+02 5.98190796e+02 6.48338623e+02 6.74300354e+02 6.72835205e+02 6.77159851e+02 6.98263550e+02 7.58604614e+02 7.72376221e+02 7.66401550e+02 8.04567505e+02 8.26588135e+02 8.45857849e+02 8.69505005e+02 8.90818176e+02 8.93687927e+02 9.38807922e+02 1.00499292e+03 1.00612854e+03 1.03316003e+03 1.06364258e+03 1.07025818e+03 1.09821094e+03 1.12023608e+03 1.14173157e+03 1.14697864e+03 1.16928040e+03 1.22237842e+03 1.25588074e+03 1.32260571e+03 1.30996106e+03 1.29224536e+03 1.36404956e+03 1.40236963e+03 1.47537354e+03 1.48750244e+03 1.47110657e+03 1.49286414e+03 1.51375281e+03 1.57213843e+03 1.60357141e+03 1.67074072e+03 1.69923059e+03 1.68874011e+03 1.71190369e+03 1.69760974e+03 1.77371387e+03 1.91494946e+03 1.91631836e+03 1.89080408e+03 1.88003589e+03 1.88457629e+03 2.00648096e+03 2.10903760e+03 2.09096899e+03 2.03867554e+03 2.07568335e+03 2.15855884e+03 2.19378662e+03 2.28629272e+03 2.30452197e+03 2.28514697e+03 2.31395728e+03 2.34885449e+03 2.47083252e+03 2.50831982e+03 2.41708105e+03 2.44922534e+03 2.62477490e+03 2.63740942e+03 2.54134204e+03 2.62843115e+03 2.80456543e+03 2.82080762e+03 2.78824414e+03 2.76086694e+03 2.78144629e+03 2.96721899e+03 3.02316626e+03 2.98480420e+03 2.95104102e+03 2.95744751e+03 3.09388843e+03 3.15539966e+03 3.18227710e+03 3.13408545e+03 3.24970923e+03 3.41783228e+03 3.37744580e+03 3.44525269e+03 3.46429761e+03 3.42677197e+03 3.51408496e+03 3.56939038e+03 3.61135620e+03 3.62075244e+03 3.60873584e+03 3.59495776e+03 3.72725708e+03 3.98454321e+03 3.82271460e+03 3.72399341e+03 3.86534009e+03 4.05378369e+03 4.19445459e+03 4.14248535e+03 4.05944019e+03 4.21878320e+03 4.24668408e+03 4.17183301e+03 4.17177783e+03 4.36046729e+03 4.42824707e+03 4.37517139e+03 4.37114990e+03 4.29434326e+03 4.52375342e+03 4.84525830e+03 4.77299756e+03 4.67892773e+03 4.60330957e+03 4.57950439e+03 4.87886572e+03 5.11141016e+03 5.01413916e+03 4.86456396e+03 4.90526416e+03 5.00805127e+03 5.04735498e+03 5.26977490e+03 5.22060547e+03 5.13238867e+03 5.26982324e+03 5.30207568e+03 5.49897070e+03 5.54660449e+03 5.41369287e+03 5.49887500e+03 5.54005469e+03 5.62963184e+03 5.57115137e+03 5.58417188e+03 5.92330908e+03 5.91506738e+03 5.85346240e+03 5.72071484e+03 5.81996631e+03 6.24621533e+03 6.23269971e+03 6.08076367e+03 6.03126611e+03 6.04637549e+03 6.17628711e+03 6.23174658e+03 6.29347705e+03 6.20132812e+03 6.38397412e+03 6.67273730e+03 6.49048926e+03 6.64647217e+03 6.79193701e+03 6.66975488e+03 6.69154199e+03 6.69516406e+03 6.78361816e+03 6.83630811e+03 6.81134912e+03 6.87121826e+03 7.10778320e+03 7.18421484e+03 6.89595166e+03 6.88925195e+03 7.10251709e+03 7.29792920e+03 7.62892578e+03 7.45217871e+03 7.15202979e+03 7.45645898e+03 7.59727441e+03 7.51628320e+03 7.51991748e+03 7.56475195e+03 7.53486182e+03 7.56873047e+03 7.79428516e+03 7.69202783e+03 7.77841992e+03 8.14704590e+03 8.05399902e+03 7.96750342e+03 7.85460107e+03 7.93098291e+03 8.34884082e+03 8.32165625e+03 8.22418750e+03 8.09248682e+03 7.94556201e+03 8.17844873e+03 8.58641016e+03 8.86452637e+03 8.55607715e+03 8.34454297e+03 8.47165527e+03 8.57886328e+03 8.98393066e+03 8.93633203e+03 8.71304492e+03 8.69333594e+03 8.72461133e+03 8.86089551e+03 8.78286719e+03 8.92168848e+03 9.38377832e+03 9.22522559e+03 9.20835938e+03 9.03809180e+03 9.00364941e+03 9.55308008e+03 9.64399316e+03 9.36302441e+03 9.21162891e+03 9.15369629e+03 9.41865723e+03 9.53651758e+03 9.84100391e+03 9.88293652e+03 9.60955664e+03 9.45588965e+03 9.63129199e+03 1.01082842e+04 1.00472510e+04 9.91625293e+03 9.87333203e+03 9.84169238e+03 9.90491211e+03 9.87076562e+03 1.01657188e+04 1.01849648e+04 1.00096406e+04 1.04457217e+04 1.05894082e+04 1.03746211e+04 1.03618730e+04 1.03790283e+04 1.04319463e+04 1.01650283e+04 1.01154912e+04 1.07374766e+04 1.09044863e+04 1.03496543e+04 1.01829258e+04 1.07449512e+04 1.12242891e+04 1.10980020e+04 1.06950566e+04 1.05415771e+04 1.09753115e+04 1.12119424e+04 1.09767832e+04 1.10911455e+04 1.08307451e+04 1.04628311e+04 1.09523701e+04 1.16619854e+04 1.17128535e+04 1.10934102e+04 1.07701016e+04 1.14640293e+04 1.18735215e+04 1.15279814e+04 1.11714600e+04 1.10803096e+04 1.12790850e+04 1.14616807e+04 1.19200498e+04 1.19556582e+04 1.15842178e+04 1.14575771e+04 1.14731855e+04 1.20048701e+04 1.17931250e+04 1.14992354e+04 1.20577773e+04 1.20675596e+04 1.19506523e+04 1.17256133e+04 1.16527842e+04 1.23677578e+04 1.20635215e+04 1.16095996e+04 1.19963711e+04 1.22428652e+04 1.23089551e+04 1.21595293e+04 1.25061162e+04 1.26097939e+04 1.22754727e+04 1.19414746e+04 1.19219053e+04 1.26815889e+04 1.25326074e+04 1.22102197e+04 1.23691084e+04 1.23405078e+04 1.25501348e+04 1.25577227e+04 1.26986543e+04 1.26213604e+04 1.23145049e+04 1.28179961e+04 1.29314434e+04 1.27392295e+04 1.27755049e+04 1.27835752e+04 1.26523359e+04 1.23162139e+04 1.22783350e+04 1.29897969e+04 1.35411094e+04 1.28231221e+04 1.22798887e+04 1.28300654e+04 1.34456436e+04 1.33294775e+04 1.27867725e+04 1.24973623e+04 1.32000693e+04 1.33110840e+04 1.28311191e+04 1.33796846e+04 1.33113330e+04 1.26300098e+04 1.28338369e+04 1.35494111e+04 1.36499756e+04 1.29825332e+04 1.26082607e+04 1.32837959e+04 1.38494424e+04 1.34924883e+04 1.29640977e+04 1.27558154e+04 1.34267100e+04 1.36490693e+04 1.32600215e+04 1.33747520e+04 1.34660820e+04 1.33068574e+04 1.32135596e+04 1.37184102e+04 1.35267832e+04 1.30617100e+04 1.35279131e+04 1.36423174e+04 1.37494668e+04 1.34045264e+04 1.31022812e+04 1.37394355e+04 1.34405352e+04 1.30827881e+04 1.36047783e+04 1.39504463e+04 1.43876377e+04 1.41006797e+04 1.47485195e+04 1.35938008e+04 1.79732539e+04 1.36681465e+04 1.61519385e+04 1.81909629e+04 1.36543193e+04 3.09511074e+04 7.17399062e+04 2.30180812e+05 -4.52047258e+09 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. 1.06926203e+10 3.16328812e+05 5.62827734e+04 3.96921523e+04 2.40370840e+04 1.91127637e+04 1.78158750e+04 1.38090352e+04 1.44472451e+04 1.35193506e+04 1.34878105e+04 1.47806211e+04 1.20744287e+04 1.62384902e+04 1.99700078e+04 1.98437500e+04 1.87426816e+04 1.85078867e+04 1.38398672e+04 1.41405859e+04 1.44122197e+04 1.34343271e+04 1.36543457e+04 1.36673818e+04 1.32004385e+04 1.32566221e+04 1.36249814e+04 1.37003711e+04 1.36805547e+04 1.33526982e+04 1.30645322e+04 1.33279121e+04 1.35043135e+04 1.33715049e+04 1.31430488e+04 1.30816240e+04 1.34402334e+04 1.34856436e+04 1.32274541e+04 1.30964648e+04 1.30915459e+04 1.35046465e+04 1.35888076e+04 1.29305107e+04 1.28354336e+04 1.31168379e+04 1.31210801e+04 1.33261221e+04 1.32186426e+04 1.28711641e+04 1.30562842e+04 1.31436055e+04 1.30294648e+04 1.30470479e+04 1.28933115e+04 1.29289248e+04 1.30308096e+04 1.28521172e+04 1.27711045e+04 1.27247461e+04 1.27778086e+04 1.29961514e+04 1.29837100e+04 1.28636484e+04 1.26047852e+04 1.24761191e+04 1.28286396e+04 1.27986934e+04 1.24295654e+04 1.25584131e+04 1.25947646e+04 1.25740068e+04 1.28040430e+04 1.26791143e+04 1.23472510e+04 1.22912578e+04 1.25834238e+04 1.26500771e+04 1.23167705e+04 1.20680420e+04 1.21247168e+04 1.22972529e+04 1.25854502e+04 1.24970537e+04 1.20057666e+04 1.20193350e+04 1.23392754e+04 1.22916689e+04 1.21809111e+04 1.18399873e+04 1.17536504e+04 1.21431611e+04 1.21690625e+04 1.18563857e+04 1.18223145e+04 1.18591377e+04 1.18195488e+04 1.17957900e+04 1.17362568e+04 1.17872441e+04 1.17683027e+04 1.18837422e+04 1.18172334e+04 1.13723027e+04 1.14085234e+04 1.16340010e+04 1.14962930e+04 1.13927090e+04 1.13489834e+04 1.13706094e+04 1.15578662e+04 1.14005215e+04 1.11966289e+04 1.13626367e+04 1.13789160e+04 1.10870811e+04 1.10457412e+04 1.10980635e+04 1.11292500e+04 1.10350869e+04 1.08821826e+04 1.08645605e+04 1.09025469e+04 1.10893691e+04 1.10056396e+04 1.05736895e+04 1.06369395e+04 1.08542832e+04 1.07943555e+04 1.06761367e+04 1.04728291e+04 1.03146465e+04 1.05269502e+04 1.07449707e+04 1.05031143e+04 1.01943135e+04 1.02234746e+04 1.04320557e+04 1.04578828e+04 1.04597529e+04 1.01610029e+04 9.84983984e+03 1.00157861e+04 1.00324922e+04 9.97457520e+03 1.00372441e+04 9.89228613e+03 9.91431445e+03 1.01081992e+04 9.87569531e+03 9.48236035e+03 9.58962207e+03 9.77087793e+03 9.73156934e+03 9.73810840e+03 9.54643359e+03 9.37212012e+03 9.38020801e+03 9.62811426e+03 9.41127441e+03 9.02164941e+03 9.18571387e+03 9.39603516e+03 9.24973438e+03 9.11015723e+03 8.96038965e+03 8.90152930e+03 9.01398438e+03 8.91884961e+03 8.88767578e+03 8.96594238e+03 8.75974805e+03 8.74788086e+03 8.90986914e+03 8.73763672e+03 8.46102344e+03 8.46156836e+03 8.56631543e+03 8.60598633e+03 8.50621777e+03 8.32414746e+03 8.15008398e+03 8.22243652e+03 8.57661426e+03 8.55713672e+03 7.96133545e+03 7.99742627e+03 8.22269336e+03 8.11763623e+03 7.96286719e+03 7.79560498e+03 7.76582373e+03 7.88328662e+03 7.89641553e+03 7.75160596e+03 7.61394678e+03 7.50887988e+03 7.58501465e+03 7.68177979e+03 7.62558008e+03 7.44512109e+03 7.35209668e+03 7.38082227e+03 7.33506201e+03 7.18828613e+03 7.16409424e+03 7.15804883e+03 7.11286133e+03 7.17865381e+03 7.23976416e+03 6.84948779e+03 6.82685156e+03 6.93127979e+03 6.93029443e+03 6.89158301e+03 6.64920557e+03 6.62419482e+03 6.77182764e+03 6.71604688e+03 6.60587305e+03 6.38201367e+03 6.30113379e+03 6.45116943e+03 6.52096680e+03 6.35744727e+03 6.26895947e+03 6.28396582e+03 6.18161572e+03 6.23676758e+03 6.16131934e+03 5.95278271e+03 5.88556543e+03 5.88635840e+03 6.00436279e+03 5.86161914e+03 5.71614990e+03 5.72174658e+03 5.77024414e+03 5.72518457e+03 5.61090332e+03 5.52060498e+03 5.47726416e+03 5.51989697e+03 5.40082861e+03 5.45818604e+03 5.33936621e+03 5.19650732e+03 5.31333008e+03 5.10377197e+03 5.11348145e+03 5.18769775e+03 5.02899609e+03 4.93131445e+03 4.96809863e+03 4.91265137e+03 4.84233545e+03 4.71092529e+03 4.83565576e+03 4.92260205e+03 4.63096680e+03 4.52450928e+03 4.57827734e+03 4.53315283e+03 4.59736914e+03 4.50458154e+03 4.33233154e+03 4.33170850e+03 4.37333838e+03 4.32308691e+03 4.23810059e+03 4.17030322e+03 4.14014014e+03 4.13635010e+03 4.00819873e+03 3.99491943e+03 3.94093335e+03 3.88002222e+03 3.88460010e+03 3.88639844e+03 3.84656226e+03 3.73545239e+03 3.65399609e+03 3.71417554e+03 3.74699634e+03 3.56836279e+03 3.55652222e+03 3.52732642e+03 3.38495923e+03 3.42137451e+03 3.40129810e+03 3.28698584e+03 3.31966406e+03 3.28075293e+03 3.20519189e+03 3.24726099e+03 3.14791724e+03 3.05740210e+03 3.03938135e+03 3.03783691e+03 3.02340210e+03 2.90667212e+03 2.85142725e+03 2.87281812e+03 2.85667944e+03 2.80424756e+03 2.74280908e+03 2.67679663e+03 2.68489771e+03 2.71988843e+03 2.59731592e+03 2.51449414e+03 2.47576074e+03 2.52355786e+03 2.51186743e+03 2.38913892e+03 2.34455273e+03 2.33145703e+03 2.30941895e+03 2.26147827e+03 2.24891211e+03 2.20442432e+03 2.12893945e+03 2.13446924e+03 2.15002002e+03 2.06095532e+03 1.95161694e+03 1.95642444e+03 1.97373352e+03 1.93381433e+03 1.90584131e+03 1.85621960e+03 1.79809399e+03 1.81860388e+03 1.81866797e+03 1.72751367e+03 1.67706555e+03 1.65701526e+03 1.67461914e+03 1.63330933e+03 1.53348291e+03 1.50897668e+03 1.50891064e+03 1.49014978e+03 1.45983740e+03 1.43950854e+03 1.39197388e+03 1.36656543e+03 1.33810303e+03 1.28700989e+03 1.26341907e+03 1.23780151e+03 1.22678674e+03 1.21761047e+03 1.17046289e+03 1.12121582e+03 1.10755066e+03 1.10237476e+03 1.10688843e+03 1.07188696e+03 9.99305847e+02 9.75427673e+02 9.73061035e+02 9.46299866e+02 9.11238159e+02 8.88137512e+02 8.70294678e+02 8.54651978e+02 8.21326172e+02 7.81778381e+02 7.75546021e+02 7.70655396e+02 7.51700317e+02 7.18422058e+02 6.82137268e+02 6.68461243e+02 6.43745544e+02 6.21374878e+02 6.22625916e+02 6.02265137e+02 5.63312317e+02 5.46063293e+02 5.35918457e+02 5.28168274e+02 5.10349701e+02 4.81928467e+02 4.62696747e+02 4.46770905e+02 4.27040131e+02 4.07957336e+02 3.98131165e+02 3.83209290e+02 3.71056427e+02 3.56189056e+02 3.27929504e+02 3.17445892e+02 3.06616486e+02 2.92061066e+02 2.85712250e+02 2.65490448e+02 2.48605850e+02 2.44504822e+02 2.33254349e+02 2.17211014e+02 2.04530762e+02 1.90476715e+02 1.78419189e+02 1.69398514e+02 1.60778839e+02 1.50230316e+02 1.43310257e+02 1.35111923e+02 1.23458931e+02 1.13086121e+02 1.03437881e+02 9.73010483e+01 9.12469177e+01 8.26878586e+01 7.36488190e+01 6.68535843e+01 6.16073265e+01 5.66304321e+01 5.16836815e+01 4.48850784e+01 3.87572784e+01 3.42586670e+01 2.97547302e+01 2.54763966e+01 2.24566135e+01 1.89589863e+01 1.53927670e+01 1.27278252e+01 1.01368361e+01 8.02316380e+00 6.31753731e+00 4.81641674e+00 3.63045883e+00 2.78409219e+00 2.29262209e+00 2.14296627e+00 2.33322048e+00 2.85517621e+00 3.69502401e+00 4.87234163e+00 6.30701017e+00 8.29078102e+00 1.06090860e+01 1.30479116e+01 1.59487848e+01 1.89733562e+01 2.23025227e+01 2.62855854e+01 3.06882343e+01 3.57906532e+01 4.05938797e+01 4.47339935e+01 5.00240021e+01 5.57607155e+01 6.19483185e+01 6.88884048e+01 7.64729309e+01 8.41411972e+01 9.08090439e+01 9.79477463e+01 1.05690804e+02 1.14649765e+02 1.26920517e+02 1.36115005e+02 1.40982193e+02 1.50469116e+02 1.61178055e+02 1.71045898e+02 1.85397003e+02 1.97421875e+02 2.05415482e+02 2.16574478e+02 2.28454498e+02 2.41671707e+02 2.58103302e+02 2.69112244e+02 2.81788208e+02 2.95861847e+02 3.07158722e+02 3.25393402e+02 3.34769257e+02 3.49932129e+02 3.75573517e+02 3.83541870e+02 3.94909973e+02 4.15517029e+02 4.29427063e+02 4.45276276e+02 4.78819611e+02 4.96339203e+02 4.89736450e+02 5.12455078e+02 5.38760193e+02 5.51294495e+02 5.83380737e+02 5.99902527e+02 6.01666077e+02 6.29821960e+02 6.52335266e+02 6.82676208e+02 7.12170471e+02 7.19942749e+02 7.43329407e+02 7.56327820e+02 7.62052856e+02 7.95963318e+02 8.38907959e+02 8.56001831e+02 8.82066223e+02 9.03008972e+02 8.92088867e+02 9.33530334e+02 9.99665894e+02 1.01909998e+03 1.01724036e+03 1.01353180e+03 1.05089380e+03 1.11580505e+03 1.13286157e+03 1.14439197e+03 1.19038000e+03 1.19787354e+03 1.22895312e+03 1.26811768e+03 1.24943201e+03 1.28939026e+03 1.35834436e+03 1.39472620e+03 1.40150000e+03 1.38628467e+03 1.42700977e+03 1.49414514e+03 1.54427515e+03 1.56300659e+03 1.55313733e+03 1.56738879e+03 1.62265051e+03 1.69114514e+03 1.74883984e+03 1.74885413e+03 1.74113843e+03 1.78787402e+03 1.81850452e+03 1.84961365e+03 1.90091064e+03 1.92333423e+03 1.95910413e+03 2.02770837e+03 2.02389392e+03 2.04165820e+03 2.10207251e+03 2.14374561e+03 2.18019165e+03 2.18826636e+03 2.19331396e+03 2.24395508e+03 2.32542847e+03 2.38959058e+03 2.44447583e+03 2.41685596e+03 2.38630542e+03 2.47330054e+03 2.50676025e+03 2.56231372e+03 2.63779224e+03 2.62065381e+03 2.63390967e+03 2.67197656e+03 2.72686694e+03 2.82635059e+03 2.90572949e+03 2.89351172e+03 2.90086108e+03 2.91456543e+03 2.89655103e+03 2.97856567e+03 3.09643018e+03 3.16772754e+03 3.19423950e+03 3.14036865e+03 3.15121777e+03 3.25801343e+03 3.33844556e+03 3.38014893e+03 3.39843848e+03 3.40068848e+03 3.40126880e+03 3.51711377e+03 3.64244287e+03 3.62793164e+03 3.56909106e+03 3.65032544e+03 3.72345752e+03 3.77734326e+03 3.84151733e+03 3.86489502e+03 3.94185718e+03 3.91844482e+03 3.91870312e+03 4.10142090e+03 4.10937500e+03 4.09086328e+03 4.24937402e+03 4.16578223e+03 4.16226514e+03 4.39752246e+03 4.43656055e+03 4.28078760e+03 4.63246387e+03 4.62819824e+03 4.16915771e+03 4.16250195e+03 8.65754883e+03 6.88345020e+03 1.40279346e+04 1.33271221e+04 4.13390450e+06 -6.07945850e+06 4571344. 5111982. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -41794592. -19494640. 3.20008223e+04 1.64387773e+04 9.62565332e+03 1.16109609e+04 1.05043174e+04 1.06570117e+04 1.02840605e+04 5.85011621e+03 6.64949121e+03 8.77974023e+03 7.45649805e+03 6.97674512e+03 6.52187842e+03 7.19633008e+03 7.89506689e+03 7.85186133e+03 7.61168701e+03 7.61824707e+03 7.90158398e+03 7.91499463e+03 8.09792920e+03 8.21362207e+03 7.97520947e+03 7.90600195e+03 8.04568164e+03 8.08407275e+03 8.22779590e+03 8.13237256e+03 8.07590576e+03 8.39459473e+03 8.72391211e+03 8.56263574e+03 8.15868115e+03 8.24516211e+03 8.64657031e+03 8.79408496e+03 8.60253027e+03 8.43683398e+03 8.59954785e+03 8.95349805e+03 9.19885645e+03 8.97021387e+03 8.59039941e+03 8.75084766e+03 9.26521191e+03 9.17741309e+03 9.24735645e+03 9.14067773e+03 8.85857520e+03 9.11231348e+03 9.47364844e+03 9.31454883e+03 9.18137695e+03 9.56359863e+03 9.65725586e+03 9.57665527e+03 9.45123438e+03 9.31224707e+03 9.55430176e+03 1.00341768e+04 9.87975000e+03 9.63485645e+03 9.55906738e+03 9.58864258e+03 1.01286260e+04 1.03435342e+04 1.00526162e+04 9.86995312e+03 9.87229004e+03 9.86401074e+03 1.01800498e+04 1.05229834e+04 1.02255508e+04 1.00597734e+04 1.03785547e+04 1.03454961e+04 1.02202109e+04 1.03050332e+04 1.05197012e+04 1.07153584e+04 1.07199590e+04 1.06749404e+04 1.04170479e+04 1.02942617e+04 1.08811924e+04 1.11769463e+04 1.06719404e+04 1.03737959e+04 1.06883428e+04 1.09740908e+04 1.12178545e+04 1.13985537e+04 1.09425596e+04 1.08211387e+04 1.11335615e+04 1.11600918e+04 1.13093486e+04 1.11842412e+04 1.09601025e+04 1.11544570e+04 1.14434873e+04 1.14818477e+04 1.14311475e+04 1.15002559e+04 1.14833115e+04 1.15509424e+04 1.16334600e+04 1.13158623e+04 1.13207012e+04 1.19700596e+04 1.20471094e+04 1.14875488e+04 1.13085127e+04 11544. 1.20945908e+04 1.24329189e+04 1.20469326e+04 1.15778525e+04 1.16067148e+04 1.18382031e+04 1.20617148e+04 1.21607451e+04 1.21134336e+04 1.20815479e+04 1.20990156e+04 1.21361768e+04 1.22005996e+04 1.19962432e+04 1.22227051e+04 1.26411670e+04 1.24238379e+04 1.22952158e+04 1.22494199e+04 1.20562461e+04 1.25567979e+04 1.29223965e+04 1.23382119e+04 1.21139697e+04 1.23732334e+04 1.28460469e+04 1.30849668e+04 1.27107100e+04 1.23657471e+04 1.23838838e+04 1.25785742e+04 1.28822051e+04 1.30573838e+04 1.25596182e+04 1.23244287e+04 1.27683457e+04 1.31501572e+04 1.30787100e+04 1.28147021e+04 1.28684014e+04 1.28579424e+04 1.30314893e+04 1.31582617e+04 1.27361396e+04 1.27358652e+04 1.31432793e+04 1.32272686e+04 1.30649893e+04 1.28377666e+04 1.29506377e+04 1.32088945e+04 1.32438027e+04 1.32983457e+04 1.30822773e+04 1.31092891e+04 1.33781650e+04 1.33161162e+04 1.31994492e+04 1.30645488e+04 1.31254180e+04 1.34425215e+04 1.37560781e+04 1.35869951e+04 1.29853457e+04 1.29097637e+04 1.35232402e+04 1.38837939e+04 1.36338770e+04 1.31474121e+04 1.29916436e+04 1.33510850e+04 1.36563926e+04 1.37099336e+04 1.33728955e+04 1.31660898e+04 1.33777930e+04 1.36792432e+04 1.37870703e+04 1.35992832e+04 1.34156230e+04 1.35050420e+04 1.35964189e+04 1.35994922e+04 1.36138369e+04 1.36065781e+04 1.35726270e+04 1.34798682e+04 1.33275732e+04 1.32737822e+04 1.37679902e+04 1.42672959e+04 1.40943809e+04 1.35342861e+04 1.30618877e+04 1.32330420e+04 1.40415391e+04 1.44245303e+04 1.39652344e+04 1.34007617e+04 1.31269336e+04 1.34941768e+04 1.40329092e+04 1.40372695e+04 1.38407227e+04 1.36415889e+04 1.36495146e+04 1.36225205e+04 1.32323379e+04 1.33093564e+04 1.36972227e+04 1.37224785e+04 1.41959004e+04 1.40008682e+04 1.30303975e+04 1.32574209e+04 1.38280625e+04 1.38907529e+04 1.38148945e+04 1.36214932e+04 1.40038730e+04 1.40717598e+04 1.33972803e+04 1.29615029e+04 1.32546035e+04 1.39533027e+04 1.43822852e+04 1.41381377e+04 1.33539658e+04 1.29252236e+04 1.32363369e+04 1.38979531e+04 1.42659395e+04 1.40408135e+04 1.32449951e+04 1.31901055e+04 1.40221631e+04 1.39272959e+04 1.32888252e+04 1.33167969e+04 1.34462988e+04 1.34378877e+04 1.39519004e+04 1.36113848e+04 1.30736230e+04 1.34325498e+04 1.31716592e+04 1.34921426e+04 1.38360586e+04 1.31190361e+04 1.33416006e+04 1.37152002e+04 1.34068633e+04 1.34170469e+04 1.33569736e+04 1.33720488e+04 1.34465830e+04 1.33146992e+04 1.29645098e+04 1.29251357e+04 1.36048721e+04 1.39643301e+04 1.35554736e+04 1.29392803e+04 1.26446445e+04 1.28593721e+04 1.34464688e+04 1.38468877e+04 1.34175459e+04 1.27496562e+04 1.28609062e+04 1.32210850e+04 1.30475693e+04 1.29347510e+04 1.29547959e+04 1.29211338e+04 1.29728271e+04 1.34003359e+04 1.30307383e+04 1.25849033e+04 1.28809209e+04 1.24719258e+04 1.28829648e+04 1.31545439e+04 1.26954805e+04 1.31721006e+04 1.28728037e+04 1.22260107e+04 1.25764551e+04 1.24392568e+04 1.25860732e+04 1.33797197e+04 1.26834180e+04 1.19677041e+04 1.21966270e+04 1.27230605e+04 1.32158193e+04 1.28978008e+04 1.22119219e+04 1.18749365e+04 1.19725195e+04 1.24676279e+04 1.29485137e+04 1.27169229e+04 1.20667666e+04 1.18948438e+04 1.22440078e+04 1.23582754e+04 1.20801094e+04 1.19836104e+04 1.20127969e+04 1.19637012e+04 1.24033730e+04 1.23972822e+04 1.16824277e+04 1.16219727e+04 1.18103691e+04 1.17965361e+04 1.18820830e+04 1.18292861e+04 1.21250654e+04 1.17771309e+04 1.13056807e+04 1.16654131e+04 1.12966963e+04 1.15278271e+04 1.23523242e+04 1.15830205e+04 1.08003721e+04 1.11309365e+04 1.16320068e+04 1.18903320e+04 1.18486123e+04 1.11429434e+04 1.06624814e+04 1.08988730e+04 1.14563193e+04 1.18604824e+04 1.14741758e+04 1.07383408e+04 1.06328242e+04 1.09862861e+04 1.10594141e+04 1.13369805e+04 1.12828184e+04 1.06203027e+04 1.05306973e+04 1.08767559e+04 1.09927910e+04 1.06428809e+04 1.05042559e+04 1.05893809e+04 1.04478369e+04 1.07983193e+04 1.08129365e+04 1.03650195e+04 1.02985332e+04 1.02716709e+04 1.02256074e+04 1.03219531e+04 1.02203945e+04 1.04065469e+04 1.04549521e+04 1.01279980e+04 9.87684082e+03 9.61174707e+03 9.98881543e+03 1.04852646e+04 1.02528047e+04 9.72271484e+03 9.37318262e+03 9.67968359e+03 1.01820908e+04 9.79979199e+03 9.24523730e+03 9.43318457e+03 9.64227539e+03 9.79151953e+03 9.98492578e+03 9.78140234e+03 9.15792676e+03 8.93328711e+03 9.16079883e+03 9.41101172e+03 9.37604980e+03 9.18188965e+03 9.13106445e+03 9.07090137e+03 9.21761426e+03 9.03563965e+03 8.71996289e+03 8.80504102e+03 8.67819629e+03 8.95812402e+03 9.09187891e+03 8.73004785e+03 8.76081934e+03 8.74514941e+03 8.66887207e+03 8.39839355e+03 8.17859375e+03 8.51327148e+03 8.83448242e+03 8.55138965e+03 8.03454834e+03 8.07234277e+03 8.42554102e+03 8.51222656e+03 8.29183496e+03 8.13557520e+03 7.78865137e+03 7.76363037e+03 8.10973145e+03 8.02286670e+03 7.84055664e+03 7.58886182e+03 7.43930664e+03 7.76212012e+03 8.04112402e+03 7.63243164e+03 7.38493555e+03 7.51968701e+03 7.44459326e+03 7.58812256e+03 7.62480811e+03 7.12244824e+03 7.03541504e+03 7.19922705e+03 7.20549561e+03 7.20254053e+03 7.12957520e+03 7.44999268e+03 7.50017432e+03 6.64258936e+03 6.90251514e+03 6.42336523e+03 8.14834326e+03 9.95965918e+03 1.05271670e+04 9.43228320e+03 1.07046055e+04 1.73072480e+04 2.06521309e+04 5288389. 1.37619525e+06 2346695. -7.84096750e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 67853944. 8939442. 1.73995762e+04 1.11886104e+04 7.30634717e+03 6.97955615e+03 6.51244873e+03 6.28946240e+03 6.09774609e+03 6.33643262e+03 6.31375293e+03 6.07798877e+03 6.12252197e+03 6.06732910e+03 5.88996436e+03 5.87106445e+03 5.81091504e+03 5.73144482e+03 5.30718457e+03 5.16708203e+03 4.01407764e+03 3.62751294e+03 3.55596289e+03 3.60358374e+03 3.58550439e+03 3.38062988e+03 3.34465210e+03 3.48398682e+03 3.42620215e+03 3.31339771e+03 3.27303589e+03 3.22156494e+03 3.17504370e+03 3.13662573e+03 3.08864355e+03 3.06236768e+03 3.01212720e+03 2.89874756e+03 2.85844458e+03 2.97016968e+03 2.93931128e+03 2.80662061e+03 2.77415674e+03 2.74461768e+03 2.71923950e+03 2.66795215e+03 2.62494946e+03 2.59409814e+03 2.51959204e+03 2.46508838e+03 2.45553125e+03 2.41393506e+03 2.47530688e+03 2.45157471e+03 2.33387524e+03 2.24477319e+03 2.18692358e+03 2.28519800e+03 2.26565479e+03 2.15649414e+03 2.08349097e+03 2.06534570e+03 2.06118701e+03 2.00537097e+03 2.02726282e+03 2.00014404e+03 1.86371704e+03 1.80818164e+03 1.86796167e+03 1.91318213e+03 1.82949512e+03 1.75359839e+03 1.72595789e+03 1.68665491e+03 1.65375830e+03 1.62721851e+03 1.61211084e+03 1.57984692e+03 1.52278064e+03 1.49349915e+03 1.46981970e+03 1.43869727e+03 1.45856360e+03 1.41987000e+03 1.34855933e+03 1.32825854e+03 1.29986389e+03 1.30726331e+03 1.28525537e+03 1.22509729e+03 1.19531921e+03 1.14822375e+03 1.10880505e+03 1.13261084e+03 1.10510608e+03 1.01981433e+03 1.01090485e+03 1.04464832e+03 1.04955164e+03 9.94903809e+02 9.43070435e+02 9.07938416e+02 8.83127258e+02 8.67804382e+02 8.43074890e+02 8.20991150e+02 7.95333374e+02 7.95903198e+02 7.73692932e+02 7.29940674e+02 7.12131104e+02 6.70935120e+02 6.66370300e+02 6.84239319e+02 6.49085632e+02 6.14993347e+02 5.79297424e+02 5.55878845e+02 5.68402466e+02 5.52357422e+02 5.17967163e+02 4.86781952e+02 4.68616058e+02 4.62794647e+02 4.44760010e+02 4.42741364e+02 4.28979248e+02 3.98447357e+02 3.79260162e+02 3.64731598e+02 3.56080322e+02 3.41786224e+02 3.22683289e+02 3.04545105e+02 2.91741791e+02 2.79205994e+02 2.57187500e+02 2.50282059e+02 2.53042892e+02 2.36081726e+02 2.16829330e+02 1.99947067e+02 1.88195404e+02 1.87999161e+02 1.77257385e+02 1.61579453e+02 1.47491287e+02 1.37267487e+02 1.32819778e+02 1.23176018e+02 1.13727646e+02 1.03204292e+02 9.75071640e+01 9.40653610e+01 8.41283951e+01 7.63034973e+01 6.97557449e+01 6.25548820e+01 5.54978981e+01 4.98242073e+01 4.46285210e+01 3.93884544e+01 3.50690689e+01 2.96810436e+01 2.57709408e+01 2.33207798e+01 1.88799553e+01 1.51633911e+01 1.26781597e+01 1.02072144e+01 8.25732708e+00 6.34794807e+00 4.73803139e+00 3.64729452e+00 2.82034087e+00 2.30742931e+00 2.14255881e+00 2.32532144e+00 2.83742952e+00 3.65851712e+00 4.81666422e+00 6.22659445e+00 8.17256546e+00 1.07907257e+01 1.31990347e+01 1.55956745e+01 1.81800575e+01 2.18634357e+01 2.71884804e+01 3.12782688e+01 3.47970619e+01 3.89007225e+01 4.37276154e+01 5.04383316e+01 5.64593277e+01 6.36908989e+01 6.94569092e+01 7.43647385e+01 8.21250992e+01 8.95904922e+01 1.00358788e+02 1.08118980e+02 1.13547333e+02 1.22822266e+02 1.32052643e+02 1.41207275e+02 1.46963135e+02 1.61507004e+02 1.82229660e+02 1.88233215e+02 1.93835785e+02 2.00442444e+02 2.10159393e+02 2.34955917e+02 2.50003510e+02 2.54996323e+02 2.60471802e+02 2.72997467e+02 2.95373932e+02 3.09279785e+02 3.31216949e+02 3.46208313e+02 3.52243134e+02 3.57486359e+02 3.71090698e+02 4.09971100e+02 4.25143097e+02 4.29663666e+02 4.39560974e+02 4.53432617e+02 4.96906128e+02 5.18361572e+02 5.05830292e+02 5.21689819e+02 5.70925049e+02 5.90623108e+02 5.79586060e+02 5.97485352e+02 6.49938293e+02 6.74949585e+02 6.71825317e+02 6.75985901e+02 6.97810730e+02 7.58406860e+02 7.72695618e+02 7.67678528e+02 8.04956055e+02 8.26978699e+02 8.43129761e+02 8.68228943e+02 8.89883789e+02 8.92851257e+02 9.39812866e+02 1.00426147e+03 1.00493201e+03 1.03225146e+03 1.06305432e+03 1.06936902e+03 1.09667432e+03 1.12000562e+03 1.14238086e+03 1.14665991e+03 1.16965356e+03 1.22262158e+03 1.25712402e+03 1.32175732e+03 1.30985742e+03 1.29186707e+03 1.36331482e+03 1.40348499e+03 1.47630896e+03 1.48768152e+03 1.47186853e+03 1.48798853e+03 1.51126160e+03 1.57267542e+03 1.60863501e+03 1.66788062e+03 1.69842639e+03 1.69065991e+03 1.71369800e+03 1.68909875e+03 1.77398889e+03 1.91118884e+03 1.91591467e+03 1.89585315e+03 1.87642432e+03 1.88211194e+03 2.01245288e+03 2.10602832e+03 2.09215210e+03 2.04160193e+03 2.07415039e+03 2.16030981e+03 2.18801758e+03 2.27941235e+03 2.30714136e+03 2.28321313e+03 2.30964136e+03 2.34961230e+03 2.47337378e+03 2.51220850e+03 2.42105859e+03 2.44706982e+03 2.61711108e+03 2.64056104e+03 2.54019531e+03 2.62305078e+03 2.80755151e+03 2.83093188e+03 2.79311401e+03 2.75304199e+03 2.78154175e+03 2.97445337e+03 3.02737012e+03 2.98082837e+03 2.94891113e+03 2.96873657e+03 3.09493970e+03 3.15983154e+03 3.17302832e+03 3.13016333e+03 3.25930273e+03 3.42659595e+03 3.37475928e+03 3.45411035e+03 3.46768311e+03 3.43393896e+03 3.50447754e+03 3.54772266e+03 3.59676636e+03 3.62437939e+03 3.60475049e+03 3.58304907e+03 3.73627051e+03 3.98591138e+03 3.82267041e+03 3.71337988e+03 3.88776636e+03 4.04773340e+03 4.17593115e+03 4.15050977e+03 4.06903809e+03 4.19899219e+03 4.25202441e+03 4.17729395e+03 4.16063770e+03 4.37006689e+03 4.43891455e+03 4.37384619e+03 4.39794580e+03 4.31658301e+03 4.54301221e+03 4.85810205e+03 4.77239551e+03 4.65683252e+03 4.62112598e+03 4.58870850e+03 4.89009326e+03 5.12232471e+03 5.02089893e+03 4.87150244e+03 4.90746631e+03 5.00540479e+03 5.03918604e+03 5.27008936e+03 5.23266113e+03 5.14206885e+03 5.24955713e+03 5.26699707e+03 5.51950977e+03 5.53713184e+03 5.40536279e+03 5.48133057e+03 5.53629346e+03 5.61512598e+03 5.54925098e+03 5.59003320e+03 5.88995361e+03 5.93464014e+03 5.87020361e+03 5.72001611e+03 5.81109521e+03 6.20924951e+03 6.21882275e+03 6.07751611e+03 6.01982324e+03 6.02667139e+03 6.15318408e+03 6.23467090e+03 6.33725098e+03 6.22191602e+03 6.38304980e+03 6.70279395e+03 6.48764844e+03 6.66950977e+03 6.79741992e+03 6.68521582e+03 6.70113281e+03 6.71187207e+03 6.80746826e+03 6.83535352e+03 6.81236035e+03 6.87416260e+03 7.09669336e+03 7.20739355e+03 6.87844141e+03 6.85893066e+03 7.08505762e+03 7.30249316e+03 7.56921973e+03 7.42749854e+03 7.16075879e+03 7.44234473e+03 7.60219043e+03 7.53324707e+03 7.52936230e+03 7.55680371e+03 7.54660156e+03 7.57392676e+03 7.78378369e+03 7.64609180e+03 7.76303271e+03 8.19342188e+03 8.09457764e+03 7.99959619e+03 7.86909277e+03 7.93331299e+03 8.38742480e+03 8.32650684e+03 8.24779492e+03 8.08236719e+03 7.90497314e+03 8.21124512e+03 8.55438965e+03 8.87890820e+03 8.58183984e+03 8.32679199e+03 8.48432031e+03 8.60216016e+03 8.96730957e+03 8.93941309e+03 8.70122070e+03 8.72391406e+03 8.74187305e+03 8.86948926e+03 8.79503613e+03 8.94555078e+03 9.37858105e+03 9.24583691e+03 9.19596387e+03 8.98905078e+03 8.97810352e+03 9.55040625e+03 9.60602148e+03 9.37813379e+03 9.20613672e+03 9.18713574e+03 9.42590527e+03 9.54409863e+03 9.90899609e+03 9.92932910e+03 9.62132422e+03 9.46049023e+03 9.63034082e+03 1.01546494e+04 1.01055771e+04 9.88522070e+03 9.87222461e+03 9.85893750e+03 9.90187598e+03 9.87147559e+03 1.01762168e+04 1.01877969e+04 1.00052383e+04 1.04246064e+04 1.05825879e+04 1.04134238e+04 1.03908350e+04 1.03802207e+04 1.04553193e+04 1.02171318e+04 1.01438535e+04 1.07547500e+04 1.08956826e+04 1.03863105e+04 1.02157852e+04 1.07373457e+04 1.12049453e+04 1.11087803e+04 1.07012686e+04 1.05104619e+04 1.09939785e+04 1.12220215e+04 1.10172578e+04 1.10961855e+04 1.08407002e+04 1.04528135e+04 1.09397305e+04 1.16648125e+04 1.17029258e+04 1.10822783e+04 1.07762842e+04 1.14808955e+04 1.19060537e+04 1.15255371e+04 1.11697158e+04 1.10991074e+04 1.12778672e+04 1.14641504e+04 1.19020420e+04 1.19447900e+04 1.15996182e+04 1.14539180e+04 1.15002812e+04 1.20290820e+04 1.17918027e+04 1.14769053e+04 1.20479580e+04 1.20918633e+04 1.19441084e+04 1.17100576e+04 1.16842178e+04 1.23773779e+04 1.20449072e+04 1.16246426e+04 1.19850225e+04 1.22652363e+04 1.23168350e+04 1.21598672e+04 1.25223770e+04 1.26160840e+04 1.22836387e+04 1.19558076e+04 1.18915156e+04 1.27055771e+04 1.25571934e+04 1.22138174e+04 1.23763008e+04 1.23394150e+04 1.25733545e+04 1.25620068e+04 1.26933633e+04 1.26140557e+04 1.23300498e+04 1.28152217e+04 1.29362178e+04 1.27351484e+04 1.27859102e+04 1.27956006e+04 1.26479678e+04 1.23218242e+04 1.22800479e+04 1.29873779e+04 1.35346016e+04 1.28586689e+04 1.22782188e+04 1.28193350e+04 1.34289102e+04 1.33286904e+04 1.28156904e+04 1.25071836e+04 1.31890908e+04 1.32879648e+04 1.28502461e+04 1.33978721e+04 1.33254248e+04 1.26248438e+04 1.28193223e+04 1.35486582e+04 1.36479629e+04 1.29854482e+04 1.26196836e+04 1.33020781e+04 1.38569971e+04 1.35113760e+04 1.29579297e+04 1.27448340e+04 1.34536611e+04 1.36612793e+04 1.32655420e+04 1.33753096e+04 1.34845605e+04 1.32961484e+04 1.32031680e+04 1.37185488e+04 1.35080459e+04 1.30836025e+04 1.35459238e+04 1.36556006e+04 1.37498594e+04 1.33994102e+04 1.31107295e+04 1.37259404e+04 1.34670107e+04 1.31022500e+04 1.35945596e+04 1.40001689e+04 1.44352920e+04 1.41036309e+04 1.46003750e+04 1.35518467e+04 1.68376211e+04 1.33109941e+04 1.58832725e+04 1.75668145e+04 1.24828262e+04 2.50352500e+04 4.09206641e+04 1.50066031e+05 6.80696422e+09 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. 1189767296. 1.22167820e+05 2.86067344e+04 2.49021680e+04 2.15377500e+04 1.62210752e+04 1.64999297e+04 1.38052988e+04 1.44840947e+04 1.35403662e+04 1.34563818e+04 1.47561758e+04 1.21129512e+04 1.54523135e+04 1.83004004e+04 1.98916934e+04 1.48495879e+04 1.57619678e+04 1.35786592e+04 1.40295586e+04 1.43349062e+04 1.34452021e+04 1.36833340e+04 1.37102998e+04 1.32097217e+04 1.32445752e+04 1.36274551e+04 1.37353467e+04 1.37415137e+04 1.33354688e+04 1.30727314e+04 1.33485576e+04 1.34768311e+04 1.33776416e+04 1.31763545e+04 1.30907559e+04 1.34678926e+04 1.35063369e+04 1.32146963e+04 1.31176289e+04 1.31164775e+04 1.35102275e+04 1.35907568e+04 1.29728242e+04 1.28655049e+04 1.31231221e+04 1.31200166e+04 1.33257178e+04 1.32265352e+04 1.29022178e+04 1.30963506e+04 1.31543027e+04 1.30281562e+04 1.30787227e+04 1.28666279e+04 1.29199648e+04 1.30327490e+04 1.28618740e+04 1.28089688e+04 1.27133594e+04 1.27711904e+04 1.30293652e+04 1.29887852e+04 1.28632324e+04 1.26377627e+04 1.24861719e+04 1.28292793e+04 1.28244355e+04 1.24607129e+04 1.25716084e+04 1.26245098e+04 1.25954775e+04 1.27812529e+04 1.26969512e+04 1.23545791e+04 1.22734326e+04 1.26127129e+04 1.27186465e+04 1.23213848e+04 1.20534561e+04 1.21518643e+04 1.23282666e+04 1.25489365e+04 1.24862656e+04 1.20102041e+04 1.20332656e+04 1.23617012e+04 1.23058213e+04 1.21994971e+04 1.18537578e+04 1.17615273e+04 1.21279912e+04 1.21847314e+04 1.18546289e+04 1.18030088e+04 1.18514893e+04 1.18427695e+04 1.18432578e+04 1.17405488e+04 1.17623701e+04 1.17881133e+04 1.18799639e+04 1.18330938e+04 1.13876191e+04 1.13947598e+04 1.16367002e+04 1.15250859e+04 1.13847500e+04 1.13379160e+04 1.13963857e+04 1.15570654e+04 1.14091221e+04 1.11914648e+04 1.13337930e+04 1.14026895e+04 1.10939287e+04 1.10290830e+04 1.11341777e+04 1.11224131e+04 1.10384277e+04 1.08886182e+04 1.08981387e+04 1.09060830e+04 1.10930938e+04 1.10184707e+04 1.05873828e+04 1.06347822e+04 1.08630537e+04 1.08285947e+04 1.06721084e+04 1.04874727e+04 1.03393223e+04 1.05338574e+04 1.07125518e+04 1.05089141e+04 1.02141748e+04 1.02553770e+04 1.04791865e+04 1.04805264e+04 1.04727646e+04 1.01571055e+04 9.84193164e+03 1.00220596e+04 1.00435586e+04 9.97903809e+03 9.99868359e+03 9.84761523e+03 9.93634082e+03 1.01870371e+04 9.94102930e+03 9.48633105e+03 9.55567871e+03 9.74133887e+03 9.71682520e+03 9.77879883e+03 9.57873828e+03 9.38669922e+03 9.40005762e+03 9.60454297e+03 9.43526660e+03 9.03077441e+03 9.14345117e+03 9.37213477e+03 9.24086914e+03 9.07954688e+03 8.97535156e+03 8.94273438e+03 8.99565918e+03 8.94020801e+03 8.88435938e+03 8.96693359e+03 8.76906641e+03 8.76036230e+03 8.86090137e+03 8.73054980e+03 8.52280957e+03 8.47797070e+03 8.57695410e+03 8.65190137e+03 8.49097949e+03 8.28930762e+03 8.14908496e+03 8.29147461e+03 8.57339062e+03 8.54429395e+03 7.98659961e+03 8.00160107e+03 8.26606836e+03 8.10452051e+03 7.95195947e+03 7.85161719e+03 7.75508984e+03 7.89108984e+03 7.91350732e+03 7.70447119e+03 7.61075244e+03 7.53565088e+03 7.59203760e+03 7.71413477e+03 7.59688672e+03 7.41914307e+03 7.36080176e+03 7.43957324e+03 7.34518457e+03 7.21942676e+03 7.17783008e+03 7.19627881e+03 7.03987598e+03 7.20402344e+03 7.20631152e+03 6.80287646e+03 6.78077783e+03 6.93277832e+03 6.93042822e+03 6.86002783e+03 6.58596729e+03 6.63768311e+03 6.81832129e+03 6.69173486e+03 6.62566016e+03 6.39966211e+03 6.27441992e+03 6.43678516e+03 6.51275342e+03 6.38020020e+03 6.26140820e+03 6.26380469e+03 6.16788965e+03 6.24410986e+03 6.15615088e+03 5.95426318e+03 5.84569141e+03 5.87585400e+03 6.00417480e+03 5.88798926e+03 5.74868701e+03 5.70614404e+03 5.76456885e+03 5.74668799e+03 5.61259863e+03 5.54697412e+03 5.49194824e+03 5.50799609e+03 5.42049512e+03 5.45831201e+03 5.32886133e+03 5.21369531e+03 5.30108105e+03 5.11358301e+03 5.11858203e+03 5.17346143e+03 5.02905469e+03 4.94835400e+03 4.94412598e+03 4.93088135e+03 4.84167676e+03 4.71291699e+03 4.83680469e+03 4.92120752e+03 4.63369385e+03 4.54096582e+03 4.58458398e+03 4.54561182e+03 4.58862354e+03 4.49816260e+03 4.33913770e+03 4.34123340e+03 4.38706982e+03 4.35505273e+03 4.26640430e+03 4.16724219e+03 4.15143604e+03 4.12960303e+03 4.03070435e+03 3.99516211e+03 3.92783936e+03 3.88593506e+03 3.91511206e+03 3.88567847e+03 3.84267871e+03 3.72882666e+03 3.64980518e+03 3.71656592e+03 3.74093091e+03 3.56123315e+03 3.55162354e+03 3.52551953e+03 3.39107935e+03 3.42889746e+03 3.39470068e+03 3.29550073e+03 3.32745825e+03 3.27548657e+03 3.21150269e+03 3.25495898e+03 3.14895605e+03 3.05458984e+03 3.03683032e+03 3.03262451e+03 3.02563232e+03 2.90560718e+03 2.85382373e+03 2.87054956e+03 2.85019629e+03 2.80910449e+03 2.75609521e+03 2.67435913e+03 2.68818115e+03 2.73028076e+03 2.60479663e+03 2.52237085e+03 2.47710522e+03 2.51371069e+03 2.51235620e+03 2.38929590e+03 2.34458545e+03 2.33231543e+03 2.30870898e+03 2.26558105e+03 2.24247095e+03 2.20048584e+03 2.13645093e+03 2.14617529e+03 2.15311938e+03 2.06438916e+03 1.95430823e+03 1.95644788e+03 1.96465784e+03 1.93002588e+03 1.90611487e+03 1.86112341e+03 1.80426025e+03 1.81903345e+03 1.81545251e+03 1.72764526e+03 1.68013660e+03 1.65480383e+03 1.67306067e+03 1.63513953e+03 1.54323291e+03 1.50893201e+03 1.50934351e+03 1.50009045e+03 1.46284668e+03 1.43918591e+03 1.39458618e+03 1.36534595e+03 1.34150977e+03 1.28879309e+03 1.26864465e+03 1.23705273e+03 1.22678589e+03 1.21824182e+03 1.16697974e+03 1.12138586e+03 1.10753247e+03 1.10305579e+03 1.10871851e+03 1.07398010e+03 1.00291663e+03 9.74737061e+02 9.69103394e+02 9.46169250e+02 9.13501831e+02 8.88786072e+02 8.71382324e+02 8.55793457e+02 8.22231750e+02 7.82723389e+02 7.78257812e+02 7.72472412e+02 7.53109619e+02 7.19347900e+02 6.82050171e+02 6.68750183e+02 6.44713867e+02 6.22451721e+02 6.24412109e+02 6.02130310e+02 5.62198059e+02 5.46055969e+02 5.35552368e+02 5.28354431e+02 5.10020874e+02 4.82860931e+02 4.61627533e+02 4.45792603e+02 4.28352539e+02 4.07976379e+02 3.98795868e+02 3.83974457e+02 3.71271606e+02 3.55281860e+02 3.26808228e+02 3.17260132e+02 3.07220123e+02 2.93644287e+02 2.86267883e+02 2.64853546e+02 2.47942886e+02 2.44349930e+02 2.32876678e+02 2.16151031e+02 2.03434113e+02 1.90827728e+02 1.79106735e+02 1.69514282e+02 1.60747314e+02 1.50115265e+02 1.42953522e+02 1.34473251e+02 1.22924614e+02 1.12661621e+02 1.03209297e+02 9.74820633e+01 9.11483917e+01 8.27797165e+01 7.34581909e+01 6.63750610e+01 6.12876968e+01 5.60591278e+01 5.12189102e+01 4.43681831e+01 3.81271858e+01 3.38203735e+01 2.93957996e+01 2.52197132e+01 2.19783401e+01 1.83448257e+01 1.46737223e+01 1.20497217e+01 9.59183788e+00 7.48594713e+00 5.71782017e+00 4.18179560e+00 2.97929740e+00 2.14782119e+00 1.67423069e+00 1.52635634e+00 1.69777179e+00 2.23343754e+00 3.12336469e+00 4.35673666e+00 5.76779127e+00 7.61171532e+00 9.83709717e+00 1.22268858e+01 1.52669687e+01 1.84988346e+01 2.17367458e+01 2.56052475e+01 2.98474121e+01 3.50583305e+01 4.00620689e+01 4.41033249e+01 4.95342789e+01 5.52087936e+01 6.12437820e+01 6.81687012e+01 7.57592697e+01 8.33994217e+01 9.01243439e+01 9.74613342e+01 1.05003029e+02 1.13786034e+02 1.26312454e+02 1.35092712e+02 1.40321671e+02 1.50559830e+02 1.60747437e+02 1.70507919e+02 1.84801010e+02 1.97882126e+02 2.05739426e+02 2.15754532e+02 2.27672729e+02 2.40645050e+02 2.57734711e+02 2.68885132e+02 2.81840149e+02 2.96062134e+02 3.06721222e+02 3.24554932e+02 3.33716278e+02 3.50465332e+02 3.77323273e+02 3.83712830e+02 3.94575470e+02 4.15565918e+02 4.27889954e+02 4.44129730e+02 4.79494904e+02 4.98741180e+02 4.91176971e+02 5.10830048e+02 5.37075439e+02 5.51061523e+02 5.83492004e+02 5.99673645e+02 6.02526062e+02 6.30892639e+02 6.52665955e+02 6.81583130e+02 7.12332642e+02 7.18880371e+02 7.43578979e+02 7.58386963e+02 7.60812256e+02 7.94987976e+02 8.37563904e+02 8.55768250e+02 8.84117920e+02 9.04998779e+02 8.91069275e+02 9.32161560e+02 9.95466125e+02 1.01712097e+03 1.01785870e+03 1.01184265e+03 1.05205652e+03 1.11845801e+03 1.13366968e+03 1.14476758e+03 1.19014783e+03 1.19558459e+03 1.22728613e+03 1.26721692e+03 1.25045874e+03 1.29219141e+03 1.36203064e+03 1.39501782e+03 1.40290771e+03 1.38766711e+03 1.42831592e+03 1.49490710e+03 1.54250696e+03 1.56028210e+03 1.55807129e+03 1.57149756e+03 1.62201477e+03 1.68879175e+03 1.74652490e+03 1.74884448e+03 1.74309875e+03 1.78782605e+03 1.81719360e+03 1.85163245e+03 1.90506079e+03 1.92333191e+03 1.96295996e+03 2.02882690e+03 2.02640662e+03 2.04665527e+03 2.10508667e+03 2.14459399e+03 2.18898291e+03 2.19861694e+03 2.18846509e+03 2.24686548e+03 2.32703101e+03 2.38496045e+03 2.44535864e+03 2.41481787e+03 2.38802344e+03 2.47611694e+03 2.50430640e+03 2.56671851e+03 2.63834375e+03 2.61572192e+03 2.63953101e+03 2.67859424e+03 2.73124097e+03 2.82618359e+03 2.90484155e+03 2.89952905e+03 2.90773022e+03 2.92625171e+03 2.90415771e+03 2.99149927e+03 3.08897778e+03 3.16296802e+03 3.18871729e+03 3.14527905e+03 3.15746436e+03 3.25936670e+03 3.33108325e+03 3.37111597e+03 3.38852319e+03 3.40602344e+03 3.40959717e+03 3.52225391e+03 3.64337329e+03 3.62295874e+03 3.57954492e+03 3.65887744e+03 3.72675757e+03 3.78529224e+03 3.85168018e+03 3.86439990e+03 3.93418701e+03 3.92253540e+03 3.93936499e+03 4.08514819e+03 4.09867432e+03 4.09095435e+03 4.23812646e+03 4.17373242e+03 4.15989990e+03 4.35111621e+03 4.35288867e+03 4.20934961e+03 4.75656299e+03 4.77005127e+03 4.11196484e+03 3.85319385e+03 5.92392041e+03 7.69549707e+03 1.26075986e+04 1.41868086e+04 4.13390450e+06 -6.07945850e+06 4571344. 5111982. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -41794592. -19494640. 3.13089668e+04 1.99101875e+04 1.20852715e+04 1.14733477e+04 1.04770205e+04 9.87011621e+03 1.02410430e+04 5.82686865e+03 6.61206006e+03 8.78779199e+03 7.38434033e+03 6.88626074e+03 6.54237598e+03 7.19002197e+03 7.88013135e+03 7.84357275e+03 7.59167090e+03 7.66702930e+03 7.89667139e+03 7.96237354e+03 8.07557520e+03 8.16805811e+03 7.97843506e+03 7.93237305e+03 8.04495898e+03 8.08641748e+03 8.25840234e+03 8.15045459e+03 8.09285498e+03 8.39360938e+03 8.71066113e+03 8.54170801e+03 8.16548145e+03 8.26622852e+03 8.63881836e+03 8.79587793e+03 8.60020312e+03 8.44403516e+03 8.57231836e+03 8.96511621e+03 9.17810742e+03 8.99308789e+03 8.63929590e+03 8.73204102e+03 9.17767773e+03 9.15712109e+03 9.26137402e+03 9.18082031e+03 8.89838965e+03 9.11591992e+03 9.47213477e+03 9.32644727e+03 9.22580957e+03 9.56153613e+03 9.65417480e+03 9.55002637e+03 9.44657617e+03 9.28872461e+03 9.58219629e+03 1.00020312e+04 9.83801758e+03 9.62498926e+03 9.58146973e+03 9.58923242e+03 1.01110918e+04 1.03775410e+04 1.00569678e+04 9.91815918e+03 9.90154395e+03 9.85494629e+03 1.01524600e+04 1.05556416e+04 1.02075947e+04 1.00544893e+04 1.04033086e+04 1.03773320e+04 1.02212334e+04 1.03191982e+04 1.04989150e+04 1.07112666e+04 1.07252061e+04 1.07258672e+04 1.04098096e+04 1.03382295e+04 1.09116934e+04 1.11871934e+04 1.06716934e+04 1.03950166e+04 1.07092129e+04 1.10130986e+04 1.12327891e+04 1.13620479e+04 1.09492354e+04 1.08267480e+04 1.11436924e+04 1.11925342e+04 1.13240020e+04 1.12220713e+04 1.09852920e+04 1.11392803e+04 1.14376250e+04 1.15055684e+04 1.14561973e+04 1.14906953e+04 1.14959824e+04 1.15761025e+04 1.16677393e+04 1.13275059e+04 1.13173984e+04 1.19981748e+04 1.20345879e+04 1.14707725e+04 1.13420996e+04 1.15429834e+04 1.21142070e+04 1.24648945e+04 1.20261357e+04 1.15798223e+04 1.16255801e+04 1.18608994e+04 1.20547949e+04 1.21580088e+04 1.21082021e+04 1.20944336e+04 1.20931787e+04 1.21350625e+04 1.22392070e+04 1.20433799e+04 1.22164961e+04 1.26439844e+04 1.24376270e+04 1.23020850e+04 1.22373916e+04 1.20813545e+04 1.25473467e+04 1.29381924e+04 1.23697646e+04 1.21073613e+04 1.24078906e+04 1.28682305e+04 1.30684346e+04 1.27347500e+04 1.24137119e+04 1.24080283e+04 1.25806328e+04 1.28572334e+04 1.30556992e+04 1.26005332e+04 1.23176904e+04 1.27827520e+04 1.32297100e+04 1.30804961e+04 1.28406328e+04 1.28397334e+04 1.28382988e+04 1.30733525e+04 1.31693535e+04 1.27317881e+04 1.27429336e+04 1.31806182e+04 1.32401592e+04 1.30686650e+04 1.28530527e+04 1.29990039e+04 1.32163330e+04 1.32621455e+04 1.33497666e+04 1.30782598e+04 1.31195166e+04 1.34000537e+04 1.32649121e+04 1.32280508e+04 1.31071846e+04 1.31154473e+04 1.34348984e+04 1.37731074e+04 1.36188008e+04 1.29944863e+04 1.29307881e+04 1.35271768e+04 1.39048467e+04 1.36418594e+04 1.31571426e+04 1.30303721e+04 1.33543350e+04 1.36503242e+04 1.37500762e+04 1.33937139e+04 1.31549502e+04 1.33947236e+04 1.36906826e+04 1.37903125e+04 1.36026396e+04 1.34128281e+04 1.34975596e+04 1.36128662e+04 1.36257568e+04 1.36437422e+04 1.35998594e+04 1.35946787e+04 1.35285273e+04 1.33190781e+04 1.32732393e+04 1.37683271e+04 1.42790068e+04 1.41123154e+04 1.35524893e+04 1.30865947e+04 1.32512432e+04 1.40351074e+04 1.44284551e+04 1.39987979e+04 1.33977227e+04 1.31338242e+04 1.35172041e+04 1.40014590e+04 1.40499961e+04 1.39082676e+04 1.36385264e+04 1.36246162e+04 1.36414277e+04 1.32608555e+04 1.33341182e+04 1.37062979e+04 1.37507266e+04 1.42351494e+04 1.39861670e+04 1.30214873e+04 1.33013027e+04 1.38452578e+04 1.38709170e+04 1.38195010e+04 1.36599844e+04 1.40105068e+04 1.40566572e+04 1.34243203e+04 1.29788369e+04 1.32726074e+04 1.39689531e+04 1.43743027e+04 1.41507979e+04 1.33834355e+04 1.29532363e+04 1.32527578e+04 1.38947686e+04 1.42710596e+04 1.40507725e+04 1.32546875e+04 1.32034053e+04 1.40301455e+04 1.39622900e+04 1.33235098e+04 1.33207627e+04 1.34512061e+04 1.34497441e+04 1.39587812e+04 1.36294424e+04 1.30927334e+04 1.34268311e+04 1.31874893e+04 1.35031943e+04 1.38517031e+04 1.31474990e+04 1.33412109e+04 1.37305723e+04 1.34269697e+04 1.34487188e+04 1.33515566e+04 1.33304531e+04 1.35193799e+04 1.33601953e+04 1.29281992e+04 1.29222373e+04 1.36074375e+04 1.39719375e+04 1.35687295e+04 1.29759600e+04 1.26667207e+04 1.28833311e+04 1.34466670e+04 1.38235820e+04 1.34369043e+04 1.27575986e+04 1.28763477e+04 1.32733076e+04 1.30586807e+04 1.29423965e+04 1.29727158e+04 1.29475449e+04 1.29796709e+04 1.34053818e+04 1.30340820e+04 1.25584307e+04 1.28782998e+04 1.24957285e+04 1.29315439e+04 1.32238145e+04 1.27087559e+04 1.31871172e+04 1.29360254e+04 1.22418613e+04 1.25827842e+04 1.24280645e+04 1.26044697e+04 1.34241572e+04 1.27163760e+04 1.19740059e+04 1.22191611e+04 1.27475322e+04 1.32131689e+04 1.29083057e+04 1.22052109e+04 1.18790107e+04 1.20334004e+04 1.24948379e+04 1.29066924e+04 1.27364004e+04 1.20974561e+04 1.19121172e+04 1.22430312e+04 1.23578301e+04 1.20779482e+04 1.20335596e+04 1.20297129e+04 1.19808203e+04 1.24292490e+04 1.23965176e+04 1.17079912e+04 1.16302549e+04 1.18103145e+04 1.18338818e+04 1.19004932e+04 1.18199756e+04 1.21099717e+04 1.17946465e+04 1.13095361e+04 1.16471582e+04 1.13181602e+04 1.15398203e+04 1.23861650e+04 1.16188418e+04 1.07949092e+04 1.11437520e+04 1.16589717e+04 1.18778018e+04 1.19103447e+04 1.11668203e+04 1.06493418e+04 1.09130391e+04 1.14953193e+04 1.18304209e+04 1.14830303e+04 1.07626787e+04 1.06414385e+04 1.09668955e+04 1.11151553e+04 1.13864941e+04 1.13150381e+04 1.06117979e+04 1.05428906e+04 1.09043027e+04 1.10195508e+04 1.06868242e+04 1.05197979e+04 1.05837764e+04 1.04650107e+04 1.08101416e+04 1.08365469e+04 1.03360068e+04 1.02733096e+04 1.02815234e+04 1.02518926e+04 1.03638271e+04 1.02370791e+04 1.03953906e+04 1.04859971e+04 1.01059922e+04 9.88924414e+03 9.64685840e+03 1.00067842e+04 1.04678936e+04 1.02531055e+04 9.70029980e+03 9.39132812e+03 9.67822070e+03 1.01610762e+04 9.82505664e+03 9.20280664e+03 9.46849512e+03 9.69126270e+03 9.77932422e+03 9.97642383e+03 9.78890918e+03 9.17416602e+03 8.94763379e+03 9.18863867e+03 9.46793848e+03 9.39786426e+03 9.19419336e+03 9.12696094e+03 9.05894336e+03 9.23054688e+03 9.06353809e+03 8.76937793e+03 8.78828516e+03 8.71078809e+03 8.91487891e+03 9.10312500e+03 8.75027832e+03 8.74272168e+03 8.74329492e+03 8.63722168e+03 8.40486621e+03 8.13849805e+03 8.50853125e+03 8.88722070e+03 8.53995020e+03 8.05578906e+03 8.07584473e+03 8.45901562e+03 8.51492285e+03 8.27020020e+03 8.13054443e+03 7.78902441e+03 7.72763770e+03 8.10559033e+03 8.07714209e+03 7.83284033e+03 7.58965674e+03 7.46165283e+03 7.77035791e+03 8.08604395e+03 7.64588428e+03 7.39431738e+03 7.46973291e+03 7.43200439e+03 7.62860889e+03 7.63150635e+03 7.14620898e+03 7.01271484e+03 7.21376270e+03 7.16357715e+03 7.21011670e+03 7.11756885e+03 7.38195117e+03 7.18552197e+03 6.86604980e+03 6.69686133e+03 6.45885010e+03 6.89817627e+03 7.36833447e+03 7.07725977e+03 6.30368555e+03 6.95280176e+03 9.60984863e+03 1.06312451e+04 2.24505801e+04 1.37619525e+06 2346695. -7.84096750e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 67853944. 8.85591953e+04 1.25663730e+04 6.83325684e+03 7.36331738e+03 6.63144238e+03 6.45533887e+03 6.27118359e+03 6.07154004e+03 6.32566846e+03 6.33826758e+03 6.07229004e+03 6.09551074e+03 6.04085010e+03 5.90392090e+03 5.87338623e+03 5.82317871e+03 5.70581445e+03 4.09209302e+03 4.45797363e+03 3.96744507e+03 3.62545850e+03 3.55005347e+03 3.58781128e+03 3.58278735e+03 3.38951294e+03 3.35521826e+03 3.46561743e+03 3.44925635e+03 3.31984863e+03 3.26466260e+03 3.21552539e+03 3.17317773e+03 3.14143018e+03 3.09469702e+03 3.05707202e+03 3.01477686e+03 2.91196191e+03 2.87462744e+03 2.96862183e+03 2.94174976e+03 2.81230054e+03 2.77862207e+03 2.75120532e+03 2.71409839e+03 2.66685791e+03 2.62234229e+03 2.59610107e+03 2.53118530e+03 2.47338086e+03 2.45801611e+03 2.41915405e+03 2.46964331e+03 2.45344141e+03 2.33588916e+03 2.23981787e+03 2.19051978e+03 2.28676782e+03 2.27313184e+03 2.15818091e+03 2.08450562e+03 2.06347241e+03 2.05774170e+03 2.00461133e+03 2.02606519e+03 2.00466162e+03 1.86348254e+03 1.80712195e+03 1.86932971e+03 1.91388794e+03 1.82982971e+03 1.75290186e+03 1.72664136e+03 1.68440942e+03 1.65490283e+03 1.62984839e+03 1.61098816e+03 1.57684302e+03 1.52972974e+03 1.49971326e+03 1.47329346e+03 1.43804089e+03 1.45819714e+03 1.42245837e+03 1.35028345e+03 1.32955945e+03 1.29385254e+03 1.30594629e+03 1.28744067e+03 1.22547925e+03 1.19611707e+03 1.15150952e+03 1.10850684e+03 1.13076282e+03 1.10240015e+03 1.01925201e+03 1.01056769e+03 1.04366858e+03 1.04979797e+03 9.95669922e+02 9.42292358e+02 9.06460815e+02 8.83102478e+02 8.68957153e+02 8.42372131e+02 8.21204773e+02 7.96293640e+02 7.94659058e+02 7.72587524e+02 7.29444519e+02 7.10049927e+02 6.69742188e+02 6.66175598e+02 6.85596008e+02 6.50507996e+02 6.14841614e+02 5.79148926e+02 5.55002258e+02 5.68800659e+02 5.53837036e+02 5.19056030e+02 4.86642395e+02 4.68563995e+02 4.62742767e+02 4.44409668e+02 4.42692841e+02 4.28926117e+02 3.98354156e+02 3.78735077e+02 3.63403748e+02 3.54726654e+02 3.41613068e+02 3.22338715e+02 3.02949066e+02 2.90413208e+02 2.78455933e+02 2.56538513e+02 2.49006012e+02 2.52139557e+02 2.35625671e+02 2.16608826e+02 1.99727036e+02 1.87725784e+02 1.87650055e+02 1.76954056e+02 1.61296967e+02 1.47300446e+02 1.36818863e+02 1.32228622e+02 1.22845993e+02 1.13508812e+02 1.02724121e+02 9.67904282e+01 9.32370224e+01 8.33257599e+01 7.54087753e+01 6.89555054e+01 6.20747147e+01 5.49651184e+01 4.90257149e+01 4.37057343e+01 3.84046974e+01 3.39954262e+01 2.86731644e+01 2.49161034e+01 2.25828400e+01 1.82172489e+01 1.45200167e+01 1.20775652e+01 9.60453606e+00 7.63579035e+00 5.73205805e+00 4.12762737e+00 3.04212689e+00 2.20023727e+00 1.68873310e+00 1.52623963e+00 1.68582797e+00 2.17021537e+00 2.99735999e+00 4.18970203e+00 5.62431240e+00 7.59014463e+00 1.01954823e+01 1.25728693e+01 1.49959002e+01 1.76533089e+01 2.13752880e+01 2.65963726e+01 3.06360378e+01 3.42272987e+01 3.83003502e+01 4.31937981e+01 4.98951492e+01 5.59186554e+01 6.32236824e+01 6.89245071e+01 7.37270050e+01 8.15632401e+01 8.89875259e+01 9.99258652e+01 1.07573692e+02 1.12691948e+02 1.21901443e+02 1.31249207e+02 1.40625717e+02 1.46403366e+02 1.61097214e+02 1.81980026e+02 1.87878403e+02 1.93450653e+02 2.00002533e+02 2.09744904e+02 2.34832718e+02 2.49783096e+02 2.54858398e+02 2.59796021e+02 2.72701385e+02 2.95533356e+02 3.08905457e+02 3.31254944e+02 3.45968964e+02 3.51933716e+02 3.57595306e+02 3.71031433e+02 4.09260010e+02 4.24110565e+02 4.28868622e+02 4.39687012e+02 4.53625336e+02 4.96415527e+02 5.17608582e+02 5.05260345e+02 5.21198120e+02 5.70801514e+02 5.91055725e+02 5.78666016e+02 5.96538025e+02 6.50074768e+02 6.74873718e+02 6.70929382e+02 6.75686157e+02 6.98523682e+02 7.58795593e+02 7.73694031e+02 7.67062500e+02 8.03158630e+02 8.26278503e+02 8.44583130e+02 8.68524353e+02 8.92017334e+02 8.93784973e+02 9.41677612e+02 1.00411829e+03 1.00238501e+03 1.03654407e+03 1.06375220e+03 1.06863049e+03 1.09664893e+03 1.11783276e+03 1.14192407e+03 1.14529285e+03 1.16666394e+03 1.22330359e+03 1.25735962e+03 1.32053137e+03 1.30927185e+03 1.29275244e+03 1.36239685e+03 1.40652161e+03 1.47381860e+03 1.49416589e+03 1.47236255e+03 1.48802307e+03 1.50826196e+03 1.57506531e+03 1.61068420e+03 1.67453760e+03 1.69555774e+03 1.69043933e+03 1.71473193e+03 1.69326123e+03 1.77525208e+03 1.91025195e+03 1.91693347e+03 1.89773181e+03 1.87439270e+03 1.88447693e+03 2.01231519e+03 2.10364307e+03 2.08972510e+03 2.03886658e+03 2.07296484e+03 2.16900269e+03 2.18940771e+03 2.28148706e+03 2.31169653e+03 2.27947827e+03 2.31227173e+03 2.34889355e+03 2.47517651e+03 2.52038696e+03 2.41961255e+03 2.45405835e+03 2.62908423e+03 2.64125317e+03 2.54228442e+03 2.62712061e+03 2.80656885e+03 2.83506299e+03 2.80552417e+03 2.76366846e+03 2.78900830e+03 2.98167358e+03 3.02903589e+03 2.98968628e+03 2.95864087e+03 2.96234351e+03 3.09716650e+03 3.16325537e+03 3.18282959e+03 3.12698975e+03 3.25689209e+03 3.43214746e+03 3.36738379e+03 3.45177368e+03 3.46865454e+03 3.43888110e+03 3.51448608e+03 3.55650098e+03 3.59835620e+03 3.62097949e+03 3.61533350e+03 3.58244775e+03 3.74561792e+03 3.98597876e+03 3.82865649e+03 3.71597192e+03 3.89795752e+03 4.05388892e+03 4.18770312e+03 4.13295166e+03 4.07428442e+03 4.21326514e+03 4.25987012e+03 4.17839111e+03 4.15903223e+03 4.37803125e+03 4.42380566e+03 4.37706396e+03 4.39794434e+03 4.30952393e+03 4.51266797e+03 4.86302588e+03 4.77099170e+03 4.67390869e+03 4.62944775e+03 4.58007373e+03 4.89853076e+03 5.12942188e+03 5.00058887e+03 4.87652393e+03 4.89157080e+03 5.01796533e+03 5.06703516e+03 5.28837695e+03 5.25622705e+03 5.14951709e+03 5.24097363e+03 5.28562012e+03 5.53317920e+03 5.55301807e+03 5.41465869e+03 5.48431689e+03 5.53181348e+03 5.64344531e+03 5.53575830e+03 5.60255664e+03 5.88699951e+03 5.92184424e+03 5.89642188e+03 5.74956445e+03 5.81953125e+03 6.24532129e+03 6.18886328e+03 6.09620361e+03 6.02342236e+03 6.01589697e+03 6.16921387e+03 6.26010791e+03 6.36090820e+03 6.22798340e+03 6.38928613e+03 6.70808740e+03 6.48134570e+03 6.71063867e+03 6.81885205e+03 6.69278418e+03 6.72450000e+03 6.70770947e+03 6.79074951e+03 6.85845605e+03 6.81792334e+03 6.88854395e+03 7.13480615e+03 7.18135303e+03 6.88191064e+03 6.86168945e+03 7.11439893e+03 7.31906885e+03 7.64675342e+03 7.46537842e+03 7.18239893e+03 7.45799902e+03 7.64970459e+03 7.57438477e+03 7.50452637e+03 7.57320215e+03 7.55630078e+03 7.60276807e+03 7.82281250e+03 7.66670361e+03 7.79424316e+03 8.18206592e+03 8.07354004e+03 7.99807227e+03 7.88805664e+03 7.95101172e+03 8.40062402e+03 8.37830957e+03 8.26857324e+03 8.07199365e+03 7.93066992e+03 8.22627734e+03 8.53467969e+03 8.85828516e+03 8.61734570e+03 8.35481445e+03 8.49320215e+03 8.57231348e+03 8.98314355e+03 8.92480176e+03 8.71477832e+03 8.73617773e+03 8.77450586e+03 8.87884473e+03 8.77411328e+03 8.96997266e+03 9.38616992e+03 9.27618750e+03 9.15889844e+03 9.05699414e+03 9.04014551e+03 9.57482324e+03 9.61456445e+03 9.34863574e+03 9.18174023e+03 9.16765332e+03 9.48903516e+03 9.51736426e+03 9.90678027e+03 9.97550000e+03 9.65448145e+03 9.45686621e+03 9.66888867e+03 1.01406602e+04 1.00792578e+04 9.86576562e+03 9.85186426e+03 9.86657715e+03 9.89162695e+03 9.86285547e+03 1.01643906e+04 1.01931836e+04 1.00387207e+04 1.04291367e+04 1.05748545e+04 1.04261074e+04 1.03740312e+04 1.03978154e+04 1.04339688e+04 1.02200908e+04 1.01823223e+04 1.07326982e+04 1.08920820e+04 1.04372568e+04 1.02146299e+04 1.07421143e+04 1.12223496e+04 1.11076270e+04 1.07210391e+04 1.05169316e+04 1.10098652e+04 1.12037021e+04 1.10139082e+04 1.11333604e+04 1.08307676e+04 1.04692266e+04 1.09581289e+04 1.16769502e+04 1.16903525e+04 1.11208477e+04 1.07715508e+04 1.14860723e+04 1.19072881e+04 1.15122363e+04 1.11891406e+04 1.11005527e+04 1.12786768e+04 1.14752920e+04 1.19016650e+04 1.19635879e+04 1.16088467e+04 1.14923203e+04 1.15283418e+04 1.20459844e+04 1.18223018e+04 1.14821816e+04 1.20536641e+04 1.20962832e+04 1.19284756e+04 1.17540547e+04 1.17145537e+04 1.23774902e+04 1.20694795e+04 1.16231465e+04 1.19990645e+04 1.22964580e+04 1.23163125e+04 1.21636445e+04 1.25500332e+04 1.26457100e+04 1.22920801e+04 1.19366680e+04 1.19213965e+04 1.27051016e+04 1.25766738e+04 1.22133389e+04 1.23700176e+04 1.23325371e+04 1.25770479e+04 1.25923203e+04 1.27027598e+04 1.26066133e+04 1.23827842e+04 1.28201270e+04 1.29224189e+04 1.27295107e+04 1.28171133e+04 1.28213613e+04 1.26379082e+04 1.23258330e+04 1.22792246e+04 1.29861455e+04 1.35807607e+04 1.28875068e+04 1.23086904e+04 1.28550605e+04 1.34260059e+04 1.33239551e+04 1.28410215e+04 1.25583662e+04 1.32052959e+04 1.32690576e+04 1.28361621e+04 1.34208965e+04 1.33465098e+04 1.26565557e+04 1.28345439e+04 1.35397686e+04 1.36625654e+04 1.30073633e+04 1.26246396e+04 1.33054814e+04 1.38699033e+04 1.35146514e+04 1.29506826e+04 1.27714863e+04 1.34668955e+04 1.36733389e+04 1.32961484e+04 1.33935400e+04 1.34907734e+04 1.33121484e+04 1.32090859e+04 1.37351895e+04 1.35296143e+04 1.30995889e+04 1.35551650e+04 1.36444863e+04 1.37478975e+04 1.34637344e+04 1.31453867e+04 1.36823740e+04 1.34197559e+04 1.31207979e+04 1.36935410e+04 1.39548867e+04 1.41337539e+04 1.36840615e+04 1.44653477e+04 1.34346816e+04 1.61815156e+04 1.34801777e+04 1.89224473e+04 2.02970547e+04 1.88706758e+04 3.33225117e+04 4.09919609e+04 1.50066031e+05 6.80696422e+09 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. 1.34839040e+10 2.14693484e+05 4.61029141e+04 2.89207109e+04 2.48802930e+04 1.92067168e+04 1.82653184e+04 1.38361084e+04 1.41163154e+04 1.33986533e+04 1.35818447e+04 1.48644707e+04 1.21297705e+04 1.59077344e+04 1.89423164e+04 2.05346348e+04 1.74009570e+04 1.72516465e+04 1.35518340e+04 1.39071035e+04 1.44604365e+04 1.39088613e+04 1.38974688e+04 1.35475908e+04 1.31352178e+04 1.34189229e+04 1.38363633e+04 1.36062266e+04 1.35377275e+04 1.33910938e+04 1.33063047e+04 1.36896982e+04 1.34011006e+04 1.29897451e+04 1.31624443e+04 1.31497031e+04 1.33875410e+04 1.35117393e+04 1.30764043e+04 1.30872715e+04 1.34907207e+04 1.40059248e+04 1.36754668e+04 1.27365518e+04 1.26493555e+04 1.30018486e+04 1.32533047e+04 1.34682607e+04 1.32853701e+04 1.28764531e+04 1.31820400e+04 1.33255615e+04 1.28862568e+04 1.27640479e+04 1.27639346e+04 1.31775625e+04 1.35592529e+04 1.28907510e+04 1.24269893e+04 1.27083223e+04 1.30236709e+04 1.32151689e+04 1.29134053e+04 1.26135146e+04 1.24962363e+04 1.27336396e+04 1.33017002e+04 1.28973770e+04 1.21989688e+04 1.24783545e+04 1.27401143e+04 1.26791875e+04 1.27578730e+04 1.25385811e+04 1.22260381e+04 1.24740938e+04 1.27701709e+04 1.25015615e+04 1.22450020e+04 1.21175918e+04 1.21780469e+04 1.25296572e+04 1.27639570e+04 1.23717178e+04 1.19110674e+04 1.21209170e+04 1.24233457e+04 1.21386328e+04 1.19542559e+04 1.19540303e+04 1.20910322e+04 1.24788164e+04 1.22240850e+04 1.16731494e+04 1.15959121e+04 1.16893574e+04 1.19212002e+04 1.20029180e+04 1.17665264e+04 1.17013916e+04 1.19318369e+04 1.22301885e+04 1.19205488e+04 1.12480781e+04 1.12540371e+04 1.16469492e+04 1.16544492e+04 1.15579385e+04 1.13709229e+04 1.12742510e+04 1.15630117e+04 1.15287803e+04 1.11727822e+04 1.12098848e+04 1.12481318e+04 1.11599971e+04 1.13651777e+04 1.12838828e+04 1.09719609e+04 1.09381494e+04 1.09033965e+04 1.08916191e+04 1.11044121e+04 1.13067910e+04 1.09316523e+04 1.04849062e+04 1.07613438e+04 1.10461055e+04 1.07665684e+04 1.05017930e+04 1.04271816e+04 1.04396133e+04 1.07252227e+04 1.07535537e+04 1.03303916e+04 1.02108262e+04 1.03243574e+04 1.04762676e+04 1.04723037e+04 1.03072520e+04 1.01651973e+04 1.01893223e+04 1.03222217e+04 1.00074365e+04 9.76662793e+03 9.88271484e+03 9.94508887e+03 1.00438125e+04 1.01740605e+04 9.93080566e+03 9.52157129e+03 9.68310059e+03 9.92586523e+03 9.70881055e+03 9.60843359e+03 9.37060449e+03 9.31835547e+03 9.72043164e+03 9.74462793e+03 9.26715918e+03 9.05466797e+03 9.30784961e+03 9.52887988e+03 9.17452051e+03 8.90794824e+03 8.94603320e+03 9.20678809e+03 9.30635156e+03 8.94573926e+03 8.74410449e+03 8.79987988e+03 8.73074805e+03 8.81777930e+03 8.85077930e+03 8.64355762e+03 8.66492871e+03 8.72646094e+03 8.67712305e+03 8.51534863e+03 8.33520996e+03 8.28914160e+03 8.24878223e+03 8.32342383e+03 8.68896387e+03 8.54073535e+03 7.94910645e+03 8.10006934e+03 8.33240137e+03 8.01199316e+03 7.76296436e+03 7.78196582e+03 7.84482812e+03 8.12870508e+03 7.98417090e+03 7.58923389e+03 7.53301123e+03 7.54318652e+03 7.66491895e+03 7.67105615e+03 7.51278662e+03 7.40347412e+03 7.57755957e+03 7.60678711e+03 7.28907080e+03 7.13099512e+03 7.14758691e+03 7.11968018e+03 7.15528076e+03 7.27342822e+03 7.26089551e+03 6.85208691e+03 6.84264062e+03 6.97058301e+03 6.86118506e+03 6.80243018e+03 6.64246240e+03 6.69860498e+03 6.83801562e+03 6.75055713e+03 6.52899707e+03 6.41280713e+03 6.39363184e+03 6.38255127e+03 6.43715137e+03 6.30011719e+03 6.28325098e+03 6.30206055e+03 6.28030908e+03 6.31942188e+03 6.04092920e+03 5.89553760e+03 5.98713867e+03 5.94390137e+03 6.01695996e+03 5.93147461e+03 5.62462549e+03 5.74949658e+03 5.88955664e+03 5.65582715e+03 5.53847412e+03 5.56608594e+03 5.56177734e+03 5.52683057e+03 5.37073291e+03 5.48665527e+03 5.43499756e+03 5.23528174e+03 5.27016650e+03 5.12176660e+03 5.16062793e+03 5.23700488e+03 4.98673926e+03 4.97331250e+03 5.03422900e+03 4.92778125e+03 4.77694092e+03 4.71997412e+03 4.88920508e+03 4.94117041e+03 4.61390039e+03 4.53235400e+03 4.65681885e+03 4.58841699e+03 4.57893848e+03 4.39562842e+03 4.32465381e+03 4.40310205e+03 4.45028906e+03 4.35116553e+03 4.21038916e+03 4.15860938e+03 4.17039551e+03 4.20174756e+03 4.02375610e+03 3.93177173e+03 3.91819385e+03 3.86375122e+03 3.92671387e+03 3.98912622e+03 3.87123120e+03 3.68702319e+03 3.62895386e+03 3.74556958e+03 3.76629614e+03 3.53796973e+03 3.55100952e+03 3.62501025e+03 3.42761279e+03 3.39347461e+03 3.32777612e+03 3.31451318e+03 3.40729346e+03 3.30652637e+03 3.16843652e+03 3.23046558e+03 3.18556543e+03 3.05367822e+03 3.06227026e+03 3.05736450e+03 3.01346094e+03 2.89125806e+03 2.83304785e+03 2.89073779e+03 2.89447827e+03 2.80997461e+03 2.71342139e+03 2.66903125e+03 2.71512720e+03 2.70991064e+03 2.56249121e+03 2.52047339e+03 2.50912183e+03 2.52945947e+03 2.49517773e+03 2.37211060e+03 2.34483228e+03 2.37943726e+03 2.34932520e+03 2.25776831e+03 2.24408203e+03 2.21892969e+03 2.14273364e+03 2.18104932e+03 2.17394556e+03 2.04346289e+03 1.94719019e+03 1.96274854e+03 1.96920862e+03 1.94026648e+03 1.90246545e+03 1.83810583e+03 1.80398083e+03 1.83275781e+03 1.81300708e+03 1.70622668e+03 1.67013318e+03 1.68270862e+03 1.69380151e+03 1.62540576e+03 1.54200964e+03 1.53844678e+03 1.51774194e+03 1.48870178e+03 1.45529150e+03 1.43877356e+03 1.40111426e+03 1.34996448e+03 1.34102698e+03 1.32602075e+03 1.28816650e+03 1.23004480e+03 1.20731372e+03 1.20890991e+03 1.18227966e+03 1.14042969e+03 1.10881140e+03 1.09191614e+03 1.09706384e+03 1.07207373e+03 1.00468866e+03 9.90851501e+02 9.78812866e+02 9.51414612e+02 9.17833252e+02 8.83651611e+02 8.79199524e+02 8.61176636e+02 8.15885071e+02 7.75551636e+02 7.79897339e+02 7.80312561e+02 7.47124329e+02 7.23901001e+02 6.96738647e+02 6.81759521e+02 6.45083191e+02 6.05350281e+02 6.08461914e+02 6.02061279e+02 5.80635986e+02 5.59864929e+02 5.25416016e+02 5.12188782e+02 5.03968536e+02 4.93463715e+02 4.77878937e+02 4.48010742e+02 4.24661652e+02 4.03110962e+02 3.98547791e+02 3.93488098e+02 3.73369690e+02 3.53562469e+02 3.24018341e+02 3.16715515e+02 3.14843781e+02 2.93821960e+02 2.83112701e+02 2.65489075e+02 2.50721436e+02 2.45125488e+02 2.27218872e+02 2.12985870e+02 2.08394928e+02 1.98330322e+02 1.80479065e+02 1.65298630e+02 1.58008286e+02 1.50315063e+02 1.44455276e+02 1.37672073e+02 1.23672539e+02 1.11967422e+02 1.02324799e+02 9.70270844e+01 9.24481277e+01 8.29836044e+01 7.36525497e+01 6.56688461e+01 6.01463470e+01 5.60161400e+01 5.11683388e+01 4.47740746e+01 3.88882484e+01 3.45220795e+01 2.94673843e+01 2.45712986e+01 2.13823738e+01 1.82530289e+01 1.51272392e+01 1.25401812e+01 9.58872414e+00 7.24570417e+00 5.60020494e+00 4.22345829e+00 3.06150937e+00 2.19390893e+00 1.70449662e+00 1.55165911e+00 1.73662651e+00 2.27444863e+00 3.12593675e+00 4.27665710e+00 5.70241451e+00 7.64546204e+00 9.89454079e+00 1.20850286e+01 1.50894222e+01 1.86638317e+01 2.21930580e+01 2.58556271e+01 2.94856358e+01 3.43909416e+01 4.00976982e+01 4.52330971e+01 5.10013466e+01 5.48699837e+01 6.01228256e+01 6.83410110e+01 7.69627609e+01 8.53026276e+01 9.10011673e+01 9.74706345e+01 1.03486168e+02 1.13899483e+02 1.27555237e+02 1.33770676e+02 1.41765579e+02 1.52181900e+02 1.60733505e+02 1.69419632e+02 1.81669495e+02 1.96289581e+02 2.09129990e+02 2.21412796e+02 2.28621246e+02 2.35785919e+02 2.52856918e+02 2.69267487e+02 2.84298462e+02 3.01035004e+02 3.08460144e+02 3.22391693e+02 3.34256409e+02 3.52941010e+02 3.81000824e+02 3.85504150e+02 3.97641754e+02 4.12721283e+02 4.17809906e+02 4.43790497e+02 4.85517242e+02 4.97803528e+02 4.96298218e+02 5.20583984e+02 5.34747375e+02 5.38834351e+02 5.72054688e+02 6.02185425e+02 6.20599548e+02 6.44141113e+02 6.43228943e+02 6.63373169e+02 7.04712585e+02 7.32631897e+02 7.73606323e+02 7.73910950e+02 7.57128052e+02 7.77169678e+02 8.31554321e+02 8.69355591e+02 8.89322815e+02 9.01990356e+02 8.88721191e+02 9.33080505e+02 1.00108502e+03 1.00460187e+03 1.01909210e+03 1.02731128e+03 1.05953577e+03 1.11707886e+03 1.10608911e+03 1.13234521e+03 1.21696423e+03 1.24126636e+03 1.24211597e+03 1.23967383e+03 1.22512195e+03 1.28894238e+03 1.37476343e+03 1.43413293e+03 1.42958716e+03 1.38653247e+03 1.40101587e+03 1.48262915e+03 1.54775635e+03 1.55538403e+03 1.57701306e+03 1.57349658e+03 1.61006726e+03 1.68516772e+03 1.73718628e+03 1.76797083e+03 1.76939771e+03 1.81844788e+03 1.82688391e+03 1.80491577e+03 1.87904688e+03 1.94850732e+03 1.99050867e+03 2.06198584e+03 2.01512891e+03 2.00229297e+03 2.09723682e+03 2.16186816e+03 2.24718335e+03 2.24126782e+03 2.18331689e+03 2.20451123e+03 2.30927075e+03 2.42374976e+03 2.47807935e+03 2.43740430e+03 2.40506689e+03 2.45183765e+03 2.48917188e+03 2.54141724e+03 2.63915796e+03 2.69661401e+03 2.69494702e+03 2.66833105e+03 2.68545996e+03 2.78522461e+03 2.90091968e+03 2.93749194e+03 2.98692407e+03 2.92762939e+03 2.87287793e+03 2.97581201e+03 3.11152246e+03 3.20774536e+03 3.21736743e+03 3.11888330e+03 3.11376611e+03 3.23875049e+03 3.40364185e+03 3.40419824e+03 3.41774023e+03 3.42069702e+03 3.38291406e+03 3.51642236e+03 3.61089233e+03 3.60625562e+03 3.62699243e+03 3.71916162e+03 3.76271216e+03 3.73071411e+03 3.80491211e+03 3.86326147e+03 3.98385815e+03 4.00692944e+03 3.91505151e+03 3.98453394e+03 4.01430884e+03 4.11263232e+03 4.37126709e+03 4.29105811e+03 4.14770410e+03 4.17241650e+03 4.27579346e+03 4.47825244e+03 4.69305566e+03 4.56460938e+03 4.44959619e+03 4.60788574e+03 4.83102295e+03 5.04034277e+03 5.58884668e+03 4.96641357e+03 7.17463721e+03 6.58448584e+03 2.20206152e+04 -11567984. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.02978056e+06 2.15216825e+06 2.58341660e+04 2.11651211e+04 1.34042881e+04 1.14081914e+04 1.02815107e+04 5.80533594e+03 6.67961719e+03 8.98860449e+03 7.63263721e+03 6.98781885e+03 6.43038623e+03 7.12789258e+03 7.89921729e+03 7.99384863e+03 7.75673486e+03 7.81690674e+03 7.84289990e+03 7.79686084e+03 8.23951465e+03 8.22397559e+03 7.91033301e+03 7.93456152e+03 8.09688184e+03 8.12540771e+03 8.01511035e+03 8.07114990e+03 8.35296973e+03 8.66868359e+03 8.72836523e+03 8.36965918e+03 7.99622900e+03 8.27579883e+03 8.79681836e+03 9.05892969e+03 8.75226465e+03 8.37189648e+03 8.40787695e+03 8.83360449e+03 9.36938672e+03 9.10085449e+03 8.67504883e+03 8.68160449e+03 9.20268555e+03 9.23864746e+03 9.10545508e+03 9.17246875e+03 9.10771680e+03 9.34067871e+03 9.43021875e+03 9.04248926e+03 9.09600098e+03 9.62089648e+03 9.93737305e+03 9.74712793e+03 9.32741016e+03 9.11172559e+03 9.67986133e+03 1.02880303e+04 1.00773564e+04 9.61438281e+03 9.39338281e+03 9.37572559e+03 9.95925879e+03 1.05287510e+04 1.02949512e+04 1.01412275e+04 1.00316143e+04 9.84490137e+03 1.00785234e+04 1.03899873e+04 1.01463535e+04 1.00593975e+04 1.05221553e+04 1.03901885e+04 9.99027637e+03 1.01780723e+04 1.07561904e+04 1.09708789e+04 1.07861797e+04 1.05804990e+04 1.03350781e+04 1.02935322e+04 1.08370098e+04 1.14127500e+04 1.10110811e+04 1.04078506e+04 1.04711270e+04 1.09542119e+04 1.14585996e+04 1.14649072e+04 1.09116562e+04 1.08274258e+04 1.12181562e+04 1.11897109e+04 1.11429229e+04 1.12436006e+04 1.12139287e+04 1.13714121e+04 1.13977549e+04 1.11001699e+04 1.12550391e+04 1.16061924e+04 1.17953975e+04 1.18629971e+04 1.16195186e+04 1.12354131e+04 1.13475352e+04 1.20431641e+04 1.21442773e+04 1.16696992e+04 1.13535908e+04 1.12874980e+04 1.18583574e+04 1.26049414e+04 1.22390186e+04 1.16003691e+04 1.16724365e+04 1.19987607e+04 1.20391895e+04 1.17927979e+04 1.19447168e+04 1.23546279e+04 1.25273418e+04 1.21777471e+04 1.18443057e+04 1.18997773e+04 1.24894062e+04 1.29671855e+04 1.26641855e+04 1.22650078e+04 1.20998789e+04 1.19384834e+04 1.24205967e+04 1.31449072e+04 1.27590381e+04 1.21265791e+04 1.21152275e+04 1.26636836e+04 1.32126025e+04 1.28736123e+04 1.25106309e+04 1.25520088e+04 1.27172275e+04 1.28546484e+04 1.28745352e+04 1.25506455e+04 1.24105078e+04 1.30231416e+04 1.32783018e+04 1.27521084e+04 1.25444023e+04 1.28011846e+04 1.31392109e+04 1.35435684e+04 1.32769414e+04 1.25191738e+04 1.26473232e+04 1.32861143e+04 1.33647812e+04 1.30868066e+04 1.29206992e+04 1.29764658e+04 1.31004541e+04 1.33163984e+04 1.31837734e+04 1.29408018e+04 1.33627383e+04 1.36413076e+04 1.32959375e+04 1.30098594e+04 1.29967197e+04 1.34350742e+04 1.38353672e+04 1.37786416e+04 1.33841289e+04 1.29436719e+04 1.28812217e+04 1.35066826e+04 1.41905713e+04 1.36969023e+04 1.30131318e+04 1.29865908e+04 1.34320537e+04 1.39521250e+04 1.38845225e+04 1.34823623e+04 1.33268506e+04 1.34565273e+04 1.34333936e+04 1.34527568e+04 1.36641709e+04 1.35706416e+04 1.36164971e+04 1.36735928e+04 1.33156133e+04 1.33936211e+04 1.38044834e+04 1.39907246e+04 1.39288867e+04 1.33377588e+04 1.30255215e+04 1.37236328e+04 1.43500635e+04 1.41148379e+04 1.36627783e+04 1.32520830e+04 1.30675273e+04 1.37923682e+04 1.46123291e+04 1.42025635e+04 1.33428828e+04 1.32043086e+04 1.36922783e+04 1.39207002e+04 1.39666055e+04 1.39391279e+04 1.37118604e+04 1.36465576e+04 1.35018682e+04 1.31176650e+04 1.33569893e+04 1.37373408e+04 1.39185664e+04 1.44548877e+04 1.41151357e+04 1.31335068e+04 1.30457676e+04 1.36144492e+04 1.41272764e+04 1.40131162e+04 1.36315723e+04 1.39846133e+04 1.41031719e+04 1.34766123e+04 1.29787031e+04 1.33107783e+04 1.39994551e+04 1.43609307e+04 1.41830176e+04 1.33956963e+04 1.29368350e+04 1.32228086e+04 1.39528486e+04 1.44163232e+04 1.40760234e+04 1.32244756e+04 1.32321094e+04 1.41400234e+04 1.39921934e+04 1.33668271e+04 1.34051553e+04 1.34132529e+04 1.34491357e+04 1.39665234e+04 1.36370762e+04 1.31743193e+04 1.34328779e+04 1.31158760e+04 1.35618545e+04 1.39267627e+04 1.31206758e+04 1.33641777e+04 1.37849629e+04 1.34588115e+04 1.34395684e+04 1.33752314e+04 1.33466025e+04 1.35142988e+04 1.34037393e+04 1.30048594e+04 1.29616973e+04 1.35824189e+04 1.39970488e+04 1.36284482e+04 1.29723789e+04 1.26616680e+04 1.29700713e+04 1.35299297e+04 1.38191953e+04 1.34004893e+04 1.27759199e+04 1.29456562e+04 1.32790928e+04 1.30550781e+04 1.30398096e+04 1.30673242e+04 1.29468594e+04 1.29391475e+04 1.34590117e+04 1.30801621e+04 1.25496064e+04 1.28677725e+04 1.25897295e+04 1.30421904e+04 1.31835410e+04 1.26998438e+04 1.32336787e+04 1.29472178e+04 1.22044297e+04 1.26278584e+04 1.24889482e+04 1.25715117e+04 1.34326465e+04 1.27889717e+04 1.20049561e+04 1.21948633e+04 1.27029131e+04 1.32413193e+04 1.29855059e+04 1.21200420e+04 1.17820752e+04 1.21416309e+04 1.26094473e+04 1.29494609e+04 1.27748848e+04 1.21177441e+04 1.19544150e+04 1.22451738e+04 1.24037988e+04 1.21330938e+04 1.20193252e+04 1.20647617e+04 1.20439453e+04 1.24065547e+04 1.23591826e+04 1.17406572e+04 1.17012021e+04 1.17785264e+04 1.18218213e+04 1.19845342e+04 1.18622168e+04 1.21038984e+04 1.18431172e+04 1.13582422e+04 1.15957021e+04 1.13398389e+04 1.16225801e+04 1.23635996e+04 1.16571338e+04 1.08437891e+04 1.11656924e+04 1.15861016e+04 1.18702842e+04 1.19925029e+04 1.12388447e+04 1.06778623e+04 1.08965762e+04 1.14463877e+04 1.18245488e+04 1.15069844e+04 1.07776885e+04 1.06516670e+04 1.09794824e+04 1.11619160e+04 1.14490918e+04 1.13147490e+04 1.06223262e+04 1.05288184e+04 1.09445547e+04 1.10513213e+04 1.06218838e+04 1.04706016e+04 1.06514717e+04 1.05004766e+04 1.08773428e+04 1.08671504e+04 1.02429492e+04 1.02293652e+04 1.04282012e+04 1.03864678e+04 1.03816006e+04 1.01803398e+04 1.03640068e+04 1.04973125e+04 1.01998105e+04 9.92987207e+03 9.64863281e+03 9.96625879e+03 1.05036152e+04 1.03123857e+04 9.72687207e+03 9.37137891e+03 9.65276758e+03 1.01988174e+04 9.88431934e+03 9.34184473e+03 9.43554297e+03 9.66866211e+03 9.80006738e+03 1.00445947e+04 9.80506152e+03 9.20549121e+03 8.91505078e+03 9.11747852e+03 9.62401660e+03 9.53683984e+03 9.19168652e+03 9.12241406e+03 9.04382227e+03 9.23778613e+03 9.14918164e+03 8.80156543e+03 8.79587305e+03 8.57461328e+03 8.92565918e+03 9.15290918e+03 8.69462695e+03 8.67333887e+03 8.74981836e+03 8.85696094e+03 8.54170508e+03 8.12711719e+03 8.42641992e+03 8.86242383e+03 8.58092773e+03 8.04693896e+03 8.14326465e+03 8.50313379e+03 8.42214062e+03 8.22363867e+03 8.14337549e+03 7.79979053e+03 7.73291064e+03 8.21761914e+03 8.17111133e+03 7.77864404e+03 7.52780371e+03 7.47136670e+03 7.75946436e+03 8.03982373e+03 7.66059961e+03 7.47904248e+03 7.49694629e+03 7.42440137e+03 7.65979639e+03 7.60869336e+03 7.19248145e+03 7.09700244e+03 7.18974072e+03 7.20784131e+03 7.19179639e+03 7.11233496e+03 7.19128564e+03 7.07541064e+03 6.73243652e+03 6.86814502e+03 6.77719385e+03 6.90814258e+03 7.30937988e+03 7.01690576e+03 6.49638477e+03 6.44987598e+03 7.05237842e+03 7.83762939e+03 7.72912793e+03 1.14647461e+04 1.82358984e+04 2.02650527e+04 13561466. -33177054. 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. 0. 0. 0. 0. 0. 0. 0. 0. -33096120. -7.12342150e+06 1.89415375e+06 2620016. 1.38158125e+04 1.14006865e+04 7.17777344e+03 6.36830225e+03 6.45075244e+03 6.34359375e+03 6.07856885e+03 6.13071240e+03 6.05369629e+03 5.92629199e+03 5.91522803e+03 5.82548682e+03 5.77603662e+03 4.64551123e+03 4.85859521e+03 3.99174756e+03 3.61017944e+03 3.54467017e+03 3.62247046e+03 3.60408154e+03 3.40158228e+03 3.35703662e+03 3.49252490e+03 3.46298193e+03 3.33082007e+03 3.26746338e+03 3.21811426e+03 3.20025977e+03 3.14181982e+03 3.09732056e+03 3.08531201e+03 3.01578882e+03 2.92396606e+03 2.88663135e+03 2.96677686e+03 2.93249731e+03 2.82716211e+03 2.78566016e+03 2.75401538e+03 2.72523315e+03 2.67243530e+03 2.62751465e+03 2.59156421e+03 2.49993164e+03 2.46806665e+03 2.47033032e+03 2.42545166e+03 2.48413306e+03 2.47066992e+03 2.34723022e+03 2.24115381e+03 2.18845312e+03 2.29235425e+03 2.29314673e+03 2.16667310e+03 2.08910767e+03 2.07643994e+03 2.05623828e+03 1.99132910e+03 2.04035828e+03 2.00481445e+03 1.85608936e+03 1.81833582e+03 1.87726013e+03 1.91736938e+03 1.83293347e+03 1.76192395e+03 1.74285583e+03 1.69164783e+03 1.64625574e+03 1.62937146e+03 1.61858154e+03 1.58082959e+03 1.52078918e+03 1.48696252e+03 1.48498022e+03 1.45155066e+03 1.45433240e+03 1.40742944e+03 1.33906030e+03 1.33652783e+03 1.30910852e+03 1.30512427e+03 1.28866321e+03 1.23336548e+03 1.20038049e+03 1.14899658e+03 1.10114478e+03 1.12850891e+03 1.11379114e+03 1.03111414e+03 1.01705151e+03 1.04877515e+03 1.04968042e+03 9.96853760e+02 9.43193542e+02 9.13237915e+02 8.91352539e+02 8.62185425e+02 8.35182800e+02 8.30633606e+02 8.03418152e+02 7.93102600e+02 7.65885803e+02 7.27043091e+02 7.17342834e+02 6.77852051e+02 6.69768372e+02 6.87347778e+02 6.51288147e+02 6.14232727e+02 5.78413330e+02 5.56151917e+02 5.70141785e+02 5.54833679e+02 5.18961792e+02 4.85852173e+02 4.70668304e+02 4.64935364e+02 4.44662109e+02 4.42224640e+02 4.29753998e+02 3.99901001e+02 3.75777557e+02 3.60789612e+02 3.59469543e+02 3.45054596e+02 3.21968719e+02 3.00733917e+02 2.87957184e+02 2.81481354e+02 2.59916016e+02 2.49843811e+02 2.53200714e+02 2.36667740e+02 2.17434311e+02 1.99902985e+02 1.87571167e+02 1.88289124e+02 1.78075470e+02 1.61916138e+02 1.47179565e+02 1.36489243e+02 1.32246033e+02 1.23339394e+02 1.13676094e+02 1.02706482e+02 9.67218094e+01 9.27143402e+01 8.28056488e+01 7.61443405e+01 6.97820358e+01 6.20735550e+01 5.44970093e+01 4.86931725e+01 4.42717743e+01 3.90564651e+01 3.43770332e+01 2.88801403e+01 2.50814133e+01 2.27268753e+01 1.82726803e+01 1.45824757e+01 1.21148033e+01 9.63549995e+00 7.67668390e+00 5.72816133e+00 4.11372280e+00 3.05720353e+00 2.22570610e+00 1.71641624e+00 1.55124855e+00 1.72228265e+00 2.22351694e+00 3.05787802e+00 4.27396154e+00 5.69537830e+00 7.61771774e+00 1.02801790e+01 1.26784344e+01 1.49447575e+01 1.75349197e+01 2.15873489e+01 2.69309673e+01 3.07123089e+01 3.43687057e+01 3.85155525e+01 4.32958374e+01 5.00683365e+01 5.60000153e+01 6.33304977e+01 6.87409668e+01 7.33779449e+01 8.27044296e+01 9.02918320e+01 9.98037720e+01 1.07665489e+02 1.13733131e+02 1.21829346e+02 1.30495728e+02 1.42647064e+02 1.48834839e+02 1.61540359e+02 1.81468933e+02 1.87928711e+02 1.94245926e+02 2.00428452e+02 2.10986267e+02 2.35220917e+02 2.49307602e+02 2.55605743e+02 2.60264587e+02 2.73326111e+02 2.96455048e+02 3.10343964e+02 3.32957764e+02 3.46083038e+02 3.52593018e+02 3.57289581e+02 3.70896515e+02 4.11205505e+02 4.24527985e+02 4.29281891e+02 4.40349365e+02 4.55225891e+02 4.96500427e+02 5.17735474e+02 5.09394012e+02 5.22971741e+02 5.69386841e+02 5.92647400e+02 5.80774292e+02 5.97614014e+02 6.51235840e+02 6.73247864e+02 6.71807129e+02 6.76932556e+02 6.97302612e+02 7.62200806e+02 7.80113342e+02 7.73677307e+02 7.95569519e+02 8.15956665e+02 8.49822815e+02 8.77714905e+02 8.93458496e+02 8.94417725e+02 9.39889893e+02 1.00472876e+03 1.00331122e+03 1.04002429e+03 1.06730188e+03 1.07210254e+03 1.10089331e+03 1.12223572e+03 1.14127258e+03 1.14786853e+03 1.16987378e+03 1.22326526e+03 1.26057532e+03 1.32700977e+03 1.31020422e+03 1.29787561e+03 1.37357385e+03 1.40647327e+03 1.47148279e+03 1.48401123e+03 1.46892017e+03 1.49726477e+03 1.52012964e+03 1.57585400e+03 1.61862952e+03 1.68127002e+03 1.69079956e+03 1.67793372e+03 1.72274084e+03 1.70125891e+03 1.79354651e+03 1.93445325e+03 1.92180847e+03 1.89496692e+03 1.88008606e+03 1.88818555e+03 2.01722217e+03 2.11374390e+03 2.09496045e+03 2.04289502e+03 2.07192627e+03 2.17511816e+03 2.19665454e+03 2.28267920e+03 2.29745239e+03 2.26197729e+03 2.34824268e+03 2.37577368e+03 2.47082715e+03 2.51293335e+03 2.42585132e+03 2.46208521e+03 2.63207324e+03 2.62382349e+03 2.52742090e+03 2.65967041e+03 2.83886719e+03 2.83073291e+03 2.79767212e+03 2.76536401e+03 2.80263940e+03 2.99250562e+03 3.02355078e+03 2.98287476e+03 2.95359912e+03 2.96865210e+03 3.11687744e+03 3.16253662e+03 3.17758154e+03 3.15021533e+03 3.27871265e+03 3.40292554e+03 3.36865503e+03 3.47556836e+03 3.45677075e+03 3.40922534e+03 3.51770215e+03 3.57774194e+03 3.60588013e+03 3.63029468e+03 3.63886279e+03 3.60214575e+03 3.77853247e+03 4.04681372e+03 3.85536328e+03 3.71877319e+03 3.88996997e+03 4.05556152e+03 4.20001611e+03 4.14424268e+03 4.07080054e+03 4.22866357e+03 4.25997021e+03 4.14011719e+03 4.13274561e+03 4.43633008e+03 4.47527588e+03 4.38258350e+03 4.41620801e+03 4.32179297e+03 4.52932129e+03 4.87394043e+03 4.76358838e+03 4.67133496e+03 4.57777979e+03 4.57766309e+03 4.88772510e+03 5.17930322e+03 5.07574951e+03 4.85648535e+03 4.88298877e+03 5.01578711e+03 5.10746387e+03 5.30896289e+03 5.21021777e+03 5.08786279e+03 5.29086182e+03 5.31135107e+03 5.51877539e+03 5.52665430e+03 5.37544678e+03 5.56092090e+03 5.61177734e+03 5.63309424e+03 5.50883350e+03 5.62385938e+03 6.02000342e+03 5.98272168e+03 5.79845410e+03 5.69138037e+03 5.87199658e+03 6.26311133e+03 6.19596484e+03 6.10607324e+03 5.99882910e+03 5.99165088e+03 6.26296387e+03 6.35145117e+03 6.35400928e+03 6.25647559e+03 6.40276025e+03 6.70111572e+03 6.53522949e+03 6.70484229e+03 6.79175684e+03 6.66664209e+03 6.73105859e+03 6.73835596e+03 6.77305078e+03 6.81343555e+03 6.80398535e+03 6.83955908e+03 7.16342432e+03 7.23494678e+03 6.86191260e+03 6.90909961e+03 7.09855957e+03 7.33770312e+03 7.67438867e+03 7.46656250e+03 7.06658154e+03 7.45473242e+03 7.84259521e+03 7.68272021e+03 7.40679883e+03 7.43716992e+03 7.61757275e+03 7.69685498e+03 7.82079785e+03 7.59940039e+03 7.83994043e+03 8.29585742e+03 8.12676904e+03 7.95283496e+03 7.84872705e+03 7.97953076e+03 8.40284473e+03 8.42197266e+03 8.22301367e+03 8.14513721e+03 7.91874512e+03 8.15492041e+03 8.64661914e+03 8.96526660e+03 8.54115039e+03 8.25214355e+03 8.54255273e+03 8.74489355e+03 9.09454102e+03 8.91083105e+03 8.61772168e+03 8.90420410e+03 8.93436816e+03 8.80334961e+03 8.69486914e+03 8.98733398e+03 9.46173730e+03 9.31739941e+03 9.16173730e+03 9.06787500e+03 9.06515137e+03 9.58017480e+03 9.61530469e+03 9.41296387e+03 9.21072168e+03 9.16953516e+03 9.44618848e+03 9.49769531e+03 9.89040527e+03 1.00479922e+04 9.57144238e+03 9.43176172e+03 9.78562988e+03 10251. 1.00411875e+04 9.87781348e+03 9.84830371e+03 9.91875098e+03 9.88081738e+03 9.75161621e+03 1.01840498e+04 1.04014697e+04 1.01582588e+04 1.04110459e+04 1.05281348e+04 1.04732910e+04 1.04865850e+04 1.04265762e+04 1.04472979e+04 1.02728516e+04 1.02139434e+04 1.06826299e+04 1.09546660e+04 1.05233379e+04 1.01882061e+04 1.05967256e+04 1.12354463e+04 1.12958408e+04 1.07636777e+04 1.03841211e+04 1.10182451e+04 1.14415215e+04 1.12140967e+04 1.11446875e+04 1.08253613e+04 1.04844053e+04 1.09603789e+04 1.16672783e+04 1.17488086e+04 1.11298691e+04 1.07440205e+04 1.14693164e+04 1.20011367e+04 1.16464443e+04 1.11138057e+04 1.08966572e+04 1.13463281e+04 1.15438760e+04 1.18962588e+04 1.20961162e+04 1.17285391e+04 1.14722012e+04 1.15439600e+04 1.20948936e+04 1.18339209e+04 1.14762061e+04 1.20581465e+04 1.20952275e+04 1.19794229e+04 1.17422705e+04 1.17573291e+04 1.24484180e+04 1.20840625e+04 1.15134277e+04 1.19160605e+04 1.24094121e+04 1.24643594e+04 1.21923994e+04 1.25397979e+04 1.26836807e+04 1.23372080e+04 1.19672354e+04 1.19644160e+04 1.27294902e+04 1.24992139e+04 1.21376836e+04 1.25223799e+04 1.25248545e+04 1.24859482e+04 1.23705879e+04 1.27050918e+04 1.28655938e+04 1.25259590e+04 1.27600684e+04 1.28134551e+04 1.28865732e+04 1.29604463e+04 1.28150469e+04 1.25652168e+04 1.22512002e+04 1.23142178e+04 1.30241963e+04 1.37002275e+04 1.29936963e+04 1.21826299e+04 1.26677646e+04 1.34882803e+04 1.36255234e+04 1.29734297e+04 1.24338125e+04 1.30763701e+04 1.33968975e+04 1.29602686e+04 1.34715947e+04 1.33169365e+04 1.25572119e+04 1.28948213e+04 1.36784111e+04 1.37132256e+04 1.30490547e+04 1.25717461e+04 1.31724785e+04 1.40291211e+04 1.36830830e+04 1.30034834e+04 1.27170928e+04 1.33660244e+04 1.38392314e+04 1.34452383e+04 1.33136914e+04 1.33723818e+04 1.34488369e+04 1.34026025e+04 1.37828701e+04 1.35749062e+04 1.30988730e+04 1.34428643e+04 1.35512705e+04 1.38413438e+04 1.35474961e+04 1.32081865e+04 1.37892471e+04 1.33864385e+04 1.30402090e+04 1.36611865e+04 1.39769824e+04 1.38702666e+04 1.35789014e+04 1.40524590e+04 1.40761768e+04 1.34358203e+04 1.32304414e+04 1.34010176e+04 1.50376865e+04 1.52020938e+04 1.53960186e+04 1.52501094e+04 3.98477891e+04 2.53745469e+05 2.60731238e+09 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. -5.66118912e+09 2.24530578e+05 3.29186016e+04 1.94121875e+04 1.66487383e+04 1.53194170e+04 1.43224873e+04 1.40757588e+04 1.39056387e+04 1.38903652e+04 1.36825625e+04 1.33175000e+04 1.36869189e+04 1.40843027e+04 1.36518320e+04 1.34838809e+04 1.37732031e+04 1.39317451e+04 1.39439678e+04 1.35174873e+04 1.31230234e+04 1.33481191e+04 1.37232139e+04 1.37938340e+04 1.36682070e+04 1.33648467e+04 1.33448018e+04 1.38306016e+04 1.41001709e+04 1.36251523e+04 1.30508027e+04 1.32198164e+04 1.36388457e+04 1.34425850e+04 1.33908516e+04 1.35083311e+04 1.31374102e+04 1.33684336e+04 1.36422646e+04 1.30737852e+04 1.30396885e+04 1.34337266e+04 1.39057666e+04 1.39841201e+04 1.30271660e+04 1.25675654e+04 1.29019814e+04 1.34104619e+04 1.35868359e+04 1.30748926e+04 1.30194160e+04 1.34141123e+04 1.32766133e+04 1.31943291e+04 1.29720967e+04 1.25677441e+04 1.30137715e+04 1.33787549e+04 1.29077334e+04 1.28289971e+04 1.30584180e+04 1.28769287e+04 1.30431650e+04 1.30830752e+04 1.26665107e+04 1.25841719e+04 1.27672227e+04 1.31928652e+04 1.30847959e+04 1.25269316e+04 12620. 1.25798613e+04 1.26645117e+04 1.29269824e+04 1.24364336e+04 1.22863018e+04 1.26015078e+04 1.27947480e+04 1.28322939e+04 1.23971631e+04 1.19868154e+04 1.21038096e+04 1.24522100e+04 1.26135156e+04 1.25460469e+04 1.22539668e+04 1.21141836e+04 1.23546367e+04 1.25073379e+04 1.21831562e+04 1.17771680e+04 1.19333857e+04 1.23358115e+04 1.24368799e+04 1.21030518e+04 1.17393662e+04 1.15834355e+04 1.19528750e+04 1.21736973e+04 1.16983281e+04 1.16571182e+04 1.19767568e+04 1.21724189e+04 1.21338027e+04 1.14719521e+04 1.11291240e+04 1.14974062e+04 1.16969814e+04 1.15622305e+04 1.14722891e+04 1.15665957e+04 1.17028027e+04 1.13949863e+04 1.12759414e+04 1.14514941e+04 1.12065986e+04 1.10693428e+04 1.13047334e+04 1.13760518e+04 1.13599893e+04 1.11264434e+04 1.07300391e+04 1.08404697e+04 1.10908965e+04 1.11998887e+04 1.10216006e+04 1.07019502e+04 1.08015166e+04 1.10583086e+04 1.10927266e+04 1.06521475e+04 1.03058672e+04 1.04294307e+04 1.06751670e+04 1.06932617e+04 1.04860254e+04 1.03525371e+04 1.03431494e+04 1.05573105e+04 1.05723906e+04 1.03705742e+04 1.02463896e+04 1.00634570e+04 1.01542822e+04 1.01132852e+04 9.94799707e+03 9.95602832e+03 9.95289844e+03 1.01796475e+04 1.02874883e+04 9.85749512e+03 9.58698242e+03 9.70739160e+03 9.81985645e+03 9.90194531e+03 9.79429297e+03 9.33415723e+03 9.30084863e+03 9.70580469e+03 9.91028027e+03 9.49739551e+03 9.07301465e+03 9.18832715e+03 9.50548926e+03 9.43461328e+03 8.89524902e+03 8.90263477e+03 9.14232031e+03 9.16178125e+03 9.07603320e+03 9.08997754e+03 9.04561328e+03 8.66187988e+03 8.83965820e+03 9.01001758e+03 8.58421875e+03 8.58317090e+03 8.67667676e+03 8.66132129e+03 8.79493555e+03 8.49624512e+03 8.16940576e+03 8.20419336e+03 8.35085352e+03 8.68626758e+03 8.55444824e+03 7.99350488e+03 8.02472314e+03 8.39643848e+03 8.16569531e+03 7.75591260e+03 7.75605176e+03 7.90899756e+03 8.08736719e+03 8.01703418e+03 7.89563916e+03 7.65258496e+03 7.47239453e+03 7.65191748e+03 7.75556836e+03 7.46866260e+03 7.39857422e+03 7.55753418e+03 7.59866260e+03 7.54178906e+03 7.25768604e+03 7.04741455e+03 7.08535352e+03 7.14090918e+03 7.33961133e+03 7.27634766e+03 6.87586670e+03 6.83235400e+03 7.01144189e+03 6.99981641e+03 6.90783936e+03 6.62661719e+03 6.65015234e+03 6.76011133e+03 6.79113721e+03 6.69451953e+03 6.46918896e+03 6.35086377e+03 6.42661279e+03 6.51856787e+03 6.29303174e+03 6.30909180e+03 6.36405225e+03 6.26193799e+03 6.35851465e+03 6.08544727e+03 5.90326807e+03 6.01092236e+03 5.97881934e+03 6.01614209e+03 5.82955176e+03 5.62399707e+03 5.77801758e+03 5.95411719e+03 5.77883740e+03 5.62643848e+03 5.60289404e+03 5.48983057e+03 5.40217041e+03 5.51083789e+03 5.62270215e+03 5.43677686e+03 5.20878564e+03 5.30966650e+03 5.21383740e+03 5.20979688e+03 5.15182568e+03 4.93655957e+03 5.02322754e+03 5.10453516e+03 4.88662842e+03 4.78969336e+03 4.80524268e+03 4.91205615e+03 4.95778906e+03 4.61123779e+03 4.54558740e+03 4.66125684e+03 4.64700488e+03 4.66150098e+03 4.46028174e+03 4.39079883e+03 4.33684570e+03 4.32293652e+03 4.44386377e+03 4.31847852e+03 4.11206250e+03 4.17573096e+03 4.24398682e+03 4.06075732e+03 3.97661426e+03 3.90907349e+03 3.85144409e+03 3.96602026e+03 3.98926636e+03 3.82385132e+03 3.71206152e+03 3.70950684e+03 3.73145630e+03 3.75804297e+03 3.58936182e+03 3.61354395e+03 3.59226660e+03 3.39753613e+03 3.37653931e+03 3.37104443e+03 3.35206836e+03 3.38169238e+03 3.28251440e+03 3.22612354e+03 3.27046069e+03 3.15153638e+03 3.05251221e+03 3.07770630e+03 3.09109741e+03 3.03615698e+03 2.88944775e+03 2.84659229e+03 2.95101074e+03 2.93513599e+03 2.77458789e+03 2.70948486e+03 2.70158301e+03 2.73558154e+03 2.72607617e+03 2.59273364e+03 2.54327563e+03 2.50434595e+03 2.51654590e+03 2.51123022e+03 2.40342358e+03 2.37297827e+03 2.34700391e+03 2.30451025e+03 2.30294409e+03 2.29343091e+03 2.20368262e+03 2.12345410e+03 2.18110620e+03 2.21406055e+03 2.06852148e+03 1.95501697e+03 1.97545593e+03 1.99211743e+03 1.95738293e+03 1.89251416e+03 1.83890808e+03 1.82247290e+03 1.83988489e+03 1.81194800e+03 1.72986243e+03 1.69758069e+03 1.66358435e+03 1.66382336e+03 1.64190918e+03 1.56152075e+03 1.54032349e+03 1.51196570e+03 1.48422363e+03 1.48263379e+03 1.45295618e+03 1.39432080e+03 1.35309290e+03 1.35482532e+03 1.33823450e+03 1.28929395e+03 1.23848730e+03 1.22014526e+03 1.22214404e+03 1.19586694e+03 1.12825818e+03 1.10469092e+03 1.09731213e+03 1.10301721e+03 1.08211353e+03 1.01513208e+03 1.01440240e+03 9.78543274e+02 9.18690613e+02 9.05764099e+02 8.94394043e+02 8.96394470e+02 8.68472046e+02 8.09483704e+02 7.79208252e+02 7.82895569e+02 7.84481934e+02 7.58818481e+02 7.25258850e+02 6.98818420e+02 6.72412354e+02 6.43998474e+02 6.21321289e+02 6.23277893e+02 6.10355347e+02 5.69435669e+02 5.51221313e+02 5.35871948e+02 5.22978333e+02 5.09670929e+02 4.90266357e+02 4.80123932e+02 4.50332672e+02 4.19068909e+02 4.04190399e+02 3.99811920e+02 3.95747742e+02 3.82183197e+02 3.55428619e+02 3.21793213e+02 3.13892944e+02 3.12198029e+02 2.95360077e+02 2.87793304e+02 2.72352692e+02 2.49151657e+02 2.43885696e+02 2.32635742e+02 2.15095932e+02 2.06245361e+02 1.93452911e+02 1.79558243e+02 1.68336838e+02 1.60131516e+02 1.50921631e+02 1.44655350e+02 1.39168564e+02 1.23870476e+02 1.10220497e+02 1.02684891e+02 9.70653687e+01 9.22777863e+01 8.41781693e+01 7.33202057e+01 6.59153595e+01 6.08918076e+01 5.63732224e+01 5.11588821e+01 4.42997971e+01 3.87142982e+01 3.38523026e+01 2.91817741e+01 2.49011192e+01 2.15877094e+01 1.82757454e+01 1.48601170e+01 1.21247034e+01 9.31446743e+00 7.14908171e+00 5.46255302e+00 3.96969843e+00 2.82641077e+00 1.96231985e+00 1.46760333e+00 1.31758869e+00 1.50533068e+00 2.04494071e+00 2.91997910e+00 4.05141735e+00 5.40931988e+00 7.33760595e+00 9.64268970e+00 1.20290346e+01 1.51922503e+01 1.86860008e+01 2.16601830e+01 2.53055840e+01 2.96714954e+01 3.48595467e+01 4.03543396e+01 4.48908844e+01 5.04445763e+01 5.47221184e+01 6.03338699e+01 6.87001877e+01 7.63171005e+01 8.49390869e+01 9.20893402e+01 9.73193054e+01 1.03504570e+02 1.14508286e+02 1.27508842e+02 1.35036758e+02 1.42541031e+02 1.52709335e+02 1.59734512e+02 1.71057358e+02 1.85574295e+02 1.96300491e+02 2.08662247e+02 2.17496155e+02 2.26893112e+02 2.39325958e+02 2.58753326e+02 2.73378693e+02 2.83226471e+02 2.99558228e+02 3.06057831e+02 3.23411163e+02 3.42823425e+02 3.54461212e+02 3.80375732e+02 3.87715759e+02 3.90306061e+02 4.09365021e+02 4.26471222e+02 4.54888489e+02 4.91543427e+02 4.99199707e+02 4.96078644e+02 5.10553070e+02 5.30206909e+02 5.49448669e+02 5.84587219e+02 6.12266357e+02 6.12905518e+02 6.32024475e+02 6.48080444e+02 6.77164246e+02 7.17546997e+02 7.30197632e+02 7.66927307e+02 7.72746643e+02 7.52399475e+02 7.84873291e+02 8.39501160e+02 8.75870911e+02 9.06437622e+02 9.03489258e+02 8.79179138e+02 9.33214172e+02 1.00928314e+03 1.01566705e+03 1.02219647e+03 1.04539697e+03 1.05665198e+03 1.10388135e+03 1.13373474e+03 1.14479736e+03 1.21207129e+03 1.22345862e+03 1.23323828e+03 1.26467505e+03 1.25597998e+03 1.30235498e+03 1.36567078e+03 1.43199597e+03 1.42229871e+03 1.37332300e+03 1.41851135e+03 1.50070947e+03 1.55538892e+03 1.57515039e+03 1.56545618e+03 1.57534473e+03 1.64213171e+03 1.70541064e+03 1.74343835e+03 1.76814001e+03 1.77627563e+03 1.79653760e+03 1.83560205e+03 1.85980957e+03 1.90608289e+03 1.95534900e+03 1.98044629e+03 2.03383899e+03 2.01253711e+03 2.04504968e+03 2.13747119e+03 2.15250122e+03 2.24679688e+03 2.24013916e+03 2.16667700e+03 2.22338062e+03 2.32126831e+03 2.42088916e+03 2.49622656e+03 2.43495435e+03 2.38788696e+03 2.46015234e+03 2.54553857e+03 2.59886548e+03 2.64199731e+03 2.68975073e+03 2.66079126e+03 2.65878882e+03 2.73836426e+03 2.84593628e+03 2.92547925e+03 2.90654370e+03 2.96941040e+03 2.95939575e+03 2.88317261e+03 2.99889575e+03 3.10067212e+03 3.19082666e+03 3.24439697e+03 3.12129810e+03 3.13046704e+03 3.27269897e+03 3.43398901e+03 3.44865112e+03 3.41801416e+03 3.44629590e+03 3.38355957e+03 3.52886938e+03 3.66512476e+03 3.63420044e+03 3.64937573e+03 3.70108643e+03 3.75803906e+03 3.79737793e+03 3.81314819e+03 3.89462451e+03 3.95491772e+03 4.00387964e+03 3.93175391e+03 4.02263306e+03 4.12372363e+03 4.15594629e+03 4.34778516e+03 4.24903711e+03 4.15229053e+03 4.27052393e+03 4.25780469e+03 4.43098730e+03 4.73105957e+03 4.68323047e+03 4.45279102e+03 4.50916553e+03 4.80327148e+03 5.26710352e+03 6.05163916e+03 5.87084082e+03 8.53542383e+03 1.42987295e+04 6.82931719e+04 17243742. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 34211788. 32195730. 3.33896094e+04 2.10566348e+04 8.44297559e+03 8.92141895e+03 8.13262451e+03 7.81692773e+03 7.58995947e+03 7.20002979e+03 7.35121143e+03 7.77629395e+03 7.77765625e+03 7.49054150e+03 7.27068311e+03 7.34422607e+03 7.83278320e+03 8.14648096e+03 7.87548779e+03 7.65304590e+03 7.63625830e+03 7.80209863e+03 8.17791162e+03 8.27907031e+03 8.02742090e+03 7.94886035e+03 7.98543115e+03 8.13650732e+03 8.24642285e+03 8.14372363e+03 8.20501953e+03 8.60538379e+03 8.83708203e+03 8.44180371e+03 8.08316309e+03 8.32509766e+03 8.78889453e+03 9.12360742e+03 8.78874512e+03 8.35770996e+03 8.49158398e+03 8.93269434e+03 9.40358594e+03 9.06617383e+03 8.59666504e+03 8.68965137e+03 9.13081836e+03 9.36512207e+03 9.40895898e+03 9.31063672e+03 9.08881543e+03 9.17483887e+03 9.49624805e+03 9.28071680e+03 9.13812695e+03 9.68343262e+03 9.80388965e+03 9.72499707e+03 9.46849414e+03 9.15597070e+03 9.74469336e+03 1.03052578e+04 1.01065195e+04 9.55713867e+03 9.31237695e+03 9.52263867e+03 1.01735176e+04 1.05541191e+04 1.03076357e+04 1.01411992e+04 9.98942285e+03 9.79848828e+03 1.01313945e+04 1.05057900e+04 1.02406309e+04 1.02082910e+04 1.04026191e+04 1.05038389e+04 1.03012969e+04 1.02558701e+04 1.06838711e+04 1.08352197e+04 1.09196973e+04 1.06222910e+04 1.02655088e+04 1.03594541e+04 1.09820967e+04 1.14742734e+04 1.09791318e+04 1.03798086e+04 1.05660459e+04 1.09994219e+04 1.13888789e+04 1.14717363e+04 1.10591807e+04 1.09987168e+04 1.10780361e+04 1.12101670e+04 1.14321895e+04 1.12949473e+04 1.12522754e+04 1.12512969e+04 1.13906104e+04 1.14888086e+04 1.13929785e+04 1.15411055e+04 1.16944053e+04 1.18757051e+04 1.16458770e+04 1.11587920e+04 1.14006094e+04 1.20703418e+04 1.23206592e+04 1.17537334e+04 1.12783926e+04 1.13755811e+04 1.20374199e+04 1.26969541e+04 1.21997871e+04 1.16532842e+04 1.18714512e+04 1.18784648e+04 1.20137119e+04 1.21771543e+04 1.20845117e+04 1.23153125e+04 1.22343877e+04 1.22160391e+04 1.22817734e+04 1.20227783e+04 1.23802881e+04 1.28228057e+04 1.27555801e+04 1.23816162e+04 1.20449541e+04 1.20977441e+04 1.26100859e+04 1.31685068e+04 1.26919873e+04 1.20413525e+04 1.22932002e+04 1.29065781e+04 1.32879883e+04 1.28275840e+04 1.25226807e+04 1.26714590e+04 1.26394141e+04 1.28657549e+04 1.30340713e+04 1.25378770e+04 1.25039082e+04 1.30039238e+04 1.32404951e+04 1.30321318e+04 1.28249785e+04 1.28800557e+04 1.30724180e+04 1.35254805e+04 1.32673984e+04 1.24842148e+04 1.27244170e+04 1.32289375e+04 1.33850693e+04 1.33453105e+04 1.29509805e+04 1.28980479e+04 1.31878164e+04 1.34933691e+04 1.34673867e+04 1.31367080e+04 1.33124766e+04 1.33757441e+04 1.33605039e+04 1.33610781e+04 1.30549883e+04 1.33585234e+04 1.37765459e+04 1.39025693e+04 1.34712324e+04 1.28612070e+04 1.30226934e+04 1.36968965e+04 1.42192607e+04 1.36396934e+04 1.29666719e+04 1.31765107e+04 1.35267119e+04 1.38132275e+04 1.38985908e+04 1.34497969e+04 1.33409258e+04 1.35697383e+04 1.37249580e+04 1.37240049e+04 1.36260762e+04 1.36718994e+04 1.35044648e+04 1.36781709e+04 1.37502637e+04 1.35530137e+04 1.37239297e+04 1.38091729e+04 1.38821475e+04 1.33999932e+04 1.31380371e+04 1.37482627e+04 1.42727822e+04 1.43229316e+04 1.37642324e+04 1.31733809e+04 1.32037041e+04 1.39782666e+04 1.47186104e+04 1.42805156e+04 1.35272979e+04 1.32733926e+04 1.33503877e+04 1.38672324e+04 1.43149404e+04 1.41059922e+04 1.37781113e+04 1.36742959e+04 1.36705645e+04 1.33616221e+04 1.34140283e+04 1.38503496e+04 1.38121631e+04 1.42669609e+04 1.41177012e+04 1.31642480e+04 1.33691240e+04 1.38492090e+04 1.39396201e+04 1.39783984e+04 1.37816680e+04 1.40357422e+04 1.41473965e+04 1.35738545e+04 1.30717598e+04 1.33448838e+04 1.40367842e+04 1.44207598e+04 1.42045732e+04 1.34607725e+04 1.30525713e+04 1.33432832e+04 1.40113770e+04 1.43827207e+04 1.41176982e+04 1.33315771e+04 1.33037588e+04 1.41569111e+04 1.40647197e+04 1.33288340e+04 1.33343916e+04 1.36126465e+04 1.35981309e+04 1.40280967e+04 1.36896172e+04 1.31969971e+04 1.35031348e+04 1.31716006e+04 1.35290254e+04 1.40260156e+04 1.32596699e+04 1.33898125e+04 1.38267324e+04 1.35569863e+04 1.35703652e+04 1.33989971e+04 1.33927285e+04 1.36387852e+04 1.34470137e+04 1.30012734e+04 1.30761699e+04 1.36532061e+04 1.39736875e+04 1.36571689e+04 1.30869805e+04 1.27521504e+04 1.29737852e+04 1.35531875e+04 1.38835459e+04 1.35714824e+04 1.28526348e+04 1.28949795e+04 1.34135146e+04 1.31990967e+04 1.30055752e+04 1.30472939e+04 1.30266367e+04 1.30079434e+04 1.35253203e+04 1.31271299e+04 1.26024668e+04 1.28953877e+04 1.25615176e+04 1.30392588e+04 1.33441650e+04 1.28261553e+04 1.32787793e+04 1.29848867e+04 1.23307539e+04 1.26738809e+04 1.24680117e+04 1.26672881e+04 1.34689434e+04 1.27801162e+04 1.21103359e+04 1.23560723e+04 1.27847832e+04 1.32294102e+04 1.29875127e+04 1.22045127e+04 1.17897090e+04 1.21168535e+04 1.27300771e+04 1.30734053e+04 1.28347822e+04 1.21424248e+04 1.19334072e+04 1.23573232e+04 1.25728076e+04 1.21311504e+04 1.19712529e+04 1.21283330e+04 1.20863301e+04 1.24561475e+04 1.24355391e+04 1.19286748e+04 1.18583174e+04 1.17587773e+04 1.17915088e+04 1.20681416e+04 1.19199482e+04 1.21239209e+04 1.19198262e+04 1.14039658e+04 1.16332461e+04 1.13974863e+04 1.16654619e+04 1.24462295e+04 1.17226396e+04 1.08384531e+04 1.11339697e+04 1.16582900e+04 1.18785273e+04 1.20419199e+04 1.13696152e+04 1.07379004e+04 1.09296035e+04 1.14827666e+04 1.19815361e+04 1.15571250e+04 1.07998721e+04 1.06838125e+04 1.09985342e+04 1.12142500e+04 1.15105020e+04 1.13768291e+04 1.06658652e+04 1.05664873e+04 1.09034414e+04 1.10183105e+04 1.09360449e+04 1.07480361e+04 1.05327412e+04 1.04458740e+04 1.09214238e+04 1.09103438e+04 1.02924609e+04 1.02667861e+04 1.04502920e+04 1.04338301e+04 1.04345645e+04 1.02804512e+04 1.04663193e+04 1.05275928e+04 1.01276123e+04 9.96878809e+03 9.82087305e+03 1.00676475e+04 1.05110996e+04 1.03639736e+04 9.76531152e+03 9.44464062e+03 9.76472656e+03 1.02843838e+04 9.89579395e+03 9.29536426e+03 9.44095215e+03 9.70809668e+03 9.85070898e+03 1.00121064e+04 9.80025684e+03 9.24902734e+03 8.92562305e+03 9.17624512e+03 9.70400781e+03 9.64917480e+03 9.19082324e+03 9.10609766e+03 9.11733887e+03 9.27413965e+03 9.10837109e+03 8.78005664e+03 8.79373926e+03 8.71083008e+03 8.99751855e+03 9.19985059e+03 8.81072656e+03 8.70596777e+03 8.76106543e+03 8.90688477e+03 8.62747070e+03 8.12135791e+03 8.51399023e+03 8.94851562e+03 8.49623535e+03 8.02518408e+03 8.22835059e+03 8.63617871e+03 8.47325781e+03 8.19886719e+03 8.20547949e+03 7.84854053e+03 7.78193066e+03 8.23367773e+03 8.18641455e+03 7.79893945e+03 7.58786914e+03 7.47374072e+03 7.79601709e+03 8.09265088e+03 7.72358350e+03 7.44318311e+03 7.50994434e+03 7.49529395e+03 7.71189209e+03 7.67670654e+03 7.18852148e+03 7.09737891e+03 7.21084668e+03 7.20063867e+03 7.24651611e+03 7.17193115e+03 7.28994922e+03 7.15538525e+03 6.82023877e+03 6.83702637e+03 6.73440674e+03 6.91394482e+03 7.29612305e+03 7.06488965e+03 6.51104297e+03 6.52309961e+03 7.25609863e+03 8.63980566e+03 8.76870898e+03 1.18639238e+04 9.95246484e+03 1.49992393e+04 7.40556875e+04 -33177054. 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. 0. 0. 0. 0. 0. 0. 0. -41762548. 1.92577676e+04 6.83820557e+03 7.40041748e+03 7.52542041e+03 4.96425439e+03 5.24212744e+03 4.53951074e+03 4.19407617e+03 4.27432715e+03 4.27038184e+03 4.08659131e+03 4.08834302e+03 4.04740601e+03 3.96803296e+03 3.94793481e+03 3.88580005e+03 3.83863013e+03 3.80004736e+03 3.75070581e+03 3.69312256e+03 3.57178613e+03 3.51098608e+03 3.64119897e+03 3.62052856e+03 3.39328711e+03 3.35324585e+03 3.50533594e+03 3.47786670e+03 3.34713452e+03 3.29170337e+03 3.23762036e+03 3.20783130e+03 3.15374731e+03 3.10472363e+03 3.08767212e+03 3.03083032e+03 2.94299902e+03 2.89608423e+03 2.97401465e+03 2.96173535e+03 2.84484741e+03 2.79788916e+03 2.76336182e+03 2.72789722e+03 2.68608691e+03 2.63995288e+03 2.60839697e+03 2.50844678e+03 2.45438794e+03 2.49582324e+03 2.45034351e+03 2.49238599e+03 2.47516919e+03 2.35153857e+03 2.25212329e+03 2.20337280e+03 2.30589087e+03 2.29421606e+03 2.17318774e+03 2.10639746e+03 2.09536304e+03 2.07965039e+03 2.01877502e+03 2.03647070e+03 2.00773718e+03 1.87632458e+03 1.82458350e+03 1.89478711e+03 1.90934021e+03 1.81974963e+03 1.76666528e+03 1.74295715e+03 1.70052332e+03 1.64690442e+03 1.62256750e+03 1.62571350e+03 1.59030286e+03 1.53417651e+03 1.50556738e+03 1.49143103e+03 1.45910498e+03 1.46382043e+03 1.42431848e+03 1.35292102e+03 1.34951489e+03 1.31947241e+03 1.30163477e+03 1.28460229e+03 1.23683093e+03 1.20538647e+03 1.15761719e+03 1.11522046e+03 1.13589319e+03 1.10959558e+03 1.02928210e+03 1.01968811e+03 1.05490063e+03 1.05880481e+03 1.00184113e+03 9.49755188e+02 9.08327698e+02 8.83302124e+02 8.71167480e+02 8.44624451e+02 8.34178284e+02 8.07147644e+02 7.96894531e+02 7.73662781e+02 7.32624084e+02 7.22423889e+02 6.80890076e+02 6.64507141e+02 6.83097229e+02 6.52782166e+02 6.16831055e+02 5.83969421e+02 5.60061157e+02 5.71748474e+02 5.54801758e+02 5.19658691e+02 4.89658783e+02 4.72984558e+02 4.67798035e+02 4.48168945e+02 4.43774597e+02 4.31066803e+02 4.01583679e+02 3.81304260e+02 3.66093323e+02 3.58082947e+02 3.42806732e+02 3.22923096e+02 3.03173340e+02 2.90086914e+02 2.83825562e+02 2.62298767e+02 2.48813354e+02 2.50563156e+02 2.37003448e+02 2.18780960e+02 2.00025909e+02 1.88205383e+02 1.88920425e+02 1.77839828e+02 1.62393906e+02 1.48133438e+02 1.37334045e+02 1.32459946e+02 1.23068314e+02 1.14254059e+02 1.03383202e+02 9.69086914e+01 9.35781708e+01 8.36984177e+01 7.57208328e+01 6.90026093e+01 6.20585098e+01 5.50340500e+01 4.89631615e+01 4.41989365e+01 3.91336250e+01 3.43900185e+01 2.87649860e+01 2.47242317e+01 2.24357300e+01 1.81194229e+01 1.43799725e+01 1.19109459e+01 9.43922615e+00 7.50241947e+00 5.51392365e+00 3.88431239e+00 2.83275747e+00 1.99452722e+00 1.48142481e+00 1.31715655e+00 1.48722029e+00 1.99909639e+00 2.84942555e+00 4.05867863e+00 5.48849440e+00 7.41403198e+00 1.00211334e+01 1.24277706e+01 1.48857164e+01 1.75581055e+01 2.12919178e+01 2.65295525e+01 3.06768265e+01 3.43675880e+01 3.84463310e+01 4.33115768e+01 4.99072723e+01 5.59671288e+01 6.35818100e+01 6.89182510e+01 7.34389877e+01 8.26428757e+01 9.04401016e+01 1.00006508e+02 1.07122940e+02 1.13000732e+02 1.23007469e+02 1.31950821e+02 1.42744583e+02 1.48689224e+02 1.61916779e+02 1.83071503e+02 1.88456558e+02 1.94382217e+02 2.01297455e+02 2.11166550e+02 2.35842514e+02 2.50944275e+02 2.56743958e+02 2.60538818e+02 2.73968567e+02 2.97840759e+02 3.11036469e+02 3.33787231e+02 3.47159088e+02 3.53506500e+02 3.58989746e+02 3.72278564e+02 4.12202820e+02 4.24534637e+02 4.29332123e+02 4.43596161e+02 4.59298004e+02 4.99081329e+02 5.18488708e+02 5.11162323e+02 5.24659485e+02 5.69247803e+02 5.95768494e+02 5.84468201e+02 6.00224792e+02 6.52218750e+02 6.74962585e+02 6.77349365e+02 6.83469238e+02 7.01671814e+02 7.62683044e+02 7.75579590e+02 7.72197632e+02 8.01038635e+02 8.24530212e+02 8.67749390e+02 8.92132874e+02 8.87737122e+02 8.89774536e+02 9.42373535e+02 1.01997144e+03 1.01790900e+03 1.03056128e+03 1.06101404e+03 1.08056995e+03 1.10631189e+03 1.12809619e+03 1.14902515e+03 1.15361084e+03 1.17043823e+03 1.22413123e+03 1.26769653e+03 1.33609814e+03 1.32005457e+03 1.29388428e+03 1.37090088e+03 1.42024072e+03 1.48706360e+03 1.48983057e+03 1.47490588e+03 1.50570325e+03 1.52891174e+03 1.58024402e+03 1.62033716e+03 1.68987866e+03 1.70558044e+03 1.69150562e+03 1.71180676e+03 1.69582056e+03 1.79925403e+03 1.95153857e+03 1.92968506e+03 1.90357336e+03 1.89195300e+03 1.88156665e+03 2.00864258e+03 2.14144165e+03 2.12004541e+03 2.05210205e+03 2.07513989e+03 2.17878418e+03 2.21530811e+03 2.29271558e+03 2.32498828e+03 2.29594604e+03 2.33533350e+03 2.36257471e+03 2.48227515e+03 2.52169604e+03 2.43447803e+03 2.47723022e+03 2.65183228e+03 2.65197949e+03 2.56244214e+03 2.65133813e+03 2.83226904e+03 2.83431641e+03 2.80265747e+03 2.78234497e+03 2.81082397e+03 3.00646362e+03 3.04085400e+03 3.01903589e+03 2.96122778e+03 2.97180298e+03 3.11034204e+03 3.18159912e+03 3.19986914e+03 3.15326294e+03 3.28438330e+03 3.43794653e+03 3.37829541e+03 3.48465503e+03 3.49960889e+03 3.45145508e+03 3.53825586e+03 3.60029517e+03 3.62550757e+03 3.63900806e+03 3.61677075e+03 3.60159790e+03 3.79156665e+03 4.06437500e+03 3.87082422e+03 3.75900635e+03 3.93272144e+03 4.01929346e+03 4.18587256e+03 4.14910596e+03 4.03711060e+03 4.29345068e+03 4.31671924e+03 4.13646826e+03 4.16144531e+03 4.45172949e+03 4.52295752e+03 4.44317578e+03 4.40409131e+03 4.30042725e+03 4.54246533e+03 4.92689502e+03 4.82207520e+03 4.67628662e+03 4.60087451e+03 4.58732520e+03 4.87312939e+03 5.21557227e+03 5.09275977e+03 4.89092676e+03 4.88329932e+03 5.04310693e+03 5.14888916e+03 5.31185742e+03 5.24485254e+03 5.14139941e+03 5.33293262e+03 5.34279053e+03 5.57846973e+03 5.61119678e+03 5.44879297e+03 5.51770703e+03 5.54571777e+03 5.73810889e+03 5.63341309e+03 5.60325391e+03 6.00884863e+03 6.01807227e+03 5.86265674e+03 5.75046289e+03 5.84807129e+03 6.23481885e+03 6.24188721e+03 6.14991748e+03 6.04019775e+03 6.05423682e+03 6.24731299e+03 6.34546729e+03 6.37097266e+03 6.25117432e+03 6.41394531e+03 6.72259229e+03 6.58871436e+03 6.71781885e+03 6.85970508e+03 6.69022656e+03 6.61558984e+03 6.66871631e+03 6.95277539e+03 6.97094336e+03 6.79061865e+03 6.77837061e+03 7.23546582e+03 7.27875098e+03 6.92181738e+03 6.86275391e+03 7.07760938e+03 7.36272461e+03 7.71392480e+03 7.48367969e+03 7.15035547e+03 7.58612744e+03 7.78287744e+03 7.65654883e+03 7.51683350e+03 7.59654102e+03 7.56282129e+03 7.67160059e+03 7.81341895e+03 7.63202100e+03 7.84277441e+03 8.27918359e+03 8.08778613e+03 8.11956445e+03 8.00874951e+03 7.97329053e+03 8.39301758e+03 8.45051562e+03 8.29587207e+03 8.18991309e+03 7.94236035e+03 8.19036230e+03 8.68125977e+03 8.96846875e+03 8.57588770e+03 8.34496582e+03 8.61541211e+03 8.69317969e+03 9.08001660e+03 9.05976953e+03 8.77831543e+03 8.76500684e+03 8.79100977e+03 8.84239258e+03 8.74497754e+03 9.06117676e+03 9.47181543e+03 9.24213867e+03 9.33765820e+03 9.19412109e+03 9.07976562e+03 9.63173438e+03 9.69345801e+03 9.38558008e+03 9.25185254e+03 9.22707324e+03 9.56130078e+03 9.57640918e+03 9.90142090e+03 1.01023535e+04 9.73989160e+03 9.48056543e+03 9.71973242e+03 1.02426191e+04 1.01222051e+04 9.94055078e+03 9.82524414e+03 9.87749121e+03 1.00210820e+04 9.99679492e+03 1.03461191e+04 1.03847236e+04 1.01241006e+04 1.05169004e+04 1.06359434e+04 1.04590303e+04 1.04266836e+04 1.04816719e+04 1.05412744e+04 1.03078203e+04 1.02099131e+04 1.07955859e+04 1.09455244e+04 1.04717031e+04 1.02046895e+04 1.07451104e+04 1.13929287e+04 1.12797441e+04 1.07000889e+04 1.05462783e+04 1.12052490e+04 1.12835264e+04 1.09533828e+04 1.12547305e+04 1.09832666e+04 1.05609521e+04 1.09519316e+04 1.16012793e+04 1.18650742e+04 1.12915947e+04 1.07772715e+04 1.14329502e+04 1.20622217e+04 1.16823389e+04 1.12028662e+04 1.10924688e+04 1.14902979e+04 1.15799736e+04 1.19356895e+04 1.19531270e+04 1.15894307e+04 1.16432295e+04 1.16679404e+04 1.21102441e+04 1.18911504e+04 1.15721533e+04 1.20159229e+04 1.20121973e+04 1.21681641e+04 11960. 1.17598740e+04 1.24755732e+04 1.22165615e+04 1.16971055e+04 1.20185889e+04 1.23282422e+04 1.24123711e+04 1.22689990e+04 1.25422588e+04 1.26918291e+04 1.24135176e+04 1.21003955e+04 1.20403955e+04 1.27190166e+04 1.25089756e+04 1.21861699e+04 1.25704375e+04 1.25909404e+04 1.25763594e+04 1.25440576e+04 1.28902861e+04 1.28026367e+04 1.24628662e+04 1.29178018e+04 1.29833115e+04 1.28097832e+04 1.28932578e+04 1.28941494e+04 1.27430068e+04 1.24172100e+04 1.22455234e+04 1.29016211e+04 1.37429404e+04 1.30648008e+04 1.22675781e+04 1.28570361e+04 1.36767285e+04 1.35849336e+04 1.28920742e+04 1.25987812e+04 1.33024590e+04 1.33268506e+04 1.29028545e+04 1.34877021e+04 1.34478135e+04 1.28020947e+04 1.27830938e+04 1.34651572e+04 1.38607363e+04 1.32309473e+04 1.26925479e+04 1.32387812e+04 1.40343721e+04 1.37327383e+04 1.30917217e+04 1.27818750e+04 1.33855537e+04 1.40425693e+04 1.36098262e+04 1.32053809e+04 1.33436982e+04 1.34996152e+04 1.34569775e+04 1.38608359e+04 1.36281602e+04 1.31631270e+04 1.34699443e+04 1.35973037e+04 1.39038740e+04 1.35985059e+04 1.32417041e+04 1.36855898e+04 1.33618320e+04 1.33768252e+04 1.39563408e+04 1.38346475e+04 1.37436094e+04 1.36713447e+04 1.41678564e+04 1.41303428e+04 1.34904785e+04 1.32671973e+04 1.34356494e+04 1.49887100e+04 1.50985146e+04 1.67930977e+04 1.90447656e+04 4.59170586e+04 2.53970203e+05 2.60731238e+09 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. -5.66118912e+09 2.24675453e+05 2.42427090e+04 1.88036270e+04 1.62337559e+04 1.50573623e+04 1.45313359e+04 1.45625283e+04 1.39513584e+04 1.35024756e+04 1.36843838e+04 1.36900654e+04 1.37903516e+04 1.42009785e+04 1.40648965e+04 1.35648848e+04 1.38306572e+04 1.41362031e+04 1.37344561e+04 1.35080420e+04 1.35251758e+04 1.37243721e+04 1.40567031e+04 1.40502881e+04 1.36931357e+04 1.32725166e+04 1.35768584e+04 1.40561562e+04 1.37670664e+04 1.37028164e+04 1.35811670e+04 1.34689531e+04 1.39113145e+04 1.36170078e+04 1.31798877e+04 1.33537490e+04 1.33714111e+04 1.35609570e+04 1.36523174e+04 1.32882803e+04 1.32557334e+04 1.36754619e+04 1.42862021e+04 1.38877256e+04 1.28606816e+04 1.28391416e+04 1.31877910e+04 1.33946270e+04 1.36930547e+04 1.34517158e+04 1.30640859e+04 1.33465254e+04 1.34971914e+04 1.31331445e+04 1.29408955e+04 1.29000146e+04 1.33603906e+04 1.37965283e+04 1.30769746e+04 1.26037021e+04 1.29379619e+04 1.31692490e+04 1.33523564e+04 1.31327588e+04 1.27836006e+04 1.26484424e+04 1.28846289e+04 1.35138809e+04 1.31436895e+04 1.23865527e+04 1.26363652e+04 1.28763428e+04 1.28651348e+04 1.30213076e+04 1.27428486e+04 1.23619258e+04 1.26687520e+04 1.29873838e+04 1.26381396e+04 1.23919980e+04 1.23377393e+04 1.23670381e+04 1.26740166e+04 1.29527881e+04 1.25957422e+04 1.20880547e+04 1.23088057e+04 1.25662568e+04 1.23183408e+04 1.21784346e+04 1.21053037e+04 1.22924609e+04 1.26293516e+04 1.23882969e+04 1.18345371e+04 1.17553867e+04 1.18675586e+04 1.20641475e+04 1.21610977e+04 1.19106641e+04 1.18592266e+04 1.21152207e+04 1.24387451e+04 1.20722930e+04 1.14042852e+04 1.14076592e+04 1.17589404e+04 1.18639912e+04 1.17889287e+04 1.15487998e+04 1.14057334e+04 1.16999814e+04 1.16787461e+04 1.13548984e+04 1.13987451e+04 1.14326738e+04 1.13190166e+04 1.15475459e+04 1.14700488e+04 1.11298496e+04 1.10783145e+04 1.10292227e+04 1.10068867e+04 1.13004668e+04 1.14830752e+04 1.10857939e+04 1.06593877e+04 1.08965352e+04 1.11937012e+04 1.09409248e+04 1.06595117e+04 1.05759072e+04 1.05871836e+04 1.08633740e+04 1.09123730e+04 1.05228545e+04 1.03787246e+04 1.04793398e+04 1.06209248e+04 1.05599189e+04 1.04393037e+04 1.03204805e+04 1.03489180e+04 1.04529307e+04 1.01798506e+04 9.92646289e+03 1.00349229e+04 1.00674268e+04 1.01448740e+04 1.03504492e+04 1.00231953e+04 9.63391602e+03 9.80696777e+03 1.00269248e+04 9.84103711e+03 9.71865723e+03 9.53567090e+03 9.43975977e+03 9.87541504e+03 9.92699902e+03 9.38834375e+03 9.18521191e+03 9.46542480e+03 9.66758594e+03 9.37492676e+03 8.99312012e+03 9.05190039e+03 9.33241504e+03 9.43551562e+03 9.05686133e+03 8.87856934e+03 8.99045898e+03 8.87301758e+03 8.91395605e+03 9.06200586e+03 8.79565918e+03 8.68697852e+03 8.86927734e+03 8.89756152e+03 8.54193262e+03 8.44804297e+03 8.38323047e+03 8.37499414e+03 8.46829492e+03 8.79517383e+03 8.63613184e+03 8.08033594e+03 8.16954688e+03 8.45387305e+03 8.12852832e+03 7.91439648e+03 7.91417822e+03 7.98719385e+03 8.24730469e+03 8.08388232e+03 7.69400439e+03 7.62557764e+03 7.64341992e+03 7.73257666e+03 7.79497559e+03 7.62763770e+03 7.57275146e+03 7.66320459e+03 7.69631348e+03 7.41989893e+03 7.22547314e+03 7.22747949e+03 7.20971484e+03 7.23104785e+03 7.39869287e+03 7.37454492e+03 6.96107422e+03 6.92032373e+03 7.08896143e+03 6.99828223e+03 6.83846729e+03 6.76920215e+03 6.78679443e+03 6.94031104e+03 6.87049023e+03 6.59192041e+03 6.47682227e+03 6.48592285e+03 6.47814502e+03 6.55185449e+03 6.38541113e+03 6.34922998e+03 6.38648975e+03 6.39306445e+03 6.41051953e+03 6.12650830e+03 6.00443408e+03 6.09037305e+03 6.01485986e+03 6.09106787e+03 5.97208008e+03 5.71352588e+03 5.85093066e+03 5.95529102e+03 5.74358301e+03 5.63638037e+03 5.62888135e+03 5.63883252e+03 5.59673926e+03 5.42755615e+03 5.54385010e+03 5.51054785e+03 5.32123633e+03 5.40242432e+03 5.21907764e+03 5.20688379e+03 5.29068555e+03 5.06755713e+03 5.06809375e+03 5.09103320e+03 4.97101172e+03 4.79520605e+03 4.78853809e+03 4.99939600e+03 5.03180518e+03 4.68027734e+03 4.61189111e+03 4.73640527e+03 4.66718213e+03 4.63206982e+03 4.48401709e+03 4.40780078e+03 4.44556006e+03 4.47277930e+03 4.42052441e+03 4.26377637e+03 4.20556885e+03 4.23369678e+03 4.26171240e+03 4.10482910e+03 3.97261890e+03 3.96850146e+03 3.92952808e+03 3.96602930e+03 4.04540063e+03 3.91482202e+03 3.71896265e+03 3.69555908e+03 3.79961426e+03 3.81760620e+03 3.58672754e+03 3.61159717e+03 3.65664526e+03 3.46858130e+03 3.46108691e+03 3.36837305e+03 3.35930884e+03 3.46346191e+03 3.34143018e+03 3.20192993e+03 3.28427173e+03 3.24129565e+03 3.09173022e+03 3.11253345e+03 3.11222485e+03 3.06213965e+03 2.92818774e+03 2.86584082e+03 2.93288940e+03 2.94266577e+03 2.84663281e+03 2.74720508e+03 2.71510083e+03 2.75382886e+03 2.75259766e+03 2.60233350e+03 2.54701611e+03 2.54981323e+03 2.57022998e+03 2.52434937e+03 2.39910181e+03 2.38216211e+03 2.41264062e+03 2.38206055e+03 2.28991724e+03 2.28081421e+03 2.25220435e+03 2.16293774e+03 2.21157495e+03 2.20637183e+03 2.06433813e+03 1.97401221e+03 1.98028027e+03 2.00557605e+03 1.98283203e+03 1.92846240e+03 1.85721667e+03 1.82732483e+03 1.86224414e+03 1.83804626e+03 1.73590930e+03 1.69374475e+03 1.70133228e+03 1.72090955e+03 1.64530664e+03 1.56351819e+03 1.56325964e+03 1.53932068e+03 1.50597229e+03 1.47339844e+03 1.45546826e+03 1.42052368e+03 1.36712610e+03 1.35699792e+03 1.34690149e+03 1.30781274e+03 1.24684839e+03 1.22255750e+03 1.22233069e+03 1.19822070e+03 1.15505701e+03 1.12501440e+03 1.10721362e+03 1.11261560e+03 1.08678772e+03 1.01703333e+03 1.00967493e+03 9.95546265e+02 9.64270325e+02 9.26036926e+02 8.95990479e+02 8.96040161e+02 8.70261719e+02 8.27182007e+02 7.86401917e+02 7.87878357e+02 7.90216064e+02 7.57980591e+02 7.34178284e+02 7.05996033e+02 6.89810486e+02 6.56234558e+02 6.15317810e+02 6.16703918e+02 6.10247131e+02 5.86282898e+02 5.66575439e+02 5.33855530e+02 5.17321838e+02 5.11647034e+02 4.99684509e+02 4.86039276e+02 4.55908508e+02 4.29844604e+02 4.08408539e+02 4.02932892e+02 3.99061615e+02 3.77636963e+02 3.58362640e+02 3.29056488e+02 3.21050415e+02 3.18017242e+02 2.96978882e+02 2.86584564e+02 2.69346771e+02 2.53697525e+02 2.48493149e+02 2.29910431e+02 2.15723907e+02 2.11723175e+02 2.00608490e+02 1.82286163e+02 1.67271271e+02 1.60091293e+02 1.51801758e+02 1.46391418e+02 1.39353134e+02 1.25021637e+02 1.13209099e+02 1.03491058e+02 9.80180588e+01 9.33923264e+01 8.38759842e+01 7.42770844e+01 6.64957733e+01 6.08421974e+01 5.61872406e+01 5.11924858e+01 4.51291695e+01 3.91041718e+01 3.45495949e+01 2.96052818e+01 2.46078453e+01 2.12888279e+01 1.80935326e+01 1.50410328e+01 1.23507671e+01 9.33687782e+00 6.98106098e+00 5.32849121e+00 3.92452669e+00 2.73638821e+00 1.85687113e+00 1.36212814e+00 1.20993686e+00 1.39837694e+00 1.93806899e+00 2.79611182e+00 3.97254968e+00 5.41570044e+00 7.41307640e+00 9.64851475e+00 1.18550949e+01 1.49783525e+01 1.85408993e+01 2.21489983e+01 2.59511700e+01 2.95951843e+01 3.45046883e+01 4.02662392e+01 4.57115479e+01 5.12672348e+01 5.49086571e+01 6.06308479e+01 6.90549469e+01 7.77841873e+01 8.59412384e+01 9.18814392e+01 9.88331299e+01 1.04337479e+02 1.15334236e+02 1.29144287e+02 1.35358139e+02 1.43538681e+02 1.53815979e+02 1.62767242e+02 1.71406998e+02 1.83864655e+02 1.98182053e+02 2.11505646e+02 2.24916550e+02 2.31761215e+02 2.38334976e+02 2.56066742e+02 2.73112457e+02 2.88466583e+02 3.04872467e+02 3.11409546e+02 3.26527771e+02 3.40136902e+02 3.57094025e+02 3.84001740e+02 3.91869019e+02 4.03643463e+02 4.17400421e+02 4.24290100e+02 4.50766968e+02 4.92817383e+02 5.03226471e+02 5.02782471e+02 5.29608154e+02 5.41945190e+02 5.45823608e+02 5.80467529e+02 6.11803162e+02 6.28429810e+02 6.50391602e+02 6.50975830e+02 6.72733521e+02 7.15913452e+02 7.43920532e+02 7.83177307e+02 7.83348572e+02 7.68695374e+02 7.88227478e+02 8.41340210e+02 8.81531677e+02 9.01211365e+02 9.14710632e+02 9.01519531e+02 9.47274414e+02 1.01418939e+03 1.01476434e+03 1.03219531e+03 1.04866895e+03 1.07494385e+03 1.12768848e+03 1.12593567e+03 1.14583398e+03 1.23317371e+03 1.26112683e+03 1.25515833e+03 1.25453320e+03 1.24652905e+03 1.30498669e+03 1.38685229e+03 1.45315393e+03 1.45091443e+03 1.40755420e+03 1.42131885e+03 1.50107104e+03 1.57273328e+03 1.57817358e+03 1.59270825e+03 1.59486316e+03 1.63378723e+03 1.71086804e+03 1.76173132e+03 1.79156030e+03 1.79859460e+03 1.84281653e+03 1.85574451e+03 1.83367468e+03 1.90191565e+03 1.97355994e+03 2.01490259e+03 2.08802393e+03 2.04556042e+03 2.02559070e+03 2.12147461e+03 2.19204565e+03 2.27230347e+03 2.27728394e+03 2.21818604e+03 2.23496436e+03 2.34057910e+03 2.46040454e+03 2.49834058e+03 2.45579053e+03 2.45410645e+03 2.49879272e+03 2.52371948e+03 2.57940649e+03 2.67949902e+03 2.74305225e+03 2.72160034e+03 2.69876538e+03 2.72453491e+03 2.81792041e+03 2.93824268e+03 2.99537769e+03 3.02073364e+03 2.95711572e+03 2.90754395e+03 3.02362866e+03 3.15005103e+03 3.25796118e+03 3.26440283e+03 3.16832910e+03 3.14111963e+03 3.28716968e+03 3.47176733e+03 3.43619385e+03 3.48669897e+03 3.47680542e+03 3.42464233e+03 3.57870410e+03 3.65247461e+03 3.66021289e+03 3.68289307e+03 3.78152563e+03 3.81085059e+03 3.78088843e+03 3.85532617e+03 3.92254468e+03 4.03236304e+03 4.05526855e+03 3.97025293e+03 4.05668799e+03 4.03773950e+03 4.18120410e+03 4.42429932e+03 4.37031982e+03 4.22187744e+03 4.24460010e+03 4.32196484e+03 4.50790381e+03 4.68644482e+03 4.59051367e+03 4.47343359e+03 4.62832812e+03 4.74395557e+03 4.74323047e+03 4.84776562e+03 5.04927441e+03 5.53402002e+03 6.44078711e+03 1.04987373e+04 1.52099668e+04 -19072426. 1.44927050e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 34211788. 32195730. -75686432. 2.60199629e+04 1.09023730e+04 9.70402637e+03 8.62444727e+03 8.02172607e+03 7.52299023e+03 7.21733154e+03 7.47444531e+03 7.85621826e+03 7.82515967e+03 7.63597949e+03 7.35253418e+03 7.34033594e+03 7.80574414e+03 8.29403027e+03 8.03080469e+03 7.79063281e+03 7.71146533e+03 7.83198535e+03 8.26074609e+03 8.28273535e+03 7.99194531e+03 7.96335645e+03 8.24860156e+03 8.24137695e+03 8.12711035e+03 8.17676123e+03 8.53065039e+03 8.83704004e+03 8.83152930e+03 8.43562793e+03 8.13507031e+03 8.40839453e+03 8.91591895e+03 9.14299316e+03 8.92328320e+03 8.56633301e+03 8.56313867e+03 8.98071875e+03 9.45066895e+03 9.21369922e+03 8.74567383e+03 8.80822070e+03 9.34803027e+03 9.39427246e+03 9.25758203e+03 9.32513184e+03 9.22933105e+03 9.45440723e+03 9.52671875e+03 9.16570605e+03 9.23390918e+03 9.77005859e+03 1.00100820e+04 9.88275293e+03 9.50244824e+03 9.23795508e+03 9.84547656e+03 1.04879277e+04 1.02062988e+04 9.77732520e+03 9.52984961e+03 9.46820020e+03 1.01030742e+04 1.07143320e+04 1.04215000e+04 1.02807246e+04 1.02055459e+04 1.00241201e+04 1.01965078e+04 1.04989023e+04 1.02747852e+04 1.01901162e+04 1.06273223e+04 1.05201074e+04 1.01328633e+04 1.03493994e+04 1.08963555e+04 1.11529639e+04 1.09778779e+04 1.06987227e+04 1.04574189e+04 1.03827432e+04 1.10071738e+04 1.15971182e+04 1.11842246e+04 1.05809229e+04 1.06102383e+04 1.11101768e+04 1.16144756e+04 1.16151406e+04 1.10926523e+04 1.09829092e+04 1.13715391e+04 1.13631514e+04 1.13122773e+04 1.13965918e+04 1.13761455e+04 1.15690088e+04 1.15617236e+04 1.12733730e+04 1.13754648e+04 1.17548379e+04 1.20201484e+04 1.20500996e+04 1.17390244e+04 1.13881328e+04 1.15056025e+04 1.21744297e+04 1.23456172e+04 1.18575986e+04 1.15038076e+04 1.14402676e+04 1.20478975e+04 1.27996826e+04 1.23812803e+04 1.17388408e+04 1.18454170e+04 1.21654424e+04 1.22021934e+04 1.19983477e+04 1.20772617e+04 1.25284033e+04 1.26860957e+04 1.23876729e+04 1.20131436e+04 1.20360322e+04 1.26893975e+04 1.31144355e+04 1.28629863e+04 1.24668516e+04 1.22489961e+04 1.21118809e+04 1.25774912e+04 1.33162373e+04 1.29699531e+04 1.23272969e+04 1.22732354e+04 1.28793115e+04 1.34548096e+04 1.30714443e+04 1.26981914e+04 1.26963896e+04 1.28958916e+04 1.30874453e+04 1.30654463e+04 1.27419717e+04 1.26014482e+04 1.31664756e+04 1.34318105e+04 1.29693203e+04 1.27263496e+04 1.29653359e+04 1.33534404e+04 1.36996318e+04 1.34706387e+04 1.26941875e+04 1.28306660e+04 1.34511074e+04 1.35375459e+04 1.33295059e+04 1.31227061e+04 1.30951025e+04 1.32539922e+04 1.35444863e+04 1.33636738e+04 1.31078916e+04 1.35383496e+04 1.38630439e+04 1.35516865e+04 1.31707041e+04 1.31965098e+04 1.35717061e+04 1.40112412e+04 1.40334824e+04 1.35846963e+04 1.31271621e+04 1.30341504e+04 1.36767070e+04 1.43953555e+04 1.39328545e+04 1.31688916e+04 1.31535430e+04 1.36650508e+04 1.41252705e+04 1.40690752e+04 1.37129316e+04 1.35448281e+04 1.36371240e+04 1.35873447e+04 1.36644404e+04 1.38568652e+04 1.37880557e+04 1.38600195e+04 1.38389697e+04 1.35124492e+04 1.35972207e+04 1.39984834e+04 1.41732070e+04 1.41168154e+04 1.35142705e+04 1.32032529e+04 1.39403682e+04 1.45439346e+04 1.42755898e+04 1.38592217e+04 1.34676689e+04 1.32650889e+04 1.39992373e+04 1.47804453e+04 1.43838857e+04 1.35734053e+04 1.33891504e+04 1.38848555e+04 1.41601436e+04 1.41214990e+04 1.40961211e+04 1.39508311e+04 1.38309609e+04 1.36661719e+04 1.33390684e+04 1.35433682e+04 1.39082891e+04 1.41235996e+04 1.46386650e+04 1.43020840e+04 1.33683145e+04 1.32471846e+04 1.37997529e+04 1.43282334e+04 1.41888984e+04 1.38245225e+04 1.41514844e+04 1.43136807e+04 1.37010498e+04 1.31947510e+04 1.34746025e+04 1.41774492e+04 1.46124473e+04 1.43389658e+04 1.35788838e+04 1.31037783e+04 1.33884238e+04 1.41982510e+04 1.46601123e+04 1.42725674e+04 1.34320811e+04 1.34266133e+04 1.43112139e+04 1.42145537e+04 1.35405156e+04 1.35483135e+04 1.36570928e+04 1.36550898e+04 1.41313799e+04 1.38267363e+04 1.33513164e+04 1.36192988e+04 1.33156963e+04 1.37158545e+04 1.40971592e+04 1.33087148e+04 1.35689170e+04 1.39870195e+04 1.36646631e+04 1.35961924e+04 1.35758115e+04 1.36179385e+04 1.36879004e+04 1.35872666e+04 1.31674473e+04 1.31611494e+04 1.38024170e+04 1.41493799e+04 1.38103193e+04 1.31701748e+04 1.28583301e+04 1.31643682e+04 1.37264521e+04 1.39554492e+04 1.36594180e+04 1.29938408e+04 1.30554473e+04 1.34219463e+04 1.32473164e+04 1.32700820e+04 1.32572275e+04 1.31325840e+04 1.31293271e+04 1.36385693e+04 1.32530488e+04 1.27432656e+04 1.30491709e+04 1.27334463e+04 1.32405332e+04 1.33526641e+04 1.28719541e+04 1.35066777e+04 1.30328955e+04 1.24418291e+04 1.28795332e+04 1.26147539e+04 1.27715479e+04 1.36230430e+04 1.29558066e+04 1.21864395e+04 1.23582305e+04 1.28872793e+04 1.34801641e+04 1.31096816e+04 1.23399111e+04 1.19963438e+04 1.22121113e+04 1.27904014e+04 1.31971514e+04 1.29285176e+04 1.22889365e+04 1.21148877e+04 1.24026504e+04 1.25701250e+04 1.23505615e+04 1.21700020e+04 1.22362510e+04 1.22701865e+04 1.25650996e+04 1.25375352e+04 1.19546924e+04 1.18578164e+04 1.19354873e+04 1.19805605e+04 1.21447627e+04 1.20083945e+04 1.22791436e+04 1.20601025e+04 1.15237627e+04 1.17551582e+04 1.14974619e+04 1.17644727e+04 1.25058838e+04 1.18326445e+04 1.10834053e+04 1.13015391e+04 1.18247490e+04 1.20712930e+04 1.20832891e+04 1.13922227e+04 1.08658711e+04 1.10821523e+04 1.15891914e+04 1.20253076e+04 1.16363691e+04 1.09109570e+04 1.08468350e+04 1.11461729e+04 1.12992783e+04 1.16140996e+04 1.15299795e+04 1.07831689e+04 1.06404531e+04 1.11068184e+04 1.12014268e+04 1.07832383e+04 1.06350537e+04 1.08145186e+04 1.06746152e+04 1.09588330e+04 1.10240596e+04 1.03795811e+04 1.03255615e+04 1.05997031e+04 1.05245928e+04 1.04917705e+04 1.03123916e+04 1.05072842e+04 1.06965986e+04 1.03752061e+04 1.00463076e+04 9.80005664e+03 1.01480840e+04 1.06227002e+04 1.04342109e+04 9.84806836e+03 9.52096484e+03 9.83157812e+03 1.03578760e+04 1.00309785e+04 9.47140527e+03 9.54267969e+03 9.76352832e+03 9.95425195e+03 1.01687041e+04 9.89554004e+03 9.31462402e+03 9.01256641e+03 9.24748242e+03 9.73342676e+03 9.68568164e+03 9.28132422e+03 9.25852441e+03 9.21722754e+03 9.41828906e+03 9.25820215e+03 9.00213770e+03 8.93594922e+03 8.68338379e+03 9.04869531e+03 9.28202246e+03 8.83913281e+03 8.83280078e+03 8.84570020e+03 8.94342480e+03 8.69159277e+03 8.26518066e+03 8.56741504e+03 8.93219824e+03 8.68304492e+03 8.17712500e+03 8.23929688e+03 8.65862793e+03 8.54681738e+03 8.30985938e+03 8.29067578e+03 7.91601953e+03 7.87930078e+03 8.33876953e+03 8.24931641e+03 7.87085742e+03 7.64153711e+03 7.57660400e+03 7.87956738e+03 8.16054932e+03 7.77251465e+03 7.56601172e+03 7.66745312e+03 7.54676807e+03 7.80594043e+03 7.77240479e+03 7.24911182e+03 7.18136914e+03 7.29737109e+03 7.26565039e+03 7.24763184e+03 7.18649902e+03 7.35312695e+03 7.16458203e+03 6.89456641e+03 6.89946631e+03 6.75827100e+03 6.95825146e+03 7.32315527e+03 7.04882471e+03 6.58095801e+03 6.49468750e+03 6.66213818e+03 6.72961475e+03 7.22108643e+03 7.49478564e+03 6.93368750e+03 7.94667139e+03 1.54222744e+04 1.49342234e+05 -15572058. 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. 0. 0. 0. 0. 0. 0. -41762548. 3721477. 8.67639062e+03 1.34971621e+04 7.34091748e+03 5.76343066e+03 5.78464990e+03 4.59440137e+03 4.27402588e+03 4.33273193e+03 4.25005176e+03 4.10674902e+03 4.15597559e+03 4.09274561e+03 3.99602368e+03 3.96808813e+03 3.91501074e+03 3.87098584e+03 3.82476685e+03 3.79875293e+03 3.73669214e+03 3.61405835e+03 3.57418628e+03 3.67821973e+03 3.62889868e+03 3.44100732e+03 3.40047559e+03 3.54888013e+03 3.50606470e+03 3.36108887e+03 3.31495850e+03 3.26220093e+03 3.23952710e+03 3.19426489e+03 3.14696582e+03 3.11377173e+03 3.04637769e+03 2.96535889e+03 2.92972412e+03 3.00762427e+03 2.97757495e+03 2.85893848e+03 2.83094507e+03 2.79898975e+03 2.76837695e+03 2.71272900e+03 2.67141089e+03 2.63501489e+03 2.53241187e+03 2.49442456e+03 2.50253198e+03 2.46393848e+03 2.51892529e+03 2.49449927e+03 2.38732007e+03 2.27550195e+03 2.21474927e+03 2.33545068e+03 2.32096045e+03 2.19351001e+03 2.12056030e+03 2.11135620e+03 2.07670044e+03 2.01410327e+03 2.08006665e+03 2.03512305e+03 1.88005969e+03 1.84000513e+03 1.90561353e+03 1.94053137e+03 1.85596729e+03 1.79116199e+03 1.76903699e+03 1.71512439e+03 1.67152478e+03 1.65683276e+03 1.63923499e+03 1.60220764e+03 1.54090332e+03 1.50442957e+03 1.50530835e+03 1.47520667e+03 1.47711340e+03 1.43137683e+03 1.35594202e+03 1.35309973e+03 1.32961572e+03 1.32685547e+03 1.30479321e+03 1.24914246e+03 1.21678381e+03 1.16726196e+03 1.11393555e+03 1.14219958e+03 1.13316650e+03 1.04748987e+03 1.03126611e+03 1.06450964e+03 1.06226331e+03 1.00797833e+03 9.54775208e+02 9.26983704e+02 9.06270142e+02 8.72477234e+02 8.47745728e+02 8.41143311e+02 8.14264709e+02 8.05359924e+02 7.75266907e+02 7.37153748e+02 7.28684692e+02 6.88325867e+02 6.78972961e+02 6.94841187e+02 6.60327026e+02 6.22879578e+02 5.87030151e+02 5.65314575e+02 5.78830322e+02 5.61992493e+02 5.24415466e+02 4.93149078e+02 4.76204071e+02 4.71509796e+02 4.52108154e+02 4.47330933e+02 4.34938324e+02 4.04189575e+02 3.80827667e+02 3.66813141e+02 3.65045166e+02 3.48530304e+02 3.25452637e+02 3.05308807e+02 2.91520233e+02 2.84986481e+02 2.63741150e+02 2.53517700e+02 2.56059326e+02 2.39381073e+02 2.20616714e+02 2.02148575e+02 1.89897949e+02 1.90694290e+02 1.79957565e+02 1.64000198e+02 1.49061081e+02 1.38257080e+02 1.33765396e+02 1.24410332e+02 1.15011658e+02 1.04002480e+02 9.75472946e+01 9.36031113e+01 8.36594467e+01 7.70850830e+01 7.05210114e+01 6.24533463e+01 5.48155327e+01 4.89720497e+01 4.45986748e+01 3.93295441e+01 3.45488892e+01 2.89718647e+01 2.50949097e+01 2.26760159e+01 1.81644249e+01 1.44290924e+01 1.19331446e+01 9.41956139e+00 7.42028856e+00 5.44640923e+00 3.81345153e+00 2.73286319e+00 1.89280450e+00 1.37611580e+00 1.20950234e+00 1.38296366e+00 1.89115942e+00 2.74068475e+00 3.97100949e+00 5.41459560e+00 7.36489296e+00 1.00356607e+01 1.24763813e+01 1.47961712e+01 1.74212399e+01 2.15471535e+01 2.69691219e+01 3.07539062e+01 3.45153885e+01 3.87744637e+01 4.35773964e+01 5.03106117e+01 5.63218536e+01 6.39163208e+01 6.95087357e+01 7.40161743e+01 8.33095169e+01 9.14175415e+01 1.00936829e+02 1.08629868e+02 1.15021721e+02 1.23329277e+02 1.31821838e+02 1.44190369e+02 1.50728546e+02 1.63259430e+02 1.83542267e+02 1.90193787e+02 1.96677170e+02 2.03127411e+02 2.13538422e+02 2.37966003e+02 2.52604630e+02 2.59186249e+02 2.63815308e+02 2.76610229e+02 3.00086945e+02 3.14495850e+02 3.37018494e+02 3.50623016e+02 3.57232788e+02 3.61594299e+02 3.76164032e+02 4.16795593e+02 4.30639832e+02 4.35799347e+02 4.45739380e+02 4.61069855e+02 5.03175262e+02 5.24591858e+02 5.16209229e+02 5.30215942e+02 5.77368225e+02 5.99413208e+02 5.88700562e+02 6.06778564e+02 6.58984375e+02 6.81107361e+02 6.82215576e+02 6.88278992e+02 7.06887268e+02 7.71973511e+02 7.90024597e+02 7.85873718e+02 8.06801636e+02 8.25039185e+02 8.62514893e+02 8.91400696e+02 9.08097473e+02 9.07260559e+02 9.51300415e+02 1.01817426e+03 1.01893719e+03 1.04988354e+03 1.08543115e+03 1.09206860e+03 1.11863647e+03 1.13894080e+03 1.15845325e+03 1.16260754e+03 1.18646667e+03 1.23964404e+03 1.27599817e+03 1.34385376e+03 1.33060071e+03 1.31841870e+03 1.39076196e+03 1.42801965e+03 1.49097473e+03 1.49590515e+03 1.48931738e+03 1.52886121e+03 1.54352930e+03 1.59842175e+03 1.63719507e+03 1.70240234e+03 1.71770288e+03 1.70063977e+03 1.74171460e+03 1.72686035e+03 1.82036841e+03 1.96373315e+03 1.94456165e+03 1.91951990e+03 1.90968152e+03 1.91411462e+03 2.04392505e+03 2.14678101e+03 2.12664868e+03 2.07479907e+03 2.10213574e+03 2.20354102e+03 2.22917163e+03 2.31394263e+03 2.32663550e+03 2.30300977e+03 2.37288428e+03 2.40666821e+03 2.51375122e+03 2.54533154e+03 2.45095557e+03 2.50246777e+03 2.67223682e+03 2.66050073e+03 2.56439673e+03 2.69930542e+03 2.87606714e+03 2.86275220e+03 2.82838062e+03 2.80700708e+03 2.84356177e+03 3.03359131e+03 3.06846997e+03 3.03298608e+03 2.99309399e+03 3.01339966e+03 3.15441455e+03 3.21738721e+03 3.23228906e+03 3.19379663e+03 3.31278589e+03 3.45677490e+03 3.40709473e+03 3.50562109e+03 3.50157593e+03 3.44430127e+03 3.56718164e+03 3.62006665e+03 3.67566919e+03 3.69001636e+03 3.68685156e+03 3.64973462e+03 3.81055127e+03 4.09796289e+03 3.91647046e+03 3.77210620e+03 3.92523608e+03 4.11979883e+03 4.27516650e+03 4.21226562e+03 4.11962988e+03 4.27549023e+03 4.31366455e+03 4.20123584e+03 4.18307910e+03 4.49315137e+03 4.53168164e+03 4.43583203e+03 4.49540820e+03 4.37182812e+03 4.58178174e+03 4.92787988e+03 4.81510400e+03 4.75027539e+03 4.66323730e+03 4.63822607e+03 4.96180371e+03 5.25787793e+03 5.17063379e+03 4.93520020e+03 4.95078174e+03 5.09752344e+03 5.20918994e+03 5.37379590e+03 5.28943701e+03 5.16386719e+03 5.40919873e+03 5.40613672e+03 5.58745801e+03 5.58834521e+03 5.44877881e+03 5.65264551e+03 5.70510010e+03 5.69740625e+03 5.58564307e+03 5.72871680e+03 6.07479102e+03 6.07908984e+03 5.86332910e+03 5.76996191e+03 5.96259570e+03 6.33668457e+03 6.34882910e+03 6.16985352e+03 6.06383789e+03 6.09082178e+03 6.31028125e+03 6.43234570e+03 6.44064941e+03 6.30336963e+03 6.50132080e+03 6.76179688e+03 6.62500977e+03 6.80190137e+03 6.86300879e+03 6.70756445e+03 6.78249414e+03 6.83844971e+03 6.88747217e+03 6.94934521e+03 6.93500781e+03 6.92897021e+03 7.29977393e+03 7.32457031e+03 6.99571387e+03 7.03681982e+03 7.23146143e+03 7.41969434e+03 7.78983398e+03 7.55474072e+03 7.17917090e+03 7.55544287e+03 7.95944092e+03 7.80660547e+03 7.49799805e+03 7.55833887e+03 7.69269482e+03 7.83184229e+03 7.88651660e+03 7.72308691e+03 7.94921436e+03 8.38698535e+03 8.24854004e+03 8.11624902e+03 7.96077002e+03 8.05492285e+03 8.58668262e+03 8.51958203e+03 8.34338281e+03 8.27183984e+03 7.99863184e+03 8.23763379e+03 8.75877441e+03 9.14707812e+03 8.67281055e+03 8.33343262e+03 8.62730078e+03 8.81470801e+03 9.18439062e+03 9.07305566e+03 8.76361328e+03 9.01889941e+03 9.04641504e+03 8.95515332e+03 8.86439844e+03 9.09754199e+03 9.51768164e+03 9.41161523e+03 9.30453809e+03 9.21956641e+03 9.21200098e+03 9.69902051e+03 9.76278125e+03 9.57256641e+03 9.35532910e+03 9.28538574e+03 9.60195801e+03 9.65851660e+03 1.00436982e+04 1.01788701e+04 9.74263184e+03 9.53994043e+03 9.94342676e+03 1.04109248e+04 1.01475000e+04 9.96795020e+03 1.00130264e+04 1.00787422e+04 1.00623428e+04 9.88902832e+03 1.03472041e+04 1.05403633e+04 1.02708809e+04 1.05645488e+04 1.07201807e+04 1.06063096e+04 1.06427295e+04 1.05968789e+04 1.06177051e+04 1.04125605e+04 1.03155049e+04 1.08193457e+04 1.11108906e+04 1.07296279e+04 1.03237861e+04 1.07134609e+04 1.13993330e+04 1.14802939e+04 1.08874414e+04 1.05405850e+04 1.11713027e+04 1.16058350e+04 1.13515576e+04 1.13179180e+04 1.10158008e+04 1.06304590e+04 1.11172891e+04 1.18228730e+04 1.19040049e+04 1.12805010e+04 1.08978145e+04 1.16233438e+04 1.21505078e+04 1.18212754e+04 1.12724600e+04 1.10532305e+04 1.14768105e+04 1.17079297e+04 1.20440332e+04 1.22557100e+04 1.18703652e+04 1.16505850e+04 1.17006982e+04 1.22263164e+04 1.20187646e+04 1.17001875e+04 1.22122910e+04 1.22260303e+04 1.21722354e+04 1.19031523e+04 1.19038613e+04 1.26357969e+04 1.22925537e+04 1.17171084e+04 1.20260801e+04 1.25787207e+04 1.26487119e+04 1.23923711e+04 1.26879336e+04 1.28049746e+04 1.25167832e+04 1.22076719e+04 1.21455000e+04 1.28591816e+04 1.26605352e+04 1.23014453e+04 1.27332637e+04 1.27287451e+04 1.26548926e+04 1.25569795e+04 1.28555322e+04 1.30149883e+04 1.27071367e+04 1.29087656e+04 1.29995830e+04 1.30889219e+04 1.30930264e+04 1.29786787e+04 1.27695898e+04 1.24311768e+04 1.25208643e+04 1.32238662e+04 1.38890391e+04 1.31561348e+04 1.23497949e+04 1.28878779e+04 1.36864131e+04 1.38334248e+04 1.31211514e+04 1.25692939e+04 1.32720020e+04 1.35631143e+04 1.31601055e+04 1.37091055e+04 1.34497832e+04 1.27162090e+04 1.30972598e+04 1.38740742e+04 1.39319434e+04 1.32275723e+04 1.27393506e+04 1.33515596e+04 1.42369688e+04 1.38939678e+04 1.31816094e+04 1.28698799e+04 1.35342803e+04 1.40638037e+04 1.36504814e+04 1.34754736e+04 1.35430547e+04 1.36664580e+04 1.36361289e+04 1.39738154e+04 1.37663174e+04 1.32715801e+04 1.35928232e+04 1.37489971e+04 1.40612266e+04 1.37111084e+04 1.33584395e+04 1.39904385e+04 1.35882559e+04 1.32416553e+04 1.38400273e+04 1.41010039e+04 1.40674189e+04 1.38340283e+04 1.42151006e+04 1.42902812e+04 1.36723633e+04 1.33335928e+04 1.34064209e+04 1.43990625e+04 1.40393926e+04 1.33742324e+04 1.58842969e+04 2.24587559e+04 8.23529375e+04 4.95441869e+09 0. 0. 0. 0. 0. 0. 0. 0. -3.16716155e+10 5.45351500e+05 5.45351500e+05 1.54504528e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.89811098e+09 3.55959312e+05 5.70828555e+04 2.90544590e+04 1.87004062e+04 1.54730234e+04 1.47425918e+04 1.40187295e+04 1.44500664e+04 1.45177764e+04 1.43028398e+04 1.43172471e+04 1.41319502e+04 1.36846182e+04 1.40589619e+04 1.45475527e+04 1.40794961e+04 1.38994268e+04 1.41659717e+04 1.43201924e+04 1.43899316e+04 1.39413438e+04 1.35327217e+04 1.38052832e+04 1.41706289e+04 1.41957881e+04 1.40314541e+04 1.37445156e+04 1.38053008e+04 1.42742715e+04 1.45081445e+04 1.40678926e+04 1.34608838e+04 1.36055938e+04 1.40475742e+04 1.38993135e+04 1.38511973e+04 1.39187061e+04 1.35082354e+04 1.37472461e+04 1.40711406e+04 1.35111553e+04 1.34157598e+04 1.38344697e+04 1.43661055e+04 1.44265820e+04 1.34098564e+04 1.29481895e+04 1.33078037e+04 1.38362422e+04 1.40529209e+04 1.34614336e+04 1.33938789e+04 1.38200088e+04 1.36480488e+04 1.36055566e+04 1.33931211e+04 1.29614570e+04 1.34053730e+04 1.38292510e+04 1.33298984e+04 1.32475420e+04 1.34959639e+04 1.32159863e+04 1.34360664e+04 1.35409111e+04 1.30461504e+04 1.29092490e+04 1.31675205e+04 1.35941963e+04 1.34961162e+04 1.29250332e+04 1.30042109e+04 1.29461025e+04 1.30643252e+04 1.33664209e+04 1.28270312e+04 1.26655664e+04 1.29822842e+04 1.32454463e+04 1.32502773e+04 1.27709951e+04 1.23565713e+04 1.24881914e+04 1.28418516e+04 1.29692012e+04 1.29441924e+04 1.26687207e+04 1.24922324e+04 1.27320010e+04 1.29358730e+04 1.25610742e+04 1.21132314e+04 1.23010205e+04 1.26835205e+04 1.27709609e+04 1.24860127e+04 1.21165439e+04 1.19635098e+04 1.23466982e+04 1.25152197e+04 1.20703369e+04 1.20130225e+04 1.23352373e+04 1.25746670e+04 1.25034600e+04 1.17980312e+04 1.14785049e+04 1.18795928e+04 1.20424062e+04 1.19654375e+04 1.18118604e+04 1.18670078e+04 1.20362471e+04 1.17176865e+04 1.16344238e+04 1.18208193e+04 1.15651748e+04 1.13950742e+04 1.16733076e+04 1.17273789e+04 1.16873115e+04 1.14677227e+04 1.11001152e+04 1.11285303e+04 1.14504775e+04 1.15474287e+04 1.13018398e+04 1.10701338e+04 1.11083740e+04 1.13661104e+04 1.14332734e+04 1.10171895e+04 1.06030996e+04 1.07201084e+04 1.10181475e+04 1.10158516e+04 1.08319551e+04 1.06940264e+04 1.06744688e+04 1.08506680e+04 1.08989883e+04 1.06687363e+04 1.05681953e+04 1.04012002e+04 1.04775117e+04 1.03949443e+04 1.02362246e+04 1.03045596e+04 1.03143496e+04 1.04542031e+04 1.05601982e+04 1.01310352e+04 9.86631055e+03 9.97618066e+03 1.01218369e+04 1.02166211e+04 1.00901143e+04 9.60511230e+03 9.59360742e+03 9.98584668e+03 1.01799443e+04 9.73451465e+03 9.37121191e+03 9.47157324e+03 9.77704199e+03 9.70364453e+03 9.18141992e+03 9.15653027e+03 9.45917188e+03 9.45271387e+03 9.24770508e+03 9.35082422e+03 9.30949609e+03 8.90207422e+03 9.09807129e+03 9.31138867e+03 8.87252246e+03 8.79556934e+03 8.90539844e+03 8.99414258e+03 9.01192188e+03 8.77861719e+03 8.39327344e+03 8.42641797e+03 8.70578125e+03 8.92996582e+03 8.82866699e+03 8.30525684e+03 8.31161523e+03 8.60540723e+03 8.42876562e+03 8.03667920e+03 8.02022021e+03 8.13428467e+03 8.28991016e+03 8.31755762e+03 8.20358691e+03 7.90446826e+03 7.66452490e+03 7.86655176e+03 7.99594824e+03 7.70611084e+03 7.67621484e+03 7.78324561e+03 7.79992676e+03 7.80578271e+03 7.49436572e+03 7.23085986e+03 7.31546387e+03 7.35922852e+03 7.55597852e+03 7.50594678e+03 7.11434326e+03 7.04330273e+03 7.19564209e+03 7.24267725e+03 7.16069922e+03 6.85844482e+03 6.82837793e+03 6.98396484e+03 6.97446436e+03 6.87626904e+03 6.65964160e+03 6.53763086e+03 6.64389990e+03 6.76830273e+03 6.52168408e+03 6.49260742e+03 6.53842041e+03 6.49677344e+03 6.52735645e+03 6.27843457e+03 6.08765771e+03 6.16892285e+03 6.16788721e+03 6.19670605e+03 5.98457129e+03 5.81051611e+03 5.98280957e+03 6.10979053e+03 5.95712256e+03 5.78832715e+03 5.76633203e+03 5.62981104e+03 5.60475928e+03 5.68701416e+03 5.82451709e+03 5.58239941e+03 5.37189062e+03 5.48006592e+03 5.36715137e+03 5.37643750e+03 5.29866748e+03 5.11062646e+03 5.17835938e+03 5.25543896e+03 5.00730127e+03 4.92278027e+03 4.96683594e+03 5.07018262e+03 5.06818164e+03 4.77017334e+03 4.68534766e+03 4.76880615e+03 4.76490723e+03 4.79028467e+03 4.58487598e+03 4.54324170e+03 4.45602246e+03 4.44032812e+03 4.54621045e+03 4.44334619e+03 4.24767139e+03 4.28591455e+03 4.38606006e+03 4.19858203e+03 4.10998828e+03 4.04374512e+03 3.99560059e+03 4.10195801e+03 4.11181641e+03 3.94312646e+03 3.82196851e+03 3.83459473e+03 3.85988062e+03 3.86719263e+03 3.70565820e+03 3.72019019e+03 3.70293506e+03 3.49569800e+03 3.49149194e+03 3.48501172e+03 3.44785327e+03 3.47083325e+03 3.38278564e+03 3.33249805e+03 3.37185352e+03 3.25420093e+03 3.14677197e+03 3.17450757e+03 3.18883789e+03 3.13796240e+03 2.99128564e+03 2.92976001e+03 3.02900098e+03 3.03185571e+03 2.86508203e+03 2.78124902e+03 2.78729028e+03 2.81819580e+03 2.80882764e+03 2.66625415e+03 2.62696313e+03 2.58079419e+03 2.59296729e+03 2.59715527e+03 2.46773975e+03 2.44174609e+03 2.42348096e+03 2.37400952e+03 2.37115942e+03 2.37481250e+03 2.27448145e+03 2.17817407e+03 2.25425806e+03 2.28620117e+03 2.12532056e+03 2.01143872e+03 2.02282507e+03 2.06429932e+03 2.02764075e+03 1.94798645e+03 1.89419373e+03 1.87971484e+03 1.89800244e+03 1.86783191e+03 1.78239209e+03 1.74480859e+03 1.71548145e+03 1.71809314e+03 1.68792432e+03 1.60670093e+03 1.59522888e+03 1.56248303e+03 1.52919971e+03 1.52468042e+03 1.49442590e+03 1.43474890e+03 1.39377087e+03 1.40042334e+03 1.37730078e+03 1.32438867e+03 1.28060681e+03 1.26037427e+03 1.25959485e+03 1.23234265e+03 1.16320801e+03 1.13830505e+03 1.13159216e+03 1.13789844e+03 1.11408569e+03 1.04616614e+03 1.04473267e+03 1.00856995e+03 9.48026733e+02 9.31924500e+02 9.20950928e+02 9.28536926e+02 8.97052002e+02 8.33914124e+02 8.03205322e+02 8.06057495e+02 8.08081238e+02 7.81795715e+02 7.48853638e+02 7.19647827e+02 6.91199463e+02 6.64238281e+02 6.41729614e+02 6.42303711e+02 6.29145325e+02 5.86396606e+02 5.67894104e+02 5.52729004e+02 5.38123108e+02 5.27307007e+02 5.04726105e+02 4.93943573e+02 4.65014435e+02 4.30730225e+02 4.17146057e+02 4.13711578e+02 4.07431366e+02 3.92216187e+02 3.66105072e+02 3.34299194e+02 3.25120941e+02 3.18436890e+02 3.02842682e+02 2.97187744e+02 2.81005646e+02 2.56689667e+02 2.51589355e+02 2.39551834e+02 2.22050766e+02 2.13083420e+02 1.99160141e+02 1.85027908e+02 1.73668701e+02 1.64796738e+02 1.55478989e+02 1.49541275e+02 1.43159271e+02 1.27501503e+02 1.13618309e+02 1.05681313e+02 9.99016953e+01 9.47922363e+01 8.66020432e+01 7.55763245e+01 6.78541870e+01 6.28444939e+01 5.81664314e+01 5.25195580e+01 4.54944229e+01 3.98531952e+01 3.48513374e+01 3.00240974e+01 2.55959949e+01 2.21404095e+01 1.87500229e+01 1.53006191e+01 1.24311314e+01 9.53166294e+00 7.31623316e+00 5.57817841e+00 4.03299665e+00 2.84900451e+00 1.96259856e+00 1.44935513e+00 1.29446471e+00 1.48596680e+00 2.03648305e+00 2.93752527e+00 4.11830711e+00 5.51543140e+00 7.51104498e+00 9.89381504e+00 1.23218880e+01 1.56015787e+01 1.91914577e+01 2.22670898e+01 2.60228691e+01 3.06161785e+01 3.59220581e+01 4.13555260e+01 4.62576103e+01 5.20394630e+01 5.61576347e+01 6.21433716e+01 7.08800735e+01 7.87784576e+01 8.74596329e+01 9.48315964e+01 1.00502701e+02 1.06801460e+02 1.17815155e+02 1.30983353e+02 1.39295609e+02 1.47039734e+02 1.56915375e+02 1.64555313e+02 1.76471664e+02 1.91342056e+02 2.02014954e+02 2.14844986e+02 2.24379486e+02 2.33717926e+02 2.47214539e+02 2.66848572e+02 2.81232574e+02 2.92294037e+02 3.09873657e+02 3.15152435e+02 3.32651855e+02 3.53448730e+02 3.64923889e+02 3.90823242e+02 4.00940063e+02 4.03621429e+02 4.21517639e+02 4.39281189e+02 4.68885620e+02 5.08494537e+02 5.14783569e+02 5.09719635e+02 5.27016479e+02 5.47002502e+02 5.64945068e+02 6.02909485e+02 6.31165710e+02 6.32003479e+02 6.49024597e+02 6.67360962e+02 6.99509888e+02 7.40074585e+02 7.51548523e+02 7.93133179e+02 7.96568970e+02 7.75329651e+02 8.12223328e+02 8.64624207e+02 9.02063965e+02 9.36023254e+02 9.30438293e+02 9.08260132e+02 9.64968628e+02 1.03775330e+03 1.04528076e+03 1.05770642e+03 1.08023047e+03 1.08652563e+03 1.13727283e+03 1.17167993e+03 1.18092358e+03 1.25094275e+03 1.25985339e+03 1.26424292e+03 1.30173218e+03 1.29874988e+03 1.34141553e+03 1.40713074e+03 1.47498145e+03 1.46652051e+03 1.41645093e+03 1.46544824e+03 1.55023120e+03 1.60758057e+03 1.62558228e+03 1.61022791e+03 1.62327942e+03 1.68738464e+03 1.75636475e+03 1.79932312e+03 1.82063757e+03 1.83713416e+03 1.85518677e+03 1.88909705e+03 1.92036743e+03 1.95517236e+03 2.01227100e+03 2.04766138e+03 2.09679321e+03 2.08131055e+03 2.09770215e+03 2.19864624e+03 2.22515137e+03 2.31384326e+03 2.30833765e+03 2.23580127e+03 2.29315112e+03 2.39038940e+03 2.49942188e+03 2.56919043e+03 2.50411475e+03 2.46917456e+03 2.54119604e+03 2.62424268e+03 2.67302197e+03 2.72009155e+03 2.76075195e+03 2.73405908e+03 2.73695801e+03 2.82429712e+03 2.92537671e+03 3.01203003e+03 3.00809937e+03 3.06696753e+03 3.03090942e+03 2.97009326e+03 3.08649121e+03 3.19213013e+03 3.30873535e+03 3.34678662e+03 3.22484521e+03 3.21397144e+03 3.36294556e+03 3.55208496e+03 3.54037500e+03 3.53155957e+03 3.54259424e+03 3.48989355e+03 3.63592969e+03 3.77037158e+03 3.73259131e+03 3.77141528e+03 3.81208545e+03 3.86534668e+03 3.90820972e+03 3.95540234e+03 4.03567285e+03 4.07761035e+03 4.09578027e+03 4.04975537e+03 4.14162158e+03 4.22604004e+03 4.27367676e+03 4.47897070e+03 4.40147998e+03 4.28611475e+03 4.39402930e+03 4.37628613e+03 4.58107324e+03 4.82824951e+03 4.77585693e+03 4.56030518e+03 4.56675635e+03 4.80720215e+03 4.93244531e+03 4.87914844e+03 5.19841992e+03 5.47794336e+03 6.73929932e+03 7.61790479e+03 1.35825029e+04 5.30832734e+04 1.44927050e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 95078592. 1.04636164e+05 2.10432832e+04 1.40554795e+04 9.79732910e+03 8.98763770e+03 7.73172314e+03 7.65818896e+03 7.67323242e+03 7.66573584e+03 7.32341846e+03 7.54487451e+03 8.00328174e+03 8.03371045e+03 7.67146582e+03 7.42078613e+03 7.59589355e+03 8.09128662e+03 8.38057910e+03 8.12382568e+03 7.89941797e+03 7.83841357e+03 8.01340576e+03 8.48124219e+03 8.52058691e+03 8.21244238e+03 8.15263086e+03 8.23397070e+03 8.40807715e+03 8.48372559e+03 8.39201074e+03 8.50929102e+03 8.85070703e+03 9.06457422e+03 8.69718066e+03 8.31620215e+03 8.58413672e+03 9.06111523e+03 9.40494531e+03 9.07611914e+03 8.67383008e+03 8.71861621e+03 9.25653223e+03 9.63744141e+03 9.37040137e+03 8.84786133e+03 8.93975098e+03 9.38309570e+03 9.68391016e+03 9.75022266e+03 9.59257910e+03 9.38226758e+03 9.40769336e+03 9.78553027e+03 9.52084668e+03 9.44557715e+03 9.98618848e+03 1.00563301e+04 1.00515928e+04 9.72964453e+03 9.44683398e+03 1.00207236e+04 1.06537793e+04 1.04137969e+04 9.83909961e+03 9.60702832e+03 9.83808301e+03 1.04873271e+04 1.08782334e+04 1.06023467e+04 1.04428457e+04 1.03334482e+04 1.01072148e+04 1.04339395e+04 1.08304404e+04 1.05374238e+04 1.05499316e+04 1.06798135e+04 1.08402666e+04 1.06517686e+04 1.05704072e+04 1.09650879e+04 1.12241729e+04 1.12463535e+04 1.09727871e+04 1.05552910e+04 1.06507314e+04 1.13075566e+04 1.18437227e+04 1.13840625e+04 1.07218262e+04 1.09013486e+04 1.13451670e+04 11700. 1.18060957e+04 1.14126201e+04 1.13355195e+04 1.14010293e+04 1.15992676e+04 1.18053184e+04 1.16368799e+04 1.16080576e+04 1.16168516e+04 1.17790781e+04 1.18532822e+04 1.17239189e+04 1.19193213e+04 1.20873633e+04 1.22669707e+04 1.19688691e+04 1.14823750e+04 1.17599102e+04 1.23998643e+04 1.27121035e+04 1.21761807e+04 1.16087451e+04 1.16951143e+04 1.24320596e+04 1.31383916e+04 1.25721289e+04 1.19485508e+04 1.22318389e+04 1.22669268e+04 1.23992871e+04 1.25746748e+04 1.24306260e+04 1.26889570e+04 1.26189062e+04 1.25859688e+04 1.26462676e+04 1.23781455e+04 1.27316436e+04 1.32423975e+04 1.31903506e+04 1.27422822e+04 1.24048184e+04 1.24642285e+04 1.29991768e+04 1.35906299e+04 1.30768750e+04 1.23981191e+04 1.26381934e+04 1.33071797e+04 1.37257881e+04 1.32331914e+04 1.28998516e+04 1.30179883e+04 1.30003516e+04 1.32926260e+04 1.34631055e+04 1.29345254e+04 1.29105605e+04 1.33888369e+04 1.36238701e+04 1.34845898e+04 1.31880996e+04 1.32963242e+04 1.35196641e+04 1.39029092e+04 1.36407109e+04 1.28979863e+04 1.31308906e+04 1.36074648e+04 1.38122568e+04 1.37861416e+04 1.33647061e+04 1.32994922e+04 1.35451123e+04 1.39116562e+04 1.38822363e+04 1.35245527e+04 1.37045762e+04 1.38131084e+04 1.38133057e+04 1.37159287e+04 1.34918760e+04 1.37470361e+04 1.41905791e+04 1.43976162e+04 1.38929268e+04 1.32599082e+04 1.34301768e+04 1.40872627e+04 1.46209180e+04 1.40772373e+04 1.33662031e+04 1.35519756e+04 1.39344541e+04 1.42753193e+04 1.43729502e+04 1.38742285e+04 1.37292510e+04 1.39766240e+04 1.41330781e+04 1.41666748e+04 1.40640684e+04 1.40856562e+04 1.39366641e+04 1.40985918e+04 1.41759277e+04 1.39900234e+04 1.41240938e+04 1.42119287e+04 1.43503750e+04 1.38276074e+04 1.35283613e+04 1.41553779e+04 1.46944697e+04 1.47764385e+04 1.41865713e+04 1.35762881e+04 1.36446221e+04 1.44348232e+04 1.51227988e+04 1.46752627e+04 1.39899023e+04 1.36908535e+04 1.37607256e+04 1.43423936e+04 1.47443672e+04 1.45081699e+04 1.42276865e+04 1.41211523e+04 1.40333799e+04 1.37399580e+04 1.38374463e+04 1.42560527e+04 1.42645225e+04 1.47140723e+04 1.45143662e+04 1.35775850e+04 1.38013311e+04 1.43039678e+04 1.43552656e+04 1.43801748e+04 1.42176973e+04 1.44562441e+04 1.45604990e+04 1.39904697e+04 1.34976680e+04 1.37425195e+04 1.44770371e+04 1.49345723e+04 1.46473047e+04 1.38633145e+04 1.34360137e+04 1.37182539e+04 1.44580244e+04 1.48534922e+04 1.45569072e+04 1.37528164e+04 1.37088516e+04 1.45655020e+04 1.45137588e+04 1.37832656e+04 1.37351914e+04 1.40439502e+04 1.40358867e+04 1.44428994e+04 1.41012979e+04 1.35990811e+04 1.39222588e+04 1.36111318e+04 1.39472080e+04 1.44000586e+04 1.36475850e+04 1.38338584e+04 1.42844883e+04 1.39792031e+04 1.39054912e+04 1.38033232e+04 1.38886484e+04 1.40661074e+04 1.38539756e+04 1.33669170e+04 1.34960029e+04 1.41359521e+04 1.43583467e+04 1.40448203e+04 1.35176465e+04 1.31796650e+04 1.33906914e+04 1.39781416e+04 1.42781152e+04 1.40273652e+04 1.32714141e+04 1.32487871e+04 1.37698662e+04 1.36261299e+04 1.34569932e+04 1.34595684e+04 1.34324385e+04 1.34054404e+04 1.38801270e+04 1.35703086e+04 1.30252959e+04 1.32436104e+04 1.29258750e+04 1.34525488e+04 1.37761592e+04 1.32162275e+04 1.36790771e+04 1.33482744e+04 1.27481855e+04 1.31155244e+04 1.28667217e+04 1.30864707e+04 1.38915186e+04 1.31786123e+04 1.24756602e+04 1.26999307e+04 1.31587793e+04 1.36667197e+04 1.33098584e+04 1.26196279e+04 1.22331025e+04 1.23940947e+04 1.30891963e+04 1.35628330e+04 1.31995684e+04 1.24950449e+04 1.23267656e+04 1.27666406e+04 1.29211611e+04 1.24854697e+04 1.23191650e+04 1.25129893e+04 1.25342246e+04 1.28157031e+04 1.28110742e+04 1.22959756e+04 1.22220029e+04 1.21144971e+04 1.21495508e+04 1.23930381e+04 1.22601807e+04 1.25493389e+04 1.22967822e+04 1.17685293e+04 1.20305410e+04 1.17301865e+04 1.20247168e+04 1.27674346e+04 1.20700420e+04 1.12509580e+04 1.14645049e+04 1.20842627e+04 1.23264580e+04 1.23089092e+04 1.16982168e+04 1.11376572e+04 1.12803770e+04 1.18446562e+04 1.23994492e+04 1.19109521e+04 1.11402559e+04 1.09796797e+04 1.13379814e+04 1.15840986e+04 1.18393418e+04 1.17267520e+04 1.10321396e+04 1.08643291e+04 1.12259043e+04 1.13872705e+04 1.12059307e+04 1.10977754e+04 1.08916533e+04 1.07960244e+04 1.12122207e+04 1.12424170e+04 1.06302041e+04 1.05666553e+04 1.08084980e+04 1.07315215e+04 1.07471201e+04 1.05980996e+04 1.07913174e+04 1.08362666e+04 1.04501689e+04 1.02218994e+04 1.00929316e+04 1.04011670e+04 1.08717637e+04 1.06292822e+04 1.00654854e+04 9.73030762e+03 1.00992256e+04 1.06086426e+04 1.01401641e+04 9.61090137e+03 9.75506055e+03 9.95410547e+03 1.01260693e+04 1.03652275e+04 1.01770547e+04 9.53010742e+03 9.22153613e+03 9.49358594e+03 9.96754688e+03 9.92395703e+03 9.54061230e+03 9.38249219e+03 9.39830078e+03 9.52937207e+03 9.36804688e+03 9.10802441e+03 9.07554102e+03 8.94509570e+03 9.25263086e+03 9.49129980e+03 9.03781543e+03 8.99662012e+03 9.02941699e+03 9.18027832e+03 8.88948047e+03 8.42382910e+03 8.80790918e+03 9.23608887e+03 8.79862988e+03 8.30576562e+03 8.46832129e+03 8.89054004e+03 8.75345703e+03 8.47707031e+03 8.46432227e+03 8.11330908e+03 8.05115430e+03 8.47474121e+03 8.39114355e+03 8.03702197e+03 7.80697119e+03 7.74042480e+03 8.05978809e+03 8.35097559e+03 7.99677295e+03 7.71384619e+03 7.77788916e+03 7.74076025e+03 7.99578467e+03 7.93861230e+03 7.42792285e+03 7.33772559e+03 7.43026367e+03 7.45101562e+03 7.46565332e+03 7.39587988e+03 7.49241504e+03 7.37422461e+03 7.08731201e+03 6.99873047e+03 6.84411328e+03 7.06241016e+03 7.44921045e+03 7.20395459e+03 6.74461963e+03 6.64194238e+03 6.82094629e+03 6.82570898e+03 7.48078320e+03 7.68380713e+03 6.92203369e+03 8.50354785e+03 1.37170723e+04 1.42656516e+05 -15572058. 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. 0. 0. 0. 0. 0. 0. 14856247. 1.57117197e+04 4.59255762e+03 6.30878076e+03 4.89267432e+03 4.71364697e+03 4.55409375e+03 4.34851025e+03 4.26374561e+03 4.38704443e+03 4.36624512e+03 4.22574951e+03 4.22051953e+03 4.16198145e+03 4.08740479e+03 4.07001587e+03 4.00923535e+03 3.94182910e+03 3.91196045e+03 3.88722681e+03 3.81197217e+03 3.67772021e+03 3.61749243e+03 3.76578906e+03 3.73163672e+03 3.49850830e+03 3.44817798e+03 3.60373047e+03 3.58326904e+03 3.44055225e+03 3.38793628e+03 3.34712012e+03 3.29911401e+03 3.25487207e+03 3.21145703e+03 3.16983813e+03 3.12509546e+03 3.02870898e+03 2.97616675e+03 3.07577222e+03 3.04642627e+03 2.92145898e+03 2.88608911e+03 2.84452124e+03 2.81185254e+03 2.76993579e+03 2.71462158e+03 2.69787036e+03 2.58308203e+03 2.52871704e+03 2.57401318e+03 2.52755786e+03 2.56610791e+03 2.55384277e+03 2.42583154e+03 2.32059082e+03 2.27661450e+03 2.38374487e+03 2.37214844e+03 2.23966992e+03 2.17150391e+03 2.16004785e+03 2.13685400e+03 2.08026001e+03 2.10417676e+03 2.06712891e+03 1.92929956e+03 1.88205579e+03 1.94862170e+03 1.96526611e+03 1.87964343e+03 1.82422510e+03 1.79917102e+03 1.75803992e+03 1.69707507e+03 1.66910217e+03 1.67471472e+03 1.64277002e+03 1.57973718e+03 1.54921521e+03 1.53704980e+03 1.50075171e+03 1.51089136e+03 1.47404236e+03 1.39666187e+03 1.39019556e+03 1.35913062e+03 1.34422070e+03 1.32434106e+03 1.27159839e+03 1.24235034e+03 1.19542871e+03 1.14999829e+03 1.17010291e+03 1.14479102e+03 1.06227222e+03 1.05213611e+03 1.08812292e+03 1.09042017e+03 1.02897400e+03 9.78940369e+02 9.36645142e+02 9.10399536e+02 8.95882568e+02 8.70419739e+02 8.58564758e+02 8.33135925e+02 8.23287109e+02 7.95516541e+02 7.54504700e+02 7.45711853e+02 7.03948914e+02 6.84451355e+02 7.02635620e+02 6.73921936e+02 6.36041626e+02 6.01465271e+02 5.78478943e+02 5.90678894e+02 5.73416077e+02 5.35021973e+02 5.03443420e+02 4.86134369e+02 4.81894653e+02 4.62700165e+02 4.57209778e+02 4.43728882e+02 4.13573181e+02 3.92253113e+02 3.77450378e+02 3.69990387e+02 3.52885010e+02 3.32634003e+02 3.13213898e+02 2.99471405e+02 2.92320831e+02 2.70272461e+02 2.56928833e+02 2.58076904e+02 2.43861298e+02 2.25431137e+02 2.06109955e+02 1.94061737e+02 1.94687057e+02 1.83015747e+02 1.67532913e+02 1.52605804e+02 1.41619308e+02 1.36700882e+02 1.26707703e+02 1.17558258e+02 1.06634071e+02 1.00045189e+02 9.63466873e+01 8.61288071e+01 7.80721893e+01 7.12081375e+01 6.39034081e+01 5.66292839e+01 5.03932495e+01 4.55140648e+01 4.03014374e+01 3.53783340e+01 2.96077137e+01 2.54800682e+01 2.30409889e+01 1.86054935e+01 1.47684345e+01 1.22213736e+01 9.67613983e+00 7.66047001e+00 5.61788273e+00 3.94228411e+00 2.85585141e+00 1.99393308e+00 1.46302140e+00 1.29406178e+00 1.47051251e+00 1.99918425e+00 2.87910938e+00 4.11771297e+00 5.58789110e+00 7.58241701e+00 1.02623539e+01 1.27607403e+01 1.53100977e+01 1.80456429e+01 2.18789158e+01 2.73225765e+01 3.15126705e+01 3.53432503e+01 3.96432915e+01 4.45733643e+01 5.12923088e+01 5.74859352e+01 6.55423050e+01 7.09595490e+01 7.56067123e+01 8.50892410e+01 9.33062286e+01 1.03208221e+02 1.10191177e+02 1.16228050e+02 1.26803787e+02 1.35825562e+02 1.47101028e+02 1.53473099e+02 1.66854752e+02 1.88357254e+02 1.93887421e+02 2.00734879e+02 2.07701920e+02 2.17254318e+02 2.43264771e+02 2.59087097e+02 2.64709381e+02 2.69011719e+02 2.82104828e+02 3.06389465e+02 3.20636566e+02 3.43883392e+02 3.57617432e+02 3.64780457e+02 3.70556396e+02 3.83671417e+02 4.24951813e+02 4.38128662e+02 4.42472107e+02 4.57089142e+02 4.73489502e+02 5.13512085e+02 5.34005371e+02 5.27079651e+02 5.41523743e+02 5.87047058e+02 6.13132080e+02 6.02570007e+02 6.19019958e+02 6.71994934e+02 6.95564941e+02 6.97771362e+02 7.05637329e+02 7.24068237e+02 7.85265686e+02 7.99304749e+02 7.95890076e+02 8.26874329e+02 8.49250854e+02 8.94259705e+02 9.17332886e+02 9.16156677e+02 9.15926208e+02 9.71518066e+02 1.05456140e+03 1.04877588e+03 1.05818042e+03 1.09746021e+03 1.11459680e+03 1.14117139e+03 1.16428467e+03 1.18395776e+03 1.18625928e+03 1.20666370e+03 1.26539441e+03 1.30897583e+03 1.37287427e+03 1.36281360e+03 1.34152600e+03 1.40783447e+03 1.46666174e+03 1.53201904e+03 1.52991174e+03 1.51787451e+03 1.55746204e+03 1.57660022e+03 1.62830078e+03 1.66675867e+03 1737. 1.76387830e+03 1.75035315e+03 1.76517139e+03 1.75145776e+03 1.85201550e+03 2.00403845e+03 1.98898010e+03 1.96729858e+03 1.95368774e+03 1.93920691e+03 2.07132422e+03 2.20526465e+03 2.18205249e+03 2.11843384e+03 2.14000977e+03 2.23866870e+03 2.28279736e+03 2.37551660e+03 2.40283105e+03 2.37349072e+03 2.39486084e+03 2.42877808e+03 2.56617358e+03 2.59938330e+03 2.50493359e+03 2.54861572e+03 2.73003125e+03 2.72727148e+03 2.64204639e+03 2.73270166e+03 2.92502881e+03 2.92026904e+03 2.88437207e+03 2.86419751e+03 2.90216626e+03 3.09700464e+03 3.14181665e+03 3.10831714e+03 3.06186304e+03 3.07077319e+03 3.21795215e+03 3.27835474e+03 3.29610425e+03 3.25648608e+03 3.37594727e+03 3.54727710e+03 3.47856885e+03 3.59354077e+03 3.61294482e+03 3.54010400e+03 3.64359277e+03 3.70761353e+03 3.73766162e+03 3.76103345e+03 3.73274487e+03 3.70200757e+03 3.90026929e+03 4.18776611e+03 4.01990283e+03 3.85857227e+03 4.03643604e+03 4.15500635e+03 4.32577832e+03 4.27252295e+03 4.17495654e+03 4.39658936e+03 4.44203369e+03 4.28473438e+03 4.27548096e+03 4.57590332e+03 4.65457178e+03 4.57415381e+03 4.54089209e+03 4.40837598e+03 4.68488721e+03 5.07706494e+03 4.94086621e+03 4.84136328e+03 4.76767041e+03 4.70557275e+03 5.03096631e+03 5.34808008e+03 5.26162256e+03 5.03567041e+03 5.03906836e+03 5.21197949e+03 5.30947266e+03 5.51428857e+03 5.40275586e+03 5.29719971e+03 5.50535693e+03 5.49440234e+03 5.74467529e+03 5.77263232e+03 5.60052246e+03 5.68136035e+03 5.76280713e+03 5.91232373e+03 5.79985059e+03 5.79964160e+03 6.14375586e+03 6.17133008e+03 6.01824707e+03 5.93388818e+03 6.05281299e+03 6.43284961e+03 6.48105322e+03 6.31723486e+03 6.22907520e+03 6.21445361e+03 6.43993604e+03 6.51301855e+03 6.57371484e+03 6.45509912e+03 6.61639453e+03 6.94990869e+03 6.76828271e+03 6.95616406e+03 7.07190820e+03 6.88192285e+03 6.86985645e+03 6.88507227e+03 7.11835498e+03 7.21028662e+03 6.98169531e+03 7.01627148e+03 7.48455371e+03 7.58444678e+03 7.15789307e+03 7.08252490e+03 7.31488330e+03 7.62526221e+03 7.93454834e+03 7.70070557e+03 7.39185840e+03 7.78078906e+03 8.06260645e+03 7.87450342e+03 7.75359619e+03 7.82947168e+03 7.80280664e+03 7.90812451e+03 8.04305518e+03 7.84489648e+03 8.13941650e+03 8.58276172e+03 8.33242773e+03 8.40468652e+03 8.28115137e+03 8.21108496e+03 8.65277246e+03 8.68162598e+03 8.55442480e+03 8.44096680e+03 8.21819824e+03 8.44368555e+03 8.91593164e+03 9.32927148e+03 8.84134375e+03 8.59029004e+03 8.84336719e+03 9.01038867e+03 9.30427832e+03 9.35187891e+03 9.06367969e+03 9.09312598e+03 9.07471973e+03 9.17554590e+03 9.02876465e+03 9.28329004e+03 9.70047461e+03 9.50837891e+03 9.66114355e+03 9.49715332e+03 9.35633789e+03 9.92642480e+03 1.00077871e+04 9.69158984e+03 9.50749316e+03 9.50420605e+03 9.80934277e+03 9.86834082e+03 1.02073945e+04 1.03912334e+04 1.00149639e+04 9.83632129e+03 1.00133320e+04 1.05105400e+04 1.04199814e+04 1.02550547e+04 1.01478389e+04 1.01778711e+04 1.03837090e+04 1.03005469e+04 1.06462803e+04 1.07269346e+04 1.04216309e+04 1.08039043e+04 1.09942744e+04 1.07596113e+04 1.07842949e+04 1.08232256e+04 1.08638896e+04 1.05910977e+04 1.05118623e+04 1.11481348e+04 1.13348291e+04 1.08219824e+04 1.04818457e+04 1.10616104e+04 1.18075352e+04 1.16191729e+04 1.10061807e+04 1.08231582e+04 1.15166562e+04 1.16488701e+04 1.12999199e+04 1.16314668e+04 1.14004170e+04 1.09005527e+04 1.12815117e+04 1.19437275e+04 1.22264092e+04 1.16245264e+04 1.10834043e+04 1.17842578e+04 1.24345381e+04 1.21003301e+04 1.15794717e+04 1.14671885e+04 1.18241025e+04 1.19334238e+04 1.23214463e+04 1.22924746e+04 1.19251104e+04 1.20070469e+04 1.20643105e+04 1.24533867e+04 1.22825264e+04 1.19379248e+04 1.23773594e+04 1.23762227e+04 1.25124941e+04 1.23330293e+04 1.21386162e+04 1.28876367e+04 1.26002520e+04 1.20494805e+04 1.23356973e+04 1.26998252e+04 1.28208350e+04 1.26462842e+04 1.29191143e+04 1.30559805e+04 1.28074902e+04 1.25082412e+04 1.23982236e+04 1.30949463e+04 1.28974443e+04 1.25830703e+04 1.29726309e+04 1.29708662e+04 1.29827744e+04 1.29450723e+04 1.32775117e+04 1.31898623e+04 1.28215459e+04 1.32937939e+04 1.34032656e+04 1.32612295e+04 1.32729785e+04 1.32266455e+04 1.31187051e+04 1.28180596e+04 1.26542227e+04 1.33524658e+04 1.41576885e+04 1.34033633e+04 1.26454150e+04 1.32504385e+04 1.41036924e+04 1.39991816e+04 1.32635000e+04 1.29676973e+04 1.37021719e+04 1.37187588e+04 1.33320947e+04 1.39368623e+04 1.38110674e+04 1.31914336e+04 1.32067070e+04 1.38854844e+04 1.43021553e+04 1.36158096e+04 1.30541523e+04 1.36319014e+04 1.44949141e+04 1.41967334e+04 1.35126426e+04 1.31756592e+04 1.37897100e+04 1.44536875e+04 1.40178896e+04 1.35922832e+04 1.37566025e+04 1.39607051e+04 1.38939512e+04 1.42879873e+04 1.40238428e+04 1.35450967e+04 1.38987021e+04 1.40299707e+04 1.43124678e+04 1.40082471e+04 1.36491338e+04 1.40769092e+04 1.37912920e+04 1.38179375e+04 1.43434951e+04 1.42325107e+04 1.41782979e+04 1.40906123e+04 1.45283838e+04 1.46040635e+04 1.40427490e+04 1.36642676e+04 1.37281807e+04 1.46523682e+04 1.42875459e+04 1.43739346e+04 1.79427949e+04 3.39170742e+04 1.27423812e+05 -1.16183521e+10 0. 0. 0. 0. 3.27249408e+10 2.86577656e+05 7.51028203e+04 5.23773242e+04 7.29535000e+04 2.42182922e+05 5.46355688e+05 1.54504528e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.89811098e+09 3.55959312e+05 3.32708047e+04 4.06829219e+04 2.84380430e+04 1.55610322e+04 1.59515938e+04 1.43043730e+04 1.46283262e+04 1.49375371e+04 1.42708779e+04 1.38815596e+04 1.40842178e+04 1.40025264e+04 1.41306660e+04 1.46411572e+04 1.44634492e+04 1.39045791e+04 1.41575166e+04 1.44816270e+04 1.41351357e+04 1.39188906e+04 1.38935684e+04 1.41078369e+04 1.44593271e+04 1.44411357e+04 1.40191406e+04 1.36048701e+04 1.39844561e+04 1.44252988e+04 1.41050518e+04 1.41045205e+04 1.40015283e+04 1.38338613e+04 1.42660781e+04 1.40201660e+04 1.35567305e+04 1.37012822e+04 1.36852920e+04 1.39035137e+04 1.40608896e+04 1.36764395e+04 1.35896562e+04 1.40127422e+04 1.46884160e+04 14287. 1.31991631e+04 1.31605586e+04 1.35544980e+04 1.38004902e+04 1.40901523e+04 1.37829189e+04 1.33865264e+04 1.37257432e+04 1.38319502e+04 1.34534814e+04 1.33455762e+04 1.32745742e+04 1.36978965e+04 1.41946504e+04 1.34546035e+04 1.29811826e+04 1.32834775e+04 1.35125586e+04 1.37234541e+04 1.35087549e+04 1.31092480e+04 1.30060518e+04 1.32910947e+04 1.38644189e+04 1.34917529e+04 1.27218779e+04 1.29702832e+04 1.32418105e+04 1.31841768e+04 1.33570312e+04 1.31009531e+04 1.27184736e+04 1.29711416e+04 1.33843652e+04 1.30492910e+04 1.27131357e+04 1.26339121e+04 1.26998037e+04 1.30146299e+04 1.32558838e+04 1.29183848e+04 1.24608379e+04 1.26197656e+04 1.29116270e+04 1.26887217e+04 1.24734170e+04 1.23946836e+04 1.26032549e+04 1.29838662e+04 1.26944971e+04 1.21823545e+04 1.21048057e+04 1.22159580e+04 1.24047998e+04 1.24662881e+04 1.22441318e+04 1.21689219e+04 1.24327236e+04 1.27469883e+04 1.24090469e+04 1.16899268e+04 1.17391182e+04 1.21042354e+04 1.21603477e+04 1.21390449e+04 1.18561270e+04 1.16677871e+04 1.19985322e+04 1.20194746e+04 1.16586641e+04 1.17256133e+04 1.17302422e+04 1.16000830e+04 1.18636748e+04 1.17891885e+04 1.13471133e+04 1.13987725e+04 1.13996738e+04 1.12631504e+04 1.16147441e+04 1.18031943e+04 1.13542871e+04 1.09418408e+04 1.11731670e+04 1.14546299e+04 1.12385576e+04 1.09952939e+04 1.08507344e+04 1.08582861e+04 1.11569082e+04 1.12268037e+04 1.08119219e+04 1.06767754e+04 1.07397832e+04 1.08593906e+04 1.08813770e+04 1.07132949e+04 1.06052803e+04 1.06692295e+04 1.07452373e+04 1.04115537e+04 1.01620469e+04 1.03770898e+04 1.03666201e+04 1.04308682e+04 1.06271436e+04 1.02982285e+04 9.91701953e+03 1.01080273e+04 1.03353525e+04 1.01608467e+04 9.99045410e+03 9.76372656e+03 9.74643750e+03 1.01697441e+04 1.01753076e+04 9.60701172e+03 9.46996875e+03 9.74570801e+03 9.89967383e+03 9.57611523e+03 9.23872754e+03 9.32837891e+03 9.57282715e+03 9.71721875e+03 9.31324609e+03 9.10109277e+03 9.19254102e+03 9.10526465e+03 9.14945410e+03 9.28556543e+03 9.04561621e+03 8.89956250e+03 9.04853906e+03 9.13983984e+03 8.79382129e+03 8.66954980e+03 8.63372461e+03 8.61187988e+03 8.72474219e+03 8.99880176e+03 8.84826953e+03 8.33625586e+03 8.38012012e+03 8.64368652e+03 8.29728320e+03 8.12608740e+03 8.12151221e+03 8.17239160e+03 8.42580566e+03 8.34897656e+03 7.97400195e+03 7.80663232e+03 7.85811523e+03 7.97342285e+03 7.97650342e+03 7.77163721e+03 7.77337500e+03 7.87834912e+03 7.85594824e+03 7.63321387e+03 7.48048389e+03 7.44568945e+03 7.41748877e+03 7.46163867e+03 7.59239453e+03 7.53416064e+03 7.14064746e+03 7.16250537e+03 7.28124414e+03 7.11962598e+03 7.10495117e+03 6.96433545e+03 6.96371436e+03 7.16806787e+03 7.02918896e+03 6.78361670e+03 6.67360547e+03 6.64694434e+03 6.71384717e+03 6.74859326e+03 6.59722168e+03 6.48910059e+03 6.53719287e+03 6.58092383e+03 6.56493359e+03 6.29106934e+03 6.11102881e+03 6.22108789e+03 6.18768262e+03 6.26928174e+03 6.13786719e+03 5.88466162e+03 5.98783740e+03 6.10782764e+03 5.90746729e+03 5.79813574e+03 5.80871191e+03 5.76366064e+03 5.77326123e+03 5.60051758e+03 5.70951562e+03 5.64483740e+03 5.46212012e+03 5.54775342e+03 5.37486328e+03 5.33438281e+03 5.44408789e+03 5.22034424e+03 5.20728857e+03 5.24659326e+03 5.10498975e+03 4928. 4.93640137e+03 5.11989355e+03 5.10963086e+03 4.82561182e+03 4.74994971e+03 4.82354785e+03 4.78804199e+03 4.76095508e+03 4.58383301e+03 4.55323633e+03 4.55880957e+03 4.59803223e+03 4.51526416e+03 4.39198730e+03 4.35577002e+03 4.32614746e+03 4.36435059e+03 4.21580957e+03 4.08280298e+03 4.09294849e+03 4.04676318e+03 4.07035693e+03 4.14337549e+03 4.02609229e+03 3.81782593e+03 3.79179004e+03 3.92506470e+03 3.92361963e+03 3.67356982e+03 3.70367456e+03 3.75914941e+03 3.56273291e+03 3.54373730e+03 3.46600903e+03 3.44082031e+03 3.54836621e+03 3.43032568e+03 3.29535547e+03 3.36880469e+03 3.33703882e+03 3.17626050e+03 3.18652344e+03 3.20181470e+03 3.15907642e+03 3.02459326e+03 2.94653149e+03 2.99887280e+03 3.03380420e+03 2.93345312e+03 2.80761377e+03 2.78576172e+03 2.83357983e+03 2.82676807e+03 2.66696680e+03 2.61821582e+03 2.61946118e+03 2.63550024e+03 2.59825928e+03 2.46248535e+03 2.44334204e+03 2.48345801e+03 2.44398022e+03 2.35596948e+03 2.34951855e+03 2.30729028e+03 2.21199316e+03 2.28273633e+03 2.27632544e+03 2.12368018e+03 2.02298340e+03 2.03037402e+03 2.06449390e+03 2.04535754e+03 1.98346533e+03 1.91055103e+03 1.87955627e+03 1.90789832e+03 1.88993213e+03 1.78445129e+03 1.73015833e+03 1.74792139e+03 1.77219775e+03 1.69273755e+03 1.60445117e+03 1.61169885e+03 1.58926892e+03 1.55297852e+03 1.51498315e+03 1.49398853e+03 1.45921228e+03 1.41011597e+03 1.40404211e+03 1.38017078e+03 1.33853918e+03 1.28565759e+03 1.26284241e+03 1.25696448e+03 1.23108728e+03 1.19017810e+03 1.15746924e+03 1.13658313e+03 1.14572510e+03 1.11643958e+03 1.04796289e+03 1.03342432e+03 1.02179303e+03 9.94345459e+02 9.54634277e+02 9.22700256e+02 9.28539307e+02 8.98751770e+02 8.48047180e+02 8.10041321e+02 8.13229736e+02 8.16502502e+02 7.82336060e+02 7.57935730e+02 7.27662476e+02 7.11298096e+02 6.77380615e+02 6.36032593e+02 6.35610535e+02 6.28196350e+02 6.05513672e+02 5.84743530e+02 5.50363098e+02 5.32854370e+02 5.29424500e+02 5.13172241e+02 4.98893036e+02 4.71556305e+02 4.42156219e+02 4.23267273e+02 4.19726227e+02 4.11253448e+02 3.88513153e+02 3.68467529e+02 3.42734039e+02 3.35099121e+02 3.26669922e+02 3.07713470e+02 2.98071350e+02 2.77726532e+02 2.62291016e+02 2.57513947e+02 2.37936615e+02 2.23161026e+02 2.18724991e+02 2.08500519e+02 1.90820740e+02 1.75098495e+02 1.66444763e+02 1.58364670e+02 1.52875748e+02 1.44632446e+02 1.30514313e+02 1.18715057e+02 1.08510612e+02 1.03447174e+02 9.82695236e+01 8.85520782e+01 7.89620895e+01 7.04485550e+01 6.48705978e+01 5.99189262e+01 5.44682159e+01 4.81377487e+01 4.23219528e+01 3.80302734e+01 3.27820396e+01 2.75999336e+01 2.39012642e+01 2.05105762e+01 1.73860893e+01 1.47613821e+01 1.17836618e+01 9.29419136e+00 7.49336147e+00 6.03557873e+00 4.83945560e+00 3.96803570e+00 3.46824360e+00 3.30667806e+00 3.48406672e+00 4.04805756e+00 4.95310450e+00 6.20485210e+00 7.65112734e+00 9.55520821e+00 1.17856665e+01 1.40368004e+01 1.73841248e+01 2.12732220e+01 2.48261223e+01 2.84702473e+01 3.22263145e+01 3.74379272e+01 4.34563828e+01 4.91202087e+01 5.47643242e+01 5.81584320e+01 6.43232193e+01 7.31695480e+01 8.17492828e+01 8.99887619e+01 9.60427551e+01 1.03568733e+02 1.09290939e+02 1.19928009e+02 1.33995468e+02 1.40635727e+02 1.49767365e+02 1.59931046e+02 1.68863266e+02 1.77899765e+02 1.90623032e+02 2.06554688e+02 2.19930923e+02 2.32701096e+02 2.39064804e+02 2.46636948e+02 2.65051788e+02 2.81951965e+02 2.99413971e+02 3.17113342e+02 3.21513885e+02 3.36233704e+02 3.50981934e+02 3.69355804e+02 3.97429535e+02 4.05978699e+02 4.16728577e+02 4.29284119e+02 4.37765137e+02 4.63760864e+02 5.10051483e+02 5.21348145e+02 5.18424683e+02 5.45306274e+02 5.57417603e+02 5.61288269e+02 5.96815369e+02 6.29962524e+02 6.50323059e+02 6.67993835e+02 6.68903687e+02 6.95870483e+02 7.36420288e+02 7.63866516e+02 8.08394287e+02 8.07318359e+02 7.88221252e+02 8.12960571e+02 8.64631042e+02 9.07784912e+02 9.26625549e+02 9.40844849e+02 9.29602417e+02 9.75222839e+02 1.03922156e+03 1.04413550e+03 1.06803796e+03 1.07836731e+03 1.10596851e+03 1.16134326e+03 1.16007495e+03 1.18231445e+03 1.27153198e+03 1.29473669e+03 1.28781116e+03 1.28947961e+03 1.28213867e+03 1.34352869e+03 1.43105139e+03 1.49628699e+03 1.49081580e+03 1.44824658e+03 1.46224658e+03 1.54578955e+03 1.61593848e+03 1.62179858e+03 1.63971802e+03 1.64204626e+03 1.67419873e+03 1.75976575e+03 1.81080359e+03 1.84166614e+03 1.86028992e+03 1.89746997e+03 1.90332190e+03 1.88543225e+03 1.95083569e+03 2.03193799e+03 2.08416528e+03 2.15093970e+03 2.10754443e+03 2.07514355e+03 2.17772461e+03 2.26781665e+03 2.33402979e+03 2.33936353e+03 2.28404346e+03 2.29177905e+03 2.40306494e+03 2.52969165e+03 2.56428931e+03 2.52999170e+03 2.52785498e+03 2.56725220e+03 2.59718823e+03 2.64500537e+03 2.73750659e+03 2.81695386e+03 2.80524316e+03 2.77505762e+03 2.79802515e+03 2.89066382e+03 3.00770801e+03 3.09087695e+03 3.11262695e+03 3.02717847e+03 2.98416553e+03 3.09779126e+03 3.24437402e+03 3.36214551e+03 3.35990942e+03 3.24697021e+03 3.21693823e+03 3.38309888e+03 3.57642432e+03 3.52933374e+03 3.57101196e+03 3.56383789e+03 3.51179199e+03 3.67388354e+03 3.74262329e+03 3.76170972e+03 3.80939575e+03 3.87710278e+03 3.91444067e+03 3.86608740e+03 3.97291187e+03 4.05543750e+03 4.15623389e+03 4.14417773e+03 4.09516211e+03 4.17089307e+03 4.14052539e+03 4.27020215e+03 4.55348828e+03 4.50734180e+03 4.32598730e+03 4.34178857e+03 4.44425000e+03 4.65328711e+03 4.81027441e+03 4.67840820e+03 4.61608789e+03 4.71432178e+03 4.81953174e+03 4.84566992e+03 4.95489062e+03 5.07579443e+03 5.23076416e+03 5.26679492e+03 5.92265137e+03 7.30047705e+03 2.67083984e+04 7.24635250e+05 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 95078592. -13921629. 1.69014388e+06 3.73738275e+06 2.52563633e+04 1.59835977e+04 8.14041406e+03 8.18602686e+03 7.90239795e+03 7.56540674e+03 7.32847412e+03 7.60343066e+03 8.12586328e+03 8.08483057e+03 7.73739160e+03 7.54186914e+03 7.54764697e+03 8.03363525e+03 8.49148535e+03 8.20290625e+03 7.99020410e+03 7.92040869e+03 8.04887354e+03 8.51535059e+03 8.52445898e+03 8.17157959e+03 8.21946777e+03 8.52645215e+03 8.49239453e+03 8.28584277e+03 8.47331836e+03 8.77625000e+03 9.04771191e+03 9.05511328e+03 8.70369629e+03 8.30464746e+03 8.64577441e+03 9.20513477e+03 9.41763281e+03 9.16010547e+03 8.80853711e+03 8.76119238e+03 9.23457129e+03 9.72408789e+03 9.46611816e+03 8.94911133e+03 9.02525781e+03 9.53164844e+03 9.62255859e+03 9.48690234e+03 9.52994238e+03 9.48785547e+03 9.71331641e+03 9.81483789e+03 9.39568066e+03 9.48005078e+03 1.00605449e+04 1.02628818e+04 1.01247324e+04 9.70392188e+03 9.45568750e+03 1.00568027e+04 1.07488486e+04 1.05045830e+04 1.00428076e+04 9.79141309e+03 9.76601465e+03 1.03535557e+04 1.09980293e+04 1.07098975e+04 1.05483018e+04 1.04500820e+04 1.03100498e+04 1.05183379e+04 1.07916025e+04 1.05656074e+04 1.04937871e+04 1.09199473e+04 1.07958818e+04 1.04119561e+04 1.06262744e+04 1.11744482e+04 1.14563398e+04 1.12709844e+04 1.10236523e+04 1.07375713e+04 1.06755352e+04 1.12903877e+04 1.18935869e+04 1.15235039e+04 1.08548193e+04 1.09083682e+04 1.14070273e+04 1.18872256e+04 1.18808105e+04 1.13847344e+04 1.12806123e+04 1.16501611e+04 1.17046562e+04 1.16222051e+04 1.17091836e+04 1.16773301e+04 1.18716328e+04 1.19006094e+04 1.15719658e+04 1.16826660e+04 1.20990898e+04 1.23576504e+04 1.23553369e+04 1.20507334e+04 1.16870576e+04 1.17971318e+04 1.24640850e+04 1.26884531e+04 1.22476436e+04 1.18327627e+04 1.17069014e+04 1.23800244e+04 1.31816436e+04 1.26698438e+04 1.20349844e+04 1.21350781e+04 1.25229941e+04 1.25143525e+04 1.23075361e+04 1.24121992e+04 1.28811279e+04 1.30280254e+04 1.27015684e+04 1.23317256e+04 1.23672852e+04 1.30028486e+04 1.35177852e+04 1.32161973e+04 1.27973896e+04 1.25865195e+04 1.24371611e+04 1.29488945e+04 1.37155254e+04 1.32614121e+04 1.26152646e+04 1.25894326e+04 1.32279355e+04 1.38596484e+04 1.34476670e+04 1.30147715e+04 1.30164531e+04 1.32110723e+04 1.34307188e+04 1.34068330e+04 1.31090225e+04 1.29779531e+04 1.35154766e+04 1.37798740e+04 1.33237900e+04 1.30587490e+04 1.33202754e+04 1.37383506e+04 1.40772275e+04 1.38031650e+04 1.30595254e+04 1.31903623e+04 1.37840342e+04 1.38894404e+04 1.37039512e+04 1.35209600e+04 1.34773623e+04 1.35574150e+04 1.39171924e+04 1.37211865e+04 1.34323750e+04 1.39062588e+04 1.42540371e+04 1.39091191e+04 1.34787080e+04 1.36005322e+04 1.39373750e+04 1.43937998e+04 1.44601543e+04 1.39490352e+04 1.34948740e+04 1.34099258e+04 1.40182471e+04 1.47690303e+04 1.43171064e+04 1.35325996e+04 1.34757324e+04 1.39940850e+04 1.45791553e+04 1.45208252e+04 1.40540283e+04 1.38906484e+04 1.40235869e+04 1.39512920e+04 1.40281387e+04 1.42416670e+04 1.41504834e+04 1.42572656e+04 1.42162715e+04 1.38473301e+04 1.39748594e+04 1.43663555e+04 1.45475938e+04 1.45562822e+04 1.39101670e+04 1.35469141e+04 1.42904062e+04 1.49312881e+04 1.46909854e+04 1.42365225e+04 1.38176611e+04 1.36537783e+04 1.44198066e+04 1.51401240e+04 1.47201113e+04 1.39491074e+04 1.37770967e+04 1.42905244e+04 1.45698809e+04 1.45015293e+04 1.44704385e+04 1.43532559e+04 1.42270811e+04 1.39682715e+04 1.36398076e+04 1.39121396e+04 1.42714434e+04 1.45640068e+04 1.50674297e+04 1.46358193e+04 1.37161621e+04 1.36194775e+04 1.42021260e+04 1.47009902e+04 1.45553486e+04 1.42194736e+04 1.45328926e+04 1.46587256e+04 1.40584199e+04 1.35630742e+04 1.38192158e+04 1.45878613e+04 1.50787510e+04 1.47368535e+04 1.39390625e+04 1.34480791e+04 1.37269180e+04 1.45932314e+04 1.50619961e+04 1.46341641e+04 1.38086660e+04 1.38051348e+04 1.46560059e+04 1.46063926e+04 1.39580625e+04 1.39261006e+04 1.40297861e+04 1.40360830e+04 1.45082715e+04 1.42016074e+04 1.37126182e+04 1.39899307e+04 1.37104336e+04 1.41163330e+04 1.44127852e+04 1.36295811e+04 1.39745625e+04 1.44259736e+04 1.40323916e+04 1.38534033e+04 1.39258145e+04 1.40775557e+04 1.40628936e+04 1.39405430e+04 1.34989697e+04 1.35279502e+04 1.42273936e+04 1.45029541e+04 1.41442305e+04 1.35517275e+04 1.32384326e+04 1.35322930e+04 1.40881787e+04 1.43254053e+04 1.40158125e+04 1.33779131e+04 1.34011309e+04 1.37288291e+04 1.36543379e+04 1.36719521e+04 1.36018613e+04 1.35014990e+04 1.34461152e+04 1.39516631e+04 1.36644297e+04 1.30958213e+04 1.33243613e+04 1.30968604e+04 1.36127461e+04 1.37343906e+04 1.32097744e+04 1.38571338e+04 1.33890303e+04 1.28175713e+04 1.32713994e+04 1.29486816e+04 1.31271816e+04 1.40131094e+04 1.33663975e+04 1.25200410e+04 1.26568564e+04 1.32267842e+04 1.38466934e+04 1.34311094e+04 1.26713711e+04 1.23847197e+04 1.24796240e+04 1.30997900e+04 1.36462500e+04 1.32456709e+04 1.25692539e+04 1.24737637e+04 1.28015127e+04 1.28894902e+04 1.26655029e+04 1.24862197e+04 1.25373711e+04 1.26615430e+04 1.29028701e+04 1.28378623e+04 1.22492188e+04 1.21814805e+04 1.22670791e+04 1.23175615e+04 1.24328135e+04 1.23572949e+04 1.26506855e+04 1.23315098e+04 1.18347236e+04 1.21092607e+04 1.17871006e+04 1.21216865e+04 1.27915254e+04 1.21336533e+04 1.14165352e+04 1.16296807e+04 1.21366699e+04 1.25050898e+04 1.23637246e+04 1.16467363e+04 1.12250605e+04 1.13822793e+04 1.19062949e+04 1.23938154e+04 1.19405098e+04 1.11722920e+04 1.11202041e+04 1.14181553e+04 1.16314775e+04 1.19227178e+04 1.18266611e+04 1.11102617e+04 1.08540703e+04 1.14407715e+04 1.15714492e+04 1.10253398e+04 1.09414072e+04 1.11444277e+04 1.09968506e+04 1.12586670e+04 1.13186445e+04 1.06452129e+04 1.06042773e+04 1.08773975e+04 1.08295518e+04 1.08221680e+04 1.05955283e+04 1.07500859e+04 1.09885439e+04 1.06765830e+04 1.02674912e+04 9.99529492e+03 1.04097305e+04 1.09863408e+04 1.06837715e+04 1.01158457e+04 9.77476953e+03 1.00712217e+04 1.06525840e+04 1.03312852e+04 9.73037305e+03 9.78377148e+03 9.98296973e+03 1.01878877e+04 1.04443525e+04 1.01936846e+04 9.57254395e+03 9.30583105e+03 9.56404688e+03 9.94098047e+03 9.90089746e+03 9.55107031e+03 9.48188574e+03 9.44469629e+03 9.62096484e+03 9.54602148e+03 9.29207129e+03 9.19670410e+03 8.87196777e+03 9.23577051e+03 9.52236816e+03 9.06954004e+03 9.13177637e+03 9.12696777e+03 9.16147949e+03 8.87830957e+03 8.49269434e+03 8.81937305e+03 9.20649805e+03 8.92771094e+03 8.40389062e+03 8.42213770e+03 8.84098926e+03 8.81418457e+03 8.54643750e+03 8.52361914e+03 8.12494629e+03 8.06929297e+03 8.55063965e+03 8.45027832e+03 8.06679834e+03 7.85182959e+03 7.79194824e+03 8.11397070e+03 8.34405566e+03 8.00675488e+03 7.74930859e+03 7.85197070e+03 7.76350830e+03 7.99293262e+03 7.92638379e+03 7.46211084e+03 7.42598828e+03 7.52029785e+03 7.45838867e+03 7.45802100e+03 7.37787891e+03 7.54722363e+03 7.38500098e+03 7.09827295e+03 7.11749414e+03 6.91239600e+03 7.11134473e+03 7.50197021e+03 7.23089404e+03 6.82887842e+03 6.67227832e+03 6.73793164e+03 6.89755908e+03 7.15824658e+03 7.21320654e+03 7.59225391e+03 6.89236865e+03 9.94426172e+03 7.14947656e+04 -7786029. 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. 0. 0. 0. 0. 0. 0. -142999024. -44676880. 1.65220352e+04 1.00532031e+04 5.00666748e+03 4.89305957e+03 4.64831982e+03 4.38668652e+03 4.33283105e+03 4.39517578e+03 4.34115625e+03 4.22044727e+03 4.28314941e+03 4.21163818e+03 4.11650439e+03 4.08630713e+03 4.03502466e+03 3.96473169e+03 3.93696338e+03 3.92610986e+03 3.83995068e+03 3.71878418e+03 3.67620337e+03 3.79373193e+03 3.74337866e+03 3.52314355e+03 3.49971631e+03 3.63461572e+03 3.60983862e+03 3.45231396e+03 3.41389795e+03 3.35664795e+03 3.32496021e+03 3.28206543e+03 3.25222925e+03 3.20129785e+03 3.13113599e+03 3.04815771e+03 3.01297534e+03 3.09341724e+03 3.05566284e+03 2.93541455e+03 2.90677539e+03 2.87356519e+03 2.84613501e+03 2.78681738e+03 2.73780981e+03 2.71158594e+03 2.60660205e+03 2.56429517e+03 2.57796973e+03 2.53345654e+03 2.58675830e+03 2.56410498e+03 2.45365820e+03 2.33512671e+03 2.28005786e+03 2.40138037e+03 2.38964502e+03 2.24977441e+03 2.18243384e+03 2.17963843e+03 2.12916553e+03 2.06917578e+03 2.13722485e+03 2.08969727e+03 1.93365308e+03 1.89003540e+03 1.95587329e+03 1.99307007e+03 1.91445752e+03 1.84304333e+03 1.81423352e+03 1.76713684e+03 1.71936926e+03 1.70049292e+03 1.68989343e+03 1.65085449e+03 1.58450513e+03 1.54606946e+03 1.54489331e+03 1.51309753e+03 1.52019824e+03 1.47223682e+03 1.39616797e+03 1.39308643e+03 1.36392188e+03 1.36423743e+03 1.34171436e+03 1.28136963e+03 1.25170410e+03 1.19915894e+03 1.14696228e+03 1.17246655e+03 1.16229407e+03 1.07721472e+03 1.06261865e+03 1.09823767e+03 1.09238025e+03 1.03622766e+03 9.82843628e+02 9.53728943e+02 9.32644836e+02 8.98462219e+02 8.72241699e+02 8.66118225e+02 8.40795715e+02 8.29203186e+02 7.95131531e+02 7.57087524e+02 7.48534424e+02 7.09557434e+02 6.99179199e+02 7.14524902e+02 6.81209656e+02 6.42133850e+02 6.05125671e+02 5.83587830e+02 5.97158997e+02 5.81758423e+02 5.41302429e+02 5.07241364e+02 4.89746277e+02 4.85366028e+02 4.66984833e+02 4.62260132e+02 4.48880646e+02 4.16905792e+02 3.91799286e+02 3.77134583e+02 3.76754517e+02 3.59620789e+02 3.36309631e+02 3.15865112e+02 3.01476074e+02 2.93169281e+02 2.71714874e+02 2.62119263e+02 2.64561340e+02 2.47777939e+02 2.28103470e+02 2.09715469e+02 1.97407898e+02 1.97829041e+02 1.86763458e+02 1.70822784e+02 1.55191910e+02 1.44138367e+02 1.39561249e+02 1.29817841e+02 1.20090645e+02 1.09011307e+02 1.02489838e+02 9.77542953e+01 8.73289490e+01 8.08605804e+01 7.43513489e+01 6.61623764e+01 5.81667595e+01 5.20588226e+01 4.74886513e+01 4.20684128e+01 3.70858383e+01 3.14441566e+01 2.76589622e+01 2.52202396e+01 2.06744804e+01 1.68527832e+01 1.43213940e+01 1.17543974e+01 9.65767765e+00 7.63774729e+00 5.96484756e+00 4.86298895e+00 3.99714613e+00 3.47209120e+00 3.30652857e+00 3.46662402e+00 3.97060061e+00 4.86068439e+00 6.15194941e+00 7.64281797e+00 9.65519524e+00 1.23996935e+01 1.48710012e+01 1.72948322e+01 2.00609531e+01 2.43235607e+01 2.98797340e+01 3.35823631e+01 3.74705734e+01 4.19842491e+01 4.68378677e+01 5.36796799e+01 5.98233223e+01 6.78622894e+01 7.35100174e+01 7.81568222e+01 8.77344971e+01 9.60104294e+01 1.06077545e+02 1.13563522e+02 1.19615715e+02 1.28348816e+02 1.37275467e+02 1.50492111e+02 1.57015701e+02 1.69543259e+02 1.90202423e+02 1.97271500e+02 2.04775986e+02 2.10664459e+02 2.20731445e+02 2.46762360e+02 2.61795807e+02 2.68602173e+02 2.73167938e+02 2.85956329e+02 3.09866058e+02 3.24902679e+02 3.48199768e+02 3.62284393e+02 3.69236359e+02 3.73801422e+02 3.88207397e+02 4.29346771e+02 4.44096344e+02 4.48941193e+02 4.59261536e+02 4.75747986e+02 5.17677185e+02 5.40151978e+02 5.32186829e+02 5.47026489e+02 5.95221741e+02 6.16320496e+02 6.05956787e+02 6.24093811e+02 6.78438904e+02 7.01733154e+02 7.00799133e+02 7.08657104e+02 7.29045593e+02 7.94524841e+02 8.13094421e+02 8.06514404e+02 8.30573059e+02 8.49231628e+02 8.86448486e+02 9.16374756e+02 9.36011353e+02 9.35144287e+02 9.76245300e+02 1.04935986e+03 1.05080774e+03 1.08145923e+03 1.11677686e+03 1.12105908e+03 1.14948804e+03 1.17358484e+03 1.18833801e+03 1.19170129e+03 1.22137329e+03 1.27656653e+03 1.31364246e+03 1.37898511e+03 1.37297046e+03 1.35871045e+03 1.42979309e+03 1.46600940e+03 1.53291162e+03 1.54036853e+03 1.52863965e+03 1.57006665e+03 1.58475598e+03 1.64375757e+03 1.68101270e+03 1.74482971e+03 1.76517249e+03 1.75330212e+03 1.79231506e+03 1.77863232e+03 1.86940942e+03 2.01376904e+03 2.00179932e+03 1.97739246e+03 1.96164783e+03 1.97026953e+03 2.10336914e+03 2.20880518e+03 2.17989185e+03 2.13322729e+03 2.15944360e+03 2.25402710e+03 2.29352051e+03 2.38504541e+03 2.39416699e+03 2.36244751e+03 2.43890405e+03 2.47495898e+03 2.58214160e+03 2.62328320e+03 2.51716138e+03 2.56587061e+03 2.74389844e+03 2.73819360e+03 2.64087622e+03 2.76615308e+03 2.95996899e+03 2.94256250e+03 2.91154199e+03 2.89164355e+03 2.92936841e+03 3.11296411e+03 3.15631274e+03 3.12185278e+03 3.08311963e+03 3.11173608e+03 3.26111157e+03 3.28726392e+03 3.31556519e+03 3.28868726e+03 3.39328149e+03 3.56840991e+03 3.50761035e+03 3.60631396e+03 3.59548291e+03 3.53317529e+03 3.67123169e+03 3.73443481e+03 3.76984204e+03 3.79152979e+03 3.78722803e+03 3.75416821e+03 3.90583813e+03 4.22318262e+03 4.02766064e+03 3.86151685e+03 4.02295752e+03 4.22281738e+03 4.38460254e+03 4.31895020e+03 4.25262451e+03 4.40052246e+03 4.42894727e+03 4.31611768e+03 4.28985010e+03 4.58288965e+03 4.65806982e+03 4.54985547e+03 4.61681055e+03 4.51412256e+03 4.72329346e+03 5.05303809e+03 4.95114453e+03 4.88613916e+03 4.77845508e+03 4.77205762e+03 5.11370996e+03 5.38320312e+03 5.30140137e+03 5.08277051e+03 5.06815234e+03 5.23740088e+03 5.32041992e+03 5.53119141e+03 5.41802393e+03 5.32634961e+03 5.56206348e+03 5.53358643e+03 5.72719922e+03 5.75657031e+03 5.58838574e+03 5.83089453e+03 5.87387891e+03 5.84045801e+03 5.74219238e+03 5.85260352e+03 6.22342822e+03 6.23433545e+03 5.99560107e+03 5.93617773e+03 6.15224023e+03 6.52592822e+03 6.48361963e+03 6.35436182e+03 6.25796533e+03 6.28533838e+03 6.50544824e+03 6.60959766e+03 6.63302148e+03 6.51554980e+03 6.64352979e+03 6.95364258e+03 6.81715723e+03 7.02957471e+03 7.06025928e+03 6.88976953e+03 7.00541455e+03 7.07797168e+03 7.04848682e+03 7.14096387e+03 7.10453906e+03 7.15183398e+03 7.49503369e+03 7.51013818e+03 7.19165137e+03 7.19221582e+03 7.39420605e+03 7.63087646e+03 7.97127148e+03 7.75318750e+03 7.37505518e+03 7.72117188e+03 8.20018848e+03 8.02582129e+03 7.71442236e+03 7.76090234e+03 7.91981982e+03 8.02120117e+03 8.12336621e+03 7.92597217e+03 8.17448145e+03 8.62506348e+03 8.43743164e+03 8.30797168e+03 8.16961426e+03 8.25611719e+03 8.79798242e+03 8.74447461e+03 8.60694727e+03 8.50842773e+03 8.19912598e+03 8.48380566e+03 9.05269531e+03 9.38507520e+03 8.91327246e+03 8.55054102e+03 8.87227930e+03 9.09978027e+03 9.46978223e+03 9.26053027e+03 9.03523145e+03 9.25649414e+03 9.31139746e+03 9.22632031e+03 9.06477637e+03 9.29650977e+03 9.75858008e+03 9.66227832e+03 9.58386719e+03 9.46865332e+03 9.45928125e+03 9.93533984e+03 1.00568955e+04 9.81746484e+03 9.64182910e+03 9.56530371e+03 9.85485059e+03 9.93436230e+03 1.02925703e+04 1.04161816e+04 9.95175879e+03 9.84933301e+03 1.02021582e+04 1.06448545e+04 1.04154932e+04 1.02482930e+04 1.02550088e+04 1.03162393e+04 1.03591162e+04 1.01602373e+04 1.06084951e+04 1.08378096e+04 1.05555078e+04 1.08611582e+04 1.10393330e+04 1.08809922e+04 1.09583135e+04 1.09568711e+04 1.08426943e+04 1.06168379e+04 1.06000469e+04 1.11467480e+04 1.14581162e+04 1.10178945e+04 1.05891562e+04 1.10326211e+04 1.17531084e+04 1.17652451e+04 1.11670020e+04 1.07822812e+04 1.14012393e+04 1.19401768e+04 1.16790859e+04 1.16816738e+04 1.13739658e+04 1.09233633e+04 1.14153320e+04 1.21445586e+04 1.22499111e+04 1.15926191e+04 1.11835244e+04 1.19368623e+04 1.25337822e+04 1.21690137e+04 1.16286777e+04 1.13680537e+04 1.17648555e+04 1.20355889e+04 1.24010205e+04 1.25874121e+04 1.21662832e+04 1.19798398e+04 1.20310703e+04 1.25828018e+04 1.23457754e+04 1.20008154e+04 1.25853711e+04 1.25951279e+04 1.24654609e+04 1.22347139e+04 1.22708740e+04 1.30006680e+04 1.26108135e+04 1.20021768e+04 1.23423594e+04 1.28922988e+04 1.29856182e+04 1.27337324e+04 1.30119688e+04 1.31141143e+04 1.28572441e+04 1.25370244e+04 1.24325879e+04 1.32053252e+04 1.30057197e+04 1.26675605e+04 1.30802441e+04 1.30694736e+04 1.29975137e+04 1.29183848e+04 1.32256289e+04 1.33531162e+04 1.30428574e+04 1.32315703e+04 1.33769580e+04 1.35330400e+04 1.34788789e+04 1.32453008e+04 1.31153203e+04 1.27875137e+04 1.28700996e+04 1.36107354e+04 1.42840205e+04 1.35136602e+04 1.26943760e+04 1.32323945e+04 1.40737188e+04 1.41729570e+04 1.34745742e+04 1.29168936e+04 1.36212871e+04 1.39328994e+04 1.35446328e+04 1.40813643e+04 1.37782764e+04 1.30744570e+04 1.35011855e+04 1.42588418e+04 1.43009238e+04 1.35502646e+04 1.30603105e+04 1.37158154e+04 1.46403047e+04 1.43115869e+04 1.35421689e+04 1.32322930e+04 1.39024033e+04 1.43965957e+04 1.39966182e+04 1.38322686e+04 1.39240068e+04 1.40886230e+04 1.40000781e+04 1.43480830e+04 1.41314658e+04 1.36197061e+04 1.39737549e+04 1.41167764e+04 1.44123008e+04 1.41267520e+04 1.37424941e+04 1.43231797e+04 1.39633477e+04 1.36085566e+04 1.41709590e+04 1.44717588e+04 1.44662061e+04 1.41739404e+04 1.45651182e+04 1.47241787e+04 1.41441152e+04 1.37397861e+04 1.37441074e+04 1.46749570e+04 1.44286387e+04 1.42847285e+04 1.63457158e+04 2.74772188e+04 1.56126266e+05 -5.80917606e+09 0. 0. 0. 0. 3.27249408e+10 2.86577656e+05 7.51028203e+04 5.23773242e+04 7.29527422e+04 1.67804672e+05 2.73167688e+05 7.72522639e+10 0. 0.
================================================ FILE: config/m2dgr/ring32_M_5.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.10578227e+09 -5.11516750e+06 7.01195679e+02 2.66716797e+02 2.21020145e+01 -3.41211748e+00 -4.69468212e+00 -2.06839967e+00 -7.70714712e+00 -9.39793587e-02 8.72342587e+00 9.17176342e+00 7.20810223e+00 5.05704260e+00 1.85229635e+00 7.30749905e-01 -1.30416870e+00 1.52145612e+00 5.61498165e+00 9.60550785e+00 9.15071869e+00 2.11744976e+00 -4.50195122e+00 -8.85156059e+00 -9.25825500e+00 -4.93593121e+00 -4.03345823e+00 -3.61387014e+00 1.21251976e+00 4.04103136e+00 2.46347809e+00 -5.56232548e+00 -1.11630497e+01 -1.13936329e+01 -6.52159405e+00 1.88672292e+00 4.66362953e+00 4.06164694e+00 3.69359899e+00 3.64541912e+00 2.40020895e+00 -2.40666199e+00 -6.50123549e+00 -4.01304007e+00 7.82995641e-01 3.36918235e+00 -2.62913048e-01 -7.00109720e-01 2.83407301e-01 -2.02799988e+00 -1.92680466e+00 -1.68021786e+00 8.61986697e-01 4.19971943e+00 6.63720179e+00 7.33847427e+00 6.43667579e-01 -7.44274139e+00 -9.58809090e+00 -4.83426666e+00 4.06256819e+00 4.85214233e+00 1.24336302e+00 -2.80506706e+00 -1.97973537e+00 -3.15936238e-01 -1.30361164e+00 -2.84444976e+00 -2.74410939e+00 1.84420145e+00 7.33166742e+00 5.49478054e+00 3.89808464e+00 1.80583405e+00 4.72717345e-01 -1.61803409e-01 -1.79678333e+00 8.42422903e-01 5.00782442e+00 8.85848522e+00 8.79031849e+00 4.19357204e+00 -9.94300246e-01 -5.52403688e+00 -5.92181206e+00 -1.00799108e+00 1.14315736e+00 1.65887821e+00 4.78929472e+00 9.49841022e+00 9.39886951e+00 2.15604806e+00 -5.03498030e+00 -5.44350147e+00 1.10030389e+00 8.44040489e+00 9.10231686e+00 8.01552391e+00 8.39858723e+00 8.31644249e+00 6.86184263e+00 3.49101663e+00 1.53673434e+00 3.09953737e+00 6.19758654e+00 7.43063879e+00 4.75303793e+00 1.94005609e-01 -2.80948758e+00 -3.38249946e+00 1.25312781e+00 5.61993122e+00 5.01467896e+00 5.11482620e+00 6.98886633e+00 8.42857647e+00 5.58106470e+00 7.59285152e-01 7.01777220e-01 6.31055164e+00 1.13466043e+01 1.21733837e+01 7.94809818e+00 3.60328269e+00 -6.95683956e-01 -2.71138763e+00 -5.25753307e+00 -2.71181164e+01 -2.23590729e+02 -4.71761536e+02 3.55132725e+06 -4.16848775e+06 -5934468. 8995803. 5.37903687e+02 2.89024170e+02 5.83151703e+01 -6.58903408e+00 -3.96750679e+01 -2.27908249e+02 -4.21943481e+02 -31383032. 142039824. -4.23466850e+06 -70661560. -3.32204275e+06 4379297. -13451174. 9094321. 4.23635550e+06 -5.23359550e+06 4.68032318e+02 2.50168457e+02 4.90702095e+01 2.00801334e+01 6.77956760e-01 3.14148641e+00 8.80291462e-01 8.84113312e-01 1.66735435e+00 5.74180937e+00 7.95171690e+00 4.45952463e+00 6.77380681e-01 8.84270072e-01 1.51198554e+00 1.72004378e+00 -2.58097124e+00 -5.67328501e+00 -6.69422913e+00 -5.87508500e-01 7.05463171e+00 8.78747845e+00 8.36378288e+00 8.09116745e+00 7.49575949e+00 5.28805923e+00 5.02721429e-01 -1.16091144e+00 2.42668438e+00 7.03290653e+00 8.02275658e+00 4.24769163e+00 1.24917853e+00 5.20317972e-01 3.98100317e-02 8.57918978e-01 -4.89723951e-01 -4.59655553e-01 1.24274230e+00 1.71647561e+00 1.15965343e+00 -1.93259847e+00 -3.53051138e+00 -3.06481218e+00 2.77986145e+00 8.87972641e+00 9.86911869e+00 7.64843321e+00 6.85997391e+00 6.20204782e+00 4.57753897e+00 7.51004398e-01 4.28600430e-01 4.85724258e+00 9.49217892e+00 1.05891209e+01 6.89300680e+00 4.46608543e+00 4.15486431e+00 4.29474020e+00 4.48508358e+00 2.90377092e+00 1.21726000e+00 3.08009839e+00 6.06371355e+00 7.60660267e+00 5.10101557e+00 1.09370100e+00 8.27215314e-02 3.26110649e+00 6.79227018e+00 7.65855074e+00 6.32596874e+00 6.32739544e+00 5.88950682e+00 6.30756235e+00 6.63657713e+00 6.78641462e+00 6.91186762e+00 7.21559620e+00 8.88235188e+00 8.95684624e+00 8.48844719e+00 7.58659554e+00 4.41333055e+00 2.54300117e+00 4.15927052e-01 2.03591347e+00 4.56114149e+00 7.24452257e+00 9.13770866e+00 5.31417990e+00 2.11830211e+00 1.66796970e+00 5.37592888e+00 7.32256985e+00 5.97030401e+00 4.06196737e+00 5.87560797e+00 7.19776678e+00 6.39137650e+00 3.40691137e+00 2.04836464e+00 3.78291202e+00 3.54169917e+00 4.17460060e+00 4.18629074e+00 5.95118093e+00 4.81114483e+00 3.78364134e+00 2.69893765e+00 1.44853687e+00 1.62995195e+00 2.45062423e+00 5.55977535e+00 7.67438984e+00 5.90601969e+00 1.46251261e+00 -1.81021258e-01 1.85183239e+00 2.96704316e+00 1.92876971e+00 9.50533152e-01 3.50879455e+00 5.08544779e+00 5.48246145e+00 4.95233393e+00 5.16907740e+00 5.46107817e+00 4.13674307e+00 4.07729053e+00 5.41254711e+00 7.09090328e+00 6.49479914e+00 7.10797882e+00 8.66299438e+00 8.68449593e+00 6.23125410e+00 3.91041422e+00 4.17248249e+00 5.00529814e+00 4.74342346e+00 3.15803599e+00 3.98530936e+00 5.15881824e+00 5.16131830e+00 3.43532181e+00 2.27789664e+00 3.39088535e+00 3.85105157e+00 4.64217424e+00 4.28632355e+00 5.89792013e+00 7.16578627e+00 6.63518000e+00 5.49246693e+00 4.93448400e+00 5.97654581e+00 6.35487700e+00 7.07520533e+00 8.06991386e+00 7.77374601e+00 6.94063711e+00 5.92536068e+00 6.82132196e+00 7.94480133e+00 6.74022150e+00 4.18815422e+00 3.79754925e+00 5.42049170e+00 6.50322628e+00 4.90084028e+00 3.45562148e+00 4.35116768e+00 5.52302313e+00 6.84899664e+00 7.21651411e+00 8.10339928e+00 8.26035690e+00 7.42201424e+00 6.79477310e+00 6.66243362e+00 6.88386488e+00 6.39234066e+00 6.69618988e+00 7.59776831e+00 7.00572252e+00 5.24538422e+00 4.09606075e+00 4.58225203e+00 5.13975382e+00 4.53113937e+00 3.89900947e+00 4.69016027e+00 5.18772507e+00 5.26858330e+00 4.32041693e+00 4.61194897e+00 5.34521341e+00 5.37964439e+00 5.42315722e+00 5.66005898e+00 7.07146692e+00 7.47143459e+00 6.82152176e+00 5.73646355e+00 4.95112324e+00 5.23687363e+00 5.66914797e+00 6.44300747e+00 7.97010517e+00 7.71914148e+00 5.68507862e+00 3.31490326e+00 2.41285610e+00 3.73883843e+00 4.47580862e+00 4.44752979e+00 4.31850100e+00 3.71390820e+00 4.47048807e+00 4.58626509e+00 5.11902857e+00 5.01573801e+00 3.59388876e+00 3.20962715e+00 3.40002322e+00 5.37087250e+00 6.65421581e+00 5.89181137e+00 4.89137173e+00 4.48282623e+00 5.70797729e+00 6.69061613e+00 6.48700428e+00 6.35546589e+00 5.72844315e+00 5.18448544e+00 4.81236792e+00 4.44611359e+00 4.94310045e+00 5.43448973e+00 5.81733465e+00 5.83180618e+00 4.95549536e+00 4.43607569e+00 4.05768251e+00 4.56291914e+00 5.53255320e+00 5.59789610e+00 5.60295820e+00 5.67815447e+00 6.37518215e+00 6.30787420e+00 5.19088507e+00 4.54126549e+00 4.52783537e+00 5.12661028e+00 5.44635725e+00 5.48421431e+00 5.75894451e+00 5.72574615e+00 5.46114683e+00 5.26802778e+00 5.01534986e+00 5.17509651e+00 5.15456247e+00 5.19285488e+00 5.26314211e+00 5.30711126e+00 5.73337889e+00 5.82543707e+00 5.78385258e+00 5.64406252e+00 5.35639668e+00 5.30921936e+00 5.32959366e+00 5.65428829e+00 5.86327124e+00 5.84279299e+00 5.67997837e+00 5.54902887e+00 5.63499022e+00 5.74022675e+00 5.75869226e+00 5.73062038e+00 5.69987202e+00 5.68400574e+00 5.68418646e+00 5.69970655e+00 5.69183874e+00 5.66093731e+00 5.62729979e+00 5.65667343e+00 5.82328033e+00 5.93310547e+00 5.92638826e+00 5.73532391e+00 5.54674387e+00 5.63824940e+00 5.86894226e+00 6.01785707e+00 5.80904055e+00 5.52998686e+00 5.55913830e+00 5.69463158e+00 5.86018229e+00 5.81974411e+00 5.74766350e+00 5.88282728e+00 5.93840313e+00 5.92082071e+00 5.91951561e+00 5.83316278e+00 6.11799192e+00 6.01342535e+00 6.00115299e+00 5.84359503e+00 5.68695068e+00 6.04353762e+00 5.73491764e+00 5.48496103e+00 4.86608124e+00 5.07894278e+00 5.97875309e+00 6.63891792e+00 6.80570269e+00 5.77865934e+00 5.01496077e+00 4.82529402e+00 5.21245623e+00 5.87561941e+00 5.99388218e+00 5.56648970e+00 5.15976048e+00 4.64250326e+00 5.08452892e+00 5.89894962e+00 6.79152727e+00 6.88368130e+00 5.60568523e+00 4.65505552e+00 4.18365240e+00 4.62249756e+00 5.88502645e+00 6.83560753e+00 6.96803665e+00 5.61869097e+00 4.41610479e+00 4.87308073e+00 6.07014418e+00 6.96383476e+00 6.12488365e+00 4.72298908e+00 4.56215477e+00 4.96507788e+00 6.21358681e+00 6.90856171e+00 6.97696447e+00 6.83032846e+00 5.95009041e+00 5.17020130e+00 5.05964661e+00 5.36542892e+00 6.64505434e+00 6.45846033e+00 5.85823870e+00 5.27795744e+00 4.36316299e+00 5.31048250e+00 5.44827890e+00 5.52129936e+00 4.35834408e+00 3.99739981e+00 6.36851120e+00 7.74429035e+00 7.81029892e+00 5.42726135e+00 3.65613890e+00 3.63082695e+00 4.40761614e+00 6.10037327e+00 7.17402315e+00 7.16602659e+00 6.85732651e+00 5.79716015e+00 5.47323322e+00 5.86203337e+00 5.58112764e+00 5.81546688e+00 4.10360765e+00 4.02090597e+00 4.02724552e+00 4.43388319e+00 6.21565437e+00 6.27586412e+00 5.38743877e+00 2.73270583e+00 1.70428729e+00 2.50418544e+00 4.07999754e+00 5.63566589e+00 4.71034670e+00 2.83080578e+00 1.94452715e+00 2.51572895e+00 4.24897242e+00 5.12497330e+00 5.40202999e+00 5.56415129e+00 5.68091679e+00 5.85249901e+00 5.79115295e+00 6.59599209e+00 7.84247637e+00 6.59088707e+00 3.99578810e+00 2.71655631e+00 3.83014369e+00 6.75208807e+00 8.00167561e+00 7.42441750e+00 4.63518953e+00 2.94004822e+00 4.15574694e+00 5.33234882e+00 6.02174091e+00 4.97550106e+00 4.63817930e+00 5.64364004e+00 6.49777794e+00 7.52623415e+00 7.87589550e+00 7.44708252e+00 7.90530777e+00 6.60136700e+00 6.12567806e+00 6.07696438e+00 5.55144787e+00 6.86088324e+00 5.86422968e+00 6.06929159e+00 4.85328007e+00 4.19638395e+00 6.43197060e+00 6.34585476e+00 6.66307783e+00 4.43801498e+00 3.47318482e+00 5.02850819e+00 5.76627922e+00 8.82533932e+00 7.65955257e+00 5.22562265e+00 2.56571245e+00 1.86988437e+00 5.20467758e+00 5.68424606e+00 4.99055958e+00 5.14401102e+00 6.01897526e+00 6.62951899e+00 3.34961987e+00 2.31324553e+00 5.52666950e+00 6.85795212e+00 6.70642996e+00 1.31014478e+00 1.26703525e+00 -1.16049223e+01 -1.73756123e+01 -2.14717209e+02 -6.15338928e+02 16171671. 235114896. 8265405. 6.00705350e+06 -247559168. 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. 0. 0. 0. 0. 0. 0. 0. -213221008. -1.42785364e+03 -2.36642105e+02 -4.11480942e+01 -1.36156464e+01 -4.28868055e-01 7.34063911e+00 9.00866795e+00 9.93142414e+00 5.90546894e+00 4.28862906e+00 4.55357552e+00 4.18767691e+00 5.70491934e+00 6.65556765e+00 6.47666454e+00 4.59536362e+00 2.97856188e+00 4.17386723e+00 6.03832054e+00 6.87060356e+00 7.58429003e+00 7.07324505e+00 6.24598026e+00 3.68158937e+00 2.51641369e+00 6.35195446e+00 7.65841198e+00 5.48501301e+00 6.69263542e-01 2.38233566e+00 6.95862007e+00 8.16171074e+00 6.24626780e+00 3.67916465e+00 3.65956664e+00 4.19526958e+00 4.05538559e+00 4.86741638e+00 5.96274519e+00 6.36686373e+00 5.38428116e+00 3.03971243e+00 4.71270466e+00 6.23715830e+00 8.90420055e+00 1.22809010e+01 1.07147512e+01 4.86866283e+00 -2.88245821e+00 -2.90049362e+00 3.75700998e+00 5.49416256e+00 4.40063667e+00 -3.70490134e-01 -1.27385139e-01 3.21088815e+00 4.85106277e+00 5.89894295e+00 4.08691168e+00 4.44432449e+00 5.33035707e+00 5.73957109e+00 8.45308590e+00 1.07250147e+01 1.04598236e+01 7.34663343e+00 4.39211941e+00 5.45870829e+00 6.74541712e+00 9.31599236e+00 1.23540192e+01 1.39423895e+01 1.43146734e+01 1.07751760e+01 8.55309868e+00 1.00172815e+01 7.49399853e+00 3.84596276e+00 -3.18511939e+00 -2.28974438e+00 2.70217228e+00 4.80393696e+00 6.29296303e+00 6.34536552e+00 6.54438448e+00 4.81363010e+00 2.24461746e+00 3.89920616e+00 5.67042494e+00 5.19158506e+00 5.32054663e+00 6.62798309e+00 9.94349957e+00 8.55657768e+00 5.25900459e+00 7.52086830e+00 7.32376671e+00 7.19402742e+00 2.77837896e+00 1.82097864e+00 7.11721516e+00 7.24490404e+00 4.88933611e+00 -1.95226073e+00 -3.13620114e+00 1.82979691e+00 4.03316212e+00 6.86307049e+00 7.15668726e+00 8.71047974e+00 9.08269691e+00 6.56257248e+00 6.49208784e+00 6.91315126e+00 7.47048473e+00 6.13510752e+00 2.84042239e+00 3.78942227e+00 3.84962130e+00 2.85650182e+00 5.64257479e+00 5.54573774e+00 4.08395576e+00 -2.34223485e+00 -3.04331994e+00 4.45950222e+00 6.91178322e+00 3.79316068e+00 -2.45488667e+00 -2.88603950e+00 2.88137960e+00 4.75485134e+00 6.27624035e+00 5.85614538e+00 4.31436872e+00 1.72942436e+00 -1.71839452e+00 1.16237676e+00 4.46675158e+00 4.84221601e+00 2.61190152e+00 -9.19850469e-01 1.41676688e+00 2.94946861e+00 3.47268987e+00 5.71766663e+00 6.35314465e+00 8.19062996e+00 7.02262115e+00 6.28864336e+00 8.27676678e+00 7.46318007e+00 5.66634274e+00 -3.23690563e-01 -4.09468842e+00 -2.67991686e+00 -4.86370564e-01 3.55471063e+00 4.45875168e+00 6.33136654e+00 8.43972111e+00 8.70021057e+00 7.37021112e+00 6.49991369e+00 7.09500933e+00 8.70936203e+00 5.86013317e+00 5.48532009e-01 -3.90772176e+00 -5.18991709e+00 2.00776148e+00 4.41201401e+00 2.89847064e+00 -1.43449652e+00 -6.93942726e-01 3.31562567e+00 2.85585642e+00 3.89814925e+00 4.14810848e+00 4.29819584e+00 2.17226076e+00 3.09636921e-01 2.81716490e+00 5.10390282e+00 4.36325502e+00 4.54463720e+00 5.22754526e+00 7.81137705e+00 1.09288597e+01 1.30394897e+01 1.48460064e+01 8.16851807e+00 3.11716151e+00 -1.13179348e-02 2.76515096e-01 5.15966225e+00 4.53657675e+00 2.50644326e+00 -4.68087626e+00 -4.57138681e+00 6.61186278e-01 5.30412722e+00 7.36717319e+00 5.69140673e+00 7.30409384e+00 9.14405441e+00 8.58440685e+00 7.23878717e+00 6.86321545e+00 7.31571198e+00 5.74648380e+00 2.28383565e+00 2.20472908e+00 -1.21154487e+00 -1.21822643e+00 4.67838669e+00 1.07800045e+01 1.03827400e+01 3.45936918e+00 4.86034781e-01 1.57609761e+00 -7.83581734e-01 -3.79336953e+00 -6.76483536e+00 -7.99997044e+00 -4.65101862e+00 -1.55399561e+00 4.13353539e+00 5.51068306e+00 1.63992643e+00 -2.87806129e+00 -3.96180916e+00 -5.18488109e-01 1.41388392e+00 1.64020956e-01 2.86550075e-01 -7.25970641e-02 -2.96558142e-01 -7.25913346e-01 -6.63602725e-02 9.42889228e-02 5.00823915e-01 1.02239490e-01 -7.94875026e-01 -2.72452140e+00 -3.44108009e+00 -2.30427313e+00 -6.15325451e-01 -3.69892567e-01 -1.24462402e+00 -8.07477713e-01 -5.44211209e-01 2.09477568e+00 3.58136296e+00 3.61521959e+00 1.30427849e+00 -1.57026398e+00 -8.52530956e-01 -6.21925354e-01 -7.83903375e-02 -3.07847559e-01 9.09154356e-01 6.18684053e-01 3.98202926e-01 -7.09283113e-01 -3.61530751e-01 -1.41658092e+00 -2.34924412e+00 -2.03656292e+00 -1.43991601e+00 -2.20808768e+00 -2.61929131e+00 -2.39457440e+00 -1.85756195e+00 -2.15604687e+00 -1.99381709e+00 -9.86303508e-01 -1.60686362e+00 -2.20323706e+00 -2.35996270e+00 -1.28720355e+00 -1.33703506e+00 -2.45054650e+00 -3.30503654e+00 -2.78176236e+00 -3.34798884e+00 -4.19179916e+00 -4.62014008e+00 -3.24722672e+00 -2.23865485e+00 -2.14685202e+00 -2.40915036e+00 -2.42138362e+00 -2.58084297e+00 -1.97284842e+00 -1.99305043e-01 1.43340349e+00 1.21190000e+00 -3.66187915e-02 -9.55619037e-01 -1.47622514e+00 -1.38131726e+00 -1.26371694e+00 -9.47437346e-01 -1.45942295e+00 -1.61774075e+00 -1.20341146e+00 -1.31110585e+00 -3.08564520e+00 -4.41695881e+00 -4.39286900e+00 -2.83505011e+00 -1.86955309e+00 -9.93694901e-01 4.36589401e-03 9.72727314e-02 -8.08001757e-01 -2.00910020e+00 -1.86780274e+00 -6.57604516e-01 -1.89789987e+00 -4.11138010e+00 -4.58847237e+00 -2.91120434e+00 -5.80807984e-01 -5.63589454e-01 -3.17783087e-01 -2.31577680e-02 -1.78510964e+00 -4.53216171e+00 -5.60404301e+00 -4.71301031e+00 -2.79584932e+00 -2.67115784e+00 -2.45889783e+00 -2.00113583e+00 -1.68364048e+00 -1.45205760e+00 -1.64628732e+00 -1.59824848e+00 -2.38227630e+00 -2.51992488e+00 -1.82440770e+00 -4.04426962e-01 1.49056733e+00 2.44760823e+00 2.02869630e+00 3.90925735e-01 -8.47690344e-01 -1.80106498e-02 4.25084591e-01 -1.07578897e+00 -3.28080893e+00 -4.53639507e+00 -2.74634600e+00 -9.56384242e-01 -1.30736426e-01 -1.28880501e+00 -1.96785152e+00 -2.04661202e+00 -1.68060434e+00 6.14544928e-01 2.66465211e+00 -6.92654967e-01 -6.47618198e+00 -7.92843962e+00 -5.11001968e+00 -1.72564709e+00 -2.03207445e+00 -2.36878443e+00 -2.85221076e+00 -2.55163383e+00 -2.08519244e+00 -2.45159793e+00 -4.16459131e+00 -6.14336014e+00 -4.71173382e+00 -1.13571632e+00 1.29844809e+00 -4.05052423e-01 -2.95328331e+00 -4.06446075e+00 -3.98043466e+00 -4.06669235e+00 -4.67659521e+00 -6.46546221e+00 -7.68143034e+00 -6.38736200e+00 -4.27915239e+00 -3.50068617e+00 -4.45172834e+00 -4.45356846e+00 -3.43700814e+00 -3.36685085e+00 -3.64355779e+00 -3.88186812e+00 -4.25519276e+00 -4.83093309e+00 -5.64439297e+00 -4.70973158e+00 -3.85882282e+00 -3.30457950e+00 -2.18989611e+00 -2.44481698e-01 2.43402910e+00 3.58145547e+00 1.68016720e+00 -6.72972918e-01 -2.32772470e+00 -2.45401740e+00 -2.27793622e+00 -1.65878761e+00 -1.65187621e+00 -2.16261697e+00 -2.71697068e+00 -2.92098832e+00 -3.28961492e+00 -1.95068669e+00 -1.74853593e-01 3.46967638e-01 -1.31786335e+00 -3.44903708e+00 -3.66016507e+00 -3.77788925e+00 -4.08936977e+00 -4.86298370e+00 -5.04505014e+00 -4.66352844e+00 -4.02364254e+00 -3.45484757e+00 -3.22386146e+00 -3.39118242e+00 -4.81674862e+00 -5.55313063e+00 -5.54639196e+00 -5.05972290e+00 -4.46342659e+00 -4.75346899e+00 -5.25653267e+00 -5.64731312e+00 -5.20613289e+00 -4.15280914e+00 -3.27386403e+00 -3.02499580e+00 -3.29241467e+00 -4.28003168e+00 -5.52346516e+00 -6.12465763e+00 -4.90697718e+00 -3.69484401e+00 -2.90953135e+00 -2.65408444e+00 -2.07243848e+00 -1.51621437e+00 -1.88080990e+00 -1.92907727e+00 -6.84825325e+00 -1.64963112e+01 -3.05463409e+01 -1.64675293e+01 -2.05337433e+02 -1.09512488e+03 30641686. 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. 0. 0. 0. 0. 0. 0. 2.02376758e+04 -1.30890320e+02 -2.50810089e+01 -1.42645960e+01 -2.60341191e+00 -1.96548355e+00 -1.53889215e+00 -5.27680445e+00 -3.92426157e+00 -3.47100067e+00 -3.84042406e+00 -5.85618353e+00 -8.00586128e+00 -8.40532970e+00 -7.71567059e+00 -6.86207199e+00 -7.34355068e+00 -7.45540285e+00 -7.40580177e+00 -7.09832144e+00 -6.72417831e+00 -6.75550413e+00 -6.32301188e+00 -5.65638924e+00 -5.38226414e+00 -5.49087191e+00 -5.78789186e+00 -5.11111784e+00 -4.71016645e+00 -4.39397907e+00 -4.35145235e+00 -4.57876778e+00 -4.58974028e+00 -4.74154043e+00 -4.35315228e+00 -4.15757656e+00 -4.01544380e+00 -4.42774820e+00 -4.39840126e+00 -4.31833839e+00 -3.99789023e+00 -4.56878424e+00 -4.99269247e+00 -5.19085121e+00 -4.82718468e+00 -4.38376236e+00 -4.01864767e+00 -3.61621022e+00 -3.96039510e+00 -3.66144300e+00 -3.51939678e+00 -3.34990501e+00 -3.89391971e+00 -4.60866880e+00 -4.55136204e+00 -4.31666708e+00 -4.36499643e+00 -4.45447683e+00 -4.55096817e+00 -4.40037632e+00 -4.35504532e+00 -4.61522293e+00 -4.66971397e+00 -5.93869305e+00 -7.00083685e+00 -7.33304548e+00 -7.02339411e+00 -6.65514183e+00 -7.40956450e+00 -7.86162519e+00 -7.19091034e+00 -6.36852264e+00 -5.30126810e+00 -5.06157446e+00 -4.86543083e+00 -4.17741060e+00 -3.36878681e+00 -2.63882089e+00 -2.73782015e+00 -3.66113544e+00 -4.45714140e+00 -4.98936415e+00 -5.11561871e+00 -5.03685188e+00 -5.84294462e+00 -6.56097603e+00 -7.53465796e+00 -7.73343515e+00 -7.34624481e+00 -6.63862705e+00 -5.90526438e+00 -5.77732944e+00 -5.95348692e+00 -6.73928308e+00 -7.36063290e+00 -7.04498243e+00 -6.27550554e+00 -5.69170666e+00 -5.83655453e+00 -6.09533978e+00 -6.28417635e+00 -6.55588388e+00 -5.78149271e+00 -4.96477938e+00 -4.56712914e+00 -4.90854883e+00 -5.53613472e+00 -5.52509022e+00 -5.69617987e+00 -6.06172705e+00 -6.36461735e+00 -6.85564280e+00 -6.79387951e+00 -6.20157528e+00 -5.41503716e+00 -4.71061039e+00 -4.78481770e+00 -4.97630692e+00 -5.22001886e+00 -5.30333185e+00 -5.14877844e+00 -5.09993553e+00 -5.16060066e+00 -5.32569265e+00 -5.44742346e+00 -5.55830097e+00 -5.59091520e+00 -5.59428596e+00 -5.65044546e+00 -6.15791893e+00 -6.65953112e+00 -6.65844965e+00 -6.28095961e+00 -5.84060001e+00 -6.08686256e+00 -6.34970999e+00 -6.73214483e+00 -6.79143476e+00 -6.49686241e+00 -6.04717255e+00 -5.65245438e+00 -5.55302000e+00 -5.55399799e+00 -5.53754616e+00 -5.52378035e+00 -5.47318363e+00 -5.43534327e+00 -5.47142315e+00 -5.59149075e+00 -5.64191103e+00 -5.61428690e+00 -5.61739588e+00 -5.66467094e+00 -5.76949692e+00 -5.98080397e+00 -6.18641090e+00 -6.13008881e+00 -5.91290140e+00 -5.70937777e+00 -5.86805010e+00 -6.02135515e+00 -6.11931705e+00 -6.10176945e+00 -6.10282755e+00 -6.08867359e+00 -5.95850134e+00 -5.86459160e+00 -5.74428368e+00 -5.72386360e+00 -5.69558907e+00 -5.68790340e+00 -5.70765066e+00 -5.70434713e+00 -5.70176554e+00 -5.69397688e+00 -5.69526052e+00 -5.68768644e+00 -5.68411207e+00 -5.70770502e+00 -5.72931767e+00 -5.71354485e+00 -5.67984009e+00 -5.66331625e+00 -5.65560770e+00 -5.67131662e+00 -5.71485853e+00 -5.66677904e+00 -5.55156755e+00 -5.51437616e+00 -5.58936930e+00 -5.69949865e+00 -5.66761446e+00 -5.62906837e+00 -5.60931683e+00 -5.64041281e+00 -5.62450743e+00 -5.61589098e+00 -5.57479334e+00 -5.56505680e+00 -5.55606604e+00 -5.55287075e+00 -5.55382347e+00 -5.74274158e+00 -5.97361803e+00 -5.98638821e+00 -5.82377625e+00 -5.58549547e+00 -5.70221949e+00 -5.68232059e+00 -5.58890486e+00 -5.51049709e+00 -5.48261261e+00 -5.55018759e+00 -5.56833315e+00 -5.59872389e+00 -5.56420803e+00 -5.48949289e+00 -5.53680134e+00 -5.61047888e+00 -5.62058973e+00 -5.63970613e+00 -5.63000154e+00 -5.75560427e+00 -5.72012043e+00 -5.66550827e+00 -5.61552238e+00 -5.67322683e+00 -6.02467823e+00 -6.28154135e+00 -6.29120636e+00 -6.08518410e+00 -5.80076647e+00 -5.91262197e+00 -5.83010674e+00 -6.00817871e+00 -6.13285208e+00 -6.19402361e+00 -6.07334805e+00 -5.89415359e+00 -6.09338951e+00 -6.15326643e+00 -6.11052370e+00 -5.80224085e+00 -5.51838589e+00 -5.46673775e+00 -5.98992062e+00 -6.61654186e+00 -6.84381342e+00 -6.35563517e+00 -4.86078262e+00 -3.84206247e+00 -3.85439682e+00 -4.73303604e+00 -5.41909075e+00 -4.57406521e+00 -3.94382787e+00 -4.09095526e+00 -5.03321791e+00 -5.74949121e+00 -5.73383856e+00 -5.69809198e+00 -5.61616755e+00 -5.48731661e+00 -5.61877537e+00 -5.74998665e+00 -5.71880293e+00 -5.39766550e+00 -5.03803968e+00 -5.53546953e+00 -6.00812864e+00 -6.17358303e+00 -5.45162487e+00 -4.88147831e+00 -4.83165407e+00 -4.85979700e+00 -4.81016779e+00 -4.82389450e+00 -4.68411064e+00 -4.77751255e+00 -4.12889385e+00 -3.66432476e+00 -3.85556746e+00 -4.78229713e+00 -5.76456690e+00 -5.81239700e+00 -5.57830381e+00 -5.13395166e+00 -4.92981863e+00 -5.69444895e+00 -6.76163578e+00 -6.76622343e+00 -5.96052074e+00 -4.97124863e+00 -5.33396816e+00 -5.40797472e+00 -5.38406801e+00 -5.11012650e+00 -4.07365990e+00 -2.95599508e+00 -2.96895742e+00 -3.85060501e+00 -5.25351334e+00 -5.25596857e+00 -5.18247938e+00 -5.08973598e+00 -5.06539154e+00 -4.25722742e+00 -2.97698522e+00 -2.68782306e+00 -3.17305756e+00 -4.40770245e+00 -4.31699562e+00 -4.51048088e+00 -4.57703161e+00 -4.92129517e+00 -4.68618250e+00 -4.30625629e+00 -3.87332106e+00 -4.18165159e+00 -4.56857586e+00 -4.84119177e+00 -4.82435036e+00 -5.15026569e+00 -5.55157852e+00 -5.85952711e+00 -6.14569712e+00 -5.84700918e+00 -4.42089415e+00 -2.52289915e+00 -1.25962901e+00 -9.41817582e-01 -1.10824025e+00 -1.49058914e+00 -3.60107040e+00 -4.57068682e+00 -5.58610487e+00 -5.07778692e+00 -5.07827234e+00 -3.99330068e+00 -2.48885322e+00 -2.83664131e+00 -3.53105378e+00 -5.87502623e+00 -7.08565426e+00 -7.46249676e+00 -6.59885645e+00 -5.14597464e+00 -4.71481514e+00 -3.84593916e+00 -2.16744876e+00 -1.11369383e+00 -2.04441619e+00 -3.90907741e+00 -6.02351236e+00 -4.85301685e+00 -3.30606389e+00 -2.31551003e+00 -2.52725816e+00 -3.79390216e+00 -4.69382191e+00 -6.17019033e+00 -6.19173956e+00 -5.87229300e+00 -5.87185144e+00 -5.89380312e+00 -5.80867815e+00 -5.63352013e+00 -5.29411936e+00 -5.19603157e+00 -5.01735210e+00 -4.79258776e+00 -4.30238771e+00 -2.45480752e+00 -3.41530442e-01 -1.77499628e+00 -4.63033295e+00 -5.39949799e+00 -2.28721189e+00 -5.47118247e-01 -1.51738000e+00 -3.30677366e+00 -1.99918807e+00 -8.79859567e-01 -6.81217611e-01 -2.00876188e+00 -3.69429183e+00 -3.59977531e+00 -3.29572558e+00 -2.31780910e+00 -2.36514902e+00 -2.83399034e+00 -3.74484944e+00 -4.05499125e+00 -4.04144764e+00 -3.31094217e+00 -3.20257354e+00 -2.54948068e+00 -1.79507756e+00 -2.09904820e-01 -2.21739984e+00 -5.65047503e+00 -5.41736603e+00 -1.95058656e+00 2.83226371e-01 -2.12779832e+00 -3.90813279e+00 -2.97570062e+00 -1.83695114e+00 -3.32610464e+00 -5.87558460e+00 -7.29389524e+00 -6.69540405e+00 -6.17450142e+00 -4.45684004e+00 -2.19219398e+00 -2.03738070e+00 -4.27952147e+00 -4.61661577e+00 -1.58349037e+00 -1.19883132e+00 -3.02681899e+00 -5.68492365e+00 -5.66484690e+00 -5.46495962e+00 -6.72386980e+00 -8.13583946e+00 -6.64497042e+00 -3.76754904e+00 -1.43731368e+00 -2.59493065e+00 -3.47499561e+00 -3.45356226e+00 -3.36574769e+00 -3.26239920e+00 -3.21940589e+00 -3.49700308e+00 -4.79647827e+00 -4.74430418e+00 -3.01837850e+00 -6.85185671e-01 -1.27402335e-01 -1.02382827e+00 2.02442810e-01 2.83875632e+00 1.64314795e+00 -2.20810270e+00 -6.35044336e+00 -6.75858307e+00 -5.08681726e+00 -5.34712362e+00 -5.78567886e+00 -5.44186401e+00 -3.83855438e+00 -2.12068248e+00 -2.19581819e+00 -3.04763937e+00 -3.73489785e+00 -5.20789623e+00 -5.54147768e+00 -5.25657225e+00 -4.86182594e+00 -4.91677904e+00 -5.05699348e+00 -2.84407830e+00 -1.23489690e+00 -2.03153086e+00 -4.07488966e+00 -4.64570141e+00 -2.99351788e+00 -4.05505180e+00 -6.14515257e+00 -5.55438042e+00 -9.51579452e-01 4.27957964e+00 5.18160486e+00 3.34701920e+00 2.48348093e+00 3.30364418e+00 2.42493820e+00 7.97402263e-01 -7.18219161e-01 -2.47911379e-01 -4.47559208e-01 1.60924554e-01 1.89477539e+00 1.82492125e+00 -4.69500721e-01 -3.75265694e+00 -2.45414519e+00 4.98066604e-01 1.04609549e+00 -1.68180215e+00 -1.64290524e+00 1.00622153e+00 -8.57725501e-01 -6.62955332e+00 -1.04554920e+01 -8.18387413e+00 -4.91098976e+00 -5.98730183e+00 -8.50978470e+00 -9.04237175e+00 -7.17706871e+00 -5.91011477e+00 -7.35307121e+00 -8.04007244e+00 -7.32391024e+00 -5.14632893e+00 -1.78260958e+00 1.84579349e+00 3.79016066e+00 3.81627011e+00 -1.15442717e+00 -5.27933979e+00 -7.31463099e+00 -4.81481552e+00 -2.79709816e+00 -2.81692195e+00 -3.12837577e+00 -4.82720232e+00 -7.99801779e+00 -7.20817995e+00 -4.28602219e+00 -1.21893263e+00 -1.20988655e+00 -1.16837502e+00 1.90239275e+00 4.32308626e+00 3.77935600e+00 9.20263231e-01 -1.16334724e+00 -1.32937729e+00 -1.57765055e+00 -1.71401024e+00 -7.64542222e-01 -9.12772305e-03 -1.38108939e-01 -1.09717667e+00 -1.76415908e+00 -2.28811526e+00 -2.37238359e+00 -1.89483881e+00 9.18943167e-01 4.72718430e+00 4.73615074e+00 2.55886316e+00 1.98084986e+00 4.46661663e+00 4.14526367e+00 2.03256869e+00 -2.89801449e-01 2.49374247e+00 4.98319149e+00 4.17105341e+00 1.18719923e+00 -3.10083747e+00 -3.37231541e+00 -3.29079247e+00 -6.63727820e-01 2.24411154e+00 2.54148078e+00 1.13384694e-01 3.78876358e-01 3.45615745e+00 4.22116995e+00 1.91281140e+00 -1.63354981e+00 6.96835220e-01 3.66720057e+00 3.36863923e+00 -1.02317631e+00 -4.51252794e+00 -2.61804867e+00 9.56695378e-01 1.67113626e+00 1.68937862e+00 6.33233011e-01 8.55760396e-01 1.61963081e+00 1.90888369e+00 4.86843967e+00 6.41622829e+00 5.74756002e+00 3.30564833e+00 6.78811908e-01 9.65496302e-01 6.00242972e-01 5.99366307e-01 7.05547929e-01 2.32163221e-01 5.36985219e-01 -1.33948192e-01 -8.24735686e-02 -7.47437894e-01 -3.77897859e+00 -6.07269812e+00 -3.00095916e+00 2.54717255e+00 4.66524887e+00 1.17524004e+00 -1.77585363e+00 -1.89067090e+00 -1.54391444e+00 -1.21144354e+00 -1.61288011e+00 -6.74088001e-01 -8.28462243e-02 5.58476448e-01 2.33747125e+00 5.91212130e+00 1.72822819e+01 4.11068115e+01 2.61785221e+01 1.70237217e+01 3.49541290e+02 9.56964355e+02 -3.33246656e+05 652480832. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.21156454e+09 -10230335. 1.40187463e+03 8.91628563e-01 -1.19857407e+02 -3.02955780e+01 -2.03149567e+01 -8.30418396e+00 -3.44912267e+00 -5.70313394e-01 1.05757666e+00 1.28484881e+00 9.23941433e-01 5.27469397e-01 4.68256027e-02 -3.50969099e-03 -2.53926545e-01 2.91333914e-01 9.62750912e-01 1.61597478e+00 1.58093703e+00 5.73838770e-01 -3.57369155e-01 -1.01847780e+00 -1.13666153e+00 -4.87500221e-01 -3.63081098e-01 -2.15910733e-01 4.79341477e-01 8.60309899e-01 6.62218690e-01 -4.71695185e-01 -1.23342383e+00 -1.28337467e+00 -6.48267865e-01 5.20079136e-01 9.37658787e-01 8.89334738e-01 8.16332340e-01 7.65156984e-01 5.77365458e-01 -1.63272470e-01 -7.62111068e-01 -3.26337457e-01 4.60113078e-01 8.80305290e-01 4.13560361e-01 5.08791208e-01 7.59508729e-01 4.38539654e-01 3.06809485e-01 2.97146142e-01 6.01058543e-01 1.04548788e+00 1.32640123e+00 1.42137587e+00 4.84403551e-01 -7.34941065e-01 -1.00321352e+00 -3.21954489e-01 9.89348471e-01 1.12478745e+00 3.63726467e-01 -6.57719910e-01 -5.58649659e-01 3.32258306e-02 3.15980643e-01 7.64114410e-02 8.91736969e-02 7.90550232e-01 1.73299861e+00 1.38305163e+00 1.10484529e+00 8.85678530e-01 8.33920121e-01 8.68570507e-01 4.39495713e-01 7.64185548e-01 1.17598712e+00 1.80634606e+00 1.83515489e+00 1.16248631e+00 3.23033035e-01 -3.37617218e-01 -4.37070698e-01 3.31345469e-01 5.14549851e-01 6.52397811e-01 1.16527069e+00 1.94875038e+00 2.03941798e+00 9.64952946e-01 -1.06349140e-02 -9.92461480e-03 1.04241812e+00 2.09472680e+00 2.21136618e+00 2.05713725e+00 2.07318115e+00 2.13275123e+00 1.87236118e+00 1.42770958e+00 1.14624846e+00 1.40904534e+00 1.93505478e+00 2.59289026e+00 2.77440476e+00 2.06685758e+00 1.01217496e+00 1.59639433e-01 7.80309021e-01 1.60508657e+00 1.78929520e+00 1.81108510e+00 1.99334419e+00 1.95732403e+00 1.69796336e+00 1.29274869e+00 1.41441607e+00 2.13188100e+00 2.55393052e+00 2.77075934e+00 2.22643900e+00 1.68681574e+00 9.23630953e-01 5.02533257e-01 -2.80750918e+00 -2.00728912e+01 -1.58331528e+02 -2.85140350e+02 -1.55255833e+01 -1.56808262e+01 -4.15312767e+00 9.95179749e+00 3.28048553e+02 1.97400681e+02 4.07782860e+01 -7.56681871e+00 -3.19770088e+01 -1.62127686e+02 -2.68458313e+02 -8.18006516e+00 4.79857349e+00 2.52961750e+01 3.73847847e+01 3.20680122e+01 2.28051777e+01 1.92998390e+01 1.26473274e+01 1.01131449e+01 1.38951607e+01 2.82187439e+02 1.77031845e+02 3.86557007e+01 1.60009060e+01 -4.00144517e-01 5.04623175e-01 2.92726427e-01 2.11991882e+00 1.55082357e+00 2.19680977e+00 2.53652024e+00 2.05118489e+00 1.57216644e+00 1.48825955e+00 1.43407559e+00 1.36789143e+00 8.77934456e-01 5.49033344e-01 5.61625540e-01 1.43966842e+00 2.44377613e+00 2.62018228e+00 2.56964874e+00 2.62218547e+00 2.53482890e+00 2.36093473e+00 1.62065017e+00 1.43742990e+00 1.80193985e+00 2.56838298e+00 2.69203210e+00 2.22643685e+00 1.96344995e+00 1.79802287e+00 1.77727747e+00 1.75255752e+00 1.75526929e+00 1.68259728e+00 1.89714098e+00 1.75088906e+00 1.43897426e+00 6.46928191e-01 1.61642492e-01 5.29468119e-01 1.74235928e+00 2.93551660e+00 3.03958178e+00 2.74037957e+00 2.63737440e+00 2.54262376e+00 2.25477099e+00 1.59567082e+00 1.48285067e+00 2.18382335e+00 3.01617408e+00 3.22297049e+00 2.69800830e+00 2.29126811e+00 2.31930900e+00 2.29056573e+00 2.39269948e+00 2.22368240e+00 1.98293734e+00 2.23363328e+00 2.63429689e+00 3.04829645e+00 2.45021677e+00 2.02677989e+00 1.56452715e+00 2.31333780e+00 2.71743274e+00 2.93707442e+00 2.66765213e+00 2.50483823e+00 2.34999251e+00 2.32211542e+00 2.47556996e+00 2.72571969e+00 2.82471490e+00 2.85901403e+00 3.13762641e+00 3.24042559e+00 3.37779236e+00 2.96480989e+00 2.43366599e+00 1.89795077e+00 1.72490990e+00 1.92705560e+00 2.40494561e+00 2.91988420e+00 3.42253566e+00 2.63982511e+00 1.99833512e+00 1.81632400e+00 2.59959745e+00 3.17278600e+00 3.00482249e+00 2.80512953e+00 3.05531478e+00 3.16005516e+00 2.96279216e+00 2.42644906e+00 2.30875278e+00 2.55896020e+00 2.69527268e+00 2.69285846e+00 2.53766131e+00 2.52742577e+00 2.47627521e+00 2.55159068e+00 2.64038658e+00 2.33816147e+00 2.29057193e+00 2.13446808e+00 2.65563703e+00 2.96701884e+00 2.87721205e+00 2.13534045e+00 1.92516005e+00 2.17656755e+00 2.37035894e+00 2.15372038e+00 2.04685974e+00 2.43391633e+00 2.73696971e+00 2.81607819e+00 2.70544553e+00 2.67312598e+00 2.73312044e+00 2.50467992e+00 2.48203516e+00 2.64673209e+00 3.04222584e+00 2.90994310e+00 2.96393871e+00 3.09589720e+00 3.22376585e+00 2.86133862e+00 2.54793596e+00 2.59311819e+00 2.78367853e+00 2.74542761e+00 2.49307561e+00 2.61128879e+00 2.73281336e+00 2.80525756e+00 2.57858038e+00 2.50403714e+00 2.68431997e+00 2.75985074e+00 2.94444203e+00 2.84933472e+00 3.02858686e+00 3.13354945e+00 3.06191063e+00 2.94658995e+00 2.82014298e+00 2.90310121e+00 2.92509007e+00 3.07203746e+00 3.27603388e+00 3.22961187e+00 3.10892463e+00 2.99019718e+00 3.10365152e+00 3.24040627e+00 3.05383635e+00 2.67141819e+00 2.62825251e+00 2.87254071e+00 3.07807994e+00 2.88567185e+00 2.56854367e+00 2.59913731e+00 2.77239895e+00 3.06854582e+00 3.11950135e+00 3.19934201e+00 3.21998453e+00 3.19187641e+00 3.12520003e+00 3.15027785e+00 3.17735219e+00 3.08379340e+00 3.07827592e+00 3.19634986e+00 3.19176531e+00 2.91432834e+00 2.62329102e+00 2.65283108e+00 2.75801086e+00 2.79921174e+00 2.72641253e+00 2.88010097e+00 2.96402383e+00 2.95348835e+00 2.81345272e+00 2.85541773e+00 2.97201586e+00 2.99642968e+00 2.96152234e+00 2.97615719e+00 3.09267998e+00 3.22577333e+00 3.12294793e+00 3.00368047e+00 2.86600828e+00 2.98288178e+00 3.10178900e+00 3.27263641e+00 3.48400807e+00 3.44859910e+00 3.10997415e+00 2.72842383e+00 2.55837011e+00 2.73283005e+00 2.84301972e+00 2.86232281e+00 2.87535405e+00 2.79006219e+00 2.90309072e+00 2.93342996e+00 3.03177881e+00 3.01200557e+00 2.78337169e+00 2.72770238e+00 2.80776095e+00 3.12024045e+00 3.31111646e+00 3.20908308e+00 3.05159211e+00 2.99064517e+00 3.15951180e+00 3.30141854e+00 3.29278302e+00 3.24682570e+00 3.14849949e+00 3.06098771e+00 3.01309705e+00 2.95017147e+00 3.01887012e+00 3.10332942e+00 3.17176008e+00 3.17139578e+00 3.04203343e+00 2.95825386e+00 2.89562964e+00 2.94921947e+00 3.10066819e+00 3.11163235e+00 3.13898802e+00 3.15283513e+00 3.27084279e+00 3.26965594e+00 3.10801482e+00 3.00919271e+00 2.99650049e+00 3.07161427e+00 3.11545300e+00 3.12524104e+00 3.15877724e+00 3.16153431e+00 3.12662578e+00 3.10015988e+00 3.06672430e+00 3.08538771e+00 3.08887243e+00 3.09032416e+00 3.09777427e+00 3.10528588e+00 3.16054130e+00 3.17497349e+00 3.17596412e+00 3.15794945e+00 3.11652231e+00 3.10174870e+00 3.10381436e+00 3.14972830e+00 3.18250036e+00 3.17936659e+00 3.15906453e+00 3.13918281e+00 3.15319777e+00 3.16559291e+00 3.17240834e+00 3.16694593e+00 3.16006064e+00 3.15631938e+00 3.15677738e+00 3.15931296e+00 3.15901423e+00 3.15378571e+00 3.14870548e+00 3.15295053e+00 3.18036604e+00 3.19606090e+00 3.19181371e+00 3.16065168e+00 3.13253355e+00 3.15300298e+00 3.18804908e+00 3.21433258e+00 3.18221378e+00 3.13843942e+00 3.13116074e+00 3.14643764e+00 3.17290831e+00 3.16373706e+00 3.14946628e+00 3.17288113e+00 3.17996860e+00 3.17463231e+00 3.14508080e+00 3.14615583e+00 3.17497349e+00 3.17871356e+00 3.17261863e+00 3.16836834e+00 3.15860820e+00 3.19704318e+00 3.13507438e+00 3.09673977e+00 3.01380229e+00 3.04802465e+00 3.17547321e+00 3.27953672e+00 3.31242299e+00 3.16197038e+00 3.03704810e+00 2.99981356e+00 3.04134703e+00 3.14209294e+00 3.17006397e+00 3.13528490e+00 3.07768273e+00 2.99854779e+00 3.06183624e+00 3.16597509e+00 3.27511239e+00 3.27738547e+00 3.10192752e+00 2.96910596e+00 2.89355564e+00 2.95410371e+00 3.15067077e+00 3.30378056e+00 3.30935168e+00 3.10530162e+00 2.91860461e+00 2.98911786e+00 3.17068839e+00 3.28808784e+00 3.14226723e+00 2.92064953e+00 2.90132904e+00 2.97778463e+00 3.18421626e+00 3.28805351e+00 3.27833319e+00 3.25227976e+00 3.12809539e+00 3.03520536e+00 3.02277994e+00 3.07772374e+00 3.26426959e+00 3.21897411e+00 3.09052706e+00 2.97394371e+00 2.75694227e+00 2.92819095e+00 2.97114801e+00 3.05915451e+00 2.87820768e+00 2.80485868e+00 3.15484142e+00 3.30955243e+00 3.32331657e+00 2.98733664e+00 2.75251746e+00 2.77695775e+00 2.94608498e+00 3.23136425e+00 3.35316181e+00 3.27594495e+00 3.20217228e+00 3.03344679e+00 2.99179363e+00 3.05399203e+00 3.02943444e+00 3.06280160e+00 2.79879045e+00 2.77914739e+00 2.76739621e+00 2.83312678e+00 3.08618498e+00 3.14265180e+00 3.01250267e+00 2.64156890e+00 2.45601606e+00 2.56142282e+00 2.78866673e+00 2.97911072e+00 2.80365372e+00 2.50341868e+00 2.37280703e+00 2.48660398e+00 2.73236513e+00 2.84146070e+00 2.87804437e+00 2.93972516e+00 2.95448327e+00 2.98814511e+00 2.97144198e+00 3.09699059e+00 3.26588202e+00 3.01007271e+00 2.55491495e+00 2.25247860e+00 2.36585927e+00 2.83209944e+00 3.15512109e+00 3.15511918e+00 2.77250123e+00 2.49587250e+00 2.61793876e+00 2.84480238e+00 2.92799449e+00 2.79548621e+00 2.73335934e+00 2.88653421e+00 3.04683876e+00 3.23188877e+00 3.31046152e+00 3.25255442e+00 3.27980065e+00 3.08713508e+00 2.95555425e+00 2.91736650e+00 2.84209704e+00 3.05484700e+00 2.95147800e+00 2.95065832e+00 2.77499461e+00 2.79034591e+00 3.29682541e+00 3.24871135e+00 3.18956780e+00 2.73502755e+00 2.53857899e+00 2.59501863e+00 2.65268326e+00 3.20561600e+00 3.15297103e+00 2.75961089e+00 2.33449483e+00 2.21243167e+00 2.77662492e+00 2.84406567e+00 2.74200106e+00 2.78278518e+00 2.93369651e+00 3.06999040e+00 2.59878969e+00 2.48549604e+00 2.93697262e+00 2.24246311e+00 1.79791665e+00 7.59453833e-01 1.01299953e+00 -5.89039087e+00 -1.08827600e+01 -3.73794594e+01 -2.23169907e+02 -5.03847076e+02 235114896. 8265405. 6.00705350e+06 -247559168. 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. 0. 0. 0. 0. 0. 0. 0. -426442016. -2.87915088e+03 -4.31928650e+02 9.59239044e+01 8.51889114e+01 1.57318611e+01 7.94773197e+00 4.54367113e+00 5.72359800e+00 2.27513456e+00 2.07506728e+00 2.23025084e+00 2.16336060e+00 2.33259368e+00 2.44663119e+00 2.42311406e+00 2.23752236e+00 1.92366707e+00 1.96603847e+00 2.22679138e+00 2.34907722e+00 2.49813557e+00 2.32630873e+00 2.19165659e+00 1.75336850e+00 1.64962542e+00 2.26163650e+00 2.54994249e+00 2.16502142e+00 1.49673760e+00 1.75723732e+00 2.51217341e+00 2.62701797e+00 2.37283325e+00 1.98653638e+00 1.98100674e+00 1.89769602e+00 1.80354166e+00 1.84498644e+00 2.06092811e+00 2.23681188e+00 2.15802026e+00 1.87917602e+00 2.01751590e+00 2.26870537e+00 2.71135378e+00 3.24197364e+00 2.93530798e+00 1.68572843e+00 2.10561961e-01 1.88519552e-01 1.48996246e+00 2.11470103e+00 1.99295557e+00 1.33700001e+00 1.35270655e+00 1.73202562e+00 1.84929252e+00 1.96092749e+00 1.78505063e+00 1.88745987e+00 2.03137875e+00 2.07592273e+00 2.53580904e+00 2.87176871e+00 2.76843524e+00 2.31207538e+00 1.86552083e+00 2.00005269e+00 2.08547449e+00 2.47575259e+00 2.97795391e+00 3.28352451e+00 3.30510068e+00 2.75941229e+00 2.35657978e+00 2.61052799e+00 2.17825341e+00 1.65677953e+00 6.42874599e-01 7.40719199e-01 1.51262152e+00 1.81914937e+00 2.00710726e+00 2.00837135e+00 1.99110651e+00 1.78588665e+00 1.36303675e+00 1.76046360e+00 2.23509669e+00 2.21961093e+00 2.15681672e+00 2.37749767e+00 2.89888644e+00 2.57492304e+00 1.82029152e+00 2.06288767e+00 2.04237008e+00 2.03374553e+00 1.37094069e+00 1.24437439e+00 2.00282717e+00 2.03007126e+00 1.64512599e+00 6.86117053e-01 5.07480443e-01 1.22443080e+00 1.58842373e+00 2.00056291e+00 1.93386137e+00 2.16305733e+00 2.17152119e+00 1.90250015e+00 1.90376472e+00 1.96209955e+00 1.97254777e+00 1.71114421e+00 1.10889661e+00 1.16742039e+00 1.19614697e+00 1.42332423e+00 2.27985168e+00 2.20831728e+00 1.68394816e+00 4.01993841e-01 3.33742231e-01 1.45759594e+00 1.83647871e+00 1.36394525e+00 4.75879520e-01 3.72568250e-01 1.23027515e+00 1.83154881e+00 2.43405414e+00 2.30914164e+00 1.79596806e+00 1.01739860e+00 5.65247118e-01 1.10279620e+00 1.69462788e+00 1.67046797e+00 1.20899642e+00 6.40066683e-01 9.47124124e-01 1.16018617e+00 1.18722844e+00 1.57569611e+00 1.62692070e+00 1.93023014e+00 1.66989124e+00 1.57728910e+00 1.94889092e+00 1.86921620e+00 1.41462862e+00 4.20276344e-01 -1.20231561e-01 1.76761746e-01 5.48288286e-01 1.13042259e+00 1.22175491e+00 1.66348720e+00 2.10446572e+00 1.96803868e+00 1.53712785e+00 1.31804478e+00 1.55382299e+00 1.77108943e+00 1.34285688e+00 5.17226636e-01 -1.58312231e-01 -4.09492940e-01 6.76031768e-01 1.02709663e+00 8.32197130e-01 1.92821518e-01 3.04466844e-01 9.65799212e-01 8.97176862e-01 9.96775329e-01 9.64054406e-01 9.08888638e-01 5.94184160e-01 2.86370695e-01 7.38000154e-01 1.11419988e+00 1.02303731e+00 9.62250173e-01 9.82791662e-01 1.39258218e+00 1.99713016e+00 2.44996881e+00 2.43576145e+00 1.17072225e+00 3.43442291e-01 1.11173570e-01 3.31193745e-01 1.05233669e+00 8.59387994e-01 5.46518445e-01 -4.90421206e-01 -3.87491047e-01 4.60653782e-01 1.11125064e+00 1.33837211e+00 9.94363129e-01 1.25569332e+00 1.45922363e+00 1.33219552e+00 1.05067670e+00 1.10932338e+00 1.24751961e+00 1.16312969e+00 6.69268250e-01 5.48960149e-01 -4.62157726e-02 -1.30415976e-01 7.25281775e-01 1.63192284e+00 1.53971553e+00 5.90670347e-01 1.28788054e-01 2.49420777e-01 -1.42773494e-01 -6.20990515e-01 -1.07595372e+00 -1.21425235e+00 -6.60966754e-01 -1.55751973e-01 6.63255394e-01 8.05563271e-01 2.42909983e-01 -3.92668009e-01 -5.47581613e-01 -8.98084044e-02 1.75948381e-01 7.57833421e-02 2.04951525e-01 9.71738324e-02 1.28634684e-02 -1.61291465e-01 -2.82077659e-02 -1.34049460e-01 -1.23864822e-01 -1.99878782e-01 -3.07588786e-01 -5.70254862e-01 -6.86614871e-01 -5.28964579e-01 -3.04228842e-01 -2.72138596e-01 -4.00496483e-01 -3.32484365e-01 -3.20937514e-01 4.69651744e-02 2.25383192e-01 2.52061367e-01 -6.51904196e-02 -4.43787575e-01 -3.64738345e-01 -3.61584872e-01 -3.21244717e-01 -2.86166072e-01 6.17755391e-03 -1.40835755e-02 -1.30060643e-01 -4.12482738e-01 -3.38489532e-01 -5.72040439e-01 -6.49593771e-01 -6.33667767e-01 -5.09199679e-01 -7.25624979e-01 -7.70944595e-01 -7.18543172e-01 -6.22947991e-01 -7.12564349e-01 -7.28275716e-01 -5.57073891e-01 -6.38892710e-01 -7.10259795e-01 -7.67607629e-01 -6.14878178e-01 -6.44288540e-01 -8.22360456e-01 -9.21002865e-01 -8.62952232e-01 -9.76479530e-01 -1.12214375e+00 -1.19676065e+00 -9.56578910e-01 -8.05697441e-01 -8.75095665e-01 -9.82349634e-01 -1.00506175e+00 -9.31504250e-01 -7.84033895e-01 -2.71703124e-01 2.00605318e-01 1.44134760e-01 -3.54375869e-01 -7.45964348e-01 -8.49399030e-01 -8.06635737e-01 -8.40812743e-01 -7.96718776e-01 -8.84647012e-01 -8.65466416e-01 -7.84912109e-01 -8.19134235e-01 -1.16129088e+00 -1.25950491e+00 -1.10724020e+00 -8.62948477e-01 -9.15995896e-01 -9.60735917e-01 -8.42921734e-01 -7.23179758e-01 -8.26617837e-01 -9.64169502e-01 -1.01256478e+00 -8.88038278e-01 -1.09056282e+00 -1.45472181e+00 -1.50762415e+00 -1.28327107e+00 -8.94868374e-01 -8.98163974e-01 -8.77025068e-01 -8.27100039e-01 -1.03569663e+00 -1.37874067e+00 -1.54304874e+00 -1.48031855e+00 -1.22005260e+00 -1.31577396e+00 -1.31243980e+00 -1.29787374e+00 -1.17200518e+00 -1.07758117e+00 -1.08326054e+00 -1.06469941e+00 -1.23874927e+00 -1.30014515e+00 -1.25879252e+00 -1.03006768e+00 -7.47435212e-01 -5.43434262e-01 -6.44040585e-01 -8.32617462e-01 -9.41384077e-01 -8.69331896e-01 -8.51926744e-01 -1.22929764e+00 -1.62116957e+00 -1.93365681e+00 -1.40660906e+00 -7.27310598e-01 -4.41686571e-01 -9.21875894e-01 -1.42282116e+00 -1.51274073e+00 -1.45848942e+00 -1.00539100e+00 -4.85799730e-01 -1.00411439e+00 -1.99417400e+00 -2.36354160e+00 -1.88251460e+00 -1.35272038e+00 -1.42741311e+00 -1.55445743e+00 -1.64968050e+00 -1.60518873e+00 -1.51729202e+00 -1.55015278e+00 -1.98943210e+00 -2.38252091e+00 -2.11653876e+00 -1.39993453e+00 -9.26497102e-01 -1.24706686e+00 -1.62650740e+00 -1.81819212e+00 -1.75417554e+00 -1.84570432e+00 -1.96714282e+00 -2.17783380e+00 -2.27402687e+00 -2.08953214e+00 -1.89028561e+00 -1.88140559e+00 -2.02047849e+00 -1.99948585e+00 -1.85235286e+00 -1.87247300e+00 -1.91806149e+00 -1.92242682e+00 -1.99053526e+00 -2.03391695e+00 -2.16397715e+00 -2.01680136e+00 -1.89196229e+00 -1.79354894e+00 -1.65780795e+00 -1.48950994e+00 -1.25262785e+00 -1.11854184e+00 -1.23848045e+00 -1.40247726e+00 -1.59899247e+00 -1.59705412e+00 -1.57443273e+00 -1.58208025e+00 -1.62451982e+00 -1.73372734e+00 -1.78249156e+00 -1.86049092e+00 -1.92878556e+00 -1.73451376e+00 -1.49410868e+00 -1.44069231e+00 -1.87771761e+00 -2.37612176e+00 -2.38260245e+00 -2.25971699e+00 -2.13374043e+00 -2.25951505e+00 -2.21462059e+00 -2.15383673e+00 -1.82197297e+00 -1.48835933e+00 -1.44528949e+00 -1.69410646e+00 -2.16477346e+00 -2.35965180e+00 -2.40723515e+00 -2.38678527e+00 -2.24095488e+00 -2.27822804e+00 -2.33707857e+00 -2.45297718e+00 -2.38104868e+00 -2.30440664e+00 -2.11949277e+00 -2.13238168e+00 -2.15490627e+00 -2.33096838e+00 -2.47804642e+00 -2.37739754e+00 -2.04103446e+00 -1.89826262e+00 -1.99121034e+00 -2.17249084e+00 -2.15527821e+00 -2.16526914e+00 -2.32363677e+00 -3.87489033e+00 -4.21629620e+00 -5.43598270e+00 -3.59236789e+00 3.31931663e+00 -4.55438948e+00 2.33397675e+01 -1.68435527e+04 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. 0. 0. 0. 0. 0. 0. 4.19125469e+04 -2.02868484e+02 9.78915634e+01 7.97382431e+01 2.29051456e+01 9.63183784e+00 2.61885858e+00 -1.45083153e+00 -3.32256705e-01 -2.22820449e+00 -2.44013739e+00 -2.79408193e+00 -3.13818502e+00 -3.18761730e+00 -3.04612827e+00 -2.93591094e+00 -3.01618290e+00 -3.04180074e+00 -2.98848176e+00 -2.92318320e+00 -2.90376592e+00 -2.94938540e+00 -3.04816794e+00 -3.09598899e+00 -3.04539919e+00 -2.93530846e+00 -2.87035966e+00 -2.80013204e+00 -2.75192261e+00 -2.67028618e+00 -2.64586520e+00 -2.67693067e+00 -2.64813805e+00 -2.67103648e+00 -2.58000374e+00 -2.59325647e+00 -2.59300971e+00 -2.69372749e+00 -2.77954435e+00 -2.81045699e+00 -2.77776074e+00 -2.75512314e+00 -2.75422621e+00 -2.79880857e+00 -2.76731062e+00 -2.71527553e+00 -2.67105699e+00 -2.61723399e+00 -2.67475629e+00 -2.63018894e+00 -2.58455157e+00 -2.58716297e+00 -2.68324375e+00 -2.83141685e+00 -2.80587745e+00 -2.76355481e+00 -2.75640249e+00 -2.76133847e+00 -2.78658509e+00 -2.76380682e+00 -2.75980186e+00 -2.74434447e+00 -2.69017053e+00 -2.85715461e+00 -3.05663896e+00 -3.17409134e+00 -3.13651872e+00 -3.07169032e+00 -3.19775581e+00 -3.31665349e+00 -3.26071119e+00 -3.14296412e+00 -2.96951699e+00 -2.93457174e+00 -2.91596937e+00 -2.80669165e+00 -2.66361904e+00 -2.53804541e+00 -2.54336643e+00 -2.69433093e+00 -2.82132936e+00 -2.89544106e+00 -2.90625858e+00 -2.87853551e+00 -3.01060653e+00 -3.22796392e+00 -3.34982729e+00 -3.40451312e+00 -3.26354647e+00 -3.22415733e+00 -3.11678982e+00 -3.10603929e+00 -3.09150100e+00 -3.18167329e+00 -3.26673007e+00 -3.23867869e+00 -3.14351463e+00 -3.07060838e+00 -3.10584617e+00 -3.13977647e+00 -3.18278813e+00 -3.22781396e+00 -3.10981393e+00 -2.96239090e+00 -2.91200638e+00 -2.97620463e+00 -3.07789850e+00 -3.07591081e+00 -3.08567309e+00 -3.14037776e+00 -3.19180107e+00 -3.26888633e+00 -3.25195837e+00 -3.14518237e+00 -3.03203940e+00 -2.93424511e+00 -2.96470141e+00 -2.99949098e+00 -3.04331493e+00 -3.05002856e+00 -3.03154397e+00 -3.03450060e+00 -3.06624842e+00 -3.09025764e+00 -3.08980799e+00 -3.08669186e+00 -3.07326365e+00 -3.07729435e+00 -3.06297803e+00 -3.15315700e+00 -3.24535680e+00 -3.27042651e+00 -3.20010924e+00 -3.11441445e+00 -3.15203547e+00 -3.20277405e+00 -3.27127028e+00 -3.28852892e+00 -3.24691296e+00 -3.19344616e+00 -3.14096308e+00 -3.14240432e+00 -3.13451934e+00 -3.12092996e+00 -3.10340738e+00 -3.08731961e+00 -3.08683372e+00 -3.09828711e+00 -3.12746286e+00 -3.13622928e+00 -3.13931274e+00 -3.14092255e+00 -3.15744781e+00 -3.17162490e+00 -3.20445514e+00 -3.22565842e+00 -3.21740317e+00 -3.18687081e+00 -3.15536380e+00 -3.18148494e+00 -3.19926691e+00 -3.21918416e+00 -3.21943903e+00 -3.22553539e+00 -3.22644496e+00 -3.20479512e+00 -3.18672371e+00 -3.16230249e+00 -3.15972090e+00 -3.15805078e+00 -3.15982199e+00 -3.16191292e+00 -3.15885234e+00 -3.15837550e+00 -3.15737247e+00 -3.15810132e+00 -3.15702009e+00 -3.15670919e+00 -3.16006422e+00 -3.16296053e+00 -3.16090989e+00 -3.15638256e+00 -3.15217686e+00 -3.14812040e+00 -3.14652538e+00 -3.15403152e+00 -3.14687419e+00 -3.13009214e+00 -3.12333870e+00 -3.13544941e+00 -3.15921450e+00 -3.15760207e+00 -3.15833664e+00 -3.15538692e+00 -3.15909815e+00 -3.15685773e+00 -3.15535593e+00 -3.15101647e+00 -3.14901710e+00 -3.14646554e+00 -3.14705968e+00 -3.14319277e+00 -3.16610909e+00 -3.19672537e+00 -3.19828200e+00 -3.17099929e+00 -3.13002515e+00 -3.14331031e+00 -3.13887239e+00 -3.12419891e+00 -3.10315871e+00 -3.10420680e+00 -3.11406159e+00 -3.12235332e+00 -3.12807155e+00 -3.12928367e+00 -3.11995149e+00 -3.12830424e+00 -3.13819575e+00 -3.13866663e+00 -3.13073397e+00 -3.14554119e+00 -3.16861606e+00 -3.16175246e+00 -3.13832712e+00 -3.12058377e+00 -3.12458229e+00 -3.17545485e+00 -3.20343900e+00 -3.20623970e+00 -3.16331482e+00 -3.13196731e+00 -3.16362548e+00 -3.16307616e+00 -3.18057275e+00 -3.19743276e+00 -3.18754768e+00 -3.18634295e+00 -3.15023804e+00 -3.18255448e+00 -3.18674111e+00 -3.19920778e+00 -3.15201783e+00 -3.10379362e+00 -3.07325959e+00 -3.17292857e+00 -3.26074696e+00 -3.27177668e+00 -3.18217111e+00 -2.97555494e+00 -2.85169578e+00 -2.84835744e+00 -2.95965791e+00 -2.99864125e+00 -2.80260825e+00 -2.77572632e+00 -2.89375925e+00 -3.11014652e+00 -3.16200399e+00 -3.14076138e+00 -3.13008022e+00 -3.11070967e+00 -3.05643177e+00 -3.06022978e+00 -3.08164430e+00 -3.07492971e+00 -3.01520419e+00 -2.92645478e+00 -2.96126437e+00 -3.04096723e+00 -3.08426690e+00 -3.01575255e+00 -2.94246745e+00 -2.96256018e+00 -2.86718678e+00 -2.74254465e+00 -2.67988682e+00 -2.71912408e+00 -2.76930285e+00 -2.67348814e+00 -2.65005565e+00 -2.66164970e+00 -2.77242446e+00 -2.84313512e+00 -2.89634681e+00 -2.85255075e+00 -2.80398297e+00 -2.76411295e+00 -2.89692640e+00 -3.09451222e+00 -3.10498333e+00 -2.98179483e+00 -2.82728434e+00 -2.84352183e+00 -2.79766250e+00 -2.85510612e+00 -2.84411049e+00 -2.73320627e+00 -2.50364733e+00 -2.47798967e+00 -2.60763168e+00 -2.85463524e+00 -2.83521485e+00 -2.83828592e+00 -2.83166862e+00 -2.91400647e+00 -2.82332420e+00 -2.61329150e+00 -2.53273058e+00 -2.58060265e+00 -2.76416874e+00 -2.73308206e+00 -2.76982903e+00 -2.73255157e+00 -2.75612736e+00 -2.69231510e+00 -2.61558294e+00 -2.62097788e+00 -2.68453264e+00 -2.79736185e+00 -2.78524995e+00 -2.76415730e+00 -2.83432031e+00 -2.90172386e+00 -3.10174680e+00 -3.22487831e+00 -3.19998026e+00 -2.86012745e+00 -2.45026898e+00 -2.25066566e+00 -2.23922253e+00 -2.25396657e+00 -2.34734750e+00 -2.57127047e+00 -2.69546247e+00 -2.81770730e+00 -2.77768683e+00 -2.82399607e+00 -2.62804389e+00 -2.39488006e+00 -2.40117764e+00 -2.50546074e+00 -2.87476850e+00 -3.11595440e+00 -3.19668722e+00 -3.08318186e+00 -2.78702831e+00 -2.49505973e+00 -2.09625936e+00 -1.79256618e+00 -1.88795912e+00 -2.19355464e+00 -2.50623584e+00 -2.73880363e+00 -2.47918105e+00 -2.13742805e+00 -1.98176742e+00 -2.15443444e+00 -2.50092578e+00 -2.73631644e+00 -2.84262490e+00 -2.80968952e+00 -2.65322232e+00 -2.73133326e+00 -2.69654775e+00 -2.70319629e+00 -2.68240452e+00 -2.62513804e+00 -2.58596373e+00 -2.54981947e+00 -2.50890827e+00 -2.46245193e+00 -2.11639833e+00 -1.79588056e+00 -1.96006989e+00 -2.42603827e+00 -2.44135857e+00 -1.86671162e+00 -1.49735439e+00 -1.84724057e+00 -2.26312447e+00 -2.23734975e+00 -1.99007976e+00 -1.94708931e+00 -2.07884693e+00 -2.25812078e+00 -2.25840092e+00 -2.22467208e+00 -2.06547809e+00 -2.06263304e+00 -2.11323738e+00 -2.26363945e+00 -2.32363009e+00 -2.29424381e+00 -2.21823025e+00 -2.17083263e+00 -2.08195972e+00 -1.99087036e+00 -1.76936555e+00 -2.05597878e+00 -2.48121762e+00 -2.37860155e+00 -1.92159319e+00 -1.60138631e+00 -1.96317720e+00 -2.17523813e+00 -1.89113343e+00 -1.53245640e+00 -1.89021075e+00 -2.58443022e+00 -3.08436346e+00 -2.86326551e+00 -2.50189900e+00 -1.96545720e+00 -1.65562987e+00 -1.75525641e+00 -2.27296591e+00 -2.28991032e+00 -1.71819496e+00 -1.56236196e+00 -1.84008527e+00 -2.30181718e+00 -2.34996367e+00 -2.26297879e+00 -2.37243438e+00 -2.69545460e+00 -2.36775303e+00 -1.86684537e+00 -1.40173030e+00 -1.65694869e+00 -1.89030719e+00 -2.00757670e+00 -2.00644064e+00 -1.98534679e+00 -1.88431370e+00 -1.85960698e+00 -2.09031272e+00 -2.08343935e+00 -2.12544966e+00 -2.04131699e+00 -1.95920861e+00 -1.83115733e+00 -1.34257007e+00 -9.78077650e-01 -1.27947152e+00 -2.07268691e+00 -2.64975357e+00 -2.48813677e+00 -2.04438972e+00 -2.08517480e+00 -2.23982120e+00 -2.40024376e+00 -2.50310087e+00 -2.22638941e+00 -1.97361243e+00 -1.80873156e+00 -1.99267650e+00 -2.26434422e+00 -2.25427890e+00 -2.14563417e+00 -2.04761767e+00 -2.08303952e+00 -2.09265089e+00 -1.73511469e+00 -1.62021780e+00 -1.85485005e+00 -2.07411623e+00 -1.98809004e+00 -1.72297955e+00 -1.96994317e+00 -2.25454974e+00 -2.11573410e+00 -1.40896499e+00 -6.71879172e-01 -5.21197021e-01 -7.60413110e-01 -8.46186876e-01 -6.28007174e-01 -7.52202928e-01 -1.04590869e+00 -1.33115089e+00 -1.27283227e+00 -1.27149367e+00 -1.04669344e+00 -5.95280349e-01 -5.53740919e-01 -1.05952942e+00 -1.74417543e+00 -1.42069221e+00 -7.80904353e-01 -6.83559775e-01 -1.24430168e+00 -1.38476121e+00 -9.84327734e-01 -1.36338878e+00 -2.25667882e+00 -2.77831292e+00 -2.31506228e+00 -1.74602449e+00 -1.85653222e+00 -2.24556875e+00 -2.36926723e+00 -2.11046815e+00 -1.95406568e+00 -2.25679874e+00 -2.32371616e+00 -2.15735197e+00 -1.68759561e+00 -1.17689431e+00 -6.15093529e-01 -3.68208736e-01 -4.29304808e-01 -1.25681448e+00 -1.89796436e+00 -2.14956832e+00 -1.70456517e+00 -1.30011952e+00 -1.30579865e+00 -1.28393614e+00 -1.61518919e+00 -2.04076481e+00 -2.04249525e+00 -1.59708869e+00 -1.23659575e+00 -1.15711021e+00 -1.09248638e+00 -5.42091310e-01 -1.95544407e-01 -2.84881055e-01 -7.53588438e-01 -1.00336170e+00 -1.05858004e+00 -1.07859492e+00 -1.14523625e+00 -9.13863599e-01 -8.47077847e-01 -8.69206786e-01 -1.04906416e+00 -1.10439646e+00 -1.11264753e+00 -1.10966587e+00 -9.39113259e-01 -4.49885428e-01 1.68493405e-01 1.51351005e-01 -2.02027276e-01 -3.12542945e-01 3.67088057e-02 1.16626071e-02 -3.13728482e-01 -6.30376816e-01 -2.53776580e-01 1.20366648e-01 2.61034109e-02 -3.63039911e-01 -1.02390981e+00 -1.10365558e+00 -1.15711188e+00 -6.89143836e-01 -2.34391674e-01 -9.83426794e-02 -4.16064739e-01 -4.48221624e-01 -9.03607830e-02 -7.91946054e-02 -3.66365850e-01 -8.58513415e-01 -4.62225407e-01 4.19545807e-02 1.23767085e-01 -5.43004990e-01 -1.05662823e+00 -8.09859574e-01 -1.77713230e-01 -3.22032534e-02 5.58229759e-02 -1.59494832e-01 -1.99653864e-01 -2.08616674e-01 -2.16451049e-01 2.15198979e-01 5.18731713e-01 5.47029614e-01 2.40422502e-01 -1.37379736e-01 -1.91243678e-01 -1.69830710e-01 -1.97929412e-01 -1.26271725e-01 -2.02073485e-01 -1.20858580e-01 -1.99812725e-01 -2.12631986e-01 -2.66010493e-01 -7.08898187e-01 -1.12765348e+00 -6.65135384e-01 3.11077069e-02 3.71702731e-01 -2.54060924e-01 -5.64246297e-01 -4.55045193e-01 -3.27631027e-01 -2.31104597e-01 -3.06050122e-01 -1.82789370e-01 -1.67520940e-01 7.26792991e-01 1.41564369e+00 4.76160479e+00 1.09656639e+01 1.62407055e+01 3.19330482e+01 3.00455074e+01 3.14057892e+02 7.63517761e+02 -3.33246656e+05 652480832. 0. 0. 0. 0. 0. 5.59779277e+09 3.92038375e+05 -8.43279453e+04 2.13765312e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.21156454e+09 -10230335. -1.96937683e+03 -6.73846375e+02 -1.05680305e+02 -3.21287918e+01 -1.82566414e+01 -3.63983655e+00 8.87605175e-02 -1.05266623e-01 -1.84284759e+00 -1.52626145e+00 -1.02418494e+00 -6.16670132e-01 1.30936489e-01 3.67488712e-01 1.10033786e+00 7.38511741e-01 1.65131539e-02 -1.29035330e+00 -1.19786000e+00 5.42645633e-01 2.41091108e+00 3.35776830e+00 3.25521564e+00 2.10173297e+00 2.12143350e+00 2.64774203e+00 1.59497797e+00 8.60852361e-01 7.52134085e-01 2.90680695e+00 4.17091131e+00 4.58175659e+00 3.47920203e+00 1.57613397e+00 7.22498715e-01 7.04326332e-01 3.36985350e-01 4.56288047e-02 4.39853817e-01 2.04625058e+00 3.40493202e+00 2.78699136e+00 1.74228215e+00 9.81613517e-01 2.09345746e+00 2.09371758e+00 2.23316693e+00 2.71753407e+00 2.58504152e+00 2.44541645e+00 2.01085114e+00 1.39717972e+00 7.89184272e-01 5.07912099e-01 2.07446694e+00 4.05399227e+00 4.45504713e+00 3.41042542e+00 9.77509201e-01 8.43828619e-01 1.75035930e+00 2.85408688e+00 2.89779282e+00 2.71498394e+00 2.98130870e+00 3.34056568e+00 3.36153817e+00 2.11344600e+00 6.40703678e-01 1.06772089e+00 1.70626497e+00 2.64228678e+00 3.13234758e+00 3.71488690e+00 3.78685331e+00 3.18724132e+00 2.12622786e+00 1.49818122e+00 1.44219792e+00 2.07669735e+00 3.13203764e+00 4.19237041e+00 4.67179966e+00 3.60228300e+00 3.11670613e+00 2.90887666e+00 2.04259205e+00 1.14768052e+00 1.05564821e+00 2.82413602e+00 4.86083984e+00 5.83227873e+00 4.49102259e+00 2.08480215e+00 1.51127803e+00 1.76414311e+00 2.24271941e+00 2.06359553e+00 2.09577274e+00 2.19920707e+00 2.88026762e+00 3.21405029e+00 3.31864452e+00 3.27889299e+00 3.92923069e+00 4.97705364e+00 5.36344957e+00 5.06313372e+00 3.89466882e+00 3.01095152e+00 3.29682732e+00 3.15275931e+00 2.80913043e+00 2.45482540e+00 3.37274742e+00 4.33506727e+00 4.45898151e+00 2.90176344e+00 1.61265087e+00 1.59901702e+00 2.83749080e+00 4.10277033e+00 5.08496284e+00 5.60126352e+00 5.18640995e+00 4.70854712e+00 4.13037443e+00 3.12578559e+00 2.51770687e+00 2.62134314e+00 3.53938675e+00 4.59845257e+00 5.09581852e+00 4.62099218e+00 3.55685329e+00 3.33127642e+00 3.44799161e+00 3.73053575e+00 3.06206632e+00 3.09905577e+00 3.97178531e+00 5.37574625e+00 6.09781122e+00 5.70511150e+00 5.25017023e+00 5.03157425e+00 4.61210775e+00 4.45659590e+00 4.88455486e+00 5.36721849e+00 6.16656303e+00 6.37334394e+00 6.16886950e+00 5.06491947e+00 4.73540878e+00 5.32239151e+00 6.09487009e+00 5.42008686e+00 4.08816862e+00 3.34887362e+00 4.53135586e+00 5.63624525e+00 5.97618675e+00 5.71585369e+00 5.68139458e+00 6.64992094e+00 7.57768250e+00 7.98111057e+00 6.67958355e+00 4.43181419e+00 4.00826168e+00 4.10167360e+00 4.28602648e+00 4.17735958e+00 4.80890656e+00 5.96924591e+00 6.66538477e+00 5.67887402e+00 4.96497202e+00 4.64892721e+00 5.35561800e+00 6.23775673e+00 6.32088661e+00 7.47288132e+00 6.90313959e+00 7.66964483e+00 7.10117054e+00 6.86093140e+00 6.62283754e+00 6.77209091e+00 7.58491707e+00 8.32210827e+00 8.12933350e+00 6.90071630e+00 4.93008280e+00 4.75515318e+00 5.38135815e+00 5.78261709e+00 6.30250788e+00 6.22603607e+00 6.80045795e+00 6.58686924e+00 5.88937140e+00 5.50249910e+00 5.11392355e+00 6.11831522e+00 6.45711994e+00 6.93456459e+00 6.72807217e+00 6.44210148e+00 7.14302158e+00 8.22859001e+00 8.34118366e+00 7.39781380e+00 6.70109797e+00 6.67237759e+00 7.78416824e+00 8.07350349e+00 7.86082077e+00 6.82775021e+00 6.53480911e+00 6.49196196e+00 6.13312864e+00 6.09396887e+00 5.83143663e+00 5.67793465e+00 6.13925934e+00 6.58690977e+00 6.84818888e+00 6.17540789e+00 5.86832905e+00 6.23520279e+00 6.52248383e+00 7.31150007e+00 7.76944876e+00 8.29665947e+00 7.89248610e+00 7.18853617e+00 6.45331192e+00 6.23153734e+00 7.03762579e+00 7.76014853e+00 7.81353283e+00 7.36756849e+00 7.39026260e+00 7.78751993e+00 7.98474646e+00 7.24242401e+00 6.83771849e+00 6.96151590e+00 7.86021662e+00 8.34229660e+00 8.20979118e+00 7.99343538e+00 8.01690674e+00 7.81089973e+00 7.70354605e+00 7.79218960e+00 7.93613482e+00 8.01479244e+00 8.18772697e+00 8.34814644e+00 8.37189484e+00 7.63058138e+00 7.06806469e+00 7.41900206e+00 8.60568619e+00 8.83563709e+00 8.46183109e+00 8.13811207e+00 8.66695499e+00 8.69561005e+00 8.20271206e+00 7.82818556e+00 7.97015667e+00 8.03286076e+00 7.84259844e+00 7.72018337e+00 8.06148720e+00 8.26626015e+00 7.92081261e+00 7.59337616e+00 7.82984066e+00 7.59882975e+00 7.25170231e+00 6.98152924e+00 7.67077303e+00 8.24032688e+00 8.39408207e+00 8.02584267e+00 8.01008511e+00 8.22672844e+00 8.08629322e+00 7.72875071e+00 7.84244776e+00 8.45401382e+00 9.33537102e+00 9.06737328e+00 9.03874493e+00 8.40283680e+00 8.63759232e+00 8.05533600e+00 7.89091396e+00 7.98443985e+00 8.26772404e+00 8.28857422e+00 7.99973297e+00 7.86522055e+00 7.81342840e+00 7.59701300e+00 7.79488182e+00 8.03682137e+00 8.30029202e+00 8.19756413e+00 7.89389086e+00 8.14320660e+00 8.64102840e+00 8.72633457e+00 8.47528458e+00 8.30725098e+00 8.56507301e+00 8.61174107e+00 8.39771652e+00 8.34837627e+00 8.30715656e+00 8.09400654e+00 7.75628042e+00 7.51329660e+00 7.85155249e+00 8.19778442e+00 8.49132156e+00 8.50229549e+00 8.55431843e+00 8.40600204e+00 8.05278778e+00 8.37891960e+00 8.86532593e+00 8.94437027e+00 8.65792370e+00 8.33259296e+00 8.72663975e+00 8.78787804e+00 8.88276958e+00 8.80453968e+00 8.80548382e+00 8.89614868e+00 8.81650925e+00 8.78582859e+00 8.93560123e+00 8.90604019e+00 8.80020809e+00 8.42343807e+00 8.59842491e+00 8.78593636e+00 9.02851963e+00 9.03581238e+00 9.00988388e+00 8.92833138e+00 8.74596786e+00 8.24885273e+00 8.38769531e+00 8.89993477e+00 9.58417130e+00 9.85914040e+00 9.48652172e+00 9.26352978e+00 9.23855972e+00 9.41243172e+00 9.59372139e+00 9.44999218e+00 9.39664745e+00 9.32666397e+00 9.28388786e+00 9.59350491e+00 9.60462761e+00 9.56950569e+00 9.14092255e+00 8.89782715e+00 9.14164352e+00 9.40247250e+00 9.51558685e+00 9.23519421e+00 8.95427418e+00 9.02261925e+00 9.10182762e+00 9.26119041e+00 9.41931343e+00 9.41510582e+00 9.52962971e+00 9.32421589e+00 9.23020840e+00 9.14968967e+00 9.22154331e+00 9.50902367e+00 9.65518761e+00 9.68227959e+00 9.47165966e+00 9.26725101e+00 9.30648041e+00 9.36291027e+00 9.34158897e+00 9.17497921e+00 9.15987396e+00 9.37504768e+00 9.51216030e+00 9.54807377e+00 9.42660427e+00 9.36236382e+00 9.34574032e+00 9.29065323e+00 9.29057884e+00 9.33966732e+00 9.37781811e+00 9.45647621e+00 9.44862080e+00 9.48877811e+00 9.45832348e+00 9.43019772e+00 9.38085365e+00 9.27821827e+00 9.25500584e+00 9.29377174e+00 9.33149147e+00 9.40847969e+00 9.41275406e+00 9.41766548e+00 9.34325981e+00 9.30436802e+00 9.30732727e+00 9.35334682e+00 9.37598610e+00 9.35733128e+00 9.32414150e+00 9.32733440e+00 9.33117676e+00 9.33638287e+00 9.33883476e+00 9.33840466e+00 9.33249283e+00 9.33313370e+00 9.34202003e+00 9.35054779e+00 9.34702492e+00 9.30055237e+00 9.26918697e+00 9.26105785e+00 9.30246544e+00 9.35671997e+00 9.32531166e+00 9.28645420e+00 9.25735378e+00 9.32023525e+00 9.35532665e+00 9.32170582e+00 9.25908947e+00 9.23145103e+00 9.25683594e+00 9.26025677e+00 9.25708103e+00 9.22577190e+00 9.24456692e+00 9.18635750e+00 9.20435143e+00 9.17858887e+00 9.20103741e+00 9.19237232e+00 9.19975185e+00 9.25717545e+00 9.18581867e+00 9.26883030e+00 9.35953999e+00 9.52635574e+00 9.46102142e+00 9.19304848e+00 9.00841618e+00 8.97479153e+00 9.26029491e+00 9.46328831e+00 9.55151844e+00 9.41214085e+00 9.23341942e+00 9.14585018e+00 9.25967979e+00 9.34436417e+00 9.44824791e+00 9.35267830e+00 9.14340591e+00 8.96672344e+00 8.85661983e+00 9.18300724e+00 9.35436344e+00 9.49134827e+00 9.34973240e+00 9.03042412e+00 8.84801769e+00 8.79322720e+00 9.14601421e+00 9.40505028e+00 9.28261185e+00 9.02978325e+00 8.69786167e+00 8.82977772e+00 9.17977333e+00 9.36388206e+00 9.35042095e+00 8.96253014e+00 8.89450645e+00 8.93004131e+00 9.01194382e+00 8.98520660e+00 9.20656013e+00 9.20219612e+00 9.19435787e+00 8.96156693e+00 9.11050320e+00 9.13499069e+00 9.22066784e+00 9.19545555e+00 9.29297733e+00 9.09526157e+00 9.18703365e+00 9.24065399e+00 9.40402603e+00 8.94291210e+00 8.49327278e+00 8.37447643e+00 8.83571434e+00 9.20573235e+00 9.23267174e+00 8.93783951e+00 8.52371502e+00 8.23163795e+00 8.35948753e+00 8.44087791e+00 8.55570889e+00 8.56025314e+00 8.56586266e+00 8.79909325e+00 8.70808983e+00 9.15015793e+00 9.22718716e+00 9.25382423e+00 9.05667305e+00 8.55873966e+00 8.59455967e+00 8.77838135e+00 9.43782806e+00 9.68606186e+00 9.46932507e+00 8.91257572e+00 8.41166782e+00 8.64091110e+00 9.15361023e+00 9.35791779e+00 9.15057850e+00 8.76319313e+00 8.53802776e+00 8.40002823e+00 8.29666233e+00 8.25739288e+00 8.22955990e+00 8.31436443e+00 7.98817396e+00 7.75461340e+00 7.76704550e+00 8.52031517e+00 8.78123474e+00 8.63328838e+00 7.87832451e+00 7.64525127e+00 7.89115715e+00 8.45588207e+00 8.72702026e+00 8.26285934e+00 8.04171371e+00 7.98689985e+00 8.37588406e+00 8.49193382e+00 8.22265625e+00 7.87371826e+00 7.64104557e+00 7.55764246e+00 7.73960638e+00 7.24823856e+00 7.47796488e+00 7.70444489e+00 8.14108658e+00 8.01501083e+00 7.84063911e+00 8.03355312e+00 8.10451698e+00 7.94763184e+00 7.98642588e+00 7.58746243e+00 7.68946743e+00 7.73979568e+00 8.27044678e+00 8.48750019e+00 7.96319103e+00 7.63039303e+00 6.86782789e+00 7.16574097e+00 7.64553690e+00 8.14645576e+00 8.27243900e+00 7.64129305e+00 7.73918915e+00 7.86317110e+00 7.65687990e+00 5.53554296e+00 5.34756613e+00 6.04793692e+00 7.19253159e+00 6.50326490e+00 5.16155529e+00 -2.74259090e+00 -3.03350002e-01 -2.30399823e+00 -1.12409973e+02 -1.74468018e+02 4.93217590e+02 2.75730127e+03 101577368. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -426442016. 3.45783862e+03 5.05451874e+02 7.25331650e+01 4.99178658e+01 2.04391136e+01 1.02032595e+01 8.67888165e+00 5.28985500e+00 4.83933735e+00 5.20171547e+00 5.45521593e+00 5.67601633e+00 5.44258261e+00 5.53476238e+00 5.66768742e+00 6.23774481e+00 6.35134745e+00 5.74398756e+00 5.06079674e+00 4.44561672e+00 4.03872156e+00 4.16088676e+00 4.79718924e+00 5.67066145e+00 6.23874283e+00 5.34848070e+00 5.13922596e+00 5.49766588e+00 6.87938499e+00 6.57662821e+00 5.53264761e+00 4.89321804e+00 5.22416162e+00 5.82801962e+00 5.85074186e+00 5.37016916e+00 5.38069630e+00 5.30283976e+00 5.30861425e+00 5.42405605e+00 5.88718987e+00 6.32131243e+00 5.92317724e+00 5.85857296e+00 4.99574947e+00 3.75264812e+00 3.16516829e+00 4.98869228e+00 7.41244316e+00 7.62139654e+00 5.50623655e+00 4.48930216e+00 4.84051466e+00 5.92791462e+00 5.80372000e+00 5.13912678e+00 4.76309443e+00 4.71995878e+00 4.81191492e+00 4.09544182e+00 3.26559544e+00 3.28771663e+00 3.17096329e+00 3.04433560e+00 2.90149331e+00 3.61454201e+00 4.11465073e+00 3.82935977e+00 3.50999928e+00 2.90495181e+00 2.35703421e+00 1.98819208e+00 1.72277462e+00 2.39371133e+00 2.88273501e+00 2.18172479e+00 2.36345744e+00 3.37078190e+00 5.98004150e+00 6.98700714e+00 6.02922010e+00 4.98557234e+00 3.86094880e+00 3.56242919e+00 3.53546286e+00 3.96254635e+00 4.35984039e+00 3.95073533e+00 3.57528067e+00 3.79089808e+00 3.89434934e+00 3.70092201e+00 3.01873875e+00 2.97192717e+00 3.58060431e+00 2.73348045e+00 2.95554566e+00 2.95710158e+00 4.17354250e+00 4.33320189e+00 2.96732855e+00 2.89462399e+00 3.71399546e+00 5.37466145e+00 5.42564440e+00 3.85961151e+00 3.20547056e+00 2.55682945e+00 2.50600672e+00 2.07111287e+00 1.90350616e+00 2.21911955e+00 2.42438173e+00 2.42309976e+00 2.46067548e+00 2.81372428e+00 3.37617850e+00 3.08321214e+00 2.88206410e+00 3.28634763e+00 2.75916004e+00 2.64802504e+00 2.94182682e+00 4.35170031e+00 4.49680042e+00 2.79582930e+00 2.10532331e+00 3.05085325e+00 4.30685377e+00 4.35287619e+00 2.64473629e+00 2.24055362e+00 1.89383566e+00 1.94972837e+00 2.10932899e+00 2.63848233e+00 3.68839478e+00 3.29959631e+00 2.42828083e+00 2.35808349e+00 2.80733752e+00 3.77758121e+00 3.18007827e+00 2.68125153e+00 2.59795356e+00 1.91230404e+00 1.91618955e+00 1.45478690e+00 1.91561425e+00 1.99537456e+00 1.56958699e+00 1.47983384e+00 1.75629687e+00 2.74705553e+00 3.54766989e+00 3.09767699e+00 2.65849924e+00 1.82012820e+00 1.49867046e+00 1.18479371e+00 5.12574077e-01 4.22037840e-01 5.27041852e-01 9.26675498e-01 8.03223550e-01 4.89559948e-01 8.56256425e-01 2.00594831e+00 3.06847382e+00 3.49260640e+00 1.82549179e+00 1.08828390e+00 1.35362017e+00 2.20759177e+00 1.92768216e+00 9.98350620e-01 1.21315587e+00 7.85118639e-01 5.49153149e-01 2.43341327e-01 8.26097250e-01 1.28109896e+00 8.20141733e-01 3.65581930e-01 5.46067119e-01 4.61624503e-01 -5.02154231e-02 -7.33533442e-01 -1.67472756e+00 -1.97736168e+00 -2.47069478e+00 -7.60368645e-01 3.22622716e-01 8.99418712e-01 9.57780421e-01 -1.28481254e-01 1.91169783e-01 4.89847869e-01 2.07699490e+00 2.16013622e+00 9.39239085e-01 -8.72890279e-02 -7.49281645e-01 -5.32719076e-01 -1.09346581e+00 -1.71253562e+00 -1.54753530e+00 -1.19485402e+00 -9.39458966e-01 -1.02325022e+00 -6.04848862e-01 2.03821197e-01 7.19704330e-02 6.86663449e-01 5.17272651e-01 -9.18538034e-01 -2.21209621e+00 -2.10060334e+00 -4.71435398e-01 -8.81355330e-02 -5.44094205e-01 1.07104965e-01 1.06994987e+00 1.84542620e+00 2.10209751e+00 1.01503062e+00 9.92062166e-02 -1.32641542e+00 -1.59117246e+00 -4.85935092e-01 7.21023917e-01 1.02155757e+00 -1.41629800e-01 -7.75693715e-01 -4.10730630e-01 -1.88801274e-01 -1.41255066e-01 -3.47362548e-01 -3.43341887e-01 -6.02127969e-01 -6.07926011e-01 -7.66265750e-01 -6.62810385e-01 -3.62494707e-01 8.41194242e-02 1.97010145e-01 -2.55315393e-01 -8.81942868e-01 -7.94364572e-01 -5.56361794e-01 -4.25187796e-01 -7.94645309e-01 -1.39198649e+00 -1.91448283e+00 -2.00541019e+00 -1.53221381e+00 -8.70525539e-01 -9.71672654e-01 -1.09361899e+00 -1.20235848e+00 -1.19605255e+00 -1.43151379e+00 -1.42293978e+00 -1.34086096e+00 -1.17364025e+00 -1.24498737e+00 -9.79235888e-01 -6.57588601e-01 -8.29599321e-01 -1.09981036e+00 -1.15527165e+00 -1.17274535e+00 -1.20255005e+00 -1.52136958e+00 -1.42769563e+00 -1.64300156e+00 -2.05588365e+00 -2.14615083e+00 -2.11080289e+00 -1.87344313e+00 -1.90414393e+00 -1.87667823e+00 -1.62815177e+00 -1.46396565e+00 -1.68687499e+00 -1.86361527e+00 -2.02261591e+00 -1.75859737e+00 -1.84001160e+00 -1.88839924e+00 -2.09725380e+00 -2.05489945e+00 -1.86242294e+00 -1.76622713e+00 -1.96499503e+00 -2.40936923e+00 -2.69910383e+00 -2.53372622e+00 -2.48890090e+00 -2.46362305e+00 -2.54752278e+00 -2.44107890e+00 -2.54181767e+00 -2.71476722e+00 -2.55815721e+00 -2.31389546e+00 -2.18583894e+00 -2.45284915e+00 -2.46407175e+00 -2.21142507e+00 -2.12382102e+00 -2.35586739e+00 -2.70498133e+00 -3.18679762e+00 -3.49861789e+00 -3.70955777e+00 -3.34572029e+00 -2.99880219e+00 -2.90057826e+00 -3.77303338e+00 -4.14689779e+00 -3.81646252e+00 -3.46033311e+00 -3.16684628e+00 -3.40857959e+00 -3.10100627e+00 -3.45196033e+00 -4.40946293e+00 -5.00179672e+00 -4.27722263e+00 -3.18678284e+00 -2.69380260e+00 -3.05804420e+00 -3.36797285e+00 -3.44395709e+00 -3.67365742e+00 -3.63962340e+00 -3.67278218e+00 -3.62374353e+00 -3.65526652e+00 -3.51233530e+00 -3.61959887e+00 -4.02965307e+00 -4.36855268e+00 -4.92941856e+00 -5.21347380e+00 -5.16381168e+00 -4.68117762e+00 -4.34768963e+00 -4.66133881e+00 -4.80354500e+00 -4.45617819e+00 -3.97576499e+00 -3.69649053e+00 -4.03968191e+00 -4.04252148e+00 -4.29254770e+00 -4.17955208e+00 -4.51933336e+00 -4.25887871e+00 -4.42494678e+00 -5.13837576e+00 -5.76912355e+00 -5.13267803e+00 -3.59755039e+00 -3.34101462e+00 -3.89147925e+00 -4.76984406e+00 -4.92352724e+00 -5.12734127e+00 -5.09269333e+00 -5.12153959e+00 -5.12095261e+00 -4.85289526e+00 -4.44323635e+00 -3.70382786e+00 -4.81293488e+00 -6.36296940e+00 -7.02800226e+00 -6.00189400e+00 -4.57939434e+00 -4.41096354e+00 -4.45381308e+00 -4.61628771e+00 -4.48280668e+00 -4.23313999e+00 -3.87460184e+00 -4.14973116e+00 -4.67571068e+00 -5.05362654e+00 -4.84064770e+00 -4.85549498e+00 -5.04431581e+00 -5.07315874e+00 -5.03664684e+00 -4.89716434e+00 -4.66413403e+00 -4.46257448e+00 -4.89273977e+00 -6.05146885e+00 -6.31824303e+00 -6.19043303e+00 -6.42478085e+00 -7.25786543e+00 -8.09290409e+00 -8.01164246e+00 -7.09387875e+00 -6.25467110e+00 -5.70965958e+00 -5.80636978e+00 -6.01098728e+00 -6.20280170e+00 -5.75577927e+00 -5.48533487e+00 -5.47748804e+00 -5.92419195e+00 -5.96244764e+00 -6.50973654e+00 -6.98693180e+00 -7.21714401e+00 -6.52245569e+00 -5.90762281e+00 -5.75569344e+00 -5.91309547e+00 -5.99226427e+00 -5.97615194e+00 -5.99239969e+00 -5.97492027e+00 -5.83312845e+00 -5.68135023e+00 -5.87185717e+00 -5.98196268e+00 -5.92066479e+00 -5.63825512e+00 -5.77613640e+00 -5.97458649e+00 -6.47054863e+00 -6.49782944e+00 -6.42946529e+00 -6.08538628e+00 -6.00432825e+00 -6.32870340e+00 -6.65381098e+00 -6.93657112e+00 -6.99684715e+00 -6.92618275e+00 -6.58176994e+00 -6.24935818e+00 -6.76122427e+00 -7.85695505e+00 -9.56176758e+00 -9.65456676e+00 -1.00973158e+01 -1.06187124e+01 -1.16491995e+01 -2.07458782e+01 -1.95182037e+01 -1.41692295e+01 5.30399990e+00 -1.34680252e+02 -1.81718502e+01 3.00151611e+03 -282066272. 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. 0. 0. 0. 0. 0. 0. -81784528. 2.67599463e+03 3.97648926e+02 5.97523727e+01 1.93252048e+01 6.48943949e+00 -1.29447234e+00 -4.55261755e+00 -6.72727823e+00 -7.95745945e+00 -8.20499802e+00 -7.97051764e+00 -7.32353163e+00 -7.07227612e+00 -7.01866961e+00 -7.31046247e+00 -7.27217674e+00 -7.31872177e+00 -7.37237883e+00 -7.47170496e+00 -7.50063133e+00 -7.31789780e+00 -7.51994371e+00 -7.85989141e+00 -8.13168240e+00 -8.08845139e+00 -7.98810625e+00 -8.06961536e+00 -8.02643394e+00 -8.03628159e+00 -8.28120041e+00 -8.39977264e+00 -8.38978481e+00 -8.16441059e+00 -8.15606689e+00 -8.26526928e+00 -8.45618820e+00 -8.50301170e+00 -8.76762962e+00 -8.96575356e+00 -9.16871548e+00 -8.80249786e+00 -8.45151329e+00 -8.28831863e+00 -8.43832970e+00 -8.66089153e+00 -8.81126499e+00 -8.83521748e+00 -8.61297798e+00 -8.70248985e+00 -8.79564190e+00 -9.08059788e+00 -8.77377033e+00 -8.45651436e+00 -8.26308727e+00 -8.49071121e+00 -8.54310131e+00 -8.65589714e+00 -8.65666103e+00 -8.75029087e+00 -8.75417233e+00 -8.67777061e+00 -8.57039547e+00 -8.33060646e+00 -8.12491322e+00 -8.13849640e+00 -8.12813282e+00 -8.24044609e+00 -8.02072716e+00 -7.94686460e+00 -8.07596016e+00 -8.36652565e+00 -8.66833210e+00 -8.80544567e+00 -8.88066101e+00 -9.11565495e+00 -9.27369976e+00 -9.26732635e+00 -9.01556015e+00 -8.80389023e+00 -8.85740852e+00 -8.91005421e+00 -8.87961769e+00 -8.79202271e+00 -8.66277599e+00 -8.62042809e+00 -8.43533230e+00 -8.38102627e+00 -8.43832874e+00 -8.65948868e+00 -8.91318321e+00 -8.98802471e+00 -8.94019699e+00 -8.70591640e+00 -8.56530285e+00 -8.72073269e+00 -8.83345604e+00 -8.93312073e+00 -8.90005207e+00 -8.93019009e+00 -8.91049576e+00 -8.75849342e+00 -8.92977333e+00 -9.16195011e+00 -9.31468296e+00 -9.25164604e+00 -9.15253353e+00 -9.17388821e+00 -9.11863613e+00 -9.05967140e+00 -9.04466152e+00 -8.93659687e+00 -8.83232212e+00 -8.92528343e+00 -9.09712219e+00 -9.28885555e+00 -9.23453236e+00 -9.23135281e+00 -9.16299248e+00 -9.15978241e+00 -9.21356201e+00 -9.25183582e+00 -9.27300739e+00 -9.22047138e+00 -9.20351887e+00 -9.12712097e+00 -9.11040306e+00 -9.12803364e+00 -9.13193989e+00 -9.03547096e+00 -8.93438911e+00 -8.96928596e+00 -9.03290462e+00 -9.15976429e+00 -9.03341484e+00 -8.96778011e+00 -8.86725903e+00 -8.92874908e+00 -9.04051876e+00 -9.17576122e+00 -9.31546783e+00 -9.33316898e+00 -9.30621719e+00 -9.27677917e+00 -9.30068016e+00 -9.31706429e+00 -9.34170532e+00 -9.33421612e+00 -9.32462311e+00 -9.32066154e+00 -9.34343719e+00 -9.32588196e+00 -9.31419277e+00 -9.27338219e+00 -9.22729874e+00 -9.17977238e+00 -9.19909477e+00 -9.26280785e+00 -9.30205441e+00 -9.26936913e+00 -9.22274303e+00 -9.20301437e+00 -9.22033978e+00 -9.22904110e+00 -9.23978138e+00 -9.25825310e+00 -9.27153778e+00 -9.30260658e+00 -9.31328678e+00 -9.32646561e+00 -9.33141613e+00 -9.33159637e+00 -9.33257484e+00 -9.33515835e+00 -9.33448982e+00 -9.33408546e+00 -9.33641911e+00 -9.33847904e+00 -9.33352089e+00 -9.32730961e+00 -9.32956600e+00 -9.33946037e+00 -9.34599781e+00 -9.34563923e+00 -9.33222771e+00 -9.31825542e+00 -9.33065796e+00 -9.36160183e+00 -9.37352848e+00 -9.35044861e+00 -9.32644558e+00 -9.32044792e+00 -9.34014416e+00 -9.34843254e+00 -9.34791374e+00 -9.35167503e+00 -9.34482384e+00 -9.36008072e+00 -9.36601257e+00 -9.38674068e+00 -9.38770199e+00 -9.36306953e+00 -9.31391811e+00 -9.25817776e+00 -9.25327873e+00 -9.26653004e+00 -9.29422855e+00 -9.25988388e+00 -9.25059128e+00 -9.30175304e+00 -9.33784103e+00 -9.34923267e+00 -9.28100014e+00 -9.25934887e+00 -9.27560520e+00 -9.29474163e+00 -9.30467129e+00 -9.27753639e+00 -9.24551678e+00 -9.22158051e+00 -9.17177486e+00 -9.21045208e+00 -9.18183708e+00 -9.16129494e+00 -9.14422035e+00 -9.11845875e+00 -9.10840702e+00 -9.03284550e+00 -8.95316792e+00 -8.97156334e+00 -8.97586155e+00 -9.10114574e+00 -9.04263210e+00 -9.11720467e+00 -9.03920746e+00 -9.01340294e+00 -8.95668983e+00 -9.00980663e+00 -9.05406761e+00 -8.95530128e+00 -8.89670086e+00 -8.81943703e+00 -8.95977688e+00 -9.03777504e+00 -9.08848476e+00 -8.91620636e+00 -8.73620510e+00 -8.62447357e+00 -8.78868198e+00 -9.17504883e+00 -9.48351479e+00 -9.48850727e+00 -9.20202637e+00 -8.96728230e+00 -9.01826954e+00 -9.19071960e+00 -9.19632530e+00 -9.03830051e+00 -8.87537098e+00 -8.84183979e+00 -8.89715099e+00 -8.92632771e+00 -8.95862198e+00 -8.89835644e+00 -8.83466911e+00 -8.81347561e+00 -8.85422611e+00 -8.89382172e+00 -8.74174786e+00 -8.58250809e+00 -8.61861992e+00 -8.78676224e+00 -8.84756088e+00 -8.71752930e+00 -8.73167706e+00 -8.65337563e+00 -8.62701797e+00 -8.67229080e+00 -8.71589565e+00 -8.89425659e+00 -8.92172527e+00 -8.90371323e+00 -8.70139217e+00 -8.41315746e+00 -8.48304653e+00 -8.52220726e+00 -8.65693665e+00 -8.64323330e+00 -8.37335587e+00 -8.13881874e+00 -8.16511536e+00 -8.47177696e+00 -8.73323345e+00 -8.53727913e+00 -8.38566208e+00 -8.51180363e+00 -8.49821186e+00 -8.89984512e+00 -8.97311401e+00 -9.03114605e+00 -8.76575470e+00 -8.27778816e+00 -8.19210339e+00 -8.05211067e+00 -8.14368534e+00 -8.26042652e+00 -8.60784245e+00 -8.91569710e+00 -8.91439915e+00 -8.75400352e+00 -8.45038509e+00 -8.46726513e+00 -8.41682243e+00 -8.35484028e+00 -8.31239223e+00 -8.47988033e+00 -8.52237988e+00 -8.62605667e+00 -8.53734875e+00 -8.41859818e+00 -8.18540096e+00 -8.10798454e+00 -8.09405899e+00 -8.05520725e+00 -7.95708752e+00 -7.80103827e+00 -7.97957325e+00 -8.31418705e+00 -8.81967640e+00 -9.10202599e+00 -9.19496155e+00 -9.06057453e+00 -8.74959850e+00 -7.78854656e+00 -7.43774605e+00 -7.22952461e+00 -7.65829182e+00 -7.69808245e+00 -7.98971701e+00 -8.37861347e+00 -8.13988113e+00 -8.16491985e+00 -7.48267794e+00 -7.37700462e+00 -7.03385925e+00 -7.27243996e+00 -7.59931993e+00 -7.64340448e+00 -7.63775349e+00 -8.08024788e+00 -8.47109890e+00 -8.37324238e+00 -7.84550619e+00 -7.34344435e+00 -7.67368841e+00 -7.84873009e+00 -8.01759338e+00 -7.92170954e+00 -7.78300571e+00 -7.50472355e+00 -7.10361958e+00 -7.08237171e+00 -7.27817297e+00 -7.43913889e+00 -7.27400208e+00 -7.08399916e+00 -6.92237759e+00 -7.06574869e+00 -6.98105478e+00 -7.08068419e+00 -7.11792660e+00 -7.35028934e+00 -7.56124401e+00 -8.04927826e+00 -7.67140532e+00 -7.03002453e+00 -6.50645113e+00 -7.07929134e+00 -7.51042128e+00 -7.77597094e+00 -7.50146055e+00 -7.89540863e+00 -8.13285160e+00 -8.21219444e+00 -7.76272917e+00 -7.19617558e+00 -7.11083412e+00 -7.34459305e+00 -7.65100718e+00 -7.61151743e+00 -7.31716108e+00 -7.06587744e+00 -6.95555401e+00 -6.98089886e+00 -7.19975662e+00 -7.11447763e+00 -7.32268333e+00 -7.41800928e+00 -7.54842806e+00 -6.94055367e+00 -5.97464418e+00 -6.14073706e+00 -6.97261620e+00 -7.58799362e+00 -6.93809462e+00 -6.44643545e+00 -6.64096117e+00 -6.78405046e+00 -6.52513742e+00 -5.97810173e+00 -5.96771860e+00 -5.96101475e+00 -5.92428493e+00 -6.00492287e+00 -6.37390137e+00 -6.52369308e+00 -6.18834686e+00 -6.27534819e+00 -6.75308990e+00 -6.66501808e+00 -6.24332380e+00 -5.61088800e+00 -5.53580952e+00 -5.50442123e+00 -5.10463190e+00 -5.05768394e+00 -5.29558182e+00 -5.91206837e+00 -6.47141218e+00 -6.22128868e+00 -6.17501545e+00 -5.98516703e+00 -5.99769783e+00 -5.81427860e+00 -5.66745806e+00 -5.61745548e+00 -5.39689922e+00 -5.42660809e+00 -5.80720091e+00 -6.40484905e+00 -6.69555664e+00 -6.45379496e+00 -6.54403543e+00 -6.86874294e+00 -6.56050205e+00 -6.07691717e+00 -5.12294340e+00 -4.86265373e+00 -5.04712868e+00 -4.85080719e+00 -4.77518988e+00 -4.76501513e+00 -5.31011105e+00 -5.75865078e+00 -5.72592211e+00 -5.51110172e+00 -5.20203257e+00 -4.88708591e+00 -4.82931280e+00 -4.86853170e+00 -4.84668303e+00 -4.71611166e+00 -4.61565208e+00 -5.00191879e+00 -5.42226839e+00 -5.27546978e+00 -4.82054234e+00 -4.39121485e+00 -4.73420954e+00 -4.34682703e+00 -3.86422658e+00 -4.00469542e+00 -5.08604813e+00 -6.27394533e+00 -6.55526924e+00 -6.07794571e+00 -5.85744905e+00 -5.90004063e+00 -5.56678391e+00 -5.18579149e+00 -4.87873316e+00 -5.01356077e+00 -5.01625967e+00 -5.10617590e+00 -5.55740213e+00 -5.56026554e+00 -5.13935709e+00 -4.43549538e+00 -4.64629364e+00 -5.10300732e+00 -5.12410879e+00 -4.52619410e+00 -4.72677612e+00 -5.30626154e+00 -4.91782713e+00 -3.54161644e+00 -2.68395162e+00 -3.17683816e+00 -3.72287369e+00 -3.44166946e+00 -2.66868329e+00 -2.68549347e+00 -3.05137444e+00 -3.38747168e+00 -2.84588027e+00 -2.52014256e+00 -2.60604453e+00 -3.04130673e+00 -3.78076482e+00 -4.56034231e+00 -4.99725914e+00 -4.90053177e+00 -3.70227051e+00 -2.65529418e+00 -2.21793342e+00 -2.71914506e+00 -3.23638463e+00 -3.29792070e+00 -3.25187445e+00 -3.00204921e+00 -2.08915329e+00 -2.12022924e+00 -2.79803395e+00 -3.57218814e+00 -3.77167153e+00 -3.64121008e+00 -4.18573856e+00 -4.73576689e+00 -4.64550734e+00 -3.87723589e+00 -3.27685809e+00 -3.11276555e+00 -3.22775555e+00 -3.15677476e+00 -3.35330939e+00 -3.41790628e+00 -3.32416248e+00 -3.16453195e+00 -2.79488111e+00 -2.54921007e+00 -2.25487137e+00 -2.36001158e+00 -2.89589810e+00 -3.93789887e+00 -3.82438612e+00 -3.58790112e+00 -3.42412591e+00 -4.29469109e+00 -4.05453777e+00 -3.38351965e+00 -2.60652590e+00 -3.23705792e+00 -3.71203423e+00 -3.58143711e+00 -2.69116998e+00 -1.85837674e+00 -1.71696007e+00 -1.82125735e+00 -2.38494420e+00 -2.99188828e+00 -2.98466921e+00 -2.46658349e+00 -2.51366854e+00 -3.26974607e+00 -3.29610062e+00 -2.85480762e+00 -1.96545374e+00 -2.57413602e+00 -3.06942272e+00 -2.94743681e+00 -1.93329954e+00 -1.21231830e+00 -1.57315648e+00 -2.29666400e+00 -2.62083507e+00 -2.53832793e+00 -1.97376478e+00 -1.64029360e+00 -1.94025135e+00 -2.14575982e+00 -2.76502037e+00 -3.13913584e+00 -2.63507938e+00 -2.20894527e+00 -1.76424682e+00 -2.33147883e+00 -2.27792645e+00 -1.91681886e+00 -1.49590933e+00 -1.27872300e+00 -1.31444180e+00 -1.19237709e+00 -1.17545819e+00 -1.36248779e+00 -1.56190664e-01 3.36052626e-01 -1.76539621e-03 -8.25913489e-01 1.00648969e-01 1.77999568e+00 5.62052488e-01 -6.26685977e-01 -1.09783661e+00 3.30599248e-01 8.34816039e-01 2.98095345e+00 6.85705900e+00 9.00972748e+00 1.23485184e+01 5.02800713e+01 2.94248505e+02 3.59907684e+02 5.52438698e+01 8.66065216e+01 8.98959290e+02 7.17807250e+06 0. 0. 0. 0. 0. 1.20540652e+10 1.20540652e+10 -464729888. 3.92038375e+05 -8.43279453e+04 2.13765312e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1207435136. -3.15264465e+02 5.31466751e+01 -2.65683270e+01 1.05780821e+01 -2.18246269e+01 -1.93368587e+01 -9.38407230e+00 1.25488734e+00 2.81906486e+00 2.84479475e+00 3.13529682e+00 2.80621314e+00 2.19847488e+00 1.71357083e+00 2.60664725e+00 4.00179386e+00 4.93332815e+00 4.36725378e+00 1.61332822e+00 -7.72877216e-01 -1.59271502e+00 -9.75215316e-01 8.76724660e-01 1.49094903e+00 1.67979908e+00 3.08423018e+00 3.71319532e+00 2.81458783e+00 8.14976811e-01 -9.24788892e-01 -3.51984024e-01 1.43529904e+00 4.14227915e+00 4.82595253e+00 4.42108870e+00 3.94680643e+00 3.85173368e+00 3.61318302e+00 2.81611919e+00 1.84369016e+00 3.23895431e+00 4.11434889e+00 5.34082985e+00 3.69860268e+00 3.36054087e+00 2.85623741e+00 1.98749149e+00 2.73053956e+00 3.04462099e+00 4.80587435e+00 6.36840343e+00 7.79261732e+00 7.90996981e+00 5.49868488e+00 2.42126203e+00 1.65209234e+00 3.41324377e+00 6.72796202e+00 7.89205265e+00 6.59449244e+00 5.57188463e+00 4.49572420e+00 4.81457472e+00 4.19841909e+00 4.79463673e+00 5.25510406e+00 6.33040476e+00 7.37761450e+00 6.76028061e+00 6.50322104e+00 5.84887028e+00 5.70074081e+00 5.70391989e+00 5.54257822e+00 6.28767633e+00 7.70874882e+00 9.28900433e+00 9.17135906e+00 7.29339933e+00 6.11361027e+00 4.73770952e+00 5.44751596e+00 6.90557814e+00 8.01220512e+00 8.55671406e+00 9.03193092e+00 1.04223595e+01 9.64843941e+00 7.84411812e+00 5.38912058e+00 5.54853678e+00 7.02090740e+00 9.52711582e+00 9.98914528e+00 9.68057823e+00 9.90057755e+00 9.79168034e+00 9.57548523e+00 9.02163029e+00 7.96490812e+00 8.40333366e+00 8.65649796e+00 8.75202847e+00 6.99405336e+00 5.63617229e+00 5.33696222e+00 6.42634201e+00 8.39073563e+00 9.81506920e+00 9.17905903e+00 9.34818554e+00 1.08623972e+01 1.25147686e+01 1.05902033e+01 7.17720127e+00 6.91690731e+00 9.26204109e+00 1.23800611e+01 1.25961628e+01 1.15007706e+01 9.68566036e+00 8.30063438e+00 8.08864403e+00 9.40264225e+00 1.01708698e+01 1.10610304e+01 1.18981791e+01 1.28662672e+01 1.29219904e+01 1.18130016e+01 1.05781212e+01 1.03507576e+01 1.03523998e+01 1.12047577e+01 1.17839298e+01 1.27638693e+01 1.24201365e+01 1.28140697e+01 1.22339735e+01 1.08438168e+01 8.19251823e+00 7.08953571e+00 7.88041067e+00 9.52785873e+00 9.09812737e+00 1.01866817e+01 1.06383467e+01 1.14943857e+01 1.10905552e+01 9.32903671e+00 8.83970833e+00 9.95811367e+00 1.19907017e+01 1.31088228e+01 1.16821833e+01 1.03767662e+01 1.09786768e+01 1.23580570e+01 1.36359453e+01 1.20933418e+01 1.09161625e+01 1.14488974e+01 1.17569523e+01 1.18564310e+01 9.73190117e+00 8.31521702e+00 7.49595642e+00 1.01757412e+01 1.33436422e+01 1.46359625e+01 1.41935749e+01 1.36385870e+01 1.32441473e+01 1.29812965e+01 1.18689804e+01 1.12590189e+01 1.20849915e+01 1.32987041e+01 1.39048433e+01 1.31933842e+01 1.09931335e+01 1.13855381e+01 1.12483492e+01 1.25309534e+01 1.12826271e+01 1.10541849e+01 1.17131739e+01 1.30480032e+01 1.32479706e+01 1.38805838e+01 1.41414576e+01 1.40110664e+01 1.44189987e+01 1.53477154e+01 1.56929655e+01 1.52768602e+01 1.46038599e+01 1.36669550e+01 1.33696699e+01 1.34136581e+01 1.37222347e+01 1.49777555e+01 1.56377354e+01 1.67929592e+01 1.53451633e+01 1.45131674e+01 1.37529764e+01 1.41039095e+01 1.39232616e+01 1.39888010e+01 1.42621126e+01 1.53065701e+01 1.60257683e+01 1.60473347e+01 1.54121981e+01 1.42058506e+01 1.43016148e+01 1.44755487e+01 1.53380489e+01 1.58960619e+01 1.58862839e+01 1.54657917e+01 1.48233185e+01 1.52751474e+01 1.59129219e+01 1.61547680e+01 1.60980091e+01 1.58790455e+01 1.61382046e+01 1.63645763e+01 1.56829157e+01 1.65775452e+01 1.51034250e+01 1.59928999e+01 1.46684456e+01 1.53475771e+01 1.54419632e+01 1.71137142e+01 1.73757973e+01 1.62511501e+01 1.51019278e+01 1.58504658e+01 1.73543091e+01 1.74371395e+01 1.70235100e+01 1.57611408e+01 1.65930176e+01 1.70382214e+01 1.74329071e+01 1.71626244e+01 1.69734840e+01 1.76840134e+01 1.60444183e+01 1.66881618e+01 1.70510025e+01 1.87281189e+01 1.74359531e+01 1.60142193e+01 1.44553080e+01 1.48807917e+01 1.54290838e+01 1.73197803e+01 1.73601570e+01 1.83507652e+01 1.74304485e+01 1.62046318e+01 1.51021967e+01 1.56665583e+01 1.62135773e+01 1.64191074e+01 1.63238430e+01 1.73785152e+01 1.77878647e+01 1.79635468e+01 1.76414394e+01 1.80110950e+01 1.85159016e+01 1.79200993e+01 1.76259975e+01 1.76550369e+01 1.79126701e+01 1.82881413e+01 1.88186512e+01 1.91804810e+01 1.87798920e+01 1.79651432e+01 1.75262280e+01 1.77992573e+01 1.75305405e+01 1.72972450e+01 1.67824650e+01 1.69671078e+01 1.81051788e+01 1.78442516e+01 1.77425385e+01 1.73409672e+01 1.79897480e+01 1.76808014e+01 1.74733543e+01 1.73753452e+01 1.82158527e+01 1.89049187e+01 1.91899529e+01 1.87435646e+01 1.87197514e+01 1.94601421e+01 2.00738506e+01 2.00258369e+01 1.94496593e+01 1.87528934e+01 1.85245361e+01 1.84339027e+01 1.90494957e+01 1.95677528e+01 1.92233791e+01 1.81868477e+01 1.81782856e+01 1.89242077e+01 1.93376293e+01 1.80364704e+01 1.75172882e+01 1.82702732e+01 1.93110218e+01 2.01172981e+01 1.99578896e+01 2.04536343e+01 2.02739582e+01 2.00011921e+01 1.97952709e+01 1.97879524e+01 1.98939667e+01 1.95645199e+01 1.96539898e+01 2.00968266e+01 1.99945297e+01 1.93826714e+01 1.90575924e+01 1.94762974e+01 1.99777050e+01 1.98211327e+01 1.91983337e+01 1.91329651e+01 1.93418198e+01 1.96547565e+01 1.93433456e+01 1.93093834e+01 1.94478283e+01 1.95304966e+01 1.95176487e+01 1.97975922e+01 2.05739822e+01 2.07740211e+01 2.07154102e+01 2.01228790e+01 1.99341526e+01 1.97608376e+01 1.96072388e+01 1.96186352e+01 2.00063305e+01 2.01005077e+01 1.95254326e+01 1.90986996e+01 1.91460152e+01 1.97631855e+01 1.98328190e+01 1.96067028e+01 1.95174370e+01 1.92412148e+01 1.96755123e+01 1.95872040e+01 1.99234142e+01 1.97253876e+01 1.93585262e+01 1.91212997e+01 1.90790348e+01 1.96834984e+01 2.03540955e+01 2.02488480e+01 1.99658661e+01 1.96302853e+01 1.99706516e+01 2.03401508e+01 2.04469624e+01 2.06952991e+01 2.02922497e+01 2.00058327e+01 1.97329960e+01 1.99647617e+01 2.02399006e+01 2.03867416e+01 2.03192234e+01 2.02265301e+01 1.99621162e+01 1.98702793e+01 1.98333931e+01 2.01216984e+01 2.04583435e+01 2.04351349e+01 2.02888603e+01 2.02590179e+01 2.04827518e+01 2.04640274e+01 2.01101685e+01 1.98912125e+01 2.00195198e+01 2.02732067e+01 2.03941269e+01 2.03716335e+01 2.04952393e+01 2.04892635e+01 2.03701420e+01 2.02985439e+01 2.01990643e+01 2.03622284e+01 2.03031502e+01 2.03087063e+01 2.02638779e+01 2.02892551e+01 2.04873886e+01 2.05807838e+01 2.05443573e+01 2.04443111e+01 2.03047295e+01 2.03353615e+01 2.03849869e+01 2.04967194e+01 2.05651531e+01 2.05819950e+01 2.05226650e+01 2.04747601e+01 2.04760056e+01 2.05264149e+01 2.05222988e+01 2.05291138e+01 2.05267601e+01 2.05275192e+01 2.05241108e+01 2.05249557e+01 2.05137272e+01 2.04989624e+01 2.04931068e+01 2.05106354e+01 2.05688744e+01 2.06057758e+01 2.06135654e+01 2.05546474e+01 2.04774761e+01 2.04577007e+01 2.05504322e+01 2.05955257e+01 2.05153980e+01 2.04067783e+01 2.04113331e+01 2.05311661e+01 2.05485954e+01 2.05738239e+01 2.05283794e+01 2.05967808e+01 2.05944691e+01 2.05687656e+01 2.07357044e+01 2.06076641e+01 2.06481647e+01 2.04986992e+01 2.05471325e+01 2.04883747e+01 2.02999287e+01 2.05016975e+01 2.04860229e+01 2.04833832e+01 2.02345295e+01 2.02584972e+01 2.05268345e+01 2.06971302e+01 2.06943817e+01 2.03578739e+01 2.01898403e+01 2.02256927e+01 2.03643913e+01 2.04985294e+01 2.03357048e+01 2.01407776e+01 1.99223804e+01 1.98227577e+01 1.99718246e+01 2.03128185e+01 2.06471920e+01 2.04595718e+01 2.00753670e+01 1.97537479e+01 1.97731190e+01 1.99339466e+01 2.02598572e+01 2.04558544e+01 2.04490929e+01 2.00398884e+01 1.96840229e+01 1.97686882e+01 2.01517353e+01 2.04492493e+01 2.03494492e+01 1.99915180e+01 1.99526157e+01 1.98934383e+01 2.03315582e+01 2.06813679e+01 2.06769981e+01 2.05495033e+01 2.00681934e+01 1.98188248e+01 1.97263527e+01 1.98304482e+01 2.02955742e+01 2.02603149e+01 1.98841400e+01 1.96461487e+01 1.94443645e+01 1.99266224e+01 1.98869095e+01 1.97055264e+01 1.93169193e+01 1.92742729e+01 2.00021381e+01 2.04134407e+01 2.03146973e+01 1.94769440e+01 1.89466038e+01 1.87625027e+01 1.87989979e+01 1.91813183e+01 1.96095695e+01 1.97686634e+01 1.98021946e+01 1.94795380e+01 1.94399853e+01 1.96073017e+01 1.93591080e+01 1.92674332e+01 1.86922035e+01 1.88936729e+01 1.88362541e+01 1.89174747e+01 1.93366146e+01 1.94119129e+01 1.90291634e+01 1.81160545e+01 1.78346539e+01 1.81157093e+01 1.84468136e+01 1.87538471e+01 1.85167294e+01 1.81049519e+01 1.79562454e+01 1.79560394e+01 1.85819626e+01 1.89096527e+01 1.89851303e+01 1.87367306e+01 1.86129799e+01 1.88747196e+01 1.87388725e+01 1.86950073e+01 1.93347092e+01 1.94992638e+01 1.92501812e+01 1.87385960e+01 1.91631966e+01 1.99623127e+01 1.99670143e+01 1.93063965e+01 1.81479683e+01 1.75476360e+01 1.81583443e+01 1.84755726e+01 1.86192722e+01 1.81887112e+01 1.80104904e+01 1.83975887e+01 1.83223991e+01 1.86906624e+01 1.86435375e+01 1.86563473e+01 1.87291546e+01 1.83595676e+01 1.81040154e+01 1.82846775e+01 1.83535099e+01 1.88169422e+01 1.82459469e+01 1.82541389e+01 1.75959110e+01 1.77965813e+01 1.84609203e+01 1.86049690e+01 1.84944744e+01 1.79363689e+01 1.76331196e+01 1.81128101e+01 1.84521122e+01 1.94999905e+01 1.87203388e+01 1.75204372e+01 1.65937672e+01 1.65436325e+01 1.73166389e+01 1.71933689e+01 1.66577682e+01 1.61198254e+01 1.48564482e+01 1.42877073e+01 1.40301895e+01 1.41372194e+01 1.48101530e+01 1.78719101e+01 1.69788437e+01 1.00525875e+01 3.65278673e+00 -1.85717621e+01 -5.67441940e+00 -4.12129456e+02 -2.58943750e+03 101577368. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 438069216. -20963992. -3.31662964e+03 -1.36104004e+03 -9.78155823e+01 4.66088837e+02 3.52003510e+02 5.72480049e+01 3.70593834e+01 2.12657375e+01 1.60675640e+01 1.68882942e+01 1.72317009e+01 1.69262085e+01 1.48314476e+01 1.40507298e+01 1.33339405e+01 1.33493509e+01 1.35055132e+01 1.40179949e+01 1.42297983e+01 1.46007605e+01 1.39943771e+01 1.29706383e+01 1.26982298e+01 1.40173845e+01 1.41961594e+01 1.31491451e+01 1.13948011e+01 1.24334373e+01 1.38465099e+01 1.39815931e+01 1.31951141e+01 1.27682791e+01 1.29511671e+01 1.33117867e+01 1.25658808e+01 1.26168537e+01 1.31062260e+01 1.37083244e+01 1.36059856e+01 1.22820511e+01 1.29229460e+01 1.31324024e+01 1.36820440e+01 1.43119574e+01 1.37684717e+01 1.25266514e+01 1.01426373e+01 1.01455574e+01 1.20765953e+01 1.20665436e+01 1.18135653e+01 9.67558861e+00 1.04276876e+01 1.16081734e+01 1.27533760e+01 1.25257931e+01 1.12352753e+01 1.10825090e+01 1.15459261e+01 1.16503143e+01 1.23426485e+01 1.33464079e+01 1.29596415e+01 1.18499470e+01 1.04307909e+01 1.16011686e+01 1.18862286e+01 1.25364666e+01 1.27463350e+01 1.22106009e+01 1.15322485e+01 1.04678173e+01 1.08648949e+01 1.16279478e+01 1.08538656e+01 9.63233948e+00 7.27051115e+00 7.59498358e+00 9.46726227e+00 9.96505833e+00 1.05720119e+01 1.03474369e+01 1.00855904e+01 9.27318382e+00 8.15128326e+00 8.83746243e+00 9.06579971e+00 8.72642612e+00 8.96554279e+00 9.93485260e+00 1.14608107e+01 1.07881937e+01 9.35923672e+00 9.28236866e+00 9.16718578e+00 9.61179447e+00 9.24854279e+00 8.83485699e+00 1.03674259e+01 9.69471455e+00 8.69972038e+00 6.80434418e+00 6.79863024e+00 8.19390202e+00 8.53141403e+00 9.11141968e+00 9.84046650e+00 9.66150188e+00 9.98815823e+00 8.86802769e+00 9.50227451e+00 9.43147373e+00 9.42948818e+00 9.16637230e+00 8.06389141e+00 7.20681810e+00 6.93148613e+00 5.02887297e+00 5.60268879e+00 5.63903046e+00 6.63413906e+00 6.54668903e+00 5.21612740e+00 7.56539822e+00 7.53970957e+00 7.10089350e+00 4.61593723e+00 4.52384377e+00 6.47235107e+00 6.71992826e+00 6.84922266e+00 6.80629539e+00 6.74913073e+00 6.41100883e+00 5.47300148e+00 6.04470682e+00 6.19560099e+00 6.08005619e+00 5.67447805e+00 4.93187380e+00 5.83974266e+00 6.47200632e+00 6.71715689e+00 6.45081663e+00 6.77662849e+00 7.75036669e+00 8.71868801e+00 7.69303703e+00 6.99548054e+00 6.14676905e+00 6.54016924e+00 5.44131422e+00 3.96558309e+00 3.60893130e+00 3.66110754e+00 5.00600815e+00 5.41332006e+00 5.84033966e+00 6.31185818e+00 7.65223408e+00 7.16437340e+00 6.73725319e+00 5.94067526e+00 6.85061264e+00 6.17676497e+00 4.19619131e+00 2.60223579e+00 2.12539935e+00 4.46126652e+00 5.30108690e+00 4.66219950e+00 3.46520996e+00 3.42915702e+00 4.58395243e+00 4.26554346e+00 4.67285490e+00 4.81530809e+00 4.29978800e+00 3.68286777e+00 3.10679078e+00 3.90671515e+00 4.51377153e+00 3.56158710e+00 3.99066901e+00 4.03290129e+00 5.19053841e+00 5.64664364e+00 6.54169989e+00 6.96041727e+00 4.69343996e+00 2.82385707e+00 1.65395606e+00 1.91396224e+00 3.69371414e+00 3.77117276e+00 2.83829665e+00 7.08902895e-01 -4.24958728e-02 1.23428452e+00 1.89435089e+00 2.90778875e+00 2.52881765e+00 3.44149184e+00 4.15930939e+00 4.05867481e+00 3.78671503e+00 3.36228514e+00 3.24546528e+00 2.18242621e+00 9.67796028e-01 9.78187382e-01 9.09998491e-02 2.35510305e-01 2.54018855e+00 4.41920042e+00 3.98100042e+00 1.57380617e+00 2.17563853e-01 7.56910801e-01 9.80128273e-02 -4.90029663e-01 -1.53755832e+00 -2.14802551e+00 -1.89984560e+00 -1.03766513e+00 5.82724512e-01 1.84724700e+00 2.75349498e-01 -8.09690177e-01 -1.57790649e+00 -5.52470803e-01 -6.20372415e-01 -9.91704106e-01 -1.01785672e+00 -6.61800504e-01 -1.31656528e+00 -1.70535338e+00 -1.77196324e+00 -1.01319385e+00 -4.66026783e-01 -7.62004197e-01 -1.30063796e+00 -1.82191813e+00 -1.52087986e+00 -1.24438846e+00 -9.90852416e-01 -1.47848940e+00 -1.81818259e+00 -1.86879599e+00 -1.74886715e+00 -8.83117974e-01 -2.80343324e-01 -8.56477499e-01 -1.89307237e+00 -3.35789132e+00 -2.97578454e+00 -2.63772821e+00 -2.33913970e+00 -2.68141389e+00 -1.73082995e+00 -2.05243897e+00 -2.00192261e+00 -3.39437079e+00 -2.90509844e+00 -2.94482279e+00 -3.10359144e+00 -3.77249408e+00 -3.73955393e+00 -3.96429706e+00 -3.83094001e+00 -4.63278151e+00 -4.73741865e+00 -4.35016203e+00 -3.92476869e+00 -3.21448898e+00 -4.28542328e+00 -4.43114138e+00 -4.50653982e+00 -3.32490325e+00 -3.24269080e+00 -4.35761118e+00 -4.02563667e+00 -3.73733854e+00 -3.31749296e+00 -5.05502272e+00 -5.70949221e+00 -6.06167412e+00 -6.07200003e+00 -6.18806696e+00 -5.67357874e+00 -4.99913406e+00 -5.24996758e+00 -5.10866976e+00 -5.64401770e+00 -5.90437984e+00 -6.17426682e+00 -5.83537388e+00 -5.23782825e+00 -5.64991188e+00 -5.32075644e+00 -5.25007963e+00 -5.02719927e+00 -5.68750048e+00 -5.83635950e+00 -5.89017630e+00 -5.62231255e+00 -6.36057663e+00 -7.14630365e+00 -7.98757887e+00 -7.28830910e+00 -6.39752531e+00 -5.42265654e+00 -5.21022749e+00 -5.74663544e+00 -6.42011404e+00 -7.09877586e+00 -6.90287733e+00 -6.53915358e+00 -6.95797729e+00 -7.48791075e+00 -7.70679855e+00 -6.64416552e+00 -5.82963037e+00 -5.39779472e+00 -5.66084099e+00 -5.96510983e+00 -6.85851860e+00 -8.11660576e+00 -8.75037670e+00 -8.83294868e+00 -8.08162498e+00 -8.15567207e+00 -8.03211403e+00 -7.97457695e+00 -7.57458305e+00 -7.75843573e+00 -7.92822218e+00 -8.00959015e+00 -7.68197346e+00 -7.98212051e+00 -7.40090179e+00 -7.26658583e+00 -6.21849775e+00 -5.99542856e+00 -6.52331924e+00 -7.28948021e+00 -8.24216843e+00 -7.50145435e+00 -7.11211491e+00 -7.43274879e+00 -8.23149014e+00 -7.88674593e+00 -7.27515316e+00 -6.70266151e+00 -7.82229233e+00 -8.00858688e+00 -8.57055950e+00 -8.21308041e+00 -8.42796040e+00 -8.67792130e+00 -9.00074673e+00 -1.03225336e+01 -1.14572639e+01 -1.14888496e+01 -1.10341558e+01 -1.00347414e+01 -1.04719677e+01 -1.05072956e+01 -1.06983948e+01 -1.07907801e+01 -1.01091557e+01 -9.87250710e+00 -9.44301510e+00 -9.68484974e+00 -9.80316067e+00 -1.00621595e+01 -1.03395834e+01 -1.05317144e+01 -1.11465187e+01 -1.10348854e+01 -1.07894869e+01 -1.10377741e+01 -1.16165543e+01 -1.23277988e+01 -1.25485191e+01 -1.21886492e+01 -1.13285637e+01 -1.09747496e+01 -1.09087105e+01 -1.12489319e+01 -1.11575365e+01 -1.11043177e+01 -1.14115953e+01 -1.13522053e+01 -1.16284542e+01 -1.17078819e+01 -1.31432352e+01 -1.26945705e+01 -1.21597462e+01 -1.14824591e+01 -1.14943743e+01 -1.14918718e+01 -1.07153673e+01 -1.02716064e+01 -1.07850733e+01 -1.11973085e+01 -1.18029985e+01 -1.15989714e+01 -1.19657831e+01 -1.18369055e+01 -1.26349773e+01 -1.28423643e+01 -1.29624395e+01 -1.22885914e+01 -1.21165304e+01 -1.19550171e+01 -1.17383080e+01 -1.16769533e+01 -1.18828268e+01 -1.22404842e+01 -1.23732395e+01 -1.27440577e+01 -1.34661970e+01 -1.38973036e+01 -1.40211668e+01 -1.32877235e+01 -1.31027651e+01 -1.33732357e+01 -1.36933575e+01 -1.37651424e+01 -1.38792944e+01 -1.38927555e+01 -1.39595051e+01 -1.38245354e+01 -1.40966215e+01 -1.42296667e+01 -1.43878822e+01 -1.45076141e+01 -1.47074747e+01 -1.41403093e+01 -1.41452322e+01 -1.40029936e+01 -1.42180605e+01 -1.41568651e+01 -1.43079748e+01 -1.49916258e+01 -1.54521408e+01 -1.79110756e+01 -1.83560085e+01 -1.74671726e+01 -1.31774349e+01 -1.35051222e+01 -1.56949129e+01 -1.40124893e+01 -2.00916252e+01 -3.02932529e+01 -3.20973434e+01 -4.45365219e+01 -3.61876221e+01 8.52537384e+01 2.61013892e+03 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. 0. 0. 0. 0. 0. 0. 0. 182845424. -7.13839551e+03 -1.33769763e+03 -2.15376068e+02 -1.06947182e+02 -5.68253403e+01 3.37750580e+02 2.47708527e+02 3.84060326e+01 7.66376877e+00 -8.69993687e+00 -1.16915331e+01 -1.42511215e+01 -1.56325560e+01 -1.75116768e+01 -1.75920105e+01 -1.78299179e+01 -1.81570435e+01 -1.84939518e+01 -1.84800186e+01 -1.83610744e+01 -1.75657406e+01 -1.66901627e+01 -1.66394539e+01 -1.68914585e+01 -1.75082150e+01 -1.73905869e+01 -1.75279160e+01 -1.76970177e+01 -1.78887978e+01 -1.81353207e+01 -1.78531151e+01 -1.76259708e+01 -1.74729252e+01 -1.75680714e+01 -1.74317112e+01 -1.78873215e+01 -1.80058327e+01 -1.82243156e+01 -1.79540844e+01 -1.81992378e+01 -1.83286057e+01 -1.83352985e+01 -1.84803925e+01 -1.83368855e+01 -1.83047295e+01 -1.80682640e+01 -1.80552597e+01 -1.83780460e+01 -1.91107388e+01 -1.92362041e+01 -1.87679005e+01 -1.81253986e+01 -1.80811596e+01 -1.83268642e+01 -1.85390167e+01 -1.85871696e+01 -1.84580116e+01 -1.82476616e+01 -1.81912251e+01 -1.83305588e+01 -1.85438538e+01 -1.92639732e+01 -1.96223221e+01 -1.97393608e+01 -1.97956505e+01 -1.98069534e+01 -2.00223026e+01 -1.96464062e+01 -1.92416630e+01 -1.89858646e+01 -1.87153835e+01 -1.86963406e+01 -1.88539619e+01 -1.87190056e+01 -1.85684757e+01 -1.80155773e+01 -1.79479408e+01 -1.80832424e+01 -1.86369190e+01 -1.91405926e+01 -1.92919502e+01 -1.93212318e+01 -1.96527271e+01 -1.94936466e+01 -1.99413681e+01 -1.98688030e+01 -2.00390358e+01 -1.96244755e+01 -1.93470993e+01 -1.92850170e+01 -1.94629917e+01 -1.98256187e+01 -2.02828598e+01 -2.03450241e+01 -2.00008469e+01 -1.98310642e+01 -1.98589859e+01 -2.00896244e+01 -2.00497932e+01 -2.01477928e+01 -2.00715294e+01 -1.98878441e+01 -1.98144608e+01 -1.97057590e+01 -1.99446507e+01 -2.00028400e+01 -2.01703663e+01 -2.03364506e+01 -2.04043388e+01 -2.06713085e+01 -2.06295261e+01 -2.05851116e+01 -2.01974888e+01 -1.97992458e+01 -1.96195316e+01 -1.96121845e+01 -1.96896820e+01 -1.98131065e+01 -1.99088154e+01 -1.99333916e+01 -1.99026070e+01 -2.00408592e+01 -2.01830368e+01 -2.02771950e+01 -2.01647758e+01 -2.01161289e+01 -2.02441559e+01 -2.04746876e+01 -2.06458035e+01 -2.05796432e+01 -2.05191460e+01 -2.05492859e+01 -2.05827675e+01 -2.06484165e+01 -2.06842442e+01 -2.07047138e+01 -2.05865364e+01 -2.04441776e+01 -2.03402939e+01 -2.02810745e+01 -2.02775421e+01 -2.02969818e+01 -2.03262444e+01 -2.03732224e+01 -2.03413544e+01 -2.03730392e+01 -2.04169750e+01 -2.04947395e+01 -2.04818611e+01 -2.04650497e+01 -2.04590740e+01 -2.04576702e+01 -2.04882183e+01 -2.05441628e+01 -2.05566063e+01 -2.05177212e+01 -2.04965153e+01 -2.05247154e+01 -2.05907745e+01 -2.05730782e+01 -2.06032772e+01 -2.05867462e+01 -2.06092510e+01 -2.05606670e+01 -2.05316010e+01 -2.05101204e+01 -2.05080624e+01 -2.05128613e+01 -2.05096645e+01 -2.05293865e+01 -2.05321198e+01 -2.05293026e+01 -2.05307236e+01 -2.05322762e+01 -2.05278568e+01 -2.05243092e+01 -2.05341663e+01 -2.05428295e+01 -2.05387135e+01 -2.05271626e+01 -2.05267239e+01 -2.05349350e+01 -2.05515976e+01 -2.05468521e+01 -2.05244923e+01 -2.04677696e+01 -2.04641800e+01 -2.05068378e+01 -2.05437603e+01 -2.05201168e+01 -2.04396725e+01 -2.04336319e+01 -2.04672832e+01 -2.04789696e+01 -2.04497108e+01 -2.03801041e+01 -2.03999367e+01 -2.04358940e+01 -2.04329090e+01 -2.04079456e+01 -2.04968433e+01 -2.06162167e+01 -2.06227913e+01 -2.05201740e+01 -2.04386749e+01 -2.03973923e+01 -2.03771133e+01 -2.03365078e+01 -2.03837299e+01 -2.03310051e+01 -2.03124485e+01 -2.02564831e+01 -2.03324528e+01 -2.02764988e+01 -2.03165264e+01 -2.02337990e+01 -2.02355537e+01 -2.01864681e+01 -2.02778301e+01 -2.02509899e+01 -2.02443333e+01 -2.02128506e+01 -2.02530556e+01 -2.02922573e+01 -2.02474022e+01 -2.03606529e+01 -2.04656029e+01 -2.04212265e+01 -2.03379745e+01 -2.01574898e+01 -2.02024288e+01 -2.02030449e+01 -2.02789307e+01 -2.03314629e+01 -2.03518753e+01 -2.01947021e+01 -2.02303200e+01 -2.02648735e+01 -2.03150444e+01 -2.00834866e+01 -1.99950485e+01 -1.99387302e+01 -2.00159454e+01 -2.01194363e+01 -2.02535305e+01 -2.02460308e+01 -2.00703411e+01 -1.95986233e+01 -1.93673801e+01 -1.93306103e+01 -1.95516911e+01 -1.99810390e+01 -1.98455467e+01 -1.93977375e+01 -1.89909534e+01 -1.90719318e+01 -1.96409760e+01 -1.97802734e+01 -1.97402191e+01 -1.96274223e+01 -1.96295910e+01 -1.96912098e+01 -1.97206707e+01 -1.97921963e+01 -1.97343636e+01 -1.95720654e+01 -1.96663265e+01 -1.96578331e+01 -1.96848164e+01 -1.92654152e+01 -1.93184986e+01 -1.93293114e+01 -1.98287201e+01 -1.97973614e+01 -1.97871227e+01 -1.93682995e+01 -1.90789604e+01 -1.88243694e+01 -1.84728813e+01 -1.85574303e+01 -1.87887974e+01 -1.94130688e+01 -1.94151745e+01 -1.92901325e+01 -1.90511513e+01 -1.89855900e+01 -1.91107292e+01 -1.92041454e+01 -1.89415379e+01 -1.88448601e+01 -1.85698166e+01 -1.85976353e+01 -1.84993114e+01 -1.82995567e+01 -1.82754822e+01 -1.80758686e+01 -1.77844410e+01 -1.80432358e+01 -1.85410137e+01 -1.89601707e+01 -1.86335278e+01 -1.82492409e+01 -1.83546810e+01 -1.81739883e+01 -1.78541603e+01 -1.74592285e+01 -1.74036732e+01 -1.74745293e+01 -1.77702904e+01 -1.77666454e+01 -1.78638515e+01 -1.81594868e+01 -1.82995548e+01 -1.84603081e+01 -1.85061436e+01 -1.77920761e+01 -1.79318066e+01 -1.78511620e+01 -1.83257008e+01 -1.82113781e+01 -1.80867138e+01 -1.82510338e+01 -1.81249657e+01 -1.80707836e+01 -1.78488770e+01 -1.75069942e+01 -1.68960857e+01 -1.62654572e+01 -1.58696871e+01 -1.60257645e+01 -1.59623365e+01 -1.68136501e+01 -1.71792603e+01 -1.77394104e+01 -1.74481506e+01 -1.72548447e+01 -1.67951202e+01 -1.64157829e+01 -1.65681534e+01 -1.67896442e+01 -1.74681244e+01 -1.79624882e+01 -1.80481663e+01 -1.78776474e+01 -1.74621162e+01 -1.70699215e+01 -1.68273678e+01 -1.65233479e+01 -1.60238018e+01 -1.62704506e+01 -1.66030865e+01 -1.74367695e+01 -1.70986462e+01 -1.64870796e+01 -1.62258968e+01 -1.61267147e+01 -1.64679375e+01 -1.67454472e+01 -1.74054184e+01 -1.71425495e+01 -1.71805801e+01 -1.68813400e+01 -1.70098667e+01 -1.70535927e+01 -1.67610970e+01 -1.64979496e+01 -1.64176044e+01 -1.68110943e+01 -1.66818581e+01 -1.61612911e+01 -1.54390812e+01 -1.44563055e+01 -1.53083448e+01 -1.59075708e+01 -1.64190102e+01 -1.52405901e+01 -1.52830048e+01 -1.47349272e+01 -1.50036306e+01 -1.40473576e+01 -1.41690388e+01 -1.40598879e+01 -1.44366808e+01 -1.51269417e+01 -1.49653883e+01 -1.47681646e+01 -1.39697151e+01 -1.40264044e+01 -1.40482969e+01 -1.46290321e+01 -1.47350225e+01 -1.48165035e+01 -1.44825153e+01 -1.45564089e+01 -1.42507200e+01 -1.36228390e+01 -1.25689850e+01 -1.32790270e+01 -1.50425320e+01 -1.54054127e+01 -1.39179258e+01 -1.29862070e+01 -1.35692329e+01 -1.43536272e+01 -1.44261332e+01 -1.46125765e+01 -1.49073982e+01 -1.53057508e+01 -1.46993065e+01 -1.45488548e+01 -1.47313023e+01 -1.52652960e+01 -1.42248955e+01 -1.37608137e+01 -1.37567930e+01 -1.38954592e+01 -1.27375603e+01 -1.28758478e+01 -1.34758902e+01 -1.44092712e+01 -1.36927538e+01 -1.37023306e+01 -1.43862867e+01 -1.44824429e+01 -1.42219801e+01 -1.34996109e+01 -1.34074373e+01 -1.36853657e+01 -1.34453440e+01 -1.24828062e+01 -1.21169071e+01 -1.21595411e+01 -1.28574305e+01 -1.31131458e+01 -1.36373224e+01 -1.32473211e+01 -1.20817909e+01 -1.11184568e+01 -1.10742216e+01 -1.14955616e+01 -1.11440763e+01 -1.03795080e+01 -1.03906374e+01 -1.11076260e+01 -1.28215246e+01 -1.40473881e+01 -1.39206123e+01 -1.34453411e+01 -1.27088604e+01 -1.20988407e+01 -1.10063581e+01 -1.04880238e+01 -1.10812435e+01 -1.13383474e+01 -1.11564960e+01 -1.11778297e+01 -1.14485893e+01 -1.15061083e+01 -1.15438728e+01 -1.11366711e+01 -1.13672066e+01 -1.02035904e+01 -9.75279713e+00 -9.95681763e+00 -1.09130764e+01 -1.18565264e+01 -1.09930277e+01 -1.13450747e+01 -1.12935314e+01 -1.06926479e+01 -8.95317268e+00 -7.29416370e+00 -7.17042875e+00 -7.84304905e+00 -8.52966022e+00 -8.56849003e+00 -8.73795986e+00 -8.77614117e+00 -9.05042934e+00 -8.88982296e+00 -8.80268860e+00 -8.30772686e+00 -7.70232725e+00 -7.85053778e+00 -8.77895737e+00 -9.94079304e+00 -9.61286259e+00 -8.78219032e+00 -8.19117641e+00 -8.88853836e+00 -8.87150764e+00 -8.30249310e+00 -8.72359180e+00 -1.02672129e+01 -1.12251406e+01 -1.07962685e+01 -9.70516109e+00 -1.01918726e+01 -1.09130955e+01 -1.09660416e+01 -1.04501362e+01 -9.45710278e+00 -9.17137718e+00 -9.29074383e+00 -9.58387566e+00 -9.86330605e+00 -8.66633129e+00 -7.02734804e+00 -5.94767094e+00 -5.69922590e+00 -6.78192711e+00 -7.70490026e+00 -8.29688931e+00 -7.86605644e+00 -7.71340799e+00 -7.76475239e+00 -8.26371861e+00 -8.51495361e+00 -9.63474369e+00 -8.61443996e+00 -7.68016195e+00 -5.66579866e+00 -5.79874182e+00 -6.23235941e+00 -5.65585089e+00 -5.05856752e+00 -5.02106237e+00 -5.93935490e+00 -6.64330435e+00 -6.37654734e+00 -6.59521675e+00 -6.27638340e+00 -6.04215717e+00 -5.72088003e+00 -5.43788815e+00 -5.65228081e+00 -5.46288061e+00 -5.55981922e+00 -5.84360313e+00 -6.40839720e+00 -6.19438601e+00 -5.66707468e+00 -5.05344534e+00 -5.07897902e+00 -4.81217241e+00 -4.62972498e+00 -5.13941956e+00 -5.74918509e+00 -5.88745737e+00 -4.53587055e+00 -3.91277242e+00 -4.27582598e+00 -5.29745674e+00 -5.83138752e+00 -5.37563992e+00 -4.63844204e+00 -3.72006583e+00 -3.55319357e+00 -3.93239188e+00 -5.65311575e+00 -5.16326332e+00 -4.00068951e+00 -2.94629502e+00 -2.80997729e+00 -4.53831768e+00 -3.22767401e+00 -2.68302536e+00 -2.62599707e+00 -4.37408495e+00 -5.44269133e+00 -4.03071642e+00 -2.99925685e+00 -3.30727148e+00 -3.64598298e+00 -3.79969931e+00 -3.32357454e+00 -2.76320696e+00 -1.80782545e+00 -5.31944990e-01 -7.75305867e-01 -1.80046868e+00 -2.58006883e+00 -2.42754507e+00 -1.84689903e+00 -2.06083679e+00 -1.96349859e+00 -1.80949593e+00 -2.15243745e+00 -1.93262243e+00 -2.88826680e+00 -2.32354164e+00 -2.58552933e+00 -2.74440527e+00 -3.02154231e+00 -2.06620026e+00 -4.89707679e-01 8.10600638e-01 -3.65463316e-01 -1.69600224e+00 -2.55892205e+00 -2.15294480e+00 -6.78739250e-01 1.14450431e+00 2.97080970e+00 5.82051897e+00 2.72535038e+00 1.72136235e+00 3.95939755e+00 6.24109497e+01 1.42756332e+02 1.22131995e+03 2.69862695e+03 9.15784688e+05 -804432768. 0. 0. 0. 0. 0. 1.20540652e+10 2.93549184e+09 4.35707764e+03 5.76740391e+04 -8.43279453e+04 2.13765312e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.57624832e+09 1.88538379e+04 9.61059448e+02 3.26793146e+00 -5.00432358e+01 -4.15819645e+00 -1.47223024e+01 8.98588002e-01 -8.62737715e-01 -2.11111498e+00 -1.99459612e+00 -1.37488472e+00 -5.21415949e-01 1.80822158e+00 3.74407911e+00 4.98995972e+00 3.54372120e+00 1.41845787e+00 1.14163494e+00 1.08574009e+00 3.93432641e+00 5.78918219e+00 8.46823883e+00 7.91985416e+00 6.52111387e+00 5.06796551e+00 5.00576353e+00 2.01795125e+00 1.27954924e+00 3.11344695e+00 8.16462231e+00 1.10543146e+01 9.51481438e+00 7.54289675e+00 4.50616693e+00 4.26714706e+00 4.76532173e+00 5.60124874e+00 6.98501635e+00 7.48354959e+00 8.83271790e+00 1.02457314e+01 9.61480045e+00 8.13795567e+00 7.33705330e+00 8.59363174e+00 8.64729691e+00 7.58023167e+00 8.42418289e+00 9.37933445e+00 9.24050140e+00 8.95322609e+00 6.73912573e+00 6.33938360e+00 6.19216347e+00 1.00718737e+01 1.33399506e+01 1.41490231e+01 1.18477125e+01 9.03338528e+00 9.63704586e+00 1.07467890e+01 1.20697880e+01 1.12266283e+01 1.10281992e+01 1.23377438e+01 1.37076826e+01 1.35717287e+01 1.14519520e+01 9.27568150e+00 1.03791161e+01 1.06775713e+01 1.06584911e+01 1.12367220e+01 1.19154291e+01 1.28312626e+01 1.19194241e+01 9.79024696e+00 8.78583336e+00 8.07664108e+00 1.11175814e+01 1.30589476e+01 1.67380085e+01 1.58885212e+01 1.36039457e+01 1.23762712e+01 1.30281830e+01 1.29310007e+01 9.95626163e+00 1.14186211e+01 1.42423048e+01 1.80549183e+01 1.70423241e+01 1.32201824e+01 1.12239161e+01 1.17085619e+01 1.41368713e+01 1.20711079e+01 1.30528574e+01 1.31564474e+01 1.59379749e+01 1.55052929e+01 1.44595165e+01 1.32039871e+01 1.21823797e+01 1.44377956e+01 1.61225319e+01 1.78857784e+01 1.77922459e+01 1.56356716e+01 1.45154076e+01 1.48337851e+01 1.57244883e+01 1.45293589e+01 1.40762777e+01 1.47525253e+01 1.66880093e+01 1.71267605e+01 1.68143196e+01 1.55554438e+01 1.46094961e+01 1.50927935e+01 1.57320356e+01 1.85248260e+01 1.94018192e+01 1.87376251e+01 1.79450340e+01 1.72611237e+01 1.53972721e+01 1.45387335e+01 1.50365868e+01 1.68889866e+01 1.76790009e+01 1.88974476e+01 2.00052738e+01 2.00579987e+01 1.86096039e+01 1.85245514e+01 1.77788506e+01 1.67836819e+01 1.62733192e+01 1.87748394e+01 2.16281357e+01 2.42195778e+01 2.33235016e+01 2.29467030e+01 2.14282322e+01 2.09744663e+01 2.09784565e+01 2.20001831e+01 2.17224407e+01 2.14599800e+01 2.15839272e+01 2.06748981e+01 1.96504135e+01 1.93304081e+01 2.08977528e+01 2.22726974e+01 2.15424004e+01 2.21688824e+01 2.21818447e+01 2.38685665e+01 2.42729664e+01 2.30974503e+01 2.25991821e+01 2.14909611e+01 2.37462521e+01 2.52471046e+01 2.71372108e+01 2.47450924e+01 2.26166477e+01 2.14557991e+01 2.11319218e+01 2.10445976e+01 2.13271465e+01 2.32996082e+01 2.62072105e+01 2.61817112e+01 2.44375515e+01 2.07973518e+01 2.13493099e+01 2.39505730e+01 2.52723312e+01 2.68887215e+01 2.60939751e+01 2.77158260e+01 2.64111538e+01 2.70458622e+01 2.47553139e+01 2.46585617e+01 2.42166481e+01 2.55019646e+01 2.49402523e+01 2.56257496e+01 2.42796955e+01 2.31234913e+01 2.29205379e+01 2.29310570e+01 2.32203064e+01 2.22760372e+01 2.47660656e+01 2.64745884e+01 2.71944103e+01 2.52879810e+01 2.21511860e+01 2.30764866e+01 2.33989048e+01 2.67507801e+01 2.51841583e+01 2.52723255e+01 2.53984795e+01 2.67237930e+01 2.58760567e+01 2.51906281e+01 2.47462826e+01 2.65782375e+01 2.73678703e+01 2.96979942e+01 2.84627495e+01 2.63983669e+01 2.35556335e+01 2.44232521e+01 2.63018246e+01 2.81712360e+01 2.87007236e+01 2.91369400e+01 2.73976116e+01 2.68610134e+01 2.63924751e+01 2.72983742e+01 2.76190853e+01 2.83140564e+01 2.73677273e+01 2.71125469e+01 2.71600075e+01 2.88489246e+01 2.91390839e+01 2.91581364e+01 2.87626705e+01 2.78204231e+01 2.74732704e+01 2.94249954e+01 3.13501873e+01 3.09129066e+01 2.87604675e+01 2.78910141e+01 2.78759632e+01 2.90243607e+01 2.97637386e+01 3.12953854e+01 3.19075375e+01 3.20686150e+01 3.16875362e+01 2.94232960e+01 3.12287865e+01 3.04276829e+01 3.16962471e+01 2.92424297e+01 3.05374050e+01 3.10409813e+01 3.24264297e+01 3.34543991e+01 3.24660301e+01 3.18747826e+01 3.07501144e+01 3.00011330e+01 3.16239891e+01 3.31675301e+01 3.42465630e+01 3.24820900e+01 3.27769432e+01 3.34949532e+01 3.45289726e+01 3.24239807e+01 3.17050095e+01 3.11058712e+01 3.15577564e+01 3.16683083e+01 3.15908089e+01 3.26615524e+01 3.25718422e+01 3.34287758e+01 3.15981407e+01 3.11574478e+01 3.08177185e+01 3.12045135e+01 3.23271408e+01 3.18171234e+01 3.24653778e+01 3.24986191e+01 3.34306717e+01 3.42267113e+01 3.52138023e+01 3.48017807e+01 3.51844444e+01 3.50759659e+01 3.54788322e+01 3.37921295e+01 3.33639259e+01 3.30533180e+01 3.51170769e+01 3.48500137e+01 3.45381279e+01 3.33605843e+01 3.40470810e+01 3.48198242e+01 3.53590317e+01 3.46640663e+01 3.48761215e+01 3.43974037e+01 3.49271545e+01 3.43953400e+01 3.47268333e+01 3.40937424e+01 3.37871284e+01 3.31497040e+01 3.42189331e+01 3.58464127e+01 3.64404449e+01 3.56440544e+01 3.52143669e+01 3.57933350e+01 3.65176544e+01 3.52406616e+01 3.47971535e+01 3.49349442e+01 3.51542892e+01 3.50139122e+01 3.48324966e+01 3.56324348e+01 3.56556969e+01 3.53564529e+01 3.54527702e+01 3.56282463e+01 3.57880173e+01 3.52529869e+01 3.57418175e+01 3.61095390e+01 3.66928520e+01 3.62866058e+01 3.68085594e+01 3.70096436e+01 3.76165810e+01 3.64050522e+01 3.62730751e+01 3.64148026e+01 3.75018730e+01 3.75171623e+01 3.68670197e+01 3.63529396e+01 3.66979752e+01 3.64761009e+01 3.61398392e+01 3.55182533e+01 3.58973999e+01 3.64941597e+01 3.68029900e+01 3.68652496e+01 3.66361313e+01 3.66664314e+01 3.62082634e+01 3.60287399e+01 3.68589745e+01 3.75640984e+01 3.82469940e+01 3.75113411e+01 3.74446602e+01 3.70368042e+01 3.70363541e+01 3.69705582e+01 3.68639565e+01 3.69128685e+01 3.71125145e+01 3.76549034e+01 3.84169273e+01 3.86775475e+01 3.84648552e+01 3.74978218e+01 3.70128517e+01 3.71154366e+01 3.75977211e+01 3.72318726e+01 3.67005424e+01 3.64330254e+01 3.70093765e+01 3.71164246e+01 3.72002640e+01 3.74116554e+01 3.79090118e+01 3.82950554e+01 3.83866539e+01 3.79560051e+01 3.77710724e+01 3.76098328e+01 3.78911667e+01 3.82262611e+01 3.83280640e+01 3.84767990e+01 3.80347672e+01 3.80098000e+01 3.78422585e+01 3.77579651e+01 3.74631081e+01 3.76130905e+01 3.82156754e+01 3.85087357e+01 3.84850655e+01 3.81953964e+01 3.80758362e+01 3.80485535e+01 3.78706970e+01 3.79973412e+01 3.81725578e+01 3.83014946e+01 3.82856331e+01 3.82623062e+01 3.82133522e+01 3.84111366e+01 3.83682213e+01 3.84726677e+01 3.82334137e+01 3.81972923e+01 3.80944443e+01 3.81686783e+01 3.82740822e+01 3.83722954e+01 3.83397408e+01 3.81914215e+01 3.80623283e+01 3.80991287e+01 3.81161690e+01 3.82002373e+01 3.81395912e+01 3.81391602e+01 3.81289062e+01 3.81279144e+01 3.81307640e+01 3.81329651e+01 3.81400261e+01 3.81367302e+01 3.81349182e+01 3.81536446e+01 3.81657448e+01 3.81389465e+01 3.80766220e+01 3.80345230e+01 3.80736427e+01 3.81407814e+01 3.82067833e+01 3.82048988e+01 3.80291595e+01 3.79328613e+01 3.79039421e+01 3.81343918e+01 3.81659584e+01 3.81813889e+01 3.80391769e+01 3.80304985e+01 3.81734581e+01 3.80868759e+01 3.80111656e+01 3.78291283e+01 3.79983406e+01 3.80321007e+01 3.76108246e+01 3.75973778e+01 3.76839142e+01 3.79849243e+01 3.79308968e+01 3.76565666e+01 3.78803787e+01 3.79534416e+01 3.80870590e+01 3.78802147e+01 3.76433372e+01 3.76131821e+01 3.76015244e+01 3.77787552e+01 3.79254761e+01 3.78430252e+01 3.78087921e+01 3.76728210e+01 3.75969849e+01 3.77774162e+01 3.77023087e+01 3.78599777e+01 3.77664871e+01 3.73851013e+01 3.70199394e+01 3.67937927e+01 3.72433548e+01 3.76352692e+01 3.78660355e+01 3.76783485e+01 3.72480392e+01 3.68001366e+01 3.68730812e+01 3.72179565e+01 3.74949722e+01 3.72127419e+01 3.66842766e+01 3.64999046e+01 3.70426559e+01 3.75632133e+01 3.74603844e+01 3.73063622e+01 3.70805969e+01 3.65143280e+01 3.62804146e+01 3.57219582e+01 3.65919189e+01 3.66965179e+01 3.69841614e+01 3.64646912e+01 3.60530586e+01 3.56142349e+01 3.60989990e+01 3.61534805e+01 3.72134819e+01 3.63603096e+01 3.66900139e+01 3.67242813e+01 3.75459213e+01 3.70557480e+01 3.51299171e+01 3.41304092e+01 3.45729446e+01 3.62599869e+01 3.74751244e+01 3.73286476e+01 3.74968796e+01 3.65954170e+01 3.63222275e+01 3.56126518e+01 3.55270233e+01 3.59415359e+01 3.58843956e+01 3.53234062e+01 3.51070099e+01 3.51457481e+01 3.56249619e+01 3.58420677e+01 3.58228874e+01 3.61161346e+01 3.51784477e+01 3.53652267e+01 3.58940353e+01 3.66929512e+01 3.67526703e+01 3.62332039e+01 3.61003838e+01 3.53880882e+01 3.52963753e+01 3.58498917e+01 3.64299660e+01 3.63904533e+01 3.54436646e+01 3.48176689e+01 3.51124496e+01 3.51334801e+01 3.49835701e+01 3.49289970e+01 3.45309677e+01 3.36026764e+01 3.34939728e+01 3.43862152e+01 3.57753830e+01 3.50482521e+01 3.47902603e+01 3.36057320e+01 3.34363174e+01 3.35175362e+01 3.49465790e+01 3.55129662e+01 3.49472122e+01 3.52219429e+01 3.47395058e+01 3.47739754e+01 3.39948463e+01 3.36446266e+01 3.31763153e+01 3.18559303e+01 3.17008648e+01 3.19491329e+01 3.29659081e+01 3.34175453e+01 3.28506279e+01 3.09882603e+01 3.22003822e+01 3.13984890e+01 3.27279320e+01 3.16793041e+01 3.28740730e+01 3.32743301e+01 3.23722725e+01 3.26703186e+01 3.23133049e+01 3.28744125e+01 3.26293755e+01 3.14381905e+01 3.05766525e+01 2.96582718e+01 3.06272793e+01 3.23698959e+01 3.34457664e+01 3.31637268e+01 3.21906242e+01 3.20726013e+01 3.30873947e+01 3.21326675e+01 3.55342331e+01 3.39680367e+01 3.53206863e+01 3.24446411e+01 3.19891720e+01 2.45988388e+01 3.43020096e+01 1.51582088e+01 2.98394718e+01 8.99664612e+01 3.78081696e+02 19714370. 433851680. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.29760219e+05 3.77587646e+02 1.02142311e+02 4.11997757e+01 3.58651085e+01 6.83140717e+01 7.93192673e+01 4.18873253e+01 3.46133575e+01 3.14078979e+01 2.70130653e+01 2.69183960e+01 2.58489456e+01 2.45276299e+01 2.36104279e+01 2.39950104e+01 2.54663677e+01 2.48762379e+01 2.43019695e+01 2.32000828e+01 2.43287563e+01 2.42925282e+01 2.56318512e+01 2.60938625e+01 2.65120735e+01 2.44749222e+01 2.19302139e+01 2.16421547e+01 2.22317963e+01 2.22654934e+01 2.18483276e+01 2.23126545e+01 2.25896835e+01 2.39001598e+01 2.45438919e+01 2.50693684e+01 2.34506149e+01 2.22621326e+01 2.06173363e+01 1.98939991e+01 1.97293205e+01 2.11871967e+01 2.04242725e+01 1.96218662e+01 1.87714024e+01 1.75711193e+01 1.88516941e+01 2.07981377e+01 2.33834324e+01 2.36103516e+01 2.14517632e+01 2.18232841e+01 2.11857567e+01 2.26599827e+01 2.26759701e+01 2.23763580e+01 2.11368465e+01 1.93022976e+01 1.81484585e+01 1.80904789e+01 1.91195946e+01 2.04292850e+01 1.94541416e+01 1.77741737e+01 1.83491440e+01 2.00649681e+01 2.18684196e+01 2.09991970e+01 1.85679874e+01 1.66054668e+01 1.50052395e+01 1.42666140e+01 1.43282509e+01 1.60552654e+01 1.75901566e+01 1.71631355e+01 1.89352036e+01 2.03035469e+01 2.23694096e+01 2.06184387e+01 1.72454433e+01 1.61661091e+01 1.46370192e+01 1.61015892e+01 1.59583874e+01 1.67899628e+01 1.63642235e+01 1.47975721e+01 1.50353012e+01 1.52510138e+01 1.52586298e+01 1.39197512e+01 1.28413391e+01 1.37832870e+01 1.52517433e+01 1.46652584e+01 1.47324142e+01 1.41826897e+01 1.52321968e+01 1.51334181e+01 1.42555017e+01 1.32736101e+01 1.34804020e+01 1.60455341e+01 1.81348743e+01 1.70279694e+01 1.58391743e+01 1.29559908e+01 1.34545336e+01 1.14782972e+01 1.19358015e+01 1.24987259e+01 1.36040411e+01 1.30503788e+01 1.22909288e+01 1.20386639e+01 1.40388927e+01 1.32431517e+01 1.32391729e+01 1.33638144e+01 1.23614912e+01 1.28944330e+01 1.35840416e+01 1.61778469e+01 1.54387369e+01 1.20781755e+01 9.97078896e+00 1.08210173e+01 1.28241539e+01 1.35424519e+01 1.06600924e+01 1.05381155e+01 1.01183052e+01 1.22676601e+01 1.27705297e+01 1.38523741e+01 1.41312485e+01 1.12641430e+01 9.28697395e+00 8.62676811e+00 1.00235128e+01 1.13929434e+01 9.67750263e+00 9.45775509e+00 9.37127495e+00 9.23168945e+00 7.57335711e+00 6.21524763e+00 5.91052294e+00 6.43131638e+00 5.31213379e+00 6.02200317e+00 6.86435223e+00 1.02577858e+01 1.22549400e+01 1.19590368e+01 9.90551853e+00 7.53043222e+00 6.89912701e+00 6.45971918e+00 6.25294352e+00 6.36320496e+00 6.87142277e+00 6.52839899e+00 5.51405954e+00 4.21015549e+00 5.40141821e+00 7.91673946e+00 9.48541069e+00 9.29276276e+00 5.57714939e+00 4.29687166e+00 4.89961147e+00 7.23831940e+00 6.98506546e+00 5.87580776e+00 6.28502369e+00 6.26728106e+00 5.76161909e+00 4.75057650e+00 4.51526356e+00 4.57607412e+00 4.01875257e+00 3.52154064e+00 3.99265409e+00 3.13253951e+00 2.53449225e+00 1.29977465e+00 1.59398317e+00 6.54846013e-01 -1.32718396e+00 -4.08043504e-01 9.48102057e-01 3.02396059e+00 2.86469960e+00 6.27305865e-01 2.50482440e-01 4.09395546e-01 3.56708884e+00 3.51709747e+00 2.92133832e+00 6.39834166e-01 -8.39060664e-01 -6.39480054e-01 -8.92357886e-01 -3.63142699e-01 -3.66732180e-01 3.23257476e-01 -1.12709537e-01 -1.05622277e-01 -7.46311963e-01 2.85587162e-01 -8.24118555e-01 2.03148365e+00 1.44953370e+00 -3.98938179e-01 -3.30503249e+00 -2.69110370e+00 9.89178479e-01 2.37338209e+00 2.42082906e+00 2.32348633e+00 2.04900217e+00 2.31667519e+00 2.36945558e+00 1.88163042e+00 1.27594602e+00 -9.28043306e-01 -1.61449003e+00 -6.64603293e-01 -1.14037044e-01 1.50804207e-01 -1.01068342e+00 -8.97120118e-01 -1.14894998e+00 -2.04576325e+00 -2.44890881e+00 -1.51555765e+00 -2.18602085e+00 -2.56414819e+00 -3.42576385e+00 -2.94679379e+00 -2.11446595e+00 -1.93612790e+00 -1.76836944e+00 1.76593989e-01 9.08157229e-02 -1.21416546e-01 -3.32634592e+00 -3.11446428e+00 -3.86687160e+00 -3.02022147e+00 -5.33832836e+00 -5.32302761e+00 -5.53045416e+00 -4.11116505e+00 -4.45779800e+00 -5.61836815e+00 -5.38883591e+00 -5.19084787e+00 -4.47249556e+00 -5.44651127e+00 -5.03882694e+00 -5.48222876e+00 -5.30330992e+00 -3.62619042e+00 -4.54322243e+00 -4.93357325e+00 -6.55576706e+00 -6.49907207e+00 -5.01045179e+00 -5.60460901e+00 -5.63472033e+00 -5.96676254e+00 -5.34428310e+00 -5.77615881e+00 -6.59693575e+00 -7.70428753e+00 -7.13200712e+00 -6.66325331e+00 -6.31508350e+00 -6.68659544e+00 -7.43799543e+00 -5.35498047e+00 -5.11678028e+00 -3.77107978e+00 -4.78177023e+00 -5.28937435e+00 -6.11675835e+00 -7.80675268e+00 -8.50234127e+00 -9.22235966e+00 -9.30373192e+00 -9.08995819e+00 -8.98567104e+00 -1.03688688e+01 -1.11205435e+01 -1.12082176e+01 -1.25282774e+01 -1.04388857e+01 -1.06356716e+01 -9.36129284e+00 -1.03469524e+01 -9.08594799e+00 -8.27577782e+00 -9.59327888e+00 -1.15728483e+01 -1.14820833e+01 -1.02791080e+01 -9.79689503e+00 -1.10976200e+01 -1.22084789e+01 -1.49803219e+01 -1.40662594e+01 -1.47479963e+01 -1.19631691e+01 -1.26335030e+01 -1.16023121e+01 -1.26943598e+01 -1.24618177e+01 -1.12384987e+01 -8.84492397e+00 -9.30993366e+00 -1.15112505e+01 -1.38899298e+01 -1.45627098e+01 -1.44414778e+01 -1.48294430e+01 -1.47393465e+01 -1.36155605e+01 -1.29917631e+01 -1.28564892e+01 -1.39743843e+01 -1.45986137e+01 -1.41967916e+01 -1.39721031e+01 -1.39440279e+01 -1.51069384e+01 -1.55134335e+01 -1.58628998e+01 -1.49421358e+01 -1.52326145e+01 -1.52122517e+01 -1.67352943e+01 -1.77135143e+01 -1.72469025e+01 -1.68980389e+01 -1.64888477e+01 -1.77992439e+01 -1.77489796e+01 -1.82500343e+01 -1.66178055e+01 -1.58965693e+01 -1.53191109e+01 -1.83720112e+01 -1.98817406e+01 -2.07296219e+01 -1.85281563e+01 -1.70016994e+01 -1.74628010e+01 -1.73675938e+01 -1.92665672e+01 -1.86805820e+01 -1.67004223e+01 -1.42733841e+01 -1.42560730e+01 -1.63520336e+01 -1.77357025e+01 -1.87081280e+01 -1.87906628e+01 -1.91380558e+01 -1.94675255e+01 -1.91825657e+01 -1.87230015e+01 -1.76495571e+01 -1.79354172e+01 -1.79797173e+01 -2.02864380e+01 -2.19772053e+01 -2.24977226e+01 -2.16904316e+01 -2.03800373e+01 -1.98451290e+01 -1.98808517e+01 -1.98495255e+01 -1.89999123e+01 -1.93986282e+01 -1.99455376e+01 -2.12469769e+01 -2.01268940e+01 -1.96549263e+01 -1.98204689e+01 -2.15453014e+01 -2.15436172e+01 -2.18440113e+01 -2.14395618e+01 -2.16489029e+01 -2.12555408e+01 -2.11858864e+01 -2.03908386e+01 -2.09443703e+01 -2.13829556e+01 -2.33467884e+01 -2.53769207e+01 -2.63783417e+01 -2.57246361e+01 -2.38146687e+01 -2.33708267e+01 -2.35705833e+01 -2.34630928e+01 -2.34361401e+01 -2.38547916e+01 -2.48798141e+01 -2.50594311e+01 -2.44556732e+01 -2.33299484e+01 -2.29490929e+01 -2.32102814e+01 -2.42752533e+01 -2.46263409e+01 -2.49957581e+01 -2.45456104e+01 -2.46938210e+01 -2.49719601e+01 -2.43402042e+01 -2.34151821e+01 -2.21946011e+01 -2.21013584e+01 -2.29808445e+01 -2.39852390e+01 -2.47363625e+01 -2.52585602e+01 -2.51892471e+01 -2.49805050e+01 -2.49853725e+01 -2.48092556e+01 -2.40782776e+01 -2.37208672e+01 -2.36005344e+01 -2.45197372e+01 -2.56461258e+01 -2.60477943e+01 -2.69550743e+01 -2.65954914e+01 -2.67842159e+01 -2.62875633e+01 -2.76387081e+01 -2.94706078e+01 -2.84019070e+01 -2.51444302e+01 -1.89346752e+01 -1.84333172e+01 -1.71719818e+01 -1.90024490e+01 -2.03631935e+01 -9.59471798e+00 -5.15389299e+00 -1.23856506e+01 -3.09535980e+01 3.78691589e+02 3.51215637e+02 -1.84278516e+04 -197921888. 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. 0. 0. 0. 0. 0. 0. 0. 182845424. 5.30159521e+03 9.29069031e+02 2.66279812e+01 -2.51612434e+01 -3.93677559e+01 1.45871058e+01 1.67684498e+01 -1.74877510e+01 -2.62171192e+01 -2.90748653e+01 -2.80582619e+01 -2.87268353e+01 -2.96211090e+01 -3.13343468e+01 -3.08369656e+01 -3.07085209e+01 -3.08698921e+01 -3.13820400e+01 -3.18738098e+01 -3.23893089e+01 -3.26334190e+01 -3.28511696e+01 -3.29664459e+01 -3.24260750e+01 -3.19580441e+01 -3.22197685e+01 -3.32387428e+01 -3.36012878e+01 -3.33761940e+01 -3.29062080e+01 -3.30797768e+01 -3.39601936e+01 -3.42101898e+01 -3.44702911e+01 -3.34755096e+01 -3.33738213e+01 -3.30312386e+01 -3.34167023e+01 -3.34865646e+01 -3.36243286e+01 -3.39413109e+01 -3.41642380e+01 -3.42330933e+01 -3.40756340e+01 -3.43096237e+01 -3.46401176e+01 -3.47838631e+01 -3.48152809e+01 -3.50226860e+01 -3.49512825e+01 -3.51935692e+01 -3.51701431e+01 -3.57768974e+01 -3.54305229e+01 -3.54072723e+01 -3.50991173e+01 -3.54518471e+01 -3.53898315e+01 -3.56643181e+01 -3.55298691e+01 -3.58598061e+01 -3.49395027e+01 -3.42902260e+01 -3.38645439e+01 -3.44086075e+01 -3.49564133e+01 -3.50842285e+01 -3.48493156e+01 -3.50963249e+01 -3.49640121e+01 -3.52573509e+01 -3.55002975e+01 -3.56160431e+01 -3.59719925e+01 -3.63504677e+01 -3.72512398e+01 -3.79362907e+01 -3.77129440e+01 -3.66832733e+01 -3.59548264e+01 -3.58628006e+01 -3.62600365e+01 -3.56437149e+01 -3.52778435e+01 -3.49803810e+01 -3.53733482e+01 -3.55669365e+01 -3.58761024e+01 -3.59004669e+01 -3.58595924e+01 -3.59326591e+01 -3.57405853e+01 -3.56811371e+01 -3.57444534e+01 -3.62439194e+01 -3.66154289e+01 -3.65283546e+01 -3.65325508e+01 -3.65439911e+01 -3.66242218e+01 -3.67769737e+01 -3.70578346e+01 -3.71705093e+01 -3.72316513e+01 -3.69725800e+01 -3.69343948e+01 -3.70646324e+01 -3.69029884e+01 -3.67419891e+01 -3.63462524e+01 -3.65049400e+01 -3.68922958e+01 -3.74304466e+01 -3.75821419e+01 -3.75646248e+01 -3.73856468e+01 -3.72901039e+01 -3.72821884e+01 -3.73363953e+01 -3.74785004e+01 -3.73557816e+01 -3.74091759e+01 -3.75199585e+01 -3.76892014e+01 -3.76989479e+01 -3.75885429e+01 -3.76171608e+01 -3.73602600e+01 -3.72691803e+01 -3.72056122e+01 -3.74851646e+01 -3.77215805e+01 -3.77246246e+01 -3.76747017e+01 -3.73854485e+01 -3.72330971e+01 -3.72998466e+01 -3.75796623e+01 -3.77323837e+01 -3.78517838e+01 -3.79181824e+01 -3.80166626e+01 -3.79851265e+01 -3.80014610e+01 -3.79740829e+01 -3.79999580e+01 -3.79635353e+01 -3.79731445e+01 -3.80051537e+01 -3.80557213e+01 -3.80792160e+01 -3.80623016e+01 -3.79810600e+01 -3.78641167e+01 -3.78845291e+01 -3.79127197e+01 -3.80309067e+01 -3.79301491e+01 -3.79093056e+01 -3.79186172e+01 -3.79197769e+01 -3.79232330e+01 -3.79097862e+01 -3.79847069e+01 -3.80254250e+01 -3.80808754e+01 -3.80940971e+01 -3.81257668e+01 -3.81291924e+01 -3.81185074e+01 -3.81146278e+01 -3.81114616e+01 -3.81239471e+01 -3.81270332e+01 -3.81383972e+01 -3.81404724e+01 -3.81290779e+01 -3.81216202e+01 -3.81274796e+01 -3.81397781e+01 -3.81371651e+01 -3.81357460e+01 -3.81359177e+01 -3.80940590e+01 -3.80933533e+01 -3.81039238e+01 -3.81391487e+01 -3.81265869e+01 -3.81055374e+01 -3.81397934e+01 -3.81135483e+01 -3.81222610e+01 -3.80967102e+01 -3.81130524e+01 -3.81149788e+01 -3.80419235e+01 -3.79935417e+01 -3.79662895e+01 -3.79997139e+01 -3.80714188e+01 -3.80079346e+01 -3.79111252e+01 -3.78847733e+01 -3.79312782e+01 -3.80232544e+01 -3.79420776e+01 -3.80015221e+01 -3.79414291e+01 -3.78391762e+01 -3.78169594e+01 -3.79010162e+01 -3.79762039e+01 -3.78719177e+01 -3.79231644e+01 -3.79227600e+01 -3.78141441e+01 -3.77779121e+01 -3.78777504e+01 -3.80378494e+01 -3.79126968e+01 -3.78355064e+01 -3.78402100e+01 -3.79341660e+01 -3.79538155e+01 -3.78879814e+01 -3.75713272e+01 -3.73831787e+01 -3.72717018e+01 -3.73122139e+01 -3.71693649e+01 -3.71962395e+01 -3.71375771e+01 -3.71420670e+01 -3.69707108e+01 -3.69043884e+01 -3.69741783e+01 -3.71390686e+01 -3.70473671e+01 -3.70580750e+01 -3.71803551e+01 -3.72398109e+01 -3.71899834e+01 -3.71233177e+01 -3.71231232e+01 -3.69612465e+01 -3.65059013e+01 -3.61582375e+01 -3.67422981e+01 -3.74907494e+01 -3.77897148e+01 -3.76303291e+01 -3.73107872e+01 -3.77655525e+01 -3.76451721e+01 -3.74367714e+01 -3.69813766e+01 -3.67560081e+01 -3.68949394e+01 -3.66189461e+01 -3.64304657e+01 -3.62567368e+01 -3.64965286e+01 -3.69229774e+01 -3.70585976e+01 -3.71929474e+01 -3.69031982e+01 -3.68082619e+01 -3.66848793e+01 -3.63925514e+01 -3.59623566e+01 -3.55699081e+01 -3.57526360e+01 -3.56611862e+01 -3.56549835e+01 -3.56716499e+01 -3.59050407e+01 -3.61428375e+01 -3.62177162e+01 -3.65795059e+01 -3.63349876e+01 -3.61044807e+01 -3.52510376e+01 -3.51136360e+01 -3.46672211e+01 -3.46539917e+01 -3.51513062e+01 -3.52228737e+01 -3.47567635e+01 -3.41629219e+01 -3.44311028e+01 -3.47064400e+01 -3.46814194e+01 -3.45322151e+01 -3.47108765e+01 -3.46063271e+01 -3.46782608e+01 -3.49498634e+01 -3.52379684e+01 -3.49753799e+01 -3.50307922e+01 -3.49007111e+01 -3.48084183e+01 -3.43472366e+01 -3.43125496e+01 -3.49993591e+01 -3.55055542e+01 -3.57924843e+01 -3.51921883e+01 -3.42221680e+01 -3.38773651e+01 -3.39670639e+01 -3.38080292e+01 -3.30452042e+01 -3.32561302e+01 -3.36078873e+01 -3.40689468e+01 -3.36730537e+01 -3.33954582e+01 -3.37711411e+01 -3.42513657e+01 -3.39311180e+01 -3.37720871e+01 -3.35354385e+01 -3.33926239e+01 -3.31591911e+01 -3.32967377e+01 -3.37069359e+01 -3.41428223e+01 -3.43629036e+01 -3.42122345e+01 -3.37751083e+01 -3.31152725e+01 -3.30143738e+01 -3.29216881e+01 -3.24420166e+01 -3.21205254e+01 -3.22915459e+01 -3.28665848e+01 -3.32102928e+01 -3.17619667e+01 -3.08090038e+01 -3.01563606e+01 -3.10152340e+01 -3.09060307e+01 -3.15241184e+01 -3.17207279e+01 -3.21121788e+01 -3.22176514e+01 -3.22603798e+01 -3.21427650e+01 -3.12898769e+01 -3.03212433e+01 -3.00032215e+01 -3.12129879e+01 -3.16579990e+01 -3.18717022e+01 -3.11613503e+01 -3.07983589e+01 -3.00527306e+01 -2.94398956e+01 -2.96270370e+01 -2.95383224e+01 -2.98258495e+01 -2.96877918e+01 -3.02054005e+01 -3.01686440e+01 -3.05172119e+01 -2.99839897e+01 -2.97928886e+01 -2.91522255e+01 -3.03575420e+01 -3.14092884e+01 -3.12230682e+01 -2.98520794e+01 -2.95042915e+01 -3.10288353e+01 -3.13569527e+01 -3.09346886e+01 -2.98331413e+01 -3.03972893e+01 -3.08949528e+01 -3.03179398e+01 -2.98164501e+01 -2.87843704e+01 -2.87487450e+01 -2.79527187e+01 -2.81359768e+01 -2.84165249e+01 -2.89258060e+01 -2.82198296e+01 -2.79014091e+01 -2.72706871e+01 -2.75506630e+01 -2.77780895e+01 -2.81851311e+01 -2.83609562e+01 -2.95424309e+01 -2.85502357e+01 -2.71393890e+01 -2.64282990e+01 -2.73068409e+01 -2.82506561e+01 -2.71483097e+01 -2.73222961e+01 -2.68912525e+01 -2.70988121e+01 -2.62563286e+01 -2.57239265e+01 -2.45119705e+01 -2.43273945e+01 -2.37408466e+01 -2.51062603e+01 -2.65604115e+01 -2.69287777e+01 -2.64432812e+01 -2.54909019e+01 -2.67553692e+01 -2.61295471e+01 -2.57417545e+01 -2.48144302e+01 -2.51116085e+01 -2.45782223e+01 -2.41787128e+01 -2.30443020e+01 -2.39658337e+01 -2.46920815e+01 -2.54287415e+01 -2.49368877e+01 -2.42071400e+01 -2.42890167e+01 -2.39257011e+01 -2.37896271e+01 -2.40674076e+01 -2.41266346e+01 -2.39754963e+01 -2.35914383e+01 -2.43140068e+01 -2.52765827e+01 -2.46600571e+01 -2.40334206e+01 -2.46110039e+01 -2.64482384e+01 -2.54902172e+01 -2.27980518e+01 -2.09426899e+01 -2.12857056e+01 -2.20315132e+01 -2.22435493e+01 -2.13442841e+01 -2.21656399e+01 -2.24049091e+01 -2.31185722e+01 -2.26773205e+01 -2.18960114e+01 -2.14032288e+01 -2.03699551e+01 -1.97408466e+01 -1.98952656e+01 -2.06621552e+01 -2.05198612e+01 -2.00781269e+01 -2.11853676e+01 -2.13000584e+01 -2.08706741e+01 -1.88394566e+01 -1.92491875e+01 -1.98742294e+01 -2.04174213e+01 -1.92052917e+01 -1.93140564e+01 -1.98105450e+01 -2.19671555e+01 -2.21347351e+01 -2.17903099e+01 -2.16703568e+01 -2.17448940e+01 -2.09179668e+01 -2.01941299e+01 -1.92485085e+01 -2.00838909e+01 -1.96837654e+01 -1.92791176e+01 -1.92323933e+01 -1.89390202e+01 -1.81354218e+01 -1.66964970e+01 -1.73752689e+01 -1.86649609e+01 -1.90036068e+01 -1.79805946e+01 -1.72814884e+01 -1.85319614e+01 -1.68297005e+01 -1.45419197e+01 -1.24182644e+01 -1.34520416e+01 -1.54183550e+01 -1.49446268e+01 -1.47694502e+01 -1.40636377e+01 -1.44209089e+01 -1.36522541e+01 -1.28162718e+01 -1.34962435e+01 -1.45356903e+01 -1.53964291e+01 -1.60860233e+01 -1.66303463e+01 -1.73985691e+01 -1.70983448e+01 -1.52785225e+01 -1.38252678e+01 -1.22480755e+01 -1.30272799e+01 -1.26023741e+01 -1.28399649e+01 -1.33462009e+01 -1.26929026e+01 -1.08962851e+01 -1.12801590e+01 -1.30626173e+01 -1.43961411e+01 -1.37338867e+01 -1.37923088e+01 -1.52844620e+01 -1.56466436e+01 -1.48060741e+01 -1.31006927e+01 -1.27057314e+01 -1.31151848e+01 -1.26811428e+01 -1.28928976e+01 -1.29160547e+01 -1.29925232e+01 -1.31975269e+01 -1.26288414e+01 -1.20988817e+01 -1.12813768e+01 -1.22562551e+01 -1.28209143e+01 -1.44855623e+01 -1.54999800e+01 -1.53783798e+01 -1.29956055e+01 -1.19613008e+01 -1.21809521e+01 -1.34043083e+01 -1.24169321e+01 -1.12729893e+01 -1.14768620e+01 -1.23177509e+01 -1.20361595e+01 -1.09101210e+01 -7.79834938e+00 -8.11315823e+00 -7.19641495e+00 -8.85570621e+00 -1.03553524e+01 -1.12124205e+01 -9.35396671e+00 -9.70001411e+00 -1.09431496e+01 -1.20936632e+01 -8.81315708e+00 -7.78091288e+00 -8.63213158e+00 -1.15738945e+01 -1.03479643e+01 -8.49387836e+00 -5.55877876e+00 -6.15944338e+00 -7.52900553e+00 -7.63345432e+00 -7.90987682e+00 -8.79865170e+00 -9.14757347e+00 -8.66903400e+00 -7.51998234e+00 -7.94288731e+00 -8.45539379e+00 -8.70480919e+00 -8.23275661e+00 -6.24405146e+00 -5.10924149e+00 -3.61115885e+00 -3.71654463e+00 -3.94665956e+00 -4.43651533e+00 -4.64535761e+00 -5.64415693e+00 -6.10225153e+00 -5.37308121e+00 -3.42283368e+00 -1.22199082e+00 -1.83372760e+00 -6.14265394e+00 -1.17936020e+01 -1.46497202e+01 -7.06730127e+00 -2.79770875e+00 2.96318007e+00 -1.82959735e+00 -1.87608385e+00 -1.24977560e+01 -1.72845974e+01 1.64199963e+01 5.97973785e+01 -1.15805763e+02 -9.45617004e+02 -2.65993311e+03 -3.00736145e+02 -106367016. 0. 0. 0. 0. 0. -1.00518359e+10 6.88672050e+06 3.08426880e+03 2.16609180e+03 -1.56779700e+03 -1411763584. 0. 0. 1.98114714e+10 1.98114714e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.57624832e+09 -35889752. 1.12338916e+04 1.53975723e+02 -5.85378540e+02 2.45243454e+01 -2.40966434e+01 -1.11883133e+02 -9.41071625e+01 3.10824490e+00 5.21268730e+01 7.91178970e+01 6.74752274e+01 2.54710865e+01 1.03900070e+01 9.22809410e+00 1.09430981e+01 5.87629843e+00 1.04151707e+01 3.37864761e+01 4.41401825e+01 3.10080128e+01 -6.82855940e+00 -4.13322830e+01 -3.60850410e+01 -2.61975384e+01 -1.49468994e+01 2.18344975e+00 3.62535810e+00 5.26326227e+00 -1.21504059e+01 -2.71094284e+01 -3.91356277e+01 -3.37302704e+01 2.39867020e+00 3.29833641e+01 5.15327339e+01 6.14492416e+01 4.96688995e+01 4.69598389e+01 4.01345215e+01 9.46918964e+00 -1.18546352e+01 -1.06141033e+01 2.49448261e+01 5.71464996e+01 6.87443314e+01 5.04912224e+01 1.30685511e+01 -1.42295504e+00 1.14280939e-01 1.37742329e+01 3.07396984e+01 3.71538887e+01 4.75535316e+01 4.81248093e+01 3.49941101e+01 1.21287394e+01 2.02492452e+00 2.70547199e+01 4.63221092e+01 5.20902748e+01 4.45977097e+01 2.91729126e+01 3.09890137e+01 3.16138535e+01 1.43773270e+01 -9.91805077e+00 -1.17260332e+01 2.25990067e+01 5.26192627e+01 5.64186363e+01 3.28867264e+01 -1.67534745e+00 -4.76414710e-02 1.20469046e+01 2.16019535e+01 2.79538231e+01 4.09803009e+01 5.61360550e+01 6.54851303e+01 4.92733078e+01 1.62218437e+01 -2.01687183e+01 -1.25934305e+01 4.41095591e+00 2.08638611e+01 3.30100899e+01 4.04197311e+01 4.41666908e+01 2.60569515e+01 3.44358587e+00 -1.70669155e+01 -1.03949928e+01 2.19999676e+01 5.53771782e+01 7.66353531e+01 8.00301971e+01 5.77305565e+01 4.48779030e+01 3.03788624e+01 8.67759228e+00 -9.34342861e+00 -4.75203276e+00 2.29325428e+01 4.53471107e+01 4.23587189e+01 1.96600018e+01 -3.07616711e+00 -3.47813249e+00 3.25991964e+00 4.12685871e+00 1.14693327e+01 1.80847778e+01 2.86938896e+01 3.71296005e+01 3.53413086e+01 2.25719643e+01 1.41950226e+01 2.44974232e+01 4.53487396e+01 5.82848244e+01 5.13452873e+01 1.80165634e+01 -8.31695461e+00 4.40245819e+00 1.43925743e+01 7.40045691e+00 -3.09629226e+00 2.01614017e+01 5.07565613e+01 6.14321518e+01 3.84520798e+01 7.10983610e+00 -5.78455687e+00 7.13978100e+00 2.39784317e+01 3.50660057e+01 4.37237740e+01 3.79472504e+01 3.65163612e+01 3.05910606e+01 1.57869940e+01 6.90917194e-01 -7.42040932e-01 1.22697773e+01 3.02483807e+01 4.10706902e+01 3.53874817e+01 1.49667339e+01 6.90735912e+00 9.73379612e+00 1.20849876e+01 9.04613400e+00 1.64702492e+01 3.46953659e+01 5.96198273e+01 6.25532303e+01 4.64677124e+01 3.50032883e+01 3.79619102e+01 3.88183594e+01 2.86412106e+01 3.11065884e+01 3.61114998e+01 4.94673729e+01 4.37696991e+01 3.20439873e+01 1.82456264e+01 2.54897900e+01 4.72645226e+01 6.74060364e+01 7.66553802e+01 7.20161743e+01 5.58748245e+01 5.05101357e+01 5.23171692e+01 4.34839134e+01 4.99425430e+01 6.28580170e+01 8.36916733e+01 9.49002838e+01 9.21766739e+01 7.01288757e+01 3.50073547e+01 2.49137287e+01 2.10821857e+01 2.00281868e+01 1.82219524e+01 2.64802208e+01 4.47908325e+01 5.28963776e+01 4.23076782e+01 2.24048080e+01 2.17491894e+01 4.03118134e+01 5.51193695e+01 6.28809853e+01 7.49928131e+01 7.47416382e+01 7.25116730e+01 5.89098434e+01 4.99981499e+01 5.15374489e+01 5.68631859e+01 7.33762054e+01 8.32299500e+01 8.75012817e+01 6.83526001e+01 3.74544296e+01 2.69581261e+01 3.25048790e+01 4.03253441e+01 4.29196625e+01 4.59506073e+01 5.85773888e+01 6.43619690e+01 4.68856316e+01 2.71606770e+01 1.97757053e+01 3.42026329e+01 4.98285942e+01 5.61418190e+01 5.73930931e+01 5.15487938e+01 5.34552002e+01 6.07043419e+01 5.17306366e+01 4.28829842e+01 4.39695740e+01 5.70854416e+01 6.79572525e+01 6.85483398e+01 5.99255905e+01 4.52247696e+01 3.54909706e+01 3.61436958e+01 3.65377159e+01 3.76341133e+01 4.06181984e+01 5.63760262e+01 6.61003189e+01 6.69026184e+01 6.10408401e+01 4.86717567e+01 4.36889534e+01 3.46135292e+01 3.55170631e+01 5.11034622e+01 5.33398285e+01 5.12913551e+01 4.20643387e+01 3.83684998e+01 3.71883507e+01 3.15526943e+01 5.06903763e+01 7.08715134e+01 7.86025848e+01 6.17028046e+01 5.00142250e+01 4.86519547e+01 5.24900208e+01 4.14881630e+01 3.72203598e+01 4.66217766e+01 6.26255646e+01 6.71296082e+01 5.07942772e+01 4.90664177e+01 4.76025505e+01 4.70278244e+01 3.87172089e+01 4.36740799e+01 5.61615181e+01 6.23694038e+01 6.72188568e+01 7.27085037e+01 7.78352127e+01 6.44027634e+01 4.88083763e+01 4.96229973e+01 6.94096527e+01 7.37308426e+01 6.46701431e+01 6.16997223e+01 6.88417892e+01 7.11436310e+01 5.68163795e+01 5.54307289e+01 6.22978210e+01 7.05018692e+01 6.74255905e+01 5.55458755e+01 5.59678001e+01 4.93791199e+01 4.35392570e+01 3.76366539e+01 4.91990700e+01 5.80158806e+01 5.76455231e+01 5.58379745e+01 5.59866600e+01 5.86630287e+01 5.08538361e+01 4.31444397e+01 4.47592278e+01 5.95732117e+01 6.88509598e+01 6.51396255e+01 5.99102173e+01 6.41976776e+01 7.09335709e+01 6.66367416e+01 6.26702499e+01 5.91333542e+01 6.10310669e+01 5.49811821e+01 4.91376839e+01 5.15171967e+01 5.31527443e+01 5.24142075e+01 4.89154091e+01 5.00890999e+01 5.14867287e+01 5.14104004e+01 5.82096443e+01 6.51473236e+01 6.91905365e+01 6.17239151e+01 5.44581223e+01 5.60295105e+01 6.57960663e+01 6.66678162e+01 6.18837128e+01 5.95681801e+01 6.66041718e+01 6.74769135e+01 5.74256096e+01 5.19369507e+01 4.74551392e+01 4.73069725e+01 4.34300652e+01 4.56086159e+01 5.25307884e+01 5.27911568e+01 4.93392181e+01 4.71242867e+01 5.52193527e+01 6.13960762e+01 6.11192093e+01 6.49284592e+01 7.16481934e+01 7.67271652e+01 7.21990738e+01 6.71005020e+01 6.59014511e+01 6.62855377e+01 6.27313690e+01 6.17517014e+01 6.23117447e+01 6.66772079e+01 6.43256302e+01 5.75650406e+01 5.36045723e+01 5.11304512e+01 5.18388100e+01 5.00530357e+01 5.31593246e+01 6.00284767e+01 6.12158203e+01 5.96524086e+01 5.58633575e+01 5.94403076e+01 6.21272354e+01 5.85048866e+01 5.98474426e+01 6.56476593e+01 7.33958282e+01 7.45900116e+01 6.86529236e+01 6.57646866e+01 6.61343689e+01 6.72802048e+01 6.96153107e+01 6.64766006e+01 6.60405807e+01 6.40482254e+01 6.42472229e+01 6.93574677e+01 6.83833237e+01 6.57669678e+01 5.86526070e+01 5.87996864e+01 6.63336792e+01 6.80369492e+01 6.58005447e+01 5.90115776e+01 5.91484375e+01 6.54624023e+01 6.90654221e+01 7.07947083e+01 6.88305206e+01 6.72433243e+01 6.59095001e+01 6.23078575e+01 6.21281891e+01 6.47849503e+01 6.75417099e+01 6.75463181e+01 6.37324677e+01 6.13349152e+01 6.00503540e+01 6.11041145e+01 6.44744415e+01 6.54075165e+01 6.40264130e+01 6.09710732e+01 6.13492126e+01 6.46734467e+01 6.73830490e+01 6.81742096e+01 6.57308350e+01 6.33954887e+01 6.27721176e+01 6.26974525e+01 6.34612503e+01 6.40060654e+01 6.45281906e+01 6.50641861e+01 6.46416473e+01 6.41649094e+01 6.36759682e+01 6.36635551e+01 6.38652954e+01 6.36265068e+01 6.35486221e+01 6.35803719e+01 6.36413879e+01 6.36354218e+01 6.35318680e+01 6.34896927e+01 6.38385620e+01 6.41193848e+01 6.40305481e+01 6.38742104e+01 6.36059113e+01 6.36688728e+01 6.32787590e+01 6.22971153e+01 6.22101402e+01 6.28341827e+01 6.32186813e+01 6.31684761e+01 6.26424484e+01 6.39132118e+01 6.46393738e+01 6.49738770e+01 6.37342110e+01 6.19414864e+01 6.27205963e+01 6.43993301e+01 6.58783112e+01 6.57534332e+01 6.34181061e+01 6.26347313e+01 6.26841202e+01 6.47653580e+01 6.53686905e+01 6.27723579e+01 6.11582298e+01 5.95845299e+01 6.05050278e+01 6.12928200e+01 6.22016716e+01 6.37537956e+01 6.43964844e+01 6.31698112e+01 6.16816521e+01 5.96627121e+01 6.06366348e+01 6.22377396e+01 6.54979553e+01 6.66837616e+01 6.24318275e+01 6.22380638e+01 6.15783195e+01 6.32696609e+01 6.38254356e+01 6.22478180e+01 6.11439323e+01 5.74471169e+01 6.13910866e+01 6.56115799e+01 6.67044449e+01 6.49397812e+01 6.13072586e+01 5.88156281e+01 5.81268196e+01 5.89337234e+01 6.27791595e+01 6.31919632e+01 6.15503769e+01 5.89571533e+01 5.72145615e+01 6.20400848e+01 6.59815063e+01 7.03100128e+01 6.83902512e+01 6.30954971e+01 6.27597618e+01 6.42973480e+01 6.83605423e+01 6.91418076e+01 6.37710991e+01 6.25179787e+01 6.10076408e+01 6.60195007e+01 6.81142502e+01 6.16443596e+01 6.22373009e+01 6.11447449e+01 6.00489006e+01 5.63072853e+01 5.54977646e+01 6.53252258e+01 7.06929703e+01 6.82189331e+01 6.12256355e+01 5.61916046e+01 6.15894279e+01 6.85269470e+01 7.22052307e+01 7.36098099e+01 6.58899918e+01 6.11051903e+01 5.95310593e+01 6.49457474e+01 6.99113846e+01 6.01802826e+01 5.22848396e+01 4.39236526e+01 4.85396652e+01 5.85346642e+01 6.29825287e+01 6.81775436e+01 6.26989403e+01 5.64032135e+01 5.12818565e+01 5.36568260e+01 6.50503769e+01 7.23944321e+01 7.02129898e+01 6.56250534e+01 5.98548012e+01 6.40758820e+01 6.82349930e+01 7.30009460e+01 7.06368942e+01 5.77323799e+01 5.25488930e+01 5.57906227e+01 6.89614487e+01 7.39189758e+01 6.97125320e+01 6.48922119e+01 5.75477486e+01 5.88053322e+01 6.18290291e+01 6.55652161e+01 6.60913467e+01 6.12627373e+01 5.68896713e+01 5.42840958e+01 5.70241890e+01 6.70433121e+01 7.35511322e+01 7.43506927e+01 6.37202415e+01 5.24855537e+01 5.67671890e+01 6.53350067e+01 7.33619461e+01 6.95849609e+01 5.32895927e+01 4.87461624e+01 5.27368164e+01 6.87411728e+01 7.59668732e+01 6.21631165e+01 5.15465813e+01 4.40682678e+01 5.44764671e+01 6.55244446e+01 6.21767616e+01 6.13722458e+01 5.53311844e+01 5.52785416e+01 5.57138023e+01 5.42131195e+01 6.31270981e+01 6.18735085e+01 6.63176346e+01 6.19580154e+01 5.21177902e+01 5.50753746e+01 5.97449989e+01 7.59332352e+01 6.88044739e+01 4.96100159e+01 3.92954369e+01 4.45093575e+01 6.34311104e+01 6.55747757e+01 5.28797607e+01 5.04825439e+01 3.93594818e+01 4.43026276e+01 5.66286430e+01 6.55215912e+01 5.25016518e+01 2.32504234e+01 1.12862695e+03 3.35792554e+03 60965684. 25801794. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 301800640. 50986700. -285477376. 53173812. -5.63902710e+10 -9.36358719e+01 2.96261168e+00 6.08747444e+01 4.25586967e+01 4.54027443e+01 6.38367424e+01 6.38577423e+01 6.69140472e+01 6.19027634e+01 3.72130432e+01 2.73137665e+01 3.45301895e+01 6.46584702e+01 7.22827377e+01 5.02063713e+01 3.33411255e+01 2.42132530e+01 4.09989853e+01 6.01015091e+01 6.23971748e+01 5.95239258e+01 3.89064178e+01 2.67873955e+01 2.40308704e+01 3.38318138e+01 4.28114319e+01 4.35760345e+01 4.48801155e+01 4.56392288e+01 4.42540894e+01 5.29945221e+01 6.32510300e+01 7.04118042e+01 5.77561417e+01 2.76405697e+01 1.75380898e+01 2.49435101e+01 5.35385246e+01 6.22229156e+01 5.53700829e+01 4.86949158e+01 3.96552010e+01 4.62400932e+01 5.10728302e+01 4.67476921e+01 4.04844170e+01 2.69045544e+01 1.90418720e+01 1.64044342e+01 2.09746094e+01 4.44389534e+01 5.24919662e+01 5.42646294e+01 3.22837639e+01 1.21232061e+01 2.19449463e+01 4.48683090e+01 6.73013077e+01 6.57696686e+01 3.96445618e+01 2.40166187e+01 2.05609818e+01 4.49613800e+01 6.24834442e+01 5.42843895e+01 4.44290581e+01 2.87691364e+01 4.25686493e+01 5.62152786e+01 5.50293732e+01 4.05395470e+01 8.27735996e+00 -4.79569912e+00 -5.22614479e+00 1.06187620e+01 2.53804531e+01 2.13138962e+01 2.72620754e+01 2.87063789e+01 1.96923332e+01 2.08003616e+01 3.09981899e+01 4.70846519e+01 3.41318016e+01 -2.89332914e+00 -9.37920284e+00 5.49853849e+00 4.46465340e+01 5.70950279e+01 4.63540993e+01 4.20220108e+01 2.27285538e+01 2.46138306e+01 3.15339451e+01 4.07674866e+01 4.36179695e+01 2.12889996e+01 8.86993885e+00 9.29800224e+00 1.81341228e+01 3.83740883e+01 4.40015488e+01 5.14779930e+01 4.55196342e+01 2.48067970e+01 2.74361267e+01 3.57775803e+01 5.60022736e+01 5.71426735e+01 3.72373581e+01 2.54529896e+01 2.34416027e+01 4.44865646e+01 5.72498207e+01 4.44188423e+01 3.40171280e+01 1.08705597e+01 -1.54093921e+00 -2.27415666e-01 1.28393040e+01 3.53766441e+01 3.60370407e+01 1.76171322e+01 5.82957554e+00 8.40878367e-01 2.65143661e+01 4.08542862e+01 5.03630943e+01 4.37885323e+01 6.30678701e+00 -4.18867970e+00 3.96035492e-01 3.48822441e+01 4.78861275e+01 2.86492195e+01 1.83690033e+01 1.93630409e+01 4.11847534e+01 6.15550308e+01 4.96247559e+01 3.97011833e+01 1.97408981e+01 2.76869335e+01 4.36447411e+01 4.65975227e+01 5.07028580e+01 4.56815453e+01 3.99939346e+01 2.92140846e+01 2.09925594e+01 3.76318245e+01 5.12140999e+01 5.66910515e+01 4.27098312e+01 2.15747471e+01 2.06259079e+01 2.66014805e+01 3.75963020e+01 3.72392426e+01 1.60682411e+01 2.64951420e+00 -1.98079777e+00 1.05466852e+01 1.53262949e+01 7.06322765e+00 1.00762033e+01 2.44742298e+00 -4.63705206e+00 -6.27995968e+00 1.87986672e+00 1.09544230e+01 1.31563282e+01 1.51821136e+01 1.39684315e+01 1.20877733e+01 2.06445503e+01 3.61250877e+01 5.10848656e+01 5.33537369e+01 3.34523659e+01 1.71414928e+01 1.80107841e+01 3.72927094e+01 5.64402122e+01 4.66284027e+01 3.63356209e+01 1.39029665e+01 2.00277748e+01 3.00344658e+01 3.26373520e+01 3.16842403e+01 2.17384815e+01 9.02721500e+00 -2.61667538e+00 -4.48592615e+00 8.66599560e+00 1.11102190e+01 4.56572247e+00 -8.48827839e+00 -1.72299805e+01 4.17661762e+00 2.83016911e+01 4.61114502e+01 4.35717354e+01 2.05522289e+01 8.20268059e+00 6.88732386e+00 2.89302368e+01 3.51503639e+01 2.03249645e+01 1.33763971e+01 9.96352100e+00 1.97540951e+01 2.42067776e+01 1.65217037e+01 5.47941303e+00 -1.70696869e+01 -3.33186493e+01 -3.75455132e+01 -3.24655418e+01 -4.79520369e+00 9.58430862e+00 3.03486519e+01 1.95668850e+01 -2.31959381e+01 -5.41807518e+01 -5.00656738e+01 -1.78936386e+01 -2.15312099e+00 -1.12596140e+01 -1.10374653e+00 1.17706919e+01 1.65573139e+01 9.88758373e+00 -6.15712547e+00 -1.04204330e+01 -1.30312843e+01 -8.41839600e+00 -2.35041499e+00 -7.74547434e+00 -1.64526405e+01 -2.27981701e+01 -1.87662010e+01 -1.09214439e+01 -8.89388371e+00 -6.67710972e+00 -9.67758274e+00 -4.61526820e-03 9.67931557e+00 1.37927828e+01 4.80378532e+00 -6.84342813e+00 -4.60837126e+00 6.83965802e-01 2.30263543e+00 1.87668771e-01 -2.04146218e+00 -2.04888880e-01 2.26629877e+00 3.83436799e-01 -1.90923512e+00 -9.91802025e+00 -1.27301102e+01 -9.78156376e+00 -7.78874159e+00 -3.84733963e+00 -9.43652534e+00 -9.04993343e+00 -1.25806561e+01 -6.53025866e+00 -5.65104103e+00 -4.12839270e+00 -9.86404991e+00 -1.22988577e+01 -9.99452972e+00 -5.47340631e+00 -6.10866261e+00 -1.25278206e+01 -2.12689571e+01 -2.01610546e+01 -2.33626823e+01 -2.44984150e+01 -2.37987976e+01 -1.57525320e+01 -9.58847713e+00 -1.04078360e+01 -9.68857288e+00 -1.02176723e+01 -1.05355759e+01 -1.71295681e+01 -1.75074253e+01 -1.45039988e+01 -8.65470886e+00 -1.19041567e+01 -1.08432217e+01 -1.35921078e+01 -1.04104424e+01 -1.28716898e+01 -1.40675592e+01 -1.31746769e+01 -1.42565355e+01 -1.22817059e+01 -1.36941347e+01 -1.78677979e+01 -2.53068371e+01 -2.81756916e+01 -2.41898022e+01 -1.52666531e+01 -1.37894516e+01 -1.13902416e+01 -1.76896400e+01 -2.10047054e+01 -2.46119633e+01 -1.99752331e+01 -1.09557972e+01 -8.83051395e+00 -1.41229448e+01 -1.55364704e+01 -1.33171854e+01 -1.01735029e+01 -1.33507328e+01 -1.68295918e+01 -1.72189598e+01 -2.19556503e+01 -2.47335243e+01 -2.79634552e+01 -2.78564014e+01 -2.77946014e+01 -2.75184517e+01 -2.35346603e+01 -2.43961658e+01 -2.45540104e+01 -2.50054646e+01 -2.40526237e+01 -2.67979736e+01 -3.34971619e+01 -3.06532803e+01 -2.35246468e+01 -1.92770004e+01 -1.97108803e+01 -2.57055626e+01 -2.68393917e+01 -2.84458332e+01 -2.47207432e+01 -2.32744122e+01 -2.40685501e+01 -2.89493866e+01 -3.69408722e+01 -4.52434578e+01 -4.92295074e+01 -5.10638428e+01 -4.47598038e+01 -3.83903542e+01 -2.75679665e+01 -2.36417713e+01 -2.69945488e+01 -3.04632187e+01 -3.42705231e+01 -4.26362305e+01 -5.31319466e+01 -4.78722687e+01 -3.82757378e+01 -2.98727417e+01 -3.60712013e+01 -4.38656731e+01 -4.87517395e+01 -4.18724213e+01 -3.09724369e+01 -2.51590252e+01 -3.56384392e+01 -4.93835449e+01 -5.23409958e+01 -4.41903992e+01 -3.08726501e+01 -2.98577156e+01 -3.27308846e+01 -3.66760101e+01 -3.74162598e+01 -3.57862854e+01 -3.34418640e+01 -4.03379517e+01 -5.01130905e+01 -4.80331802e+01 -4.01907997e+01 -3.32788200e+01 -3.47289848e+01 -3.44459381e+01 -3.28055420e+01 -3.23743935e+01 -3.17194309e+01 -3.78324471e+01 -4.52744751e+01 -4.54980354e+01 -4.10971107e+01 -3.51872063e+01 -3.80071373e+01 -3.89016495e+01 -3.53011703e+01 -2.95546646e+01 -1.79560165e+01 -1.08151312e+01 -1.99314079e+01 -3.22699394e+01 -4.05464401e+01 -3.75715866e+01 -3.45276337e+01 -3.33965416e+01 -2.93841343e+01 -2.94643955e+01 -3.10435925e+01 -3.40075455e+01 -3.63785782e+01 -3.69906731e+01 -3.48281517e+01 -3.42506027e+01 -3.27343292e+01 -3.43458023e+01 -3.36630974e+01 -3.52342262e+01 -3.75438805e+01 -4.40290260e+01 -4.79345169e+01 -4.52442284e+01 -3.50410042e+01 -2.73083801e+01 -2.55618382e+01 -3.11754723e+01 -4.26430664e+01 -4.69572105e+01 -4.42046280e+01 -4.12064133e+01 -3.99354324e+01 -4.28700371e+01 -3.49620514e+01 -2.62818050e+01 -2.45268822e+01 -3.30392113e+01 -4.18488197e+01 -4.26017189e+01 -3.73389053e+01 -3.32396011e+01 -3.33854561e+01 -3.68154182e+01 -4.42464828e+01 -4.34860649e+01 -4.39445038e+01 -4.27503052e+01 -4.46148224e+01 -3.96106834e+01 -3.32324448e+01 -3.22742615e+01 -3.75313911e+01 -4.33819923e+01 -6.94338989e+01 -6.49885864e+01 -4.10402298e+01 1.14392493e+03 9.82107227e+03 24924678. 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. 0. 0. 0. 0. 0. 0. 0. 531313536. 101834000. 25236908. 79759368. 5.72096729e+03 -6.93767944e+02 -7.08361023e+02 -1.27531670e+02 -8.90819473e+01 -5.84684753e+01 -6.61067505e+01 -6.35153465e+01 -6.33442764e+01 -6.30930977e+01 -6.40345917e+01 -6.30894852e+01 -6.13401222e+01 -5.98603592e+01 -5.42086182e+01 -4.91530685e+01 -5.19720497e+01 -5.81276894e+01 -5.99558678e+01 -5.54290314e+01 -5.13843918e+01 -5.06679153e+01 -4.79247284e+01 -4.56383896e+01 -4.19538269e+01 -4.14719620e+01 -4.31165810e+01 -4.61687851e+01 -4.77019577e+01 -4.68469772e+01 -4.67161026e+01 -4.68436089e+01 -5.24875107e+01 -5.96115685e+01 -6.10830574e+01 -6.01653633e+01 -5.75243340e+01 -5.93667526e+01 -5.88486443e+01 -5.69067383e+01 -5.67891388e+01 -5.63444672e+01 -5.93787994e+01 -5.80248260e+01 -5.61763306e+01 -5.34922562e+01 -5.60700455e+01 -5.94625816e+01 -6.09095345e+01 -5.83260155e+01 -5.78552895e+01 -5.89264221e+01 -6.15370216e+01 -6.31167641e+01 -6.36082840e+01 -6.24395981e+01 -5.80916901e+01 -5.84014320e+01 -6.10144386e+01 -6.45895844e+01 -6.60993423e+01 -6.67369843e+01 -6.74061661e+01 -6.71007004e+01 -6.57628860e+01 -6.61457901e+01 -6.47725906e+01 -6.41518326e+01 -6.30517883e+01 -6.18244934e+01 -6.13670235e+01 -5.50049667e+01 -4.95305977e+01 -4.92376366e+01 -5.43513527e+01 -5.99677811e+01 -5.99391136e+01 -6.02896805e+01 -6.37569580e+01 -6.78833160e+01 -7.25797272e+01 -7.45401382e+01 -7.11301498e+01 -6.68771210e+01 -6.21794930e+01 -6.31123619e+01 -6.42265549e+01 -6.48949509e+01 -6.40171967e+01 -6.31847382e+01 -6.22193604e+01 -6.23898354e+01 -6.24902077e+01 -6.24129219e+01 -6.13634300e+01 -6.16199760e+01 -6.00229836e+01 -5.98519135e+01 -5.87554245e+01 -5.92965317e+01 -5.85595665e+01 -5.81396217e+01 -5.94878311e+01 -6.32969818e+01 -6.68032150e+01 -6.83770599e+01 -6.88550339e+01 -6.52245636e+01 -6.22035561e+01 -5.76224747e+01 -5.81522293e+01 -5.96077957e+01 -5.95986023e+01 -5.82482109e+01 -5.71749153e+01 -5.85931511e+01 -6.08606606e+01 -6.18121910e+01 -6.29951439e+01 -6.36165733e+01 -6.48582611e+01 -6.53180161e+01 -6.55398712e+01 -6.50597229e+01 -6.46826248e+01 -6.44556274e+01 -6.43551483e+01 -6.42061996e+01 -6.61543198e+01 -6.80589905e+01 -7.00292587e+01 -6.99353180e+01 -6.82321701e+01 -6.64421005e+01 -6.39934311e+01 -6.34317398e+01 -6.33072128e+01 -6.32797623e+01 -6.30923271e+01 -6.27283020e+01 -6.24731979e+01 -6.28874435e+01 -6.31600761e+01 -6.31091499e+01 -6.27539024e+01 -6.28007088e+01 -6.28291931e+01 -6.33126068e+01 -6.44535828e+01 -6.60636520e+01 -6.59410858e+01 -6.50035553e+01 -6.38598022e+01 -6.47822952e+01 -6.56899338e+01 -6.64220505e+01 -6.60125504e+01 -6.50250397e+01 -6.43901062e+01 -6.38277283e+01 -6.37450943e+01 -6.35152016e+01 -6.34780769e+01 -6.34799728e+01 -6.34902878e+01 -6.35683823e+01 -6.35792160e+01 -6.36007156e+01 -6.35958862e+01 -6.36265526e+01 -6.36338501e+01 -6.36304626e+01 -6.36577454e+01 -6.36083031e+01 -6.34374657e+01 -6.33289757e+01 -6.34130707e+01 -6.35977478e+01 -6.36400146e+01 -6.38469582e+01 -6.35102615e+01 -6.29859467e+01 -6.27078781e+01 -6.31048813e+01 -6.35380096e+01 -6.32694016e+01 -6.32901497e+01 -6.33291931e+01 -6.34161911e+01 -6.30915642e+01 -6.29667473e+01 -6.32797890e+01 -6.34249344e+01 -6.35076942e+01 -6.33471222e+01 -6.30593681e+01 -6.27790642e+01 -6.24474068e+01 -6.16375427e+01 -6.08697433e+01 -6.00019531e+01 -6.03257828e+01 -6.12064934e+01 -6.21024246e+01 -6.33019829e+01 -6.35532494e+01 -6.37186890e+01 -6.36179504e+01 -6.34441414e+01 -6.35239601e+01 -6.35307121e+01 -6.39073448e+01 -6.41887054e+01 -6.39032516e+01 -6.38046837e+01 -6.36575966e+01 -6.59011612e+01 -6.77684708e+01 -6.69604340e+01 -6.47409973e+01 -6.29002876e+01 -6.34919930e+01 -6.36641541e+01 -6.17672501e+01 -5.92646294e+01 -5.86580658e+01 -6.03249245e+01 -6.28452644e+01 -6.24834557e+01 -6.22758751e+01 -6.16979446e+01 -6.17975388e+01 -6.15382347e+01 -6.17129745e+01 -6.15966797e+01 -6.15077171e+01 -6.13172150e+01 -6.07148209e+01 -6.02186546e+01 -6.02442093e+01 -6.05147667e+01 -5.85565796e+01 -5.44111900e+01 -5.27300224e+01 -5.40196190e+01 -5.75398407e+01 -5.96503181e+01 -5.92947388e+01 -5.55108948e+01 -5.13780632e+01 -5.27045135e+01 -5.69491196e+01 -6.10752411e+01 -6.16377182e+01 -6.22617989e+01 -6.14387016e+01 -6.10039635e+01 -6.41373978e+01 -6.93398514e+01 -7.00423203e+01 -6.63119507e+01 -6.12861328e+01 -6.15537872e+01 -6.20643539e+01 -6.21175232e+01 -6.06926727e+01 -5.72405968e+01 -5.39249268e+01 -5.34860573e+01 -5.58676682e+01 -5.91604271e+01 -5.92408485e+01 -5.97030182e+01 -5.61956329e+01 -5.26946297e+01 -5.38927803e+01 -5.76272278e+01 -6.33538704e+01 -6.34064789e+01 -6.44652328e+01 -6.27159958e+01 -6.09900169e+01 -6.00175323e+01 -6.00096092e+01 -6.04008675e+01 -6.04881744e+01 -6.10481834e+01 -6.11669044e+01 -6.10396385e+01 -5.96912155e+01 -5.70099030e+01 -5.01133842e+01 -4.39778519e+01 -4.09868088e+01 -4.28927536e+01 -5.08027496e+01 -5.66356812e+01 -6.12232780e+01 -5.98906670e+01 -5.81403160e+01 -5.74847260e+01 -5.60673599e+01 -5.65184708e+01 -5.67190514e+01 -5.88072701e+01 -5.80618286e+01 -5.84756012e+01 -5.77114944e+01 -5.77399521e+01 -5.57157135e+01 -5.52115707e+01 -5.62181053e+01 -5.62021179e+01 -5.70664711e+01 -5.69461632e+01 -5.84136162e+01 -5.92975578e+01 -5.98576088e+01 -5.53993454e+01 -5.10226364e+01 -4.99107285e+01 -4.73422012e+01 -4.24824944e+01 -3.57591896e+01 -3.55965958e+01 -3.85805740e+01 -3.81677132e+01 -4.04822502e+01 -3.84500961e+01 -4.27397194e+01 -4.73856773e+01 -5.27881927e+01 -4.77277451e+01 -3.89071617e+01 -4.02399940e+01 -4.49340706e+01 -5.09167366e+01 -4.94354553e+01 -4.94117393e+01 -5.02969627e+01 -5.18517151e+01 -5.09683952e+01 -4.86081581e+01 -3.96828461e+01 -3.27226334e+01 -3.54710121e+01 -4.16963120e+01 -4.99351006e+01 -4.36419868e+01 -4.08819580e+01 -3.76245117e+01 -3.58575020e+01 -3.15910397e+01 -2.42311230e+01 -3.09038353e+01 -4.01278343e+01 -5.00596199e+01 -5.38072777e+01 -5.69647369e+01 -5.55154381e+01 -5.17761650e+01 -3.96623154e+01 -3.23153839e+01 -2.18786755e+01 -1.88030643e+01 -2.49102783e+01 -2.50352135e+01 -2.52016144e+01 -2.47179985e+01 -3.34985046e+01 -4.41195412e+01 -4.61608200e+01 -4.49542198e+01 -4.25429230e+01 -4.23779564e+01 -3.58602791e+01 -3.08678989e+01 -3.05666084e+01 -3.92734718e+01 -4.94509964e+01 -5.02090988e+01 -4.94139977e+01 -4.64255943e+01 -4.62742462e+01 -4.85515442e+01 -5.30091324e+01 -5.38661537e+01 -5.29955139e+01 -4.33644295e+01 -3.45048485e+01 -3.13497143e+01 -3.56954422e+01 -3.91076431e+01 -3.97480278e+01 -4.42080650e+01 -4.94202347e+01 -5.05342178e+01 -3.93017197e+01 -2.75097637e+01 -2.43267155e+01 -2.82138367e+01 -3.49597015e+01 -3.59354858e+01 -3.58244743e+01 -3.91339417e+01 -4.23034935e+01 -5.12677536e+01 -4.26826782e+01 -2.82003689e+01 -2.76102180e+01 -3.99260483e+01 -5.15740891e+01 -4.44650726e+01 -3.24264984e+01 -2.41301231e+01 -2.77011604e+01 -3.61694374e+01 -4.28895035e+01 -4.03438835e+01 -4.00022278e+01 -3.02246418e+01 -2.35567131e+01 -2.17412853e+01 -2.50810509e+01 -2.80041370e+01 -2.51187229e+01 -2.91032639e+01 -2.26680298e+01 -1.28946180e+01 -1.17355394e+01 -2.10035038e+01 -3.33839378e+01 -2.83485832e+01 -1.89488411e+01 -1.56167727e+01 -2.02451496e+01 -3.11037292e+01 -3.41532440e+01 -3.50492821e+01 -3.33669968e+01 -3.72696686e+01 -4.40961876e+01 -4.49009056e+01 -3.91359177e+01 -2.96280842e+01 -2.47525558e+01 -2.24013729e+01 -2.55873241e+01 -2.91531658e+01 -3.71710358e+01 -4.14796524e+01 -4.65132484e+01 -4.61603661e+01 -4.21907845e+01 -3.51711426e+01 -3.42741051e+01 -3.78045197e+01 -3.40844421e+01 -2.75630741e+01 -3.15644608e+01 -3.98155937e+01 -5.23586159e+01 -5.38388557e+01 -5.00720406e+01 -3.86775169e+01 -2.40584049e+01 -1.16493769e+01 1.95995343e+00 -1.29399574e+00 -1.49511127e+01 -2.01462440e+01 -1.19213190e+01 -1.18457136e+01 -2.23953533e+01 -2.88942719e+01 -2.86197643e+01 -2.81735573e+01 -2.92611465e+01 -2.48815975e+01 -2.61528759e+01 -3.21749191e+01 -4.18427010e+01 -3.77166023e+01 -2.92730408e+01 -3.03679066e+01 -3.52164803e+01 -2.70397606e+01 -9.40425014e+00 -1.10200548e+01 -2.94129887e+01 -4.67511711e+01 -4.30235977e+01 -2.87200985e+01 -1.27029762e+01 -1.21139565e+01 -2.16293297e+01 -2.75502834e+01 -1.78298359e+01 -1.15770779e+01 -1.29937811e+01 -2.23360271e+01 -2.13270817e+01 -6.75381136e+00 1.25160408e+01 2.40156898e+01 2.61825485e+01 -3.86894882e-01 -2.74052486e+01 -3.20838585e+01 -6.53446674e+00 1.17176132e+01 1.59405303e+00 -1.40502176e+01 -2.33032589e+01 -2.91278248e+01 -3.58829460e+01 -3.75169601e+01 -3.32476616e+01 -2.51045036e+01 -1.44272718e+01 -3.48888564e+00 9.53611183e+00 8.13449764e+00 -5.76777458e+00 -1.85367546e+01 -1.84425087e+01 -1.58181019e+01 -1.94360123e+01 -1.90010376e+01 -1.84525967e+01 -1.65152187e+01 -1.71117954e+01 -2.15099354e+01 -1.38427200e+01 -3.36809039e+00 1.22156411e-01 2.87127709e+00 7.55599928e+00 4.46775961e+00 -7.69297791e+00 -2.03862953e+01 -1.92427292e+01 -1.92894268e+01 -2.07184467e+01 -1.96121521e+01 -3.27058697e+00 1.16572571e+01 2.40804005e+01 2.48821201e+01 5.38074589e+00 -1.10403461e+01 -2.11915855e+01 -8.03838348e+00 5.71628714e+00 1.56622338e+00 -7.29797697e+00 -1.27926140e+01 -9.44854450e+00 -4.29540537e-02 5.35216713e+00 4.70871115e+00 8.45459843e+00 2.66784725e+01 4.54415131e+01 3.89606628e+01 1.19576178e+01 -4.09372759e+00 7.72035456e+00 2.24252968e+01 2.59037399e+01 1.05664339e+01 -2.99735975e+00 4.16776991e+00 1.53050880e+01 3.15676842e+01 3.54542198e+01 2.04453907e+01 3.05707663e-01 -1.94040127e+01 -2.04714565e+01 -1.78365440e+01 -1.98190804e+01 -1.76382389e+01 -9.50009918e+00 4.24162531e+00 5.40886784e+00 -4.47193480e+00 -1.63193474e+01 -2.48697090e+01 -2.24369030e+01 -3.32821059e+00 1.78763447e+01 1.40446148e+01 -2.00182891e+00 -1.18426676e+01 -1.12258577e+01 -1.00559721e+01 -1.22246017e+01 -1.29007215e+01 -8.25597286e+00 -9.37087059e+00 -1.09000111e+00 1.95980053e+01 3.11175251e+01 2.65282822e+01 2.88831863e+01 9.46967621e+01 7.57686621e+03 0. 0. 0. 0. 0. -1.00518359e+10 6.88672050e+06 -1.24118050e+06 9.57281860e+02 -3.14223584e+03 -3.96726831e+03 2.57269953e+05 2.57294008e+10 1.98114714e+10 1.98114714e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.57624832e+09 -35889752. 4.13504025e+06 -9.55014258e+03 -3.63270850e+03 -8.92118286e+02 4.69423180e+01 -1.40610870e+02 -4.91317825e+01 -7.70866089e+01 -6.53300934e+01 -3.56595383e+01 -1.48999224e+01 2.23559046e+00 8.13846874e+00 1.72853203e+01 -1.81375813e+00 -2.81874161e+01 -5.40693016e+01 -4.95848618e+01 3.10126901e-01 4.52137680e+01 7.02692566e+01 8.24026108e+01 5.99827271e+01 5.48896027e+01 4.21984444e+01 1.22133503e+01 -5.90283298e+00 7.93133402e+00 5.15341797e+01 9.68395233e+01 9.24767838e+01 5.83153915e+01 -1.06262808e+01 -2.43504715e+01 -1.15616293e+01 5.33186555e-01 2.06375003e+00 9.33802223e+00 4.26323738e+01 6.40844345e+01 4.83635597e+01 1.59242287e+01 3.78769708e+00 3.18709373e+01 3.75166779e+01 2.85057278e+01 4.10847321e+01 3.86122169e+01 4.03644333e+01 2.34516697e+01 4.23555613e+00 -1.27981157e+01 -1.69206505e+01 2.86491528e+01 8.37764130e+01 9.67177963e+01 6.43094101e+01 9.45005322e+00 3.46088290e+00 2.63076763e+01 4.39370232e+01 3.61464272e+01 2.86456833e+01 3.98759575e+01 4.90332832e+01 4.70948067e+01 2.05077267e+01 -1.24107285e+01 1.44517332e-01 9.68098450e+00 2.39358845e+01 3.40182266e+01 3.86702766e+01 5.20656013e+01 3.28750763e+01 6.45219517e+00 -2.36805305e+01 -1.60681629e+01 1.85631714e+01 5.46816101e+01 7.48311996e+01 7.58116074e+01 4.58312149e+01 3.33921585e+01 3.24758873e+01 1.04408855e+01 -1.79056759e+01 -1.95408478e+01 2.95044346e+01 7.32888565e+01 7.09925613e+01 3.04734955e+01 -1.17422352e+01 -1.41043186e+01 -5.77285624e+00 -5.23232460e+00 -5.93651772e+00 8.83265400e+00 3.34028893e+01 4.53994293e+01 3.00899200e+01 4.17137861e+00 4.20450258e+00 2.88484535e+01 5.83085632e+01 6.87532196e+01 6.66026382e+01 3.74358864e+01 1.10449085e+01 1.66862812e+01 1.73387604e+01 5.75653219e+00 -1.92489755e+00 1.93804951e+01 5.72018204e+01 5.56119804e+01 1.81800499e+01 -1.85848446e+01 -2.41706791e+01 7.58601999e+00 3.81019287e+01 6.08133240e+01 7.13821106e+01 5.53270683e+01 4.36381340e+01 3.57411041e+01 1.07002535e+01 -1.34204969e+01 -1.35624676e+01 9.67767811e+00 4.02002029e+01 5.32835083e+01 5.24590187e+01 3.38926239e+01 2.32769165e+01 2.14084778e+01 1.82597046e+01 7.10705423e+00 3.19522786e+00 2.81034241e+01 6.44435806e+01 8.48851929e+01 7.75206299e+01 6.09102821e+01 5.86888885e+01 4.39898300e+01 3.68991165e+01 4.34401588e+01 4.98730774e+01 6.98260574e+01 7.44985733e+01 6.99739075e+01 4.85304985e+01 4.13185005e+01 5.93162880e+01 7.75521545e+01 6.64613647e+01 3.80052032e+01 2.46958542e+01 4.61274643e+01 6.99605789e+01 6.71342392e+01 6.39052582e+01 6.68762894e+01 9.65654221e+01 1.17731834e+02 1.18960968e+02 7.73622284e+01 3.01211586e+01 2.24412231e+01 2.92628880e+01 3.16067772e+01 3.28706017e+01 4.72901192e+01 7.60779724e+01 8.94618454e+01 6.44956665e+01 3.74360237e+01 2.98635979e+01 5.91063194e+01 8.07379150e+01 8.01573410e+01 7.78677444e+01 6.99679337e+01 8.16322327e+01 8.28496475e+01 7.37286911e+01 7.11549759e+01 7.60476074e+01 9.84576492e+01 1.09991547e+02 1.08009117e+02 6.88616180e+01 3.12056980e+01 2.35739059e+01 3.86223259e+01 4.62281456e+01 5.03917236e+01 6.06399994e+01 8.47204742e+01 8.69367676e+01 5.68896599e+01 2.68242054e+01 2.04538803e+01 4.96533508e+01 6.25334206e+01 6.46656723e+01 6.32896385e+01 6.37160912e+01 7.30596390e+01 8.49735260e+01 6.85464630e+01 4.70486641e+01 3.72796059e+01 5.93897743e+01 8.30233002e+01 8.69196091e+01 6.51458359e+01 4.81960373e+01 4.64093513e+01 5.58763771e+01 5.32118835e+01 5.27252159e+01 4.99277496e+01 5.60700111e+01 5.60958099e+01 5.34922523e+01 4.66078377e+01 3.73508492e+01 3.86154022e+01 4.31319237e+01 4.90023956e+01 7.03551254e+01 8.02944565e+01 9.57065582e+01 8.47361221e+01 6.77888184e+01 5.29631157e+01 3.91352386e+01 6.57004395e+01 8.62963791e+01 9.08882523e+01 6.63383560e+01 5.25797424e+01 6.37688828e+01 7.63581848e+01 6.58594818e+01 5.26673088e+01 5.91600761e+01 8.03779984e+01 9.08336945e+01 8.03221588e+01 7.79169922e+01 7.54862671e+01 7.64957123e+01 6.64022369e+01 7.36032028e+01 8.01790161e+01 8.68289490e+01 9.57524796e+01 9.44760971e+01 8.94489899e+01 6.96493073e+01 5.67465744e+01 6.81484680e+01 9.73514175e+01 1.07892021e+02 9.61236115e+01 8.87908630e+01 9.31031265e+01 1.00418701e+02 8.61140976e+01 7.76032562e+01 7.67731018e+01 8.14278793e+01 8.05366745e+01 7.72856903e+01 8.29824905e+01 8.32630768e+01 7.27518616e+01 6.42165146e+01 6.80773926e+01 6.45985947e+01 5.20970192e+01 5.28393021e+01 7.02030487e+01 8.73962860e+01 8.54818802e+01 8.09519958e+01 8.43845901e+01 9.50497513e+01 8.95315170e+01 7.96562347e+01 7.84171906e+01 8.88308487e+01 9.91064148e+01 9.43668823e+01 9.10579987e+01 8.38280411e+01 8.53957977e+01 7.69841995e+01 6.86910400e+01 7.08914719e+01 7.81588593e+01 8.49138184e+01 8.05967255e+01 7.72298431e+01 7.12226791e+01 6.27592850e+01 6.54503479e+01 7.10731354e+01 7.97567139e+01 7.32214966e+01 6.68697357e+01 7.35558929e+01 8.99079514e+01 9.15686722e+01 8.12521133e+01 7.40269928e+01 8.45078583e+01 9.37428970e+01 8.93462524e+01 8.30801086e+01 7.44493027e+01 7.33371048e+01 6.75564957e+01 6.65428391e+01 7.11068268e+01 7.54495316e+01 7.73649063e+01 7.57009354e+01 7.86799088e+01 7.65982971e+01 7.26882858e+01 7.53990402e+01 8.66733780e+01 9.40070038e+01 9.25158539e+01 8.97114334e+01 9.27709885e+01 9.70358810e+01 9.27353363e+01 8.96419525e+01 8.83476639e+01 9.46619873e+01 9.35238419e+01 8.91975098e+01 8.91311874e+01 8.76335373e+01 8.69908676e+01 7.76067810e+01 7.43072281e+01 7.72594452e+01 8.47942276e+01 9.30689850e+01 9.17189178e+01 8.85795441e+01 8.23981400e+01 7.34258041e+01 7.52480469e+01 8.84377518e+01 1.03842720e+02 1.08548935e+02 1.00253151e+02 9.49855499e+01 9.72402115e+01 9.82129059e+01 1.02987091e+02 9.69606476e+01 9.63998947e+01 9.28146133e+01 9.30484543e+01 1.02283684e+02 1.05075897e+02 1.05024780e+02 9.30108643e+01 8.52645416e+01 8.99986801e+01 9.62047806e+01 9.90399857e+01 9.13312073e+01 8.50977020e+01 8.61060104e+01 8.64444199e+01 9.07021179e+01 9.37199707e+01 9.71833649e+01 9.92884674e+01 9.61689987e+01 9.30282440e+01 9.05644302e+01 9.04107361e+01 9.62081528e+01 9.87872391e+01 1.01656982e+02 9.85784607e+01 9.32074814e+01 9.26251984e+01 9.25143585e+01 9.19907608e+01 8.76465683e+01 8.80891495e+01 9.55584641e+01 1.00132599e+02 1.00252670e+02 9.61610565e+01 9.39906769e+01 9.33204575e+01 9.14034500e+01 9.15583420e+01 9.37453842e+01 9.52890320e+01 9.70970917e+01 9.58472519e+01 9.54108810e+01 9.51889038e+01 9.47838211e+01 9.47788849e+01 9.21363144e+01 9.19770584e+01 9.23722610e+01 9.31686249e+01 9.48897705e+01 9.53218842e+01 9.51962128e+01 9.30533142e+01 9.17269974e+01 9.18163300e+01 9.29414673e+01 9.37961655e+01 9.31743011e+01 9.24660797e+01 9.23228226e+01 9.25760345e+01 9.27980881e+01 9.29036484e+01 9.28828812e+01 9.27796631e+01 9.28319626e+01 9.30157700e+01 9.32748108e+01 9.30422363e+01 9.19570999e+01 9.12147903e+01 9.12807159e+01 9.23750687e+01 9.36275101e+01 9.29392395e+01 9.16460648e+01 9.07637329e+01 9.21628265e+01 9.36871033e+01 9.34138870e+01 9.25085068e+01 9.15072861e+01 9.16781235e+01 9.20376511e+01 9.11935120e+01 9.11066971e+01 9.12387085e+01 9.09254456e+01 9.07995987e+01 8.91513596e+01 9.02860794e+01 9.08182373e+01 9.15843506e+01 9.21586685e+01 8.96334763e+01 9.11968231e+01 9.27457352e+01 9.66963196e+01 9.59118958e+01 9.01252747e+01 8.56732788e+01 8.39171295e+01 9.05714722e+01 9.57677917e+01 9.75808487e+01 9.44129791e+01 8.97994614e+01 8.93576126e+01 9.23396912e+01 9.52927780e+01 9.80393600e+01 9.51242447e+01 8.92648163e+01 8.21826706e+01 8.19784851e+01 9.08726425e+01 9.84543686e+01 1.01484772e+02 9.86990128e+01 8.98424530e+01 8.26013031e+01 8.13670197e+01 8.96687088e+01 9.79651489e+01 9.56599274e+01 8.74777222e+01 8.17406158e+01 8.75627136e+01 9.68391266e+01 9.84792023e+01 9.50439072e+01 8.68907623e+01 8.11772537e+01 8.03783112e+01 8.19166412e+01 8.81857758e+01 9.34939957e+01 9.40172577e+01 9.13819275e+01 8.18746796e+01 8.32457199e+01 8.72961349e+01 9.08014374e+01 9.62234344e+01 8.87640076e+01 8.82676849e+01 8.61866760e+01 9.41101074e+01 9.65863800e+01 8.24914627e+01 7.50179901e+01 7.42629471e+01 8.83465500e+01 9.83523026e+01 9.99507065e+01 9.49795151e+01 8.39890823e+01 7.63754959e+01 7.67118454e+01 7.83568726e+01 8.64593964e+01 8.95837173e+01 8.71369553e+01 8.67492752e+01 8.31975708e+01 9.42663956e+01 9.44329300e+01 9.53049164e+01 9.21365662e+01 7.98321915e+01 7.90228958e+01 8.37783203e+01 1.01832718e+02 1.08028099e+02 1.03834801e+02 9.41922684e+01 8.37464523e+01 9.02286377e+01 1.00947456e+02 1.07660080e+02 1.03829552e+02 9.39908218e+01 8.77811737e+01 8.44101639e+01 8.19871979e+01 8.12134323e+01 8.13977280e+01 8.11820374e+01 7.81195908e+01 6.63173676e+01 7.66188812e+01 9.02383423e+01 1.01657341e+02 9.13021851e+01 7.12816620e+01 6.20869102e+01 6.65588760e+01 8.38953018e+01 9.56619339e+01 8.94793167e+01 8.06539383e+01 7.56824722e+01 8.02797546e+01 8.38175659e+01 7.73365936e+01 7.34826736e+01 6.83525620e+01 6.54188995e+01 6.39247475e+01 6.12307968e+01 7.10995941e+01 7.66551590e+01 7.72879410e+01 7.81559525e+01 6.90870361e+01 7.34798431e+01 7.44726639e+01 8.40247955e+01 8.96806335e+01 7.52566833e+01 7.33308334e+01 6.86616058e+01 8.11627960e+01 8.76355667e+01 7.76651840e+01 7.43278961e+01 5.51663551e+01 6.37384300e+01 7.52309418e+01 9.13655930e+01 9.81738892e+01 7.68173599e+01 6.97241135e+01 6.67290802e+01 6.43866043e+01 6.35925827e+01 6.58580399e+01 9.18109589e+01 9.65374527e+01 7.05763550e+01 7.52270737e+01 9.89781494e+01 1.50885269e+02 1.21322792e+02 7.92845520e+02 1.34213391e+03 -2.36623120e+03 -7.82761475e+03 60965684. 25801794. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 301800640. 50986700. 4.51143555e+03 1.69298975e+03 1.64395157e+02 2.86761292e+02 3.42492493e+02 1.74693542e+02 1.04269867e+02 9.08753891e+01 7.82637253e+01 7.85289764e+01 6.41625900e+01 5.33728828e+01 5.11076851e+01 6.06372604e+01 6.20699120e+01 4.47315483e+01 3.31369095e+01 3.54503784e+01 3.95856705e+01 4.88767738e+01 5.44861069e+01 7.42397995e+01 7.86923523e+01 5.10516396e+01 3.71251526e+01 4.88701363e+01 7.55085831e+01 5.82595253e+01 2.23138905e+01 1.72933197e+01 3.74225922e+01 5.99631081e+01 6.10575714e+01 5.60519409e+01 5.83570061e+01 5.15937042e+01 4.11324120e+01 3.41168785e+01 3.97765656e+01 5.49995117e+01 4.63621178e+01 3.54885902e+01 1.82200546e+01 -4.76333427e+00 1.14632950e+01 4.16861267e+01 8.58656616e+01 8.34438248e+01 4.30047073e+01 3.61251678e+01 4.53412933e+01 7.58331909e+01 7.41204605e+01 5.02129745e+01 3.77905312e+01 2.67389584e+01 4.44829788e+01 4.80189857e+01 4.73908997e+01 3.95697823e+01 1.70727463e+01 2.55068779e+00 1.29619193e+00 1.93038445e+01 3.60541153e+01 3.03940811e+01 2.63919334e+01 7.93116951e+00 -1.66729870e+01 -2.95471382e+01 -2.88691139e+01 -1.12160027e+00 1.11285973e+01 -1.78418481e+00 1.20646143e+01 3.48883743e+01 7.62673340e+01 6.55694351e+01 3.53075562e+01 2.45643272e+01 2.24357281e+01 1.90417824e+01 1.42853298e+01 2.68314610e+01 4.72933578e+01 4.27290955e+01 3.09852123e+01 2.85225983e+01 2.39616146e+01 1.44921341e+01 -3.80803227e+00 6.97242737e+00 2.39298668e+01 4.30793762e+00 -2.91247904e-01 4.77295446e+00 3.58981552e+01 4.64947739e+01 5.97193432e+00 3.22276211e+00 1.64096851e+01 6.33102379e+01 7.23304214e+01 4.23438988e+01 2.60664234e+01 1.00814896e+01 6.55327511e+00 -4.31748581e+00 -9.88277340e+00 9.12330627e+00 7.67311144e+00 4.84164047e+00 -3.10611439e+00 5.03406143e+00 2.45002537e+01 1.86266251e+01 2.19607086e+01 2.81655636e+01 1.02507534e+01 7.82246733e+00 1.58767653e+01 5.52011681e+01 6.19025688e+01 9.56762886e+00 -3.45049453e+00 1.42099104e+01 5.95926437e+01 6.10739670e+01 2.64643402e+01 1.76404152e+01 1.23856382e+01 9.27750587e+00 1.46102896e+01 2.44595890e+01 4.92541962e+01 3.22498894e+01 1.31099615e+01 8.95490646e+00 2.21027775e+01 4.59320984e+01 3.36212006e+01 2.45213776e+01 1.47086916e+01 -3.50418735e+00 -1.02627935e+01 -1.73935661e+01 -1.05220366e+01 -6.21792221e+00 -2.22090931e+01 -1.44264822e+01 -1.14717014e-01 3.58985939e+01 6.05135880e+01 4.86254768e+01 3.81860504e+01 9.89104939e+00 2.57599115e+00 -9.25600147e+00 -2.29962063e+01 -2.29651337e+01 -1.53042059e+01 -1.14719095e+01 -2.05660114e+01 -3.26733475e+01 -1.32396336e+01 2.28781948e+01 5.04180450e+01 5.73809242e+01 9.84493542e+00 -5.51308775e+00 5.75455284e+00 3.19011993e+01 2.54201851e+01 -8.30974817e-01 1.41537571e+00 -4.23704720e+00 -8.46253014e+00 -8.34984112e+00 7.76747847e+00 2.19191036e+01 6.43035698e+00 -1.28179369e+01 -9.94157600e+00 -1.34293375e+01 -1.42353954e+01 -3.02666092e+01 -5.06074829e+01 -6.74116821e+01 -8.26587982e+01 -4.31442719e+01 -1.10119104e+01 1.30646544e+01 1.45015669e+01 -1.86464748e+01 -1.50236273e+01 1.26967406e+00 4.74645653e+01 4.38135376e+01 3.57767510e+00 -2.69176102e+01 -3.78976707e+01 -2.78560905e+01 -4.14729729e+01 -5.48527565e+01 -4.57280807e+01 -3.90058708e+01 -3.65390434e+01 -4.37468605e+01 -3.20503845e+01 -9.96608639e+00 -5.82909966e+00 1.52244129e+01 1.62116337e+01 -2.72700768e+01 -6.88785858e+01 -6.41655807e+01 -2.04258404e+01 -8.74249578e-01 -1.12542791e+01 4.00911236e+00 2.22583370e+01 4.19173775e+01 4.93544922e+01 2.92651234e+01 7.88205624e+00 -2.88114986e+01 -4.05070076e+01 -1.93789158e+01 8.12117195e+00 1.60822678e+01 -2.20428181e+00 -1.40958204e+01 -5.27569675e+00 -3.64828849e+00 -6.42064929e-01 -1.20317936e+00 2.87191540e-01 -5.50589800e+00 -5.93672609e+00 -1.01451559e+01 -1.07306919e+01 -6.25477219e+00 5.51447630e+00 7.36315060e+00 4.27355208e-02 -1.02345848e+01 -8.29508686e+00 1.56481981e-01 -1.76334321e+00 -3.48663592e+00 -2.23220577e+01 -3.50857544e+01 -3.58038406e+01 -2.33337231e+01 -3.90030479e+00 -8.44210052e+00 -9.95403957e+00 -1.43934689e+01 -1.36304150e+01 -1.99447327e+01 -1.92633858e+01 -1.84781399e+01 -1.37359009e+01 -1.90702362e+01 -1.25122757e+01 -7.61748314e+00 -8.42514992e+00 -1.00855560e+01 -5.68252182e+00 -1.02243018e+00 -5.81075668e+00 -9.05602646e+00 -8.49333382e+00 -8.84976578e+00 -1.43713512e+01 -8.43518257e+00 -7.23811436e+00 -8.18975067e+00 -1.68862762e+01 -1.50074730e+01 -7.23889732e+00 -6.23042107e+00 -1.24380636e+01 -8.80821514e+00 -1.19830537e+00 1.80943882e+00 -1.04287930e+01 -1.60986423e+01 -1.57591276e+01 -1.13997345e+01 -1.21779566e+01 -1.20929775e+01 -1.83378639e+01 -2.78616123e+01 -3.76684036e+01 -3.79532166e+01 -2.85452862e+01 -2.71830425e+01 -2.08427887e+01 -2.45886555e+01 -2.51385384e+01 -3.07103329e+01 -3.07040634e+01 -2.68445320e+01 -2.87949677e+01 -2.72891197e+01 -1.49892063e+01 -6.71120405e+00 -7.05331516e+00 -1.72843227e+01 -1.76867943e+01 -2.69530602e+01 -3.61243172e+01 -4.35102158e+01 -3.69741096e+01 -2.94902687e+01 -2.99611225e+01 -3.56426735e+01 -2.55788956e+01 -1.35373402e+01 -1.14872885e+01 -2.35834827e+01 -3.87499084e+01 -4.20030861e+01 -4.51482887e+01 -4.28960915e+01 -2.18088932e+01 -4.86960220e+00 -1.98552573e+00 -1.66427116e+01 -3.09376278e+01 -3.09745541e+01 -3.27583504e+01 -3.66835632e+01 -4.04500847e+01 -4.06658630e+01 -3.90492935e+01 -3.98380280e+01 -3.67466049e+01 -3.58907967e+01 -3.93031273e+01 -4.91757660e+01 -6.27039528e+01 -7.24348450e+01 -6.90727081e+01 -5.64187164e+01 -4.39103165e+01 -4.97580948e+01 -5.36698227e+01 -4.86643181e+01 -3.87102013e+01 -3.03069553e+01 -3.77231445e+01 -4.53087883e+01 -5.21452751e+01 -4.89747467e+01 -4.55233459e+01 -4.54642601e+01 -4.91180420e+01 -6.27873039e+01 -7.94942932e+01 -5.96842766e+01 -2.55584946e+01 -1.34045849e+01 -3.06748219e+01 -5.27124786e+01 -4.94521332e+01 -4.53447800e+01 -4.06177979e+01 -4.35223770e+01 -4.75653191e+01 -4.76146469e+01 -3.98594437e+01 -3.24371338e+01 -4.03091545e+01 -5.81309319e+01 -6.88881989e+01 -5.87786636e+01 -4.60392990e+01 -4.09215736e+01 -4.27013359e+01 -4.23957291e+01 -3.91368523e+01 -2.79840240e+01 -1.79181728e+01 -2.65398235e+01 -4.03216133e+01 -4.90210342e+01 -4.16339378e+01 -4.39197731e+01 -4.95147362e+01 -5.19585114e+01 -5.03443680e+01 -4.98015366e+01 -4.81823654e+01 -4.44455452e+01 -3.51954498e+01 -3.97129936e+01 -4.57183228e+01 -5.33208351e+01 -5.62415848e+01 -6.57926559e+01 -8.46047897e+01 -9.54292603e+01 -8.87367859e+01 -7.41799545e+01 -6.36687202e+01 -5.93572807e+01 -6.10182304e+01 -6.64345779e+01 -6.91739349e+01 -6.66406097e+01 -6.22337341e+01 -6.17742119e+01 -5.76887474e+01 -6.78530426e+01 -7.96763229e+01 -8.31409912e+01 -7.35624695e+01 -6.21716385e+01 -6.29266014e+01 -5.90576057e+01 -5.57953568e+01 -5.11216202e+01 -5.55310097e+01 -5.74462471e+01 -5.70648308e+01 -5.53229866e+01 -5.66655273e+01 -5.89633446e+01 -5.35928459e+01 -5.26501045e+01 -5.23676414e+01 -5.59455986e+01 -5.86186981e+01 -5.53569908e+01 -5.26352768e+01 -4.93544617e+01 -5.20842590e+01 -6.06304550e+01 -6.77604599e+01 -7.01915665e+01 -6.75005722e+01 -6.12249794e+01 -5.02835159e+01 -4.45455017e+01 -5.80338020e+01 -7.02968140e+01 -8.25431137e+01 -8.28193130e+01 -8.67845612e+01 -8.50620346e+01 -7.45430908e+01 -4.95228729e+01 -2.39851437e+01 6.14920759e+00 5.66165962e+01 8.44484558e+01 8.34894470e+02 8.08708069e+02 -2.74765156e+04 24924678. 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. 0. 0. 0. 0. 0. 0. 0. 531313536. 101834000. 25236908. 79759368. 5.72096729e+03 2.46978638e+03 1.22397461e+03 8.17712402e+02 1.53224655e+02 6.11054153e+01 2.17246571e+01 -2.29391632e+01 -3.82312393e+01 -4.14504242e+01 -3.15600910e+01 -3.72121429e+01 -7.98399658e+01 -1.22775284e+02 -1.18417305e+02 -7.63772812e+01 -1.73616982e+01 -1.78769627e+01 2.46478672e+01 4.98513107e+01 5.74214401e+01 1.70466537e+01 3.86943460e+00 3.15963936e+01 3.93133659e+01 3.77796860e+01 3.07731934e+01 9.31594467e+00 -4.22559090e+01 -6.32018166e+01 -7.44851151e+01 -7.37928085e+01 -7.73440857e+01 -8.13201981e+01 -8.58367081e+01 -8.39891434e+01 -8.08807602e+01 -8.12095795e+01 -8.45746994e+01 -8.83018112e+01 -9.11994934e+01 -9.41682510e+01 -9.27932358e+01 -9.43019028e+01 -9.52422028e+01 -9.52070312e+01 -9.27169952e+01 -8.86551819e+01 -8.99352570e+01 -9.09581680e+01 -9.03402328e+01 -8.93799133e+01 -8.82063828e+01 -8.92854614e+01 -8.99930954e+01 -8.72580566e+01 -8.57977295e+01 -7.88300552e+01 -7.43890610e+01 -7.38502350e+01 -7.57593002e+01 -7.79911804e+01 -7.31198196e+01 -7.05295639e+01 -7.48779297e+01 -8.13431320e+01 -8.81317520e+01 -8.98389130e+01 -9.10174026e+01 -9.50799332e+01 -1.00404640e+02 -1.03910011e+02 -1.02973312e+02 -9.74758148e+01 -9.32821426e+01 -9.02356873e+01 -8.96746445e+01 -9.06151276e+01 -8.60380020e+01 -8.16634979e+01 -7.53434753e+01 -7.35766830e+01 -7.66068192e+01 -8.11113586e+01 -8.57895813e+01 -8.72119751e+01 -8.63218231e+01 -8.09599838e+01 -7.61907806e+01 -7.77450104e+01 -8.36886139e+01 -8.78583603e+01 -8.72566147e+01 -8.56337128e+01 -8.45466995e+01 -8.29331436e+01 -8.84949112e+01 -9.39880753e+01 -9.65165329e+01 -9.40404358e+01 -8.94175949e+01 -8.96065063e+01 -8.83113480e+01 -8.66527634e+01 -8.51170731e+01 -8.30611649e+01 -8.36200790e+01 -8.70315781e+01 -9.14803543e+01 -9.59736481e+01 -9.58577881e+01 -9.44331741e+01 -9.29676514e+01 -9.28391571e+01 -9.44656906e+01 -9.47023010e+01 -9.44530563e+01 -9.39025345e+01 -9.32395325e+01 -9.21760864e+01 -9.14795761e+01 -9.17896652e+01 -9.13224640e+01 -8.81090851e+01 -8.43312836e+01 -8.44288635e+01 -8.70834427e+01 -8.97730637e+01 -8.87080917e+01 -8.73860016e+01 -8.56608200e+01 -8.51160049e+01 -8.68029556e+01 -8.95085220e+01 -9.19093781e+01 -9.27113876e+01 -9.29849091e+01 -9.28945694e+01 -9.27338943e+01 -9.29558945e+01 -9.34556427e+01 -9.35137329e+01 -9.27979965e+01 -9.25321045e+01 -9.26060715e+01 -9.26539383e+01 -9.23840027e+01 -9.17484131e+01 -9.03188019e+01 -8.92157440e+01 -8.97014542e+01 -9.13220749e+01 -9.26043091e+01 -9.16251526e+01 -9.06326294e+01 -9.00633316e+01 -9.02544556e+01 -9.01947098e+01 -9.02182159e+01 -9.10265427e+01 -9.16973877e+01 -9.24557343e+01 -9.25604630e+01 -9.27421646e+01 -9.28380737e+01 -9.27142410e+01 -9.27486267e+01 -9.27874069e+01 -9.28464890e+01 -9.28449936e+01 -9.28649445e+01 -9.28839340e+01 -9.27449646e+01 -9.25969086e+01 -9.26800537e+01 -9.29034653e+01 -9.29987564e+01 -9.30254822e+01 -9.29031372e+01 -9.26991196e+01 -9.30314484e+01 -9.38116455e+01 -9.38991776e+01 -9.33991852e+01 -9.25358429e+01 -9.27111206e+01 -9.29010315e+01 -9.30800323e+01 -9.27500916e+01 -9.28201141e+01 -9.27905045e+01 -9.32794952e+01 -9.34311905e+01 -9.35405350e+01 -9.33265381e+01 -9.31350708e+01 -9.17104645e+01 -9.01548004e+01 -9.00654449e+01 -9.11541290e+01 -9.26902313e+01 -9.17382965e+01 -9.17300110e+01 -9.23701706e+01 -9.32197342e+01 -9.33874054e+01 -9.27483368e+01 -9.22983322e+01 -9.21189423e+01 -9.23227844e+01 -9.30024185e+01 -9.27950668e+01 -9.23641434e+01 -9.20405426e+01 -9.16182175e+01 -9.17837601e+01 -9.10499191e+01 -9.15381241e+01 -9.14182968e+01 -9.16483536e+01 -9.10597763e+01 -8.89674606e+01 -8.73160324e+01 -8.70694275e+01 -8.82132339e+01 -9.00531311e+01 -8.94963837e+01 -8.99696808e+01 -8.87938309e+01 -8.81297531e+01 -8.83775787e+01 -8.85485611e+01 -8.93356018e+01 -8.76811142e+01 -8.73834534e+01 -8.75549011e+01 -8.92463379e+01 -9.08464127e+01 -9.09540558e+01 -8.69889679e+01 -8.26582870e+01 -8.15250778e+01 -8.48564911e+01 -9.45881805e+01 -1.00282921e+02 -1.00175804e+02 -9.37918320e+01 -8.90986252e+01 -9.44795609e+01 -9.89741592e+01 -9.87210159e+01 -9.28712082e+01 -8.79795151e+01 -8.72714691e+01 -8.67708511e+01 -8.73811417e+01 -8.81515884e+01 -8.73313217e+01 -8.59326172e+01 -8.64871445e+01 -8.84990768e+01 -9.13221283e+01 -8.69697418e+01 -8.33271561e+01 -8.14647980e+01 -8.71012497e+01 -9.25614243e+01 -9.38341370e+01 -9.27858200e+01 -9.24428253e+01 -9.15845718e+01 -9.19316483e+01 -9.07077866e+01 -9.46845474e+01 -9.77397690e+01 -9.59063110e+01 -8.85712128e+01 -8.29522858e+01 -8.33621140e+01 -8.62629318e+01 -8.87353592e+01 -8.90815353e+01 -8.32982559e+01 -7.55953369e+01 -7.59991531e+01 -8.10414047e+01 -8.73212433e+01 -8.47575150e+01 -8.43361893e+01 -8.34300232e+01 -8.56493378e+01 -9.17635422e+01 -9.91235046e+01 -9.78339386e+01 -9.17391663e+01 -8.30513000e+01 -8.38970795e+01 -8.52737808e+01 -8.60806732e+01 -8.51650162e+01 -8.96727676e+01 -9.75848923e+01 -9.97742081e+01 -9.69996490e+01 -8.85938110e+01 -8.93925476e+01 -8.70563736e+01 -8.59308929e+01 -8.38814926e+01 -8.45448837e+01 -8.74281082e+01 -8.97417374e+01 -8.90303802e+01 -8.63556366e+01 -8.43282623e+01 -8.20874252e+01 -7.93373032e+01 -7.64765549e+01 -7.60579987e+01 -7.57980499e+01 -7.74462280e+01 -8.53149796e+01 -9.54665833e+01 -1.01724854e+02 -1.03671280e+02 -1.03893822e+02 -1.04036613e+02 -9.07871323e+01 -8.28763428e+01 -7.47197495e+01 -7.83943176e+01 -7.87909088e+01 -8.60551071e+01 -9.43073883e+01 -9.14015198e+01 -8.71397858e+01 -7.28882675e+01 -6.47964096e+01 -6.23170853e+01 -6.71321716e+01 -7.50519028e+01 -7.49438858e+01 -8.06792679e+01 -9.11497040e+01 -9.83400650e+01 -9.07014389e+01 -7.93323746e+01 -6.61023178e+01 -7.39684143e+01 -8.28115158e+01 -8.91303024e+01 -8.77073593e+01 -7.96120758e+01 -7.29481888e+01 -6.36986847e+01 -6.43106308e+01 -6.56645126e+01 -6.47467346e+01 -6.53427734e+01 -6.67140656e+01 -6.70775452e+01 -6.71150208e+01 -6.62191849e+01 -6.71904144e+01 -6.83973923e+01 -7.25803070e+01 -8.36163483e+01 -9.62139664e+01 -8.55851440e+01 -6.61752472e+01 -6.44755783e+01 -8.22659378e+01 -9.52810440e+01 -8.46842270e+01 -7.26767120e+01 -8.03771057e+01 -8.77421951e+01 -8.98502197e+01 -8.18785477e+01 -7.25167999e+01 -7.45871048e+01 -7.67898178e+01 -8.09157333e+01 -7.66375427e+01 -7.28781967e+01 -6.86204147e+01 -6.79012070e+01 -6.77559128e+01 -7.11200790e+01 -7.09533157e+01 -7.49117661e+01 -8.05902328e+01 -9.13230286e+01 -7.95599289e+01 -5.66142082e+01 -5.86828270e+01 -8.10306396e+01 -9.47376556e+01 -7.65287628e+01 -6.16287231e+01 -6.76640549e+01 -7.66768188e+01 -6.73330765e+01 -4.84704704e+01 -3.73333206e+01 -4.23229599e+01 -4.89834251e+01 -6.08365135e+01 -7.37593307e+01 -7.27824783e+01 -5.55205612e+01 -5.43999214e+01 -7.29410248e+01 -7.72406235e+01 -6.26088943e+01 -4.64266930e+01 -4.68658752e+01 -5.03423615e+01 -4.19207268e+01 -3.10347214e+01 -3.81625824e+01 -5.61718483e+01 -7.26941605e+01 -6.54124374e+01 -5.90055275e+01 -5.69321594e+01 -5.76828423e+01 -5.92885666e+01 -5.75757065e+01 -5.39178352e+01 -4.43258018e+01 -4.54858627e+01 -6.09329681e+01 -7.88563004e+01 -8.29638290e+01 -7.37349396e+01 -7.86689377e+01 -9.53915253e+01 -8.94357529e+01 -6.27072525e+01 -3.60282059e+01 -3.30166702e+01 -4.43725357e+01 -4.04231415e+01 -3.62418785e+01 -3.87523308e+01 -4.88599243e+01 -5.92149429e+01 -5.87686920e+01 -5.20640144e+01 -4.86986504e+01 -3.84868202e+01 -3.70772591e+01 -3.87715874e+01 -4.02453079e+01 -3.98699188e+01 -3.94839745e+01 -5.17199364e+01 -6.54052048e+01 -6.39657707e+01 -5.30336723e+01 -4.76426201e+01 -5.45486641e+01 -4.48948708e+01 -2.70237579e+01 -2.80621243e+01 -5.92276649e+01 -9.45958633e+01 -1.01435959e+02 -8.78249817e+01 -8.19532700e+01 -8.86429825e+01 -8.24691849e+01 -7.25616150e+01 -6.09135475e+01 -6.46421280e+01 -6.20683517e+01 -6.54005890e+01 -7.12497025e+01 -6.98504486e+01 -5.54230804e+01 -3.62083092e+01 -4.32875290e+01 -6.02186852e+01 -6.42536087e+01 -4.78551559e+01 -4.96139679e+01 -6.62409363e+01 -5.50581818e+01 -1.78110828e+01 7.58223057e+00 -6.12218952e+00 -2.36192188e+01 -1.49458294e+01 4.98407459e+00 6.34365177e+00 -5.26886368e+00 -1.61111908e+01 -6.89709663e+00 -1.82118046e+00 -4.74985600e+00 -1.69149380e+01 -3.93623924e+01 -6.08787880e+01 -7.32184601e+01 -7.28818207e+01 -4.51841087e+01 -1.98840160e+01 -5.37253046e+00 -1.77812004e+01 -3.02018166e+01 -2.94135399e+01 -2.77907753e+01 -1.47903519e+01 5.21982813e+00 -4.25528646e-01 -1.68646049e+01 -3.39505043e+01 -3.44622726e+01 -3.54387398e+01 -5.37747421e+01 -6.91370621e+01 -6.58884659e+01 -4.94160500e+01 -3.49100876e+01 -3.37204590e+01 -3.11000214e+01 -3.13806896e+01 -3.73557968e+01 -4.39739418e+01 -4.29740181e+01 -3.50328674e+01 -2.99068108e+01 -2.47971172e+01 -2.39849014e+01 -2.31999531e+01 -3.87928810e+01 -6.16696739e+01 -6.53292313e+01 -5.32675018e+01 -5.05128250e+01 -6.71801910e+01 -6.31176682e+01 -5.04629402e+01 -3.58701210e+01 -5.34670868e+01 -6.69659195e+01 -5.93321533e+01 -4.09036140e+01 -1.55321636e+01 -1.35886230e+01 -1.40377302e+01 -3.08179989e+01 -4.82984161e+01 -4.89476776e+01 -3.31109238e+01 -3.46892395e+01 -5.24024544e+01 -5.34001579e+01 -3.96470222e+01 -1.45837164e+01 -2.88871288e+01 -4.35562630e+01 -4.09890976e+01 -1.25034637e+01 6.13700867e+00 -8.12154579e+00 -2.98279781e+01 -3.15270596e+01 -3.02994213e+01 -2.27677765e+01 -2.63329182e+01 -3.04741116e+01 -3.23472862e+01 -5.05739594e+01 -6.06101456e+01 -5.83140717e+01 -4.17101631e+01 -2.44617939e+01 -2.51256161e+01 -2.22721462e+01 -2.29750309e+01 -2.48186035e+01 -1.93501358e+01 -1.95415344e+01 -1.19976816e+01 -1.38928499e+01 -9.69482994e+00 6.68973732e+00 2.27952957e+01 2.49683952e+00 -3.02614899e+01 -4.22373505e+01 -1.75568771e+01 4.08157587e-01 3.68527246e+00 -3.89750576e+00 -3.06335402e+00 -5.71687508e+00 -7.77822828e+00 -2.89480629e+01 -1.12842087e+02 -2.34545746e+02 -3.92028923e+01 2.09651062e+02 4.61481720e+02 1.48868604e+03 -7.52770625e+04 0. 0. 0. 0. 0. -1.00518359e+10 6.88672050e+06 -1.24118050e+06 -4.76051914e+04 -5.55621211e+04 4.10306281e+05 2.57269953e+05 2.57294008e+10 1.98114714e+10 1.98114714e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -159208016. -6352621. -3.79659125e+06 5.54782520e+03 2.49753540e+03 1.15740681e+01 1.64225204e+02 2.21915955e+02 2.01277283e+02 8.84983063e+01 1.47258501e+01 -4.56982880e+01 -4.72347107e+01 -6.04728556e+00 1.17534027e+01 -8.70933086e-02 1.62280674e+01 5.08991585e+01 7.61177216e+01 4.10423470e+01 -2.76752510e+01 -6.43796768e+01 -4.10433922e+01 7.13413095e+00 3.78686295e+01 3.18102646e+01 1.89662800e+01 3.09136715e+01 4.96328278e+01 3.72538300e+01 1.36125052e+00 -1.75852222e+01 -3.54772425e+00 2.64361515e+01 3.82796707e+01 1.42434340e+01 -2.28628979e+01 -4.02481956e+01 -2.03057404e+01 -2.32925339e+01 -4.79416008e+01 -2.76727257e+01 2.25043621e+01 5.66036873e+01 1.71196690e+01 -6.04275322e+01 -8.35555344e+01 -4.60919075e+01 -5.86202431e+00 1.86609859e+01 2.33453751e+01 2.30485764e+01 2.31038799e+01 2.96528111e+01 2.03977776e+01 -3.49504890e+01 -7.90482712e+01 -5.70486450e+01 -4.66779041e+00 2.47712803e+01 5.32107592e-01 -3.25466385e+01 -4.36916237e+01 -8.86725807e+00 2.38804176e-01 -1.41291475e+01 -3.73210597e+00 3.22084770e+01 7.14358063e+01 6.23278770e+01 3.07027102e+00 -1.56072912e+01 6.66600561e+00 4.89254341e+01 4.06037369e+01 8.42810345e+00 1.88932896e+01 4.22333908e+01 5.62711868e+01 3.38572044e+01 -1.44516916e+01 -3.05238018e+01 -1.28799648e+01 3.92770386e+01 6.39274597e+01 5.45686951e+01 3.05158195e+01 4.00040283e+01 6.49035110e+01 6.41602249e+01 3.29200134e+01 1.64658604e+01 4.96481209e+01 8.74353104e+01 9.07307510e+01 4.36750298e+01 4.03541994e+00 1.39678240e+00 3.39086990e+01 4.37995186e+01 3.69188156e+01 5.86734314e+01 1.01430244e+02 1.23984520e+02 8.48794174e+01 2.24441719e+01 -9.16722107e+00 1.00028210e+01 4.59937325e+01 8.46349335e+01 1.08506477e+02 9.90566483e+01 8.58709946e+01 8.48114624e+01 8.36519547e+01 4.75705147e+01 1.27036819e+01 3.28929596e+01 9.12089081e+01 1.17069908e+02 9.40672073e+01 3.80277214e+01 1.53410559e+01 3.62342224e+01 6.12509727e+01 6.14546089e+01 5.92995682e+01 8.11251526e+01 1.31902908e+02 1.28873032e+02 8.75192032e+01 4.14518738e+01 4.32443810e+01 6.98422775e+01 9.18317108e+01 9.58886795e+01 8.94533691e+01 7.29461899e+01 6.29561958e+01 8.64267502e+01 9.54570541e+01 7.51664276e+01 5.19579163e+01 4.61225777e+01 6.00280685e+01 6.20758514e+01 4.87550354e+01 4.88269730e+01 6.29198685e+01 8.13256073e+01 9.02764664e+01 7.03245926e+01 6.00167694e+01 6.64733810e+01 8.33511658e+01 6.89793701e+01 1.41307812e+01 -1.13129511e+01 2.99278984e+01 7.60223312e+01 8.40928497e+01 5.43929787e+01 4.10724030e+01 4.24885063e+01 4.24278564e+01 2.48369579e+01 2.14277238e-01 -8.56293201e+00 9.07812214e+00 4.55206947e+01 7.35606384e+01 5.44551582e+01 3.89203873e+01 4.12849045e+01 6.51767273e+01 5.15612793e+01 9.87886238e+00 9.89289284e+00 3.13101768e+01 5.17233849e+01 2.89890575e+01 -2.13053379e+01 -4.09180870e+01 -1.04685984e+01 4.68413849e+01 7.08510437e+01 6.43738556e+01 6.59421844e+01 8.12117691e+01 7.18301086e+01 3.90991592e+01 2.91414595e+00 1.10573616e+01 4.30335083e+01 8.84178162e+01 1.08228813e+02 9.83183670e+01 6.64169159e+01 4.07761917e+01 3.87860336e+01 3.05402870e+01 1.47386761e+01 2.35900784e+01 5.74305534e+01 9.36325912e+01 7.56407089e+01 3.09160767e+01 3.87155581e+00 3.32897034e+01 8.37010269e+01 9.86192169e+01 7.77581711e+01 5.08490982e+01 6.41963654e+01 8.41058273e+01 7.83910446e+01 5.32454987e+01 4.70017090e+01 7.22304153e+01 1.07692802e+02 1.14868919e+02 9.81085281e+01 7.67857819e+01 7.76933594e+01 8.67950058e+01 8.42504044e+01 6.89453430e+01 8.23232880e+01 9.91589966e+01 1.04748840e+02 9.87959137e+01 8.18219757e+01 7.58064728e+01 7.92674255e+01 7.95183487e+01 8.03194809e+01 6.55908203e+01 7.91423492e+01 9.93724594e+01 1.09269485e+02 9.84613724e+01 5.52410431e+01 3.32400780e+01 3.97532425e+01 8.59449844e+01 1.12678078e+02 1.14969681e+02 9.58241196e+01 8.25242386e+01 9.42697754e+01 9.04632950e+01 7.83429565e+01 7.09020309e+01 8.60907822e+01 9.64297867e+01 7.35347824e+01 4.71915970e+01 5.28352509e+01 6.88475952e+01 7.69610443e+01 6.90796432e+01 5.31908188e+01 7.24632874e+01 8.63645630e+01 9.76991501e+01 8.64400406e+01 6.60879745e+01 5.84489746e+01 5.53939781e+01 7.60140457e+01 8.28704224e+01 8.63758621e+01 6.83234863e+01 6.94752350e+01 7.05685577e+01 6.76709595e+01 5.61086807e+01 5.07957954e+01 7.36202240e+01 8.62015839e+01 8.74772415e+01 6.97399750e+01 7.67351761e+01 8.34573135e+01 9.28011017e+01 9.50808487e+01 9.37359390e+01 9.30748138e+01 7.64965668e+01 6.77085571e+01 6.50256653e+01 6.87217865e+01 7.52857285e+01 8.25121460e+01 1.00028069e+02 1.08720589e+02 1.02317970e+02 7.54371796e+01 6.96656342e+01 7.47120285e+01 8.45959473e+01 8.45807037e+01 9.32189331e+01 1.13659973e+02 1.22851379e+02 1.11425987e+02 8.69205399e+01 7.88109970e+01 8.74600372e+01 9.93870621e+01 1.02370468e+02 9.28798294e+01 9.32897339e+01 9.09106293e+01 1.01945282e+02 1.08554306e+02 1.08611839e+02 9.80074387e+01 9.13403778e+01 1.02485466e+02 1.13997116e+02 1.07255669e+02 9.23236847e+01 9.53197250e+01 1.05778542e+02 1.06051392e+02 9.71100388e+01 9.64919510e+01 1.10009415e+02 1.15297462e+02 1.09984482e+02 9.47698364e+01 9.58610001e+01 1.00189507e+02 1.07156639e+02 1.02681091e+02 9.64678574e+01 9.91747742e+01 9.84306335e+01 1.07630836e+02 1.08908615e+02 1.09969330e+02 1.03636101e+02 1.00946732e+02 1.05334839e+02 1.10366158e+02 1.06651100e+02 9.68127060e+01 9.48380737e+01 9.55841370e+01 9.14339066e+01 8.05841751e+01 8.35064011e+01 9.26226807e+01 9.68971405e+01 9.09834747e+01 8.39845123e+01 9.28151321e+01 9.78320999e+01 1.03714012e+02 1.07758797e+02 1.08314285e+02 1.03230408e+02 9.02619781e+01 8.82591171e+01 9.68300781e+01 1.06129539e+02 1.00487823e+02 8.93004761e+01 8.25336380e+01 9.06267319e+01 9.74043655e+01 9.64610672e+01 9.29262238e+01 8.79674225e+01 8.26779480e+01 7.49164352e+01 7.76451874e+01 8.59463425e+01 8.90688400e+01 8.52137833e+01 8.15783539e+01 9.04352875e+01 9.54455872e+01 9.85277481e+01 9.73523941e+01 9.60252533e+01 9.20691071e+01 8.20126190e+01 8.03015823e+01 8.82185364e+01 1.02945526e+02 1.06068474e+02 9.54408188e+01 8.60976639e+01 8.57001114e+01 9.25569763e+01 9.60818710e+01 9.43016891e+01 8.98640671e+01 8.73961639e+01 9.11756363e+01 9.84141083e+01 1.00141815e+02 9.66313858e+01 9.21332626e+01 8.80836868e+01 8.86099701e+01 9.10852051e+01 9.70858917e+01 1.03009483e+02 1.04806717e+02 1.01069771e+02 9.43683090e+01 9.10454025e+01 9.45804596e+01 9.93063431e+01 9.92602692e+01 9.50363617e+01 9.14200134e+01 9.32666245e+01 9.74008026e+01 1.00655243e+02 1.00701126e+02 9.86428223e+01 9.72521820e+01 9.66741333e+01 9.83792114e+01 9.91471710e+01 9.96097412e+01 9.89633636e+01 9.87071533e+01 9.94643707e+01 1.00023674e+02 1.00477608e+02 1.00335686e+02 1.00071213e+02 9.98657150e+01 9.99092407e+01 1.00188103e+02 1.00156281e+02 9.94119034e+01 9.87369843e+01 9.89668884e+01 1.00371506e+02 1.01617523e+02 1.01429962e+02 1.00617195e+02 1.00601067e+02 1.01598175e+02 1.02321625e+02 1.02864319e+02 1.01197899e+02 9.99937286e+01 9.82883530e+01 9.79003296e+01 9.87615585e+01 1.00106255e+02 1.02563576e+02 1.02228676e+02 1.00396141e+02 9.77566605e+01 9.75930099e+01 1.00321022e+02 1.03990211e+02 1.02989517e+02 9.96927490e+01 9.73602371e+01 1.00400475e+02 1.05325096e+02 1.05228127e+02 1.01445908e+02 9.56198273e+01 9.57265167e+01 1.00639893e+02 1.04734062e+02 1.08173523e+02 1.02693512e+02 9.99907837e+01 9.68416290e+01 9.71454468e+01 9.66216660e+01 9.53322754e+01 9.83589706e+01 9.68466949e+01 9.36133194e+01 9.38318405e+01 9.91697235e+01 1.08894478e+02 1.11654320e+02 1.06414322e+02 9.33097916e+01 8.23211365e+01 8.34191742e+01 9.60402069e+01 1.09638359e+02 1.14363922e+02 1.05012985e+02 9.38564758e+01 9.10867538e+01 9.96511993e+01 1.09165634e+02 1.05792229e+02 9.72209473e+01 8.86508636e+01 8.70636673e+01 9.03720398e+01 9.79655457e+01 1.05891655e+02 1.04653580e+02 9.57229462e+01 8.36159286e+01 8.12639923e+01 9.06930389e+01 1.02298935e+02 1.03241547e+02 9.23486786e+01 8.46037216e+01 8.69226074e+01 9.40764465e+01 9.71428833e+01 9.96628647e+01 9.57589645e+01 9.27393875e+01 9.59362106e+01 9.78209991e+01 1.02703293e+02 9.53003693e+01 8.90071182e+01 8.01990280e+01 7.40834351e+01 8.15922546e+01 8.76015091e+01 1.00339813e+02 1.04839584e+02 9.90839081e+01 8.66459351e+01 8.28063736e+01 9.53051529e+01 1.09460892e+02 1.08414558e+02 1.00233688e+02 8.46248550e+01 8.04480057e+01 8.63967972e+01 9.57513351e+01 9.90868301e+01 8.60606308e+01 7.36036072e+01 6.14617157e+01 6.27753029e+01 7.88141708e+01 7.82795715e+01 7.19631042e+01 5.61903381e+01 5.42949829e+01 5.95702934e+01 7.07036209e+01 9.22669678e+01 1.01557343e+02 9.69027481e+01 7.74958649e+01 6.97831955e+01 8.32899704e+01 1.00163353e+02 9.92475510e+01 7.87957840e+01 6.34509506e+01 6.77980728e+01 8.84733200e+01 1.07707756e+02 1.09948250e+02 9.18810425e+01 7.14668503e+01 6.58091202e+01 6.53039780e+01 7.09681015e+01 7.78100357e+01 9.15419464e+01 9.25358047e+01 8.56368256e+01 8.09783936e+01 8.94993362e+01 1.09884026e+02 1.21261192e+02 1.04592857e+02 7.75426559e+01 6.46578293e+01 8.00528183e+01 1.06294670e+02 1.11807526e+02 9.55237885e+01 6.86586227e+01 6.31710358e+01 7.94017715e+01 8.87760849e+01 9.32195129e+01 7.77301559e+01 7.07925644e+01 7.19237823e+01 7.76345596e+01 9.38429489e+01 8.94498520e+01 8.59224243e+01 5.82325630e+01 3.35366173e+01 2.02694740e+01 2.77739620e+01 5.49553528e+01 8.05734177e+01 8.92285614e+01 5.57412910e+01 -1.56361618e+01 -4.63960457e+00 9.48287277e+01 -4.41220886e+02 -8.49604065e+02 3.03847504e+02 2.76829102e+02 1.84871933e+02 3.45699524e+02 -2.36623120e+03 -7.82761475e+03 60965684. 25801794. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -28653518. -6.23179834e+03 -1.97039307e+03 6.07653625e+02 -1.61621497e+03 -1.28731250e+03 -1.02078293e+02 8.66894150e+00 5.65631142e+01 4.63656769e+01 3.36214142e+01 3.68868904e+01 5.22012711e+01 9.46212387e+01 9.46963196e+01 7.39371109e+01 3.82085266e+01 4.15491638e+01 7.50634613e+01 1.05300385e+02 1.12096687e+02 8.57869492e+01 3.91588516e+01 2.97718563e+01 6.24387856e+01 1.02051277e+02 1.03748947e+02 7.18354950e+01 6.83580170e+01 8.78475876e+01 9.25608368e+01 7.21898041e+01 4.75347977e+01 4.91927299e+01 4.36551857e+01 3.32441254e+01 2.99806976e+01 5.71572456e+01 1.02022423e+02 1.09047852e+02 7.81919403e+01 4.62178230e+01 4.41037025e+01 7.54055634e+01 1.13442238e+02 1.10063370e+02 6.13383484e+01 6.19571090e-01 1.21019447e+00 5.73285561e+01 8.84832535e+01 9.37781601e+01 6.13515053e+01 4.72677917e+01 3.90911598e+01 3.66949577e+01 4.47175217e+01 6.47039795e+01 9.52419205e+01 8.41921768e+01 5.13071518e+01 4.39773331e+01 6.89893723e+01 1.09021866e+02 1.05908707e+02 8.45964279e+01 5.25585899e+01 3.70718880e+01 6.95355301e+01 1.10244720e+02 1.46691162e+02 1.26816345e+02 7.97637024e+01 6.20588226e+01 9.29534225e+01 1.16437584e+02 1.10534248e+02 6.25248032e+01 5.14967155e+01 6.31278267e+01 8.69085693e+01 8.17626648e+01 8.33796921e+01 9.66979065e+01 8.25190964e+01 4.63180161e+01 2.79869785e+01 6.09648323e+01 1.16214081e+02 1.28857346e+02 1.11907341e+02 7.32028275e+01 4.57664452e+01 4.16558723e+01 7.00083618e+01 9.37582397e+01 8.86235046e+01 4.02062492e+01 1.89094925e+01 5.44617195e+01 9.08341827e+01 8.97371674e+01 3.69626465e+01 7.63120604e+00 1.57018490e+01 2.37531433e+01 3.63102188e+01 5.05494652e+01 9.38175354e+01 9.07731018e+01 5.56202011e+01 2.36610756e+01 2.62534981e+01 5.93696556e+01 6.55651321e+01 4.41325836e+01 2.55172195e+01 6.67766380e+00 1.65067520e+01 4.85623207e+01 8.30836258e+01 8.78998184e+01 3.58049545e+01 8.71770859e+00 3.11662674e+01 5.15343285e+01 5.32829781e+01 2.42922802e+01 2.75320797e+01 3.09333115e+01 1.77537098e+01 1.10779152e+01 2.14935284e+01 6.96803207e+01 6.92088165e+01 3.24971275e+01 1.00326419e+00 5.66924191e+00 3.91477394e+01 3.78314056e+01 6.75950909e+00 -8.36018848e+00 -2.86329651e+01 -4.52944994e+00 2.78973866e+01 6.23430023e+01 5.71269836e+01 2.22899113e+01 1.44717894e+01 3.07138252e+01 3.20752907e+01 2.23048077e+01 -7.02475166e+00 -2.66385059e+01 -4.01375465e+01 -4.68482590e+01 -2.40434380e+01 2.62468219e+00 4.96952896e+01 6.80528488e+01 5.86986923e+01 3.30303307e+01 2.93866386e+01 6.50170746e+01 9.52155457e+01 7.66151810e+01 1.92366180e+01 -2.15104218e+01 -2.34670696e+01 2.83657188e+01 5.62100105e+01 5.50899582e+01 2.20002041e+01 1.48303385e+01 3.45678596e+01 2.92882290e+01 3.10889282e+01 3.49504852e+01 3.71300545e+01 8.10652828e+00 -3.24085846e+01 -3.89576111e+01 -2.42171516e+01 1.75901365e+00 2.80119057e+01 3.14169521e+01 2.11112480e+01 1.72511959e+01 4.86060867e+01 8.12326508e+01 6.71184921e+01 1.83630219e+01 -2.75208015e+01 -3.49157333e+01 3.94211197e+00 1.36499071e+01 1.74965744e+01 -2.19337387e+01 -1.76718826e+01 3.46772718e+00 4.07639656e+01 6.76017990e+01 7.36591034e+01 9.50211716e+01 7.49583206e+01 3.22778320e+01 -4.01610136e-01 1.56936204e+00 3.82549210e+01 4.10450096e+01 1.24724550e+01 -2.27659378e+01 -5.94746170e+01 -3.69214134e+01 2.11498032e+01 7.51405563e+01 5.50837555e+01 -3.33476925e+00 -1.55104752e+01 7.28380775e+00 2.15546207e+01 2.13338089e+01 2.06564927e+00 -1.49164667e+01 -3.01657867e+01 -2.95361004e+01 -1.62154083e+01 9.32956791e+00 4.53872528e+01 5.48878860e+01 4.04163513e+01 1.73308926e+01 1.04282265e+01 1.30554485e+01 -3.26219893e+00 -2.81251221e+01 -3.67888641e+01 -2.86805553e+01 -3.81309330e-01 8.35963631e+00 1.42965269e+01 4.31626177e+00 -1.37028627e+01 -2.24174614e+01 -1.73151722e+01 1.88834831e-01 9.23318863e+00 5.33511519e-01 -8.13412952e+00 -1.04647160e+01 -4.12700176e+00 1.95624912e+00 -4.00070047e+00 -9.02334499e+00 -1.56115885e+01 -1.76788368e+01 -1.71772308e+01 -2.34880371e+01 -2.07838783e+01 -2.00929012e+01 -1.15642948e+01 -1.65914497e+01 -2.30760632e+01 -2.46321945e+01 -1.95967579e+01 -1.63208160e+01 -2.11727448e+01 -2.38147411e+01 -2.78444576e+01 -4.05575485e+01 -3.75551910e+01 -3.01468468e+01 -1.94996395e+01 -3.15704613e+01 -3.32616997e+01 -3.18308067e+01 -3.06763859e+01 -3.29342842e+01 -3.63368530e+01 -3.55027809e+01 -3.65271339e+01 -3.25641708e+01 -2.82522144e+01 -2.58118000e+01 -3.23556328e+01 -3.32866478e+01 -4.11094475e+01 -3.68986969e+01 -3.56981354e+01 -3.09668541e+01 -3.79587784e+01 -3.77304230e+01 -3.95341034e+01 -2.52750244e+01 -1.36899462e+01 -5.71168756e+00 -1.57894945e+01 -2.17025013e+01 -3.01003361e+01 -3.13101978e+01 -3.44554710e+01 -2.98980122e+01 -2.54279022e+01 -3.05142040e+01 -3.01756153e+01 -2.92583332e+01 -3.10017262e+01 -4.00635490e+01 -4.42442856e+01 -3.94005318e+01 -3.49932861e+01 -3.70754585e+01 -3.55328636e+01 -3.16639900e+01 -2.46953754e+01 -2.42132149e+01 -2.49983978e+01 -3.22206879e+01 -3.73794289e+01 -5.43359108e+01 -6.26310806e+01 -6.50613861e+01 -5.35146523e+01 -4.25997963e+01 -3.73673782e+01 -3.14528770e+01 -3.41704330e+01 -4.91805992e+01 -6.48054352e+01 -6.20601654e+01 -4.71523170e+01 -3.48456001e+01 -3.38086395e+01 -3.58248520e+01 -3.09934425e+01 -3.12391624e+01 -3.27221222e+01 -3.73792915e+01 -3.36681747e+01 -3.19318466e+01 -3.50605850e+01 -3.98618813e+01 -3.56748085e+01 -2.32856140e+01 -7.65178204e+00 -7.54891777e+00 -1.86510563e+01 -3.63372116e+01 -3.54008293e+01 -3.09997578e+01 -3.54314880e+01 -3.84794540e+01 -4.18318405e+01 -2.49300671e+01 -1.61498756e+01 -1.25278406e+01 -2.90385170e+01 -4.30176315e+01 -5.33119164e+01 -4.33118706e+01 -2.02455978e+01 5.21051121e+00 -9.35652256e+00 -3.93912010e+01 -5.75417633e+01 -4.96311951e+01 -3.68250847e+01 -3.51886024e+01 -2.69509678e+01 -2.34591770e+01 -2.91981030e+01 -4.50392036e+01 -5.69450188e+01 -5.83404503e+01 -5.23746834e+01 -4.09763374e+01 -2.64292393e+01 -3.01198788e+01 -3.97978630e+01 -5.27199974e+01 -5.62405891e+01 -5.68955917e+01 -5.82531242e+01 -6.55584106e+01 -6.96015930e+01 -6.95557175e+01 -5.99804993e+01 -5.53481903e+01 -5.82882729e+01 -6.58755646e+01 -6.50794449e+01 -5.93753967e+01 -5.95854912e+01 -6.54061890e+01 -5.54652977e+01 -4.73440666e+01 -5.05806274e+01 -6.81770401e+01 -7.43500366e+01 -6.54341888e+01 -5.90368919e+01 -5.62894173e+01 -5.01682358e+01 -4.37964630e+01 -4.34052467e+01 -4.30192680e+01 -4.69112854e+01 -5.10324745e+01 -6.00589752e+01 -6.12695885e+01 -5.51761894e+01 -5.77939568e+01 -6.30758133e+01 -6.66727295e+01 -6.52350540e+01 -6.39513855e+01 -5.35151100e+01 -4.25926628e+01 -4.19361000e+01 -5.62134171e+01 -6.90942001e+01 -7.04174576e+01 -7.02140884e+01 -7.06169052e+01 -6.83254929e+01 -6.50438385e+01 -6.78771515e+01 -7.95769348e+01 -8.98884430e+01 -9.02476654e+01 -8.31402130e+01 -7.54766617e+01 -7.39849472e+01 -7.77313690e+01 -7.79908447e+01 -7.50222473e+01 -7.39164658e+01 -8.99728851e+01 -1.06884911e+02 -1.06170914e+02 -8.49564819e+01 -6.70230331e+01 -6.67422562e+01 -8.50560532e+01 -1.29522797e+02 -1.93775101e+02 -2.72067566e+02 -2.88310883e+02 -2.08542038e+02 -1.02073541e+03 -1.65731738e+03 -3.23661652e+02 -3.34371094e+02 -3.46787170e+02 -3.33597443e+02 -2.94690704e+02 -3.04400513e+02 -3.56958344e+02 -5.08916260e+02 -6.58673157e+02 -4.83707666e+03 -2.74765156e+04 24924678. 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. 0. 0. 0. 0. 0. 0. 0. 0. 632492160. -82336936. -50741084. -4.49175049e+03 -1.91035181e+03 -2.03214905e+02 -1.57984009e+02 -9.92762146e+01 -1.11097542e+02 -1.12939774e+02 -1.12735535e+02 -1.03454933e+02 -8.85846939e+01 -9.10716553e+01 -9.30171509e+01 -9.48890991e+01 -9.40762939e+01 -9.95877762e+01 -1.07907059e+02 -1.01284676e+02 -8.69481812e+01 -8.34379349e+01 -9.22608261e+01 -1.01796394e+02 -9.58709259e+01 -9.59007034e+01 -9.84841385e+01 -1.04346085e+02 -1.06506783e+02 -1.06563400e+02 -1.03628410e+02 -9.66490555e+01 -9.45882721e+01 -9.42294006e+01 -9.65396500e+01 -8.84722519e+01 -7.68924942e+01 -7.41851959e+01 -8.04577942e+01 -8.79481888e+01 -8.58052292e+01 -8.30417557e+01 -8.29483643e+01 -8.08542557e+01 -7.89285812e+01 -7.74291382e+01 -7.67530975e+01 -7.66749344e+01 -8.00012436e+01 -8.15579071e+01 -8.40881348e+01 -8.09239655e+01 -8.27717285e+01 -8.42875900e+01 -8.37118607e+01 -8.20781403e+01 -7.98627930e+01 -7.99080734e+01 -8.34846725e+01 -8.99496307e+01 -9.83305054e+01 -1.02800507e+02 -1.00762970e+02 -9.57373123e+01 -9.19855423e+01 -9.66385651e+01 -1.01731102e+02 -9.95113754e+01 -9.24826355e+01 -8.58174896e+01 -8.57215195e+01 -8.54960556e+01 -8.19920959e+01 -7.61223526e+01 -8.15897827e+01 -9.06823196e+01 -9.83088913e+01 -9.57889252e+01 -9.18250198e+01 -9.33685684e+01 -9.32933960e+01 -9.37066650e+01 -9.26334152e+01 -9.27046890e+01 -9.24595184e+01 -9.57428360e+01 -9.66913376e+01 -9.78470688e+01 -9.56856537e+01 -9.61527863e+01 -1.01714622e+02 -1.07562248e+02 -1.06193939e+02 -1.01369240e+02 -9.60293427e+01 -9.80028687e+01 -1.00359344e+02 -1.04041817e+02 -1.04975586e+02 -1.01351440e+02 -9.56267319e+01 -9.44206161e+01 -9.67701416e+01 -1.02587372e+02 -1.03163887e+02 -1.02416473e+02 -9.96137848e+01 -9.71123810e+01 -9.82783585e+01 -9.67920685e+01 -9.75874863e+01 -9.62508545e+01 -9.79101791e+01 -9.79701233e+01 -9.75309601e+01 -9.95913773e+01 -1.01901100e+02 -1.01654640e+02 -9.95471497e+01 -9.67643127e+01 -9.67367783e+01 -9.60511017e+01 -9.58596268e+01 -9.51400833e+01 -9.47758942e+01 -9.55420685e+01 -9.96621399e+01 -1.04055779e+02 -1.04506790e+02 -1.01853004e+02 -9.85229568e+01 -9.70552902e+01 -9.57558975e+01 -9.60124588e+01 -9.75671768e+01 -9.84264603e+01 -9.73804169e+01 -9.75476761e+01 -9.77943420e+01 -9.82280655e+01 -9.83579559e+01 -9.86762009e+01 -9.89976349e+01 -9.92681503e+01 -9.89603500e+01 -9.92808075e+01 -9.96775894e+01 -1.00038902e+02 -1.00048431e+02 -1.00272263e+02 -1.00451607e+02 -1.00497375e+02 -9.99916000e+01 -9.96324844e+01 -9.92659454e+01 -9.93162994e+01 -9.93068771e+01 -9.91045990e+01 -9.89937515e+01 -9.94478607e+01 -1.01067581e+02 -1.01796486e+02 -1.01700455e+02 -1.01090981e+02 -1.00539886e+02 -1.00460258e+02 -1.00192154e+02 -1.00079506e+02 -1.00090599e+02 -1.00097092e+02 -1.00052361e+02 -9.99740143e+01 -9.99234390e+01 -9.98876266e+01 -9.98856735e+01 -1.00023056e+02 -1.00249474e+02 -1.00368912e+02 -1.00295959e+02 -1.00034668e+02 -9.96370316e+01 -9.96385574e+01 -9.96777496e+01 -9.98008194e+01 -9.97634201e+01 -9.98826141e+01 -9.97819214e+01 -9.97667084e+01 -9.99086914e+01 -9.97267456e+01 -9.95982895e+01 -9.95416107e+01 -9.97590790e+01 -9.98906479e+01 -9.91367188e+01 -9.87341461e+01 -9.83099976e+01 -9.84856339e+01 -9.91889496e+01 -1.01126862e+02 -1.03501076e+02 -1.04485008e+02 -1.04382889e+02 -1.03721298e+02 -1.04403603e+02 -1.02875320e+02 -1.00842834e+02 -9.81538544e+01 -9.76576233e+01 -9.76477966e+01 -9.81610718e+01 -9.83748322e+01 -9.81720352e+01 -9.70653229e+01 -9.69063110e+01 -9.70690155e+01 -9.80131302e+01 -9.81015854e+01 -9.81255264e+01 -9.51142197e+01 -9.17428436e+01 -9.24174576e+01 -9.52870026e+01 -9.87012634e+01 -1.00164948e+02 -1.01727509e+02 -1.04889816e+02 -1.07197166e+02 -1.05995911e+02 -1.03929581e+02 -9.91576691e+01 -1.00330673e+02 -1.01684258e+02 -1.03413948e+02 -1.03085236e+02 -1.01311768e+02 -1.01843185e+02 -1.01923737e+02 -1.01826370e+02 -9.96715851e+01 -9.79916306e+01 -9.86269836e+01 -1.02732368e+02 -1.07749382e+02 -1.11959991e+02 -1.14009331e+02 -1.04291283e+02 -9.44144821e+01 -8.88783188e+01 -9.32963257e+01 -9.88443985e+01 -9.81506271e+01 -9.90466690e+01 -9.79448547e+01 -9.86074600e+01 -9.73339157e+01 -9.61273270e+01 -9.47710648e+01 -9.58276978e+01 -9.60840149e+01 -9.20908966e+01 -8.45001907e+01 -8.26088257e+01 -8.58267517e+01 -9.10821915e+01 -9.48961182e+01 -9.85842438e+01 -9.87614746e+01 -9.48545227e+01 -9.33532181e+01 -9.70536804e+01 -9.72567596e+01 -9.43146439e+01 -9.00225449e+01 -8.97336578e+01 -8.99656601e+01 -9.01794586e+01 -9.15538483e+01 -9.09056625e+01 -9.30846024e+01 -9.23592300e+01 -9.18419952e+01 -8.76005173e+01 -8.62204514e+01 -8.67163849e+01 -9.41630554e+01 -1.03469078e+02 -1.02785782e+02 -9.60718307e+01 -8.66462631e+01 -8.94254684e+01 -9.19225693e+01 -9.49178391e+01 -9.56922531e+01 -9.67165527e+01 -9.62068787e+01 -1.00322189e+02 -1.02672607e+02 -1.00659500e+02 -9.23097610e+01 -8.49937439e+01 -8.48916855e+01 -8.63269958e+01 -8.16283875e+01 -7.44412155e+01 -7.16822891e+01 -7.36467743e+01 -8.04760513e+01 -8.00470352e+01 -8.09269562e+01 -8.19839706e+01 -8.48001404e+01 -8.59637299e+01 -8.35931244e+01 -7.80321350e+01 -7.91770859e+01 -8.10591736e+01 -8.34953918e+01 -8.17944565e+01 -8.24435043e+01 -8.41563492e+01 -9.12204285e+01 -9.84836884e+01 -9.75646820e+01 -9.23573456e+01 -8.66177902e+01 -8.71724701e+01 -8.34836044e+01 -7.88644943e+01 -8.07589951e+01 -9.51072693e+01 -1.06094666e+02 -1.06870880e+02 -9.48577271e+01 -8.62393417e+01 -8.62535934e+01 -8.74044113e+01 -8.69696732e+01 -8.53133850e+01 -9.40298157e+01 -1.05419960e+02 -1.07928833e+02 -9.85448456e+01 -8.49333649e+01 -8.61453323e+01 -8.61240387e+01 -8.59588623e+01 -8.39858856e+01 -8.49930801e+01 -9.06132660e+01 -9.50650406e+01 -9.52953568e+01 -8.99150467e+01 -8.48428421e+01 -8.76433945e+01 -1.01039589e+02 -1.17743248e+02 -1.18732025e+02 -1.05802811e+02 -9.15687256e+01 -8.63491669e+01 -8.07984848e+01 -8.01229858e+01 -8.54057312e+01 -1.00535530e+02 -1.11510834e+02 -1.23770493e+02 -1.26295616e+02 -1.12378433e+02 -9.87688675e+01 -8.22958145e+01 -9.35043564e+01 -1.03628189e+02 -9.14281082e+01 -6.59069595e+01 -5.21049309e+01 -6.55451202e+01 -7.83835220e+01 -7.64104385e+01 -7.35633087e+01 -7.31251526e+01 -7.06123657e+01 -6.83647079e+01 -6.54664307e+01 -6.45430450e+01 -6.27993584e+01 -6.21037788e+01 -6.35044327e+01 -6.05165215e+01 -6.16206055e+01 -6.05161705e+01 -7.06872787e+01 -8.26110916e+01 -8.28553009e+01 -7.14035873e+01 -5.33829994e+01 -6.57724991e+01 -8.52040939e+01 -7.37315979e+01 -4.50255699e+01 -4.48296509e+01 -8.03265533e+01 -1.01402359e+02 -8.75165024e+01 -6.80923767e+01 -7.69534454e+01 -9.35381699e+01 -9.86411209e+01 -8.84758835e+01 -7.28104782e+01 -7.21696472e+01 -7.49965744e+01 -7.46609650e+01 -7.47086563e+01 -6.13222160e+01 -4.93879890e+01 -6.35423393e+01 -9.17970581e+01 -1.04822342e+02 -9.26279449e+01 -8.01127319e+01 -9.43932724e+01 -1.05306183e+02 -1.08163979e+02 -9.50180359e+01 -7.97968063e+01 -8.11492462e+01 -8.21923523e+01 -8.45054474e+01 -7.86751328e+01 -8.50304718e+01 -9.83225555e+01 -1.02676666e+02 -9.96453705e+01 -8.12839661e+01 -7.08469620e+01 -6.21103973e+01 -5.99173737e+01 -6.28636208e+01 -4.17963181e+01 -1.57396841e+01 -2.04533310e+01 -5.31406364e+01 -8.23371658e+01 -7.27205353e+01 -5.86329117e+01 -6.84379501e+01 -8.94135818e+01 -9.00641327e+01 -7.70980911e+01 -6.05005951e+01 -5.61481171e+01 -5.41092262e+01 -5.15919991e+01 -5.51877556e+01 -5.76933022e+01 -6.13839035e+01 -6.90311279e+01 -7.20175018e+01 -6.71017838e+01 -5.59497871e+01 -4.99282990e+01 -4.63795395e+01 -4.72213402e+01 -3.22080231e+01 -1.79488029e+01 -3.30672798e+01 -6.86567535e+01 -8.71251602e+01 -6.72389755e+01 -4.69011574e+01 -3.53600121e+01 -3.01898232e+01 -2.71291142e+01 -3.09309368e+01 -3.51906776e+01 -3.02420979e+01 -3.30103455e+01 -3.05725784e+01 -3.55918579e+01 -3.13474770e+01 -2.79779015e+01 -2.39583073e+01 -2.99699059e+01 -3.68064079e+01 -3.41581917e+01 -2.47781734e+01 -2.06700153e+01 -3.10177193e+01 -4.08929520e+01 -4.52478981e+01 -5.45388222e+01 -7.10201340e+01 -7.38243484e+01 -6.38044052e+01 -6.21001205e+01 -9.57122421e+01 -1.16128983e+02 -1.02827263e+02 -7.91259918e+01 -8.45564270e+01 -1.04283890e+02 -1.06228004e+02 -8.33068924e+01 -6.79929428e+01 -6.24214439e+01 -6.37278633e+01 -6.49085083e+01 -6.73431091e+01 -6.55998077e+01 -5.65322037e+01 -6.72503128e+01 -8.57532120e+01 -9.67529297e+01 -7.97045822e+01 -5.86642532e+01 -5.79810486e+01 -7.30941696e+01 -5.57390709e+01 -2.74141102e+01 -1.14741802e+01 -2.47268143e+01 -4.12912292e+01 -3.23522873e+01 -3.14717388e+01 -3.24381638e+01 -3.22247581e+01 -2.97613335e+01 -3.17468491e+01 -3.92916603e+01 -3.49959145e+01 -2.76005440e+01 -2.00781879e+01 -2.23605156e+01 -2.90359402e+01 -3.04615211e+01 -4.67752991e+01 -6.12210121e+01 -5.91607246e+01 -3.82411003e+01 -1.22103348e+01 -8.52032089e+00 -8.27253056e+00 3.99898458e+00 2.38278599e+01 2.57785835e+01 1.12690697e+01 -1.21893721e+01 -1.62929668e+01 -1.72247791e+01 -3.91386414e+01 -6.48277817e+01 -7.16515503e+01 -4.89958267e+01 -3.06666298e+01 -2.88554802e+01 -2.40558929e+01 -1.47875471e+01 -1.76031246e+01 -8.28559208e+00 1.06916027e+01 3.99159145e+00 -2.39856377e+01 -4.66646233e+01 -3.93443947e+01 -4.33588448e+01 -7.68796997e+01 -9.77275391e+01 -8.31445694e+01 -4.56211433e+01 -3.70834656e+01 -5.04872932e+01 -5.24742699e+01 -3.44004135e+01 -9.68020725e+00 -1.42789278e+01 -2.80245056e+01 -3.08494968e+01 -2.13338375e+01 -3.12517834e+00 7.35938692e+00 1.37601738e+01 1.65560246e+01 8.27355576e+00 1.35407963e+01 1.14137497e+01 -2.16211677e+00 -2.23455639e+01 -2.65286560e+01 -1.25591288e+01 -7.08413541e-01 -7.85500813e+00 2.75522461e+01 1.71236450e+02 2.07371765e+02 3.13027863e+02 1.57762073e+03 2.43280029e+03 -5.83038807e+00 -3.10142612e+00 -2.27130688e+03 -1.64960571e+03 -4.01599701e+02 -4.40451599e+02 1.09485522e+03 1.93000952e+03 -1.47691376e+02 -6.72176895e+01 3.56904114e+02 3.04276733e+03 82858136. 0. 0. 0. 0. 0. 0. 0. 0. 4.70811402e+10 -7.49743688e+05 4.10306281e+05 2.57269953e+05 2.57294008e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.97151386e+10 2395078. 3.07521055e+04 1.12800479e+04 8.32711487e+02 1.36611731e+03 3.09711890e+03 1.75065393e+03 -2.97898960e+01 2.07326599e+02 2.67215118e+01 6.36181145e+01 7.26031799e+01 4.21551704e+01 2.47620010e+01 3.96463737e+01 5.84019928e+01 4.29921265e+01 6.22459555e+00 -7.65015936e+00 3.51525421e+01 9.47329559e+01 8.85649033e+01 2.43138142e+01 -5.01794205e+01 -8.08384399e+01 -4.72692032e+01 -4.47429543e+01 -5.64100647e+01 -4.32657700e+01 -1.24537344e+01 4.87944889e+00 -3.19257622e+01 -1.20701614e+02 -1.23724442e+02 -6.21881523e+01 3.02518253e+01 5.97254448e+01 5.13889771e+01 5.71636543e+01 7.87215347e+01 8.68541794e+01 4.67871323e+01 -4.51902275e+01 -9.24650497e+01 -6.01089554e+01 5.52554989e+00 4.02126808e+01 4.19714699e+01 2.49521694e+01 9.55410004e-01 9.24547672e+00 -4.28364038e+00 -1.54269533e+01 6.41191959e+00 7.15289688e+01 1.32386627e+02 1.04655167e+02 4.27915841e-01 -4.21028481e+01 -5.38474131e+00 6.83895187e+01 6.21967735e+01 9.76038361e+00 2.02415752e+00 4.86716652e+01 1.00064217e+02 8.43441544e+01 6.84304142e+00 -4.23499413e+01 -1.70127506e+01 3.92441902e+01 5.08419037e+01 4.42087784e+01 3.97251053e+01 6.15141678e+01 8.24969635e+01 6.36635361e+01 5.36334496e+01 6.87693863e+01 1.09022285e+02 1.13850288e+02 9.19115524e+01 5.26101227e+01 2.32240124e+01 1.33812037e+01 4.48172798e+01 6.11879539e+01 5.58709831e+01 9.19378433e+01 1.47552628e+02 1.69714172e+02 1.07256874e+02 1.86654530e+01 -2.02620049e+01 1.77768021e+01 9.39750366e+01 1.57924530e+02 1.77613434e+02 1.60415497e+02 1.43180527e+02 1.44248871e+02 1.21298012e+02 6.55901413e+01 2.86190052e+01 4.87428665e+01 9.58245544e+01 1.11036903e+02 9.11257324e+01 5.32841225e+01 3.84585381e+01 7.28472137e+01 9.77484360e+01 9.50680618e+01 8.67170868e+01 1.16120636e+02 1.62481445e+02 1.62169693e+02 1.13773865e+02 6.83928757e+01 7.92606201e+01 1.23070686e+02 1.54399765e+02 1.49602051e+02 1.14307739e+02 7.54399261e+01 5.69944496e+01 8.04760971e+01 8.07650833e+01 5.81607819e+01 5.79659042e+01 9.66338043e+01 1.31558578e+02 1.26755363e+02 8.56211624e+01 6.38846016e+01 8.53998413e+01 1.10612442e+02 1.24854591e+02 1.05345322e+02 1.12618324e+02 1.46954575e+02 1.59993805e+02 1.15040520e+02 3.30999336e+01 -6.35455132e+00 2.20239487e+01 6.92365265e+01 8.12632065e+01 7.65535965e+01 6.35359001e+01 6.77329941e+01 6.50623474e+01 4.23054314e+01 1.05270424e+01 3.55975008e+00 4.26519890e+01 1.13969467e+02 1.39175644e+02 1.01621445e+02 6.23907509e+01 6.94098129e+01 9.02047348e+01 6.85032959e+01 2.01056652e+01 2.87644463e+01 7.20379944e+01 1.11105637e+02 7.05821152e+01 -6.56717920e+00 -4.49170952e+01 -3.71308994e+00 6.48599167e+01 9.55528412e+01 9.10196075e+01 9.87042313e+01 1.11173546e+02 9.61181107e+01 5.11316605e+01 -2.52482086e-01 3.32324638e+01 8.42901154e+01 1.31252640e+02 1.12842110e+02 8.78280029e+01 6.80227127e+01 5.96774330e+01 6.20384369e+01 4.48285179e+01 2.62766800e+01 4.12882843e+01 8.80562744e+01 1.25118088e+02 1.01447807e+02 4.76128120e+01 1.29998035e+01 4.41717453e+01 9.69160995e+01 1.22265190e+02 1.15717857e+02 1.15877731e+02 1.49382416e+02 1.62558411e+02 1.28121765e+02 7.76728058e+01 7.58859406e+01 1.08834641e+02 1.46649323e+02 1.50788101e+02 1.43449188e+02 1.24852165e+02 1.08164055e+02 1.05205238e+02 9.25896454e+01 7.48972931e+01 9.18495483e+01 1.26287659e+02 1.41602707e+02 1.35347961e+02 1.05702461e+02 1.03100151e+02 1.15626060e+02 1.25205246e+02 1.22650322e+02 1.02091576e+02 1.18487770e+02 1.39831726e+02 1.53307068e+02 1.51123398e+02 1.20310844e+02 1.05725502e+02 1.23685677e+02 1.63516602e+02 1.66349915e+02 1.37793045e+02 1.05872345e+02 1.04483154e+02 1.20858063e+02 1.18470840e+02 1.05839859e+02 1.05692566e+02 1.34711044e+02 1.51932556e+02 1.29160019e+02 1.07124237e+02 1.23307419e+02 1.42856903e+02 1.38215408e+02 1.19407928e+02 1.02188553e+02 1.14537460e+02 1.07986816e+02 1.02820091e+02 9.64666901e+01 9.22027130e+01 8.48441849e+01 8.17014771e+01 1.11952156e+02 1.27389229e+02 1.36102325e+02 1.06743523e+02 1.11825165e+02 1.11492935e+02 1.01279861e+02 8.31254120e+01 7.69037399e+01 1.15138695e+02 1.40171249e+02 1.42860153e+02 1.08125977e+02 1.00008667e+02 1.06839447e+02 1.17514030e+02 1.17245293e+02 9.57734146e+01 1.10595932e+02 1.24358612e+02 1.53559647e+02 1.61210495e+02 1.57939896e+02 1.40166122e+02 1.21027710e+02 1.30412354e+02 1.48647583e+02 1.62250549e+02 1.53210968e+02 1.63369217e+02 1.66068726e+02 1.48627716e+02 1.20621040e+02 1.16690674e+02 1.47874985e+02 1.60438004e+02 1.44653030e+02 1.18083450e+02 1.26980598e+02 1.43618896e+02 1.49275208e+02 1.42704620e+02 1.30207275e+02 1.31839844e+02 1.26515900e+02 1.41017181e+02 1.48131958e+02 1.49596222e+02 1.41929688e+02 1.37034241e+02 1.46096436e+02 1.53353119e+02 1.56179993e+02 1.61932327e+02 1.82233841e+02 1.94252823e+02 1.90559921e+02 1.78531555e+02 1.78078995e+02 1.90774017e+02 1.96966187e+02 1.83237015e+02 1.58578369e+02 1.53672867e+02 1.58733414e+02 1.58583679e+02 1.48649857e+02 1.31800888e+02 1.29523041e+02 1.30128036e+02 1.43699493e+02 1.51710434e+02 1.54790283e+02 1.54805939e+02 1.56147888e+02 1.61077271e+02 1.66968872e+02 1.67070206e+02 1.64672470e+02 1.74205841e+02 1.85740723e+02 1.80713989e+02 1.63441925e+02 1.54777313e+02 1.54675278e+02 1.46389847e+02 1.38134521e+02 1.32624130e+02 1.47794678e+02 1.49001572e+02 1.51410477e+02 1.53392471e+02 1.53701706e+02 1.48450394e+02 1.32819168e+02 1.31562469e+02 1.45409470e+02 1.61609848e+02 1.61633423e+02 1.51184631e+02 1.40334473e+02 1.43188690e+02 1.50622772e+02 1.60715393e+02 1.62250473e+02 1.57118362e+02 1.49501572e+02 1.35714523e+02 1.31153854e+02 1.29460892e+02 1.30827530e+02 1.32166061e+02 1.32192093e+02 1.42943359e+02 1.42635696e+02 1.44404022e+02 1.44173172e+02 1.44061676e+02 1.38741730e+02 1.21451172e+02 1.17275162e+02 1.27676315e+02 1.51405365e+02 1.63924866e+02 1.51328873e+02 1.34379150e+02 1.33666245e+02 1.51705383e+02 1.70654205e+02 1.66218933e+02 1.52269058e+02 1.41505981e+02 1.41427567e+02 1.49768387e+02 1.48507416e+02 1.43728577e+02 1.39172134e+02 1.39578903e+02 1.47495605e+02 1.46383453e+02 1.41926544e+02 1.38087082e+02 1.39654861e+02 1.45971375e+02 1.44241531e+02 1.44058487e+02 1.50691956e+02 1.59251862e+02 1.58596756e+02 1.44189087e+02 1.35778595e+02 1.38618408e+02 1.48781296e+02 1.54098907e+02 1.52614044e+02 1.48390091e+02 1.46058945e+02 1.44883377e+02 1.48797119e+02 1.49047455e+02 1.48886902e+02 1.47453003e+02 1.46528442e+02 1.49590698e+02 1.51180328e+02 1.54591721e+02 1.53809967e+02 1.51998657e+02 1.49621490e+02 1.46571701e+02 1.46005692e+02 1.48159515e+02 1.52495529e+02 1.54597046e+02 1.52802155e+02 1.49758255e+02 1.48921875e+02 1.50865250e+02 1.52695114e+02 1.52363022e+02 1.51027878e+02 1.50658966e+02 1.50802094e+02 1.50899445e+02 1.50860107e+02 1.50955063e+02 1.51320663e+02 1.51786102e+02 1.51996155e+02 1.52865738e+02 1.53380768e+02 1.52540543e+02 1.50735474e+02 1.49459976e+02 1.51238632e+02 1.53333694e+02 1.53121048e+02 1.49952850e+02 1.46337997e+02 1.47446136e+02 1.51381790e+02 1.53004898e+02 1.51043594e+02 1.46965500e+02 1.47739594e+02 1.51200867e+02 1.54896255e+02 1.57615189e+02 1.55017975e+02 1.55513641e+02 1.52963394e+02 1.53002228e+02 1.53077179e+02 1.54448181e+02 1.58150238e+02 1.55023376e+02 1.50598022e+02 1.44806412e+02 1.46828659e+02 1.55347946e+02 1.62316360e+02 1.59508560e+02 1.49254318e+02 1.41176285e+02 1.40833008e+02 1.47684235e+02 1.51265060e+02 1.52175385e+02 1.47796463e+02 1.50052917e+02 1.53734238e+02 1.58404770e+02 1.65360321e+02 1.65600372e+02 1.58189835e+02 1.46500244e+02 1.43488800e+02 1.46604233e+02 1.52349564e+02 1.60748291e+02 1.65840012e+02 1.57307556e+02 1.39657455e+02 1.31478226e+02 1.41748215e+02 1.57212692e+02 1.58908249e+02 1.41596024e+02 1.22391907e+02 1.23829536e+02 1.44117783e+02 1.66920944e+02 1.75689774e+02 1.63638290e+02 1.51365707e+02 1.48812057e+02 1.53004837e+02 1.57511154e+02 1.50358337e+02 1.53593842e+02 1.50809174e+02 1.43535233e+02 1.39913712e+02 1.38825333e+02 1.52659988e+02 1.52166107e+02 1.38640457e+02 1.19421898e+02 1.20185875e+02 1.50239670e+02 1.71635010e+02 1.65348389e+02 1.38903595e+02 1.20838005e+02 1.19887207e+02 1.40382446e+02 1.62111786e+02 1.72548859e+02 1.55896301e+02 1.44475662e+02 1.32496140e+02 1.32795761e+02 1.37824875e+02 1.35505646e+02 1.35984116e+02 1.17590164e+02 1.10397629e+02 1.09965813e+02 1.20694443e+02 1.47139633e+02 1.54087601e+02 1.39865555e+02 1.12053703e+02 1.04661461e+02 1.19591850e+02 1.42264175e+02 1.44010696e+02 1.26022148e+02 1.01520882e+02 9.63505478e+01 1.20353973e+02 1.43697571e+02 1.51795929e+02 1.33439133e+02 1.16674759e+02 1.19544556e+02 1.33462097e+02 1.49846420e+02 1.53096527e+02 1.54670532e+02 1.42025681e+02 1.21438622e+02 1.13558983e+02 1.32918213e+02 1.67793030e+02 1.82446014e+02 1.59846268e+02 1.30037888e+02 1.11676743e+02 1.24737427e+02 1.48136642e+02 1.60273834e+02 1.53657791e+02 1.33654495e+02 1.33987320e+02 1.47060867e+02 1.64795853e+02 1.67970886e+02 1.45970459e+02 1.29819489e+02 1.30812424e+02 1.48117569e+02 1.70805923e+02 1.66683182e+02 1.67426849e+02 1.53845871e+02 1.39089035e+02 1.28271439e+02 1.25228256e+02 1.51358490e+02 1.65479401e+02 1.60023300e+02 1.38062714e+02 1.15358681e+02 1.29860947e+02 1.48969925e+02 1.67123138e+02 1.40333054e+02 9.34525223e+01 6.84584732e+01 8.57350388e+01 1.24187263e+02 1.37586334e+02 9.77319794e+01 4.46903725e+01 5.68048429e+00 -1.41662827e+02 -2.68966644e+02 -1.04057935e+03 -9.88183777e+02 -1.77957690e+03 -5.02545947e+03 -126094704. -52204196. -29627628. -33506270. -176723664. 260606832. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 615633472. 49117268. -1.01545195e+04 -3.44664917e+03 -9.98306702e+02 -4.19947853e+01 -1.58850723e+02 -2.07787109e+02 -7.68060608e+01 1.61939430e+01 2.88907051e+01 6.94761047e+01 1.13240829e+02 1.38063492e+02 1.33671341e+02 8.92290726e+01 5.51318016e+01 6.80658569e+01 1.24396294e+02 1.73057343e+02 1.63400711e+02 1.30416214e+02 1.05245575e+02 9.47729797e+01 8.60748215e+01 6.80225754e+01 9.84130707e+01 1.07585495e+02 7.88786774e+01 5.43570404e+01 9.00498505e+01 1.68991638e+02 1.97414154e+02 1.37764816e+02 6.41921997e+01 2.80731239e+01 5.16974945e+01 1.20371468e+02 1.72408463e+02 1.99033707e+02 1.53038467e+02 1.20340347e+02 1.12432732e+02 1.45459869e+02 1.69181824e+02 1.50603653e+02 1.53813751e+02 1.25652565e+02 9.58942490e+01 6.80502167e+01 9.16428375e+01 1.70314850e+02 1.79461899e+02 1.23350983e+02 4.23787231e+01 2.28590908e+01 8.32260818e+01 1.40674408e+02 1.47854004e+02 9.88255768e+01 7.37961044e+01 1.12450218e+02 1.82095428e+02 2.11178848e+02 1.86801178e+02 1.14044533e+02 5.66837692e+01 5.50325089e+01 1.06323753e+02 1.66543335e+02 2.09313095e+02 2.31481125e+02 2.16391144e+02 1.81112244e+02 1.33258743e+02 1.11304916e+02 1.28446457e+02 1.17384666e+02 6.66307449e+01 1.13614454e+01 1.43041677e+01 7.68489304e+01 1.18742599e+02 1.13713631e+02 8.87773132e+01 5.33625298e+01 2.43462372e+01 4.16537895e+01 1.01980423e+02 1.40142868e+02 1.05254356e+02 6.15144577e+01 7.33148499e+01 1.06323524e+02 1.11942764e+02 8.62712173e+01 1.00440353e+02 9.91622162e+01 7.75652847e+01 5.25548935e+01 6.25509453e+01 1.34084015e+02 1.42291962e+02 8.42917862e+01 -1.50721340e+01 -5.38169632e+01 2.87704825e+00 7.14402695e+01 1.05973373e+02 8.98323822e+01 7.02463150e+01 7.05775146e+01 8.36101761e+01 1.15537750e+02 1.31568863e+02 9.87018661e+01 3.33600807e+01 7.96655083e+00 2.87995300e+01 5.09946175e+01 5.13149223e+01 8.01529465e+01 8.00203552e+01 2.46032333e+01 -4.49906273e+01 -4.78726501e+01 5.26086998e+01 9.16555557e+01 4.44493523e+01 -3.73262291e+01 -4.88652344e+01 2.63070354e+01 8.80295792e+01 1.06190552e+02 8.63894348e+01 3.31086922e+01 -1.04233561e+01 -1.13831110e+01 4.87294655e+01 9.37526855e+01 6.00076180e+01 -2.95284247e+00 -3.25123062e+01 -8.04906940e+00 2.52621174e+01 4.92615471e+01 8.63961411e+01 1.02501907e+02 8.50293045e+01 5.58652916e+01 4.85679893e+01 9.37694397e+01 1.06152260e+02 6.23181839e+01 -2.65422726e+01 -8.57929916e+01 -5.77132568e+01 2.05052605e+01 8.72994461e+01 8.27460938e+01 4.75604553e+01 3.67181053e+01 4.65382156e+01 4.59712029e+01 6.83717270e+01 6.60343857e+01 6.26360359e+01 3.04151630e+01 -2.54704628e+01 -4.49784241e+01 -5.48814774e+01 1.46595573e+01 3.81059952e+01 7.22790480e-01 -3.83684082e+01 -2.05567398e+01 6.23690414e+01 9.30916290e+01 6.70131454e+01 2.76066971e+01 -1.43754172e+00 -6.49059153e+00 1.03983517e+01 2.57878056e+01 3.74919815e+01 -8.75852585e+00 5.85933256e+00 3.17942867e+01 8.16798248e+01 1.20259506e+02 1.51251068e+02 1.84135529e+02 1.36138031e+02 5.73226471e+01 3.41323280e+00 3.36104178e+00 5.14594345e+01 5.44928970e+01 -2.40316898e-01 -7.00831146e+01 -9.45739899e+01 -1.44837046e+01 7.96340485e+01 1.23193031e+02 1.00327507e+02 6.58721848e+01 5.75262833e+01 5.71695976e+01 6.79520264e+01 8.80879364e+01 7.13319855e+01 2.74762764e+01 -5.08748531e-01 2.49981747e+01 3.10011444e+01 3.65690384e+01 6.49796066e+01 9.07691269e+01 7.41803055e+01 3.68966599e+01 2.57483578e+01 2.79142227e+01 -1.42495155e+00 -3.88437996e+01 -7.06214066e+01 -8.00194016e+01 -3.98767548e+01 -7.76632833e+00 5.21940117e+01 6.75172272e+01 2.67223511e+01 -2.84267044e+01 -5.05907860e+01 -1.56638489e+01 7.54137516e+00 -1.10705256e+00 -2.88936782e+00 -1.91184938e+00 -5.73830366e+00 -5.74831200e+00 -4.00930738e+00 -2.99279547e+00 -4.42452478e+00 -1.51128969e+01 -2.24479446e+01 -4.06813507e+01 -4.31868629e+01 -4.00470886e+01 -2.43822613e+01 -2.17968349e+01 -3.07949619e+01 -3.05657635e+01 -2.87656422e+01 -4.05721235e+00 1.05661707e+01 1.20613575e+01 4.00648499e+00 -1.42365780e+01 -1.06981049e+01 -1.28812752e+01 -1.48801394e+01 -2.28054447e+01 -2.00592060e+01 -1.75930901e+01 -1.98262997e+01 -2.91868877e+01 -3.09917107e+01 -3.01320229e+01 -3.21296501e+01 -3.52816010e+01 -4.53759422e+01 -5.48534775e+01 -5.73123436e+01 -4.28301315e+01 -3.70987091e+01 -3.64404259e+01 -4.39991570e+01 -4.53171577e+01 -5.42997932e+01 -5.34481850e+01 -4.96026726e+01 -3.35802193e+01 -3.39444504e+01 -4.14198532e+01 -5.12124748e+01 -4.30051994e+01 -4.44259491e+01 -4.50085526e+01 -4.98120232e+01 -3.89802895e+01 -3.69901009e+01 -4.32607117e+01 -4.73427696e+01 -4.41535416e+01 -4.39167442e+01 -5.05531273e+01 -4.45173645e+01 -2.70475521e+01 -2.31306248e+01 -3.09897766e+01 -3.98995895e+01 -4.19710274e+01 -3.55438347e+01 -3.44959908e+01 -3.22266350e+01 -3.92176857e+01 -4.28294296e+01 -4.01206741e+01 -3.61300392e+01 -4.68896790e+01 -5.58874931e+01 -6.37984200e+01 -5.77314720e+01 -6.28337860e+01 -7.66741791e+01 -7.06646881e+01 -5.98368835e+01 -4.15269623e+01 -4.56456108e+01 -4.57978897e+01 -4.28206482e+01 -5.16826363e+01 -4.86212387e+01 -4.93820763e+01 -4.43380547e+01 -3.92884102e+01 -3.37370338e+01 -2.74978867e+01 -3.70380020e+01 -4.77491722e+01 -5.34012947e+01 -5.79540901e+01 -5.80887146e+01 -5.15126457e+01 -4.59893761e+01 -4.59335747e+01 -4.01094131e+01 -3.78925934e+01 -4.29360695e+01 -5.56259422e+01 -6.13635597e+01 -5.74959526e+01 -5.05426559e+01 -4.53121567e+01 -4.18477249e+01 -4.71808510e+01 -5.53502617e+01 -5.67385483e+01 -5.44188042e+01 -4.87571640e+01 -4.84163780e+01 -5.31096458e+01 -6.43474426e+01 -6.74870148e+01 -7.68171616e+01 -7.26313858e+01 -7.99199448e+01 -7.35801086e+01 -7.47773056e+01 -6.69786072e+01 -6.98378830e+01 -7.69063568e+01 -6.83882675e+01 -5.74971657e+01 -6.59055099e+01 -8.94079208e+01 -9.64458008e+01 -8.78405457e+01 -7.59282913e+01 -7.97470551e+01 -9.85984344e+01 -1.21191994e+02 -1.18686317e+02 -9.56536407e+01 -7.37506485e+01 -8.81128769e+01 -1.06832382e+02 -1.09716843e+02 -9.37772141e+01 -7.43679810e+01 -8.34010391e+01 -9.88728409e+01 -1.07872482e+02 -1.03869118e+02 -9.75652008e+01 -1.03744164e+02 -1.20076462e+02 -1.30674225e+02 -1.15969902e+02 -9.23516312e+01 -8.31048050e+01 -9.50187531e+01 -9.75963516e+01 -9.30808563e+01 -8.66870270e+01 -8.82927017e+01 -9.99236679e+01 -1.16166168e+02 -1.13733147e+02 -1.02979134e+02 -8.35497437e+01 -8.40260849e+01 -8.37168427e+01 -8.52550735e+01 -6.79796524e+01 -4.30417747e+01 -3.70381584e+01 -5.89093933e+01 -8.37153473e+01 -9.42463150e+01 -9.83237228e+01 -1.13222900e+02 -1.14138542e+02 -8.57966537e+01 -5.54822044e+01 -5.19268303e+01 -7.37468948e+01 -9.88178024e+01 -9.55139465e+01 -9.23005219e+01 -7.72551117e+01 -7.08367996e+01 -7.88823929e+01 -9.55398102e+01 -1.15803833e+02 -1.17267029e+02 -1.19743835e+02 -9.64890823e+01 -7.02589188e+01 -6.81919708e+01 -8.38731003e+01 -1.07189392e+02 -1.20268875e+02 -1.34384033e+02 -1.31723053e+02 -1.12185234e+02 -1.03793892e+02 -9.84670029e+01 -1.01334984e+02 -1.02815720e+02 -1.03361473e+02 -9.80426025e+01 -8.99856415e+01 -9.15522995e+01 -1.13019691e+02 -1.78081635e+02 -2.30189041e+02 -2.40276276e+02 -1.94740341e+02 -1.70720978e+02 -1.08857031e+03 -4.32718115e+03 -9.67403906e+03 -102494104. 27880224. -38967472. -164276416. -183627600. -520968256. -30965944. 48248820. -56369688. 52246980. -171502464. 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. 0. 0. 0. 0. 0. 0. 0. 155501632. -126679384. -2.57015742e+04 -1.09068018e+04 -2.50779785e+03 -1.55792078e+03 -1.31048193e+03 -2.97244116e+03 -1.74970117e+03 -5.11489990e+02 -3.38555908e+02 -2.71754761e+02 -1.95242920e+02 -1.82252502e+02 -1.84664719e+02 -2.01271591e+02 -1.95412277e+02 -1.24657692e+02 -5.64231987e+01 -5.92690277e+01 -1.28655426e+02 -2.33677811e+02 -2.47332855e+02 -3.19184357e+02 -3.51648590e+02 -3.50392212e+02 -2.89538910e+02 -2.70023773e+02 -3.19975616e+02 -3.29972076e+02 -3.22886658e+02 -3.06028076e+02 -2.64194061e+02 -1.84916931e+02 -1.51906906e+02 -1.40464127e+02 -1.38722366e+02 -1.34171265e+02 -1.26757637e+02 -1.20049377e+02 -1.21112656e+02 -1.26627975e+02 -1.23521454e+02 -1.20525345e+02 -1.17735008e+02 -1.16221329e+02 -1.15071304e+02 -1.18989998e+02 -1.32209305e+02 -1.42329742e+02 -1.44936218e+02 -1.38617126e+02 -1.32731583e+02 -1.28931259e+02 -1.27774666e+02 -1.31457748e+02 -1.36606949e+02 -1.36589859e+02 -1.32398346e+02 -1.28631882e+02 -1.27863022e+02 -1.24861084e+02 -1.30586395e+02 -1.39140732e+02 -1.45226440e+02 -1.48219040e+02 -1.49047043e+02 -1.51507889e+02 -1.48781631e+02 -1.44532410e+02 -1.42999649e+02 -1.41120544e+02 -1.33870621e+02 -1.30324875e+02 -1.29597794e+02 -1.33875809e+02 -1.35510117e+02 -1.34860031e+02 -1.42423782e+02 -1.51413925e+02 -1.52478348e+02 -1.48980789e+02 -1.42161209e+02 -1.54393829e+02 -1.65122665e+02 -1.68958405e+02 -1.62183258e+02 -1.56179230e+02 -1.56395645e+02 -1.55457367e+02 -1.52739090e+02 -1.53053741e+02 -1.60742004e+02 -1.67407120e+02 -1.64756256e+02 -1.53962250e+02 -1.46253799e+02 -1.43793549e+02 -1.46046539e+02 -1.47167450e+02 -1.50057343e+02 -1.44220764e+02 -1.39345535e+02 -1.41101135e+02 -1.48075287e+02 -1.50832260e+02 -1.46835312e+02 -1.43916550e+02 -1.50996918e+02 -1.56151627e+02 -1.56557877e+02 -1.50339340e+02 -1.44271225e+02 -1.41476715e+02 -1.40425430e+02 -1.41039322e+02 -1.43130905e+02 -1.44691864e+02 -1.45197556e+02 -1.43838333e+02 -1.44371811e+02 -1.46529587e+02 -1.47230362e+02 -1.47335220e+02 -1.46743134e+02 -1.48203506e+02 -1.48284714e+02 -1.49164001e+02 -1.53978027e+02 -1.59375656e+02 -1.58271851e+02 -1.53722763e+02 -1.49862076e+02 -1.53607391e+02 -1.57863480e+02 -1.58450089e+02 -1.56196793e+02 -1.53052338e+02 -1.51619675e+02 -1.50468933e+02 -1.49117935e+02 -1.49789688e+02 -1.50572861e+02 -1.51003311e+02 -1.49909576e+02 -1.48410507e+02 -1.48268311e+02 -1.49448624e+02 -1.50762421e+02 -1.50777878e+02 -1.50837204e+02 -1.50735611e+02 -1.52002029e+02 -1.54457443e+02 -1.56916901e+02 -1.56256836e+02 -1.54145554e+02 -1.52078384e+02 -1.53779800e+02 -1.55248108e+02 -1.54822189e+02 -1.53064102e+02 -1.51655502e+02 -1.51856888e+02 -1.51745255e+02 -1.51721375e+02 -1.51417160e+02 -1.51350189e+02 -1.51191254e+02 -1.51047623e+02 -1.51011017e+02 -1.51258438e+02 -1.51388290e+02 -1.51219177e+02 -1.51013214e+02 -1.50899185e+02 -1.50901443e+02 -1.50960449e+02 -1.50861969e+02 -1.50540085e+02 -1.50353775e+02 -1.50465683e+02 -1.50659668e+02 -1.50625565e+02 -1.50808685e+02 -1.50169846e+02 -1.48943451e+02 -1.48473785e+02 -1.49171997e+02 -1.50447525e+02 -1.50348770e+02 -1.50164856e+02 -1.50073700e+02 -1.50329178e+02 -1.49852570e+02 -1.49776794e+02 -1.47908203e+02 -1.46211578e+02 -1.45726578e+02 -1.47556747e+02 -1.49355072e+02 -1.49244034e+02 -1.49302872e+02 -1.47011459e+02 -1.44808762e+02 -1.44267059e+02 -1.47663162e+02 -1.50540436e+02 -1.49822784e+02 -1.48634384e+02 -1.48093292e+02 -1.48774261e+02 -1.49915146e+02 -1.50231155e+02 -1.50375229e+02 -1.49781265e+02 -1.49633011e+02 -1.50026825e+02 -1.49757278e+02 -1.51769608e+02 -1.52436737e+02 -1.53679169e+02 -1.53175613e+02 -1.52156265e+02 -1.52401230e+02 -1.52430176e+02 -1.53077057e+02 -1.52472061e+02 -1.51609528e+02 -1.51913239e+02 -1.50583389e+02 -1.50875610e+02 -1.51400162e+02 -1.53352585e+02 -1.53715317e+02 -1.51643906e+02 -1.50764587e+02 -1.49519394e+02 -1.51712936e+02 -1.50373367e+02 -1.51211288e+02 -1.48133026e+02 -1.46852493e+02 -1.45936340e+02 -1.50699814e+02 -1.56149948e+02 -1.52726776e+02 -1.43380844e+02 -1.34869003e+02 -1.35559204e+02 -1.39171783e+02 -1.41809494e+02 -1.42637115e+02 -1.40145035e+02 -1.37230118e+02 -1.36087189e+02 -1.38450592e+02 -1.42172577e+02 -1.45267715e+02 -1.47960114e+02 -1.48817337e+02 -1.47324936e+02 -1.43872742e+02 -1.41683807e+02 -1.39640701e+02 -1.39727020e+02 -1.38649017e+02 -1.43486969e+02 -1.44920776e+02 -1.46970108e+02 -1.42090622e+02 -1.34948135e+02 -1.28253555e+02 -1.30001083e+02 -1.34366287e+02 -1.39189651e+02 -1.39110229e+02 -1.39576614e+02 -1.33764267e+02 -1.26360153e+02 -1.23626846e+02 -1.25564682e+02 -1.33362930e+02 -1.37932816e+02 -1.43709671e+02 -1.39944077e+02 -1.35883453e+02 -1.34718613e+02 -1.39011047e+02 -1.40816498e+02 -1.41067947e+02 -1.36615570e+02 -1.34173080e+02 -1.34030853e+02 -1.32628006e+02 -1.32969864e+02 -1.20581322e+02 -1.11027954e+02 -1.12450684e+02 -1.25209991e+02 -1.36953690e+02 -1.32477768e+02 -1.28044647e+02 -1.28397873e+02 -1.29703461e+02 -1.21529991e+02 -1.10579361e+02 -1.10065140e+02 -1.20299110e+02 -1.31707687e+02 -1.27654053e+02 -1.27057823e+02 -1.29887558e+02 -1.36787796e+02 -1.36578842e+02 -1.32539658e+02 -1.25919952e+02 -1.27340958e+02 -1.34364868e+02 -1.36865005e+02 -1.35457245e+02 -1.33429825e+02 -1.37856003e+02 -1.30855942e+02 -1.21010399e+02 -1.17939217e+02 -1.11208961e+02 -9.97443695e+01 -8.71598892e+01 -8.40105438e+01 -8.87348938e+01 -8.65313187e+01 -1.00608025e+02 -1.06142616e+02 -1.20994911e+02 -1.29100250e+02 -1.43723541e+02 -1.42599884e+02 -1.36548981e+02 -1.32686676e+02 -1.33451462e+02 -1.34235291e+02 -1.33858047e+02 -1.35397812e+02 -1.39608612e+02 -1.27273384e+02 -1.09466385e+02 -9.70633240e+01 -9.66762772e+01 -1.08272934e+02 -1.12986839e+02 -1.17426086e+02 -1.26321053e+02 -1.14871811e+02 -1.10413399e+02 -1.02067825e+02 -1.01917709e+02 -9.89571457e+01 -9.06553421e+01 -1.03698715e+02 -1.14818642e+02 -1.19115570e+02 -1.05597168e+02 -9.92386017e+01 -1.06005875e+02 -1.19297577e+02 -1.08074326e+02 -9.67565918e+01 -9.11858215e+01 -9.98497467e+01 -1.06906883e+02 -8.95792160e+01 -7.40558319e+01 -7.98239059e+01 -1.05879700e+02 -1.17096420e+02 -1.00051804e+02 -8.57110062e+01 -1.05075508e+02 -1.29495361e+02 -1.14996315e+02 -8.81352768e+01 -7.50225372e+01 -8.30009079e+01 -9.11380615e+01 -8.67379456e+01 -7.56617050e+01 -6.38234138e+01 -7.17709198e+01 -9.45889587e+01 -1.14325096e+02 -1.12765007e+02 -1.07760963e+02 -1.01795975e+02 -1.04351707e+02 -1.03377968e+02 -9.69316177e+01 -8.17358704e+01 -8.41627197e+01 -1.01912743e+02 -1.05631683e+02 -9.83144989e+01 -7.82659607e+01 -7.69146347e+01 -8.49215546e+01 -8.88021851e+01 -9.67067642e+01 -9.72491150e+01 -1.06625427e+02 -1.17528458e+02 -1.21823318e+02 -1.17185066e+02 -8.27292023e+01 -5.92841911e+01 -7.79673386e+01 -1.20852692e+02 -1.23748383e+02 -8.49972076e+01 -7.02740631e+01 -9.21611938e+01 -1.05481186e+02 -9.13671875e+01 -8.16383362e+01 -8.82111893e+01 -1.06828094e+02 -9.58550720e+01 -8.16435013e+01 -7.13756790e+01 -8.27976990e+01 -9.83770752e+01 -9.87559814e+01 -9.66680450e+01 -7.87681351e+01 -6.72837143e+01 -6.65175781e+01 -8.46618347e+01 -8.37003021e+01 -4.36447220e+01 -1.63861637e+01 -2.39706402e+01 -5.96507111e+01 -6.07320557e+01 -4.47424202e+01 -6.25139236e+01 -1.02529984e+02 -1.20763008e+02 -9.69264374e+01 -7.51049271e+01 -7.57215881e+01 -8.30932617e+01 -7.67941895e+01 -7.91222382e+01 -7.54005508e+01 -7.63171844e+01 -8.10116348e+01 -8.97423630e+01 -9.76647644e+01 -8.94150543e+01 -8.13602066e+01 -6.65340424e+01 -6.43625183e+01 -6.08350868e+01 -4.91167526e+01 -4.10138168e+01 -4.89611816e+01 -6.69594803e+01 -6.70812149e+01 -4.66585274e+01 -4.30982895e+01 -5.25904922e+01 -4.12124023e+01 3.66276932e+00 3.66063805e+01 2.02249565e+01 -2.51959724e+01 -3.79868584e+01 -2.22371788e+01 -2.07631130e+01 -4.20664673e+01 -5.99764709e+01 -6.22879562e+01 -6.77215424e+01 -6.40394516e+01 -5.53942833e+01 -5.63122139e+01 -7.35034714e+01 -8.07605743e+01 -4.80266342e+01 -2.66334248e+01 -3.89086838e+01 -6.36841240e+01 -3.96310120e+01 -1.79941692e+01 -3.68500137e+01 -8.75594711e+01 -1.18650055e+02 -1.10737602e+02 -1.04008148e+02 -9.62089691e+01 -1.01367508e+02 -9.43180237e+01 -9.63945694e+01 -7.99546280e+01 -7.48821487e+01 -7.41096115e+01 -9.12741165e+01 -7.86329727e+01 -3.01271152e+01 3.21282744e+00 1.63383484e+01 4.06070089e+00 -1.62264519e+01 -4.06920967e+01 -6.10070801e+01 -5.65442238e+01 -5.68704491e+01 -5.74504509e+01 -5.67868996e+01 -5.42212219e+01 -6.05496750e+01 -5.70372047e+01 -4.95485191e+01 -4.73247833e+01 -4.63213120e+01 -5.14520988e+01 -2.12995033e+01 7.12358093e+00 1.08319740e+01 -1.56830025e+01 -3.78650017e+01 -3.52300758e+01 -3.30676079e+01 -3.42082024e+01 -3.30983047e+01 -2.67682037e+01 -2.15615768e+01 -1.02917528e+01 6.02209902e+00 -5.78664398e+00 -2.66352444e+01 -3.84129944e+01 9.44075012e+00 4.18964119e+01 3.02492390e+01 -1.30526543e+01 -1.66770363e+01 8.07094193e+00 6.30004215e+00 -1.19486446e+01 -3.27910614e+01 -5.85995674e+00 1.22157402e+01 2.90556793e+01 3.28973618e+01 3.94342995e+00 -1.66328011e+01 -1.62998505e+01 4.19918900e+01 7.08858566e+01 4.46626968e+01 -5.30872631e+00 2.25137830e+00 3.55358009e+01 3.94822235e+01 1.58992462e+01 -1.24716787e+01 8.15087318e+00 3.04784126e+01 4.15539246e+01 2.47136784e+01 9.03835595e-01 -5.90990353e+00 1.98249779e+01 4.50816422e+01 5.39388008e+01 2.97091408e+01 -2.55595374e+00 1.08470364e+01 3.31616745e+01 4.43643341e+01 2.87361488e+01 2.52638721e+01 4.72674484e+01 3.92918930e+01 1.33413572e+01 -1.93153191e+01 -2.26649628e+01 -2.13883152e+01 -2.41385674e+00 2.41418705e+01 3.10683575e+01 2.56791592e+01 9.59262657e+00 6.50247955e+01 2.11782028e+02 2.84199432e+02 4.52165619e+02 2.04086719e+03 7.84252002e+03 1.45237881e+04 -3.12742875e+06 4.31392250e+06 -1.35223193e+04 -6.35457520e+03 -1.16841272e+03 -1.35547375e+03 4.50291992e+03 1.13168516e+04 -2.45156850e+06 19237962. -13841511. 4.60260550e+06 -3.53934157e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.97151386e+10 2395078. 3.07521055e+04 1.12800479e+04 8.32711487e+02 -4.55796387e+03 -2.03760754e+03 4.11819366e+02 1.77560577e+02 -3.68672577e+02 -5.16457947e+02 -1.53106232e+02 -1.17184639e+00 1.37484421e+02 1.42299332e+02 5.09233818e+01 1.25099020e+01 4.33229713e+01 1.18330584e+01 -4.59522896e+01 -1.07037590e+02 -3.37022247e+01 1.07091415e+02 1.84483505e+02 1.43407974e+02 4.69428406e+01 -1.41733103e+01 -7.89335430e-01 2.14338131e+01 -7.17522383e+00 -4.16404152e+01 -1.06297760e+01 6.85307770e+01 1.09840721e+02 8.48115540e+01 1.87209263e+01 -2.32344937e+00 5.29755173e+01 1.37519424e+02 1.72712982e+02 1.32485260e+02 1.38779114e+02 1.83205795e+02 1.49943344e+02 5.90430412e+01 -1.43750172e+01 7.47361069e+01 2.21202728e+02 2.70717987e+02 1.92497696e+02 1.11710182e+02 6.48957596e+01 5.57327995e+01 6.35832634e+01 7.15682297e+01 5.61944504e+01 7.66071320e+01 1.83423950e+02 2.70607483e+02 2.41677368e+02 1.37990509e+02 7.47872543e+01 1.18269798e+02 1.90579178e+02 2.19827774e+02 1.58222183e+02 1.35174454e+02 1.58708069e+02 1.38653976e+02 7.42214584e+01 4.03259563e+00 2.41418209e+01 1.47170578e+02 1.82532227e+02 1.38189636e+02 4.41762505e+01 5.85838509e+01 1.33002274e+02 1.21667564e+02 7.80382004e+01 4.22939415e+01 8.62528305e+01 1.83435333e+02 2.27762146e+02 1.94276184e+02 9.66515503e+01 4.27764206e+01 6.82704544e+01 1.15312592e+02 1.00409668e+02 4.99618645e+01 5.60208702e+01 1.22398170e+02 1.50924332e+02 8.30028076e+01 6.60068095e-01 2.51337910e+00 1.01010880e+02 1.83876541e+02 1.84976212e+02 1.26309349e+02 1.12369576e+02 1.27139427e+02 7.83988037e+01 -9.78406715e+00 -5.37243919e+01 3.37740402e+01 1.63160721e+02 2.32652557e+02 1.90465775e+02 1.20657494e+02 4.20746841e+01 -4.18528986e+00 1.14993467e+01 3.07823582e+01 3.69054375e+01 5.28822365e+01 1.30714996e+02 1.99739197e+02 1.56707687e+02 3.84406471e+01 -1.25408382e+01 4.03268280e+01 1.59955292e+02 2.08991806e+02 1.64279663e+02 1.14820290e+02 1.03718864e+02 1.17981728e+02 7.36950531e+01 -1.69118500e+01 -1.40668554e+01 7.36406326e+01 1.67937500e+02 1.59673187e+02 1.10571381e+02 6.58790283e+01 6.25640297e+01 7.51793976e+01 1.14734070e+02 1.36330444e+02 8.95024796e+01 6.67156906e+01 1.12085106e+02 1.55342316e+02 1.70225967e+02 1.43678635e+02 1.42832138e+02 1.72417206e+02 1.74816544e+02 1.51984955e+02 1.17992142e+02 9.60927124e+01 1.31774261e+02 1.49515656e+02 1.43950455e+02 1.14926903e+02 1.51220520e+02 2.56043121e+02 3.04005646e+02 2.24254303e+02 1.32217575e+02 1.18607018e+02 1.71860291e+02 2.02592239e+02 2.04410187e+02 2.08266068e+02 2.45565872e+02 2.87245178e+02 3.01479156e+02 2.75374603e+02 2.07499847e+02 1.65922806e+02 2.08143631e+02 2.37340942e+02 2.24409225e+02 1.72649139e+02 2.08449661e+02 2.85463715e+02 2.87096161e+02 2.49424591e+02 2.14318115e+02 2.64480408e+02 3.49541687e+02 3.98002411e+02 3.43928741e+02 2.51719971e+02 1.98437424e+02 2.07758255e+02 1.99065094e+02 1.73492020e+02 1.90786392e+02 2.54269745e+02 3.25589447e+02 3.07843201e+02 2.53243729e+02 1.61053421e+02 1.27809097e+02 1.47783249e+02 2.13757004e+02 2.72189209e+02 2.72516724e+02 2.93499268e+02 3.14667603e+02 3.08451691e+02 2.37947769e+02 1.68569977e+02 1.98871841e+02 3.02462799e+02 3.59520508e+02 3.02163910e+02 1.96568130e+02 1.58895477e+02 2.04924454e+02 2.58703491e+02 2.37778488e+02 1.99193069e+02 2.10509537e+02 2.65600922e+02 2.79651367e+02 2.31905563e+02 1.56277802e+02 1.41696396e+02 1.80189529e+02 2.24823166e+02 2.23436127e+02 2.05003906e+02 2.07243164e+02 2.38017441e+02 2.24815109e+02 1.86918533e+02 1.75790207e+02 1.76651566e+02 2.26304108e+02 2.35881119e+02 2.31792084e+02 2.25897079e+02 2.27317993e+02 2.61315369e+02 2.36180420e+02 1.93461411e+02 1.74263504e+02 1.98741135e+02 2.87929962e+02 3.30800995e+02 3.24789490e+02 2.27211243e+02 1.78964981e+02 1.72987411e+02 2.12502640e+02 2.38560684e+02 2.15120270e+02 2.26236450e+02 2.50807312e+02 2.67305786e+02 2.38277390e+02 2.13603714e+02 2.55696548e+02 3.09259399e+02 3.00402802e+02 2.75950317e+02 2.61557251e+02 2.79496643e+02 3.13260376e+02 2.76052856e+02 2.51146072e+02 2.26506836e+02 2.46903183e+02 2.88764801e+02 3.05254761e+02 3.17400452e+02 2.81054443e+02 2.61661011e+02 2.53353592e+02 2.87238068e+02 2.90463959e+02 2.86139832e+02 2.92559540e+02 3.19744293e+02 3.30845520e+02 2.87152985e+02 2.60634064e+02 2.59812317e+02 2.96047699e+02 2.85254120e+02 2.73543304e+02 2.56336456e+02 2.48771011e+02 2.56039886e+02 2.53133163e+02 2.90543518e+02 3.06628174e+02 3.16827972e+02 3.11966064e+02 3.00010529e+02 2.86889557e+02 2.49233887e+02 2.34248505e+02 2.49873047e+02 3.04105499e+02 3.21529541e+02 3.10753937e+02 2.90864746e+02 2.88592560e+02 2.79276947e+02 2.38685120e+02 2.18492722e+02 2.34759003e+02 2.85743652e+02 3.03436920e+02 2.83517609e+02 2.59590424e+02 2.57751740e+02 2.82611206e+02 2.82679047e+02 2.86600983e+02 2.59118591e+02 2.51072800e+02 2.49991165e+02 2.76423126e+02 2.84196198e+02 2.63947510e+02 2.43729080e+02 2.59904602e+02 2.93306488e+02 2.86601013e+02 2.66247681e+02 2.61628540e+02 2.80089233e+02 2.82078247e+02 2.57446747e+02 2.46000259e+02 2.56387085e+02 2.87355804e+02 2.85177307e+02 2.76721191e+02 2.65661530e+02 2.75351990e+02 2.88877960e+02 2.84790131e+02 2.88665649e+02 2.71996552e+02 2.70717499e+02 2.65573669e+02 2.78501587e+02 2.81828064e+02 2.74762543e+02 2.65293732e+02 2.74841553e+02 2.95243622e+02 2.98521973e+02 2.97588226e+02 3.07996094e+02 3.31983032e+02 3.25813507e+02 3.05973389e+02 2.99093719e+02 3.10453918e+02 3.28069763e+02 3.08821136e+02 3.00429565e+02 2.87868896e+02 2.80691467e+02 2.79258240e+02 2.89032532e+02 3.16995880e+02 3.21640594e+02 3.03748993e+02 2.84426208e+02 2.95649078e+02 3.18687378e+02 3.32994415e+02 3.16672699e+02 3.05592529e+02 3.07435730e+02 3.14443298e+02 3.23318481e+02 3.34785645e+02 3.53379364e+02 3.48539459e+02 3.31211243e+02 3.23655945e+02 3.30408264e+02 3.39556335e+02 3.22281219e+02 3.12205688e+02 3.06971466e+02 3.08190948e+02 3.11090698e+02 3.18615356e+02 3.40951508e+02 3.44843140e+02 3.28007141e+02 3.00954620e+02 2.95613922e+02 3.17512299e+02 3.35302185e+02 3.35534088e+02 3.22651459e+02 3.15674866e+02 3.19931061e+02 3.30139282e+02 3.35873810e+02 3.29319885e+02 3.13682373e+02 3.09033264e+02 3.15073151e+02 3.24412231e+02 3.34082214e+02 3.32491882e+02 3.27133148e+02 3.15993042e+02 3.05123199e+02 3.01682953e+02 3.08381348e+02 3.22123169e+02 3.29644897e+02 3.22839081e+02 3.13660553e+02 3.13896973e+02 3.22513000e+02 3.29994385e+02 3.26231262e+02 3.18132538e+02 3.12062897e+02 3.11882446e+02 3.15735901e+02 3.18824036e+02 3.20279633e+02 3.16932770e+02 3.15346039e+02 3.14290344e+02 3.15626251e+02 3.16357544e+02 3.14869507e+02 3.13601349e+02 3.12803955e+02 3.13121826e+02 3.13613647e+02 3.14030548e+02 3.14054199e+02 3.13565552e+02 3.13467316e+02 3.14882294e+02 3.16378662e+02 3.15725433e+02 3.12745850e+02 3.10253204e+02 3.10438416e+02 3.12050690e+02 3.12413239e+02 3.10178375e+02 3.08605286e+02 3.07420715e+02 3.10555206e+02 3.13297974e+02 3.16552826e+02 3.17389954e+02 3.15475067e+02 3.12523041e+02 3.07709747e+02 3.08051147e+02 3.10618439e+02 3.16745819e+02 3.16863342e+02 3.11370544e+02 3.04243835e+02 3.06546204e+02 3.13563751e+02 3.17206299e+02 3.10793640e+02 3.00691528e+02 3.00225311e+02 3.07590332e+02 3.19528442e+02 3.18916931e+02 3.09295624e+02 2.99952057e+02 2.92630127e+02 3.03453827e+02 3.07933533e+02 3.13790649e+02 3.14345490e+02 3.16937653e+02 3.19359375e+02 3.12137299e+02 3.14042175e+02 3.21075897e+02 3.20536621e+02 3.10357697e+02 2.92081146e+02 2.84675720e+02 2.94809357e+02 3.20107300e+02 3.40391602e+02 3.38757965e+02 3.12013397e+02 2.83966278e+02 2.74655670e+02 2.93341461e+02 3.17129181e+02 3.22913300e+02 3.07113831e+02 2.86352386e+02 2.91922150e+02 3.07296478e+02 3.21631134e+02 3.22962769e+02 3.16355011e+02 3.03976685e+02 2.87040375e+02 2.88376526e+02 3.04232880e+02 3.28229095e+02 3.34202759e+02 3.15223572e+02 2.88907684e+02 2.87777557e+02 3.11073944e+02 3.27039093e+02 3.21890045e+02 3.05339783e+02 2.97266113e+02 2.90436157e+02 2.97805817e+02 3.05368439e+02 3.02205750e+02 2.97614380e+02 2.86835022e+02 2.98593170e+02 3.12063995e+02 3.26491272e+02 3.36767609e+02 3.20391724e+02 3.09509796e+02 2.82756744e+02 2.72932312e+02 2.84898346e+02 3.10216217e+02 3.15600342e+02 2.90625671e+02 2.61143799e+02 2.66957642e+02 2.84323029e+02 3.15809113e+02 3.24322815e+02 3.08073059e+02 2.89224487e+02 2.78306030e+02 3.06275818e+02 3.27521576e+02 3.49639252e+02 3.46673126e+02 3.17101105e+02 3.20983185e+02 3.31402344e+02 3.63239471e+02 3.63229431e+02 3.51306854e+02 3.28021790e+02 2.83860260e+02 2.65620483e+02 2.75956665e+02 3.14372467e+02 3.27242096e+02 3.01631744e+02 2.62312012e+02 2.67408295e+02 3.04678955e+02 3.39382935e+02 3.23066040e+02 2.81661560e+02 2.40834351e+02 2.37945755e+02 2.72860870e+02 3.15025421e+02 3.25015533e+02 3.25193542e+02 3.13916656e+02 2.98715607e+02 2.70582092e+02 2.65985016e+02 2.80925171e+02 2.90547028e+02 2.72151672e+02 2.25976135e+02 2.05980820e+02 2.41288940e+02 2.96224121e+02 3.21739075e+02 2.88106934e+02 2.34922760e+02 2.22305893e+02 2.51237869e+02 3.03625488e+02 3.10903870e+02 2.81853760e+02 2.62755005e+02 2.52161301e+02 2.81943298e+02 2.94841339e+02 2.86443207e+02 2.76382965e+02 2.43176971e+02 2.52821609e+02 2.54401947e+02 3.03813080e+02 3.55573425e+02 3.81178741e+02 3.73692322e+02 3.12913879e+02 2.62275391e+02 2.43868591e+02 3.15109253e+02 4.73255951e+02 4.47115936e+02 2.24484467e+02 2.41858545e+03 6.32164014e+03 -273986432. -843729088. -68009928. -263046736. 797366976. -40158668. -265194240. -68327544. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 615633472. 49117268. -1.01545195e+04 -3.84925146e+03 3.53379395e+03 2.85891797e+03 1.03630640e+03 8.93999512e+02 5.40466431e+02 3.98834564e+02 2.75342712e+02 2.38374710e+02 2.76915710e+02 2.98570923e+02 2.58205292e+02 1.62341202e+02 1.58696503e+02 2.02808167e+02 2.69435760e+02 2.57574890e+02 1.88951797e+02 1.20123184e+02 1.10282967e+02 1.64745285e+02 2.57918915e+02 2.70400421e+02 2.03140137e+02 1.22751396e+02 1.21330383e+02 1.84640625e+02 1.88515472e+02 1.45624496e+02 1.30172958e+02 1.71230667e+02 2.18274765e+02 2.15275513e+02 2.20216461e+02 2.45725403e+02 2.46900116e+02 1.93585800e+02 9.91311111e+01 9.11059418e+01 1.56840988e+02 2.18418472e+02 2.18591263e+02 1.49187820e+02 6.64762039e+01 7.57191772e+01 1.70138321e+02 2.97180054e+02 2.91313354e+02 1.83873962e+02 1.12882149e+02 1.00821640e+02 1.63307053e+02 1.89567429e+02 1.97862152e+02 2.04159988e+02 1.88620941e+02 1.52201569e+02 9.00591202e+01 1.05970055e+02 1.76434479e+02 1.88888138e+02 1.40334503e+02 5.07899132e+01 5.27828178e+01 1.02896492e+02 1.70136566e+02 2.08168274e+02 1.31888916e+02 3.63739281e+01 -4.33926315e+01 -7.84113526e-01 1.01461792e+02 1.38180054e+02 7.99846802e+01 2.82432041e+01 2.85008545e+01 1.26238457e+02 1.42786728e+02 1.28147903e+02 7.10115433e+01 8.43443375e+01 7.79096069e+01 5.51461487e+01 8.41239395e+01 1.48983795e+02 1.75937668e+02 1.00774467e+02 -1.64292583e+01 -2.96830025e+01 1.35152817e+01 9.91543503e+01 1.54257401e+02 1.53027039e+02 8.50662842e+01 3.19688339e+01 3.80704269e+01 1.43521927e+02 1.78386017e+02 1.09563751e+02 1.90042400e+01 2.85941010e+01 1.28387619e+02 1.86219025e+02 1.73551712e+02 1.60249710e+02 1.37455246e+02 9.75474854e+01 1.69692688e+01 2.30423431e+01 8.75884857e+01 1.38927933e+02 1.30190811e+02 6.13622093e+01 5.23632851e+01 9.75969925e+01 1.33121429e+02 1.68480026e+02 1.56376907e+02 9.16341324e+01 3.09117451e+01 7.84725094e+00 1.12638199e+02 1.57482895e+02 1.16600876e+02 8.26537170e+01 7.46449432e+01 1.23077301e+02 1.08721886e+02 1.00020126e+02 1.29917557e+02 1.41935638e+02 1.20000999e+02 2.23291912e+01 2.17294197e+01 9.53916092e+01 1.49079590e+02 1.44402634e+02 7.13434067e+01 7.89094391e+01 1.31289581e+02 1.57733185e+02 1.89693405e+02 1.41464737e+02 7.59741440e+01 4.71449661e+00 1.11872978e+01 8.21567841e+01 9.46727448e+01 6.99471283e+01 6.58665771e+01 9.32878342e+01 1.44845123e+02 1.77514587e+02 1.94613312e+02 1.95797119e+02 1.46856796e+02 1.00930878e+02 7.54504967e+00 -1.77045593e+01 -1.07724524e+01 4.53225555e+01 4.31596222e+01 -1.31714878e+01 -7.88331299e+01 -3.71568871e+01 5.93835983e+01 1.39638336e+02 1.44963440e+02 4.26473122e+01 -1.98355331e+01 -1.15665636e+01 5.37464485e+01 7.43532639e+01 2.76077423e+01 3.14422531e+01 2.06264610e+01 1.50378199e+01 1.41351347e+01 7.40611954e+01 1.47967697e+02 1.58005234e+02 1.25191513e+02 6.43905334e+01 1.99249706e+01 8.20845318e+00 2.30321712e+01 2.07917233e+01 -3.72086945e+01 -1.00384445e+02 -7.94017792e+01 1.83647022e+01 1.09550407e+02 1.27089539e+02 4.87160263e+01 2.28079453e+01 1.35286379e+01 9.14550247e+01 7.64858932e+01 2.56558895e+01 -4.66968384e+01 -9.76224976e+01 -1.08383904e+02 -1.56992630e+02 -1.14365349e+02 -3.25295868e+01 3.26190834e+01 2.55493755e+01 -5.11511383e+01 -5.65768738e+01 -2.50606298e+00 6.65481949e+01 1.32941650e+02 8.61001663e+01 -3.31687126e+01 -1.39286102e+02 -1.00184372e+02 1.57634096e+01 3.49846878e+01 -2.22611237e+01 -5.05429802e+01 -4.79013443e+01 1.02402508e+00 3.33135872e+01 6.94940796e+01 6.40495300e+01 4.29147606e+01 -1.48314152e+01 -9.66802826e+01 -1.22078712e+02 -9.66385803e+01 -4.98257217e+01 -4.40025673e+01 -4.72445641e+01 -1.33688812e+01 3.54290657e+01 4.95407333e+01 3.05187588e+01 -2.51063023e+01 -4.49050140e+01 -5.59773216e+01 -3.79339981e+01 -4.87170362e+00 1.46589146e+01 6.47142029e+00 -2.48731556e+01 -5.07936783e+01 -3.78246002e+01 -2.42311554e+01 -3.02701721e+01 -5.02981491e+01 -6.29797134e+01 -4.53382301e+01 -3.41367912e+01 -2.50704041e+01 -2.31143913e+01 -3.06087513e+01 -1.77268658e+01 -2.77274380e+01 -3.15015087e+01 -5.09430542e+01 -4.25925407e+01 -2.98714466e+01 -3.11148357e+01 -3.91482925e+01 -4.37358627e+01 -3.04933167e+01 -3.08968334e+01 -2.42432346e+01 -4.45158195e+00 -1.64564686e+01 -3.28012466e+01 -5.32727356e+01 -3.13447762e+01 -2.98819942e+01 -3.16111279e+01 -3.02128639e+01 -2.82856617e+01 -2.89170513e+01 -3.54685898e+01 -3.36155434e+01 -3.94915047e+01 -4.81590080e+01 -5.68757591e+01 -4.85641479e+01 -5.23042755e+01 -3.15631523e+01 -4.60750542e+01 -4.13110924e+01 -5.50433998e+01 -3.36993828e+01 -3.79202881e+01 -4.09974251e+01 -7.06885452e+01 -9.06889191e+01 -1.07955269e+02 -9.70666962e+01 -8.12462921e+01 -6.83515854e+01 -6.86285400e+01 -7.08136215e+01 -8.67274780e+01 -9.35860977e+01 -8.11425400e+01 -7.92928314e+01 -8.65742111e+01 -8.89805222e+01 -7.05618744e+01 -5.99859390e+01 -7.15084152e+01 -8.33811722e+01 -8.32241287e+01 -9.25458450e+01 -1.06278503e+02 -1.17092384e+02 -1.19402565e+02 -1.10137001e+02 -9.55092239e+01 -8.74214249e+01 -6.18971939e+01 -5.41594849e+01 -4.26473656e+01 -6.96744385e+01 -8.85389404e+01 -1.06918068e+02 -1.22254349e+02 -1.24604904e+02 -9.54777832e+01 -5.80649681e+01 -6.35232353e+01 -9.45310135e+01 -1.24296753e+02 -1.22776764e+02 -1.18119080e+02 -1.31213806e+02 -1.37635178e+02 -1.40037521e+02 -1.26820206e+02 -1.34833710e+02 -1.36110001e+02 -1.28028214e+02 -1.18030197e+02 -1.29903107e+02 -1.61533752e+02 -1.95334549e+02 -2.00393967e+02 -1.79661240e+02 -1.44794998e+02 -1.47280899e+02 -1.61514755e+02 -1.60585281e+02 -1.50950089e+02 -1.36479462e+02 -1.70107666e+02 -1.89931732e+02 -2.04443039e+02 -1.71374786e+02 -1.44753006e+02 -1.22507484e+02 -1.47505997e+02 -1.91096771e+02 -2.33905090e+02 -2.04059464e+02 -1.50371521e+02 -1.28882584e+02 -1.46364502e+02 -1.67271545e+02 -1.72388931e+02 -1.92127945e+02 -2.11362564e+02 -1.98893036e+02 -1.68181274e+02 -1.45607376e+02 -1.41088516e+02 -1.56548859e+02 -1.78677567e+02 -2.06978058e+02 -2.01816116e+02 -1.79061432e+02 -1.57442688e+02 -1.52395782e+02 -1.53623718e+02 -1.51400391e+02 -1.41485153e+02 -1.31419952e+02 -1.31576202e+02 -1.49858597e+02 -1.67818787e+02 -1.62719131e+02 -1.52300278e+02 -1.54519958e+02 -1.67958649e+02 -1.68643250e+02 -1.54924133e+02 -1.76186813e+02 -1.94101746e+02 -1.91982513e+02 -1.52488358e+02 -1.39659531e+02 -1.63455750e+02 -1.81813293e+02 -1.91155121e+02 -2.02265778e+02 -2.18372269e+02 -2.18017685e+02 -2.22595230e+02 -2.22670029e+02 -2.17508301e+02 -1.94506622e+02 -1.89149445e+02 -1.99824173e+02 -2.02699341e+02 -1.90026352e+02 -1.87095642e+02 -1.90791809e+02 -1.91620773e+02 -2.14366180e+02 -2.33676910e+02 -2.36860321e+02 -2.07919861e+02 -1.80170624e+02 -1.87152710e+02 -1.88133865e+02 -1.93556686e+02 -1.93494171e+02 -2.03885788e+02 -1.95405670e+02 -1.75830444e+02 -1.59391205e+02 -1.60575836e+02 -1.73151718e+02 -1.91651169e+02 -1.95111649e+02 -1.89892639e+02 -1.85450623e+02 -1.96730865e+02 -1.99221771e+02 -1.70345596e+02 -1.36799271e+02 -1.36549057e+02 -1.78388062e+02 -2.16502060e+02 -2.18398560e+02 -1.79239410e+02 -9.12901764e+01 2.36047077e+01 1.65932251e+02 2.01597275e+02 1.21628937e+02 3.08367944e+03 8.28708691e+03 -92078840. -47853516. -262688832. -42032992. -545635776. 541758464. 90642192. -60858756. 37681580. 95644312. 199722080. -854541824. 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. 0. 0. 0. 0. 0. 0. 155501632. -126679384. -2.57015742e+04 -1.09068018e+04 -2.50779785e+03 2.42084229e+03 1.79721265e+03 2.64538361e+02 -6.74367752e+01 -1.90366165e+02 -2.16137787e+02 -1.95888092e+02 -1.97392807e+02 -2.17941101e+02 -2.46517532e+02 -2.48077408e+02 -2.52563171e+02 -2.53046921e+02 -2.53565857e+02 -2.39817032e+02 -2.22018707e+02 -2.39805695e+02 -2.67759766e+02 -2.75452332e+02 -2.55252548e+02 -2.42989197e+02 -2.54104492e+02 -2.57570068e+02 -2.54657257e+02 -2.46998886e+02 -2.40667892e+02 -2.39197510e+02 -2.43426743e+02 -2.58740814e+02 -2.64396606e+02 -2.68592346e+02 -2.61920074e+02 -2.79238892e+02 -3.01364990e+02 -3.06311554e+02 -2.94379364e+02 -2.79019714e+02 -2.85388428e+02 -2.92758423e+02 -2.95659912e+02 -3.00751648e+02 -3.02761414e+02 -3.06463287e+02 -3.08802673e+02 -3.09474487e+02 -3.04407532e+02 -3.01728394e+02 -3.00631622e+02 -3.06601074e+02 -3.04562103e+02 -3.00564423e+02 -3.01680908e+02 -3.05178223e+02 -3.11213470e+02 -3.10045654e+02 -3.03395050e+02 -2.90475037e+02 -2.76034241e+02 -2.69403351e+02 -2.76359467e+02 -2.87299652e+02 -2.93955261e+02 -2.84116791e+02 -2.74475769e+02 -2.79000854e+02 -2.93988770e+02 -3.09389618e+02 -3.11131958e+02 -3.10747253e+02 -3.17281250e+02 -3.28361603e+02 -3.19701904e+02 -3.01260162e+02 -2.87965088e+02 -2.93799835e+02 -3.02111115e+02 -3.00989502e+02 -3.02120605e+02 -3.02299744e+02 -3.04023224e+02 -3.04020294e+02 -3.04057159e+02 -2.98983154e+02 -2.97716583e+02 -2.96086487e+02 -3.01497437e+02 -3.00235382e+02 -2.89264618e+02 -2.76351562e+02 -2.81076630e+02 -2.92740387e+02 -3.04034546e+02 -2.99363770e+02 -2.94721527e+02 -2.88933868e+02 -2.85887085e+02 -2.92680969e+02 -3.03899231e+02 -3.07331909e+02 -3.03680634e+02 -2.92533142e+02 -2.93410736e+02 -2.96196655e+02 -3.03095276e+02 -3.07441559e+02 -3.04563873e+02 -3.06614044e+02 -3.06148987e+02 -3.09731781e+02 -3.06901428e+02 -3.06287384e+02 -3.07127777e+02 -3.03695496e+02 -2.98880920e+02 -3.00198090e+02 -3.05589233e+02 -3.11600830e+02 -3.12198425e+02 -3.12888123e+02 -3.13251221e+02 -3.13725677e+02 -3.16237488e+02 -3.15873840e+02 -3.08335907e+02 -2.99428314e+02 -2.99232574e+02 -3.04837616e+02 -3.11826538e+02 -3.15646820e+02 -3.18193542e+02 -3.17004395e+02 -3.13905670e+02 -3.12851868e+02 -3.15416046e+02 -3.15057800e+02 -3.14572998e+02 -3.13503998e+02 -3.12960785e+02 -3.12499512e+02 -3.12761963e+02 -3.13022461e+02 -3.13256866e+02 -3.12782990e+02 -3.11940704e+02 -3.11877106e+02 -3.12056549e+02 -3.11666290e+02 -3.11378754e+02 -3.11137482e+02 -3.12332947e+02 -3.13018311e+02 -3.13805878e+02 -3.13943634e+02 -3.14227325e+02 -3.15013550e+02 -3.15133270e+02 -3.14272064e+02 -3.11030151e+02 -3.09753571e+02 -3.10006470e+02 -3.11258575e+02 -3.12275269e+02 -3.12579956e+02 -3.13116180e+02 -3.13450500e+02 -3.13434235e+02 -3.13433594e+02 -3.13561646e+02 -3.13702698e+02 -3.13867218e+02 -3.13975067e+02 -3.14004364e+02 -3.13765411e+02 -3.13339783e+02 -3.13035645e+02 -3.13195496e+02 -3.13664703e+02 -3.14437256e+02 -3.14496521e+02 -3.14314728e+02 -3.14220551e+02 -3.14149536e+02 -3.13910553e+02 -3.13738434e+02 -3.13648834e+02 -3.13163910e+02 -3.13409302e+02 -3.13545441e+02 -3.13765259e+02 -3.13378357e+02 -3.13099640e+02 -3.14224243e+02 -3.14895966e+02 -3.15455292e+02 -3.14913635e+02 -3.13478210e+02 -3.10103973e+02 -3.05286865e+02 -3.03155060e+02 -3.02685455e+02 -3.04083618e+02 -3.02323456e+02 -3.05454681e+02 -3.09385620e+02 -3.14420898e+02 -3.14680756e+02 -3.14448547e+02 -3.13249268e+02 -3.12550507e+02 -3.13391724e+02 -3.15437103e+02 -3.15137848e+02 -3.14151367e+02 -3.11646881e+02 -3.11474792e+02 -3.10816925e+02 -3.16871002e+02 -3.24402008e+02 -3.22159698e+02 -3.15331543e+02 -3.07741211e+02 -3.05087067e+02 -3.02447327e+02 -2.93880646e+02 -2.89010376e+02 -2.90627045e+02 -2.95819550e+02 -3.04816162e+02 -3.03371857e+02 -3.00374023e+02 -2.96317657e+02 -2.95094818e+02 -2.98475769e+02 -2.98467651e+02 -2.98539673e+02 -2.97478119e+02 -3.00860443e+02 -3.03952698e+02 -3.02988983e+02 -2.94252319e+02 -2.82710083e+02 -2.73322449e+02 -2.69350464e+02 -2.89670868e+02 -3.09380219e+02 -3.20526764e+02 -3.11062653e+02 -2.99811584e+02 -2.99093048e+02 -2.96327393e+02 -2.97152405e+02 -2.96368286e+02 -2.99737091e+02 -3.00627258e+02 -3.02944458e+02 -3.00702484e+02 -3.00096802e+02 -3.07822205e+02 -3.21074371e+02 -3.24779633e+02 -3.16841431e+02 -3.06914459e+02 -2.99060852e+02 -2.90817200e+02 -2.89362335e+02 -2.96363525e+02 -2.97389191e+02 -2.88261292e+02 -2.88118195e+02 -2.95146088e+02 -3.03746185e+02 -3.05170898e+02 -3.01653442e+02 -2.99638092e+02 -2.96632233e+02 -2.97546173e+02 -2.94494659e+02 -2.94758728e+02 -2.95328461e+02 -3.01702576e+02 -3.02633484e+02 -3.00907532e+02 -2.85857147e+02 -2.68238281e+02 -2.71559784e+02 -2.84008331e+02 -2.98097473e+02 -2.91782776e+02 -2.90207855e+02 -2.85993958e+02 -2.80944794e+02 -2.76183502e+02 -2.74377106e+02 -2.64641571e+02 -2.59361450e+02 -2.60392334e+02 -2.78263885e+02 -2.92794617e+02 -2.94258484e+02 -2.89266602e+02 -2.98805725e+02 -3.12009094e+02 -3.15899628e+02 -3.11685364e+02 -2.97226990e+02 -2.99249115e+02 -2.95873688e+02 -2.93440674e+02 -2.85498199e+02 -2.81589355e+02 -2.83853821e+02 -2.93775238e+02 -2.91234924e+02 -2.88228119e+02 -2.84171692e+02 -2.86731812e+02 -2.83570862e+02 -2.78994049e+02 -2.63583374e+02 -2.47744766e+02 -2.48817581e+02 -2.55296951e+02 -2.65157715e+02 -2.63907898e+02 -2.73303711e+02 -2.81769562e+02 -2.75821991e+02 -2.44096176e+02 -2.23107224e+02 -2.22010910e+02 -2.49463516e+02 -2.64467285e+02 -2.60600555e+02 -2.52976501e+02 -2.52313919e+02 -2.60153229e+02 -2.48676529e+02 -2.25314499e+02 -2.16289169e+02 -2.32527603e+02 -2.58314697e+02 -2.55097198e+02 -2.53486984e+02 -2.51870575e+02 -2.54607315e+02 -2.52243301e+02 -2.42995300e+02 -2.35755341e+02 -2.29816818e+02 -2.41377121e+02 -2.47653778e+02 -2.46953308e+02 -2.18031235e+02 -1.83766373e+02 -1.78882477e+02 -2.03140442e+02 -2.32365005e+02 -2.37072479e+02 -2.46646011e+02 -2.49381485e+02 -2.41187836e+02 -2.03490814e+02 -1.77377914e+02 -1.49960342e+02 -1.47508255e+02 -1.71483612e+02 -1.98243042e+02 -2.29857986e+02 -2.05423126e+02 -1.86805771e+02 -2.11877441e+02 -2.64538055e+02 -2.88389313e+02 -2.59805084e+02 -2.30817368e+02 -2.35348145e+02 -2.41487335e+02 -2.44577972e+02 -2.45421982e+02 -2.47750000e+02 -2.49401886e+02 -2.52092865e+02 -2.52766815e+02 -2.53796234e+02 -2.51002197e+02 -2.55195694e+02 -2.49701172e+02 -2.46467514e+02 -2.22937546e+02 -2.02520691e+02 -2.04971512e+02 -2.29303818e+02 -2.60451996e+02 -2.31051926e+02 -1.92717300e+02 -2.13948166e+02 -2.75052582e+02 -2.77043549e+02 -2.05590759e+02 -1.61120270e+02 -1.86647537e+02 -2.20803177e+02 -2.04147751e+02 -1.67680313e+02 -1.57462067e+02 -1.73003296e+02 -2.02812698e+02 -2.02260269e+02 -1.99451752e+02 -2.00706024e+02 -1.99431839e+02 -2.24309296e+02 -2.45128387e+02 -2.18376373e+02 -1.63420944e+02 -1.34267441e+02 -1.48107864e+02 -1.74466858e+02 -1.46266464e+02 -1.21447243e+02 -1.13891518e+02 -1.37115814e+02 -1.71950180e+02 -1.67010330e+02 -1.63257355e+02 -1.54688599e+02 -1.70891830e+02 -1.62005844e+02 -1.36143936e+02 -1.23538094e+02 -1.24195572e+02 -1.60800842e+02 -1.78652649e+02 -1.92818039e+02 -1.90975769e+02 -1.84996002e+02 -2.31373657e+02 -2.82995697e+02 -2.67211792e+02 -1.97524673e+02 -1.41453766e+02 -1.57941696e+02 -1.85859116e+02 -1.63971878e+02 -1.24863136e+02 -1.21968292e+02 -1.47319534e+02 -1.77072205e+02 -1.86354233e+02 -1.87451996e+02 -1.88482376e+02 -1.75382324e+02 -1.70130753e+02 -1.63490997e+02 -1.46954407e+02 -1.37487579e+02 -1.44693771e+02 -1.63625656e+02 -1.77986511e+02 -1.80836014e+02 -1.78101685e+02 -2.02881866e+02 -2.32538773e+02 -1.96559570e+02 -1.26489944e+02 -9.01512451e+01 -1.31388107e+02 -1.71461395e+02 -1.91599930e+02 -1.99691422e+02 -2.04661926e+02 -1.94015152e+02 -1.81235046e+02 -1.87924606e+02 -1.84970581e+02 -1.89066071e+02 -1.82468430e+02 -1.90143295e+02 -1.91811676e+02 -1.98171951e+02 -1.79214554e+02 -1.64798721e+02 -1.72391953e+02 -1.92765991e+02 -2.01044510e+02 -1.76113220e+02 -1.51392578e+02 -1.36435730e+02 -1.13165932e+02 -7.84542542e+01 -7.43352356e+01 -9.73775253e+01 -9.89438553e+01 -2.78640137e+01 1.69244576e+01 -1.24398003e+01 -6.30478439e+01 -5.29353371e+01 -9.70722675e+00 -9.87262428e-01 -4.10615005e+01 -7.54380417e+01 -8.44134750e+01 -8.84945755e+01 -7.68705902e+01 -7.33923950e+01 -7.38388519e+01 -9.07891541e+01 -5.98832664e+01 -2.67873917e+01 -5.91718912e+00 -4.16282806e+01 -7.45683670e+01 -6.59564743e+01 -3.05098972e+01 -5.85693321e+01 -1.20250603e+02 -1.51085007e+02 -1.29120773e+02 -9.36633911e+01 -1.05858330e+02 -1.02915535e+02 -1.03858833e+02 -1.06095757e+02 -1.12055313e+02 -1.07446709e+02 -8.81566467e+01 -9.17725525e+01 -1.01806419e+02 -1.17104240e+02 -1.11292526e+02 -9.70187607e+01 -9.87938766e+01 -6.75408173e+01 -3.49928055e+01 -3.31945457e+01 -6.84310074e+01 -1.21266487e+02 -1.30823776e+02 -1.34205002e+02 -1.60275772e+02 -1.96970947e+02 -1.94270859e+02 -1.59947968e+02 -1.14640434e+02 -1.04030685e+02 -1.02639549e+02 -5.28764229e+01 -9.37106460e-02 1.41294479e+01 -2.72413635e+01 -5.72594337e+01 -5.77045097e+01 -6.50774536e+01 -8.36274261e+01 -7.95681305e+01 -9.96410294e+01 -1.34039474e+02 -1.15366425e+02 -5.71644516e+01 -1.52056866e+01 -3.07444687e+01 -2.12519417e+01 5.31844139e+01 9.68766251e+01 7.51997757e+01 -2.66825914e+00 -1.78660526e+01 7.42317963e+00 1.66220570e+01 -2.00618496e+01 -7.04703445e+01 -6.30239220e+01 -3.17390690e+01 -2.09887218e+01 -4.02435036e+01 -7.69881973e+01 -9.82588959e+01 -1.09800751e+02 -1.07456444e+02 -8.75063782e+01 -9.21393433e+01 -9.81319580e+01 -7.05833511e+01 -2.85166969e+01 -9.57037163e+00 -3.60315781e+01 -6.15903282e+01 -4.22774277e+01 -1.16574005e+02 -3.95502289e+02 -4.86237335e+02 -8.44188660e+02 -5.57575781e+03 -1.49876807e+04 -5786565. -4.53292050e+06 1.34953896e+04 6.34027637e+03 1.16379968e+03 1.34281897e+03 -4.49511426e+03 -1.19925869e+04 -2.82100025e+06 -29960634. -5.69750950e+06 5.74074778e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.60025088e+10 7.60025088e+10 3.80012544e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.97151386e+10 2395078. 2957467. -10597720. -1.29338936e+04 -2.88130054e+03 -5.60705078e+02 -3.11993579e+03 -2.63802734e+02 -3.31959045e+02 8.00898457e+00 -2.27432327e+01 -5.32476807e+01 -1.44302759e+01 9.91922379e+00 -2.58418007e+01 -7.28104401e+01 -4.36119156e+01 4.09537697e+01 7.99564133e+01 2.61473789e+01 -8.34530258e+01 -8.61532364e+01 2.23083782e+00 1.15604706e+02 1.45657593e+02 1.00496849e+02 1.11618492e+02 1.56767609e+02 1.52681503e+02 1.08766922e+02 7.20570908e+01 1.29331375e+02 2.34170563e+02 2.56930176e+02 1.73659927e+02 8.27371140e+01 3.42912216e+01 3.19846153e+01 4.84468460e+00 -3.76806030e+01 -5.48007393e+01 5.13839674e+00 1.57410660e+02 2.54001816e+02 2.18055176e+02 1.10195930e+02 2.78882866e+01 2.99603767e+01 6.99884109e+01 1.13357254e+02 9.96803207e+01 1.18693031e+02 1.47428665e+02 1.19793282e+02 2.16651497e+01 -8.35671768e+01 -6.04739685e+01 9.68601532e+01 1.58813004e+02 1.12683060e+02 1.44713068e+01 3.11124363e+01 1.23719215e+02 1.30485168e+02 5.37496681e+01 -3.69248505e+01 -1.17769470e+01 1.17195084e+02 2.10130829e+02 1.81953979e+02 1.10023392e+02 7.85050583e+01 9.64689941e+01 9.43920441e+01 4.45771408e+01 -4.03406906e+00 2.47950401e+01 6.24515533e+01 5.10019875e+01 4.39937210e+00 -1.36076679e+01 1.37684908e+01 6.25187187e+01 1.14643822e+02 1.34583328e+02 1.04305862e+02 8.08339386e+01 8.63756714e+01 3.98613091e+01 -4.07211418e+01 -7.77880707e+01 4.07506847e+00 1.36776886e+02 2.07930267e+02 1.71454590e+02 7.00384521e+01 -4.03598557e+01 -7.36500015e+01 -4.63707619e+01 -1.99993439e+01 -3.72299805e+01 -4.91855812e+00 8.69931641e+01 1.60948395e+02 1.39562164e+02 6.43088684e+01 3.91232834e+01 6.52093735e+01 1.25306175e+02 1.41930939e+02 1.01858330e+02 7.49572372e+01 7.68186188e+01 8.97685471e+01 4.88819580e+01 -3.29626770e+01 -4.63961067e+01 2.41585884e+01 1.10898170e+02 1.13529305e+02 5.73040390e+01 6.58909798e+00 2.82512689e+00 5.55308685e+01 1.15806755e+02 1.42927185e+02 1.12733025e+02 1.20114609e+02 1.62828568e+02 1.70262665e+02 1.12648201e+02 5.31969414e+01 5.63641396e+01 1.13687325e+02 1.42234604e+02 1.12671349e+02 8.46240845e+01 6.70818100e+01 9.58456268e+01 8.18175888e+01 4.12453880e+01 2.27071609e+01 8.78774414e+01 2.19995438e+02 2.82217407e+02 2.35573624e+02 1.53481323e+02 1.32807144e+02 1.53361099e+02 1.85092636e+02 1.71456848e+02 1.75404755e+02 2.09392136e+02 2.68148468e+02 2.82894104e+02 2.21678589e+02 1.08337708e+02 5.08460922e+01 1.18716156e+02 1.85527298e+02 1.91264374e+02 1.57100998e+02 1.90971298e+02 2.73118378e+02 2.63269897e+02 1.88215225e+02 1.13679817e+02 1.64839691e+02 2.77400085e+02 3.45245331e+02 3.04782806e+02 2.25139359e+02 1.79068680e+02 1.80381409e+02 1.64490173e+02 1.49711227e+02 1.68434952e+02 2.35304214e+02 3.10327240e+02 2.66626465e+02 1.97045914e+02 1.30634567e+02 1.46117645e+02 1.84697937e+02 2.20257050e+02 2.38742630e+02 2.45831696e+02 2.69703918e+02 3.07189728e+02 2.81232300e+02 2.11266373e+02 1.44692245e+02 1.68146439e+02 2.51036209e+02 2.97062103e+02 2.76626709e+02 2.07234543e+02 1.81414505e+02 1.87002472e+02 1.80632065e+02 1.16916183e+02 9.23435440e+01 1.40401932e+02 2.26206924e+02 2.45874191e+02 2.16012985e+02 1.51921555e+02 1.24229355e+02 1.34157379e+02 1.66197189e+02 1.95181564e+02 1.93921097e+02 2.17548569e+02 2.46705322e+02 2.25879639e+02 1.79427979e+02 1.61080688e+02 1.68472855e+02 2.13682709e+02 2.19844193e+02 2.07756668e+02 1.92002701e+02 1.90403091e+02 2.18492630e+02 1.97770279e+02 1.64373154e+02 1.43069595e+02 1.42497162e+02 1.99545258e+02 2.33082870e+02 2.03057388e+02 1.41479477e+02 1.32327530e+02 1.86484512e+02 2.38244293e+02 2.35473785e+02 1.99988464e+02 1.99546265e+02 2.25849960e+02 2.35738800e+02 2.00116745e+02 1.82973801e+02 2.11982117e+02 2.34004211e+02 1.99167511e+02 1.82082230e+02 2.01682037e+02 2.23572327e+02 2.52118317e+02 2.31455933e+02 2.56062195e+02 2.61098724e+02 2.62475403e+02 2.62424805e+02 2.81204834e+02 2.94912659e+02 2.51135834e+02 2.26789291e+02 2.16764359e+02 2.54194168e+02 2.40758453e+02 2.41378128e+02 2.62636505e+02 2.96311615e+02 3.02995117e+02 2.46232773e+02 2.09208832e+02 2.05117950e+02 2.53922302e+02 2.72786224e+02 2.68247894e+02 2.51759232e+02 2.44102478e+02 2.76525482e+02 2.63296997e+02 2.42946350e+02 1.92253754e+02 1.73916595e+02 1.85503311e+02 2.22922318e+02 2.53943924e+02 2.34299530e+02 2.06843246e+02 1.93661484e+02 2.12518372e+02 2.00796051e+02 2.02730865e+02 2.33269165e+02 2.64889038e+02 2.65892853e+02 2.10121948e+02 1.97930237e+02 2.22915894e+02 2.62825043e+02 2.50442657e+02 2.26695007e+02 2.19860840e+02 2.27670898e+02 2.48738602e+02 2.43087372e+02 2.56548248e+02 2.36604675e+02 2.30055023e+02 2.28751572e+02 2.46999939e+02 2.54692368e+02 2.38685333e+02 2.20482056e+02 2.20190491e+02 2.13850952e+02 1.80512253e+02 1.64754807e+02 1.69656525e+02 1.88864517e+02 1.89450928e+02 1.76162338e+02 1.66506531e+02 1.82246094e+02 2.10764938e+02 2.26512100e+02 2.26281723e+02 2.36185684e+02 2.46691681e+02 2.69699860e+02 2.73640991e+02 2.79666107e+02 2.59365570e+02 2.46784897e+02 2.42627884e+02 2.50857269e+02 2.45711227e+02 2.35216980e+02 2.23965057e+02 2.27406677e+02 2.29735184e+02 2.13851151e+02 1.99304810e+02 2.08870972e+02 2.34004532e+02 2.42553635e+02 2.42185944e+02 2.59075989e+02 2.74260101e+02 2.84135071e+02 2.63452820e+02 2.63508667e+02 2.58951050e+02 2.48383865e+02 2.47150909e+02 2.61921265e+02 2.93642059e+02 2.99144989e+02 2.73718964e+02 2.49394440e+02 2.52876312e+02 2.70564117e+02 2.85703888e+02 2.75480347e+02 2.63390594e+02 2.49316513e+02 2.51392365e+02 2.64723389e+02 2.76139160e+02 2.92879730e+02 2.94113983e+02 2.94904083e+02 2.96793762e+02 2.98607788e+02 2.96705444e+02 2.77611176e+02 2.74917419e+02 2.75470703e+02 2.76110168e+02 2.79149231e+02 2.89027557e+02 3.15915131e+02 3.23031281e+02 3.04939545e+02 2.70029480e+02 2.53310959e+02 2.73537354e+02 2.99795990e+02 2.99539795e+02 2.72194305e+02 2.44671692e+02 2.50745590e+02 2.76418823e+02 2.92687714e+02 2.92548584e+02 2.75820526e+02 2.77688293e+02 2.86715637e+02 2.95652252e+02 2.96440552e+02 2.84935303e+02 2.84670868e+02 2.90858307e+02 2.95894958e+02 2.95093903e+02 2.88165863e+02 2.91775940e+02 2.92276917e+02 2.81299072e+02 2.68716217e+02 2.69110321e+02 2.89679413e+02 3.03318176e+02 2.99385895e+02 2.83985474e+02 2.74767426e+02 2.77623108e+02 2.87213684e+02 2.92360474e+02 2.93081360e+02 2.85033936e+02 2.84609955e+02 2.85046143e+02 2.87987823e+02 2.89943176e+02 2.86066925e+02 2.83360626e+02 2.78762604e+02 2.79751862e+02 2.82271881e+02 2.86177795e+02 2.91051331e+02 2.91989197e+02 2.88478241e+02 2.82183868e+02 2.79636841e+02 2.82304138e+02 2.87053925e+02 2.88305145e+02 2.85159546e+02 2.82785217e+02 2.83339020e+02 2.85370087e+02 2.85922241e+02 2.85682159e+02 2.85517456e+02 2.85638336e+02 2.85423859e+02 2.84713654e+02 2.83827271e+02 2.83386719e+02 2.82262726e+02 2.81857819e+02 2.82995911e+02 2.85621796e+02 2.86964386e+02 2.84232574e+02 2.81145508e+02 2.81872437e+02 2.86582428e+02 2.91960114e+02 2.90510101e+02 2.83939606e+02 2.81311707e+02 2.83963531e+02 2.91083557e+02 2.90185333e+02 2.83498505e+02 2.78330536e+02 2.73386200e+02 2.78650848e+02 2.76993774e+02 2.80417847e+02 2.79821503e+02 2.78159485e+02 2.75752075e+02 2.70555664e+02 2.75892273e+02 2.81469238e+02 2.89889343e+02 2.85858856e+02 2.74437775e+02 2.63055908e+02 2.70016327e+02 2.83905640e+02 2.94492249e+02 2.95257568e+02 2.86086151e+02 2.81058563e+02 2.77641663e+02 2.82314148e+02 2.78703186e+02 2.72280090e+02 2.63002960e+02 2.54596756e+02 2.56892487e+02 2.72437592e+02 2.85202728e+02 2.85786102e+02 2.77799683e+02 2.70115814e+02 2.58413513e+02 2.53426270e+02 2.69844543e+02 2.96929962e+02 3.06450073e+02 2.88543213e+02 2.63311249e+02 2.62678223e+02 2.87848206e+02 3.14312592e+02 3.09935089e+02 2.77517151e+02 2.44597458e+02 2.32437363e+02 2.51638596e+02 2.69993042e+02 2.68556885e+02 2.59612701e+02 2.50768326e+02 2.67617279e+02 2.65021637e+02 2.69557373e+02 2.76746796e+02 2.82784882e+02 2.79342621e+02 2.57709351e+02 2.60491180e+02 2.86752197e+02 3.16462982e+02 3.11552612e+02 2.67021332e+02 2.33931549e+02 2.45534714e+02 2.82488251e+02 3.07821045e+02 3.05640472e+02 2.70536926e+02 2.37672775e+02 2.22212738e+02 2.51149673e+02 2.66901367e+02 2.82541290e+02 2.80861969e+02 2.77831451e+02 2.83351318e+02 2.82110199e+02 3.03883759e+02 3.15064148e+02 3.15399689e+02 2.98757416e+02 2.62524811e+02 2.47449203e+02 2.69427490e+02 3.02948639e+02 3.14848175e+02 2.89378479e+02 2.55040726e+02 2.56633331e+02 2.83582550e+02 3.17408478e+02 3.22461243e+02 2.81689636e+02 2.46570923e+02 2.35855026e+02 2.69308380e+02 2.97422882e+02 2.88706543e+02 2.65597565e+02 2.34098297e+02 2.28586578e+02 2.32068985e+02 2.52276443e+02 2.82567169e+02 2.84824158e+02 2.52780563e+02 1.99875748e+02 1.83530914e+02 2.20843750e+02 2.62575317e+02 2.87354462e+02 2.65884521e+02 2.28769806e+02 2.09296310e+02 2.18335205e+02 2.49670609e+02 2.47180191e+02 2.25511444e+02 2.02177704e+02 1.99897736e+02 2.37362503e+02 2.62668701e+02 2.56731934e+02 2.28718018e+02 1.84717148e+02 1.85440414e+02 1.86159195e+02 2.07893326e+02 2.30022964e+02 2.43159119e+02 2.50373718e+02 2.15963364e+02 1.91044098e+02 2.00128998e+02 2.30063019e+02 2.62272491e+02 2.39519272e+02 2.00317520e+02 1.75216919e+02 2.12315552e+02 2.85462433e+02 3.26751251e+02 2.87088928e+02 2.26703400e+02 1.99877365e+02 2.70236053e+02 3.70072601e+02 4.39355621e+02 6.81389038e+02 8.51772522e+02 2.55379761e+03 3.56217065e+03 9.97904907e+02 9.31182922e+02 8.04269653e+02 6.00746338e+02 3.67025665e+02 8.74381409e+02 -3.92753735e+03 -1.25673594e+04 -265194240. -68327544. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 615633472. 49117268. -281170432. 72323480. 3.02630352e+04 1.09305322e+04 3.68754663e+03 8.72170227e+02 4.26080139e+02 3.66936554e+02 3.29763092e+02 2.66050903e+02 1.64201294e+02 1.26841728e+02 1.45445953e+02 2.19064011e+02 2.60577850e+02 2.49356079e+02 1.88054794e+02 1.12320175e+02 1.10044350e+02 1.34105942e+02 1.60042145e+02 1.60046814e+02 1.55977264e+02 1.81051453e+02 1.46645630e+02 1.53495300e+02 2.13655655e+02 2.58125977e+02 2.17643188e+02 1.00286827e+02 4.31003380e+01 1.14978378e+02 2.07667572e+02 2.63119049e+02 2.31008926e+02 1.18421104e+02 2.86051788e+01 -1.75811462e+01 7.43480148e+01 1.34376938e+02 1.40528900e+02 7.32123642e+01 3.61994629e+01 6.74405136e+01 7.22254333e+01 1.14250610e+02 1.58111679e+02 1.78679504e+02 1.37792404e+02 1.11689739e+01 4.57181215e+00 9.98477707e+01 2.27419373e+02 2.55006866e+02 1.56645889e+02 5.48956833e+01 5.57856598e+01 1.31268723e+02 1.63192871e+02 9.76155319e+01 -1.71833935e+01 -5.95154610e+01 -1.77279644e+01 1.08698143e+02 1.95137741e+02 1.91159531e+02 1.10982033e+02 7.67553186e+00 -6.31629791e+01 -1.00200401e+02 -6.66492386e+01 -5.81325054e+00 6.61784439e+01 9.65250626e+01 7.50841751e+01 7.84402313e+01 1.53160461e+02 2.25436417e+02 2.28966370e+02 1.34778793e+02 6.64955750e+01 7.21183624e+01 1.14846680e+02 1.77208908e+02 2.20022491e+02 1.79529510e+02 7.31360092e+01 1.18016548e+01 7.71080551e+01 1.54438553e+02 1.38849792e+02 8.71536865e+01 7.52369614e+01 1.05578438e+02 7.93703918e+01 8.70928040e+01 1.26089127e+02 1.57803421e+02 1.30942490e+02 1.65943336e+01 1.39197311e+01 1.12976387e+02 2.50231323e+02 2.97253082e+02 2.02604462e+02 1.02096680e+02 4.68475342e+01 7.47323685e+01 1.08920868e+02 1.16879845e+02 8.46955338e+01 2.81245384e+01 -3.77286673e+00 5.58234520e+01 1.60061935e+02 1.96284897e+02 1.60593292e+02 1.20766220e+02 1.12637161e+02 5.97168655e+01 5.96294403e+01 1.45391754e+02 2.51394180e+02 2.51326141e+02 1.17356346e+02 5.90066147e+01 1.33492798e+02 2.38130432e+02 2.46548981e+02 1.33021072e+02 2.75749607e+01 -2.72063041e+00 3.28354301e+01 1.20173714e+02 1.91578598e+02 1.74816895e+02 8.38457108e+01 1.11906490e+01 6.57389755e+01 1.64223923e+02 1.99824783e+02 1.64281281e+02 1.07322853e+02 7.34462738e+01 1.13409796e+01 -1.07639093e+01 1.66511612e+01 6.70152740e+01 7.08053207e+01 -4.88152313e+00 -3.77678032e+01 2.95196533e+01 1.71804337e+02 2.59640228e+02 2.23514908e+02 8.22932205e+01 -2.21776085e+01 -7.02288723e+00 6.37619362e+01 9.20626678e+01 6.24364319e+01 5.81509628e+01 1.37881136e+01 3.01273537e+01 4.25253334e+01 8.63792496e+01 1.52647125e+02 1.72786484e+02 1.90702499e+02 9.15148849e+01 5.42973480e+01 1.12348656e+02 1.63220200e+02 1.36852722e+02 -5.67086840e+00 -5.20006866e+01 -1.72672749e+01 5.61691132e+01 9.83919525e+01 1.02978371e+02 6.33701553e+01 4.31491699e+01 3.35991135e+01 1.06258720e+02 8.27122345e+01 3.59317055e+01 -4.38334618e+01 -1.16923645e+02 -1.70307007e+02 -2.12163788e+02 -1.38167877e+02 -1.75151482e+01 5.72042923e+01 5.40078201e+01 -1.21259537e+01 -2.40989304e+01 5.80342331e+01 1.53129105e+02 1.99288376e+02 8.79066162e+01 -7.02995987e+01 -1.46821747e+02 -1.19399765e+02 -5.42191010e+01 -2.45380898e+01 -2.86709042e+01 -4.93163795e+01 -9.49225235e+01 -6.32296028e+01 -1.48295593e+00 3.32795334e+01 -1.71835499e+01 -4.08198509e+01 -5.79568329e+01 -8.81043091e+01 -1.01970123e+02 -6.42084351e+01 -2.96850643e+01 -3.69127693e+01 -3.98736992e+01 -1.00123234e-01 5.86454544e+01 9.19155655e+01 1.02802147e+02 5.10750618e+01 7.99185896e+00 -7.27223434e+01 -9.81397018e+01 -4.13490715e+01 3.74715271e+01 5.93810120e+01 2.74261260e+00 -3.79293022e+01 -2.51178532e+01 -2.19312878e+01 -2.34464130e+01 -1.77344666e+01 -1.73921604e+01 -2.10327740e+01 -2.11353741e+01 -2.11502800e+01 2.18800354e+00 4.16801500e+00 3.59005699e+01 2.79740105e+01 2.70695591e+01 -1.09448786e+01 -8.03187943e+00 -9.14814568e+00 -1.53219194e+01 -1.85042706e+01 -4.39693642e+01 -5.46409225e+01 -7.19226532e+01 -6.36261063e+01 -4.22629166e+01 -4.53313828e+01 -4.03795013e+01 -3.14617500e+01 -1.86521740e+01 -3.05526791e+01 -4.37624626e+01 -5.01758423e+01 -2.89735279e+01 -3.00798569e+01 -2.86253967e+01 -3.30019493e+01 -1.94822025e+01 -1.06128807e+01 -2.68065548e+00 5.01872206e+00 -1.24576979e+01 -1.82055893e+01 -3.27382507e+01 -1.86712265e+01 -1.59210348e+01 -8.88890076e+00 -1.65018826e+01 -2.67701702e+01 -5.17925682e+01 -6.08342400e+01 -4.53560371e+01 -2.75259056e+01 -3.40293274e+01 -4.88103256e+01 -5.48210945e+01 -4.67276840e+01 -5.95800819e+01 -5.97734604e+01 -5.19902840e+01 -4.28228264e+01 -4.95961304e+01 -5.60817680e+01 -4.49415703e+01 -5.82739220e+01 -8.17651596e+01 -9.47955017e+01 -7.84020157e+01 -6.88665619e+01 -7.34621353e+01 -8.72100220e+01 -8.40489426e+01 -8.63558578e+01 -8.00427780e+01 -7.97782745e+01 -8.47750702e+01 -9.93556671e+01 -9.41831284e+01 -9.18779449e+01 -7.70131607e+01 -8.16236343e+01 -6.26529121e+01 -3.41697807e+01 -4.42909546e+01 -6.43367157e+01 -1.07666260e+02 -9.85462570e+01 -9.57738800e+01 -9.86372604e+01 -9.91601257e+01 -1.15764122e+02 -1.15315750e+02 -1.12958939e+02 -1.13363663e+02 -1.21640907e+02 -1.29491180e+02 -1.12497513e+02 -1.09513596e+02 -1.09317192e+02 -1.12431335e+02 -1.01124207e+02 -1.10867363e+02 -1.17012161e+02 -1.23577713e+02 -1.39620239e+02 -1.44138245e+02 -1.37334732e+02 -1.10510574e+02 -1.03086060e+02 -1.13776588e+02 -1.30136017e+02 -1.39017761e+02 -1.36590195e+02 -1.13467819e+02 -8.71525879e+01 -9.49426804e+01 -1.17483002e+02 -1.50005157e+02 -1.49450150e+02 -1.42119995e+02 -1.26060265e+02 -1.14425423e+02 -1.08048996e+02 -1.02293243e+02 -9.65427399e+01 -1.03150162e+02 -1.09550430e+02 -1.30625336e+02 -1.28347855e+02 -1.17472191e+02 -1.14947548e+02 -1.24367508e+02 -1.24846527e+02 -1.15853073e+02 -1.10914635e+02 -1.16259575e+02 -1.21089134e+02 -1.22177773e+02 -9.88794937e+01 -6.97486572e+01 -7.36225739e+01 -1.10828331e+02 -1.49634338e+02 -1.29935379e+02 -1.01193008e+02 -9.41464157e+01 -1.11299393e+02 -1.41767822e+02 -1.28419907e+02 -1.15250130e+02 -1.03678940e+02 -1.11162964e+02 -1.23855324e+02 -1.14594139e+02 -9.08106079e+01 -7.15722733e+01 -9.53884583e+01 -1.39618973e+02 -1.56110626e+02 -1.40686752e+02 -1.32573441e+02 -1.35437149e+02 -1.46423157e+02 -1.52596588e+02 -1.35470306e+02 -1.17417877e+02 -1.20406708e+02 -1.44246170e+02 -1.71623596e+02 -1.67918045e+02 -1.62689850e+02 -1.55691498e+02 -1.79845871e+02 -2.18446701e+02 -2.31062317e+02 -1.99787430e+02 -1.67581421e+02 -1.56897995e+02 -1.62401245e+02 -1.39686371e+02 -1.38955978e+02 -1.83473068e+02 -2.34883072e+02 -2.44390289e+02 -2.06992752e+02 -1.70461044e+02 -1.71107300e+02 -1.71128036e+02 -1.96628311e+02 -2.14270645e+02 -2.06575790e+02 -1.77192841e+02 -1.47574448e+02 -1.53673172e+02 -1.52414307e+02 -1.88147614e+02 -2.33690735e+02 -2.37455444e+02 -2.14994629e+02 -1.73748688e+02 -1.50039185e+02 -1.33171783e+02 -1.34598740e+02 -1.68658951e+02 -1.81936859e+02 -1.93844635e+02 -1.93779419e+02 -1.93792419e+02 -2.03385834e+02 -2.18289093e+02 -2.26088791e+02 -2.19311920e+02 -1.84770828e+02 -7.68045807e+01 -1.12457485e+01 -1.87736626e+01 -1.27023293e+02 -1.74456238e+02 1.50590894e+03 2.66599829e+03 -7.76443054e+02 -8.38617554e+02 -8.63366455e+02 -8.57659912e+02 -8.80284668e+02 -1.10517017e+03 -8.65689941e+02 -1.30070483e+03 -1.68941882e+03 -1.06066855e+04 -2.60787363e+04 199722080. -854541824. 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. 0. 0. 0. 0. 0. 0. 155501632. -126679384. 52295800. 45721904. 927507328. 1.60011963e+04 7.28576953e+03 2.06495215e+03 9.07070847e+01 -1.47696350e+02 -2.07092026e+02 -2.01118591e+02 -2.04067368e+02 -2.03359009e+02 -2.06118805e+02 -2.01950668e+02 -1.98649475e+02 -1.98654785e+02 -2.00652435e+02 -2.20440964e+02 -2.26813766e+02 -2.23671387e+02 -2.06788498e+02 -2.10045181e+02 -2.24475098e+02 -2.45546906e+02 -2.54313004e+02 -2.52667282e+02 -2.55097321e+02 -2.57014618e+02 -2.67978668e+02 -2.73276062e+02 -2.78377167e+02 -2.76494171e+02 -2.78826385e+02 -2.77793182e+02 -2.76551483e+02 -2.76553619e+02 -2.79169006e+02 -2.82117737e+02 -2.76854950e+02 -2.72986023e+02 -2.74138367e+02 -2.78341766e+02 -2.82329163e+02 -2.84584381e+02 -2.84242767e+02 -2.77299194e+02 -2.60328918e+02 -2.47581955e+02 -2.46008179e+02 -2.53867920e+02 -2.64953949e+02 -2.71879272e+02 -2.77023682e+02 -2.70660431e+02 -2.62230530e+02 -2.61215240e+02 -2.69152893e+02 -2.76512238e+02 -2.80071930e+02 -2.84757141e+02 -2.79139038e+02 -2.68024170e+02 -2.61302551e+02 -2.55180756e+02 -2.53101288e+02 -2.53440796e+02 -2.59138000e+02 -2.65404602e+02 -2.63195282e+02 -2.65764038e+02 -2.80340057e+02 -2.86057373e+02 -2.84036987e+02 -2.74544220e+02 -2.71104950e+02 -2.73711823e+02 -2.63698425e+02 -2.49662842e+02 -2.51444550e+02 -2.59356964e+02 -2.70287506e+02 -2.51449982e+02 -2.35635162e+02 -2.33657043e+02 -2.47876816e+02 -2.55831207e+02 -2.55593750e+02 -2.53565216e+02 -2.59133667e+02 -2.59180206e+02 -2.50134964e+02 -2.40976379e+02 -2.44738297e+02 -2.60991455e+02 -2.73423309e+02 -2.78700684e+02 -2.75983032e+02 -2.72434967e+02 -2.69234222e+02 -2.79162689e+02 -2.87223602e+02 -2.82931061e+02 -2.71669464e+02 -2.70083221e+02 -2.77455658e+02 -2.83408081e+02 -2.72160339e+02 -2.64216217e+02 -2.64191711e+02 -2.75523132e+02 -2.84806549e+02 -2.88108002e+02 -2.87731079e+02 -2.87612274e+02 -2.85536438e+02 -2.83726257e+02 -2.82366058e+02 -2.83688507e+02 -2.83508789e+02 -2.81441559e+02 -2.80231049e+02 -2.80377563e+02 -2.82505310e+02 -2.82071747e+02 -2.82605072e+02 -2.81672089e+02 -2.75387482e+02 -2.68385559e+02 -2.69900604e+02 -2.76273010e+02 -2.82740173e+02 -2.76963867e+02 -2.70517365e+02 -2.71067535e+02 -2.75604187e+02 -2.80746552e+02 -2.80850555e+02 -2.81545197e+02 -2.83458710e+02 -2.82017792e+02 -2.81102234e+02 -2.81206177e+02 -2.84207367e+02 -2.86985077e+02 -2.86855560e+02 -2.85051819e+02 -2.82604645e+02 -2.83216003e+02 -2.83373627e+02 -2.83963165e+02 -2.82614136e+02 -2.79417419e+02 -2.76168304e+02 -2.76347015e+02 -2.79090424e+02 -2.82273254e+02 -2.80409851e+02 -2.78517578e+02 -2.79257935e+02 -2.82241730e+02 -2.84699890e+02 -2.84722809e+02 -2.84550964e+02 -2.84486786e+02 -2.84582886e+02 -2.84606384e+02 -2.84766663e+02 -2.84992615e+02 -2.85201965e+02 -2.84775299e+02 -2.84564240e+02 -2.84832001e+02 -2.85279449e+02 -2.85510010e+02 -2.85504364e+02 -2.85478058e+02 -2.85685059e+02 -2.86133209e+02 -2.86320099e+02 -2.86052582e+02 -2.85703339e+02 -2.85827545e+02 -2.85441254e+02 -2.86283600e+02 -2.87951111e+02 -2.88782745e+02 -2.87610474e+02 -2.85911621e+02 -2.85947601e+02 -2.86091492e+02 -2.85876892e+02 -2.85620819e+02 -2.86406708e+02 -2.86715179e+02 -2.89642700e+02 -2.92562622e+02 -2.92794464e+02 -2.89205261e+02 -2.85673981e+02 -2.86881226e+02 -2.87234131e+02 -2.90979431e+02 -2.93817017e+02 -2.94155823e+02 -2.88719330e+02 -2.83301453e+02 -2.83369019e+02 -2.84454285e+02 -2.85784515e+02 -2.85110687e+02 -2.83610474e+02 -2.82262909e+02 -2.81737518e+02 -2.81734009e+02 -2.81580994e+02 -2.80312958e+02 -2.80591797e+02 -2.77846252e+02 -2.76224762e+02 -2.74061462e+02 -2.74219208e+02 -2.75660004e+02 -2.74508545e+02 -2.74108948e+02 -2.74252777e+02 -2.75891724e+02 -2.77057007e+02 -2.75130981e+02 -2.75995483e+02 -2.75718994e+02 -2.74694061e+02 -2.70654022e+02 -2.68739410e+02 -2.70600037e+02 -2.72565582e+02 -2.74732727e+02 -2.72633026e+02 -2.75786652e+02 -2.74143707e+02 -2.78539734e+02 -2.79184906e+02 -2.80599487e+02 -2.74234039e+02 -2.66138672e+02 -2.70392761e+02 -2.82307556e+02 -2.91787323e+02 -2.88619324e+02 -2.83368774e+02 -2.81090088e+02 -2.81850372e+02 -2.82944458e+02 -2.85497986e+02 -2.84994629e+02 -2.82734924e+02 -2.79314636e+02 -2.76148438e+02 -2.70937531e+02 -2.68836945e+02 -2.70547272e+02 -2.76461609e+02 -2.79092163e+02 -2.79943695e+02 -2.77525391e+02 -2.76061096e+02 -2.70940552e+02 -2.69099274e+02 -2.66817627e+02 -2.72791260e+02 -2.83767761e+02 -2.94922180e+02 -2.91391602e+02 -2.83885132e+02 -2.72233490e+02 -2.70611389e+02 -2.68176605e+02 -2.77379486e+02 -2.86031616e+02 -2.92136017e+02 -2.91642273e+02 -2.82501617e+02 -2.73295319e+02 -2.58886505e+02 -2.63180115e+02 -2.68490723e+02 -2.72693573e+02 -2.68306915e+02 -2.63928680e+02 -2.59790955e+02 -2.62162231e+02 -2.66486786e+02 -2.69094910e+02 -2.73124695e+02 -2.73352325e+02 -2.89973663e+02 -3.02019135e+02 -2.95141174e+02 -2.75915100e+02 -2.57842285e+02 -2.65872955e+02 -2.73595703e+02 -2.70707275e+02 -2.68204712e+02 -2.75801483e+02 -2.90888733e+02 -2.90290497e+02 -2.74989380e+02 -2.57496979e+02 -2.65490082e+02 -2.67180176e+02 -2.63852814e+02 -2.49819107e+02 -2.47548706e+02 -2.49757935e+02 -2.57834839e+02 -2.52074738e+02 -2.42231461e+02 -2.41655350e+02 -2.43828751e+02 -2.48178131e+02 -2.40616760e+02 -2.53626511e+02 -2.68441864e+02 -2.70330353e+02 -2.77263977e+02 -2.92955963e+02 -3.12038635e+02 -3.13390320e+02 -2.99594604e+02 -3.01197083e+02 -2.85400482e+02 -2.81638214e+02 -2.61617798e+02 -2.44150238e+02 -2.17359589e+02 -2.12459778e+02 -2.18008392e+02 -2.24970810e+02 -2.26185120e+02 -2.29799377e+02 -2.31744827e+02 -2.30021011e+02 -2.19318802e+02 -2.36979462e+02 -2.62269592e+02 -2.75208252e+02 -2.70052124e+02 -2.49651764e+02 -2.48430145e+02 -2.43289322e+02 -2.30643921e+02 -2.42911789e+02 -2.42145706e+02 -2.50472488e+02 -2.46940765e+02 -2.59562805e+02 -2.81238708e+02 -2.65890198e+02 -2.42120483e+02 -2.31363251e+02 -2.56436401e+02 -2.66630280e+02 -2.54181351e+02 -2.24015411e+02 -2.40988251e+02 -2.61102936e+02 -2.69822632e+02 -2.54209702e+02 -2.38293930e+02 -2.63189423e+02 -2.82884094e+02 -2.80060425e+02 -2.44669983e+02 -2.17270981e+02 -2.29792343e+02 -2.47104996e+02 -2.23061523e+02 -1.89312286e+02 -2.08092407e+02 -2.48617661e+02 -2.70472076e+02 -2.58146179e+02 -2.48947281e+02 -2.47974457e+02 -2.66508636e+02 -2.84595428e+02 -2.78160278e+02 -2.38208435e+02 -2.03923584e+02 -2.06313538e+02 -2.14390411e+02 -2.19958084e+02 -2.11703384e+02 -2.13594238e+02 -2.18336975e+02 -2.27188080e+02 -2.25234787e+02 -2.08675064e+02 -2.04685226e+02 -2.09022400e+02 -2.34495728e+02 -2.45874847e+02 -2.36587555e+02 -2.29899155e+02 -2.11080429e+02 -2.13405365e+02 -2.11835693e+02 -1.99311981e+02 -1.89749893e+02 -1.83945267e+02 -2.31281616e+02 -2.61937714e+02 -2.27462265e+02 -1.61473129e+02 -1.55607162e+02 -2.12098511e+02 -2.33339157e+02 -2.03707443e+02 -1.85910843e+02 -2.12336349e+02 -2.20461227e+02 -2.14366608e+02 -1.83956299e+02 -2.04317978e+02 -2.13171524e+02 -2.21074692e+02 -1.99392334e+02 -1.71055099e+02 -1.72744690e+02 -1.76050766e+02 -2.07879730e+02 -2.27324432e+02 -2.31056610e+02 -2.03848312e+02 -2.03445801e+02 -2.58099548e+02 -2.94241821e+02 -2.74055084e+02 -2.18687729e+02 -2.15338440e+02 -2.36330475e+02 -2.07552765e+02 -1.50248856e+02 -1.27461716e+02 -1.59205200e+02 -1.85958939e+02 -1.86637405e+02 -1.77176086e+02 -1.92706558e+02 -1.90124954e+02 -1.89897308e+02 -1.78672012e+02 -1.68956924e+02 -1.53476059e+02 -1.43306870e+02 -1.54402649e+02 -1.62662964e+02 -1.84004776e+02 -1.86293716e+02 -1.91396942e+02 -2.04231995e+02 -2.07198074e+02 -1.90777557e+02 -1.61642853e+02 -1.72600525e+02 -2.09392029e+02 -2.20872055e+02 -2.09007233e+02 -2.20143250e+02 -2.75842804e+02 -3.13597595e+02 -2.80225922e+02 -2.08098984e+02 -1.89782669e+02 -2.03670898e+02 -2.07532761e+02 -1.75523529e+02 -1.54622620e+02 -1.49736343e+02 -1.43688629e+02 -1.34866348e+02 -1.46386597e+02 -1.43572235e+02 -1.31361740e+02 -1.26807068e+02 -1.74500809e+02 -1.99014954e+02 -1.69477310e+02 -1.36811951e+02 -1.73674194e+02 -1.97554214e+02 -1.67890427e+02 -9.80197067e+01 -6.08890305e+01 -6.16167412e+01 -6.24047394e+01 -7.63203888e+01 -8.13984146e+01 -9.34721222e+01 -8.21204376e+01 -9.98667145e+01 -1.04239738e+02 -1.09360512e+02 -7.83946381e+01 -1.03688538e+02 -1.70072632e+02 -2.21302048e+02 -2.30541397e+02 -2.10976120e+02 -1.86024780e+02 -1.55180679e+02 -1.26213318e+02 -1.26576988e+02 -1.15419685e+02 -1.08822533e+02 -1.05360046e+02 -1.17289703e+02 -1.13749229e+02 -1.15060646e+02 -1.17841949e+02 -1.10723854e+02 -1.10315308e+02 -9.51665649e+01 -1.41257126e+02 -1.82283051e+02 -1.91419388e+02 -1.47820419e+02 -1.16263969e+02 -1.21929993e+02 -1.23383652e+02 -1.18748749e+02 -1.14491493e+02 -1.17125023e+02 -1.18012367e+02 -1.42724762e+02 -1.76229156e+02 -1.58902634e+02 -1.16008156e+02 -1.03091560e+02 -1.77836487e+02 -2.23020599e+02 -1.90153748e+02 -1.16589012e+02 -1.12899239e+02 -1.41557739e+02 -1.40191360e+02 -1.15060791e+02 -8.55554504e+01 -1.20029541e+02 -1.43662994e+02 -1.72960373e+02 -1.87230911e+02 -1.43781204e+02 -1.11884811e+02 -1.11690895e+02 -1.95704117e+02 -2.31417236e+02 -1.84406372e+02 -1.03230049e+02 -1.14711456e+02 -1.62519730e+02 -1.77718430e+02 -1.38410294e+02 -9.70298843e+01 -1.20144371e+02 -1.50710022e+02 -1.68931076e+02 -1.45071671e+02 -1.16461952e+02 -9.55634995e+01 -1.29665085e+02 -1.66526016e+02 -1.80658859e+02 -1.40116959e+02 -8.51661530e+01 -1.09666206e+02 -1.43614944e+02 -1.45755707e+02 -1.07164604e+02 -1.07952568e+02 -1.49717819e+02 -1.45000763e+02 -1.00137177e+02 -4.43583641e+01 -3.94790001e+01 -3.52662621e+01 -7.03664932e+01 -1.10251312e+02 -1.26470268e+02 -1.09317085e+02 -8.36580505e+01 -1.85245758e+02 -4.13161316e+02 -4.34863525e+02 -7.13725159e+02 -3.36862036e+03 -5.09734668e+03 4.49235115e+01 2.85204601e+01 -1.35099411e+01 -3.14363575e+01 -4.73037491e+01 -7.01793518e+01 1.51878067e+02 3.51634979e+02 5.78339478e+02 9.80398254e+02 -1.03761328e+03 -1.19404492e+04 -1.68798688e+05 2.50198897e+10 0. 0. 0. 0. 0. 0. 0. 1.97394739e+10 -12251109. 6.69585438e+05 2.78315039e+04 4.10479297e+04 8367779. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2048812928. 5.29756250e+06 2.13574258e+04 9.49296875e+03 2.37792310e+03 -3.82037506e+02 -1.32116302e+02 4.51557281e+02 5.45840149e+02 1.93312286e+02 3.90063133e+01 -8.67842865e+01 -8.52225037e+01 6.15389347e+00 3.54708939e+01 -7.52273798e-01 3.13108215e+01 9.75306931e+01 1.65369476e+02 9.76381912e+01 -4.90620270e+01 -1.21426918e+02 -7.17846985e+01 3.50299072e+01 8.58589783e+01 7.31106796e+01 5.33391724e+01 8.20985489e+01 1.25083725e+02 9.22020569e+01 1.18424511e+01 -3.24056320e+01 -4.73335646e-02 7.42510681e+01 1.00707108e+02 5.06345520e+01 -3.73908005e+01 -8.16115494e+01 -4.18865547e+01 -4.27282410e+01 -8.88444672e+01 -6.59925613e+01 3.36259651e+01 1.20160667e+02 4.58198318e+01 -1.08330421e+02 -1.61644516e+02 -7.67607803e+01 1.81062107e+01 6.61590576e+01 6.80562134e+01 5.14953575e+01 4.35211449e+01 6.91767349e+01 5.89151306e+01 -4.97687492e+01 -1.45068817e+02 -1.07045959e+02 3.03017735e+00 6.85509720e+01 2.86818256e+01 -3.82737961e+01 -7.12553940e+01 -7.16371679e+00 7.06137848e+00 -1.30778303e+01 1.35621538e+01 9.67269287e+01 1.74218765e+02 1.55830170e+02 2.36293850e+01 -1.76623535e+01 2.76839466e+01 1.25555046e+02 1.17016388e+02 4.27251930e+01 5.93073921e+01 1.03218910e+02 1.39098312e+02 9.11362839e+01 -1.25261765e+01 -6.09021950e+01 -2.51690636e+01 8.78945389e+01 1.55709473e+02 1.31774612e+02 7.86647797e+01 8.61370163e+01 1.38530350e+02 1.37250916e+02 6.82358475e+01 3.85554428e+01 1.06405045e+02 1.99192123e+02 2.06392319e+02 1.13561691e+02 2.84628506e+01 3.09881992e+01 9.42302475e+01 1.13406776e+02 9.21726074e+01 1.37192520e+02 2.17564957e+02 2.58714935e+02 1.78733521e+02 5.22745857e+01 -1.31106119e+01 3.23601418e+01 1.11201561e+02 1.88860306e+02 2.35167694e+02 2.28576248e+02 2.14243866e+02 2.16468155e+02 2.00533508e+02 1.26097595e+02 5.35676651e+01 9.84217300e+01 2.24168396e+02 2.75836975e+02 2.20767853e+02 9.54720459e+01 4.30705528e+01 9.86619720e+01 1.50147354e+02 1.68553375e+02 1.55223709e+02 2.05614212e+02 2.87399048e+02 2.80540863e+02 1.88083740e+02 1.00191772e+02 1.10068329e+02 1.70203888e+02 2.12801636e+02 2.17478210e+02 2.05091095e+02 1.67900299e+02 1.53740356e+02 1.99321793e+02 2.26363281e+02 1.83936539e+02 1.39191177e+02 1.27949638e+02 1.53680634e+02 1.52087799e+02 1.20565193e+02 1.19272911e+02 1.49065643e+02 1.91814117e+02 2.16719894e+02 1.83717422e+02 1.66939346e+02 1.77279922e+02 2.01227951e+02 1.64967209e+02 5.65234604e+01 2.86342645e+00 8.34943161e+01 1.87944153e+02 2.07263382e+02 1.55642426e+02 1.22437340e+02 1.27141464e+02 1.24494301e+02 8.64752426e+01 3.85826950e+01 2.54424400e+01 5.90038109e+01 1.28717682e+02 1.71632446e+02 1.29205231e+02 1.02192551e+02 1.19692894e+02 1.69446564e+02 1.44180710e+02 6.07967262e+01 6.75679932e+01 1.05098396e+02 1.35602966e+02 9.06425781e+01 5.31047535e+00 -3.29643021e+01 1.51473303e+01 1.08594872e+02 1.57867508e+02 1.49305405e+02 1.63035355e+02 1.91343185e+02 1.77567200e+02 1.19463135e+02 4.41598167e+01 6.63548813e+01 1.19202644e+02 2.13881149e+02 2.47446869e+02 2.26610138e+02 1.60538559e+02 1.03868355e+02 1.00989319e+02 9.02049866e+01 6.85449677e+01 9.10894089e+01 1.60435440e+02 2.23195770e+02 1.94918106e+02 9.39187698e+01 4.40092430e+01 9.76290436e+01 2.04263901e+02 2.40910507e+02 1.94658401e+02 1.42972214e+02 1.64230545e+02 2.09826004e+02 2.01502457e+02 1.46913040e+02 1.29903732e+02 1.83288574e+02 2.64049622e+02 2.73248901e+02 2.36931229e+02 1.90342560e+02 1.97684692e+02 2.13825302e+02 2.16899231e+02 1.91335403e+02 2.07524780e+02 2.44871872e+02 2.54222656e+02 2.57353394e+02 2.03097549e+02 1.93438156e+02 2.01513702e+02 2.12939362e+02 2.06745819e+02 1.69266022e+02 2.01016159e+02 2.41537613e+02 2.68035980e+02 2.46745514e+02 1.61810272e+02 1.10158569e+02 1.18434830e+02 2.05109497e+02 2.58580139e+02 2.65573608e+02 2.39490387e+02 2.14669617e+02 2.39345871e+02 2.32048019e+02 2.11433044e+02 1.95923386e+02 2.23714554e+02 2.45915207e+02 2.02439697e+02 1.48261551e+02 1.57212357e+02 1.84854843e+02 1.99905472e+02 1.87677811e+02 1.53849442e+02 1.90030594e+02 2.13347763e+02 2.42505814e+02 2.27911362e+02 1.87963104e+02 1.67742722e+02 1.54756973e+02 1.92486084e+02 2.11939407e+02 2.18397919e+02 1.89676910e+02 1.87256897e+02 1.94292969e+02 1.88270050e+02 1.63743790e+02 1.52528824e+02 1.92286957e+02 2.21805222e+02 2.22255463e+02 1.90686279e+02 1.99571320e+02 2.13976242e+02 2.31183319e+02 2.42067856e+02 2.34009094e+02 2.41536469e+02 2.07240891e+02 2.00302475e+02 1.87625305e+02 1.89478088e+02 2.00906204e+02 2.12948868e+02 2.49153549e+02 2.60723938e+02 2.52670319e+02 2.01277313e+02 1.89468552e+02 1.99023819e+02 2.18549179e+02 2.15819351e+02 2.24667465e+02 2.70634674e+02 2.91525238e+02 2.76188293e+02 2.21577560e+02 2.06361435e+02 2.24961349e+02 2.51525681e+02 2.58968018e+02 2.31371231e+02 2.32662476e+02 2.29437408e+02 2.63684387e+02 2.70013184e+02 2.74887268e+02 2.47072083e+02 2.43652100e+02 2.60573944e+02 2.76331604e+02 2.57190887e+02 2.26427643e+02 2.40144333e+02 2.64141754e+02 2.66801971e+02 2.53160904e+02 2.49048004e+02 2.78125977e+02 2.87198181e+02 2.76354675e+02 2.44906891e+02 2.47315903e+02 2.57982117e+02 2.71016174e+02 2.61969330e+02 2.49647430e+02 2.50354828e+02 2.48110977e+02 2.64982758e+02 2.70908020e+02 2.74359985e+02 2.60072754e+02 2.57894806e+02 2.64635345e+02 2.79385590e+02 2.68255157e+02 2.49150558e+02 2.43767960e+02 2.47345581e+02 2.39655731e+02 2.19124496e+02 2.23143570e+02 2.44621796e+02 2.50251373e+02 2.38125290e+02 2.20858398e+02 2.39204285e+02 2.50166931e+02 2.61382690e+02 2.72692169e+02 2.75141449e+02 2.65088501e+02 2.36129929e+02 2.31086700e+02 2.50592514e+02 2.71491577e+02 2.60564240e+02 2.37861099e+02 2.24668457e+02 2.39587631e+02 2.50709091e+02 2.47846420e+02 2.42836594e+02 2.34770264e+02 2.25159363e+02 2.09776321e+02 2.14191956e+02 2.29755402e+02 2.36476456e+02 2.30986313e+02 2.23285355e+02 2.39609451e+02 2.48385788e+02 2.55092484e+02 2.52842819e+02 2.52247910e+02 2.44178040e+02 2.26213272e+02 2.20796600e+02 2.37020340e+02 2.61226990e+02 2.68648224e+02 2.47252686e+02 2.29961929e+02 2.29080841e+02 2.43948914e+02 2.52714066e+02 2.48681671e+02 2.36937775e+02 2.31400024e+02 2.37756653e+02 2.55071564e+02 2.59447540e+02 2.52474579e+02 2.42521637e+02 2.33847672e+02 2.36181351e+02 2.40957199e+02 2.52361938e+02 2.63479370e+02 2.67498322e+02 2.61096985e+02 2.47523880e+02 2.40660141e+02 2.46913834e+02 2.56525085e+02 2.56293884e+02 2.48140930e+02 2.41354752e+02 2.44745926e+02 2.52801392e+02 2.58998962e+02 2.59456421e+02 2.55514786e+02 2.52626373e+02 2.50907013e+02 2.54162491e+02 2.56009827e+02 2.57414124e+02 2.55998520e+02 2.55467117e+02 2.56832520e+02 2.58116272e+02 2.59157471e+02 2.58918945e+02 2.58260834e+02 2.57822449e+02 2.57956146e+02 2.58564056e+02 2.58518097e+02 2.57086639e+02 2.55749893e+02 2.56440582e+02 2.59381256e+02 2.62035583e+02 2.61325653e+02 2.59754700e+02 2.59791412e+02 2.62005768e+02 2.63139099e+02 2.63672180e+02 2.60405731e+02 2.57796112e+02 2.54209915e+02 2.53409378e+02 2.55552460e+02 2.58793762e+02 2.63895813e+02 2.63816803e+02 2.60470245e+02 2.54594025e+02 2.53965622e+02 2.59312500e+02 2.65994843e+02 2.63729797e+02 2.56770813e+02 2.52815308e+02 2.58824524e+02 2.69389618e+02 2.69151367e+02 2.61176819e+02 2.47190567e+02 2.47395966e+02 2.57629639e+02 2.67735504e+02 2.73636902e+02 2.62127167e+02 2.56422394e+02 2.51747345e+02 2.51261292e+02 2.50245361e+02 2.48441055e+02 2.54419357e+02 2.51324005e+02 2.44027374e+02 2.45660675e+02 2.54771835e+02 2.71353027e+02 2.77649109e+02 2.68037933e+02 2.42562729e+02 2.20830307e+02 2.22650726e+02 2.49371368e+02 2.75642914e+02 2.83603943e+02 2.63049164e+02 2.39525925e+02 2.33440262e+02 2.49464706e+02 2.68299957e+02 2.64795258e+02 2.51710175e+02 2.36471588e+02 2.32706100e+02 2.37485626e+02 2.50907715e+02 2.67088318e+02 2.65693054e+02 2.49362625e+02 2.23230423e+02 2.16805298e+02 2.37355392e+02 2.59840668e+02 2.57936035e+02 2.35129944e+02 2.22065430e+02 2.30816879e+02 2.43566422e+02 2.49548737e+02 2.54218353e+02 2.46394379e+02 2.38387909e+02 2.40899796e+02 2.45420898e+02 2.55183807e+02 2.43556702e+02 2.30249695e+02 2.13406708e+02 2.02898209e+02 2.18253250e+02 2.32719757e+02 2.57737000e+02 2.66360748e+02 2.52716278e+02 2.27367905e+02 2.21544586e+02 2.46733841e+02 2.76240845e+02 2.70639282e+02 2.50959717e+02 2.20174835e+02 2.10181381e+02 2.25500656e+02 2.41885941e+02 2.52469772e+02 2.23263992e+02 2.00551712e+02 1.75888275e+02 1.80269409e+02 2.11079468e+02 2.08653381e+02 1.96724365e+02 1.61662094e+02 1.56304047e+02 1.68958862e+02 1.95171524e+02 2.39829666e+02 2.60054779e+02 2.49032593e+02 2.10276215e+02 1.89895111e+02 2.19177994e+02 2.56116486e+02 2.57630432e+02 2.11828537e+02 1.81157425e+02 1.90081482e+02 2.33289536e+02 2.66896423e+02 2.68677429e+02 2.33038025e+02 1.89586594e+02 1.77334381e+02 1.78459961e+02 1.91848694e+02 2.08021454e+02 2.35265594e+02 2.38683273e+02 2.25541199e+02 2.12755524e+02 2.30785202e+02 2.70922241e+02 2.94952881e+02 2.57210907e+02 2.04656265e+02 1.76305710e+02 2.07337677e+02 2.56309265e+02 2.65159363e+02 2.39100403e+02 1.87698776e+02 1.81215576e+02 2.10066727e+02 2.26011078e+02 2.31043579e+02 1.95986786e+02 1.87056244e+02 1.91656693e+02 2.06585281e+02 2.34490982e+02 2.25127869e+02 2.23558746e+02 1.78034042e+02 1.39907776e+02 1.45495590e+02 1.73290451e+02 2.20018387e+02 2.51505783e+02 2.56343475e+02 2.20075470e+02 1.35579910e+02 1.19253822e+02 1.29792038e+02 1.04815826e+02 -1.50502823e+02 -1.80607654e+03 -2.80929395e+03 3.67025665e+02 8.74381409e+02 -3.92753735e+03 -1.25673594e+04 -265194240. -68327544. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.07519795e+09 -3.53418047e+04 -5.22131250e+03 -1.03346997e+03 -6.01721924e+02 -1.37734695e+02 8.21874714e+00 1.04831032e+02 1.38359619e+02 9.78477173e+01 8.26847458e+01 1.24915359e+02 2.19833038e+02 2.23675507e+02 1.72554855e+02 1.05680099e+02 1.24778587e+02 2.03026291e+02 2.64753021e+02 2.70295746e+02 2.06200089e+02 1.09043175e+02 8.50982895e+01 1.49721176e+02 2.33390686e+02 2.32303574e+02 1.69332336e+02 1.65991150e+02 2.14687607e+02 2.34128143e+02 1.92371933e+02 1.47129608e+02 1.43026184e+02 1.31321075e+02 9.77573853e+01 9.78722076e+01 1.52230789e+02 2.45640320e+02 2.53803482e+02 1.84756287e+02 1.21847656e+02 1.23355217e+02 1.94097549e+02 2.69793640e+02 2.58154388e+02 1.60122208e+02 4.14989243e+01 5.02899208e+01 1.57314178e+02 2.16242798e+02 2.21291107e+02 1.63543854e+02 1.45379593e+02 1.38697006e+02 1.26852432e+02 1.42596329e+02 1.61964340e+02 2.13650391e+02 1.97180832e+02 1.34794159e+02 1.24515610e+02 1.58152710e+02 2.36558655e+02 2.40668106e+02 1.98512482e+02 1.28036118e+02 9.22338333e+01 1.67954422e+02 2.65891083e+02 3.35123108e+02 2.90505890e+02 1.85539169e+02 1.47980972e+02 2.10419174e+02 2.62525421e+02 2.50448837e+02 1.51050690e+02 1.28705719e+02 1.54763535e+02 2.05598465e+02 1.94290848e+02 1.99387817e+02 2.17276505e+02 1.83315155e+02 1.10180565e+02 8.43830338e+01 1.59127335e+02 2.65027924e+02 2.85219635e+02 2.38891174e+02 1.67752945e+02 1.06641029e+02 1.04815598e+02 1.51333313e+02 2.08956680e+02 1.91936966e+02 9.22770767e+01 5.18594398e+01 1.36771484e+02 2.25829941e+02 2.12445633e+02 1.07001999e+02 4.84889450e+01 5.69768181e+01 7.13390579e+01 8.67093582e+01 1.27937279e+02 2.11843979e+02 2.11066696e+02 1.35478790e+02 7.30616226e+01 7.88601074e+01 1.49778137e+02 1.60848709e+02 1.16122116e+02 7.42818756e+01 3.62644920e+01 4.62284546e+01 1.14670097e+02 1.79790222e+02 1.95557953e+02 8.65318680e+01 3.52076569e+01 8.40165100e+01 1.17020096e+02 1.19342514e+02 6.32857246e+01 7.46602402e+01 8.27013474e+01 4.95961876e+01 3.23819885e+01 5.45872879e+01 1.46881271e+02 1.52264389e+02 7.94723129e+01 2.73845367e+01 2.87291965e+01 1.03199150e+02 8.40123672e+01 3.36503220e+01 -9.72980022e+00 -3.69451904e+01 3.33668661e+00 8.06617126e+01 1.49414322e+02 1.49626495e+02 7.40238724e+01 5.80577621e+01 7.75878143e+01 7.70124664e+01 5.11491699e+01 -1.22826853e+01 -4.19011192e+01 -6.13608551e+01 -5.09748535e+01 -3.71194506e+00 4.62569008e+01 1.27923218e+02 1.43382690e+02 1.28007309e+02 6.79282379e+01 6.91156235e+01 1.28307449e+02 1.96070480e+02 1.61486374e+02 5.27019119e+01 -3.37856941e+01 -4.09748344e+01 6.29518471e+01 1.20502495e+02 1.17385185e+02 5.59903908e+01 3.49431725e+01 6.19912224e+01 4.57801018e+01 6.42989960e+01 7.80276337e+01 7.66389999e+01 7.11689758e+00 -6.90931931e+01 -6.81524506e+01 -3.69317360e+01 1.75751247e+01 6.50475540e+01 8.15100861e+01 6.56171799e+01 4.78868408e+01 1.01217415e+02 1.62040161e+02 1.37013855e+02 3.93735161e+01 -5.66377525e+01 -7.37055664e+01 6.09499598e+00 3.02651539e+01 4.01514511e+01 -3.45304413e+01 -1.91593609e+01 3.36216431e+01 1.02801682e+02 1.41257278e+02 1.39638733e+02 1.89261581e+02 1.57284424e+02 7.88122330e+01 6.78104687e+00 1.04554090e+01 8.71098709e+01 9.29216537e+01 3.29123688e+01 -4.50893326e+01 -1.10342545e+02 -6.63559418e+01 4.87120819e+01 1.46483627e+02 1.06118980e+02 -4.12970400e+00 -2.54566441e+01 3.16129379e+01 5.48311195e+01 4.79477654e+01 -7.06255770e+00 -4.26482010e+01 -7.06152802e+01 -5.55744743e+01 -3.92485504e+01 1.19415741e+01 7.98976059e+01 1.07676796e+02 8.15434723e+01 3.00137978e+01 2.20005207e+01 2.09481258e+01 -1.22616262e+01 -6.09236031e+01 -7.77691269e+01 -5.96072998e+01 -1.01838913e+01 9.79937077e+00 1.74787464e+01 -1.89179051e+00 -3.79022293e+01 -5.66506996e+01 -4.91164894e+01 -1.14150381e+01 -1.65147197e+00 -7.04278755e+00 -3.40253220e+01 -2.29257221e+01 -1.34710512e+01 -1.39652157e+00 -1.48648148e+01 -3.04844704e+01 -3.18931503e+01 -3.76597519e+01 -3.41035118e+01 -5.26050720e+01 -4.52217522e+01 -4.20151634e+01 -2.98660316e+01 -4.26450615e+01 -5.72414246e+01 -4.80419426e+01 -4.11247063e+01 -4.01689224e+01 -6.16056976e+01 -5.68896065e+01 -5.75461006e+01 -7.14705124e+01 -5.62526817e+01 -4.18008728e+01 -2.77885532e+01 -6.65102844e+01 -7.72971420e+01 -7.06864777e+01 -6.57138901e+01 -7.49123001e+01 -8.00327835e+01 -7.47713394e+01 -7.56158676e+01 -6.31798630e+01 -6.32398834e+01 -5.79579010e+01 -7.72746964e+01 -6.40185089e+01 -8.48260651e+01 -7.64983597e+01 -8.39088516e+01 -7.01540756e+01 -8.80292587e+01 -9.31687546e+01 -9.83937836e+01 -7.10055771e+01 -5.56026154e+01 -4.09204636e+01 -6.82198715e+01 -7.94323730e+01 -9.28221130e+01 -8.27325439e+01 -8.34382706e+01 -7.44178543e+01 -6.56707916e+01 -7.69569931e+01 -7.54931030e+01 -7.38814316e+01 -7.66216278e+01 -9.68485031e+01 -1.07169106e+02 -9.80398788e+01 -8.71773148e+01 -9.33976593e+01 -8.44485321e+01 -7.38473892e+01 -5.64524536e+01 -6.40341721e+01 -7.53316269e+01 -9.42451553e+01 -1.00746124e+02 -1.27432159e+02 -1.38402908e+02 -1.54684692e+02 -1.30630142e+02 -1.15960052e+02 -9.29301758e+01 -8.11094055e+01 -7.74799805e+01 -1.17520157e+02 -1.58244766e+02 -1.54367828e+02 -1.16739899e+02 -8.50591965e+01 -8.33598557e+01 -9.56366730e+01 -8.40078735e+01 -8.00184555e+01 -7.78090668e+01 -9.22766571e+01 -9.15400467e+01 -8.57355118e+01 -9.97849121e+01 -1.09740776e+02 -1.05978264e+02 -7.81582870e+01 -5.24619598e+01 -4.74379044e+01 -6.71702118e+01 -9.83409729e+01 -1.00661316e+02 -8.78643875e+01 -8.74456863e+01 -9.97143326e+01 -1.09058281e+02 -8.71941833e+01 -6.62645874e+01 -6.22460327e+01 -8.91066437e+01 -1.16128677e+02 -1.33039261e+02 -1.13978600e+02 -6.67037964e+01 -2.98136997e+01 -6.07486801e+01 -1.24804451e+02 -1.48779755e+02 -1.28808762e+02 -1.06907112e+02 -1.01818756e+02 -8.60539093e+01 -7.28864670e+01 -8.96699829e+01 -1.15899628e+02 -1.34359528e+02 -1.32716766e+02 -1.26774338e+02 -1.03980347e+02 -7.78623199e+01 -8.01867142e+01 -1.10156586e+02 -1.37966064e+02 -1.44233337e+02 -1.42381042e+02 -1.51227188e+02 -1.67302856e+02 -1.80075912e+02 -1.74978775e+02 -1.57006226e+02 -1.42065414e+02 -1.50711609e+02 -1.63444275e+02 -1.66231934e+02 -1.51239304e+02 -1.53183746e+02 -1.61271957e+02 -1.46382797e+02 -1.28521729e+02 -1.35623734e+02 -1.80685623e+02 -2.00144775e+02 -1.76396011e+02 -1.57025391e+02 -1.42882278e+02 -1.29918365e+02 -1.14056992e+02 -1.17602287e+02 -1.16363205e+02 -1.17528519e+02 -1.24239052e+02 -1.52536835e+02 -1.62107117e+02 -1.54356903e+02 -1.51072403e+02 -1.55335724e+02 -1.58585800e+02 -1.60719818e+02 -1.66264450e+02 -1.46245361e+02 -1.22949585e+02 -1.18665070e+02 -1.48708664e+02 -1.79629242e+02 -1.77112762e+02 -1.81067810e+02 -1.71916565e+02 -1.67573013e+02 -1.56328812e+02 -1.71956390e+02 -1.97546921e+02 -2.20833328e+02 -2.23063507e+02 -2.06246735e+02 -1.83639221e+02 -1.79982178e+02 -1.87344025e+02 -1.93773865e+02 -1.86802872e+02 -1.85112579e+02 -2.20750275e+02 -2.51913193e+02 -2.53835052e+02 -2.14614243e+02 -1.82393845e+02 -1.84075974e+02 -2.07838898e+02 -2.54463226e+02 -3.25611755e+02 -3.54942932e+02 -4.57458740e+02 -3.86446106e+02 -5.01994873e+02 -2.41968481e+03 -1.05239966e+03 -1.62428015e+03 -4.17964160e+03 -8.80284668e+02 -1.10517017e+03 -8.65689941e+02 -1.30070483e+03 -1.68941882e+03 -1.06066855e+04 -2.60787363e+04 199722080. -854541824. 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. 0. 0. 0. 0. 0. 0. 0. 0. -443228992. -139696864. 74457600. -1.15396162e+04 -4.41895020e+03 -9.23593445e+02 -4.60492432e+02 -3.04627197e+02 -2.71075958e+02 -2.80875183e+02 -2.83506470e+02 -2.61846008e+02 -2.37907669e+02 -2.37408325e+02 -2.35229065e+02 -2.34955246e+02 -2.38930099e+02 -2.50661209e+02 -2.66026306e+02 -2.46541275e+02 -2.18904190e+02 -2.12488388e+02 -2.34537674e+02 -2.49847778e+02 -2.41231995e+02 -2.32696472e+02 -2.36079865e+02 -2.43708527e+02 -2.56599976e+02 -2.61746918e+02 -2.61324799e+02 -2.48912445e+02 -2.43697540e+02 -2.40808044e+02 -2.46784042e+02 -2.30561325e+02 -2.08144653e+02 -2.02412399e+02 -2.15087555e+02 -2.31206879e+02 -2.29206985e+02 -2.19861435e+02 -2.17692368e+02 -2.12997360e+02 -2.11139206e+02 -2.06954269e+02 -2.02441650e+02 -2.02408905e+02 -2.09812393e+02 -2.17239471e+02 -2.20452164e+02 -2.12732086e+02 -2.14617889e+02 -2.18774658e+02 -2.20403809e+02 -2.16209564e+02 -2.11827423e+02 -2.12827576e+02 -2.21687500e+02 -2.40347382e+02 -2.58670441e+02 -2.65263794e+02 -2.54347824e+02 -2.41688187e+02 -2.34784393e+02 -2.46253860e+02 -2.57796295e+02 -2.53937881e+02 -2.40240250e+02 -2.27057129e+02 -2.26966232e+02 -2.28031891e+02 -2.20478485e+02 -2.07738098e+02 -2.19028992e+02 -2.38505753e+02 -2.54571762e+02 -2.46954391e+02 -2.37264023e+02 -2.37049316e+02 -2.36439087e+02 -2.36572098e+02 -2.34637680e+02 -2.35836197e+02 -2.38644165e+02 -2.45232056e+02 -2.49118286e+02 -2.50362564e+02 -2.47914169e+02 -2.48405350e+02 -2.59769012e+02 -2.73402374e+02 -2.68912140e+02 -2.58050171e+02 -2.45980179e+02 -2.50595078e+02 -2.55773407e+02 -2.61933716e+02 -2.65422180e+02 -2.58450470e+02 -2.47433701e+02 -2.45092178e+02 -2.50625763e+02 -2.62535248e+02 -2.62897339e+02 -2.59329651e+02 -2.52674988e+02 -2.48307236e+02 -2.52105606e+02 -2.51301086e+02 -2.52186905e+02 -2.48811615e+02 -2.52013351e+02 -2.52718735e+02 -2.52236984e+02 -2.56655243e+02 -2.63112640e+02 -2.61953247e+02 -2.55570099e+02 -2.49078400e+02 -2.48530945e+02 -2.47987915e+02 -2.48354065e+02 -2.48659454e+02 -2.47315155e+02 -2.47163605e+02 -2.54724594e+02 -2.63933472e+02 -2.65128113e+02 -2.59834076e+02 -2.53399918e+02 -2.50368744e+02 -2.48544937e+02 -2.49772476e+02 -2.52042068e+02 -2.53674896e+02 -2.51627319e+02 -2.52341919e+02 -2.52447983e+02 -2.53521622e+02 -2.54619034e+02 -2.55911240e+02 -2.55955719e+02 -2.55896210e+02 -2.55263412e+02 -2.55900070e+02 -2.56825836e+02 -2.56891052e+02 -2.57564331e+02 -2.58084106e+02 -2.58793121e+02 -2.59146027e+02 -2.57967896e+02 -2.57718292e+02 -2.57217163e+02 -2.57061340e+02 -2.56817535e+02 -2.55850113e+02 -2.55893677e+02 -2.56598511e+02 -2.59728485e+02 -2.61299255e+02 -2.61351471e+02 -2.60174713e+02 -2.59150513e+02 -2.58736298e+02 -2.58363586e+02 -2.58149261e+02 -2.58288727e+02 -2.58261261e+02 -2.58147064e+02 -2.58088287e+02 -2.58024109e+02 -2.57945984e+02 -2.57880432e+02 -2.58152100e+02 -2.58653564e+02 -2.58971466e+02 -2.58707764e+02 -2.58077026e+02 -2.57274078e+02 -2.57244324e+02 -2.57401093e+02 -2.57488403e+02 -2.57381561e+02 -2.57504120e+02 -2.57565002e+02 -2.57780334e+02 -2.58305267e+02 -2.57869507e+02 -2.57504028e+02 -2.57258636e+02 -2.57468994e+02 -2.57622437e+02 -2.56422516e+02 -2.55751953e+02 -2.55466827e+02 -2.55596512e+02 -2.56566193e+02 -2.59272339e+02 -2.63652802e+02 -2.65858734e+02 -2.66496277e+02 -2.65324524e+02 -2.67063171e+02 -2.63164307e+02 -2.57946472e+02 -2.52964386e+02 -2.53219421e+02 -2.54408295e+02 -2.54416336e+02 -2.53938553e+02 -2.53235214e+02 -2.51196411e+02 -2.51295654e+02 -2.50922226e+02 -2.52696167e+02 -2.53162918e+02 -2.53733841e+02 -2.47345871e+02 -2.39194031e+02 -2.41195526e+02 -2.48012329e+02 -2.55784409e+02 -2.58892090e+02 -2.60914490e+02 -2.68960052e+02 -2.73238434e+02 -2.71485840e+02 -2.65416199e+02 -2.54748413e+02 -2.56667786e+02 -2.58619537e+02 -2.63061066e+02 -2.62396088e+02 -2.59973267e+02 -2.60376190e+02 -2.59941498e+02 -2.60836365e+02 -2.57091034e+02 -2.54047607e+02 -2.53927414e+02 -2.62266205e+02 -2.72178040e+02 -2.81686005e+02 -2.84210175e+02 -2.65695160e+02 -2.43931122e+02 -2.32879257e+02 -2.40369980e+02 -2.52860168e+02 -2.53609161e+02 -2.56710236e+02 -2.55067215e+02 -2.53762512e+02 -2.50869583e+02 -2.48201904e+02 -2.45392151e+02 -2.45724167e+02 -2.45691437e+02 -2.38297424e+02 -2.24445557e+02 -2.21792969e+02 -2.28236511e+02 -2.37977463e+02 -2.44425858e+02 -2.51019669e+02 -2.52868881e+02 -2.45567612e+02 -2.45141556e+02 -2.51995453e+02 -2.51529358e+02 -2.44698151e+02 -2.36075378e+02 -2.33864578e+02 -2.36839737e+02 -2.37693893e+02 -2.38939865e+02 -2.38262039e+02 -2.40596451e+02 -2.39428192e+02 -2.38252808e+02 -2.31181778e+02 -2.30331680e+02 -2.29987045e+02 -2.45023621e+02 -2.60288269e+02 -2.57386475e+02 -2.43270157e+02 -2.30299423e+02 -2.36910019e+02 -2.37494659e+02 -2.37114746e+02 -2.37802444e+02 -2.42085617e+02 -2.44413437e+02 -2.52730194e+02 -2.58169983e+02 -2.56250916e+02 -2.39401169e+02 -2.24605118e+02 -2.22240921e+02 -2.27306152e+02 -2.18005676e+02 -2.05360764e+02 -1.96775177e+02 -2.03203690e+02 -2.16945938e+02 -2.14886490e+02 -2.14838959e+02 -2.15314346e+02 -2.22554169e+02 -2.25220016e+02 -2.19577820e+02 -2.14072189e+02 -2.13402069e+02 -2.15893066e+02 -2.13881058e+02 -2.11727051e+02 -2.16821777e+02 -2.21099503e+02 -2.36324020e+02 -2.48887405e+02 -2.46740753e+02 -2.37271790e+02 -2.27514343e+02 -2.28655807e+02 -2.20691956e+02 -2.11188049e+02 -2.14061966e+02 -2.39202469e+02 -2.59259949e+02 -2.60728424e+02 -2.37663879e+02 -2.20461609e+02 -2.22213303e+02 -2.29602509e+02 -2.29948563e+02 -2.21597763e+02 -2.33048080e+02 -2.53580841e+02 -2.62809113e+02 -2.46805908e+02 -2.20072083e+02 -2.21806076e+02 -2.20565582e+02 -2.22289520e+02 -2.17422623e+02 -2.16016891e+02 -2.22762802e+02 -2.27832581e+02 -2.33720917e+02 -2.23679657e+02 -2.17311203e+02 -2.16236969e+02 -2.45625076e+02 -2.80667908e+02 -2.84669830e+02 -2.54804199e+02 -2.22366623e+02 -2.18277863e+02 -2.05614227e+02 -2.05220612e+02 -2.08463791e+02 -2.46641312e+02 -2.68810333e+02 -2.99853668e+02 -2.97933502e+02 -2.77083893e+02 -2.46729156e+02 -2.14569946e+02 -2.34864517e+02 -2.53994125e+02 -2.29073700e+02 -1.73817474e+02 -1.49856522e+02 -1.75376190e+02 -2.01516998e+02 -1.96992508e+02 -1.92715927e+02 -1.88169937e+02 -1.87495895e+02 -1.79444397e+02 -1.76637299e+02 -1.74222015e+02 -1.71642654e+02 -1.67091339e+02 -1.60562836e+02 -1.57916550e+02 -1.66322922e+02 -1.72111359e+02 -1.95072372e+02 -2.11968338e+02 -2.09287140e+02 -1.82361282e+02 -1.50509888e+02 -1.78847092e+02 -2.16351120e+02 -1.91353760e+02 -1.28934998e+02 -1.22631889e+02 -1.94192322e+02 -2.36739410e+02 -2.14973740e+02 -1.74153732e+02 -1.89754486e+02 -2.23865356e+02 -2.33689835e+02 -2.20454559e+02 -1.87771881e+02 -1.88633957e+02 -1.89790146e+02 -1.86385086e+02 -1.84505997e+02 -1.58089264e+02 -1.32012009e+02 -1.55021713e+02 -2.08167557e+02 -2.37297195e+02 -2.19811600e+02 -1.95672592e+02 -2.23027252e+02 -2.48125153e+02 -2.53882858e+02 -2.25788589e+02 -1.87722656e+02 -1.93023331e+02 -1.99787567e+02 -2.10547867e+02 -1.89492905e+02 -1.99017044e+02 -2.27705994e+02 -2.40407486e+02 -2.34011093e+02 -1.87818558e+02 -1.67280045e+02 -1.54877838e+02 -1.63068161e+02 -1.68334702e+02 -1.22870857e+02 -6.44708099e+01 -7.67331772e+01 -1.45679153e+02 -1.97817566e+02 -1.79796753e+02 -1.43216614e+02 -1.64802216e+02 -2.02810471e+02 -2.06728760e+02 -1.79860031e+02 -1.48447495e+02 -1.35428696e+02 -1.34625214e+02 -1.35263092e+02 -1.45684769e+02 -1.47489075e+02 -1.55948990e+02 -1.68060623e+02 -1.78477280e+02 -1.67522598e+02 -1.47562592e+02 -1.31532455e+02 -1.32147888e+02 -1.35401901e+02 -1.04973190e+02 -6.76218109e+01 -9.91421204e+01 -1.67382492e+02 -2.04269791e+02 -1.63060776e+02 -1.19951080e+02 -9.29732666e+01 -8.00875320e+01 -7.87183151e+01 -9.13031082e+01 -1.04836166e+02 -9.73547211e+01 -9.70079651e+01 -8.84115982e+01 -9.07959213e+01 -7.78193207e+01 -7.66886520e+01 -7.12868042e+01 -9.93191071e+01 -1.14488060e+02 -1.03797600e+02 -7.50957642e+01 -6.12353363e+01 -8.47454224e+01 -1.07004272e+02 -1.21909462e+02 -1.45677551e+02 -1.85112732e+02 -1.85100449e+02 -1.53358704e+02 -1.42076706e+02 -2.09088715e+02 -2.55007477e+02 -2.25171921e+02 -1.72958618e+02 -1.87280899e+02 -2.30775040e+02 -2.37066345e+02 -1.92017105e+02 -1.57348083e+02 -1.48421738e+02 -1.43710220e+02 -1.54133698e+02 -1.53720657e+02 -1.52990677e+02 -1.29369751e+02 -1.50764038e+02 -1.84943024e+02 -2.04969833e+02 -1.75981873e+02 -1.39623718e+02 -1.45569916e+02 -1.72946747e+02 -1.47026764e+02 -8.66657028e+01 -5.84377518e+01 -7.07919159e+01 -1.04271980e+02 -9.08386459e+01 -9.53757935e+01 -9.30650940e+01 -9.27797623e+01 -8.13410187e+01 -8.49106674e+01 -9.33656845e+01 -8.90766220e+01 -7.96218185e+01 -6.44801636e+01 -7.16566315e+01 -7.96819305e+01 -7.39805069e+01 -1.03144470e+02 -1.33861877e+02 -1.34804764e+02 -9.44347916e+01 -4.33873100e+01 -2.96175556e+01 -2.56047592e+01 2.42316675e+00 3.88851089e+01 3.49156837e+01 -3.51707029e+00 -4.55918159e+01 -5.10016747e+01 -4.76612244e+01 -9.81804581e+01 -1.43855179e+02 -1.51256653e+02 -1.07028511e+02 -7.62411652e+01 -7.82423935e+01 -7.35212173e+01 -5.23445358e+01 -5.32638206e+01 -2.64215050e+01 1.18812618e+01 -1.13804264e+01 -7.22797089e+01 -1.16497063e+02 -8.91948242e+01 -9.03560791e+01 -1.54446167e+02 -2.02922470e+02 -1.83851532e+02 -1.07134628e+02 -7.81539307e+01 -9.83507538e+01 -1.16667862e+02 -8.15061111e+01 -2.77580528e+01 -2.76900482e+01 -6.16631012e+01 -6.70356293e+01 -5.17554703e+01 -1.38768063e+01 2.11821961e+00 1.69483051e+01 1.83521290e+01 5.42482424e+00 1.00687962e+01 1.99820156e+01 -4.27774334e+00 -3.91139297e+01 -6.10531845e+01 -3.55547409e+01 -1.21090040e+01 -3.52840576e+01 -7.72484665e+01 -7.56762466e+01 -3.52985115e+01 8.63038101e+01 2.64727997e+02 3.94207031e+02 5.38292786e+02 5.33348267e+02 6.18891716e+01 -2.14087204e+02 -4.76140259e+02 -6.65112152e+01 1.96817780e+02 1.65700180e+02 -1.82974792e+02 1.39104688e+03 -2.05818146e+02 -1.68798688e+05 2.50198897e+10 0. 0. 0. 0. -3.88826496e+09 -3.88826496e+09 -17269332. 2.82984243e+09 7.00192109e+04 6.69585438e+05 2.78315039e+04 4.10479297e+04 8367779. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.37251052e+10 -4.24189250e+06 9.54083008e+03 1.61088757e+03 2.78105981e+03 3.04544373e+02 2.18969070e+02 3.20224146e+03 3.45573914e+02 3.77085510e+02 3.60407829e+01 7.08155594e+01 8.95059662e+01 5.21659660e+01 2.64481735e+01 6.83696594e+01 1.15516731e+02 8.59555664e+01 -1.71183312e+00 -4.05100517e+01 2.35891705e+01 1.38786774e+02 1.40585068e+02 5.72315712e+01 -6.15553627e+01 -8.63970795e+01 -3.46653786e+01 -4.35279541e+01 -9.05693283e+01 -8.92135162e+01 -3.43474197e+01 1.22812643e+01 -4.20521088e+01 -1.54583664e+02 -1.75728394e+02 -9.17710724e+01 4.51661921e+00 5.81193848e+01 5.36612091e+01 8.47187881e+01 1.27798447e+02 1.53985016e+02 9.08034515e+01 -6.78293076e+01 -1.60045319e+02 -1.12999901e+02 -9.79868829e-01 8.29310684e+01 8.02442627e+01 4.73180122e+01 5.58261871e-01 9.72618103e+00 -1.34972706e+01 -3.97020531e+01 -8.20818710e+00 1.00326683e+02 2.08492996e+02 1.92063461e+02 3.15081558e+01 -4.23558617e+01 -4.27678251e+00 9.57627792e+01 8.29713440e+01 6.61482096e+00 9.04393005e+00 7.94183731e+01 1.60212875e+02 1.30473785e+02 2.07878399e+01 -7.20517960e+01 -3.76895447e+01 2.91356812e+01 6.66154251e+01 4.40745506e+01 5.20622215e+01 1.06241646e+02 1.59895401e+02 1.35665466e+02 1.06318573e+02 1.23280289e+02 1.68248886e+02 1.85911423e+02 1.59182556e+02 1.15922638e+02 6.04371796e+01 4.28730431e+01 6.29429855e+01 8.91014938e+01 8.53073502e+01 1.43206497e+02 2.30098938e+02 2.60491455e+02 1.80065933e+02 4.54949608e+01 -2.32028275e+01 1.31158743e+01 1.19517120e+02 2.17878082e+02 2.59944855e+02 2.40284637e+02 2.22716705e+02 2.37779053e+02 2.03971985e+02 1.11535583e+02 3.74943504e+01 6.18975410e+01 1.38667175e+02 1.61331528e+02 1.31750763e+02 6.87328568e+01 5.90053215e+01 1.04419807e+02 1.37498550e+02 1.33509125e+02 1.26484344e+02 1.70154861e+02 2.51917648e+02 2.65431061e+02 1.90794785e+02 1.07532776e+02 1.05936958e+02 1.75589111e+02 2.25399124e+02 2.29980286e+02 1.79613434e+02 1.21312134e+02 9.17529907e+01 1.22320145e+02 1.21998940e+02 8.65363541e+01 7.82877502e+01 1.35631424e+02 2.00339584e+02 1.97411087e+02 1.42364380e+02 1.08609993e+02 1.41149612e+02 1.67775909e+02 1.83046951e+02 1.57383850e+02 1.81427383e+02 2.21393585e+02 2.36233276e+02 1.71494553e+02 4.55767937e+01 -1.37030563e+01 3.82691650e+01 1.27737656e+02 1.49046280e+02 1.23110405e+02 8.79726181e+01 9.49678268e+01 9.68477631e+01 6.64290390e+01 1.50866938e+01 -1.15498514e+01 4.38608322e+01 1.54709335e+02 2.16530426e+02 1.56575302e+02 9.83540726e+01 1.00116028e+02 1.40318848e+02 1.04634216e+02 2.24720097e+01 3.06938572e+01 1.11040077e+02 1.79755844e+02 1.31349487e+02 2.07484093e+01 -3.59876366e+01 5.44108200e+00 8.78896637e+01 1.29761307e+02 1.31335251e+02 1.45964737e+02 1.67661240e+02 1.46560287e+02 8.38828354e+01 6.51411343e+00 4.77092400e+01 1.24454651e+02 1.82472336e+02 1.75283295e+02 1.28035965e+02 1.02594315e+02 8.26338577e+01 8.15115509e+01 6.06792908e+01 2.14797974e+01 4.85864944e+01 1.20745155e+02 1.77048203e+02 1.69982361e+02 9.01854858e+01 4.32842026e+01 5.59092865e+01 1.30195328e+02 1.64421265e+02 1.57752686e+02 1.63904663e+02 2.27191055e+02 2.52901566e+02 1.98088409e+02 1.15584297e+02 1.00635582e+02 1.36122406e+02 1.97708664e+02 2.29849472e+02 2.23348343e+02 1.90868607e+02 1.57033524e+02 1.61242264e+02 1.40832352e+02 1.16221161e+02 1.41830704e+02 1.90592453e+02 2.09961395e+02 2.02335403e+02 1.56481918e+02 1.46916229e+02 1.59769012e+02 1.77454803e+02 1.82998886e+02 1.57603027e+02 1.80942413e+02 2.19028915e+02 2.37839371e+02 2.43541382e+02 1.79348801e+02 1.40237869e+02 1.63916809e+02 2.25112213e+02 2.44480774e+02 1.98930237e+02 1.61732162e+02 1.62288223e+02 1.94248199e+02 1.92722137e+02 1.66689804e+02 1.58130524e+02 1.99532211e+02 2.13655914e+02 1.89861099e+02 1.64745270e+02 2.03255356e+02 2.15220840e+02 1.95768875e+02 1.72501724e+02 1.59960068e+02 1.82065109e+02 1.64631104e+02 1.51842377e+02 1.46710434e+02 1.37075531e+02 1.26903488e+02 1.18248169e+02 1.64377914e+02 1.83253693e+02 1.93445953e+02 1.61378815e+02 1.73824142e+02 1.76506836e+02 1.57435211e+02 1.27276230e+02 1.20194740e+02 1.76037750e+02 2.11315353e+02 2.11137970e+02 1.66537979e+02 1.47416824e+02 1.55384644e+02 1.76853027e+02 1.89441772e+02 1.62853943e+02 1.74931595e+02 1.96190338e+02 2.39499817e+02 2.54452072e+02 2.44494583e+02 2.10490173e+02 1.79845184e+02 2.01379837e+02 2.33315735e+02 2.50686447e+02 2.34348892e+02 2.47326050e+02 2.41406204e+02 2.17284348e+02 1.82046371e+02 1.86893280e+02 2.41265976e+02 2.55354507e+02 2.30511154e+02 1.88429443e+02 2.01457306e+02 2.23831955e+02 2.28393036e+02 2.19426788e+02 1.99714432e+02 2.05976440e+02 1.96503342e+02 2.26256714e+02 2.33508362e+02 2.36653351e+02 2.12236084e+02 2.07512161e+02 2.23008911e+02 2.43336334e+02 2.38915787e+02 2.43866272e+02 2.73409180e+02 2.92121368e+02 2.91187378e+02 2.77019043e+02 2.78961365e+02 2.92166748e+02 3.01763550e+02 2.89138519e+02 2.57561340e+02 2.39404205e+02 2.34999146e+02 2.37472031e+02 2.30795609e+02 2.10993881e+02 1.98815521e+02 1.88209991e+02 2.10416870e+02 2.23630447e+02 2.35849899e+02 2.31437668e+02 2.37207718e+02 2.45969971e+02 2.56957611e+02 2.53115906e+02 2.51420013e+02 2.66162231e+02 2.81389191e+02 2.72066406e+02 2.48337860e+02 2.42801544e+02 2.39669342e+02 2.22309677e+02 2.06797058e+02 2.00071350e+02 2.22787018e+02 2.24196686e+02 2.28363434e+02 2.40101761e+02 2.41324173e+02 2.27182449e+02 1.94942368e+02 1.90326523e+02 2.17816666e+02 2.43344635e+02 2.42347763e+02 2.23045975e+02 2.07996140e+02 2.16496643e+02 2.29881088e+02 2.44807938e+02 2.43287247e+02 2.30414230e+02 2.19597382e+02 2.03544144e+02 2.04475830e+02 2.04519669e+02 2.01993118e+02 2.02384979e+02 2.00586990e+02 2.21051392e+02 2.23276367e+02 2.26477982e+02 2.26891754e+02 2.22563263e+02 2.11820862e+02 1.84272186e+02 1.80519348e+02 1.98929169e+02 2.33589966e+02 2.51227478e+02 2.31338531e+02 2.07515656e+02 2.06415695e+02 2.34684662e+02 2.61326569e+02 2.54251892e+02 2.27093689e+02 2.11216782e+02 2.14007843e+02 2.29407867e+02 2.28596283e+02 2.18903824e+02 2.12305511e+02 2.11509521e+02 2.21975967e+02 2.22469757e+02 2.16099503e+02 2.11744125e+02 2.13367004e+02 2.21663818e+02 2.18924835e+02 2.17666733e+02 2.28753494e+02 2.41329071e+02 2.41325348e+02 2.20629501e+02 2.07685059e+02 2.11156830e+02 2.26999481e+02 2.35792526e+02 2.33470795e+02 2.23578827e+02 2.19903534e+02 2.19827179e+02 2.27111572e+02 2.27229218e+02 2.26726425e+02 2.25114258e+02 2.22728516e+02 2.26648712e+02 2.29042084e+02 2.34825500e+02 2.34037231e+02 2.31328171e+02 2.27330460e+02 2.22377014e+02 2.21523132e+02 2.24912003e+02 2.31186111e+02 2.33961899e+02 2.31172729e+02 2.26550125e+02 2.25549545e+02 2.28644089e+02 2.31439133e+02 2.30868790e+02 2.28618683e+02 2.28188034e+02 2.28448196e+02 2.28628845e+02 2.28538391e+02 2.28742157e+02 2.29574661e+02 2.30425720e+02 2.30854172e+02 2.31851013e+02 2.32380447e+02 2.30981155e+02 2.27717728e+02 2.26226929e+02 2.28806808e+02 2.32193649e+02 2.31329376e+02 2.25987808e+02 2.21051025e+02 2.22923599e+02 2.29727310e+02 2.32144623e+02 2.28959366e+02 2.22317184e+02 2.22890656e+02 2.29262909e+02 2.33530930e+02 2.38413040e+02 2.33113739e+02 2.35150421e+02 2.31439804e+02 2.31805328e+02 2.32445923e+02 2.35606598e+02 2.41377197e+02 2.37769257e+02 2.30827438e+02 2.21868271e+02 2.24625519e+02 2.34926025e+02 2.45540527e+02 2.38964828e+02 2.24475021e+02 2.14222137e+02 2.14836182e+02 2.24778381e+02 2.27888870e+02 2.29691208e+02 2.25078522e+02 2.29856003e+02 2.37198364e+02 2.46152740e+02 2.54274231e+02 2.51327484e+02 2.33911026e+02 2.20296234e+02 2.17454193e+02 2.25330048e+02 2.33224731e+02 2.45405869e+02 2.51165680e+02 2.34179413e+02 2.05757004e+02 1.95397446e+02 2.14009216e+02 2.39635864e+02 2.40525894e+02 2.15746552e+02 1.87858170e+02 1.91523636e+02 2.23511871e+02 2.55695755e+02 2.66647827e+02 2.46198441e+02 2.27529739e+02 2.29610107e+02 2.40460022e+02 2.48848663e+02 2.32182587e+02 2.31868729e+02 2.27028656e+02 2.16722992e+02 2.10584747e+02 2.11974533e+02 2.34386047e+02 2.30698273e+02 2.05759781e+02 1.75497772e+02 1.81917816e+02 2.25717560e+02 2.59583282e+02 2.45538483e+02 2.07015976e+02 1.77473541e+02 1.78687378e+02 2.13446777e+02 2.45619278e+02 2.61137512e+02 2.31909714e+02 2.16149460e+02 2.01650085e+02 2.03036377e+02 2.07092392e+02 2.00830521e+02 2.01427826e+02 1.79564972e+02 1.65386581e+02 1.63459274e+02 1.78394119e+02 2.14902939e+02 2.31250809e+02 2.08383194e+02 1.74121735e+02 1.61471237e+02 1.85360275e+02 2.19138107e+02 2.14663040e+02 1.90268417e+02 1.52239929e+02 1.47694412e+02 1.83768387e+02 2.20055984e+02 2.35870621e+02 2.06250137e+02 1.76464752e+02 1.78760468e+02 1.99585968e+02 2.32898239e+02 2.37166550e+02 2.32108398e+02 2.10447388e+02 1.79934753e+02 1.81625427e+02 2.11671631e+02 2.60384399e+02 2.75504364e+02 2.40715485e+02 1.98043900e+02 1.68184662e+02 1.88299576e+02 2.27052460e+02 2.46923691e+02 2.34372833e+02 2.03880814e+02 2.05458069e+02 2.27324142e+02 2.50139008e+02 2.48581009e+02 2.13429504e+02 1.85840454e+02 1.94197662e+02 2.16192291e+02 2.58779358e+02 2.54325821e+02 2.55910934e+02 2.36666611e+02 2.13362305e+02 1.98886032e+02 1.88178024e+02 2.20679123e+02 2.44890656e+02 2.30791992e+02 1.96367065e+02 1.64340836e+02 1.88380524e+02 2.28634644e+02 2.53943054e+02 2.14165024e+02 1.38775909e+02 1.03082787e+02 1.44253937e+02 2.21825485e+02 2.65611725e+02 2.37430359e+02 1.81749603e+02 1.38710510e+02 9.73696365e+01 5.51480064e+01 5.83873901e+01 7.62711945e+01 -1.38024060e+03 -2.90722925e+03 -7.72152734e+03 -1.68600625e+04 -382237856. -93150256. 159774448. 1627912. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.06372465e+10 -589859840. 59025448. 249763968. 142146384. -2.01766875e+04 -8.78452734e+03 -4.23833789e+03 -2.53446802e+03 -4.46829773e+02 -7.34166489e+01 -2.70117111e+01 9.41280174e+00 8.61959686e+01 1.93401154e+02 2.28485413e+02 2.00411667e+02 1.19425331e+02 7.76823578e+01 8.75672913e+01 1.51271561e+02 2.27219727e+02 2.27434402e+02 2.05804916e+02 1.81844147e+02 1.81382141e+02 1.74530533e+02 1.45028290e+02 1.81845749e+02 1.88590744e+02 1.25050545e+02 7.06089935e+01 1.09532738e+02 2.26992279e+02 2.90845490e+02 2.15258316e+02 1.20433884e+02 6.37197723e+01 9.22914200e+01 2.02297043e+02 2.87295776e+02 3.32340454e+02 2.40396927e+02 1.74230408e+02 1.62134109e+02 2.23319504e+02 2.64093414e+02 2.31567245e+02 2.24516708e+02 1.89510162e+02 1.48436096e+02 1.25050278e+02 1.59372223e+02 2.76559692e+02 2.86212189e+02 1.83195831e+02 5.68418922e+01 2.85149879e+01 1.29277161e+02 2.29235382e+02 2.29994080e+02 1.50023300e+02 1.17447136e+02 1.78787231e+02 2.95451843e+02 3.26908752e+02 2.88612946e+02 1.64894669e+02 7.32936096e+01 6.63227539e+01 1.45533798e+02 2.44822388e+02 3.14401245e+02 3.42393066e+02 3.18278839e+02 2.63010284e+02 1.94915527e+02 1.63373901e+02 1.78528702e+02 1.73713104e+02 9.76326675e+01 2.49240723e+01 2.44067802e+01 1.16443428e+02 1.80745514e+02 1.73470291e+02 1.36305267e+02 6.81274109e+01 2.10386181e+01 5.14926872e+01 1.53431824e+02 2.04373016e+02 1.44729065e+02 6.81559601e+01 8.52687836e+01 1.29891174e+02 1.47878448e+02 1.17537407e+02 1.41550751e+02 1.34659332e+02 9.05926132e+01 5.46567688e+01 8.54448547e+01 1.93010605e+02 2.01213654e+02 9.32014389e+01 -4.38864059e+01 -8.19513550e+01 1.18816853e+01 1.02165565e+02 1.46053925e+02 1.23218857e+02 9.47194443e+01 8.19315414e+01 1.16042999e+02 1.72247253e+02 2.02849670e+02 1.32925552e+02 2.69371910e+01 -8.13398743e+00 3.50508881e+01 7.43772964e+01 7.79702454e+01 1.19472061e+02 1.17207230e+02 3.32518616e+01 -7.70175171e+01 -6.41478043e+01 6.03652458e+01 1.15102715e+02 2.90958328e+01 -7.35014114e+01 -8.09610825e+01 2.41848660e+01 1.30119568e+02 1.61392776e+02 1.22462669e+02 3.59621811e+01 -3.48313293e+01 -1.95769253e+01 6.79492722e+01 1.35849152e+02 8.51251526e+01 -9.15378475e+00 -5.04463577e+01 -2.06607304e+01 3.30254974e+01 6.57686539e+01 1.24070198e+02 1.42050201e+02 1.13053238e+02 6.28929253e+01 5.87678070e+01 1.34254089e+02 1.64473740e+02 1.00618965e+02 -4.68200111e+01 -1.36545166e+02 -9.76294022e+01 4.34566269e+01 1.42361816e+02 1.25650879e+02 4.77311096e+01 1.64282036e+01 4.10471153e+01 4.89497681e+01 9.42111511e+01 6.97626190e+01 5.66124115e+01 1.27953281e+01 -5.40104103e+01 -7.85281067e+01 -1.01036644e+02 -5.54475129e-01 4.20991211e+01 -1.50294323e+01 -6.95192490e+01 -4.67781944e+01 8.79577637e+01 1.32447449e+02 1.00339767e+02 3.34999428e+01 -1.22277594e+01 -2.21896381e+01 1.45689545e+01 3.81042442e+01 4.66548004e+01 -2.20448246e+01 -4.01980019e+00 3.28753357e+01 9.94770737e+01 1.74800003e+02 2.26117249e+02 2.66655151e+02 1.91840805e+02 6.85826645e+01 -1.45216703e+00 5.84152102e-01 6.93937912e+01 7.85654526e+01 -7.53263855e+00 -1.08669510e+02 -1.43164291e+02 -2.73430347e+01 1.29083496e+02 1.96365906e+02 1.60523315e+02 8.70310593e+01 5.53641090e+01 6.42721863e+01 8.78936920e+01 1.32534698e+02 9.31219711e+01 3.13303394e+01 -1.63540668e+01 3.43605995e+01 5.66155930e+01 7.59765472e+01 1.04699608e+02 1.15308533e+02 7.55198441e+01 3.23267365e+01 4.27228165e+01 4.37135925e+01 9.71142673e+00 -5.51354332e+01 -8.70279770e+01 -1.03169785e+02 -5.78611794e+01 -2.30531902e+01 6.32567940e+01 9.29950790e+01 4.13357239e+01 -4.70004768e+01 -7.16302719e+01 -1.97473736e+01 2.35419579e+01 7.94618511e+00 -2.29189086e+00 -1.04262276e+01 -1.78463840e+01 -1.68273811e+01 -1.18391714e+01 -1.10247765e+01 -1.18232422e+01 -3.47246170e+01 -4.13606834e+01 -7.48994598e+01 -6.22387428e+01 -5.43145065e+01 -3.12084789e+01 -3.98609238e+01 -4.04429436e+01 -1.82512226e+01 -1.56317406e+01 1.40437710e+00 1.05158415e+01 2.31939831e+01 9.46066856e+00 -2.01411991e+01 -2.15601406e+01 -2.38775463e+01 -3.42112007e+01 -5.25342560e+01 -4.72361908e+01 -4.08601036e+01 -3.92606468e+01 -4.96023674e+01 -4.40952187e+01 -4.01900635e+01 -4.64985313e+01 -6.60059357e+01 -7.01380844e+01 -8.52031174e+01 -8.75321121e+01 -7.75702515e+01 -6.83169785e+01 -5.64763145e+01 -7.05643082e+01 -7.33450623e+01 -8.08000488e+01 -7.30896301e+01 -6.94195404e+01 -4.92188416e+01 -5.20697174e+01 -5.55636940e+01 -7.96488800e+01 -6.95263901e+01 -7.09825516e+01 -6.72073669e+01 -7.02370453e+01 -5.05616798e+01 -4.76482162e+01 -6.28845901e+01 -7.83654556e+01 -6.96674194e+01 -6.73846970e+01 -8.12660904e+01 -7.18295059e+01 -4.70043259e+01 -3.39026718e+01 -4.35348129e+01 -4.77878113e+01 -5.24736099e+01 -4.66083565e+01 -5.97890472e+01 -5.23587685e+01 -5.76229019e+01 -5.18759995e+01 -4.62949905e+01 -4.03055077e+01 -5.06685867e+01 -6.17447395e+01 -7.35377121e+01 -6.09444504e+01 -8.07756805e+01 -1.16078506e+02 -1.27561157e+02 -1.03581688e+02 -6.05663948e+01 -5.91919250e+01 -6.49966354e+01 -6.85336456e+01 -6.70922165e+01 -5.57501335e+01 -5.23277168e+01 -5.76403275e+01 -5.81772194e+01 -5.32634811e+01 -4.44253578e+01 -6.56355972e+01 -7.60220795e+01 -7.83223724e+01 -7.38926697e+01 -8.23099594e+01 -8.27380981e+01 -8.12778244e+01 -7.71282654e+01 -6.03261414e+01 -5.24885368e+01 -5.93329048e+01 -8.24687805e+01 -9.82680664e+01 -9.32548676e+01 -7.95816269e+01 -6.75724869e+01 -7.07012253e+01 -1.00475624e+02 -1.28947327e+02 -1.25468819e+02 -1.03538757e+02 -7.10643921e+01 -7.19720764e+01 -7.55375824e+01 -9.33106232e+01 -1.08085022e+02 -1.23005768e+02 -1.37700302e+02 -1.41389343e+02 -1.40604538e+02 -1.34327118e+02 -1.13997574e+02 -1.06260712e+02 -1.09550812e+02 -1.16659500e+02 -1.10134056e+02 -1.15045494e+02 -1.26879990e+02 -1.31055130e+02 -1.26989281e+02 -1.15731308e+02 -1.20822334e+02 -1.44787445e+02 -1.78601471e+02 -1.74299835e+02 -1.35334076e+02 -1.04687325e+02 -1.22593956e+02 -1.59202866e+02 -1.64065933e+02 -1.54095673e+02 -1.24735664e+02 -1.35052307e+02 -1.48766708e+02 -1.61076416e+02 -1.60072830e+02 -1.52687897e+02 -1.63857880e+02 -1.89227234e+02 -2.13554474e+02 -1.89013901e+02 -1.42415222e+02 -1.25897789e+02 -1.44755249e+02 -1.52746201e+02 -1.44585663e+02 -1.33468231e+02 -1.28595520e+02 -1.43150833e+02 -1.65784164e+02 -1.75037888e+02 -1.50913895e+02 -1.18311012e+02 -1.19708626e+02 -1.31805328e+02 -1.41635666e+02 -1.19282196e+02 -8.04837494e+01 -6.82665710e+01 -1.04578690e+02 -1.38750381e+02 -1.51045471e+02 -1.45084869e+02 -1.66161850e+02 -1.73925018e+02 -1.37518616e+02 -8.83114319e+01 -7.87940750e+01 -1.14102013e+02 -1.52021408e+02 -1.53861359e+02 -1.54304779e+02 -1.32719223e+02 -1.15820206e+02 -1.25671349e+02 -1.49248123e+02 -1.80135147e+02 -1.75023605e+02 -1.79143356e+02 -1.43628403e+02 -9.63749008e+01 -9.48934860e+01 -1.21067719e+02 -1.51517532e+02 -1.60632187e+02 -1.77658203e+02 -1.92101898e+02 -1.75118835e+02 -1.56691895e+02 -1.46751495e+02 -1.48257217e+02 -1.53971817e+02 -1.47240128e+02 -1.39825409e+02 -1.34072983e+02 -1.35392853e+02 -1.32591797e+02 -2.07184494e+02 -1.20177010e+02 -3.67939880e+02 -4.78040405e+02 -6.97223633e+02 -2.51575439e+03 -4.09828223e+03 -1.01045557e+04 -3.62242163e+03 -8.17192139e+03 -2.59109492e+04 -84643824. -169784160. 76916320. -100493344. 179656800. 60456676. -701517568. 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. 0. 0. -1133359616. -1133359616. -1133359616. 0. 0. 466143744. 180400144. 93516384. -1.93080703e+04 -9.08322461e+03 -1.81823669e+03 -1.31062341e+03 -3.37692554e+03 -2.14565161e+03 -4.98082336e+02 -2.78414032e+02 -2.24804428e+02 -2.33188339e+02 -2.34575226e+02 -2.32169861e+02 -2.25427032e+02 -2.30666946e+02 -2.36454514e+02 -2.38976135e+02 -2.35570267e+02 -2.18432358e+02 -2.10641357e+02 -2.14458359e+02 -2.31616821e+02 -2.31738968e+02 -2.18937943e+02 -1.97859192e+02 -1.93286392e+02 -1.90366760e+02 -1.86276764e+02 -1.81992584e+02 -1.78552444e+02 -1.77396072e+02 -1.75129669e+02 -1.74214966e+02 -1.73598953e+02 -1.75456955e+02 -1.81028091e+02 -1.79515930e+02 -1.80151123e+02 -1.76314499e+02 -1.85447922e+02 -1.87693359e+02 -1.85453156e+02 -1.78802612e+02 -1.76570251e+02 -1.76559418e+02 -1.79143234e+02 -1.85607056e+02 -2.03791595e+02 -2.18625443e+02 -2.22083466e+02 -2.14198364e+02 -2.03778107e+02 -1.98425980e+02 -1.92976532e+02 -1.97870377e+02 -2.06927414e+02 -2.07647568e+02 -2.01583466e+02 -1.94728653e+02 -1.95535965e+02 -1.90544342e+02 -1.97051575e+02 -2.07507706e+02 -2.14668701e+02 -2.20783936e+02 -2.22684860e+02 -2.23983917e+02 -2.18434311e+02 -2.14120911e+02 -2.16077087e+02 -2.15935883e+02 -2.04307129e+02 -2.00006546e+02 -2.01780670e+02 -2.10735779e+02 -2.12696442e+02 -2.09802246e+02 -2.20209457e+02 -2.35732773e+02 -2.34810455e+02 -2.28963379e+02 -2.20015030e+02 -2.39087769e+02 -2.53498077e+02 -2.55136841e+02 -2.42071075e+02 -2.34154205e+02 -2.35090698e+02 -2.36719193e+02 -2.31035767e+02 -2.31552322e+02 -2.41799637e+02 -2.53491119e+02 -2.49275253e+02 -2.34956589e+02 -2.22729523e+02 -2.18930466e+02 -2.21484344e+02 -2.24226151e+02 -2.28224472e+02 -2.19121841e+02 -2.11284271e+02 -2.15732590e+02 -2.26365952e+02 -2.28186646e+02 -2.20256104e+02 -2.15279678e+02 -2.26681839e+02 -2.34851761e+02 -2.34510361e+02 -2.24373154e+02 -2.15260361e+02 -2.13988724e+02 -2.14675537e+02 -2.16610260e+02 -2.18294220e+02 -2.20879990e+02 -2.21164093e+02 -2.21309067e+02 -2.22647659e+02 -2.24697876e+02 -2.26309525e+02 -2.25467834e+02 -2.24230865e+02 -2.23788849e+02 -2.24181824e+02 -2.24680984e+02 -2.30761520e+02 -2.37205505e+02 -2.37070938e+02 -2.31848648e+02 -2.26520157e+02 -2.32807358e+02 -2.38851761e+02 -2.38796463e+02 -2.33864182e+02 -2.29837326e+02 -2.29864792e+02 -2.28624115e+02 -2.26143112e+02 -2.26942535e+02 -2.28303772e+02 -2.28675964e+02 -2.26932632e+02 -2.24502792e+02 -2.24640198e+02 -2.26153488e+02 -2.28717529e+02 -2.28852173e+02 -2.29396988e+02 -2.29049088e+02 -2.30219498e+02 -2.33537766e+02 -2.36986496e+02 -2.36817200e+02 -2.33979248e+02 -2.30591110e+02 -2.32431763e+02 -2.34266159e+02 -2.34003433e+02 -2.31219299e+02 -2.29145264e+02 -2.29245590e+02 -2.29398254e+02 -2.29429718e+02 -2.29287949e+02 -2.29382004e+02 -2.29240601e+02 -2.29067490e+02 -2.28878723e+02 -2.29297836e+02 -2.29501480e+02 -2.29265778e+02 -2.28832550e+02 -2.28632919e+02 -2.28632812e+02 -2.28647949e+02 -2.28455460e+02 -2.28021362e+02 -2.27767502e+02 -2.27883255e+02 -2.28239029e+02 -2.28243225e+02 -2.28668457e+02 -2.27744476e+02 -2.25847183e+02 -2.25095657e+02 -2.26243515e+02 -2.27848648e+02 -2.27482452e+02 -2.26962387e+02 -2.27298431e+02 -2.27445648e+02 -2.26493408e+02 -2.26111313e+02 -2.23054367e+02 -2.20123489e+02 -2.19695007e+02 -2.22790573e+02 -2.25950333e+02 -2.24299088e+02 -2.23987610e+02 -2.20748825e+02 -2.17957489e+02 -2.18239532e+02 -2.23335953e+02 -2.28172409e+02 -2.27385696e+02 -2.26157074e+02 -2.24836182e+02 -2.25994858e+02 -2.26969559e+02 -2.28303070e+02 -2.28688263e+02 -2.27487137e+02 -2.26793350e+02 -2.27013397e+02 -2.26633041e+02 -2.29559570e+02 -2.31334793e+02 -2.33969208e+02 -2.34027084e+02 -2.31793686e+02 -2.31440933e+02 -2.31504593e+02 -2.31634247e+02 -2.29932999e+02 -2.28882675e+02 -2.30488419e+02 -2.28657898e+02 -2.27786026e+02 -2.27771988e+02 -2.31618240e+02 -2.32575653e+02 -2.30639908e+02 -2.28386353e+02 -2.26811111e+02 -2.27619186e+02 -2.25155823e+02 -2.25370010e+02 -2.21111526e+02 -2.20401199e+02 -2.20069611e+02 -2.26377487e+02 -2.34428284e+02 -2.29819580e+02 -2.16840378e+02 -2.06674789e+02 -2.09363312e+02 -2.15305527e+02 -2.17761749e+02 -2.14514664e+02 -2.12228210e+02 -2.09240463e+02 -2.10410080e+02 -2.11886276e+02 -2.13897507e+02 -2.17896820e+02 -2.21912415e+02 -2.23899643e+02 -2.20259232e+02 -2.15266937e+02 -2.10707855e+02 -2.10909439e+02 -2.13574844e+02 -2.16215378e+02 -2.19093979e+02 -2.19554337e+02 -2.19744339e+02 -2.14307877e+02 -2.02352737e+02 -1.91645813e+02 -1.90218002e+02 -1.97571625e+02 -2.07997131e+02 -2.12316422e+02 -2.12017685e+02 -2.04262207e+02 -1.93632111e+02 -1.87682373e+02 -1.84156006e+02 -1.92866180e+02 -2.00825485e+02 -2.14089676e+02 -2.10951141e+02 -2.08429901e+02 -2.07853256e+02 -2.12659134e+02 -2.14496414e+02 -2.17237183e+02 -2.13561035e+02 -2.08976700e+02 -2.01796936e+02 -1.97217300e+02 -1.96028030e+02 -1.81724564e+02 -1.69472900e+02 -1.74288879e+02 -1.92869278e+02 -2.08332092e+02 -1.99308853e+02 -1.90166504e+02 -193. -1.96913971e+02 -1.87357071e+02 -1.68595032e+02 -1.67540161e+02 -1.83368347e+02 -2.02590988e+02 -1.95222672e+02 -1.90441406e+02 -1.93172180e+02 -2.03370590e+02 -2.05269943e+02 -2.01493378e+02 -1.98143799e+02 -2.04831390e+02 -2.16596085e+02 -2.16411911e+02 -2.13099167e+02 -2.05992615e+02 -2.08644180e+02 -1.95383850e+02 -1.80000931e+02 -1.72040359e+02 -1.64771225e+02 -1.50649368e+02 -1.33926514e+02 -1.29564270e+02 -1.41275757e+02 -1.43266846e+02 -1.55020798e+02 -1.55615479e+02 -1.73342514e+02 -1.98695679e+02 -2.28700043e+02 -2.34164459e+02 -2.23466858e+02 -2.14176331e+02 -2.09885559e+02 -2.07318710e+02 -2.01699402e+02 -2.03334213e+02 -2.08242310e+02 -1.93223480e+02 -1.66122803e+02 -1.55837494e+02 -1.60297180e+02 -1.78586090e+02 -1.82326218e+02 -1.84998138e+02 -1.95926178e+02 -1.79769257e+02 -1.74059067e+02 -1.65581863e+02 -1.67053116e+02 -1.54939056e+02 -1.31295258e+02 -1.43150894e+02 -1.66416397e+02 -1.76978943e+02 -1.49715363e+02 -1.41746445e+02 -1.52782547e+02 -1.80826157e+02 -1.59244858e+02 -1.37671906e+02 -1.28927780e+02 -1.42685501e+02 -1.59852448e+02 -1.33967789e+02 -1.11063828e+02 -1.14618835e+02 -1.44500183e+02 -1.70152115e+02 -1.48914886e+02 -1.34804123e+02 -1.57893341e+02 -1.94251495e+02 -1.77355301e+02 -1.36198837e+02 -1.13897995e+02 -1.20596977e+02 -1.32882507e+02 -1.34300873e+02 -1.13629349e+02 -9.07527084e+01 -9.48878555e+01 -1.37075729e+02 -1.66781006e+02 -1.65954895e+02 -1.56135910e+02 -1.54732910e+02 -1.58200027e+02 -1.61186234e+02 -1.60037872e+02 -1.48102646e+02 -1.44838699e+02 -1.57817917e+02 -1.59442047e+02 -1.54202820e+02 -1.27200531e+02 -1.12905724e+02 -1.20506454e+02 -1.28367477e+02 -1.45452011e+02 -1.43509979e+02 -1.46223877e+02 -1.55407181e+02 -1.65027634e+02 -1.61979843e+02 -1.15680069e+02 -7.86716766e+01 -1.15348976e+02 -1.81655670e+02 -1.86497894e+02 -1.26063118e+02 -1.05251740e+02 -1.37662399e+02 -1.59573944e+02 -1.36327637e+02 -1.18053345e+02 -1.20274796e+02 -1.43514877e+02 -1.29198212e+02 -1.19967194e+02 -1.12577606e+02 -1.30724808e+02 -1.53706223e+02 -1.47157410e+02 -1.44735733e+02 -1.14423607e+02 -9.41745682e+01 -8.68814011e+01 -1.17979691e+02 -1.17482483e+02 -6.44934464e+01 -2.58529263e+01 -4.86962166e+01 -9.79736023e+01 -9.71192245e+01 -7.15087433e+01 -9.66108704e+01 -1.55145340e+02 -1.81829178e+02 -1.49675125e+02 -1.19881897e+02 -1.17943245e+02 -1.20784363e+02 -1.02929764e+02 -1.00145424e+02 -1.01414055e+02 -1.12623840e+02 -1.23587021e+02 -1.37871460e+02 -1.44722092e+02 -1.38000473e+02 -1.22096260e+02 -9.92507172e+01 -8.93293991e+01 -8.63849487e+01 -7.42919006e+01 -7.07889938e+01 -8.44006958e+01 -1.08079445e+02 -1.01071846e+02 -6.40747604e+01 -5.51532745e+01 -6.39856529e+01 -4.81249771e+01 6.88500834e+00 3.97421112e+01 8.90965748e+00 -5.53801193e+01 -6.78577881e+01 -5.31705208e+01 -4.86595802e+01 -7.92290649e+01 -1.02507408e+02 -1.10179733e+02 -1.11846199e+02 -1.17654724e+02 -1.02461388e+02 -1.06044357e+02 -1.14755356e+02 -1.15916016e+02 -6.35524406e+01 -3.30872688e+01 -6.58832626e+01 -9.55173340e+01 -5.59910393e+01 -2.01758423e+01 -5.56438560e+01 -1.29613800e+02 -1.75493637e+02 -1.68721069e+02 -1.59894897e+02 -1.38241898e+02 -1.36427979e+02 -1.30754379e+02 -1.41178024e+02 -1.18566528e+02 -1.10067566e+02 -1.02663170e+02 -1.33294403e+02 -1.03743919e+02 -3.76386452e+01 1.33752937e+01 2.23557911e+01 7.83926773e+00 -1.46939383e+01 -4.09408607e+01 -7.40657806e+01 -7.22140884e+01 -8.03624115e+01 -7.78149338e+01 -8.11994019e+01 -6.88690338e+01 -7.54690323e+01 -7.40068130e+01 -7.01912155e+01 -7.53312378e+01 -7.35541992e+01 -8.28928223e+01 -3.18328667e+01 1.10161600e+01 1.76400833e+01 -2.45018482e+01 -5.59628525e+01 -4.66024170e+01 -4.19540825e+01 -4.13205414e+01 -4.65883484e+01 -4.45153770e+01 -4.51489296e+01 -1.92171249e+01 1.56581287e+01 3.02383661e+00 -3.78127327e+01 -4.39967842e+01 2.83288422e+01 7.62090149e+01 4.08703346e+01 -2.75898590e+01 -3.04687538e+01 6.15630913e+00 5.04284811e+00 -1.76387520e+01 -4.92768135e+01 -1.19593744e+01 1.89970894e+01 4.54586143e+01 6.25085487e+01 1.82646675e+01 -8.11652756e+00 -1.19363203e+01 6.62561340e+01 9.68729401e+01 4.03989258e+01 -2.91561203e+01 -1.39671535e+01 4.94913177e+01 6.17609596e+01 3.00048599e+01 -8.87591934e+00 2.10129204e+01 5.64579124e+01 7.44780273e+01 5.01100540e+01 1.92101421e+01 2.33337092e+00 4.08713989e+01 8.23964615e+01 9.56488342e+01 6.02707863e+01 1.32466996e+00 2.65316639e+01 5.78919449e+01 6.29466133e+01 2.62202606e+01 2.81370945e+01 7.44591904e+01 6.59056854e+01 2.14622726e+01 -2.93050175e+01 -3.52119980e+01 -3.95472183e+01 -4.37833786e+00 3.83629608e+01 6.41146927e+01 4.18057861e+01 7.37052441e+00 -7.01336622e+00 -5.34921765e-01 2.75678005e+01 6.74022446e+01 2.11523483e+02 3.34201874e+02 2.18791718e+02 3.36946564e+02 5.82100830e+02 6.54139343e+02 7.27754578e+02 3.94476685e+02 3.02642609e+02 2.80897974e+03 4.15544629e+03 -1.44161536e+03 6.09277930e+03 1.87852402e+04 16086440. 2.50198897e+10 0. 0. 0. 0. -3.88826496e+09 -3.88826496e+09 -17269332. 2.82984243e+09 7.00192109e+04 6.69585438e+05 1.04387962e+06 2.31803575e+06 -3.29552650e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.37251052e+10 -4.24189250e+06 9.54083008e+03 1.61088757e+03 -2.88534302e+03 2.73519745e+02 1.18816357e+03 -4.23493164e+03 -3.25687891e+03 -7.38516541e+02 -6.96857849e+02 -1.88169846e+02 -1.35752344e+01 1.08661331e+02 1.13466080e+02 3.16553078e+01 1.17180462e+01 5.17071228e+01 2.57614765e+01 -5.26258392e+01 -1.18557007e+02 -4.63404694e+01 1.01046684e+02 1.70225266e+02 1.23306374e+02 2.12008266e+01 -2.52251434e+01 -3.85802579e+00 2.31663418e+01 -4.17670250e+00 -5.32311401e+01 -2.18342609e+01 5.01847992e+01 9.32353210e+01 6.72860107e+01 -3.82701445e+00 -2.31758404e+01 3.33189201e+01 1.30068634e+02 1.69242645e+02 1.29158234e+02 1.21937988e+02 1.64070328e+02 1.38635803e+02 4.20872192e+01 -3.63988686e+01 3.50111580e+01 2.09210068e+02 2.49718552e+02 1.68677505e+02 7.24070511e+01 2.72983494e+01 3.66997070e+01 5.68615379e+01 6.93763809e+01 4.49059677e+01 5.22559586e+01 1.63357254e+02 2.42204758e+02 2.17337967e+02 1.17070656e+02 5.63800049e+01 8.86707077e+01 1.44566208e+02 1.76584320e+02 1.26589653e+02 1.21015564e+02 1.44472061e+02 1.14625061e+02 3.93475494e+01 -4.43323975e+01 -3.29833794e+01 8.59837646e+01 1.35794189e+02 1.03783180e+02 2.14155197e+01 3.75379944e+01 1.13291840e+02 9.32810898e+01 4.41025581e+01 1.12642574e+01 5.52315102e+01 1.60381058e+02 1.99904922e+02 1.73162521e+02 6.36213303e+01 -1.23270869e+00 1.89316711e+01 6.87097778e+01 7.29608536e+01 2.10245399e+01 2.17883568e+01 8.42726212e+01 1.16671539e+02 6.09117851e+01 -3.47080879e+01 -4.14198952e+01 4.76830902e+01 1.37449554e+02 1.39289200e+02 7.77240829e+01 6.05505257e+01 8.02092590e+01 4.43956909e+01 -3.14647160e+01 -7.52952805e+01 -1.38797677e+00 1.15120499e+02 1.83976440e+02 1.48796494e+02 8.15710449e+01 -5.43361330e+00 -4.85370140e+01 -3.59465981e+01 -9.46242142e+00 -1.82821789e+01 -5.44452572e+00 7.00904846e+01 1.45597687e+02 1.07740829e+02 -1.39676199e+01 -5.93788414e+01 -3.28182530e+00 1.14958107e+02 1.65782700e+02 1.09410324e+02 5.89779091e+01 4.38135452e+01 6.27106323e+01 2.06883698e+01 -6.44055252e+01 -5.96696434e+01 3.30056725e+01 1.11813049e+02 1.09338310e+02 4.77550240e+01 9.75688744e+00 1.15209162e+00 2.60812225e+01 6.86688995e+01 9.04662628e+01 3.80969772e+01 1.78554382e+01 6.30041122e+01 1.00258034e+02 1.05141563e+02 7.77127991e+01 7.89063034e+01 1.19963112e+02 1.16764648e+02 8.13304672e+01 3.64870148e+01 2.00981579e+01 6.96964874e+01 9.18163300e+01 7.66464157e+01 4.30081558e+01 7.37306671e+01 1.92943314e+02 2.44040176e+02 1.82136490e+02 7.98020782e+01 6.10710449e+01 1.11019707e+02 1.40772415e+02 1.33772049e+02 1.37873734e+02 1.76398621e+02 2.27003784e+02 2.37900803e+02 2.14613312e+02 1.44856583e+02 9.57001266e+01 1.31891541e+02 1.62176010e+02 1.52921814e+02 1.10371117e+02 1.36509552e+02 2.23652451e+02 2.12434494e+02 1.76082413e+02 1.43231522e+02 1.88717834e+02 2.83505280e+02 3.23703491e+02 2.75581238e+02 1.82958939e+02 1.26664185e+02 1.40723389e+02 1.25116501e+02 1.06382294e+02 1.19657997e+02 1.79921097e+02 2.51701263e+02 2.43439667e+02 1.90543411e+02 9.17893524e+01 4.68366356e+01 7.46050339e+01 1.45618240e+02 1.98680969e+02 2.01788971e+02 2.14545715e+02 2.41968582e+02 2.21154312e+02 1.67987656e+02 1.02014328e+02 1.38995972e+02 2.25058304e+02 2.60992828e+02 2.13182785e+02 1.11457886e+02 8.68712921e+01 1.25951912e+02 1.87569321e+02 1.64302567e+02 1.19268379e+02 1.23674309e+02 1.79992233e+02 1.99856094e+02 1.44940567e+02 6.61701660e+01 6.04874077e+01 9.96314697e+01 1.40978409e+02 1.37814560e+02 1.20183823e+02 1.22869118e+02 1.45331848e+02 1.26194649e+02 9.80838470e+01 8.96564865e+01 1.00405083e+02 1.46303116e+02 1.59463928e+02 1.52545197e+02 1.49428253e+02 1.47511444e+02 1.77443741e+02 1.44932968e+02 1.11688431e+02 8.65305710e+01 1.07204605e+02 1.86934311e+02 2.41859680e+02 2.31851379e+02 1.43884338e+02 9.24746704e+01 9.21955643e+01 1.30275146e+02 1.53169861e+02 1.27218575e+02 1.23223984e+02 1.43494492e+02 1.64612564e+02 1.43913742e+02 1.26421196e+02 1.69155624e+02 2.24351746e+02 2.12064240e+02 1.82773926e+02 1.64897583e+02 1.79768524e+02 2.11213760e+02 1.75000122e+02 1.50510773e+02 1.22192429e+02 1.42539139e+02 1.88872559e+02 2.14001572e+02 2.31105759e+02 1.94406967e+02 1.73513916e+02 1.67514481e+02 1.95365952e+02 2.00160629e+02 1.95306427e+02 2.05214630e+02 2.26752960e+02 2.36913605e+02 1.94339417e+02 1.68607605e+02 1.70618301e+02 2.03085541e+02 1.94751328e+02 1.77411255e+02 1.60127502e+02 1.50045868e+02 1.58847321e+02 1.54866989e+02 1.89879547e+02 2.02410126e+02 2.16586441e+02 2.11656525e+02 2.00842255e+02 1.89579880e+02 1.54364014e+02 1.41153122e+02 1.47463989e+02 1.96902695e+02 2.06572281e+02 1.98539856e+02 1.82850510e+02 1.93500412e+02 1.81095901e+02 1.38291763e+02 1.16089775e+02 1.34946716e+02 1.90766632e+02 2.04926453e+02 1.86690079e+02 1.55756790e+02 1.49044479e+02 1.77923447e+02 1.81350616e+02 1.85293610e+02 1.53320129e+02 1.43638885e+02 1.38881546e+02 1.67323303e+02 1.76777542e+02 1.62741837e+02 1.42853302e+02 1.56843597e+02 1.87033051e+02 1.75413773e+02 1.58448074e+02 1.58782532e+02 1.76477692e+02 1.76921158e+02 1.49086914e+02 1.36867172e+02 1.46610992e+02 1.81767776e+02 1.80882248e+02 1.71058945e+02 1.54136017e+02 1.63274399e+02 1.79003586e+02 1.76514633e+02 1.81194061e+02 1.64590225e+02 1.60743774e+02 1.57742050e+02 1.70347534e+02 1.73755264e+02 1.64858704e+02 1.53406876e+02 1.61859924e+02 1.83580460e+02 1.90075500e+02 1.91816437e+02 1.98295090e+02 2.16505157e+02 2.09629593e+02 1.90566330e+02 1.88645920e+02 2.01297775e+02 2.16888397e+02 1.98802704e+02 1.89645981e+02 1.80864182e+02 1.69749481e+02 1.66790359e+02 1.77218628e+02 2.05459824e+02 2.11396927e+02 1.93651581e+02 1.73698166e+02 1.83701340e+02 2.05203262e+02 2.19076599e+02 2.05235718e+02 1.94280685e+02 1.97178940e+02 2.02324997e+02 2.11694473e+02 2.22742828e+02 2.37975372e+02 2.31978745e+02 2.16009094e+02 2.11571823e+02 2.17199203e+02 2.26183914e+02 2.08381348e+02 2.01200638e+02 1.95502258e+02 1.98342682e+02 1.98967239e+02 2.06767365e+02 2.26473389e+02 2.32151016e+02 2.16831085e+02 1.91632355e+02 1.83225174e+02 2.03304138e+02 2.21678192e+02 2.22508514e+02 2.09449158e+02 2.00788635e+02 2.05012924e+02 2.15911407e+02 2.21101776e+02 2.15660767e+02 1.99268234e+02 1.96264069e+02 2.03427658e+02 2.13160385e+02 2.22970688e+02 2.21425903e+02 2.16744049e+02 2.04559372e+02 1.92847687e+02 1.88221634e+02 1.95148605e+02 2.09427521e+02 2.16095230e+02 2.09073227e+02 1.99646286e+02 2.00124939e+02 2.08708221e+02 2.15673096e+02 2.12060379e+02 2.03851807e+02 1.98008804e+02 1.97722809e+02 2.01836060e+02 2.04898056e+02 2.06955048e+02 2.03598038e+02 2.01901642e+02 2.00391205e+02 2.01711868e+02 2.02334518e+02 2.01130936e+02 1.99701675e+02 1.98747482e+02 1.99007233e+02 1.99742722e+02 2.00180573e+02 2.00133057e+02 1.99593033e+02 1.99580856e+02 2.01027527e+02 2.02440933e+02 2.01551987e+02 1.98497604e+02 1.96221878e+02 1.96881943e+02 1.98642990e+02 1.98375412e+02 1.96063416e+02 1.94679688e+02 1.94014175e+02 1.97398376e+02 1.99457138e+02 2.02723587e+02 2.02964844e+02 2.00114990e+02 1.96859299e+02 1.92473175e+02 1.93855225e+02 1.97149231e+02 2.02555984e+02 2.02388458e+02 1.97470047e+02 1.90078033e+02 1.92914215e+02 1.98843674e+02 2.02993744e+02 1.96850967e+02 1.86278091e+02 1.85755371e+02 1.93636459e+02 2.08127365e+02 2.07844986e+02 1.96415283e+02 1.86266388e+02 1.80635651e+02 1.92735428e+02 1.97065826e+02 2.01618378e+02 2.01129501e+02 2.01696167e+02 2.01933197e+02 1.95767944e+02 1.99921127e+02 2.05492950e+02 2.03206787e+02 1.93335022e+02 1.75521545e+02 1.70164047e+02 1.81140244e+02 2.07577515e+02 2.28845444e+02 2.25529373e+02 2.00081039e+02 1.73732376e+02 1.64103714e+02 1.84267151e+02 2.06640762e+02 2.11210083e+02 1.94124451e+02 1.74037186e+02 1.79584061e+02 1.94269394e+02 2.11641830e+02 2.14716904e+02 2.09275711e+02 1.93334579e+02 1.75380051e+02 1.76340042e+02 1.95348190e+02 2.22253143e+02 2.29021301e+02 2.05212021e+02 1.79732224e+02 1.81273407e+02 2.04590805e+02 2.18236435e+02 2.10519882e+02 1.97163910e+02 1.91028580e+02 1.85382706e+02 1.91824554e+02 2.00144897e+02 1.92048782e+02 1.89972748e+02 1.78178085e+02 1.92043106e+02 2.01904358e+02 2.20781250e+02 2.29824585e+02 2.17350006e+02 1.99462448e+02 1.73258987e+02 1.61825226e+02 1.76622559e+02 2.04426086e+02 2.09209213e+02 1.81137299e+02 1.46825012e+02 1.49965714e+02 1.71335754e+02 2.06648148e+02 2.14082321e+02 2.00018845e+02 1.82394608e+02 1.76897720e+02 2.06380005e+02 2.30515610e+02 2.51852341e+02 2.43644470e+02 2.09627884e+02 2.09621796e+02 2.21981842e+02 2.54888031e+02 2.60356384e+02 2.50085373e+02 2.25325607e+02 1.79805878e+02 1.58188446e+02 1.67727692e+02 2.03558060e+02 2.24886963e+02 1.95935760e+02 1.57704285e+02 1.57276306e+02 2.00074005e+02 2.33930893e+02 2.21061356e+02 1.79471603e+02 1.44992783e+02 1.39461182e+02 1.76868439e+02 2.20532349e+02 2.31222290e+02 2.24388351e+02 2.07976196e+02 1.93417297e+02 1.68611954e+02 1.64958786e+02 1.76178421e+02 1.88081772e+02 1.69985428e+02 1.30271835e+02 1.03730766e+02 1.36406952e+02 1.90147583e+02 2.18889404e+02 1.93321121e+02 1.38031006e+02 1.29104752e+02 1.53406021e+02 2.03654037e+02 2.07449356e+02 1.76316177e+02 1.61105621e+02 1.58201538e+02 1.92748398e+02 2.01489075e+02 1.94107162e+02 1.79016556e+02 1.49734390e+02 1.56580856e+02 1.60921860e+02 2.05067368e+02 2.39790695e+02 2.30734451e+02 2.01822998e+02 1.53778671e+02 1.18190590e+02 1.16601891e+02 1.55511032e+02 2.41503128e+02 2.60951691e+02 2.42132370e+02 2.94320892e+02 6.08699524e+02 4.51857861e+03 9.98805273e+03 68677808. -338659552. 201786704. -245724176. 362859104. -2.41568486e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 1.06372465e+10 -589859840. 59025448. 249763968. 142146384. -2.01766875e+04 -8.78452734e+03 -4.12454346e+02 3.62422412e+03 2.53368359e+03 4.88218933e+02 2.53980347e+02 1.80925552e+02 1.70274643e+02 2.14122986e+02 2.13674942e+02 1.81017029e+02 7.96544647e+01 8.19546890e+01 1.26518089e+02 1.96945587e+02 1.78208099e+02 9.84224930e+01 3.87466202e+01 3.26557770e+01 9.46642685e+01 1.88214462e+02 2.06000412e+02 1.42835785e+02 5.98550377e+01 5.91531143e+01 1.16052452e+02 1.19986237e+02 7.42091064e+01 5.71096077e+01 9.09911118e+01 1.36498199e+02 1.38324127e+02 1.53162964e+02 1.78313614e+02 1.78882004e+02 1.27521706e+02 2.93391972e+01 1.79038239e+01 8.00624695e+01 1.35640991e+02 1.35859543e+02 6.92752762e+01 5.07370853e+00 1.41601458e+01 1.10787422e+02 2.20609283e+02 2.10510559e+02 1.00759987e+02 4.27130661e+01 3.07627792e+01 9.55960922e+01 1.15175819e+02 1.22035477e+02 1.31158234e+02 1.14585831e+02 9.12341995e+01 3.42572441e+01 5.68814926e+01 1.12498238e+02 1.23175293e+02 8.12691803e+01 1.34105444e+00 1.58313513e+00 4.06432037e+01 1.02061752e+02 1.30019272e+02 6.33655777e+01 -2.79741592e+01 -1.00829483e+02 -5.74995956e+01 4.35858688e+01 7.88738022e+01 1.22543335e+01 -3.46547470e+01 -2.57108746e+01 7.18601303e+01 9.03085785e+01 6.25569153e+01 1.50823126e+01 2.17884903e+01 1.72424393e+01 -8.57728481e+00 3.09856262e+01 9.91946564e+01 1.34041245e+02 5.28282013e+01 -5.24723244e+01 -7.99921570e+01 -4.06659126e+01 1.64064960e+01 8.06436462e+01 8.90732803e+01 4.25937347e+01 -1.13673887e+01 4.30122423e+00 9.93867722e+01 1.44012360e+02 5.35201683e+01 -1.48186092e+01 -2.02054367e+01 9.42673416e+01 1.38707520e+02 1.25000305e+02 1.07284592e+02 9.07033539e+01 5.49382401e+01 -2.80751495e+01 -2.76759377e+01 4.38223801e+01 1.04134827e+02 9.64733429e+01 2.63354015e+01 9.99214268e+00 5.72572212e+01 9.40942917e+01 1.39848022e+02 1.19853989e+02 4.53722496e+01 -3.41348381e+01 -5.66376610e+01 5.38603325e+01 1.09285774e+02 6.43693619e+01 3.00809517e+01 2.44612808e+01 8.10467911e+01 7.34289398e+01 6.23206787e+01 8.88490829e+01 1.08958687e+02 9.29254532e+01 4.26072550e+00 -8.47285366e+00 6.06389427e+01 1.06250389e+02 1.05901817e+02 3.33414345e+01 4.76068268e+01 9.96145630e+01 1.43357574e+02 1.74323517e+02 1.25238136e+02 3.98826180e+01 -2.95687485e+01 -2.37081490e+01 4.85234642e+01 6.33596954e+01 4.08394852e+01 4.47234421e+01 6.77557144e+01 1.19005646e+02 1.47857956e+02 1.64023788e+02 1.70291016e+02 1.32730286e+02 6.79920120e+01 -1.44382229e+01 -3.50560951e+01 -6.25448608e+00 3.70313988e+01 2.82582932e+01 -3.16717243e+01 -9.79741135e+01 -5.43891525e+01 4.78663673e+01 1.36288712e+02 1.30254715e+02 2.61435566e+01 -3.19774570e+01 -3.98352814e+01 2.45387154e+01 3.55588684e+01 2.19578915e+01 2.81432686e+01 1.13807745e+01 -1.01858587e+01 -1.14357576e+01 5.08136635e+01 1.22932220e+02 1.23333748e+02 9.37046661e+01 3.36865921e+01 -1.47717075e+01 -2.91318035e+01 -1.14748325e+01 7.88283873e+00 -5.16873703e+01 -1.19718925e+02 -9.54207611e+01 6.57994080e+00 1.06596352e+02 1.14767914e+02 3.99105568e+01 1.72920399e+01 4.88860607e+00 7.66530151e+01 6.14712105e+01 1.41487713e+01 -6.28151474e+01 -1.08621376e+02 -1.16744652e+02 -1.63471558e+02 -1.34191483e+02 -4.74378319e+01 2.87275505e+01 2.39637356e+01 -6.45749130e+01 -7.96769791e+01 -1.67315388e+01 6.23872528e+01 1.35830582e+02 8.91161804e+01 -2.64902287e+01 -1.33103027e+02 -1.02407860e+02 6.35825729e+00 2.94983482e+01 -2.14969406e+01 -4.21123657e+01 -4.49353714e+01 2.79395938e+00 3.60645905e+01 5.35461540e+01 4.18789330e+01 2.34599667e+01 -1.33976183e+01 -8.31220016e+01 -1.17418900e+02 -8.56458817e+01 -4.24202309e+01 -3.30871658e+01 -3.97796745e+01 -8.62883377e+00 3.35361710e+01 5.21521759e+01 3.43917503e+01 -1.11106634e+01 -3.35892944e+01 -4.58428917e+01 -2.85494823e+01 6.54501629e+00 2.10445900e+01 7.96106482e+00 -3.27837105e+01 -4.60557709e+01 -3.03715496e+01 -2.19402719e+00 1.01129651e+00 -1.66097355e+01 -3.72036972e+01 -3.42691612e+01 -2.07334595e+01 -1.18334398e+01 -4.24308872e+00 -6.25247812e+00 9.69208527e+00 -6.58753932e-01 -7.93987703e+00 -2.95957813e+01 -1.62766132e+01 -6.52803278e+00 -8.92891026e+00 -1.97777042e+01 -1.83266048e+01 -3.30384922e+00 -1.84736538e+00 -1.73047757e+00 7.31679487e+00 -4.32954311e+00 -2.98238430e+01 -3.87008095e+01 -1.48050003e+01 -3.81720066e+00 -1.47389412e+01 -2.07304649e+01 -1.07624054e+01 -3.71277547e+00 -8.33362293e+00 -1.21470718e+01 -1.89526691e+01 -2.46147060e+01 -2.88181705e+01 -1.88721409e+01 -2.03376122e+01 4.98819858e-01 -3.73660326e+00 -6.97425175e+00 -2.92463207e+01 -1.87595406e+01 -1.72809544e+01 -1.65277882e+01 -4.84817810e+01 -6.71811752e+01 -7.48854675e+01 -5.18294144e+01 -3.21396675e+01 -2.24506950e+01 -2.67880764e+01 -3.64945068e+01 -5.11242447e+01 -6.38456573e+01 -4.87517624e+01 -4.70837822e+01 -4.17510529e+01 -4.39691734e+01 -3.13900604e+01 -3.16733780e+01 -4.05323486e+01 -4.78183136e+01 -4.22270279e+01 -5.33119431e+01 -7.60162201e+01 -9.89347839e+01 -8.87510300e+01 -7.93696747e+01 -5.85033875e+01 -5.53741570e+01 -1.74242001e+01 -8.22178364e+00 2.66222644e+00 -2.42665005e+01 -3.89216919e+01 -6.44785614e+01 -7.81283646e+01 -7.66835022e+01 -3.35632858e+01 3.10015535e+00 -9.10989666e+00 -4.91703873e+01 -8.74610443e+01 -9.39690247e+01 -8.80243988e+01 -9.31000671e+01 -9.83074036e+01 -1.02954918e+02 -9.36335220e+01 -8.63993988e+01 -9.35845642e+01 -8.08061218e+01 -7.64618683e+01 -8.82750244e+01 -1.07198868e+02 -1.27323509e+02 -1.25148064e+02 -1.17403519e+02 -9.71036072e+01 -1.01978500e+02 -1.12242958e+02 -1.07119453e+02 -9.20386276e+01 -8.29315414e+01 -1.08127098e+02 -1.34785309e+02 -1.45718887e+02 -1.14450432e+02 -8.62642822e+01 -6.92679825e+01 -9.18288422e+01 -1.43765869e+02 -1.84075439e+02 -1.55403458e+02 -8.79886627e+01 -6.09961243e+01 -8.12280807e+01 -1.10980568e+02 -1.20049255e+02 -1.41167419e+02 -1.49941040e+02 -1.39192413e+02 -1.13126205e+02 -9.62943726e+01 -9.89834290e+01 -1.06917610e+02 -1.33111176e+02 -1.58718918e+02 -1.55977615e+02 -1.29217133e+02 -9.83719635e+01 -9.04313965e+01 -9.08720398e+01 -8.87585144e+01 -7.75621185e+01 -6.74287949e+01 -7.16032104e+01 -9.31459427e+01 -1.05719551e+02 -9.88807602e+01 -8.70338440e+01 -8.60167084e+01 -1.00439354e+02 -1.04884079e+02 -9.62927628e+01 -1.17281822e+02 -1.30198318e+02 -1.28723785e+02 -8.23563385e+01 -6.50824432e+01 -8.39748383e+01 -1.09539749e+02 -1.20866714e+02 -1.36338638e+02 -1.50421188e+02 -1.53499908e+02 -1.67087662e+02 -1.65195801e+02 -1.53768890e+02 -1.19632278e+02 -1.11508774e+02 -1.24645653e+02 -1.30675781e+02 -1.26740456e+02 -1.20323700e+02 -1.19287331e+02 -1.22279411e+02 -1.46131363e+02 -1.70804581e+02 -1.74222824e+02 -1.51079819e+02 -1.25284302e+02 -1.19687393e+02 -1.14609764e+02 -1.20908394e+02 -1.27408424e+02 -1.36563217e+02 -1.24670166e+02 -1.02209999e+02 -8.03084030e+01 -7.70261002e+01 -9.21065598e+01 -1.19171608e+02 -1.24763176e+02 -1.18487473e+02 -1.16334381e+02 -1.19610207e+02 -1.24185242e+02 -8.98206940e+01 -6.65049820e+01 -6.25672874e+01 -9.97511215e+01 -1.33369980e+02 -1.35423691e+02 -1.13389351e+02 -7.28124771e+01 1.14845409e+01 5.27081108e+01 1.30589767e+02 9.67775650e+01 2.31406204e+02 4.26168750e+03 1.20663306e+03 3.11888330e+03 1.13723281e+04 -119527008. -117451168. 479742816. -86874448. -191214496. 72932464. 726899072. 581115200. 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. 0. -1133359616. -1133359616. -1133359616. 0. 0. 466143744. 180400144. 93516384. -1.93080703e+04 -9.08322461e+03 -1.81823669e+03 -1.31062341e+03 2.45321338e+03 1.59874072e+03 1.30131790e+02 -8.51618347e+01 -1.23230286e+02 -1.07192841e+02 -1.10294708e+02 -1.27189209e+02 -1.49301193e+02 -1.47280365e+02 -1.47936096e+02 -1.51147278e+02 -1.50433975e+02 -1.38562500e+02 -1.24277893e+02 -1.41318420e+02 -1.73269745e+02 -1.83609665e+02 -1.62234146e+02 -1.46088516e+02 -1.56060242e+02 -1.65118317e+02 -1.58766907e+02 -1.51869949e+02 -1.41676254e+02 -1.39989685e+02 -1.44859467e+02 -1.56259323e+02 -1.62369766e+02 -1.62011032e+02 -1.55259598e+02 -1.73166000e+02 -1.94409286e+02 -2.02937363e+02 -1.90988281e+02 -1.77886948e+02 -1.78900894e+02 -1.85782486e+02 -1.88348190e+02 -1.96834412e+02 -2.02289993e+02 -2.06522614e+02 -2.11236969e+02 -2.11298172e+02 -2.03934692e+02 -1.94971313e+02 -1.91950577e+02 -1.99439880e+02 -2.01470901e+02 -1.99262619e+02 -1.97716583e+02 -1.99329575e+02 -2.03983749e+02 -2.07079697e+02 -2.02134537e+02 -1.83679443e+02 -1.65065506e+02 -1.55969788e+02 -1.69324249e+02 -1.83475601e+02 -1.91018494e+02 -1.80060165e+02 -1.68814255e+02 -1.73900757e+02 -1.86656967e+02 -1.99969925e+02 -1.99899582e+02 -2.00164154e+02 -2.07521301e+02 -2.23293869e+02 -2.12657562e+02 -1.94798386e+02 -1.76553345e+02 -1.83370026e+02 -1.93727798e+02 -1.93659256e+02 -1.94865784e+02 -1.95764648e+02 -2.00043472e+02 -1.99306091e+02 -1.96485367e+02 -1.91026627e+02 -1.88591019e+02 -1.89462357e+02 -1.91952332e+02 -1.90986847e+02 -1.80461334e+02 -1.67668869e+02 -1.73948166e+02 -1.82850403e+02 -1.94196396e+02 -1.88576996e+02 -1.84104904e+02 -1.79731003e+02 -1.77654739e+02 -1.85251984e+02 -1.95081512e+02 -1.98199615e+02 -1.93116745e+02 -1.82324829e+02 -1.82458496e+02 -1.84657349e+02 -1.91707840e+02 -1.96220367e+02 -1.94495682e+02 -1.95119446e+02 -1.93894791e+02 -1.96087906e+02 -1.94647430e+02 -1.95393875e+02 -1.97285049e+02 -1.92578339e+02 -1.85831223e+02 -1.87339310e+02 -1.94000015e+02 -2.01164581e+02 -2.01411118e+02 -2.01965088e+02 -2.01704880e+02 -2.01791580e+02 -2.02926498e+02 -2.03395203e+02 -1.96290024e+02 -1.87795898e+02 -1.86931183e+02 -1.92506058e+02 -1.99881241e+02 -2.02481369e+02 -2.04377960e+02 -2.02911118e+02 -2.01216034e+02 -1.99966492e+02 -2.02122833e+02 -2.01239914e+02 -2.01585022e+02 -2.01096771e+02 -2.00895889e+02 -1.99884750e+02 -1.99094315e+02 -1.98729523e+02 -1.99440796e+02 -1.99376785e+02 -1.98849640e+02 -1.98802216e+02 -1.98557129e+02 -1.98888351e+02 -1.98310181e+02 -1.97704788e+02 -1.98381134e+02 -1.98803970e+02 -1.99489822e+02 -1.99525406e+02 -2.00358536e+02 -2.01306213e+02 -2.01466202e+02 -2.00785339e+02 -1.97998444e+02 -1.96499298e+02 -1.96519958e+02 -1.97706390e+02 -1.98947601e+02 -1.99245575e+02 -1.99695190e+02 -1.99951752e+02 -1.99748871e+02 -1.99748505e+02 -1.99818253e+02 -1.99928848e+02 -1.99979706e+02 -2.00051437e+02 -2.00104324e+02 -1.99830856e+02 -1.99337097e+02 -1.99009537e+02 -1.99242676e+02 -1.99774658e+02 -2.00583618e+02 -2.00513794e+02 -2.00293228e+02 -1.99920502e+02 -2.00153885e+02 -2.00054413e+02 -2.00157471e+02 -1.99821457e+02 -1.99102539e+02 -1.99470154e+02 -1.99898193e+02 -1.99997742e+02 -1.99673569e+02 -1.98903168e+02 -2.00052704e+02 -2.00455170e+02 -2.01298767e+02 -2.01453751e+02 -2.00516327e+02 -1.96859955e+02 -1.92459747e+02 -1.89894196e+02 -1.89224808e+02 -1.89602325e+02 -1.88376007e+02 -1.91571014e+02 -1.97295944e+02 -2.02472717e+02 -2.03377823e+02 -2.01711166e+02 -2.00576401e+02 -2.00264664e+02 -2.00356628e+02 -2.01987793e+02 -2.01712494e+02 -2.01569977e+02 -2.00480209e+02 -2.00029770e+02 -1.99687988e+02 -2.05727280e+02 -2.13003693e+02 -2.11586914e+02 -2.04954758e+02 -1.97497879e+02 -1.93900055e+02 -1.90619461e+02 -1.82353439e+02 -1.77436371e+02 -1.78674042e+02 -1.84763855e+02 -1.94978760e+02 -1.91764664e+02 -1.89625504e+02 -1.84406647e+02 -1.85419937e+02 -1.87220535e+02 -1.86366989e+02 -1.85270676e+02 -1.85127747e+02 -1.89245560e+02 -1.92091125e+02 -1.91326813e+02 -1.82569366e+02 -1.72570786e+02 -1.62603210e+02 -1.59502274e+02 -1.76635300e+02 -1.97009827e+02 -2.07052719e+02 -2.01898514e+02 -1.89440475e+02 -1.88978897e+02 -1.84471268e+02 -1.85418182e+02 -1.86656479e+02 -1.88932236e+02 -1.90936966e+02 -1.89884125e+02 -1.88071869e+02 -1.87581177e+02 -1.98013702e+02 -2.12424911e+02 -2.14467682e+02 -2.08099777e+02 -1.97231155e+02 -1.90122543e+02 -1.81095566e+02 -1.77861526e+02 -1.84479935e+02 -1.85447388e+02 -1.80277603e+02 -1.81283188e+02 -1.90277344e+02 -1.96519348e+02 -1.96886276e+02 -1.94194519e+02 -1.92605927e+02 -1.89238342e+02 -1.88882706e+02 -1.85425339e+02 -1.86036423e+02 -1.86625198e+02 -1.94291092e+02 -1.98548309e+02 -1.98336670e+02 -1.84717529e+02 -1.65851440e+02 -1.63556030e+02 -1.76519363e+02 -1.92300278e+02 -1.86709229e+02 -1.82521255e+02 -1.79394623e+02 -1.81705078e+02 -1.80705460e+02 -1.77963074e+02 -1.69415375e+02 -1.60699677e+02 -1.61261490e+02 -1.74628616e+02 -1.87817535e+02 -1.88508270e+02 -1.80918121e+02 -1.89384445e+02 -2.03455887e+02 -2.12260803e+02 -2.04888107e+02 -1.91270325e+02 -1.92074478e+02 -1.91039993e+02 -1.90524506e+02 -1.84467209e+02 -1.84418793e+02 -1.89093887e+02 -1.95330856e+02 -1.92482300e+02 -1.88164047e+02 -1.87788330e+02 -1.89690720e+02 -1.83615555e+02 -1.77019669e+02 -1.62598694e+02 -1.52213913e+02 -1.54342560e+02 -1.62876373e+02 -1.72750946e+02 -1.72728195e+02 -1.77696548e+02 -1.84707047e+02 -1.81151489e+02 -1.56696564e+02 -1.33858505e+02 -1.26883469e+02 -1.45807159e+02 -1.65332077e+02 -1.68723465e+02 -1.62036240e+02 -1.58363815e+02 -1.62521957e+02 -1.49042374e+02 -1.22501762e+02 -1.14306305e+02 -1.30078934e+02 -1.62049088e+02 -1.59844879e+02 -1.60123795e+02 -1.54215103e+02 -1.58072617e+02 -1.58997345e+02 -1.52967590e+02 -1.41822281e+02 -1.35225601e+02 -1.39754898e+02 -1.49303360e+02 -1.46042282e+02 -1.21021477e+02 -8.56837463e+01 -8.52198410e+01 -1.11675018e+02 -1.41116516e+02 -1.43941788e+02 -1.51460602e+02 -1.47452072e+02 -1.43346603e+02 -1.10295280e+02 -9.05499268e+01 -6.58929977e+01 -6.57059479e+01 -8.78773499e+01 -1.14406761e+02 -1.44523666e+02 -1.22454964e+02 -1.00241608e+02 -1.23060257e+02 -1.74487167e+02 -2.01459854e+02 -1.77800858e+02 -1.46076065e+02 -1.50164658e+02 -1.48085434e+02 -1.53795807e+02 -1.54771744e+02 -1.62890015e+02 -1.66417419e+02 -1.67798477e+02 -1.71265350e+02 -1.75074661e+02 -1.77890259e+02 -1.75193329e+02 -1.70172012e+02 -1.66806229e+02 -1.47451294e+02 -1.21547203e+02 -1.23427361e+02 -1.46473541e+02 -1.77102798e+02 -1.50046417e+02 -1.14976097e+02 -1.41179901e+02 -1.99218353e+02 -1.99577423e+02 -1.27386475e+02 -8.49150772e+01 -1.08561920e+02 -1.43177567e+02 -1.27369293e+02 -8.95606461e+01 -8.12234955e+01 -9.44782486e+01 -1.25337837e+02 -1.22497612e+02 -1.18849640e+02 -1.20324463e+02 -1.20313354e+02 -1.46040512e+02 -1.72986633e+02 -1.47280960e+02 -9.54821701e+01 -6.05750694e+01 -8.31038666e+01 -1.03352928e+02 -7.81892700e+01 -5.05156784e+01 -4.38971214e+01 -6.89750061e+01 -1.02014748e+02 -9.60969696e+01 -8.99927597e+01 -8.02563782e+01 -9.70132370e+01 -8.24265594e+01 -4.94605980e+01 -3.58214989e+01 -4.36232529e+01 -9.03071823e+01 -1.14928429e+02 -1.27372726e+02 -1.18202744e+02 -1.05752136e+02 -1.47409149e+02 -2.04862701e+02 -1.92873917e+02 -1.30222626e+02 -7.07233582e+01 -8.40104599e+01 -1.16330727e+02 -9.65302200e+01 -5.79254913e+01 -5.22878914e+01 -7.72300873e+01 -1.14577507e+02 -1.19616859e+02 -1.19729637e+02 -1.19672630e+02 -1.17077240e+02 -1.14929352e+02 -1.00992516e+02 -7.88486176e+01 -6.73787308e+01 -8.15617752e+01 -1.05161186e+02 -1.13857643e+02 -1.14216286e+02 -1.08182373e+02 -1.43964432e+02 -1.79563004e+02 -1.44861191e+02 -7.42572784e+01 -2.96967449e+01 -7.17807617e+01 -1.13950005e+02 -1.41312469e+02 -1.46047852e+02 -1.46033463e+02 -1.34378265e+02 -1.26423203e+02 -1.32609573e+02 -1.26318321e+02 -1.28198502e+02 -1.25105812e+02 -1.39831314e+02 -1.44679276e+02 -1.44225525e+02 -1.14305687e+02 -1.01180168e+02 -1.13385704e+02 -1.35866837e+02 -1.47049271e+02 -1.25335625e+02 -1.07986969e+02 -9.40127792e+01 -6.39559288e+01 -3.00342674e+01 -2.30493317e+01 -5.17394066e+01 -5.39062653e+01 9.90879822e+00 5.70245209e+01 3.25216560e+01 -1.39017601e+01 -3.36925912e+00 3.96979294e+01 4.28679695e+01 1.42364395e+00 -2.72190018e+01 -3.05180416e+01 -2.60928783e+01 -2.55044422e+01 -2.30713997e+01 -2.40309677e+01 -4.66463356e+01 -3.18587627e+01 1.33603287e+00 2.80639648e+01 5.55610561e+00 -3.31194725e+01 -3.02374649e+01 -2.69301367e+00 -3.37452736e+01 -8.81125412e+01 -1.12236313e+02 -9.70919342e+01 -6.24672089e+01 -7.55692902e+01 -6.79614410e+01 -7.02496643e+01 -6.58230972e+01 -7.08688278e+01 -7.03830261e+01 -6.33076363e+01 -6.81019440e+01 -7.33815384e+01 -8.40446548e+01 -7.41746521e+01 -6.20286674e+01 -6.30375786e+01 -3.27460823e+01 -2.10379577e+00 -6.83945715e-01 -4.26630859e+01 -9.19239197e+01 -1.03279724e+02 -9.99079666e+01 -1.26361061e+02 -1.60176544e+02 -1.53173904e+02 -1.16012962e+02 -7.86811295e+01 -7.90403214e+01 -8.04998627e+01 -3.07299404e+01 2.50848503e+01 3.51599770e+01 -3.02090788e+00 -3.47853394e+01 -3.32309608e+01 -3.94540558e+01 -5.43739891e+01 -5.25555840e+01 -7.34619141e+01 -1.12784561e+02 -8.70536880e+01 -2.54816780e+01 1.76159897e+01 -5.05760670e+00 -5.06933737e+00 6.02108879e+01 1.06129501e+02 9.18706055e+01 1.56155205e+01 -7.76524878e+00 1.98003807e+01 3.41185760e+01 2.11973667e+00 -5.79303703e+01 -4.99915962e+01 -1.62867336e+01 -1.12194166e+01 -2.87913170e+01 -5.95256195e+01 -6.84359970e+01 -7.77942200e+01 -8.88297119e+01 -7.32384415e+01 -7.75476913e+01 -8.22803879e+01 -5.49241867e+01 -2.19111671e+01 9.54504371e-01 -1.84470692e+01 -3.37383423e+01 -5.71434784e+00 3.49384460e+01 3.26123924e+01 -5.03631020e+00 -1.18971046e+02 -2.90203491e+02 -3.92629272e+02 -5.76533752e+02 -6.30318604e+02 -9.80886154e+01 2.41788116e+02 6.27467712e+02 3.66799164e+02 4.64436432e+02 2.20267120e+02 2.19779160e+02 -4.25161133e+03 -1.49063164e+04 -4.65134450e+06 4.73921290e+10 0. 0. 0. 0. -3.88826496e+09 -3.88826496e+09 -17269332. -1.44161423e+10 -6.19512832e+09 -1.64064050e+06 -1.64064050e+06 3.13963192e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.37251052e+10 -4.24189250e+06 -6.49064750e+06 23994826. -3.59720450e+06 -1.84273672e+04 -8.81400781e+03 6.12560974e+02 -1.32325122e+03 -3.43172925e+03 -3.88652527e+02 -5.80236855e+01 -5.33480034e+01 -2.75759754e+01 -6.46129990e+00 -4.19490585e+01 -7.25198898e+01 -4.18528976e+01 4.44189987e+01 8.31719742e+01 1.79349632e+01 -9.91798859e+01 -9.60603485e+01 8.61253798e-01 1.19113441e+02 1.35459656e+02 8.73432693e+01 9.82366791e+01 1.51715729e+02 1.52342941e+02 9.38516312e+01 4.54228439e+01 9.53573914e+01 2.11743973e+02 2.31340439e+02 1.58184921e+02 6.80041962e+01 1.81399155e+01 1.47560377e+01 -1.89194775e+01 -5.94122467e+01 -7.43677368e+01 -1.18091879e+01 1.46505417e+02 2.27852173e+02 1.89294617e+02 7.95698471e+01 8.45738575e-02 3.63884544e+00 3.57245979e+01 8.26524887e+01 7.59196930e+01 1.05409950e+02 1.35417130e+02 1.03242737e+02 -1.25456219e+01 -1.27969078e+02 -1.14516273e+02 5.42102165e+01 1.35687469e+02 1.04958138e+02 1.43315744e+01 2.45997639e+01 9.27808228e+01 8.71626968e+01 1.84532948e+01 -5.19526405e+01 -2.55674953e+01 9.01132736e+01 1.74185989e+02 1.46497391e+02 7.72313385e+01 4.86686325e+01 7.58924561e+01 7.56218338e+01 2.95928726e+01 -2.45209465e+01 -9.00381947e+00 2.01464958e+01 1.42972031e+01 -3.02077160e+01 -4.58993530e+01 -2.01395149e+01 3.42928276e+01 8.79381485e+01 9.18424683e+01 6.96099777e+01 4.44067345e+01 5.82143784e+01 2.62017798e+00 -8.49617386e+01 -1.21565903e+02 -3.80259781e+01 1.10131378e+02 1.77732697e+02 1.35323822e+02 2.33305397e+01 -7.83808517e+01 -1.11624725e+02 -8.56205978e+01 -6.76455612e+01 -7.48129349e+01 -3.98499908e+01 6.12354202e+01 1.29303848e+02 1.06912071e+02 2.50622597e+01 1.89417136e+00 3.76049652e+01 9.59035568e+01 1.06650826e+02 6.03873215e+01 2.91619587e+01 3.26956787e+01 4.34519348e+01 8.16694832e+00 -7.03796234e+01 -8.44407806e+01 -1.22829065e+01 6.70889435e+01 6.70173035e+01 4.29187536e+00 -4.76487274e+01 -5.11488953e+01 1.98070824e+00 6.37216568e+01 9.11780548e+01 5.58310394e+01 5.41525574e+01 9.28805084e+01 1.05182014e+02 5.27085075e+01 -1.31425352e+01 -9.15359211e+00 4.91196671e+01 8.38554535e+01 5.47619438e+01 2.86039658e+01 1.65952930e+01 4.61487617e+01 2.39638863e+01 -2.20863819e+01 -3.63756866e+01 3.39992104e+01 1.62152573e+02 2.18984985e+02 1.66934357e+02 8.27647781e+01 5.57478905e+01 7.70148087e+01 1.05942017e+02 1.05721245e+02 1.13859512e+02 1.53762558e+02 2.08266373e+02 2.25009415e+02 1.70986267e+02 5.49755669e+01 -2.93078566e+00 5.57741661e+01 1.25924759e+02 1.26915413e+02 8.99360886e+01 1.19796341e+02 2.00111191e+02 1.94700516e+02 1.20072632e+02 4.94008484e+01 1.05072227e+02 2.26329239e+02 2.88843079e+02 2.41918289e+02 1.45482941e+02 9.91041870e+01 9.89034042e+01 9.18485260e+01 7.94593353e+01 1.03598305e+02 1.68926315e+02 2.41164841e+02 1.99484894e+02 1.29645721e+02 7.05740204e+01 7.83058853e+01 1.15489517e+02 1.38949570e+02 1.62684372e+02 1.65353729e+02 1.95071198e+02 2.21510895e+02 2.02822266e+02 1.26926453e+02 6.96039886e+01 7.67958298e+01 1.49562744e+02 2.06952988e+02 1.95085327e+02 1.36894440e+02 1.03475029e+02 1.04578926e+02 9.42982254e+01 2.98036880e+01 1.02526674e+01 8.00366821e+01 1.53041916e+02 1.72537308e+02 1.26918289e+02 7.70877686e+01 5.23126907e+01 5.89181442e+01 8.82948532e+01 1.17924896e+02 1.16431015e+02 1.35910538e+02 1.66280579e+02 1.39548050e+02 9.37259979e+01 6.52337570e+01 7.23014374e+01 1.18970016e+02 1.34657272e+02 1.25649216e+02 1.14918861e+02 1.12745789e+02 1.45273544e+02 1.19498253e+02 7.51669693e+01 4.96962585e+01 4.26910782e+01 1.09984726e+02 1.48487762e+02 1.35927444e+02 7.71163101e+01 6.36966438e+01 9.90912933e+01 1.38912796e+02 1.32878983e+02 1.08441704e+02 1.13465019e+02 1.48104218e+02 1.56043869e+02 1.02501350e+02 8.18903427e+01 1.07147163e+02 1.49558685e+02 1.16693413e+02 1.03653435e+02 1.13646194e+02 1.34387222e+02 1.41701004e+02 1.26964767e+02 1.47145584e+02 1.65169830e+02 1.69393478e+02 1.84744690e+02 1.96632019e+02 2.04896393e+02 1.52374863e+02 1.31527786e+02 1.30075516e+02 1.70106277e+02 1.60595459e+02 1.55346634e+02 1.68393478e+02 1.97108337e+02 2.07669373e+02 1.59672150e+02 1.32666229e+02 1.30936462e+02 1.76396652e+02 1.84951279e+02 1.80792709e+02 1.59478806e+02 1.51769348e+02 1.75572433e+02 1.62810699e+02 1.45049271e+02 1.06578911e+02 9.14053726e+01 1.02051956e+02 1.33054611e+02 1.61578705e+02 1.42679581e+02 1.10880356e+02 9.63437805e+01 1.06178207e+02 9.30782089e+01 1.00492050e+02 1.28030548e+02 1.67127945e+02 1.64498672e+02 1.10140419e+02 9.70750885e+01 1.18953842e+02 1.64004196e+02 1.48085938e+02 1.26561714e+02 1.20872963e+02 1.33845947e+02 1.54907867e+02 1.55350754e+02 1.58715973e+02 1.31523682e+02 1.21265144e+02 1.24125877e+02 1.47753891e+02 1.57755661e+02 1.39796616e+02 1.22781410e+02 1.23114174e+02 1.23096680e+02 9.20912781e+01 7.13209839e+01 7.45001831e+01 8.83523941e+01 8.75393372e+01 6.87391815e+01 6.31326065e+01 7.81466217e+01 1.16284767e+02 1.31335983e+02 1.36253204e+02 1.25899490e+02 1.30848923e+02 1.52746490e+02 1.69023193e+02 1.81474594e+02 1.62156021e+02 1.50046021e+02 1.35279221e+02 1.37639969e+02 1.31850449e+02 1.24371193e+02 1.14179321e+02 1.19200310e+02 1.22248322e+02 1.07564468e+02 9.32430725e+01 1.01782379e+02 1.25164192e+02 1.30766724e+02 1.35034973e+02 1.54430969e+02 1.71266342e+02 1.76796463e+02 1.54297668e+02 1.52911133e+02 1.51429916e+02 1.37919708e+02 1.37649506e+02 1.50643478e+02 1.82148895e+02 1.89635757e+02 1.64945175e+02 1.42054993e+02 1.42164764e+02 1.59740524e+02 1.76544434e+02 1.69866226e+02 1.56631989e+02 1.41652313e+02 1.39386520e+02 1.54822754e+02 1.65230759e+02 1.82023026e+02 1.79821930e+02 1.79524414e+02 1.86102386e+02 1.86856842e+02 1.90529358e+02 1.69231476e+02 1.66550888e+02 1.63614807e+02 1.61820297e+02 1.66694794e+02 1.79774384e+02 2.08452438e+02 2.13190399e+02 1.92093430e+02 1.57361740e+02 1.39916229e+02 1.59378830e+02 1.86240997e+02 1.88151169e+02 1.60998825e+02 1.32668213e+02 1.39320587e+02 1.66269714e+02 1.81152512e+02 1.79107803e+02 1.63829926e+02 1.66135559e+02 1.75512741e+02 1.81823456e+02 1.83602020e+02 1.73286270e+02 1.74027893e+02 1.79816025e+02 1.85180298e+02 1.83685333e+02 1.76422821e+02 1.78346542e+02 1.79640671e+02 1.68113708e+02 1.57438385e+02 1.57860199e+02 1.79037613e+02 1.90900055e+02 1.86532349e+02 1.71267166e+02 1.63615036e+02 1.65379761e+02 1.73602859e+02 1.76665344e+02 1.78425354e+02 1.72173523e+02 1.72196243e+02 1.73257446e+02 1.74619751e+02 1.77114273e+02 1.72567551e+02 1.70750671e+02 1.65466492e+02 1.65963943e+02 1.67829712e+02 1.71980728e+02 1.77704315e+02 1.78719101e+02 1.75348389e+02 1.69006165e+02 1.66646576e+02 1.69076889e+02 1.73827927e+02 1.74906693e+02 1.71928909e+02 1.69289185e+02 1.69904007e+02 1.71961029e+02 1.72509445e+02 1.72277313e+02 1.72098785e+02 1.72160492e+02 1.71881226e+02 1.71118729e+02 1.70276840e+02 1.69887726e+02 1.68963928e+02 1.68470901e+02 1.69932587e+02 1.72901901e+02 1.74463303e+02 1.71873825e+02 1.68638519e+02 1.69441574e+02 1.74778229e+02 1.79698990e+02 1.77496628e+02 1.70587067e+02 1.68031754e+02 1.71316589e+02 1.77358444e+02 1.76185257e+02 1.70012009e+02 1.65108490e+02 1.60595184e+02 1.65956543e+02 1.64407318e+02 1.67787216e+02 1.67027115e+02 1.66531631e+02 1.63057220e+02 1.56077499e+02 1.60136124e+02 1.68086670e+02 1.77589844e+02 1.74345901e+02 1.62577576e+02 1.51719818e+02 1.58244415e+02 1.72945251e+02 1.84192551e+02 1.81164978e+02 1.70293976e+02 1.66397430e+02 1.64405563e+02 1.67379929e+02 1.63585861e+02 1.58866730e+02 1.50772324e+02 1.40495728e+02 1.43902267e+02 1.60119370e+02 1.73561798e+02 1.75273590e+02 1.68423889e+02 1.60295410e+02 1.46915970e+02 1.39530182e+02 1.56422089e+02 1.83461258e+02 1.94942215e+02 1.76771698e+02 1.50740799e+02 1.50575470e+02 1.75397003e+02 2.04685669e+02 1.99812332e+02 1.67457031e+02 1.33102127e+02 1.22824860e+02 1.43891983e+02 1.62498444e+02 1.60993774e+02 1.49631073e+02 1.42661194e+02 1.54865158e+02 1.56358688e+02 1.57143661e+02 1.70218948e+02 1.74942627e+02 1.74064774e+02 1.54511856e+02 1.56702667e+02 1.81772873e+02 2.08277252e+02 2.01107254e+02 1.58374329e+02 1.21389687e+02 1.33460892e+02 1.74181091e+02 2.03749954e+02 2.03910339e+02 1.68546875e+02 1.36113571e+02 1.21756332e+02 1.48785095e+02 1.65333450e+02 1.79771973e+02 1.76397491e+02 1.70109970e+02 1.73984818e+02 1.72517685e+02 1.94284164e+02 2.06706284e+02 2.09890488e+02 1.92831970e+02 1.53614624e+02 1.40439514e+02 1.64473358e+02 2.01746002e+02 2.11841660e+02 1.89305527e+02 1.52528580e+02 1.55301865e+02 1.77460159e+02 2.17911880e+02 2.23203217e+02 1.87448425e+02 1.46706726e+02 1.28582153e+02 1.58465561e+02 1.89929214e+02 1.89292801e+02 1.66006134e+02 1.31796234e+02 1.27392082e+02 1.32157684e+02 1.47910919e+02 1.77764771e+02 1.82418854e+02 1.59194717e+02 1.06684296e+02 8.12951660e+01 1.13431679e+02 1.56610138e+02 1.85980286e+02 1.66572418e+02 1.29043579e+02 1.12549980e+02 1.24335457e+02 1.53363831e+02 1.49826508e+02 1.26843956e+02 9.71830063e+01 9.58078842e+01 1.28407959e+02 1.59687424e+02 1.51035355e+02 1.29218033e+02 8.51730118e+01 8.95548096e+01 8.96868057e+01 1.11010460e+02 1.30914444e+02 1.44201843e+02 1.52344604e+02 1.19161186e+02 9.60720596e+01 1.10893906e+02 1.46863129e+02 1.79003006e+02 1.56379410e+02 1.17728996e+02 9.48861389e+01 1.29533936e+02 2.04841980e+02 2.32147995e+02 1.94480667e+02 1.10332085e+02 6.16695213e+01 8.91585083e+01 1.42605179e+02 1.85576874e+02 2.16927475e+02 2.52307022e+02 2.60077301e+02 2.50930008e+02 1.73936975e+03 2.80472266e+03 3.94219116e+02 2.25297073e+02 1.79565338e+02 6.75605652e+02 -3.68945703e+03 -1.14620293e+04 362859104. -2.41568486e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 1.06372465e+10 -589859840. 59025448. 249763968. 142146384. -210576608. -475286016. 1.26736729e+04 5.08961719e+03 9.15561829e+02 3.79609467e+02 2.91738495e+02 2.53144104e+02 1.83333878e+02 8.49715195e+01 4.96587296e+01 7.47643890e+01 1.49041321e+02 1.96530197e+02 1.81022064e+02 1.19403236e+02 3.21451035e+01 2.99876938e+01 5.29701538e+01 7.32159576e+01 7.92802811e+01 8.44353638e+01 1.20976135e+02 7.57839203e+01 6.92870102e+01 1.26265991e+02 1.78177231e+02 1.38795990e+02 1.69199963e+01 -4.49149742e+01 3.00803833e+01 1.27142082e+02 1.84435837e+02 1.51393005e+02 4.18968506e+01 -4.63320885e+01 -8.46984406e+01 3.89702916e+00 6.72647324e+01 7.26317062e+01 7.80201864e+00 -3.58468666e+01 6.85973704e-01 1.14993620e+01 4.51916885e+01 8.45436401e+01 1.04106728e+02 7.31770782e+01 -4.43001366e+01 -5.56790390e+01 4.36658821e+01 1.60519257e+02 1.88389069e+02 9.02505798e+01 -4.53509140e+00 2.05693102e+00 7.33654175e+01 1.05936119e+02 3.53594971e+01 -7.68906326e+01 -1.16982910e+02 -7.77652893e+01 5.12085991e+01 1.40667938e+02 1.43950378e+02 6.44898987e+01 -3.99667778e+01 -1.11353737e+02 -1.43171753e+02 -1.04599960e+02 -4.74758224e+01 6.67197466e+00 3.14827213e+01 1.31652508e+01 3.04082127e+01 1.04352119e+02 1.72303345e+02 1.71011978e+02 7.20300827e+01 4.22006178e+00 1.29342775e+01 5.09015465e+01 1.23850418e+02 1.61513489e+02 1.25710052e+02 1.36162472e+01 -4.33740082e+01 2.09823341e+01 1.03495445e+02 9.26512146e+01 4.08992615e+01 2.24544926e+01 5.25488358e+01 3.98542328e+01 4.04026337e+01 7.76041946e+01 1.00953514e+02 7.24888611e+01 -3.51473656e+01 -4.86816483e+01 6.21834679e+01 1.92336700e+02 2.39722305e+02 1.43104080e+02 5.29861946e+01 1.16802330e+01 3.17482643e+01 5.91854935e+01 7.46905594e+01 4.62232132e+01 -1.54895353e+01 -4.79072876e+01 1.52334957e+01 1.25703812e+02 1.59076447e+02 1.20381783e+02 7.72751160e+01 6.50792542e+01 1.81879864e+01 2.05628624e+01 1.09557953e+02 2.14481018e+02 2.06096405e+02 6.72209702e+01 9.71189499e+00 9.06363678e+01 2.06525528e+02 2.21437302e+02 1.10471733e+02 9.16043663e+00 -2.12579479e+01 2.18239994e+01 1.00095436e+02 1.60948853e+02 1.38462036e+02 4.61040993e+01 -1.96361160e+01 3.35250664e+01 1.26154305e+02 1.49832809e+02 1.17407837e+02 7.35919724e+01 4.81488419e+01 -1.30696964e+01 -4.14730873e+01 -1.00458088e+01 3.95095100e+01 4.99222488e+01 -2.63532047e+01 -5.64783936e+01 -4.23794079e+00 1.43003052e+02 2.28760635e+02 1.90767792e+02 4.46188431e+01 -5.07213554e+01 -2.59874554e+01 4.37176361e+01 7.24193115e+01 3.49995079e+01 3.22246437e+01 -2.07011127e+01 5.22037506e+00 1.67062435e+01 6.89363861e+01 1.28944580e+02 1.56174408e+02 1.73910095e+02 7.27278137e+01 2.12374878e+01 7.45678635e+01 1.31515717e+02 1.11387695e+02 -2.19328632e+01 -7.44934845e+01 -3.59040642e+01 2.87893829e+01 7.55990677e+01 7.38427811e+01 3.47810440e+01 1.14522219e+01 8.35090351e+00 7.31904831e+01 5.87082634e+01 1.31213779e+01 -3.91949959e+01 -1.13216560e+02 -1.64111374e+02 -2.11090652e+02 -1.28498810e+02 -1.02867680e+01 4.87890625e+01 3.70614433e+01 -3.67145271e+01 -4.24732323e+01 4.35143700e+01 1.38246368e+02 1.74664825e+02 5.19488907e+01 -1.03040398e+02 -1.73650650e+02 -1.31362961e+02 -6.02145348e+01 -3.08529015e+01 -4.41375351e+01 -7.35630493e+01 -1.17696014e+02 -8.21725845e+01 -1.37701731e+01 3.02000446e+01 -1.66314335e+01 -4.10413399e+01 -6.10130081e+01 -9.83560791e+01 -1.07633301e+02 -6.92293549e+01 -2.76526394e+01 -4.08924828e+01 -4.20088158e+01 -4.47071981e+00 6.02113724e+01 8.65470810e+01 1.07285942e+02 6.32089996e+01 3.65323143e+01 -6.75625839e+01 -1.02510155e+02 -5.73254776e+01 4.24354668e+01 6.77085114e+01 1.39068527e+01 -3.98686142e+01 -2.65752087e+01 -1.47467203e+01 -4.20569515e+00 -2.21734428e+00 -7.63075066e+00 -1.06452961e+01 -9.82066917e+00 -9.67259407e+00 2.68903232e+00 8.00565529e+00 4.45858040e+01 3.74597664e+01 2.68097572e+01 -5.21771717e+00 4.44211197e+00 1.24521351e+01 -7.28453875e+00 -9.49639225e+00 -4.21347046e+01 -6.13083649e+01 -7.57602005e+01 -6.12760086e+01 -2.46018524e+01 -2.68619881e+01 -2.59333305e+01 -2.61733913e+01 -1.06741314e+01 -1.13402052e+01 -7.10759687e+00 -5.85133219e+00 -4.43645906e+00 -1.51388054e+01 -2.48873062e+01 -1.41470098e+01 5.91722918e+00 -5.35090876e+00 1.41166325e+01 1.26039219e+01 1.70890293e+01 -2.16703534e+00 -1.47133646e+01 -1.12983456e+01 -1.09982338e+01 -5.42040169e-01 -2.60843635e+00 -8.63823223e+00 -3.30803604e+01 -2.88836727e+01 -3.65446739e+01 -7.68288708e+00 -1.99110622e+01 -2.57377934e+00 -1.18518934e+01 -2.60526676e+01 -5.31261635e+01 -4.73055611e+01 -2.46163177e+01 -1.43458843e+01 -3.20595589e+01 -3.62764320e+01 -1.84392509e+01 -2.83800850e+01 -5.24391708e+01 -7.75511551e+01 -7.23695450e+01 -6.57856827e+01 -5.11037560e+01 -5.84899864e+01 -4.99476509e+01 -5.29496155e+01 -4.88055611e+01 -5.18200035e+01 -6.27751503e+01 -7.04834747e+01 -6.01071053e+01 -4.80825195e+01 -3.58625107e+01 -5.80938759e+01 -3.74612503e+01 -1.04621820e+01 2.27215981e+00 -2.04835491e+01 -6.85047455e+01 -6.78888245e+01 -7.17213058e+01 -5.65210304e+01 -4.64633217e+01 -6.84376144e+01 -7.38897858e+01 -8.33188705e+01 -7.12475204e+01 -8.52968063e+01 -9.20536499e+01 -7.57469482e+01 -6.79519653e+01 -6.82390747e+01 -7.01382294e+01 -6.26798897e+01 -7.05108948e+01 -7.43759155e+01 -7.94964676e+01 -9.32427292e+01 -1.05940323e+02 -1.00508499e+02 -8.27320328e+01 -7.06925888e+01 -7.31036682e+01 -8.08116455e+01 -9.15906982e+01 -8.55613251e+01 -6.15072708e+01 -3.26356316e+01 -4.22970543e+01 -6.07878456e+01 -1.00155830e+02 -1.01133629e+02 -9.56138000e+01 -7.35106430e+01 -6.55812149e+01 -5.35816269e+01 -4.34798927e+01 -4.01690521e+01 -4.55493698e+01 -5.14281387e+01 -6.57268066e+01 -7.32603455e+01 -8.00941315e+01 -7.33865204e+01 -8.21244125e+01 -7.32688293e+01 -7.52400665e+01 -7.52282486e+01 -7.53206558e+01 -8.43997803e+01 -7.21284943e+01 -5.56434898e+01 -1.45887575e+01 -3.14908943e+01 -6.79804535e+01 -1.02103416e+02 -8.32883606e+01 -4.73059158e+01 -4.26673927e+01 -5.86889076e+01 -8.69677353e+01 -8.02630386e+01 -6.03139305e+01 -4.72637634e+01 -4.83554802e+01 -5.67222939e+01 -5.16127396e+01 -2.63076916e+01 -9.57606888e+00 -3.27252350e+01 -7.41838684e+01 -9.10061264e+01 -7.60412750e+01 -6.81434097e+01 -7.55334396e+01 -8.60028534e+01 -9.50874710e+01 -8.09210358e+01 -5.56948509e+01 -5.74883957e+01 -7.99675064e+01 -1.16261536e+02 -1.14403267e+02 -1.02476059e+02 -9.41940765e+01 -1.15771622e+02 -1.58869232e+02 -1.74324188e+02 -1.39376328e+02 -1.00552162e+02 -8.93497314e+01 -9.51012192e+01 -6.86819992e+01 -5.80756340e+01 -1.00399933e+02 -1.61809860e+02 -1.77499390e+02 -1.37813156e+02 -9.38968658e+01 -8.38105545e+01 -8.94146194e+01 -1.18069496e+02 -1.34823349e+02 -1.25616806e+02 -9.73827744e+01 -7.57755051e+01 -7.88555984e+01 -8.08938751e+01 -1.16908882e+02 -1.67941055e+02 -1.71856598e+02 -1.46973450e+02 -1.12635002e+02 -1.01281731e+02 -8.17555695e+01 -7.58076477e+01 -9.76729279e+01 -1.18325188e+02 -1.26526291e+02 -1.22670982e+02 -1.22137169e+02 -1.31080017e+02 -1.36862411e+02 -1.40919250e+02 -1.40612396e+02 -1.43951538e+02 -7.06430664e+01 -1.56008408e+02 8.58144608e+01 1.95158218e+02 4.01266815e+02 2.09155859e+03 3.14894141e+03 -4.17050476e+02 -5.00505127e+02 -6.30640320e+02 -8.88686707e+02 -7.97525024e+02 -4.73307556e+02 -7.19672363e+02 -1.24995740e+03 -1.01706836e+04 -2.52621699e+04 726899072. 581115200. 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. 0. -1133359616. -1133359616. -1133359616. 0. 0. 466143744. 180400144. 93516384. 107867184. -507650400. 200183296. 123007416. 8.78252148e+03 3.64914160e+03 3.52589844e+02 1.39380608e+01 -1.00465981e+02 -1.06597801e+02 -1.08327080e+02 -1.09358101e+02 -1.11608742e+02 -1.09577530e+02 -1.02290215e+02 -9.95897827e+01 -1.01514229e+02 -1.18694336e+02 -1.23602570e+02 -1.22032669e+02 -1.05520012e+02 -1.11612762e+02 -1.25469650e+02 -1.45358749e+02 -1.47572037e+02 -1.50876495e+02 -1.59377106e+02 -1.67771439e+02 -1.69834366e+02 -1.74883316e+02 -1.81385498e+02 -1.82067307e+02 -1.80479843e+02 -1.74135422e+02 -1.70801086e+02 -1.76380630e+02 -1.82788528e+02 -1.89150833e+02 -1.77433273e+02 -1.70856857e+02 -1.73224640e+02 -1.80720108e+02 -1.82806000e+02 -1.83948975e+02 -1.82223404e+02 -1.78522461e+02 -1.62365616e+02 -1.49446381e+02 -1.43664719e+02 -1.50416763e+02 -1.57162064e+02 -1.62279648e+02 -1.66945572e+02 -1.65227066e+02 -1.58704041e+02 -1.59628143e+02 -1.64304077e+02 -1.72567368e+02 -1.74019699e+02 -1.80924423e+02 -1.74046875e+02 -1.62756943e+02 -1.55284149e+02 -1.48930115e+02 -1.49559113e+02 -1.46097305e+02 -1.52826859e+02 -1.56924133e+02 -1.56681580e+02 -1.59234177e+02 -1.69883667e+02 -1.76744095e+02 -1.74723816e+02 -1.68532715e+02 -1.64612106e+02 -1.67348694e+02 -1.57434418e+02 -1.43048843e+02 -1.43640457e+02 -1.49469604e+02 -1.57846817e+02 -1.41602585e+02 -1.26858772e+02 -1.27200668e+02 -1.39387085e+02 -1.47929169e+02 -1.47486786e+02 -1.45415756e+02 -1.51442566e+02 -1.49525558e+02 -1.41101044e+02 -1.29457443e+02 -1.32422424e+02 -1.47554657e+02 -1.60698853e+02 -1.67591125e+02 -1.64895401e+02 -1.64333527e+02 -1.60061691e+02 -1.68237839e+02 -1.74568771e+02 -1.69277023e+02 -1.59557449e+02 -1.57828064e+02 -1.67308945e+02 -1.73602371e+02 -1.62212311e+02 -1.54819351e+02 -1.56870178e+02 -1.67672668e+02 -1.75769501e+02 -1.77327072e+02 -1.77313248e+02 -1.75331100e+02 -1.73423599e+02 -1.71285126e+02 -1.72040359e+02 -1.72346497e+02 -1.71266083e+02 -1.69161896e+02 -1.67923294e+02 -1.68020523e+02 -1.69267548e+02 -1.68985565e+02 -1.69420181e+02 -1.68879501e+02 -1.63115097e+02 -1.57485001e+02 -1.57369797e+02 -1.63789124e+02 -1.69486710e+02 -1.63919098e+02 -1.58093307e+02 -1.58165405e+02 -1.63184814e+02 -1.67242142e+02 -1.67561188e+02 -1.69248718e+02 -1.72300400e+02 -1.71557709e+02 -1.70043808e+02 -1.69110840e+02 -1.70451492e+02 -1.72836624e+02 -1.73186646e+02 -1.72365662e+02 -1.70613953e+02 -1.70165054e+02 -1.69652496e+02 -1.70220657e+02 -1.69193542e+02 -1.65893906e+02 -1.62364120e+02 -1.62910995e+02 -1.65870117e+02 -1.69013840e+02 -1.67464447e+02 -1.65723129e+02 -1.66491974e+02 -1.69188751e+02 -1.71448013e+02 -1.71261124e+02 -1.71115555e+02 -1.71054855e+02 -1.71178665e+02 -1.71125778e+02 -1.71113312e+02 -1.71334015e+02 -1.71529724e+02 -1.71323517e+02 -1.71163330e+02 -1.71457947e+02 -1.71844925e+02 -1.72078232e+02 -1.72087524e+02 -1.72076736e+02 -1.72271896e+02 -1.72777802e+02 -1.72998688e+02 -1.72869965e+02 -1.72432938e+02 -1.72430832e+02 -1.71949081e+02 -1.72809509e+02 -1.74685883e+02 -1.75313904e+02 -1.74169342e+02 -1.72513779e+02 -1.72996017e+02 -1.73463699e+02 -1.73094986e+02 -1.72977234e+02 -1.73909027e+02 -1.74181229e+02 -1.76844772e+02 -1.79244629e+02 -1.79582962e+02 -1.76850388e+02 -1.73819473e+02 -1.75069489e+02 -1.75099182e+02 -1.78366394e+02 -1.80865143e+02 -1.80182907e+02 -1.74816055e+02 -1.70142899e+02 -1.70822098e+02 -1.71719955e+02 -1.72608780e+02 -1.71104813e+02 -1.69981918e+02 -1.68876114e+02 -1.68577942e+02 -1.69675583e+02 -1.70195908e+02 -1.69878952e+02 -1.70034561e+02 -1.66490341e+02 -1.64768051e+02 -1.62258591e+02 -1.61951599e+02 -1.63728577e+02 -1.63612411e+02 -1.63895844e+02 -1.63493042e+02 -1.63392960e+02 -1.63840866e+02 -1.62089981e+02 -1.64466125e+02 -1.65552155e+02 -1.65214752e+02 -1.61384171e+02 -1.61427094e+02 -1.63031525e+02 -1.64853714e+02 -1.64528671e+02 -1.63230301e+02 -1.65039017e+02 -1.64760178e+02 -1.69302521e+02 -1.69829178e+02 -1.69300003e+02 -1.61449677e+02 -1.52475937e+02 -1.58875168e+02 -1.74341522e+02 -1.85275787e+02 -1.80898300e+02 -1.71872742e+02 -1.71025345e+02 -1.72307831e+02 -1.73776230e+02 -1.73718552e+02 -1.73640442e+02 -1.72787827e+02 -1.70757736e+02 -1.64716095e+02 -1.60298065e+02 -1.56774384e+02 -1.60956940e+02 -1.64829758e+02 -1.70182648e+02 -1.70995621e+02 -1.67007034e+02 -1.63660263e+02 -1.59483063e+02 -1.60393417e+02 -1.58888336e+02 -1.63167206e+02 -1.75058090e+02 -1.86590881e+02 -1.87533279e+02 -1.77192154e+02 -1.68826843e+02 -1.63647476e+02 -1.64622971e+02 -1.68604996e+02 -1.78080872e+02 -1.83432251e+02 -1.87591156e+02 -1.79026596e+02 -1.70495117e+02 -1.57747345e+02 -1.61000870e+02 -1.63425400e+02 -1.66098969e+02 -1.60805267e+02 -1.57415863e+02 -1.52426086e+02 -1.57501938e+02 -1.63143936e+02 -1.67781738e+02 -1.69676041e+02 -1.67327118e+02 -1.81513351e+02 -1.93681763e+02 -1.91096939e+02 -1.70348602e+02 -1.54713043e+02 -1.61545593e+02 -1.71841705e+02 -1.68419495e+02 -1.65109543e+02 -1.74876617e+02 -1.90407547e+02 -1.90391403e+02 -1.71417816e+02 -1.52642868e+02 -1.59681442e+02 -1.65865021e+02 -1.62380219e+02 -1.56665710e+02 -1.52694427e+02 -1.55683136e+02 -1.58102692e+02 -1.50689102e+02 -1.36017761e+02 -1.31601562e+02 -1.34319275e+02 -1.44221146e+02 -1.42722504e+02 -1.56939224e+02 -1.74011475e+02 -1.78651154e+02 -1.83257172e+02 -1.91669891e+02 -2.09566605e+02 -2.12101593e+02 -2.05214645e+02 -2.01089890e+02 -1.90338791e+02 -1.87557632e+02 -1.68431885e+02 -1.40680252e+02 -1.09977966e+02 -1.04575943e+02 -1.13377754e+02 -1.21439804e+02 -1.27118019e+02 -1.28461884e+02 -1.33965240e+02 -1.30466156e+02 -1.26369072e+02 -1.40188477e+02 -1.68814011e+02 -1.77239258e+02 -1.70263260e+02 -1.53272980e+02 -1.50112137e+02 -1.46524399e+02 -1.31568634e+02 -1.45364777e+02 -1.47503159e+02 -1.55823059e+02 -1.58818405e+02 -1.71503204e+02 -1.96080231e+02 -1.77164062e+02 -1.52098694e+02 -1.41852661e+02 -1.68435883e+02 -1.72610168e+02 -1.62006699e+02 -1.36220963e+02 -1.59505096e+02 -1.79953033e+02 -1.84569229e+02 -1.67324692e+02 -1.49714584e+02 -1.74858887e+02 -2.00422943e+02 -1.94911224e+02 -1.62420624e+02 -1.34947144e+02 -1.54465546e+02 -1.69539673e+02 -1.47603821e+02 -1.12372986e+02 -1.25819397e+02 -1.63854614e+02 -1.83150925e+02 -1.76945557e+02 -1.63722336e+02 -1.66309265e+02 -1.84323288e+02 -2.08308609e+02 -2.01718842e+02 -1.59580017e+02 -1.27841064e+02 -1.24671127e+02 -1.35018570e+02 -1.41544617e+02 -1.37493271e+02 -1.31360611e+02 -1.28449600e+02 -1.44296066e+02 -1.48566620e+02 -1.30945969e+02 -1.22865128e+02 -1.26916260e+02 -1.58305222e+02 -1.70163025e+02 -1.61478851e+02 -1.51814072e+02 -1.33327759e+02 -1.34602783e+02 -1.26443710e+02 -1.14026077e+02 -1.01891792e+02 -1.06946007e+02 -1.57845703e+02 -1.92662033e+02 -1.55416824e+02 -8.81336441e+01 -8.58782272e+01 -1.40322464e+02 -1.63340698e+02 -1.28394684e+02 -1.06482567e+02 -1.24508263e+02 -1.43235550e+02 -1.39288895e+02 -1.15439751e+02 -1.23032234e+02 -1.30931396e+02 -1.39505371e+02 -1.24711647e+02 -1.00562317e+02 -1.00386627e+02 -1.02800758e+02 -1.31892197e+02 -1.53691406e+02 -1.53926239e+02 -1.24284279e+02 -1.22475388e+02 -1.76177383e+02 -2.14991028e+02 -1.93328140e+02 -1.39191452e+02 -1.35560242e+02 -1.59566132e+02 -1.37898544e+02 -8.56796570e+01 -6.57522736e+01 -1.04436615e+02 -1.29325592e+02 -1.22973900e+02 -1.07969849e+02 -1.31451721e+02 -1.37015213e+02 -1.40147110e+02 -1.23947487e+02 -1.09831871e+02 -9.06060257e+01 -8.38413925e+01 -8.64517365e+01 -1.00264381e+02 -1.24645752e+02 -1.38973694e+02 -1.43289124e+02 -1.51641052e+02 -1.56231995e+02 -1.42368271e+02 -1.21802521e+02 -1.17050903e+02 -1.44075760e+02 -1.48704041e+02 -1.43266418e+02 -1.58125519e+02 -2.10337341e+02 -2.46345673e+02 -2.15697357e+02 -1.51700272e+02 -1.32669327e+02 -1.50742630e+02 -1.55075302e+02 -1.23568550e+02 -9.65298080e+01 -8.23376999e+01 -8.03829575e+01 -7.99862289e+01 -1.05311768e+02 -1.01084808e+02 -8.06798859e+01 -7.36272888e+01 -1.28247528e+02 -1.63917877e+02 -1.31497391e+02 -9.66973877e+01 -1.28809937e+02 -1.58992874e+02 -1.23469788e+02 -4.72125473e+01 2.19408059e+00 -7.80767775e+00 -1.15864573e+01 -3.20799866e+01 -3.07522240e+01 -3.70316582e+01 -3.19317436e+01 -5.25165062e+01 -6.65230484e+01 -6.32443848e+01 -3.22486687e+01 -5.36413956e+01 -1.22442787e+02 -1.68390884e+02 -1.73315048e+02 -1.63201370e+02 -1.33884491e+02 -1.08589828e+02 -7.41758728e+01 -8.16566925e+01 -7.35387115e+01 -6.83617477e+01 -6.08891830e+01 -7.21119843e+01 -6.61515732e+01 -7.66219559e+01 -7.80551758e+01 -6.98082809e+01 -6.65102310e+01 -6.17731667e+01 -1.07865448e+02 -1.47957565e+02 -1.52521530e+02 -1.13220100e+02 -7.95136871e+01 -8.21253586e+01 -8.54345779e+01 -8.49256973e+01 -7.70321808e+01 -7.14280548e+01 -7.26707993e+01 -1.01577293e+02 -1.39300751e+02 -1.25400970e+02 -8.46079788e+01 -7.17882004e+01 -1.38231354e+02 -1.83220123e+02 -1.54285965e+02 -8.76893082e+01 -8.60787048e+01 -1.25973946e+02 -1.20022842e+02 -8.77539825e+01 -5.06692467e+01 -9.15495758e+01 -1.25549454e+02 -1.56175049e+02 -1.71179535e+02 -1.20201248e+02 -8.42005768e+01 -8.04062195e+01 -1.60543884e+02 -1.89138382e+02 -1.29685959e+02 -5.87432480e+01 -6.70752945e+01 -1.34174728e+02 -1.43643158e+02 -1.15072060e+02 -7.00030136e+01 -9.92008667e+01 -1.38561646e+02 -1.52145660e+02 -1.27247818e+02 -8.91045227e+01 -8.06835632e+01 -1.14187111e+02 -1.54180130e+02 -1.57864685e+02 -1.25453201e+02 -6.44012680e+01 -8.34261551e+01 -1.12626999e+02 -1.17366982e+02 -8.66113663e+01 -8.28967361e+01 -1.24368698e+02 -1.15468498e+02 -7.32622375e+01 -2.81264019e+01 -1.93499966e+01 -1.04226160e+01 -3.74618378e+01 -8.00274963e+01 -1.01493553e+02 -8.27628708e+01 -4.46861687e+01 -3.18405933e+01 -3.43175163e+01 -6.20385094e+01 -1.01273689e+02 -2.41602234e+02 -3.64005066e+02 -2.62935730e+02 -3.72504364e+02 -5.60409607e+02 -6.04747314e+02 -5.38358276e+02 -7.88404846e+01 8.69964142e+01 -2.35603003e+03 -4.09146191e+03 -1.80620825e+03 -2.62980200e+03 -5.22028516e+03 -2.32289375e+04 -652330752. 0. 0. 0. 0. 0. 0. 2.26273956e+10 2.26273956e+10 2.44004434e+04 5.29405391e+04 5.29405391e+04 3.13963192e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 157636080. 6.89158154e+03 6.25953418e+03 3.63216089e+03 9.34642944e+02 7.39877808e+02 2.00187485e+02 5.17107353e+01 -7.56138611e+01 -9.44043732e+01 -2.19370861e+01 5.49788904e+00 -2.91991787e+01 2.30710268e+00 8.04430389e+01 1.37710938e+02 7.25568848e+01 -6.65614243e+01 -1.26928741e+02 -8.14658585e+01 1.59237766e+01 5.94685669e+01 4.22218552e+01 1.75843983e+01 5.60533524e+01 1.01237000e+02 7.27426987e+01 -1.20325117e+01 -5.37494278e+01 -2.00833721e+01 5.16823654e+01 7.77368164e+01 1.87771626e+01 -6.06851807e+01 -9.56806488e+01 -4.90167694e+01 -4.94525642e+01 -9.99977036e+01 -6.68677902e+01 3.27505646e+01 1.02478424e+02 2.28900890e+01 -1.33420670e+02 -1.69387497e+02 -8.79601669e+01 -9.39701748e+00 3.52635040e+01 2.97678299e+01 2.75421829e+01 1.66185322e+01 3.26328430e+01 1.68160706e+01 -9.08486862e+01 -1.60157166e+02 -1.29432541e+02 -2.34642868e+01 3.36439285e+01 5.59746933e+00 -5.95211639e+01 -8.99050751e+01 -3.93141098e+01 -2.08157177e+01 -4.05946426e+01 -1.02410421e+01 5.27699013e+01 1.25137230e+02 1.17064056e+02 1.04349527e+01 -3.02846947e+01 6.00306913e-02 7.95816116e+01 5.08946609e+01 -2.13368988e+01 -1.54290748e+00 6.64586563e+01 9.42949295e+01 5.34499207e+01 -4.42626266e+01 -7.22318954e+01 -4.80513916e+01 4.59571877e+01 9.78928909e+01 8.38688736e+01 4.84421501e+01 5.72618484e+01 1.01311127e+02 9.19237823e+01 2.70504169e+01 -3.79263830e+00 5.78696251e+01 1.52986908e+02 1.68925110e+02 8.34273682e+01 -1.53538072e+00 -1.00724573e+01 5.75847626e+01 7.51969147e+01 5.68585777e+01 9.18522186e+01 1.73115097e+02 2.18825714e+02 1.46649612e+02 3.18545418e+01 -3.52917824e+01 -7.60086966e+00 5.58545303e+01 1.38869049e+02 1.86872925e+02 1.73556305e+02 1.45951889e+02 1.55335663e+02 1.47649536e+02 7.59197235e+01 4.08730841e+00 4.18723488e+01 1.54603027e+02 2.00368332e+02 1.57196075e+02 4.87489319e+01 1.77014005e+00 4.65504990e+01 9.60393753e+01 1.00645721e+02 9.51074295e+01 1.32856476e+02 2.19847702e+02 2.08077927e+02 1.25501060e+02 4.25089455e+01 4.58416328e+01 1.04481293e+02 1.50004761e+02 1.55078796e+02 1.33448395e+02 9.17038803e+01 8.00225220e+01 1.30148834e+02 1.51371811e+02 1.15946571e+02 7.68125916e+01 7.50564423e+01 1.01967964e+02 1.02265633e+02 6.17458000e+01 6.17592697e+01 9.70056686e+01 1.38655136e+02 1.50092819e+02 9.93017654e+01 8.44963150e+01 1.00222763e+02 1.39746902e+02 1.10852623e+02 2.62222838e+00 -5.29146156e+01 1.35234690e+01 1.15794815e+02 1.37366745e+02 9.03512039e+01 5.72209816e+01 6.16391716e+01 5.90046883e+01 2.45629826e+01 -2.83091660e+01 -3.89906235e+01 -1.62797279e+01 5.70534439e+01 1.09013168e+02 8.00130081e+01 5.93699722e+01 6.57298889e+01 1.12576050e+02 7.58882675e+01 -7.20224476e+00 3.36172342e+00 4.66199074e+01 8.15450287e+01 2.76085110e+01 -6.83080597e+01 -1.10659943e+02 -6.15134621e+01 2.63704300e+01 8.86341553e+01 7.69972382e+01 9.73995438e+01 1.08331902e+02 1.01888084e+02 4.34140739e+01 -2.71268253e+01 -2.66910286e+01 3.14568367e+01 1.37467377e+02 1.81431870e+02 1.53951660e+02 8.33215637e+01 3.20955467e+01 3.82284088e+01 1.74687386e+01 -9.29872799e+00 5.09395599e+00 6.60873871e+01 1.33537781e+02 9.92301178e+01 1.94939137e+01 -2.86221199e+01 2.61038361e+01 1.22880424e+02 1.53404984e+02 1.09114853e+02 5.48092766e+01 8.08940277e+01 1.28993484e+02 1.17525581e+02 6.29735146e+01 3.87571526e+01 9.14731979e+01 1.66977158e+02 1.85488632e+02 1.45194412e+02 1.03451096e+02 1.06926819e+02 1.28472061e+02 1.30954407e+02 1.12262291e+02 1.32784821e+02 1.63487122e+02 1.59839996e+02 1.47252899e+02 1.07342926e+02 9.26135559e+01 1.10569633e+02 1.11220306e+02 1.19434830e+02 9.07435837e+01 1.21351807e+02 1.51684021e+02 1.66172821e+02 1.50098267e+02 7.25203934e+01 3.37853317e+01 4.14020157e+01 1.31902481e+02 1.72745224e+02 1.76152557e+02 1.34608566e+02 1.20803917e+02 1.43539185e+02 1.45587555e+02 1.19850624e+02 1.02776901e+02 1.30996475e+02 1.50016754e+02 1.08001320e+02 4.96747780e+01 6.24699326e+01 9.43286057e+01 1.16234627e+02 1.00347527e+02 7.02192383e+01 1.10802383e+02 1.35980972e+02 1.62554993e+02 1.40374802e+02 9.85776215e+01 7.62033920e+01 5.75902100e+01 9.43889313e+01 1.18489189e+02 1.30851898e+02 9.99488068e+01 8.74890518e+01 9.28013916e+01 8.21698074e+01 6.45171051e+01 5.09788513e+01 9.97184219e+01 1.25888657e+02 1.23564156e+02 8.88753586e+01 9.67041855e+01 1.15130539e+02 1.35148712e+02 1.50375443e+02 1.41229416e+02 1.46368103e+02 1.08567253e+02 9.30541077e+01 7.43588104e+01 7.73599777e+01 9.20842743e+01 1.10832550e+02 1.46493423e+02 1.62828064e+02 1.53877914e+02 1.04421684e+02 9.56106949e+01 1.04445969e+02 1.19737633e+02 1.10200890e+02 1.21955910e+02 1.64807678e+02 1.87970474e+02 1.68233078e+02 1.18249100e+02 1.07508385e+02 1.27388298e+02 1.57004944e+02 1.62971436e+02 1.38770309e+02 1.35994507e+02 1.29381104e+02 1.57082993e+02 1.67511948e+02 1.74548279e+02 1.46418304e+02 1.35875748e+02 1.53319336e+02 1.76231476e+02 1.60537323e+02 1.33466980e+02 1.41284103e+02 1.54851898e+02 1.53757904e+02 1.32491257e+02 1.36879166e+02 1.63436050e+02 1.78142960e+02 1.69032227e+02 1.34208862e+02 1.39620956e+02 1.48525650e+02 1.65562286e+02 1.55736969e+02 1.39577713e+02 1.45280869e+02 1.44787598e+02 1.64346756e+02 1.68471924e+02 1.68078323e+02 1.54711105e+02 1.49441360e+02 1.58967453e+02 1.68463287e+02 1.61063171e+02 1.40481018e+02 1.36131607e+02 1.33047897e+02 1.24643883e+02 1.08997726e+02 1.16751999e+02 1.38928040e+02 1.41420258e+02 1.30656006e+02 1.14671234e+02 1.34211197e+02 1.41027740e+02 1.48111084e+02 1.57566895e+02 1.62594147e+02 1.53761261e+02 1.26027824e+02 1.20075691e+02 1.37640518e+02 1.56174744e+02 1.47368317e+02 1.24485001e+02 1.12727982e+02 1.25493713e+02 1.39626038e+02 1.37177948e+02 1.31752762e+02 1.20902206e+02 1.11234695e+02 9.80814590e+01 1.05121269e+02 1.18779793e+02 1.22380821e+02 1.15773186e+02 1.08596802e+02 1.27249130e+02 1.34816437e+02 1.40867813e+02 1.37129730e+02 1.36808884e+02 1.30242233e+02 1.10864471e+02 1.06097908e+02 1.20650291e+02 1.47371567e+02 1.54670532e+02 1.35203415e+02 1.16993362e+02 1.15642868e+02 1.29246323e+02 1.37899338e+02 1.33208755e+02 1.23481262e+02 1.19459389e+02 1.26604332e+02 1.41613708e+02 1.44348099e+02 1.36882339e+02 1.27489174e+02 1.18181343e+02 1.20047478e+02 1.24830429e+02 1.37109756e+02 1.49186295e+02 1.53031250e+02 1.46369614e+02 1.32805756e+02 1.26472878e+02 1.32942932e+02 1.41355118e+02 1.41335495e+02 1.33284637e+02 1.27037056e+02 1.30298462e+02 1.38627304e+02 1.44682098e+02 1.44934555e+02 1.40571823e+02 1.38058624e+02 1.36650177e+02 1.39837479e+02 1.41119629e+02 1.42094772e+02 1.41027481e+02 1.40521637e+02 1.42016037e+02 1.43324936e+02 1.44477325e+02 1.44201309e+02 1.43374542e+02 1.42942780e+02 1.43065292e+02 1.43608749e+02 1.43520813e+02 1.42018875e+02 1.40686737e+02 1.41325150e+02 1.44364609e+02 1.46663742e+02 1.46271286e+02 1.44383255e+02 1.44507492e+02 1.46536560e+02 1.48075378e+02 1.48753464e+02 1.45464523e+02 1.43338211e+02 1.40397400e+02 1.40282867e+02 1.42592087e+02 1.45219101e+02 1.48897064e+02 1.47526917e+02 1.43834274e+02 1.38813400e+02 1.38634415e+02 1.43736771e+02 1.50196533e+02 1.47496643e+02 1.41397156e+02 1.37540344e+02 1.43639969e+02 1.53609650e+02 1.54906479e+02 1.48173691e+02 1.35825089e+02 1.34817810e+02 1.44512268e+02 1.53551605e+02 1.59122147e+02 1.47586426e+02 1.44282272e+02 1.37922562e+02 1.38223434e+02 1.37193314e+02 1.35497269e+02 1.40621643e+02 1.36208252e+02 1.32634766e+02 1.35130463e+02 1.44320023e+02 1.61473907e+02 1.66620041e+02 1.56989883e+02 1.29956924e+02 1.08895004e+02 1.12512062e+02 1.37623871e+02 1.63880066e+02 1.70470795e+02 1.52087143e+02 1.30319458e+02 1.24774498e+02 1.40846207e+02 1.61527893e+02 1.55358246e+02 1.40620148e+02 1.21760773e+02 1.17977745e+02 1.24833786e+02 1.40597656e+02 1.58709381e+02 1.57180359e+02 1.37168015e+02 1.10286812e+02 1.06659363e+02 1.28707794e+02 1.57808762e+02 1.52891373e+02 1.27606728e+02 1.10405182e+02 1.17526993e+02 1.34741638e+02 1.40040909e+02 1.45217865e+02 1.37341965e+02 1.30466553e+02 1.39954208e+02 1.41246445e+02 1.49978333e+02 1.34688293e+02 1.24691612e+02 1.05235672e+02 9.40233231e+01 1.04928581e+02 1.23031906e+02 1.49189880e+02 1.61542053e+02 1.46457779e+02 1.19558815e+02 1.13373863e+02 1.42122086e+02 1.73078690e+02 1.70704559e+02 1.47554337e+02 1.13350533e+02 1.04998314e+02 1.19252609e+02 1.36640137e+02 1.39287918e+02 1.12130692e+02 8.87262268e+01 6.82618637e+01 7.49535370e+01 1.08326836e+02 1.04318649e+02 9.22763596e+01 5.89042664e+01 5.56943588e+01 6.50981674e+01 8.58635864e+01 1.31866898e+02 1.50052704e+02 1.43753448e+02 1.04846298e+02 8.62017746e+01 1.14049232e+02 1.52745438e+02 1.52837173e+02 1.09026329e+02 7.39086838e+01 8.50876312e+01 1.26953781e+02 1.60368088e+02 1.65311615e+02 1.30248016e+02 8.61416168e+01 7.27468796e+01 7.84402390e+01 9.56064148e+01 1.08834641e+02 1.35087799e+02 1.38002930e+02 1.25804779e+02 1.11019630e+02 1.26337555e+02 1.66317062e+02 1.92775421e+02 1.62947754e+02 1.06195763e+02 7.43409348e+01 1.03445511e+02 1.60713638e+02 1.73679794e+02 1.43873032e+02 9.03711777e+01 8.40598145e+01 1.17075081e+02 1.34398422e+02 1.36577560e+02 1.02515739e+02 9.18613358e+01 9.83853912e+01 1.12809067e+02 1.43988419e+02 1.37555161e+02 1.34360458e+02 8.24883499e+01 4.68394775e+01 5.23562698e+01 8.01549606e+01 1.28669312e+02 1.49524048e+02 1.49063889e+02 9.16841431e+01 -3.79773664e+00 -4.51490326e+01 -2.98581600e+01 9.15785599e+01 1.25665207e+02 1.79947159e+02 2.03030441e+02 -1.15853687e+03 -1.84409937e+03 -3.68945703e+03 -1.14620293e+04 362859104. -2.41568486e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 238809552. 180030000. 205186256. -205166352. -2.87536582e+04 -1.00697207e+04 -2.77751367e+03 -2.18407883e+02 1.22181454e+01 7.86886368e+01 8.62977371e+01 4.19480705e+01 3.27194214e+01 5.76427383e+01 1.48958801e+02 1.47182693e+02 9.91612091e+01 2.69396381e+01 3.80432816e+01 1.08904854e+02 1.73745316e+02 1.92459229e+02 1.35207108e+02 4.25837669e+01 2.29567833e+01 8.66911240e+01 1.60884811e+02 1.59551331e+02 1.02510300e+02 1.00652534e+02 1.43098099e+02 1.53087479e+02 1.13252419e+02 6.73653107e+01 6.43299408e+01 5.06279297e+01 3.02518959e+01 3.10707588e+01 8.34282150e+01 1.74756073e+02 1.83155228e+02 1.23027489e+02 5.96123428e+01 5.75241280e+01 1.20207298e+02 1.87008194e+02 1.78840729e+02 8.35838699e+01 -2.60081749e+01 -1.70014095e+01 9.48052673e+01 1.50230530e+02 1.57354980e+02 9.18564301e+01 6.67325211e+01 5.02278137e+01 4.27578850e+01 6.41706848e+01 1.01520737e+02 1.68139374e+02 1.45479874e+02 8.17198486e+01 5.92770081e+01 1.03821793e+02 1.81324890e+02 1.81095627e+02 1.38630600e+02 6.96632233e+01 4.04815826e+01 1.10431808e+02 2.01497375e+02 2.73227753e+02 2.32383667e+02 1.30542633e+02 9.58106384e+01 1.52102554e+02 1.93569901e+02 1.80365585e+02 9.03166504e+01 7.40570831e+01 9.77998199e+01 1.39378448e+02 1.33182632e+02 1.33272400e+02 1.63702393e+02 1.25831474e+02 6.03208313e+01 2.47589378e+01 1.00142075e+02 2.04518951e+02 2.24791260e+02 1.93624939e+02 1.16494225e+02 5.11622200e+01 4.41185188e+01 1.07282585e+02 1.67598740e+02 1.51954163e+02 4.92251854e+01 -1.86624956e+00 8.38772736e+01 1.54538757e+02 1.58482193e+02 4.75743446e+01 -3.01756859e+00 5.12960577e+00 2.27771988e+01 4.55550919e+01 7.47400436e+01 1.54753479e+02 1.46493042e+02 8.47656937e+01 2.55361576e+01 3.80535393e+01 1.06224289e+02 1.19249130e+02 6.96925507e+01 2.92559814e+01 -1.52383099e+01 3.06150246e+00 7.77099838e+01 1.50412582e+02 1.72024567e+02 6.00897636e+01 1.18693190e+01 4.75882988e+01 8.55859833e+01 8.59268265e+01 3.61889229e+01 4.47512436e+01 5.01102829e+01 2.07793217e+01 2.00692248e+00 2.02802162e+01 1.08965477e+02 1.09452904e+02 4.23608894e+01 -7.09108543e+00 2.77740455e+00 7.01721115e+01 5.52708969e+01 5.00811115e-02 -3.64869804e+01 -7.23913956e+01 -2.36128349e+01 5.65686150e+01 1.23968552e+02 1.16344398e+02 4.32524490e+01 2.81162796e+01 4.41433372e+01 4.11057129e+01 1.72141132e+01 -2.18703442e+01 -5.87252846e+01 -8.32059784e+01 -1.00341835e+02 -6.31927948e+01 3.11014414e+00 9.05068588e+01 1.18688499e+02 8.41158752e+01 3.48062515e+01 4.32701149e+01 1.06349800e+02 1.63595078e+02 1.21801071e+02 1.66456871e+01 -6.23053856e+01 -5.45023155e+01 4.92970314e+01 1.02298035e+02 9.96133194e+01 2.67210464e+01 1.66690331e+01 3.32630539e+01 3.96339111e+01 4.90744133e+01 6.51535339e+01 6.93157425e+01 3.52986908e+00 -7.44274979e+01 -7.84796143e+01 -4.46864548e+01 1.23253117e+01 5.66359787e+01 6.27012672e+01 5.03621674e+01 3.84852715e+01 1.04336258e+02 1.62910843e+02 1.34984558e+02 2.71022091e+01 -6.82379227e+01 -7.46242294e+01 4.88853598e+00 2.87689266e+01 3.16941071e+01 -5.03742485e+01 -4.16597900e+01 6.80957174e+00 9.02175598e+01 1.36199524e+02 1.43256134e+02 1.92272858e+02 1.51601212e+02 5.38983383e+01 -2.14402828e+01 -1.48497019e+01 7.48799210e+01 8.40733032e+01 2.62188168e+01 -5.44959450e+01 -1.26872467e+02 -8.50530014e+01 2.87863464e+01 1.40566925e+02 1.15992859e+02 4.43001747e+00 -2.52820568e+01 1.48889437e+01 4.16023636e+01 4.70982666e+01 6.59689474e+00 -2.86812019e+01 -5.27693481e+01 -4.11095467e+01 -2.62329922e+01 1.29099007e+01 7.83897095e+01 1.15847328e+02 8.66042633e+01 4.02510452e+01 2.38159695e+01 2.76312237e+01 -4.82632208e+00 -5.25466690e+01 -6.67678680e+01 -5.65945549e+01 -7.97230291e+00 8.60239315e+00 2.63152905e+01 1.24531107e+01 -2.41876488e+01 -3.62390976e+01 -2.95110760e+01 6.81126070e+00 1.41557217e+01 -3.63843155e+00 -1.99931965e+01 -2.28535576e+01 8.16007996e+00 1.95766716e+01 1.81167450e+01 -6.82223225e+00 -2.28149185e+01 -3.50588837e+01 -3.59631920e+01 -4.45285606e+01 -3.41516304e+01 -2.69302273e+01 -9.50769711e+00 -2.36450424e+01 -2.94816494e+01 -3.71675072e+01 -3.39351692e+01 -4.49633636e+01 -6.01781998e+01 -5.59118042e+01 -6.54982147e+01 -6.94950943e+01 -6.35072517e+01 -3.10506516e+01 -2.23879337e+01 -4.72339439e+01 -6.21809044e+01 -5.23674088e+01 -4.53955460e+01 -5.42093620e+01 -6.58275223e+01 -6.43341446e+01 -6.48088684e+01 -5.14993324e+01 -4.45512276e+01 -3.91808167e+01 -5.42168732e+01 -5.49779129e+01 -7.33774033e+01 -7.60037079e+01 -6.56990662e+01 -4.82122040e+01 -5.46947479e+01 -6.70423279e+01 -7.02671051e+01 -4.08448830e+01 -1.75678825e+01 -6.52843475e+00 -2.90872078e+01 -4.71897774e+01 -6.06503830e+01 -5.49183884e+01 -4.48045273e+01 -3.56366882e+01 -3.22275276e+01 -5.33616753e+01 -5.48122063e+01 -5.73614655e+01 -5.34053879e+01 -6.79854126e+01 -6.84462891e+01 -6.21610069e+01 -6.21176376e+01 -5.76786575e+01 -4.88158875e+01 -3.19396095e+01 -1.66770630e+01 -2.80214272e+01 -2.98191090e+01 -5.19921112e+01 -6.02907944e+01 -1.01134758e+02 -1.28352524e+02 -1.24153084e+02 -9.27326584e+01 -6.49282913e+01 -5.44890518e+01 -3.58348885e+01 -3.71063309e+01 -7.31878967e+01 -1.14122864e+02 -1.04910675e+02 -6.72597198e+01 -3.51647034e+01 -3.17297096e+01 -3.95571327e+01 -3.52581863e+01 -3.55110741e+01 -2.82164879e+01 -4.11962700e+01 -4.48566933e+01 -4.52910233e+01 -5.77278633e+01 -6.66505966e+01 -5.42983208e+01 -3.85337143e+01 -1.09989376e+01 -2.12491589e+01 -2.20694351e+01 -5.84298096e+01 -5.26327515e+01 -4.65354385e+01 -4.46355972e+01 -5.94372253e+01 -6.45292587e+01 -3.60032349e+01 -5.65945005e+00 -3.51067877e+00 -4.06798706e+01 -7.09688950e+01 -8.29120178e+01 -6.60230331e+01 -1.77178669e+01 1.38743954e+01 -7.82273245e+00 -7.72914886e+01 -1.04045677e+02 -8.42638092e+01 -6.64132614e+01 -4.79290619e+01 -2.97710876e+01 -1.91033351e+00 -2.01671009e+01 -4.52403450e+01 -7.73644867e+01 -7.31674194e+01 -7.02944031e+01 -4.50635262e+01 -3.64604874e+01 -4.42568092e+01 -7.12836304e+01 -8.88775101e+01 -9.52630005e+01 -9.10106125e+01 -9.21422272e+01 -9.92503204e+01 -1.08315163e+02 -1.09106964e+02 -9.25962524e+01 -7.52422409e+01 -8.53441391e+01 -9.46544342e+01 -9.95322266e+01 -8.96147690e+01 -8.74131241e+01 -1.01782127e+02 -7.60751190e+01 -5.46043205e+01 -5.47370148e+01 -9.14973450e+01 -1.15422852e+02 -9.77360611e+01 -8.79063644e+01 -7.93650665e+01 -6.72011337e+01 -5.20484238e+01 -5.15798950e+01 -4.23720245e+01 -4.27140160e+01 -5.01268120e+01 -8.14183426e+01 -9.04195862e+01 -8.15328598e+01 -7.92310791e+01 -8.31052094e+01 -8.84430695e+01 -8.55915604e+01 -8.52819824e+01 -5.88157310e+01 -3.72791901e+01 -3.65273781e+01 -6.28803825e+01 -8.66769028e+01 -9.33401260e+01 -9.93634033e+01 -1.00158875e+02 -9.83285446e+01 -9.37912979e+01 -9.85270386e+01 -1.13713852e+02 -1.36925812e+02 -1.44552719e+02 -1.34970612e+02 -1.08577538e+02 -1.06021172e+02 -1.13954193e+02 -1.18217850e+02 -1.13325760e+02 -1.06590248e+02 -1.38849747e+02 -1.73429398e+02 -1.79327667e+02 -1.42399582e+02 -1.03773018e+02 -9.89266205e+01 -1.23287704e+02 -1.60940552e+02 -2.76704742e+02 -4.51772034e+02 -6.77577271e+02 -2.60120898e+03 -3.75594922e+03 -4.17050476e+02 -5.00505127e+02 -6.30640320e+02 -8.88686707e+02 -7.97525024e+02 -4.73307556e+02 -7.19672363e+02 -1.24995740e+03 -1.01706836e+04 -2.52621699e+04 726899072. 581115200. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1342290816. -200843328. -525966304. -9.63161133e+03 -3.56590454e+03 -4.33552917e+02 -1.97430420e+02 -1.53939133e+02 -1.70416199e+02 -1.66839066e+02 -1.48718826e+02 -1.28391525e+02 -1.34461945e+02 -1.39623962e+02 -1.39501495e+02 -1.39895142e+02 -1.51979340e+02 -1.65539139e+02 -1.50414185e+02 -1.20469147e+02 -1.13203697e+02 -1.34022705e+02 -1.52298340e+02 -1.40058960e+02 -1.38201996e+02 -1.42585571e+02 -1.52433762e+02 -1.56087326e+02 -1.57517212e+02 -1.52803329e+02 -1.42334396e+02 -1.38214874e+02 -1.39479614e+02 -1.45260605e+02 -1.29023788e+02 -1.10275314e+02 -1.07218140e+02 -1.19001991e+02 -1.29770523e+02 -1.25855064e+02 -1.18634705e+02 -1.17762291e+02 -1.11138481e+02 -1.06195641e+02 -1.03854568e+02 -1.01450851e+02 -1.02600639e+02 -1.06986343e+02 -1.12492050e+02 -1.17590294e+02 -1.14605659e+02 -1.14099464e+02 -1.15519104e+02 -1.15391312e+02 -1.15902679e+02 -1.11032967e+02 -1.08178505e+02 -1.13059860e+02 -1.28567429e+02 -1.47300079e+02 -1.56964081e+02 -1.48772568e+02 -1.36963043e+02 -1.29106232e+02 -1.40835403e+02 -1.50787155e+02 -1.46035156e+02 -1.30948685e+02 -1.18190834e+02 -1.18240433e+02 -1.18916931e+02 -1.12248909e+02 -9.74747543e+01 -1.07367126e+02 -1.26262459e+02 -1.43522675e+02 -1.41162766e+02 -1.31980347e+02 -1.32887894e+02 -1.29526901e+02 -1.31714691e+02 -1.29804428e+02 -1.33663589e+02 -1.34161514e+02 -1.37907684e+02 -1.39483887e+02 -1.38458023e+02 -1.35793365e+02 -1.36687729e+02 -1.47297241e+02 -1.60483719e+02 -1.53398300e+02 -1.45055664e+02 -1.34690033e+02 -1.41222733e+02 -1.44848389e+02 -1.50607819e+02 -1.55625351e+02 -1.48329758e+02 -1.37019485e+02 -1.32517197e+02 -1.38070709e+02 -1.49646683e+02 -1.49888153e+02 -1.48939255e+02 -1.42851944e+02 -1.39380737e+02 -1.39688644e+02 -1.38903320e+02 -1.39512787e+02 -1.38066208e+02 -1.40395752e+02 -1.39877243e+02 -1.38614410e+02 -1.43691956e+02 -1.49665894e+02 -1.49335159e+02 -1.43309372e+02 -1.37953369e+02 -1.37876938e+02 -1.35599670e+02 -1.36009155e+02 -1.34831543e+02 -1.35325470e+02 -1.35061111e+02 -1.42622314e+02 -1.49418121e+02 -1.50013580e+02 -1.44495865e+02 -1.39297928e+02 -1.36141632e+02 -1.34146439e+02 -1.34510895e+02 -1.37290756e+02 -1.39120438e+02 -1.37450226e+02 -1.40111954e+02 -1.41029739e+02 -1.41255783e+02 -1.40010849e+02 -1.40188156e+02 -1.41524750e+02 -1.41899612e+02 -1.41664734e+02 -1.41788971e+02 -1.42703201e+02 -1.42582184e+02 -1.42746582e+02 -1.42846130e+02 -1.43566086e+02 -1.44074036e+02 -1.43416397e+02 -1.42766724e+02 -1.42342529e+02 -1.42206024e+02 -1.41763382e+02 -1.41282242e+02 -1.41244156e+02 -1.41879883e+02 -1.44607086e+02 -1.46155624e+02 -1.46102768e+02 -1.45042343e+02 -1.43898132e+02 -1.43767319e+02 -1.43121536e+02 -1.42863678e+02 -1.42994614e+02 -1.43155930e+02 -1.43186996e+02 -1.43150375e+02 -1.43069458e+02 -1.43003998e+02 -1.43013077e+02 -1.43333115e+02 -1.43806961e+02 -1.44098465e+02 -1.43809235e+02 -1.43287201e+02 -1.42454605e+02 -1.42663589e+02 -1.42803360e+02 -1.43097763e+02 -1.42796967e+02 -1.43068649e+02 -1.43092392e+02 -1.43338730e+02 -1.43595123e+02 -1.43080292e+02 -1.42726501e+02 -1.42811142e+02 -1.43351242e+02 -1.43828110e+02 -1.42132599e+02 -1.41162674e+02 -1.40246185e+02 -1.40336716e+02 -1.41393646e+02 -1.44773087e+02 -1.49084747e+02 -1.51363022e+02 -1.51888367e+02 -1.51482712e+02 -1.52796509e+02 -1.49558182e+02 -1.44297974e+02 -1.37999924e+02 -1.36496948e+02 -1.37425247e+02 -1.39549286e+02 -1.39876663e+02 -1.39403122e+02 -1.37247864e+02 -1.37250031e+02 -1.37607544e+02 -1.39146225e+02 -1.38969376e+02 -1.38462723e+02 -1.32731857e+02 -1.26418816e+02 -1.27911842e+02 -1.32817017e+02 -1.39071655e+02 -1.42132080e+02 -1.45761948e+02 -1.53711548e+02 -1.59138519e+02 -1.56597336e+02 -1.51394913e+02 -1.41304871e+02 -1.44764145e+02 -1.47223923e+02 -1.52074280e+02 -1.51707779e+02 -1.49294998e+02 -1.49237717e+02 -1.49819290e+02 -1.49343521e+02 -1.45671280e+02 -1.42226196e+02 -1.42431168e+02 -1.50228256e+02 -1.59891022e+02 -1.69507538e+02 -1.72891739e+02 -1.55923660e+02 -1.36148071e+02 -1.25372070e+02 -1.31082733e+02 -1.42318802e+02 -1.41519760e+02 -1.45013901e+02 -1.43173431e+02 -1.42638779e+02 -1.39207611e+02 -1.37909241e+02 -1.38786240e+02 -1.42065018e+02 -1.41521378e+02 -1.30318039e+02 -1.15508621e+02 -1.12540924e+02 -1.18703339e+02 -1.27547653e+02 -1.34173599e+02 -1.42927872e+02 -1.44320663e+02 -1.38367508e+02 -1.36754333e+02 -1.42857010e+02 -1.44246750e+02 -1.36356400e+02 -1.29572403e+02 -1.26108269e+02 -1.27840813e+02 -1.29723312e+02 -1.33327393e+02 -1.31536316e+02 -1.33801575e+02 -1.32882050e+02 -1.32392914e+02 -1.24292198e+02 -1.19007500e+02 -1.20107216e+02 -1.32449066e+02 -1.52859756e+02 -1.54261734e+02 -1.40914993e+02 -1.23651939e+02 -1.27996941e+02 -1.31560913e+02 -1.31911530e+02 -1.29023102e+02 -1.28873840e+02 -1.33490067e+02 -1.43469971e+02 -1.52694580e+02 -1.50430222e+02 -1.34815399e+02 -1.21058037e+02 -1.19954056e+02 -1.26973961e+02 -1.17924919e+02 -1.00707703e+02 -9.40724106e+01 -9.93055878e+01 -1.14878525e+02 -1.12530678e+02 -1.14493919e+02 -1.13393684e+02 -1.20725716e+02 -1.19632385e+02 -1.18230545e+02 -1.08763649e+02 -1.13101395e+02 -1.12571404e+02 -1.14090103e+02 -1.10585838e+02 -1.16576019e+02 -1.22196541e+02 -1.35197266e+02 -1.46741104e+02 -1.44495865e+02 -1.35080261e+02 -1.24064377e+02 -1.25160393e+02 -1.19067345e+02 -1.11591988e+02 -1.12538246e+02 -1.38201706e+02 -1.59787460e+02 -1.63491776e+02 -1.43915085e+02 -1.26642418e+02 -1.27139740e+02 -1.29810562e+02 -1.30600967e+02 -1.26501068e+02 -1.39493240e+02 -1.66503067e+02 -1.70940933e+02 -1.53118851e+02 -1.22114616e+02 -1.24164291e+02 -1.24029289e+02 -1.26317436e+02 -1.22195717e+02 -1.25668320e+02 -1.31902145e+02 -1.41748901e+02 -1.44451569e+02 -1.36513290e+02 -1.27302124e+02 -1.30831284e+02 -1.54909866e+02 -1.88839432e+02 -1.90875412e+02 -1.64190979e+02 -1.33005493e+02 -1.27243614e+02 -1.21751938e+02 -1.21622002e+02 -1.25782448e+02 -1.57357956e+02 -1.76335800e+02 -2.05536179e+02 -2.08693863e+02 -1.82118881e+02 -1.53906204e+02 -1.20762466e+02 -1.43126160e+02 -1.64031937e+02 -1.38837692e+02 -8.68082809e+01 -5.62254601e+01 -7.97910156e+01 -1.14472710e+02 -1.11100929e+02 -1.11032784e+02 -1.04564468e+02 -1.03471558e+02 -9.27665482e+01 -8.53369598e+01 -8.10114899e+01 -7.88174210e+01 -8.08135147e+01 -8.42554779e+01 -8.60070572e+01 -8.29863510e+01 -8.53412094e+01 -1.00008430e+02 -1.29784302e+02 -1.22196449e+02 -1.01711754e+02 -6.95195923e+01 -9.80439606e+01 -1.29347992e+02 -1.00953461e+02 -4.31000900e+01 -4.47327919e+01 -1.13997284e+02 -1.56363312e+02 -1.28993408e+02 -9.62777939e+01 -1.13615929e+02 -1.50045929e+02 -1.55486832e+02 -1.41392014e+02 -1.09853981e+02 -1.12808426e+02 -1.14758331e+02 -1.09147858e+02 -1.07472542e+02 -8.16451721e+01 -6.05383606e+01 -9.05610275e+01 -1.43796310e+02 -1.74133591e+02 -1.46746262e+02 -1.25072655e+02 -1.49086731e+02 -1.71655060e+02 -1.77688339e+02 -1.50823959e+02 -1.18536797e+02 -1.21902039e+02 -1.25703545e+02 -1.32249557e+02 -1.16713554e+02 -1.32147812e+02 -1.59384613e+02 -1.67437943e+02 -1.59267807e+02 -1.21820717e+02 -9.74554749e+01 -8.74709015e+01 -8.75171280e+01 -1.04639870e+02 -5.52858887e+01 -4.77974749e+00 -9.48329353e+00 -7.14624786e+01 -1.22757996e+02 -1.09638062e+02 -8.50226974e+01 -1.06025650e+02 -1.43641800e+02 -1.44217667e+02 -1.18082169e+02 -8.42619781e+01 -7.61803894e+01 -7.53273621e+01 -7.36783295e+01 -7.58669739e+01 -7.67912903e+01 -8.81621017e+01 -1.13241600e+02 -1.22631035e+02 -1.11685387e+02 -8.62452850e+01 -7.32087631e+01 -6.44744720e+01 -6.81759949e+01 -3.28612480e+01 2.61228538e+00 -2.72607155e+01 -1.03582031e+02 -1.46315857e+02 -1.06420746e+02 -5.95270042e+01 -3.65265923e+01 -2.82046185e+01 -2.56736259e+01 -3.28986473e+01 -4.12257538e+01 -3.59783363e+01 -4.23619576e+01 -4.02767792e+01 -4.46600914e+01 -2.98402481e+01 -2.63265324e+01 -2.23988914e+01 -4.45270576e+01 -4.83479042e+01 -3.53512726e+01 -1.47991533e+01 -7.74688196e+00 -3.05277157e+01 -5.08440247e+01 -6.41774292e+01 -9.63170013e+01 -1.25462883e+02 -1.34718979e+02 -1.04673393e+02 -1.03554230e+02 -1.65388336e+02 -2.06632477e+02 -1.78496811e+02 -1.28844513e+02 -1.35406235e+02 -1.79774277e+02 -1.81602371e+02 -1.40839050e+02 -1.07339508e+02 -1.03515869e+02 -1.07974823e+02 -1.09773041e+02 -1.14158257e+02 -1.10272789e+02 -9.11113129e+01 -1.07034210e+02 -1.39933197e+02 -1.64128876e+02 -1.34872101e+02 -9.47355728e+01 -9.52579651e+01 -1.21852737e+02 -8.91990891e+01 -3.68847885e+01 -5.30018044e+00 -2.77608013e+01 -5.75289154e+01 -4.28120537e+01 -4.56890373e+01 -4.68499832e+01 -5.41498375e+01 -4.67582970e+01 -4.52833862e+01 -5.27363510e+01 -4.60529823e+01 -3.82656250e+01 -1.93568230e+01 -2.79512806e+01 -4.27143936e+01 -5.03154716e+01 -7.59288254e+01 -1.02915627e+02 -9.67414093e+01 -5.62740784e+01 -8.38111782e+00 5.37941504e+00 -1.99682742e-01 2.57760429e+01 5.68408813e+01 6.02866173e+01 3.44213943e+01 -3.88545878e-02 2.86502004e-01 -2.50459105e-01 -5.57739716e+01 -1.09851654e+02 -1.20650070e+02 -8.03644485e+01 -5.31120224e+01 -5.79831543e+01 -4.64232140e+01 -2.28488407e+01 -2.46338806e+01 3.08886504e+00 4.07227173e+01 2.51352119e+01 -3.62652931e+01 -7.91224060e+01 -6.10575371e+01 -6.73597031e+01 -1.36104034e+02 -1.77445099e+02 -1.55325439e+02 -7.61604385e+01 -5.38602448e+01 -8.07814636e+01 -8.60007172e+01 -5.68462524e+01 -1.51677918e+00 -1.15883560e+01 -4.06312599e+01 -4.30871162e+01 -2.39940186e+01 1.03831625e+01 2.60313091e+01 3.37056885e+01 4.14218483e+01 2.40893230e+01 2.99450054e+01 3.39578400e+01 2.57626963e+00 -2.83070183e+01 -4.50854530e+01 -1.41474724e+01 1.08483534e+01 -9.01068020e+00 -3.94771309e+01 -2.35455723e+01 1.72376450e+02 3.28999969e+02 3.86801605e+02 2.82317188e+03 4.55244678e+03 2.18530334e+02 6.24774902e+02 7.27376892e+02 -3.20098267e+03 -1.45053638e+03 3.29319116e+03 3.85698828e+03 -1.80620825e+03 -2.62980200e+03 -5.22028516e+03 -2.32289375e+04 -652330752. 0. 0. 0. 0. 0. 0. 2.26273956e+10 2.26273956e+10 2.44004434e+04 5.29405391e+04 5.29405391e+04 3.13963192e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -855827968. -8622476. 6835689. 1.97393965e+04 8.13630615e+03 -8.81611450e+02 8.63096985e+02 3.10262622e+03 3.69037018e+02 7.28763351e+01 7.18290558e+01 4.49999161e+01 2.92763481e+01 6.53043823e+01 1.05900772e+02 7.67033463e+01 -9.03530216e+00 -4.97146759e+01 1.37813206e+01 1.23876480e+02 1.16288055e+02 2.29962425e+01 -9.00945206e+01 -1.05883774e+02 -5.42587357e+01 -6.24374771e+01 -1.03309921e+02 -1.09137169e+02 -5.99316101e+01 -1.77437382e+01 -5.92276878e+01 -1.63078751e+02 -1.81847519e+02 -1.12780533e+02 -2.65086327e+01 2.29290791e+01 3.52316208e+01 7.18866043e+01 1.16285172e+02 1.29199951e+02 6.88424530e+01 -9.07870865e+01 -1.73310913e+02 -1.29870346e+02 -1.98524647e+01 5.52070923e+01 4.93319054e+01 2.05268459e+01 -2.67416935e+01 -8.57312775e+00 -2.82054520e+01 -5.55666275e+01 -2.92110062e+01 7.14235077e+01 1.83176224e+02 1.64581528e+02 1.42516098e+01 -6.19023018e+01 -2.44336262e+01 5.92957497e+01 4.54148979e+01 -1.93980083e+01 -1.85320301e+01 5.64001274e+01 1.32082947e+02 1.16799530e+02 -2.34380078e+00 -8.39881058e+01 -5.95003777e+01 1.55483017e+01 3.71344223e+01 8.11025620e+00 7.63497210e+00 5.49057884e+01 1.21728554e+02 1.02846069e+02 6.70124283e+01 6.89259262e+01 1.11898384e+02 1.30498123e+02 1.02764709e+02 5.14211311e+01 1.06564033e+00 -1.00985250e+01 2.38960476e+01 5.58180733e+01 5.28228493e+01 9.75257950e+01 1.71898422e+02 1.96469437e+02 1.20235641e+02 -1.75388470e+01 -7.81409378e+01 -3.29556465e+01 7.78800888e+01 1.83052536e+02 2.20309265e+02 1.98481598e+02 1.71634750e+02 1.78920410e+02 1.49265503e+02 5.91558952e+01 -1.28119392e+01 1.59216881e+01 8.28097839e+01 1.14749489e+02 8.95549393e+01 3.23373718e+01 1.90562210e+01 5.30253372e+01 9.29257736e+01 8.56893845e+01 7.81292877e+01 1.14674759e+02 1.98975037e+02 2.11561981e+02 1.49642334e+02 6.55526657e+01 6.52252884e+01 1.24028503e+02 1.70142044e+02 1.70907211e+02 1.18383789e+02 6.17750244e+01 4.13048134e+01 7.19307480e+01 7.10236359e+01 2.62451782e+01 2.08167858e+01 7.49164124e+01 1.27944946e+02 1.29595490e+02 7.54099808e+01 4.82715683e+01 7.62707138e+01 1.07408226e+02 1.23723358e+02 1.02050064e+02 1.17270218e+02 1.68411514e+02 1.82238876e+02 1.13234955e+02 -1.04273052e+01 -7.74418411e+01 -2.47017879e+01 6.12766647e+01 9.86769943e+01 8.09972382e+01 5.28124428e+01 5.00931740e+01 4.41112633e+01 2.94386506e+00 -4.71944084e+01 -5.42923851e+01 1.58849144e+01 1.30463455e+02 1.74549744e+02 1.06766693e+02 3.29481964e+01 3.51635551e+01 6.93961411e+01 4.08812981e+01 -4.01065598e+01 -3.53054543e+01 4.92037239e+01 1.26796921e+02 7.24946060e+01 -5.99451828e+01 -1.34401352e+02 -7.84364319e+01 2.39866600e+01 7.98930130e+01 7.75610733e+01 8.48044205e+01 1.01327843e+02 8.13653183e+01 1.89951859e+01 -6.41330948e+01 -2.62997932e+01 4.09911728e+01 1.11597404e+02 9.53658600e+01 6.55388641e+01 3.06918316e+01 1.86860943e+01 1.91482353e+01 -3.26495409e+00 -4.11828308e+01 -2.21580257e+01 5.56706886e+01 1.29283066e+02 1.14672935e+02 3.54179764e+01 -2.95423775e+01 -1.61446686e+01 3.89475098e+01 7.66218872e+01 8.31951141e+01 9.77826233e+01 1.54957001e+02 1.81916611e+02 1.23273926e+02 4.44321213e+01 1.20650177e+01 5.67083817e+01 1.11450172e+02 1.37524414e+02 1.23907791e+02 1.02941940e+02 8.04427185e+01 8.79839783e+01 6.74497681e+01 3.77151413e+01 6.66914825e+01 1.12636200e+02 1.38198471e+02 1.25462227e+02 8.52082977e+01 7.81173172e+01 9.44597244e+01 1.01644173e+02 9.49547882e+01 5.77765121e+01 8.49107971e+01 1.24844902e+02 1.55339523e+02 1.59385651e+02 1.00943298e+02 6.36051712e+01 7.44842911e+01 1.36449127e+02 1.49786041e+02 1.16239052e+02 6.98303299e+01 7.96199646e+01 1.08169250e+02 1.04865807e+02 6.85236588e+01 5.97086220e+01 1.12099167e+02 1.42015778e+02 1.14462585e+02 8.18709488e+01 1.05832306e+02 1.25564758e+02 1.11217270e+02 9.53162994e+01 8.24696426e+01 9.66877136e+01 7.04915543e+01 5.70277252e+01 5.73177071e+01 4.64294930e+01 3.13215923e+01 2.71529598e+01 8.28132553e+01 1.04046494e+02 1.05078087e+02 6.22962990e+01 7.39792099e+01 7.96373138e+01 6.96760101e+01 3.89223061e+01 2.72036972e+01 7.50944672e+01 1.08805763e+02 1.10848534e+02 6.44038544e+01 6.10566330e+01 7.31483765e+01 9.77215729e+01 9.58287506e+01 6.04780045e+01 7.02054062e+01 9.39801025e+01 1.39979172e+02 1.56453278e+02 1.44220901e+02 1.12697823e+02 8.63129959e+01 1.05619385e+02 1.35765198e+02 1.48419586e+02 1.33811874e+02 1.49036392e+02 1.50512436e+02 1.23179886e+02 8.40336380e+01 8.03476410e+01 1.35093414e+02 1.50146393e+02 1.28295853e+02 8.42231827e+01 1.02437904e+02 1.25005348e+02 1.31121841e+02 1.15607185e+02 9.59321899e+01 9.98707504e+01 9.25491333e+01 1.17374565e+02 1.29531387e+02 1.32128601e+02 1.08529755e+02 9.56612854e+01 1.17331131e+02 1.35587021e+02 1.41630096e+02 1.39600662e+02 1.74173813e+02 1.92046799e+02 1.88663879e+02 1.73471313e+02 1.72904465e+02 1.92323563e+02 1.99375916e+02 1.82299210e+02 1.44295715e+02 1.29759277e+02 1.27291878e+02 1.37050903e+02 1.28893738e+02 1.06645782e+02 8.94189987e+01 8.23078232e+01 1.07813026e+02 1.19831360e+02 1.29754776e+02 1.21493286e+02 1.26334259e+02 1.34604431e+02 1.46472809e+02 1.43192352e+02 1.43585281e+02 1.59059036e+02 1.72911667e+02 1.63614777e+02 1.43433609e+02 1.42070709e+02 1.37650894e+02 1.15954201e+02 9.57838364e+01 8.85409241e+01 1.10825935e+02 1.14971741e+02 1.18418869e+02 1.32188416e+02 1.32155533e+02 1.19402908e+02 8.95603333e+01 8.30870056e+01 1.07979828e+02 1.29005692e+02 1.28082138e+02 1.10670486e+02 9.72782288e+01 1.06731918e+02 1.23907433e+02 1.37434219e+02 1.37910126e+02 1.21892517e+02 1.12636253e+02 9.83607483e+01 1.00245621e+02 1.00641830e+02 9.27435760e+01 8.87751389e+01 8.65493011e+01 1.10183296e+02 1.13758163e+02 1.15446114e+02 1.13865005e+02 1.10171982e+02 9.68016205e+01 6.97288437e+01 6.64701080e+01 8.89799118e+01 1.24210579e+02 1.38955048e+02 1.18176743e+02 9.12292404e+01 9.11954803e+01 1.18327103e+02 1.47266556e+02 1.39250320e+02 1.14755684e+02 1.00955292e+02 1.02567596e+02 1.17674034e+02 1.14701134e+02 1.06808754e+02 9.99241791e+01 9.83508987e+01 1.10316109e+02 1.09847969e+02 1.05523026e+02 9.83727417e+01 9.94418030e+01 1.05807388e+02 1.04106911e+02 1.02343231e+02 1.13114838e+02 1.25972176e+02 1.24888573e+02 1.05919701e+02 9.40325623e+01 9.95379562e+01 1.14025436e+02 1.21599480e+02 1.19010773e+02 1.09989128e+02 1.06002319e+02 1.05059921e+02 1.12622284e+02 1.13783783e+02 1.12963844e+02 1.09865692e+02 1.07945900e+02 1.12643585e+02 1.15599838e+02 1.20455223e+02 1.19878349e+02 1.18348610e+02 1.14496727e+02 1.09495110e+02 1.07989746e+02 1.11526443e+02 1.17606018e+02 1.19964836e+02 1.17286156e+02 1.12508316e+02 1.11596626e+02 1.14460854e+02 1.17360970e+02 1.16704933e+02 1.14612534e+02 1.14056816e+02 1.14276054e+02 1.14417099e+02 1.14315697e+02 1.14573082e+02 1.15325661e+02 1.16344910e+02 1.16638023e+02 1.17722801e+02 1.18279953e+02 1.16932915e+02 1.13874374e+02 1.12171600e+02 1.14778564e+02 1.17822052e+02 1.17144470e+02 1.12293571e+02 1.07519653e+02 1.09337059e+02 1.15777672e+02 1.17599403e+02 1.14686752e+02 1.08050369e+02 1.09768555e+02 1.15871750e+02 1.21156433e+02 1.25416458e+02 1.20090889e+02 1.20405746e+02 1.17466263e+02 1.17917686e+02 1.20011734e+02 1.22336205e+02 1.28060638e+02 1.22894485e+02 1.15107262e+02 1.06127693e+02 1.09865135e+02 1.21593239e+02 1.31738098e+02 1.25033707e+02 1.10781998e+02 1.00010796e+02 1.02857315e+02 1.12447739e+02 1.17574150e+02 1.19126465e+02 1.15224594e+02 1.17323952e+02 1.21920906e+02 1.30208374e+02 1.40542053e+02 1.37522720e+02 1.20676689e+02 1.07557762e+02 1.06008850e+02 1.15170135e+02 1.22299301e+02 1.33888092e+02 1.40483582e+02 1.21810921e+02 9.50598755e+01 8.24106598e+01 1.02588829e+02 1.28070709e+02 1.30032761e+02 1.06045235e+02 7.51018600e+01 7.84501572e+01 1.08845551e+02 1.43398422e+02 1.55683334e+02 1.36635590e+02 1.18791443e+02 1.17457970e+02 1.26923965e+02 1.34212769e+02 1.22348793e+02 1.22866623e+02 1.19264648e+02 1.08119728e+02 1.04356499e+02 1.03736061e+02 1.22597305e+02 1.16871521e+02 9.33852463e+01 6.46726074e+01 6.97294159e+01 1.14871422e+02 1.48764801e+02 1.41252899e+02 1.00120110e+02 7.21181564e+01 6.94597321e+01 1.02977554e+02 1.34693787e+02 1.48923080e+02 1.23642075e+02 1.07233498e+02 9.25658951e+01 9.36708298e+01 9.88503876e+01 9.52403412e+01 9.36639557e+01 6.93487091e+01 5.59864731e+01 5.66081696e+01 7.55244370e+01 1.12994370e+02 1.25773544e+02 1.04170052e+02 6.59176178e+01 5.45303650e+01 7.70894470e+01 1.13903572e+02 1.11738396e+02 8.68747864e+01 4.67401085e+01 4.17328300e+01 7.68096542e+01 1.16771935e+02 1.35607224e+02 1.04074020e+02 7.19838867e+01 6.93557663e+01 9.53959656e+01 1.23244507e+02 1.25782036e+02 1.23818314e+02 1.11198341e+02 7.91095657e+01 7.06710129e+01 9.48339005e+01 1.52080948e+02 1.73783310e+02 1.41470276e+02 9.53116913e+01 6.19588737e+01 8.44991302e+01 1.22374908e+02 1.44596588e+02 1.30789810e+02 9.74414291e+01 1.00201683e+02 1.26874825e+02 1.57007935e+02 1.57610565e+02 1.17549408e+02 8.88304291e+01 9.64308167e+01 1.28057968e+02 1.65186005e+02 1.59631210e+02 1.53818375e+02 1.38424225e+02 1.16395935e+02 1.01111801e+02 9.06198959e+01 1.26198700e+02 1.49776337e+02 1.39968582e+02 1.03134567e+02 6.89320908e+01 9.39117279e+01 1.31378769e+02 1.55133759e+02 1.16555626e+02 3.84027786e+01 -2.58159947e+00 3.64386902e+01 1.28542755e+02 1.83103333e+02 1.56664017e+02 1.00979881e+02 7.58370056e+01 7.38546448e+01 6.42839661e+01 3.02612743e+01 7.98870697e+01 -2.11959248e+01 -1.00003799e+02 -1.65536304e+03 -2.22267383e+03 -3.89407642e+03 -1.02722529e+04 -155285872. -3.63683302e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.74436659e+09 -366176064. -6.34325439e+03 -1.21440259e+03 1.00040802e+03 -9.69398071e+02 -5.28750488e+03 -2.85249927e+03 -5.52344421e+02 -1.58050934e+02 -8.05359879e+01 -4.29439812e+01 1.79975510e+01 1.10114639e+02 1.41724136e+02 1.22186340e+02 5.48185005e+01 1.21470366e+01 1.97491589e+01 7.65024643e+01 1.57297546e+02 1.57105835e+02 1.33425690e+02 1.06378403e+02 1.04682152e+02 1.04132767e+02 7.31054230e+01 1.03837746e+02 1.04368446e+02 4.71558952e+01 3.64070034e+00 4.33397598e+01 1.57463120e+02 2.20390289e+02 1.47037048e+02 5.24106560e+01 -9.66890049e+00 2.09881573e+01 1.26412804e+02 2.13323425e+02 2.51270630e+02 1.68271133e+02 1.08363098e+02 1.01870338e+02 1.62899948e+02 2.04728317e+02 1.68774338e+02 1.63604736e+02 1.22494102e+02 8.02854767e+01 5.59893532e+01 8.80499725e+01 2.02433167e+02 2.12607544e+02 1.18710930e+02 7.63853639e-02 -2.70081310e+01 7.38566513e+01 1.67413544e+02 1.60547745e+02 8.45754395e+01 4.96919975e+01 1.17992104e+02 2.29255508e+02 2.62175934e+02 2.20049637e+02 9.69833832e+01 1.19555035e+01 8.50647259e+00 8.13748856e+01 1.86320801e+02 2.54688950e+02 2.89720795e+02 2.53735657e+02 1.92037277e+02 1.31344574e+02 1.01747177e+02 1.23783012e+02 1.08128380e+02 3.32812500e+01 -3.89423294e+01 -2.96050758e+01 6.87782974e+01 1.39829712e+02 1.19490410e+02 7.48952637e+01 7.60542393e+00 -2.92053413e+01 6.99016380e+00 1.06070892e+02 1.60849350e+02 1.00817154e+02 2.39051781e+01 3.32315445e+01 8.37888489e+01 9.86972656e+01 6.96961899e+01 8.79060364e+01 8.53661575e+01 4.42486649e+01 1.85374260e+01 4.83300476e+01 1.60835175e+02 1.69766769e+02 6.63095169e+01 -7.29654617e+01 -1.24310478e+02 -2.99134178e+01 6.88479156e+01 1.09120361e+02 8.47166748e+01 4.56595917e+01 3.80211525e+01 6.04557953e+01 1.18377098e+02 1.51790268e+02 9.47760925e+01 -1.01034403e+01 -4.51338005e+01 -7.49200678e+00 3.12415581e+01 4.20783424e+01 8.52776184e+01 8.66554718e+01 -4.36481524e+00 -1.10594421e+02 -1.06739265e+02 3.10598965e+01 9.13332291e+01 1.22506094e+01 -1.01863876e+02 -1.20421173e+02 -1.71509781e+01 8.32041702e+01 1.04713295e+02 6.56937866e+01 -2.15934582e+01 -8.47159195e+01 -5.97686043e+01 4.11824265e+01 1.13582832e+02 5.75727463e+01 -4.10081863e+01 -7.30347366e+01 -4.02013512e+01 3.65667373e-01 3.00920601e+01 9.48099670e+01 1.28045670e+02 9.82522736e+01 4.19289894e+01 3.64318886e+01 1.03212067e+02 1.33912872e+02 6.09984665e+01 -7.05624084e+01 -1.59951691e+02 -1.10378426e+02 2.23144016e+01 1.13370819e+02 9.01289291e+01 1.73094006e+01 -1.23829327e+01 2.78704319e+01 3.45457878e+01 8.53446503e+01 5.62570763e+01 4.59838371e+01 -1.29952550e+00 -6.38579407e+01 -9.18597946e+01 -1.06151634e+02 -1.95508804e+01 2.37248878e+01 -2.73369579e+01 -8.67709808e+01 -5.98524628e+01 5.98032417e+01 1.17355019e+02 7.31717224e+01 1.68989754e+01 -2.68240967e+01 -2.67612514e+01 7.85548687e+00 2.73357906e+01 3.77342033e+01 -3.30276985e+01 -2.33716164e+01 1.49015036e+01 8.16543732e+01 1.54116302e+02 1.97950134e+02 2.39748810e+02 1.67862595e+02 5.25501900e+01 -1.36786356e+01 -1.56812525e+01 5.30910912e+01 5.56286430e+01 -1.69037113e+01 -1.09002396e+02 -1.50287857e+02 -3.41960487e+01 1.13164551e+02 1.88894928e+02 1.48103729e+02 7.87430496e+01 4.66258011e+01 5.57535477e+01 8.67517853e+01 1.26281876e+02 9.68131332e+01 2.54127598e+01 -1.14733381e+01 3.12364006e+01 5.04203682e+01 6.76806412e+01 9.64274521e+01 1.05556587e+02 6.78316574e+01 2.85812054e+01 2.97281246e+01 4.19621811e+01 4.87275267e+00 -4.96077118e+01 -9.45923920e+01 -1.16846558e+02 -6.53200684e+01 -2.63738384e+01 6.37686005e+01 9.71100159e+01 4.67011414e+01 -3.73216095e+01 -7.01956100e+01 -1.02023020e+01 3.80680008e+01 2.78061218e+01 1.00853014e+01 3.81266427e+00 -1.70895755e+00 -8.03125381e+00 -9.99438858e+00 -9.70954418e+00 -5.24599218e+00 -2.00159016e+01 -3.19088421e+01 -6.66081772e+01 -6.27344437e+01 -4.97502823e+01 -1.37796946e+01 -1.73060627e+01 -3.22836266e+01 -3.40548325e+01 -2.70537949e+01 1.47055826e+01 4.32098846e+01 4.93019981e+01 3.12659950e+01 -7.11773062e+00 -6.89314127e+00 -7.97405958e+00 -4.86904621e+00 -2.17929440e+01 -2.03138065e+01 -1.86407509e+01 -1.72761631e+01 -3.81986809e+01 -3.44013290e+01 -3.56056938e+01 -3.82186165e+01 -5.49455910e+01 -5.40872688e+01 -5.72400017e+01 -5.96026077e+01 -4.75297127e+01 -3.79198074e+01 -2.36331615e+01 -3.45235519e+01 -3.52040825e+01 -5.08662491e+01 -5.19640656e+01 -4.74768486e+01 -1.95877094e+01 -2.39286919e+01 -2.04500732e+01 -3.76105614e+01 -2.36851368e+01 -4.50215874e+01 -4.17496567e+01 -4.02012634e+01 -1.79341774e+01 -2.55806026e+01 -3.29698753e+01 -3.67846413e+01 -2.68599472e+01 -2.65701122e+01 -4.59503860e+01 -4.06266365e+01 -2.26858425e+01 -4.29331183e-01 -1.79608679e+00 1.86642611e+00 -3.36528254e+00 -1.08120041e+01 -1.86712627e+01 -1.09293652e+01 -1.63344345e+01 -2.17639828e+01 -2.32927189e+01 -3.63136578e+00 -1.67153015e+01 -2.75910358e+01 -4.34184189e+01 -3.05925999e+01 -5.77390976e+01 -8.52760544e+01 -8.88042908e+01 -6.61929703e+01 -3.41838875e+01 -3.22183533e+01 -3.86428452e+01 -4.51966057e+01 -6.03090973e+01 -3.89949608e+01 -3.46327095e+01 -2.95859051e+01 -3.10340996e+01 -1.04295225e+01 -6.08791399e+00 -3.07414188e+01 -3.96769333e+01 -3.37419128e+01 -3.09136143e+01 -4.09997978e+01 -3.46062622e+01 -2.41313572e+01 -1.88147430e+01 -1.76364231e+01 -8.36260891e+00 -1.74870415e+01 -2.63862534e+01 -3.75715370e+01 -3.56010132e+01 -3.27944603e+01 -2.13249912e+01 -2.90173454e+01 -4.91525650e+01 -8.53443069e+01 -7.06153564e+01 -4.99734039e+01 -2.19183006e+01 -2.31608524e+01 -3.92573853e+01 -4.91324120e+01 -5.88792038e+01 -6.74069901e+01 -7.90266724e+01 -9.02693481e+01 -7.06938629e+01 -6.91833954e+01 -5.63125801e+01 -6.63159256e+01 -5.86321945e+01 -5.30995407e+01 -4.50359688e+01 -5.82328339e+01 -6.62416077e+01 -6.94527206e+01 -6.17674332e+01 -5.52121048e+01 -6.54819717e+01 -8.63740616e+01 -1.24640350e+02 -1.13879349e+02 -8.08872833e+01 -3.36099205e+01 -5.44695320e+01 -8.40982895e+01 -1.06378181e+02 -8.67933350e+01 -6.15543747e+01 -6.41268845e+01 -8.70197906e+01 -1.07128098e+02 -1.08631363e+02 -9.58036118e+01 -1.02476997e+02 -1.24699059e+02 -1.38803345e+02 -1.13682426e+02 -7.40488968e+01 -6.27747154e+01 -8.06006393e+01 -8.94180145e+01 -8.87022629e+01 -7.03919449e+01 -6.38854942e+01 -7.85871735e+01 -1.05396782e+02 -1.00134727e+02 -8.11770782e+01 -4.75680962e+01 -5.31376495e+01 -5.62554169e+01 -6.69650879e+01 -4.61361351e+01 -1.04101648e+01 5.79408312e+00 -2.84445210e+01 -6.66261139e+01 -8.20089417e+01 -8.12958221e+01 -1.01450638e+02 -1.10096771e+02 -6.12820740e+01 -7.66626000e-02 6.86712027e+00 -3.86160889e+01 -8.18112259e+01 -8.53827591e+01 -7.67858353e+01 -5.17220230e+01 -3.50778961e+01 -4.68641510e+01 -7.74336090e+01 -9.86934433e+01 -9.92365875e+01 -1.05293533e+02 -7.52277451e+01 -2.91291008e+01 -2.03389626e+01 -5.01235962e+01 -8.52630463e+01 -1.01731346e+02 -1.11595764e+02 -1.13261917e+02 -8.75516052e+01 -7.75095596e+01 -7.15663605e+01 -7.13703232e+01 -6.48857880e+01 -5.78178368e+01 -5.40945244e+01 -5.69964638e+01 -5.92053947e+01 -6.00237694e+01 -5.09375877e+01 -4.72139969e+01 -6.33425522e+01 -8.21657639e+01 -1.79700165e+02 -2.41680664e+02 -1.70348160e+02 -1.10953903e+02 1.29140869e+02 -3.06715723e+03 -8.11410742e+03 278654560. 136519120. 136705408. -278194656. 464661568. -950955392. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -875751680. 229478736. -2.56669766e+04 -1.01079121e+04 -2.06051636e+03 -3.78615820e+03 -2.29509766e+03 -5.54885254e+02 -2.51302582e+02 -1.40268738e+02 -1.28597244e+02 -1.25573242e+02 -1.24599480e+02 -1.31437042e+02 -1.36106033e+02 -1.42018219e+02 -1.41020081e+02 -1.37996597e+02 -1.21112709e+02 -1.16693413e+02 -1.21090218e+02 -1.38743561e+02 -1.35461197e+02 -1.21401215e+02 -1.00884781e+02 -9.84893723e+01 -9.60543747e+01 -9.26893234e+01 -8.39566269e+01 -7.94029541e+01 -7.67972183e+01 -7.23047714e+01 -7.43196030e+01 -7.29341125e+01 -7.91922607e+01 -8.02635117e+01 -7.37985764e+01 -6.92515793e+01 -6.73170776e+01 -8.03525314e+01 -8.67970428e+01 -8.68115387e+01 -8.01465607e+01 -7.72270050e+01 -7.15404510e+01 -7.02941132e+01 -7.40265045e+01 -9.46747665e+01 -1.10701408e+02 -1.18997383e+02 -1.11564407e+02 -1.05230087e+02 -9.95323410e+01 -9.31634979e+01 -9.36644058e+01 -9.86253967e+01 -1.02552727e+02 -1.01258194e+02 -9.49773560e+01 -9.26365891e+01 -8.48723907e+01 -9.28014526e+01 -1.00040329e+02 -1.06974815e+02 -1.13812164e+02 -1.17639290e+02 -1.21553337e+02 -1.14882286e+02 -1.10048729e+02 -1.11164223e+02 -1.07511490e+02 -9.76707687e+01 -9.16961136e+01 -9.62991562e+01 -1.03250473e+02 -1.04636467e+02 -1.02030182e+02 -1.10659828e+02 -1.25142220e+02 -1.23491989e+02 -1.18354164e+02 -1.11663826e+02 -1.29047745e+02 -1.44077011e+02 -1.43024002e+02 -1.34057144e+02 -1.26864471e+02 -1.28631271e+02 -1.29469711e+02 -1.23332397e+02 -1.26035187e+02 -1.32368454e+02 -1.44215302e+02 -1.40572342e+02 -1.28359451e+02 -1.15061981e+02 -1.08761009e+02 -1.09116669e+02 -1.10315613e+02 -1.13634293e+02 -1.08403786e+02 -1.02797997e+02 -1.08737984e+02 -1.18457581e+02 -1.21050514e+02 -1.11412598e+02 -1.05316116e+02 -1.16760933e+02 -1.24779495e+02 -1.22202744e+02 -1.10395515e+02 -1.03425865e+02 -1.02966545e+02 -1.03088264e+02 -1.03724327e+02 -1.05564316e+02 -1.09306877e+02 -1.09276253e+02 -1.07850380e+02 -1.07566246e+02 -1.10275986e+02 -1.12162827e+02 -1.12415657e+02 -1.11706749e+02 -1.12584183e+02 -1.13015900e+02 -1.13416191e+02 -1.19886215e+02 -1.26075775e+02 -1.25144417e+02 -1.18756721e+02 -1.13022453e+02 -1.19127205e+02 -1.25122185e+02 -1.25579338e+02 -1.20707329e+02 -1.16037132e+02 -1.15314560e+02 -1.14365677e+02 -1.11963837e+02 -1.13205215e+02 -1.14090546e+02 -1.15181305e+02 -1.13281235e+02 -1.11502991e+02 -1.11652428e+02 -1.13291100e+02 -1.14979866e+02 -1.14856506e+02 -1.14685814e+02 -1.14490410e+02 -1.15678993e+02 -1.19234596e+02 -1.22681007e+02 -1.22392990e+02 -1.19536346e+02 -1.16867203e+02 -1.18726555e+02 -1.20699966e+02 -1.19852081e+02 -1.16826378e+02 -1.14282021e+02 -1.14290001e+02 -1.14786781e+02 -1.15052116e+02 -1.15135506e+02 -1.15009041e+02 -1.15027046e+02 -1.14809303e+02 -1.14763283e+02 -1.15067009e+02 -1.15362022e+02 -1.15037399e+02 -1.14647797e+02 -1.14406197e+02 -1.14422142e+02 -1.14453613e+02 -1.14228699e+02 -1.13704910e+02 -1.13503708e+02 -1.13690422e+02 -1.14018257e+02 -1.13930855e+02 -1.14386810e+02 -1.13575478e+02 -1.11828995e+02 -1.11088646e+02 -1.12143486e+02 -1.13557335e+02 -1.13129234e+02 -1.12776039e+02 -1.13171684e+02 -1.13539162e+02 -1.12750938e+02 -1.12360565e+02 -1.09632126e+02 -1.07027588e+02 -1.06570374e+02 -1.09193176e+02 -1.11934547e+02 -1.10931694e+02 -1.10411079e+02 -1.07143837e+02 -1.04411484e+02 -1.04617256e+02 -1.09569809e+02 -1.14046989e+02 -1.13277809e+02 -1.12523956e+02 -1.11432510e+02 -1.12840790e+02 -1.13893951e+02 -1.15010071e+02 -1.14658829e+02 -1.14229378e+02 -1.14149231e+02 -1.15091347e+02 -1.14836517e+02 -1.17496117e+02 -1.19965187e+02 -1.21347366e+02 -1.21582016e+02 -1.18995277e+02 -1.19393394e+02 -1.19436348e+02 -1.19160271e+02 -1.18705650e+02 -1.17724823e+02 -1.19688858e+02 -1.16932137e+02 -1.15175354e+02 -1.15050995e+02 -1.19603760e+02 -1.19993752e+02 -1.18637039e+02 -1.16368393e+02 -1.16675339e+02 -1.17984901e+02 -1.15206017e+02 -1.16302101e+02 -1.10740356e+02 -1.09264381e+02 -1.06982788e+02 -1.15181465e+02 -1.24876236e+02 -1.19534920e+02 -1.03519348e+02 -9.12976303e+01 -9.50271606e+01 -1.02831139e+02 -1.05069153e+02 -1.04523270e+02 -1.05274612e+02 -1.04554588e+02 -1.03919830e+02 -1.02930008e+02 -1.04557037e+02 -1.09129173e+02 -1.13686333e+02 -1.15706642e+02 -1.12024734e+02 -1.07704071e+02 -1.03043724e+02 -1.02068893e+02 -1.04289032e+02 -1.05975395e+02 -1.09687241e+02 -1.10580360e+02 -1.14615021e+02 -1.09273415e+02 -9.62231140e+01 -8.24737167e+01 -8.50362396e+01 -9.43778000e+01 -1.06147141e+02 -1.07809708e+02 -1.08137375e+02 -1.01315758e+02 -9.21802368e+01 -8.65348282e+01 -8.24624329e+01 -9.19834213e+01 -1.01527588e+02 -1.13491135e+02 -1.07457199e+02 -1.01845825e+02 -9.76272278e+01 -1.03553841e+02 -1.05834084e+02 -1.10561035e+02 -1.04351227e+02 -9.75547562e+01 -9.31837158e+01 -9.08422165e+01 -9.22712021e+01 -7.60107117e+01 -6.42509613e+01 -6.73115768e+01 -8.72251892e+01 -1.02346581e+02 -9.85335159e+01 -8.99890823e+01 -9.24527740e+01 -9.19059753e+01 -8.17880630e+01 -6.51850357e+01 -6.67665558e+01 -8.62893600e+01 -1.05276718e+02 -9.55344772e+01 -8.37732849e+01 -8.68579788e+01 -9.85489807e+01 -1.03785782e+02 -9.75801239e+01 -9.02406693e+01 -9.73986969e+01 -1.11928299e+02 -1.14989517e+02 -1.12043983e+02 -1.03036812e+02 -1.09496819e+02 -9.50897064e+01 -7.66036911e+01 -7.17857590e+01 -6.52799911e+01 -5.52900848e+01 -3.71447906e+01 -3.71497154e+01 -4.40592613e+01 -4.20344963e+01 -5.23060570e+01 -5.54097786e+01 -7.43315811e+01 -9.43806915e+01 -1.21606117e+02 -1.27679550e+02 -1.21755394e+02 -1.14890816e+02 -1.10316628e+02 -1.06830650e+02 -1.05009819e+02 -1.10353737e+02 -1.15272575e+02 -9.71768646e+01 -6.80250168e+01 -5.80980263e+01 -6.08668633e+01 -7.52645416e+01 -8.08933487e+01 -8.46517563e+01 -1.00163902e+02 -9.13855438e+01 -9.04649429e+01 -7.81533585e+01 -6.63821564e+01 -5.35069656e+01 -3.23869820e+01 -5.29067459e+01 -7.64874344e+01 -8.65102158e+01 -5.98213577e+01 -5.44486465e+01 -6.46488037e+01 -9.00746002e+01 -6.88369598e+01 -4.63177986e+01 -3.74325981e+01 -5.60685806e+01 -7.70061569e+01 -5.32793083e+01 -2.77881203e+01 -3.31587257e+01 -6.84701614e+01 -9.54544678e+01 -7.56657486e+01 -5.77907448e+01 -7.92970505e+01 -1.10078667e+02 -9.40210876e+01 -5.13209648e+01 -3.24821091e+01 -4.26835442e+01 -5.57373657e+01 -4.51252060e+01 -2.60255184e+01 -7.94434834e+00 -2.05234909e+01 -5.72054863e+01 -8.76336441e+01 -8.71763611e+01 -7.79471054e+01 -7.18042068e+01 -7.51972351e+01 -7.83594589e+01 -7.24301605e+01 -5.50234451e+01 -5.50936203e+01 -7.34148865e+01 -7.92575073e+01 -7.11084518e+01 -4.18895607e+01 -2.78965378e+01 -3.74940033e+01 -4.89653893e+01 -7.10468445e+01 -6.41836395e+01 -6.80768356e+01 -7.55187531e+01 -9.23983536e+01 -9.22121201e+01 -4.53358841e+01 -1.16971502e+01 -4.68964005e+01 -1.12774940e+02 -1.13938255e+02 -5.81607437e+01 -3.59016190e+01 -6.56096725e+01 -8.08125992e+01 -5.87023468e+01 -4.65630112e+01 -5.09696770e+01 -7.80329819e+01 -6.36027641e+01 -5.71286545e+01 -4.51295891e+01 -5.88165092e+01 -8.71497955e+01 -8.55425034e+01 -8.63222122e+01 -5.15390282e+01 -2.75176678e+01 -2.47062244e+01 -5.45129051e+01 -5.69295807e+01 9.73888934e-01 4.01956062e+01 2.10586853e+01 -3.44320297e+01 -3.85965042e+01 -1.51925268e+01 -3.72190094e+01 -8.48871078e+01 -1.03160835e+02 -6.02519073e+01 -3.51369934e+01 -4.11317520e+01 -5.90233994e+01 -3.81134453e+01 -2.60286865e+01 -2.20682220e+01 -3.49772797e+01 -5.13144569e+01 -6.77259445e+01 -7.80804214e+01 -6.79984512e+01 -5.45846939e+01 -3.54893227e+01 -2.94994850e+01 -2.48295975e+01 -3.16880608e+00 3.59362936e+00 -1.36338062e+01 -3.48964691e+01 -3.44998932e+01 -7.20014668e+00 -4.83893919e+00 -8.82436752e+00 7.95483828e+00 6.39603004e+01 1.01160004e+02 7.55935287e+01 8.68977737e+00 -1.26033850e+01 5.55339718e+00 1.38189306e+01 -1.39135942e+01 -3.59413528e+01 -4.93823280e+01 -5.91789055e+01 -5.53101921e+01 -3.41917191e+01 -3.45744629e+01 -5.44036064e+01 -5.77861137e+01 -2.90506363e+00 2.53903809e+01 9.29585993e-01 -3.61195679e+01 -8.19376850e+00 1.14852209e+01 -1.96304169e+01 -8.48739319e+01 -1.30388992e+02 -1.21313011e+02 -1.17493340e+02 -9.88161392e+01 -8.53281784e+01 -7.53030853e+01 -7.25061264e+01 -6.37619400e+01 -5.24001083e+01 -5.66480179e+01 -8.37159042e+01 -6.08204193e+01 5.41383266e+00 5.00522385e+01 5.62273865e+01 4.74042625e+01 1.84042130e+01 -5.03190088e+00 -3.45084343e+01 -2.39187393e+01 -3.33657379e+01 -4.73207054e+01 -5.28594513e+01 -3.90522842e+01 -2.93950253e+01 -2.03801785e+01 -2.23553619e+01 -3.11364746e+01 -3.68523788e+01 -4.07933083e+01 1.50243926e+00 4.78979149e+01 5.66017151e+01 2.54638710e+01 -1.03095970e+01 -7.47239494e+00 -1.05292873e+01 -7.39168119e+00 -1.90107517e+01 -2.04713154e+01 -1.55605841e+01 2.09196720e+01 5.78548088e+01 3.72961693e+01 -3.35562277e+00 -1.22029514e+01 5.85170593e+01 1.01516907e+02 7.46305847e+01 5.83166742e+00 1.10509520e+01 3.96373940e+01 4.00894470e+01 6.85977697e+00 -2.07779675e+01 1.95671005e+01 4.85518341e+01 7.78210068e+01 9.33158646e+01 4.96862411e+01 1.29246082e+01 9.06751251e+00 9.31839676e+01 1.29582550e+02 7.69385147e+01 6.45534182e+00 1.72464027e+01 7.55831604e+01 8.01302490e+01 4.91302681e+01 1.52162523e+01 4.10949020e+01 7.50926361e+01 8.19801254e+01 6.35398788e+01 3.29159775e+01 2.60024948e+01 5.90419426e+01 9.59676361e+01 9.87385101e+01 6.70747070e+01 1.08144474e+01 3.52805328e+01 6.40596237e+01 6.70407333e+01 3.42287598e+01 3.31891022e+01 8.16644363e+01 7.80933990e+01 3.52718086e+01 -1.46313505e+01 -1.92111511e+01 -2.18134308e+01 8.27511311e+00 4.97419815e+01 7.13953018e+01 5.37191772e+01 1.24085712e+01 -9.14430332e+00 -1.26492929e+01 1.67930813e+01 4.49319115e+01 4.42155876e+01 2.43836578e+02 5.09911041e+02 4.85195068e+02 2.03178131e+02 -1.41682373e+02 1.74226868e+02 1.99874695e+02 4.10787079e+02 4.85387598e+03 1.14639746e+04 21604182. 9025177. 6713434. -16907282. -4.11726561e+10 0. 0. 0. 0. 0. 0. 2.26273956e+10 2.26273956e+10 10582239. -3.54597233e+10 -3.54597233e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -855827968. -8622476. 6835689. 3.98411094e+04 1.70962891e+04 2.33563916e+03 -5.22220020e+03 -3.96949048e+03 -1.23438757e+03 -6.94770264e+02 -2.47669861e+02 6.86582108e+01 8.65398483e+01 2.10933228e+01 -1.79034698e+00 4.18557167e+01 1.20840302e+01 -5.96044807e+01 -1.19319000e+02 -4.98894997e+01 9.40282211e+01 1.53819122e+02 1.02750832e+02 2.33307886e+00 -4.23064537e+01 -2.37578468e+01 -4.54543889e-01 -2.80627003e+01 -6.22373352e+01 -2.34403038e+01 5.82158546e+01 9.75959091e+01 6.33673210e+01 -1.06847725e+01 -3.58584175e+01 1.50331717e+01 8.88688354e+01 1.23984245e+02 8.37811432e+01 9.22353210e+01 1.35279297e+02 9.66440811e+01 -1.30762506e+00 -6.59353180e+01 2.93067570e+01 1.85678177e+02 2.22433182e+02 1.39226151e+02 6.13711243e+01 1.15553741e+01 6.49533510e+00 1.14985485e+01 2.10751820e+01 1.77917271e+01 3.82009392e+01 1.48537445e+02 2.20792603e+02 1.88200043e+02 8.07910004e+01 5.95818901e+00 4.19883614e+01 1.08014839e+02 1.54159241e+02 9.62657776e+01 7.64757156e+01 9.49288025e+01 6.86636581e+01 2.65605092e+00 -7.87366867e+01 -5.79710693e+01 5.80746803e+01 9.75461273e+01 6.05544815e+01 -2.95857105e+01 -1.42676878e+00 6.63527298e+01 5.62358246e+01 -3.90184951e+00 -3.12898674e+01 1.40430832e+01 1.12423317e+02 1.55378510e+02 1.25733543e+02 3.40728798e+01 -2.62209625e+01 -7.64685583e+00 3.25862961e+01 2.09535923e+01 -2.57899437e+01 -1.64150772e+01 4.77061272e+01 8.05867767e+01 1.68202190e+01 -7.18600998e+01 -8.57349091e+01 8.74284649e+00 8.75678864e+01 9.11685638e+01 2.37764492e+01 6.87607813e+00 2.52517471e+01 -1.00770330e+01 -9.17487564e+01 -1.35130188e+02 -6.87422638e+01 5.68086472e+01 1.22756126e+02 9.81529922e+01 2.74665356e+01 -4.90522156e+01 -1.01014938e+02 -8.51050644e+01 -6.77687988e+01 -6.73805237e+01 -5.20519485e+01 2.35516930e+01 8.92718201e+01 4.56158943e+01 -7.42533188e+01 -1.23118454e+02 -7.57227859e+01 4.10846329e+01 9.84075089e+01 6.64909210e+01 2.18236504e+01 1.03612776e+01 9.49227142e+00 -3.36698112e+01 -1.23170578e+02 -1.18784935e+02 -3.13881588e+01 6.51376495e+01 6.48886185e+01 2.39038682e+00 -4.77352905e+01 -4.73115158e+01 -2.13639450e+01 1.86699524e+01 3.79114799e+01 -1.32767305e+01 -3.91114044e+01 -4.23830271e+00 4.20262985e+01 4.91572189e+01 2.16468372e+01 1.97549591e+01 5.61782608e+01 5.65150261e+01 2.52973080e+01 -1.38845415e+01 -2.78272991e+01 1.61801987e+01 3.37204933e+01 2.03510151e+01 -2.11264248e+01 1.05830870e+01 1.19514725e+02 1.76012985e+02 1.03367134e+02 2.27997637e+00 -1.55460339e+01 4.12703629e+01 7.91351700e+01 7.44930801e+01 7.35164642e+01 1.14079178e+02 1.67744827e+02 1.81620148e+02 1.55923065e+02 7.91074448e+01 2.93043003e+01 5.86380730e+01 7.92198029e+01 6.77394714e+01 2.39341354e+01 5.91311264e+01 1.47401398e+02 1.37998871e+02 1.01662781e+02 6.06481972e+01 1.12498383e+02 2.11974777e+02 2.55495270e+02 2.07984344e+02 1.04635513e+02 4.87485847e+01 6.65836487e+01 5.41231689e+01 3.52437515e+01 4.44529839e+01 1.15229248e+02 1.95357010e+02 1.89078979e+02 1.23099678e+02 1.03333654e+01 -2.67592564e+01 1.39965076e+01 8.51044540e+01 1.28222076e+02 1.17814186e+02 1.36463852e+02 1.58183304e+02 1.50368011e+02 7.69464951e+01 8.91977882e+00 3.89351234e+01 1.38558136e+02 1.90297409e+02 1.32066040e+02 3.28414421e+01 6.77440822e-01 4.65073738e+01 1.00035126e+02 7.65270844e+01 3.12812119e+01 4.54758301e+01 9.72616272e+01 1.16682709e+02 7.26391144e+01 6.25361323e-01 -1.10578804e+01 1.91066055e+01 6.40810547e+01 6.42749481e+01 4.52862129e+01 3.76872330e+01 5.38431931e+01 3.38759232e+01 1.34990358e+00 -2.87917793e-01 1.20869780e+01 4.97943344e+01 6.67771301e+01 4.95023193e+01 5.35523643e+01 5.29374542e+01 8.34397812e+01 5.66961823e+01 1.98245316e+01 4.81237268e+00 2.37505703e+01 1.03343307e+02 1.48376205e+02 1.45210373e+02 5.27561989e+01 9.79472446e+00 -1.57126927e+00 3.65851173e+01 5.22934265e+01 3.35413704e+01 4.05063858e+01 6.51774597e+01 8.21118927e+01 5.32983704e+01 3.14724445e+01 7.86175156e+01 1.35970490e+02 1.28483337e+02 9.47254028e+01 7.34372482e+01 9.37946930e+01 1.28217148e+02 9.23915253e+01 6.49052429e+01 3.22936745e+01 5.04246979e+01 8.85432968e+01 1.11709358e+02 1.21659073e+02 8.15995102e+01 6.20960579e+01 6.04157562e+01 9.86531830e+01 1.09068779e+02 1.08868980e+02 1.15979126e+02 1.34141708e+02 1.45212540e+02 9.65004196e+01 6.72427292e+01 6.69703293e+01 1.13128517e+02 1.15121170e+02 9.47854233e+01 6.70455856e+01 4.59340286e+01 5.63875237e+01 5.88626900e+01 9.25558090e+01 1.09287827e+02 1.23797165e+02 1.20894753e+02 1.11110069e+02 9.24352341e+01 6.08878822e+01 4.32748528e+01 5.27036743e+01 9.93685760e+01 1.07620796e+02 9.82051849e+01 8.64381943e+01 9.29902573e+01 8.19128952e+01 3.48390045e+01 1.69036160e+01 3.97080421e+01 9.47642288e+01 1.06984451e+02 8.77165222e+01 5.75594139e+01 4.72678337e+01 6.55296783e+01 6.80919724e+01 7.98212891e+01 5.52706375e+01 4.55226326e+01 4.12437248e+01 6.30947342e+01 7.29345779e+01 5.61462021e+01 3.66561623e+01 5.47751961e+01 8.04849014e+01 7.29814224e+01 5.64373474e+01 5.93496933e+01 7.69065704e+01 7.51681290e+01 4.60210876e+01 3.70605164e+01 4.53869438e+01 7.50487518e+01 7.27881851e+01 6.50693130e+01 5.51051178e+01 6.19836502e+01 7.69504318e+01 7.16366882e+01 6.82939301e+01 4.65362740e+01 4.03235741e+01 4.39272232e+01 5.92287102e+01 6.85451279e+01 6.15014305e+01 5.11387253e+01 5.62750969e+01 7.65165710e+01 8.20216446e+01 8.26142273e+01 9.29940109e+01 1.10596535e+02 1.04218483e+02 7.99741364e+01 7.62955017e+01 8.99122543e+01 1.06492355e+02 8.70306931e+01 7.79355469e+01 7.14003296e+01 6.29201622e+01 5.99421387e+01 6.96892471e+01 9.89541321e+01 1.05114388e+02 8.39879532e+01 6.53043747e+01 7.37979736e+01 9.87567902e+01 1.10167068e+02 9.60748901e+01 8.29633560e+01 8.59470367e+01 9.36353149e+01 1.03952057e+02 1.12808601e+02 1.26559052e+02 1.20620171e+02 1.05213112e+02 1.00342781e+02 1.07273483e+02 1.17450333e+02 1.00368019e+02 9.10713730e+01 8.27356110e+01 8.71298599e+01 8.73899078e+01 9.69833755e+01 1.14621704e+02 1.19189034e+02 1.03887779e+02 7.74332962e+01 7.07516708e+01 9.15720520e+01 1.11670082e+02 1.12580254e+02 9.79207993e+01 8.85184937e+01 9.34708405e+01 1.03826721e+02 1.08856308e+02 1.01974319e+02 8.60292435e+01 8.29770279e+01 9.00944138e+01 9.97432098e+01 1.09794952e+02 1.08144226e+02 1.03137001e+02 9.08181992e+01 7.91350708e+01 7.56014404e+01 8.24645462e+01 9.60713348e+01 1.02057701e+02 9.54687271e+01 8.71975098e+01 8.75225449e+01 9.61743927e+01 1.02698547e+02 9.86287689e+01 8.93397522e+01 8.35921021e+01 8.35378494e+01 8.80181885e+01 9.03072891e+01 9.24697647e+01 8.91442566e+01 8.78870697e+01 8.69226379e+01 8.80571518e+01 8.87110291e+01 8.70315781e+01 8.58495789e+01 8.47507401e+01 8.49789124e+01 8.57004547e+01 8.61366577e+01 8.61034851e+01 8.55983429e+01 8.56057510e+01 8.70881958e+01 8.84550552e+01 8.77141724e+01 8.46688919e+01 8.22400513e+01 8.24773560e+01 8.41774368e+01 8.38946915e+01 8.21459122e+01 8.05958862e+01 7.98871841e+01 8.31679382e+01 8.58732300e+01 8.92003098e+01 8.91821289e+01 8.74846268e+01 8.43124008e+01 8.01574783e+01 8.03158569e+01 8.48626556e+01 8.97932663e+01 9.03546906e+01 8.44810257e+01 7.75149536e+01 8.01341476e+01 8.68424530e+01 9.03776093e+01 8.37315063e+01 7.26640167e+01 7.24420471e+01 7.94459076e+01 9.17523651e+01 9.27596817e+01 8.43646317e+01 7.52903748e+01 6.76914673e+01 7.72869415e+01 8.18057251e+01 8.81901169e+01 8.93680115e+01 9.04830627e+01 9.29582901e+01 8.60517731e+01 8.86849060e+01 9.32782211e+01 9.17314224e+01 8.21867371e+01 6.53068085e+01 5.70454941e+01 6.71477356e+01 9.16264877e+01 1.15685776e+02 1.13075554e+02 8.77795792e+01 6.02735519e+01 5.17085533e+01 7.07957458e+01 9.36256180e+01 9.98642044e+01 8.59021072e+01 6.55267029e+01 7.01878967e+01 8.43616638e+01 1.00892464e+02 1.03981758e+02 9.60538940e+01 7.99820099e+01 6.28787155e+01 6.61397324e+01 8.46191635e+01 1.09864220e+02 1.12931473e+02 9.32526093e+01 6.51034088e+01 7.03030090e+01 9.43972931e+01 1.11966957e+02 1.03054588e+02 8.62435379e+01 7.89948654e+01 7.27802353e+01 8.41186447e+01 9.11281128e+01 8.27951508e+01 7.71076431e+01 6.73517685e+01 8.23258362e+01 9.42564163e+01 1.12191284e+02 1.25020058e+02 1.12293007e+02 9.72944870e+01 7.23373871e+01 6.23295479e+01 7.74360733e+01 1.00775940e+02 1.04889610e+02 7.46344070e+01 4.47314796e+01 4.62774353e+01 6.78606262e+01 9.88382187e+01 1.09261154e+02 9.80321503e+01 8.14759903e+01 7.37525024e+01 9.72807312e+01 1.19301552e+02 1.41512894e+02 1.35110138e+02 1.04030937e+02 1.03303780e+02 1.17983368e+02 1.49537338e+02 1.55795975e+02 1.42373474e+02 1.22506248e+02 7.87565994e+01 6.17794151e+01 7.03558655e+01 1.06438866e+02 1.23419823e+02 9.07959900e+01 5.78699265e+01 5.47691231e+01 1.03140648e+02 1.30219620e+02 1.20644737e+02 7.76663132e+01 4.31133575e+01 3.93811302e+01 7.40578461e+01 1.15973808e+02 1.28156937e+02 1.24583603e+02 1.11631226e+02 9.58782883e+01 6.68059464e+01 6.55579300e+01 7.73129959e+01 9.01892014e+01 6.95651169e+01 2.98679619e+01 3.06034994e+00 4.06387215e+01 9.14619522e+01 1.20333031e+02 8.71264801e+01 3.29320831e+01 2.30831776e+01 5.33988647e+01 1.08212326e+02 1.18026909e+02 8.23945389e+01 6.45418625e+01 5.86431923e+01 9.48171234e+01 1.01011971e+02 9.64861832e+01 8.11570740e+01 5.04930382e+01 5.30935440e+01 5.53867722e+01 1.03390053e+02 1.39084488e+02 1.33975906e+02 1.11332664e+02 5.73595963e+01 3.34245605e+01 3.42886429e+01 8.78377838e+01 1.77647964e+02 2.14160278e+02 2.02436630e+02 8.72386932e+01 5.06423454e+01 -4.62948990e+00 -2.88022881e+01 2.65661157e+03 7.05225928e+03 516205440. 557197568. 1252064128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.74436659e+09 -366176064. -6.34325439e+03 -1.21440259e+03 1.00040802e+03 -9.69398071e+02 -1.95148975e+03 -5.13851685e+02 3.35446069e+03 2.22597144e+03 3.38654999e+02 2.82058990e+02 2.08933441e+02 1.61044266e+02 1.28373672e+02 1.00263931e+02 1.67655144e+01 1.18815155e+01 5.94120789e+01 1.24056648e+02 1.15283218e+02 4.28595581e+01 -2.38532467e+01 -4.24560013e+01 1.93425884e+01 1.07913780e+02 1.27125572e+02 5.11924706e+01 -2.05723495e+01 -2.03541203e+01 4.67965202e+01 4.35131187e+01 -5.81421041e+00 -1.79457321e+01 2.25441551e+01 8.18064957e+01 8.27595215e+01 9.75020676e+01 1.17374123e+02 1.15571465e+02 5.94345970e+01 -4.35090637e+01 -5.10072670e+01 1.58512640e+01 8.50522537e+01 8.18034210e+01 1.34349222e+01 -5.90432816e+01 -4.56707764e+01 4.92617874e+01 1.61688293e+02 1.47920166e+02 4.12659950e+01 -1.94142323e+01 -3.16338577e+01 3.08835602e+01 5.50356293e+01 7.48399658e+01 8.21763458e+01 5.86347237e+01 1.90215378e+01 -4.51525154e+01 -1.95755806e+01 4.01341400e+01 6.50533447e+01 1.84329662e+01 -6.33013802e+01 -6.13794785e+01 -2.14146366e+01 5.41378860e+01 7.94260864e+01 1.26488667e+01 -8.50769730e+01 -1.57413834e+02 -1.14351166e+02 -1.16860332e+01 2.29126396e+01 -3.67070503e+01 -7.95671005e+01 -7.09147491e+01 2.25336094e+01 4.27647247e+01 1.49189129e+01 -2.87797756e+01 -3.00135307e+01 -2.45810375e+01 -5.52596359e+01 -2.25204277e+01 3.69566803e+01 7.02319641e+01 6.16015673e+00 -1.00992950e+02 -1.19968590e+02 -8.53631287e+01 -9.91183472e+00 5.23630447e+01 5.58563499e+01 -9.20810282e-01 -5.82678223e+01 -4.46799736e+01 5.67923279e+01 9.89941406e+01 2.40634289e+01 -5.62337341e+01 -6.02284660e+01 4.69140930e+01 9.37989807e+01 8.97510376e+01 7.36467743e+01 5.35030861e+01 8.99988079e+00 -7.36838226e+01 -6.56221466e+01 4.89452648e+00 5.80644951e+01 4.98983612e+01 -2.52551975e+01 -3.76994171e+01 6.95263195e+00 4.91703186e+01 9.38942795e+01 7.60537491e+01 -2.44778156e+00 -7.44774704e+01 -9.16572342e+01 2.53280201e+01 7.07055817e+01 2.82870140e+01 -9.88166142e+00 -1.87147446e+01 3.34113922e+01 2.63360081e+01 2.55919762e+01 5.61393242e+01 7.28561707e+01 5.68164673e+01 -4.29001579e+01 -4.39628677e+01 2.33409557e+01 7.90776672e+01 7.11304092e+01 5.12742186e+00 1.33069725e+01 6.70690994e+01 1.02730263e+02 1.43446655e+02 9.65342407e+01 1.80481262e+01 -5.60992966e+01 -5.08161049e+01 2.30469780e+01 4.15775261e+01 1.04371510e+01 1.18344393e+01 2.17353287e+01 9.11819153e+01 1.18588753e+02 1.48728867e+02 1.43050018e+02 1.05080589e+02 4.76208954e+01 -4.80078087e+01 -7.30855179e+01 -4.76290131e+01 1.55841227e+01 1.87375317e+01 -5.13697243e+01 -1.18541573e+02 -8.72478867e+01 3.03543167e+01 1.07125343e+02 1.03795410e+02 -4.50485325e+00 -5.24862747e+01 -5.30840874e+01 1.26720629e+01 1.81588573e+01 -8.87629414e+00 -8.45662498e+00 -1.61728764e+01 -2.61343346e+01 -2.86824360e+01 3.30818367e+01 1.06222359e+02 1.06865288e+02 7.75836792e+01 2.00162983e+01 -2.54774227e+01 -3.96017647e+01 -1.53780413e+01 -9.91372585e+00 -7.72387924e+01 -1.37901489e+02 -9.63498306e+01 1.32436266e+01 9.59296265e+01 9.45710602e+01 1.68887386e+01 -9.87711811e+00 -1.40429010e+01 6.55910263e+01 5.27303886e+01 1.10980046e+00 -6.69627304e+01 -1.05411713e+02 -1.16156143e+02 -1.72881607e+02 -1.40096191e+02 -5.46570473e+01 1.60966949e+01 1.21619864e+01 -6.65070190e+01 -6.24739876e+01 -9.26268864e+00 7.30101547e+01 1.41911423e+02 1.01991112e+02 -2.05717983e+01 -1.38538651e+02 -1.09036026e+02 4.29098701e+00 3.19229965e+01 -7.33816719e+00 -3.13510227e+01 -3.55914268e+01 -3.99428666e-01 2.53458214e+01 5.86554489e+01 4.97751579e+01 2.72173424e+01 -2.81301823e+01 -9.87215424e+01 -1.21205040e+02 -8.80257950e+01 -4.27134972e+01 -2.72168961e+01 -2.95089664e+01 3.10774326e-01 4.48877258e+01 5.41149025e+01 3.98022537e+01 -1.75361366e+01 -2.94811974e+01 -4.63197746e+01 -3.32943802e+01 1.00041819e+00 1.83101482e+01 1.45646391e+01 -1.90588589e+01 -3.21874084e+01 -1.55362921e+01 1.60497773e+00 3.24347705e-01 -2.77648525e+01 -3.74126816e+01 -3.55196228e+01 -1.87126217e+01 -1.91493587e+01 -9.87315369e+00 -1.12167072e+01 3.66684318e+00 -1.12967765e+00 -8.11234891e-01 -1.44670858e+01 -3.80656624e+00 -5.20544112e-01 8.06707382e+00 -3.84235196e-02 4.81678867e+00 1.81502209e+01 1.35275364e+01 1.44099474e+01 2.72552834e+01 2.03460655e+01 6.96020508e+00 -1.72174110e+01 1.63468800e+01 1.67619686e+01 9.85413742e+00 -3.84911990e+00 4.63317919e+00 1.38963079e+01 1.36587467e+01 2.14952469e+01 1.24640789e+01 5.77366829e+00 -5.50225067e+00 2.03989291e+00 -1.96249831e+00 2.90740085e+00 2.74509597e+00 3.38288975e+00 4.90838432e+00 1.23806200e+01 1.42468586e+01 1.36858730e+01 -1.08157921e+01 -3.71967087e+01 -5.36591339e+01 -3.86857910e+01 -1.70232239e+01 5.43967342e+00 -3.65826416e+00 -1.63711815e+01 -2.91257687e+01 -2.04641247e+01 -2.12824416e+00 -3.08422589e+00 -1.56525097e+01 -1.59320145e+01 -7.37837017e-01 4.12682295e+00 -4.76783323e+00 -1.22180710e+01 -1.15720301e+01 -1.91411171e+01 -2.50830460e+01 -4.06669693e+01 -4.53994904e+01 -4.56203079e+01 -2.36836262e+01 2.83001089e+00 3.39006996e+01 6.22487106e+01 4.55864944e+01 1.23264837e+01 -1.85692596e+01 -2.05343628e+01 -3.10928707e+01 -4.67070312e+01 -1.44048491e+01 2.28727722e+01 2.10159111e+01 -1.60470066e+01 -4.19076538e+01 -3.87500229e+01 -3.35426140e+01 -4.84107132e+01 -5.05214119e+01 -5.32630959e+01 -3.81005325e+01 -4.40225372e+01 -4.46035843e+01 -3.35643463e+01 -2.01468964e+01 -2.70824318e+01 -5.82530632e+01 -9.40768585e+01 -9.49826965e+01 -7.93884888e+01 -4.51319847e+01 -4.85999832e+01 -5.84316788e+01 -5.45360184e+01 -5.23333359e+01 -4.30591736e+01 -7.64263687e+01 -1.04743759e+02 -1.03950539e+02 -6.94347687e+01 -3.82596436e+01 -2.92923603e+01 -4.50303230e+01 -8.13916702e+01 -1.14904770e+02 -9.22554169e+01 -3.70723686e+01 -1.69856415e+01 -3.48232727e+01 -5.63303299e+01 -6.35630302e+01 -9.07615967e+01 -1.12504471e+02 -1.01809395e+02 -8.01798325e+01 -4.51934662e+01 -4.23001366e+01 -3.80537910e+01 -6.63935776e+01 -8.02592697e+01 -7.92604904e+01 -5.22210999e+01 -3.64820251e+01 -2.74261494e+01 -3.46099205e+01 -3.17974319e+01 -2.56594334e+01 -1.68214378e+01 -2.40333233e+01 -3.57880974e+01 -5.05213013e+01 -3.82592812e+01 -3.09739571e+01 -3.53940582e+01 -4.93568077e+01 -4.23892860e+01 -2.87247334e+01 -5.42176590e+01 -8.05858688e+01 -7.09768372e+01 -3.29031029e+01 -1.27304659e+01 -3.64734383e+01 -4.15756187e+01 -5.35197563e+01 -6.04537086e+01 -8.01301804e+01 -7.56098633e+01 -8.26997375e+01 -8.08365860e+01 -8.38537064e+01 -6.18055115e+01 -5.26703644e+01 -6.10027428e+01 -5.99342995e+01 -5.78928909e+01 -5.08331146e+01 -5.11026115e+01 -4.68326492e+01 -7.53893738e+01 -9.99156265e+01 -1.10665649e+02 -7.88059845e+01 -5.62562332e+01 -4.61276169e+01 -4.32340431e+01 -4.20163536e+01 -4.62254829e+01 -5.34473305e+01 -4.84375420e+01 -2.96607990e+01 -8.85450554e+00 -6.53090096e+00 -1.82929993e+01 -4.08625298e+01 -4.20966911e+01 -3.60355148e+01 -3.33280525e+01 -4.18473358e+01 -4.80025749e+01 -1.55733652e+01 1.64667072e+01 2.04474373e+01 -1.68344383e+01 -5.17244453e+01 -5.26955719e+01 -3.34483795e+01 2.91344047e+00 1.09549774e+02 2.88302338e+02 5.29342896e+02 2.50059497e+03 3.32434131e+03 -1.59889511e+02 -6.06660339e+02 5.75978906e+03 1.47661787e+04 895762240. 3.07605274e+09 3.65783475e+09 481550656. 829045312. 5.95769344e+09 253882064. -3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -875751680. 229478736. -2.56669766e+04 -1.01079121e+04 -2.06051636e+03 -1.09017627e+03 2.45521094e+03 1.72096704e+03 3.03496002e+02 1.75784027e+02 2.80584297e+01 -5.33661222e+00 -3.63723030e+01 -6.22638588e+01 -5.95482597e+01 -5.54045181e+01 -5.19914398e+01 -5.04388962e+01 -3.90182419e+01 -2.45130939e+01 -4.28183136e+01 -7.23982697e+01 -7.78185043e+01 -5.90766525e+01 -3.99368820e+01 -5.08017921e+01 -5.37390671e+01 -5.66794891e+01 -5.04601898e+01 -4.37336311e+01 -4.06979637e+01 -4.53532372e+01 -5.94598808e+01 -6.11839943e+01 -6.53615036e+01 -6.28651123e+01 -8.10579605e+01 -9.85888748e+01 -9.92821655e+01 -8.81488647e+01 -7.68027573e+01 -8.19513474e+01 -8.91628494e+01 -9.16221924e+01 -9.56769562e+01 -9.97323761e+01 -1.01177818e+02 -1.06043465e+02 -1.05153793e+02 -1.01863426e+02 -9.69990540e+01 -9.31815796e+01 -9.58308105e+01 -9.47966919e+01 -9.52419739e+01 -9.63008347e+01 -9.76500473e+01 -1.00968575e+02 -1.03738846e+02 -9.75127335e+01 -8.26218643e+01 -6.24017944e+01 -5.35043755e+01 -5.88863869e+01 -6.99261322e+01 -7.95538330e+01 -7.20489426e+01 -6.39510880e+01 -6.69931793e+01 -8.29122314e+01 -9.62361298e+01 -9.75652695e+01 -9.53094330e+01 -1.02224434e+02 -1.15064560e+02 -1.05361816e+02 -8.74865723e+01 -7.17321014e+01 -7.41946182e+01 -8.31716080e+01 -8.29823761e+01 -8.85959702e+01 -8.68134155e+01 -8.84140778e+01 -8.40271072e+01 -8.36206741e+01 -7.73624420e+01 -7.55536346e+01 -7.50978699e+01 -7.95197220e+01 -7.99048615e+01 -6.94304962e+01 -5.81732178e+01 -6.37814178e+01 -7.32739487e+01 -8.38825302e+01 -7.93453064e+01 -7.48946991e+01 -6.77722244e+01 -6.37468987e+01 -7.31786575e+01 -8.59280624e+01 -8.89002228e+01 -8.36298218e+01 -7.23926468e+01 -7.31941986e+01 -7.47114410e+01 -8.04236832e+01 -8.40143738e+01 -8.15518723e+01 -8.29294815e+01 -8.23680115e+01 -8.57907867e+01 -8.33505402e+01 -8.33577347e+01 -8.33955307e+01 -7.90698395e+01 -7.32726746e+01 -7.36308975e+01 -7.93247070e+01 -8.70873795e+01 -8.85639191e+01 -9.12598190e+01 -8.97906494e+01 -9.10186691e+01 -9.10549393e+01 -9.18016968e+01 -8.46613770e+01 -7.75694885e+01 -7.63707809e+01 -8.10525131e+01 -8.57368546e+01 -9.01891632e+01 -9.28179703e+01 -9.38422623e+01 -9.01013412e+01 -8.81110077e+01 -8.93695297e+01 -8.73652420e+01 -8.58177643e+01 -8.56330948e+01 -8.70147858e+01 -8.73479919e+01 -8.66624374e+01 -8.61715927e+01 -8.66873169e+01 -8.61132965e+01 -8.53107910e+01 -8.51208420e+01 -8.47231674e+01 -8.43186569e+01 -8.43841858e+01 -8.45509338e+01 -8.56829910e+01 -8.65180435e+01 -8.68150024e+01 -8.66710052e+01 -8.64890976e+01 -8.69625702e+01 -8.74972153e+01 -8.69326859e+01 -8.42502289e+01 -8.26299667e+01 -8.26812134e+01 -8.36446381e+01 -8.46999588e+01 -8.50637665e+01 -8.57022705e+01 -8.59781723e+01 -8.58214035e+01 -8.58340683e+01 -8.59161606e+01 -8.59753418e+01 -8.60028915e+01 -8.60806808e+01 -8.61002121e+01 -8.58320312e+01 -8.53908081e+01 -8.50963440e+01 -8.53812637e+01 -8.59022903e+01 -8.67475281e+01 -8.65522156e+01 -8.63794022e+01 -8.60422287e+01 -8.60861282e+01 -8.58102341e+01 -8.60352707e+01 -8.58927841e+01 -8.56324539e+01 -8.56899948e+01 -8.59205246e+01 -8.58980789e+01 -8.54640884e+01 -8.54627686e+01 -8.71201019e+01 -8.79616394e+01 -8.80245590e+01 -8.76209641e+01 -8.68159790e+01 -8.40077133e+01 -7.94713821e+01 -7.71437302e+01 -7.66931686e+01 -7.76311798e+01 -7.60041199e+01 -7.92072144e+01 -8.40393829e+01 -8.94580917e+01 -8.98476105e+01 -8.89136887e+01 -8.74517899e+01 -8.72985153e+01 -8.77282104e+01 -8.99666977e+01 -8.94120712e+01 -8.86266174e+01 -8.65800781e+01 -8.68482590e+01 -8.79572906e+01 -9.31572495e+01 -9.94072113e+01 -9.69660873e+01 -9.23568039e+01 -8.60170517e+01 -8.22031784e+01 -7.81444321e+01 -7.11409073e+01 -6.61706619e+01 -6.84921494e+01 -7.23932953e+01 -8.29390564e+01 -8.00349655e+01 -7.75032501e+01 -7.38730850e+01 -7.43289642e+01 -7.73414841e+01 -7.55797577e+01 -7.45597000e+01 -7.43595581e+01 -7.75413589e+01 -8.10716705e+01 -8.09420166e+01 -7.37843628e+01 -6.35510368e+01 -5.35599709e+01 -4.83827934e+01 -6.59029007e+01 -8.44553070e+01 -9.61028366e+01 -9.01424255e+01 -7.91955338e+01 -8.01120300e+01 -7.61260071e+01 -7.95720520e+01 -7.92709885e+01 -8.27911606e+01 -8.29243622e+01 -8.41599884e+01 -8.11534195e+01 -8.10994492e+01 -9.13142090e+01 -1.05491493e+02 -1.07452614e+02 -9.84193039e+01 -8.95607224e+01 -8.44107513e+01 -7.79751968e+01 -7.57760391e+01 -7.96307449e+01 -8.00024338e+01 -7.26748962e+01 -7.01751785e+01 -7.64712143e+01 -8.52907791e+01 -8.95525665e+01 -8.89007416e+01 -8.70251312e+01 -8.50780258e+01 -8.53754959e+01 -8.18460007e+01 -8.27233887e+01 -8.54012527e+01 -9.18233719e+01 -9.44487000e+01 -9.13359604e+01 -7.64040451e+01 -5.61632729e+01 -5.85022011e+01 -7.26148605e+01 -8.89071274e+01 -8.13287735e+01 -7.85190125e+01 -7.93785706e+01 -8.12151718e+01 -7.77524261e+01 -7.32403412e+01 -6.03375549e+01 -5.22412949e+01 -5.34222870e+01 -7.31884155e+01 -9.00593338e+01 -9.02528000e+01 -8.51550980e+01 -9.27237625e+01 -1.09718147e+02 -1.11489693e+02 -1.05913742e+02 -9.11474609e+01 -9.43737335e+01 -9.29512100e+01 -9.14940338e+01 -8.58862610e+01 -8.39636841e+01 -8.49437485e+01 -8.99508209e+01 -8.75988159e+01 -8.57332153e+01 -8.66253662e+01 -8.77513199e+01 -8.51217575e+01 -8.08380203e+01 -6.56506424e+01 -5.01881866e+01 -5.11361084e+01 -6.13782120e+01 -7.16069641e+01 -6.73115616e+01 -7.18372498e+01 -8.36981430e+01 -8.46818695e+01 -6.05885010e+01 -3.75026855e+01 -3.56441536e+01 -5.56390686e+01 -6.88225861e+01 -6.66169357e+01 -6.57730331e+01 -6.55206985e+01 -6.79559631e+01 -5.10582886e+01 -2.71537342e+01 -2.28490601e+01 -3.88935738e+01 -6.60102463e+01 -6.16041756e+01 -6.24796219e+01 -6.21098137e+01 -6.72271271e+01 -6.48469849e+01 -5.79112892e+01 -4.81457405e+01 -4.46448631e+01 -5.38742180e+01 -5.89321976e+01 -5.90459099e+01 -3.28562584e+01 -1.76896274e+00 2.49091005e+00 -2.33603725e+01 -5.35192223e+01 -5.99728737e+01 -6.47985153e+01 -6.44971924e+01 -5.88269882e+01 -2.60847282e+01 -2.26052976e+00 2.66408329e+01 3.26618004e+01 3.67508006e+00 -2.32609558e+01 -5.70451660e+01 -3.26111450e+01 -1.50421762e+01 -3.60833473e+01 -8.71688614e+01 -1.15173386e+02 -9.37622910e+01 -6.17545738e+01 -6.31446991e+01 -6.44205475e+01 -6.99362564e+01 -7.06483231e+01 -7.72769928e+01 -8.10085754e+01 -8.60776215e+01 -8.99215546e+01 -8.56874390e+01 -8.26661911e+01 -8.04052277e+01 -8.15539474e+01 -7.88843765e+01 -6.59029083e+01 -3.88473701e+01 -4.34068832e+01 -6.23568001e+01 -9.45204239e+01 -6.49261932e+01 -3.10077553e+01 -5.57591019e+01 -1.17784546e+02 -1.19172562e+02 -5.04768562e+01 -2.58392882e+00 -2.58758774e+01 -5.80326042e+01 -3.99872513e+01 -5.04031849e+00 -1.03534389e+00 -1.64152107e+01 -4.42349548e+01 -4.16266403e+01 -3.69645691e+01 -4.70708160e+01 -4.70403786e+01 -7.36406860e+01 -9.11002579e+01 -5.59348907e+01 -2.83055544e+00 2.99666061e+01 3.05188346e+00 -2.25588169e+01 2.63484693e+00 2.03009701e+01 3.07469120e+01 2.36779284e+00 -2.83675404e+01 -2.98876534e+01 -2.37126369e+01 -1.35880327e+01 -2.42134266e+01 -8.16188717e+00 1.92363834e+01 2.54205761e+01 1.63138924e+01 -1.87411175e+01 -3.86475410e+01 -4.93574867e+01 -4.92183914e+01 -3.93226204e+01 -9.09515076e+01 -1.42497604e+02 -1.32717117e+02 -6.45170288e+01 -1.29587011e+01 -2.81414070e+01 -5.26682320e+01 -3.00895023e+01 1.34699841e+01 1.44335938e+01 -1.20663528e+01 -4.75664177e+01 -5.48552704e+01 -5.56521797e+01 -5.48390121e+01 -4.57572327e+01 -4.43842430e+01 -3.62474442e+01 -1.85832386e+01 -9.78547573e+00 -1.64216309e+01 -3.88012352e+01 -4.98575668e+01 -6.25693855e+01 -5.76625862e+01 -8.78754196e+01 -1.15034966e+02 -8.83189926e+01 -1.20172176e+01 2.85372372e+01 -8.09950733e+00 -5.82141609e+01 -8.07471466e+01 -9.35485458e+01 -9.71219864e+01 -9.18230743e+01 -7.81807404e+01 -8.22951050e+01 -7.19111862e+01 -7.56720047e+01 -7.15646744e+01 -8.18851776e+01 -8.52615662e+01 -8.87786865e+01 -6.74122772e+01 -5.78616295e+01 -6.37629623e+01 -8.57003937e+01 -9.04664230e+01 -6.93314590e+01 -4.41493721e+01 -3.60628586e+01 -6.60315943e+00 2.54972057e+01 3.38006706e+01 7.95682907e+00 -1.44454026e+00 6.85626526e+01 1.10492149e+02 7.80999680e+01 2.24244938e+01 3.59482384e+01 8.36967468e+01 8.96413574e+01 4.64676819e+01 1.13102713e+01 8.82131100e+00 8.10723495e+00 2.16264076e+01 2.75629463e+01 2.52113762e+01 7.17384911e+00 2.34578724e+01 6.57690353e+01 8.68230515e+01 6.16132774e+01 1.83413086e+01 2.19039879e+01 5.12465096e+01 1.60144329e+01 -4.27346344e+01 -7.52617493e+01 -4.99253120e+01 -2.60271587e+01 -4.18867722e+01 -4.18493576e+01 -3.32142105e+01 -2.51452618e+01 -2.93697987e+01 -2.56807613e+01 -1.34469910e+01 -2.15236530e+01 -2.98669910e+01 -4.87873650e+01 -4.06155663e+01 -3.08092632e+01 -2.91355534e+01 3.90052676e+00 2.75766983e+01 2.93074551e+01 -1.56584759e+01 -5.61732178e+01 -6.58600464e+01 -6.17264366e+01 -8.70104218e+01 -1.22680359e+02 -1.26264648e+02 -1.03251678e+02 -6.74096603e+01 -6.12177544e+01 -5.41987114e+01 1.41852164e+00 5.54101715e+01 6.54001999e+01 2.75148296e+01 -4.68880749e+00 -1.32547259e+00 -1.18719244e+01 -2.80513706e+01 -1.82921562e+01 -4.02646637e+01 -7.62631226e+01 -6.46133347e+01 -1.15160675e+01 3.19035225e+01 1.29180832e+01 1.87272148e+01 8.93022308e+01 1.32427765e+02 1.18668510e+02 3.61198578e+01 1.45592632e+01 4.17538757e+01 4.76454086e+01 1.69803848e+01 -3.81490555e+01 -2.85386162e+01 5.51722813e+00 1.53000603e+01 -2.46564722e+00 -4.26920929e+01 -6.39708443e+01 -7.44679642e+01 -7.50198517e+01 -6.26130600e+01 -5.88589401e+01 -6.52847214e+01 -2.74087257e+01 3.52443767e+00 2.51995258e+01 -9.41496181e+00 -3.67949409e+01 -3.05441723e+01 3.64840579e+00 -1.09861422e+01 -1.88172150e+02 -3.43840942e+02 -4.31035126e+02 -3.17384619e+03 -4.75090869e+03 -6.07446960e+02 -4.41996155e+01 -4.82090424e+02 3.59446924e+03 7.83416199e+02 -5.89000586e+03 -3.42433984e+04 4.74124616e+10 -3.51075983e+10 1583832192. 1583832192. 2.60913623e+10 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. -855827968. -8622476. 6835689. 4.89724250e+06 9355888. 12616733. -9.36792480e+03 -3.33173193e+03 2.94482605e+02 -2.31771317e+02 -3.81276794e+02 -8.66647461e+02 -7.48400574e+02 -5.32390320e+02 -2.10408340e+02 -1.47909790e+02 -2.44299713e+02 -2.85679291e+02 -5.19346558e+02 -6.80408203e+02 -4.30912292e+02 -1.10307022e+02 2.27274227e+01 6.74318390e+01 4.36673660e+01 6.65603638e+01 1.24447662e+02 1.25036629e+02 7.85081558e+01 4.12980843e+01 9.28499756e+01 1.96557465e+02 2.16375946e+02 1.36674500e+02 4.37943687e+01 -8.28018856e+00 -8.63674736e+00 -3.57397118e+01 -7.86371689e+01 -9.88147354e+01 -3.48748245e+01 1.28071365e+02 2.07081558e+02 1.68320908e+02 5.92956848e+01 -1.43951387e+01 -5.57043600e+00 2.01994820e+01 6.94179306e+01 4.11932068e+01 5.57187767e+01 7.56452560e+01 5.85444489e+01 -3.17098885e+01 -1.36040054e+02 -1.23855690e+02 2.87605190e+01 1.02168060e+02 7.16736298e+01 -1.28560028e+01 -4.46320504e-01 6.85386734e+01 6.92320251e+01 -3.25469136e+00 -8.50009308e+01 -6.80287552e+01 5.41008987e+01 1.35703903e+02 1.11706764e+02 3.69539948e+01 2.09434910e+01 4.53054733e+01 3.57870331e+01 -1.93575706e+01 -8.19630661e+01 -5.07833252e+01 -1.18573294e+01 -2.29351101e+01 -6.27779846e+01 -7.74582443e+01 -5.02339287e+01 -7.27470875e+00 3.87053032e+01 6.14423027e+01 3.33004684e+01 -8.35602939e-01 -5.72875071e+00 -4.46256485e+01 -1.11444717e+02 -1.35554092e+02 -6.08492622e+01 7.30993042e+01 1.33415543e+02 9.57991486e+01 -1.09289131e+01 -1.24080719e+02 -1.64158829e+02 -1.34241287e+02 -1.03985191e+02 -1.20452431e+02 -8.84679565e+01 3.07049537e+00 7.83880844e+01 4.79563789e+01 -1.88187656e+01 -4.71932564e+01 -2.08190575e+01 4.56893120e+01 5.94615631e+01 2.80255013e+01 -1.61171818e+01 -6.81897020e+00 3.28828812e+00 -3.79398384e+01 -1.25361580e+02 -1.45628967e+02 -7.75553894e+01 4.64842367e+00 6.32953930e+00 -5.45098343e+01 -1.04117065e+02 -1.00877480e+02 -4.40754623e+01 1.09998026e+01 3.01767426e+01 1.77252603e+00 2.71385264e+00 4.72768860e+01 6.06550446e+01 1.16999378e+01 -4.82043266e+01 -5.04557419e+01 9.45333290e+00 4.41294899e+01 5.67001390e+00 -2.57162971e+01 -4.24094658e+01 -1.17619305e+01 -2.26435471e+01 -7.58980942e+01 -9.13639069e+01 -3.03833065e+01 9.69636002e+01 1.61123825e+02 1.07789856e+02 2.81385593e+01 -4.07806921e+00 1.87141685e+01 4.48773956e+01 4.01099091e+01 4.27228279e+01 7.93071594e+01 1.28177872e+02 1.40611176e+02 6.48646774e+01 -4.50379410e+01 -9.16020203e+01 -1.12304306e+01 5.93911667e+01 5.31206207e+01 2.16162720e+01 5.52236366e+01 1.37821579e+02 1.27493896e+02 4.19860764e+01 -3.30492554e+01 2.33215809e+01 1.50806870e+02 2.21876892e+02 1.69803085e+02 8.10099258e+01 2.99513416e+01 3.47228470e+01 1.88700600e+01 1.03903043e+00 2.10685520e+01 8.51136551e+01 1.63898529e+02 1.24788666e+02 6.21641998e+01 -1.26441555e+01 3.51429963e+00 3.66755867e+01 8.23411484e+01 9.69634781e+01 1.01991722e+02 1.14997093e+02 1.55206299e+02 1.29135391e+02 6.14412270e+01 -1.71984005e+01 1.30128508e+01 9.08231049e+01 1.46015808e+02 1.19731392e+02 6.52163010e+01 3.18967915e+01 3.71819687e+01 1.94297791e+01 -3.88764648e+01 -7.18796616e+01 -1.53493376e+01 8.27640533e+01 1.07032005e+02 6.97926788e+01 -7.53030539e+00 -2.28431683e+01 -1.31398067e+01 1.42213440e+01 3.03791904e+01 3.44977188e+01 5.72800903e+01 8.65905762e+01 5.70635910e+01 1.23302841e+01 -1.09232807e+01 -5.20248747e+00 2.68842735e+01 3.78668137e+01 3.11627026e+01 3.03736019e+01 3.24765854e+01 6.10839195e+01 3.25914078e+01 -7.48457479e+00 -3.37476730e+01 -3.17277107e+01 3.25929909e+01 6.67097321e+01 4.89359474e+01 -1.47799282e+01 -2.45237961e+01 1.76690712e+01 6.15965767e+01 5.37478828e+01 1.73633289e+01 2.27776070e+01 5.46773872e+01 7.04326324e+01 2.84806080e+01 -2.48189509e-01 1.93882484e+01 3.98856583e+01 1.88363285e+01 7.25219393e+00 3.10243912e+01 5.23944054e+01 6.84537354e+01 4.27108192e+01 6.29341736e+01 7.27152023e+01 8.18618851e+01 9.43714676e+01 1.11498726e+02 1.17474060e+02 5.92146759e+01 3.60138512e+01 3.37735100e+01 7.61331024e+01 6.47730103e+01 5.79104767e+01 7.00655060e+01 9.84955444e+01 1.07570923e+02 5.80966568e+01 2.18261242e+01 1.71498814e+01 6.42022705e+01 7.15265732e+01 6.21412735e+01 4.33244591e+01 4.83032227e+01 8.80421295e+01 7.74652023e+01 5.34946556e+01 5.02794409e+00 -9.77121353e+00 6.39413881e+00 4.22411499e+01 6.76624146e+01 4.51340599e+01 1.40141850e+01 4.57962275e+00 2.33544750e+01 1.37839770e+00 -2.00209832e+00 2.18361282e+01 6.58195572e+01 6.72894745e+01 1.71285324e+01 -2.37592554e+00 2.02430267e+01 6.05180931e+01 5.16210060e+01 3.19696102e+01 2.69821548e+01 3.70729446e+01 5.68628693e+01 5.66879044e+01 6.52378998e+01 3.96114044e+01 2.38207550e+01 1.88207512e+01 4.18389168e+01 5.22060280e+01 3.76725349e+01 1.91677437e+01 1.72991695e+01 1.26395950e+01 -2.08005867e+01 -4.06767197e+01 -3.89143982e+01 -2.38113289e+01 -1.99827728e+01 -3.68230858e+01 -4.04680328e+01 -2.53454475e+01 1.19700909e+01 2.80270519e+01 3.13568497e+01 2.34437733e+01 3.23971825e+01 5.55521469e+01 7.35418777e+01 7.58206406e+01 4.87296333e+01 3.69699287e+01 3.36775856e+01 4.22906151e+01 3.52654343e+01 2.41279793e+01 1.42520847e+01 1.99277363e+01 1.83814468e+01 3.46168542e+00 -9.34665394e+00 -1.10376430e+00 1.98553371e+01 2.25016537e+01 2.46051769e+01 4.64270287e+01 6.68121109e+01 7.86482925e+01 5.62952576e+01 5.28718224e+01 4.48793488e+01 3.21731186e+01 3.02151222e+01 4.45754280e+01 7.16123352e+01 7.95865707e+01 5.35141029e+01 3.51449203e+01 3.66223793e+01 5.48210793e+01 6.69834366e+01 5.38399963e+01 3.69121399e+01 2.34557114e+01 2.70803871e+01 4.36945572e+01 5.53821983e+01 7.11203995e+01 7.06507797e+01 6.84665985e+01 7.26595306e+01 7.56716309e+01 7.86335983e+01 5.51615372e+01 5.23417358e+01 5.13653183e+01 5.48552895e+01 5.78549538e+01 6.89993057e+01 9.64477081e+01 1.00966064e+02 8.07447052e+01 4.59945908e+01 3.06672459e+01 5.04865494e+01 7.64545441e+01 7.87232590e+01 5.07528648e+01 2.28702335e+01 2.95230579e+01 5.54344673e+01 7.06251678e+01 6.89325485e+01 5.36267586e+01 5.58700523e+01 6.36014366e+01 7.10611191e+01 7.18111191e+01 5.91306648e+01 5.78042221e+01 6.31410255e+01 6.99081345e+01 6.92333069e+01 6.20614815e+01 6.44805908e+01 6.57412415e+01 5.61361008e+01 4.33665924e+01 4.46060562e+01 6.42727966e+01 7.66975021e+01 7.17485886e+01 5.65204926e+01 5.00031395e+01 5.25206718e+01 6.12023697e+01 6.49846802e+01 6.61461945e+01 5.90659561e+01 5.83951225e+01 5.88867531e+01 6.18000793e+01 6.32029037e+01 5.92959213e+01 5.58150330e+01 5.13782768e+01 5.17742729e+01 5.40615959e+01 5.79369469e+01 6.26210136e+01 6.40193634e+01 6.02099457e+01 5.42771530e+01 5.16765251e+01 5.44187012e+01 5.94775162e+01 6.04508018e+01 5.74342613e+01 5.44812851e+01 5.49920311e+01 5.70025177e+01 5.76273079e+01 5.74189873e+01 5.72371292e+01 5.73463745e+01 5.71691475e+01 5.64476128e+01 5.53440971e+01 5.48765411e+01 5.37589912e+01 5.35865326e+01 5.48752289e+01 5.78128052e+01 5.91252480e+01 5.62185822e+01 5.30695992e+01 5.37060776e+01 5.89002342e+01 6.37415581e+01 6.25105553e+01 5.62436333e+01 5.43264961e+01 5.68779640e+01 6.26906967e+01 6.12550850e+01 5.59039726e+01 5.04025002e+01 4.56923447e+01 5.00319061e+01 5.02672424e+01 5.32541161e+01 5.25628548e+01 5.04062386e+01 4.80264091e+01 4.22999954e+01 4.73929214e+01 5.51433601e+01 6.34352531e+01 5.93046722e+01 4.59179153e+01 3.68871574e+01 4.42762718e+01 5.96946411e+01 6.88763351e+01 6.77949066e+01 5.66369476e+01 5.29222603e+01 5.08635292e+01 5.67449989e+01 5.30085106e+01 4.55057640e+01 3.55368767e+01 2.54474335e+01 2.92645988e+01 4.56114502e+01 5.93874168e+01 6.13610458e+01 5.42250290e+01 4.66155434e+01 3.45602684e+01 2.84667568e+01 4.58083305e+01 7.15823517e+01 8.38181152e+01 6.53632355e+01 3.96661835e+01 3.68811607e+01 6.27173996e+01 9.26296310e+01 8.97744980e+01 5.71459351e+01 2.25188217e+01 8.36218643e+00 2.87699375e+01 4.81611900e+01 5.03221626e+01 4.02885361e+01 3.09964199e+01 4.40427475e+01 4.33912163e+01 5.01487770e+01 5.76647148e+01 6.21565437e+01 6.08459015e+01 4.16128540e+01 4.54319000e+01 6.70480652e+01 9.61363373e+01 9.16241684e+01 4.77552872e+01 1.49616385e+01 2.44455528e+01 6.32145157e+01 9.09003983e+01 9.26580887e+01 6.05990524e+01 2.73713837e+01 1.25486870e+01 3.75462799e+01 5.38636208e+01 6.86384125e+01 7.10574493e+01 6.59479675e+01 6.81960449e+01 6.81563721e+01 9.33333435e+01 1.06992584e+02 1.04102730e+02 8.61154556e+01 4.91134796e+01 3.67950134e+01 5.51113129e+01 9.16202774e+01 1.02451111e+02 8.08880463e+01 4.60963326e+01 4.65687218e+01 7.15537262e+01 1.05685547e+02 1.11813454e+02 7.77295609e+01 3.83168755e+01 2.08709984e+01 5.48798409e+01 8.86934433e+01 8.87808914e+01 5.80415726e+01 3.29051590e+01 2.93353577e+01 3.40272179e+01 4.42732048e+01 7.11449051e+01 7.78812180e+01 5.28598671e+01 7.00922191e-01 -1.79070454e+01 1.55105057e+01 5.77251968e+01 9.15731735e+01 6.97809448e+01 3.24985809e+01 7.76231337e+00 1.62927856e+01 4.70705185e+01 4.82114677e+01 2.66404839e+01 -8.81366611e-01 -8.04318523e+00 3.33517265e+01 6.05342293e+01 5.09875069e+01 2.15495319e+01 -1.39785509e+01 -6.55787945e+00 -3.74269414e+00 9.35168648e+00 3.27593193e+01 4.70605354e+01 5.47699738e+01 1.50268993e+01 -9.08433056e+00 7.13290930e+00 4.39156837e+01 7.47612991e+01 4.67386818e+01 8.90215111e+00 -1.46950464e+01 2.75276222e+01 1.03677650e+02 1.45620605e+02 1.00009857e+02 4.26586056e+00 -5.31085968e+01 -2.19103451e+01 3.39326515e+01 5.73203011e+01 6.40748825e+01 7.18149719e+01 1.05302147e+02 3.64376717e+01 1.23118103e+02 2.05285522e+02 1.77956079e+03 2.71184302e+03 -4.44546997e+02 3.01194458e+02 -4.31568896e+03 -1.51168643e+04 1252064128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.74436659e+09 -366176064. 229783328. -625852608. 718892352. -249392048. -931135680. -444683168. 2.03038867e+04 9.28786719e+03 2.68042358e+03 5.30097839e+02 3.94183258e+02 -1.42795935e+03 8.85760498e+01 1.50039636e+03 -1.16056816e+02 7.16766739e+01 2.81951813e+02 2.87280701e+02 2.07059021e+02 2.21468414e+02 1.69422440e+02 1.02522202e+02 4.59960442e+01 3.98763695e+01 6.07738914e+01 2.30741100e+01 1.41817150e+01 7.26657562e+01 1.14898705e+02 6.73712158e+01 -5.12457657e+01 -1.16440033e+02 -4.00074615e+01 5.42590904e+01 1.19255997e+02 8.42163925e+01 -2.39677505e+01 -1.15655289e+02 -1.58691818e+02 -7.29136658e+01 -5.50084734e+00 5.65702248e+00 -5.47834320e+01 -1.01094460e+02 -6.55110855e+01 -6.04189262e+01 -1.14955893e+01 2.87659454e+01 5.11862335e+01 1.08222389e+01 -1.08081223e+02 -1.16616127e+02 -2.29175377e+01 9.54389954e+01 1.22927055e+02 2.45260696e+01 -6.66723328e+01 -5.93250809e+01 1.54513807e+01 4.52048149e+01 -3.25755463e+01 -1.33989822e+02 -1.65916840e+02 -1.14388885e+02 3.63965213e-01 8.14654999e+01 7.98368301e+01 7.78287935e+00 -9.15763931e+01 -1.61168488e+02 -1.97127548e+02 -1.65496063e+02 -9.84518814e+01 -3.90210762e+01 -9.71325970e+00 -3.90707817e+01 -2.10945702e+01 5.30409393e+01 1.24305237e+02 1.14919106e+02 2.24306297e+01 -5.21974754e+01 -2.83781662e+01 1.35133400e+01 7.95942612e+01 1.11149460e+02 7.50043716e+01 -1.55354557e+01 -7.17018967e+01 -1.97035542e+01 4.84605713e+01 2.99433460e+01 -9.26394653e+00 -2.63270874e+01 7.69742584e+00 -1.57089977e+01 -1.06206818e+01 3.07742844e+01 5.73219833e+01 2.46630917e+01 -9.19937210e+01 -1.04527855e+02 3.50042844e+00 1.34243378e+02 1.97648483e+02 1.10065819e+02 8.59101772e+00 -4.30482635e+01 -2.27804680e+01 1.95927982e+01 2.52660980e+01 1.64461720e+00 -5.93578529e+01 -9.39211807e+01 -3.36502724e+01 7.66678696e+01 1.05249123e+02 5.95972672e+01 1.73514900e+01 1.46491785e+01 -1.99278488e+01 -1.63014011e+01 7.04638214e+01 1.68780289e+02 1.59899170e+02 2.40443592e+01 -4.07331581e+01 4.09910774e+01 1.52147980e+02 1.73661942e+02 6.89838028e+01 -4.16053429e+01 -6.65555038e+01 -3.47183838e+01 5.87427292e+01 1.23235847e+02 1.00935921e+02 7.92033863e+00 -6.70301743e+01 -7.88600874e+00 9.23548355e+01 1.30503952e+02 1.03463097e+02 5.50672646e+01 1.67906265e+01 -5.01639442e+01 -7.40762329e+01 -4.28318138e+01 5.71275234e+00 9.56965542e+00 -5.58670425e+01 -8.62110443e+01 -1.19795961e+01 1.11416817e+02 2.01043076e+02 1.54252808e+02 2.82610302e+01 -6.61713333e+01 -6.03776894e+01 1.74796333e+01 4.29303360e+01 1.86112652e+01 4.59974146e+00 -4.04602318e+01 -2.24745655e+01 -1.93955078e+01 2.40987949e+01 9.08092880e+01 1.35209930e+02 1.53126434e+02 6.87116013e+01 2.15919762e+01 6.73175964e+01 1.24847725e+02 1.01980309e+02 -1.82771969e+01 -8.16870346e+01 -4.27312012e+01 1.56569090e+01 5.88820457e+01 5.17793465e+01 2.70698566e+01 7.02361405e-01 -1.51738787e+01 4.89000893e+01 3.99710197e+01 8.37746811e+00 -6.80558929e+01 -1.42042694e+02 -1.86969391e+02 -2.25574661e+02 -1.47667435e+02 -3.83156166e+01 2.71493855e+01 3.69919624e+01 -3.57945099e+01 -3.55556717e+01 2.56993542e+01 1.20159599e+02 1.65299484e+02 5.56219406e+01 -9.08496857e+01 -1.66796173e+02 -1.29392654e+02 -6.28122826e+01 -3.18928452e+01 -4.12649460e+01 -7.39416199e+01 -1.16665680e+02 -8.60749283e+01 -1.98084908e+01 2.06592140e+01 -1.88402634e+01 -3.62097931e+01 -6.00156288e+01 -8.89067535e+01 -1.00136032e+02 -6.08219528e+01 -2.90616226e+01 -2.87456036e+01 -3.94332542e+01 -3.37522817e+00 4.96626854e+01 9.91983032e+01 1.15809692e+02 5.43882713e+01 3.46194077e+00 -7.68014221e+01 -9.58445740e+01 -4.10880737e+01 3.59924431e+01 6.54619293e+01 3.79332137e+00 -3.48760338e+01 -2.63849373e+01 -1.00941420e+01 -1.38497915e+01 -3.32139087e+00 -2.09257174e+00 -3.00053978e+00 -1.44908123e+01 -1.24436922e+01 6.43717146e+00 2.46768265e+01 4.86367378e+01 4.26028938e+01 2.72097702e+01 1.24100578e+00 4.67287970e+00 1.81808128e+01 1.62023544e+01 3.48200202e+00 -3.19972000e+01 -5.87215805e+01 -5.72536316e+01 -4.82188454e+01 -1.09482861e+01 -1.44538155e+01 -8.42564487e+00 -8.26775932e+00 1.17561598e+01 9.60803318e+00 3.57200813e+00 -3.60768342e+00 1.69939079e+01 1.57298222e+01 1.28008709e+01 7.51986885e+00 2.06643639e+01 3.54362679e+01 3.29496498e+01 3.61255875e+01 1.92915936e+01 1.43602238e+01 7.17715263e-01 2.76625061e+00 3.92680860e+00 2.07900200e+01 1.93589249e+01 1.66458130e+01 -1.03375902e+01 -6.57337093e+00 3.14481401e+00 8.26377201e+00 -6.43487263e+00 -1.27405891e+01 -3.30545688e+00 1.25317039e+01 -3.52628517e+00 -4.61328936e+00 -3.21932137e-01 8.25806904e+00 -7.56706953e+00 -1.56408653e+01 3.45048213e+00 5.37211657e+00 -2.11987762e+01 -4.29762917e+01 -4.10977440e+01 -4.48199501e+01 -5.22501755e+01 -4.12047119e+01 -4.50508919e+01 -5.19236679e+01 -5.59675865e+01 -3.39157524e+01 -2.34633770e+01 -3.25962982e+01 -2.32815552e+01 -9.11315727e+00 -2.56523347e+00 -1.16110573e+01 8.97368240e+00 3.99598999e+01 3.70542450e+01 1.43382654e+01 -1.08978891e+01 -2.16600780e+01 -1.36561251e+01 -1.46355038e+01 1.11995578e+00 -1.26951313e+01 -2.32552567e+01 -3.39075584e+01 -4.26951447e+01 -6.23628693e+01 -6.05941658e+01 -3.65723343e+01 -2.04835529e+01 -2.57124863e+01 -3.08867970e+01 -2.65247612e+01 -2.73215981e+01 -4.12067299e+01 -4.35044289e+01 -5.18620224e+01 -5.19587784e+01 -3.94171829e+01 -2.44914246e+01 -9.95265865e+00 -1.93299809e+01 -2.80975533e+01 -4.33055573e+01 -4.79139786e+01 -2.31800976e+01 -4.92515516e+00 -1.21015558e+01 -3.71036453e+01 -4.34510651e+01 -4.29536247e+01 -2.36912079e+01 -2.40564175e+01 -2.30359192e+01 -2.47811966e+01 -1.45989037e+01 1.89994526e+01 8.42032850e-01 9.68973696e-01 -2.17057610e+01 -5.49470997e+00 -9.79176521e+00 -2.00064144e+01 -4.02467308e+01 -2.88681774e+01 -5.64582062e+00 2.02048135e+00 -1.91458759e+01 -3.22251282e+01 -2.66009464e+01 2.52187014e+00 3.78600922e+01 3.48320541e+01 3.46246624e+00 -4.56280479e+01 -2.47871075e+01 8.99269009e+00 3.09312267e+01 7.12171650e+00 -2.54051037e+01 -2.69214916e+01 -2.84164047e+00 1.36672754e+01 1.76054134e+01 5.75230503e+00 1.62417431e+01 3.60330276e+01 4.40136337e+01 1.78733044e+01 -2.12259598e+01 -3.01024914e+01 -1.21392870e+01 -5.49346972e+00 -2.00576630e+01 -3.60113678e+01 -3.53209343e+01 -4.96808958e+00 1.73536034e+01 1.57042656e+01 -8.35974979e+00 -4.12425690e+01 -4.49604187e+01 -4.17228394e+01 -3.77385635e+01 -5.46305771e+01 -8.88024063e+01 -9.50482788e+01 -7.13407822e+01 -4.05500221e+01 -2.21933708e+01 -1.51659679e+01 6.15531921e-01 4.03130531e-01 -5.07999382e+01 -1.02674431e+02 -1.02851395e+02 -6.46647415e+01 -2.50259666e+01 -2.95823307e+01 -3.11827450e+01 -5.41769485e+01 -7.86469727e+01 -7.45427856e+01 -4.26121941e+01 -1.15804167e+01 -6.60090494e+00 9.25557673e-01 -3.40483360e+01 -7.34605103e+01 -8.50778732e+01 -5.50868797e+01 -2.38837070e+01 -6.42470789e+00 4.66533756e+00 1.04265623e+01 -1.67562389e+01 -3.00205307e+01 -4.48426208e+01 -4.75755920e+01 -4.92752724e+01 -5.34681969e+01 -5.38636513e+01 -5.36892128e+01 -5.21015434e+01 -5.80403824e+01 -6.93504181e+01 -7.36501007e+01 -5.67035675e+01 -3.48693047e+01 5.86509743e+01 9.45813980e+01 2.40386791e+01 -4.93514824e+01 -2.82277069e+02 1.30735156e+03 2.32696216e+03 7.85812531e+01 -4.98739014e+02 -8.77386621e+03 -2.08308535e+04 829045312. 5.95769344e+09 253882064. -3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -875751680. 229478736. 595909952. 984809472. 380755104. -102812792. 1.57804512e+04 7.27544922e+03 1.00884534e+03 5.40870911e+02 1.49597435e+01 -1.10351639e+02 -1.70282013e+02 -2.01386337e+02 -2.01514877e+02 -1.88385468e+02 2.73608057e+03 1.87522791e+03 3.85026001e+02 1.24674644e+02 6.58411407e+01 4.13255386e+01 2.84665470e+01 7.65443802e+00 -3.00693913e+01 -4.18571930e+01 -5.61268959e+01 -5.64393654e+01 -6.49428406e+01 -6.51867981e+01 -6.71634445e+01 -7.08460693e+01 -7.47169800e+01 -7.92742920e+01 -7.42116165e+01 -7.31579285e+01 -7.72716827e+01 -7.93339233e+01 -8.15208130e+01 -7.28280258e+01 -6.80040131e+01 -6.57099533e+01 -7.09114075e+01 -7.48252029e+01 -8.09438858e+01 -8.21251907e+01 -7.62069626e+01 -5.47909622e+01 -3.81046257e+01 -3.53315392e+01 -4.56939278e+01 -5.34644661e+01 -5.75822792e+01 -6.39039917e+01 -6.28358841e+01 -5.84826660e+01 -5.58149147e+01 -5.81391830e+01 -6.31972466e+01 -6.47781296e+01 -7.49649429e+01 -6.70904999e+01 -5.92745667e+01 -5.02672386e+01 -4.40059662e+01 -4.00957870e+01 -3.76100693e+01 -4.59131470e+01 -5.15790443e+01 -5.01264305e+01 -5.41012230e+01 -6.50244064e+01 -6.90144348e+01 -6.53533554e+01 -5.69504700e+01 -5.72818832e+01 -5.82146950e+01 -5.02869873e+01 -3.62854004e+01 -3.73756714e+01 -4.26789551e+01 -5.04173317e+01 -3.31106987e+01 -1.87177658e+01 -1.90027046e+01 -2.95457401e+01 -3.68735085e+01 -3.38332939e+01 -3.23843536e+01 -3.71440735e+01 -3.62271423e+01 -3.08094997e+01 -2.18867893e+01 -2.65841236e+01 -3.99379463e+01 -5.32682114e+01 -5.73615646e+01 -5.75139961e+01 -5.43956871e+01 -5.03248367e+01 -5.48753281e+01 -6.22257042e+01 -5.76347961e+01 -4.83601151e+01 -4.51510582e+01 -5.46944046e+01 -6.11213379e+01 -4.95662613e+01 -4.11937752e+01 -4.24904785e+01 -5.53155441e+01 -6.51745071e+01 -6.57106552e+01 -6.55206146e+01 -6.39411392e+01 -6.34586525e+01 -5.97392807e+01 -5.90114326e+01 -6.05115242e+01 -6.08053436e+01 -5.79074821e+01 -5.53064156e+01 -5.55673141e+01 -5.62873955e+01 -5.66767273e+01 -5.60329094e+01 -5.65140648e+01 -4.99730148e+01 -4.32325363e+01 -4.40529099e+01 -5.03115997e+01 -5.73413620e+01 -5.08649788e+01 -4.53733177e+01 -4.49059982e+01 -5.01056709e+01 -5.40721512e+01 -5.49541359e+01 -5.59200668e+01 -5.82214203e+01 -5.68910484e+01 -5.63485260e+01 -5.56487999e+01 -5.79510345e+01 -5.95887070e+01 -5.90665855e+01 -5.67492447e+01 -5.53681259e+01 -5.60111465e+01 -5.66950493e+01 -5.62468987e+01 -5.47164345e+01 -5.10733757e+01 -4.76663704e+01 -4.83343849e+01 -5.13230057e+01 -5.46271210e+01 -5.23792419e+01 -5.03234825e+01 -5.11416512e+01 -5.46267891e+01 -5.72088470e+01 -5.69047737e+01 -5.62674217e+01 -5.60792694e+01 -5.63496628e+01 -5.64882240e+01 -5.65754738e+01 -5.68962212e+01 -5.69821854e+01 -5.65687408e+01 -5.62602463e+01 -5.65687065e+01 -5.70042152e+01 -5.72364426e+01 -5.72332382e+01 -5.72105141e+01 -5.74463997e+01 -5.79133263e+01 -5.80614815e+01 -5.77969093e+01 -5.75568886e+01 -5.76403770e+01 -5.71905022e+01 -5.79849701e+01 -5.97019997e+01 -6.04618721e+01 -5.94555244e+01 -5.80591049e+01 -5.83157997e+01 -5.85943642e+01 -5.80323296e+01 -5.75658379e+01 -5.80101662e+01 -5.82992363e+01 -6.13741379e+01 -6.42698746e+01 -6.46867065e+01 -6.14056206e+01 -5.87238350e+01 -6.00319901e+01 -6.09018250e+01 -6.39090843e+01 -6.70073318e+01 -6.67707748e+01 -6.17415047e+01 -5.68583221e+01 -5.77843094e+01 -5.84107780e+01 -5.92330780e+01 -5.75868530e+01 -5.61353340e+01 -5.51952820e+01 -5.51374435e+01 -5.58543358e+01 -5.55760612e+01 -5.51804962e+01 -5.55534668e+01 -5.19936867e+01 -4.82630806e+01 -4.62352676e+01 -4.66175575e+01 -4.99574394e+01 -5.02092400e+01 -5.06060677e+01 -5.01226158e+01 -5.07452240e+01 -5.18303947e+01 -5.00616150e+01 -5.15803146e+01 -5.30344887e+01 -5.28435173e+01 -4.89739380e+01 -4.77071991e+01 -4.89343834e+01 -5.08352013e+01 -5.06471863e+01 -5.02020798e+01 -5.26444435e+01 -5.20157280e+01 -5.61351089e+01 -5.81607437e+01 -5.96845093e+01 -5.19897041e+01 -4.23524246e+01 -4.71447983e+01 -6.24782333e+01 -7.19786224e+01 -6.96203232e+01 -6.28687057e+01 -5.97790298e+01 -6.00087967e+01 -5.98720589e+01 -6.31284447e+01 -6.31184425e+01 -6.27746201e+01 -6.06891136e+01 -5.75172234e+01 -5.36382332e+01 -5.15270081e+01 -5.43594704e+01 -5.83443756e+01 -6.16505089e+01 -6.12297211e+01 -5.97084465e+01 -5.88638420e+01 -5.49037056e+01 -5.33486977e+01 -5.05906372e+01 -5.59383926e+01 -6.77792816e+01 -8.02952042e+01 -7.86546097e+01 -7.07306595e+01 -5.73395538e+01 -5.53842163e+01 -5.25422745e+01 -6.27815094e+01 -7.18997879e+01 -7.74491577e+01 -7.98486404e+01 -7.00572052e+01 -6.18937759e+01 -4.93016510e+01 -5.31963387e+01 -5.68149338e+01 -5.87821045e+01 -5.51251907e+01 -5.36208305e+01 -4.97026672e+01 -5.38468781e+01 -6.01869392e+01 -6.43049088e+01 -6.71661453e+01 -6.54862595e+01 -8.11698914e+01 -9.07964020e+01 -8.70934753e+01 -6.81113663e+01 -5.44644012e+01 -6.04758110e+01 -6.58944702e+01 -6.38507347e+01 -6.21113434e+01 -7.32712784e+01 -8.92070389e+01 -8.86508408e+01 -6.91482239e+01 -4.85394173e+01 -5.60447578e+01 -6.43341064e+01 -6.34063034e+01 -5.12646561e+01 -4.83321609e+01 -5.18601913e+01 -6.08775139e+01 -5.51430206e+01 -4.27889481e+01 -3.85476303e+01 -4.14018707e+01 -4.66192284e+01 -3.85716705e+01 -5.08871117e+01 -6.92151642e+01 -7.45215073e+01 -8.12206497e+01 -9.32012253e+01 -1.10402687e+02 -1.08886650e+02 -9.98533936e+01 -1.03033913e+02 -9.38214645e+01 -8.99454193e+01 -7.00282364e+01 -4.94182549e+01 -2.19858456e+01 -1.66080647e+01 -2.35091896e+01 -2.99034882e+01 -3.46757698e+01 -3.76071053e+01 -3.76981430e+01 -3.27066803e+01 -2.68417587e+01 -4.44394836e+01 -7.29159927e+01 -8.38345261e+01 -7.89548492e+01 -5.96087189e+01 -5.13640060e+01 -5.02881203e+01 -3.83257751e+01 -4.90532455e+01 -4.83636703e+01 -6.08627663e+01 -6.87338257e+01 -8.21328583e+01 -1.02102806e+02 -8.46367264e+01 -6.34264870e+01 -5.23752708e+01 -7.71844559e+01 -8.40845642e+01 -7.54249268e+01 -4.84982338e+01 -6.70286636e+01 -8.82013474e+01 -9.96593552e+01 -8.21387558e+01 -6.26586761e+01 -8.44516373e+01 -1.06818779e+02 -9.97752151e+01 -6.21936569e+01 -4.00923119e+01 -6.26853256e+01 -7.92938080e+01 -5.27711563e+01 -1.99102440e+01 -3.90874786e+01 -8.62945938e+01 -1.04707909e+02 -9.22416458e+01 -7.38177795e+01 -7.88455124e+01 -9.96214752e+01 -1.19554558e+02 -1.07459564e+02 -7.06073914e+01 -3.68350258e+01 -3.97758064e+01 -4.68167610e+01 -5.18209763e+01 -4.72064934e+01 -4.71498299e+01 -5.49601364e+01 -7.28523636e+01 -7.52060928e+01 -5.62689438e+01 -4.92558937e+01 -5.23568039e+01 -8.31327362e+01 -9.44635162e+01 -7.92604141e+01 -6.58241272e+01 -4.50233078e+01 -5.01851273e+01 -4.49054527e+01 -3.93917656e+01 -2.79520073e+01 -3.10368214e+01 -7.36620636e+01 -1.08633507e+02 -7.04355927e+01 -5.47870970e+00 -6.11166060e-01 -6.00520477e+01 -8.15764771e+01 -4.60914268e+01 -2.62915192e+01 -5.15705223e+01 -6.40822220e+01 -5.84587364e+01 -3.09195614e+01 -4.46037025e+01 -5.71918602e+01 -6.50373001e+01 -5.18659935e+01 -2.44184647e+01 -2.65352135e+01 -2.63977089e+01 -5.63113174e+01 -7.89147186e+01 -8.38037567e+01 -5.01125259e+01 -5.05438652e+01 -1.09085762e+02 -1.50654053e+02 -1.33459534e+02 -7.32925568e+01 -7.05009155e+01 -8.82321091e+01 -6.94446869e+01 -1.40887127e+01 2.78614116e+00 -3.36123085e+01 -6.85108109e+01 -6.06651535e+01 -4.94765587e+01 -6.09114761e+01 -6.81979980e+01 -6.49091492e+01 -5.72442589e+01 -3.66474342e+01 -2.25282650e+01 -1.05696697e+01 -2.95563354e+01 -4.28595276e+01 -5.82726402e+01 -5.97186279e+01 -6.79325714e+01 -8.97825699e+01 -9.03254623e+01 -6.93356171e+01 -4.30349007e+01 -5.21359329e+01 -8.47711258e+01 -8.82089005e+01 -8.68249054e+01 -9.72460785e+01 -1.56102921e+02 -1.86415359e+02 -1.60726273e+02 -9.15579529e+01 -7.15397034e+01 -8.29770279e+01 -9.21356430e+01 -6.55852127e+01 -5.20801697e+01 -3.52567596e+01 -2.21420403e+01 -2.07170639e+01 -3.58450165e+01 -3.72331276e+01 -1.49971905e+01 -1.55146656e+01 -6.63883057e+01 -8.98625870e+01 -6.74922333e+01 -3.54004211e+01 -7.47686462e+01 -9.50340042e+01 -6.06241875e+01 7.74256039e+00 4.95570221e+01 4.72427559e+01 4.52291946e+01 2.82478008e+01 6.63287830e+00 -5.54280710e+00 1.31754959e+00 -5.34942865e+00 -1.71944199e+01 -1.91563892e+01 7.92837238e+00 -1.07176752e+01 -7.41170425e+01 -1.15094276e+02 -1.20235458e+02 -1.09986572e+02 -8.76229935e+01 -6.07600098e+01 -2.97471333e+01 -2.88962879e+01 -2.29606495e+01 -1.67963543e+01 -1.73797970e+01 -2.95922318e+01 -3.33545036e+01 -4.05131607e+01 -3.46673584e+01 -2.16876564e+01 -1.41881456e+01 -1.22731180e+01 -6.05470886e+01 -1.08836662e+02 -1.16115616e+02 -8.01944122e+01 -4.24673996e+01 -4.67418137e+01 -4.51751022e+01 -4.84484482e+01 -3.51647415e+01 -3.98414421e+01 -4.21673508e+01 -8.03523026e+01 -1.09042595e+02 -9.13670273e+01 -4.88081055e+01 -3.69228439e+01 -1.03897736e+02 -1.44590897e+02 -1.18500572e+02 -5.12371635e+01 -5.27211380e+01 -7.61298599e+01 -8.10392685e+01 -5.26001740e+01 -2.70800648e+01 -6.31705399e+01 -8.59418793e+01 -1.14590706e+02 -1.26711189e+02 -8.52759247e+01 -5.34660683e+01 -5.18861465e+01 -1.32753342e+02 -1.72295456e+02 -1.17623062e+02 -4.51833153e+01 -5.44202614e+01 -1.10743584e+02 -1.24268250e+02 -9.41040726e+01 -5.82092247e+01 -7.93338776e+01 -1.02133553e+02 -1.15519051e+02 -9.42652130e+01 -6.63449402e+01 -5.00225449e+01 -8.82426300e+01 -1.30901154e+02 -1.38281906e+02 -1.03086815e+02 -4.19163055e+01 -6.67655258e+01 -9.68429108e+01 -1.01251244e+02 -6.55603180e+01 -6.03659325e+01 -1.08266579e+02 -1.07393333e+02 -6.75585938e+01 -1.29024048e+01 2.71413946e+00 3.74683523e+00 -3.06506500e+01 -8.30988464e+01 -9.93912659e+01 -7.88562775e+01 -3.29223328e+01 -1.48806753e+01 -1.26626902e+01 -3.35564308e+01 -5.23433075e+01 -4.03611412e+01 -2.21607208e+02 -3.59278717e+02 -2.86311127e+02 4.73044205e+01 2.19424103e+02 -4.81239891e+01 -1.25920845e+02 -2.45253525e+02 -1.35615186e+03 -2.56578101e+03 -5.13050293e+03 3.77181978e+09 1.39022500e+05 1583832192. 2.60913623e+10 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. 0. 0. 0. 1.72460215e+04 6.52683105e+03 1.17781970e+03 6.67517273e+02 2.22836426e+02 -7.37948303e+01 -8.79293137e+01 -1.06612329e+01 1.20292625e+01 -3.26986923e+01 5.83143806e+00 8.29117126e+01 1.39918243e+02 7.04519958e+01 -7.95663681e+01 -1.49859894e+02 -9.48110580e+01 -1.46157110e+00 4.55856552e+01 2.97715511e+01 8.37552166e+00 3.42513161e+01 7.62916412e+01 4.21918602e+01 -2.77812290e+01 -6.99270096e+01 -4.04904404e+01 2.35641632e+01 4.25102615e+01 -3.40323853e+00 -7.75314713e+01 -1.13638695e+02 -7.61244431e+01 -8.37480011e+01 -1.32578979e+02 -8.90615540e+01 2.00839500e+01 9.55596924e+01 9.79972649e+00 -1.50914154e+02 -1.97312271e+02 -1.18602905e+02 -3.19589710e+01 1.78384323e+01 2.56694641e+01 4.38008595e+00 -2.09922862e+00 -1.92220461e+00 -1.40074997e+01 -1.31320831e+02 -2.08762695e+02 -1.65961548e+02 -5.40794449e+01 2.05110340e+01 -2.39615746e+01 -9.11868057e+01 -1.34933441e+02 -7.05222092e+01 -5.19073715e+01 -7.44347763e+01 -5.08419342e+01 2.03262024e+01 1.00745346e+02 8.71984482e+01 -2.29645157e+01 -6.28192520e+01 -3.18858643e+01 5.35021935e+01 3.79545937e+01 -2.09992847e+01 -1.59141245e+01 3.07798271e+01 6.40692673e+01 2.30831928e+01 -7.78382111e+01 -1.30019745e+02 -1.02377663e+02 4.52575505e-01 6.53129807e+01 5.06096420e+01 5.11187315e+00 1.21925182e+01 6.28851166e+01 5.80440102e+01 -6.89024639e+00 -4.35655403e+01 2.14127731e+01 1.07829796e+02 1.14309822e+02 2.17572536e+01 -5.66533127e+01 -5.12907944e+01 1.08256102e+01 2.12403412e+01 -2.33517647e+00 4.19145088e+01 1.31756104e+02 1.73250290e+02 1.07532654e+02 -1.33057127e+01 -8.35290985e+01 -5.13553200e+01 2.23738003e+01 1.04877884e+02 1.58715729e+02 1.41880157e+02 1.21132889e+02 1.13554382e+02 9.97970352e+01 2.38607655e+01 -4.48005867e+01 -2.92720318e+00 1.10272888e+02 1.62804977e+02 1.16752800e+02 5.51882172e+00 -5.79045753e+01 -2.00777473e+01 2.71251316e+01 4.65845337e+01 4.17336693e+01 8.69259491e+01 1.72316833e+02 1.76666855e+02 9.09149170e+01 -6.77872300e-01 -2.69697332e+00 5.84213753e+01 9.97118149e+01 1.08090981e+02 8.17594147e+01 4.76157188e+01 1.96613827e+01 7.21702118e+01 9.58404312e+01 5.82877808e+01 1.42125168e+01 5.52765417e+00 2.99051590e+01 3.13707657e+01 -4.10552531e-01 8.52091694e+00 3.52432556e+01 7.04012680e+01 8.42881470e+01 4.49491844e+01 2.24311543e+01 3.80531578e+01 7.79401245e+01 5.03215485e+01 -6.06068649e+01 -1.15085312e+02 -3.57122116e+01 6.42254639e+01 6.83663788e+01 1.10167580e+01 -2.29305096e+01 -7.25330687e+00 -7.22709322e+00 -4.50693588e+01 -9.44588318e+01 -1.02769989e+02 -7.21236191e+01 -7.35902882e+00 3.62627487e+01 3.98143649e+00 -2.11416817e+01 -1.09199200e+01 2.81428432e+01 6.25412512e+00 -8.27399216e+01 -6.92307663e+01 -3.23568687e+01 1.67665977e+01 -3.20525894e+01 -1.34314636e+02 -1.84664703e+02 -1.39276688e+02 -3.03506908e+01 1.85165138e+01 1.02140856e+01 1.79118843e+01 4.37419815e+01 2.60511208e+01 -4.59498863e+01 -1.24966827e+02 -1.22744377e+02 -5.21561089e+01 5.65217819e+01 9.58424301e+01 6.09291458e+01 -7.10873842e+00 -4.11041756e+01 -3.57321739e+01 -5.93684540e+01 -8.57622528e+01 -7.48076935e+01 5.98747683e+00 6.21524506e+01 3.59402618e+01 -6.84890060e+01 -1.08672760e+02 -5.37722321e+01 4.56807365e+01 7.52882080e+01 2.93395596e+01 -2.32194595e+01 2.58788514e+00 4.36102448e+01 3.61331177e+01 -1.39094276e+01 -2.41333790e+01 2.56613388e+01 9.28207321e+01 1.02584412e+02 6.66421509e+01 1.96490364e+01 1.90444202e+01 4.17432175e+01 5.12918320e+01 2.87855453e+01 4.19951057e+01 7.05048981e+01 7.76708755e+01 7.25481720e+01 3.75141106e+01 2.49090271e+01 3.62826385e+01 3.64506226e+01 3.26003151e+01 2.16761899e+00 2.65042496e+01 6.51008606e+01 8.48272400e+01 7.11132660e+01 -9.86924076e+00 -5.71623802e+01 -5.03810539e+01 4.18248444e+01 8.80111084e+01 9.23919830e+01 5.17799187e+01 3.41682739e+01 5.58099403e+01 5.36532860e+01 2.93340912e+01 9.77325249e+00 3.46194916e+01 5.59276695e+01 1.48161659e+01 -4.14577980e+01 -3.52025070e+01 -1.16706324e+00 2.00143681e+01 5.82803965e-01 -4.07971115e+01 -5.44184780e+00 2.46917286e+01 5.80674858e+01 4.38759651e+01 1.93934035e+00 -2.01433125e+01 -3.14516773e+01 1.24361153e+01 2.62957306e+01 2.91064816e+01 -9.39937019e+00 -9.28080082e+00 -8.43410301e+00 -1.16280994e+01 -3.25115929e+01 -4.40465660e+01 2.36969173e-01 3.03744221e+01 3.27818527e+01 -1.02707787e+01 -1.15473433e+01 8.75361252e+00 3.45053368e+01 5.24362564e+01 4.29882126e+01 4.40491371e+01 9.83591938e+00 -8.35041332e+00 -2.23547821e+01 -1.65705261e+01 -4.83345127e+00 1.19659557e+01 4.59788895e+01 6.55953598e+01 5.24623184e+01 4.79188061e+00 -5.02420378e+00 6.09767914e+00 1.17198505e+01 7.41559744e+00 2.13061008e+01 7.27351608e+01 8.68619080e+01 6.16460876e+01 7.61351681e+00 -4.31735420e+00 1.39700842e+01 4.34130249e+01 5.39409752e+01 3.48073654e+01 3.23880997e+01 2.22555523e+01 4.84209671e+01 6.14220467e+01 6.36569672e+01 4.16141319e+01 2.72559223e+01 4.37079430e+01 6.46537170e+01 5.22044640e+01 2.67355099e+01 3.34825249e+01 5.17473488e+01 5.33309364e+01 4.03271294e+01 4.12161064e+01 6.80869446e+01 7.52878113e+01 5.98057823e+01 3.24432945e+01 3.05504646e+01 4.21138191e+01 5.07347221e+01 4.62474136e+01 3.30377045e+01 3.57943077e+01 3.63915901e+01 5.49852486e+01 6.39088516e+01 6.37860870e+01 5.18530769e+01 4.52638245e+01 5.47222900e+01 6.55459290e+01 5.68895340e+01 3.36657829e+01 2.66060963e+01 2.71365395e+01 2.13939247e+01 3.50121379e+00 9.64058208e+00 2.96451168e+01 3.30929947e+01 1.88522491e+01 2.48367950e-01 1.93758163e+01 3.06585979e+01 3.89692116e+01 4.77204933e+01 4.91266594e+01 4.00799942e+01 1.24066610e+01 7.81060410e+00 2.84614830e+01 4.61192970e+01 3.70243530e+01 1.38426542e+01 2.05898809e+00 1.69252625e+01 2.86015701e+01 2.58048973e+01 1.76604252e+01 7.16125727e+00 -1.78694785e+00 -1.48303194e+01 -9.09184170e+00 6.28868437e+00 1.12409496e+01 5.25720930e+00 -2.46668935e+00 1.37442799e+01 2.27813854e+01 2.98821983e+01 2.73647766e+01 2.58375530e+01 1.62624874e+01 -3.10076857e+00 -7.78196669e+00 8.63228703e+00 3.66075172e+01 4.32641525e+01 2.18557777e+01 2.68544316e+00 1.78840339e+00 1.61222839e+01 2.41782494e+01 2.00512524e+01 1.02373600e+01 5.23243809e+00 1.17049313e+01 2.61817150e+01 3.02290611e+01 2.36482754e+01 1.46692896e+01 5.27192879e+00 5.86775351e+00 1.02389727e+01 2.24236870e+01 3.38249435e+01 3.77014923e+01 3.10208836e+01 1.82179947e+01 1.21405783e+01 1.86057606e+01 2.77360725e+01 2.70884285e+01 1.85266380e+01 1.22542639e+01 1.64975166e+01 2.55775223e+01 3.12765789e+01 3.12451496e+01 2.68551483e+01 2.41195850e+01 2.21219234e+01 2.52683449e+01 2.67351933e+01 2.80839767e+01 2.67983227e+01 2.62491684e+01 2.77224445e+01 2.88441849e+01 3.00194893e+01 2.97979393e+01 2.90613060e+01 2.85645180e+01 2.86467361e+01 2.91999741e+01 2.92114162e+01 2.77590179e+01 2.64865513e+01 2.72165966e+01 3.02721119e+01 3.26849174e+01 3.21535187e+01 3.03817635e+01 3.05564308e+01 3.26248093e+01 3.44369926e+01 3.50829697e+01 3.14594555e+01 2.79770565e+01 2.44815063e+01 2.44930305e+01 2.70781536e+01 3.01952248e+01 3.41939087e+01 3.38414955e+01 2.95638580e+01 2.46342278e+01 2.46786804e+01 3.03418102e+01 3.75665131e+01 3.43137550e+01 2.73024025e+01 2.36203232e+01 3.03108406e+01 4.23800468e+01 4.20310745e+01 3.42466011e+01 2.13344326e+01 2.07611351e+01 3.11390514e+01 4.00410995e+01 4.72394447e+01 3.66322594e+01 3.21204262e+01 2.56508732e+01 2.36057224e+01 2.20702400e+01 2.09393597e+01 2.84769440e+01 2.51496544e+01 1.79909649e+01 1.86435127e+01 2.84152908e+01 4.54080048e+01 5.35924072e+01 4.41519890e+01 1.97675972e+01 -2.87920332e+00 -5.16674876e-01 2.58800945e+01 5.28390884e+01 6.16796074e+01 4.23246536e+01 1.68331566e+01 1.12898836e+01 2.71651402e+01 4.71450844e+01 4.00651512e+01 2.48014965e+01 1.13632078e+01 8.78294849e+00 1.54757490e+01 2.86600895e+01 4.50421562e+01 4.33270454e+01 2.69440002e+01 4.24385160e-01 -4.38536787e+00 1.55532637e+01 4.37325325e+01 4.15856590e+01 1.91559620e+01 2.45907140e+00 1.10398493e+01 2.43512478e+01 3.14741669e+01 3.51098366e+01 2.42762737e+01 1.69817276e+01 2.61650467e+01 3.46804848e+01 4.47490005e+01 2.89265671e+01 1.52831125e+01 -3.29491758e+00 -1.57177753e+01 -1.95178199e+00 1.23657026e+01 3.80324135e+01 4.81361809e+01 3.31720390e+01 8.64819431e+00 4.40336800e+00 3.29358482e+01 6.15717201e+01 5.88826790e+01 4.19192429e+01 1.06929388e+01 1.41295207e+00 1.02252884e+01 2.72060432e+01 3.80712051e+01 1.40312901e+01 -8.51214314e+00 -3.63236580e+01 -2.97133808e+01 6.89960718e-01 3.07561970e+00 -1.08757257e+01 -4.17210274e+01 -5.09672585e+01 -3.90459099e+01 -1.61523590e+01 2.69384251e+01 4.36547241e+01 3.23925591e+01 -3.85875487e+00 -1.98368664e+01 8.55517673e+00 4.33051529e+01 4.28309631e+01 1.58867979e+00 -3.03815651e+01 -2.02545948e+01 2.25574570e+01 5.95347366e+01 6.22649689e+01 2.88454647e+01 -1.37721148e+01 -2.56572742e+01 -2.19430828e+01 -8.54363728e+00 6.76860762e+00 2.96348228e+01 3.22460060e+01 1.97791557e+01 1.08386030e+01 3.04224663e+01 7.49147415e+01 9.82964478e+01 6.12428703e+01 4.89441729e+00 -2.31893692e+01 1.33141203e+01 6.53938522e+01 7.60912094e+01 4.36913910e+01 -1.15286436e+01 -2.11256332e+01 1.25331373e+01 3.11925850e+01 4.04184914e+01 7.24111223e+00 -2.02311143e-01 3.14320230e+00 1.42041664e+01 4.39061317e+01 3.39277420e+01 2.52269535e+01 -2.04170818e+01 -5.88332634e+01 -4.28806190e+01 -2.02709770e+01 3.28196449e+01 4.32630234e+01 3.53875961e+01 -2.39596062e+01 -8.58169861e+01 -9.31389008e+01 -4.39226456e+01 -1.36971498e+00 -1.49893219e+02 -1.53436584e+02 -4.90495644e+01 -1.35070203e+03 -1.90111267e+03 -4.31568896e+03 -1.51168643e+04 1252064128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98855859e+03 -3.81954419e+03 -3.59041595e+02 -2.52202255e+02 -1.55202621e+02 -1.33030655e+02 -6.09685669e+01 -3.26861191e+01 6.15505371e+01 6.10941734e+01 1.97751312e+01 -4.59125900e+01 -3.32215424e+01 4.44072342e+01 1.11305611e+02 1.23646767e+02 5.17029266e+01 -3.71878204e+01 -5.59837837e+01 2.11583042e+01 9.14925995e+01 9.42255096e+01 3.16343670e+01 3.63177071e+01 7.85378265e+01 8.68490677e+01 4.98024940e+01 -2.48112059e+00 -5.56118727e+00 -2.07350464e+01 -4.67185898e+01 -4.17194557e+01 5.84258270e+00 1.03174553e+02 1.04982788e+02 4.67622337e+01 -1.49586296e+01 -8.99771500e+00 5.87107162e+01 1.33461502e+02 1.21989296e+02 2.17218857e+01 -1.00239662e+02 -8.79272003e+01 2.75115547e+01 9.20403824e+01 9.47753372e+01 2.93341064e+01 7.99947786e+00 -3.62016869e+00 -1.53669262e+01 2.90421939e+00 3.21266975e+01 1.08829987e+02 8.00920105e+01 1.56908503e+01 -1.44303226e+01 3.58133774e+01 1.19532463e+02 1.20680367e+02 8.03346176e+01 8.05333614e+00 -2.08315830e+01 4.87939301e+01 1.47155350e+02 2.19024155e+02 1.76651001e+02 7.25984802e+01 3.72033997e+01 9.62567215e+01 1.40260391e+02 1.29052841e+02 3.67465897e+01 1.74951382e+01 4.42398338e+01 8.92336273e+01 8.50826187e+01 8.00880890e+01 1.05441101e+02 7.22966003e+01 1.33651819e+01 -1.66971970e+01 5.19787369e+01 1.56338837e+02 1.73344009e+02 1.35984421e+02 5.49261894e+01 -3.59573990e-01 -9.26344776e+00 5.46988640e+01 1.06233955e+02 9.81854553e+01 -4.94553947e+00 -4.49118614e+01 3.04387608e+01 1.02994232e+02 9.94305344e+01 -3.15322876e+00 -4.38871765e+01 -3.21706161e+01 -1.97732964e+01 -4.38426447e+00 3.26496239e+01 1.19854759e+02 1.13866219e+02 4.46446228e+01 -1.02908878e+01 -8.99221992e+00 5.79495926e+01 6.49298859e+01 2.43074093e+01 -8.99279118e+00 -5.26481628e+01 -3.72609673e+01 2.85420170e+01 1.03457855e+02 1.21334114e+02 2.01017265e+01 -3.01447868e+01 1.29127674e+01 4.09346428e+01 5.01865730e+01 -1.65246630e+00 6.12332106e+00 9.99234867e+00 -2.20734940e+01 -3.13837719e+01 -1.84169407e+01 8.09001617e+01 8.14189453e+01 1.62664509e+01 -4.65497437e+01 -3.86789665e+01 2.15039539e+01 2.44263554e+01 -2.81890965e+01 -6.24397430e+01 -1.12955254e+02 -6.81326675e+01 6.81891775e+00 7.86766968e+01 6.62337952e+01 -8.47215748e+00 -1.92315006e+01 1.40977526e+01 1.76572151e+01 -4.09291792e+00 -6.83763657e+01 -9.88876953e+01 -1.27396423e+02 -1.30996429e+02 -8.24789505e+01 -2.33801003e+01 6.61530075e+01 9.15371323e+01 7.47391205e+01 1.99403095e+01 1.78133812e+01 8.19363403e+01 1.42439392e+02 1.06152405e+02 -7.67807102e+00 -8.97916946e+01 -8.44213409e+01 2.43671398e+01 8.32002640e+01 7.52775421e+01 7.97710037e+00 -5.82575655e+00 2.74548149e+01 2.28537712e+01 3.14413013e+01 4.06375351e+01 4.62573586e+01 -1.01683455e+01 -8.73612137e+01 -8.28691330e+01 -5.10408936e+01 7.00134230e+00 4.17689400e+01 5.73069649e+01 2.52139969e+01 2.22843342e+01 8.17467422e+01 1.49432266e+02 1.08043175e+02 9.63793373e+00 -7.81216812e+01 -7.97679749e+01 -5.57192183e+00 2.09413548e+01 3.25561943e+01 -3.96876907e+01 -3.20912819e+01 2.18142128e+01 9.01596603e+01 1.29300064e+02 1.27892334e+02 1.76808105e+02 1.46883194e+02 6.41606369e+01 -1.02937565e+01 -1.36950846e+01 5.76015091e+01 6.68723450e+01 1.83282890e+01 -6.56057968e+01 -1.39871124e+02 -9.62191467e+01 2.84989510e+01 1.37309982e+02 9.77851639e+01 -1.37239513e+01 -3.05947247e+01 2.63668022e+01 4.97125244e+01 5.00375443e+01 2.93670440e+00 -2.51380692e+01 -5.66576538e+01 -5.00584793e+01 -2.75683193e+01 2.12494907e+01 9.58025513e+01 1.18410469e+02 9.01938248e+01 4.05508614e+01 2.30548248e+01 2.64806080e+01 -6.17514610e+00 -4.40544205e+01 -5.66281929e+01 -4.02871895e+01 1.22476463e+01 1.84946117e+01 3.01116505e+01 1.77915192e+01 -1.09502640e+01 -2.12613735e+01 -1.69613819e+01 2.68736019e+01 3.81058273e+01 1.55070858e+01 -1.62246723e+01 -1.53008451e+01 6.57869148e+00 2.41523018e+01 1.29707651e+01 -3.41151857e+00 -5.18500042e+00 -8.88159370e+00 -5.87438405e-01 -1.85642052e+01 -1.15640860e+01 -1.48226328e+01 6.09668875e+00 -1.09735136e+01 -2.42486076e+01 -3.09224072e+01 -2.29173031e+01 -1.43999224e+01 -3.13389969e+01 -4.27413788e+01 -3.87935028e+01 -4.55203400e+01 -4.10558624e+01 -3.39332352e+01 -1.22008276e+01 -2.20530052e+01 -2.44804897e+01 -2.88441982e+01 -2.18555317e+01 -3.06444893e+01 -3.69763412e+01 -3.41917191e+01 -3.63737068e+01 -3.22391167e+01 -2.09069672e+01 -1.72049103e+01 -2.39805470e+01 -2.96396465e+01 -3.78442383e+01 -3.23534851e+01 -4.91022377e+01 -3.83208809e+01 -4.71223679e+01 -3.53566360e+01 -3.69363708e+01 -1.45365877e+01 1.68940086e+01 2.77781315e+01 1.34464808e+01 -8.29477406e+00 -2.32120953e+01 -9.20576096e+00 -1.26447468e+01 1.13015699e+00 -9.09757996e+00 -2.38804722e+01 -3.00246601e+01 -1.70127239e+01 -4.76301479e+00 -1.45151520e+01 -1.93958015e+01 -9.40195942e+00 -9.94335842e+00 -2.92381096e+01 -2.04589424e+01 -4.34436560e+00 1.80116024e+01 1.19388552e+01 1.27940245e+01 -1.38630733e+01 -3.98861389e+01 -7.68825607e+01 -8.44601135e+01 -6.92372818e+01 -4.14414635e+01 -2.48070164e+01 -1.78192692e+01 -1.71409168e+01 -6.79822397e+00 -3.49671783e+01 -6.56402969e+01 -6.05955505e+01 -2.88461342e+01 -9.42799926e-01 -5.90686417e+00 -1.31187830e+01 -2.69463587e+00 3.45970583e+00 2.62443423e+00 -2.36282158e+00 2.53176427e+00 5.47785473e+00 -1.35778265e+01 -2.45366135e+01 -1.14614811e+01 2.34521999e+01 5.77425003e+01 5.81840057e+01 3.98297844e+01 4.39747572e+00 1.13286257e+01 1.78089161e+01 1.92598286e+01 1.37962503e+01 3.13684011e+00 2.69868221e+01 4.12379036e+01 4.67609940e+01 7.48628712e+00 -2.18792706e+01 -3.53129272e+01 -5.46596050e+00 3.20652733e+01 6.80584335e+01 3.93069344e+01 -1.45144539e+01 -3.30106583e+01 -2.21233120e+01 8.05364990e+00 1.01110191e+01 4.40233841e+01 5.65211449e+01 4.69379158e+01 1.81016006e+01 -6.83134270e+00 -2.00385056e+01 -1.30438948e+01 6.06837177e+00 3.30470695e+01 3.29737778e+01 7.63516998e+00 -1.13566608e+01 -2.58973866e+01 -2.28287048e+01 -2.83168468e+01 -3.66640549e+01 -3.96967773e+01 -3.02084827e+01 -2.10092220e+01 -1.26895056e+01 -2.21889305e+01 -2.70869579e+01 -2.67084885e+01 -1.17617416e+01 -1.97512684e+01 -3.26377296e+01 -1.65989819e+01 3.34802485e+00 -3.74146724e+00 -4.37827148e+01 -5.93913231e+01 -3.52208214e+01 -1.86291752e+01 -1.32271614e+01 -8.52545738e+00 1.16340971e+01 1.38163424e+01 2.45243263e+01 1.61167412e+01 1.25148659e+01 -1.13239899e+01 -1.39175406e+01 -1.59122527e+00 -5.52471590e+00 -1.27190552e+01 -2.47462482e+01 -2.74562130e+01 -3.19763317e+01 2.14068675e+00 3.28947754e+01 4.51039734e+01 6.70439863e+00 -1.29823771e+01 -2.44328499e+01 -2.49437199e+01 -3.12734394e+01 -3.24505806e+01 -2.17316132e+01 -3.34410210e+01 -5.27830048e+01 -7.57261810e+01 -7.29292526e+01 -5.84850998e+01 -3.27654381e+01 -3.31476822e+01 -3.77341347e+01 -4.63200455e+01 -4.33138199e+01 -3.51176682e+01 -6.44664307e+01 -9.43247223e+01 -9.35996552e+01 -5.70545883e+01 -1.31550674e+01 -1.01551666e+01 -3.67690353e+01 -7.95358658e+01 -1.80671936e+02 -4.54600311e+02 -6.19631775e+02 -6.51332336e+02 -8.05892944e+02 -2.87709692e+03 -4.14713623e+03 -5.46478943e+02 -2.66634338e+02 7.85812531e+01 -4.98739014e+02 -8.77386621e+03 -2.08308535e+04 829045312. 5.95769344e+09 253882064. -3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.23476855e+03 -3.83377271e+03 -6.12698608e+02 -4.12772766e+02 -1.88964539e+02 -1.36008896e+02 -9.22733994e+01 -4.64535866e+01 -4.93045959e+01 -4.95302505e+01 -4.34809990e+01 -4.62795753e+01 -6.03344269e+01 -7.77909470e+01 -5.87565269e+01 -3.11655121e+01 -2.67104015e+01 -4.74779739e+01 -6.58357086e+01 -5.27669678e+01 -4.62841339e+01 -4.47425232e+01 -4.91555481e+01 -5.83381844e+01 -5.73520355e+01 -5.43336449e+01 -4.36876602e+01 -4.38488770e+01 -3.96275749e+01 -3.90156822e+01 -2.02110538e+01 -3.44473720e+00 -2.80428886e+00 -1.51925974e+01 -2.61717377e+01 -2.28825970e+01 -1.30575247e+01 -9.58068752e+00 -3.06747532e+00 -9.98523355e-01 -2.27727127e+00 2.14252687e+00 2.24723625e+00 -1.00521755e+00 -6.52708960e+00 -1.11130953e+01 -8.55661774e+00 -1.10461922e+01 -1.24191895e+01 -1.08293953e+01 -1.01217823e+01 -4.40664911e+00 -1.63069701e+00 -6.17243433e+00 -2.39465828e+01 -4.50768280e+01 -5.30493546e+01 -4.57376862e+01 -3.42793236e+01 -2.65136318e+01 -3.38906822e+01 -4.34266434e+01 -4.03360023e+01 -2.66501713e+01 -1.16088390e+01 -1.16852493e+01 -1.31455297e+01 -8.09906006e+00 6.44064903e+00 -3.83464170e+00 -2.13041458e+01 -3.90031281e+01 -3.54531708e+01 -2.60481720e+01 -2.55032845e+01 -2.14134064e+01 -1.90900173e+01 -1.60928192e+01 -1.95347633e+01 -2.46991100e+01 -3.29599991e+01 -3.45303688e+01 -3.44933472e+01 -2.86482124e+01 -2.94705086e+01 -3.90938148e+01 -5.11329079e+01 -4.76873703e+01 -3.77958488e+01 -2.85546741e+01 -3.15513687e+01 -3.71091614e+01 -4.34242210e+01 -4.63218880e+01 -3.80730515e+01 -2.49498901e+01 -2.37859077e+01 -2.68599033e+01 -3.83210373e+01 -3.49351578e+01 -3.40936852e+01 -2.77395649e+01 -2.50975666e+01 -2.75560036e+01 -2.76758881e+01 -2.87462330e+01 -2.62937069e+01 -2.86925793e+01 -2.87253704e+01 -2.86969395e+01 -3.25656052e+01 -3.94681587e+01 -3.94396057e+01 -3.30560303e+01 -2.42666187e+01 -2.22747459e+01 -2.10087509e+01 -2.31135292e+01 -2.20742188e+01 -2.06567135e+01 -1.96096401e+01 -2.72464733e+01 -3.73515816e+01 -3.94952698e+01 -3.50294724e+01 -2.77192516e+01 -2.43166351e+01 -2.18535995e+01 -2.17503452e+01 -2.49173870e+01 -2.63556843e+01 -2.50330620e+01 -2.62303791e+01 -2.66125946e+01 -2.74452896e+01 -2.66483498e+01 -2.73689270e+01 -2.76390209e+01 -2.88093605e+01 -2.85564938e+01 -2.89445534e+01 -2.86554852e+01 -2.91321220e+01 -2.93690968e+01 -2.97576122e+01 -2.95603142e+01 -2.94773159e+01 -2.83020782e+01 -2.79020863e+01 -2.74369812e+01 -2.79833145e+01 -2.76573277e+01 -2.74321976e+01 -2.69116440e+01 -2.78788948e+01 -3.07488937e+01 -3.21896095e+01 -3.21584091e+01 -3.10667572e+01 -3.00588989e+01 -2.96492233e+01 -2.91002331e+01 -2.88198948e+01 -2.90809288e+01 -2.89891186e+01 -2.89575653e+01 -2.87395096e+01 -2.87273026e+01 -2.86408653e+01 -2.86200275e+01 -2.89068947e+01 -2.93754005e+01 -2.96149101e+01 -2.93062744e+01 -2.87617931e+01 -2.78755836e+01 -2.80073128e+01 -2.81816807e+01 -2.87085209e+01 -2.86138611e+01 -2.87728729e+01 -2.83035412e+01 -2.85752392e+01 -2.87120419e+01 -2.86480312e+01 -2.81332150e+01 -2.81607456e+01 -2.84405937e+01 -2.86113243e+01 -2.75402317e+01 -2.69812870e+01 -2.66667023e+01 -2.67282562e+01 -2.71776676e+01 -3.04860287e+01 -3.45401382e+01 -3.73603859e+01 -3.74589157e+01 -3.71875763e+01 -3.80500755e+01 -3.48174515e+01 -2.98454819e+01 -2.47279320e+01 -2.35545444e+01 -2.46706867e+01 -2.63713303e+01 -2.68484478e+01 -2.55803833e+01 -2.30041485e+01 -2.42102184e+01 -2.53588486e+01 -2.72291985e+01 -2.67237911e+01 -2.57809353e+01 -2.04216347e+01 -1.34424810e+01 -1.59172983e+01 -2.10354137e+01 -2.84168835e+01 -3.11283836e+01 -3.44024963e+01 -4.11620216e+01 -4.64991226e+01 -4.52633362e+01 -3.99485855e+01 -3.08359051e+01 -3.40135384e+01 -3.67134323e+01 -3.81976547e+01 -3.62690659e+01 -3.36493874e+01 -3.63514214e+01 -3.75633774e+01 -3.78986893e+01 -3.49078407e+01 -3.08446617e+01 -3.12454472e+01 -3.74635086e+01 -4.83462029e+01 -5.72872124e+01 -6.24539032e+01 -4.44182968e+01 -2.57923698e+01 -1.40162659e+01 -2.03915310e+01 -3.04543953e+01 -2.94091396e+01 -3.41056442e+01 -3.05445976e+01 -2.97917728e+01 -2.58631496e+01 -2.51979198e+01 -2.57929554e+01 -2.65786705e+01 -2.73637962e+01 -1.66465855e+01 -3.40281725e+00 5.28050840e-01 -8.63617325e+00 -1.78777409e+01 -2.63103046e+01 -3.41276093e+01 -3.71656075e+01 -3.08019543e+01 -2.85401573e+01 -3.37545738e+01 -3.45748634e+01 -2.72714710e+01 -1.90213966e+01 -1.75926170e+01 -1.76036034e+01 -1.82201385e+01 -2.10900917e+01 -2.27722454e+01 -2.69942341e+01 -2.34302025e+01 -2.03199024e+01 -1.43526545e+01 -1.34401388e+01 -1.61029987e+01 -3.10803204e+01 -5.01316605e+01 -4.72488480e+01 -3.26947594e+01 -1.59368439e+01 -2.37684746e+01 -2.72158451e+01 -3.00980282e+01 -2.98753300e+01 -3.41385269e+01 -3.50129128e+01 -4.63802185e+01 -5.30176353e+01 -5.17754593e+01 -3.34620361e+01 -1.65919838e+01 -1.69618988e+01 -2.02937412e+01 -1.22251501e+01 5.33187246e+00 8.92411804e+00 3.57975698e+00 -1.10477972e+01 -8.12567043e+00 -7.82319450e+00 -9.89733028e+00 -1.29869604e+01 -1.70633698e+01 -1.39028883e+01 -1.04682245e+01 -1.23541498e+01 -1.54938259e+01 -1.36979532e+01 -9.75535393e+00 -1.01916695e+01 -1.49923897e+01 -3.14939079e+01 -4.83686256e+01 -4.61201820e+01 -3.54588203e+01 -2.43922901e+01 -2.85456791e+01 -2.36795540e+01 -1.24032345e+01 -1.30035229e+01 -3.71047440e+01 -6.00655899e+01 -6.29958344e+01 -4.18542480e+01 -2.64762955e+01 -2.76552277e+01 -3.11488552e+01 -3.07450848e+01 -2.85482597e+01 -4.32447472e+01 -6.77731781e+01 -6.94842148e+01 -5.22807770e+01 -2.08319626e+01 -2.48713989e+01 -2.62472172e+01 -3.24374924e+01 -2.67729263e+01 -2.68503017e+01 -3.27172813e+01 -4.14429550e+01 -4.56450500e+01 -3.91118164e+01 -3.55108147e+01 -3.48214417e+01 -5.87529678e+01 -9.00017395e+01 -9.58664169e+01 -7.16691208e+01 -3.94663010e+01 -3.10872421e+01 -2.50011387e+01 -2.82958469e+01 -3.74279289e+01 -6.80560303e+01 -8.95594406e+01 -1.13414490e+02 -1.16257011e+02 -8.85339966e+01 -6.57532272e+01 -3.20846367e+01 -5.48376541e+01 -7.19036560e+01 -5.10951805e+01 -1.08860326e+00 2.58081722e+01 5.01832914e+00 -2.46008663e+01 -2.10336189e+01 -2.05597229e+01 -1.52757473e+01 -1.33705807e+01 -8.48812962e+00 -7.47426891e+00 -5.20742083e+00 -6.72032759e-02 -2.45404029e+00 -3.29902148e+00 -4.08438110e+00 -1.23759592e+00 -3.80647612e+00 -2.00035095e+01 -4.42128983e+01 -4.22944183e+01 -1.90450401e+01 1.19691210e+01 -1.25241070e+01 -4.91262321e+01 -2.68169708e+01 3.18327808e+01 3.84955978e+01 -2.96012764e+01 -7.78997879e+01 -5.83539391e+01 -2.39909554e+01 -4.19349060e+01 -7.45455246e+01 -8.00701675e+01 -6.33442268e+01 -3.67304916e+01 -3.70905876e+01 -4.14056320e+01 -3.09881840e+01 -3.01906300e+01 -2.90175486e+00 1.63443775e+01 -1.75500660e+01 -7.04276810e+01 -1.01506058e+02 -7.80751877e+01 -5.49571037e+01 -7.60883942e+01 -9.34962463e+01 -1.00944016e+02 -8.22169952e+01 -4.98577881e+01 -4.82788467e+01 -4.92403374e+01 -6.06901054e+01 -4.97251320e+01 -6.37711067e+01 -8.73314362e+01 -9.74301224e+01 -9.00335464e+01 -5.28757210e+01 -3.05374413e+01 -1.42201328e+01 -1.60480194e+01 -2.54523277e+01 2.17282906e+01 7.45764465e+01 6.61534653e+01 -2.23001194e+00 -5.39441261e+01 -4.16915550e+01 -1.51756363e+01 -4.06450119e+01 -8.03653030e+01 -8.29188156e+01 -5.80224304e+01 -1.83721161e+01 -1.10418835e+01 -1.24107475e+01 -1.59979143e+01 -2.28114090e+01 -1.85886002e+01 -2.81314621e+01 -4.35556946e+01 -5.37166862e+01 -4.17494545e+01 -2.40028992e+01 -1.47112026e+01 -7.59865379e+00 -9.60715103e+00 2.38811474e+01 5.26315193e+01 2.59711647e+01 -5.03310928e+01 -8.73866806e+01 -5.15678177e+01 -3.12350988e+00 2.56020298e+01 3.93596573e+01 3.91721191e+01 3.01465912e+01 1.58598433e+01 2.06639900e+01 8.44731045e+00 1.43263607e+01 1.72764988e+01 2.79783325e+01 3.86340599e+01 4.07128296e+01 2.13084545e+01 -2.98489809e-01 3.84067273e+00 2.82812099e+01 4.13580360e+01 1.79275532e+01 -3.65919948e+00 -1.70618782e+01 -3.60620728e+01 -7.63605194e+01 -7.80378647e+01 -6.00140762e+01 -4.81870537e+01 -1.14922798e+02 -1.60207367e+02 -1.29743790e+02 -7.40793762e+01 -8.07121658e+01 -1.27972130e+02 -1.41160370e+02 -1.00026833e+02 -6.12243385e+01 -5.39131851e+01 -5.40646782e+01 -6.68583374e+01 -7.24113083e+01 -7.17487640e+01 -5.41279564e+01 -6.88225861e+01 -1.09612961e+02 -1.26543060e+02 -1.03764137e+02 -5.74833031e+01 -6.39516678e+01 -9.31416473e+01 -6.08267670e+01 -4.62869167e+00 3.30920486e+01 9.36844921e+00 -1.43283558e+01 -3.51195312e+00 -2.84931469e+00 -5.95336533e+00 -8.15755558e+00 -1.83316588e+00 -6.63242292e+00 -1.41135941e+01 -6.69553661e+00 2.99657893e+00 1.22903795e+01 8.01241779e+00 -4.63165426e+00 -7.61423886e-01 -3.84400139e+01 -6.46474152e+01 -6.40965271e+01 -1.92144775e+01 2.43595104e+01 3.30689468e+01 2.91573296e+01 5.64675522e+01 9.48220062e+01 9.91906738e+01 7.47806015e+01 3.81904068e+01 3.00014668e+01 2.13820229e+01 -3.05698338e+01 -8.26849670e+01 -9.77857361e+01 -6.42566605e+01 -2.81318951e+01 -2.46750698e+01 -1.26836395e+01 -4.38595533e+00 -1.61994858e+01 5.03411531e+00 4.84359283e+01 3.71259613e+01 -1.52818899e+01 -5.74498901e+01 -3.13021030e+01 -3.40224266e+01 -1.06628014e+02 -1.56954803e+02 -1.40392624e+02 -6.05416451e+01 -3.73224602e+01 -6.43457947e+01 -7.54733429e+01 -4.90789452e+01 7.57913685e+00 -4.36387599e-01 -3.12976665e+01 -4.89134331e+01 -3.11085854e+01 9.13961983e+00 3.33480148e+01 4.88429565e+01 4.97369156e+01 3.31782761e+01 3.38966484e+01 4.40500221e+01 1.21456947e+01 -2.33327446e+01 -4.51784897e+01 -1.47156410e+01 1.60725422e+01 8.64035988e+00 -2.47168369e+01 1.69585919e+00 1.67263199e+02 2.89870941e+02 4.87984375e+02 4.68632599e+02 3.16217651e+03 5.05980615e+03 -4.56781738e+03 -2.52883276e+03 2.64771094e+03 1.06806628e+03 3.01941162e+03 3.11157012e+04 -5.13050293e+03 3.77181978e+09 1.39022500e+05 1583832192. 2.60913623e+10 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. -5.72994478e+10 5.50336289e+04 1.51437617e+04 1.63462268e+03 1.01430029e+03 3.55508838e+03 1.98860083e+03 -2.87865295e+02 2.16272369e+02 3.48247711e+02 8.60936646e+02 7.70141968e+02 5.44504578e+02 2.12840637e+02 1.48561768e+02 2.51886826e+02 2.93618225e+02 5.25230591e+02 6.63090820e+02 4.22833527e+02 1.06030182e+02 -2.95019760e+01 -7.39602890e+01 -4.91843948e+01 -6.64561920e+01 -1.37942581e+02 -1.33263992e+02 -8.29400330e+01 -2.88375702e+01 -8.13648987e+01 -1.97414566e+02 -2.17675278e+02 -1.29417023e+02 -3.06278439e+01 1.35224581e+01 2.71692824e+00 3.06866112e+01 7.56901627e+01 9.94819489e+01 3.58888168e+01 -1.29467499e+02 -2.16423691e+02 -1.71062531e+02 -5.52673683e+01 1.68818264e+01 1.38567228e+01 -1.65413647e+01 -6.49083939e+01 -3.63009911e+01 -5.64706001e+01 -7.04951096e+01 -5.90552216e+01 3.51564102e+01 1.41500229e+02 1.29434753e+02 -1.76721630e+01 -9.93834229e+01 -6.61022186e+01 2.49302044e+01 1.70117474e+01 -5.65635071e+01 -6.12434082e+01 1.45320864e+01 9.63139420e+01 7.31783600e+01 -5.48404541e+01 -1.37713074e+02 -1.03135841e+02 -3.11275883e+01 -1.37283440e+01 -3.97905312e+01 -3.44252510e+01 2.27434654e+01 7.63748856e+01 5.03855400e+01 1.51759710e+01 2.83203831e+01 7.71707458e+01 9.21344833e+01 7.07272873e+01 2.14641781e+01 -2.77854195e+01 -4.62825737e+01 -1.33509245e+01 1.45724907e+01 1.61226501e+01 6.19221878e+01 1.44849426e+02 1.72418930e+02 9.15539703e+01 -4.61676750e+01 -1.13732475e+02 -6.95990524e+01 3.63627930e+01 1.43272263e+02 1.78727448e+02 1.50456680e+02 1.18440117e+02 1.27803986e+02 9.89961700e+01 2.44187951e+00 -6.73486557e+01 -3.68539085e+01 3.84289398e+01 6.63579178e+01 3.57078323e+01 -2.47020721e+01 -4.00425072e+01 2.88992119e+00 3.93827820e+01 2.66374378e+01 1.64350700e+01 6.51011353e+01 1.54849075e+02 1.66446930e+02 9.53865891e+01 1.81741199e+01 1.91214275e+01 7.10577316e+01 1.22372536e+02 1.22563751e+02 8.01607513e+01 1.74445553e+01 -4.59199953e+00 2.20094852e+01 2.56899204e+01 -1.63159161e+01 -2.85275288e+01 2.09282513e+01 8.50316010e+01 8.37590103e+01 2.42388039e+01 -1.43092566e+01 3.06113205e+01 5.87101593e+01 7.00791321e+01 3.36550064e+01 5.43785400e+01 1.10130714e+02 1.22735893e+02 5.73950882e+01 -6.96108704e+01 -1.30504303e+02 -7.81687088e+01 -4.78701973e+00 2.54067345e+01 2.00330183e-01 -2.42350426e+01 -1.70504360e+01 -1.91464558e+01 -5.31948929e+01 -1.00754997e+02 -1.20799583e+02 -5.98746834e+01 4.89457550e+01 1.04864281e+02 4.56959114e+01 -2.43767910e+01 -2.28258495e+01 1.36030474e+01 -1.72629890e+01 -9.90202332e+01 -8.79552536e+01 -1.14889288e+01 6.20358505e+01 4.48244667e+00 -1.16812073e+02 -1.81198654e+02 -1.36228378e+02 -5.22737198e+01 -8.65168190e+00 -1.27950096e+01 9.33541870e+00 2.45496006e+01 4.64743376e+00 -6.18323288e+01 -1.35304489e+02 -9.26350861e+01 -2.14781799e+01 5.07099075e+01 3.90747414e+01 1.63109398e+00 -4.69359436e+01 -7.22699432e+01 -7.56412430e+01 -8.66328354e+01 -1.21931030e+02 -9.33730011e+01 -2.24284172e+01 4.95443878e+01 2.30485744e+01 -4.99963150e+01 -1.05141571e+02 -7.53310852e+01 -1.99953823e+01 7.83455324e+00 -1.75995815e+00 2.14090309e+01 8.23439484e+01 1.07667465e+02 4.81992455e+01 -4.85724907e+01 -6.47199554e+01 -3.62982254e+01 4.27883415e+01 5.25883636e+01 5.15965424e+01 2.20024185e+01 2.41723537e+00 1.46938846e-01 -2.46943073e+01 -5.26582451e+01 -2.93475437e+01 1.85500164e+01 4.76678352e+01 4.29831123e+01 5.77118063e+00 -1.19712868e+01 -5.60341740e+00 6.72366381e-01 6.01923752e+00 -1.35896215e+01 1.71401272e+01 5.71404877e+01 7.56424484e+01 7.66993713e+01 1.25978451e+01 -2.24437256e+01 -2.35250497e+00 5.82955894e+01 6.84747238e+01 2.74360237e+01 -1.26961565e+01 -2.22425246e+00 2.47196579e+01 2.15353603e+01 -1.27912474e+01 -2.36638966e+01 1.68015156e+01 4.43590431e+01 2.61242256e+01 2.38860488e+00 2.68089695e+01 3.57264977e+01 1.46566114e+01 -7.33741426e+00 -2.49191055e+01 -3.63640404e+00 -2.28164272e+01 -2.79969158e+01 -2.61429195e+01 -4.08470306e+01 -6.02089691e+01 -7.51546936e+01 -2.15390701e+01 1.32903230e+00 5.29266739e+00 -3.34202118e+01 -1.97472935e+01 -1.25987701e+01 -2.73149567e+01 -5.64569588e+01 -6.88037491e+01 -1.50449295e+01 1.91636791e+01 3.06177540e+01 -1.27720270e+01 -2.46284485e+01 -2.36963177e+01 -8.29984093e+00 -5.40431595e+00 -3.79069824e+01 -2.53858566e+01 -8.04485321e+00 3.69291916e+01 5.15071678e+01 4.06044083e+01 4.56285238e+00 -2.31036549e+01 -1.24285720e-01 3.08695278e+01 4.41774940e+01 2.66407413e+01 4.45389252e+01 4.60981369e+01 2.09362259e+01 -1.79339981e+01 -1.64134579e+01 3.01561012e+01 4.80418129e+01 2.43142624e+01 -1.60404739e+01 -5.65053940e+00 1.76295433e+01 2.79163685e+01 1.87661304e+01 -2.64199090e+00 -8.73721027e+00 -1.58055897e+01 9.74373913e+00 3.03821316e+01 3.36557426e+01 9.09509182e+00 -4.40719366e+00 8.17683983e+00 2.79066753e+01 3.26562424e+01 4.19876938e+01 7.23805084e+01 8.84167709e+01 8.38289108e+01 7.56969452e+01 7.65143051e+01 9.25594864e+01 9.27792053e+01 7.74345322e+01 4.05133133e+01 2.60057087e+01 2.04736843e+01 2.69399719e+01 2.18442459e+01 4.18549681e+00 -9.74545002e+00 -1.66015301e+01 7.98791075e+00 2.00012131e+01 2.54583588e+01 1.69385223e+01 2.53227997e+01 3.32065544e+01 4.28087692e+01 3.68161430e+01 3.85081596e+01 5.42812996e+01 6.37256699e+01 5.40578346e+01 3.25390739e+01 2.99589252e+01 3.13850307e+01 9.16833687e+00 -7.62731600e+00 -1.97709503e+01 2.62008691e+00 5.66342974e+00 1.37683363e+01 2.72102222e+01 2.90542393e+01 1.43911304e+01 -1.44736691e+01 -2.14730759e+01 2.60404444e+00 2.19003868e+01 1.92551346e+01 7.93121576e-01 -1.35660553e+01 -2.51069570e+00 1.24754810e+01 2.90633202e+01 2.56922779e+01 1.08615675e+01 -2.67496109e+00 -1.88787670e+01 -1.92242985e+01 -1.89220676e+01 -2.21142941e+01 -2.24521236e+01 -2.21176949e+01 -7.35506654e-01 1.10226715e+00 2.43986964e+00 9.64942276e-01 -1.78875268e+00 -1.14795914e+01 -4.01906853e+01 -4.42405548e+01 -2.65864944e+01 8.96145535e+00 2.65600700e+01 6.58824158e+00 -1.74339466e+01 -2.05535164e+01 7.25260448e+00 3.37431297e+01 2.65161610e+01 1.74356031e+00 -1.32839956e+01 -1.12960091e+01 3.39934039e+00 2.26006079e+00 -7.14614296e+00 -1.52821989e+01 -1.61359482e+01 -2.54233813e+00 -1.25122321e+00 -7.12766552e+00 -1.34555178e+01 -1.36334124e+01 -6.09318924e+00 -8.42350006e+00 -8.18115139e+00 2.18964410e+00 1.49055481e+01 1.31421938e+01 -7.05297089e+00 -2.01775093e+01 -1.51739483e+01 -2.34810412e-01 7.33468485e+00 5.15714073e+00 -2.76838279e+00 -6.12354088e+00 -7.87761450e+00 -1.65581477e+00 -1.81186914e+00 -2.40573454e+00 -4.87143278e+00 -5.79687262e+00 -1.85948002e+00 1.38383746e+00 6.15090513e+00 6.10306072e+00 3.37203526e+00 -6.73282802e-01 -5.79963398e+00 -6.97509623e+00 -3.29753280e+00 3.25202346e+00 6.07386017e+00 3.12827611e+00 -1.98113692e+00 -3.03112364e+00 8.57274607e-03 2.99201465e+00 2.40561843e+00 3.39814097e-01 -3.82521033e-01 -1.93289861e-01 -2.13131565e-03 -8.10442790e-02 1.32928938e-01 8.23659480e-01 1.87303674e+00 2.25302577e+00 3.40734434e+00 3.65422988e+00 2.48093629e+00 -4.84859973e-01 -1.77953231e+00 9.16428566e-01 4.16468573e+00 3.40811944e+00 -2.07121158e+00 -7.16350937e+00 -5.75364971e+00 3.68189633e-01 2.93000603e+00 5.22286117e-01 -5.29291821e+00 -4.66883373e+00 9.56806600e-01 6.84898281e+00 1.13435249e+01 6.64457989e+00 7.27764177e+00 4.28587866e+00 5.08960915e+00 6.21655798e+00 8.35478687e+00 1.42253571e+01 9.12864685e+00 1.73059809e+00 -7.93841982e+00 -2.66311383e+00 1.05541306e+01 2.11587658e+01 1.25618687e+01 -3.49676037e+00 -1.44254274e+01 -1.35531397e+01 -1.21106517e+00 3.65211368e+00 7.11517811e+00 8.85725677e-01 4.06627512e+00 1.09583712e+01 1.95945892e+01 2.93937721e+01 2.59251575e+01 1.12986670e+01 -3.04003000e+00 -5.53995800e+00 -8.66882354e-02 7.66769791e+00 1.97383461e+01 2.72510300e+01 1.28290682e+01 -1.36291208e+01 -2.66331844e+01 -8.53146648e+00 1.63177509e+01 1.67534790e+01 -1.17203245e+01 -4.21680603e+01 -3.54672318e+01 -1.02257156e+00 3.26730843e+01 4.44112930e+01 2.40097218e+01 6.43504715e+00 5.14739323e+00 1.43322449e+01 2.20250130e+01 9.11700153e+00 1.17689514e+01 7.71399784e+00 -2.61228609e+00 -9.28976154e+00 -8.77791786e+00 1.02542744e+01 8.87129498e+00 -1.41617956e+01 -4.16119843e+01 -3.78881264e+01 5.39958048e+00 4.00674324e+01 2.98615284e+01 -9.82565308e+00 -3.90180244e+01 -3.85926018e+01 -3.63459897e+00 2.95210915e+01 4.39559059e+01 1.81305275e+01 -8.38215351e-02 -1.69305420e+01 -1.86969872e+01 -1.29991312e+01 -1.43648920e+01 -1.26701422e+01 -3.71301804e+01 -5.10621948e+01 -4.99582329e+01 -3.11760540e+01 6.18805885e+00 1.63187733e+01 -4.05758095e+00 -4.16951714e+01 -5.10521393e+01 -2.98198013e+01 4.35868645e+00 3.08557773e+00 -2.10258236e+01 -5.74024124e+01 -6.26044884e+01 -2.46580906e+01 1.59393282e+01 3.18845673e+01 -2.54477549e+00 -3.60070953e+01 -3.45966263e+01 -8.58469009e+00 2.07913551e+01 2.37549686e+01 2.10699978e+01 6.85890293e+00 -1.86798229e+01 -2.42162971e+01 -6.30172312e-01 4.75468674e+01 6.94779282e+01 3.88236732e+01 -1.14576888e+00 -3.09186993e+01 -1.23024826e+01 1.81284561e+01 3.86065483e+01 3.25243607e+01 7.89813137e+00 3.35125685e+00 2.05247707e+01 4.56005363e+01 5.26198311e+01 1.77768612e+01 -1.24766521e+01 -6.45504236e+00 1.84386311e+01 5.92676010e+01 5.47558556e+01 5.33994293e+01 3.72912521e+01 1.40373449e+01 1.47177947e+00 -3.21159148e+00 3.45290337e+01 6.00796356e+01 4.14991798e+01 7.86917543e+00 -2.18326435e+01 5.53666258e+00 4.32035217e+01 6.10922775e+01 2.22466812e+01 -6.01519890e+01 -9.18540115e+01 -5.14144707e+01 4.45860710e+01 9.07499695e+01 5.55210342e+01 -1.36312351e+01 -4.20399551e+01 -7.12135773e+01 -1.30894730e+02 -7.77431641e+01 1.35091782e+02 1.45229660e+02 -1.12947762e+02 -1.94889172e+03 -2.51649829e+03 -4.26926318e+03 -1.00683184e+04 -1.13229046e+10 2.03060879e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -914026496. -423721024. -2.42461992e+04 -8.56551270e+03 -7.65737183e+02 -1.05972061e+02 -4.78749573e+02 -1.83614365e+02 -5.92792091e+01 -3.79746753e+03 -2.48620337e+03 -4.81401855e+02 -3.43190216e+02 1.52889160e+03 -1.51519947e+01 -1.40126636e+03 1.50766937e+02 -3.82153625e+01 -2.51107559e+02 -2.54993118e+02 -1.70555649e+02 -1.80084641e+02 -1.31495224e+02 -6.58641052e+01 -1.28486452e+01 -7.57472515e+00 -3.03670177e+01 1.22134724e+01 2.97773113e+01 -3.01886158e+01 -8.11158295e+01 -3.61602631e+01 8.67799606e+01 1.56104553e+02 7.63752060e+01 -2.19500504e+01 -8.11751556e+01 -4.60826149e+01 6.09207726e+01 1.48585983e+02 1.81503464e+02 9.79811096e+01 3.29730072e+01 2.62659702e+01 8.97229004e+01 1.28127121e+02 9.14812927e+01 7.79124451e+01 4.11615562e+01 2.14571095e+00 -1.77872810e+01 2.31494102e+01 1.37864471e+02 1.51027084e+02 5.26981430e+01 -6.69962082e+01 -9.81090088e+01 1.98893398e-01 9.51117783e+01 9.14306259e+01 1.89912319e+01 -1.44709082e+01 6.43337555e+01 1.71151367e+02 1.99711258e+02 1.46603882e+02 2.92608967e+01 -5.19219780e+01 -4.69134789e+01 2.75113010e+01 1.25118828e+02 1.89256882e+02 2.20881226e+02 1.97786301e+02 1.32598938e+02 7.14122162e+01 4.07100525e+01 7.00959396e+01 5.63226738e+01 -1.73595695e+01 -9.15533142e+01 -8.82624207e+01 2.76756620e+00 7.83022156e+01 5.85789566e+01 1.47951899e+01 -5.49935570e+01 -9.05596390e+01 -5.13064499e+01 4.64694786e+01 1.03320824e+02 4.72181473e+01 -2.37978668e+01 -1.08602924e+01 1.84561253e+01 3.64905815e+01 6.52284384e+00 3.72575874e+01 3.17422104e+01 -5.21931553e+00 -3.24301453e+01 -1.05022001e+00 1.08528503e+02 1.25836800e+02 1.81271744e+01 -1.19472267e+02 -1.79614059e+02 -8.55999908e+01 1.56488285e+01 6.04286003e+01 3.55346756e+01 -1.57143521e+00 -1.11757827e+00 2.91277466e+01 9.14212570e+01 1.22606400e+02 5.93466644e+01 -5.52187576e+01 -8.80358124e+01 -4.19531898e+01 2.39438033e+00 6.51071644e+00 4.47706299e+01 3.71157722e+01 -4.68041801e+01 -1.54389359e+02 -1.43347855e+02 -7.67769480e+00 5.92002640e+01 -2.26231117e+01 -1.38541656e+02 -1.59762100e+02 -4.81134033e+01 6.28623886e+01 8.96797104e+01 5.08428001e+01 -4.00993843e+01 -1.11595192e+02 -9.19999924e+01 4.83353615e+00 8.01182175e+01 2.11006126e+01 -8.09306335e+01 -1.18143089e+02 -8.75263138e+01 -3.76033745e+01 -4.81078100e+00 5.92532730e+01 8.65772629e+01 5.54466553e+01 4.47075367e+00 -8.74716568e+00 6.55251007e+01 9.98273163e+01 3.91358337e+01 -1.03347527e+02 -1.98605896e+02 -1.59112961e+02 -2.50963707e+01 7.85343323e+01 6.87267685e+01 -8.81656766e-01 -2.90184708e+01 -2.69764066e+00 1.09384527e+01 5.53218269e+01 3.51454315e+01 2.40404243e+01 -2.66163216e+01 -9.01433258e+01 -1.28437820e+02 -1.43033340e+02 -5.58847389e+01 -1.24099360e+01 -6.65119171e+01 -1.26452316e+02 -9.36478195e+01 3.13980675e+01 9.88473053e+01 4.92907867e+01 -5.01804304e+00 -4.98527031e+01 -4.15532150e+01 -8.02084732e+00 1.35800142e+01 2.29003353e+01 -4.80522804e+01 -3.88178368e+01 6.63215351e+00 7.77178650e+01 1.55762863e+02 1.97073853e+02 2.39349442e+02 1.62691101e+02 4.00371437e+01 -2.41342754e+01 -2.63736210e+01 4.66479950e+01 4.69027634e+01 -1.61707191e+01 -1.04549286e+02 -1.51196838e+02 -4.39729385e+01 9.12808151e+01 1.71073532e+02 1.33305679e+02 6.84425049e+01 4.42011948e+01 5.08456993e+01 7.32036362e+01 1.08542183e+02 7.37444229e+01 1.20798626e+01 -3.60289497e+01 8.16837025e+00 3.00519791e+01 5.01723671e+01 8.06228561e+01 9.81480179e+01 6.30584679e+01 2.36357136e+01 2.71516533e+01 3.05174675e+01 -9.06958580e+00 -7.13600769e+01 -1.11718842e+02 -1.17186058e+02 -5.04270821e+01 -7.35452652e+00 7.00916214e+01 7.56939240e+01 2.76591377e+01 -5.38339958e+01 -7.08961868e+01 -1.46990919e+01 2.28292274e+01 1.45716057e+01 7.04327917e+00 8.38721275e+00 -3.78709555e+00 -8.09879017e+00 -7.70603371e+00 3.12314415e+00 4.60814762e+00 -7.10834980e+00 -1.83041840e+01 -3.99020538e+01 -3.72108688e+01 -3.23546410e+01 -8.07412815e+00 -2.36198082e+01 -3.49303474e+01 -3.13590164e+01 -6.59160328e+00 3.17054119e+01 5.16965218e+01 4.26609192e+01 2.77937622e+01 -4.69165277e+00 8.59826946e+00 5.38821888e+00 6.40935421e+00 -1.46966591e+01 -1.75637321e+01 -1.31534567e+01 2.05551219e+00 -1.31275425e+01 -1.53169937e+01 -2.19557781e+01 -1.19535666e+01 -2.48476906e+01 -2.65364380e+01 -4.07884598e+01 -5.03727264e+01 -4.93547592e+01 -3.13794689e+01 -9.54046249e+00 -9.12117672e+00 -1.88501530e+01 -3.98220329e+01 -3.46801567e+01 -2.84578362e+01 -1.99232602e+00 1.00922232e+01 -8.95421410e+00 -2.39019413e+01 -2.16571083e+01 5.16840172e+00 6.63461018e+00 -3.99745345e+00 4.50980949e+00 5.93599224e+00 -8.78390789e+00 -2.38183689e+01 -1.02636604e+01 4.56347287e-01 -1.77887421e+01 -1.52780371e+01 6.67804050e+00 3.67333221e+01 2.70719242e+01 2.20785351e+01 2.20717258e+01 2.17403431e+01 2.71267014e+01 2.45592270e+01 2.78088856e+01 9.23965359e+00 7.02828121e+00 1.67441578e+01 1.34384289e+01 4.34698963e+00 -9.85356331e+00 -2.36483741e+00 -2.85795536e+01 -5.72208290e+01 -4.84962540e+01 -2.39291515e+01 8.04517460e+00 6.73611546e+00 5.58692312e+00 2.01202226e+00 -9.06771660e+00 5.96288157e+00 1.34014959e+01 2.12525616e+01 1.72033024e+01 3.29593010e+01 3.33067780e+01 1.44864111e+01 5.25943089e+00 2.76667571e+00 6.35255241e+00 -1.95097208e+00 4.31374502e+00 1.80002308e+01 1.92707500e+01 3.26660042e+01 3.19942837e+01 2.31437092e+01 2.92539167e+00 -1.54169817e+01 -9.98253822e+00 -2.40316010e+00 1.64574490e+01 2.38434887e+01 2.33652544e+00 -1.06500778e+01 -6.20776606e+00 1.51978207e+01 2.15706177e+01 1.15469017e+01 -5.41258216e-01 -1.07271290e+01 -1.27194273e+00 -3.51860595e+00 -9.12244034e+00 -3.68229027e+01 -3.08844299e+01 -2.38738823e+01 -2.25064063e+00 -5.54180861e+00 -6.70843554e+00 -8.75168610e+00 7.29180861e+00 -3.21757603e+00 -1.51738520e+01 -2.73339863e+01 -1.51363182e+01 -4.62361783e-01 -3.99664354e+00 -2.99647808e+01 -6.76520004e+01 -5.92094536e+01 -2.96245346e+01 9.76475716e+00 -1.61744308e+01 -4.39059639e+01 -5.44369202e+01 -3.24411736e+01 -5.39232302e+00 -1.14068899e+01 -3.35935898e+01 -4.68345337e+01 -4.66532860e+01 -3.68690414e+01 -4.46191483e+01 -6.13080978e+01 -6.71585312e+01 -4.64142838e+01 -1.55203514e+01 -5.10344744e+00 -2.04088020e+01 -2.90786896e+01 -1.79155903e+01 -2.99661851e+00 -8.51615191e-01 -3.54529495e+01 -6.22733421e+01 -6.17343483e+01 -3.16095963e+01 2.34104171e-02 6.29391015e-01 -9.75947762e+00 -5.97218657e+00 1.85605793e+01 5.79969482e+01 5.44077873e+01 2.45723228e+01 -5.75448847e+00 -1.15294209e+01 -1.36485682e+01 -3.61975784e+01 -4.63167496e+01 9.38578904e-01 5.38725166e+01 6.15268440e+01 1.96495018e+01 -1.82438908e+01 -1.26437359e+01 -6.46934700e+00 1.85980072e+01 3.63502922e+01 2.90121784e+01 2.00901294e+00 -2.92333813e+01 -2.82754402e+01 -3.67310410e+01 -4.38706160e-01 4.19606171e+01 5.17419243e+01 2.65053921e+01 -1.27379303e+01 -4.00541344e+01 -5.90096245e+01 -6.33229980e+01 -3.22522659e+01 -1.56102791e+01 -9.89716232e-01 2.04076603e-01 -4.76110764e-02 9.40755653e+00 1.17587719e+01 1.04764452e+01 9.26726246e+00 1.32657373e+00 -3.97754021e+01 -1.48105316e+02 -2.55180847e+02 -2.45441055e+02 -2.36387451e+02 -1.99542374e+02 -3.70441956e+02 -1.81709183e+02 -1.98053932e+01 5.21529968e+02 -2.30579834e+03 -5.16046082e+02 -3.38795361e+03 -4.38676406e+04 -3.41135488e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.94549770e+10 -8.94549770e+10 993453312. -2.62259121e+04 -7.58207861e+03 -8.43289551e+02 -6.01180359e+02 -1.24290596e+02 -6.72395325e+01 -4.55873833e+01 -4.31550789e+01 2.15570068e+01 9.25956573e+01 1.32547241e+02 9.83896713e+01 5.51155510e+01 6.67156754e+01 6.20307884e+01 -2.79882715e+03 -1.93659424e+03 -4.39669647e+02 -1.80518265e+02 -1.18119827e+02 -9.30019379e+01 -7.90624008e+01 -5.88001366e+01 -2.09264107e+01 -1.27560625e+01 -5.85960925e-01 -7.29495287e-01 9.83876133e+00 1.15975895e+01 1.95492439e+01 2.27134304e+01 2.45490780e+01 2.59365082e+01 2.15039597e+01 2.27302685e+01 2.51005440e+01 3.12651329e+01 3.78715477e+01 3.12726574e+01 2.10609989e+01 1.66288414e+01 1.81045513e+01 2.34333439e+01 2.67146759e+01 3.08067989e+01 2.63360882e+01 7.85191298e+00 -1.12138262e+01 -1.32446728e+01 -4.75160074e+00 3.05240130e+00 5.03862667e+00 1.21158571e+01 1.22876472e+01 7.70191765e+00 5.28543043e+00 8.33219433e+00 1.24348402e+01 1.46846008e+01 2.47513123e+01 1.57833834e+01 6.66859245e+00 -2.83579707e+00 -6.91611338e+00 -1.16567688e+01 -1.50067625e+01 -8.17704201e+00 -2.55953622e+00 -1.86919928e+00 2.75970221e+00 1.56078997e+01 1.97765007e+01 1.58051939e+01 5.36146116e+00 1.60405433e+00 1.33609235e+00 -9.11890984e+00 -2.20354958e+01 -2.06665649e+01 -1.35741510e+01 -5.53002834e+00 -2.28725128e+01 -3.64660454e+01 -3.56537590e+01 -2.33744106e+01 -1.46761894e+01 -1.74343987e+01 -1.91038647e+01 -1.59291162e+01 -1.69376907e+01 -2.39158306e+01 -3.20534668e+01 -2.83287239e+01 -1.34362078e+01 -7.85399556e-01 4.80570126e+00 1.78697622e+00 -1.28552806e+00 -5.76579905e+00 1.41141212e+00 9.76297855e+00 5.30094624e+00 -5.19782543e+00 -8.84960747e+00 -3.77733678e-01 5.85004711e+00 -6.35000372e+00 -1.45678587e+01 -1.40015316e+01 -1.16616797e+00 9.88150692e+00 1.17923937e+01 9.82609272e+00 6.52386284e+00 4.88211584e+00 2.71237111e+00 1.53364885e+00 3.07448649e+00 2.79803085e+00 2.08621129e-01 -2.47298551e+00 -9.68973875e-01 9.04963017e-01 1.69677055e+00 1.03925860e+00 7.29083598e-01 -6.56776476e+00 -1.36421967e+01 -1.25292072e+01 -5.39549351e+00 1.02575076e+00 -5.57095051e+00 -1.15282488e+01 -1.19097252e+01 -6.88542271e+00 -2.46312189e+00 -2.10805154e+00 -1.45854282e+00 5.32963812e-01 -8.02410364e-01 -1.25066614e+00 -1.69138932e+00 6.27952814e-01 2.45802116e+00 1.62501061e+00 1.56990796e-01 -1.01144552e+00 -7.14374006e-01 -5.19383907e-01 -9.06584501e-01 -2.32682610e+00 -5.50520325e+00 -8.91196537e+00 -8.31752682e+00 -5.66397524e+00 -2.11013293e+00 -4.18934822e+00 -6.33986521e+00 -6.06992435e+00 -2.55431342e+00 -3.24022658e-02 -3.93518180e-01 -1.02952778e+00 -1.34055114e+00 -9.25918937e-01 -8.08418095e-01 -6.59831107e-01 -2.94139773e-01 -2.08181188e-01 -5.80679536e-01 -9.95993674e-01 -7.21249342e-01 -2.83998132e-01 -1.65107902e-02 -1.86920370e-04 -8.94319918e-03 2.09051147e-01 6.78186953e-01 8.53105962e-01 6.18343353e-01 3.71796250e-01 4.84289914e-01 1.02955624e-01 7.73759723e-01 2.41158509e+00 3.32406116e+00 2.50068855e+00 8.11975539e-01 6.44481778e-01 9.11870539e-01 7.84944832e-01 7.19896376e-01 1.42926621e+00 1.71992087e+00 5.07636595e+00 7.97215557e+00 7.99625301e+00 4.62168646e+00 1.64701998e+00 3.28077960e+00 3.39268446e+00 6.68406010e+00 9.88978767e+00 9.68773842e+00 4.44454241e+00 -8.77236247e-01 7.16868043e-01 2.12360620e+00 3.10984826e+00 1.51541865e+00 -3.76764119e-01 -1.17103732e+00 -1.53768265e+00 -6.99534893e-01 -2.22043589e-01 -9.04674590e-01 -5.93635261e-01 -4.90437841e+00 -7.44306135e+00 -9.59271431e+00 -8.66245079e+00 -6.13283253e+00 -5.43054008e+00 -5.27652836e+00 -5.87441444e+00 -5.94141340e+00 -4.73655653e+00 -6.52366257e+00 -5.50563431e+00 -4.43389654e+00 -4.49012518e+00 -8.34743595e+00 -9.49709034e+00 -7.29595089e+00 -4.45633173e+00 -4.41588879e+00 -5.57844925e+00 -2.96952462e+00 -2.88726282e+00 1.02289200e+00 1.32144606e+00 1.30239391e+00 -4.74170208e+00 -1.20973368e+01 -6.41727686e+00 7.42087936e+00 1.65200348e+01 1.34361906e+01 6.13087130e+00 3.93726158e+00 5.36873579e+00 6.56648111e+00 1.01660099e+01 1.08564911e+01 9.12732506e+00 6.82628822e+00 3.15246105e+00 1.36642335e-02 -2.48796701e+00 7.43094981e-02 4.27462244e+00 6.52037287e+00 5.79080582e+00 4.68790817e+00 5.55877066e+00 2.19583797e+00 2.10469246e+00 -1.59078225e-01 4.29353476e+00 1.49082022e+01 2.69801712e+01 2.78081608e+01 2.00119419e+01 8.21526432e+00 4.51480818e+00 2.26394296e+00 1.07899313e+01 1.89097157e+01 2.35763130e+01 2.49538422e+01 1.60126152e+01 8.13281631e+00 -3.67654157e+00 1.42546415e-01 4.58501577e+00 5.50253010e+00 2.81833839e+00 -1.55639517e+00 -3.74580932e+00 2.91019827e-01 9.85897350e+00 1.46402063e+01 1.56378183e+01 1.31414289e+01 2.62866592e+01 3.90196228e+01 3.30693283e+01 1.59565201e+01 1.73210371e+00 1.17674637e+01 1.72807484e+01 1.54973383e+01 1.21812735e+01 2.32532005e+01 3.83908691e+01 3.64094772e+01 1.58904285e+01 -5.18880463e+00 -7.06265926e-01 8.59805012e+00 9.72902966e+00 6.52464867e-01 -2.71980405e+00 -5.43380141e-01 8.54438305e+00 2.71852756e+00 -6.91213608e+00 -1.02810469e+01 -7.66594362e+00 -4.28034639e+00 -1.04479189e+01 5.51081276e+00 2.40720024e+01 2.62948246e+01 3.11462326e+01 4.21014900e+01 6.13302689e+01 6.27929649e+01 5.22562866e+01 5.45424957e+01 4.12557411e+01 3.93690529e+01 2.03860149e+01 1.40809774e+00 -2.24612255e+01 -2.80619373e+01 -2.02323780e+01 -1.59174862e+01 -1.03300877e+01 -1.05366154e+01 -9.37120438e+00 -1.28560057e+01 -1.59676542e+01 2.56388640e+00 3.10793667e+01 4.15893135e+01 3.23607407e+01 1.24251127e+01 5.94157696e+00 2.93238163e+00 -7.17004156e+00 4.51883984e+00 6.04241943e+00 1.46928701e+01 1.79397831e+01 3.31976357e+01 5.45554886e+01 4.02990532e+01 1.76554470e+01 1.00895529e+01 3.65263672e+01 4.38572845e+01 3.14152260e+01 3.30355501e+00 2.33733749e+01 4.43101807e+01 5.69758263e+01 3.92388306e+01 2.10730839e+01 4.40040817e+01 6.26967697e+01 5.48241692e+01 1.79954967e+01 -4.47862196e+00 1.80338459e+01 3.07876778e+01 7.64346075e+00 -2.43112812e+01 -4.02006954e-01 4.56291733e+01 6.28928413e+01 4.83142166e+01 2.87030792e+01 3.31443596e+01 5.67857170e+01 8.23110123e+01 7.40447998e+01 3.36660614e+01 -2.09683704e+00 -4.04066849e+00 3.89953804e+00 1.01616850e+01 9.52285004e+00 1.13904390e+01 1.53515081e+01 3.19469261e+01 3.47365341e+01 1.52281666e+01 4.52128935e+00 -2.39501095e+00 2.72728767e+01 3.99225845e+01 3.44615974e+01 2.26819439e+01 4.61368370e+00 8.28443527e+00 3.14877439e+00 -8.10219669e+00 -1.72601738e+01 -1.29476957e+01 3.79349785e+01 7.63170090e+01 3.57174873e+01 -3.45390549e+01 -4.22324524e+01 2.01231785e+01 4.40762100e+01 1.10169687e+01 -5.22152901e+00 1.88959675e+01 3.22514229e+01 2.39062672e+01 5.63477933e-01 1.39652481e+01 2.53539429e+01 3.41002007e+01 2.24388237e+01 3.08400798e+00 2.72184825e+00 2.92970157e+00 2.51470890e+01 4.48584442e+01 4.82574692e+01 1.93391018e+01 1.76385956e+01 8.15813751e+01 1.20263046e+02 1.06208366e+02 4.31784058e+01 3.86044426e+01 5.67564240e+01 3.59832344e+01 -1.68381729e+01 -3.22318153e+01 1.59412432e+00 3.28609009e+01 2.37405338e+01 1.04654474e+01 2.83969727e+01 3.76752510e+01 3.88298912e+01 2.74604511e+01 2.49428892e+00 -1.34963007e+01 -2.15855541e+01 -6.13966131e+00 6.43303490e+00 2.51999397e+01 3.31294708e+01 4.70218163e+01 6.14059258e+01 6.10533638e+01 3.83271179e+01 8.69212914e+00 1.51565886e+01 4.81713409e+01 5.73547096e+01 5.20019760e+01 6.65580978e+01 1.21644554e+02 1.55645081e+02 1.31535675e+02 6.77490158e+01 4.84685898e+01 5.95630836e+01 6.33495483e+01 3.90051346e+01 2.09217205e+01 9.40498829e+00 -3.02188706e+00 -1.98405826e+00 1.52825260e+01 1.95372353e+01 -1.03913345e+01 -1.45910139e+01 3.22102013e+01 6.17150879e+01 3.85499458e+01 1.22592878e+01 5.65947647e+01 8.69875488e+01 4.76832962e+01 -2.19681263e+01 -6.84571991e+01 -6.52078476e+01 -6.14813004e+01 -4.51670227e+01 -3.86065178e+01 -2.98124256e+01 -3.70836601e+01 -1.75468884e+01 3.18187445e-01 -2.64295936e+00 -3.57010002e+01 -2.09837780e+01 5.65058632e+01 1.00762596e+02 1.09742050e+02 8.95982971e+01 6.87872772e+01 3.62013855e+01 5.63003492e+00 -6.95499241e-01 -6.90577507e+00 -8.08123302e+00 -2.40552592e+00 9.76097393e+00 6.40121508e+00 1.49063139e+01 1.58849726e+01 4.72782755e+00 -3.69070679e-01 -1.09915407e-02 4.78672104e+01 9.18281097e+01 9.36910324e+01 5.51464310e+01 2.03089790e+01 2.32999477e+01 2.51594772e+01 2.68633118e+01 1.50121794e+01 2.05355568e+01 2.34865341e+01 5.93662186e+01 8.95009766e+01 7.84211197e+01 3.78467598e+01 2.45070877e+01 9.10501785e+01 1.36066299e+02 1.10794472e+02 3.92419167e+01 3.40858192e+01 6.23712769e+01 6.03519783e+01 2.89722748e+01 -1.22859430e+00 3.74013748e+01 6.79159393e+01 9.99736938e+01 1.13251289e+02 8.01596146e+01 3.94307213e+01 3.79029655e+01 1.15749786e+02 1.57554901e+02 1.02750458e+02 2.52356491e+01 3.33327675e+01 9.27123642e+01 1.12320908e+02 8.42040863e+01 4.73354683e+01 6.37672729e+01 8.66922913e+01 1.00347221e+02 7.85408554e+01 5.41126747e+01 3.84188004e+01 7.68808823e+01 1.19851891e+02 1.22799835e+02 9.01297302e+01 2.66315479e+01 5.64096146e+01 8.75861664e+01 1.00981873e+02 6.82095718e+01 5.87239799e+01 9.40149689e+01 8.99380341e+01 5.30079346e+01 9.07789898e+00 -6.64027309e+00 -1.26271229e+01 1.91961193e+01 6.95109558e+01 8.99781189e+01 6.64900436e+01 2.79269714e+01 1.23706341e+01 1.19319248e+01 6.58159943e+01 2.88869385e+02 4.83430237e+02 6.07103394e+02 4.78332794e+02 4.82174658e+03 1.40941934e+04 -1.71781797e+04 -5.30711865e+03 7.82370801e+03 2.41867529e+03 1.88411597e+03 1.10586961e+05 204508384. 1.02358991e+11 1.02358991e+11 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. -5.72994478e+10 5.50336289e+04 1.51437617e+04 1.63462268e+03 1.01430029e+03 -4.99594629e+03 -3.73757104e+03 -9.35938354e+02 -5.25404968e+02 -4.33104782e+01 1.00713791e+02 1.05753494e+02 2.55888634e+01 -1.01225376e+00 3.07182236e+01 -8.92947865e+00 -9.78207550e+01 -1.53112579e+02 -7.21985931e+01 8.14245682e+01 1.45899551e+02 9.98477097e+01 8.80132961e+00 -3.57306480e+01 -1.42164736e+01 5.81973600e+00 -2.28259048e+01 -7.14005280e+01 -4.19559402e+01 2.58274956e+01 5.61496544e+01 2.81076813e+01 -3.72107887e+01 -5.39102287e+01 -8.61221313e+00 6.95581436e+01 1.10017456e+02 7.01209259e+01 7.69352341e+01 1.22866074e+02 9.19280090e+01 -1.61311626e+01 -9.64799347e+01 -2.21169186e+01 1.46218048e+02 1.90777512e+02 1.21138725e+02 3.03290386e+01 -1.01366634e+01 -1.48920317e+01 6.28017473e+00 6.33313227e+00 -1.25609887e+00 1.32011585e+01 1.28036728e+02 1.93597031e+02 1.58713318e+02 4.59208298e+01 -2.10854168e+01 2.54244690e+01 1.00712990e+02 1.35734131e+02 6.72474594e+01 4.86912079e+01 7.36590347e+01 5.28739204e+01 -2.23926296e+01 -9.90361557e+01 -9.09760284e+01 2.03400440e+01 5.86032715e+01 3.22130432e+01 -5.19636307e+01 -3.19445267e+01 2.90528316e+01 1.52311459e+01 -3.99045258e+01 -7.30228500e+01 -2.65851326e+01 7.29600754e+01 1.19536171e+02 9.03297501e+01 -8.09649372e+00 -6.96672821e+01 -5.55345306e+01 -1.57525826e+01 -2.93493385e+01 -7.19485321e+01 -5.77596931e+01 1.31841002e+01 4.33722572e+01 -2.23909302e+01 -1.12467613e+02 -1.21103691e+02 -2.66728630e+01 5.23023834e+01 5.35229568e+01 -1.26603842e+01 -2.05539246e+01 7.70432234e-01 -4.04009819e+01 -1.31154007e+02 -1.79221542e+02 -1.00783928e+02 2.13548737e+01 8.71331711e+01 5.30926132e+01 -1.99227066e+01 -1.00211159e+02 -1.51181381e+02 -1.37618698e+02 -1.20351082e+02 -1.19665070e+02 -1.00751297e+02 -2.54397583e+01 4.24293098e+01 6.72316408e+00 -9.65662537e+01 -1.50991226e+02 -1.10147141e+02 -4.19248915e+00 5.09049149e+01 9.73489285e+00 -3.93250237e+01 -5.20026512e+01 -4.46336975e+01 -8.95453339e+01 -1.75095764e+02 -1.73753189e+02 -8.61837921e+01 4.84198618e+00 5.03720093e+00 -5.28205681e+01 -1.00790375e+02 -1.10198502e+02 -8.17263184e+01 -4.27340202e+01 -2.34367466e+01 -7.73667603e+01 -1.02379463e+02 -6.36875305e+01 -2.10435600e+01 -9.79380608e+00 -2.79552269e+01 -2.85655556e+01 4.18828249e+00 -3.66447210e+00 -2.91113396e+01 -6.84201279e+01 -7.70567322e+01 -3.59926834e+01 -1.23693218e+01 -3.01107178e+01 -6.75351028e+01 -4.10909920e+01 6.70444946e+01 1.12539108e+02 3.70555801e+01 -6.77824631e+01 -7.44772797e+01 -1.99046917e+01 1.82749538e+01 7.01266289e+00 6.37180328e+00 3.88814583e+01 8.29111938e+01 9.94411697e+01 7.39697266e+01 9.54488277e+00 -3.77652664e+01 3.28400373e+00 3.04471283e+01 1.94427204e+01 -2.67539692e+01 -5.50793648e+00 7.67666931e+01 6.99070358e+01 3.43811493e+01 -1.25144787e+01 3.57427330e+01 1.34436005e+02 1.81934738e+02 1.37538849e+02 3.30875893e+01 -1.83625031e+01 -1.68962936e+01 -2.22126122e+01 -4.38613548e+01 -2.81981659e+01 3.30190468e+01 9.89990768e+01 8.69336853e+01 3.01641273e+01 -7.19283447e+01 -1.02943680e+02 -7.97291031e+01 -9.63248539e+00 3.19302483e+01 3.60232010e+01 5.88186760e+01 8.73538513e+01 6.58925705e+01 -6.75424576e+00 -6.06738129e+01 -2.25223827e+01 6.74180984e+01 1.08067825e+02 5.52095299e+01 -3.60150604e+01 -7.41905060e+01 -2.77064304e+01 1.91219826e+01 -4.67374039e+00 -5.07582932e+01 -3.92947922e+01 1.17505045e+01 2.66468887e+01 -2.44537544e+01 -9.68760605e+01 -1.05073090e+02 -6.73273773e+01 -2.47060738e+01 -2.72359104e+01 -4.64708786e+01 -4.28947792e+01 -1.89716339e+01 -3.37710953e+01 -6.92494278e+01 -7.78632584e+01 -7.34804764e+01 -3.18870716e+01 -2.31862431e+01 -3.46104202e+01 -3.71529312e+01 -3.79467506e+01 -4.63674736e+00 -3.33160553e+01 -6.31911888e+01 -8.44571152e+01 -6.63221817e+01 7.68731403e+00 4.78009186e+01 4.06422195e+01 -4.63298607e+01 -8.74956818e+01 -9.11403275e+01 -5.67036705e+01 -3.80131836e+01 -6.24584198e+01 -5.96870575e+01 -3.17711601e+01 -1.28317118e+01 -4.18351555e+01 -6.31524506e+01 -2.12338467e+01 4.08491058e+01 2.77969570e+01 -5.90462446e+00 -2.59520626e+01 -7.90092087e+00 3.40016785e+01 -4.13783932e+00 -2.89874535e+01 -5.85600700e+01 -3.92609253e+01 5.72779703e+00 2.41499252e+01 3.93958397e+01 -1.73397863e+00 -1.74744720e+01 -2.63086891e+01 4.37694120e+00 4.71670055e+00 2.95170808e+00 4.44019175e+00 2.47224045e+01 3.80262375e+01 -3.04698229e+00 -2.91364822e+01 -3.45207214e+01 1.55398405e+00 -5.61268759e+00 -1.92994442e+01 -3.68414345e+01 -4.65732803e+01 -3.82577286e+01 -4.30534248e+01 -8.63139820e+00 5.21846056e+00 1.51864185e+01 7.11011600e+00 -3.16185117e+00 -1.77637482e+01 -5.53837585e+01 -7.04223633e+01 -5.62120667e+01 -3.53391361e+00 5.72414923e+00 -5.41730165e+00 -1.59398413e+01 -1.17797365e+01 -2.56486130e+01 -7.29311676e+01 -9.12114563e+01 -7.18805389e+01 -1.87392941e+01 -7.05990887e+00 -2.43407249e+01 -5.24244423e+01 -5.88412933e+01 -3.44625168e+01 -3.21670303e+01 -2.48696785e+01 -5.10876579e+01 -6.39671173e+01 -6.23535423e+01 -3.75587654e+01 -2.42799587e+01 -4.52787209e+01 -6.87695923e+01 -5.70705452e+01 -2.70313950e+01 -3.32263870e+01 -5.22725029e+01 -5.68556519e+01 -4.11970673e+01 -4.20537872e+01 -6.58204422e+01 -7.68227158e+01 -6.16028824e+01 -3.35841141e+01 -3.20002365e+01 -4.26125984e+01 -5.44507904e+01 -4.84757729e+01 -3.88932419e+01 -3.97049789e+01 -3.64902344e+01 -5.10506554e+01 -5.81188240e+01 -6.09741135e+01 -4.85372734e+01 -4.43209915e+01 -5.47893982e+01 -6.53547821e+01 -5.29156876e+01 -2.92246113e+01 -2.31701622e+01 -2.58708038e+01 -2.09513130e+01 -3.50879836e+00 -8.78264427e+00 -2.74225006e+01 -3.01827888e+01 -1.87410355e+01 -7.69467413e-01 -2.03192730e+01 -3.12509193e+01 -4.15254097e+01 -5.13620224e+01 -5.45531425e+01 -4.50551529e+01 -1.73843460e+01 -1.06027117e+01 -3.02669697e+01 -4.60141792e+01 -3.63080177e+01 -1.30612822e+01 -7.30667710e-01 -1.52371311e+01 -2.63628082e+01 -2.45406570e+01 -1.75892029e+01 -8.08008480e+00 1.03210056e+00 1.70531960e+01 1.04170628e+01 -4.62066555e+00 -1.04785862e+01 -3.59990954e+00 4.66028166e+00 -1.29636202e+01 -2.23384476e+01 -2.93492737e+01 -2.68204861e+01 -2.32867603e+01 -1.44613466e+01 5.31672430e+00 7.38642216e+00 -1.02165194e+01 -3.81055641e+01 -4.42663460e+01 -2.16147461e+01 -3.76875925e+00 -3.95682836e+00 -1.78093624e+01 -2.48793430e+01 -2.13310394e+01 -1.07981281e+01 -5.32812548e+00 -1.11359310e+01 -2.68250370e+01 -3.19109268e+01 -2.52884617e+01 -1.59543324e+01 -4.32976866e+00 -5.42458773e+00 -1.01458063e+01 -2.26548328e+01 -3.37639732e+01 -3.79933052e+01 -3.15638752e+01 -1.87416286e+01 -1.24516296e+01 -1.89730148e+01 -2.78546028e+01 -2.73399601e+01 -1.89585209e+01 -1.17407961e+01 -1.58323574e+01 -2.47056007e+01 -3.07801228e+01 -3.09723244e+01 -2.64557877e+01 -2.36272774e+01 -2.17358017e+01 -2.51486759e+01 -2.69957905e+01 -2.83577328e+01 -2.70425243e+01 -2.63064499e+01 -2.76977119e+01 -2.88127346e+01 -2.99834805e+01 -2.96778393e+01 -2.90406361e+01 -2.85552044e+01 -2.86440964e+01 -2.91740189e+01 -2.91673908e+01 -2.77796154e+01 -2.64325924e+01 -2.70793018e+01 -3.00909920e+01 -3.24599342e+01 -3.19779758e+01 -3.01473122e+01 -3.02646027e+01 -3.24268494e+01 -3.40853233e+01 -3.48984451e+01 -3.13052864e+01 -2.81598778e+01 -2.52044411e+01 -2.51379662e+01 -2.71344261e+01 -2.99532871e+01 -3.41765862e+01 -3.42529335e+01 -2.99406738e+01 -2.48786907e+01 -2.44408054e+01 -3.04082069e+01 -3.77462769e+01 -3.48938675e+01 -2.81614151e+01 -2.39635544e+01 -2.98785629e+01 -4.11869965e+01 -4.08983688e+01 -3.42255325e+01 -2.12925415e+01 -2.16957836e+01 -3.15855255e+01 -4.02177505e+01 -4.71166115e+01 -3.52612953e+01 -3.05095596e+01 -2.47058125e+01 -2.37558651e+01 -2.29839077e+01 -2.18183022e+01 -2.84615345e+01 -2.43820095e+01 -1.73737507e+01 -1.71333504e+01 -2.67785397e+01 -4.29659615e+01 -5.28436127e+01 -4.27705841e+01 -1.83060970e+01 3.48747301e+00 -2.67205480e-02 -2.73029118e+01 -5.32795143e+01 -6.22436371e+01 -4.14046707e+01 -1.77822247e+01 -1.34113407e+01 -2.93334255e+01 -4.85591698e+01 -4.13187485e+01 -2.75191154e+01 -1.63960285e+01 -1.44011345e+01 -1.82182560e+01 -2.87687569e+01 -4.45685539e+01 -4.21045609e+01 -2.48650436e+01 2.93568671e-01 4.25261164e+00 -1.58373995e+01 -4.25873833e+01 -3.97128563e+01 -1.79792652e+01 -3.26471400e+00 -1.51612730e+01 -2.86016254e+01 -3.52933769e+01 -3.81564331e+01 -2.69882355e+01 -1.89047642e+01 -2.67233410e+01 -3.45107117e+01 -4.63918839e+01 -2.99079857e+01 -1.70391102e+01 2.07078648e+00 1.31623049e+01 -7.54568219e-01 -1.67587585e+01 -4.54392662e+01 -5.36853676e+01 -3.78770485e+01 -1.11836205e+01 -8.23124409e+00 -3.47045708e+01 -6.24423485e+01 -5.67910118e+01 -3.82162094e+01 -7.79158258e+00 5.04408002e-01 -1.17322893e+01 -2.85926304e+01 -4.11462173e+01 -1.57323875e+01 6.10591507e+00 3.33363495e+01 2.81340141e+01 -6.48814261e-01 9.36692357e-01 9.76879787e+00 3.92246323e+01 4.28163223e+01 3.62563171e+01 1.47016487e+01 -3.00741768e+01 -4.55945549e+01 -3.43454437e+01 3.18624973e+00 1.98447132e+01 -7.79173994e+00 -4.54895325e+01 -4.87103157e+01 -7.54239035e+00 2.62134266e+01 1.55879011e+01 -2.52533569e+01 -5.92116203e+01 -6.28017616e+01 -2.59933281e+01 1.81777344e+01 2.96219215e+01 2.22696381e+01 6.35575151e+00 -8.34756088e+00 -2.87598057e+01 -3.13438015e+01 -1.85508766e+01 -9.34732628e+00 -2.50109730e+01 -6.70327530e+01 -8.96187744e+01 -5.71227989e+01 -4.08074379e+00 2.15904884e+01 -1.18092146e+01 -6.49489899e+01 -7.53173447e+01 -4.59679298e+01 8.29335594e+00 1.37690258e+01 -1.50895195e+01 -3.36010246e+01 -4.06156044e+01 -8.45092583e+00 2.52334690e+00 -2.25103402e+00 -1.51493502e+01 -4.60013123e+01 -3.41447601e+01 -2.57700214e+01 1.99235592e+01 5.14938316e+01 3.72304039e+01 1.62232647e+01 -3.15537415e+01 -3.80442848e+01 -2.32301311e+01 3.60291862e+01 9.20693817e+01 7.89372330e+01 1.64038353e+01 -1.95285149e+01 1.58341675e+02 1.77770935e+02 4.58368149e+01 2.45091748e+03 5.41397656e+03 -881920960. -560643584. 1533132160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -914026496. -423721024. -2.42461992e+04 -8.56551270e+03 -7.65737183e+02 -1.05972061e+02 -4.78749573e+02 -1.83614365e+02 3.19781885e+03 2.13238452e+03 2.67701660e+02 2.38669708e+02 1.11806160e+02 7.67535706e+01 6.01640358e+01 3.05373821e+01 -6.06046600e+01 -6.29905663e+01 -2.36481400e+01 4.50825043e+01 3.26921730e+01 -4.19748840e+01 -1.10194138e+02 -1.21670341e+02 -5.71359634e+01 3.55018044e+01 5.76166954e+01 -1.49005814e+01 -8.82669067e+01 -9.81762772e+01 -3.13146915e+01 -2.92680168e+01 -6.38166809e+01 -7.71004868e+01 -4.43184929e+01 1.43199098e+00 9.29539979e-01 1.11387873e+01 3.72031784e+01 3.76925659e+01 -4.01536512e+00 -9.95508804e+01 -9.90708923e+01 -4.31992722e+01 1.54366627e+01 8.93755341e+00 -5.50600319e+01 -1.29006195e+02 -1.21379974e+02 -2.15587673e+01 9.70702591e+01 8.50589981e+01 -3.08047161e+01 -8.87005386e+01 -9.10769272e+01 -1.99533920e+01 -2.36418653e+00 5.31637192e+00 1.73128757e+01 1.77113235e+00 -2.70026035e+01 -1.07519341e+02 -8.02318878e+01 -1.55604601e+01 1.76476154e+01 -3.47588196e+01 -1.22235123e+02 -1.24391594e+02 -7.97124405e+01 -1.34800301e+01 2.00117264e+01 -4.74996338e+01 -1.40288254e+02 -2.15611160e+02 -1.82242401e+02 -7.46392822e+01 -3.54947510e+01 -8.97601242e+01 -1.40440750e+02 -1.36160645e+02 -3.96588554e+01 -1.54251766e+01 -3.89832458e+01 -8.40786591e+01 -8.13113708e+01 -8.11691666e+01 -1.03831421e+02 -6.69229584e+01 -4.30812836e+00 2.25827618e+01 -4.85841560e+01 -1.56457977e+02 -1.72881454e+02 -1.34090057e+02 -5.10238457e+01 -3.47758937e+00 9.69180298e+00 -5.95438232e+01 -1.04872307e+02 -1.04794579e+02 3.84899092e+00 4.44797897e+01 -2.94619694e+01 -1.08051682e+02 -1.06321220e+02 -1.39273679e+00 4.25572166e+01 2.94129219e+01 2.04250546e+01 7.07285929e+00 -2.72163143e+01 -1.13335037e+02 -1.12679604e+02 -4.33800430e+01 1.41180592e+01 1.74132595e+01 -5.04511452e+01 -5.92414436e+01 -1.91672211e+01 1.46221437e+01 5.58971901e+01 3.87915459e+01 -2.84865856e+01 -1.02651054e+02 -1.24436081e+02 -2.12078362e+01 3.23073959e+01 -1.02189531e+01 -4.12797852e+01 -4.87618713e+01 7.90990210e+00 1.95822692e+00 -9.81587982e+00 1.96785469e+01 2.59763813e+01 9.10113239e+00 -8.80517426e+01 -7.80042801e+01 -5.79661131e+00 4.59151230e+01 3.27669487e+01 -3.07089500e+01 -2.85147877e+01 2.21919289e+01 5.42478104e+01 9.77436295e+01 5.50797768e+01 -1.46342096e+01 -7.90875397e+01 -7.13156509e+01 7.34795570e+00 1.46325417e+01 -4.20712948e+00 -1.31390629e+01 1.29112988e+01 6.08280487e+01 9.08812561e+01 1.13353577e+02 1.19212471e+02 8.01146698e+01 2.34221210e+01 -6.38613625e+01 -9.61737518e+01 -7.34123230e+01 -1.99180660e+01 -1.49557981e+01 -8.28133698e+01 -1.46682861e+02 -1.08428978e+02 6.66692615e-01 8.14234161e+01 6.82003403e+01 -3.74843674e+01 -1.00123680e+02 -8.66274872e+01 -1.10342379e+01 8.02387714e+00 -3.17781754e+01 -3.11182079e+01 -4.03361320e+01 -4.27119865e+01 -4.35558014e+01 1.60662861e+01 1.01010033e+02 9.35762177e+01 6.64249802e+01 1.84065008e+00 -3.12933025e+01 -4.98413887e+01 -2.83957024e+01 -1.94751797e+01 -6.74359665e+01 -1.33091660e+02 -1.05924515e+02 -1.40338860e+01 8.27579117e+01 9.06135406e+01 1.40929222e+01 -1.08042717e+01 -2.13163662e+01 5.37961922e+01 3.95914879e+01 -1.49057922e+01 -8.44074554e+01 -1.26235527e+02 -1.29806396e+02 -1.74704376e+02 -1.39367279e+02 -5.64067574e+01 1.88924294e+01 1.97821445e+01 -5.31000671e+01 -6.57798843e+01 -1.09639645e+01 6.40730133e+01 1.41637878e+02 9.43697433e+01 -1.56515341e+01 -1.32681320e+02 -9.98021774e+01 6.74016619e+00 2.98834209e+01 -2.12805042e+01 -4.93059311e+01 -4.65317001e+01 -4.26215857e-01 4.19367790e+01 6.01805763e+01 5.68505630e+01 2.06121540e+01 -1.29587374e+01 -9.12854919e+01 -1.10882774e+02 -8.54017715e+01 -3.92940331e+01 -2.24713078e+01 -1.94221802e+01 1.48062115e+01 5.87781906e+01 7.05909348e+01 5.39891701e+01 2.06236315e+00 -8.18009567e+00 -1.96586361e+01 -1.22108736e+01 1.40720091e+01 1.67208118e+01 1.38182249e+01 -3.28266296e+01 -3.57491798e+01 -2.31990471e+01 1.08310251e+01 4.83230257e+00 -1.09271460e+01 -2.49465065e+01 -1.04253588e+01 8.21452618e+00 8.00244999e+00 1.64019337e+01 9.49062634e+00 2.18664646e+01 8.60543060e+00 4.61846733e+00 -1.33985929e+01 6.58540821e+00 2.31158047e+01 3.41770515e+01 2.68766918e+01 2.16366138e+01 3.28959198e+01 3.45754929e+01 3.12333927e+01 3.48678894e+01 3.09584885e+01 2.41178970e+01 1.29312687e+01 2.52170486e+01 2.82282543e+01 2.65177917e+01 2.34146271e+01 2.87670269e+01 3.52406425e+01 3.11759071e+01 3.65047379e+01 2.62280540e+01 1.56965599e+01 1.09876928e+01 2.84220104e+01 3.11852779e+01 4.05237808e+01 2.86837120e+01 4.36271782e+01 3.41246414e+01 4.54111633e+01 4.25244141e+01 4.33487129e+01 1.42115631e+01 -2.50747166e+01 -4.71948128e+01 -2.67320786e+01 -2.22958660e+00 1.43501215e+01 3.38355589e+00 9.82961464e+00 -6.61229658e+00 -4.82660580e+00 9.33556366e+00 2.44684315e+01 1.86552830e+01 8.12711525e+00 1.64359035e+01 1.98481655e+01 1.08953838e+01 6.36026812e+00 2.46565933e+01 1.91546192e+01 5.63565493e+00 -1.61823406e+01 -1.15236425e+01 -1.08686972e+01 1.59770098e+01 4.27249641e+01 8.57102356e+01 9.52747955e+01 7.73518295e+01 4.21482620e+01 1.84210339e+01 1.09138556e+01 1.18345432e+01 4.00312376e+00 2.68710041e+01 5.80191231e+01 5.78373070e+01 2.68895264e+01 -6.24323893e+00 -6.73584080e+00 5.91859341e+00 -3.59749460e+00 -3.57476139e+00 -5.19540310e+00 -3.65324736e+00 -6.69107533e+00 -1.35386400e+01 4.24890661e+00 1.23293409e+01 -4.53485340e-01 -1.48645172e+01 -4.40009232e+01 -4.45228615e+01 -3.98959732e+01 -1.19622822e+01 -1.96833515e+01 -2.15672474e+01 -1.86314335e+01 -5.75206804e+00 4.04728079e+00 -1.59089098e+01 -3.30035515e+01 -4.53800125e+01 -1.18496246e+01 1.68591976e+01 3.01896038e+01 -2.77106190e+00 -3.79860573e+01 -6.89912949e+01 -3.66647682e+01 1.25982199e+01 3.14635563e+01 2.22897835e+01 -1.48726726e+00 -2.02792764e+00 -3.92806892e+01 -5.51593895e+01 -4.21301117e+01 -1.34356298e+01 1.17999086e+01 2.04452400e+01 1.78670273e+01 -1.54742193e+00 -3.02992153e+01 -3.42485313e+01 -8.53042603e+00 9.54589176e+00 1.83862686e+01 1.66679287e+01 2.54161110e+01 3.91498871e+01 4.14748039e+01 3.92433624e+01 3.06473274e+01 1.85724010e+01 2.21372967e+01 2.24843845e+01 2.31808987e+01 8.35019207e+00 1.90602226e+01 3.37324829e+01 1.70440216e+01 -1.82335210e+00 4.80016470e+00 5.00426331e+01 6.65231628e+01 4.29161949e+01 2.06417046e+01 2.06965008e+01 1.62288685e+01 -1.23299599e+01 -3.00587273e+01 -4.02166328e+01 -2.53067722e+01 -9.88051319e+00 1.06932297e+01 1.28143673e+01 -6.30561531e-01 4.75366974e+00 1.11087265e+01 2.13442993e+01 1.79969025e+01 2.58887501e+01 -7.28841019e+00 -3.39133110e+01 -4.38777275e+01 -1.33132744e+01 8.97339153e+00 1.66546612e+01 1.96003838e+01 1.97219925e+01 2.42014656e+01 1.15126171e+01 3.06989784e+01 4.55397644e+01 7.29062805e+01 6.78788147e+01 5.20008163e+01 3.08437271e+01 3.41652946e+01 4.21127853e+01 4.86070442e+01 4.35051117e+01 3.61557198e+01 6.45750580e+01 9.67716217e+01 9.85897675e+01 6.19408035e+01 1.49745140e+01 1.02435570e+01 3.87766304e+01 8.65607605e+01 1.94412628e+02 4.57351440e+02 6.28721558e+02 6.65815063e+02 8.33081116e+02 2.68299854e+03 3.72373218e+03 -4.82158630e+02 5.63206006e+03 8.38958191e+02 5.65309033e+03 2.03313184e+04 375353952. 857250240. 309577056. 569123392. 3.30910413e+09 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. 0. 0. 0. 0. 0. 0. -8.94549770e+10 -8.94549770e+10 993453312. -2.62259121e+04 -7.58207861e+03 -8.43289551e+02 2.76617358e+03 1.94521912e+03 5.40832947e+02 4.74805084e+02 3.64085114e+02 1.49002930e+02 8.01347580e+01 7.73152466e+01 5.58295135e+01 3.31501274e+01 3.59468613e+01 3.72369080e+01 3.75151520e+01 3.70561790e+01 5.40021935e+01 6.88919983e+01 5.40446892e+01 2.57481308e+01 2.19067917e+01 3.88446159e+01 5.19868584e+01 4.07466240e+01 3.91656647e+01 4.47060928e+01 5.02358170e+01 5.48296089e+01 5.52848625e+01 5.42457199e+01 4.69651947e+01 4.54889145e+01 4.00134621e+01 4.08358688e+01 2.15844688e+01 6.23220062e+00 3.10358930e+00 1.50849438e+01 2.47493687e+01 2.15737057e+01 1.25341167e+01 1.10160084e+01 3.00847459e+00 2.63690531e-01 -2.63703990e+00 -5.23574591e+00 -6.98986578e+00 -1.26614416e+00 5.41545343e+00 1.11105423e+01 9.12200165e+00 1.04064360e+01 1.31926470e+01 1.04849730e+01 8.88036346e+00 2.62572074e+00 7.84994543e-01 7.93671989e+00 2.60878334e+01 4.57463188e+01 5.30713310e+01 4.25729103e+01 3.14817600e+01 2.36256046e+01 3.46507950e+01 4.43059578e+01 3.88826866e+01 2.40238132e+01 1.06985798e+01 1.15599470e+01 1.33376884e+01 5.59323883e+00 -8.68043232e+00 7.90966511e-01 1.95549889e+01 3.79825516e+01 3.49919853e+01 2.68557720e+01 2.71132755e+01 2.33568039e+01 2.12766075e+01 1.69560413e+01 1.95522385e+01 2.31053715e+01 3.07648697e+01 3.30382614e+01 3.29751854e+01 2.63490200e+01 2.71282349e+01 3.68940468e+01 5.15985832e+01 4.75634727e+01 3.81656418e+01 2.73324432e+01 3.03503532e+01 3.60714951e+01 4.28185081e+01 4.55688629e+01 3.72083130e+01 2.47126255e+01 2.29791737e+01 2.67257557e+01 3.83049736e+01 3.57923050e+01 3.50937157e+01 2.85230713e+01 2.66770172e+01 2.77162685e+01 2.88274403e+01 2.86239738e+01 2.77749081e+01 2.84579258e+01 2.83959465e+01 2.68801765e+01 3.18667793e+01 3.93703575e+01 4.04236641e+01 3.34723015e+01 2.58626976e+01 2.38242798e+01 2.27070141e+01 2.31430950e+01 2.18342381e+01 2.10243034e+01 2.02365265e+01 2.81882706e+01 3.76280251e+01 3.93227654e+01 3.47492752e+01 2.76339321e+01 2.45293770e+01 2.24487972e+01 2.34441071e+01 2.61011028e+01 2.72346783e+01 2.56779861e+01 2.70114594e+01 2.71623249e+01 2.75991974e+01 2.69389019e+01 2.77028751e+01 2.80775547e+01 2.92365322e+01 2.87509689e+01 2.89373188e+01 2.86185093e+01 2.87758446e+01 2.87569790e+01 2.92505550e+01 2.97681236e+01 2.98036518e+01 2.83096867e+01 2.78874779e+01 2.75716820e+01 2.80238781e+01 2.75957890e+01 2.73026943e+01 2.73280640e+01 2.81645641e+01 3.11302700e+01 3.23619652e+01 3.23014030e+01 3.12259731e+01 3.02834053e+01 2.99319839e+01 2.91830978e+01 2.88666286e+01 2.90357361e+01 2.90234165e+01 2.89588375e+01 2.87642803e+01 2.87035675e+01 2.86233921e+01 2.86204967e+01 2.89140949e+01 2.93831062e+01 2.96156616e+01 2.93195419e+01 2.88235226e+01 2.79617462e+01 2.81058311e+01 2.81549835e+01 2.86579361e+01 2.84848804e+01 2.87411213e+01 2.84028778e+01 2.86627846e+01 2.87284012e+01 2.83623276e+01 2.78806171e+01 2.83308964e+01 2.89685040e+01 2.93150482e+01 2.81978912e+01 2.73689880e+01 2.68982582e+01 2.68032341e+01 2.77027798e+01 3.13407593e+01 3.47879677e+01 3.74874153e+01 3.73288689e+01 3.72466812e+01 3.79163132e+01 3.48350677e+01 2.98196735e+01 2.46068649e+01 2.31301231e+01 2.41683655e+01 2.60066662e+01 2.66809902e+01 2.58543701e+01 2.29327221e+01 2.34976826e+01 2.37329121e+01 2.56187801e+01 2.60759697e+01 2.58469315e+01 2.03179798e+01 1.35202484e+01 1.55454388e+01 2.12551212e+01 2.78878803e+01 3.13403759e+01 3.48187523e+01 4.21680183e+01 4.67200699e+01 4.43883781e+01 3.85243721e+01 2.97738323e+01 3.38940392e+01 3.70952911e+01 3.97044678e+01 3.77507591e+01 3.63048897e+01 3.76930161e+01 3.91466446e+01 3.87334366e+01 3.62759628e+01 3.25260468e+01 3.27911377e+01 3.98357506e+01 4.87148323e+01 5.82708702e+01 6.13745651e+01 4.25885048e+01 2.32717896e+01 1.29829931e+01 2.08371525e+01 3.10861359e+01 2.94516735e+01 3.33983040e+01 3.06885777e+01 2.98227463e+01 2.73017025e+01 2.59445839e+01 2.66542206e+01 2.69145451e+01 2.79462109e+01 1.78176498e+01 4.75294638e+00 6.07464612e-02 7.51692677e+00 1.74584751e+01 2.57601700e+01 3.53891411e+01 3.68876839e+01 2.97242641e+01 2.63980198e+01 3.24430161e+01 3.34317474e+01 2.67096329e+01 2.01715679e+01 1.94481277e+01 2.05961571e+01 2.11361294e+01 2.35985413e+01 2.34102936e+01 2.56263943e+01 2.29031296e+01 2.22048702e+01 1.62323093e+01 1.54182596e+01 1.72864571e+01 3.26659813e+01 4.96934929e+01 4.62550201e+01 3.18980198e+01 1.76110802e+01 2.47896919e+01 2.88385086e+01 3.17822609e+01 3.13500156e+01 3.47395630e+01 3.64475822e+01 4.74238091e+01 5.30102921e+01 5.22914581e+01 3.41262550e+01 1.91832771e+01 1.66145649e+01 2.23559170e+01 1.30038958e+01 -1.97268224e+00 -8.46865368e+00 -3.34622836e+00 1.19064398e+01 1.26804619e+01 1.38416882e+01 1.37314434e+01 1.47526178e+01 1.72485542e+01 1.30116529e+01 7.56052542e+00 9.02864361e+00 1.14792681e+01 1.17448950e+01 8.10600853e+00 1.19899130e+01 1.67557240e+01 3.28526077e+01 4.83916130e+01 4.58798714e+01 3.68573380e+01 2.64459534e+01 2.99689026e+01 2.55785084e+01 1.48351498e+01 1.83529282e+01 4.06766968e+01 6.17678108e+01 6.03013039e+01 3.82376862e+01 2.34519329e+01 2.78174839e+01 3.46782417e+01 3.62958221e+01 3.15135651e+01 4.65084000e+01 6.87826385e+01 7.45989838e+01 5.55732079e+01 2.45419979e+01 2.61050320e+01 2.77226543e+01 3.33090210e+01 2.75744896e+01 2.55900860e+01 3.26644249e+01 3.97207832e+01 4.48782768e+01 3.79594955e+01 3.26671371e+01 3.77342796e+01 6.32396469e+01 9.78705750e+01 9.90346603e+01 7.33849869e+01 4.37719269e+01 3.65541306e+01 3.04338970e+01 3.13999348e+01 3.89800339e+01 6.84682159e+01 9.02826614e+01 1.13618599e+02 1.17290031e+02 9.59815063e+01 7.43923187e+01 4.08594856e+01 5.75905952e+01 7.43993607e+01 5.62739944e+01 7.63317156e+00 -2.02852592e+01 3.58738244e-01 3.15383358e+01 2.97309284e+01 2.71989346e+01 1.96222801e+01 1.65418110e+01 6.93085337e+00 4.67949820e+00 3.67972183e+00 6.32832813e+00 9.52947330e+00 8.09518528e+00 4.17347044e-01 -4.51859665e+00 7.62779176e-01 2.46173649e+01 4.90654297e+01 4.21755180e+01 1.89091644e+01 -9.42072105e+00 1.86344719e+01 5.31677055e+01 2.51506901e+01 -3.44452095e+01 -4.16416550e+01 3.38211937e+01 7.70446396e+01 5.82121315e+01 2.13695984e+01 3.99155350e+01 7.46825638e+01 7.98043671e+01 6.29947395e+01 3.39568558e+01 3.70257072e+01 4.02177773e+01 3.06461601e+01 2.76793098e+01 2.64767861e+00 -1.88177948e+01 1.32453747e+01 6.53266144e+01 9.58113174e+01 7.53617401e+01 5.42189865e+01 7.68142548e+01 9.79894714e+01 1.01056480e+02 8.08264999e+01 4.49211845e+01 4.60239182e+01 5.23545837e+01 6.41562958e+01 4.75218620e+01 5.95795631e+01 8.24724045e+01 9.67656021e+01 9.30811996e+01 5.64666595e+01 3.43678055e+01 1.32685928e+01 1.20130529e+01 1.80945168e+01 -2.42757244e+01 -7.16355667e+01 -5.97472878e+01 6.02361774e+00 5.50468178e+01 4.57023468e+01 1.85406666e+01 4.72426910e+01 8.02694702e+01 8.28881226e+01 5.55419426e+01 2.36657848e+01 1.62494164e+01 1.99883118e+01 1.55457077e+01 2.38005219e+01 1.73973389e+01 2.97488842e+01 4.25351448e+01 5.33684196e+01 4.17855453e+01 2.45959053e+01 1.59952536e+01 1.11701908e+01 1.39791098e+01 -2.33482132e+01 -5.62471657e+01 -2.99303341e+01 4.78689613e+01 8.78155060e+01 5.13091202e+01 1.53959394e+00 -2.50979462e+01 -3.54019661e+01 -3.45391808e+01 -2.36911716e+01 -1.48894482e+01 -1.94114094e+01 -7.16843319e+00 -1.27607498e+01 -1.50796671e+01 -2.88725300e+01 -3.75713806e+01 -4.01240959e+01 -2.43769493e+01 -4.00652313e+00 -7.97535372e+00 -2.83361683e+01 -4.24707413e+01 -1.98614082e+01 -1.94904292e+00 1.89785786e+01 3.77769165e+01 7.58337250e+01 7.73014221e+01 5.77261009e+01 5.33259087e+01 1.19733833e+02 1.63910294e+02 1.38323380e+02 8.53520355e+01 9.22780914e+01 1.34588898e+02 1.44410858e+02 1.07268158e+02 7.38023376e+01 5.96212387e+01 5.73555908e+01 6.22718697e+01 7.04384689e+01 6.71335602e+01 4.90068092e+01 6.87197647e+01 1.06863800e+02 1.23063934e+02 9.60881805e+01 5.11334457e+01 5.32277298e+01 7.96815262e+01 5.35388374e+01 8.08053970e+00 -2.26892853e+01 -2.52613807e+00 1.96218224e+01 7.03585482e+00 5.56155539e+00 8.08941746e+00 1.28116369e+01 7.39955187e+00 9.04474163e+00 1.09217100e+01 2.78051615e+00 -7.80994606e+00 -1.80799503e+01 -1.53720055e+01 3.53394002e-01 1.09256721e+00 3.68178825e+01 6.81854782e+01 6.74749146e+01 2.69332943e+01 -2.58798504e+01 -3.63608971e+01 -3.26927414e+01 -5.81929207e+01 -9.24104080e+01 -9.67298889e+01 -7.02840347e+01 -2.96215057e+01 -1.85286636e+01 -1.47206278e+01 3.50563469e+01 8.18639221e+01 9.65027695e+01 5.85835876e+01 2.80204601e+01 2.98337364e+01 2.23498192e+01 9.89739513e+00 1.31063747e+01 -1.18108854e+01 -5.26337967e+01 -3.22687645e+01 2.41655502e+01 6.04519539e+01 3.29751282e+01 3.49673042e+01 1.11205627e+02 1.59988907e+02 1.40659348e+02 6.56345139e+01 4.00325165e+01 6.71708221e+01 6.49462357e+01 3.67605972e+01 -1.50258045e+01 -3.41302705e+00 2.91646442e+01 4.13955803e+01 2.92091084e+01 -2.89562964e+00 -2.00906353e+01 -3.37654190e+01 -3.71044807e+01 -1.77460957e+01 -2.36046314e+01 -3.45864601e+01 -1.08133612e+01 2.70847321e+01 4.41387100e+01 6.80703306e+00 -2.30356388e+01 -8.91817665e+00 3.59907341e+01 8.66223621e+00 -1.70456436e+02 -3.01992737e+02 -4.74660553e+02 -4.48880524e+02 -4.99268213e+03 -1.39724590e+04 1.32154268e+04 5.17507471e+03 -6.69870801e+03 -9.00275757e+02 -1.28611877e+03 -2.22937246e+04 8.62917427e+09 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. 0. 0. -5.72994478e+10 230083248. -140996784. -43314828. -1.59190781e+04 -6.46976855e+03 -8.96385071e+02 -2.98797668e+02 -9.08916931e+01 -4.95646362e+01 -1.82326088e+01 5.87351656e+00 -4.46514015e+01 -9.02500610e+01 -5.86512184e+01 2.93384247e+01 7.55058975e+01 1.84925480e+01 -7.88853683e+01 -6.22378683e+00 1.19009628e+02 2.50121628e+02 2.70097839e+02 2.24503448e+02 1.07464409e+02 5.47769203e+01 1.18547554e+01 6.72100372e+01 4.74816475e+01 7.77863693e+01 1.62279572e+02 1.82068130e+02 1.03459091e+02 1.58114872e+01 -1.94689121e+01 -1.52650938e+01 -5.02504044e+01 -9.79122467e+01 -1.13291039e+02 -4.78983765e+01 1.10547150e+02 1.89954330e+02 1.46516190e+02 3.71126175e+01 -3.52917938e+01 -3.13290176e+01 -1.78427470e+00 4.45217438e+01 2.32517376e+01 4.28463669e+01 6.56632690e+01 4.95426102e+01 -4.08090782e+01 -1.63098663e+02 -1.48052689e+02 -2.28003359e+00 8.30411911e+01 4.43654327e+01 -4.48510551e+01 -3.61384354e+01 3.62177849e+01 3.65320969e+01 -3.23618126e+01 -1.07222435e+02 -8.14552383e+01 3.89405556e+01 1.11757072e+02 7.94554825e+01 5.89992762e+00 -5.93527985e+00 2.08106899e+01 1.66302071e+01 -4.24598770e+01 -1.03564903e+02 -7.94825516e+01 -4.09183960e+01 -5.24933052e+01 -1.01181976e+02 -1.21723785e+02 -1.02086884e+02 -4.27643166e+01 9.71121502e+00 2.80717392e+01 -1.17259588e+01 -4.15817375e+01 -3.48371391e+01 -7.85803452e+01 -1.55538162e+02 -1.93580795e+02 -1.12235207e+02 1.70046291e+01 8.09435730e+01 3.60691490e+01 -6.57751465e+01 -1.72672012e+02 -2.08036179e+02 -1.70776733e+02 -1.45941238e+02 -1.53125351e+02 -1.37296127e+02 -3.67474976e+01 3.72048912e+01 1.75628681e+01 -6.55586853e+01 -1.12469910e+02 -8.12669067e+01 -2.31431904e+01 -3.87546480e-01 -4.19985886e+01 -7.08538971e+01 -6.09761810e+01 -5.18821335e+01 -1.00697777e+02 -1.92518494e+02 -2.04909637e+02 -1.29207565e+02 -4.10296745e+01 -4.17554932e+01 -9.02753754e+01 -1.44693375e+02 -1.45682526e+02 -1.00886292e+02 -3.99593887e+01 -1.56972380e+01 -4.21434250e+01 -4.57521095e+01 -3.79291058e+00 -1.19034147e+00 -5.00988655e+01 -1.16889198e+02 -1.09762871e+02 -4.84973831e+01 -1.59130716e+01 -5.46765404e+01 -8.66038055e+01 -1.01005867e+02 -7.36997452e+01 -9.56886826e+01 -1.42772415e+02 -1.56253632e+02 -9.11449966e+01 3.60577202e+01 9.67807312e+01 4.96338081e+01 -2.39065056e+01 -5.00103760e+01 -2.34717236e+01 8.90317345e+00 5.77140808e+00 8.11405563e+00 2.77940922e+01 7.63524780e+01 9.29435120e+01 4.67514038e+01 -6.72332230e+01 -1.30117783e+02 -7.98529968e+01 -1.13782501e+01 -1.14630423e+01 -4.47825737e+01 -1.58049974e+01 6.79212875e+01 5.84804382e+01 -1.14740458e+01 -8.69297333e+01 -2.69647827e+01 9.39897537e+01 1.58299393e+02 1.09039177e+02 1.84106884e+01 -2.26618805e+01 -2.70802250e+01 -4.50712967e+01 -6.78635483e+01 -4.90262184e+01 2.33709240e+01 1.02140366e+02 6.70740280e+01 -8.48173904e+00 -8.08794937e+01 -7.15114059e+01 -3.06113873e+01 5.93636894e+00 2.86996708e+01 2.48739986e+01 4.08463974e+01 7.30105438e+01 5.67096901e+01 -2.31792545e+01 -9.35953522e+01 -7.04417038e+01 1.79027157e+01 7.64636154e+01 4.60145035e+01 -1.28570309e+01 -5.41464310e+01 -4.52043610e+01 -6.21485901e+01 -1.11285065e+02 -1.35107407e+02 -8.11137085e+01 4.65001917e+00 2.67043972e+01 -2.17310929e+00 -7.48197403e+01 -9.84899902e+01 -8.88487167e+01 -5.61484718e+01 -3.04481068e+01 -3.61415367e+01 -1.19841366e+01 1.17218180e+01 -1.20118284e+01 -6.30589027e+01 -8.93681259e+01 -7.96735840e+01 -3.84905777e+01 -2.59459877e+01 -3.93158340e+01 -4.42519722e+01 -4.73589325e+01 -2.42898083e+01 -5.35667648e+01 -9.03073273e+01 -1.10124756e+02 -1.14481705e+02 -5.57421570e+01 -2.08587952e+01 -3.90832977e+01 -9.94402237e+01 -1.14020561e+02 -7.35157623e+01 -3.12588634e+01 -3.56166801e+01 -6.05784454e+01 -6.17210655e+01 -2.57091465e+01 -2.48676376e+01 -6.26031418e+01 -9.67545929e+01 -7.12738571e+01 -4.93856659e+01 -7.15613098e+01 -8.43254166e+01 -6.58926544e+01 -4.79250298e+01 -3.30186157e+01 -4.60309029e+01 -2.13152580e+01 -1.39078255e+01 -2.04399834e+01 -1.36034288e+01 5.63382196e+00 2.19582615e+01 -2.56338921e+01 -4.90901604e+01 -5.77880287e+01 -1.93201294e+01 -2.91782627e+01 -3.27143440e+01 -2.06116104e+01 6.95501423e+00 2.12974167e+01 -3.23259697e+01 -6.34726677e+01 -7.39611511e+01 -2.69767303e+01 -1.90994720e+01 -2.86012287e+01 -4.69705963e+01 -5.18573723e+01 -1.48939209e+01 -2.83577538e+01 -4.45171204e+01 -9.08912201e+01 -1.06882095e+02 -9.72275391e+01 -6.14993286e+01 -3.26209373e+01 -5.28200150e+01 -8.31357727e+01 -9.73523712e+01 -7.72523880e+01 -9.43493423e+01 -9.35089874e+01 -7.15463333e+01 -2.92245960e+01 -2.83785076e+01 -7.80611572e+01 -9.80068741e+01 -7.55384827e+01 -3.28339310e+01 -4.72684097e+01 -7.27804031e+01 -8.43652496e+01 -7.44228134e+01 -5.15358696e+01 -5.01148300e+01 -4.09063797e+01 -6.70215988e+01 -8.41667328e+01 -8.78459473e+01 -6.28243103e+01 -5.00124397e+01 -6.53333435e+01 -8.48495560e+01 -8.77045670e+01 -9.53042831e+01 -1.28022339e+02 -1.42290955e+02 -1.36018311e+02 -1.26321426e+02 -1.28368866e+02 -1.44865494e+02 -1.45332809e+02 -1.31060165e+02 -9.35470200e+01 -8.11904678e+01 -7.43867645e+01 -8.06098938e+01 -7.32612610e+01 -5.27374382e+01 -4.18736839e+01 -3.64018784e+01 -6.10356522e+01 -7.23462830e+01 -7.61190491e+01 -6.74841766e+01 -7.36587296e+01 -8.17705078e+01 -9.38534927e+01 -9.01448212e+01 -9.17717972e+01 -1.09218048e+02 -1.19351891e+02 -1.12639252e+02 -8.82075272e+01 -8.30692291e+01 -8.20087814e+01 -6.33954773e+01 -4.96317482e+01 -4.07964478e+01 -6.45893860e+01 -6.60972519e+01 -6.97975006e+01 -8.11783600e+01 -8.16285629e+01 -6.82797775e+01 -3.86091728e+01 -3.30068626e+01 -5.67303810e+01 -7.73322525e+01 -7.47739105e+01 -5.48121300e+01 -3.92525330e+01 -4.84272537e+01 -6.59031296e+01 -8.18961868e+01 -8.01511307e+01 -6.67900925e+01 -5.48895950e+01 -3.94038811e+01 -3.74001236e+01 -3.70695076e+01 -3.32461624e+01 -3.37153625e+01 -3.30482101e+01 -5.40681190e+01 -5.51346283e+01 -5.60514603e+01 -5.56482773e+01 -5.41953049e+01 -4.48503799e+01 -1.67101860e+01 -1.19714804e+01 -3.08938484e+01 -6.67528534e+01 -8.26218185e+01 -6.40463867e+01 -3.92444992e+01 -3.74685707e+01 -6.42405319e+01 -8.97342377e+01 -8.38901749e+01 -5.92235069e+01 -4.44309540e+01 -4.65406532e+01 -6.24864082e+01 -6.27190018e+01 -5.27228241e+01 -4.43398857e+01 -4.06389236e+01 -5.43645287e+01 -5.47817001e+01 -4.95168610e+01 -4.32970314e+01 -4.34172516e+01 -5.09953003e+01 -4.67913742e+01 -4.65372543e+01 -5.78510170e+01 -7.15299225e+01 -6.98061142e+01 -4.94250336e+01 -3.64109306e+01 -4.24487534e+01 -5.70631027e+01 -6.48694687e+01 -6.21235733e+01 -5.38452530e+01 -5.03232613e+01 -4.88275604e+01 -5.59980125e+01 -5.66210938e+01 -5.58006325e+01 -5.25446854e+01 -5.04107666e+01 -5.49202271e+01 -5.83580284e+01 -6.28166618e+01 -6.26777725e+01 -6.04455986e+01 -5.67366524e+01 -5.12161713e+01 -4.97468834e+01 -5.35815620e+01 -6.01285248e+01 -6.31408195e+01 -6.03255386e+01 -5.52801399e+01 -5.42711563e+01 -5.72444725e+01 -6.00189514e+01 -5.94964142e+01 -5.74791222e+01 -5.68424301e+01 -5.70602684e+01 -5.72310410e+01 -5.71144600e+01 -5.73182411e+01 -5.79841881e+01 -5.90803795e+01 -5.94662895e+01 -6.07270622e+01 -6.09912186e+01 -5.97792664e+01 -5.67397079e+01 -5.53499298e+01 -5.80644798e+01 -6.12852478e+01 -6.05456009e+01 -5.53396416e+01 -5.05460129e+01 -5.18781548e+01 -5.83777657e+01 -6.07413406e+01 -5.78995743e+01 -5.14006081e+01 -5.20738297e+01 -5.75246353e+01 -6.36133881e+01 -6.81398239e+01 -6.37199249e+01 -6.31818886e+01 -6.06950760e+01 -6.21298561e+01 -6.35246544e+01 -6.55673599e+01 -7.06128540e+01 -6.60104904e+01 -5.82481956e+01 -4.91206932e+01 -5.32718582e+01 -6.59660873e+01 -7.58339767e+01 -6.80511551e+01 -5.34176903e+01 -4.34498024e+01 -4.38627472e+01 -5.50920372e+01 -6.02951164e+01 -6.31214752e+01 -5.68198624e+01 -6.00410500e+01 -6.60959549e+01 -7.40650482e+01 -8.28091965e+01 -7.89426270e+01 -6.49816895e+01 -5.08401146e+01 -4.99014702e+01 -5.58703194e+01 -6.35538673e+01 -7.59801559e+01 -8.31173096e+01 -6.77782211e+01 -4.19710426e+01 -2.86883869e+01 -4.70462036e+01 -6.94464417e+01 -6.97759171e+01 -4.29906197e+01 -1.63037739e+01 -2.11608486e+01 -5.34278107e+01 -8.81999359e+01 -1.01921997e+02 -8.06456451e+01 -6.26608849e+01 -6.11795769e+01 -7.15421295e+01 -7.95273361e+01 -6.86255951e+01 -7.12302399e+01 -6.55579224e+01 -5.37512779e+01 -4.70828629e+01 -4.55783806e+01 -6.61888962e+01 -6.43357925e+01 -4.17247047e+01 -1.35462704e+01 -1.52802439e+01 -6.10489883e+01 -9.46047668e+01 -8.62035370e+01 -4.54905853e+01 -1.71497192e+01 -1.54017811e+01 -4.91374588e+01 -8.23720856e+01 -9.63253937e+01 -7.18694000e+01 -5.17297287e+01 -3.60287247e+01 -3.65226822e+01 -4.28733864e+01 -4.20420074e+01 -3.96390266e+01 -1.59360819e+01 -5.20963609e-01 -6.70393944e-01 -2.04167500e+01 -5.74473991e+01 -7.05977707e+01 -4.84704170e+01 -1.18792467e+01 -1.81806505e+00 -2.21612682e+01 -5.94854622e+01 -5.95003128e+01 -3.24609184e+01 5.80504704e+00 1.43809156e+01 -2.61342907e+01 -6.69049454e+01 -8.36803131e+01 -5.39895134e+01 -2.27181110e+01 -2.30227623e+01 -4.08545303e+01 -6.53080368e+01 -7.11295013e+01 -7.39282455e+01 -5.96645546e+01 -3.13241692e+01 -2.19194813e+01 -4.94872208e+01 -1.01051048e+02 -1.19313576e+02 -8.83256683e+01 -4.85859680e+01 -2.06555538e+01 -3.68114281e+01 -6.87347870e+01 -9.20797958e+01 -8.38891373e+01 -5.46338272e+01 -4.91240997e+01 -6.94400177e+01 -9.61192398e+01 -1.01443275e+02 -6.20783463e+01 -3.31771431e+01 -3.69285469e+01 -6.94063110e+01 -1.09086563e+02 -1.11254295e+02 -1.05878777e+02 -8.91161270e+01 -6.48418198e+01 -5.23865356e+01 -4.57421722e+01 -8.34134064e+01 -1.08635902e+02 -9.77722626e+01 -6.68086777e+01 -3.57714005e+01 -6.06116524e+01 -9.39560776e+01 -1.12337936e+02 -7.06363754e+01 1.25116692e+01 4.74779472e+01 5.14647007e+00 -9.64530334e+01 -1.44269775e+02 -1.03527832e+02 -3.12275200e+01 -1.59481468e+01 4.16837692e-01 4.58180122e+01 8.30794334e+00 -1.76758194e+02 -1.86412888e+02 3.98583679e+01 1.78901953e+03 2.78590039e+03 -4.55772736e+02 -9.41168457e+02 -6.62357666e+03 -6.13413516e+04 1533132160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -914026496. -423721024. 530500992. -1351590528. -1.23915878e+10 246353968. 636666944. 1.10055088e+04 4.54575342e+03 4.15053131e+02 9.33286819e+01 1.82015427e+02 8.65165024e+01 -3.88666306e+01 -9.75642090e+01 -9.06704025e+01 -1.42327309e+01 3.01547031e+01 1.55865526e+01 -6.91494675e+01 -1.42713211e+02 -1.34299973e+02 -8.12066193e+01 -6.44792557e+01 -6.16296082e+01 -5.50660744e+01 -1.88959808e+01 -4.63173485e+01 -6.29027519e+01 -4.40513849e+00 3.80445633e+01 5.19065046e+00 -1.07921349e+02 -1.67358124e+02 -9.02252884e+01 -1.66311324e+00 5.66947327e+01 1.92629986e+01 -8.69459229e+01 -1.71927216e+02 -2.12812332e+02 -1.30567429e+02 -7.05713043e+01 -6.42389526e+01 -1.27521255e+02 -1.64302811e+02 -1.25463524e+02 -1.12840446e+02 -7.60230713e+01 -4.00914688e+01 -2.38825760e+01 -6.19766312e+01 -1.75068130e+02 -1.80325104e+02 -7.93592911e+01 3.87506981e+01 7.42117462e+01 -2.88281364e+01 -1.25848740e+02 -1.27189796e+02 -5.77238312e+01 -2.36244717e+01 -9.04552231e+01 -1.95491531e+02 -2.32937973e+02 -1.89836533e+02 -6.56114883e+01 1.83015308e+01 1.52958097e+01 -5.80639305e+01 -1.60990646e+02 -2.29177444e+02 -2.63022705e+02 -2.28706177e+02 -1.61316620e+02 -9.99404297e+01 -7.06614609e+01 -1.01705757e+02 -9.16745224e+01 -1.55774479e+01 5.77316360e+01 5.93115578e+01 -3.10270329e+01 -9.92334442e+01 -8.34725723e+01 -4.23371887e+01 2.27266045e+01 6.24135780e+01 2.34970627e+01 -7.26254425e+01 -1.36083267e+02 -7.89216919e+01 -3.00837040e+00 -9.04400063e+00 -4.23627930e+01 -6.66823349e+01 -4.24878540e+01 -7.03508301e+01 -5.75025024e+01 -1.94550915e+01 1.22910805e+01 -1.91127815e+01 -1.30568237e+02 -1.41638412e+02 -3.67860909e+01 1.02347885e+02 1.47560379e+02 6.12964172e+01 -4.51432266e+01 -7.97565308e+01 -6.19441566e+01 -2.25228786e+01 -2.39129925e+01 -5.04886322e+01 -1.06748238e+02 -1.39706680e+02 -7.96433716e+01 3.12372265e+01 5.82381363e+01 1.47689209e+01 -2.86503010e+01 -2.75932827e+01 -6.40558853e+01 -6.28269310e+01 2.45728951e+01 1.27770996e+02 1.25145416e+02 -1.11157351e+01 -7.28612823e+01 7.89086914e+00 1.22826363e+02 1.39329254e+02 3.24917870e+01 -7.87541275e+01 -1.08447235e+02 -7.22607727e+01 1.90126629e+01 9.48763428e+01 6.57382050e+01 -2.81623878e+01 -1.04783722e+02 -3.84684067e+01 6.60365219e+01 9.92702179e+01 6.53400192e+01 1.72860031e+01 -1.57422819e+01 -7.72992249e+01 -1.01021431e+02 -6.72392044e+01 -1.33610392e+01 -8.45336437e+00 -7.43635483e+01 -1.14807159e+02 -4.89254875e+01 8.32276306e+01 1.85432755e+02 1.45253174e+02 9.45168209e+00 -9.45269775e+01 -8.60855789e+01 -1.37149563e+01 2.37239552e+01 2.07065892e+00 -1.33691015e+01 -6.32134323e+01 -4.84553490e+01 -2.98088837e+01 1.48186827e+01 7.25918961e+01 1.11156029e+02 1.21159332e+02 4.26501007e+01 -2.62780118e+00 5.19881821e+01 1.10440567e+02 7.25980759e+01 -4.28259125e+01 -1.11173820e+02 -6.28351135e+01 -1.26203794e+01 4.03331337e+01 4.22939720e+01 7.05691576e+00 -1.31747026e+01 -2.13174686e+01 5.44225998e+01 3.77752457e+01 -8.93730354e+00 -8.24326477e+01 -1.57499481e+02 -2.02658936e+02 -2.39528488e+02 -1.56679321e+02 -3.94390717e+01 1.91761513e+01 1.76923885e+01 -5.32680359e+01 -4.93916855e+01 1.52517910e+01 1.01235085e+02 1.55184006e+02 4.50338364e+01 -9.30863190e+01 -1.78196518e+02 -1.35578796e+02 -6.65397110e+01 -4.03145447e+01 -4.70583801e+01 -7.07861862e+01 -1.07689140e+02 -7.23689728e+01 -1.02900362e+01 4.01883163e+01 -5.31003094e+00 -2.59016724e+01 -4.94525795e+01 -7.92755585e+01 -9.76865845e+01 -6.49602890e+01 -3.00088749e+01 -2.51144447e+01 -3.00918274e+01 1.44311247e+01 7.16548691e+01 1.15985008e+02 1.30876114e+02 6.23900452e+01 1.87530060e+01 -7.21837616e+01 -7.55344849e+01 -2.60614700e+01 5.52620659e+01 7.41817780e+01 1.73536167e+01 -1.38443136e+01 -1.17028475e+01 -3.61702561e+00 -1.00866261e+01 5.83523571e-01 5.89573956e+00 8.50361633e+00 8.53581619e+00 2.92473578e+00 5.93385744e+00 1.64924698e+01 4.13115005e+01 4.46224632e+01 2.95986710e+01 1.47723017e+01 2.74554577e+01 4.53989334e+01 3.40208588e+01 9.10937500e+00 -3.09047775e+01 -4.76960907e+01 -3.50129967e+01 -1.84688206e+01 9.58905506e+00 -1.47373068e+00 -1.70708513e+00 6.00928724e-01 1.67900829e+01 1.47044325e+01 1.38824463e+01 9.89562130e+00 2.77253437e+01 3.02030277e+01 3.32015953e+01 1.97462387e+01 3.35470009e+01 4.12768402e+01 6.32815628e+01 6.31440468e+01 4.75995827e+01 3.25503159e+01 1.97478561e+01 2.77293015e+01 3.62209435e+01 5.58938255e+01 4.84096718e+01 4.91250420e+01 1.58827801e+01 4.34266615e+00 1.71863213e+01 3.16750565e+01 3.04461098e+01 1.42074232e+01 1.63685513e+01 2.59466438e+01 1.35206337e+01 1.60096569e+01 2.74385967e+01 3.50470581e+01 2.22698441e+01 1.30121670e+01 2.40045910e+01 1.32291603e+01 -1.39482117e+01 -2.18495216e+01 -3.91363955e+00 4.10809755e+00 -1.16184511e+01 -1.41487942e+01 -1.50622215e+01 -7.45718718e+00 -2.28901505e+00 1.27776165e+01 1.65030632e+01 3.69446135e+00 8.28666210e+00 1.38505802e+01 1.46048260e+01 1.24504805e+01 3.72557640e+01 7.14952011e+01 6.37998428e+01 4.16490402e+01 2.15689278e+01 2.05241566e+01 2.04869518e+01 1.48116102e+01 1.88983669e+01 5.98966074e+00 -2.36136746e+00 -1.23866189e+00 -5.82161331e+00 -1.25019417e+01 -1.93696747e+01 2.19927826e+01 2.37947903e+01 2.68344307e+01 1.48164473e+01 2.50590954e+01 2.18874855e+01 9.75800610e+00 6.63693476e+00 9.29894298e-02 -9.58357430e+00 -1.68800187e+00 8.51273918e+00 3.25332260e+01 2.07141037e+01 1.66483955e+01 -3.83761215e+00 -3.25824594e+00 1.91268692e+01 3.49496078e+01 3.83145027e+01 8.95917511e+00 5.11486435e+00 1.57440224e+01 2.72927437e+01 3.84546967e+01 3.65744781e+01 4.55159492e+01 4.85568275e+01 6.37698555e+01 6.32336502e+01 4.73420944e+01 2.27330894e+01 1.47833805e+01 2.23308735e+01 3.31794815e+01 3.37896042e+01 4.17550316e+01 4.74081154e+01 5.65726280e+01 5.19221802e+01 3.48714981e+01 3.89931679e+01 7.45190964e+01 1.16674019e+02 1.02856636e+02 6.34514351e+01 1.74238129e+01 4.30522614e+01 6.46463776e+01 8.10021286e+01 6.19836044e+01 3.77268677e+01 5.05325050e+01 6.68784561e+01 7.93168564e+01 7.07764587e+01 6.43686752e+01 7.92600174e+01 9.69932785e+01 1.00569283e+02 7.76343307e+01 4.66008682e+01 4.04462433e+01 5.38628197e+01 6.10458069e+01 6.08374519e+01 3.73335686e+01 4.47282562e+01 6.44270325e+01 9.91005020e+01 8.37865677e+01 5.78905334e+01 2.90484333e+01 4.11994820e+01 4.64355698e+01 4.04721947e+01 1.17162724e+01 -2.54988213e+01 -2.10406551e+01 7.20418978e+00 4.42159309e+01 4.95146179e+01 5.56929359e+01 7.44519958e+01 8.62907257e+01 4.19497185e+01 -1.16499891e+01 -2.18262539e+01 1.86375370e+01 5.30769272e+01 4.39580345e+01 3.32402458e+01 1.69323978e+01 6.10187531e+00 1.85246067e+01 3.60181732e+01 6.31246948e+01 6.11654167e+01 7.32823029e+01 3.93369370e+01 -7.92572927e+00 -2.22558346e+01 1.09963155e+00 4.42262306e+01 7.24240799e+01 9.20028915e+01 9.34392776e+01 6.67452393e+01 5.09285164e+01 4.05217590e+01 3.65256462e+01 3.69507141e+01 2.96468678e+01 2.62821407e+01 2.78184662e+01 2.90427418e+01 4.41235008e+01 8.63042374e+01 1.92819168e+02 2.92104095e+02 2.75631195e+02 2.81637177e+02 2.60556976e+02 4.08300537e+02 2.16225937e+02 1.47164658e+02 -1.84251251e+02 1.41490918e+03 2.33700989e+02 9.46768799e+02 3.28826147e+03 -2.45517944e+03 -1.37887129e+04 -3.13007383e+04 569123392. 3.30910413e+09 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. 0. 0. 0. 0. 0. 0. -8.94549770e+10 -8.94549770e+10 993453312. 1566925568. 1248277632. 524154048. 1.80504980e+04 6.89924219e+03 2.02456006e+03 4.01787262e+02 3.33315765e+02 1.38010452e+02 9.19312973e+01 7.59334106e+01 7.47323074e+01 7.49962082e+01 7.55176086e+01 7.70091095e+01 4.57441521e+01 -2.67646198e+01 -7.41965027e+01 -4.88823853e+01 -2.22229805e+01 2.08933887e+01 1.17082214e+02 1.70309692e+02 1.60826843e+02 1.39168304e+02 1.61901993e+02 2.10705536e+02 1.45890488e+02 1.70214401e+02 1.56169128e+02 1.32917801e+02 7.25429840e+01 5.25222092e+01 4.25717010e+01 3.42034454e+01 2.56421432e+01 1.76442852e+01 1.45770168e+01 2.03896122e+01 3.11853428e+01 3.37214508e+01 3.44430428e+01 2.96171646e+01 2.58791580e+01 2.01997929e+01 2.48702793e+01 4.27370186e+01 6.48722382e+01 7.01465683e+01 6.32843475e+01 5.23484764e+01 4.92707481e+01 4.07888908e+01 4.18054962e+01 4.51650658e+01 4.77240181e+01 4.28677025e+01 3.84598770e+01 3.84425430e+01 3.22094383e+01 4.15325279e+01 4.84053612e+01 5.54079514e+01 5.48217316e+01 5.87461281e+01 6.10794296e+01 5.78653679e+01 5.29792595e+01 5.35827713e+01 5.15055504e+01 3.99371872e+01 3.60637398e+01 3.82110329e+01 4.86254921e+01 5.19855843e+01 5.26022110e+01 6.14841309e+01 7.49977417e+01 7.07168274e+01 6.54301300e+01 5.79236450e+01 7.89450378e+01 9.24369431e+01 9.05493164e+01 7.84109802e+01 6.96613846e+01 7.24234390e+01 7.32604218e+01 6.97552338e+01 7.15040665e+01 7.82338562e+01 8.76673279e+01 8.42931061e+01 6.93791122e+01 5.62161407e+01 5.15127487e+01 5.50332603e+01 5.73819084e+01 6.03823891e+01 5.20978317e+01 4.42724876e+01 4.92516327e+01 6.08119659e+01 6.42079315e+01 5.57429543e+01 4.93053284e+01 6.14819717e+01 7.08763351e+01 6.92714462e+01 5.65356445e+01 4.59918365e+01 4.57099724e+01 4.74454460e+01 4.96078186e+01 5.02305641e+01 5.36355247e+01 5.53832779e+01 5.46406021e+01 5.41583939e+01 5.57906876e+01 5.76244087e+01 5.56044540e+01 5.34925461e+01 5.35449409e+01 5.52694778e+01 5.66171494e+01 6.33560867e+01 6.93842392e+01 6.81408691e+01 6.14689484e+01 5.66432343e+01 6.34981499e+01 7.03607178e+01 7.01595535e+01 6.48426895e+01 5.96730270e+01 5.88230247e+01 5.84421387e+01 5.60954094e+01 5.73832054e+01 5.79092293e+01 5.84821777e+01 5.68213120e+01 5.47360077e+01 5.53523560e+01 5.62968483e+01 5.78542976e+01 5.73425217e+01 5.72495003e+01 5.75714226e+01 5.94008904e+01 6.25587349e+01 6.55667496e+01 6.48523788e+01 6.24447708e+01 5.91481476e+01 6.09139633e+01 6.28768921e+01 6.24637642e+01 5.95014534e+01 5.70285988e+01 5.72753448e+01 5.78118744e+01 5.82281532e+01 5.79912949e+01 5.78819351e+01 5.76345329e+01 5.73496132e+01 5.73395157e+01 5.77232475e+01 5.81599045e+01 5.79056816e+01 5.75243530e+01 5.72527428e+01 5.72336578e+01 5.72414780e+01 5.70153732e+01 5.65009689e+01 5.63081322e+01 5.64998360e+01 5.68280334e+01 5.67149696e+01 5.70571098e+01 5.63073044e+01 5.45926132e+01 5.37441826e+01 5.45893021e+01 5.62926064e+01 5.64898605e+01 5.60985756e+01 5.63242874e+01 5.62777557e+01 5.58456306e+01 5.56053925e+01 5.25490913e+01 4.92654266e+01 4.89639778e+01 5.19122124e+01 5.51241035e+01 5.37762947e+01 5.37273026e+01 5.05430756e+01 4.74323120e+01 4.77314491e+01 5.28983040e+01 5.78147087e+01 5.59243011e+01 5.44406700e+01 5.36316719e+01 5.56646729e+01 5.69928246e+01 5.79169617e+01 5.76858177e+01 5.71727486e+01 5.63312454e+01 5.70251198e+01 5.72980652e+01 6.07773132e+01 6.28097420e+01 6.43869934e+01 6.37443085e+01 6.25864868e+01 6.24573326e+01 6.28976517e+01 6.28494453e+01 6.17600136e+01 6.03014412e+01 6.23451958e+01 6.11146011e+01 6.05128479e+01 6.04976540e+01 6.43062210e+01 6.51391296e+01 6.13382301e+01 5.91778831e+01 5.93216438e+01 6.16465683e+01 5.89854126e+01 5.85421715e+01 5.50618401e+01 5.51846085e+01 5.51811829e+01 6.09157028e+01 6.76507568e+01 6.21163597e+01 4.85200272e+01 4.01542549e+01 4.36013985e+01 5.01656075e+01 5.22023964e+01 5.00995369e+01 4.81339531e+01 4.44262161e+01 4.33229256e+01 4.47934875e+01 4.75641823e+01 5.21076660e+01 5.53276215e+01 5.55171585e+01 5.36514053e+01 5.02568359e+01 4.89844780e+01 4.88074226e+01 4.95738869e+01 4.90259514e+01 5.11434364e+01 5.19881821e+01 5.56677094e+01 5.14540977e+01 3.86807175e+01 2.51667652e+01 2.61186962e+01 3.66271667e+01 4.80836983e+01 5.14043503e+01 5.21329498e+01 4.67229118e+01 3.72879791e+01 3.15325298e+01 2.78927574e+01 3.81000633e+01 4.77009087e+01 5.86466179e+01 5.28772202e+01 4.79129295e+01 4.70844154e+01 5.09626160e+01 5.40295601e+01 5.70381699e+01 5.30450897e+01 4.62561531e+01 4.01386604e+01 3.92314796e+01 3.94368858e+01 2.54379044e+01 1.16624041e+01 1.69596272e+01 3.65087090e+01 5.19772949e+01 4.24052696e+01 3.36835060e+01 3.57728500e+01 3.96669044e+01 3.00754089e+01 1.36336613e+01 1.44076147e+01 3.42182808e+01 5.43890419e+01 4.81896629e+01 3.92354240e+01 3.99312820e+01 5.10957718e+01 5.27987213e+01 4.95641327e+01 4.08912582e+01 4.70664368e+01 5.83013382e+01 5.97637291e+01 5.68885918e+01 5.27318802e+01 5.92650566e+01 4.35288887e+01 2.39612789e+01 2.21414680e+01 1.73497028e+01 5.48621225e+00 -1.38754826e+01 -1.60461750e+01 -4.01097059e+00 -7.82563972e+00 5.43395472e+00 7.58384323e+00 2.58454266e+01 4.43597870e+01 6.98978729e+01 7.90926132e+01 7.10337296e+01 6.52283859e+01 5.84699478e+01 5.87683640e+01 5.60821571e+01 5.91484833e+01 6.45947876e+01 4.73454437e+01 1.75879726e+01 3.66643739e+00 1.06355524e+01 3.13270741e+01 3.60204163e+01 4.15563011e+01 5.22355499e+01 4.02424088e+01 3.53807831e+01 2.55114174e+01 2.24160175e+01 1.10410690e+01 -8.45247746e+00 1.02996922e+01 3.03873386e+01 3.83155518e+01 1.09737682e+01 4.14125395e+00 1.55428705e+01 4.26816559e+01 1.97095318e+01 -2.57737207e+00 -1.27724915e+01 7.46226645e+00 2.86694946e+01 6.85953140e+00 -1.61612587e+01 -1.01923418e+01 2.49793797e+01 5.07827034e+01 2.76837578e+01 1.20114841e+01 3.04390240e+01 6.59534149e+01 4.28726501e+01 1.90577579e+00 -1.81284122e+01 5.32373041e-03 1.27190189e+01 7.37936926e+00 -1.65214825e+01 -3.69637032e+01 -2.70049458e+01 1.62087078e+01 4.83065834e+01 4.62025642e+01 3.53319397e+01 3.45186768e+01 3.70421066e+01 3.29980507e+01 2.34461803e+01 7.18126774e+00 7.69427156e+00 2.73978939e+01 4.17764587e+01 4.75458488e+01 2.20589771e+01 3.27782536e+00 6.53200150e+00 1.74472198e+01 3.70564804e+01 2.84196701e+01 2.76458149e+01 3.59140511e+01 5.63803062e+01 5.58553047e+01 6.17596579e+00 -3.45865746e+01 1.17956734e+00 6.79825821e+01 7.20684128e+01 1.57717810e+01 -5.45880890e+00 2.86333599e+01 4.06116447e+01 1.75897636e+01 5.18882656e+00 1.48909826e+01 3.78744774e+01 2.17562542e+01 7.46174669e+00 -4.49383497e+00 1.01231880e+01 3.33008766e+01 3.22441216e+01 3.12005806e+01 5.57777834e+00 -1.24647074e+01 -1.30558100e+01 1.19205513e+01 1.26922579e+01 -4.97354851e+01 -8.11417770e+01 -6.52035370e+01 -8.82742977e+00 -4.97123671e+00 -2.29223785e+01 2.76691198e-01 5.23305168e+01 6.53823624e+01 2.88805943e+01 9.81736422e-01 1.09418459e+01 2.66033096e+01 8.11220932e+00 -1.56830251e+00 -7.73664427e+00 2.51923347e+00 2.50036621e+01 4.29989052e+01 5.08942909e+01 3.80251656e+01 2.29558926e+01 2.92678332e+00 -5.94971466e+00 -1.19879160e+01 -2.89287357e+01 -2.98209457e+01 -1.13043177e+00 2.96852169e+01 2.21513367e+01 -1.36350479e+01 -2.39736385e+01 -1.68055115e+01 -3.74353638e+01 -9.25717621e+01 -1.27981750e+02 -1.06420479e+02 -3.81710014e+01 -1.93411121e+01 -3.09228783e+01 -3.81238060e+01 -1.18351727e+01 1.76132107e+01 2.37110710e+01 3.45725708e+01 2.33839722e+01 1.07376595e+01 9.86917591e+00 3.51751823e+01 3.86375542e+01 -1.57557526e+01 -4.37650223e+01 -1.87185822e+01 1.53363113e+01 -1.95736065e+01 -4.58013954e+01 -1.09002132e+01 5.62199669e+01 1.01030609e+02 8.66125565e+01 8.00001907e+01 6.23213043e+01 6.41303406e+01 5.79378624e+01 6.10971832e+01 4.05382881e+01 1.85999813e+01 2.23234730e+01 5.88788261e+01 4.27171936e+01 -3.42427177e+01 -8.43271255e+01 -9.61153946e+01 -7.42508316e+01 -4.73588676e+01 -7.43623400e+00 2.02849674e+01 1.99545879e+01 2.53198109e+01 2.71793079e+01 2.24924908e+01 1.01923094e+01 1.31157417e+01 1.12359514e+01 8.57535744e+00 1.26670771e+01 1.28563862e+01 1.14016619e+01 -2.94159679e+01 -7.21900406e+01 -7.07443161e+01 -3.41473732e+01 -4.50645256e+00 -7.72697735e+00 -4.64526033e+00 -6.65970945e+00 -2.72405863e+00 -8.95497513e+00 -1.01486387e+01 -3.86402435e+01 -7.23724747e+01 -5.85096703e+01 -1.47770281e+01 -4.32702065e+00 -7.68794403e+01 -1.28894394e+02 -9.86103745e+01 -2.60457630e+01 -2.10401402e+01 -5.10350304e+01 -5.10392380e+01 -1.72613869e+01 1.52580738e+01 -1.86220112e+01 -5.11233139e+01 -8.66380844e+01 -9.81605530e+01 -5.92335167e+01 -1.78265305e+01 -2.14901390e+01 -1.01541153e+02 -1.38327850e+02 -8.68992767e+01 -1.38468552e+01 -2.87217503e+01 -8.39092636e+01 -9.81223450e+01 -6.56853867e+01 -3.12772503e+01 -5.55573883e+01 -8.23519669e+01 -9.50256729e+01 -6.93364182e+01 -3.83541183e+01 -2.14287758e+01 -6.20528259e+01 -1.08050575e+02 -1.12951683e+02 -8.02095184e+01 -2.03324871e+01 -4.99027252e+01 -8.02584229e+01 -9.50801849e+01 -6.28200035e+01 -5.86851349e+01 -9.63774185e+01 -8.81984177e+01 -4.64439812e+01 9.68103504e+00 1.61314850e+01 2.40142479e+01 -1.53879499e+01 -5.92801323e+01 -8.03693161e+01 -5.57179298e+01 -2.00573292e+01 3.39447570e+00 -3.82021451e+00 -6.64692383e+01 -2.93143158e+02 -4.95245697e+02 -6.33640198e+02 -5.38176880e+02 -2.96952881e+03 -4.52245947e+03 5.38963672e+03 1.70928931e+03 -3.24928345e+03 -1.77186133e+03 -2.43098413e+03 -1.43347305e+04 -3.87784766e+04 25046594. -8.42500710e+09 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. 0. -1.06434068e+10 -31487976. -31614706. 3.41439961e+04 1.39529121e+04 4.63979102e+03 9.91061951e+02 5.28219116e+02 4.95315132e+01 -8.39189224e+01 -9.10445862e+01 -2.25636024e+01 2.76125717e+00 -3.03889370e+01 7.00950098e+00 8.91233139e+01 1.48559418e+02 7.07961884e+01 -9.22786942e+01 -1.60337234e+02 -1.05218666e+02 -1.21789789e+01 3.32471619e+01 4.38650036e+00 -7.64467859e+00 1.13233004e+01 5.29362526e+01 1.96042881e+01 -5.23957100e+01 -8.17230911e+01 -5.03969994e+01 2.10718479e+01 3.93224487e+01 -1.36454411e+01 -9.80137711e+01 -1.31297760e+02 -8.33707199e+01 -8.42687454e+01 -1.37207458e+02 -1.12579063e+02 -7.23909473e+00 6.30643425e+01 -1.33545513e+01 -1.82290649e+02 -2.26659088e+02 -1.48267242e+02 -5.34253006e+01 -1.69405537e+01 -1.87106533e+01 -3.39057198e+01 -3.44844437e+01 -2.38197689e+01 -3.65873489e+01 -1.46204758e+02 -2.16840439e+02 -1.79382507e+02 -7.37277222e+01 -1.42967644e+01 -5.82650909e+01 -1.24763588e+02 -1.53541199e+02 -8.80500793e+01 -7.02580109e+01 -9.99954071e+01 -7.82603455e+01 -7.75974941e+00 6.05009804e+01 5.20472069e+01 -6.23467140e+01 -9.62220764e+01 -6.53669205e+01 1.77498074e+01 -6.09334230e-01 -6.74181061e+01 -4.64862022e+01 7.34775972e+00 3.92631187e+01 -9.76821613e+00 -1.08507034e+02 -1.57630478e+02 -1.21757599e+02 -2.06280994e+01 3.89145737e+01 1.79113960e+01 -2.21421299e+01 -9.96437931e+00 3.59216385e+01 2.01848068e+01 -4.34604950e+01 -7.36045456e+01 -7.49807978e+00 8.09211044e+01 8.69108047e+01 -1.06501169e+01 -9.05495148e+01 -1.00821899e+02 -3.16026192e+01 -2.50540619e+01 -3.73590240e+01 5.19271469e+00 9.11532211e+01 1.28353897e+02 5.19448814e+01 -7.28001022e+01 -1.34844116e+02 -1.02538849e+02 -2.91324139e+01 4.35061951e+01 9.31298294e+01 8.46504440e+01 7.11728210e+01 7.49664459e+01 5.11155357e+01 -2.50154324e+01 -9.79713287e+01 -5.55718002e+01 5.07109871e+01 1.03602722e+02 6.01502838e+01 -5.43940163e+01 -1.09076073e+02 -6.59985962e+01 -1.15306664e+01 -3.10606456e+00 -4.30152082e+00 3.91424484e+01 1.28825684e+02 1.20525871e+02 3.78364220e+01 -5.38612938e+01 -5.39699516e+01 8.31365490e+00 5.14961281e+01 5.77211418e+01 2.49790497e+01 -1.74377270e+01 -3.74030952e+01 1.67163429e+01 4.19354858e+01 6.03158522e+00 -4.22844658e+01 -5.41276245e+01 -2.76345501e+01 -2.36938610e+01 -5.07101555e+01 -4.94286613e+01 -2.24670944e+01 1.26841297e+01 1.54327612e+01 -2.55560150e+01 -4.09051781e+01 -1.22854071e+01 1.84870415e+01 -1.90961018e+01 -1.36110474e+02 -1.91478821e+02 -1.15058479e+02 -1.49191637e+01 3.27422428e+00 -4.58199196e+01 -7.99730606e+01 -7.24821091e+01 -7.20261993e+01 -1.06117767e+02 -1.60199112e+02 -1.83967300e+02 -1.57324814e+02 -8.35841446e+01 -3.38760567e+01 -7.11242447e+01 -1.00558601e+02 -8.73268661e+01 -4.01982117e+01 -6.66385040e+01 -1.48718781e+02 -1.49721420e+02 -1.18206787e+02 -8.11069565e+01 -1.17026917e+02 -2.09818726e+02 -2.55517822e+02 -2.06757248e+02 -9.85018463e+01 -5.33286781e+01 -6.40290070e+01 -6.19163551e+01 -2.91595535e+01 -4.53023987e+01 -1.06905121e+02 -1.78469452e+02 -1.61702362e+02 -1.02873589e+02 -2.95816636e+00 2.79139366e+01 7.01389647e+00 -6.39811592e+01 -1.08205292e+02 -1.10679276e+02 -1.28407104e+02 -1.55767517e+02 -1.37504349e+02 -7.75018463e+01 -1.86141148e+01 -5.91208534e+01 -1.45094910e+02 -1.96877716e+02 -1.36420242e+02 -3.94907379e+01 -1.79188180e+00 -4.51579018e+01 -9.94205322e+01 -7.42297211e+01 -3.10665855e+01 -3.96038742e+01 -1.00583397e+02 -1.23944542e+02 -7.37759628e+01 1.99580133e+00 1.52103434e+01 -1.92427750e+01 -5.60734673e+01 -5.11646690e+01 -3.62105408e+01 -4.50570068e+01 -7.16138611e+01 -5.05551376e+01 -1.42263889e+01 -7.46399117e+00 -1.79843388e+01 -5.63278160e+01 -6.82293930e+01 -5.40140953e+01 -5.72127113e+01 -5.13385963e+01 -8.54708710e+01 -5.31067810e+01 -2.71820259e+01 -7.11473799e+00 -2.82472992e+01 -1.04707085e+02 -1.42930191e+02 -1.33903915e+02 -4.72495308e+01 -4.62528849e+00 2.87965631e+00 -3.04910984e+01 -5.14508629e+01 -3.08207436e+01 -3.21330223e+01 -5.94069519e+01 -7.62537231e+01 -5.21453934e+01 -3.08351879e+01 -7.60117645e+01 -1.33397110e+02 -1.24195503e+02 -8.88772812e+01 -7.10332642e+01 -8.80458069e+01 -1.28692871e+02 -9.02021103e+01 -6.74162445e+01 -3.86920624e+01 -5.69673538e+01 -1.00149269e+02 -1.21215591e+02 -1.37954056e+02 -1.01532227e+02 -8.46299438e+01 -7.41479263e+01 -1.02283997e+02 -1.04725441e+02 -1.03941956e+02 -1.08614754e+02 -1.27282204e+02 -1.39865692e+02 -9.71434097e+01 -6.99485168e+01 -6.69271622e+01 -1.03233200e+02 -9.77586975e+01 -8.33203964e+01 -6.70210266e+01 -5.32960320e+01 -6.25123901e+01 -5.94428253e+01 -9.50363998e+01 -1.08797157e+02 -1.16352264e+02 -1.11805656e+02 -9.80146179e+01 -8.75520172e+01 -5.04204636e+01 -3.51831207e+01 -4.39335403e+01 -9.98374786e+01 -1.10572067e+02 -9.80656967e+01 -8.30922623e+01 -8.50435104e+01 -7.36358337e+01 -2.55283470e+01 -8.92343044e+00 -2.81086464e+01 -8.24968338e+01 -9.49684448e+01 -7.72221756e+01 -4.96855659e+01 -4.55479927e+01 -7.25771484e+01 -7.51567307e+01 -8.03501892e+01 -5.39345779e+01 -4.22462387e+01 -4.23178825e+01 -6.39785805e+01 -7.45427475e+01 -5.42455101e+01 -3.49442749e+01 -4.81427155e+01 -7.89892426e+01 -7.04865112e+01 -5.51967201e+01 -5.38601265e+01 -6.93388519e+01 -6.76951447e+01 -4.06366196e+01 -3.07913399e+01 -4.09897652e+01 -7.14930267e+01 -7.18095703e+01 -6.58973541e+01 -5.32335892e+01 -6.07488747e+01 -7.09888458e+01 -6.79377213e+01 -6.97710876e+01 -5.39715958e+01 -4.82470703e+01 -4.81373329e+01 -6.33417206e+01 -6.62298660e+01 -5.86180153e+01 -4.68169098e+01 -5.66650238e+01 -7.70730667e+01 -8.19442291e+01 -8.38676300e+01 -9.10809784e+01 -1.09220985e+02 -1.03427162e+02 -8.59844284e+01 -8.23532486e+01 -9.28254395e+01 -1.06830124e+02 -8.76745987e+01 -7.95402527e+01 -6.99312439e+01 -5.96131248e+01 -5.45940247e+01 -6.57018585e+01 -9.37270126e+01 -1.01236267e+02 -8.02286758e+01 -6.31074982e+01 -7.43057251e+01 -9.73179932e+01 -1.11248535e+02 -9.50638428e+01 -8.36755524e+01 -8.61426010e+01 -9.39508896e+01 -1.03062263e+02 -1.11868958e+02 -1.25956528e+02 -1.21466537e+02 -1.06684952e+02 -1.02610657e+02 -1.08445930e+02 -1.16144440e+02 -9.73887634e+01 -8.87819443e+01 -8.35419693e+01 -8.61604538e+01 -8.95625076e+01 -9.76039734e+01 -1.17843559e+02 -1.21125481e+02 -1.03773438e+02 -7.62866364e+01 -7.09899521e+01 -9.26702652e+01 -1.10052979e+02 -1.09448250e+02 -9.50761795e+01 -8.86909256e+01 -9.28231812e+01 -1.03683861e+02 -1.08675751e+02 -1.02049332e+02 -8.64866486e+01 -8.22041550e+01 -8.91098862e+01 -9.85793991e+01 -1.08607521e+02 -1.07511490e+02 -1.03425774e+02 -9.10149460e+01 -8.00027542e+01 -7.59755936e+01 -8.29761658e+01 -9.59452896e+01 -1.02479378e+02 -9.55496597e+01 -8.68460388e+01 -8.70889740e+01 -9.54422913e+01 -1.02015656e+02 -9.85147629e+01 -9.01931839e+01 -8.40770721e+01 -8.36268311e+01 -8.78616333e+01 -9.06891327e+01 -9.25244980e+01 -8.89697952e+01 -8.75116806e+01 -8.62888412e+01 -8.77382126e+01 -8.83952789e+01 -8.69669647e+01 -8.59714966e+01 -8.48907700e+01 -8.51397781e+01 -8.57012100e+01 -8.61420898e+01 -8.60996857e+01 -8.55903015e+01 -8.55899887e+01 -8.69774246e+01 -8.84392395e+01 -8.77906876e+01 -8.48482132e+01 -8.24299927e+01 -8.31819382e+01 -8.49938126e+01 -8.48389740e+01 -8.24220581e+01 -8.09371185e+01 -8.03724518e+01 -8.34250488e+01 -8.61228638e+01 -8.93507156e+01 -8.97852402e+01 -8.79841614e+01 -8.49576263e+01 -8.04815063e+01 -8.03275986e+01 -8.44212570e+01 -8.93878403e+01 -8.95811691e+01 -8.34794540e+01 -7.61310043e+01 -7.85991516e+01 -8.56910477e+01 -9.03323135e+01 -8.43547058e+01 -7.35692825e+01 -7.39883423e+01 -8.12057266e+01 -9.34868317e+01 -9.34582291e+01 -8.37782593e+01 -7.50549927e+01 -6.83927383e+01 -7.96541748e+01 -8.46696854e+01 -9.00496445e+01 -8.97494888e+01 -8.90492325e+01 -8.99678116e+01 -8.36001053e+01 -8.90012054e+01 -9.64513474e+01 -9.72154617e+01 -8.58074341e+01 -6.76069031e+01 -5.80409584e+01 -6.78389282e+01 -9.37019272e+01 -1.15652412e+02 -1.13403572e+02 -8.67935562e+01 -6.08756599e+01 -5.12675285e+01 -7.05602036e+01 -9.09311218e+01 -9.77725067e+01 -8.24369507e+01 -6.34647179e+01 -6.88420029e+01 -8.18877258e+01 -9.67056427e+01 -9.89235306e+01 -9.36246033e+01 -8.02693481e+01 -6.50539703e+01 -6.72117310e+01 -8.55674515e+01 -1.10546951e+02 -1.14015564e+02 -9.32112808e+01 -6.71538620e+01 -7.16781387e+01 -9.53410187e+01 -1.09891762e+02 -9.91158447e+01 -8.36889114e+01 -7.81706543e+01 -7.24755630e+01 -8.16413040e+01 -8.96004257e+01 -8.32254791e+01 -7.97521667e+01 -6.71419983e+01 -8.23335190e+01 -9.22798843e+01 -1.11298225e+02 -1.22813675e+02 -1.08765572e+02 -9.24143524e+01 -6.48743515e+01 -5.64085388e+01 -7.16027985e+01 -9.89384613e+01 -1.02158882e+02 -7.41304016e+01 -4.36590195e+01 -4.95148621e+01 -6.96812897e+01 -1.01599503e+02 -1.08762985e+02 -9.63110352e+01 -8.00269928e+01 -6.93311310e+01 -9.41136627e+01 -1.16075134e+02 -1.42070526e+02 -1.37408112e+02 -1.04996216e+02 -1.05929146e+02 -1.16586838e+02 -1.48580429e+02 -1.51791626e+02 -1.42024063e+02 -1.17848747e+02 -7.52106400e+01 -5.99171524e+01 -7.08666611e+01 -1.09225029e+02 -1.25588463e+02 -9.21877975e+01 -5.56133080e+01 -5.15773201e+01 -9.89331818e+01 -1.30040207e+02 -1.21155594e+02 -7.70548553e+01 -4.23149338e+01 -3.71353378e+01 -7.49375610e+01 -1.18925476e+02 -1.30420074e+02 -1.25836731e+02 -1.08174576e+02 -9.25678635e+01 -6.66275406e+01 -6.44126434e+01 -7.87089462e+01 -9.22009506e+01 -7.57481384e+01 -3.92882538e+01 -1.34223442e+01 -4.46687164e+01 -9.59366608e+01 -1.19950134e+02 -8.87233276e+01 -3.38481903e+01 -2.53596535e+01 -5.38389778e+01 -1.06347397e+02 -1.13318199e+02 -8.18242645e+01 -6.46579437e+01 -5.91144295e+01 -9.27423172e+01 -1.01440971e+02 -9.68903656e+01 -8.00824738e+01 -5.08620987e+01 -6.35795555e+01 -7.09456406e+01 -1.17801643e+02 -1.53990280e+02 -1.43074799e+02 -1.20319542e+02 -7.20796585e+01 -8.88019028e+01 -1.49219925e+02 -2.10091888e+02 -2.35615875e+02 -2.41048843e+02 -5.84798401e+02 -2.34765210e+03 -1.10423938e+03 -1.34442676e+03 -3.70847290e+03 -4.55772736e+02 -9.41168457e+02 -6.62357666e+03 -6.13413516e+04 1533132160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 372310976. 244396064. -379121888. 997909696. -2.39366406e+04 -9.08108203e+03 -2.49267847e+03 -3.16111481e+02 -3.04153900e+02 -1.79770248e+02 -1.45808411e+02 -1.33262497e+02 -1.07545898e+02 -1.91032925e+01 -1.24928799e+01 -4.50616531e+01 -1.15727066e+02 -1.05394508e+02 -3.51265717e+01 3.02998829e+01 4.17779503e+01 -2.38539810e+01 -1.18763214e+02 -1.38252502e+02 -6.68706436e+01 1.41461315e+01 1.65315208e+01 -4.73260803e+01 -5.36792755e+01 -7.59240294e+00 6.25422764e+00 -2.56859798e+01 -7.43311539e+01 -7.04752045e+01 -8.49788437e+01 -1.12229446e+02 -1.13181709e+02 -6.13631287e+01 3.86999741e+01 4.32001114e+01 -1.85684433e+01 -8.17011108e+01 -7.76647949e+01 -1.08113022e+01 5.80161018e+01 5.27569275e+01 -4.25522003e+01 -1.54217392e+02 -1.45593018e+02 -3.41094894e+01 1.97491150e+01 2.20353603e+01 -4.15044212e+01 -6.38981972e+01 -7.98848419e+01 -8.93754120e+01 -6.68627014e+01 -3.51065331e+01 3.70705338e+01 9.06460476e+00 -5.10079536e+01 -7.48931046e+01 -2.71778851e+01 5.60870476e+01 5.60877495e+01 1.63929501e+01 -5.03877945e+01 -8.19153748e+01 -1.25674734e+01 8.06084213e+01 1.52016464e+02 1.19529892e+02 1.67226257e+01 -2.15245228e+01 4.19404068e+01 9.91807785e+01 9.43509750e+01 -1.06807070e+01 -4.65221481e+01 -2.36004734e+01 2.28007126e+01 2.17467041e+01 2.15307961e+01 4.94020309e+01 1.03807955e+01 -4.98408928e+01 -7.94351273e+01 -5.07844400e+00 9.96564026e+01 1.26203568e+02 9.82156982e+01 9.07979012e+00 -3.87007713e+01 -5.77699471e+01 1.34468527e+01 4.85095482e+01 4.81557884e+01 -5.66845512e+01 -9.47974243e+01 -2.21119404e+01 5.52818069e+01 5.59072685e+01 -4.04428673e+01 -8.65319443e+01 -8.13949509e+01 -6.64157867e+01 -4.83253975e+01 -9.76134872e+00 6.93684464e+01 7.01516418e+01 -1.77254677e+00 -5.69027290e+01 -5.53289337e+01 1.58304482e+01 3.22010040e+01 -1.09770012e+01 -5.40438271e+01 -1.03069405e+02 -8.42417068e+01 -5.76812792e+00 7.14818726e+01 8.58170395e+01 -2.33257732e+01 -7.84684067e+01 -3.47296638e+01 3.41533232e+00 1.41161079e+01 -3.48860130e+01 -3.33680344e+01 -2.62926521e+01 -5.58888550e+01 -6.24206009e+01 -4.71260872e+01 4.64723320e+01 3.06991291e+01 -3.58458595e+01 -9.15004272e+01 -7.14792557e+01 -1.03027515e+01 -1.55482836e+01 -6.98186951e+01 -9.52888412e+01 -1.31630295e+02 -8.22809906e+01 -1.65173512e+01 4.65055809e+01 3.87262039e+01 -3.41327896e+01 -4.86332741e+01 -2.22189465e+01 -1.31907511e+01 -2.49279747e+01 -8.32514114e+01 -1.18571968e+02 -1.46690872e+02 -1.48515472e+02 -1.07794350e+02 -5.65324974e+01 3.26420174e+01 6.63889389e+01 4.84265518e+01 -9.17814541e+00 -1.66505032e+01 5.23515854e+01 1.17148285e+02 8.88630219e+01 -1.87660294e+01 -9.59731598e+01 -8.71633911e+01 1.77573395e+01 7.08916702e+01 5.89757652e+01 -1.01035404e+01 -2.54537659e+01 1.29172783e+01 5.80569649e+00 2.29655190e+01 2.52554131e+01 2.41017838e+01 -3.79777298e+01 -1.23419601e+02 -1.15250557e+02 -9.61408768e+01 -3.03061924e+01 8.53533459e+00 3.50404320e+01 2.18702641e+01 1.75643349e+01 6.59999847e+01 1.26054642e+02 9.07410507e+01 6.41346741e+00 -9.09342346e+01 -9.78547134e+01 -2.99817963e+01 -5.10579062e+00 1.38754797e+00 -5.69065170e+01 -4.61600609e+01 1.34356852e+01 7.44049377e+01 1.18953110e+02 1.22846024e+02 1.77036819e+02 1.38604568e+02 5.08825874e+01 -2.34751320e+01 -1.50522299e+01 6.29204559e+01 6.94208984e+01 6.64226437e+00 -6.45929031e+01 -1.38476639e+02 -9.10333862e+01 1.17645578e+01 1.26304337e+02 9.53283997e+01 -4.15490961e+00 -3.38295517e+01 6.77511549e+00 2.49390545e+01 3.23302193e+01 -5.56981802e-01 -4.23283539e+01 -6.24882545e+01 -6.69534683e+01 -2.32821693e+01 1.07821150e+01 9.14764404e+01 1.13395485e+02 9.01695328e+01 4.32282333e+01 2.66171494e+01 2.21061592e+01 -1.21222858e+01 -6.31135178e+01 -6.85805740e+01 -4.60779076e+01 1.39138403e+01 2.83876801e+01 3.75374413e+01 2.45161743e+01 2.89370251e+00 -1.24897108e+01 -6.37380552e+00 2.50881386e+01 4.08711243e+01 3.39725800e+01 5.16628504e+00 8.73570824e+00 1.83777027e+01 3.81368294e+01 3.04462337e+01 2.26942844e+01 2.04420700e+01 9.37699032e+00 7.25302029e+00 -6.20385122e+00 2.04412794e+00 1.01113844e+01 2.04336681e+01 5.73343706e+00 -6.61025000e+00 -1.95103111e+01 -1.00539243e+00 2.81090045e+00 5.51426840e+00 6.60176849e+00 7.41566610e+00 6.32836640e-01 9.31199455e+00 6.08026457e+00 2.46332455e+00 -2.88368664e+01 -2.72522812e+01 -1.43881159e+01 -5.92702675e+00 -5.85346270e+00 -6.43635130e+00 -5.69721746e+00 -1.74698162e+01 -1.62340736e+01 -8.97399902e+00 1.53861630e+00 -5.97945929e+00 -4.94056988e+00 -2.45841360e+00 1.04280624e+01 9.98412991e+00 3.43553305e+00 -1.24780426e+01 -1.48940754e+01 -1.08480005e+01 1.24907923e+01 4.68038521e+01 6.67049484e+01 6.21087112e+01 2.81024990e+01 9.40807724e+00 4.21807718e+00 1.61263084e+01 4.00844955e+01 3.53097267e+01 2.37434864e+01 5.56902981e+00 1.33223085e+01 1.32129459e+01 9.94575500e-01 2.06798458e+00 1.28303404e+01 2.72596474e+01 1.29106789e+01 1.75903091e+01 2.89476929e+01 4.94950485e+01 5.16865196e+01 3.62197380e+01 1.58391285e+01 -2.22244835e+00 -3.45777855e+01 -5.22850494e+01 -4.69948616e+01 -1.31909342e+01 2.07604656e+01 3.08835506e+01 3.85040970e+01 4.09674149e+01 1.53315496e+01 -2.22645741e+01 -2.42386436e+01 6.49646473e+00 4.23546982e+01 4.48343315e+01 3.69638214e+01 4.90191002e+01 4.88622284e+01 4.66093063e+01 4.08830070e+01 4.64757195e+01 5.16336136e+01 4.24467278e+01 3.65865784e+01 4.88292999e+01 6.40394440e+01 8.66978226e+01 1.00649834e+02 8.57069626e+01 7.11105347e+01 7.18740692e+01 8.02859268e+01 6.01887817e+01 4.44655571e+01 3.96521568e+01 6.77336044e+01 8.85807495e+01 1.03762939e+02 7.78094864e+01 5.30929985e+01 3.03847084e+01 5.07718658e+01 8.37536774e+01 1.22187386e+02 8.74789658e+01 4.94313354e+01 2.32877483e+01 4.40627785e+01 5.69436951e+01 6.50787964e+01 9.14798203e+01 1.02655197e+02 9.26175766e+01 7.02110977e+01 4.18765602e+01 3.66543465e+01 3.60229759e+01 6.51874084e+01 9.29057541e+01 9.93874283e+01 7.09188232e+01 5.16236076e+01 4.21114731e+01 4.56994591e+01 3.58030205e+01 1.97868690e+01 1.55591221e+01 1.79344330e+01 3.08599224e+01 4.18072357e+01 3.95540390e+01 3.87313995e+01 4.58893509e+01 5.85265121e+01 4.61712914e+01 3.23738403e+01 5.17579918e+01 7.21903305e+01 6.38557320e+01 2.03682709e+01 1.85523546e+00 2.21174107e+01 3.74788742e+01 4.06894150e+01 4.65020981e+01 8.01390305e+01 8.81183701e+01 1.00001495e+02 9.11625290e+01 8.51542664e+01 6.77725983e+01 5.27945251e+01 6.38282394e+01 5.93797684e+01 5.77734222e+01 5.34357872e+01 5.91881752e+01 5.13840981e+01 8.00566254e+01 9.89077072e+01 1.12419685e+02 8.94222488e+01 6.63668442e+01 5.80226555e+01 5.06122017e+01 5.59728851e+01 5.49186020e+01 6.77819748e+01 4.59228516e+01 2.86578217e+01 1.45774737e-01 3.36767673e+00 2.36410732e+01 4.57753181e+01 4.63125191e+01 3.70811615e+01 3.53975792e+01 4.46846657e+01 5.05948105e+01 2.03130188e+01 -1.11224699e+01 -1.50728960e+01 2.55463657e+01 6.39348907e+01 6.69498901e+01 4.80273743e+01 8.88349950e-01 -1.25170883e+02 -5.09393501e+01 -2.39916977e+02 -8.19508972e+01 -1.84655408e+03 -2.87520923e+03 1.86553085e+02 1.43498322e+02 1.28857775e+01 1.88022919e+02 -4.70253716e+01 -4.03748444e+02 -2.45517944e+03 -1.37887129e+04 -3.13007383e+04 569123392. 3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 389030656. -914048064. 908183104. -8.97945117e+03 -3.42545679e+03 -5.46184998e+02 -4.07128082e+02 -3.08194336e+02 -6.40424500e+01 1.29527874e+01 1.79905643e+01 4.30516129e+01 6.53282700e+01 6.55813599e+01 6.35335159e+01 5.92068100e+01 5.81923065e+01 4.17537041e+01 3.19434910e+01 4.67156487e+01 7.59235764e+01 8.16934891e+01 6.26685791e+01 5.23519516e+01 6.32722855e+01 6.53214798e+01 5.88570404e+01 5.27568970e+01 4.91534615e+01 4.10785599e+01 4.14617310e+01 5.39239502e+01 6.01946983e+01 6.52545471e+01 5.82056274e+01 7.76115265e+01 9.47807770e+01 1.01501846e+02 9.13933563e+01 7.90697021e+01 8.34837570e+01 8.89195404e+01 9.22868881e+01 9.94436035e+01 1.03350777e+02 1.08369843e+02 1.10446297e+02 1.13233582e+02 1.06118256e+02 9.80120468e+01 9.34718933e+01 9.88183746e+01 9.87410202e+01 9.34556351e+01 9.35140076e+01 9.44602966e+01 1.00411736e+02 1.01923615e+02 9.68927689e+01 8.07745972e+01 6.39125786e+01 5.43169479e+01 6.43353958e+01 7.37147827e+01 8.34290924e+01 7.12504044e+01 6.49581757e+01 6.94846954e+01 8.51701813e+01 9.80255966e+01 9.84320145e+01 9.71570969e+01 1.04181122e+02 1.17849152e+02 1.07170174e+02 8.44257126e+01 6.81525345e+01 7.17353287e+01 8.37893906e+01 8.22115555e+01 8.67111130e+01 8.61975937e+01 8.99690475e+01 8.79597244e+01 8.68063660e+01 7.97135315e+01 7.85950394e+01 7.83784485e+01 8.56468811e+01 8.49098740e+01 7.46574707e+01 5.96990204e+01 6.26183090e+01 7.31659393e+01 8.43262177e+01 8.11518173e+01 7.47794647e+01 6.86629639e+01 6.50993576e+01 7.44049988e+01 8.59978790e+01 8.83400803e+01 8.28304749e+01 7.10666351e+01 7.36548233e+01 7.59980164e+01 8.12349091e+01 8.28057709e+01 7.98267517e+01 8.05451355e+01 8.02570343e+01 8.35124969e+01 8.38751221e+01 8.50081100e+01 8.51502609e+01 7.91029129e+01 7.16075745e+01 7.18757172e+01 7.91081467e+01 8.67583694e+01 8.81410599e+01 8.93282471e+01 8.97129822e+01 9.10218048e+01 9.14481354e+01 9.17984238e+01 8.41932602e+01 7.61815414e+01 7.45237503e+01 8.01951218e+01 8.66670609e+01 8.92450256e+01 8.98312149e+01 8.95041046e+01 8.76013641e+01 8.71929779e+01 8.86969986e+01 8.68994293e+01 8.64563828e+01 8.59995041e+01 8.67134857e+01 8.62098083e+01 8.61171646e+01 8.58661041e+01 8.68154373e+01 8.63900375e+01 8.59198532e+01 8.58064804e+01 8.60235062e+01 8.57458496e+01 8.46031723e+01 8.44227905e+01 8.58644104e+01 8.65758286e+01 8.68249893e+01 8.63119278e+01 8.68597412e+01 8.72702560e+01 8.74781113e+01 8.64970703e+01 8.35500641e+01 8.21991730e+01 8.24488831e+01 8.35056305e+01 8.43199387e+01 8.47344437e+01 8.55620728e+01 8.59081116e+01 8.57308044e+01 8.56875305e+01 8.58223495e+01 8.59772797e+01 8.59870529e+01 8.60761490e+01 8.60999374e+01 8.58310852e+01 8.53869476e+01 8.51185684e+01 8.53379822e+01 8.58325424e+01 8.66204453e+01 8.65125504e+01 8.63281403e+01 8.59538269e+01 8.59519272e+01 8.56531677e+01 8.60355530e+01 8.58759689e+01 8.56434479e+01 8.57006226e+01 8.61711807e+01 8.60589066e+01 8.56076736e+01 8.51284409e+01 8.64638901e+01 8.71464844e+01 8.78314285e+01 8.78703232e+01 8.67401276e+01 8.33593140e+01 7.94013519e+01 7.71383514e+01 7.73204117e+01 7.76074982e+01 7.64621429e+01 7.90905838e+01 8.33535919e+01 8.82590561e+01 8.95082474e+01 8.91120987e+01 8.78649979e+01 8.70339890e+01 8.70439606e+01 8.98192520e+01 9.01480789e+01 9.03402634e+01 8.92203293e+01 8.83447571e+01 8.84405060e+01 9.33463669e+01 1.00207466e+02 9.81632004e+01 9.18225021e+01 8.57196960e+01 8.19130478e+01 7.80896072e+01 6.98210144e+01 6.52461395e+01 6.82499390e+01 7.33978729e+01 8.28467026e+01 7.87215881e+01 7.57909241e+01 7.19417572e+01 7.36539841e+01 7.51453934e+01 7.46977539e+01 7.33343658e+01 7.47599716e+01 7.72812347e+01 8.05915604e+01 7.98515396e+01 7.17305756e+01 6.17079391e+01 5.27906609e+01 4.96662750e+01 6.84840393e+01 8.81889725e+01 9.83679733e+01 9.03178329e+01 7.78122253e+01 7.96209717e+01 7.78066177e+01 8.05884705e+01 7.96402588e+01 7.99353867e+01 8.12534180e+01 8.21299133e+01 8.10644989e+01 8.02965622e+01 9.01176376e+01 1.03689880e+02 1.07229202e+02 1.02042374e+02 9.17038193e+01 8.56744385e+01 7.44860535e+01 7.34601746e+01 7.80785065e+01 8.11157303e+01 7.36672516e+01 7.41344452e+01 8.10169525e+01 8.93025360e+01 8.95781631e+01 8.68529434e+01 8.55932770e+01 8.41521912e+01 8.47833481e+01 8.25374222e+01 8.30078354e+01 8.32548828e+01 8.80425186e+01 8.92874298e+01 8.83650284e+01 7.38576736e+01 5.74236450e+01 5.93467522e+01 7.32486877e+01 8.68406219e+01 8.15329590e+01 7.76716309e+01 7.51803589e+01 7.29808655e+01 6.93991928e+01 6.68540344e+01 5.48308907e+01 5.05614128e+01 5.19336357e+01 7.10882874e+01 8.43520279e+01 8.67920990e+01 8.10331955e+01 9.00871964e+01 1.03302574e+02 1.10197624e+02 1.06261864e+02 8.96512985e+01 8.91084900e+01 8.68558121e+01 8.87321472e+01 8.75806885e+01 8.42408295e+01 8.71473541e+01 9.04216080e+01 8.95666351e+01 9.11291885e+01 9.18421097e+01 9.25771713e+01 8.34900589e+01 7.95923386e+01 6.51847000e+01 5.06255951e+01 4.99841919e+01 5.93139000e+01 7.08432770e+01 6.84828568e+01 7.14431763e+01 8.22576218e+01 7.84144745e+01 5.74060249e+01 3.64001122e+01 3.70518341e+01 5.98411446e+01 7.53931046e+01 7.34037323e+01 6.55816650e+01 6.02889786e+01 6.15317116e+01 4.44453392e+01 2.34632835e+01 2.07068233e+01 4.10673141e+01 7.17753830e+01 6.83851929e+01 6.49389877e+01 5.86581268e+01 6.46145935e+01 6.89156952e+01 6.12433548e+01 5.32914238e+01 4.69525566e+01 5.48676682e+01 5.88636932e+01 5.47862473e+01 3.06416950e+01 -3.27165246e+00 -6.08459663e+00 1.70084324e+01 4.87025261e+01 5.66694221e+01 6.25967751e+01 6.07183914e+01 5.41957436e+01 2.13882122e+01 -1.75022984e+00 -2.91371784e+01 -2.95735493e+01 -5.68010855e+00 1.82728767e+01 4.74413338e+01 3.04087772e+01 1.03186817e+01 2.83495655e+01 7.67287445e+01 1.04734108e+02 9.03658905e+01 5.47975578e+01 5.69248619e+01 5.81882515e+01 6.95408401e+01 7.11571808e+01 8.27982254e+01 7.90738983e+01 8.27175827e+01 8.08983078e+01 8.48492508e+01 8.41663513e+01 8.60477676e+01 8.50765305e+01 7.98866501e+01 6.02424316e+01 3.37221451e+01 3.74669609e+01 5.55053978e+01 8.72687454e+01 5.86355858e+01 2.40624886e+01 5.34543648e+01 1.14289162e+02 1.20124969e+02 4.34441185e+01 2.72429109e+00 2.91112671e+01 6.52447662e+01 4.49599190e+01 8.02173615e+00 2.56598639e+00 2.41932964e+01 5.36784935e+01 5.17173729e+01 4.23902893e+01 4.74505577e+01 4.53800049e+01 6.83562241e+01 9.20158234e+01 6.59817734e+01 1.36090574e+01 -1.59790802e+01 6.76338243e+00 3.14337158e+01 3.17204905e+00 -2.37065563e+01 -3.36572495e+01 -4.68473625e+00 3.11508675e+01 3.04338894e+01 1.91704407e+01 1.14708548e+01 2.93973217e+01 1.80798950e+01 -1.01248207e+01 -2.54829311e+01 -2.20411739e+01 1.48248663e+01 3.09553146e+01 5.09165344e+01 5.55070992e+01 5.57743759e+01 9.78233566e+01 1.44920975e+02 1.30522705e+02 6.20765419e+01 9.32989788e+00 2.13089371e+01 5.26282005e+01 2.78600216e+01 -8.84985447e+00 -1.36005278e+01 1.32039642e+01 4.73879471e+01 5.21875191e+01 5.05559235e+01 5.51089821e+01 4.85445633e+01 4.55052071e+01 3.49339066e+01 2.25835686e+01 1.89035263e+01 2.90318241e+01 4.74258995e+01 5.48899117e+01 6.07258072e+01 5.04509048e+01 8.19609909e+01 1.13771118e+02 8.73355026e+01 1.02786474e+01 -3.32492943e+01 5.88075924e+00 5.65671272e+01 8.41502686e+01 9.08008041e+01 9.02799072e+01 8.10819397e+01 7.59746170e+01 7.92024918e+01 6.84650269e+01 7.52275085e+01 7.30335922e+01 8.17361984e+01 8.14090424e+01 8.39612808e+01 7.19287415e+01 5.54792786e+01 6.22102013e+01 8.02831573e+01 8.78881912e+01 6.70467453e+01 4.76827316e+01 3.61291046e+01 1.27883835e+01 -2.05935135e+01 -2.51318226e+01 -5.49744368e+00 -5.53422880e+00 -7.86264725e+01 -1.21692337e+02 -9.42312546e+01 -4.03577271e+01 -5.40234566e+01 -1.01707855e+02 -1.11568748e+02 -6.94567108e+01 -3.15536251e+01 -1.90659103e+01 -2.18422222e+01 -2.43634834e+01 -2.72332096e+01 -1.73715534e+01 -1.91004276e+00 -2.03135014e+01 -6.31006393e+01 -8.00483246e+01 -5.27162285e+01 -8.78883362e+00 -1.33515244e+01 -4.01707573e+01 -1.12666082e+01 3.71175117e+01 6.14315300e+01 4.11110764e+01 1.58715057e+01 2.88000240e+01 2.58894444e+01 2.51687679e+01 2.54921570e+01 3.20672340e+01 3.10518646e+01 2.19600296e+01 3.37956123e+01 4.21528282e+01 5.47739449e+01 4.74133034e+01 3.45497322e+01 3.63736916e+01 2.99958396e+00 -3.30148544e+01 -3.68652420e+01 -1.36750150e+00 5.80511017e+01 7.42674103e+01 7.44341583e+01 9.31538239e+01 1.27606178e+02 1.35250153e+02 1.05924744e+02 6.19762764e+01 5.57228584e+01 5.25509605e+01 3.50067067e+00 -5.32645416e+01 -6.89475708e+01 -2.70215168e+01 4.51240349e+00 -4.51572371e+00 -1.45854855e+00 1.52411661e+01 1.71486378e+01 3.23997955e+01 6.77141876e+01 5.30637398e+01 4.85565042e+00 -3.49761543e+01 -1.39106855e+01 -2.25222206e+01 -9.45060883e+01 -1.40699097e+02 -1.16549179e+02 -3.96019630e+01 -2.26243706e+01 -4.93093300e+01 -5.19906082e+01 -1.23920479e+01 4.04718094e+01 2.92740517e+01 -6.38598633e+00 -1.44681292e+01 -2.30086207e+00 2.72180195e+01 4.17766838e+01 5.42047386e+01 5.91742668e+01 4.03967781e+01 4.84314537e+01 5.66903534e+01 3.33252602e+01 -6.61336851e+00 -1.78692570e+01 1.31646729e+01 3.48021469e+01 1.21745052e+01 -1.93051262e+01 -1.64174976e+01 -5.34625530e+00 4.53758583e+01 1.13716118e+02 2.64608643e+02 3.94561005e+02 5.04489532e+02 7.00908752e+02 5.69626099e+02 1.00899971e+02 -4.97854401e+02 -1.13342456e+03 -2.68537183e+03 -9.37060352e+03 25046594. -8.42500710e+09 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. -1101049216. -22439274. 4.14685898e+04 1.67291855e+04 2.34686670e+03 5.51308789e+03 3.64827075e+03 7.35839417e+02 2.63583588e+02 6.90797119e+01 4.11492577e+01 9.09780025e+00 -1.33699255e+01 3.28410225e+01 6.92685547e+01 4.38442001e+01 -4.25098419e+01 -8.70895309e+01 -4.44668350e+01 5.32612648e+01 -1.71298141e+01 -1.30161102e+02 -2.67532715e+02 -2.76197876e+02 -2.29595688e+02 -1.19824669e+02 -7.72829819e+01 -3.90505066e+01 -9.36254501e+01 -7.41948929e+01 -1.02661682e+02 -1.87305527e+02 -2.06829590e+02 -1.31304504e+02 -4.97913475e+01 -1.58273706e+01 -1.54918566e+01 2.22740078e+01 7.29334183e+01 8.34142761e+01 1.70655975e+01 -1.45102066e+02 -2.31813782e+02 -1.86257202e+02 -7.12917175e+01 -7.95021713e-01 -2.79099441e+00 -3.57695580e+01 -8.07969666e+01 -5.91070328e+01 -8.19487686e+01 -1.02393158e+02 -8.68101578e+01 5.74873161e+00 1.15744888e+02 9.57600174e+01 -4.72843399e+01 -1.26148148e+02 -8.34619064e+01 3.67627883e+00 -1.27987814e+01 -8.84174423e+01 -9.14864655e+01 -2.18608437e+01 5.92525482e+01 3.61074829e+01 -7.89840317e+01 -1.55562485e+02 -1.17546677e+02 -3.92358208e+01 -3.28166885e+01 -5.93238640e+01 -6.06756973e+01 5.36938810e+00 6.35268288e+01 4.11066093e+01 -1.31738496e+00 5.54279625e-01 4.47692642e+01 7.01460571e+01 5.35662041e+01 -5.59237957e+00 -6.49027786e+01 -8.50639572e+01 -4.52563705e+01 -1.50417833e+01 -2.95538635e+01 1.27569704e+01 9.37190628e+01 1.32068466e+02 5.64291916e+01 -7.40587540e+01 -1.38887024e+02 -1.03051239e+02 -3.30505610e+00 9.20562897e+01 1.29277573e+02 1.01950386e+02 7.90065613e+01 9.07800293e+01 6.87046432e+01 -2.69895687e+01 -1.02444763e+02 -8.37207947e+01 -9.18878317e-01 4.17646942e+01 2.07633152e+01 -4.30268097e+01 -6.90129700e+01 -3.43096313e+01 -4.54548359e+00 -9.33361626e+00 -2.09932480e+01 2.23327827e+01 1.05305817e+02 1.20174690e+02 5.54665451e+01 -3.08873672e+01 -2.96069927e+01 1.71685791e+01 6.75338898e+01 6.84602737e+01 2.10427666e+01 -4.08549843e+01 -7.16178970e+01 -3.78984756e+01 -3.92067604e+01 -7.85922318e+01 -8.32608109e+01 -3.02398605e+01 3.06894398e+01 2.46552181e+01 -3.19377975e+01 -6.23543243e+01 -2.96865330e+01 -1.16396397e-01 1.39251242e+01 -9.89917850e+00 1.29984560e+01 5.97203522e+01 6.96384583e+01 -2.75194645e+00 -1.30247604e+02 -1.90541534e+02 -1.36820496e+02 -6.42905884e+01 -4.38439789e+01 -6.97049866e+01 -9.92967758e+01 -9.18806000e+01 -9.40684357e+01 -1.13546227e+02 -1.66314728e+02 -1.84862274e+02 -1.34181931e+02 -1.77974434e+01 3.94669952e+01 -1.54070749e+01 -9.03324814e+01 -9.10357208e+01 -5.84760246e+01 -8.37115860e+01 -1.67223297e+02 -1.57693207e+02 -8.93758087e+01 -1.37216406e+01 -7.11845627e+01 -1.86269943e+02 -2.55963028e+02 -2.11167709e+02 -1.24795135e+02 -7.68722916e+01 -7.05266190e+01 -5.24574242e+01 -2.71662407e+01 -4.89061317e+01 -1.20150963e+02 -2.08362778e+02 -1.74708038e+02 -1.04613480e+02 -3.86197090e+01 -4.78814125e+01 -7.67821350e+01 -1.08560402e+02 -1.29759445e+02 -1.28103149e+02 -1.45584625e+02 -1.78732910e+02 -1.63371841e+02 -9.01028137e+01 -1.95435696e+01 -4.95113335e+01 -1.36301743e+02 -1.99236801e+02 -1.65152908e+02 -1.06453354e+02 -6.37626190e+01 -6.93775711e+01 -5.08551712e+01 -1.89531557e-02 2.23938122e+01 -3.24114532e+01 -1.18824989e+02 -1.34805771e+02 -1.00272980e+02 -3.37997093e+01 -1.37592716e+01 -1.71165009e+01 -5.37244720e+01 -8.69069748e+01 -8.87783585e+01 -1.08864540e+02 -1.27746635e+02 -9.91666183e+01 -4.75162811e+01 -2.99590778e+01 -4.63822441e+01 -8.67892914e+01 -9.88156891e+01 -8.36100159e+01 -8.08303146e+01 -7.95746689e+01 -1.03619713e+02 -7.50197754e+01 -3.29219055e+01 -1.05845690e+01 -1.45456791e+00 -6.65021591e+01 -1.03624992e+02 -8.87675323e+01 -2.86521358e+01 -1.67599812e+01 -6.15823174e+01 -1.03632553e+02 -1.02363785e+02 -7.40047073e+01 -7.58556366e+01 -1.10546265e+02 -1.14725327e+02 -7.87323380e+01 -4.85098152e+01 -7.40397339e+01 -8.78878250e+01 -6.43665695e+01 -5.49963913e+01 -7.83098373e+01 -9.71259995e+01 -1.11360886e+02 -9.66688614e+01 -1.22887817e+02 -1.29970459e+02 -1.26870209e+02 -1.30427734e+02 -1.47951019e+02 -1.60136658e+02 -1.06050797e+02 -8.57116241e+01 -7.67109756e+01 -1.19238510e+02 -1.08123451e+02 -1.04941734e+02 -1.20637459e+02 -1.53144638e+02 -1.65931168e+02 -1.09275818e+02 -8.10990448e+01 -8.05785980e+01 -1.29309052e+02 -1.37744537e+02 -1.17012856e+02 -9.62530670e+01 -8.60546188e+01 -1.24380135e+02 -1.14053871e+02 -9.83596725e+01 -5.57868462e+01 -3.97430267e+01 -4.87308273e+01 -8.48842850e+01 -1.14341133e+02 -9.40545731e+01 -6.34367332e+01 -5.01469688e+01 -7.04287338e+01 -5.19053917e+01 -5.21979446e+01 -7.28104935e+01 -1.14082031e+02 -1.13096458e+02 -6.63858490e+01 -5.01553497e+01 -6.96695099e+01 -1.14785934e+02 -9.99952774e+01 -8.06924515e+01 -6.54739227e+01 -7.82752609e+01 -9.89961014e+01 -1.00420296e+02 -1.11172050e+02 -8.41955643e+01 -7.14777908e+01 -6.44110947e+01 -8.91460571e+01 -1.01350044e+02 -8.76631393e+01 -7.18443527e+01 -6.76788025e+01 -6.10525360e+01 -2.99377766e+01 -1.30433569e+01 -2.07537689e+01 -2.98874493e+01 -3.02058125e+01 -1.20867329e+01 -8.21991062e+00 -2.28051014e+01 -5.91426964e+01 -7.23100662e+01 -7.63043213e+01 -7.18931580e+01 -8.40575562e+01 -1.08010269e+02 -1.19941566e+02 -1.21244965e+02 -9.76062393e+01 -8.71556473e+01 -8.52995758e+01 -9.35577240e+01 -8.79938278e+01 -7.78561172e+01 -6.57847519e+01 -6.60549774e+01 -6.82035751e+01 -5.21590652e+01 -3.96303215e+01 -4.78844452e+01 -7.05061798e+01 -7.91373978e+01 -7.87590485e+01 -9.90441132e+01 -1.13443634e+02 -1.20790283e+02 -9.79980316e+01 -9.59692459e+01 -9.45274506e+01 -8.42400589e+01 -8.45998459e+01 -9.73163376e+01 -1.24315239e+02 -1.30087479e+02 -1.08850021e+02 -8.87596664e+01 -9.00025864e+01 -1.08143982e+02 -1.23352577e+02 -1.15181084e+02 -9.89431992e+01 -8.39401550e+01 -8.46194153e+01 -9.88014526e+01 -1.10839500e+02 -1.25458229e+02 -1.26515556e+02 -1.26245270e+02 -1.31583160e+02 -1.30125717e+02 -1.31142899e+02 -1.11283379e+02 -1.10736900e+02 -1.10709068e+02 -1.11153015e+02 -1.13287125e+02 -1.22173935e+02 -1.48912857e+02 -1.53326096e+02 -1.35665451e+02 -1.00405830e+02 -8.36939926e+01 -1.04138428e+02 -1.30225586e+02 -1.31590881e+02 -1.03381142e+02 -7.59249954e+01 -8.43618622e+01 -1.08485405e+02 -1.25417625e+02 -1.22634117e+02 -1.05826469e+02 -1.05057564e+02 -1.14498093e+02 -1.24027725e+02 -1.26131660e+02 -1.13271431e+02 -1.13585701e+02 -1.19686653e+02 -1.25468292e+02 -1.24734535e+02 -1.17758804e+02 -1.21680832e+02 -1.21544777e+02 -1.10475525e+02 -9.82448273e+01 -1.00934258e+02 -1.21133972e+02 -1.33002060e+02 -1.27595078e+02 -1.13460266e+02 -1.06448212e+02 -1.09568497e+02 -1.18571655e+02 -1.21463303e+02 -1.22305046e+02 -1.14799019e+02 -1.14197166e+02 -1.15583725e+02 -1.18618698e+02 -1.21166618e+02 -1.16394539e+02 -1.13395416e+02 -1.08790047e+02 -1.09033112e+02 -1.11123901e+02 -1.14600487e+02 -1.19874168e+02 -1.21223755e+02 -1.17774490e+02 -1.11258423e+02 -1.08558868e+02 -1.11556427e+02 -1.16577614e+02 -1.17530998e+02 -1.14239372e+02 -1.11651688e+02 -1.12212921e+02 -1.14235405e+02 -1.14735115e+02 -1.14558784e+02 -1.14429031e+02 -1.14587852e+02 -1.14383530e+02 -1.13692886e+02 -1.12653358e+02 -1.12343361e+02 -1.11233513e+02 -1.10833626e+02 -1.12063362e+02 -1.15046181e+02 -1.16279541e+02 -1.13422653e+02 -1.10037071e+02 -1.10757057e+02 -1.16204887e+02 -1.21334770e+02 -1.19621193e+02 -1.12755791e+02 -1.10773674e+02 -1.13606796e+02 -1.20202469e+02 -1.18765160e+02 -1.13574768e+02 -1.07291275e+02 -1.03218033e+02 -1.07810677e+02 -1.07690681e+02 -1.10471489e+02 -1.08621315e+02 -1.07646614e+02 -1.05427933e+02 -9.99604416e+01 -1.04080223e+02 -1.11286926e+02 -1.20676842e+02 -1.16684845e+02 -1.03665810e+02 -9.35849991e+01 -1.00961327e+02 -1.15802269e+02 -1.25866730e+02 -1.25164703e+02 -1.14475166e+02 -1.09760994e+02 -1.07217979e+02 -1.13307106e+02 -1.09223335e+02 -1.03277794e+02 -9.49154129e+01 -8.65666046e+01 -8.93632584e+01 -1.04010330e+02 -1.17793777e+02 -1.19042305e+02 -1.11162956e+02 -1.02922401e+02 -9.10756454e+01 -8.45711212e+01 -1.00161461e+02 -1.27070038e+02 -1.40125626e+02 -1.21479187e+02 -9.95642319e+01 -9.66920395e+01 -1.21685059e+02 -1.49073944e+02 -1.46619476e+02 -1.13714500e+02 -7.78316269e+01 -6.41795883e+01 -8.63977814e+01 -1.04646919e+02 -1.05187874e+02 -9.45572815e+01 -8.71694412e+01 -9.97681656e+01 -1.00710930e+02 -1.04654137e+02 -1.15760895e+02 -1.18326485e+02 -1.18270187e+02 -9.79646149e+01 -1.00468384e+02 -1.22285278e+02 -1.50568863e+02 -1.46800491e+02 -1.02375671e+02 -6.84293900e+01 -7.86088333e+01 -1.17678673e+02 -1.46003799e+02 -1.47008636e+02 -1.14888802e+02 -8.21279907e+01 -6.62029419e+01 -9.18057098e+01 -1.11560112e+02 -1.28740860e+02 -1.25335930e+02 -1.16961075e+02 -1.18804001e+02 -1.20129181e+02 -1.45103317e+02 -1.59544846e+02 -1.59919708e+02 -1.40767166e+02 -1.02007210e+02 -8.64717636e+01 -1.08178558e+02 -1.47123093e+02 -1.59751999e+02 -1.35466690e+02 -9.60239410e+01 -9.58513489e+01 -1.23841454e+02 -1.63894760e+02 -1.72269470e+02 -1.31565140e+02 -9.14171982e+01 -7.29621353e+01 -1.05867805e+02 -1.37596664e+02 -1.39286362e+02 -1.18910255e+02 -9.13931961e+01 -8.50262909e+01 -8.07696075e+01 -9.77608795e+01 -1.32603271e+02 -1.42243591e+02 -1.11305328e+02 -5.73511162e+01 -3.90309906e+01 -6.87830505e+01 -1.12302986e+02 -1.41100006e+02 -1.21787766e+02 -8.00515594e+01 -5.70492325e+01 -6.85912552e+01 -9.85280609e+01 -9.93330688e+01 -7.88311615e+01 -5.51416435e+01 -5.43211594e+01 -9.08712158e+01 -1.16901550e+02 -1.04645592e+02 -7.48706894e+01 -3.50132370e+01 -3.83585014e+01 -3.78552513e+01 -5.52522354e+01 -7.88449707e+01 -9.39372101e+01 -9.83341675e+01 -6.29137726e+01 -3.99136696e+01 -5.26516342e+01 -8.55772858e+01 -1.17420090e+02 -9.46119919e+01 -6.07894135e+01 -3.96477470e+01 -8.43088150e+01 -1.58804596e+02 -1.94173538e+02 -1.52011200e+02 -6.34409065e+01 -4.29308968e+01 -1.23781952e+02 -2.15709991e+02 -1.23274055e+02 -1.50884369e+02 -1.24769821e+02 -1.22425430e+02 2.87493286e+02 -1.22395068e+03 -2.37746118e+03 -7.06446191e+03 -2.36734648e+04 -5.90321971e+09 271363584. 6.41086925e+09 544389376. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 888686720. 981909888. -1.75417285e+04 -6.57703418e+03 -6.05154785e+02 -1.39233301e+03 -4.02011206e+03 -2.52497119e+03 -4.51570068e+02 -2.04850327e+02 -2.78377716e+02 -1.95557220e+02 -8.28491364e+01 -2.76884651e+01 -3.18019695e+01 -1.02461136e+02 -1.45067368e+02 -1.30382401e+02 -4.23781929e+01 2.97385998e+01 1.73286972e+01 -3.37085266e+01 -4.40853348e+01 -4.36913109e+01 -4.78529663e+01 -9.22147598e+01 -5.78385963e+01 -4.83420715e+01 -1.03389748e+02 -1.53648743e+02 -1.17036232e+02 -1.98778927e+00 5.82789459e+01 -1.47104807e+01 -1.07153313e+02 -1.64668625e+02 -1.30419800e+02 -2.15601120e+01 6.57586212e+01 1.12266777e+02 3.18038502e+01 -2.88061256e+01 -4.13180962e+01 1.87651577e+01 5.78202400e+01 2.23214283e+01 1.35038109e+01 -2.39840965e+01 -5.89929771e+01 -7.35655899e+01 -3.52143631e+01 7.22071381e+01 8.05825806e+01 -1.06760559e+01 -1.22190552e+02 -1.55428284e+02 -6.35706978e+01 3.01261311e+01 2.99770279e+01 -4.01356544e+01 -7.22992554e+01 1.59608376e+00 1.18532784e+02 1.46187439e+02 9.93569717e+01 -2.68623180e+01 -1.11890961e+02 -1.13273979e+02 -3.21448631e+01 7.20479965e+01 1.37162399e+02 1.67363098e+02 1.40859283e+02 8.17777100e+01 1.48614492e+01 -1.60803699e+01 8.24856091e+00 1.10132611e+00 -7.22641525e+01 -1.42449326e+02 -1.37164948e+02 -4.98963699e+01 1.71427746e+01 -2.63042307e+00 -3.87543602e+01 -1.02728668e+02 -1.40544952e+02 -1.04404411e+02 -3.68398952e+00 6.24217796e+01 3.19424987e+00 -6.75867004e+01 -6.52233810e+01 -1.46712923e+01 -3.09377503e+00 -2.57806206e+01 -8.96588230e+00 -1.56253614e+01 -5.66787148e+01 -8.57309799e+01 -5.22113152e+01 5.66986160e+01 6.95121994e+01 -3.42667923e+01 -1.72998886e+02 -2.14767853e+02 -1.25674515e+02 -1.81626148e+01 1.67958736e+01 2.24572039e+00 -3.98753777e+01 -4.08813438e+01 -1.94978600e+01 4.02181625e+01 7.19492416e+01 1.48439245e+01 -9.29683380e+01 -1.21883766e+02 -8.08723755e+01 -3.48387260e+01 -3.09345894e+01 1.11212616e+01 1.10411615e+01 -8.40689850e+01 -1.87719162e+02 -1.84553162e+02 -4.32617035e+01 1.72030373e+01 -6.25728569e+01 -1.78840851e+02 -1.98658401e+02 -8.52219849e+01 3.05690174e+01 6.10137253e+01 1.41800995e+01 -7.51983795e+01 -1.46309189e+02 -1.18072342e+02 -1.94318161e+01 5.06102104e+01 -1.44990015e+01 -1.21513931e+02 -1.54918365e+02 -1.13640152e+02 -5.88660965e+01 -2.31795101e+01 3.48995209e+01 4.86524353e+01 1.54674749e+01 -3.15778160e+01 -2.91539249e+01 3.38832703e+01 7.02216949e+01 5.03665447e+00 -1.24375854e+02 -2.24640701e+02 -1.78357819e+02 -4.41923752e+01 5.27448769e+01 4.24451523e+01 -3.02993946e+01 -5.49073563e+01 -4.01730118e+01 -2.19367409e+01 1.28216801e+01 5.94222689e+00 -1.25278749e+01 -4.81589470e+01 -1.08510712e+02 -1.45280350e+02 -1.52896912e+02 -7.61664352e+01 -2.75485592e+01 -8.63121262e+01 -1.44189667e+02 -1.15117752e+02 9.96682549e+00 8.20452957e+01 4.56767960e+01 -2.02919102e+01 -7.36744690e+01 -8.25034103e+01 -4.91934662e+01 -2.94929581e+01 -2.61444607e+01 -8.60108719e+01 -7.09199829e+01 -1.13958292e+01 5.91063499e+01 1.32687622e+02 1.71517700e+02 2.06921173e+02 1.29341415e+02 1.97388802e+01 -4.21523476e+01 -2.68602982e+01 3.74020386e+01 4.55546379e+01 -3.06554165e+01 -1.28886627e+02 -1.73023636e+02 -6.83864899e+01 8.51745987e+01 1.54414185e+02 1.20044891e+02 4.93902321e+01 2.80126438e+01 3.77730713e+01 5.88400612e+01 9.46853714e+01 6.31795921e+01 8.52574825e+00 -3.51006927e+01 1.04651623e+01 2.26647091e+01 4.65254631e+01 6.58336029e+01 9.30334167e+01 6.39430771e+01 3.77528992e+01 4.52066231e+01 4.62039566e+01 4.47504520e+00 -6.12885971e+01 -1.06602036e+02 -1.28535431e+02 -6.69479980e+01 -2.13793869e+01 6.97796021e+01 8.36743011e+01 3.37919731e+01 -4.63547783e+01 -7.22974167e+01 -1.25783281e+01 2.15055180e+01 1.75593739e+01 7.92331505e+00 1.98954830e+01 1.60520782e+01 2.13333092e+01 1.58295860e+01 9.69958973e+00 7.25239325e+00 7.24398661e+00 -1.74832571e+00 -2.85243073e+01 -3.33370552e+01 -1.46768093e+01 5.57870007e+00 -2.63030624e+00 -2.33541985e+01 -8.28277206e+00 2.21067977e+00 4.03164902e+01 5.34047813e+01 5.69859505e+01 4.57235413e+01 1.38310499e+01 1.58436975e+01 1.79978466e+01 1.85042496e+01 5.68883228e+00 2.75538325e+00 2.39572120e+00 -1.39029527e+00 -6.56079102e+00 -5.76933479e+00 8.04119110e+00 1.26739883e+00 -3.20581532e+00 -2.29036274e+01 -2.80538521e+01 -3.56005478e+01 -1.52796564e+01 -9.72272873e+00 -3.07098222e+00 -8.26923561e+00 -7.65309095e+00 -1.42438231e+01 -1.38414583e+01 -1.39753036e+01 9.82263374e+00 1.31504154e+01 1.57507098e+00 -5.07725191e+00 -1.05374229e+00 5.41052628e+00 -9.86061156e-01 -5.10599971e-01 2.29298573e+01 2.20937634e+01 1.16405449e+01 2.11890054e+00 1.69016476e+01 2.70384007e+01 1.39153862e+01 2.87162132e+01 4.96795921e+01 6.63264008e+01 4.54956131e+01 4.46471024e+01 4.59796638e+01 5.59773407e+01 6.78671188e+01 7.12502518e+01 6.26474609e+01 3.66512108e+01 3.24619331e+01 3.34720306e+01 3.16668301e+01 1.69612331e+01 2.39259033e+01 2.89625454e+01 1.36595030e+01 -2.09237804e+01 -1.76164551e+01 5.85307121e+00 4.02116623e+01 4.45412979e+01 4.45704231e+01 4.36850243e+01 4.15681458e+01 5.32998581e+01 6.14428711e+01 6.06448174e+01 6.90473022e+01 7.37972031e+01 8.03599014e+01 4.23015671e+01 3.68023720e+01 3.88733253e+01 4.80492287e+01 4.47626228e+01 4.71584015e+01 5.59153633e+01 5.72323647e+01 6.46486740e+01 7.82783737e+01 7.42553864e+01 6.33778191e+01 4.60780373e+01 5.35972748e+01 6.01373482e+01 7.33883438e+01 7.31522446e+01 4.64584579e+01 3.47143860e+01 2.78577271e+01 6.31413841e+01 7.31059952e+01 8.16776886e+01 5.85808182e+01 4.08532600e+01 2.59546337e+01 2.80145130e+01 1.93509369e+01 1.51706114e+01 1.30482845e+01 3.20870781e+01 5.30300140e+01 5.86115952e+01 4.75749016e+01 4.22842941e+01 3.88421326e+01 4.04874763e+01 3.16207275e+01 3.45957909e+01 4.00783958e+01 5.84716682e+01 5.39773293e+01 1.04707527e+01 -3.25993500e+01 -2.51258430e+01 2.46871014e+01 6.80218811e+01 4.77150383e+01 1.88077927e+01 5.98663044e+00 2.36889057e+01 4.95440254e+01 3.60227051e+01 2.06518764e+01 1.63243866e+01 2.33960838e+01 2.60198803e+01 1.09419985e+01 -2.68166256e+00 -4.77740192e+00 2.35055828e+01 5.42357483e+01 5.96974640e+01 3.69981995e+01 3.12119293e+01 3.75399551e+01 5.33987122e+01 4.56882439e+01 2.56368370e+01 3.87497997e+00 1.59809980e+01 5.07305603e+01 7.86875610e+01 7.59268799e+01 6.96074753e+01 7.47416458e+01 1.02450089e+02 1.35840500e+02 1.38728851e+02 1.07672913e+02 7.08479385e+01 5.62800255e+01 4.78190460e+01 2.76805859e+01 2.34830704e+01 6.73255920e+01 1.19995071e+02 1.31865326e+02 9.11708221e+01 5.25781021e+01 5.49540443e+01 6.57543335e+01 8.28518372e+01 9.95176315e+01 9.13634186e+01 7.49718323e+01 4.35593719e+01 4.17248917e+01 3.61143150e+01 7.13396378e+01 1.19755531e+02 1.29882477e+02 1.09138916e+02 6.76154251e+01 4.79297791e+01 2.07276096e+01 2.30696087e+01 4.63513985e+01 7.03174286e+01 8.53583069e+01 8.84742584e+01 8.28113022e+01 8.95454330e+01 9.21025238e+01 9.71362762e+01 9.23532333e+01 8.97425613e+01 7.93551102e+01 -5.26047039e+00 -7.99024429e+01 -1.77632950e+02 -1.14462708e+02 -2.98372631e+01 8.33094330e+01 2.36987972e+01 -6.67640076e+01 4.45229950e+01 -2.16536148e+02 -4.33758301e+03 -1.03038721e+04 -468581088. -166904384. -278647392. 34589056. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1153186048. 374735552. -1.91875703e+04 -7.17846191e+03 -5.49217407e+02 -1.04884766e+02 -2.57562183e+03 -1.71737524e+03 -2.51602890e+02 -1.56704224e+02 1.60976830e+01 5.64893341e+01 6.64836121e+01 6.84655228e+01 6.73558044e+01 6.82617569e+01 6.55307922e+01 1.01446671e+02 1.76237839e+02 2.28616623e+02 2.02971817e+02 1.76853165e+02 1.37709747e+02 3.99217224e+01 -1.24436874e+01 -7.68625832e+00 1.33022585e+01 -8.61943531e+00 -5.44288750e+01 1.05006886e+01 -2.20124359e+01 -5.93175364e+00 1.61505451e+01 8.30534973e+01 1.02050301e+02 1.14158401e+02 1.20709785e+02 1.28214523e+02 1.32205261e+02 1.34608704e+02 1.26239555e+02 1.19289108e+02 1.19110313e+02 1.23018425e+02 1.28634415e+02 1.31633835e+02 1.34422531e+02 1.25621902e+02 1.08625473e+02 9.24173355e+01 8.88168945e+01 9.69906387e+01 1.04935387e+02 1.09778709e+02 1.16203590e+02 1.11443077e+02 1.07398552e+02 1.08006157e+02 1.16578964e+02 1.23607079e+02 1.20609726e+02 1.27075470e+02 1.16885284e+02 1.10192139e+02 1.03378746e+02 1.02936089e+02 1.00683945e+02 9.79790192e+01 1.01220001e+02 1.05806168e+02 1.04747398e+02 1.05555428e+02 1.17308266e+02 1.21695892e+02 1.21460838e+02 1.11364044e+02 1.09623085e+02 1.11313385e+02 1.04804825e+02 9.08259811e+01 9.24487000e+01 9.83856964e+01 1.05156830e+02 8.71479874e+01 7.29635849e+01 7.33774643e+01 8.41019974e+01 9.20139694e+01 9.14566879e+01 9.04833603e+01 9.45643463e+01 9.21900711e+01 8.57021408e+01 7.59019318e+01 8.02537537e+01 9.55030136e+01 1.08764442e+02 1.13430260e+02 1.11441895e+02 1.09242165e+02 1.05855103e+02 1.12231262e+02 1.18904373e+02 1.14526810e+02 1.05264954e+02 1.03940804e+02 1.12381950e+02 1.17582886e+02 1.04692017e+02 9.58196564e+01 9.76673889e+01 1.10410309e+02 1.20116310e+02 1.20778870e+02 1.19704338e+02 1.17851196e+02 1.17121811e+02 1.14303261e+02 1.14189835e+02 1.15369827e+02 1.15373459e+02 1.13900452e+02 1.13025635e+02 1.14192940e+02 1.15910538e+02 1.14102058e+02 1.13759827e+02 1.12892990e+02 1.06835976e+02 1.00098381e+02 1.00618790e+02 1.06869949e+02 1.12138435e+02 1.05338013e+02 9.86382904e+01 9.87497177e+01 1.04904572e+02 1.10634216e+02 1.11741608e+02 1.12541580e+02 1.14683495e+02 1.14189095e+02 1.13401001e+02 1.12890198e+02 1.13993919e+02 1.15744171e+02 1.15192474e+02 1.13994537e+02 1.12680855e+02 1.13551163e+02 1.14023277e+02 1.13704323e+02 1.11784401e+02 1.08480766e+02 1.05477783e+02 1.06500862e+02 1.09110214e+02 1.12356857e+02 1.10286263e+02 1.08317108e+02 1.09013710e+02 1.11901665e+02 1.14517799e+02 1.14320221e+02 1.14128235e+02 1.13771553e+02 1.13957863e+02 1.13919319e+02 1.14061073e+02 1.14192429e+02 1.14218040e+02 1.13816628e+02 1.13506256e+02 1.13715324e+02 1.14107079e+02 1.14383904e+02 1.14421791e+02 1.14421913e+02 1.14671379e+02 1.15165604e+02 1.15354179e+02 1.15148445e+02 1.14769890e+02 1.14712883e+02 1.14265663e+02 1.15098160e+02 1.16840775e+02 1.17546829e+02 1.16763161e+02 1.15519394e+02 1.15449890e+02 1.15590332e+02 1.15062805e+02 1.15180023e+02 1.15600731e+02 1.15734238e+02 1.18520302e+02 1.21518196e+02 1.21864014e+02 1.18856674e+02 1.16125877e+02 1.16886024e+02 1.17033119e+02 1.19673340e+02 1.23007103e+02 1.22623764e+02 1.17554810e+02 1.12531647e+02 1.14127907e+02 1.15163963e+02 1.15881660e+02 1.13792984e+02 1.12668442e+02 1.11904449e+02 1.12627563e+02 1.13649879e+02 1.13566391e+02 1.12770622e+02 1.11928131e+02 1.09390938e+02 1.06835930e+02 1.05005180e+02 1.04887718e+02 1.06735466e+02 1.06710938e+02 1.06872391e+02 1.05968826e+02 1.07708824e+02 1.08854118e+02 1.07456841e+02 1.07919037e+02 1.08629150e+02 1.08276520e+02 1.05552116e+02 1.04997223e+02 1.07601036e+02 1.07641182e+02 1.06257858e+02 1.04739792e+02 1.08649445e+02 1.09511086e+02 1.12930565e+02 1.12240753e+02 1.12885704e+02 1.05782303e+02 9.87732315e+01 1.03621155e+02 1.18421944e+02 1.26557007e+02 1.22433784e+02 1.13213493e+02 1.13335365e+02 1.15575668e+02 1.19367439e+02 1.21223236e+02 1.20919983e+02 1.18930183e+02 1.15836403e+02 1.11705620e+02 1.08177124e+02 1.08133049e+02 1.10808357e+02 1.13179970e+02 1.13342453e+02 1.13659203e+02 1.13694199e+02 1.13848557e+02 1.09948738e+02 1.08735970e+02 1.05124687e+02 1.10639832e+02 1.22829704e+02 1.36699417e+02 1.35263596e+02 1.23670265e+02 1.11884598e+02 1.09230835e+02 1.09045982e+02 1.14656654e+02 1.25531288e+02 1.33333939e+02 1.35554611e+02 1.23170319e+02 1.13198128e+02 1.02098763e+02 1.08154640e+02 1.10608246e+02 1.12340553e+02 1.09830215e+02 1.09681648e+02 1.05957367e+02 1.08706772e+02 1.12196846e+02 1.15380051e+02 1.16965172e+02 1.16103706e+02 1.31850388e+02 1.40877914e+02 1.37677307e+02 1.16956223e+02 1.02491089e+02 1.10138916e+02 1.18411377e+02 1.17063126e+02 1.13404327e+02 1.22004669e+02 1.37017807e+02 1.36810989e+02 1.21201584e+02 1.04003151e+02 1.10704811e+02 1.15311592e+02 1.13364609e+02 9.90567551e+01 9.86957245e+01 1.01559227e+02 1.10698578e+02 1.05746010e+02 9.35293121e+01 9.33735580e+01 9.58378448e+01 1.00324265e+02 9.24990692e+01 1.01788521e+02 1.17567230e+02 1.20556786e+02 1.29819855e+02 1.43951675e+02 1.62912140e+02 1.64311295e+02 1.52750656e+02 1.54995651e+02 1.42080582e+02 1.37385254e+02 1.17011620e+02 9.14859238e+01 6.08804932e+01 5.55336723e+01 6.72371063e+01 8.00283279e+01 8.30511932e+01 8.62225494e+01 8.92625504e+01 8.78546295e+01 7.70280457e+01 9.31176224e+01 1.23483322e+02 1.37582825e+02 1.34043121e+02 1.11309769e+02 1.04530647e+02 9.73638153e+01 8.43025055e+01 1.01938240e+02 1.02922562e+02 1.15983238e+02 1.17261749e+02 1.29137329e+02 1.49598389e+02 1.31420212e+02 1.10860504e+02 9.72715149e+01 1.19873795e+02 1.26879326e+02 1.15691719e+02 9.22905273e+01 1.12963600e+02 1.36601105e+02 1.44261887e+02 1.25007683e+02 1.04468742e+02 1.29861725e+02 1.52594620e+02 1.48636246e+02 1.11667572e+02 8.66361771e+01 1.09173683e+02 1.25146988e+02 1.01321693e+02 6.44865494e+01 8.59966507e+01 1.26082916e+02 1.47876892e+02 1.32124451e+02 1.22516579e+02 1.21638908e+02 1.42261673e+02 1.58758438e+02 1.51673477e+02 1.08857491e+02 7.94814606e+01 8.18766022e+01 8.91265259e+01 9.09631805e+01 8.17310486e+01 8.45670624e+01 9.07013702e+01 1.11706329e+02 1.12152809e+02 9.62724686e+01 8.54492569e+01 8.50405197e+01 1.09214607e+02 1.25279099e+02 1.21015480e+02 1.09236435e+02 8.37315216e+01 8.96820145e+01 9.15214157e+01 8.71561203e+01 6.86966934e+01 6.68607025e+01 1.10937233e+02 1.48153046e+02 1.13737358e+02 4.77949753e+01 4.26675606e+01 1.00132149e+02 1.23788681e+02 9.25150146e+01 7.51933823e+01 9.95559540e+01 1.09426949e+02 9.99214554e+01 7.71791992e+01 9.18008575e+01 1.05851501e+02 1.12532516e+02 9.69138107e+01 7.31662369e+01 7.11327133e+01 6.93505936e+01 9.79220123e+01 1.18672981e+02 1.21783279e+02 9.62119141e+01 9.46805420e+01 1.52757050e+02 1.81832092e+02 1.63629135e+02 1.13100746e+02 1.11092171e+02 1.28713959e+02 1.06579407e+02 5.45213242e+01 3.49925003e+01 6.74477310e+01 9.34614334e+01 9.04513931e+01 7.61528625e+01 9.13817291e+01 9.22471390e+01 9.32255402e+01 8.36188278e+01 7.14015579e+01 5.38725052e+01 4.87966042e+01 5.83290825e+01 7.27880478e+01 9.44886627e+01 1.01843330e+02 1.03485176e+02 1.16560112e+02 1.19758141e+02 9.60098495e+01 6.60512085e+01 7.46811905e+01 1.09522362e+02 1.16235260e+02 1.08701370e+02 1.29797958e+02 1.85151566e+02 2.13726593e+02 1.86651108e+02 1.17794243e+02 9.94803696e+01 1.13014374e+02 1.21083031e+02 8.84091568e+01 6.34605827e+01 5.50730553e+01 4.75558510e+01 5.31274872e+01 6.53497009e+01 6.68741684e+01 4.76738968e+01 4.73115501e+01 1.00901489e+02 1.28304459e+02 9.87977753e+01 6.39999123e+01 9.82715073e+01 1.25702156e+02 9.50404205e+01 1.76783161e+01 -2.57553997e+01 -1.74464760e+01 -4.49391222e+00 8.87092209e+00 6.49235773e+00 1.12738161e+01 4.27124739e+00 2.44552364e+01 4.27899513e+01 4.95010452e+01 1.23802652e+01 2.78680439e+01 9.07841644e+01 1.40936508e+02 1.52621155e+02 1.39934143e+02 1.12342613e+02 7.57665939e+01 4.30983505e+01 5.35525093e+01 5.30021439e+01 5.22739487e+01 4.50155182e+01 5.13024254e+01 4.86840057e+01 5.20400391e+01 5.38382568e+01 4.72076836e+01 4.61600227e+01 4.12176094e+01 8.23745499e+01 1.24120728e+02 1.30502335e+02 9.61863022e+01 6.40939636e+01 6.78669357e+01 6.27420807e+01 6.63989792e+01 6.39528160e+01 6.42292709e+01 6.34913177e+01 8.66597214e+01 1.26627487e+02 1.08981300e+02 6.26210747e+01 4.75563431e+01 1.23332336e+02 1.73682861e+02 1.40576248e+02 6.88900833e+01 6.91340103e+01 1.08512512e+02 1.06498940e+02 7.91389771e+01 4.47228203e+01 7.95347366e+01 1.05013496e+02 1.30224197e+02 1.34284317e+02 9.00707932e+01 5.83130989e+01 6.68991394e+01 1.44076889e+02 1.80976379e+02 1.25538414e+02 5.37954712e+01 6.56883545e+01 1.22875717e+02 1.32941635e+02 1.01171585e+02 6.72413025e+01 9.41332932e+01 1.20989029e+02 1.36770111e+02 1.20163727e+02 8.49580841e+01 5.96371040e+01 9.11364212e+01 1.36408035e+02 1.50661057e+02 1.21342125e+02 6.26035118e+01 8.65631638e+01 1.08651634e+02 1.16209366e+02 8.04552002e+01 7.81826172e+01 1.21899933e+02 1.14762779e+02 7.60379562e+01 1.35348434e+01 4.32123375e+00 -4.01488580e-02 4.35059013e+01 9.15194855e+01 1.10277641e+02 9.10083771e+01 5.31944237e+01 3.12427292e+01 3.59878731e+01 5.98464127e+01 1.05819778e+02 1.16285049e+02 2.29840225e+02 2.72266296e+02 5.16150085e+02 2.47385956e+02 2.89264209e+03 -2.14130264e+02 -1.66074072e+03 3.14277173e+03 3.87220947e+03 4.06610522e+03 1.29894014e+04 25046594. -8.42500710e+09 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. -1101049216. -22439274. 4.14685898e+04 1.67291855e+04 2.34686670e+03 -3.62198901e+03 -1.93899158e+03 -8.67557907e+01 6.25456238e+00 -5.71653557e+01 9.76858444e+01 2.45580734e+02 3.50779266e+01 1.55488342e+03 2.78223291e+03 1.56362595e+02 -4.64798779e+03 -2.98160303e+03 -8.30647827e+02 -5.72818298e+02 -3.39329926e+02 -3.75329170e+01 3.19712505e+01 4.30337524e+01 1.32319870e+01 2.03633232e+01 2.86197281e+01 -3.78588796e+00 -3.29555969e+01 -2.25058002e+01 5.22423897e+01 1.09516281e+02 1.21016388e+02 6.73276672e+01 -1.13336439e+01 -4.52222023e+01 -3.66169128e+01 -3.88975143e+01 -4.45583458e+01 -4.26342125e+01 8.00564384e+00 5.98518562e+01 5.18428230e+01 5.26911068e+00 -2.58712730e+01 -2.10566878e+00 -5.51374376e-01 -6.63918018e+00 1.72704887e+01 1.67758350e+01 2.25348186e+01 2.40530729e+00 -2.99444637e+01 -6.84016800e+01 -9.09380264e+01 -2.91773243e+01 5.40705757e+01 8.38343964e+01 4.09061852e+01 -4.11676712e+01 -4.48424149e+01 -6.49980307e+00 2.11757469e+01 4.81551695e+00 -2.47720108e+01 -8.65808392e+00 2.25409298e+01 3.70639420e+01 -4.70290422e+00 -6.34315033e+01 -4.89912376e+01 -3.19488792e+01 -1.47540894e+01 -1.51760902e+01 -1.95767612e+01 -2.38458395e+00 -1.84269791e+01 -5.05438538e+01 -8.79088669e+01 -9.13969345e+01 -5.40861511e+01 -2.91754580e+00 4.22423019e+01 4.68078613e+01 1.09201694e+00 -2.00632915e+01 -2.33201656e+01 -5.38222847e+01 -1.07114357e+02 -1.08806091e+02 -4.23353653e+01 3.31204758e+01 4.04369698e+01 -1.53217573e+01 -8.68364105e+01 -1.00210304e+02 -9.58850632e+01 -9.23833389e+01 -8.92773590e+01 -7.78772964e+01 -4.73875732e+01 -2.14901161e+01 -2.71904430e+01 -5.81723633e+01 -7.15434036e+01 -3.91388779e+01 5.56542206e+00 2.33151035e+01 1.80387745e+01 -2.45708466e+01 -5.87103195e+01 -4.67020378e+01 -4.63236389e+01 -6.72425385e+01 -9.42709122e+01 -7.44552536e+01 -2.37568855e+01 -1.37678938e+01 -5.94732780e+01 -1.09992516e+02 -1.22264404e+02 -7.99198608e+01 -3.83334122e+01 -4.49696392e-01 1.26461201e+01 -1.15249052e+01 -2.91763458e+01 -3.26816406e+01 -6.43853912e+01 -9.97515030e+01 -1.14795578e+02 -8.67625275e+01 -4.55397491e+01 -2.31649952e+01 -2.60412540e+01 -5.17111855e+01 -6.71611557e+01 -7.05941391e+01 -7.68770370e+01 -1.01582718e+02 -1.01251770e+02 -6.16368866e+01 4.56504393e+00 3.79518547e+01 1.67579994e+01 -1.60203266e+01 -2.94766369e+01 -4.36863708e+01 -4.76016960e+01 -3.60303612e+01 -2.34945621e+01 -1.45511603e+00 1.15795832e+01 2.27340055e+00 -3.40496941e+01 -6.07994499e+01 -4.20314980e+01 -7.40441656e+00 -1.12393408e+01 -4.47201729e+01 -6.63111877e+01 -3.61287003e+01 4.99260139e+00 -7.60880089e+00 -2.65246983e+01 -4.14965935e+01 7.32187414e+00 5.55289230e+01 7.64334412e+01 1.90232620e+01 -5.71095047e+01 -8.02137451e+01 -7.81943665e+01 -7.65752487e+01 -7.76080551e+01 -5.01847839e+01 -7.79704189e+00 2.06789436e+01 -1.47241879e+01 -5.78080406e+01 -7.77271881e+01 -4.56218147e+01 -1.95754604e+01 -8.94827557e+00 -1.41988201e+01 -6.62692881e+00 6.04813242e+00 1.85938263e+01 -6.51810741e+00 -2.18834114e+01 -3.10452290e+01 -7.81135035e+00 1.95052280e+01 2.51511974e+01 -2.51998863e+01 -8.50257034e+01 -9.78478775e+01 -7.86813202e+01 -7.52896194e+01 -8.09444885e+01 -7.50326767e+01 -3.65294418e+01 -1.87974472e+01 -4.88249779e+01 -9.38347549e+01 -1.10597054e+02 -7.92359009e+01 -5.65660858e+01 -4.80472336e+01 -4.84755363e+01 -4.66401062e+01 -3.83111649e+01 -2.13453045e+01 -4.41477890e+01 -7.49235458e+01 -8.95675278e+01 -6.45259094e+01 -2.21742878e+01 -1.54367132e+01 -4.47396469e+01 -7.34758072e+01 -7.66274643e+01 -6.33649712e+01 -7.08545380e+01 -7.77739487e+01 -8.14694138e+01 -8.42901764e+01 -7.18959808e+01 -7.02418976e+01 -7.11315842e+01 -9.11785355e+01 -9.28562393e+01 -8.40385208e+01 -7.33927231e+01 -4.49790344e+01 -3.68661270e+01 -2.16253033e+01 -3.39663887e+01 -4.87072105e+01 -7.23102951e+01 -8.86719131e+01 -5.65256500e+01 -2.92103634e+01 -3.12720299e+01 -6.31246834e+01 -7.84658508e+01 -6.44493256e+01 -4.81353149e+01 -6.24907646e+01 -7.07378769e+01 -6.27824821e+01 -3.65225487e+01 -2.61797543e+01 -3.58660278e+01 -3.20256004e+01 -4.47262650e+01 -5.08900299e+01 -7.22183685e+01 -5.57190094e+01 -4.75996666e+01 -3.68229561e+01 -2.33308430e+01 -1.83506718e+01 -2.28524990e+01 -5.95187454e+01 -8.37258835e+01 -6.92246094e+01 -2.43816624e+01 -6.64657640e+00 -2.68946953e+01 -3.76312523e+01 -3.36216011e+01 -2.11696014e+01 -4.34237633e+01 -5.61380577e+01 -6.58752441e+01 -6.25102043e+01 -6.51480103e+01 -6.09573860e+01 -4.58200836e+01 -4.66431656e+01 -6.20508003e+01 -7.83712082e+01 -7.07272873e+01 -7.72323227e+01 -9.37438660e+01 -9.18840179e+01 -6.75449295e+01 -4.58171234e+01 -5.40392189e+01 -6.26407547e+01 -5.52510071e+01 -3.90586205e+01 -4.68414574e+01 -6.00136833e+01 -6.09276009e+01 -4.86054153e+01 -3.91568069e+01 -4.70215111e+01 -4.70019226e+01 -5.38398628e+01 -5.47160721e+01 -6.88973541e+01 -7.78273010e+01 -7.29226913e+01 -6.24729919e+01 -6.05858421e+01 -6.93088074e+01 -7.85467834e+01 -8.75336304e+01 -9.53640289e+01 -9.06682968e+01 -8.20700302e+01 -7.59349213e+01 -8.66773300e+01 -9.68593369e+01 -8.46001892e+01 -5.88298836e+01 -5.46051025e+01 -6.65686951e+01 -7.52313995e+01 -5.92145920e+01 -4.38722534e+01 -4.83075981e+01 -5.77549973e+01 -7.28271866e+01 -7.73306427e+01 -8.52786789e+01 -8.73520813e+01 -8.27569733e+01 -7.96241150e+01 -7.79921341e+01 -7.99893112e+01 -7.63515396e+01 -8.15419312e+01 -8.99939651e+01 -8.46911621e+01 -6.67511597e+01 -5.66647263e+01 -5.84066124e+01 -6.01303291e+01 -5.11546974e+01 -4.32988129e+01 -5.45960999e+01 -5.88569908e+01 -6.24578667e+01 -5.70849075e+01 -6.00250626e+01 -6.42217865e+01 -5.77476158e+01 -5.95941353e+01 -6.32675056e+01 -7.74295044e+01 -7.98110886e+01 -7.38102493e+01 -6.43297424e+01 -5.97079735e+01 -6.37714615e+01 -6.78725204e+01 -7.24636917e+01 -8.27033844e+01 -8.12744980e+01 -6.27258682e+01 -4.27371407e+01 -3.57267418e+01 -4.70723877e+01 -5.23459244e+01 -5.03931847e+01 -5.14460487e+01 -4.75282707e+01 -5.42856369e+01 -5.60358963e+01 -5.98604279e+01 -5.81647186e+01 -4.33702545e+01 -3.99518929e+01 -4.39854584e+01 -6.32550735e+01 -7.65077438e+01 -6.73882675e+01 -5.58440170e+01 -5.13897285e+01 -6.56103592e+01 -7.86087341e+01 -7.40561295e+01 -7.08447876e+01 -6.37972374e+01 -6.11455498e+01 -5.95737076e+01 -5.58739243e+01 -5.91082916e+01 -6.11827087e+01 -6.41039200e+01 -6.62815094e+01 -5.93481789e+01 -5.48531380e+01 -5.08811760e+01 -5.45134468e+01 -6.32085114e+01 -6.30068855e+01 -6.34464645e+01 -6.59456024e+01 -7.29258652e+01 -7.16075974e+01 -5.93338623e+01 -5.27363014e+01 -5.34523621e+01 -6.06894264e+01 -6.43788681e+01 -6.41595154e+01 -6.47299194e+01 -6.38441734e+01 -6.17936287e+01 -6.14934769e+01 -5.95726662e+01 -6.09647522e+01 -6.02619629e+01 -6.07393990e+01 -6.22828712e+01 -6.36418152e+01 -6.72001648e+01 -6.72653046e+01 -6.62010269e+01 -6.47386322e+01 -6.19896011e+01 -6.14545059e+01 -6.20006218e+01 -6.55881653e+01 -6.76111755e+01 -6.71542511e+01 -6.50288696e+01 -6.39010849e+01 -6.49056091e+01 -6.62626266e+01 -6.62984085e+01 -6.58277054e+01 -6.55141449e+01 -6.54207840e+01 -6.54530258e+01 -6.55654373e+01 -6.55366821e+01 -6.54107971e+01 -6.52817459e+01 -6.54587936e+01 -6.68446503e+01 -6.78907242e+01 -6.78112030e+01 -6.59397888e+01 -6.41357498e+01 -6.51021957e+01 -6.72824936e+01 -6.83094254e+01 -6.59952393e+01 -6.29208107e+01 -6.29308205e+01 -6.48152542e+01 -6.69391861e+01 -6.61702423e+01 -6.44053421e+01 -6.53396683e+01 -6.75833588e+01 -6.88120575e+01 -6.95696182e+01 -6.81239700e+01 -6.95789413e+01 -6.85439072e+01 -6.84946136e+01 -6.75965805e+01 -6.62460938e+01 -6.97921524e+01 -6.66329346e+01 -6.39491806e+01 -5.79664536e+01 -6.03303070e+01 -6.85482025e+01 -7.49521255e+01 -7.55539169e+01 -6.60898438e+01 -5.83509140e+01 -5.70407143e+01 -6.14664650e+01 -6.88390274e+01 -7.01494827e+01 -6.49912491e+01 -6.14267349e+01 -5.89607315e+01 -6.33087006e+01 -7.20554199e+01 -7.90442123e+01 -7.83235245e+01 -6.47035294e+01 -5.62123833e+01 -5.39739838e+01 -5.76854134e+01 -6.94872589e+01 -7.76671600e+01 -7.73481064e+01 -6.29925613e+01 -5.16099129e+01 -5.72574730e+01 -7.04009247e+01 -7.86162033e+01 -6.77475357e+01 -5.09912987e+01 -4.93986740e+01 -5.90840492e+01 -7.32893448e+01 -8.14932327e+01 -7.88424988e+01 -7.56630402e+01 -6.74243927e+01 -6.18145866e+01 -6.18786545e+01 -6.34907455e+01 -7.36033859e+01 -7.12326508e+01 -6.53066940e+01 -6.16542435e+01 -5.30923424e+01 -6.30300865e+01 -6.27372093e+01 -6.01631432e+01 -4.76223793e+01 -4.58497086e+01 -7.21434860e+01 -8.56578140e+01 -8.46381302e+01 -5.90048027e+01 -4.25848007e+01 -4.15445747e+01 -5.26713905e+01 -6.87320786e+01 -7.90417328e+01 -7.73520050e+01 -7.23047485e+01 -6.25397301e+01 -5.89291763e+01 -6.56014023e+01 -6.42927780e+01 -6.60391998e+01 -4.68093681e+01 -4.18754082e+01 -4.21346359e+01 -4.91180038e+01 -6.74601898e+01 -6.90057907e+01 -6.02005501e+01 -3.41300087e+01 -2.52031574e+01 -3.27653885e+01 -5.15171700e+01 -6.43847427e+01 -5.33703194e+01 -3.05663261e+01 -2.22872829e+01 -3.20317688e+01 -5.07258263e+01 -6.01143761e+01 -5.80379028e+01 -5.56379204e+01 -5.58018570e+01 -6.16814880e+01 -6.59908371e+01 -7.38938599e+01 -8.51497192e+01 -7.18995667e+01 -4.79273338e+01 -3.34586449e+01 -4.67497253e+01 -7.51902237e+01 -9.04996948e+01 -8.39194870e+01 -5.66627884e+01 -3.31633873e+01 -4.71719971e+01 -6.13893127e+01 -7.49761887e+01 -6.45129166e+01 -5.97778702e+01 -6.83057861e+01 -7.64291611e+01 -8.38462448e+01 -8.54327469e+01 -7.81712418e+01 -7.91857529e+01 -7.19636993e+01 -7.19583054e+01 -7.44028397e+01 -6.97052689e+01 -7.85509033e+01 -7.30021896e+01 -6.79714508e+01 -5.62408066e+01 -4.66210938e+01 -6.85172806e+01 -7.13644867e+01 -7.16271210e+01 -5.00452690e+01 -3.96013794e+01 -5.79975204e+01 -6.91663589e+01 -9.40109329e+01 -7.71002350e+01 -4.56787186e+01 -1.72365608e+01 -1.59022484e+01 -5.92067909e+01 -6.73455353e+01 -4.52359695e+01 -1.11338504e-01 9.17937374e+00 1.74928246e+01 2.35831490e+01 4.19100609e+01 1.41624786e+02 1.95870410e+03 1.10258655e+03 2.13292310e+03 6.74792822e+03 -125253952. 185504224. -139222448. 967352960. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 888686720. 981909888. -1.75417285e+04 -6.57703418e+03 -6.05154785e+02 -1.39233301e+03 -7.29704956e+02 1.84465344e+03 4.05449493e+02 -2.52783798e+02 -2.61522766e+02 -1.95381149e+02 -5.38930664e+02 -3.60985291e+02 -1.08202858e+02 8.11611099e+01 1.92987061e+02 1.63544418e+02 2.00001160e+02 1.44241058e+02 1.06313171e+02 1.90300007e+01 8.81903362e+00 -1.11463947e+01 -1.22672141e+00 -5.01148272e+00 -5.12246094e+01 -6.93178406e+01 -4.50298615e+01 -7.92007017e+00 -3.00837784e+01 -8.28856888e+01 -9.70344086e+01 -6.86202164e+01 -3.44236336e+01 -2.71981163e+01 -3.72052650e+01 -5.51965027e+01 -7.82789688e+01 -9.39541931e+01 -8.39266434e+01 -6.32849388e+01 -3.94759178e+01 -6.31000862e+01 -8.24304276e+01 -1.00105255e+02 -1.22953697e+02 -9.61950989e+01 -5.37856941e+01 4.63988781e-02 -7.72993279e+00 -6.96704178e+01 -7.90768051e+01 -5.45916595e+01 1.11182988e+00 7.39457893e+00 -3.36723862e+01 -5.76478691e+01 -6.69248352e+01 -4.06191978e+01 -3.97229767e+01 -5.60393372e+01 -7.78510666e+01 -1.07133179e+02 -1.21623894e+02 -1.02271294e+02 -6.44640198e+01 -3.80982208e+01 -5.46593323e+01 -8.02254028e+01 -1.16135887e+02 -1.51215668e+02 -1.58777176e+02 -1.48561188e+02 -1.06934166e+02 -8.12742920e+01 -1.01003479e+02 -7.99594193e+01 -4.28511620e+01 2.64683800e+01 1.57874918e+01 -3.42391739e+01 -6.17786026e+01 -6.64230118e+01 -6.37819862e+01 -5.78271484e+01 -3.94167824e+01 -2.58626881e+01 -4.65310516e+01 -7.23397293e+01 -6.04638901e+01 -5.63663330e+01 -6.53852005e+01 -9.56355667e+01 -8.31843109e+01 -5.26590614e+01 -7.50371246e+01 -7.33749924e+01 -6.62095718e+01 -2.35700455e+01 -1.89765110e+01 -7.46000290e+01 -8.01019516e+01 -4.63190956e+01 2.54560165e+01 4.24200020e+01 -7.84918118e+00 -4.25999489e+01 -7.13526993e+01 -7.38594055e+01 -8.01415558e+01 -8.81306839e+01 -6.89783325e+01 -7.21277924e+01 -7.88000488e+01 -7.87570953e+01 -5.29300766e+01 -2.02812634e+01 -3.11594753e+01 -3.43868790e+01 -2.55262146e+01 -5.66260414e+01 -5.74878120e+01 -3.22020645e+01 3.81522064e+01 4.21257858e+01 -3.85993462e+01 -6.58562012e+01 -3.37138863e+01 3.20710907e+01 3.85951843e+01 -1.63466892e+01 -3.98214111e+01 -5.25408745e+01 -4.73919067e+01 -2.78846607e+01 5.08304644e+00 2.42363853e+01 -1.16795588e+01 -5.36263885e+01 -4.10357475e+01 -6.32522821e+00 2.98815689e+01 5.90640962e-01 -1.97641621e+01 -3.33506775e+01 -5.08745689e+01 -5.38826141e+01 -6.12292099e+01 -4.68825340e+01 -4.40769157e+01 -7.35948868e+01 -8.10159836e+01 -5.78148270e+01 1.18057785e+01 6.57113037e+01 4.66849480e+01 1.04536114e+01 -3.89030571e+01 -4.34085846e+01 -4.77098694e+01 -6.66849976e+01 -8.23012619e+01 -6.81605530e+01 -5.68343506e+01 -5.38419342e+01 -7.09043198e+01 -4.60980835e+01 1.79808736e+00 4.39777412e+01 4.97286377e+01 -1.42232113e+01 -3.29125481e+01 -9.99386311e+00 3.64987450e+01 2.12747307e+01 -2.68340073e+01 -3.55862198e+01 -4.18906326e+01 -3.79752312e+01 -3.13394737e+01 -1.34988194e+01 2.25102091e+00 -2.01909370e+01 -4.15824394e+01 -2.74352798e+01 -2.87111626e+01 -3.89233932e+01 -7.96762772e+01 -1.18212585e+02 -1.33544739e+02 -1.48921371e+02 -8.67361755e+01 -3.79069824e+01 -2.64322233e+00 -2.50668049e+00 -4.73514595e+01 -4.06398926e+01 -1.55417099e+01 4.66527138e+01 5.65966339e+01 -1.01402121e+01 -6.37272644e+01 -9.68900909e+01 -7.02328186e+01 -7.15501328e+01 -7.55705261e+01 -7.34235992e+01 -6.56142731e+01 -7.51462936e+01 -7.54167175e+01 -5.59943962e+01 -1.46609716e+01 -2.12590351e+01 3.71220922e+00 -2.30875826e+00 -4.31319313e+01 -8.77035675e+01 -8.07307892e+01 -3.42964058e+01 -1.17896366e+01 -1.83857956e+01 1.53885889e+01 3.93435287e+01 6.83400269e+01 8.10699158e+01 4.30292397e+01 9.11840343e+00 -5.24115562e+01 -5.80041847e+01 -1.57215357e+01 2.79145699e+01 3.53449669e+01 3.42869306e+00 -1.51099491e+01 9.79104042e-01 2.40011141e-01 3.72589588e+00 6.51881027e+00 5.06860685e+00 4.55115604e+00 2.01356626e+00 5.71592808e-01 -8.31075609e-01 6.17400217e+00 2.63752518e+01 3.57602386e+01 2.23153152e+01 5.97067118e+00 5.41074848e+00 1.70363731e+01 1.31634312e+01 7.28190756e+00 -2.46208210e+01 -3.99171066e+01 -4.03746681e+01 -1.74530697e+01 8.10647392e+00 3.98078966e+00 2.92555022e+00 -8.11628327e-02 1.74499214e+00 -4.83527136e+00 -4.83765841e+00 -4.53893232e+00 7.35899162e+00 2.63285613e+00 1.08415871e+01 1.48618374e+01 2.08439465e+01 2.57152157e+01 2.80664673e+01 2.78620014e+01 1.83627949e+01 2.79175797e+01 3.41143532e+01 3.86379433e+01 2.38389626e+01 2.77288055e+01 3.16448860e+01 2.75948429e+01 1.57663345e+01 1.31627579e+01 3.24448318e+01 4.23686600e+01 3.78106537e+01 3.75519447e+01 4.90236092e+01 4.77348175e+01 3.37126045e+01 1.57573557e+01 1.75186749e+01 1.84123745e+01 1.77414913e+01 2.09633656e+01 2.27878418e+01 1.19260769e+01 -6.19955635e+00 -6.82276773e+00 6.84827900e+00 1.87044945e+01 1.24539833e+01 1.83201408e+01 1.26264706e+01 1.70837841e+01 1.15151615e+01 1.64910450e+01 1.24185629e+01 1.32313395e+01 2.94402199e+01 4.50614052e+01 4.16299820e+01 3.10556698e+01 2.81555653e+01 2.57415371e+01 1.49830036e+01 8.89198685e+00 1.95016251e+01 2.81653652e+01 2.35284100e+01 8.76208401e+00 1.96730461e+01 3.67676620e+01 4.15106659e+01 2.48291302e+01 4.12551260e+00 9.47832093e-02 5.27119815e-01 7.99122667e+00 3.28291931e+01 5.52776108e+01 6.31418037e+01 4.85237198e+01 3.26389771e+01 2.79904099e+01 2.54582729e+01 2.08917046e+01 1.89032269e+01 2.28583546e+01 2.69505272e+01 2.64290638e+01 2.87668171e+01 2.83199482e+01 1.94596806e+01 5.43457747e+00 -4.95130444e+00 -8.07832527e+00 -1.24822350e+01 -1.82957077e+00 7.44757318e+00 1.34416924e+01 8.61930275e+00 2.47994061e+01 3.30687065e+01 4.19610901e+01 2.69996910e+01 3.03349609e+01 2.20680981e+01 3.04080563e+01 2.22961807e+01 3.18410931e+01 2.70590496e+01 1.29962606e+01 -1.28360367e+01 1.97910233e+01 6.01514397e+01 7.55295334e+01 4.63566704e+01 1.95690308e+01 2.49867001e+01 3.14908581e+01 4.04577675e+01 3.54399414e+01 3.05951729e+01 2.64877720e+01 4.10973282e+01 4.94969177e+01 4.70327301e+01 2.42612572e+01 6.36489344e+00 2.09533710e+01 3.68689957e+01 5.35300636e+01 5.03165245e+01 5.26471405e+01 5.85601006e+01 7.39551239e+01 8.48457184e+01 7.21774139e+01 5.05590591e+01 4.00597916e+01 4.54427261e+01 4.28692017e+01 3.99896774e+01 3.47282143e+01 4.08675842e+01 3.88955269e+01 4.95951195e+01 4.52888412e+01 5.65543365e+01 4.70499687e+01 4.98512726e+01 4.51637383e+01 3.67285042e+01 1.89154282e+01 -1.42550402e+01 -2.48387432e+01 -1.29115601e+01 1.00101318e+01 2.31120129e+01 2.93044796e+01 3.43787384e+01 2.95941601e+01 2.15707016e+01 1.75661392e+01 1.98414078e+01 3.00288486e+01 3.74919167e+01 2.67013321e+01 8.98540974e+00 2.34735942e+00 9.44202137e+00 2.36522121e+01 2.84716568e+01 3.85770912e+01 4.63624535e+01 5.75942421e+01 5.14868851e+01 4.43139763e+01 4.04609451e+01 4.96997108e+01 5.32047844e+01 5.17246475e+01 5.59004669e+01 5.84225616e+01 5.22567863e+01 4.78564987e+01 4.26561584e+01 4.94424477e+01 5.46688156e+01 5.71917038e+01 5.20541267e+01 4.01753731e+01 3.42249222e+01 3.38135719e+01 3.87825546e+01 6.42227249e+01 1.44478592e+02 1.21165703e+02 2.29416397e+02 1.42254944e+02 1.09733960e+03 1.58870959e+03 3.08006134e+02 2.18010086e+02 5.78293030e+02 4.83591357e+03 1.15579453e+04 177180416. 45672612. 77218000. 593099968. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1153186048. 374735552. -1.91875703e+04 -7.17846191e+03 -5.49217407e+02 -1.04884766e+02 2.15180756e+02 2.89480377e+02 3.61253418e+02 3.94289246e+02 4.51289978e+02 4.98751190e+02 5.14952515e+02 4.71387604e+02 4.28284119e+02 4.31613403e+02 4.28861633e+02 4.46881317e+02 2.58912646e+03 1.48641089e+03 2.99929749e+02 1.24724983e+02 1.00089844e+02 8.60798416e+01 8.50577011e+01 7.63937683e+01 6.21607399e+01 5.17073326e+01 4.58931122e+01 4.59683418e+01 4.94176292e+01 5.44132080e+01 5.36395721e+01 4.84724960e+01 4.45315552e+01 4.45003624e+01 4.96491699e+01 5.07675743e+01 5.27310524e+01 5.06357613e+01 5.36552658e+01 5.71420174e+01 5.74024353e+01 5.42015533e+01 4.81887856e+01 4.31035347e+01 3.94908180e+01 4.36427078e+01 4.25558815e+01 4.13555260e+01 4.14025726e+01 4.76661224e+01 5.32552872e+01 5.16819763e+01 4.91060982e+01 5.17713242e+01 5.47147827e+01 5.79360161e+01 5.53356323e+01 5.34871330e+01 5.47288513e+01 5.60852356e+01 6.55158844e+01 7.38273010e+01 7.65748672e+01 7.73696518e+01 7.53761215e+01 8.14623718e+01 8.27836533e+01 7.68468933e+01 6.95874939e+01 5.94226227e+01 5.67253571e+01 5.44611588e+01 5.03656197e+01 4.42409210e+01 4.05398483e+01 4.24107780e+01 5.01074448e+01 5.79920654e+01 6.04922791e+01 6.16810532e+01 5.92098198e+01 6.76070786e+01 7.47217331e+01 8.28708267e+01 8.64249496e+01 8.30608597e+01 7.70939560e+01 6.85704193e+01 6.78774643e+01 6.90390625e+01 7.74589462e+01 8.31340561e+01 8.10531464e+01 7.13843079e+01 6.49921799e+01 6.56529007e+01 6.87572174e+01 7.08730545e+01 7.32696381e+01 6.64198990e+01 5.84553108e+01 5.58993492e+01 6.01485405e+01 6.56521912e+01 6.38140488e+01 6.40627747e+01 6.93885727e+01 7.37168655e+01 7.81916275e+01 7.62619476e+01 7.06802216e+01 6.28237648e+01 5.60798836e+01 5.59110374e+01 5.88243294e+01 6.17728233e+01 6.31631584e+01 6.06129532e+01 5.97831001e+01 6.07179680e+01 6.18794289e+01 6.28886414e+01 6.29786491e+01 6.49079361e+01 6.48881760e+01 6.51154709e+01 6.95425186e+01 7.48500748e+01 7.52192688e+01 7.04601822e+01 6.61709747e+01 6.91917648e+01 7.25517120e+01 7.49978485e+01 7.47816162e+01 7.23882141e+01 6.87361145e+01 6.55212402e+01 6.41552200e+01 6.45659637e+01 6.43400345e+01 6.42003937e+01 6.33992996e+01 6.25738411e+01 6.31410675e+01 6.46645279e+01 6.52303085e+01 6.45698624e+01 6.44884109e+01 6.49786758e+01 6.64246368e+01 6.84617233e+01 7.04994278e+01 7.01299362e+01 6.79925156e+01 6.58879700e+01 6.71559372e+01 6.87422028e+01 6.96258316e+01 6.94675980e+01 6.92252731e+01 6.91054001e+01 6.77858276e+01 6.70334091e+01 6.60417557e+01 6.58821793e+01 6.55679321e+01 6.54174118e+01 6.55870972e+01 6.56215591e+01 6.56736069e+01 6.55794907e+01 6.55746231e+01 6.54722137e+01 6.54527206e+01 6.56542664e+01 6.57939224e+01 6.55908813e+01 6.52727814e+01 6.51194992e+01 6.50683289e+01 6.52354507e+01 6.56730423e+01 6.51936874e+01 6.40303802e+01 6.37423210e+01 6.44154434e+01 6.54407120e+01 6.50954437e+01 6.48020935e+01 6.46068039e+01 6.48358307e+01 6.47695618e+01 6.48652115e+01 6.36501427e+01 6.29114075e+01 6.27907906e+01 6.34122543e+01 6.39427528e+01 6.49569550e+01 6.69839630e+01 6.67191467e+01 6.49993668e+01 6.29955139e+01 6.46389999e+01 6.57868347e+01 6.52688980e+01 6.43973160e+01 6.38012733e+01 6.42808151e+01 6.46754684e+01 6.49254837e+01 6.46893692e+01 6.35771027e+01 6.36360435e+01 6.40915527e+01 6.40173492e+01 6.49700546e+01 6.53012161e+01 6.66198654e+01 6.61786270e+01 6.57181015e+01 6.56771851e+01 6.56103592e+01 6.79177704e+01 6.98335724e+01 7.00917664e+01 6.87485428e+01 6.62668304e+01 6.70057068e+01 6.66095810e+01 6.84460678e+01 6.92307510e+01 6.98215256e+01 6.85022125e+01 6.74670486e+01 6.82132416e+01 6.83205948e+01 6.67117462e+01 6.38614655e+01 6.12206306e+01 6.15778236e+01 6.72446823e+01 7.36325531e+01 7.49352646e+01 6.87881470e+01 5.59606323e+01 4.77513466e+01 4.82579155e+01 5.57685013e+01 6.24095192e+01 5.45450287e+01 4.84876823e+01 4.83351326e+01 5.69422722e+01 6.37045403e+01 6.38603897e+01 6.41581116e+01 6.33259583e+01 6.17668457e+01 6.26389694e+01 6.39393234e+01 6.50702209e+01 6.10172195e+01 5.70804634e+01 6.05147362e+01 6.53557358e+01 6.82468796e+01 6.17244148e+01 5.54754829e+01 5.13814888e+01 5.16419830e+01 5.18307228e+01 5.50348663e+01 5.56194725e+01 5.67828941e+01 4.99401207e+01 4.53550529e+01 4.74916687e+01 5.53762779e+01 6.38221512e+01 6.23222694e+01 6.19146881e+01 5.70301666e+01 5.60196533e+01 6.27444687e+01 7.18258743e+01 7.21769867e+01 6.64728317e+01 5.80936012e+01 6.17202415e+01 6.23767738e+01 6.15804138e+01 5.87678032e+01 4.67122955e+01 3.68635254e+01 3.77862625e+01 4.64510689e+01 5.87458801e+01 5.74015503e+01 5.70232620e+01 5.66781425e+01 5.69237556e+01 4.82749367e+01 3.67852058e+01 3.34127350e+01 3.84103279e+01 5.31939087e+01 5.23710175e+01 5.31973076e+01 5.07828255e+01 5.57040291e+01 5.48154221e+01 5.22139626e+01 4.83057785e+01 5.20820389e+01 5.63495903e+01 5.71681213e+01 5.44097862e+01 5.57944145e+01 6.00596085e+01 5.98530388e+01 5.88078461e+01 5.52551689e+01 4.77069855e+01 3.21948738e+01 2.14257584e+01 1.70429611e+01 1.91216202e+01 1.98591309e+01 3.54841118e+01 4.31414566e+01 5.14088249e+01 5.17473183e+01 5.67922249e+01 4.95433426e+01 3.74313583e+01 3.88767395e+01 4.48328171e+01 6.30670815e+01 7.31133957e+01 7.45029297e+01 6.90719757e+01 5.25764236e+01 4.80020714e+01 4.13930397e+01 3.18341656e+01 2.52104359e+01 3.13867798e+01 4.63383636e+01 6.52294769e+01 5.78818855e+01 4.97139587e+01 4.01257782e+01 3.94476242e+01 4.14112396e+01 4.42136230e+01 5.54293213e+01 6.21211548e+01 6.17717552e+01 5.94749298e+01 5.86103020e+01 6.14205856e+01 6.42260742e+01 6.16928368e+01 5.67111740e+01 4.91293373e+01 4.34793091e+01 4.25145683e+01 2.57807121e+01 9.23375893e+00 1.78011932e+01 4.82670784e+01 5.75434990e+01 3.38815269e+01 1.77115784e+01 2.81623344e+01 4.74248810e+01 3.10541210e+01 1.54236031e+01 1.07361803e+01 2.40692959e+01 3.54834251e+01 3.64273491e+01 3.11186943e+01 2.28855553e+01 2.00884533e+01 3.08395023e+01 4.71989784e+01 4.91962318e+01 4.76916695e+01 3.93540230e+01 4.06318932e+01 3.52321396e+01 2.79670277e+01 1.25577927e+01 3.04725761e+01 6.25088081e+01 6.02559280e+01 3.19839134e+01 7.70287991e+00 2.52706509e+01 3.86423416e+01 3.19128418e+01 2.53505592e+01 3.65509377e+01 5.55289307e+01 6.85582428e+01 6.44784775e+01 6.03171806e+01 3.94330750e+01 1.62485466e+01 2.36583176e+01 5.13166351e+01 5.66257210e+01 2.27547913e+01 1.46386137e+01 3.49985313e+01 5.85001144e+01 5.57641258e+01 5.04356689e+01 6.26740265e+01 8.18714600e+01 6.89503021e+01 4.21117096e+01 2.07629986e+01 3.31789970e+01 4.32018967e+01 4.19846001e+01 3.75877380e+01 3.11631126e+01 2.66459103e+01 2.96226692e+01 4.27844467e+01 4.45870705e+01 2.23483257e+01 -1.22674954e+00 -8.06179225e-01 1.41756697e+01 6.03714466e+00 -2.12697029e+01 -8.01495838e+00 3.18881493e+01 6.80721436e+01 6.56562881e+01 4.77501259e+01 5.19463882e+01 5.89664192e+01 4.96490898e+01 3.41089745e+01 2.00917130e+01 2.65630207e+01 3.88025284e+01 4.59251709e+01 5.38319588e+01 5.41345520e+01 4.91604004e+01 4.59701157e+01 4.53377647e+01 4.60268211e+01 2.70903740e+01 1.03942385e+01 1.82720413e+01 4.28892746e+01 4.89024467e+01 2.98506298e+01 3.54688835e+01 5.47743950e+01 4.88258171e+01 1.40032709e+00 -4.87816200e+01 -5.27511673e+01 -2.62347755e+01 -1.96127682e+01 -2.83390961e+01 -2.16511078e+01 1.99748170e+00 1.68713970e+01 1.12024879e+01 1.27649126e+01 1.32253561e+01 1.15056634e+00 8.81590664e-01 2.19158955e+01 4.66998749e+01 3.21114540e+01 2.96044159e+00 5.05111074e+00 2.59112206e+01 1.92676105e+01 -1.01997299e+01 8.93314457e+00 7.02680817e+01 1.08108383e+02 9.12042618e+01 6.07383995e+01 6.90948410e+01 9.01762390e+01 9.20378189e+01 7.60912933e+01 6.33163033e+01 7.34373627e+01 7.88010254e+01 7.58610229e+01 5.47794800e+01 1.67773495e+01 -1.64338303e+01 -3.75425949e+01 -3.98887825e+01 -2.28471190e-01 4.12394600e+01 5.98887100e+01 4.40202599e+01 2.98246746e+01 3.60856705e+01 3.39584351e+01 4.81260986e+01 7.09772186e+01 6.59216690e+01 4.53257561e+01 2.37362003e+01 2.37926350e+01 1.90524502e+01 -1.44230013e+01 -3.83741722e+01 -3.17007542e+01 -4.66895247e+00 1.42947645e+01 1.19611416e+01 1.74247189e+01 1.57341909e+01 4.90876007e+00 -4.45798159e+00 -1.93760943e+00 5.09520912e+00 8.54451370e+00 1.40156326e+01 2.26822853e+01 2.02544518e+01 -1.25303955e+01 -5.51601677e+01 -5.00634460e+01 -2.26024380e+01 -1.21454248e+01 -3.79977684e+01 -3.96392326e+01 -1.92679787e+01 2.53494477e+00 -2.24951706e+01 -4.95851135e+01 -4.84230270e+01 -2.19936943e+01 2.10117149e+01 2.90292645e+01 2.69701672e+01 -6.55700636e+00 -3.59640198e+01 -3.06538982e+01 8.83186460e-01 1.43840432e+00 -3.22776337e+01 -4.51249924e+01 -2.78277054e+01 8.16239643e+00 -8.92369938e+00 -3.19695969e+01 -3.38741226e+01 -1.26358771e+00 2.93465824e+01 1.71420631e+01 -1.54369507e+01 -2.93457870e+01 -3.10254688e+01 -1.82360821e+01 -1.37529058e+01 -2.41038723e+01 -2.83702946e+01 -5.05313683e+01 -5.49560814e+01 -5.15236893e+01 -3.37023201e+01 -1.30506220e+01 -8.95942593e+00 2.97714376e+00 -3.73777062e-01 -7.94509947e-01 -6.71158743e+00 -1.10164919e+01 -1.31932173e+01 -1.01756382e+01 -5.12718022e-01 2.42741566e+01 3.41196060e+01 8.47553253e-01 -4.01681252e+01 -5.63676796e+01 -7.99318848e+01 -1.48022812e+02 -2.64781433e+02 -2.81401367e+02 -7.76567932e+02 -3.74135406e+02 -1.37690186e+02 -5.12692383e+02 5.70276337e+01 -1.48233337e+03 -4.31090820e+03 -7.69042850e+06 6.81935411e+09 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. -18890046. -2.78302417e+03 -5.65158752e+02 -4.35592804e+02 -1.85760437e+02 5.40331841e+01 9.18388748e+01 2.21943169e+01 3.61165161e+01 4.96953239e+01 2.64753933e+01 1.17102461e+01 1.61708546e+01 -9.51639099e+01 -1.34022079e+02 -4.75708847e+01 1.47646561e+02 2.05017426e+02 1.13462181e+02 5.65123253e+01 -8.29691887e+00 -3.56314507e+01 -2.28150215e+01 -1.78270569e+01 -1.04873142e+01 -4.84984159e+00 1.97070370e+01 4.89609070e+01 5.07047844e+01 2.03807583e+01 -1.01660490e+01 -6.21350241e+00 -2.99037242e+00 -3.58854938e+00 1.60477028e+01 1.67867699e+01 1.39723978e+01 -2.95037031e+00 -1.99032841e+01 -3.57167854e+01 -4.31467857e+01 -8.78202343e+00 3.78948708e+01 5.37417603e+01 2.61505108e+01 -2.34343700e+01 -2.84011059e+01 -1.08606672e+01 -1.03056679e+01 -1.69449310e+01 -2.98277855e+00 2.26086674e+01 3.66313477e+01 1.43145428e+01 -2.03412399e+01 -5.37498245e+01 -4.94144020e+01 -3.79669228e+01 -2.75495167e+01 -8.01783371e+00 4.90974140e+00 1.55385771e+01 -2.40814090e+00 -2.48615437e+01 -4.62159538e+01 -4.66764259e+01 -1.38501425e+01 1.62766361e+01 2.92084389e+01 3.58415375e+01 1.92448215e+01 1.83757191e+01 3.35595012e+00 -2.75970936e+01 -5.17511024e+01 -5.53200417e+01 -2.61790943e+01 6.42745137e-01 8.84368801e+00 -2.62433553e+00 -2.69470081e+01 -3.54097748e+01 -4.15984268e+01 -3.86678352e+01 -2.92580643e+01 -2.55314045e+01 -1.73820992e+01 -1.23615217e+01 -1.35494070e+01 -2.72730770e+01 -4.47334976e+01 -3.73148727e+01 -1.24348955e+01 1.35431919e+01 1.41557741e+01 -2.04448814e+01 -4.07036591e+01 -2.66146488e+01 -1.73912220e+01 -3.25759544e+01 -4.48321953e+01 -2.35183811e+01 1.38411713e+01 2.55983524e+01 -1.12225747e+00 -3.65683975e+01 -5.62432251e+01 -4.42176819e+01 -3.34689102e+01 -1.86036968e+01 -4.84203911e+00 -6.75297642e+00 -6.42037058e+00 -1.18841972e+01 -3.42153282e+01 -5.87194099e+01 -6.49295959e+01 -3.62592545e+01 -9.02729452e-01 1.22837477e+01 -2.06880474e+00 -2.85377445e+01 -3.91592979e+01 -3.92027321e+01 -3.99635963e+01 -3.63525620e+01 -2.40971661e+01 -2.39627218e+00 2.39460335e+01 2.64556713e+01 8.70576859e+00 -1.25922680e+01 -1.79905796e+01 -2.44071007e+01 -3.69117012e+01 -3.33327293e+01 -2.72258930e+01 -1.24245176e+01 -1.49493494e+01 -2.02655621e+01 -2.45299625e+01 -2.30250950e+01 -1.08861675e+01 -8.51525688e+00 -1.86389809e+01 -3.21031990e+01 -3.58908119e+01 -1.41895952e+01 3.65501595e+00 -6.74519300e+00 -1.44317713e+01 -1.85896873e+01 -4.56199884e+00 7.54976702e+00 6.90397215e+00 -2.58122482e+01 -5.88328476e+01 -5.29169884e+01 -1.49060850e+01 9.27288723e+00 8.68210793e+00 -2.89795899e+00 2.23897743e+00 1.19264118e-01 -2.14512196e+01 -4.68999557e+01 -5.23557320e+01 -2.99675102e+01 -1.12087059e+01 9.90461445e+00 2.29843216e+01 1.45980749e+01 1.05423546e+01 1.45850372e+00 -8.93409348e+00 -1.52686224e+01 -1.84385738e+01 1.63740468e+00 1.04485760e+01 1.07248383e+01 -6.47431278e+00 -2.92892742e+01 -3.39353943e+01 -2.54531918e+01 -2.10682507e+01 -1.74925804e+01 -1.95432262e+01 -3.87697601e+00 7.35733151e-01 -2.22736015e+01 -5.21194420e+01 -6.21151009e+01 -4.14510765e+01 -1.71284237e+01 5.36180878e+00 1.76888866e+01 8.23328209e+00 -2.28294873e+00 -1.37834864e+01 -3.67875290e+01 -5.81106644e+01 -6.13993607e+01 -3.13357773e+01 2.43245554e+00 1.94005718e+01 4.72528219e+00 -2.84066849e+01 -4.44082756e+01 -3.76320572e+01 -2.37833672e+01 -2.24713326e+01 -2.49946804e+01 -2.75330772e+01 -2.29766502e+01 -2.07606735e+01 -2.03066921e+01 -3.17943573e+01 -4.12492943e+01 -4.02620926e+01 -2.69293900e+01 -7.00973558e+00 -2.79590797e+00 -2.84698510e+00 -1.55070391e+01 -3.16105042e+01 -3.57558174e+01 -3.76047363e+01 -1.47860661e+01 -3.77532744e+00 -6.23877573e+00 -2.06343994e+01 -2.14876328e+01 -9.43076515e+00 7.33612478e-01 -2.20282803e+01 -4.34518127e+01 -5.25565338e+01 -2.97599182e+01 -1.20264292e+01 -1.19677114e+01 -9.22257996e+00 -2.48831367e+01 -3.74579811e+01 -5.18335304e+01 -3.23075600e+01 -1.18783255e+01 -1.27413321e+01 -1.85896301e+01 -1.45548458e+01 2.38844109e+00 4.38816220e-01 -1.97277431e+01 -2.61522217e+01 -1.06837759e+01 -6.95338535e+00 -2.11150875e+01 -2.74425087e+01 -2.04559631e+01 -1.43885498e+01 -2.77063408e+01 -3.56559563e+01 -3.64346046e+01 -2.20528736e+01 -1.28116646e+01 -1.50480776e+01 -1.54097538e+01 -2.56430016e+01 -3.45950050e+01 -3.79639320e+01 -3.34794235e+01 -3.42070770e+01 -4.33547516e+01 -3.59128952e+01 -2.61929379e+01 -2.35752029e+01 -3.71949387e+01 -4.64735451e+01 -4.26642494e+01 -2.87589741e+01 -2.49051323e+01 -3.25008354e+01 -3.47977219e+01 -3.03851261e+01 -2.75895481e+01 -3.04453964e+01 -2.11307983e+01 -1.23689985e+01 -1.18959293e+01 -2.87025986e+01 -4.53813477e+01 -4.75621414e+01 -4.25425949e+01 -3.58470383e+01 -3.57917137e+01 -3.47299461e+01 -3.93169479e+01 -4.59453011e+01 -4.58483543e+01 -4.16426086e+01 -3.55368843e+01 -4.15826035e+01 -4.66105270e+01 -3.88539238e+01 -2.19864044e+01 -2.04601059e+01 -3.32445412e+01 -4.36341934e+01 -3.85025368e+01 -3.83321114e+01 -4.30611649e+01 -4.43622093e+01 -4.41592293e+01 -4.59963379e+01 -5.20617752e+01 -5.33977509e+01 -4.94525948e+01 -5.17974548e+01 -5.34265137e+01 -5.03068275e+01 -4.13121910e+01 -3.73867455e+01 -4.25139465e+01 -4.06356010e+01 -2.90130634e+01 -2.14023418e+01 -2.16312485e+01 -2.42695866e+01 -2.12302246e+01 -1.83405380e+01 -2.54980831e+01 -3.31984062e+01 -3.80273590e+01 -3.59731407e+01 -3.70533409e+01 -4.20870857e+01 -4.21355171e+01 -4.21618042e+01 -4.55817528e+01 -4.92777100e+01 -4.77540512e+01 -3.71220284e+01 -3.63086853e+01 -3.74210167e+01 -3.95213318e+01 -3.70708771e+01 -3.71667442e+01 -4.64397469e+01 -4.55803757e+01 -3.61902008e+01 -2.55656643e+01 -2.18191509e+01 -2.89203110e+01 -2.90465431e+01 -2.62689705e+01 -2.31845856e+01 -2.41121120e+01 -3.31552162e+01 -3.75170670e+01 -4.09345589e+01 -3.60621414e+01 -2.19117813e+01 -1.87625790e+01 -2.49417686e+01 -3.97503738e+01 -4.48494987e+01 -3.53469429e+01 -3.11572933e+01 -3.20734329e+01 -4.01418457e+01 -4.40939941e+01 -3.91146698e+01 -3.77044830e+01 -3.36654625e+01 -2.98674908e+01 -2.87964935e+01 -2.97216682e+01 -3.59537773e+01 -3.73343658e+01 -3.60652618e+01 -3.28704224e+01 -3.00903759e+01 -3.30076408e+01 -3.59321556e+01 -3.97005730e+01 -3.71541176e+01 -2.99527340e+01 -2.67794361e+01 -3.09030476e+01 -3.85424271e+01 -4.12339668e+01 -3.48690567e+01 -2.86616993e+01 -2.61571445e+01 -3.07744179e+01 -3.63198013e+01 -3.66696053e+01 -3.69114532e+01 -3.41438675e+01 -3.13100033e+01 -2.97416115e+01 -2.93298645e+01 -3.27378120e+01 -3.34802055e+01 -3.42346497e+01 -3.33471870e+01 -3.24609795e+01 -3.40219612e+01 -3.57018776e+01 -3.66822128e+01 -3.52208824e+01 -3.06473484e+01 -2.97583828e+01 -3.11975899e+01 -3.51623344e+01 -3.70752983e+01 -3.56426353e+01 -3.44138641e+01 -3.31238251e+01 -3.43645935e+01 -3.53304062e+01 -3.48794479e+01 -3.41674156e+01 -3.36144753e+01 -3.30184326e+01 -3.30451927e+01 -3.30855713e+01 -3.42426338e+01 -3.45325050e+01 -3.40525284e+01 -3.30081215e+01 -3.22118607e+01 -3.28144569e+01 -3.35049210e+01 -3.38889160e+01 -3.35819130e+01 -3.29953651e+01 -3.29664001e+01 -3.30992775e+01 -3.31481743e+01 -3.30121651e+01 -3.31304169e+01 -3.35958862e+01 -3.42099495e+01 -3.41163673e+01 -3.34658356e+01 -3.29352722e+01 -3.24712906e+01 -3.25465088e+01 -3.31963959e+01 -3.36627083e+01 -3.35879707e+01 -3.23064651e+01 -3.16344261e+01 -3.12886410e+01 -3.17727165e+01 -3.33889542e+01 -3.30226440e+01 -3.24356651e+01 -3.04460907e+01 -3.03113480e+01 -3.18870239e+01 -3.38786087e+01 -3.54282150e+01 -3.39651871e+01 -3.31691055e+01 -3.24132843e+01 -3.27537537e+01 -3.37492752e+01 -3.56124687e+01 -3.59454956e+01 -3.60493240e+01 -3.46858978e+01 -3.48083496e+01 -3.50490837e+01 -3.44808960e+01 -3.44954872e+01 -3.06518555e+01 -3.14356022e+01 -3.17905922e+01 -3.33544464e+01 -3.48364677e+01 -3.24695511e+01 -3.22754631e+01 -3.27099609e+01 -3.67642479e+01 -4.23662643e+01 -4.27832489e+01 -4.08816338e+01 -3.41729851e+01 -2.78371944e+01 -3.05413532e+01 -3.56400375e+01 -4.21877823e+01 -4.31136894e+01 -3.91452560e+01 -3.48710098e+01 -2.75609455e+01 -2.57526989e+01 -2.84205666e+01 -3.26502647e+01 -3.51178398e+01 -3.13354092e+01 -2.66848259e+01 -2.43710232e+01 -2.46356888e+01 -3.40373192e+01 -3.96291580e+01 -4.06758080e+01 -3.26111832e+01 -2.65732479e+01 -3.19394264e+01 -4.04672432e+01 -4.37411728e+01 -3.69460220e+01 -2.86874771e+01 -2.88644218e+01 -2.73449154e+01 -2.96113167e+01 -3.37987747e+01 -3.65398827e+01 -3.44002151e+01 -2.64412632e+01 -2.22462330e+01 -2.58795719e+01 -2.79868279e+01 -3.35689659e+01 -2.97082024e+01 -2.92785511e+01 -2.85631180e+01 -2.83517513e+01 -3.66239128e+01 -3.87608795e+01 -3.82547913e+01 -2.68970985e+01 -2.22141476e+01 -2.14175644e+01 -2.46646729e+01 -2.45339222e+01 -2.51047611e+01 -2.47965794e+01 -2.60018787e+01 -2.18717155e+01 -2.12586250e+01 -2.44498615e+01 -2.85985203e+01 -3.31001472e+01 -2.88454838e+01 -3.00098705e+01 -3.13238831e+01 -3.69243660e+01 -4.05275154e+01 -2.94896679e+01 -2.54918175e+01 -2.27275810e+01 -2.62372169e+01 -3.80842705e+01 -4.41091385e+01 -4.52571030e+01 -3.02572250e+01 -1.62356968e+01 -1.56896105e+01 -2.24022312e+01 -3.33952179e+01 -3.03065643e+01 -2.15409870e+01 -2.19522610e+01 -2.43924809e+01 -2.99487114e+01 -3.32004509e+01 -3.52305298e+01 -3.47311363e+01 -2.65644588e+01 -2.64121685e+01 -2.75441875e+01 -2.58375568e+01 -3.51682892e+01 -3.81431274e+01 -4.19256134e+01 -3.33732948e+01 -2.67856121e+01 -2.88145809e+01 -3.11728230e+01 -2.80361443e+01 -1.75736141e+01 -3.68899345e+00 -1.74697113e+01 -2.98067055e+01 -4.58098259e+01 -4.67108498e+01 -3.97944221e+01 -3.89240837e+01 -2.97424545e+01 -3.17723370e+01 -3.55185890e+01 -3.77690506e+01 -4.64151649e+01 -3.87507133e+01 -3.67729797e+01 -2.92688885e+01 -2.51363068e+01 -3.45977592e+01 -2.62024803e+01 -1.75991344e+01 -5.08045006e+00 -8.50793648e+00 -2.77583866e+01 -3.64530334e+01 -3.71084213e+01 -9.26942825e+00 2.44756527e+01 -2.77979398e+00 2.42950416e+00 -3.98044777e+01 -6.52128754e+01 -2.07011780e+02 7.08321457e+01 1.19370506e+02 -3.28015967e+03 -6.76067285e+03 -125253952. 185504224. -139222448. 967352960. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 888686720. 981909888. 5.54291943e+03 2.14342554e+03 3.08234070e+02 1.57952515e+02 4.09287643e+01 -7.10944977e+01 -2.96683102e+01 1.03744698e+01 1.61063061e+01 -1.26421630e+00 -9.28594875e+00 -2.53943672e+01 -2.88971539e+01 -1.40817871e+01 -1.19285192e+01 -1.70720196e+01 -3.44989700e+01 -4.95572739e+01 -4.25266342e+01 -2.45511703e+01 -2.13159161e+01 -2.27624893e+01 -3.57417374e+01 -2.66871796e+01 -1.77998734e+01 -1.08420019e+01 -3.84355307e+00 -1.14941263e+01 -1.39510307e+01 -3.10239296e+01 -4.78721504e+01 -3.33712997e+01 -1.32051907e+01 8.14173031e+00 7.11411655e-01 -3.89790878e+01 -6.23500862e+01 -6.95073090e+01 -3.50603485e+01 -2.14701672e+01 -3.16121864e+01 -4.41768188e+01 -4.98891258e+01 -2.08749218e+01 1.02038264e+00 5.85801840e+00 -1.20044699e+01 -4.36179504e+01 -5.83770256e+01 -6.11868095e+01 -5.62021980e+01 -2.97709675e+01 -1.71679688e+01 -6.61115885e+00 -1.83053322e+01 -4.33437042e+01 -3.48473930e+01 -2.13664665e+01 -9.87806606e+00 -3.46684990e+01 -7.17012329e+01 -6.21970062e+01 -2.72511444e+01 1.68547020e+01 2.86281414e+01 1.16201553e+01 -1.30986433e+01 -4.48276939e+01 -5.44589653e+01 -4.41047516e+01 -2.09851017e+01 1.93902624e+00 5.15870619e+00 1.99584758e+00 1.83788979e+00 -1.58441849e+01 -1.21400356e+01 -2.52544327e+01 -1.62970924e+01 -1.86804085e+01 -3.23216667e+01 -1.54004993e+01 -4.07390371e-02 2.64015560e+01 2.74715023e+01 -4.02916610e-01 -2.75483608e+01 -3.79857979e+01 -1.52274847e+01 1.21907406e+01 1.63130455e+01 1.51744232e+01 4.24430180e+00 -4.69072580e+00 1.93123865e+00 1.44182134e+00 1.59490929e+01 -6.79987550e-01 -1.63002014e+01 -2.50138664e+01 -2.67531452e+01 -4.25641012e+00 6.34484673e+00 1.71547527e+01 1.41113100e+01 -1.09610701e+01 -6.13535738e+00 2.42517161e+00 2.54427128e+01 2.91815643e+01 5.05051804e+00 -1.75591736e+01 -2.48564091e+01 2.58288860e+00 3.49069290e+01 2.78393269e+01 2.02798233e+01 3.17688489e+00 -6.88895988e+00 -1.01544199e+01 -8.21154308e+00 1.79133873e+01 2.07870007e+01 1.59700375e+01 9.82187653e+00 7.06893802e-01 1.00678864e+01 1.27952995e+01 1.71451035e+01 8.74601173e+00 -2.24284134e+01 -2.45228329e+01 -7.56266308e+00 1.82527828e+01 2.89579792e+01 3.25576663e+00 -1.30538712e+01 -1.75016193e+01 4.32487011e+00 2.67265720e+01 2.04792976e+01 2.23686733e+01 9.99873543e+00 -3.98598671e+00 -1.51873283e+01 -1.53720846e+01 9.96341324e+00 2.26953201e+01 2.08427887e+01 8.97998047e+00 -5.32619047e+00 5.71022177e+00 1.60592785e+01 3.05217056e+01 2.20458183e+01 -9.81557465e+00 -2.61124420e+01 -1.14332418e+01 2.11615257e+01 4.33992462e+01 3.61995125e+01 2.56621952e+01 7.98052597e+00 1.56889057e+01 3.14567604e+01 2.83865433e+01 1.96240463e+01 2.79763675e+00 1.37737024e+00 1.40414152e+01 1.60152302e+01 2.90467091e+01 2.53129654e+01 1.64330750e+01 -5.01014709e+00 -3.31991043e+01 -8.68879986e+00 1.67043171e+01 3.60385361e+01 2.64567280e+01 -1.78872085e+00 9.12586117e+00 1.97789631e+01 3.93313522e+01 3.52019768e+01 1.85451450e+01 1.42670832e+01 4.57003927e+00 -6.49939954e-01 -4.53030872e+00 -1.54768543e+01 2.21837330e+00 7.81275749e+00 6.03379726e+00 1.15806551e+01 2.37879014e+00 2.15430145e+01 1.74265728e+01 3.20445786e+01 2.50201130e+01 -8.86495399e+00 -1.79517689e+01 -1.71462994e+01 1.99747391e+01 3.62332649e+01 2.76327953e+01 1.16541033e+01 -1.92989922e+00 1.46764383e+01 2.97233238e+01 2.00594788e+01 4.57803696e-01 -2.52694511e+01 -2.93670254e+01 -3.45107698e+00 2.40787354e+01 3.43018074e+01 8.33103561e+00 -1.46088133e+01 -7.59039831e+00 -7.91048336e+00 6.47398353e-01 -1.86388946e+00 -6.41314507e+00 -4.59449291e+00 -4.92298126e+00 2.09299469e+00 -1.98557222e+00 -4.60129118e+00 6.48003757e-01 6.99028158e+00 8.00617313e+00 1.56566584e+00 -4.37341738e+00 -1.59173727e+00 -4.08792162e+00 -2.20691729e+00 -5.15191936e+00 1.39154136e+00 3.22922301e+00 7.24628019e+00 7.33392239e+00 5.66124058e+00 2.16227078e+00 -9.92367983e-01 1.45720136e+00 4.61768675e+00 1.05686474e+01 8.52536774e+00 8.49163055e+00 2.88759923e+00 9.08740330e+00 1.27123785e+01 1.35012274e+01 4.49276924e+00 -1.65076390e-01 1.56110895e+00 8.32732856e-01 3.97426581e+00 9.26478672e+00 1.86584606e+01 1.37942858e+01 1.23675747e+01 6.71893883e+00 1.11191435e+01 3.19108868e+00 3.59847069e+00 5.04525948e+00 1.39455194e+01 1.19861794e+01 1.38373699e+01 7.22360373e+00 4.93085194e+00 3.14402199e+00 9.15682316e+00 1.85493507e+01 1.47088394e+01 1.11086283e+01 7.03381252e+00 9.41164970e+00 1.10224943e+01 9.58456135e+00 8.01750660e+00 7.25502443e+00 -1.47339475e+00 -7.40662432e+00 -1.09858818e+01 -4.56489420e+00 -1.15358584e-01 5.43657875e+00 4.27540350e+00 6.10880280e+00 6.34186411e+00 2.15037556e+01 2.46523552e+01 2.85060120e+01 1.09418697e+01 6.69066095e+00 -3.44049883e+00 3.01240945e+00 -1.38051820e+00 1.01938748e+00 1.78152645e+00 8.06793499e+00 9.93859291e+00 1.17246027e+01 5.25948381e+00 -4.58570290e+00 -8.87827206e+00 -2.38845801e+00 2.53971624e+00 1.72209988e+01 3.36873093e+01 4.20629196e+01 3.06666470e+01 8.69559860e+00 2.83983731e+00 2.84402013e+00 1.19520063e+01 6.51358891e+00 -6.98930883e+00 -1.04211168e+01 -1.89027172e-02 1.39914255e+01 1.26114979e+01 1.27417583e+01 1.75591316e+01 2.69509578e+00 -1.52031231e+01 -1.84442997e+01 -5.90964317e+00 3.21213889e+00 1.33317113e+00 4.40636492e+00 5.92490578e+00 4.82771397e+00 9.13166714e+00 1.29892673e+01 1.68631668e+01 5.60549355e+00 2.49374604e+00 4.08717728e+00 1.59965277e+01 3.62504082e+01 4.95008240e+01 4.73001060e+01 2.67078400e+01 1.16472826e+01 1.29671288e+01 2.38312397e+01 2.22516651e+01 1.80674858e+01 1.14563417e+01 2.60883789e+01 3.24878464e+01 3.83588448e+01 2.77131500e+01 2.33457870e+01 1.97951965e+01 2.17893333e+01 3.18226776e+01 4.33429985e+01 2.58608551e+01 9.04837549e-01 -6.02640629e+00 1.00099049e+01 2.11782074e+01 1.92508926e+01 3.20982552e+01 4.50998650e+01 4.54300194e+01 3.04930134e+01 1.55941658e+01 1.45872145e+01 1.88338413e+01 3.11093960e+01 4.32942772e+01 4.75088120e+01 4.00705986e+01 3.27520180e+01 2.65917206e+01 2.68459892e+01 2.35527515e+01 2.38347225e+01 1.80785809e+01 1.43328304e+01 1.13585138e+01 1.65339108e+01 1.70918503e+01 2.01400242e+01 1.96052761e+01 2.45814838e+01 2.29149208e+01 2.24855614e+01 3.12693901e+01 4.01754608e+01 3.60434570e+01 1.10475445e+01 -3.65550447e+00 2.33194160e+00 1.17958279e+01 2.00963135e+01 1.58651943e+01 2.60850639e+01 3.16960144e+01 3.88987961e+01 3.46309967e+01 2.77047482e+01 2.72811298e+01 3.91685181e+01 4.94879570e+01 3.28614159e+01 7.54313469e+00 5.36804676e-01 1.68196125e+01 2.89767361e+01 3.66813393e+01 4.39580460e+01 3.85472336e+01 2.24890022e+01 1.54345417e+01 2.37666912e+01 3.39757347e+01 3.09674778e+01 2.80548267e+01 1.53589001e+01 -2.26741004e+00 -3.89530897e+00 3.31025004e+00 2.02277870e+01 2.87053928e+01 3.52813797e+01 3.06645069e+01 2.22664375e+01 1.80059128e+01 1.60423374e+01 1.36228628e+01 1.12966242e+01 7.91797638e+00 8.21333218e+00 1.22527933e+01 1.89164753e+01 2.04356232e+01 2.31280861e+01 5.15115662e+01 7.22225037e+01 1.09711372e+02 7.83744125e+01 4.41529236e+01 -9.78644466e+00 -1.08890667e+01 -5.57824230e+00 -1.35865993e+01 4.29348259e+01 5.92594482e+02 7.72261658e+01 -8.27843945e+03 45672612. 77218000. 593099968. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1153186048. 6.28572070e+03 1.30400806e+03 1.14375816e+02 1.61247467e+02 7.06306381e+01 6.18631248e+01 5.46031570e+01 4.49700470e+01 3.93374825e+01 2.34453564e+01 1.20196514e+01 9.43473434e+00 2.03248158e+01 2.86696720e+01 2.61280193e+01 2.69992313e+01 2.47502060e+01 -4.52656441e+01 -5.10920372e+01 2.86107326e+00 2.18710957e+01 3.20121269e+01 3.32003098e+01 2.70704327e+01 2.13167496e+01 2.60171299e+01 2.89888515e+01 2.94850388e+01 2.58318443e+01 2.47896557e+01 2.17922668e+01 2.08833523e+01 2.27323418e+01 2.57961025e+01 2.73448944e+01 2.58453903e+01 2.26067028e+01 2.09586754e+01 2.10585804e+01 2.32889462e+01 2.40932693e+01 2.14677448e+01 2.22419605e+01 2.36701164e+01 2.57117653e+01 2.75615292e+01 2.84214802e+01 3.82248154e+01 4.56279259e+01 4.70183640e+01 3.94795265e+01 3.28920784e+01 3.11070061e+01 3.12227516e+01 3.11860828e+01 3.31462097e+01 3.19939442e+01 2.99808788e+01 2.73977757e+01 2.57153225e+01 2.25190105e+01 1.91314087e+01 1.63388119e+01 1.87490902e+01 2.13913918e+01 2.47696018e+01 2.20322247e+01 1.81322250e+01 1.99737282e+01 2.43515205e+01 3.11968708e+01 2.86163826e+01 2.82650299e+01 3.30934296e+01 4.25261002e+01 4.82955856e+01 4.71647415e+01 4.46300163e+01 4.41654968e+01 4.00150604e+01 3.66462440e+01 3.45909233e+01 3.60175095e+01 3.73720398e+01 3.18193150e+01 2.70877914e+01 2.61128101e+01 3.04644699e+01 3.50795135e+01 3.43649025e+01 3.40957642e+01 3.14800262e+01 3.11551094e+01 3.17662258e+01 3.21912422e+01 3.12216778e+01 2.82026691e+01 2.67422409e+01 2.59251518e+01 2.58069382e+01 2.89257755e+01 3.25006905e+01 3.64768143e+01 3.73471794e+01 3.32880554e+01 3.10039177e+01 2.84652367e+01 3.08620796e+01 3.18037262e+01 2.88201294e+01 2.53054256e+01 2.54577560e+01 2.88224049e+01 3.39197502e+01 3.46537704e+01 3.46437263e+01 3.37386131e+01 3.34905624e+01 3.38140488e+01 3.43665810e+01 3.46556549e+01 3.40571938e+01 3.34158134e+01 3.22080460e+01 3.27757225e+01 3.22601624e+01 3.18013477e+01 3.10162563e+01 3.07918148e+01 3.08412571e+01 3.07539043e+01 3.11153488e+01 3.26365395e+01 3.41644974e+01 3.23535385e+01 2.92766495e+01 2.85110340e+01 3.08234444e+01 3.30774956e+01 3.29593048e+01 3.30464668e+01 3.33592224e+01 3.35259361e+01 3.33839264e+01 3.31622238e+01 3.31672554e+01 3.31126022e+01 3.35229340e+01 3.36952286e+01 3.35182724e+01 3.31280022e+01 3.28955688e+01 3.29883575e+01 3.30324707e+01 3.31768570e+01 3.35900307e+01 3.37178116e+01 3.35742645e+01 3.33290863e+01 3.25534439e+01 3.16097126e+01 3.06370163e+01 3.07734947e+01 3.16450806e+01 3.22726593e+01 3.29107513e+01 3.30005379e+01 3.32096863e+01 3.32092171e+01 3.30750618e+01 3.32128563e+01 3.33588295e+01 3.33350334e+01 3.31961441e+01 3.31356850e+01 3.31506577e+01 3.30257454e+01 3.28058472e+01 3.27124672e+01 3.28369217e+01 3.30377846e+01 3.32050972e+01 3.31056175e+01 3.29926262e+01 3.30079269e+01 3.30753746e+01 3.29983788e+01 3.27757759e+01 3.26312485e+01 3.27634239e+01 3.29452934e+01 3.30858498e+01 3.29612122e+01 3.28485718e+01 3.29733429e+01 3.22595634e+01 3.13687553e+01 3.10915718e+01 3.20582314e+01 3.28093758e+01 3.14517727e+01 3.00622368e+01 2.90158806e+01 2.87912502e+01 3.02373352e+01 3.13676548e+01 3.31185226e+01 3.30845795e+01 3.31396675e+01 3.31177444e+01 3.31484680e+01 3.35969582e+01 3.36243248e+01 3.39008179e+01 3.40709305e+01 3.36228294e+01 3.35943527e+01 3.33962669e+01 3.41788254e+01 3.49440918e+01 3.48713150e+01 3.53517380e+01 3.45810394e+01 3.45785370e+01 3.40361404e+01 3.20990601e+01 3.00069332e+01 2.96687393e+01 3.14183350e+01 3.26784286e+01 3.14667587e+01 3.19919777e+01 3.21111870e+01 3.14381008e+01 3.08335247e+01 3.11463642e+01 3.24528732e+01 3.19379559e+01 3.07342472e+01 3.11417065e+01 3.10297413e+01 3.25782471e+01 3.22646866e+01 3.17375584e+01 3.03743744e+01 2.68556042e+01 2.42648106e+01 2.96713753e+01 3.75389137e+01 4.09502487e+01 3.54737625e+01 3.06671848e+01 3.40153122e+01 3.71493721e+01 3.65079041e+01 3.14756927e+01 2.83651371e+01 2.96635551e+01 3.09678154e+01 3.17173977e+01 3.10428734e+01 2.87946892e+01 2.74412632e+01 2.74662857e+01 3.01636333e+01 3.20019531e+01 3.03067570e+01 2.72916489e+01 2.70740108e+01 2.89693527e+01 2.99979553e+01 2.70814819e+01 2.70456161e+01 2.90300846e+01 3.11308937e+01 3.32745285e+01 3.34968414e+01 3.49124489e+01 3.26740685e+01 2.72289124e+01 2.07047176e+01 1.95832138e+01 2.40070362e+01 3.04525623e+01 3.17066536e+01 3.14361916e+01 2.58586540e+01 1.96647797e+01 1.99400558e+01 2.47837486e+01 2.85716400e+01 2.47728920e+01 2.53181438e+01 2.43591461e+01 2.81959305e+01 2.68157310e+01 2.94262638e+01 2.90723782e+01 3.04142036e+01 2.89376488e+01 2.61702747e+01 2.47462463e+01 2.52523327e+01 2.63236370e+01 2.79542522e+01 3.03095455e+01 3.20649796e+01 3.43635521e+01 3.27902374e+01 3.06138020e+01 2.83798332e+01 3.00911427e+01 3.28248749e+01 3.38200455e+01 3.43457947e+01 3.27622948e+01 3.32686462e+01 3.39609528e+01 3.46242638e+01 3.30789719e+01 3.01368732e+01 3.01707458e+01 2.76417484e+01 2.10478039e+01 2.03488750e+01 2.22358341e+01 2.80437832e+01 2.89029655e+01 3.09827023e+01 3.17546597e+01 2.84618187e+01 2.07847576e+01 1.69405537e+01 1.90007172e+01 3.08298225e+01 4.12076759e+01 4.88505173e+01 5.35956154e+01 4.79896469e+01 4.20340309e+01 2.54943981e+01 1.74244118e+01 1.72126083e+01 2.52112522e+01 2.60015125e+01 1.46107969e+01 1.58851757e+01 2.72904167e+01 4.20296745e+01 3.98010178e+01 3.04679050e+01 2.19340878e+01 2.05205040e+01 2.95239105e+01 3.04575539e+01 2.86986847e+01 1.63351250e+01 5.22421694e+00 4.34089804e+00 1.21702728e+01 1.76832085e+01 8.92531395e+00 5.98219776e+00 1.07813730e+01 1.94151363e+01 1.41678190e+01 5.95905876e+00 3.77307796e+00 1.06650381e+01 2.02311020e+01 2.17976379e+01 2.60247288e+01 1.79018974e+01 1.27470770e+01 1.56386023e+01 2.37743912e+01 2.93669624e+01 3.30072784e+01 3.91603546e+01 4.09050522e+01 3.27794037e+01 2.58916721e+01 2.02761765e+01 1.39843569e+01 1.28137302e+01 6.68174028e+00 5.16806412e+00 6.76132584e+00 1.99952450e+01 2.56866493e+01 2.40742111e+01 2.14793663e+01 2.43355904e+01 2.81902847e+01 3.26466293e+01 3.59619141e+01 3.93840370e+01 2.63332214e+01 1.17854881e+01 1.51084604e+01 3.50424805e+01 3.78181419e+01 1.77682190e+01 8.21854210e+00 1.78248730e+01 3.34476662e+01 2.31581650e+01 8.15906715e+00 1.36372411e+00 1.00647087e+01 1.32930937e+01 6.65729046e+00 7.66035938e+00 2.15079422e+01 3.25736809e+01 3.15786819e+01 2.65030823e+01 1.89175587e+01 1.78330288e+01 1.07043343e+01 1.88482225e+00 -4.40688819e-01 -6.63245487e+00 -8.03356171e+00 -5.85794592e+00 7.43923664e+00 1.95316639e+01 1.89311905e+01 2.13639011e+01 2.23122959e+01 2.52089825e+01 1.54133272e+01 7.84311056e+00 2.68758941e+00 3.22809768e+00 2.09909010e+00 -5.74169970e+00 -7.98853934e-02 1.13077669e+01 2.43925228e+01 3.03363476e+01 3.72654991e+01 3.86760406e+01 3.50185051e+01 1.76600361e+01 1.76691127e+00 1.56528795e+00 1.64331114e+00 1.24230754e+00 -9.03014600e-01 1.12450399e+01 2.18540096e+01 2.49372559e+01 1.86303806e+01 2.01139526e+01 1.09980059e+01 6.41000605e+00 3.14878345e+00 -3.07005000e+00 -6.92422485e+00 -8.55484581e+00 1.84690142e+00 1.13293505e+01 1.46135178e+01 1.17191448e+01 6.55247068e+00 3.65871620e+00 -7.01971483e+00 -1.98937626e+01 -2.52742348e+01 -1.79153843e+01 1.37062454e+00 1.74773006e+01 3.09406567e+01 3.20723114e+01 3.01907978e+01 2.32205906e+01 2.56544094e+01 2.67810287e+01 3.13061733e+01 3.18764992e+01 3.26909828e+01 3.49394913e+01 3.34520187e+01 2.70957451e+01 1.25007591e+01 1.70726311e+00 4.63045216e+00 1.53617058e+01 1.23175993e+01 9.40495431e-01 4.79974699e+00 3.43651390e+00 -1.58837128e+00 -5.40233755e+00 7.45305395e+00 2.01073666e+01 7.34523201e+00 -9.17079926e+00 -1.08440809e+01 2.78112388e+00 1.96338785e+00 -1.30540781e+01 -1.92038937e+01 -2.13770413e+00 4.22412777e+00 -5.18845975e-01 4.10480738e+00 1.00162954e+01 1.77889347e+01 -4.10488462e+00 -1.80838966e+01 -1.89653797e+01 -7.34504414e+00 6.70174503e+00 7.69717741e+00 7.53478909e+00 -6.50727749e+00 -2.79834576e+01 -2.44607048e+01 -1.01755695e+01 1.08454237e+01 1.19274359e+01 1.60108414e+01 1.81603889e+01 1.69363670e+01 1.21772642e+01 7.96345043e+00 8.95982838e+00 4.79537630e+00 4.68485689e+00 2.55319285e+00 9.77378941e+00 1.41786633e+01 1.19141884e+01 -3.65480733e+00 -2.24007416e+01 -1.94503670e+01 -4.73287010e+00 1.29474533e+00 -9.54486847e+00 -4.32814169e+00 8.09888554e+00 2.27919006e+01 1.91634312e+01 1.85373821e+01 1.61278934e+01 1.43379688e+01 1.52290268e+01 1.85606136e+01 2.23630962e+01 6.62599754e+00 -1.80417900e+01 -3.01604061e+01 -1.73114128e+01 -1.51858435e+01 -2.59878101e+01 -2.62808857e+01 -8.70253849e+00 2.54452300e+00 3.17441463e+00 3.38087296e+00 3.89607763e+00 -3.50357085e-01 -1.08825960e+01 -7.31040668e+00 -2.37480447e-01 -7.42009544e+00 -2.84379597e+01 -3.83692169e+01 -1.91514702e+01 -8.49143887e+00 -1.93649540e+01 -2.27315159e+01 -1.80670242e+01 3.05656910e+00 -2.13611293e+00 -1.01406622e+01 6.34900475e+00 2.78087616e+01 2.66158695e+01 -5.46064377e+00 -2.09120369e+01 -7.18721437e+00 8.15055275e+00 1.25102854e+01 1.51140699e+01 -1.66750264e+00 -2.01569309e+01 -3.20611839e+01 -2.02689915e+01 -8.62518501e+00 -1.87399731e+01 -3.71576233e+01 -2.67890987e+01 -9.67425632e+00 -1.84581995e+00 -6.31231804e+01 -9.41390991e+01 -1.86823441e+02 -9.62816849e+01 -9.12954468e+02 4.44621086e+01 6.48769226e+02 -1.17668518e+03 -1.48813391e+03 4.60575391e+03 1.02681279e+04 -7.69042850e+06 6.81935411e+09 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. -6.86737715e+09 -1.88435586e+04 -4.14930859e+03 -6.08133728e+02 -3.60543457e+02 1.07170850e+03 7.33421387e+02 6.22430534e+01 -1.02482712e+00 -1.47140608e+01 -7.62071838e+01 -1.28299133e+02 -3.35501099e+01 -5.54912720e+02 -8.05727966e+02 8.09428596e+00 1.28434839e+03 9.52475098e+02 2.70512970e+02 1.69655670e+02 1.11267807e+02 2.75158310e+01 2.14447289e+01 2.13283386e+01 1.28287191e+01 9.02995682e+00 4.49375582e+00 3.40422802e-02 -3.42730689e+00 -3.73092842e+00 -4.76856142e-01 4.41382170e+00 2.18951988e+00 -1.14715803e+00 -7.21218348e+00 -3.86654305e+00 -2.55399346e+00 -8.31151605e-01 -4.67425919e+00 -2.42763615e+00 -2.90449691e+00 1.95943034e+00 1.15607178e+00 8.56369972e-01 -1.70352113e+00 -2.98938084e+00 -3.65110087e+00 -5.60909605e+00 -4.11957073e+00 -4.44081020e+00 -5.48065758e+00 -6.70872355e+00 -5.52333069e+00 -5.62039375e+00 -4.78681564e+00 -4.39038754e+00 -1.92477369e+00 -2.82623100e+00 -4.76917982e+00 -8.34470749e+00 -8.18294811e+00 -7.10528612e+00 -6.88527489e+00 -8.47470188e+00 -8.35928154e+00 -8.01232624e+00 -5.15305328e+00 -5.79319000e+00 -4.92805958e+00 -6.99175978e+00 -7.09045935e+00 -5.79674625e+00 -2.60489655e+00 4.51889336e-02 -1.47459579e+00 -2.06809425e+00 -4.42728424e+00 -7.74245501e+00 -1.20649776e+01 -1.15473337e+01 -7.98741055e+00 -6.71390295e+00 -5.57427311e+00 -6.41614962e+00 -6.60821295e+00 -6.23969269e+00 -7.17768908e+00 -8.84821892e+00 -1.14010162e+01 -1.00625343e+01 -6.98068428e+00 -4.93558788e+00 -5.17693901e+00 -8.75360489e+00 -1.24902744e+01 -1.57348375e+01 -1.41609602e+01 -1.33416615e+01 -1.18033381e+01 -1.05669279e+01 -9.81051159e+00 -8.30351830e+00 -8.14694405e+00 -7.19355392e+00 -8.84874725e+00 -1.10499973e+01 -1.24228640e+01 -9.63555622e+00 -8.28966618e+00 -9.31121731e+00 -1.21658936e+01 -1.43697186e+01 -1.46713800e+01 -1.65262070e+01 -1.58510847e+01 -1.31551723e+01 -1.00005484e+01 -9.17851734e+00 -1.09418383e+01 -1.34396849e+01 -1.35770397e+01 -1.45604277e+01 -1.16031256e+01 -9.46519947e+00 -8.47608471e+00 -9.88562775e+00 -1.12537537e+01 -1.00658264e+01 -1.20124245e+01 -1.47237272e+01 -1.55590096e+01 -1.31347399e+01 -9.78318024e+00 -9.45332909e+00 -9.57536507e+00 -1.09234657e+01 -1.09744663e+01 -1.05306950e+01 -1.11063805e+01 -1.25190620e+01 -1.54660473e+01 -1.34183302e+01 -9.28780651e+00 -6.30713081e+00 -7.01689768e+00 -1.11428232e+01 -1.35082617e+01 -1.55714159e+01 -1.43561068e+01 -1.23677282e+01 -1.09764986e+01 -1.04380503e+01 -1.05624313e+01 -1.19605961e+01 -1.20850878e+01 -1.20054646e+01 -1.30010405e+01 -1.37056246e+01 -1.51976614e+01 -1.39859276e+01 -1.49509983e+01 -1.53811502e+01 -1.40028925e+01 -1.16479521e+01 -9.79424858e+00 -9.09323215e+00 -9.99605274e+00 -1.05419559e+01 -1.08868523e+01 -1.29808044e+01 -1.57778330e+01 -1.85264645e+01 -1.69747581e+01 -1.55575495e+01 -1.44271946e+01 -1.63905983e+01 -1.27524452e+01 -1.21144133e+01 -1.25200119e+01 -1.80294857e+01 -1.94352360e+01 -1.63091946e+01 -1.26843624e+01 -9.71783257e+00 -9.30211926e+00 -1.13138447e+01 -1.31850281e+01 -1.37419443e+01 -1.52620459e+01 -1.52963581e+01 -1.64860420e+01 -1.44844437e+01 -1.04085121e+01 -9.31747913e+00 -1.16305494e+01 -1.67061939e+01 -1.74840965e+01 -1.64282665e+01 -1.60452156e+01 -1.50526276e+01 -1.32873735e+01 -1.14363728e+01 -1.39512424e+01 -1.68169727e+01 -1.88448067e+01 -1.67923088e+01 -1.50965500e+01 -1.50040426e+01 -1.88156700e+01 -1.85226669e+01 -1.78284931e+01 -1.45810308e+01 -1.57785788e+01 -1.63437195e+01 -1.62507095e+01 -1.74665756e+01 -1.49510355e+01 -1.62195072e+01 -1.44516754e+01 -1.91936169e+01 -1.86423187e+01 -1.81443748e+01 -1.67410870e+01 -1.74465733e+01 -1.78101139e+01 -1.88638992e+01 -1.55255690e+01 -1.84024296e+01 -1.68726521e+01 -2.09684181e+01 -1.92479534e+01 -1.78009739e+01 -1.81459389e+01 -1.85619297e+01 -1.77198029e+01 -1.72982426e+01 -1.59987431e+01 -1.79675026e+01 -1.94049816e+01 -2.15915470e+01 -2.17841091e+01 -1.76404362e+01 -1.65655403e+01 -1.64976730e+01 -1.97776203e+01 -1.87381248e+01 -1.85575485e+01 -1.73476219e+01 -1.91222763e+01 -1.99617519e+01 -2.04941692e+01 -1.93274727e+01 -1.77719784e+01 -1.82902927e+01 -1.90697937e+01 -1.97846184e+01 -2.03349552e+01 -1.96605415e+01 -2.01399441e+01 -1.86158314e+01 -1.84765892e+01 -1.75476093e+01 -1.81527538e+01 -1.80396557e+01 -1.84088421e+01 -1.74082565e+01 -1.84859390e+01 -1.87394047e+01 -2.04384136e+01 -2.00237350e+01 -1.97348976e+01 -1.93502502e+01 -1.92320099e+01 -1.88140945e+01 -1.93840351e+01 -1.86453724e+01 -1.98621578e+01 -1.99964237e+01 -2.19776115e+01 -2.16012611e+01 -2.11745605e+01 -2.09875965e+01 -2.15412445e+01 -2.10827618e+01 -2.17325249e+01 -2.19512081e+01 -2.30164967e+01 -2.16267776e+01 -2.15542450e+01 -2.15834694e+01 -2.16633835e+01 -2.09128628e+01 -2.04408360e+01 -2.16256313e+01 -2.22073116e+01 -2.15761986e+01 -2.08447914e+01 -2.05853405e+01 -2.10105076e+01 -2.14424973e+01 -2.25988026e+01 -2.25599117e+01 -2.27596722e+01 -2.20638657e+01 -2.20822010e+01 -2.32930298e+01 -2.29329433e+01 -2.28084221e+01 -2.04646301e+01 -2.03465252e+01 -2.21822929e+01 -2.16225452e+01 -2.16151943e+01 -2.11413364e+01 -2.28117790e+01 -2.34957199e+01 -2.23314972e+01 -2.20284119e+01 -2.23065434e+01 -2.34673328e+01 -2.33646183e+01 -2.26148491e+01 -2.16256485e+01 -2.27347336e+01 -2.33866386e+01 -2.34399014e+01 -2.28688850e+01 -2.27373066e+01 -2.22071533e+01 -2.14867344e+01 -2.16575317e+01 -2.23110752e+01 -2.26313705e+01 -2.25589409e+01 -2.24325542e+01 -2.26990891e+01 -2.22643471e+01 -2.23363552e+01 -2.19354496e+01 -2.20774937e+01 -2.31806526e+01 -2.37469234e+01 -2.42304573e+01 -2.33312283e+01 -2.33755836e+01 -2.28328934e+01 -2.32489319e+01 -2.36708946e+01 -2.31327324e+01 -2.25323391e+01 -2.25653706e+01 -2.31745987e+01 -2.38178177e+01 -2.40187683e+01 -2.38500481e+01 -2.38123493e+01 -2.32309589e+01 -2.34097347e+01 -2.32102089e+01 -2.34835453e+01 -2.37698231e+01 -2.33139629e+01 -2.23259945e+01 -2.19752274e+01 -2.18650608e+01 -2.26385193e+01 -2.32463741e+01 -2.34167042e+01 -2.34809666e+01 -2.28130646e+01 -2.31295395e+01 -2.28076839e+01 -2.30662613e+01 -2.29495926e+01 -2.25179653e+01 -2.24214134e+01 -2.25584583e+01 -2.30419407e+01 -2.33673534e+01 -2.34423599e+01 -2.33990040e+01 -2.34252205e+01 -2.39443035e+01 -2.41100597e+01 -2.46968651e+01 -2.37313862e+01 -2.32889385e+01 -2.21157284e+01 -2.23240051e+01 -2.29040527e+01 -2.32392044e+01 -2.35519238e+01 -2.32018318e+01 -2.37722721e+01 -2.37873688e+01 -2.36481705e+01 -2.32305107e+01 -2.32257957e+01 -2.38535194e+01 -2.39930649e+01 -2.41140022e+01 -2.39077377e+01 -2.42056522e+01 -2.38341541e+01 -2.38130054e+01 -2.36260185e+01 -2.39159679e+01 -2.38080730e+01 -2.36473083e+01 -2.36224117e+01 -2.36776924e+01 -2.37469349e+01 -2.36268120e+01 -2.35301285e+01 -2.33924255e+01 -2.33108997e+01 -2.33620682e+01 -2.34187679e+01 -2.35300064e+01 -2.35452290e+01 -2.37361202e+01 -2.40644894e+01 -2.41248379e+01 -2.40668812e+01 -2.37856007e+01 -2.38388062e+01 -2.38873158e+01 -2.39686966e+01 -2.40052052e+01 -2.39197865e+01 -2.39282417e+01 -2.38512573e+01 -2.39605770e+01 -2.39280491e+01 -2.39460316e+01 -2.39416313e+01 -2.39514675e+01 -2.39385700e+01 -2.39266300e+01 -2.39330769e+01 -2.39367676e+01 -2.39278316e+01 -2.39072933e+01 -2.39322014e+01 -2.40056858e+01 -2.40693684e+01 -2.39769058e+01 -2.38432732e+01 -2.37494488e+01 -2.38455296e+01 -2.39932404e+01 -2.40424461e+01 -2.38739300e+01 -2.38042431e+01 -2.39678631e+01 -2.42204628e+01 -2.40971031e+01 -2.40002537e+01 -2.39420757e+01 -2.41351013e+01 -2.38341045e+01 -2.39776745e+01 -2.37583771e+01 -2.37120781e+01 -2.36808701e+01 -2.36086273e+01 -2.37919979e+01 -2.35561066e+01 -2.38331623e+01 -2.40502949e+01 -2.41263847e+01 -2.37133064e+01 -2.35515480e+01 -2.32997189e+01 -2.40236149e+01 -2.41870461e+01 -2.43763409e+01 -2.36415501e+01 -2.33961105e+01 -2.33367271e+01 -2.35271912e+01 -2.34659061e+01 -2.34404278e+01 -2.35690155e+01 -2.34335747e+01 -2.31224613e+01 -2.32183762e+01 -2.31300640e+01 -2.33292503e+01 -2.35779839e+01 -2.36062126e+01 -2.32096272e+01 -2.20627365e+01 -2.26889877e+01 -2.34719410e+01 -2.42817650e+01 -2.41166763e+01 -2.35199928e+01 -2.32097187e+01 -2.31047287e+01 -2.35316792e+01 -2.37079525e+01 -2.36423149e+01 -2.33080826e+01 -2.38478565e+01 -2.34950848e+01 -2.42572708e+01 -2.37652950e+01 -2.36494884e+01 -2.36489391e+01 -2.31389313e+01 -2.34180698e+01 -2.29329052e+01 -2.36637516e+01 -2.39236565e+01 -2.32961502e+01 -2.24995384e+01 -2.18028584e+01 -2.23737392e+01 -2.29316139e+01 -2.32343330e+01 -2.29971581e+01 -2.25154915e+01 -2.19548454e+01 -2.23108311e+01 -2.27388515e+01 -2.32898121e+01 -2.29206619e+01 -2.24522400e+01 -2.23113327e+01 -2.24900513e+01 -2.31465511e+01 -2.45525150e+01 -2.43851223e+01 -2.42177315e+01 -2.27143383e+01 -2.20718269e+01 -2.14902382e+01 -2.16418781e+01 -2.20226822e+01 -2.19977970e+01 -2.27149162e+01 -2.29023705e+01 -2.28545761e+01 -2.29351425e+01 -2.27473640e+01 -2.25962543e+01 -2.16093807e+01 -2.10700474e+01 -2.08784618e+01 -2.11304646e+01 -2.12973061e+01 -2.10487099e+01 -2.09357471e+01 -2.01059799e+01 -2.03821201e+01 -2.04377804e+01 -2.19558487e+01 -2.24948330e+01 -2.28021507e+01 -2.21270809e+01 -2.14872398e+01 -2.06972027e+01 -2.24181194e+01 -2.13214378e+01 -2.09910450e+01 -1.78210487e+01 -1.92565727e+01 -2.01633282e+01 -2.26805477e+01 -2.31383953e+01 -2.27824211e+01 -2.18082085e+01 -2.07674732e+01 -2.00986118e+01 -2.03810291e+01 -2.05440750e+01 -2.06321602e+01 -1.96853828e+01 -1.98373089e+01 -2.07915077e+01 -2.17566872e+01 -2.26243210e+01 -2.11636925e+01 -2.21952400e+01 -2.07029877e+01 -2.05812283e+01 -2.07372265e+01 -2.11312199e+01 -2.25920544e+01 -2.04033718e+01 -2.04949856e+01 -1.96443462e+01 -1.98506012e+01 -2.04796829e+01 -2.17223759e+01 -2.22515354e+01 -2.16428452e+01 -2.03220272e+01 -2.04482403e+01 -1.99046574e+01 -2.08334198e+01 -1.92207489e+01 -1.73590984e+01 -1.62128048e+01 -1.48964901e+01 -1.64610996e+01 -1.71569004e+01 -1.95633450e+01 -2.04715557e+01 -1.97031574e+01 -1.59168530e+01 -1.41833591e+01 -1.15074177e+01 -1.10650492e+01 1.85387969e+00 9.62174034e+00 4.45003624e+01 2.15972595e+01 -8.74906235e+01 -2.78782623e+02 -1.28486743e+03 9.98227625e+05 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -466714336. -49914308. 6.91996240e+03 3.26204224e+03 5.08377716e+02 -5.31287903e+02 -1.70254517e+02 7.10043335e+01 7.25418472e+01 4.62726440e+01 1.72888870e+02 9.37595291e+01 -5.35256577e+00 -7.27273407e+01 -1.04666336e+02 -9.08087387e+01 -1.12466034e+02 -1.02804214e+02 -8.79323502e+01 -5.39700966e+01 -4.69585304e+01 -3.72356300e+01 -3.37818375e+01 -2.74831429e+01 -2.18179264e+01 -1.82795181e+01 -1.78820534e+01 -1.53327293e+01 -1.60516396e+01 -1.64902534e+01 -1.85947437e+01 -1.83630543e+01 -1.67137566e+01 -1.53507338e+01 -1.42631435e+01 -1.25345011e+01 -1.18110752e+01 -1.29279079e+01 -1.53152723e+01 -1.57610197e+01 -1.39396257e+01 -1.39151735e+01 -1.29239111e+01 -1.26665487e+01 -1.23417616e+01 -1.49788885e+01 -1.38022213e+01 -1.20170269e+01 -1.09550552e+01 -1.45953674e+01 -1.49940987e+01 -1.56098089e+01 -1.42289047e+01 -1.44301586e+01 -1.31724625e+01 -1.19626513e+01 -1.27777195e+01 -1.28665380e+01 -1.35811243e+01 -1.34905567e+01 -1.32292719e+01 -1.42176085e+01 -1.57902880e+01 -1.52176514e+01 -1.23863106e+01 -9.21777534e+00 -1.07329369e+01 -1.27952681e+01 -1.33270102e+01 -1.41349945e+01 -1.50235491e+01 -1.77010994e+01 -1.70651779e+01 -1.59610262e+01 -1.47926159e+01 -1.49689007e+01 -1.41653080e+01 -1.18122215e+01 -1.17539282e+01 -1.38402500e+01 -1.40398970e+01 -1.20218544e+01 -1.09244070e+01 -1.14072914e+01 -1.13809385e+01 -8.17956734e+00 -7.98654652e+00 -7.57158327e+00 -1.03750763e+01 -1.12879505e+01 -1.33834858e+01 -1.34636765e+01 -1.50575438e+01 -1.32647324e+01 -1.49361696e+01 -1.22477665e+01 -1.35768080e+01 -1.21377106e+01 -1.30664244e+01 -1.37856569e+01 -1.19810381e+01 -1.05542574e+01 -6.43344164e+00 -5.43448019e+00 -7.28467751e+00 -9.81089115e+00 -1.33166428e+01 -1.33461866e+01 -1.28761911e+01 -1.15497770e+01 -9.81257915e+00 -9.65920353e+00 -1.13589640e+01 -1.04008379e+01 -1.11142817e+01 -9.50972080e+00 -1.18390865e+01 -1.24358816e+01 -1.07393017e+01 -8.63542080e+00 -8.66772366e+00 -7.54625654e+00 -6.74220943e+00 -3.04566860e+00 -4.49627447e+00 -6.50038147e+00 -5.42034054e+00 -5.19341087e+00 -6.59502554e+00 -9.57056904e+00 -9.62548733e+00 -8.66114902e+00 -9.24178600e+00 -8.88829803e+00 -6.09609747e+00 -3.12347817e+00 -3.43927097e+00 -4.92771196e+00 -6.97730112e+00 -6.42504549e+00 -6.88248301e+00 -7.81786680e+00 -1.01896257e+01 -9.68569660e+00 -1.28595924e+01 -1.15417099e+01 -1.25217409e+01 -9.93567371e+00 -1.00119486e+01 -1.12673225e+01 -9.32127476e+00 -8.42178059e+00 -5.19671297e+00 -5.76580667e+00 -5.05790520e+00 -9.30459309e+00 -8.01558971e+00 -8.80251694e+00 -5.76596737e+00 -7.20913124e+00 -6.25957394e+00 -9.56139469e+00 -8.56722832e+00 -8.62413979e+00 -7.15430546e+00 -8.39818001e+00 -5.29758263e+00 -2.66617990e+00 -2.31072330e+00 -5.77233505e+00 -9.33603573e+00 -9.20522404e+00 -8.87412453e+00 -6.83686829e+00 -7.36435080e+00 -4.82607460e+00 -5.87813187e+00 -3.97459292e+00 -3.61158276e+00 -1.42102146e+00 -2.95032191e+00 -6.27284527e+00 -6.13032675e+00 -4.33924198e+00 -5.37770176e+00 -7.69281244e+00 -8.79424763e+00 -5.27284813e+00 -4.69052219e+00 -8.41668606e+00 -7.61305285e+00 -6.29276419e+00 -1.76250565e+00 -3.07603335e+00 -4.91399574e+00 -5.40262365e+00 -5.38833046e+00 -1.58127582e+00 -2.89374757e+00 -4.61811972e+00 -6.79484510e+00 -4.23502827e+00 -3.38782763e+00 -4.12327242e+00 -6.29579830e+00 -3.32997251e+00 -4.03190279e+00 -2.30908060e+00 -3.71676517e+00 -2.14466977e+00 -6.82551086e-01 -1.25133169e+00 1.22983932e+00 -2.65889317e-01 -1.59393656e+00 -4.88775539e+00 -2.83269739e+00 4.29699332e-01 1.94123852e+00 4.91725355e-01 1.14269924e+00 2.64766240e+00 2.92256236e+00 4.23226213e+00 1.99400496e+00 2.94257545e+00 3.43504876e-01 9.99592170e-02 1.10308111e+00 1.27693164e+00 1.79461420e+00 -1.44087672e+00 -1.31455755e+00 2.15307355e+00 3.03337908e+00 3.34885740e+00 3.85482311e-01 1.11255741e+00 -6.41308546e-01 1.84360743e-01 2.00875258e+00 3.83272052e+00 3.15527439e+00 3.24849582e+00 1.69642818e+00 6.25087380e-01 6.90277815e-01 -1.19044375e+00 -7.85560966e-01 -4.03627586e+00 -1.24376655e+00 7.70757139e-01 3.85181928e+00 3.65093613e+00 4.07333565e+00 2.89159942e+00 3.41070390e+00 3.25285554e+00 3.64643884e+00 5.56354666e+00 6.73347425e+00 8.28894520e+00 7.51845217e+00 8.45200443e+00 8.04933262e+00 6.88421059e+00 5.73749542e+00 4.11334610e+00 2.87843609e+00 1.90846074e+00 2.39859223e+00 3.49224067e+00 4.22514915e+00 4.46582699e+00 4.54301453e+00 2.33343434e+00 3.21964765e+00 3.33581662e+00 5.56930113e+00 4.40278196e+00 4.46025610e+00 2.62981439e+00 3.87133026e+00 3.42703342e+00 8.47037029e+00 5.84788370e+00 6.66582108e+00 2.75687528e+00 4.39470196e+00 5.07681561e+00 5.73835659e+00 7.57703447e+00 6.69063854e+00 6.10366821e+00 2.81778741e+00 1.66414785e+00 3.33532953e+00 4.81833363e+00 3.78269529e+00 3.59168601e+00 3.11597753e+00 6.16305208e+00 4.02771330e+00 7.34521389e+00 6.17814255e+00 6.61291122e+00 5.01807117e+00 6.85504055e+00 7.46696949e+00 7.48384428e+00 5.71418333e+00 5.82806253e+00 6.20192814e+00 6.47458649e+00 6.48230791e+00 6.49070072e+00 7.30426645e+00 7.73904228e+00 6.79373360e+00 7.62769270e+00 8.99320889e+00 9.63958836e+00 8.71783447e+00 7.24849796e+00 7.95888853e+00 7.52489090e+00 9.50265503e+00 9.60258198e+00 1.17591267e+01 9.36822224e+00 1.00284367e+01 8.06471252e+00 8.83103657e+00 8.15244389e+00 8.39144897e+00 9.25480080e+00 1.04860592e+01 1.02972260e+01 1.03735838e+01 9.88131809e+00 1.07041855e+01 1.01423903e+01 8.83310223e+00 7.66409445e+00 7.19097614e+00 6.86125278e+00 7.63816833e+00 7.84422112e+00 7.72586441e+00 7.65262318e+00 9.37948418e+00 1.26248236e+01 1.49768457e+01 1.30485067e+01 1.36201878e+01 1.07798033e+01 1.16501007e+01 9.46241760e+00 8.64156151e+00 1.08664341e+01 9.71193218e+00 1.00358305e+01 9.86243057e+00 1.34335957e+01 1.42384186e+01 1.36420469e+01 1.23681126e+01 1.19664145e+01 1.26532526e+01 1.34566593e+01 1.47036753e+01 1.22847672e+01 1.34338093e+01 1.33620615e+01 1.61570358e+01 1.27313576e+01 1.16758575e+01 9.57796001e+00 1.01481686e+01 1.24419937e+01 1.29201441e+01 1.34515219e+01 1.22412519e+01 1.28776836e+01 1.43984432e+01 1.47429485e+01 1.31467810e+01 1.12168465e+01 1.22313290e+01 1.20436554e+01 1.37009583e+01 1.22654028e+01 1.35184822e+01 1.38848076e+01 1.53046370e+01 1.47418957e+01 1.32618551e+01 1.24106750e+01 1.57321033e+01 1.66505241e+01 1.51698904e+01 1.22464771e+01 1.08371611e+01 1.03840179e+01 1.06073618e+01 1.29415960e+01 1.44554300e+01 1.67238731e+01 1.60775261e+01 1.70586243e+01 1.66287842e+01 1.70249062e+01 1.71977787e+01 1.52952471e+01 1.30870514e+01 1.22107697e+01 1.32147980e+01 1.32360439e+01 1.36017313e+01 1.41068077e+01 1.54516058e+01 1.61669865e+01 1.59312525e+01 1.69963169e+01 1.66238079e+01 1.71239471e+01 1.66838341e+01 1.70137138e+01 1.76289082e+01 1.76346550e+01 1.69614086e+01 1.67343884e+01 1.63493500e+01 1.65025349e+01 1.58518057e+01 1.65397720e+01 1.61274567e+01 1.48739252e+01 1.53044119e+01 1.52787514e+01 1.64524250e+01 1.57803574e+01 1.68661366e+01 1.69266148e+01 1.77244701e+01 1.86026802e+01 1.90239887e+01 2.17113609e+01 2.05603828e+01 2.21793365e+01 1.73457928e+01 1.39881973e+01 1.39878044e+01 1.79754448e+01 2.33067551e+01 6.18554306e+01 9.53967438e+01 9.65203476e+01 1.25058228e+03 2.61711182e+03 222337152. -152192576. 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. 0. 0. 0. 0. 0. 0. 0. 0. -589007808. -148787952. 39189644. 53970552. 4.67588525e+03 2.09151611e+03 2.98112915e+02 1.17330185e+02 8.21103668e+01 8.95008469e+01 1.09841919e+02 1.15440033e+02 1.03513062e+02 9.26671295e+01 9.74155197e+01 9.79315567e+01 9.77155533e+01 -6.19581604e+02 -4.40560394e+02 -6.52079544e+01 -6.80401981e-01 6.16303301e+00 1.13817272e+01 1.34085197e+01 1.76445713e+01 2.07264824e+01 2.06941547e+01 2.11638660e+01 2.07688332e+01 2.18692188e+01 2.24131145e+01 2.24881840e+01 2.21048431e+01 2.07342834e+01 2.05146313e+01 2.01978989e+01 2.03777027e+01 1.91908951e+01 1.94630775e+01 1.93712502e+01 2.05350094e+01 2.03884201e+01 2.06331863e+01 2.11522064e+01 2.16106548e+01 2.18440418e+01 2.19020634e+01 2.22879696e+01 2.22264786e+01 2.24087944e+01 2.17717476e+01 2.16943226e+01 2.17270298e+01 2.08317242e+01 2.09572620e+01 2.03332691e+01 2.08472271e+01 2.10621948e+01 2.15333271e+01 2.17759190e+01 2.15612392e+01 2.21370201e+01 2.31270504e+01 2.31193275e+01 2.21488228e+01 2.13675594e+01 2.22741852e+01 2.26574402e+01 2.28548698e+01 2.28471909e+01 2.22110500e+01 2.22840328e+01 2.21678524e+01 2.22714901e+01 2.17288761e+01 2.07982826e+01 2.11331444e+01 2.12089348e+01 2.19862823e+01 2.19427128e+01 2.23049355e+01 2.18953037e+01 2.26456795e+01 2.28781414e+01 2.40650768e+01 2.34946461e+01 2.38875446e+01 2.31247597e+01 2.34736080e+01 2.25893841e+01 2.29194183e+01 2.32120342e+01 2.43390980e+01 2.38631802e+01 2.35911026e+01 2.30184860e+01 2.31416950e+01 2.30926647e+01 2.29220028e+01 2.33909607e+01 2.28022842e+01 2.25574303e+01 2.21908436e+01 2.24808464e+01 2.32926388e+01 2.32744617e+01 2.36912899e+01 2.36546631e+01 2.35078449e+01 2.36161461e+01 2.33731384e+01 2.32556248e+01 2.28001652e+01 2.25947514e+01 2.27970066e+01 2.29805393e+01 2.30226135e+01 2.27944450e+01 2.29806538e+01 2.31765308e+01 2.32250519e+01 2.31417885e+01 2.28611679e+01 2.30607910e+01 2.28432636e+01 2.33491211e+01 2.35791473e+01 2.38005695e+01 2.37164822e+01 2.35214462e+01 2.38282452e+01 2.40688782e+01 2.42056751e+01 2.42019825e+01 2.43377762e+01 2.44382496e+01 2.42004814e+01 2.40038891e+01 2.38076172e+01 2.37788296e+01 2.36752663e+01 2.37078171e+01 2.38260918e+01 2.37748203e+01 2.38209114e+01 2.36514206e+01 2.36855125e+01 2.36961842e+01 2.39020481e+01 2.38955822e+01 2.39353333e+01 2.40375061e+01 2.41154442e+01 2.41378841e+01 2.38853836e+01 2.38013706e+01 2.37727795e+01 2.39743423e+01 2.40597496e+01 2.40303421e+01 2.39215908e+01 2.39066048e+01 2.39185486e+01 2.39453812e+01 2.39062366e+01 2.38884716e+01 2.38649731e+01 2.38692760e+01 2.38777714e+01 2.39023838e+01 2.39246998e+01 2.39206257e+01 2.39365501e+01 2.39363194e+01 2.39351826e+01 2.39265633e+01 2.39324245e+01 2.39409275e+01 2.39235134e+01 2.39168129e+01 2.39133987e+01 2.39404087e+01 2.39626865e+01 2.40013084e+01 2.39682560e+01 2.39105473e+01 2.38622723e+01 2.38189545e+01 2.38579159e+01 2.38362656e+01 2.39280872e+01 2.39232140e+01 2.39599361e+01 2.38514500e+01 2.38454189e+01 2.39314632e+01 2.40524235e+01 2.40128078e+01 2.38712425e+01 2.37176495e+01 2.38679008e+01 2.39657669e+01 2.41112366e+01 2.39496059e+01 2.38221359e+01 2.38163128e+01 2.38014317e+01 2.37490864e+01 2.37032471e+01 2.37321377e+01 2.37040405e+01 2.38429642e+01 2.37569542e+01 2.38073578e+01 2.37547169e+01 2.37962914e+01 2.38197536e+01 2.38402157e+01 2.39287663e+01 2.38977127e+01 2.38799019e+01 2.37873535e+01 2.36988487e+01 2.37046089e+01 2.37816067e+01 2.40675068e+01 2.40890465e+01 2.40038242e+01 2.38942680e+01 2.36528988e+01 2.37920399e+01 2.38249207e+01 2.37154560e+01 2.39335728e+01 2.37718639e+01 2.39245243e+01 2.39194813e+01 2.37231941e+01 2.34119873e+01 2.32496452e+01 2.32735672e+01 2.32814465e+01 2.31541157e+01 2.31515350e+01 2.36923008e+01 2.31765327e+01 2.28121662e+01 2.18737316e+01 2.19905739e+01 2.23063927e+01 2.28103428e+01 2.27456226e+01 2.25465107e+01 2.22172585e+01 2.25572891e+01 2.28750763e+01 2.32435741e+01 2.33297386e+01 2.31105461e+01 2.27497826e+01 2.34597988e+01 2.36303120e+01 2.36963577e+01 2.27265682e+01 2.33091736e+01 2.28397732e+01 2.31447716e+01 2.33862019e+01 2.38088322e+01 2.32761822e+01 2.19127312e+01 2.24390278e+01 2.26700687e+01 2.27773571e+01 2.15653229e+01 2.11823101e+01 2.16419258e+01 2.22737293e+01 2.12331734e+01 2.04145813e+01 2.05133018e+01 2.17062740e+01 2.28926296e+01 2.29651909e+01 2.26187859e+01 2.21858139e+01 2.14928398e+01 2.19963856e+01 2.17383289e+01 2.18764458e+01 2.18203640e+01 2.10413532e+01 2.12451630e+01 2.15561848e+01 2.19301739e+01 2.11778202e+01 2.03433342e+01 2.04933701e+01 2.08167362e+01 2.09644928e+01 2.04571323e+01 2.09562874e+01 2.10905228e+01 2.10273190e+01 2.04131069e+01 2.00810661e+01 2.12027531e+01 2.17796993e+01 2.12995033e+01 2.03646145e+01 2.11022320e+01 2.16118126e+01 2.12086258e+01 2.01100521e+01 2.00524044e+01 1.99789715e+01 1.94738750e+01 1.87773857e+01 1.96744804e+01 2.11619415e+01 2.32785339e+01 2.22244606e+01 2.16959305e+01 2.07426224e+01 2.15152531e+01 2.01770687e+01 1.95892467e+01 1.85539875e+01 1.93944778e+01 1.86224251e+01 1.86938572e+01 1.91904907e+01 1.99480019e+01 2.16561661e+01 2.16241264e+01 2.13240738e+01 2.03322315e+01 2.00703545e+01 2.01528206e+01 2.07345715e+01 2.17321091e+01 2.11990013e+01 2.06549053e+01 1.92511826e+01 1.97350063e+01 1.97317410e+01 1.99004917e+01 1.89281082e+01 1.73041573e+01 1.72910137e+01 1.79002800e+01 1.96764507e+01 1.92338333e+01 1.86903954e+01 1.80883465e+01 1.68087025e+01 1.79288292e+01 1.88606853e+01 2.10571842e+01 2.09557762e+01 2.01794472e+01 1.95908394e+01 1.83751163e+01 1.90255909e+01 1.87990742e+01 1.81745815e+01 1.68726692e+01 1.82808781e+01 1.89312763e+01 1.91177044e+01 1.75672092e+01 1.68177567e+01 1.79607906e+01 1.82413521e+01 1.91668663e+01 1.79680386e+01 1.75568886e+01 1.78569946e+01 1.75631962e+01 1.77310581e+01 1.76965313e+01 1.69832668e+01 1.75052376e+01 1.82815285e+01 1.87479076e+01 1.82179279e+01 1.72681026e+01 1.77494926e+01 1.72976227e+01 1.67720814e+01 1.78254490e+01 1.81287327e+01 1.81292152e+01 1.72673225e+01 1.74519730e+01 1.85749893e+01 1.78273544e+01 1.75910149e+01 1.67555065e+01 1.53854952e+01 1.29175730e+01 1.28679428e+01 1.39372988e+01 1.59292097e+01 1.34664850e+01 1.15694370e+01 1.40181608e+01 1.76082535e+01 1.95026512e+01 1.66713505e+01 1.59000082e+01 1.60018787e+01 1.62367153e+01 1.57225447e+01 1.75374279e+01 1.74160271e+01 1.68495293e+01 1.67965088e+01 1.71796398e+01 1.71805820e+01 1.55216055e+01 1.48475952e+01 1.47475729e+01 1.57065544e+01 1.57478867e+01 1.59026432e+01 1.48858624e+01 1.49139957e+01 1.38833675e+01 1.38808165e+01 1.50237007e+01 1.60137024e+01 1.64554882e+01 1.53747463e+01 1.58484840e+01 1.56883202e+01 1.47079487e+01 1.38457432e+01 1.17259750e+01 1.14906511e+01 1.04704323e+01 1.04307919e+01 1.08266392e+01 1.24844599e+01 1.48581495e+01 1.59684076e+01 1.39934244e+01 1.37164593e+01 1.25005980e+01 1.41411772e+01 1.35372210e+01 1.35631113e+01 1.24142962e+01 1.09221077e+01 1.12562590e+01 1.32127581e+01 1.41270428e+01 1.42935619e+01 1.20417070e+01 1.27728167e+01 1.32263603e+01 1.32902937e+01 1.15828056e+01 9.66270733e+00 9.53374863e+00 1.12624025e+01 1.05378580e+01 1.07814245e+01 1.12719793e+01 1.22140198e+01 1.09345217e+01 8.84952354e+00 7.55158234e+00 7.45953846e+00 9.69928551e+00 1.04274492e+01 1.10797262e+01 8.47540665e+00 9.23976803e+00 9.73555279e+00 1.00765524e+01 9.60010910e+00 8.66061306e+00 8.35905647e+00 8.00407410e+00 1.04256239e+01 9.69478607e+00 8.41101360e+00 6.09443188e+00 8.34360695e+00 1.02403765e+01 1.05367403e+01 1.13808384e+01 1.25887318e+01 1.19078379e+01 1.05467148e+01 1.04848537e+01 1.21492062e+01 1.27879868e+01 1.10419865e+01 1.07260942e+01 1.07072210e+01 1.09899359e+01 1.13502626e+01 1.18370724e+01 1.13514585e+01 1.02862940e+01 8.59028053e+00 8.48474216e+00 9.03166771e+00 1.08338537e+01 1.24566078e+01 1.24913445e+01 1.04832277e+01 8.00715065e+00 6.78552246e+00 8.27658844e+00 8.52543545e+00 9.89218044e+00 8.52858829e+00 6.65502119e+00 4.58581972e+00 3.89191055e+00 6.45087624e+00 6.85049057e+00 6.20273304e+00 3.96224260e+00 5.09373474e+00 5.94337797e+00 6.53826046e+00 4.79251623e+00 5.70958662e+00 7.46727133e+00 9.10562420e+00 8.95903301e+00 8.28256798e+00 7.40566397e+00 7.89385128e+00 6.84603119e+00 6.18276691e+00 5.04874372e+00 4.23061895e+00 2.92173886e+00 3.29263854e+00 3.56390738e+00 3.21739650e+00 4.22718430e+00 5.00963926e+00 6.69139862e+00 4.70356369e+00 4.34687996e+00 5.62450838e+00 7.28355694e+00 7.65821743e+00 5.27022934e+00 5.34010124e+00 4.71620417e+00 5.49201393e+00 5.24630165e+00 5.45612288e+00 4.80575466e+00 2.97164321e+00 2.99667597e+00 3.60531807e+00 5.33654928e+00 3.25820088e+00 2.67393970e+00 1.31698120e+00 5.24286890e+00 5.70377827e+00 5.07046652e+00 3.20298386e+00 2.31721091e+00 3.13775444e+00 3.76348710e+00 4.73489571e+00 2.99726796e+00 9.90484655e-01 -1.49579093e-01 2.04320803e-01 2.24410081e+00 1.25083041e+00 3.21319747e+00 3.03641129e+00 4.21303082e+00 4.97238541e+00 2.83804584e+00 3.03207922e+00 1.65283656e+00 3.64156890e+00 2.64673877e+00 2.48619914e+00 3.58695579e+00 3.89628768e+00 2.90406084e+00 -9.83766198e-01 -3.75117207e+00 -4.16271067e+00 -2.33039141e+00 1.53763139e+00 2.54455113e+00 -1.15251887e+00 -5.51524353e+00 -1.64847984e+01 -3.36935043e+01 -6.09991913e+01 -1.24053627e+02 -1.29254852e+02 -1.63538098e+03 -9.66793945e+03 -1638379008. 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. 2.75057254e+09 9.10379590e+03 1.56643201e+03 3.54193634e+02 1.56131119e+02 4.90150223e+01 1.49881184e+00 -3.39687705e+00 -3.20769477e+00 8.68863165e-01 4.14139652e+00 4.49025393e+00 3.30277276e+00 1.33455908e+00 -1.58992517e+00 -7.42653310e-01 -1.47440457e+00 9.49045479e-01 3.01023185e-01 8.47012997e-01 -3.62867802e-01 -1.69109690e+00 -3.69897246e+00 -6.00239038e+00 -7.60358095e+00 -6.31420469e+00 -5.48581028e+00 -4.18385839e+00 -1.08723080e+00 8.34556282e-01 -1.83786285e+00 -6.34200716e+00 -9.58170795e+00 -8.16304398e+00 -4.53372288e+00 -4.04057771e-01 1.69256020e+00 3.08179945e-01 -8.11212420e-01 -2.32168841e+00 -3.65080142e+00 -4.95794058e+00 -5.91784954e+00 -4.06453228e+00 -2.90952921e+00 -1.48533297e+00 -3.01030326e+00 -3.30342340e+00 -3.72212029e+00 -4.93832922e+00 -3.98690081e+00 -5.41816282e+00 -3.48041630e+00 -1.86033082e+00 -4.02778208e-01 -8.67546916e-01 -4.61722994e+00 -6.28022575e+00 -7.59537458e+00 -5.34121418e+00 -1.90935349e+00 -1.72015083e+00 -3.55564427e+00 -4.87468386e+00 -3.56560946e+00 -4.01334906e+00 -6.26819801e+00 -7.56055260e+00 -7.05074501e+00 -4.03691292e+00 -2.59024453e+00 -4.23347187e+00 -5.44042063e+00 -5.47351646e+00 -5.12377787e+00 -5.49048901e+00 -5.71849394e+00 -3.95159364e+00 -2.70088553e+00 -1.70984697e+00 -1.37190640e+00 -2.85942650e+00 -5.74302244e+00 -8.37337875e+00 -7.72146845e+00 -4.91606045e+00 -3.47568274e+00 -4.81939220e+00 -3.76426530e+00 -1.96595573e+00 -8.40689063e-01 -2.95435452e+00 -5.46129417e+00 -5.15053988e+00 -2.34176254e+00 2.55488485e-01 5.71284890e-01 -1.02332306e+00 -1.65008903e+00 -3.25096798e+00 -4.26916075e+00 -4.83678770e+00 -4.72424746e+00 -3.91180897e+00 -3.68713331e+00 -4.03145313e+00 -6.01662588e+00 -7.22480345e+00 -8.07087994e+00 -7.29999256e+00 -5.82073498e+00 -4.79249716e+00 -5.89637566e+00 -5.94878483e+00 -4.15563965e+00 -3.10741043e+00 -3.64679670e+00 -6.64866400e+00 -6.16337299e+00 -3.44483495e+00 -1.65849045e-01 -4.19532537e-01 -3.23577642e+00 -4.58438253e+00 -7.08595514e+00 -7.57776880e+00 -8.02023697e+00 -7.41115952e+00 -7.26372957e+00 -5.13862610e+00 -2.41726685e+00 -2.79406643e+00 -4.53313398e+00 -7.77398920e+00 -8.33784103e+00 -8.92062092e+00 -6.90228748e+00 -4.98563385e+00 -4.63375330e+00 -4.80838060e+00 -4.79860687e+00 -4.90398788e+00 -6.60744667e+00 -9.44888210e+00 -1.07127047e+01 -9.37400913e+00 -7.32594681e+00 -6.16085958e+00 -5.29455423e+00 -6.06381512e+00 -6.51249504e+00 -6.69307613e+00 -8.25039482e+00 -9.29400158e+00 -9.26059723e+00 -6.73073244e+00 -5.79488325e+00 -7.05732346e+00 -9.66357517e+00 -9.80739594e+00 -9.43351460e+00 -8.59359169e+00 -1.10008030e+01 -1.16640911e+01 -1.06043673e+01 -9.87299061e+00 -9.81380272e+00 -1.11427908e+01 -1.25812531e+01 -1.40348167e+01 -1.29580555e+01 -8.25165272e+00 -6.44296265e+00 -6.12089586e+00 -6.28553343e+00 -6.49563742e+00 -7.52107239e+00 -1.11132975e+01 -1.17289467e+01 -9.96115017e+00 -5.94522953e+00 -5.91186285e+00 -7.98653460e+00 -1.16917543e+01 -1.19519949e+01 -1.16662979e+01 -9.35253906e+00 -9.54229450e+00 -1.03155317e+01 -1.17274923e+01 -1.08369226e+01 -9.54164124e+00 -8.67380238e+00 -1.07425642e+01 -1.09474764e+01 -8.07370758e+00 -4.47837830e+00 -5.06879139e+00 -7.32490969e+00 -8.10708427e+00 -8.20771217e+00 -8.73097706e+00 -1.04308643e+01 -1.06899786e+01 -8.35462666e+00 -7.89899302e+00 -7.82174444e+00 -1.02886848e+01 -9.48828125e+00 -7.90041685e+00 -7.07328987e+00 -6.52977133e+00 -8.91645813e+00 -1.00327978e+01 -1.08761730e+01 -8.98736763e+00 -8.41439724e+00 -8.92620659e+00 -1.01055622e+01 -1.18330469e+01 -1.09285545e+01 -1.11175060e+01 -1.00686417e+01 -1.03763237e+01 -8.58695602e+00 -9.21535492e+00 -8.91758728e+00 -9.66605568e+00 -9.35318565e+00 -9.56990910e+00 -9.77807140e+00 -9.09105015e+00 -9.66143322e+00 -9.14515305e+00 -8.55377293e+00 -9.72234535e+00 -1.08672924e+01 -1.29326496e+01 -1.29342680e+01 -1.12648506e+01 -9.18817806e+00 -9.00196362e+00 -1.05276165e+01 -1.24035177e+01 -1.08407145e+01 -9.68876362e+00 -9.43660069e+00 -9.87251472e+00 -1.02768364e+01 -8.60956287e+00 -8.93313789e+00 -1.01188946e+01 -1.22878504e+01 -1.26313238e+01 -1.20433054e+01 -1.21204901e+01 -1.18008919e+01 -1.13868093e+01 -1.00112448e+01 -9.56250381e+00 -1.03584671e+01 -1.09129572e+01 -1.22212543e+01 -1.16782713e+01 -1.14051847e+01 -9.73510742e+00 -8.32618046e+00 -9.26861954e+00 -1.10762520e+01 -1.33360291e+01 -1.30683823e+01 -1.37271805e+01 -1.36492882e+01 -1.29571571e+01 -1.14404087e+01 -1.09008245e+01 -1.11854134e+01 -1.12990484e+01 -1.08245840e+01 -1.05952101e+01 -1.15840302e+01 -1.15809231e+01 -1.06130323e+01 -1.01908932e+01 -1.11837645e+01 -1.16139441e+01 -1.04993410e+01 -1.07092934e+01 -1.20464993e+01 -1.28321438e+01 -1.21856089e+01 -1.09262848e+01 -1.11539764e+01 -1.20380535e+01 -1.25085430e+01 -1.21538601e+01 -1.27417278e+01 -1.32000437e+01 -1.33547764e+01 -1.15973558e+01 -1.13036242e+01 -1.09973955e+01 -1.18187790e+01 -1.12920685e+01 -1.12755442e+01 -1.16218071e+01 -1.20098572e+01 -1.14334106e+01 -1.08848753e+01 -1.06473866e+01 -1.12424994e+01 -1.03431606e+01 -1.10360184e+01 -1.10278988e+01 -1.18649654e+01 -1.08750286e+01 -1.05687714e+01 -1.11151657e+01 -1.29545708e+01 -1.30983801e+01 -1.20658951e+01 -1.09093838e+01 -1.20267220e+01 -1.28290319e+01 -1.29152679e+01 -1.24847565e+01 -1.24266796e+01 -1.30292797e+01 -1.21596279e+01 -1.20060234e+01 -1.17613468e+01 -1.24695129e+01 -1.23985233e+01 -1.20630512e+01 -1.22249460e+01 -1.18854265e+01 -1.14476738e+01 -1.19834204e+01 -1.28892164e+01 -1.37371273e+01 -1.31531820e+01 -1.21931610e+01 -1.25149851e+01 -1.26394768e+01 -1.36501570e+01 -1.35690918e+01 -1.37806797e+01 -1.39082251e+01 -1.36167774e+01 -1.35188322e+01 -1.32183723e+01 -1.28824692e+01 -1.28925610e+01 -1.24480438e+01 -1.23415461e+01 -1.27052507e+01 -1.28922033e+01 -1.33660078e+01 -1.27322569e+01 -1.27386532e+01 -1.26213646e+01 -1.17586069e+01 -1.18100471e+01 -1.26105042e+01 -1.42117872e+01 -1.45137358e+01 -1.40483866e+01 -1.36185637e+01 -1.34876442e+01 -1.34298763e+01 -1.37348766e+01 -1.39378128e+01 -1.43835020e+01 -1.41163416e+01 -1.44359703e+01 -1.48463316e+01 -1.49215021e+01 -1.43179340e+01 -1.33077660e+01 -1.28378258e+01 -1.37057858e+01 -1.41839733e+01 -1.42336235e+01 -1.35094032e+01 -1.31855793e+01 -1.33744736e+01 -1.31428175e+01 -1.35852280e+01 -1.35432339e+01 -1.42461843e+01 -1.41044073e+01 -1.42921267e+01 -1.36986752e+01 -1.34396782e+01 -1.33647861e+01 -1.38485641e+01 -1.42872829e+01 -1.46687765e+01 -1.43749485e+01 -1.37140179e+01 -1.34801626e+01 -1.33488808e+01 -1.36438522e+01 -1.32533627e+01 -1.33107700e+01 -1.35758419e+01 -1.40398111e+01 -1.40843363e+01 -1.38846483e+01 -1.37893114e+01 -1.37593708e+01 -1.37121525e+01 -1.36944714e+01 -1.38973989e+01 -1.39505405e+01 -1.41080179e+01 -1.40184412e+01 -1.40803080e+01 -1.40367823e+01 -1.38867865e+01 -1.38409491e+01 -1.36422052e+01 -1.37958546e+01 -1.37709169e+01 -1.39111795e+01 -1.40360689e+01 -1.40453424e+01 -1.39117002e+01 -1.37188807e+01 -1.37176504e+01 -1.37190886e+01 -1.38144598e+01 -1.38328152e+01 -1.38238087e+01 -1.37613344e+01 -1.37523613e+01 -1.37648172e+01 -1.37771349e+01 -1.37885485e+01 -1.37844496e+01 -1.37838259e+01 -1.37985411e+01 -1.37966366e+01 -1.37830677e+01 -1.37608881e+01 -1.37424173e+01 -1.36860361e+01 -1.37361698e+01 -1.37560053e+01 -1.38101015e+01 -1.37180109e+01 -1.36347647e+01 -1.36771536e+01 -1.38132448e+01 -1.38715258e+01 -1.38704815e+01 -1.37288647e+01 -1.37514210e+01 -1.36264811e+01 -1.36505651e+01 -1.35124445e+01 -1.35412655e+01 -1.35817604e+01 -1.35832462e+01 -1.36529179e+01 -1.35051327e+01 -1.36185045e+01 -1.37290745e+01 -1.37808638e+01 -1.37314768e+01 -1.33306742e+01 -1.35248976e+01 -1.37673035e+01 -1.39802017e+01 -1.38476038e+01 -1.33393278e+01 -1.32548695e+01 -1.30578480e+01 -1.35051956e+01 -1.38327169e+01 -1.40399456e+01 -1.38100271e+01 -1.34282131e+01 -1.34058867e+01 -1.38231869e+01 -1.38911543e+01 -1.38692350e+01 -1.33242130e+01 -1.33302870e+01 -1.29652691e+01 -1.29438057e+01 -1.33427725e+01 -1.39978085e+01 -1.42386312e+01 -1.38385315e+01 -1.34678144e+01 -1.31288624e+01 -1.31524601e+01 -1.37240562e+01 -1.46088610e+01 -1.42276201e+01 -1.36769743e+01 -1.26078701e+01 -1.29605331e+01 -1.32636337e+01 -1.37788773e+01 -1.38229933e+01 -1.32145548e+01 -1.30118198e+01 -1.29105244e+01 -1.29192200e+01 -1.29051361e+01 -1.31143675e+01 -1.33008986e+01 -1.31211615e+01 -1.29256029e+01 -1.31946516e+01 -1.33374157e+01 -1.32779875e+01 -1.39338541e+01 -1.36432409e+01 -1.37513847e+01 -1.31287508e+01 -1.36698332e+01 -1.40398932e+01 -1.34142609e+01 -1.25919466e+01 -1.20657768e+01 -1.29280539e+01 -1.38259544e+01 -1.40197678e+01 -1.32773247e+01 -1.23949537e+01 -1.15293360e+01 -1.15684843e+01 -1.17698307e+01 -1.30783558e+01 -1.32826614e+01 -1.29921904e+01 -1.24489565e+01 -1.25056524e+01 -1.34453793e+01 -1.35165796e+01 -1.34363012e+01 -1.30984859e+01 -1.24033909e+01 -1.21808138e+01 -1.31515293e+01 -1.48071508e+01 -1.54193630e+01 -1.43862600e+01 -1.30785112e+01 -1.24956408e+01 -1.29619951e+01 -1.36377192e+01 -1.37091255e+01 -1.34605055e+01 -1.24172764e+01 -1.22201653e+01 -1.19634418e+01 -1.23663893e+01 -1.30004225e+01 -1.29789076e+01 -1.22626944e+01 -1.09947786e+01 -1.05428782e+01 -1.20219002e+01 -1.32771969e+01 -1.42744112e+01 -1.37297668e+01 -1.19255705e+01 -1.07815056e+01 -1.06091938e+01 -1.25269966e+01 -1.38236666e+01 -1.42221460e+01 -1.32880621e+01 -1.25602570e+01 -1.21709337e+01 -1.24977484e+01 -1.19293909e+01 -1.14998350e+01 -1.08100882e+01 -1.10739775e+01 -1.05409164e+01 -1.09160814e+01 -1.10615473e+01 -1.22667294e+01 -1.16303864e+01 -1.13474598e+01 -1.03242903e+01 -1.08088322e+01 -1.10420227e+01 -1.16093502e+01 -1.15547533e+01 -1.10214872e+01 -1.09182825e+01 -1.08660440e+01 -1.14179535e+01 -1.20101595e+01 -1.16820946e+01 -1.11808367e+01 -1.01186495e+01 -1.02561178e+01 -1.08622284e+01 -1.14380817e+01 -1.10351467e+01 -9.56071472e+00 -9.95600510e+00 -1.07134829e+01 -1.16703138e+01 -9.02381611e+00 -3.80177593e+00 2.07488871e+00 8.00098991e+00 1.53010511e+01 2.97354183e+01 7.57691498e+01 3.23103333e+02 3.85932343e+02 -1.15392632e+02 -1.19968225e+03 -5.31114404e+03 153894144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -77444984. -367311776. -2.57832446e+03 -9.90230591e+02 -1.61073166e+02 -1.29564270e+02 -4.87485733e+01 -2.62190018e+01 -1.37280989e+01 -1.24724112e+01 -1.28791819e+01 -1.22702398e+01 -1.12191830e+01 -7.95900249e+00 -5.60059404e+00 -5.21286631e+00 -5.46661615e+00 -8.83930779e+00 -9.66686726e+00 -9.11511517e+00 -7.14427853e+00 -6.40426111e+00 -6.25864077e+00 -7.51396561e+00 -8.51098728e+00 -8.08598232e+00 -6.65073586e+00 -6.08561802e+00 -7.10057402e+00 -8.55038738e+00 -7.66382980e+00 -7.39055157e+00 -7.06792545e+00 -7.72127199e+00 -7.71668148e+00 -7.69211340e+00 -7.21056414e+00 -6.66332197e+00 -7.36812210e+00 -7.66314363e+00 -8.31646347e+00 -7.61437464e+00 -6.49759674e+00 -4.71985435e+00 -4.20286512e+00 -4.09318304e+00 -3.25628662e+00 -3.93296909e+00 -6.36283493e+00 -1.12234116e+01 -1.13114548e+01 -9.43025303e+00 -8.48782253e+00 -9.39930248e+00 -1.11106062e+01 -1.05219746e+01 -7.95935583e+00 -6.67456341e+00 -5.88949871e+00 -7.41141701e+00 -7.79542351e+00 -8.15314007e+00 -8.04841232e+00 -5.88427353e+00 -3.89191294e+00 -3.87784958e+00 -5.57171583e+00 -6.82384539e+00 -5.64553452e+00 -3.71553564e+00 -3.98175836e+00 -3.59349680e+00 -4.32577991e+00 -2.57032847e+00 -3.92782259e+00 -4.30988073e+00 -3.01806211e+00 -2.47043085e+00 -3.01559448e+00 -5.70295048e+00 -5.53760386e+00 -4.72342062e+00 -5.29157019e+00 -5.74568319e+00 -5.06393766e+00 -3.38296461e+00 -3.81673932e+00 -5.26889896e+00 -7.09677458e+00 -6.00778580e+00 -6.43533707e+00 -4.59700441e+00 -4.46903419e+00 -2.74937868e+00 -3.43490505e+00 -3.73277807e+00 -1.91343546e+00 -1.27008283e+00 -2.51802444e+00 -3.84220076e+00 -5.67216825e+00 -2.87074399e+00 -4.42122698e+00 -4.86302996e+00 -7.02218580e+00 -6.60385656e+00 -4.33778429e+00 -4.78878069e+00 -2.55929565e+00 -2.37370324e+00 -1.03498542e+00 -1.62522876e+00 -4.60695839e+00 -4.20318747e+00 -4.02621555e+00 -2.61454940e+00 -3.19698358e+00 -4.12193775e+00 -3.35105062e+00 -2.76503444e+00 -4.14761782e+00 -2.65671444e+00 -3.49508739e+00 -4.18987656e+00 -6.28560877e+00 -6.51415825e+00 -2.26802635e+00 -2.06062388e+00 -2.64749885e+00 -5.45817327e+00 -4.49153376e+00 -1.17470479e+00 -1.46654356e+00 -1.94303906e+00 -3.87042856e+00 -3.82191396e+00 -3.75818706e+00 -5.00974941e+00 -4.14793634e+00 -4.22870922e+00 -3.25766563e+00 -4.18865395e+00 -5.47262478e+00 -5.34592628e+00 -4.89095783e+00 -2.93018293e+00 -1.14993906e+00 -1.28957725e+00 -2.56685495e+00 -3.90497065e+00 -3.51307559e+00 -1.67768049e+00 -8.66673410e-01 -1.52230036e+00 -3.05927682e+00 -6.09825468e+00 -5.35135984e+00 -5.17692518e+00 -2.54495215e+00 -1.95632613e+00 -1.40120745e+00 -7.41408527e-01 -1.24794590e+00 -2.23688555e+00 -2.28578830e+00 -5.72952807e-01 1.17828023e+00 9.04599965e-01 -1.88226259e+00 -4.19804621e+00 -4.02285147e+00 -1.94179201e+00 -1.37927067e+00 -3.06269598e+00 -4.76601315e+00 -3.44253278e+00 -1.81257594e+00 -2.03866267e+00 -2.86159515e+00 -2.58388901e+00 -1.90841484e+00 -1.62155771e+00 -1.37515628e+00 -4.52158421e-01 1.70905650e+00 3.49149108e-01 6.63612664e-01 1.57337236e+00 4.02911472e+00 4.78222132e+00 3.46888089e+00 4.42743015e+00 2.89110708e+00 5.17468750e-01 -1.66858399e+00 -2.73907495e+00 8.82835090e-02 -8.41649175e-01 -2.23405457e+00 -6.34591103e+00 -6.63055563e+00 -3.26313996e+00 -6.75835550e-01 1.26292765e+00 6.99102581e-01 1.33705103e+00 2.00546670e+00 2.31880426e+00 2.74940085e+00 2.02402854e+00 2.03735924e+00 1.54509783e+00 9.69908416e-01 1.08951294e+00 -2.25404525e+00 -1.39274430e+00 5.57050467e-01 4.03398800e+00 3.24582934e+00 1.75733650e+00 1.23939729e+00 2.22159433e+00 1.72395438e-01 -1.89346898e+00 -4.35507679e+00 -5.58518648e+00 -2.43526626e+00 -1.29890889e-01 3.12608385e+00 1.90754879e+00 -4.47763741e-01 -2.59546638e+00 -2.28712630e+00 -2.95984715e-01 1.08230603e+00 1.13831937e+00 4.38998461e-01 2.26634175e-01 -1.42620325e+00 -1.06368613e+00 -1.14638388e+00 1.57266945e-01 3.98201168e-01 7.52301157e-01 1.26943254e+00 1.38859272e+00 1.55040753e+00 1.42581856e+00 4.28257436e-02 9.12902653e-02 -2.19191462e-01 7.65248001e-01 -1.29328206e-01 8.56495619e-01 1.89342833e+00 2.07561326e+00 1.32969046e+00 3.11139643e-01 1.68574059e+00 1.93678010e+00 2.32536483e+00 1.86317885e+00 3.71330810e+00 2.98698068e+00 3.08616233e+00 1.30992246e+00 3.73211741e+00 3.50306439e+00 3.37803364e+00 1.73578048e+00 1.76786387e+00 1.25987291e+00 1.03981185e+00 1.21224797e+00 8.51647854e-01 8.60688448e-01 8.78365219e-01 2.42782259e+00 2.23113632e+00 2.40715170e+00 1.58476138e+00 1.56888032e+00 2.13393879e+00 -2.88342535e-01 7.75138915e-01 1.05922483e-01 2.27769423e+00 2.40067410e+00 2.66730237e+00 3.29104638e+00 3.02119207e+00 1.95641708e+00 2.31588054e+00 1.76426005e+00 1.67746508e+00 5.26755512e-01 2.43515658e+00 3.62785029e+00 5.16648626e+00 4.31849909e+00 5.11852074e+00 5.79477024e+00 4.64494991e+00 4.36796618e+00 2.33351970e+00 1.62136483e+00 1.30877292e+00 3.91866398e+00 4.78873682e+00 4.69402981e+00 2.73598242e+00 3.87056065e+00 5.45192432e+00 4.81425333e+00 4.51912022e+00 4.61847878e+00 5.93030930e+00 5.93726110e+00 4.53544331e+00 4.15107203e+00 4.73636246e+00 5.57744455e+00 5.67702389e+00 5.82802582e+00 6.46924782e+00 6.00787306e+00 5.76758242e+00 4.14746618e+00 4.16603518e+00 1.98075485e+00 5.84612489e-01 1.65465605e+00 3.49726176e+00 4.89334869e+00 5.27253532e+00 5.23348284e+00 4.87118435e+00 3.47066474e+00 2.23609447e+00 3.11217427e+00 4.05254841e+00 7.04595709e+00 7.10914087e+00 7.79412079e+00 8.12505150e+00 6.66203785e+00 7.33091640e+00 5.85481834e+00 7.29856014e+00 5.63731527e+00 5.92491341e+00 6.02406836e+00 5.65493822e+00 5.19534159e+00 4.73135138e+00 6.09422588e+00 4.81527424e+00 6.52503061e+00 5.16326141e+00 6.82221889e+00 5.92416716e+00 6.87586021e+00 7.26185369e+00 9.84515285e+00 7.79919338e+00 6.64234495e+00 4.01862335e+00 5.50327396e+00 7.06086159e+00 6.56200790e+00 6.57875872e+00 5.36506796e+00 6.15145302e+00 6.65413094e+00 8.33881569e+00 6.44470692e+00 5.97265005e+00 4.12110281e+00 6.23891830e+00 7.11175680e+00 7.20165491e+00 6.02432442e+00 5.88900614e+00 6.44538403e+00 7.34520197e+00 6.72519445e+00 5.08943605e+00 4.96431255e+00 5.07400513e+00 6.93989754e+00 6.93940401e+00 7.49168444e+00 7.73503113e+00 8.00516701e+00 8.16523933e+00 6.69463539e+00 6.97344542e+00 6.61581802e+00 8.11271286e+00 7.45929575e+00 8.80423164e+00 8.90160942e+00 9.91635132e+00 1.00310211e+01 1.09754372e+01 1.15556364e+01 1.11764374e+01 1.11509209e+01 1.03946733e+01 1.00295277e+01 8.75431728e+00 8.93387413e+00 9.47800922e+00 1.05853109e+01 1.11364126e+01 1.06113272e+01 8.84623528e+00 7.97525978e+00 8.77497578e+00 1.12056513e+01 1.16862240e+01 1.02988997e+01 8.56492043e+00 7.95098591e+00 8.94458485e+00 8.87377548e+00 8.10437775e+00 8.13263321e+00 8.86033821e+00 1.02399883e+01 1.02961264e+01 9.93002892e+00 8.90564728e+00 7.88912058e+00 7.54387093e+00 8.16907310e+00 7.86875629e+00 8.43218517e+00 7.55435801e+00 8.44708443e+00 8.31973171e+00 9.36817169e+00 9.85122299e+00 1.06151428e+01 1.16198502e+01 1.11200590e+01 9.70191383e+00 7.44250107e+00 5.45794439e+00 9.63981056e+00 1.64923306e+01 2.65772877e+01 3.45532265e+01 4.23695450e+01 4.00585403e+01 4.83919106e+01 9.01679993e+01 3.89438263e+02 4.88958282e+02 -1.04028824e+02 -4.88586044e+01 -9.13721375e+02 -3.89800903e+03 -152192576. 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. 0. 0. 0. 0. 0. 0. 0. 186387872. -1.09556042e+03 -4.07465637e+02 2.89119072e+01 -2.47893753e+01 -3.98855782e+01 -3.76375275e+01 -1.58534765e+00 8.15391827e+00 1.04399853e+01 1.08935909e+01 9.99221611e+00 9.61750221e+00 9.46550083e+00 9.40536880e+00 9.32410145e+00 9.96098804e+00 1.09955902e+01 1.12047758e+01 1.10414562e+01 1.00959435e+01 1.01132078e+01 1.06430416e+01 1.10942707e+01 1.12042112e+01 1.09589672e+01 1.13427191e+01 1.12146406e+01 1.17352076e+01 1.21413240e+01 1.27404909e+01 1.27878561e+01 1.25653963e+01 1.20808697e+01 1.18667316e+01 1.22014742e+01 1.23539457e+01 1.32433739e+01 1.34029207e+01 1.34235420e+01 1.26728563e+01 1.21117649e+01 1.26799345e+01 1.29796724e+01 1.31791096e+01 1.32514200e+01 1.31806211e+01 1.27151737e+01 1.29443960e+01 1.29690504e+01 1.35820551e+01 1.32227840e+01 1.34147673e+01 1.33957644e+01 1.35462246e+01 1.34248066e+01 1.32914448e+01 1.31149178e+01 1.29878941e+01 1.31490955e+01 1.28952866e+01 1.25136108e+01 1.18517284e+01 1.16298647e+01 1.16214066e+01 1.20483761e+01 1.25793457e+01 1.23853645e+01 1.20118246e+01 1.23501778e+01 1.30562801e+01 1.36402903e+01 1.36770878e+01 1.34267731e+01 1.34768276e+01 1.35982685e+01 1.38125706e+01 1.38388615e+01 1.36280527e+01 1.35061359e+01 1.34480886e+01 1.31956568e+01 1.31083870e+01 1.24966297e+01 1.23755283e+01 1.21351891e+01 1.23320961e+01 1.24972696e+01 1.28746414e+01 1.29108458e+01 1.30798311e+01 1.27364960e+01 1.27666178e+01 1.24509535e+01 1.24916840e+01 1.26846609e+01 1.28256369e+01 1.30571928e+01 1.32375546e+01 1.33466969e+01 1.33183346e+01 1.34319620e+01 1.35838499e+01 1.36720304e+01 1.35344124e+01 1.34766102e+01 1.34346285e+01 1.32923899e+01 1.31074381e+01 1.30465212e+01 1.28182993e+01 1.28552694e+01 1.31762266e+01 1.37964439e+01 1.39575281e+01 1.38800755e+01 1.35341892e+01 1.33415718e+01 1.31168356e+01 1.33979702e+01 1.37208700e+01 1.38915520e+01 1.38906441e+01 1.35460386e+01 1.34193916e+01 1.33920670e+01 1.36143970e+01 1.38076057e+01 1.35989676e+01 1.33018227e+01 1.30974360e+01 1.33644600e+01 1.36529264e+01 1.37809696e+01 1.36505079e+01 1.33730621e+01 1.32406006e+01 1.31696291e+01 1.34895678e+01 1.36514378e+01 1.36496553e+01 1.36824293e+01 1.36494837e+01 1.37962046e+01 1.37606421e+01 1.37945843e+01 1.37723064e+01 1.37082272e+01 1.36876211e+01 1.37291832e+01 1.37509861e+01 1.37648134e+01 1.37421417e+01 1.36252327e+01 1.35268288e+01 1.34717531e+01 1.35720310e+01 1.36289387e+01 1.36218042e+01 1.36093674e+01 1.36162186e+01 1.36158113e+01 1.35733461e+01 1.35678835e+01 1.36161652e+01 1.37035980e+01 1.37504435e+01 1.37763281e+01 1.37777290e+01 1.37957973e+01 1.37811956e+01 1.37805109e+01 1.37752209e+01 1.37831192e+01 1.37776413e+01 1.37823610e+01 1.37844095e+01 1.37726526e+01 1.37638521e+01 1.37736654e+01 1.37901134e+01 1.37939100e+01 1.37978516e+01 1.37809954e+01 1.37439680e+01 1.37369251e+01 1.38170815e+01 1.38401766e+01 1.38309460e+01 1.37517405e+01 1.37728338e+01 1.37804022e+01 1.38260784e+01 1.37893314e+01 1.38176193e+01 1.37587328e+01 1.38330708e+01 1.37629051e+01 1.38293915e+01 1.38594217e+01 1.39107695e+01 1.37833176e+01 1.36181765e+01 1.36835299e+01 1.37692795e+01 1.38145027e+01 1.36617765e+01 1.36334438e+01 1.36759081e+01 1.36685648e+01 1.35903301e+01 1.35675125e+01 1.35156202e+01 1.35755405e+01 1.35655518e+01 1.36039419e+01 1.37005997e+01 1.36405878e+01 1.36820469e+01 1.36244926e+01 1.36482325e+01 1.36086912e+01 1.35353136e+01 1.34398813e+01 1.34942122e+01 1.34572926e+01 1.35552530e+01 1.35348597e+01 1.34614258e+01 1.34884186e+01 1.35164747e+01 1.36025524e+01 1.35442305e+01 1.34245224e+01 1.32676764e+01 1.31031046e+01 1.31027088e+01 1.32325115e+01 1.30901318e+01 1.29132414e+01 1.29260645e+01 1.34112911e+01 1.36747675e+01 1.35790977e+01 1.31264906e+01 1.30073023e+01 1.30145807e+01 1.32199306e+01 1.37246399e+01 1.43110685e+01 1.43439054e+01 1.39156227e+01 1.33700886e+01 1.39596167e+01 1.43308764e+01 1.40698795e+01 1.33224277e+01 1.28441572e+01 1.29401064e+01 1.29947443e+01 1.31543856e+01 1.33458805e+01 1.33793087e+01 1.30280085e+01 1.29808607e+01 1.27382545e+01 1.31747742e+01 1.30860720e+01 1.30405645e+01 1.30633221e+01 1.33912382e+01 1.30768785e+01 1.28041868e+01 1.28398809e+01 1.37844801e+01 1.38676052e+01 1.36126184e+01 1.31989803e+01 1.35722094e+01 1.37917042e+01 1.41068296e+01 1.38379583e+01 1.35860882e+01 1.34601536e+01 1.26835308e+01 1.26655655e+01 1.24390602e+01 1.25880585e+01 1.24353180e+01 1.23183527e+01 1.29995947e+01 1.33079977e+01 1.34322948e+01 1.24847326e+01 1.23934269e+01 1.16590719e+01 1.31879139e+01 1.40907993e+01 1.43522644e+01 1.35454121e+01 1.24033327e+01 1.26190796e+01 1.22969952e+01 1.24871836e+01 1.27733593e+01 1.31625538e+01 1.30794964e+01 1.31899910e+01 1.34602461e+01 1.31983328e+01 1.30776958e+01 1.24393587e+01 1.24990482e+01 1.23475943e+01 1.27625351e+01 1.30523272e+01 1.33951778e+01 1.29304466e+01 1.20953836e+01 1.16221838e+01 1.13711023e+01 1.13716488e+01 1.10627537e+01 1.14006433e+01 1.18521776e+01 1.22499952e+01 1.29203415e+01 1.26879892e+01 1.29636641e+01 1.23067865e+01 1.35190296e+01 1.38166981e+01 1.42722378e+01 1.32376890e+01 1.23669949e+01 1.18101254e+01 1.21924276e+01 1.23888454e+01 1.28664503e+01 1.21038847e+01 1.22668571e+01 1.21834784e+01 1.15255299e+01 1.12052345e+01 1.05727921e+01 1.18106089e+01 1.23499823e+01 1.21244555e+01 1.25894594e+01 1.31952896e+01 1.37165842e+01 1.29100866e+01 1.16396713e+01 1.26887293e+01 1.24407873e+01 1.32839603e+01 1.21281443e+01 1.22144213e+01 1.05823326e+01 9.43280220e+00 8.93775082e+00 9.05961609e+00 9.22010422e+00 9.27882004e+00 9.70945072e+00 9.78035069e+00 9.47571850e+00 9.63521004e+00 9.87900829e+00 1.03442945e+01 1.10514107e+01 1.17210093e+01 1.25943213e+01 1.16000328e+01 1.05995493e+01 1.00463238e+01 1.19856853e+01 1.28016768e+01 1.22308664e+01 1.08283596e+01 1.00269012e+01 1.12407074e+01 1.07289591e+01 1.12027521e+01 1.07658005e+01 1.14577570e+01 1.16475239e+01 1.14977779e+01 1.05104885e+01 9.65602493e+00 9.05793953e+00 9.74328232e+00 9.85699749e+00 9.68573952e+00 1.00482407e+01 1.01597099e+01 1.11442823e+01 1.05408154e+01 1.04279394e+01 8.72327232e+00 8.96512127e+00 1.05474205e+01 1.15815821e+01 1.03887949e+01 9.01990891e+00 9.88707829e+00 1.02649660e+01 9.74195480e+00 9.39403629e+00 8.32873249e+00 8.30384541e+00 7.56476736e+00 8.98997211e+00 9.43107224e+00 9.54258537e+00 9.07583046e+00 9.14559269e+00 9.78302097e+00 9.46042156e+00 8.40992928e+00 6.77014780e+00 7.01896334e+00 6.70721579e+00 7.43161011e+00 6.77550936e+00 8.35502338e+00 9.13522339e+00 1.02957640e+01 9.72585201e+00 8.40649509e+00 8.21559525e+00 7.61201620e+00 8.83455372e+00 7.93843746e+00 8.20809555e+00 8.03937912e+00 9.40152645e+00 1.03067789e+01 1.08385439e+01 1.01476908e+01 9.46104145e+00 9.92727947e+00 1.13994827e+01 1.08999109e+01 8.76828098e+00 7.41659641e+00 6.93255758e+00 8.25412750e+00 6.35899162e+00 6.40897083e+00 6.45328522e+00 7.43390751e+00 8.49560738e+00 7.74101973e+00 7.57790375e+00 5.76592875e+00 5.30571413e+00 5.50744343e+00 5.94255543e+00 6.25378990e+00 5.89068794e+00 6.20944786e+00 6.84353447e+00 7.49303007e+00 6.93284512e+00 5.86532545e+00 5.04626036e+00 5.92019701e+00 5.13961363e+00 5.27700472e+00 5.67491627e+00 8.90568542e+00 1.14277859e+01 1.20054464e+01 1.03110914e+01 9.44259930e+00 9.62775326e+00 9.27085209e+00 7.97826147e+00 5.71792316e+00 7.82122469e+00 8.77613163e+00 9.62334538e+00 8.11827564e+00 8.12163448e+00 8.18278408e+00 6.09576130e+00 5.24833536e+00 5.86647320e+00 7.82998466e+00 7.05177498e+00 7.35666943e+00 8.58582020e+00 8.76752758e+00 5.21255350e+00 2.47826052e+00 1.70411170e+00 3.99318218e+00 3.87819195e+00 3.66088414e+00 3.69412231e+00 4.38208580e+00 5.61990929e+00 4.94717216e+00 4.38389730e+00 3.75252843e+00 3.46282601e+00 5.03511000e+00 6.47408819e+00 7.80701399e+00 7.53796196e+00 5.76332760e+00 4.24648666e+00 3.34104013e+00 4.10958958e+00 3.65480280e+00 3.77758265e+00 4.31927490e+00 3.60701013e+00 1.89723301e+00 1.57283092e+00 4.03161240e+00 4.43204308e+00 4.46982861e+00 4.94538403e+00 7.63839817e+00 8.26614761e+00 6.84538651e+00 5.19051600e+00 3.81054306e+00 4.36962461e+00 4.07357025e+00 4.77414656e+00 6.00126219e+00 6.45101213e+00 6.50529099e+00 4.93612432e+00 4.86560059e+00 5.00602102e+00 5.19011354e+00 6.52894688e+00 7.26787710e+00 8.27049255e+00 6.95103359e+00 5.79322147e+00 5.82097721e+00 7.53065395e+00 6.36584187e+00 4.51737404e+00 2.08971620e+00 3.27331233e+00 4.69085979e+00 4.51924086e+00 4.76223993e+00 3.73782492e+00 2.75283623e+00 1.90312457e+00 2.50108647e+00 5.12464857e+00 6.75633860e+00 5.34546757e+00 5.02558994e+00 5.14765453e+00 4.63987875e+00 4.04923725e+00 2.83866787e+00 4.66888475e+00 5.19134903e+00 3.77637243e+00 1.52645731e+00 1.17589928e-01 2.01176286e+00 3.63575554e+00 3.80688334e+00 3.25030589e+00 3.11512661e+00 3.63318729e+00 3.19336486e+00 3.26590157e+00 4.21906805e+00 5.89579678e+00 5.47957373e+00 4.18029642e+00 2.46297240e+00 3.78623652e+00 3.60007858e+00 4.08776951e+00 2.67075610e+00 2.41546464e+00 2.65649223e+00 3.06025553e+00 9.74893868e-01 -4.76014882e-01 -3.89597964e+00 -2.79021811e+00 -1.41852272e+00 2.49152136e+00 1.79199517e+00 4.14213568e-01 -9.16099668e-01 -2.23338199e+00 -2.09031534e+00 -2.22061682e+00 -2.87523985e+00 -7.10333157e+00 -4.46260834e+01 -1.14003059e+02 -5.10893219e+02 -6.08851685e+02 2.47417627e+03 1.64311953e+04 -1638379008. 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. 2.75057254e+09 -6.25107520e+03 2.29594406e+02 3.92353943e+02 9.91939163e+01 5.53960762e+01 1.29673672e+01 1.84001207e+00 1.39472103e+00 -6.66706711e-02 -4.12799120e-02 -7.53637850e-01 -6.47033215e-01 -9.43506122e-01 2.79523939e-01 7.22882211e-01 -2.90064663e-01 -2.02865505e+00 -3.82159472e+00 -4.06781244e+00 -3.41497874e+00 -1.51238394e+00 -3.45806152e-01 6.76226616e-01 -1.39336109e-01 -8.84987354e-01 -8.84445310e-01 -5.85370362e-01 -1.88748527e+00 -2.48642945e+00 -1.78767920e+00 -7.66435638e-02 4.68951881e-01 7.68140256e-01 7.39777863e-01 -9.75473505e-03 -1.72669268e+00 -2.45489717e+00 -3.07664180e+00 -1.61823702e+00 -2.17786074e+00 -8.56720805e-01 -5.51900506e-01 1.43043935e-01 -1.29734075e+00 -2.12925029e+00 -1.84726679e+00 -1.34025693e+00 -8.87690365e-01 -1.09180188e+00 -9.25451875e-01 -1.95461464e+00 -2.26492214e+00 -3.67134356e+00 -3.55810595e+00 -4.32534075e+00 -2.78615928e+00 -1.08290780e+00 4.81229156e-01 2.84637511e-01 -1.16723979e+00 -1.88636363e+00 -2.16357803e+00 -1.93008757e+00 -1.98011649e+00 -2.63884521e+00 -2.62789702e+00 -2.52004313e+00 -1.42442155e+00 -2.49427629e+00 -3.09198999e+00 -3.36443162e+00 -3.55294943e+00 -3.47215772e+00 -3.44010282e+00 -3.17996573e+00 -3.57612848e+00 -3.40303969e+00 -3.62960982e+00 -3.48005414e+00 -4.49233532e+00 -4.00535107e+00 -3.06995869e+00 -2.89571524e+00 -2.97957397e+00 -4.30125237e+00 -4.39823771e+00 -4.06089640e+00 -3.27749014e+00 -3.55387068e+00 -3.74739361e+00 -2.90049076e+00 -1.57586265e+00 -1.88486898e+00 -3.44636250e+00 -4.24020720e+00 -3.12938118e+00 -2.65563345e+00 -3.40093064e+00 -4.28167391e+00 -4.26142025e+00 -3.45440531e+00 -3.47882581e+00 -4.32170153e+00 -5.57837439e+00 -5.39861393e+00 -4.49353266e+00 -2.76560807e+00 -1.85108614e+00 -1.33270073e+00 -2.79507947e+00 -4.28415489e+00 -4.49285746e+00 -3.48826790e+00 -2.98527622e+00 -2.68437505e+00 -3.09186649e+00 -2.01068830e+00 -2.14045048e+00 -3.84194303e+00 -5.08846855e+00 -5.82185888e+00 -4.22983885e+00 -3.74913406e+00 -2.97936988e+00 -2.36872673e+00 -3.44686389e+00 -4.22541046e+00 -5.54493284e+00 -5.77767611e+00 -5.81673193e+00 -5.33793736e+00 -5.21540689e+00 -5.41567326e+00 -4.68581390e+00 -4.08150005e+00 -3.21824837e+00 -3.73098421e+00 -4.74327421e+00 -6.30572510e+00 -6.80970573e+00 -6.07113314e+00 -4.46671295e+00 -3.75055814e+00 -3.58670592e+00 -4.23390818e+00 -3.60613322e+00 -3.63334966e+00 -3.57252455e+00 -4.98725557e+00 -5.59271288e+00 -6.49585295e+00 -5.63240814e+00 -4.76943111e+00 -4.05050468e+00 -4.79798889e+00 -5.10255051e+00 -4.38267946e+00 -2.89133644e+00 -3.29549623e+00 -5.00061417e+00 -5.55361986e+00 -4.56413698e+00 -3.41049004e+00 -4.55263758e+00 -4.80781269e+00 -4.84224176e+00 -3.59128094e+00 -3.18209791e+00 -4.09855509e+00 -5.39058161e+00 -6.73646212e+00 -6.16465330e+00 -6.52982569e+00 -6.73326731e+00 -5.76513624e+00 -5.79848766e+00 -4.76195621e+00 -5.48343277e+00 -5.37765455e+00 -6.12122583e+00 -6.93397760e+00 -6.31459093e+00 -5.92836380e+00 -6.02172136e+00 -5.66669893e+00 -6.31120872e+00 -4.94493008e+00 -5.88638687e+00 -5.79799604e+00 -5.92410898e+00 -4.72676516e+00 -4.56631565e+00 -6.09247303e+00 -6.27981520e+00 -7.33239222e+00 -6.70709085e+00 -7.43266106e+00 -6.31703424e+00 -6.53150415e+00 -6.29697132e+00 -6.19473171e+00 -6.10744095e+00 -5.44443798e+00 -6.08456707e+00 -5.23516846e+00 -6.02880621e+00 -5.61271858e+00 -6.61487389e+00 -5.89111757e+00 -6.40887308e+00 -6.13906670e+00 -6.44457912e+00 -5.21502733e+00 -5.79847956e+00 -6.75711441e+00 -7.17029715e+00 -7.13078928e+00 -5.15592813e+00 -5.01158381e+00 -4.44498682e+00 -5.96887398e+00 -7.19463015e+00 -7.23723173e+00 -6.51704407e+00 -5.81302738e+00 -5.92482281e+00 -7.19668388e+00 -7.20666075e+00 -7.50668335e+00 -6.13657856e+00 -6.36088991e+00 -6.17920780e+00 -6.50989962e+00 -6.18354177e+00 -6.27901983e+00 -5.48686028e+00 -5.42393351e+00 -5.50489378e+00 -6.42929029e+00 -6.08299017e+00 -6.31512213e+00 -6.85395050e+00 -6.35600662e+00 -6.04896688e+00 -5.72330713e+00 -7.22055817e+00 -7.06537104e+00 -7.06195164e+00 -6.66594601e+00 -7.26773739e+00 -7.24843025e+00 -6.90258884e+00 -6.54414225e+00 -5.93821430e+00 -5.85108328e+00 -6.08384132e+00 -6.11748743e+00 -5.92619801e+00 -6.14762497e+00 -6.23637342e+00 -6.83505297e+00 -5.89063597e+00 -6.55582714e+00 -6.90224695e+00 -7.36349487e+00 -7.55204391e+00 -6.53421640e+00 -5.90524530e+00 -5.72169876e+00 -6.34738302e+00 -5.94988108e+00 -5.78730726e+00 -5.15795040e+00 -6.24713421e+00 -6.54411793e+00 -7.00070953e+00 -6.81348991e+00 -6.80033207e+00 -6.51641130e+00 -6.89067888e+00 -7.35627604e+00 -8.28065968e+00 -7.79002714e+00 -7.35782814e+00 -7.37543201e+00 -7.80355978e+00 -7.56322193e+00 -7.09543276e+00 -6.41684675e+00 -6.60185575e+00 -6.73860216e+00 -7.18420172e+00 -6.83764124e+00 -7.04274178e+00 -7.37635088e+00 -7.20031595e+00 -7.21109724e+00 -6.73554277e+00 -7.17294884e+00 -6.42504215e+00 -6.09804916e+00 -6.14426947e+00 -6.82188988e+00 -7.66159534e+00 -7.45303488e+00 -7.10737562e+00 -7.17134142e+00 -7.57211781e+00 -7.78611279e+00 -7.99357653e+00 -7.76874018e+00 -7.80567265e+00 -7.38058138e+00 -7.39542580e+00 -7.66351509e+00 -8.06174564e+00 -7.93709040e+00 -7.19893789e+00 -6.91766787e+00 -7.03228855e+00 -7.53455067e+00 -7.57654095e+00 -7.20427704e+00 -7.29126930e+00 -7.45657015e+00 -8.15523720e+00 -8.75248337e+00 -8.87283039e+00 -8.77525234e+00 -8.09455109e+00 -8.02022839e+00 -8.03482437e+00 -8.17903042e+00 -7.90317535e+00 -7.91781235e+00 -8.43354511e+00 -8.43068695e+00 -8.21129322e+00 -7.94311333e+00 -8.28587818e+00 -8.23169231e+00 -7.61723089e+00 -7.07369661e+00 -7.58310556e+00 -8.00590801e+00 -8.73329735e+00 -8.30880833e+00 -8.36659241e+00 -8.22691345e+00 -8.45790291e+00 -8.07527161e+00 -8.08032799e+00 -8.38871574e+00 -8.72398853e+00 -8.36496067e+00 -7.96921873e+00 -7.78576565e+00 -8.16201115e+00 -8.43604851e+00 -8.68776608e+00 -8.98333073e+00 -8.78466511e+00 -8.41142464e+00 -7.99483871e+00 -8.06102943e+00 -7.96817636e+00 -8.01752663e+00 -7.88721180e+00 -8.26042366e+00 -8.23555756e+00 -8.34042740e+00 -8.28358364e+00 -8.18342400e+00 -8.21829128e+00 -8.05461025e+00 -7.97322321e+00 -7.88940287e+00 -8.18279171e+00 -8.37208271e+00 -8.18611431e+00 -7.95677280e+00 -7.99996996e+00 -8.38370037e+00 -8.36482430e+00 -8.48972607e+00 -8.28501606e+00 -8.48104477e+00 -8.35531712e+00 -8.37531090e+00 -8.04896641e+00 -8.09409904e+00 -8.36246204e+00 -8.83863354e+00 -8.49052525e+00 -8.03792763e+00 -7.81291056e+00 -7.99651670e+00 -8.34787178e+00 -8.47893810e+00 -8.59992123e+00 -8.49423122e+00 -8.58182812e+00 -8.55189228e+00 -8.73980713e+00 -8.32677078e+00 -8.26639843e+00 -8.07427979e+00 -8.35370350e+00 -8.45625591e+00 -8.51840305e+00 -8.53466320e+00 -8.46679401e+00 -8.42463684e+00 -8.38323212e+00 -8.36486721e+00 -8.46738529e+00 -8.45977211e+00 -8.50499630e+00 -8.46697998e+00 -8.45090866e+00 -8.54816914e+00 -8.55444622e+00 -8.57328510e+00 -8.51691628e+00 -8.47631168e+00 -8.43968868e+00 -8.43036366e+00 -8.51738453e+00 -8.56767845e+00 -8.57459641e+00 -8.51769257e+00 -8.51655293e+00 -8.52110863e+00 -8.55104160e+00 -8.54205227e+00 -8.53912354e+00 -8.52828407e+00 -8.52991104e+00 -8.53403664e+00 -8.53775215e+00 -8.53036213e+00 -8.52599049e+00 -8.50767899e+00 -8.50977325e+00 -8.54113102e+00 -8.54676437e+00 -8.56561184e+00 -8.53795147e+00 -8.51618004e+00 -8.51762486e+00 -8.54203224e+00 -8.57637024e+00 -8.57468033e+00 -8.52646542e+00 -8.55751801e+00 -8.51484966e+00 -8.50939178e+00 -8.46413898e+00 -8.48977280e+00 -8.59478951e+00 -8.60314655e+00 -8.51883602e+00 -8.57163811e+00 -8.55576324e+00 -8.70152855e+00 -8.54784489e+00 -8.56371498e+00 -8.49987984e+00 -8.49998856e+00 -8.58763504e+00 -8.45923996e+00 -8.39377117e+00 -8.14874840e+00 -8.21480656e+00 -8.35918236e+00 -8.45897675e+00 -8.56259537e+00 -8.39142132e+00 -8.31637669e+00 -8.25163651e+00 -8.44852829e+00 -8.49363518e+00 -8.46753502e+00 -8.17530537e+00 -8.24616814e+00 -8.07436943e+00 -8.35214901e+00 -8.38049126e+00 -8.76141644e+00 -8.57794285e+00 -8.47822285e+00 -8.39794636e+00 -8.49816132e+00 -8.43987179e+00 -8.47032738e+00 -8.55972099e+00 -8.66835499e+00 -8.38935852e+00 -8.18991852e+00 -8.39278507e+00 -8.42311478e+00 -8.52812672e+00 -8.21750450e+00 -8.16872311e+00 -7.88821030e+00 -7.95034647e+00 -7.99936533e+00 -8.35904980e+00 -8.43054771e+00 -8.48084068e+00 -8.49579144e+00 -8.18382740e+00 -8.25674629e+00 -8.07955456e+00 -8.48082066e+00 -8.42881012e+00 -8.28724861e+00 -8.10758400e+00 -8.04361343e+00 -8.17771626e+00 -8.26697063e+00 -8.37321377e+00 -8.18909645e+00 -8.31724548e+00 -8.45186043e+00 -8.73615837e+00 -8.38177776e+00 -8.21020794e+00 -7.83761263e+00 -7.94587326e+00 -7.60162067e+00 -8.09843254e+00 -8.17566872e+00 -8.53205776e+00 -8.39225292e+00 -8.34469223e+00 -8.10317326e+00 -8.49553490e+00 -8.34755993e+00 -8.33055878e+00 -7.74942112e+00 -7.36131001e+00 -7.29507303e+00 -7.66710854e+00 -8.33374786e+00 -8.77421093e+00 -8.15468407e+00 -7.32498121e+00 -6.77606726e+00 -7.07119560e+00 -7.73855591e+00 -8.51268101e+00 -8.13956165e+00 -7.61408567e+00 -7.40887642e+00 -7.42293692e+00 -7.93284130e+00 -7.70793962e+00 -7.90128422e+00 -7.89696884e+00 -7.83658218e+00 -7.67144203e+00 -7.41912317e+00 -7.52250767e+00 -8.48383141e+00 -9.13549709e+00 -8.79980183e+00 -8.09108829e+00 -7.52552271e+00 -7.95621681e+00 -8.14699841e+00 -8.25726700e+00 -7.03423834e+00 -6.76621389e+00 -7.30187607e+00 -8.23945045e+00 -7.91289282e+00 -7.12664080e+00 -7.04010677e+00 -7.46059608e+00 -7.85809374e+00 -8.21444988e+00 -8.24251556e+00 -7.63571358e+00 -7.65596628e+00 -7.57283115e+00 -8.00502491e+00 -7.87769938e+00 -7.67838478e+00 -7.90211487e+00 -7.93060637e+00 -7.55269623e+00 -7.23674536e+00 -7.05668354e+00 -8.10534000e+00 -7.85069847e+00 -7.48416758e+00 -6.84876633e+00 -7.42831182e+00 -7.99599743e+00 -8.10512161e+00 -8.24645710e+00 -8.04189873e+00 -7.70388031e+00 -6.93391895e+00 -6.61615515e+00 -7.57601023e+00 -7.44329977e+00 -6.70145702e+00 -5.85148668e+00 -5.92944765e+00 -6.14857292e+00 -5.53958941e+00 -5.94149303e+00 -6.53786469e+00 -6.21295691e+00 -4.72536612e+00 -1.93173707e+00 -2.75404263e+00 5.38519001e+00 4.19462013e+01 4.19347198e+02 9.95509644e+02 130009296. -133904840. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -77444984. -367311776. 878504896. 2.26729395e+03 -1.51179459e+02 -2.76879150e+02 -7.72380676e+01 -3.87421455e+01 -1.90842991e+01 -1.26877689e+01 -9.06159019e+00 -9.31713867e+00 -8.86458206e+00 -7.19921780e+00 -6.17544365e+00 -5.04050303e+00 -6.32977009e+00 -5.51157188e+00 -6.03708172e+00 -6.53497267e+00 -6.51864719e+00 -7.32037735e+00 -6.83818054e+00 -6.81585455e+00 -4.74340010e+00 -3.77503467e+00 -5.80824327e+00 -6.67563057e+00 -5.88008213e+00 -4.16823864e+00 -4.90732861e+00 -7.26165915e+00 -7.30848265e+00 -6.43666220e+00 -5.11945677e+00 -5.03200245e+00 -5.10604239e+00 -5.46726751e+00 -5.77668142e+00 -6.04503202e+00 -5.60776091e+00 -5.62691307e+00 -5.54899073e+00 -5.79436827e+00 -5.91985178e+00 -6.46411705e+00 -7.20074701e+00 -6.44119358e+00 -5.91981840e+00 -5.08330965e+00 -5.45906925e+00 -6.57332516e+00 -6.17770243e+00 -5.21529007e+00 -3.89366436e+00 -4.34384394e+00 -5.24125576e+00 -4.79730511e+00 -4.75230217e+00 -3.66900992e+00 -3.72999859e+00 -3.50005889e+00 -4.05181980e+00 -5.16399860e+00 -6.17642260e+00 -6.38390112e+00 -5.73438835e+00 -5.24085522e+00 -4.97698975e+00 -4.85066605e+00 -5.23817205e+00 -6.49083185e+00 -6.83952332e+00 -6.14258623e+00 -4.95047665e+00 -4.43120384e+00 -4.89367151e+00 -3.74424791e+00 -3.18791270e+00 -2.34962058e+00 -2.94122744e+00 -4.07556009e+00 -3.67859221e+00 -4.59655476e+00 -3.54634237e+00 -3.67646646e+00 -2.70778275e+00 -3.08513308e+00 -4.10654640e+00 -4.51885128e+00 -4.54019737e+00 -4.08350706e+00 -4.30756378e+00 -4.14489412e+00 -3.74000907e+00 -2.81679487e+00 -3.57282782e+00 -3.94244337e+00 -4.05342388e+00 -3.44658208e+00 -2.80795288e+00 -4.48555994e+00 -5.33946371e+00 -5.28648567e+00 -4.34356928e+00 -3.88903284e+00 -5.03610086e+00 -5.08198452e+00 -4.86275482e+00 -4.62000847e+00 -4.53532410e+00 -4.42421961e+00 -4.20540047e+00 -5.13899803e+00 -5.21258211e+00 -5.01968527e+00 -4.51915264e+00 -4.83607435e+00 -4.80390120e+00 -3.97162557e+00 -3.33847380e+00 -3.94870234e+00 -3.35005975e+00 -3.37537599e+00 -1.91620398e+00 -2.55585170e+00 -3.89927888e+00 -4.49900532e+00 -3.95611453e+00 -2.52923322e+00 -2.09383249e+00 -3.33537316e+00 -3.97932220e+00 -4.49136829e+00 -4.13289452e+00 -3.58432531e+00 -3.75045896e+00 -3.59542799e+00 -4.00848389e+00 -4.06575584e+00 -3.14036965e+00 -2.65351582e+00 -2.23244715e+00 -3.30545282e+00 -3.57638097e+00 -3.36913919e+00 -2.83933902e+00 -2.87043500e+00 -2.56500077e+00 -3.44393730e+00 -3.20998502e+00 -3.93638587e+00 -3.20738053e+00 -3.43183589e+00 -2.36250234e+00 -1.48024821e+00 -1.33499444e+00 -6.89817131e-01 -1.81489670e+00 -1.77081585e+00 -3.22484517e+00 -2.86802101e+00 -2.18422842e+00 -1.68623650e+00 -2.83939528e+00 -3.80340576e+00 -3.09569669e+00 -2.32253885e+00 -6.44841433e-01 -5.40993392e-01 1.88221848e+00 -6.40843391e-01 -5.75437188e-01 -1.18495619e+00 -2.33443424e-01 4.85644042e-01 -8.32305908e-01 -6.49224699e-01 -2.05020261e+00 -2.56687045e+00 -2.27603483e+00 -1.68495786e+00 -2.94797421e-01 -8.03233206e-01 -1.51671052e+00 -1.48439562e+00 -1.49129435e-01 -2.05334514e-01 -8.66475701e-01 -3.50428128e+00 -4.26517773e+00 -3.66127896e+00 -1.30451190e+00 -7.87899196e-02 4.80556697e-01 -5.07639587e-01 -1.98501229e+00 -2.36596131e+00 -7.69357264e-01 6.53208673e-01 8.57773602e-01 -1.71128854e-01 -9.32884455e-01 -2.18114734e+00 -2.03341460e+00 -2.02530813e+00 -1.78252232e+00 -1.81618738e+00 -1.31189644e+00 -1.60141516e+00 -2.26258945e+00 -2.88456702e+00 -2.02777624e+00 -8.97444785e-01 2.10720137e-01 -2.91680992e-02 -1.97560024e+00 -3.44183183e+00 -3.11951804e+00 -2.11625242e+00 -1.84436917e+00 -1.93107331e+00 -6.96724117e-01 4.21699643e-01 2.04483247e+00 2.40922451e+00 1.94128919e+00 4.83075321e-01 -4.43436086e-01 -5.34523785e-01 7.66499117e-02 5.99035323e-01 1.20644629e+00 1.43497360e+00 1.09983921e+00 1.08041227e+00 7.56538689e-01 9.33095753e-01 7.45166004e-01 1.66327834e+00 1.61582839e+00 1.50218165e+00 2.20060065e-01 -6.59360066e-02 1.87258697e+00 1.91830719e+00 2.68412876e+00 1.21190166e+00 1.37355971e+00 1.21147668e+00 1.69882250e+00 2.19545674e+00 1.93843651e+00 1.01071429e+00 -2.38189518e-01 -6.84134185e-01 -4.87680405e-01 4.44415882e-02 6.57568216e-01 6.94945395e-01 7.95514107e-01 -1.44294128e-01 -6.33054912e-01 -2.58637667e-01 1.61424935e+00 1.30132246e+00 4.97609109e-01 -6.16725206e-01 2.44872761e+00 2.52069998e+00 3.03195238e+00 1.41744936e+00 1.64071417e+00 2.23042560e+00 1.18477893e+00 1.34612501e+00 1.21961260e+00 2.53269458e+00 2.57493877e+00 1.92819417e+00 8.14672351e-01 7.10021555e-01 2.44190621e+00 2.65456438e+00 2.35012269e+00 1.28715515e+00 2.39404082e+00 3.19182062e+00 2.85787344e+00 1.75148952e+00 1.18673432e+00 1.44436777e+00 1.89514101e+00 1.67509234e+00 1.80603349e+00 2.04782772e+00 2.94702744e+00 2.65718865e+00 3.11342144e+00 2.75266862e+00 2.83043671e+00 4.42795658e+00 3.20102406e+00 3.41663265e+00 1.87440920e+00 2.54471064e+00 2.30030632e+00 1.19086909e+00 1.72888911e+00 2.39525628e+00 2.74128079e+00 2.50970721e+00 2.92971539e+00 2.47545600e+00 1.78429985e+00 2.03934145e+00 2.24963927e+00 3.32923508e+00 2.47034502e+00 3.14434290e+00 3.37532973e+00 3.23863411e+00 3.43514562e+00 2.50399518e+00 3.35569763e+00 3.02871418e+00 3.36867356e+00 2.65453839e+00 2.29939342e+00 3.34170914e+00 3.50405550e+00 3.85440755e+00 3.33546877e+00 3.60811973e+00 3.56869912e+00 3.85119724e+00 3.12603474e+00 2.79190922e+00 2.02096558e+00 2.39716101e+00 1.99847555e+00 4.22089863e+00 3.54243279e+00 3.82995653e+00 2.40544534e+00 2.16094661e+00 8.24083507e-01 2.58104181e+00 2.97904515e+00 4.54159832e+00 2.81721997e+00 3.10986543e+00 2.14401031e+00 3.24358511e+00 2.82767725e+00 4.88155603e+00 3.84273052e+00 4.93618250e+00 4.39689636e+00 4.35293531e+00 3.77706933e+00 4.38348007e+00 3.63947415e+00 4.20920038e+00 3.99258733e+00 5.73768091e+00 5.26207304e+00 3.75395823e+00 3.99986959e+00 3.24375987e+00 4.86628294e+00 3.82171655e+00 4.51936102e+00 3.61260438e+00 3.65509892e+00 4.43551302e+00 5.74798822e+00 5.95267820e+00 4.64601755e+00 4.47092485e+00 5.11731911e+00 5.26598930e+00 4.50337267e+00 4.09181070e+00 4.63551712e+00 5.21735239e+00 5.55012846e+00 5.74439001e+00 5.48363829e+00 4.65360928e+00 4.34667683e+00 4.05525827e+00 4.83969975e+00 4.85678720e+00 5.64005518e+00 4.81595659e+00 5.44926691e+00 4.51429033e+00 6.62276316e+00 5.45704412e+00 5.93842697e+00 4.18213844e+00 5.77702856e+00 5.69193697e+00 5.67441750e+00 3.25090384e+00 2.06921768e+00 2.67562485e+00 4.00113153e+00 5.34216452e+00 5.64899063e+00 5.40869999e+00 5.28049660e+00 4.99952984e+00 5.33296251e+00 5.68104076e+00 5.78184175e+00 6.31243420e+00 5.26537704e+00 4.91121483e+00 4.52013683e+00 5.60859871e+00 5.66443729e+00 5.32175064e+00 4.61057997e+00 4.36061001e+00 4.54059219e+00 4.80625391e+00 5.67892838e+00 5.65574121e+00 5.47540951e+00 4.74918413e+00 4.75012016e+00 5.15116644e+00 6.01319313e+00 6.42870426e+00 5.99970388e+00 5.82098103e+00 5.58684444e+00 6.35688543e+00 6.08896112e+00 5.90191460e+00 5.53142357e+00 5.25296402e+00 5.79701853e+00 6.04320812e+00 6.85420036e+00 7.14231634e+00 6.90745306e+00 5.74420118e+00 5.27436590e+00 4.81864786e+00 6.14016771e+00 6.65579796e+00 6.34270382e+00 5.98871517e+00 7.50708628e+00 7.58951902e+00 1.03069372e+01 2.28306446e+01 2.24735947e+01 5.19342041e+01 4.46850647e+02 3.53963623e+03 68307016. 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. 0. 0. 0. 0. 0. 0. 186387872. 36761196. 1.11109082e+03 7.80300537e+02 9.85371323e+01 -2.48511551e+02 -1.78236374e+02 -2.12954330e+01 2.00043845e+00 6.03901243e+00 7.98186636e+00 8.06787395e+00 7.30520153e+00 7.25245476e+00 7.59531260e+00 7.68490791e+00 7.70361805e+00 8.29364300e+00 8.71714973e+00 8.44476700e+00 8.00701523e+00 7.60996485e+00 7.75022840e+00 7.47472525e+00 7.49289513e+00 7.24900627e+00 7.09725761e+00 7.19931984e+00 7.49755144e+00 7.55852175e+00 7.10714579e+00 6.82110453e+00 7.01201868e+00 7.23404789e+00 7.25973225e+00 7.24164391e+00 7.48328352e+00 7.61439562e+00 7.74153566e+00 7.50433922e+00 8.03433704e+00 8.07704163e+00 8.24586868e+00 7.92851496e+00 7.51891518e+00 7.45732212e+00 7.33340216e+00 7.34733105e+00 7.04963350e+00 7.00475550e+00 6.99624634e+00 7.19200277e+00 7.58084011e+00 7.68884754e+00 7.83772326e+00 7.82676315e+00 7.78185892e+00 7.82190418e+00 7.49636793e+00 7.90521431e+00 7.63735151e+00 7.75197315e+00 8.01976109e+00 8.50142384e+00 8.59548187e+00 8.25148487e+00 8.15081215e+00 8.35470104e+00 8.54445362e+00 8.64251518e+00 8.18353558e+00 8.03217316e+00 7.65818501e+00 7.71355438e+00 7.42361355e+00 7.31628466e+00 7.46163225e+00 7.49763012e+00 7.85854721e+00 7.90907049e+00 8.13469028e+00 8.27830887e+00 8.24252224e+00 8.19674206e+00 8.23654842e+00 8.33942795e+00 8.57016373e+00 8.28163052e+00 8.23321438e+00 8.14087963e+00 8.36350346e+00 8.32771587e+00 8.37029266e+00 8.44129467e+00 8.53553391e+00 8.46289539e+00 8.34067154e+00 8.15009785e+00 8.25201607e+00 8.44878864e+00 8.71089363e+00 8.66735840e+00 8.45447159e+00 8.40786743e+00 8.38642216e+00 8.46624851e+00 8.27195740e+00 8.30708027e+00 8.42455387e+00 8.75707436e+00 8.85896778e+00 8.64671516e+00 8.45392704e+00 8.38916302e+00 8.42429733e+00 8.52823257e+00 8.41390038e+00 8.42444038e+00 8.26306629e+00 8.13416004e+00 8.07728672e+00 8.11925411e+00 8.43926525e+00 8.56836796e+00 8.64120007e+00 8.52832603e+00 8.45674706e+00 8.50518513e+00 8.68640614e+00 8.86392307e+00 8.80461884e+00 8.65085411e+00 8.45350552e+00 8.48775673e+00 8.47296810e+00 8.62675667e+00 8.60668182e+00 8.60202122e+00 8.45972538e+00 8.45383263e+00 8.49285698e+00 8.54856396e+00 8.51499176e+00 8.47690201e+00 8.49617672e+00 8.50043106e+00 8.55630589e+00 8.50559616e+00 8.53829002e+00 8.48866940e+00 8.51517200e+00 8.45460796e+00 8.41673183e+00 8.48530006e+00 8.59895802e+00 8.61040211e+00 8.55927944e+00 8.51531792e+00 8.57152843e+00 8.60654068e+00 8.62339687e+00 8.63746643e+00 8.63739109e+00 8.62762260e+00 8.56971169e+00 8.53535271e+00 8.52477741e+00 8.54706383e+00 8.54281235e+00 8.53549480e+00 8.53905106e+00 8.53660774e+00 8.54067993e+00 8.53415108e+00 8.53581810e+00 8.53472042e+00 8.53393459e+00 8.53578091e+00 8.53624725e+00 8.53612614e+00 8.53117752e+00 8.52974224e+00 8.52469158e+00 8.51108551e+00 8.52187729e+00 8.50995159e+00 8.51015186e+00 8.50618172e+00 8.56576157e+00 8.55495453e+00 8.56356621e+00 8.51146698e+00 8.56014824e+00 8.50935841e+00 8.49391937e+00 8.46212196e+00 8.47641182e+00 8.46051216e+00 8.44007015e+00 8.46761799e+00 8.53756618e+00 8.56480789e+00 8.58915424e+00 8.50780201e+00 8.48554707e+00 8.48704433e+00 8.55697823e+00 8.54620647e+00 8.46685791e+00 8.37095833e+00 8.44727898e+00 8.47071838e+00 8.48691368e+00 8.41683674e+00 8.40105438e+00 8.41511059e+00 8.43593311e+00 8.42929173e+00 8.39039040e+00 8.32310200e+00 8.30612659e+00 8.35645676e+00 8.43880653e+00 8.50880051e+00 8.47850418e+00 8.39239788e+00 8.35240746e+00 8.37984657e+00 8.49074364e+00 8.48515892e+00 8.45437241e+00 8.40840244e+00 8.32060814e+00 8.50007534e+00 8.51024914e+00 8.61354065e+00 8.51030540e+00 8.46148586e+00 8.57107067e+00 8.57328415e+00 8.49991417e+00 8.39963627e+00 8.35032177e+00 8.42279148e+00 8.57062912e+00 8.63720894e+00 8.80779839e+00 8.76407242e+00 8.52309799e+00 8.11878109e+00 8.15989304e+00 8.29737473e+00 8.55383873e+00 8.20827675e+00 8.03374958e+00 7.99991083e+00 8.35911560e+00 8.54094124e+00 8.75535393e+00 8.72103977e+00 8.70146561e+00 8.21250057e+00 8.00242424e+00 7.97233438e+00 8.23662949e+00 7.79739666e+00 8.14101124e+00 8.20680237e+00 8.71368313e+00 8.45069981e+00 8.52670479e+00 8.43014240e+00 8.37608433e+00 8.33004761e+00 8.28774929e+00 8.45951939e+00 8.28862095e+00 8.13472939e+00 7.69444513e+00 7.70874357e+00 7.89016151e+00 8.23745060e+00 8.52589226e+00 8.38544846e+00 8.11089706e+00 7.90985775e+00 8.08643055e+00 8.31875420e+00 8.50134182e+00 8.40907288e+00 8.16551399e+00 7.95510435e+00 8.19643307e+00 8.15748978e+00 8.12611961e+00 8.09156322e+00 8.19139957e+00 7.93568230e+00 7.52293444e+00 7.61879253e+00 7.87511635e+00 8.21945858e+00 7.66647100e+00 7.58542204e+00 7.29039717e+00 7.66940022e+00 7.35004377e+00 7.24302721e+00 6.91193104e+00 7.02875137e+00 7.03054380e+00 7.03382444e+00 7.21634769e+00 7.25207615e+00 7.49161577e+00 7.23850203e+00 7.50312519e+00 7.54933119e+00 8.11122990e+00 7.61025620e+00 7.86579466e+00 7.22323322e+00 7.68472147e+00 7.55339956e+00 7.68614197e+00 7.47816324e+00 6.98027563e+00 6.58636999e+00 6.30130482e+00 6.08831453e+00 6.54218626e+00 6.62900400e+00 7.46733189e+00 7.57854319e+00 7.83762836e+00 7.48832512e+00 7.71990538e+00 7.31682062e+00 6.73630476e+00 6.43883228e+00 6.79964447e+00 7.46356726e+00 8.11953831e+00 8.09716511e+00 8.12942791e+00 7.51379538e+00 7.37945032e+00 7.26704264e+00 6.80460644e+00 6.68010712e+00 6.75159454e+00 7.20441866e+00 7.46022415e+00 6.68786430e+00 5.78949976e+00 5.77922487e+00 6.22711229e+00 6.69577312e+00 6.62390709e+00 7.01597929e+00 6.63899517e+00 6.80104876e+00 6.46093941e+00 6.75261593e+00 6.28552961e+00 6.49724340e+00 6.48284864e+00 6.90101147e+00 7.44002295e+00 7.95261574e+00 7.80402374e+00 6.85880709e+00 5.89281273e+00 6.15832138e+00 7.14756966e+00 7.74976730e+00 7.42342281e+00 6.68746805e+00 6.68772173e+00 6.64777279e+00 5.96175718e+00 5.57111835e+00 5.52714348e+00 5.98580980e+00 6.41446590e+00 5.98483086e+00 5.99137402e+00 5.47183752e+00 6.02397156e+00 6.22918510e+00 6.33104181e+00 5.88458347e+00 5.62030554e+00 5.59165096e+00 6.12478209e+00 6.39149237e+00 6.19195509e+00 5.51947975e+00 5.67903519e+00 6.46954584e+00 6.59758139e+00 6.25619125e+00 5.70678949e+00 6.36719942e+00 6.21189928e+00 6.70314550e+00 6.87476110e+00 7.06961870e+00 6.25864601e+00 5.98357391e+00 5.94208956e+00 7.00812483e+00 5.93265533e+00 5.59479952e+00 5.34217501e+00 6.13805723e+00 6.34514475e+00 5.49637508e+00 5.43541908e+00 5.39602709e+00 6.01531267e+00 6.35223436e+00 6.48607159e+00 7.18072510e+00 6.78626347e+00 6.81186104e+00 5.41884327e+00 5.48818970e+00 5.22343493e+00 5.75278664e+00 5.72644281e+00 5.17148304e+00 5.03146887e+00 4.61707497e+00 5.40058661e+00 5.66708136e+00 6.04210043e+00 5.26063061e+00 4.66564035e+00 4.22228575e+00 4.48087883e+00 4.28651094e+00 4.07928991e+00 4.48082066e+00 5.13214302e+00 6.40765238e+00 6.17563868e+00 6.40243435e+00 5.47072649e+00 5.47881222e+00 4.80533504e+00 4.98627949e+00 4.94604206e+00 5.14843845e+00 5.24466991e+00 5.37637901e+00 5.59179783e+00 5.63020706e+00 4.84378052e+00 5.34972477e+00 5.00839758e+00 5.26012278e+00 4.00587893e+00 4.60022593e+00 5.24093962e+00 6.27187872e+00 4.81095505e+00 4.35435486e+00 3.63540673e+00 4.73985004e+00 4.63860559e+00 4.80025578e+00 4.04282904e+00 4.34454632e+00 4.04994535e+00 3.52046061e+00 3.08483005e+00 2.80840898e+00 4.54977274e+00 5.38778543e+00 5.50214434e+00 3.98707032e+00 2.40962148e+00 2.16642404e+00 2.72006059e+00 4.43042278e+00 4.39364672e+00 4.24346590e+00 3.53070164e+00 4.27501202e+00 4.05009365e+00 2.62313199e+00 7.36737013e-01 5.24888039e-01 1.30116868e+00 3.60198307e+00 4.08973694e+00 4.06936026e+00 3.50880861e+00 3.31484723e+00 3.83032990e+00 3.03323531e+00 2.37871861e+00 2.40804529e+00 2.66764808e+00 3.73258162e+00 4.00482416e+00 3.91356921e+00 2.92720795e+00 2.13426900e+00 1.83064103e+00 2.49207187e+00 2.19513750e+00 2.88864231e+00 2.41947937e+00 2.86350727e+00 2.78670835e+00 3.06479597e+00 3.69078612e+00 4.25579453e+00 3.95796967e+00 3.22817302e+00 3.12166405e+00 3.56313515e+00 3.67588282e+00 2.80924726e+00 2.17912889e+00 2.09693003e+00 2.25967765e+00 2.89733338e+00 2.81363344e+00 2.51149559e+00 2.37067342e+00 2.48382282e+00 2.21074462e+00 1.74482751e+00 1.37610769e+00 2.01907301e+00 2.49116468e+00 3.41661596e+00 3.31256676e+00 2.85324383e+00 1.53972626e+00 1.80208671e+00 2.03244996e+00 1.59213293e+00 1.07040215e+00 1.80971313e+00 2.55062914e+00 2.47828412e+00 1.39280856e+00 1.21130955e+00 1.70351422e+00 2.23660064e+00 3.57347012e+00 3.85970020e+00 3.52118015e+00 3.19141769e+00 2.09499788e+00 2.20822620e+00 1.70807993e+00 1.24204481e+00 4.97278363e-01 3.10761034e-02 9.72345293e-01 1.77417529e+00 1.29711616e+00 6.18928969e-01 1.10642564e+00 2.16713572e+00 3.13108587e+00 1.88058519e+00 1.37660384e+00 7.46684909e-01 1.23918009e+00 1.35034895e+00 1.16642320e+00 1.05631006e+00 1.11042714e+00 6.91035807e-01 2.24686280e-01 -8.72745037e-01 -2.58658469e-01 1.07248873e-01 7.29461908e-01 8.48008513e-01 6.41456187e-01 1.27347004e+00 6.40314758e-01 8.27198476e-02 -4.92521703e-01 6.86360240e-01 8.42789471e-01 1.39410150e+00 1.18390477e+00 1.00501204e+00 -4.83876765e-01 -1.60800219e+00 -1.15193570e+00 -5.83839238e-01 -1.17245865e+00 -9.74456429e-01 8.06671858e-01 2.18834019e+00 2.38732314e+00 -4.53537405e-01 -1.90018272e+00 -2.49558878e+00 2.98708415e+00 1.07168264e+01 1.32301056e+02 22310668. 0. 0. 0. 0. 0. 0. 0. 0. -1482731520. -3.15743656e+05 -3.15743656e+05 -3.32142592e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.67776768e+09 3.24284825e+06 1.58901904e+03 5.32333435e+02 6.52723312e+01 1.24403706e+01 2.15389180e+00 -1.25448272e-01 1.53786147e+00 1.53366852e+00 1.00045073e+00 1.15675175e+00 1.47740281e+00 8.69968891e-01 -1.05666257e-01 -2.86927134e-01 -1.44407079e-01 -7.59894431e-01 -1.37658191e+00 -1.48579121e+00 5.43775484e-02 1.12237597e+00 1.33270657e+00 2.33921021e-01 -4.37122047e-01 -6.83361650e-01 -1.41835606e+00 -1.66417325e+00 -2.08150744e+00 -2.13041425e+00 -1.43413901e+00 -1.02356243e+00 -5.23802757e-01 -1.19952250e+00 -2.06398296e+00 -2.16868830e+00 -1.94626081e+00 -8.18457901e-01 -1.02735090e+00 -1.05769026e+00 -6.38250232e-01 -2.30186731e-01 2.36075848e-01 -1.18050814e+00 -2.17398143e+00 -2.42035437e+00 -1.47757554e+00 -1.38853860e+00 -2.08628726e+00 -1.87416148e+00 -1.06571019e+00 -1.33075249e+00 -1.92333710e+00 -1.88096189e+00 -1.93121016e+00 -1.94963813e+00 -1.75312912e+00 -8.91375542e-01 -1.63277698e+00 -3.56467438e+00 -4.31827879e+00 -3.19177055e+00 -1.70302665e+00 -1.29396248e+00 -1.45333111e+00 -1.64449608e+00 -2.05735826e+00 -1.89511883e+00 -1.50633132e+00 -1.34580219e+00 -1.81301510e+00 -2.16871190e+00 -1.56264818e+00 -1.66326368e+00 -1.76313269e+00 -2.17932963e+00 -2.28500772e+00 -1.92050660e+00 -2.44765353e+00 -1.93820214e+00 -1.12700629e+00 -5.43070771e-03 -4.25064802e-01 -1.34962523e+00 -2.22361779e+00 -2.89085197e+00 -3.17151570e+00 -2.16681361e+00 -1.47061896e+00 -1.10955405e+00 -8.67068946e-01 -6.58940494e-01 -1.26568031e+00 -2.90550900e+00 -4.35640955e+00 -4.96400261e+00 -3.77230334e+00 -2.48024321e+00 -1.87261581e+00 -1.76620293e+00 -1.32150555e+00 -6.71064854e-01 -1.33743370e+00 -2.09018970e+00 -3.31826186e+00 -2.33803916e+00 -1.83124387e+00 -1.14612293e+00 -1.98700523e+00 -2.59553480e+00 -2.86021280e+00 -3.19026017e+00 -2.20388246e+00 -1.83407068e+00 -1.97732055e+00 -2.05869055e+00 -2.16897798e+00 -1.87401652e+00 -2.42590404e+00 -2.70189404e+00 -2.82410097e+00 -2.79481530e+00 -2.15049529e+00 -1.86073518e+00 -2.25071645e+00 -2.77534246e+00 -3.64318037e+00 -3.74750233e+00 -3.21836615e+00 -2.23530364e+00 -1.89161479e+00 -1.83226621e+00 -1.49662530e+00 -1.66896236e+00 -2.08733773e+00 -2.05512953e+00 -1.89214003e+00 -1.93099010e+00 -2.28991556e+00 -2.77066803e+00 -2.62275982e+00 -2.24906492e+00 -2.10150313e+00 -1.77613819e+00 -2.64129591e+00 -2.65224338e+00 -4.04734898e+00 -4.59511900e+00 -4.67697430e+00 -3.85484219e+00 -2.86765981e+00 -2.48355198e+00 -2.89843607e+00 -3.17421198e+00 -3.73821712e+00 -3.59746599e+00 -3.17718792e+00 -2.75693750e+00 -2.93880272e+00 -3.56054544e+00 -3.63632751e+00 -3.70806026e+00 -3.05698466e+00 -2.37259769e+00 -2.22825432e+00 -2.57766891e+00 -3.00163722e+00 -3.17765784e+00 -3.49438119e+00 -4.56557274e+00 -4.78381968e+00 -5.06531143e+00 -3.67522311e+00 -3.31094265e+00 -2.88517761e+00 -2.90216208e+00 -2.87943268e+00 -3.30202651e+00 -4.62805700e+00 -4.79592276e+00 -4.83780956e+00 -3.58905339e+00 -3.06691623e+00 -3.12267065e+00 -4.09511232e+00 -3.76497889e+00 -4.12809467e+00 -3.93945599e+00 -4.69781780e+00 -4.92159081e+00 -4.79400396e+00 -4.77648306e+00 -4.66494799e+00 -5.76045036e+00 -7.06147385e+00 -7.10603094e+00 -6.26287651e+00 -4.50366306e+00 -3.88141346e+00 -3.53658462e+00 -3.92437267e+00 -3.76420236e+00 -3.84630156e+00 -3.53130269e+00 -4.70503950e+00 -4.82720613e+00 -5.33678532e+00 -4.21949387e+00 -4.31728888e+00 -4.09264946e+00 -4.11800480e+00 -4.14582396e+00 -4.43862343e+00 -4.98394537e+00 -4.70333385e+00 -5.72694111e+00 -5.43428230e+00 -4.40542269e+00 -4.04572535e+00 -3.70581794e+00 -5.97682762e+00 -5.59306669e+00 -5.26616859e+00 -4.13065052e+00 -4.18852949e+00 -4.54783487e+00 -4.91676903e+00 -4.33937550e+00 -4.88589764e+00 -4.41335487e+00 -4.27512550e+00 -3.67124033e+00 -3.55253768e+00 -3.88138962e+00 -4.02599669e+00 -4.38035727e+00 -4.93689775e+00 -5.02457571e+00 -5.19813585e+00 -4.68955708e+00 -4.47612095e+00 -4.40056372e+00 -4.69151163e+00 -4.65986300e+00 -4.98635769e+00 -5.37754536e+00 -5.84602022e+00 -4.91133118e+00 -4.49636459e+00 -4.68226337e+00 -5.12230206e+00 -4.91555834e+00 -4.10929441e+00 -4.24944162e+00 -4.13644457e+00 -4.69734716e+00 -4.67506123e+00 -5.22130299e+00 -4.93525076e+00 -4.57321978e+00 -3.86625886e+00 -4.54617357e+00 -4.40406275e+00 -4.67800665e+00 -4.78660583e+00 -5.45905638e+00 -5.73224115e+00 -5.59348011e+00 -5.53420687e+00 -5.77977324e+00 -6.19450283e+00 -6.19090176e+00 -5.35564375e+00 -4.98604012e+00 -5.25946379e+00 -6.56583071e+00 -6.41581440e+00 -6.21396017e+00 -5.68133116e+00 -5.49897814e+00 -5.43415499e+00 -5.53009748e+00 -5.62893581e+00 -5.66522455e+00 -5.28909874e+00 -5.26176310e+00 -5.01961899e+00 -4.80555820e+00 -4.52718973e+00 -4.48216391e+00 -4.91244555e+00 -5.25679731e+00 -5.28721571e+00 -5.21812201e+00 -5.35850811e+00 -5.81591320e+00 -5.58352661e+00 -5.15516090e+00 -5.01234150e+00 -5.01298428e+00 -5.49264717e+00 -5.79308367e+00 -6.05566359e+00 -5.76179552e+00 -5.32724667e+00 -5.26561213e+00 -4.70738220e+00 -4.90881205e+00 -5.01649237e+00 -5.68777418e+00 -5.50996447e+00 -5.44933987e+00 -5.18495083e+00 -5.25900364e+00 -5.23611641e+00 -5.50172281e+00 -5.49837875e+00 -5.52010059e+00 -5.27421522e+00 -5.49740696e+00 -5.86385965e+00 -5.88278341e+00 -5.74771214e+00 -5.42838621e+00 -6.02589989e+00 -6.32135391e+00 -6.28571320e+00 -5.56951237e+00 -5.60084629e+00 -5.53814507e+00 -5.66843843e+00 -5.25908518e+00 -5.36524439e+00 -5.26255655e+00 -5.21789455e+00 -5.11458492e+00 -5.16999292e+00 -5.38922262e+00 -5.34436750e+00 -5.53582382e+00 -5.76418257e+00 -5.81427240e+00 -5.81305456e+00 -5.82489634e+00 -5.95528364e+00 -6.21963024e+00 -5.75349760e+00 -5.70340347e+00 -5.42842627e+00 -5.70947218e+00 -5.37892723e+00 -5.49898624e+00 -5.68814802e+00 -6.22445583e+00 -5.93038654e+00 -5.43880701e+00 -5.22699547e+00 -5.38757038e+00 -5.89481258e+00 -6.06009579e+00 -6.19864273e+00 -5.99296570e+00 -5.77756357e+00 -5.76440382e+00 -5.89287806e+00 -6.24475861e+00 -6.35329580e+00 -6.50842571e+00 -6.26329041e+00 -6.16293621e+00 -6.09528494e+00 -6.19526911e+00 -6.25409412e+00 -6.08531380e+00 -5.93068266e+00 -5.84309006e+00 -5.77725077e+00 -6.01829195e+00 -6.22973442e+00 -6.43937492e+00 -6.23418283e+00 -6.03569794e+00 -6.00452709e+00 -6.13869953e+00 -6.20751047e+00 -6.09144449e+00 -5.83103943e+00 -5.90364552e+00 -6.01881456e+00 -6.16000509e+00 -6.32157707e+00 -6.16249466e+00 -6.33186483e+00 -6.09746981e+00 -6.19181633e+00 -6.13803577e+00 -5.99238825e+00 -6.00808764e+00 -6.14372540e+00 -6.31363821e+00 -6.30947781e+00 -6.16791964e+00 -6.21680021e+00 -6.31592703e+00 -6.21236944e+00 -6.15594244e+00 -6.07956743e+00 -6.33747244e+00 -6.37458706e+00 -6.41354990e+00 -6.27667570e+00 -6.13147211e+00 -6.09464455e+00 -6.01199055e+00 -6.12152863e+00 -6.14589500e+00 -6.20933771e+00 -6.20979977e+00 -6.25899076e+00 -6.23410130e+00 -6.25099993e+00 -6.28718996e+00 -6.30447292e+00 -6.20759916e+00 -6.13229513e+00 -6.18152189e+00 -6.21384954e+00 -6.20576525e+00 -6.20114994e+00 -6.25284910e+00 -6.26291561e+00 -6.21543407e+00 -6.22009802e+00 -6.23840141e+00 -6.25807524e+00 -6.23703814e+00 -6.20604801e+00 -6.20244169e+00 -6.21164370e+00 -6.21711969e+00 -6.21566391e+00 -6.21301699e+00 -6.20612383e+00 -6.20083475e+00 -6.20423555e+00 -6.21518946e+00 -6.20958662e+00 -6.17175865e+00 -6.17000294e+00 -6.15894794e+00 -6.19017696e+00 -6.23132467e+00 -6.22371626e+00 -6.19173717e+00 -6.13846493e+00 -6.16572523e+00 -6.20643425e+00 -6.19240570e+00 -6.22267818e+00 -6.20792532e+00 -6.23108053e+00 -6.22726440e+00 -6.21685505e+00 -6.19468307e+00 -6.21113300e+00 -6.21263266e+00 -6.25073338e+00 -6.18573952e+00 -6.14415741e+00 -6.07801914e+00 -6.10679150e+00 -6.17452431e+00 -6.12835073e+00 -6.18334150e+00 -6.18962622e+00 -6.35009480e+00 -6.27132797e+00 -6.18457937e+00 -5.99737644e+00 -6.06203747e+00 -6.12605810e+00 -6.20408010e+00 -6.11464167e+00 -6.20791054e+00 -6.20016241e+00 -6.24762821e+00 -6.15474463e+00 -6.19464254e+00 -6.16240597e+00 -6.34463263e+00 -6.15553188e+00 -6.14162159e+00 -6.02961874e+00 -6.21510744e+00 -6.26284933e+00 -6.30527067e+00 -6.35756493e+00 -6.20578718e+00 -5.95322609e+00 -5.85284138e+00 -5.92355251e+00 -5.96849346e+00 -5.92032576e+00 -5.68822384e+00 -5.80500078e+00 -5.94565582e+00 -6.27804041e+00 -6.15236330e+00 -6.16428852e+00 -5.98057318e+00 -5.86695862e+00 -5.79677725e+00 -5.85136795e+00 -6.09488487e+00 -6.10952234e+00 -6.10157061e+00 -6.09179449e+00 -5.87696838e+00 -5.61145782e+00 -5.78966951e+00 -6.04100323e+00 -6.29956055e+00 -5.97273302e+00 -5.73964787e+00 -5.81562996e+00 -6.14848375e+00 -6.24624872e+00 -6.04083157e+00 -5.79325771e+00 -5.85757399e+00 -6.07479286e+00 -6.10259390e+00 -6.17485905e+00 -6.23745155e+00 -6.19077396e+00 -5.96527290e+00 -5.95755482e+00 -6.03087282e+00 -6.23232317e+00 -6.30783319e+00 -6.14872122e+00 -6.18652105e+00 -5.82656813e+00 -6.15647793e+00 -6.11417723e+00 -6.35402679e+00 -6.28785324e+00 -5.95539761e+00 -5.96535158e+00 -6.01091719e+00 -6.17838430e+00 -6.16859293e+00 -5.94313431e+00 -6.04810619e+00 -5.82072973e+00 -5.92265129e+00 -6.16991282e+00 -6.32694960e+00 -6.22875309e+00 -5.92844772e+00 -5.60885811e+00 -5.44021225e+00 -5.27411652e+00 -5.07946920e+00 -5.18566370e+00 -5.49773264e+00 -5.75018930e+00 -5.51807070e+00 -5.25690651e+00 -5.38497400e+00 -5.46243954e+00 -5.33237219e+00 -5.21718550e+00 -5.19388962e+00 -5.39020681e+00 -5.71649075e+00 -5.46571636e+00 -4.89963245e+00 -4.50457525e+00 -4.78272915e+00 -5.12432575e+00 -4.64420700e+00 -4.60821962e+00 -4.63084316e+00 -5.00996971e+00 -4.78516912e+00 -4.93389702e+00 -4.87486172e+00 -5.16348410e+00 -5.02458382e+00 -5.29735041e+00 -5.36593390e+00 -5.38557482e+00 -5.34258080e+00 -5.39988470e+00 -5.58352661e+00 -5.98899937e+00 -5.42745781e+00 -5.15688753e+00 -4.59491730e+00 -4.97572136e+00 -5.20177937e+00 -5.02666855e+00 -4.63831139e+00 -3.94361925e+00 -4.29323483e+00 -4.56011915e+00 -5.11540890e+00 -4.93191528e+00 -5.04276991e+00 -4.67548656e+00 -5.06582737e+00 -4.36228466e+00 -4.77868080e+00 -4.38259602e+00 -5.24950790e+00 -4.95531416e+00 -3.56842375e+00 -2.25561380e+00 5.01724243e-01 7.06090257e-02 8.96974182e+00 2.21998825e+01 1.41167160e+02 1.89902939e+02 -6.24494324e+02 -2.65695361e+03 -133904840. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -92942288. -2.82418042e+03 -5.11950134e+02 -8.53073883e+01 -4.35279198e+01 -2.61827641e+01 -1.18030081e+01 -7.26940155e+00 -5.13783836e+00 -4.81285000e+00 -4.73482895e+00 -4.41126156e+00 -4.11031675e+00 -4.41848278e+00 -4.51331711e+00 -4.49545622e+00 -4.50082636e+00 -4.81617355e+00 -4.37210894e+00 -4.13253260e+00 -3.53720641e+00 -3.88877892e+00 -3.29724813e+00 -3.67645478e+00 -3.58079576e+00 -3.83870387e+00 -4.39145756e+00 -3.89349055e+00 -3.96599603e+00 -3.89958644e+00 -4.98179960e+00 -5.30720663e+00 -4.14663744e+00 -3.38023376e+00 -3.28308964e+00 -3.66998649e+00 -3.49397087e+00 -3.62575912e+00 -3.78393579e+00 -3.83922195e+00 -3.52902150e+00 -3.65013194e+00 -3.52476788e+00 -4.00480366e+00 -3.71720576e+00 -3.05639720e+00 -2.58130622e+00 -1.82161498e+00 -2.81849742e+00 -2.60261321e+00 -3.41374612e+00 -3.35618687e+00 -2.95611954e+00 -2.94892597e+00 -3.03588891e+00 -3.69560122e+00 -3.38195300e+00 -3.10288763e+00 -2.97212267e+00 -2.86960173e+00 -2.43415189e+00 -2.04231882e+00 -1.74340010e+00 -2.17251992e+00 -2.01584578e+00 -2.02641606e+00 -2.39136195e+00 -2.94229031e+00 -3.40409207e+00 -3.13254786e+00 -2.85604835e+00 -2.08754253e+00 -1.05143023e+00 -6.88210011e-01 -1.02281678e+00 -2.30349803e+00 -2.89542580e+00 -2.70907950e+00 -2.98772979e+00 -3.50425935e+00 -4.07174492e+00 -3.17710614e+00 -1.95370781e+00 -2.10132527e+00 -2.38898349e+00 -2.99114442e+00 -3.09399796e+00 -2.92406726e+00 -2.98119235e+00 -2.47513747e+00 -2.99061251e+00 -3.11791706e+00 -3.47064662e+00 -2.34824705e+00 -1.18921649e+00 -1.44204295e+00 -2.01709843e+00 -2.14643884e+00 -2.10231614e+00 -2.40294719e+00 -3.12823057e+00 -2.94975996e+00 -2.16002250e+00 -1.96471500e+00 -2.22252226e+00 -2.91426587e+00 -3.21358728e+00 -2.75409389e+00 -2.90170431e+00 -2.82414579e+00 -2.82112980e+00 -2.26654387e+00 -1.73336923e+00 -1.15375865e+00 -1.62822175e+00 -2.12004900e+00 -2.37821674e+00 -2.53113317e+00 -3.05249786e+00 -3.50561547e+00 -3.32354188e+00 -2.97147369e+00 -2.48814988e+00 -2.62076712e+00 -2.96135616e+00 -3.92498493e+00 -4.13442469e+00 -3.24453235e+00 -2.25199509e+00 -2.45334578e+00 -2.80659175e+00 -3.09521890e+00 -2.52138686e+00 -2.20603514e+00 -1.83579814e+00 -9.23191845e-01 -1.10709488e+00 -1.61727941e+00 -2.44841385e+00 -2.23399711e+00 -1.30259538e+00 -1.35350490e+00 -1.57254314e+00 -2.39145112e+00 -1.85584998e+00 -1.33469093e+00 -8.57505083e-01 -5.63419342e-01 -4.27379787e-01 -2.68107593e-01 -4.14644986e-01 -1.05092859e+00 -9.17074323e-01 -1.03009939e+00 -7.35328972e-01 -1.38561261e+00 -2.13417125e+00 -2.30976868e+00 -2.81248903e+00 -1.47735178e+00 -1.39034986e+00 -3.52389514e-01 -2.63531446e-01 6.54882789e-02 -2.12708205e-01 -5.77970982e-01 -7.92166412e-01 -5.45694709e-01 -1.25245059e+00 -1.17516184e+00 -1.90805876e+00 -2.22718120e+00 -1.26351690e+00 -5.20979404e-01 -1.06612213e-01 -7.06970394e-01 -1.09430325e+00 -9.24651623e-01 -1.02983963e+00 -8.51647198e-01 -7.44894147e-01 -1.28668511e+00 -1.67359424e+00 -2.31940484e+00 -1.37041247e+00 -1.17267704e+00 -3.27822179e-01 -4.63154465e-01 -9.84251201e-01 -1.88279963e+00 -6.93310440e-01 1.04223788e+00 1.02517474e+00 -3.80508810e-01 -1.61246669e+00 -1.60450935e+00 -9.40015316e-01 2.02162638e-02 3.93003762e-01 -5.90315819e-01 -1.41212952e+00 -8.54957521e-01 -2.03147098e-01 -2.63189655e-02 -2.40733370e-01 -6.16491497e-01 1.66611537e-01 6.08151734e-01 4.65157151e-01 -7.50897080e-02 1.96639448e-01 5.64828873e-01 4.33376171e-02 -4.41309094e-01 -2.24699587e-01 -1.94091816e-02 -3.77479047e-01 2.77929991e-01 5.52479863e-01 2.13656023e-01 -5.91862321e-01 -9.89174128e-01 -1.55854475e+00 -1.19290972e+00 -4.52461421e-01 1.60556480e-01 2.35018879e-01 -4.82422024e-01 3.23665529e-01 8.27646315e-01 2.19202065e+00 1.80405188e+00 7.45775580e-01 3.18709731e-01 2.74845809e-01 8.05082560e-01 6.32579446e-01 1.81890833e+00 2.25131392e+00 2.83607316e+00 2.30380201e+00 2.00547433e+00 9.07589674e-01 6.07786000e-01 4.90552962e-01 -4.25809592e-01 4.37712371e-02 -2.66201615e-01 1.11982942e+00 1.20568621e+00 1.31488800e+00 8.94649565e-01 1.01404715e+00 1.44789791e+00 1.63200963e+00 1.68831408e+00 1.58466136e+00 1.44143665e+00 8.09300840e-01 4.65970278e-01 5.25154293e-01 4.46934283e-01 4.30088162e-01 1.40252277e-01 6.53484821e-01 4.92456138e-01 1.22605026e+00 9.02875960e-02 3.75718206e-01 1.06615447e-01 1.22954178e+00 7.73510098e-01 3.05821508e-01 2.74573676e-02 9.28311169e-01 1.44145083e+00 1.12847698e+00 9.06940460e-01 8.90417218e-01 1.08479536e+00 8.27078223e-01 9.58545506e-01 1.24458051e+00 2.72993118e-01 6.56673968e-01 1.50581315e-01 1.49419212e+00 1.12863457e+00 5.40336132e-01 3.13952602e-02 -1.55875146e-01 5.06744504e-01 9.74260926e-01 1.49154270e+00 1.65117145e+00 1.79883313e+00 2.22148252e+00 2.46669102e+00 3.15113616e+00 1.85235679e+00 2.11497831e+00 1.83076346e+00 1.24675655e+00 1.69485724e+00 1.02463579e+00 1.92782664e+00 1.58439744e+00 1.71970475e+00 1.06779933e+00 8.78687918e-01 5.40414155e-01 1.68790472e+00 1.62178349e+00 2.37302732e+00 2.33942938e+00 2.88477159e+00 3.00388408e+00 3.17416692e+00 2.23641133e+00 1.88895524e+00 2.02264977e+00 2.08510590e+00 6.06583118e-01 -1.33154299e-02 5.04853368e-01 1.61038029e+00 1.75638306e+00 1.48983145e+00 1.92868137e+00 2.43692946e+00 2.70241642e+00 2.69237638e+00 2.00276875e+00 2.17187905e+00 2.35038757e+00 2.38418770e+00 2.07508063e+00 2.48313093e+00 2.95227885e+00 3.62012291e+00 2.88644290e+00 2.57203817e+00 2.12282395e+00 2.68575001e+00 2.88874316e+00 2.89417553e+00 2.72404981e+00 2.44803166e+00 2.60699153e+00 2.95635223e+00 3.51014757e+00 3.79026198e+00 3.67928863e+00 3.51554894e+00 2.71002936e+00 2.17034292e+00 1.83371651e+00 2.44497681e+00 1.65699887e+00 2.23375535e+00 2.22968006e+00 2.83647704e+00 3.04990458e+00 3.30915594e+00 3.08096790e+00 2.65878582e+00 1.56106794e+00 2.09194922e+00 1.78858030e+00 2.12567234e+00 2.77294874e+00 2.82846498e+00 3.79020023e+00 3.50262904e+00 3.98566675e+00 2.83731151e+00 2.54957485e+00 1.58070076e+00 2.37860608e+00 2.69129968e+00 3.42437315e+00 3.32200861e+00 3.24590111e+00 2.58382893e+00 2.79780984e+00 2.65822434e+00 3.37328911e+00 2.97451878e+00 2.71227956e+00 2.56865287e+00 2.47005057e+00 2.94449997e+00 3.17489290e+00 3.60777283e+00 3.17405677e+00 2.98082352e+00 3.51034713e+00 3.39785194e+00 2.80651832e+00 2.03600860e+00 2.86906433e+00 3.11821771e+00 3.38205671e+00 3.06086993e+00 3.53237200e+00 4.23741722e+00 4.65273237e+00 4.86286449e+00 3.52607226e+00 3.15920568e+00 3.24717784e+00 3.91306233e+00 3.73629975e+00 3.44200230e+00 3.37744522e+00 3.99438477e+00 3.79301858e+00 4.32520342e+00 4.04593182e+00 4.65196705e+00 4.44496584e+00 4.43747902e+00 4.35370922e+00 4.12177086e+00 4.05608988e+00 3.71758747e+00 3.40432644e+00 3.34873438e+00 3.33660436e+00 3.54706645e+00 3.43838716e+00 3.37619138e+00 3.52644515e+00 3.76470423e+00 3.94862342e+00 4.00331783e+00 4.15470552e+00 4.55400944e+00 4.63001204e+00 4.63453102e+00 4.26076746e+00 4.14277506e+00 4.05053949e+00 4.40212440e+00 4.45404625e+00 4.16535091e+00 3.97121072e+00 4.18349695e+00 3.69293904e+00 2.80156994e+00 2.26068568e+00 3.00700235e+00 3.98241568e+00 5.13165903e+00 5.18133974e+00 5.32653332e+00 5.07234287e+00 6.75841999e+00 7.66030073e+00 1.88280945e+01 2.61398487e+01 2.04808006e+01 1.36465500e+02 6.37814331e+01 -3.80820068e+03 68307016. 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. 0. 0. 0. 0. 0. 0. 4.00486531e+05 1.67677216e+02 2.60538273e+01 -2.26473694e+01 1.41447401e+00 3.37273002e+00 4.53683805e+00 5.33837509e+00 4.69911814e+00 4.63656950e+00 4.59787703e+00 4.86639595e+00 5.12659597e+00 5.15398073e+00 5.28275537e+00 5.29728556e+00 4.99504614e+00 4.85407162e+00 4.83118248e+00 5.23883867e+00 5.47004986e+00 5.75132847e+00 5.56261730e+00 5.11932182e+00 5.03787374e+00 5.20236635e+00 5.66885996e+00 5.71564245e+00 5.61479521e+00 5.44975853e+00 5.21250153e+00 5.13753319e+00 5.12394190e+00 5.39460230e+00 5.46634436e+00 5.42271376e+00 5.50842571e+00 5.54362535e+00 5.57284689e+00 5.55899286e+00 5.54619217e+00 5.58353996e+00 5.39965057e+00 5.38646221e+00 5.49443436e+00 5.62367916e+00 5.68957329e+00 5.72954369e+00 5.73133469e+00 6.01232100e+00 5.95725965e+00 6.04999876e+00 5.57797098e+00 5.66063261e+00 5.62807655e+00 5.81056595e+00 5.87865114e+00 5.81480169e+00 5.78750992e+00 5.75916290e+00 5.82464600e+00 5.96988487e+00 5.80181217e+00 5.54420233e+00 5.44495296e+00 5.39549685e+00 5.44407129e+00 5.39719534e+00 5.46243238e+00 5.65510750e+00 5.68292284e+00 5.73614025e+00 5.75455809e+00 5.74006081e+00 5.83453417e+00 6.04589748e+00 6.07522631e+00 6.02405739e+00 5.83430576e+00 5.81760645e+00 5.92607403e+00 5.95010614e+00 6.11567545e+00 6.08300638e+00 5.99026346e+00 5.85279179e+00 5.71269226e+00 5.71650267e+00 5.78435993e+00 5.94144964e+00 5.89786530e+00 5.92908335e+00 5.72242308e+00 5.66666698e+00 5.71601391e+00 5.85634756e+00 6.00107241e+00 5.89944220e+00 5.91141129e+00 5.81983185e+00 5.78482914e+00 5.80993176e+00 6.02519417e+00 6.11990404e+00 6.18277025e+00 6.08828735e+00 6.01892614e+00 5.96114492e+00 5.89862394e+00 5.91395473e+00 5.88629818e+00 5.94584322e+00 6.01197481e+00 6.06379414e+00 6.08133507e+00 6.07341814e+00 6.15662622e+00 6.22065544e+00 6.25265646e+00 6.10610962e+00 6.01746988e+00 6.02266264e+00 6.08271790e+00 6.20856380e+00 6.18942499e+00 6.15998316e+00 6.10982513e+00 6.04944706e+00 6.04552937e+00 6.00542307e+00 6.08205128e+00 6.14947128e+00 6.20258427e+00 6.10731936e+00 5.98281050e+00 5.95376015e+00 5.97591448e+00 6.07345724e+00 6.07979155e+00 6.16216660e+00 6.21412611e+00 6.21485138e+00 6.21840382e+00 6.23916531e+00 6.25293684e+00 6.26538944e+00 6.23202801e+00 6.21704817e+00 6.20184231e+00 6.18986368e+00 6.23427868e+00 6.23756075e+00 6.23410892e+00 6.16058588e+00 6.13207340e+00 6.17615271e+00 6.19776630e+00 6.23488522e+00 6.18302250e+00 6.16770744e+00 6.12946558e+00 6.11958075e+00 6.13619280e+00 6.15396595e+00 6.19143724e+00 6.21298504e+00 6.22644949e+00 6.22394371e+00 6.21355772e+00 6.20698214e+00 6.20356798e+00 6.20800591e+00 6.21384430e+00 6.21156883e+00 6.20983601e+00 6.21083641e+00 6.21314764e+00 6.21038771e+00 6.20647144e+00 6.21077204e+00 6.21522951e+00 6.21925640e+00 6.21014929e+00 6.22126245e+00 6.22092915e+00 6.23674774e+00 6.23765993e+00 6.22651052e+00 6.21294451e+00 6.19719982e+00 6.22118282e+00 6.21385574e+00 6.22504044e+00 6.20050049e+00 6.18544340e+00 6.17194557e+00 6.15842056e+00 6.18144655e+00 6.15482521e+00 6.14248896e+00 6.14191723e+00 6.14611340e+00 6.12685728e+00 6.09802341e+00 6.08946514e+00 6.13689041e+00 6.14873600e+00 6.20594406e+00 6.19842148e+00 6.19649649e+00 6.20441818e+00 6.19150305e+00 6.18593836e+00 6.14409447e+00 6.18935251e+00 6.22428942e+00 6.22256231e+00 6.18731689e+00 6.16205549e+00 6.11559296e+00 6.09498739e+00 6.02772188e+00 6.02736616e+00 6.09394741e+00 6.14350462e+00 6.20264053e+00 6.15099812e+00 6.07818508e+00 6.04069090e+00 6.04173040e+00 6.03982210e+00 5.98897123e+00 5.99270391e+00 5.99906158e+00 6.02355385e+00 6.03011370e+00 6.01996565e+00 6.00104618e+00 5.98184204e+00 6.03897619e+00 6.06513739e+00 6.07562494e+00 6.08150816e+00 6.11546373e+00 5.96116829e+00 5.77308369e+00 5.70194387e+00 5.78898716e+00 6.04658985e+00 6.06646585e+00 6.04386950e+00 5.87285376e+00 5.80767536e+00 6.00133276e+00 6.21395063e+00 6.28581667e+00 6.21337080e+00 6.01677418e+00 6.08455420e+00 6.00985909e+00 6.01385355e+00 5.94646311e+00 5.92984819e+00 6.00021505e+00 5.97912884e+00 6.07894707e+00 6.09124470e+00 6.12355661e+00 6.18442535e+00 6.18232393e+00 6.15752792e+00 6.21464777e+00 6.08774900e+00 6.06728983e+00 5.81751156e+00 5.91977644e+00 5.94640493e+00 5.86327600e+00 6.20697832e+00 6.25612974e+00 6.44424057e+00 6.04320049e+00 5.86488008e+00 5.63930178e+00 5.91856337e+00 5.97583103e+00 6.00664949e+00 5.63536930e+00 5.46536875e+00 5.56417322e+00 5.52988243e+00 5.64466286e+00 5.38362169e+00 5.33497000e+00 5.30368614e+00 5.68216515e+00 5.85926628e+00 5.96748400e+00 5.88725233e+00 5.82007790e+00 5.57535267e+00 5.51057243e+00 5.54993010e+00 5.63512325e+00 5.40143061e+00 5.49143982e+00 5.89520264e+00 5.98834181e+00 5.98462772e+00 5.59831524e+00 5.73189545e+00 5.60331678e+00 5.62592459e+00 5.45437908e+00 5.49384356e+00 5.33482265e+00 5.38048983e+00 5.47639322e+00 5.76707172e+00 5.75295782e+00 5.71378946e+00 5.44205332e+00 5.39321661e+00 5.38905144e+00 5.47506571e+00 5.53540039e+00 5.60263491e+00 5.69953299e+00 5.98896837e+00 6.04405975e+00 5.92240191e+00 5.72148848e+00 5.20921850e+00 5.28525686e+00 5.11472416e+00 5.42068481e+00 5.05134869e+00 5.22165108e+00 5.39313841e+00 5.55552912e+00 5.16946602e+00 4.52515411e+00 4.48551178e+00 4.61019278e+00 5.08247137e+00 5.05748606e+00 4.86568260e+00 4.95737696e+00 5.23035669e+00 5.48181534e+00 4.91769743e+00 4.56598616e+00 4.33894444e+00 4.38116217e+00 4.55425024e+00 4.44222641e+00 4.97973680e+00 4.85572863e+00 5.03454590e+00 4.68285227e+00 4.76577806e+00 4.85366726e+00 4.80627012e+00 4.78015280e+00 4.74045849e+00 4.70387506e+00 5.04689407e+00 5.21765518e+00 5.36402512e+00 4.96279335e+00 4.63703299e+00 4.97558689e+00 5.37459326e+00 5.48993826e+00 4.99043465e+00 5.00373459e+00 5.13746738e+00 5.14032173e+00 5.13083839e+00 4.77458477e+00 5.14011335e+00 4.67151260e+00 4.98619318e+00 4.88093424e+00 4.69771051e+00 4.55246782e+00 4.66912603e+00 4.97303867e+00 5.08108282e+00 4.70397711e+00 4.85740089e+00 4.78414583e+00 4.96216917e+00 4.85263586e+00 4.70489502e+00 4.85881805e+00 4.74535751e+00 5.05038929e+00 4.47041225e+00 4.21064854e+00 4.33780146e+00 4.88572121e+00 5.02576923e+00 4.64531279e+00 4.53563738e+00 4.63572359e+00 4.78486061e+00 4.58592463e+00 4.00056791e+00 3.81411624e+00 3.47832513e+00 3.80843496e+00 3.78141236e+00 4.29908466e+00 4.29795218e+00 3.95741391e+00 3.97931767e+00 4.49624825e+00 4.58083248e+00 4.51731205e+00 4.32952929e+00 4.23789358e+00 4.18009901e+00 3.76601553e+00 3.84638047e+00 3.62884402e+00 4.04837036e+00 4.00443125e+00 3.74034452e+00 3.70487309e+00 3.83911371e+00 4.13750982e+00 3.65108562e+00 3.82045078e+00 3.62117815e+00 3.62288451e+00 2.99176455e+00 3.28810334e+00 3.61625361e+00 3.80223846e+00 3.64308405e+00 3.41560483e+00 4.11612368e+00 3.98087907e+00 3.90556359e+00 3.41187596e+00 3.50275445e+00 3.11412168e+00 2.87693930e+00 2.63699150e+00 3.15233421e+00 3.57021904e+00 3.37914991e+00 3.22596931e+00 2.96270299e+00 3.37858105e+00 3.62532759e+00 3.63261247e+00 3.98009038e+00 3.96781969e+00 4.00250006e+00 3.31410885e+00 3.00051618e+00 3.26895714e+00 3.26512241e+00 2.97782707e+00 2.89859653e+00 3.27617931e+00 3.51799035e+00 3.01560163e+00 3.10591865e+00 3.09271049e+00 3.37407756e+00 3.36743116e+00 3.21266079e+00 3.69041800e+00 3.62146330e+00 3.83402061e+00 3.40905952e+00 3.53370976e+00 2.92338347e+00 2.36490154e+00 2.12899470e+00 3.07284570e+00 3.01877308e+00 2.51630974e+00 2.01850557e+00 2.43592429e+00 3.10427189e+00 2.29699683e+00 2.36359525e+00 1.91774189e+00 2.44933844e+00 1.60047531e+00 1.19434011e+00 8.70307684e-01 1.76504695e+00 2.49798965e+00 2.24224353e+00 1.29828000e+00 2.30024576e-01 3.87057781e-01 6.34987533e-01 5.54842412e-01 8.26736867e-01 8.25995624e-01 1.84763765e+00 2.50087786e+00 3.02669740e+00 3.31775570e+00 3.54478693e+00 3.19625974e+00 2.29401040e+00 1.66178465e+00 1.77957904e+00 2.49380851e+00 2.21963525e+00 1.90780795e+00 1.37978578e+00 1.09244382e+00 9.97500777e-01 8.98334801e-01 1.46119916e+00 2.19086480e+00 2.30267596e+00 2.02980876e+00 1.75142944e+00 1.52381694e+00 1.89399421e+00 1.90686083e+00 1.82535231e+00 1.33511531e+00 1.17940319e+00 1.30554271e+00 1.47693908e+00 1.73758256e+00 1.66197419e+00 1.60970879e+00 7.72987604e-01 4.61255312e-01 2.31675148e-01 1.70496142e+00 2.60317850e+00 3.17467260e+00 2.07285023e+00 1.93079400e+00 1.77825129e+00 2.88425207e+00 2.93898034e+00 2.58736467e+00 2.05299878e+00 1.70279670e+00 1.92988658e+00 1.91793668e+00 1.36982894e+00 1.29118061e+00 1.20257533e+00 1.68189573e+00 2.18015957e+00 1.41850078e+00 1.31935871e+00 1.27508736e+00 1.72420454e+00 1.83614635e+00 1.54065311e+00 1.28842139e+00 1.12177956e+00 1.44106138e+00 1.64034009e+00 1.87740231e+00 1.58234406e+00 1.43476987e+00 1.20031822e+00 6.44170940e-01 1.00109303e+00 1.37044001e+00 2.14706874e+00 2.55252576e+00 2.40825915e+00 2.04235625e+00 1.18618071e+00 8.75845194e-01 5.46337545e-01 9.24955606e-01 1.01077306e+00 1.29934716e+00 7.14992106e-01 3.72743577e-01 6.42953753e-01 1.19443285e+00 7.84719765e-01 6.82023406e-01 4.42810327e-01 6.52827740e-01 -3.31278145e-01 9.12576467e-02 1.17233440e-01 8.25424612e-01 -5.18623888e-01 -8.82829607e-01 -1.95303559e+00 -1.38222122e+00 -6.82692170e-01 9.19699550e-01 1.02631497e+00 7.97712147e-01 1.19783700e+00 1.49816217e+01 1.05747366e+01 7.11579971e+01 3.26375656e+01 -1267417728. 0. 0. 0. 0. 693049472. -1.19657625e+06 2.43456525e+06 4.04202750e+05 4.00055273e+03 1.19903330e+04 1.99676035e+04 -3.32142592e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.67776768e+09 3.24284825e+06 2.30516025e+06 1.90124365e+03 7.60904663e+02 7.60815201e+01 5.12376175e+01 9.78202629e+00 -1.04957366e+00 -9.81751442e+00 -1.22167959e+01 1.97805119e+00 1.68637848e+01 1.68880482e+01 1.13038235e+01 7.12443113e+00 1.03061008e+00 -1.81577885e+00 -5.42223072e+00 6.68655336e-01 9.63175774e+00 1.81033363e+01 1.73051853e+01 2.56562161e+00 -1.12466240e+01 -1.99537754e+01 -2.12220554e+01 -1.37961473e+01 -1.38073940e+01 -1.27276812e+01 -1.31447375e+00 6.20813131e+00 2.33334947e+00 -1.47102709e+01 -2.76111984e+01 -2.74265976e+01 -1.77184753e+01 -8.81456554e-01 4.87207794e+00 3.59892702e+00 2.94081163e+00 2.33372641e+00 7.10061133e-01 -9.91860008e+00 -1.91260490e+01 -1.57133427e+01 -5.60956573e+00 -1.38617918e-01 -6.85377359e+00 -7.68468618e+00 -5.37422895e+00 -9.96842289e+00 -1.04933529e+01 -9.30927181e+00 -3.83529329e+00 2.82506371e+00 7.05643606e+00 9.52806950e+00 -4.41372252e+00 -2.21259975e+01 -2.76627312e+01 -1.78734722e+01 -4.43523377e-01 1.97417343e+00 -3.71118331e+00 -9.01296139e+00 -7.45115995e+00 -4.47733021e+00 -7.18636894e+00 -1.11025782e+01 -1.23009319e+01 -4.58516932e+00 5.91258955e+00 2.78737020e+00 -4.34475511e-01 -5.34758997e+00 -7.74181604e+00 -8.12598896e+00 -1.10953693e+01 -5.93630409e+00 2.60848188e+00 1.12685633e+01 1.17042933e+01 1.74952459e+00 -8.85450554e+00 -1.79255066e+01 -1.85947685e+01 -8.74720955e+00 -4.17934608e+00 -3.42982197e+00 1.51940584e+00 1.04648542e+01 1.02117262e+01 -4.88270140e+00 -2.01350117e+01 -2.00965900e+01 -5.83814240e+00 7.80831671e+00 8.53165054e+00 5.47105503e+00 7.13515186e+00 7.70500660e+00 3.53137445e+00 -3.68745613e+00 -8.20881748e+00 -2.89243174e+00 3.34681630e+00 4.98447371e+00 -3.27272320e+00 -1.27364197e+01 -1.71698933e+01 -1.70165768e+01 -6.68266344e+00 1.47397768e+00 3.17419112e-01 -1.65665102e+00 1.17786169e+00 3.88063097e+00 -1.28944290e+00 -1.16291466e+01 -1.15856476e+01 -3.78115356e-01 1.10810976e+01 1.32651892e+01 3.30475235e+00 -5.12232733e+00 -1.40954895e+01 -1.75547695e+01 -1.21423035e+01 -6.97721720e+00 -3.76103973e+00 2.99671865e+00 1.04370279e+01 1.07237644e+01 3.74575758e+00 -3.91770124e+00 -8.43980408e+00 -9.62879562e+00 -6.83762598e+00 -3.64484286e+00 -1.12471318e+00 2.16953182e+00 5.87389374e+00 6.24261284e+00 -3.04234886e+00 -1.42994518e+01 -2.18994083e+01 -1.91228657e+01 -1.47694464e+01 -1.12890024e+01 -6.03438997e+00 -3.00467610e+00 -5.51595402e+00 -7.33294535e+00 -1.34022894e+01 -1.59204655e+01 -1.42727871e+01 -7.11870241e+00 -4.38488865e+00 -9.47346878e+00 -1.62435722e+01 -1.31905355e+01 -5.15714741e+00 2.99862266e-01 -6.07394934e+00 -1.41372385e+01 -1.29374790e+01 -1.19082756e+01 -1.21404963e+01 -2.19781532e+01 -2.79941368e+01 -2.90441360e+01 -1.61186295e+01 -1.84703231e+00 2.29302096e+00 1.44646156e+00 6.78512692e-01 -1.90931892e+00 -7.16360569e+00 -1.74153671e+01 -1.96210823e+01 -1.14388561e+01 -9.17147398e-01 1.35973644e+00 -8.56633282e+00 -1.47002316e+01 -1.67970390e+01 -1.65460052e+01 -1.56177139e+01 -1.85000305e+01 -1.76782589e+01 -1.51030893e+01 -1.34461250e+01 -1.59227152e+01 -2.18936348e+01 -2.51681919e+01 -2.36779404e+01 -1.03557673e+01 6.48739517e-01 2.95677137e+00 -3.33483791e+00 -4.51263523e+00 -5.72988510e+00 -8.11846733e+00 -1.68567924e+01 -1.76651726e+01 -9.47382736e+00 -1.37506497e+00 4.11452085e-01 -7.43657780e+00 -9.66081524e+00 -9.79251862e+00 -8.71465302e+00 -9.69229698e+00 -1.25140371e+01 -1.78002911e+01 -1.39797382e+01 -6.43268871e+00 -3.11471725e+00 -7.33003283e+00 -1.86656761e+01 -2.03858414e+01 -1.41821451e+01 -6.76764345e+00 -4.19523811e+00 -7.63163471e+00 -7.98154116e+00 -8.00194073e+00 -7.66283989e+00 -6.32012177e+00 -5.41270733e+00 -4.82915497e+00 -4.94917965e+00 -3.80047393e+00 -4.30105448e+00 -4.95188904e+00 -6.76697350e+00 -1.24323473e+01 -1.64308910e+01 -1.93476143e+01 -1.56308928e+01 -1.04718628e+01 -6.64428568e+00 -3.91573691e+00 -1.10325279e+01 -1.78610630e+01 -1.87170830e+01 -1.11411848e+01 -6.00808048e+00 -8.72671318e+00 -1.25254517e+01 -9.27394581e+00 -5.46779633e+00 -7.24134207e+00 -1.28708849e+01 -1.64356956e+01 -1.43847122e+01 -1.54859467e+01 -1.32375116e+01 -1.20310240e+01 -7.93378687e+00 -1.04698839e+01 -1.26982298e+01 -1.44611435e+01 -1.82345123e+01 -1.80952015e+01 -1.69213772e+01 -1.12161388e+01 -7.76793957e+00 -1.16219683e+01 -1.95562649e+01 -2.21156960e+01 -1.76696262e+01 -1.64898396e+01 -1.81935177e+01 -2.19477005e+01 -1.67952099e+01 -1.39632578e+01 -1.26919870e+01 -1.32066965e+01 -1.24646597e+01 -1.20854530e+01 -1.42031870e+01 -1.41315098e+01 -1.01958752e+01 -8.20868778e+00 -9.69072723e+00 -8.91655731e+00 -5.15857553e+00 -4.71829748e+00 -1.01189928e+01 -1.52517548e+01 -1.45811577e+01 -1.29847574e+01 -1.37033100e+01 -1.74206333e+01 -1.54375381e+01 -1.25209913e+01 -1.29190569e+01 -1.56286592e+01 -1.83566151e+01 -1.63862247e+01 -1.69337063e+01 -1.55833035e+01 -1.54367285e+01 -1.21479540e+01 -8.83631229e+00 -1.01248846e+01 -1.23147669e+01 -1.40506001e+01 -1.16510792e+01 -1.10929737e+01 -9.51806831e+00 -7.80011463e+00 -8.64763165e+00 -1.08520823e+01 -1.27136831e+01 -1.03133221e+01 -7.74027109e+00 -1.05964260e+01 -1.64525337e+01 -1.71445312e+01 -1.41677065e+01 -1.13759851e+01 -1.51722155e+01 -1.83156948e+01 -1.65106812e+01 -1.32826452e+01 -1.07093506e+01 -1.01374893e+01 -8.74236012e+00 -8.07008839e+00 -1.00102196e+01 -1.10833912e+01 -1.10420685e+01 -1.01299534e+01 -1.10816116e+01 -1.10401363e+01 -9.07916737e+00 -1.04108639e+01 -1.40957756e+01 -1.64898624e+01 -1.54378767e+01 -1.39570360e+01 -1.59444008e+01 -1.77653904e+01 -1.60833168e+01 -1.47193985e+01 -1.35571547e+01 -1.55351048e+01 -1.44884300e+01 -1.40428820e+01 -1.41203165e+01 -1.47733545e+01 -1.39083118e+01 -1.08014421e+01 -9.46477985e+00 -1.09052620e+01 -1.35696907e+01 -1.56212912e+01 -1.48931103e+01 -1.39726963e+01 -1.23199558e+01 -9.45825672e+00 -1.01421623e+01 -1.43668509e+01 -1.92240543e+01 -2.06341667e+01 -1.82658882e+01 -1.67233047e+01 -1.68656864e+01 -1.68105736e+01 -1.79317417e+01 -1.65535507e+01 -1.63486557e+01 -1.55384178e+01 -1.56066732e+01 -1.83745575e+01 -1.92955341e+01 -1.91709614e+01 -1.54964218e+01 -1.30507812e+01 -1.44864216e+01 -1.66802750e+01 -1.73873672e+01 -1.47754993e+01 -1.27900391e+01 -1.29275265e+01 -1.36113253e+01 -1.46815929e+01 -1.60158539e+01 -1.65797501e+01 -1.75640469e+01 -1.64937286e+01 -1.52840242e+01 -1.42063093e+01 -1.41154509e+01 -1.61377716e+01 -1.74862251e+01 -1.83664455e+01 -1.71612320e+01 -1.50852346e+01 -1.48392992e+01 -1.49316368e+01 -1.47549038e+01 -1.36108294e+01 -1.36918211e+01 -1.61345997e+01 -1.72890854e+01 -1.73672333e+01 -1.60454769e+01 -1.53572941e+01 -1.52052975e+01 -1.47522116e+01 -1.50189400e+01 -1.55655804e+01 -1.60082779e+01 -1.65090675e+01 -1.62676010e+01 -1.62120876e+01 -1.60492573e+01 -1.58909931e+01 -1.58584576e+01 -1.50161924e+01 -1.47921019e+01 -1.49087915e+01 -1.52591639e+01 -1.58435335e+01 -1.59299049e+01 -1.58942900e+01 -1.52618704e+01 -1.48352709e+01 -1.48661833e+01 -1.52304773e+01 -1.54870529e+01 -1.53057308e+01 -1.50682945e+01 -1.50420189e+01 -1.51049833e+01 -1.51659861e+01 -1.51876764e+01 -1.51788492e+01 -1.51432838e+01 -1.51569433e+01 -1.52102814e+01 -1.52952204e+01 -1.52300005e+01 -1.48928776e+01 -1.46854525e+01 -1.46890507e+01 -1.50440550e+01 -1.54338789e+01 -1.52454767e+01 -1.47943268e+01 -1.44897871e+01 -1.49190331e+01 -1.54312830e+01 -1.53327026e+01 -1.51032753e+01 -1.48698988e+01 -1.50009880e+01 -1.50996780e+01 -1.47096472e+01 -1.45927172e+01 -1.46389341e+01 -1.46602478e+01 -1.48845119e+01 -1.43389921e+01 -1.45799999e+01 -1.44542780e+01 -1.47952852e+01 -1.50382051e+01 -1.42098904e+01 -1.48877983e+01 -1.53925619e+01 -1.68119488e+01 -1.63557987e+01 -1.45418720e+01 -1.32215509e+01 -1.28745899e+01 -1.48302383e+01 -1.62086506e+01 -1.65172195e+01 -1.57953234e+01 -1.45969181e+01 -1.44910097e+01 -1.53931713e+01 -1.60266590e+01 -1.68131123e+01 -1.59519997e+01 -1.45039768e+01 -1.26727228e+01 -1.25030813e+01 -1.47664032e+01 -1.66758842e+01 -1.77605896e+01 -1.71489277e+01 -1.46485071e+01 -1.23700113e+01 -1.18741913e+01 -1.44537792e+01 -1.68139610e+01 -1.58411360e+01 -1.34987688e+01 -1.19495039e+01 -1.37539473e+01 -1.64803009e+01 -1.66537971e+01 -1.60608826e+01 -1.36051083e+01 -1.22719278e+01 -1.20279760e+01 -1.21807785e+01 -1.38985233e+01 -1.54004021e+01 -1.57083635e+01 -1.50287800e+01 -1.23592730e+01 -1.24979486e+01 -1.37641001e+01 -1.51709194e+01 -1.69345913e+01 -1.50299559e+01 -1.43070269e+01 -1.41433344e+01 -1.65826073e+01 -1.74338226e+01 -1.33405619e+01 -1.05605545e+01 -1.08037663e+01 -1.47389355e+01 -1.78266544e+01 -1.79319000e+01 -1.70776863e+01 -1.38014994e+01 -1.10890732e+01 -1.04932213e+01 -1.13476353e+01 -1.40127020e+01 -1.51113720e+01 -1.36877165e+01 -1.38703976e+01 -1.31898251e+01 -1.71487713e+01 -1.76694298e+01 -1.79045067e+01 -1.66091576e+01 -1.27037563e+01 -1.21423950e+01 -1.41794415e+01 -1.96815796e+01 -2.20833187e+01 -2.02211170e+01 -1.66056557e+01 -1.29325352e+01 -1.49052982e+01 -1.88936749e+01 -2.08408585e+01 -1.99054165e+01 -1.63834057e+01 -1.43292217e+01 -1.30979424e+01 -1.24448204e+01 -1.27000189e+01 -1.27892752e+01 -1.32399101e+01 -1.13413944e+01 -8.29802322e+00 -9.87497139e+00 -1.50390320e+01 -1.77348080e+01 -1.60472775e+01 -9.99691296e+00 -7.32167006e+00 -8.12865067e+00 -1.44867525e+01 -1.80453415e+01 -1.50530891e+01 -1.15733271e+01 -1.06938648e+01 -1.34707289e+01 -1.35135803e+01 -1.13211069e+01 -9.30492115e+00 -7.78732681e+00 -6.72980309e+00 -8.19350719e+00 -7.17520189e+00 -9.79756451e+00 -1.04225368e+01 -1.07835693e+01 -1.15679770e+01 -9.07211590e+00 -1.08800621e+01 -1.13081589e+01 -1.40191278e+01 -1.58688841e+01 -1.10188770e+01 -1.04975567e+01 -9.43799114e+00 -1.34349165e+01 -1.49284410e+01 -1.12984877e+01 -9.62414169e+00 -4.03372478e+00 -6.78593302e+00 -1.12696686e+01 -1.68235226e+01 -1.79990768e+01 -1.11606827e+01 -9.60550404e+00 -1.13324900e+01 -1.16567392e+01 -1.03641205e+01 -9.21753025e+00 -1.56078682e+01 -1.71093903e+01 -9.58164024e+00 -6.37731600e+00 -6.27559423e+00 -1.02726212e+01 -9.48406887e+00 -1.36079812e+00 -1.57865572e+01 -4.30552979e+01 -3.40200897e+02 -1.34761426e+03 -66952420. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -92942288. 74114848. -8866299. -19721688. -1.64556213e+03 -5.96046204e+02 -6.73279648e+01 -3.30105629e+01 -1.07333975e+01 -3.09873033e+00 -9.28190422e+00 -1.11173668e+01 -9.98922253e+00 -9.81311798e+00 -7.37854147e+00 -4.34484625e+00 -5.08266926e+00 -7.42101908e+00 -1.12273970e+01 -8.65042305e+00 -4.00959158e+00 -2.62965250e+00 -4.65624362e-01 -2.14893126e+00 -3.45000744e+00 -9.01066589e+00 -1.23569622e+01 -4.11592817e+00 -1.79152727e+00 -5.98826981e+00 -1.63955574e+01 -1.26637535e+01 -2.27386308e+00 9.67079163e-01 -3.08279562e+00 -8.72849369e+00 -8.85718536e+00 -8.06103420e+00 -7.99495935e+00 -6.61590958e+00 -3.85097361e+00 -3.58785343e+00 -4.88758659e+00 -8.87155247e+00 -4.90903425e+00 -1.76914275e+00 2.91308260e+00 9.35075951e+00 5.08239937e+00 -3.48335242e+00 -1.67217846e+01 -1.68231297e+01 -4.50904322e+00 -2.71892715e+00 -5.65479708e+00 -1.57324095e+01 -1.44419012e+01 -7.24084902e+00 -5.10271502e+00 -3.19629669e+00 -6.85624647e+00 -6.39056301e+00 -5.43019152e+00 -4.25859213e+00 3.00861597e+00 9.08308029e+00 7.91060114e+00 5.55928290e-01 -5.89256191e+00 -3.79723287e+00 -3.21856380e-01 5.01441193e+00 1.27897415e+01 1.58197651e+01 1.58679457e+01 7.35106277e+00 2.17179108e+00 5.55322790e+00 2.62682773e-02 -6.54181576e+00 -1.88230286e+01 -1.46624508e+01 -3.80877542e+00 -2.12464666e+00 -9.84187484e-01 -2.43609357e+00 -8.58303308e-01 -4.00280666e+00 -8.55722904e+00 -6.03461933e+00 -3.19776630e+00 -2.99914122e+00 -2.19456387e+00 1.78491354e+00 8.16520023e+00 5.34282351e+00 -7.60431409e-01 3.87877202e+00 4.00004578e+00 2.84870243e+00 -5.70852375e+00 -7.81262636e+00 3.53821015e+00 4.13441658e+00 -5.59108794e-01 -1.32380371e+01 -1.60328445e+01 -5.61192083e+00 -2.35015512e+00 3.52177835e+00 3.78281713e+00 7.34800768e+00 8.28076553e+00 3.67876554e+00 3.77137756e+00 4.07208967e+00 5.29947567e+00 2.86746597e+00 -2.52480316e+00 -1.01300907e+00 -1.17279041e+00 -3.89174342e+00 8.97055626e-01 -3.64110351e-01 -3.42512798e+00 -1.57955647e+01 -1.75820980e+01 -1.98212767e+00 3.63449240e+00 -1.90606523e+00 -1.37683315e+01 -1.43572187e+01 -2.43707585e+00 2.05767512e-01 2.27133679e+00 2.51894093e+00 3.45544845e-01 -4.26221514e+00 -1.11412325e+01 -5.46124268e+00 1.46400070e+00 1.16330099e+00 -3.62645578e+00 -1.02462711e+01 -4.37590742e+00 -4.07336146e-01 9.42066371e-01 4.99517012e+00 5.63803196e+00 7.76245165e+00 5.85511732e+00 4.42545891e+00 9.79552269e+00 8.47009659e+00 5.96985769e+00 -6.34658098e+00 -1.45330572e+01 -1.33467255e+01 -9.46574879e+00 -4.39534187e-01 2.22727227e+00 6.60628176e+00 1.08042917e+01 1.10216064e+01 8.81329346e+00 6.85887480e+00 8.36773396e+00 1.08132353e+01 5.99147224e+00 -4.64068699e+00 -1.38235826e+01 -1.80561123e+01 -2.51469040e+00 3.20696878e+00 1.47045696e+00 -6.92114544e+00 -7.50995111e+00 1.08245456e+00 -6.33903146e-01 2.95245910e+00 3.41661119e+00 2.72261500e+00 -1.46148801e+00 -6.52540874e+00 7.04288304e-01 5.81967211e+00 4.96992493e+00 3.95222211e+00 5.35947800e+00 1.09157391e+01 1.86755199e+01 2.29058304e+01 2.55837669e+01 1.14799557e+01 1.59291303e+00 -5.09456682e+00 -2.86609030e+00 8.79400826e+00 8.18604088e+00 1.96381533e+00 -1.26177683e+01 -1.18616819e+01 -3.61247696e-02 8.43305397e+00 1.23939457e+01 8.27900410e+00 1.25401602e+01 1.56733789e+01 1.39992094e+01 1.13427868e+01 1.14029036e+01 1.35405369e+01 1.10956345e+01 3.74710321e+00 3.03237534e+00 -4.35192156e+00 -3.26136184e+00 8.05758667e+00 1.99662971e+01 1.77500935e+01 6.40065384e+00 8.21959376e-01 2.43346667e+00 -2.86651683e+00 -7.30903769e+00 -1.33710756e+01 -1.67056046e+01 -1.06210823e+01 -3.05914593e+00 9.46526527e+00 1.20014353e+01 3.85804272e+00 -4.83834314e+00 -6.57677698e+00 -1.99196607e-01 3.57326198e+00 1.06484719e-01 2.17220759e+00 2.20593238e+00 3.10345340e+00 9.22016263e-01 1.64586437e+00 9.29068744e-01 2.13583040e+00 1.81338727e+00 -2.39295983e+00 -4.45794725e+00 -6.23913717e+00 -1.93638459e-01 1.51207829e+00 2.78200555e+00 3.85936350e-02 1.83683538e+00 1.57911396e+00 6.51296377e+00 9.40138340e+00 1.00281181e+01 6.23122931e+00 1.20698822e+00 1.34304011e+00 1.58667350e+00 2.30545211e+00 2.48399901e+00 4.98110580e+00 3.92723966e+00 2.00923491e+00 3.65292817e-01 1.73916769e+00 2.27974892e+00 -2.17456698e+00 -1.03710043e+00 -1.31525350e+00 -8.62437785e-01 -2.06626630e+00 -8.84961724e-01 6.42362177e-01 -3.80924404e-01 -2.39731416e-01 2.14905167e+00 1.03925979e+00 1.72755048e-01 3.34785908e-01 3.17588949e+00 1.19822800e+00 -1.18833828e+00 -2.59716511e+00 6.77282929e-01 -2.16492414e+00 -4.83739710e+00 -5.70126390e+00 -7.37838268e-01 2.06092763e+00 1.98354256e+00 1.79982364e+00 2.49588585e+00 2.86085153e+00 4.63876009e+00 7.40552807e+00 1.24093161e+01 7.57997751e+00 5.88994408e+00 3.45431828e+00 2.94343066e+00 3.13785481e+00 1.96556759e+00 4.89120722e+00 3.74463439e+00 3.91195798e+00 5.71725655e+00 5.05361032e+00 8.14564347e-01 -1.49364650e+00 1.96442157e-01 3.84651470e+00 5.49918079e+00 8.07809830e+00 9.44725418e+00 1.02527905e+01 5.78475380e+00 4.16390991e+00 3.70211267e+00 6.03304529e+00 2.78532696e+00 -1.00642765e+00 2.85665661e-01 4.05191898e+00 7.74701595e+00 6.87847757e+00 7.88773489e+00 8.13605595e+00 2.41939926e+00 -2.55155635e+00 -3.74397087e+00 4.46293652e-01 3.71556854e+00 4.28625870e+00 4.23263216e+00 6.43205976e+00 6.84676218e+00 8.21977329e+00 6.81759214e+00 7.55113888e+00 4.46592474e+00 5.46194315e+00 7.09756088e+00 1.17360153e+01 1.38322706e+01 1.69067459e+01 1.44473410e+01 1.30878210e+01 9.46553040e+00 1.17685032e+01 1.22885427e+01 1.04942322e+01 5.96719980e+00 3.08408546e+00 4.61604548e+00 5.88971806e+00 6.50380898e+00 5.17717791e+00 7.22897482e+00 7.69379187e+00 7.81021500e+00 1.18466520e+01 1.56890392e+01 9.68736172e+00 -1.77135253e+00 -4.05026627e+00 2.27384877e+00 7.54393148e+00 8.45110512e+00 6.90014696e+00 8.57100868e+00 7.95649147e+00 1.02833281e+01 8.44068050e+00 4.79645777e+00 -4.52760644e-02 2.40893245e+00 9.30728054e+00 1.42302237e+01 1.09735432e+01 6.69390106e+00 3.81961989e+00 5.39600134e+00 5.07526207e+00 4.73600721e+00 5.01499400e-02 -2.06309676e+00 -3.58953834e-01 5.37745857e+00 7.28123426e+00 7.47259665e+00 6.69076967e+00 7.57517433e+00 7.01831198e+00 7.68732214e+00 7.15644836e+00 6.97220087e+00 4.89749241e+00 4.33020735e+00 3.90482569e+00 6.20064688e+00 6.38117599e+00 1.01369085e+01 1.42707214e+01 2.27050152e+01 2.52569199e+01 2.01640377e+01 1.42233086e+01 9.97008228e+00 9.90917587e+00 1.00878754e+01 1.17489548e+01 1.23172932e+01 1.20919590e+01 1.11048517e+01 1.12549353e+01 9.92471600e+00 1.33091345e+01 1.72807102e+01 1.82747173e+01 1.44022560e+01 1.06564312e+01 1.04579563e+01 1.07428503e+01 9.06212616e+00 7.45997524e+00 7.15994549e+00 7.32331133e+00 7.89492846e+00 7.46381807e+00 8.93368530e+00 9.57242966e+00 8.44867039e+00 6.63623476e+00 7.16722202e+00 8.88758278e+00 9.97563171e+00 8.87658501e+00 7.46944761e+00 7.09837532e+00 8.26593781e+00 1.07045927e+01 1.26058683e+01 1.21508121e+01 1.07292929e+01 8.79599571e+00 5.28507519e+00 2.54965472e+00 4.13121796e+00 8.49005508e+00 1.26948004e+01 1.47457504e+01 1.62200947e+01 1.81994171e+01 1.72964516e+01 1.52308016e+01 1.45362959e+01 9.01046562e+00 -3.66923547e+00 -1.70894039e+00 -6.91141701e+00 -2.55207047e+02 -1.89865051e+03 34153508. 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. 0. 0. 0. 0. 0. 0. -94158472. -201580864. -1.24439307e+03 -4.23945343e+02 -2.55678158e+01 -1.22803030e+01 -8.77172410e-01 7.68980551e+00 9.34512520e+00 1.09217577e+01 8.25754833e+00 5.44439793e+00 5.72055340e+00 7.30868292e+00 8.57434654e+00 7.88786936e+00 7.69494247e+00 7.57594585e+00 7.49735069e+00 8.50506687e+00 9.12586880e+00 1.07036610e+01 1.17642784e+01 1.16215219e+01 1.10809212e+01 1.07436609e+01 1.27703362e+01 1.40873766e+01 1.43825140e+01 1.41745300e+01 1.36957436e+01 1.34690866e+01 1.32214680e+01 1.39918661e+01 1.50757837e+01 1.54077339e+01 1.50646048e+01 1.49200735e+01 1.49076920e+01 1.52679510e+01 1.40671978e+01 1.32609577e+01 1.27543936e+01 1.36808414e+01 1.50748644e+01 1.58864470e+01 1.66621723e+01 1.60055237e+01 1.69811172e+01 1.79263554e+01 1.82360764e+01 1.70942020e+01 1.53133802e+01 1.53409958e+01 1.58861380e+01 1.57404222e+01 1.59020691e+01 1.52701702e+01 1.55868587e+01 1.51063118e+01 1.48043251e+01 1.45026245e+01 1.21314707e+01 9.80126381e+00 9.37516594e+00 1.02418594e+01 1.13389301e+01 9.79343605e+00 8.97249317e+00 1.01984816e+01 1.20795259e+01 1.45230083e+01 1.52566385e+01 1.53529072e+01 1.66236820e+01 1.84780674e+01 1.97188549e+01 1.95137386e+01 1.75851974e+01 1.60605488e+01 1.52037458e+01 1.46780100e+01 1.52530947e+01 1.37729406e+01 1.26456900e+01 1.05968304e+01 1.00092802e+01 1.07004919e+01 1.21655903e+01 1.35836916e+01 1.36349449e+01 1.33043976e+01 1.17004156e+01 1.03736286e+01 1.08318233e+01 1.25670595e+01 1.39693165e+01 1.38288584e+01 1.34308348e+01 1.29170980e+01 1.21511765e+01 1.35748186e+01 1.54981642e+01 1.63733597e+01 1.59008961e+01 1.44893923e+01 1.46140966e+01 1.40916395e+01 1.33121386e+01 1.26435843e+01 1.17513895e+01 1.22552166e+01 1.35198336e+01 1.50609713e+01 1.62096958e+01 1.59715919e+01 1.58039227e+01 1.54985199e+01 1.55678816e+01 1.58298206e+01 1.58873014e+01 1.58167219e+01 1.54586458e+01 1.53020287e+01 1.49933138e+01 1.49511461e+01 1.48924980e+01 1.47118006e+01 1.37499590e+01 1.27666645e+01 1.28565035e+01 1.37324867e+01 1.46253939e+01 1.42493763e+01 1.37929258e+01 1.30169811e+01 1.27652588e+01 1.31887884e+01 1.41467457e+01 1.49843721e+01 1.51703205e+01 1.51327019e+01 1.51649313e+01 1.53310719e+01 1.54318409e+01 1.55361662e+01 1.53977499e+01 1.51867485e+01 1.50975819e+01 1.51805573e+01 1.52243233e+01 1.51851730e+01 1.50148802e+01 1.45356350e+01 1.40798998e+01 1.42461185e+01 1.47163525e+01 1.51418896e+01 1.47511396e+01 1.44575796e+01 1.42460670e+01 1.42606611e+01 1.42684498e+01 1.43316355e+01 1.46581755e+01 1.48927507e+01 1.51108685e+01 1.51205330e+01 1.51641245e+01 1.51807461e+01 1.51335793e+01 1.51377230e+01 1.51469078e+01 1.51579733e+01 1.51511307e+01 1.51667032e+01 1.51795168e+01 1.51384497e+01 1.50958614e+01 1.51297150e+01 1.51961288e+01 1.52368011e+01 1.52330484e+01 1.52250013e+01 1.51265459e+01 1.52312021e+01 1.54378405e+01 1.54959440e+01 1.53151217e+01 1.51186829e+01 1.51948929e+01 1.52654114e+01 1.52700062e+01 1.52162924e+01 1.52568464e+01 1.52534685e+01 1.53344383e+01 1.53503265e+01 1.53419123e+01 1.53073568e+01 1.52660208e+01 1.49349737e+01 1.44511271e+01 1.44583120e+01 1.47486525e+01 1.51861868e+01 1.48969154e+01 1.49434958e+01 1.51516762e+01 1.53642149e+01 1.53177557e+01 1.51575470e+01 1.50435581e+01 1.50627756e+01 1.51922464e+01 1.54016457e+01 1.53146238e+01 1.51421604e+01 1.51077061e+01 1.49883652e+01 1.49755220e+01 1.46194000e+01 1.45854244e+01 1.46060266e+01 1.47441578e+01 1.48261471e+01 1.42758045e+01 1.37699690e+01 1.35896606e+01 1.39600086e+01 1.44608307e+01 1.42498426e+01 1.43213072e+01 1.38893156e+01 1.36279650e+01 1.34552927e+01 1.36368160e+01 1.39203548e+01 1.35607843e+01 1.36274776e+01 1.39333630e+01 1.46556168e+01 1.51756201e+01 1.51231403e+01 1.37590570e+01 1.23342180e+01 1.18534307e+01 1.28577890e+01 1.57684126e+01 1.78884010e+01 1.78249454e+01 1.58664875e+01 1.43257742e+01 1.63532066e+01 1.79457645e+01 1.77511215e+01 1.54996004e+01 1.37057123e+01 1.36094742e+01 1.36509275e+01 1.40191965e+01 1.44674110e+01 1.43612776e+01 1.39979925e+01 1.38149796e+01 1.46880093e+01 1.52687435e+01 1.45164547e+01 1.34049902e+01 1.31422329e+01 1.42471056e+01 1.54450874e+01 1.53950882e+01 1.52764196e+01 1.53144913e+01 1.52866373e+01 1.56367817e+01 1.52670851e+01 1.71880093e+01 1.79906292e+01 1.77512074e+01 1.52742157e+01 1.31668749e+01 1.30349569e+01 1.38022738e+01 1.48775749e+01 1.47518072e+01 1.31073542e+01 1.09654198e+01 1.12020693e+01 1.25353861e+01 1.41872549e+01 1.31824646e+01 1.27427578e+01 1.26109867e+01 1.34723997e+01 1.58234329e+01 1.82231693e+01 1.84443836e+01 1.64448662e+01 1.36222124e+01 1.33448400e+01 1.37271719e+01 1.40575581e+01 1.41659069e+01 1.55955782e+01 1.81032696e+01 1.85138493e+01 1.80869179e+01 1.55126257e+01 1.58996372e+01 1.49930782e+01 1.50850563e+01 1.42811489e+01 1.47554693e+01 1.53463755e+01 1.58992586e+01 1.54396448e+01 1.41279936e+01 1.39378195e+01 1.32764463e+01 1.27997608e+01 1.19034090e+01 1.24024019e+01 1.26455450e+01 1.31714439e+01 1.54900866e+01 1.82625675e+01 2.09805431e+01 2.14522705e+01 2.11026211e+01 2.02482185e+01 1.61545467e+01 1.43033514e+01 1.18754177e+01 1.28785257e+01 1.21393824e+01 1.44924107e+01 1.75347691e+01 1.74352322e+01 1.53649969e+01 1.01886053e+01 7.57820320e+00 7.44179249e+00 9.21014118e+00 1.19693336e+01 1.20462637e+01 1.33799076e+01 1.66365948e+01 1.94037495e+01 1.77463818e+01 1.36005640e+01 9.02419281e+00 1.13368120e+01 1.43822346e+01 1.61429672e+01 1.60922089e+01 1.38003330e+01 1.22252989e+01 8.89651871e+00 8.82749271e+00 9.30673122e+00 9.56276703e+00 9.48536491e+00 9.79094696e+00 9.57946682e+00 1.05272236e+01 1.10305424e+01 1.09013243e+01 1.04469166e+01 1.07431431e+01 1.53143930e+01 1.99015045e+01 1.73665390e+01 1.06851482e+01 8.67280388e+00 1.37851152e+01 1.74429035e+01 1.54986200e+01 1.28043337e+01 1.56614285e+01 1.77149277e+01 1.83922825e+01 1.55762911e+01 1.23241014e+01 1.26915560e+01 1.33236876e+01 1.54502735e+01 1.44830952e+01 1.28982687e+01 1.12667809e+01 1.14339085e+01 1.18027697e+01 1.27815390e+01 1.25447311e+01 1.37287588e+01 1.50623341e+01 1.80261402e+01 1.40373907e+01 7.55510950e+00 8.49925613e+00 1.58595724e+01 1.99766006e+01 1.45793886e+01 1.07790375e+01 1.27527094e+01 1.50848637e+01 1.17062521e+01 7.14152527e+00 3.82663250e+00 4.98597240e+00 4.82593107e+00 8.78524876e+00 1.31379566e+01 1.34970894e+01 8.44496059e+00 7.92927313e+00 1.38253613e+01 1.44443016e+01 1.09478903e+01 5.89508247e+00 5.90441513e+00 5.92953396e+00 2.96037722e+00 7.84928203e-01 3.02869391e+00 9.05890942e+00 1.29022427e+01 1.09521532e+01 8.95275402e+00 9.03875732e+00 9.95860481e+00 9.86863995e+00 1.02915373e+01 9.00883102e+00 6.49703121e+00 5.59662294e+00 1.02811556e+01 1.52563639e+01 1.69336529e+01 1.46415548e+01 1.61847572e+01 2.18796654e+01 1.94514160e+01 1.20539274e+01 2.97947621e+00 2.18880129e+00 4.51746941e+00 3.93197846e+00 2.87500501e+00 4.86814976e+00 8.49136925e+00 1.08680305e+01 9.93418026e+00 8.03520012e+00 6.64814949e+00 4.05789089e+00 3.49881577e+00 5.61455727e+00 5.91336632e+00 5.44829321e+00 3.91299367e+00 8.39595795e+00 1.16018257e+01 1.03820868e+01 4.96198654e+00 4.63261986e+00 8.30703926e+00 7.67500353e+00 2.50522351e+00 3.08278394e+00 1.08396873e+01 2.08383865e+01 2.24665012e+01 1.90705147e+01 1.84001141e+01 1.96061668e+01 1.85686398e+01 1.35622950e+01 9.98948288e+00 1.02180262e+01 1.09341021e+01 1.28780127e+01 1.59357109e+01 1.54410658e+01 9.94672489e+00 3.87202263e+00 5.62892771e+00 1.13409805e+01 1.10950966e+01 7.47739267e+00 8.28940773e+00 1.50696592e+01 1.10770893e+01 -5.21743894e-01 -9.08073807e+00 -5.18246126e+00 1.39420295e+00 -7.32944906e-01 -5.78190279e+00 -7.79719400e+00 -3.61793518e+00 -2.53874421e-01 -2.70123792e+00 -4.07405806e+00 -4.82950401e+00 -6.98291481e-01 5.61529827e+00 1.34534168e+01 1.80553017e+01 1.89470005e+01 9.66388130e+00 1.58749056e+00 -3.43503308e+00 1.22856998e+00 4.77747393e+00 4.79911089e+00 3.76535892e+00 -4.44253236e-01 -7.27662134e+00 -5.89229727e+00 -2.37117440e-01 5.37059498e+00 6.17664814e+00 6.28786182e+00 1.21905165e+01 1.58916101e+01 1.48156004e+01 1.01628227e+01 6.09665632e+00 6.06084108e+00 5.47945356e+00 5.17956352e+00 6.82441902e+00 8.35658360e+00 8.85195351e+00 7.05574751e+00 5.10560894e+00 2.65668416e+00 1.25522852e+00 2.17203736e+00 9.20667839e+00 1.78051472e+01 1.80049038e+01 1.25034952e+01 1.15033674e+01 1.57875347e+01 1.57735920e+01 1.12109823e+01 6.52902222e+00 1.13789787e+01 1.50844765e+01 1.32558537e+01 7.78650951e+00 -1.13050163e+00 -1.39948714e+00 -9.42025065e-01 4.36629868e+00 1.08177671e+01 1.01003151e+01 5.94623280e+00 6.84503889e+00 1.35366411e+01 1.52757721e+01 1.01356134e+01 2.50433087e+00 6.69338846e+00 1.21568012e+01 1.13985529e+01 3.04867268e+00 -4.00030947e+00 7.43670702e-01 6.77147627e+00 7.86635351e+00 7.53822088e+00 6.27338505e+00 7.86679220e+00 9.81623936e+00 1.01298647e+01 1.45087519e+01 1.59514332e+01 1.53006687e+01 9.98953819e+00 5.49192905e+00 5.61261177e+00 4.77196550e+00 4.40600777e+00 3.48196340e+00 3.88643122e+00 5.35922718e+00 3.83355141e+00 2.77121735e+00 9.83222902e-01 -4.95002604e+00 -9.83227634e+00 -3.55727315e+00 7.96161366e+00 1.28161774e+01 3.78099728e+00 -2.70457673e+00 -4.15747833e+00 -2.99080157e+00 -2.02048922e+00 -5.18656731e-01 2.92615104e+00 4.25952816e+00 6.16342497e+00 3.40619392e+01 8.54001083e+01 6.52724304e+02 3.70589697e+03 -633708864. 0. 0. 0. 0. 693049472. -1.19657625e+06 2.43456525e+06 4.04202750e+05 4.00009937e+03 8.30788281e+03 9.98359766e+03 -1660712960. 0. 0.
================================================ FILE: config/m2dgr/ring32_M_6.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 201144560. 113401328. 1.60678463e+01 4.99960232e+00 -4.53779888e+00 -5.88477087e+00 -5.97438574e+00 -5.82587481e+00 -6.21096468e+00 -5.70433140e+00 -5.05896521e+00 -4.99526310e+00 -5.12207413e+00 -5.27889395e+00 -5.54332209e+00 -5.64076281e+00 -5.83279181e+00 -5.56179380e+00 -5.14274883e+00 -4.70646524e+00 -4.72374010e+00 -5.48171234e+00 -6.24423409e+00 -6.78327131e+00 -6.86710358e+00 -6.35420179e+00 -6.25680494e+00 -6.21762562e+00 -5.57078600e+00 -5.17166090e+00 -5.38738823e+00 -6.56880617e+00 -7.44207335e+00 -7.52088976e+00 -6.79005814e+00 -5.45213842e+00 -4.98875713e+00 -5.07720184e+00 -5.12963820e+00 -5.12834692e+00 -5.34290552e+00 -6.22155857e+00 -7.00200653e+00 -6.55312538e+00 -5.63803291e+00 -5.12675381e+00 -5.85156965e+00 -5.94659901e+00 -5.74753189e+00 -6.24275398e+00 -6.23261642e+00 -6.18978024e+00 -5.63151884e+00 -4.87421751e+00 -4.30074215e+00 -4.11646891e+00 -5.68968201e+00 -7.65222931e+00 -8.21309566e+00 -7.06542253e+00 -4.83452988e+00 -4.62190437e+00 -5.54965210e+00 -6.62128067e+00 -6.41573000e+00 -5.97615623e+00 -6.25546741e+00 -6.69690180e+00 -6.68478870e+00 -5.38403368e+00 -3.78844976e+00 -4.30717945e+00 -4.76856852e+00 -5.39198065e+00 -5.79928541e+00 -6.00047302e+00 -6.52064610e+00 -5.69595528e+00 -4.36143208e+00 -3.09806466e+00 -3.09290075e+00 -4.59454250e+00 -6.33267927e+00 -7.88799667e+00 -8.05368137e+00 -6.37041140e+00 -5.62356710e+00 -5.44278240e+00 -4.31636381e+00 -2.59162068e+00 -2.59818864e+00 -5.26229429e+00 -7.96770906e+00 -8.15096664e+00 -5.66601229e+00 -2.82246423e+00 -2.53728676e+00 -2.93904281e+00 -2.76196671e+00 -2.76979017e+00 -3.33807588e+00 -4.70854235e+00 -5.51711655e+00 -4.86258554e+00 -3.54389834e+00 -2.99892282e+00 -4.13592720e+00 -6.11847353e+00 -7.45315790e+00 -7.72990847e+00 -5.66854048e+00 -3.69163799e+00 -3.95503092e+00 -3.89757681e+00 -3.01219630e+00 -2.31545591e+00 -3.64161110e+00 -5.93916988e+00 -5.97430658e+00 -3.24585748e+00 -7.52615392e-01 -3.04069072e-01 -2.37632275e+00 -4.54745674e+00 -6.73451281e+00 -7.78572273e+00 -9.13032532e+00 -2.06175594e+01 -1.27184700e+02 -2.68729065e+02 -6606219. 7.72394550e+06 10930837. -16376169. 2.78985931e+02 1.51581741e+02 2.62712479e+01 -1.02835464e+01 -2.93263817e+01 -1.41191483e+02 -2.63339172e+02 53804900. -240486640. 7.11620850e+06 117234920. 5.50663150e+06 -7243306. 21696244. -14542091. -6791696. 8.38355450e+06 2.78052063e+02 1.49951675e+02 2.48133259e+01 6.25773287e+00 -6.34944582e+00 -4.73680115e+00 -6.23969841e+00 -6.24877644e+00 -5.73162174e+00 -2.97000575e+00 -1.44414651e+00 -3.82844329e+00 -6.45174503e+00 -6.32006931e+00 -5.88955498e+00 -5.75097799e+00 -8.84115505e+00 -1.11052170e+01 -1.18958473e+01 -7.47499704e+00 -1.86035991e+00 -5.53893745e-01 -8.41390371e-01 -1.01972365e+00 -1.44603801e+00 -3.11136746e+00 -6.78802633e+00 -8.09595680e+00 -5.31723213e+00 -1.69808519e+00 -8.93623412e-01 -3.88160467e+00 -6.28992128e+00 -6.89387274e+00 -7.30355930e+00 -6.65184069e+00 -7.78376579e+00 -7.78304529e+00 -6.37778044e+00 -5.99170256e+00 -6.47779036e+00 -9.14610386e+00 -1.05612125e+01 -1.01998644e+01 -5.12082291e+00 2.51221001e-01 1.16147268e+00 -7.85321891e-01 -1.47095776e+00 -2.04829264e+00 -3.51675701e+00 -7.03279161e+00 -7.35146332e+00 -3.24200153e+00 1.11640596e+00 2.19045997e+00 -1.28384984e+00 -3.59183812e+00 -3.88906717e+00 -3.75163007e+00 -3.56296515e+00 -5.11950874e+00 -6.80309200e+00 -4.95847797e+00 -1.95961201e+00 -3.80641848e-01 -2.91421771e+00 -7.03000164e+00 -8.09919357e+00 -4.81160641e+00 -1.10893130e+00 -1.73036814e-01 -1.56594694e+00 -1.54815423e+00 -2.00481248e+00 -1.53712094e+00 -1.16055119e+00 -9.76793885e-01 -8.17644298e-01 -4.57051843e-01 1.44335055e+00 1.56505442e+00 1.06761372e+00 6.42322972e-02 -3.58566952e+00 -5.76808119e+00 -8.28450203e+00 -6.39837360e+00 -3.40663671e+00 -1.83904603e-01 2.12884974e+00 -2.48478198e+00 -6.39725494e+00 -6.97412443e+00 -2.38423848e+00 6.27418756e-02 -1.61754608e+00 -4.02933788e+00 -1.71128702e+00 6.10862672e-03 -1.01575470e+00 -4.90253353e+00 -6.70418882e+00 -4.42482710e+00 -4.75473738e+00 -3.91208673e+00 -3.90014100e+00 -1.49191487e+00 -3.04783940e+00 -4.47095633e+00 -5.99550056e+00 -7.77673054e+00 -7.55262756e+00 -6.41129446e+00 -1.95942914e+00 1.11564755e+00 -1.43439198e+00 -7.96348143e+00 -1.04388618e+01 -7.45373678e+00 -5.80660486e+00 -7.40301704e+00 -8.93192577e+00 -5.03393650e+00 -2.60110617e+00 -1.97648537e+00 -2.80374217e+00 -2.45770168e+00 -1.98584557e+00 -4.11490107e+00 -4.22040272e+00 -2.04165745e+00 7.37344146e-01 -2.25779504e-01 8.24034691e-01 3.48236322e+00 3.56996751e+00 -5.92570901e-01 -4.59547234e+00 -4.15207005e+00 -2.69606161e+00 -3.16027546e+00 -6.00205517e+00 -4.53522158e+00 -2.41425014e+00 -2.40702057e+00 -5.59848356e+00 -7.78368759e+00 -5.73154306e+00 -4.88394022e+00 -3.38893676e+00 -4.08241606e+00 -9.57896173e-01 1.54457927e+00 5.29780030e-01 -1.72538781e+00 -2.84280753e+00 -7.27155149e-01 6.43470585e-02 1.57683623e+00 3.68882799e+00 3.12100172e+00 1.40109622e+00 -7.41584480e-01 1.21258616e+00 3.69935679e+00 1.10067451e+00 -4.54781008e+00 -5.44688320e+00 -1.79469061e+00 6.88582003e-01 -2.98671603e+00 -6.36819124e+00 -4.29688168e+00 -1.52848649e+00 1.66342199e+00 2.59349179e+00 4.81329298e+00 5.27112246e+00 3.25110626e+00 1.72228301e+00 1.42396283e+00 2.03068280e+00 7.92757869e-01 1.62192094e+00 4.05831766e+00 2.53180313e+00 -2.20427084e+00 -5.36629009e+00 -4.05258560e+00 -2.50975704e+00 -4.24609900e+00 -6.08939123e+00 -3.83806324e+00 -2.39842272e+00 -2.16481638e+00 -5.02102518e+00 -4.17186832e+00 -1.94256544e+00 -1.83763933e+00 -1.70163763e+00 -9.45247769e-01 3.62289333e+00 4.99613571e+00 2.92879009e+00 -6.52210951e-01 -3.30977249e+00 -2.34795904e+00 -8.49804521e-01 1.89376330e+00 7.40436077e+00 6.61607504e+00 -7.53749371e-01 -9.59864712e+00 -1.31369286e+01 -8.20221233e+00 -5.42598391e+00 -5.59699535e+00 -6.17877150e+00 -8.71821213e+00 -5.69769096e+00 -5.27801466e+00 -3.06660390e+00 -3.54250193e+00 -9.84742641e+00 -1.17134113e+01 -1.10219574e+01 -2.05581021e+00 3.96816182e+00 4.08680737e-01 -4.44105291e+00 -6.53108120e+00 -4.34854835e-01 4.63249922e+00 3.67291164e+00 3.06127453e+00 -2.74071664e-01 -3.28413057e+00 -5.44595337e+00 -7.66567326e+00 -4.86245489e+00 -1.97450292e+00 3.67291033e-01 4.87876564e-01 -5.14886570e+00 -8.69650078e+00 -1.14599733e+01 -8.20241356e+00 -1.47471440e+00 -1.01520920e+00 -9.83958542e-01 -4.11037832e-01 5.11390686e+00 4.73478270e+00 -4.47847652e+00 -1.02326536e+01 -1.06602201e+01 -5.45122433e+00 -2.56220269e+00 -2.25718737e+00 4.89235997e-01 1.75731674e-01 -2.70846343e+00 -5.01467323e+00 -8.23292637e+00 -6.57547140e+00 -7.12252855e+00 -6.92102718e+00 -6.24134302e+00 -5.88911295e+00 6.11639023e-01 2.21960568e+00 1.63333094e+00 -9.08642709e-01 -6.87380505e+00 -8.44048595e+00 -8.64720821e+00 -8.81218255e-01 5.05017948e+00 4.97448063e+00 -2.17216447e-01 -5.64717054e+00 -2.41343284e+00 3.20228958e+00 5.33273983e+00 4.44960499e+00 2.30139208e+00 6.88737109e-02 -1.79699457e+00 -4.19257593e+00 -1.09202707e+00 2.20283484e+00 4.08398247e+00 1.59661186e+00 -6.49872208e+00 -9.95579720e+00 -8.47896099e+00 -1.53566670e+00 4.01288319e+00 1.29202378e+00 -4.26643229e+00 -7.16375637e+00 -2.40580487e+00 3.07738614e+00 2.38620734e+00 -1.22048873e-02 -2.61281300e+00 -1.85017395e+00 -7.10787416e-01 -2.48986125e+00 -3.07716060e+00 -2.70758533e+00 -2.56013894e+00 -1.45391631e+00 -4.49452829e+00 -3.20711470e+00 -2.94931483e+00 -1.28129458e+00 2.68239498e-01 -2.99485135e+00 -1.36247233e-01 2.04432225e+00 7.19351339e+00 5.27129269e+00 -1.97160864e+00 -6.96453762e+00 -8.00301266e+00 -3.03001404e-01 5.15311432e+00 6.36357784e+00 3.60748553e+00 -8.38183045e-01 -1.56175971e+00 1.18776023e+00 3.69118357e+00 6.75674248e+00 4.01934052e+00 -7.56512165e-01 -5.77184105e+00 -6.14593315e+00 9.43054974e-01 6.02268267e+00 8.40300941e+00 6.00734329e+00 -4.57488537e-01 -5.13455582e+00 -5.66610432e+00 8.99520874e-01 6.55940723e+00 4.35549068e+00 -1.13697112e+00 -5.08773708e+00 -1.30025637e+00 4.80715561e+00 5.43847466e+00 3.68385601e+00 -1.50963509e+00 -4.29197884e+00 -4.48033857e+00 -3.81547308e+00 -3.17114204e-01 2.69937468e+00 3.09989047e+00 1.93598557e+00 -2.77431774e+00 -2.03963923e+00 1.55099273e-01 2.22261620e+00 5.40332031e+00 2.09353924e+00 1.61933076e+00 1.37451065e+00 5.22824335e+00 6.36441755e+00 -1.34967005e+00 -5.69698429e+00 -5.81509876e+00 1.68920314e+00 7.13931561e+00 7.15344477e+00 4.75626516e+00 -3.05669010e-01 -3.43191910e+00 -3.34815574e+00 -2.40404606e+00 6.50684357e-01 1.57336688e+00 4.97824162e-01 1.28472662e+00 6.55756950e-01 5.27044058e+00 5.45591116e+00 5.40328264e+00 4.30882120e+00 -3.06004554e-01 -4.35168833e-01 1.83293474e+00 8.47263241e+00 1.09555578e+01 8.90686798e+00 5.01610184e+00 1.25183213e+00 3.46139359e+00 7.87721634e+00 9.89214611e+00 8.49881649e+00 4.47146368e+00 2.46469140e+00 1.84112597e+00 1.48522127e+00 1.23592484e+00 8.71458054e-01 1.01773345e+00 -6.94887221e-01 -3.31316090e+00 -6.27729952e-01 4.81412077e+00 7.44012165e+00 5.11260128e+00 -8.46765995e-01 -3.33230996e+00 -2.12928295e+00 3.42971468e+00 6.74935293e+00 4.34830475e+00 2.06375146e+00 7.50149310e-01 2.74996018e+00 3.38340688e+00 1.50316095e+00 -6.58857003e-02 -1.92823315e+00 -2.52527571e+00 -1.70857477e+00 -2.49064398e+00 -1.35716304e-01 7.24765480e-01 8.26600373e-01 1.75248122e+00 -4.87349868e-01 1.23729038e+00 9.03809667e-01 2.95882893e+00 4.05159426e+00 3.52556914e-01 5.13907194e-01 1.76530574e-02 3.62826324e+00 5.16737938e+00 2.68131018e+00 1.52172971e+00 -3.24672675e+00 -1.39089501e+00 2.38935924e+00 6.45951986e+00 7.49005413e+00 2.43736410e+00 1.72644687e+00 2.76551342e+00 2.54308891e+00 1.27067435e+00 4.00400102e-01 5.13998985e+00 6.60641432e+00 2.02603221e+00 1.62936404e-01 3.97582024e-01 7.90117311e+00 7.92721319e+00 2.55127258e+01 3.32078781e+01 3.04379211e+02 8.57763916e+02 12271988. 179269984. 6380537. 4.71044650e+06 -810436672. 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. 0. 0. 0. 0. 0. 0. 0. 430126272. 1.43951733e+03 2.44966080e+02 4.83169937e+01 2.11784096e+01 8.31580162e+00 8.37431014e-01 -7.27487147e-01 -1.56569302e+00 2.25215173e+00 3.77254200e+00 3.53006053e+00 3.87090182e+00 2.48793244e+00 1.63843369e+00 1.81773376e+00 3.51597953e+00 4.95618916e+00 3.89764404e+00 2.26839852e+00 1.55956304e+00 9.63384748e-01 1.42461741e+00 2.14854121e+00 4.33036232e+00 5.30806160e+00 2.10660815e+00 1.04268348e+00 2.85059237e+00 6.78840303e+00 5.38427639e+00 1.69959080e+00 7.58901536e-01 2.30240417e+00 4.33734035e+00 4.35362434e+00 3.93937945e+00 4.05100679e+00 3.43357372e+00 2.61032891e+00 2.32011914e+00 3.07100534e+00 4.82233095e+00 3.58728194e+00 2.47923160e+00 5.58781624e-01 -1.84383023e+00 -6.76873505e-01 3.51325989e+00 8.98996067e+00 8.97046089e+00 4.31070566e+00 3.11546946e+00 3.87560320e+00 7.12377882e+00 6.94157887e+00 4.69044018e+00 3.60119462e+00 2.91911530e+00 4.11836481e+00 3.89139342e+00 3.32737279e+00 3.07668185e+00 1.36867166e+00 -3.35519202e-02 1.70278236e-01 2.13455248e+00 3.97167277e+00 3.32759309e+00 2.56056547e+00 1.03540957e+00 -7.42541671e-01 -1.63552690e+00 -1.80181420e+00 3.08705091e-01 1.62709343e+00 8.16237271e-01 2.28141356e+00 4.35717726e+00 8.29120445e+00 7.76746225e+00 5.00064373e+00 3.85500216e+00 3.05980635e+00 3.04803109e+00 2.95908189e+00 3.88826466e+00 5.24018383e+00 4.38114309e+00 3.47707987e+00 3.73465824e+00 3.68123126e+00 3.03923345e+00 1.41280699e+00 2.12654114e+00 3.75954866e+00 2.67927527e+00 2.79531169e+00 2.87769270e+00 4.97433853e+00 5.42212963e+00 2.97425771e+00 2.93594646e+00 4.02406931e+00 7.10850334e+00 7.61773729e+00 5.40502691e+00 4.44088554e+00 3.22452688e+00 3.11804032e+00 2.48000002e+00 2.35046577e+00 3.42611361e+00 3.47289777e+00 3.31904411e+00 3.11399961e+00 3.66926932e+00 4.98871565e+00 4.61997080e+00 4.60350895e+00 4.99178457e+00 3.93776417e+00 3.98865986e+00 4.54593182e+00 6.91775942e+00 7.15589428e+00 4.43610764e+00 3.57379508e+00 4.69059134e+00 6.87300825e+00 7.00457335e+00 5.02353001e+00 4.39753199e+00 3.90322852e+00 4.05871344e+00 4.57511139e+00 5.41436148e+00 6.50780487e+00 5.59207344e+00 4.56777191e+00 4.46396112e+00 5.14890242e+00 6.20504951e+00 5.50788116e+00 5.06208992e+00 4.91740131e+00 4.29014874e+00 4.12867165e+00 3.64140081e+00 3.98342752e+00 4.20065975e+00 3.69448137e+00 3.93133831e+00 4.41430807e+00 5.94469261e+00 6.87858725e+00 6.51082659e+00 5.96531868e+00 4.99634218e+00 4.79277706e+00 4.37293482e+00 3.91368437e+00 3.88184500e+00 4.20084143e+00 4.41121864e+00 4.30444717e+00 3.98976421e+00 4.60071039e+00 5.68752813e+00 6.56784201e+00 6.79906607e+00 5.40347528e+00 4.95749283e+00 5.24709177e+00 6.03295708e+00 5.89362812e+00 5.19577456e+00 5.28178310e+00 5.11622000e+00 5.08654070e+00 5.07464552e+00 5.41552830e+00 5.70160532e+00 5.32966471e+00 5.00776196e+00 5.12718248e+00 5.11526728e+00 5.03778028e+00 4.71886301e+00 4.35172892e+00 4.13029385e+00 3.96022725e+00 4.77881670e+00 5.37024021e+00 5.71846390e+00 5.68602705e+00 5.18995380e+00 5.26706648e+00 5.47253895e+00 6.13340187e+00 6.10546732e+00 5.64838362e+00 5.27635193e+00 5.13556671e+00 5.28252029e+00 5.18925095e+00 5.09203291e+00 5.15717840e+00 5.26525593e+00 5.31052971e+00 5.31037045e+00 5.41115522e+00 5.58632326e+00 5.59659958e+00 5.73454142e+00 5.72974205e+00 5.54053926e+00 5.38876581e+00 5.43492842e+00 5.61297703e+00 5.67619324e+00 5.66242123e+00 5.69228888e+00 5.71036863e+00 5.70765305e+00 5.68393946e+00 5.66744423e+00 5.67299271e+00 5.72815561e+00 5.76254654e+00 5.71359873e+00 5.62442970e+00 5.58846664e+00 5.67148066e+00 5.73138905e+00 5.69303942e+00 5.69909477e+00 5.68573093e+00 5.67614794e+00 5.65496635e+00 5.68823767e+00 5.69807768e+00 5.72370386e+00 5.70146084e+00 5.64343500e+00 5.50681591e+00 5.44607210e+00 5.52316904e+00 5.65271187e+00 5.67272949e+00 5.59659195e+00 5.63378000e+00 5.65775681e+00 5.91675138e+00 6.07764769e+00 6.09597635e+00 5.85934877e+00 5.54328156e+00 5.62309790e+00 5.64993525e+00 5.71689653e+00 5.69015217e+00 5.84994411e+00 5.81699991e+00 5.79164267e+00 5.63999510e+00 5.69049644e+00 5.53623724e+00 5.39298344e+00 5.43617582e+00 5.52653790e+00 5.40018511e+00 5.32737970e+00 5.35936308e+00 5.44693327e+00 5.39118671e+00 5.41625786e+00 5.59774017e+00 5.48167515e+00 5.36584949e+00 5.33123827e+00 5.53930140e+00 5.52861214e+00 5.29926348e+00 5.11595058e+00 5.21939135e+00 5.09110451e+00 4.89787102e+00 4.79123735e+00 5.09082699e+00 5.31634235e+00 5.33446980e+00 5.26884794e+00 5.26191902e+00 5.21878529e+00 5.36581802e+00 5.81275511e+00 6.23689651e+00 6.18974304e+00 5.86947203e+00 5.62831020e+00 5.48877621e+00 5.51499128e+00 5.54832554e+00 5.63899946e+00 5.49443102e+00 5.44888496e+00 5.57075262e+00 5.54014444e+00 5.00535631e+00 4.59282875e+00 4.58994102e+00 5.06792688e+00 5.36984253e+00 5.65059853e+00 5.97812939e+00 6.01564407e+00 5.72147846e+00 5.32093191e+00 5.36824083e+00 5.78503799e+00 5.35765505e+00 4.57807493e+00 4.39945793e+00 4.99279833e+00 5.83737755e+00 5.84928322e+00 5.94624281e+00 6.06367254e+00 5.40196609e+00 4.34837103e+00 3.92260885e+00 4.25755167e+00 5.00603533e+00 5.05322552e+00 5.13671780e+00 5.32227468e+00 5.45378780e+00 5.55220461e+00 5.47362328e+00 5.49637079e+00 5.16284657e+00 5.10268974e+00 5.40550184e+00 6.03419876e+00 6.88678217e+00 7.33313608e+00 7.16268635e+00 6.43065548e+00 5.86980915e+00 6.26368570e+00 6.48269558e+00 5.78155136e+00 4.73061037e+00 4.12000227e+00 4.98426533e+00 5.86437893e+00 6.28143454e+00 5.71153355e+00 5.37391424e+00 5.33631468e+00 5.52692604e+00 6.72141123e+00 7.80840492e+00 6.06057978e+00 2.99399686e+00 2.19838500e+00 3.69834518e+00 5.53303051e+00 5.36909676e+00 5.18555784e+00 4.91721201e+00 5.08625889e+00 5.35258341e+00 5.14593410e+00 4.15856218e+00 3.00074792e+00 3.82536817e+00 5.93200827e+00 7.39231825e+00 6.38824177e+00 4.85631657e+00 4.17794418e+00 4.22449017e+00 4.16612339e+00 3.77976894e+00 2.64509034e+00 1.85693657e+00 2.66180778e+00 4.00396919e+00 4.50366497e+00 3.87916112e+00 3.87140322e+00 4.54042387e+00 4.58598900e+00 4.39822149e+00 4.23389339e+00 3.97469521e+00 3.57223558e+00 2.99863434e+00 3.64080453e+00 4.23348665e+00 4.62454081e+00 5.42269897e+00 6.83243752e+00 8.79638863e+00 9.66832066e+00 8.30281067e+00 6.58113527e+00 5.35725355e+00 5.26798344e+00 5.40688419e+00 5.88701820e+00 5.90216780e+00 5.51604128e+00 5.09024525e+00 4.93420076e+00 4.64537907e+00 5.71587706e+00 7.15352106e+00 7.59620142e+00 6.26031733e+00 4.52245855e+00 4.34869576e+00 4.25045538e+00 3.98822427e+00 3.33194304e+00 3.16985679e+00 3.48882127e+00 4.03523159e+00 4.52781677e+00 4.73184013e+00 4.58766079e+00 3.32410717e+00 2.65925384e+00 2.65429449e+00 3.08443499e+00 3.62122393e+00 3.35046744e+00 2.87897873e+00 2.50548291e+00 2.90817857e+00 3.89554954e+00 4.73133326e+00 4.97422361e+00 4.72222424e+00 3.76600647e+00 2.54629087e+00 1.94291806e+00 3.13721561e+00 4.34334469e+00 5.13686705e+00 5.40390205e+00 6.00785112e+00 6.59414434e+00 6.23526573e+00 6.20109367e+00 1.05097318e+00 -9.16026878e+00 -2.41640148e+01 -9.30012703e+00 -2.09403778e+02 -1.15877014e+03 -84771944. 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. 0. 0. 0. 0. 0. 0. 2.87524922e+04 -1.71477844e+02 -2.59168930e+01 -1.05625172e+01 6.23750687e+00 7.19191313e+00 7.84965515e+00 2.34115410e+00 4.35542107e+00 5.04718351e+00 4.50128222e+00 1.43094862e+00 -1.89114571e+00 -2.54882884e+00 -1.51416445e+00 -2.04907343e-01 -9.94298756e-01 -1.20443070e+00 -1.15727103e+00 -6.90184474e-01 -1.06236018e-01 -1.82080850e-01 5.12535512e-01 1.61148632e+00 2.06473660e+00 1.87319553e+00 1.35474133e+00 2.51488280e+00 3.21252465e+00 3.77251816e+00 3.85577440e+00 3.45776772e+00 3.44368100e+00 3.17330456e+00 3.88943696e+00 4.26108646e+00 4.53942108e+00 3.77955174e+00 3.84469247e+00 4.00839615e+00 4.63868380e+00 3.54495144e+00 2.72092533e+00 2.32995796e+00 3.05428195e+00 3.95219040e+00 4.70706177e+00 5.55212927e+00 4.86733198e+00 5.51333570e+00 5.84088087e+00 6.23256207e+00 5.10019255e+00 3.57692623e+00 3.71325326e+00 4.24311638e+00 4.15342426e+00 3.96997309e+00 3.76689100e+00 4.12587261e+00 4.24813557e+00 3.66024017e+00 3.54582453e+00 5.39487183e-01 -2.02805758e+00 -2.87524223e+00 -2.16689968e+00 -1.29933655e+00 -3.22009850e+00 -4.41604376e+00 -2.77155566e+00 -7.01586246e-01 2.05004144e+00 2.68142772e+00 3.21061707e+00 5.07466459e+00 7.30831480e+00 9.37463284e+00 9.18106842e+00 6.66528463e+00 4.45649481e+00 2.95599580e+00 2.60190916e+00 2.84186459e+00 4.57685143e-01 -1.71625102e+00 -4.71771955e+00 -5.40604496e+00 -4.28655243e+00 -2.12975788e+00 1.63002402e-01 5.57350159e-01 -3.28761339e-02 -2.65673304e+00 -4.79492712e+00 -3.80584240e+00 -1.22859514e+00 7.70562887e-01 2.48266831e-01 -6.95794046e-01 -1.41089714e+00 -2.45041800e+00 3.83461535e-01 3.46067739e+00 5.01772642e+00 3.73937273e+00 1.29147160e+00 1.33476758e+00 6.37288809e-01 -8.84588659e-01 -2.18995929e+00 -4.33741045e+00 -4.16024542e+00 -1.64213097e+00 1.83038831e+00 5.04692173e+00 4.76747131e+00 3.92748284e+00 2.80856657e+00 2.43186617e+00 3.22243738e+00 3.50739646e+00 3.24027157e+00 2.41574597e+00 1.79090130e+00 1.20163226e+00 1.02366447e+00 1.00527763e+00 6.80327773e-01 -2.32541800e+00 -5.42317581e+00 -5.55652571e+00 -3.32130480e+00 -5.75373232e-01 -2.23732352e+00 -4.09043455e+00 -6.86220551e+00 -7.47855806e+00 -5.54677439e+00 -2.34673905e+00 6.09457493e-01 1.39340889e+00 1.40508425e+00 1.56545508e+00 1.71226406e+00 2.19788718e+00 2.59682178e+00 2.32028270e+00 1.19784403e+00 7.05397069e-01 1.00495839e+00 9.88252521e-01 4.67144668e-01 -7.83846736e-01 -3.46517253e+00 -6.30809832e+00 -5.86213255e+00 -3.07635808e+00 -1.96590289e-01 -2.74924994e+00 -5.50580835e+00 -7.61642742e+00 -7.80889750e+00 -8.40522861e+00 -8.76377106e+00 -6.42759562e+00 -4.59497833e+00 -1.63366973e+00 -1.18671250e+00 -3.45218122e-01 -9.64308977e-02 -1.08208632e+00 -1.12978625e+00 -1.24947846e+00 -9.45823789e-01 -1.61889625e+00 -1.10459709e+00 2.91126990e+00 6.42912483e+00 6.28622150e+00 2.75811601e+00 -3.20578724e-01 -1.21813405e+00 -1.39862192e+00 -5.80224037e-01 1.02686834e+00 -6.29355252e-01 -3.88415861e+00 -4.51731586e+00 -2.37010407e+00 2.14329287e-01 -4.70442355e-01 -1.19224298e+00 -1.49062145e+00 -8.98144066e-01 -1.12140501e+00 -1.21065438e+00 -1.75650811e+00 -1.82464111e+00 -1.87684333e+00 -1.85532868e+00 -1.78551686e+00 4.24081445e-01 2.92046142e+00 2.92656612e+00 1.14604700e+00 -1.25515938e+00 -1.23746753e-01 -3.22252005e-01 -1.16402316e+00 -1.82592237e+00 -2.02513504e+00 -1.43531847e+00 -1.27139628e+00 -1.02263927e+00 -1.27419925e+00 -1.80607402e+00 -1.44306242e+00 -9.16380525e-01 -8.45463693e-01 -7.19534814e-01 -7.85053015e-01 5.30889817e-03 -2.33290359e-01 -5.77649534e-01 -8.81122470e-01 -5.48799098e-01 1.43402803e+00 2.81188607e+00 2.78882170e+00 1.61476254e+00 7.49520734e-02 6.28563583e-01 1.81145251e-01 1.03964531e+00 1.60795081e+00 1.85260642e+00 1.23399448e+00 3.64381939e-01 1.24353206e+00 1.47077012e+00 1.23953295e+00 -1.34837061e-01 -1.36283052e+00 -1.57875884e+00 5.86412251e-01 3.10613203e+00 3.94966030e+00 1.94416440e+00 -3.92297530e+00 -7.80029392e+00 -7.66364908e+00 -4.29573536e+00 -1.73260629e+00 -4.79653120e+00 -7.01108408e+00 -6.41854429e+00 -3.06760335e+00 -5.83072782e-01 -6.49229646e-01 -7.81410098e-01 -1.06343639e+00 -1.49203515e+00 -1.06996226e+00 -6.59060657e-01 -7.70324647e-01 -1.78130591e+00 -2.88744378e+00 -1.36169732e+00 5.33327758e-02 5.22815168e-01 -1.62320125e+00 -3.28126121e+00 -3.40833759e+00 -3.31113124e+00 -3.43497753e+00 -3.38010287e+00 -3.74866891e+00 -3.47562504e+00 -5.20402765e+00 -6.40648603e+00 -5.85615158e+00 -3.40143013e+00 -8.56209219e-01 -7.46629477e-01 -1.35106349e+00 -2.46928668e+00 -2.97087526e+00 -1.08940208e+00 1.48729026e+00 1.46257722e+00 -4.88232136e-01 -2.83489656e+00 -1.98310435e+00 -1.81460059e+00 -1.87382555e+00 -2.49844790e+00 -4.82458973e+00 -7.28905964e+00 -7.21424913e+00 -5.24328279e+00 -2.18098164e+00 -2.17774367e+00 -2.33576274e+00 -2.53201342e+00 -2.58206582e+00 -4.25273323e+00 -6.86232662e+00 -7.41158485e+00 -6.39112043e+00 -3.89198518e+00 -4.05993986e+00 -3.66713691e+00 -3.52848697e+00 -2.85654473e+00 -3.30442333e+00 -4.01941776e+00 -4.82222319e+00 -4.22913885e+00 -3.50062418e+00 -2.99435663e+00 -3.02258277e+00 -2.43262458e+00 -1.71754611e+00 -1.17992091e+00 -6.89525425e-01 -1.22778666e+00 -3.71040821e+00 -6.96523046e+00 -9.08658981e+00 -9.57511044e+00 -9.24295425e+00 -8.55626774e+00 -5.02580643e+00 -3.42104435e+00 -1.76770377e+00 -2.59668422e+00 -2.59896350e+00 -4.32486153e+00 -6.68538475e+00 -6.11381054e+00 -5.01315403e+00 -1.38967800e+00 4.46544409e-01 9.90761340e-01 -3.39539289e-01 -2.53029060e+00 -3.17437220e+00 -4.45279646e+00 -6.89523458e+00 -8.39618111e+00 -7.01778889e+00 -4.32633972e+00 -1.32236373e+00 -2.98311067e+00 -5.14606285e+00 -6.50630379e+00 -6.19136333e+00 -4.43969154e+00 -3.21167922e+00 -1.22579873e+00 -1.21249008e+00 -1.65198517e+00 -1.66559887e+00 -1.64978671e+00 -1.77354336e+00 -2.01129818e+00 -2.45617628e+00 -2.58831930e+00 -2.82034326e+00 -3.10710454e+00 -3.71972203e+00 -6.00022507e+00 -8.57511520e+00 -6.79385471e+00 -3.31985664e+00 -2.39904618e+00 -6.11649942e+00 -8.15865135e+00 -6.98674250e+00 -4.87582922e+00 -6.38263035e+00 -7.65160894e+00 -7.85092831e+00 -6.31615019e+00 -4.39994526e+00 -4.50129509e+00 -4.83393574e+00 -5.90531492e+00 -5.83873224e+00 -5.31504154e+00 -4.32120895e+00 -3.98556733e+00 -3.99931955e+00 -4.77091551e+00 -4.87889385e+00 -5.55325222e+00 -6.32348442e+00 -7.93776751e+00 -5.85936451e+00 -2.36531949e+00 -2.61131978e+00 -6.08763790e+00 -8.29205227e+00 -5.88417149e+00 -4.12810564e+00 -5.03444672e+00 -6.12748337e+00 -4.68514824e+00 -2.25423193e+00 -9.27079797e-01 -1.51074541e+00 -2.01451325e+00 -3.61949992e+00 -5.70557880e+00 -5.83646822e+00 -3.79212284e+00 -3.49159336e+00 -6.20860672e+00 -6.53622484e+00 -4.90869570e+00 -2.57790136e+00 -2.60751581e+00 -2.79183650e+00 -1.72410154e+00 -5.41362047e-01 -1.82693875e+00 -4.25833893e+00 -6.20039511e+00 -5.22983932e+00 -4.50111961e+00 -4.51784420e+00 -4.58812284e+00 -4.67000628e+00 -4.70260334e+00 -4.48097038e+00 -3.45858717e+00 -3.50647688e+00 -4.85190582e+00 -6.64591122e+00 -7.05709553e+00 -6.35844231e+00 -7.26963234e+00 -9.22321606e+00 -8.30073833e+00 -5.43355560e+00 -2.39647532e+00 -2.11645770e+00 -3.33970737e+00 -3.16279769e+00 -2.86199188e+00 -3.11733413e+00 -4.25094318e+00 -5.44776249e+00 -5.39018297e+00 -4.80182648e+00 -4.33395481e+00 -3.34346390e+00 -3.13074231e+00 -3.33203721e+00 -3.60298061e+00 -3.57557917e+00 -3.49353886e+00 -4.92894173e+00 -5.95688534e+00 -5.44242811e+00 -4.15102816e+00 -3.79952121e+00 -4.83162260e+00 -4.17868280e+00 -2.90871501e+00 -3.28162169e+00 -6.05899191e+00 -9.16894341e+00 -9.66891193e+00 -8.55414581e+00 -8.02222538e+00 -8.47135735e+00 -7.93954039e+00 -6.99029303e+00 -6.11944437e+00 -6.37291813e+00 -6.25058317e+00 -6.57459545e+00 -7.50701618e+00 -7.44855118e+00 -6.19754219e+00 -4.44213915e+00 -5.13147926e+00 -6.67389154e+00 -6.94446898e+00 -5.52610397e+00 -5.54192066e+00 -6.87604046e+00 -5.92702293e+00 -3.05549216e+00 -1.19230044e+00 -2.33372331e+00 -3.93949628e+00 -3.43498254e+00 -2.25371170e+00 -2.02883863e+00 -2.92585111e+00 -3.53128266e+00 -2.88636112e+00 -2.59593439e+00 -2.94105935e+00 -3.93082333e+00 -5.42579556e+00 -7.00867796e+00 -7.83319139e+00 -7.81958961e+00 -5.68454838e+00 -3.94698930e+00 -3.11319399e+00 -4.16382694e+00 -4.99754238e+00 -4.99222136e+00 -4.87052965e+00 -4.20248604e+00 -2.97223401e+00 -3.30183721e+00 -4.44336653e+00 -5.61696482e+00 -5.61726046e+00 -5.62960386e+00 -6.75619078e+00 -7.62201262e+00 -7.40146732e+00 -6.36081934e+00 -5.61624146e+00 -5.55562639e+00 -5.46810865e+00 -5.42062092e+00 -5.73964977e+00 -5.98692513e+00 -5.93763208e+00 -5.61976385e+00 -5.40318775e+00 -5.23714256e+00 -5.21308851e+00 -5.36334991e+00 -6.22431374e+00 -7.36469507e+00 -7.34319162e+00 -6.67803097e+00 -6.49423599e+00 -7.19407463e+00 -7.08046913e+00 -6.46885872e+00 -5.81561756e+00 -6.56757307e+00 -7.21999645e+00 -6.98077297e+00 -6.18239260e+00 -5.07236958e+00 -5.00993633e+00 -5.03763914e+00 -5.68960524e+00 -6.39044619e+00 -6.44840193e+00 -5.86457682e+00 -5.92067242e+00 -6.61380911e+00 -6.76762152e+00 -6.24001837e+00 -5.46199894e+00 -5.95885706e+00 -6.57268715e+00 -6.49360275e+00 -5.59188461e+00 -4.90132141e+00 -5.28146076e+00 -5.96860886e+00 -6.09500170e+00 -6.08867264e+00 -5.88898706e+00 -5.92227936e+00 -6.04753304e+00 -6.08719730e+00 -6.56720877e+00 -6.79779863e+00 -6.66546631e+00 -6.26328564e+00 -5.85096264e+00 -5.88796520e+00 -5.82896614e+00 -5.82387066e+00 -5.83348417e+00 -5.76503420e+00 -5.80123615e+00 -5.71202564e+00 -5.71635437e+00 -5.63498878e+00 -5.28499746e+00 -5.03967714e+00 -5.39170122e+00 -5.98259163e+00 -6.18697500e+00 -5.82615137e+00 -5.54151821e+00 -5.53540325e+00 -5.57057381e+00 -5.60209513e+00 -5.57243204e+00 -5.64876127e+00 -5.69302368e+00 -5.73671722e+00 -5.85153246e+00 -6.06710482e+00 -6.72626257e+00 -8.02966404e+00 -7.08432388e+00 -6.53393459e+00 -2.43073330e+01 -5.94676666e+01 -7.87669850e+06 -34023064. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 402289120. 226802656. 4.19350967e+01 -5.99763203e+00 -1.04159384e+01 -4.88692379e+00 -4.38398218e+00 -3.68879008e+00 -3.39351535e+00 -3.20440459e+00 -3.08741426e+00 -3.06697989e+00 -3.09243608e+00 -3.12347627e+00 -3.16469407e+00 -3.17010760e+00 -3.19486094e+00 -3.14326859e+00 -3.07506943e+00 -3.00409365e+00 -3.00335097e+00 -3.11208606e+00 -3.21924853e+00 -3.30074167e+00 -3.32019639e+00 -3.24351263e+00 -3.23050618e+00 -3.21359587e+00 -3.12051010e+00 -3.06676912e+00 -3.09385252e+00 -3.26072645e+00 -3.37940311e+00 -3.39324880e+00 -3.29889655e+00 -3.11358976e+00 -3.04435468e+00 -3.05104256e+00 -3.06237721e+00 -3.07042837e+00 -3.10348845e+00 -3.23957348e+00 -3.35439706e+00 -3.27599382e+00 -3.12635660e+00 -3.04362535e+00 -3.13689137e+00 -3.11811137e+00 -3.06616092e+00 -3.13404441e+00 -3.16336989e+00 -3.16683578e+00 -3.10026789e+00 -2.99954820e+00 -2.93338728e+00 -2.90882158e+00 -3.12969446e+00 -3.42589498e+00 -3.49729872e+00 -3.33383822e+00 -3.00578856e+00 -2.97021914e+00 -3.16738176e+00 -3.43911576e+00 -3.41803074e+00 -3.26229382e+00 -3.18735600e+00 -3.25628304e+00 -3.25556087e+00 -3.05723977e+00 -2.78355908e+00 -2.88341403e+00 -2.96456647e+00 -3.03003860e+00 -3.04599023e+00 -3.03562069e+00 -3.17046475e+00 -3.06934643e+00 -2.93780303e+00 -2.73206782e+00 -2.71938324e+00 -2.94001961e+00 -3.22214794e+00 -3.44988966e+00 -3.48941779e+00 -3.22739387e+00 -3.16563964e+00 -3.11863756e+00 -2.93550134e+00 -2.64982629e+00 -2.61302376e+00 -3.00912309e+00 -3.37661982e+00 -3.38079071e+00 -2.98114848e+00 -2.57315254e+00 -2.52357054e+00 -2.58041239e+00 -2.57040191e+00 -2.54269814e+00 -2.64517379e+00 -2.82581782e+00 -2.94215250e+00 -2.83192992e+00 -2.60783982e+00 -2.32287598e+00 -2.23869181e+00 -2.54166436e+00 -3.00373101e+00 -3.38461590e+00 -3.11026931e+00 -2.73813581e+00 -2.65252233e+00 -2.64046860e+00 -2.55339336e+00 -2.56756783e+00 -2.68817115e+00 -2.88094926e+00 -2.82243395e+00 -2.47225070e+00 -2.26128602e+00 -2.14857841e+00 -2.41528010e+00 -2.68445015e+00 -3.07232928e+00 -3.29106879e+00 -5.01192427e+00 -1.40691376e+01 -8.83174438e+01 -1.59586288e+02 -3.83397560e+01 -3.85518646e+01 -3.23851013e+01 -2.46994915e+01 1.73456421e+02 1.05237846e+02 1.93300610e+01 -7.93258619e+00 -2.19828739e+01 -9.86080780e+01 -1.64293640e+02 -3.54625244e+01 -2.78799801e+01 -1.57007484e+01 -8.38701916e+00 -1.14907951e+01 -1.70538197e+01 -1.91669521e+01 -2.32660389e+01 -2.48564453e+01 -2.24929504e+01 1.70708084e+02 1.08026245e+02 2.11311016e+01 6.62410402e+00 -4.03474426e+00 -3.44867826e+00 -3.59577990e+00 -2.37953234e+00 -2.76165581e+00 -2.32367659e+00 -2.08886743e+00 -2.41989303e+00 -2.75160050e+00 -2.81157470e+00 -2.85152316e+00 -2.90063977e+00 -3.25402093e+00 -3.49638104e+00 -3.49413037e+00 -2.85824633e+00 -2.12007117e+00 -1.98595357e+00 -2.01977897e+00 -1.97649872e+00 -2.03889084e+00 -2.16843653e+00 -2.73629260e+00 -2.88016582e+00 -2.59810424e+00 -1.99562800e+00 -1.89409935e+00 -2.26174140e+00 -2.47183895e+00 -2.60597682e+00 -2.62399602e+00 -2.64559960e+00 -2.64485121e+00 -2.70697021e+00 -2.52891397e+00 -2.65336013e+00 -2.92070317e+00 -3.60364103e+00 -4.03128910e+00 -3.72293115e+00 -2.67018390e+00 -1.62006283e+00 -1.52232897e+00 -1.78405464e+00 -1.87286282e+00 -1.95552301e+00 -2.21579289e+00 -2.82135558e+00 -2.92935443e+00 -2.27978086e+00 -1.49773836e+00 -1.29645312e+00 -1.78955281e+00 -2.17630625e+00 -2.14854217e+00 -2.17566347e+00 -2.07504201e+00 -2.24052668e+00 -2.47969627e+00 -2.23061061e+00 -1.82700336e+00 -1.40425444e+00 -2.00955892e+00 -2.44381618e+00 -2.92441130e+00 -2.14841485e+00 -1.72370470e+00 -1.48818028e+00 -1.77045345e+00 -1.94241202e+00 -2.10825086e+00 -2.13834977e+00 -1.97026300e+00 -1.69323397e+00 -1.58029866e+00 -1.53821397e+00 -1.22033441e+00 -1.09748971e+00 -9.33577657e-01 -1.40075421e+00 -2.01158500e+00 -2.63655567e+00 -2.84416938e+00 -2.61052728e+00 -2.04485154e+00 -1.42674506e+00 -8.14722538e-01 -1.75941932e+00 -2.54455924e+00 -2.77342987e+00 -1.80448139e+00 -1.08504391e+00 -1.29072404e+00 -1.53974271e+00 -1.21650064e+00 -1.07620931e+00 -1.32623136e+00 -2.02363873e+00 -2.17955756e+00 -1.84943140e+00 -1.66682756e+00 -1.66845477e+00 -1.87750292e+00 -1.89158535e+00 -1.96224093e+00 -1.85859537e+00 -1.73463941e+00 -2.15935898e+00 -2.22933960e+00 -2.45543265e+00 -1.71016419e+00 -1.25795805e+00 -1.38518846e+00 -2.47431445e+00 -2.79135394e+00 -2.42342830e+00 -2.13674617e+00 -2.46846700e+00 -2.63742328e+00 -2.04818416e+00 -1.58030331e+00 -1.45558751e+00 -1.62812853e+00 -1.67905593e+00 -1.58300698e+00 -1.95093846e+00 -1.99006259e+00 -1.72280777e+00 -1.07011580e+00 -1.28595102e+00 -1.19269049e+00 -9.66139078e-01 -7.43032932e-01 -1.35914421e+00 -1.90036261e+00 -1.82412958e+00 -1.49062943e+00 -1.55803990e+00 -2.00989318e+00 -1.80045986e+00 -1.58157611e+00 -1.44918942e+00 -1.86811435e+00 -2.01032925e+00 -1.67556834e+00 -1.53390801e+00 -1.18125963e+00 -1.36243653e+00 -1.01277137e+00 -8.03039908e-01 -9.39503551e-01 -1.16567826e+00 -1.41838121e+00 -1.24989021e+00 -1.20355654e+00 -8.97926748e-01 -4.67747331e-01 -5.57479084e-01 -8.06909740e-01 -1.05678105e+00 -8.08658481e-01 -5.05080819e-01 -9.09096718e-01 -1.75673461e+00 -1.85815310e+00 -1.30950522e+00 -8.39264035e-01 -1.28003299e+00 -2.02055192e+00 -1.95601094e+00 -1.55078256e+00 -8.42423499e-01 -7.15067327e-01 -5.14526069e-01 -4.56673265e-01 -5.19680560e-01 -6.81512773e-01 -6.12600505e-01 -5.37261009e-01 -7.74858952e-01 -7.85733342e-01 -4.67996418e-01 -4.73538935e-01 -1.22112501e+00 -2.02242374e+00 -1.95071554e+00 -1.66508508e+00 -1.55491364e+00 -1.76977241e+00 -1.33166814e+00 -1.08859289e+00 -1.12080538e+00 -1.54328966e+00 -1.42211759e+00 -1.06840575e+00 -9.93516505e-01 -1.10401273e+00 -1.05919158e+00 -6.84105158e-01 -2.45581880e-01 -5.77809691e-01 -9.73843515e-01 -1.44289792e+00 -1.04763341e+00 -6.35059476e-01 -2.81502195e-02 7.40142941e-01 6.33179963e-01 -5.93123496e-01 -2.01434731e+00 -2.67544031e+00 -2.03216124e+00 -1.62078774e+00 -1.55680478e+00 -1.51637983e+00 -1.87539744e+00 -1.42508233e+00 -1.30823827e+00 -8.97863925e-01 -9.86460626e-01 -1.99769747e+00 -2.26839399e+00 -1.93070030e+00 -5.05889416e-01 3.95332068e-01 -7.51763508e-02 -8.32765102e-01 -1.13896716e+00 -2.95075774e-01 4.41308558e-01 4.15516168e-01 1.89057261e-01 -3.31890672e-01 -8.13689172e-01 -1.09098089e+00 -1.46717060e+00 -1.08045793e+00 -5.81974804e-01 -1.60835490e-01 -1.55412331e-01 -9.84013081e-01 -1.55073559e+00 -2.00151157e+00 -1.66733539e+00 -6.19598210e-01 -5.44313967e-01 -3.42351377e-01 -2.33733967e-01 7.05889821e-01 7.27934122e-01 -5.96067131e-01 -1.45807135e+00 -1.60654235e+00 -9.55282807e-01 -5.58364272e-01 -4.69983488e-01 -1.32957563e-01 -9.75624323e-02 -4.73891914e-01 -7.84923613e-01 -1.20578659e+00 -1.01475775e+00 -1.00417817e+00 -1.02106583e+00 -9.54738438e-01 -8.80904853e-01 -3.76795940e-02 2.14892596e-01 2.57417738e-01 -5.85981496e-02 -9.00755286e-01 -1.28552234e+00 -1.33306217e+00 -2.42712602e-01 6.88111901e-01 6.75495982e-01 4.12253588e-02 -7.59359539e-01 -2.00865045e-01 4.87440705e-01 1.11528981e+00 9.73231792e-01 4.79728848e-01 -1.13194354e-01 -4.89323586e-01 -7.05518901e-01 -3.12795997e-01 2.91897178e-01 5.90018153e-01 2.40894258e-01 -1.08817887e+00 -1.55917752e+00 -1.20371628e+00 -7.49974474e-02 7.43679523e-01 1.56765878e-01 -6.78316414e-01 -1.19104695e+00 -4.41851735e-01 4.30191427e-01 5.44152558e-01 2.66226172e-01 -1.57420859e-01 -7.07246305e-04 2.13702619e-01 -1.03514992e-01 -1.80082351e-01 -9.53239202e-02 2.70578653e-01 2.58376211e-01 -5.66510372e-02 -8.32078159e-02 -7.40499794e-03 4.53890972e-02 1.47529006e-01 -1.99600726e-01 3.69257361e-01 6.99653625e-01 1.38433826e+00 1.07713056e+00 5.05234227e-02 -7.40069807e-01 -9.55283165e-01 1.77120060e-01 1.07112610e+00 1.31397057e+00 1.01236832e+00 3.34134281e-01 1.56874329e-01 3.83746117e-01 7.41580486e-01 1.21416306e+00 8.25699449e-01 2.17150509e-01 -3.94479841e-01 -3.87953520e-01 5.85661948e-01 1.29456723e+00 1.67706251e+00 1.34577119e+00 3.40171963e-01 -4.13430989e-01 -4.21910197e-01 5.72334528e-01 1.45115876e+00 1.11206782e+00 2.79647291e-01 -2.38329232e-01 4.17880535e-01 1.38142967e+00 1.45343101e+00 1.12158585e+00 2.62940288e-01 -1.52278975e-01 -9.95468646e-02 1.61681827e-02 5.10440230e-01 8.70760322e-01 9.16734219e-01 7.10354388e-01 2.59303730e-02 2.01248705e-01 6.69533312e-01 1.08371127e+00 1.83716059e+00 1.23552978e+00 1.08518565e+00 7.87802279e-01 1.38822746e+00 1.62216890e+00 4.83666331e-01 -4.27642604e-03 -3.60868424e-02 1.02178812e+00 1.74334967e+00 1.66017091e+00 1.14434564e+00 2.95417517e-01 -5.40181994e-02 1.82453871e-01 4.03786480e-01 8.89678538e-01 1.00838518e+00 8.36305439e-01 9.06376541e-01 8.17729712e-01 1.53013432e+00 1.57789826e+00 1.60396826e+00 1.42783630e+00 7.72718847e-01 6.32561743e-01 9.66462135e-01 1.89542913e+00 2.34724951e+00 2.07762265e+00 1.51785398e+00 1.05746329e+00 1.47625935e+00 2.18084025e+00 2.47645259e+00 2.20193863e+00 1.63065410e+00 1.37990057e+00 1.29682434e+00 1.15958416e+00 1.12837827e+00 1.05651820e+00 1.09503686e+00 8.27969491e-01 4.73815858e-01 1.02029634e+00 1.97302294e+00 2.59316087e+00 2.35005784e+00 1.39427388e+00 7.43730605e-01 7.49597073e-01 1.51258159e+00 2.05462241e+00 1.81194150e+00 1.37124884e+00 1.21285939e+00 1.46629190e+00 1.58319402e+00 1.29684198e+00 1.00209618e+00 6.66898131e-01 5.31005919e-01 6.43714726e-01 6.02364838e-01 9.51806128e-01 1.18820512e+00 1.25789046e+00 1.39077544e+00 1.02687192e+00 1.20753515e+00 1.21206772e+00 1.50982690e+00 1.48516560e+00 6.50218248e-01 7.36763775e-01 8.39993715e-01 1.57929516e+00 1.89432085e+00 1.80306256e+00 1.71131754e+00 8.46721053e-01 9.34990168e-01 1.54654288e+00 2.19742846e+00 2.37904811e+00 1.52515256e+00 1.42610288e+00 1.57993531e+00 1.52138448e+00 1.30296445e+00 1.10901082e+00 1.79198432e+00 1.95387423e+00 1.31290865e+00 2.29383683e+00 2.91133451e+00 4.34353256e+00 3.97625613e+00 1.34025631e+01 2.01052341e+01 5.59535713e+01 3.08615784e+02 6.92939514e+02 179269984. 6380537. 4.71044650e+06 -810436672. 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. 0. 0. 0. 0. 0. 0. 0. 860252544. 2.88851587e+03 4.42013733e+02 -8.63506393e+01 -7.71113205e+01 -1.07868586e+01 -3.24411273e+00 3.28968577e-02 -1.06663442e+00 2.19389057e+00 2.38118601e+00 2.23705459e+00 2.29912615e+00 2.14479280e+00 2.04274035e+00 2.06603980e+00 2.23393321e+00 2.51339412e+00 2.47501659e+00 2.24602652e+00 2.14067316e+00 2.01378393e+00 2.16369867e+00 2.27993989e+00 2.65117764e+00 2.73653388e+00 2.22447467e+00 1.98747683e+00 2.30675912e+00 2.85262370e+00 2.63887525e+00 2.03077483e+00 1.94213545e+00 2.14731431e+00 2.45362639e+00 2.45816422e+00 2.52303529e+00 2.59534979e+00 2.56302166e+00 2.39874411e+00 2.26712322e+00 2.32793283e+00 2.53643727e+00 2.43446445e+00 2.25143766e+00 1.93214679e+00 1.55419135e+00 1.78104854e+00 2.67463517e+00 3.71441555e+00 3.72147012e+00 2.80865502e+00 2.37617636e+00 2.46120119e+00 2.90795732e+00 2.89516902e+00 2.63927007e+00 2.56126356e+00 2.48819041e+00 2.60440111e+00 2.53823638e+00 2.44637346e+00 2.41947103e+00 2.12948179e+00 1.92217827e+00 1.99266982e+00 2.28086710e+00 2.55861807e+00 2.47753167e+00 2.42750096e+00 2.19520044e+00 1.90000808e+00 1.72586679e+00 1.72111142e+00 2.04660559e+00 2.28459501e+00 2.14286685e+00 2.39318967e+00 2.68979859e+00 3.25673223e+00 3.19845057e+00 2.77071977e+00 2.60361552e+00 2.50342679e+00 2.50505352e+00 2.51661730e+00 2.62707424e+00 2.84945607e+00 2.64309335e+00 2.40063429e+00 2.41209197e+00 2.44730973e+00 2.34008050e+00 2.08554339e+00 2.25136113e+00 2.62440634e+00 2.50910187e+00 2.52191615e+00 2.52893567e+00 2.84361768e+00 2.90274930e+00 2.55208659e+00 2.54251671e+00 2.72010422e+00 3.15235305e+00 3.22932529e+00 2.91005993e+00 2.75090075e+00 2.57397723e+00 2.60567856e+00 2.51135492e+00 2.51164103e+00 2.62744522e+00 2.62973118e+00 2.60882568e+00 2.60782146e+00 2.71556687e+00 2.95607233e+00 2.93295074e+00 2.92188311e+00 2.83497000e+00 2.51100564e+00 2.54253674e+00 2.74182296e+00 3.21554375e+00 3.23766494e+00 2.83035946e+00 2.69704700e+00 2.86644220e+00 3.17677093e+00 3.21015239e+00 2.91583300e+00 2.71441007e+00 2.51725960e+00 2.56393099e+00 2.73576593e+00 2.98877168e+00 3.13234997e+00 2.96250463e+00 2.78000593e+00 2.79036522e+00 2.93248057e+00 3.10313582e+00 3.01183677e+00 2.95018315e+00 2.94351816e+00 2.83488011e+00 2.82330203e+00 2.74272728e+00 2.81754375e+00 2.84554148e+00 2.75031161e+00 2.77531075e+00 2.89595389e+00 3.14979744e+00 3.28317022e+00 3.20702600e+00 3.11509275e+00 2.97577286e+00 2.95584154e+00 2.85581708e+00 2.75926447e+00 2.79489207e+00 2.89424729e+00 2.94475150e+00 2.89707518e+00 2.85504723e+00 2.94697714e+00 3.11592245e+00 3.24921727e+00 3.29523897e+00 3.08467603e+00 3.01934004e+00 3.05671239e+00 3.17262840e+00 3.15166092e+00 3.03668189e+00 3.04982495e+00 3.03467584e+00 3.04172397e+00 3.05214477e+00 3.10233617e+00 3.14927435e+00 3.08197570e+00 3.02879143e+00 3.04401231e+00 3.05444431e+00 3.05362487e+00 3.00243950e+00 2.92963576e+00 2.87979269e+00 2.88885546e+00 3.04238844e+00 3.13796902e+00 3.16316748e+00 3.13927484e+00 3.06612992e+00 3.08763051e+00 3.11913300e+00 3.21428823e+00 3.20257759e+00 3.12915993e+00 3.07757020e+00 3.06315827e+00 3.09228134e+00 3.07678008e+00 3.06692529e+00 3.07922697e+00 3.09988713e+00 3.09967470e+00 3.09579659e+00 3.10375786e+00 3.12962794e+00 3.13648844e+00 3.16078901e+00 3.16315842e+00 3.13552260e+00 3.11252570e+00 3.12013102e+00 3.14503717e+00 3.15493894e+00 3.15352678e+00 3.15834999e+00 3.16102648e+00 3.16031361e+00 3.15649033e+00 3.15430617e+00 3.15566254e+00 3.16387606e+00 3.16832423e+00 3.16146016e+00 3.14909434e+00 3.14419079e+00 3.15541053e+00 3.16382384e+00 3.16127944e+00 3.16693044e+00 3.16354585e+00 3.16054368e+00 3.15257168e+00 3.15959334e+00 3.15415406e+00 3.15492320e+00 3.15036082e+00 3.14320564e+00 3.12445092e+00 3.11469221e+00 3.12529421e+00 3.14242530e+00 3.14494658e+00 3.13370419e+00 3.13947964e+00 3.14043760e+00 3.17645931e+00 3.19588661e+00 3.20064235e+00 3.16822791e+00 3.12670803e+00 3.13556194e+00 3.13594818e+00 3.14095044e+00 3.14564514e+00 3.18407607e+00 3.18286061e+00 3.16840959e+00 3.12975144e+00 3.14054132e+00 3.10644913e+00 3.09432054e+00 3.09618926e+00 3.11538720e+00 3.08028603e+00 3.07199216e+00 3.07996655e+00 3.09581208e+00 3.07972598e+00 3.07633305e+00 3.10718584e+00 3.09192562e+00 3.07810688e+00 3.06653500e+00 3.09624267e+00 3.09032536e+00 3.05370307e+00 3.03240991e+00 3.04376578e+00 3.01846290e+00 2.98533010e+00 2.96702456e+00 3.01978850e+00 3.05369401e+00 3.03709531e+00 3.01097798e+00 3.00458479e+00 3.02171063e+00 3.05783653e+00 3.18752623e+00 3.31077027e+00 3.29974008e+00 3.17145514e+00 3.06817365e+00 3.04035211e+00 3.05206847e+00 3.04265356e+00 3.05520272e+00 3.03024220e+00 3.03579402e+00 3.05957651e+00 3.04979134e+00 2.94676089e+00 2.91580510e+00 2.96170807e+00 3.03765345e+00 3.02114081e+00 3.00694060e+00 3.04528379e+00 3.08523154e+00 3.05182672e+00 3.00619459e+00 2.98989320e+00 3.03282666e+00 2.96284509e+00 2.83439422e+00 2.81396151e+00 2.89301229e+00 3.03359270e+00 3.03317237e+00 3.04181123e+00 3.06149101e+00 2.98335624e+00 2.85200548e+00 2.78725934e+00 2.81027603e+00 2.91204023e+00 2.87355590e+00 2.87433600e+00 2.87977266e+00 2.93125749e+00 2.97071004e+00 2.96892142e+00 2.97740841e+00 2.90350842e+00 2.87696266e+00 2.89485002e+00 2.99582601e+00 3.12279987e+00 3.21677494e+00 3.17424297e+00 3.09065938e+00 3.04246759e+00 3.07775784e+00 3.08798146e+00 2.91081357e+00 2.72356677e+00 2.57137609e+00 2.82608724e+00 3.16041756e+00 3.30521441e+00 3.06881547e+00 2.81787062e+00 2.77204800e+00 2.79961395e+00 3.03449917e+00 3.30822611e+00 3.03921866e+00 2.51480508e+00 2.31441045e+00 2.57065916e+00 2.85788393e+00 2.81756783e+00 2.74756217e+00 2.69425654e+00 2.71883893e+00 2.76856971e+00 2.74994445e+00 2.49637461e+00 2.26564837e+00 2.41806173e+00 2.83952379e+00 3.12281227e+00 2.93346620e+00 2.70542407e+00 2.58845639e+00 2.62705112e+00 2.56981134e+00 2.49303913e+00 2.35889745e+00 2.29546905e+00 2.41066599e+00 2.53719854e+00 2.54208326e+00 2.45025849e+00 2.46269631e+00 2.55920601e+00 2.54523373e+00 2.51389480e+00 2.51016498e+00 2.46277165e+00 2.43181491e+00 2.34017563e+00 2.44141364e+00 2.52842665e+00 2.59804416e+00 2.69544482e+00 2.81783843e+00 2.99189782e+00 3.09332776e+00 3.00895882e+00 2.89058304e+00 2.74613309e+00 2.74921131e+00 2.76804638e+00 2.76409125e+00 2.73326087e+00 2.65024686e+00 2.61329579e+00 2.55284929e+00 2.49925399e+00 2.65456414e+00 2.84923553e+00 2.89535666e+00 2.54203796e+00 2.13332081e+00 2.12581205e+00 2.22604060e+00 2.33033872e+00 2.22344518e+00 2.26034951e+00 2.31148529e+00 2.59736013e+00 2.88891721e+00 2.93030643e+00 2.71486044e+00 2.29934287e+00 2.12466073e+00 2.08023143e+00 2.09690785e+00 2.22844386e+00 2.19346786e+00 2.13810706e+00 2.02878213e+00 2.09439015e+00 2.16541886e+00 2.34071016e+00 2.32871842e+00 2.30736756e+00 2.13639140e+00 1.99150002e+00 2.08893657e+00 2.42192841e+00 2.56607652e+00 2.47482610e+00 2.29271555e+00 2.31085229e+00 2.30128908e+00 2.13803124e+00 5.19917428e-01 1.49926171e-01 -1.15322626e+00 7.86676884e-01 8.18457413e+00 -1.72007471e-01 3.24506798e+01 -1.82783086e+04 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. 0. 0. 0. 0. 0. 0. 5.95277344e+04 -2.67634796e+02 1.49732620e+02 1.22204720e+02 3.88568039e+01 1.96772938e+01 9.47439384e+00 3.49454117e+00 5.17938089e+00 2.35069966e+00 2.03385067e+00 1.49515831e+00 9.63468552e-01 8.80999923e-01 1.09592736e+00 1.26498818e+00 1.13424385e+00 1.08902025e+00 1.17049706e+00 1.27281713e+00 1.30167067e+00 1.22367072e+00 1.05600846e+00 9.71261382e-01 1.05171096e+00 1.23499370e+00 1.34368277e+00 1.46340358e+00 1.54671311e+00 1.69030440e+00 1.73474050e+00 1.68071294e+00 1.73385334e+00 1.69391119e+00 1.86236167e+00 1.84083116e+00 1.84418881e+00 1.65777576e+00 1.49652958e+00 1.43765390e+00 1.50057590e+00 1.54509473e+00 1.54775226e+00 1.46053469e+00 1.52380502e+00 1.62964475e+00 1.72154438e+00 1.83486331e+00 1.71994829e+00 1.81614459e+00 1.91648638e+00 1.91611457e+00 1.71531057e+00 1.39804149e+00 1.45458007e+00 1.54921436e+00 1.56745446e+00 1.55904043e+00 1.50444162e+00 1.55885208e+00 1.57093775e+00 1.61013782e+00 1.74143219e+00 1.34909701e+00 8.71051550e-01 5.82684278e-01 6.68676674e-01 8.23903561e-01 5.04962385e-01 1.97748959e-01 3.30809683e-01 6.26077652e-01 1.07269692e+00 1.16414905e+00 1.21419203e+00 1.50926328e+00 1.90271473e+00 2.25672412e+00 2.25490952e+00 1.84398198e+00 1.49209857e+00 1.28422463e+00 1.25571859e+00 1.33980536e+00 9.51025844e-01 2.96845287e-01 -8.21431801e-02 -2.63117582e-01 1.61287546e-01 2.75881648e-01 6.10333264e-01 6.40995443e-01 6.84940279e-01 3.83201122e-01 9.10283178e-02 1.75960436e-01 4.94400680e-01 7.43746221e-01 6.17582262e-01 4.92870063e-01 3.31993192e-01 1.59379765e-01 5.90513289e-01 1.14550996e+00 1.34397829e+00 1.10194242e+00 7.04563022e-01 7.11633503e-01 6.71132684e-01 4.43744004e-01 2.23278329e-01 -1.13443278e-01 -5.33698760e-02 4.04602170e-01 9.06341553e-01 1.35497391e+00 1.22548676e+00 1.07145131e+00 8.69034350e-01 8.40385258e-01 9.35941100e-01 9.26745176e-01 7.69322157e-01 6.46734059e-01 6.50255978e-01 6.68791175e-01 7.45507896e-01 7.26593554e-01 8.13273668e-01 2.85914630e-01 -2.76342899e-01 -4.48558092e-01 -2.57680491e-02 5.16054213e-01 2.68069565e-01 -8.04749802e-02 -5.69448590e-01 -7.18292832e-01 -4.44245398e-01 -6.61445260e-02 3.25323939e-01 3.11753064e-01 3.73624384e-01 4.87582892e-01 6.42879069e-01 7.95493066e-01 8.14304650e-01 7.21427441e-01 4.47858155e-01 3.63145411e-01 3.32905143e-01 3.16600442e-01 1.28973886e-01 -4.60322686e-02 -4.68045801e-01 -7.76197195e-01 -7.11805463e-01 -3.21583807e-01 1.24870837e-01 -2.95215368e-01 -6.23723328e-01 -1.03128672e+00 -1.11628485e+00 -1.33234215e+00 -1.46762145e+00 -1.08460045e+00 -7.23036587e-01 -1.05827145e-01 -4.69772443e-02 -5.07966336e-03 -8.96594450e-02 -2.17407331e-01 -9.63719487e-02 -9.86860916e-02 -4.86437678e-02 -1.92138210e-01 -8.99239480e-02 4.85988945e-01 9.43855286e-01 8.76873195e-01 3.81643951e-01 -4.38420251e-02 -2.84768969e-01 -4.39771712e-01 -4.53349769e-01 -1.39516890e-01 -3.61495316e-01 -8.14832509e-01 -9.26350176e-01 -5.72052896e-01 -1.66291445e-02 -5.88900223e-02 -5.14619276e-02 -1.11880511e-01 -5.34241572e-02 -9.70575064e-02 -1.25125021e-01 -1.91567466e-01 -2.20454529e-01 -2.54144877e-01 -2.46729746e-01 -2.93139696e-01 -3.05439625e-02 2.96002448e-01 2.90503263e-01 -8.95338785e-03 -4.22334939e-01 -2.92886078e-01 -3.35078090e-01 -4.66240823e-01 -6.44720376e-01 -6.27736986e-01 -5.40157259e-01 -4.70395476e-01 -4.24539179e-01 -4.15221632e-01 -4.83472049e-01 -4.22730774e-01 -3.54716957e-01 -3.53989393e-01 -4.09170747e-01 -3.15093368e-01 -1.73339471e-01 -2.22824484e-01 -3.70477170e-01 -4.78616685e-01 -4.56576943e-01 -1.69949308e-01 -2.20783297e-02 -1.75241511e-02 -2.57681221e-01 -4.28121418e-01 -2.68506497e-01 -2.77387351e-01 -1.96875155e-01 -1.22447632e-01 -1.78732321e-01 -1.92431092e-01 -3.67372811e-01 -2.25531250e-01 -2.14302987e-01 -1.67081654e-01 -3.79980206e-01 -5.90821505e-01 -7.21031547e-01 -3.09509277e-01 4.13483940e-02 7.36334100e-02 -2.92766243e-01 -1.10412121e+00 -1.57499480e+00 -1.57666171e+00 -1.15074730e+00 -1.00283277e+00 -1.71184087e+00 -1.79654646e+00 -1.36708081e+00 -6.06080234e-01 -4.31091726e-01 -5.09086788e-01 -5.49846292e-01 -6.18512869e-01 -7.99737394e-01 -7.89099395e-01 -7.22612381e-01 -7.46585786e-01 -9.35043752e-01 -1.20850658e+00 -1.09998274e+00 -8.59213650e-01 -7.32316792e-01 -9.36658084e-01 -1.15041757e+00 -1.09139049e+00 -1.36159372e+00 -1.70813811e+00 -1.87504482e+00 -1.75865054e+00 -1.61512589e+00 -1.86722088e+00 -1.92150915e+00 -1.88240778e+00 -1.58594155e+00 -1.39906061e+00 -1.26080215e+00 -1.37036097e+00 -1.48973513e+00 -1.58521760e+00 -1.25584769e+00 -7.76063323e-01 -7.55156994e-01 -1.05261564e+00 -1.41826403e+00 -1.37865770e+00 -1.48332155e+00 -1.34977174e+00 -1.37391937e+00 -1.62208581e+00 -2.12971282e+00 -2.17851591e+00 -1.88743448e+00 -1.34777868e+00 -1.38926530e+00 -1.38224959e+00 -1.39590311e+00 -1.22375751e+00 -1.41259110e+00 -1.84281075e+00 -2.00247860e+00 -1.90082943e+00 -1.53007972e+00 -1.59064233e+00 -1.51710176e+00 -1.58896625e+00 -1.54227841e+00 -1.66363788e+00 -1.80751157e+00 -1.79455447e+00 -1.67347002e+00 -1.46334004e+00 -1.48594534e+00 -1.52451992e+00 -1.39801300e+00 -1.27857137e+00 -9.25872326e-01 -7.14255214e-01 -7.64511228e-01 -1.35954130e+00 -2.06544828e+00 -2.40181065e+00 -2.41482806e+00 -2.38374114e+00 -2.22234678e+00 -1.84795833e+00 -1.64292312e+00 -1.44434869e+00 -1.51054096e+00 -1.43764246e+00 -1.75059783e+00 -2.11739159e+00 -2.10434604e+00 -1.93955314e+00 -1.36926293e+00 -1.00343049e+00 -8.86538625e-01 -1.06378913e+00 -1.51129901e+00 -1.94599342e+00 -2.53139138e+00 -2.96928287e+00 -2.82224679e+00 -2.37490916e+00 -1.92420208e+00 -1.59383798e+00 -1.96075213e+00 -2.43713498e+00 -2.64859056e+00 -2.40507388e+00 -1.92773926e+00 -1.60817921e+00 -1.46701002e+00 -1.51402605e+00 -1.72436130e+00 -1.62279725e+00 -1.67037606e+00 -1.66359651e+00 -1.69228542e+00 -1.76733744e+00 -1.81840229e+00 -1.86497521e+00 -1.91696036e+00 -1.97512066e+00 -2.40244031e+00 -2.79247665e+00 -2.58696365e+00 -2.01970577e+00 -2.00128317e+00 -2.68616509e+00 -3.11853838e+00 -2.69992042e+00 -2.21024132e+00 -2.23900986e+00 -2.52217937e+00 -2.56812406e+00 -2.41533256e+00 -2.21121216e+00 -2.21011496e+00 -2.24683666e+00 -2.42146087e+00 -2.42246699e+00 -2.36545157e+00 -2.20147634e+00 -2.13680696e+00 -2.16823745e+00 -2.24857926e+00 -2.29783940e+00 -2.38966990e+00 -2.48260570e+00 -2.70839071e+00 -2.41221309e+00 -1.97966111e+00 -2.08466077e+00 -2.54262495e+00 -2.85840106e+00 -2.49738169e+00 -2.28805113e+00 -2.56410933e+00 -2.90837383e+00 -2.56088638e+00 -1.89804220e+00 -1.42822087e+00 -1.64175272e+00 -1.98324692e+00 -2.48219490e+00 -2.76590800e+00 -2.67191505e+00 -2.20019388e+00 -2.18591452e+00 -2.69817734e+00 -2.83408475e+00 -2.58600712e+00 -2.18036985e+00 -2.13995051e+00 -2.21674538e+00 -2.12420130e+00 -1.85127485e+00 -2.13204145e+00 -2.55427742e+00 -2.94078803e+00 -2.72606993e+00 -2.53238606e+00 -2.43611813e+00 -2.43712211e+00 -2.45421219e+00 -2.53490615e+00 -2.55405068e+00 -2.37201715e+00 -2.37816548e+00 -2.34639859e+00 -2.41226506e+00 -2.47570777e+00 -2.57312512e+00 -2.94084907e+00 -3.21049547e+00 -2.98173022e+00 -2.39379716e+00 -1.97263992e+00 -2.09429455e+00 -2.41763687e+00 -2.38951874e+00 -2.28095627e+00 -2.16996956e+00 -2.10103250e+00 -2.29694438e+00 -2.47349143e+00 -2.58732891e+00 -2.46247292e+00 -2.28038764e+00 -2.28971076e+00 -2.36441422e+00 -2.43108606e+00 -2.40945864e+00 -2.40500355e+00 -2.63723087e+00 -2.71084690e+00 -2.56161070e+00 -2.42438745e+00 -2.48003840e+00 -2.64594030e+00 -2.49433565e+00 -2.32219839e+00 -2.40919423e+00 -2.83608222e+00 -3.27434492e+00 -3.35901427e+00 -3.21364284e+00 -3.15984273e+00 -3.28240275e+00 -3.20691919e+00 -3.03633094e+00 -2.87326503e+00 -2.90487909e+00 -2.90440869e+00 -3.02680349e+00 -3.27074909e+00 -3.28912854e+00 -3.01370239e+00 -2.64781880e+00 -2.81952310e+00 -3.15370607e+00 -3.20121694e+00 -2.90967512e+00 -2.83726096e+00 -3.03929734e+00 -2.84763622e+00 -2.40408516e+00 -2.15114760e+00 -2.38307905e+00 -2.66217279e+00 -2.61090612e+00 -2.42841148e+00 -2.37398148e+00 -2.49897647e+00 -2.57457542e+00 -2.43874097e+00 -2.41237044e+00 -2.49134874e+00 -2.70408726e+00 -2.93099689e+00 -3.17594886e+00 -3.28007174e+00 -3.25028849e+00 -2.89583945e+00 -2.62651372e+00 -2.52460623e+00 -2.71183896e+00 -2.87888598e+00 -2.87705159e+00 -2.88631725e+00 -2.75568390e+00 -2.59083056e+00 -2.59371281e+00 -2.76827955e+00 -2.90706205e+00 -2.93742394e+00 -2.96165395e+00 -3.16406083e+00 -3.28795004e+00 -3.25234151e+00 -3.08245969e+00 -2.99337792e+00 -2.97399664e+00 -2.96721387e+00 -2.94474268e+00 -3.02309871e+00 -3.04497218e+00 -3.03714275e+00 -2.97829509e+00 -2.96083951e+00 -2.95877886e+00 -2.96035647e+00 -3.01376867e+00 -3.16332674e+00 -3.34817362e+00 -3.33897972e+00 -3.23105121e+00 -3.19635201e+00 -3.29436159e+00 -3.28389263e+00 -3.18981290e+00 -3.10061693e+00 -3.20214915e+00 -3.30020809e+00 -3.27177000e+00 -3.16738820e+00 -2.99623823e+00 -2.97695422e+00 -2.96488547e+00 -3.08123970e+00 -3.19097638e+00 -3.22156024e+00 -3.14474869e+00 -3.13621902e+00 -3.21653080e+00 -3.21680737e+00 -3.15150499e+00 -3.04403567e+00 -3.12895250e+00 -3.23352861e+00 -3.24780321e+00 -3.11072850e+00 -3.00881791e+00 -3.05837727e+00 -3.17965722e+00 -3.20538855e+00 -3.21959400e+00 -3.17866373e+00 -3.17014766e+00 -3.16735458e+00 -3.16487527e+00 -3.23519230e+00 -3.28176427e+00 -3.28258896e+00 -3.23145390e+00 -3.17177582e+00 -3.16266489e+00 -3.16481495e+00 -3.15988493e+00 -3.16885996e+00 -3.15767956e+00 -3.16748857e+00 -3.15652895e+00 -3.15428233e+00 -3.14733243e+00 -3.09576392e+00 -3.05010176e+00 -3.10306048e+00 -3.17729855e+00 -3.21061945e+00 -3.14691472e+00 -3.11747074e+00 -3.12834024e+00 -3.14010167e+00 -3.14840007e+00 -3.14226818e+00 -3.15195870e+00 -3.15289068e+00 -3.21518230e+00 -3.25758982e+00 -3.46239018e+00 -3.81548262e+00 -4.07601118e+00 -4.86160851e+00 -4.65765476e+00 -1.96368217e+01 -4.41984253e+01 -7.87669850e+06 -34023064. 0. 0. 0. 0. 0. 54467284. 45908868. -11309393. 32765716. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 402289120. 226802656. -1.29240341e+02 -4.93974648e+01 -1.52379885e+01 -1.11798029e+01 -1.04512434e+01 -9.58732700e+00 -9.35324001e+00 -9.36875629e+00 -9.49940395e+00 -9.48402500e+00 -9.45145607e+00 -9.42339993e+00 -9.36279869e+00 -9.34372044e+00 -9.27606392e+00 -9.31084156e+00 -9.38494396e+00 -9.52584457e+00 -9.52399540e+00 -9.33632755e+00 -9.12164402e+00 -9.00395203e+00 -9.00865746e+00 -9.14707088e+00 -9.14127922e+00 -9.06771851e+00 -9.20713139e+00 -9.30932999e+00 -9.32669640e+00 -9.01033592e+00 -8.81354427e+00 -8.74009418e+00 -8.90354729e+00 -9.20487976e+00 -9.34613228e+00 -9.35217094e+00 -9.41882896e+00 -9.47484875e+00 -9.40964603e+00 -9.11883831e+00 -8.86306763e+00 -8.97507572e+00 -9.17460632e+00 -9.32563972e+00 -9.10430431e+00 -9.10333824e+00 -9.07348442e+00 -8.96931934e+00 -8.99522305e+00 -9.02377224e+00 -9.11941528e+00 -9.25915527e+00 -9.40217400e+00 -9.47322083e+00 -9.10565281e+00 -8.62674046e+00 -8.52138519e+00 -8.77377987e+00 -9.38578892e+00 -9.42507648e+00 -9.19428635e+00 -8.90475750e+00 -8.89134789e+00 -8.93935490e+00 -8.86498356e+00 -8.76272678e+00 -8.75376797e+00 -9.10884285e+00 -9.53895855e+00 -9.42069626e+00 -9.23617935e+00 -8.95706844e+00 -8.80743408e+00 -8.62555313e+00 -8.59934139e+00 -8.78590107e+00 -9.12544250e+00 -9.33254147e+00 -9.35649395e+00 -9.15108204e+00 -8.79906940e+00 -8.43729401e+00 -8.26759720e+00 -8.63396740e+00 -8.80306435e+00 -8.87709141e+00 -9.19007683e+00 -9.52054214e+00 -9.56274700e+00 -8.91330338e+00 -8.14903545e+00 -7.77364302e+00 -8.27873993e+00 -9.20798492e+00 -9.43828201e+00 -9.34576035e+00 -9.16104221e+00 -9.23851013e+00 -9.23133850e+00 -9.19455814e+00 -8.91640091e+00 -8.77899361e+00 -8.73634243e+00 -8.75488853e+00 -8.47502899e+00 -8.01615429e+00 -7.84058952e+00 -7.96774435e+00 -8.48784447e+00 -8.88871861e+00 -8.76142120e+00 -8.83057880e+00 -8.99419022e+00 -9.16592789e+00 -8.73646355e+00 -8.27795696e+00 -8.21676445e+00 -8.97489548e+00 -9.61474323e+00 -9.63260937e+00 -9.02338982e+00 -8.38987064e+00 -7.88977337e+00 -7.62071991e+00 -7.83001900e+00 -8.07599640e+00 -8.37926102e+00 -8.91460609e+00 -9.24650478e+00 -9.19915485e+00 -8.70679855e+00 -8.12861729e+00 -7.85246086e+00 -8.11537075e+00 -8.71498585e+00 -8.84803295e+00 -8.78709030e+00 -8.62946987e+00 -9.02296638e+00 -9.00911617e+00 -8.50053120e+00 -7.66724586e+00 -7.23051023e+00 -7.46230364e+00 -7.73597956e+00 -7.86871958e+00 -8.12823391e+00 -8.22699070e+00 -7.95988941e+00 -7.65412474e+00 -7.14104128e+00 -7.00221634e+00 -7.12857199e+00 -7.84584904e+00 -8.06352425e+00 -7.67558908e+00 -7.15748787e+00 -7.60825539e+00 -8.51269817e+00 -9.02518177e+00 -8.21924973e+00 -7.45507383e+00 -7.21550751e+00 -7.39600468e+00 -7.41888094e+00 -6.72387838e+00 -6.04825830e+00 -5.74398422e+00 -6.68344069e+00 -8.33497334e+00 -8.65573120e+00 -8.59440041e+00 -8.46364498e+00 -8.55351925e+00 -8.07878876e+00 -7.18971395e+00 -6.64810991e+00 -7.41389513e+00 -7.97633219e+00 -8.23169613e+00 -7.67400885e+00 -6.96713018e+00 -6.89757586e+00 -5.95542955e+00 -6.41449356e+00 -5.77459288e+00 -6.23814058e+00 -6.43329859e+00 -6.62953234e+00 -6.49902153e+00 -5.79775286e+00 -5.15217209e+00 -5.30635166e+00 -6.37003756e+00 -8.10342026e+00 -8.26679611e+00 -7.71572733e+00 -7.35967588e+00 -6.89110231e+00 -6.96090364e+00 -6.43296194e+00 -6.62776899e+00 -7.27694988e+00 -7.64362860e+00 -8.01734638e+00 -7.06928587e+00 -6.74640083e+00 -6.28518581e+00 -6.48314476e+00 -6.76188660e+00 -6.07121801e+00 -4.98885298e+00 -4.86482859e+00 -5.80309200e+00 -6.50441313e+00 -6.53353834e+00 -5.38984871e+00 -5.08239508e+00 -5.29458952e+00 -6.37166595e+00 -6.68120813e+00 -6.72879171e+00 -7.11622047e+00 -7.16384411e+00 -7.45532894e+00 -7.63163471e+00 -7.13191509e+00 -6.64075089e+00 -6.35130167e+00 -7.11031151e+00 -7.46542740e+00 -7.05520439e+00 -6.73118830e+00 -5.82109976e+00 -5.28480053e+00 -4.65944481e+00 -5.12807941e+00 -5.96111441e+00 -6.84360838e+00 -7.11822319e+00 -6.14485216e+00 -5.26035261e+00 -5.18977118e+00 -5.73985243e+00 -5.71074343e+00 -5.20868587e+00 -4.95381403e+00 -5.89825249e+00 -6.42148209e+00 -6.26581144e+00 -5.09432507e+00 -4.45476675e+00 -4.62215424e+00 -4.90430117e+00 -4.86780024e+00 -5.14217138e+00 -5.28597975e+00 -5.16245365e+00 -4.96050835e+00 -4.84707451e+00 -4.59924841e+00 -4.36579132e+00 -4.32449293e+00 -5.38377428e+00 -6.20018291e+00 -5.69424343e+00 -3.95066166e+00 -3.59981871e+00 -4.14634418e+00 -4.62597036e+00 -3.81954980e+00 -3.76580858e+00 -4.51478958e+00 -5.09208727e+00 -4.87031698e+00 -4.77045202e+00 -5.07089233e+00 -5.26781368e+00 -4.71956158e+00 -4.38512754e+00 -4.94743443e+00 -5.48911810e+00 -5.10078955e+00 -5.49076033e+00 -6.08377838e+00 -6.55528545e+00 -5.38543320e+00 -4.40427208e+00 -4.13358641e+00 -4.77809525e+00 -4.80760908e+00 -4.42174482e+00 -4.67413712e+00 -5.32618618e+00 -5.12455797e+00 -3.99871039e+00 -2.35071039e+00 -2.83760667e+00 -2.87903190e+00 -4.08340549e+00 -3.62842917e+00 -4.75610113e+00 -5.08334780e+00 -4.90555286e+00 -4.34598446e+00 -4.30547237e+00 -4.89415407e+00 -5.17702723e+00 -5.29394817e+00 -5.75723410e+00 -5.35605860e+00 -4.85396051e+00 -4.29685163e+00 -4.52253008e+00 -5.19209862e+00 -4.65449667e+00 -3.55395150e+00 -3.35960650e+00 -3.92504525e+00 -4.31149817e+00 -3.72128224e+00 -3.61247683e+00 -4.11630917e+00 -4.23848724e+00 -4.34392214e+00 -4.86914539e+00 -5.71028471e+00 -6.33418798e+00 -5.51681566e+00 -4.66317463e+00 -3.92656565e+00 -3.90361571e+00 -3.77379465e+00 -4.16895866e+00 -5.11871576e+00 -4.26111031e+00 -2.94953084e+00 -2.72945666e+00 -3.52020764e+00 -4.43855810e+00 -3.33377552e+00 -3.16078997e+00 -2.88613868e+00 -3.11451840e+00 -3.11302209e+00 -2.84225178e+00 -3.08321905e+00 -3.17991471e+00 -2.71693659e+00 -2.80892181e+00 -3.14682341e+00 -4.36901951e+00 -3.81667161e+00 -3.20928621e+00 -2.40209484e+00 -2.37403798e+00 -2.45981336e+00 -2.74278355e+00 -3.38966393e+00 -5.18262863e+00 -4.71508551e+00 -2.86037374e+00 -3.12115133e-01 7.58771718e-01 -6.27161920e-01 -1.47118533e+00 -1.55776739e+00 -8.49500954e-01 -8.97572935e-02 -6.51437581e-01 -8.52193654e-01 -1.13033199e+00 -1.30035806e+00 7.55086467e-02 1.60266295e-01 3.72223556e-02 -1.91152489e+00 -3.05526328e+00 -1.90719688e+00 -6.36409044e-01 -5.28222322e-02 -1.43688488e+00 -2.87673330e+00 -2.53870392e+00 -2.13114929e+00 -1.27079165e+00 -3.83917391e-01 -3.81595701e-01 3.07630539e-01 -8.67694736e-01 -1.42129672e+00 -1.91695011e+00 -1.47346830e+00 3.84043247e-01 1.39422596e+00 1.64496195e+00 2.56487757e-01 -1.15948248e+00 -8.69725525e-01 -4.36423957e-01 -5.79294801e-01 -1.88180733e+00 -2.02679563e+00 -2.47311190e-01 9.64300811e-01 1.34932244e+00 3.07715893e-01 -2.61056274e-01 -4.00356352e-01 -9.44275916e-01 -9.47172225e-01 -4.11264688e-01 4.26859967e-02 1.01719272e+00 9.97430921e-01 1.59779644e+00 1.29264569e+00 9.88805652e-01 3.30900818e-01 -1.25303257e+00 -1.68588030e+00 -1.06122017e+00 -3.78659278e-01 1.20689297e+00 1.42792439e+00 1.70070708e+00 -5.29893264e-02 -1.14487696e+00 -1.14144957e+00 4.04115647e-01 1.42815697e+00 8.09450865e-01 -9.11638021e-01 -8.68724465e-01 -7.57095337e-01 -3.39612275e-01 7.22045898e-02 5.84982872e-01 1.64176238e+00 7.72946417e-01 -2.87611723e-01 -7.91766346e-01 -4.00155723e-01 1.89895654e+00 2.93286753e+00 2.88713050e+00 1.28591335e+00 -3.55894834e-01 5.20242691e-01 1.43312681e+00 1.99176645e+00 6.00250542e-01 -7.44350702e-02 5.59671402e-01 1.61194992e+00 1.99130702e+00 1.53799975e+00 1.44268513e+00 1.44894159e+00 1.82035708e+00 1.54055071e+00 2.20042586e+00 1.93925512e+00 2.17846584e+00 1.89214230e+00 1.94509971e+00 1.83700204e+00 1.26289690e+00 1.90973675e+00 1.14297462e+00 3.58157873e-01 -1.01706266e+00 -4.24082547e-01 1.73772454e+00 3.14303946e+00 3.34305215e+00 1.20721054e+00 -2.32477933e-01 -8.06100965e-01 1.88668862e-01 1.39676225e+00 1.96215856e+00 1.23277891e+00 7.15458810e-01 1.06114484e-01 7.00915992e-01 1.92980480e+00 2.92436600e+00 3.50975776e+00 1.69689977e+00 7.82442987e-01 8.26340914e-02 8.42164338e-01 2.47124171e+00 3.36366534e+00 3.60335541e+00 1.88624072e+00 6.69784069e-01 1.25711679e+00 2.41841602e+00 3.89532709e+00 3.28526664e+00 1.75184834e+00 9.72958446e-01 1.04755521e+00 2.66722035e+00 2.93753695e+00 2.78461123e+00 2.45353365e+00 2.55522418e+00 1.70301867e+00 1.72906733e+00 1.76802146e+00 2.63328934e+00 2.09053206e+00 2.00830531e+00 1.71244526e+00 1.81185985e+00 1.48655188e+00 2.17247987e+00 1.87098253e+00 1.70352221e+00 1.18243170e+00 2.69021726e+00 4.12539864e+00 4.48384905e+00 3.02800274e+00 1.88843203e+00 1.81816566e+00 2.71693659e+00 3.94982076e+00 4.79674482e+00 4.40529966e+00 4.15632629e+00 3.81839538e+00 3.79810572e+00 3.77553320e+00 3.12876463e+00 3.37683368e+00 2.18750548e+00 1.99419594e+00 1.93750703e+00 2.46544123e+00 3.75766945e+00 3.66268516e+00 3.19616461e+00 1.55093861e+00 9.56516862e-01 1.51248324e+00 2.88277864e+00 4.09242105e+00 3.54250360e+00 2.33615613e+00 1.87233973e+00 2.36856174e+00 3.26781201e+00 3.78280091e+00 4.09276056e+00 4.31995344e+00 4.40203142e+00 4.45804644e+00 4.26960611e+00 4.96603489e+00 5.45308924e+00 5.41360521e+00 3.82938671e+00 3.29166818e+00 3.60198045e+00 5.14036989e+00 5.60110044e+00 5.09754992e+00 3.97202897e+00 3.44223523e+00 4.35198736e+00 4.77810955e+00 4.87905931e+00 4.13688326e+00 3.92069650e+00 4.42671156e+00 5.07176924e+00 5.49352074e+00 5.63692236e+00 5.29947472e+00 6.17206860e+00 5.75140381e+00 5.34359884e+00 4.57546520e+00 4.79459429e+00 5.09320688e+00 4.76147747e+00 4.64134121e+00 4.90532398e+00 4.84001684e+00 5.49846554e+00 5.32632828e+00 5.24105740e+00 4.38271952e+00 4.03982782e+00 4.87924147e+00 5.40456486e+00 6.59385204e+00 6.11978674e+00 5.37302876e+00 4.60553312e+00 4.41850233e+00 5.37390423e+00 5.22628832e+00 5.04239225e+00 5.34727526e+00 8.44446373e+00 8.69361401e+00 7.66095781e+00 6.00906372e+00 6.98132420e+00 8.85762882e+00 1.98795338e+01 1.63892612e+01 1.90661030e+01 1.73728790e+02 2.64558594e+02 -6.05405762e+02 -3.57975928e+03 -53644572. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 860252544. -3.35480640e+03 -4.75817108e+02 -5.73350105e+01 -3.52324677e+01 -6.74090195e+00 3.15593839e+00 4.63142061e+00 7.85017204e+00 8.26589775e+00 7.91789579e+00 7.67562962e+00 7.46704197e+00 7.67619228e+00 7.58723402e+00 7.46293402e+00 6.94965649e+00 6.84899521e+00 7.38542461e+00 7.98100185e+00 8.50907707e+00 8.84991360e+00 8.73271656e+00 8.17976189e+00 7.43430662e+00 6.95572042e+00 7.69880295e+00 7.86815023e+00 7.56906652e+00 6.44007540e+00 6.69099808e+00 7.53415585e+00 8.04283810e+00 7.77536917e+00 7.29711151e+00 7.27974319e+00 7.65288019e+00 7.64290237e+00 7.70079517e+00 7.69454241e+00 7.60577250e+00 7.25831127e+00 6.93764639e+00 7.23521852e+00 7.28471041e+00 7.91333914e+00 8.80704021e+00 9.21858120e+00 7.91107607e+00 6.19955540e+00 6.06405735e+00 7.54552031e+00 8.24793148e+00 8.00337219e+00 7.26242018e+00 7.34972477e+00 7.79744482e+00 8.04712772e+00 8.07362461e+00 8.01143074e+00 8.47504425e+00 9.00493431e+00 8.98218346e+00 9.04794312e+00 9.11865330e+00 9.19828606e+00 8.74636555e+00 8.43260956e+00 8.60317516e+00 8.79174995e+00 9.14906406e+00 9.46656227e+00 9.67313385e+00 9.81591320e+00 9.41145134e+00 9.11858463e+00 9.51167107e+00 9.39717197e+00 8.81936169e+00 7.35616875e+00 6.80502129e+00 7.34239101e+00 7.91816235e+00 8.52847862e+00 8.68599987e+00 8.69651794e+00 8.46758270e+00 8.25831699e+00 8.47054672e+00 8.66205597e+00 8.54920101e+00 8.49504948e+00 8.59047890e+00 8.92702484e+00 8.94518089e+00 8.64355659e+00 9.05073929e+00 8.93874741e+00 8.93346214e+00 8.35679436e+00 8.28335953e+00 8.91591930e+00 8.94523239e+00 8.56957912e+00 7.82304144e+00 7.80701017e+00 8.50410748e+00 8.79030418e+00 9.06879997e+00 9.08588409e+00 9.26555252e+00 9.32946777e+00 9.19129467e+00 9.10124874e+00 9.09722137e+00 9.07751274e+00 8.93214893e+00 8.70699501e+00 8.82162857e+00 8.89839840e+00 8.74139595e+00 8.94138145e+00 8.98100185e+00 8.86932659e+00 8.34963417e+00 8.30144215e+00 8.91861153e+00 9.16301632e+00 8.82623863e+00 8.38900375e+00 8.37812138e+00 8.96432877e+00 9.09898186e+00 9.21155262e+00 9.18914509e+00 9.13359547e+00 8.96077442e+00 8.62716293e+00 8.75233555e+00 9.02398109e+00 9.04419994e+00 8.90722275e+00 8.61861897e+00 8.79864693e+00 8.94564247e+00 8.96990395e+00 9.16393852e+00 9.16053486e+00 9.28541756e+00 9.15645885e+00 9.13321781e+00 9.24408531e+00 9.26444912e+00 9.19037342e+00 8.93770313e+00 8.74009514e+00 8.85529041e+00 8.96475124e+00 9.16616726e+00 9.24035740e+00 9.31050396e+00 9.45976543e+00 9.47437286e+00 9.44549465e+00 9.35378361e+00 9.37625599e+00 9.43760395e+00 9.35724545e+00 9.12198353e+00 8.91238499e+00 8.83469772e+00 9.15867519e+00 9.29688549e+00 9.24598885e+00 9.09130764e+00 9.14269352e+00 9.30419540e+00 9.26586628e+00 9.33557796e+00 9.37122726e+00 9.41627121e+00 9.32172680e+00 9.25092125e+00 9.31862164e+00 9.38226128e+00 9.35345078e+00 9.36234665e+00 9.42776489e+00 9.51205540e+00 9.62412453e+00 9.65127850e+00 9.69902134e+00 9.48855495e+00 9.36077309e+00 9.29565048e+00 9.28927231e+00 9.39949226e+00 9.36440659e+00 9.33376408e+00 9.18813992e+00 9.18537903e+00 9.29245949e+00 9.37566280e+00 9.42363548e+00 9.40267086e+00 9.43752861e+00 9.47249413e+00 9.45417786e+00 9.42589569e+00 9.40553188e+00 9.40477371e+00 9.37902641e+00 9.33878040e+00 9.34361553e+00 9.31901169e+00 9.32618237e+00 9.37188911e+00 9.40365982e+00 9.39244556e+00 9.35032177e+00 9.34149170e+00 9.34702778e+00 9.33790112e+00 9.33135986e+00 9.33233166e+00 9.33887196e+00 9.34218025e+00 9.33937168e+00 9.32501221e+00 9.31711864e+00 9.33140373e+00 9.35581493e+00 9.36639881e+00 9.33818245e+00 9.31858540e+00 9.32980728e+00 9.33811474e+00 9.34082413e+00 9.33236408e+00 9.33290768e+00 9.31967354e+00 9.31903744e+00 9.30938244e+00 9.31529903e+00 9.33507156e+00 9.36736107e+00 9.37826443e+00 9.34648132e+00 9.29769135e+00 9.30467510e+00 9.32549667e+00 9.33843327e+00 9.30497265e+00 9.24681282e+00 9.19201183e+00 9.17905807e+00 9.22683239e+00 9.29940128e+00 9.28833771e+00 9.27423096e+00 9.26098347e+00 9.26159954e+00 9.23093987e+00 9.23136234e+00 9.24198627e+00 9.26533794e+00 9.25555801e+00 9.29514027e+00 9.34534550e+00 9.32134819e+00 9.28075790e+00 9.27305698e+00 9.27150631e+00 9.26778316e+00 9.21404743e+00 9.23078823e+00 9.19280434e+00 9.11709499e+00 9.09899616e+00 9.10422039e+00 9.14912987e+00 9.14271927e+00 9.14797115e+00 9.19898224e+00 9.23432350e+00 9.18856239e+00 9.15133858e+00 9.11676025e+00 9.17590618e+00 9.15840244e+00 9.14817524e+00 9.09991932e+00 9.11024570e+00 9.15729237e+00 9.18225861e+00 9.13448524e+00 9.02311134e+00 8.94827843e+00 8.99007034e+00 9.00123692e+00 9.00773525e+00 8.98483944e+00 9.01387024e+00 8.98597622e+00 8.93693542e+00 8.98125076e+00 9.05236626e+00 9.09122562e+00 9.01345634e+00 9.01095200e+00 9.08915043e+00 9.11829090e+00 9.04799366e+00 8.93904018e+00 8.78483677e+00 8.68221760e+00 8.61044025e+00 8.72856331e+00 8.84389114e+00 8.87738895e+00 8.57736778e+00 8.44430733e+00 8.55651951e+00 8.68069077e+00 8.78511810e+00 8.69719505e+00 8.80956173e+00 8.67963982e+00 8.31896591e+00 8.08953762e+00 8.36097431e+00 8.78032303e+00 8.97439098e+00 8.83309555e+00 8.71059799e+00 8.68042946e+00 8.58695507e+00 8.60046673e+00 8.58642387e+00 8.60674953e+00 8.59340382e+00 8.65470028e+00 8.60902023e+00 8.43033791e+00 8.27961063e+00 8.02725601e+00 7.89486551e+00 7.91178131e+00 8.12744236e+00 8.27830505e+00 8.13017654e+00 8.06013107e+00 8.22173214e+00 8.45008469e+00 8.58554649e+00 8.41975403e+00 8.41869736e+00 8.29484177e+00 8.35093403e+00 8.17930412e+00 8.31085587e+00 8.22541618e+00 7.85491848e+00 7.52139139e+00 7.85070610e+00 8.66368866e+00 8.80495071e+00 8.51210117e+00 8.03562260e+00 7.94983101e+00 7.83507156e+00 7.85168219e+00 7.83304977e+00 7.83084011e+00 7.98224449e+00 8.21779919e+00 8.64947033e+00 8.00328350e+00 7.08619881e+00 6.68216324e+00 7.28811169e+00 8.14420319e+00 8.24831772e+00 8.22413158e+00 8.12566948e+00 8.21068096e+00 8.37027740e+00 8.60156536e+00 8.43115902e+00 8.09658813e+00 7.85307312e+00 7.99270821e+00 7.98427153e+00 7.86024618e+00 7.84159994e+00 7.86704159e+00 7.96286535e+00 8.12440777e+00 8.26660156e+00 7.97196293e+00 7.16270924e+00 6.97104883e+00 7.05694342e+00 6.88525009e+00 6.27913332e+00 5.66302443e+00 5.70847654e+00 6.37173605e+00 6.98677206e+00 7.39098549e+00 7.31744957e+00 7.16129446e+00 7.01256657e+00 7.35412836e+00 7.56368923e+00 7.57134199e+00 7.22128773e+00 7.19012213e+00 6.75239515e+00 6.36487293e+00 6.17183876e+00 6.73077965e+00 7.23238182e+00 7.35831213e+00 7.22840834e+00 7.16246414e+00 7.17614746e+00 7.16272259e+00 7.17810678e+00 7.30126238e+00 7.43501759e+00 7.27104521e+00 7.17567730e+00 7.23138428e+00 7.48577356e+00 7.36533451e+00 7.18849802e+00 6.73736143e+00 6.71137047e+00 6.77356625e+00 7.09414244e+00 7.17214823e+00 6.86801147e+00 6.55888319e+00 6.28640747e+00 6.22498608e+00 6.29046059e+00 6.62499857e+00 6.95268631e+00 6.44658995e+00 5.34949064e+00 3.62372160e+00 3.50914574e+00 3.03617764e+00 2.47609043e+00 1.38063633e+00 -8.13438225e+00 -6.94782257e+00 -1.38823354e+00 1.92856483e+01 -1.26997398e+02 7.50660229e+00 3.35985986e+03 -194268432. 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. 0. 0. 0. 0. 0. 0. 274490496. 3.89359302e+03 5.97174622e+02 1.03021851e+02 4.45502167e+01 2.60326939e+01 1.47154055e+01 9.95204926e+00 6.73826742e+00 4.89806747e+00 4.52058315e+00 4.87429762e+00 5.86906099e+00 6.26514101e+00 6.35838270e+00 5.90885830e+00 5.97679281e+00 5.91017246e+00 5.83124304e+00 5.67702246e+00 5.63588619e+00 5.94382048e+00 5.61652231e+00 5.05266905e+00 4.59528112e+00 4.66776085e+00 4.84000635e+00 4.69997025e+00 4.77574682e+00 4.75951338e+00 4.32628822e+00 4.11220932e+00 4.12670994e+00 4.53340960e+00 4.54909754e+00 4.34787941e+00 3.99117494e+00 3.89966869e+00 3.39381099e+00 3.00651336e+00 2.60377669e+00 3.30196047e+00 3.98274684e+00 4.30370712e+00 4.00509644e+00 3.55538630e+00 3.24465346e+00 3.18782997e+00 3.63957977e+00 3.44907188e+00 3.24749827e+00 2.63507128e+00 3.28092313e+00 3.96196628e+00 4.38499737e+00 3.88800812e+00 3.77188087e+00 3.51792717e+00 3.51370192e+00 3.29706693e+00 3.28418660e+00 3.45854878e+00 3.70949054e+00 4.28080654e+00 4.78174114e+00 4.76077843e+00 4.79833651e+00 4.53339052e+00 5.09370518e+00 5.29715300e+00 4.98667622e+00 4.25377321e+00 3.47670317e+00 3.11722732e+00 2.91526461e+00 2.27963185e+00 1.83927929e+00 1.84183574e+00 2.52642894e+00 3.11438751e+00 2.96214294e+00 2.80969524e+00 2.89511943e+00 3.15125537e+00 3.53722167e+00 3.67134285e+00 4.24323893e+00 4.42643929e+00 4.26655102e+00 3.58642650e+00 2.78612900e+00 2.54454494e+00 2.69851565e+00 3.47448087e+00 3.95654702e+00 3.44495249e+00 3.06770658e+00 2.72630978e+00 2.84525633e+00 2.74150562e+00 2.81630659e+00 3.38101172e+00 2.75503945e+00 1.88081861e+00 1.28734004e+00 1.51733148e+00 1.89795280e+00 1.80630255e+00 2.02497458e+00 2.26581812e+00 2.33042073e+00 2.79422522e+00 3.25726247e+00 2.86669302e+00 2.11081314e+00 1.23980892e+00 1.47875488e+00 1.48558140e+00 1.80487669e+00 1.81901383e+00 1.55127180e+00 1.35329080e+00 1.23613739e+00 1.50111485e+00 1.58749461e+00 2.00127101e+00 2.10104418e+00 2.01019835e+00 1.99639118e+00 2.57626939e+00 3.20962977e+00 3.03162432e+00 2.66477513e+00 1.87321103e+00 2.72014451e+00 3.19749141e+00 3.94160128e+00 3.57076383e+00 2.81341028e+00 1.84011042e+00 7.80408144e-01 6.29542172e-01 8.34173679e-01 1.07214093e+00 8.64722431e-01 7.12319016e-01 4.75916117e-01 5.30024171e-01 6.08935714e-01 6.38372421e-01 3.86297435e-01 5.62226236e-01 6.84756041e-01 1.16693521e+00 1.75833094e+00 2.42329168e+00 2.24265361e+00 1.40905178e+00 8.59163523e-01 1.39288354e+00 2.22780275e+00 2.68796277e+00 2.50249362e+00 2.46927595e+00 2.39146280e+00 2.11487842e+00 1.92637193e+00 1.19165266e+00 9.50043261e-01 5.62129796e-01 4.00774062e-01 4.25415963e-01 4.20276850e-01 3.02394927e-01 4.30463612e-01 6.53638005e-01 6.04823887e-01 -3.32160294e-01 -1.40204620e+00 -1.60933244e+00 -8.82872701e-01 3.87903489e-03 3.46156597e-01 2.41209060e-01 -3.68034333e-01 -8.51478457e-01 -3.95866245e-01 4.95490402e-01 7.29339600e-01 8.90753865e-02 -4.75832522e-01 -5.96977293e-01 -2.13570908e-01 -8.31164196e-02 -1.19334847e-01 -8.36205110e-02 -2.14722186e-01 -1.81487482e-02 3.13496776e-02 2.66507864e-01 2.35810831e-01 -9.91107672e-02 -6.88662350e-01 -1.30619681e+00 -1.34170437e+00 -1.18937504e+00 -9.08666849e-01 -1.23650289e+00 -1.31414986e+00 -8.49288046e-01 -5.43910921e-01 -4.64930296e-01 -1.03979278e+00 -1.21386421e+00 -1.08813524e+00 -9.48096037e-01 -8.83566320e-01 -1.08705556e+00 -1.31440413e+00 -1.47738278e+00 -1.80375612e+00 -1.54541683e+00 -1.72379160e+00 -1.84538412e+00 -1.94130790e+00 -2.08459902e+00 -2.13230109e+00 -2.54984593e+00 -2.97477746e+00 -2.84891272e+00 -2.80314732e+00 -2.12664080e+00 -2.42077303e+00 -2.03338242e+00 -2.41605973e+00 -2.53195906e+00 -2.79219890e+00 -2.52779627e+00 -2.31326842e+00 -2.75682926e+00 -3.00701952e+00 -3.33203173e+00 -2.70434070e+00 -2.36242366e+00 -2.14632154e+00 -2.85868669e+00 -3.58185840e+00 -4.00999165e+00 -3.33536911e+00 -1.81645036e+00 -6.40109479e-01 -6.46072030e-01 -1.73925602e+00 -2.61209750e+00 -2.42499280e+00 -1.80858552e+00 -1.79851711e+00 -2.35932040e+00 -2.92313099e+00 -3.03310919e+00 -2.84282684e+00 -2.74419832e+00 -2.63825631e+00 -2.83405781e+00 -3.03657532e+00 -3.10041809e+00 -2.97058344e+00 -2.84758615e+00 -3.31075740e+00 -3.78476262e+00 -3.66773152e+00 -3.16646791e+00 -2.98838544e+00 -3.36261654e+00 -3.31946707e+00 -3.53684139e+00 -3.60587883e+00 -3.47671890e+00 -3.35565543e+00 -2.87494898e+00 -2.80620098e+00 -2.85880780e+00 -3.39062691e+00 -4.13293600e+00 -3.94703269e+00 -3.84286690e+00 -3.50229836e+00 -3.53610039e+00 -4.19701529e+00 -4.75928402e+00 -4.68453884e+00 -3.94472575e+00 -3.32606030e+00 -3.78629971e+00 -4.13568592e+00 -3.84290051e+00 -3.87305450e+00 -2.97023869e+00 -2.81517386e+00 -2.69693589e+00 -3.28720856e+00 -4.34869909e+00 -4.52860212e+00 -4.82110643e+00 -4.62066031e+00 -4.37165070e+00 -3.65018463e+00 -3.02313328e+00 -3.03524542e+00 -3.36791372e+00 -3.98093367e+00 -3.94951463e+00 -4.05097628e+00 -4.17318583e+00 -4.25601673e+00 -3.93606257e+00 -3.85897017e+00 -3.66836500e+00 -3.83982825e+00 -4.06438446e+00 -4.49505472e+00 -4.63596058e+00 -4.66003466e+00 -4.72851133e+00 -4.90132952e+00 -5.17343903e+00 -4.85751724e+00 -4.27631807e+00 -3.41131115e+00 -2.94056439e+00 -2.79769659e+00 -3.03868437e+00 -3.57005715e+00 -5.16659451e+00 -5.73872852e+00 -6.07023382e+00 -5.36983347e+00 -5.30284023e+00 -4.83723021e+00 -4.22587585e+00 -4.60493612e+00 -4.56955910e+00 -5.62379217e+00 -5.78132105e+00 -6.29671860e+00 -5.92900085e+00 -5.43523264e+00 -5.36803055e+00 -5.37534952e+00 -4.72830009e+00 -4.16607809e+00 -4.31554365e+00 -5.07674503e+00 -5.79029274e+00 -5.32283211e+00 -5.07910872e+00 -4.84780312e+00 -4.98442459e+00 -5.17772436e+00 -5.55750990e+00 -6.09745026e+00 -6.12218714e+00 -5.85879612e+00 -5.64503050e+00 -5.86111784e+00 -6.10635328e+00 -6.31197405e+00 -6.12439060e+00 -6.22939682e+00 -6.10056305e+00 -6.05173635e+00 -5.76135445e+00 -5.50160599e+00 -4.90614843e+00 -5.37334347e+00 -6.15242863e+00 -6.77943754e+00 -6.09129810e+00 -5.58068562e+00 -5.27202320e+00 -5.59770775e+00 -5.14488888e+00 -4.87877798e+00 -4.79700613e+00 -5.31621742e+00 -5.96023560e+00 -6.05753326e+00 -5.79923964e+00 -5.46459150e+00 -5.51364374e+00 -5.83915615e+00 -6.11397600e+00 -6.23394871e+00 -6.20795202e+00 -5.97795391e+00 -6.07052279e+00 -5.85614681e+00 -5.76168966e+00 -5.63270617e+00 -6.25966883e+00 -7.24094915e+00 -7.06910419e+00 -6.23394394e+00 -5.62576056e+00 -6.27343464e+00 -6.75752592e+00 -6.56783581e+00 -6.43079281e+00 -6.68115234e+00 -7.20248270e+00 -7.20918083e+00 -7.21266413e+00 -7.24419737e+00 -7.16671419e+00 -6.82533216e+00 -6.68899059e+00 -6.99463272e+00 -6.91582394e+00 -6.48897266e+00 -6.57061481e+00 -6.94522667e+00 -7.49928570e+00 -7.56121635e+00 -7.58478069e+00 -7.92380810e+00 -7.95798159e+00 -7.75121641e+00 -7.22967911e+00 -6.76329517e+00 -6.97312069e+00 -7.01273727e+00 -7.16911077e+00 -7.15956593e+00 -7.30777454e+00 -7.42482328e+00 -7.46355438e+00 -7.63611126e+00 -7.61089849e+00 -7.31399918e+00 -6.85448551e+00 -6.63622522e+00 -6.82539034e+00 -6.76183414e+00 -6.52411652e+00 -6.76008606e+00 -7.12192869e+00 -7.82295752e+00 -8.00992489e+00 -7.87363100e+00 -8.01202106e+00 -8.06271744e+00 -8.06673908e+00 -7.68199301e+00 -7.37013674e+00 -7.39500475e+00 -7.54425049e+00 -7.75561523e+00 -7.96786594e+00 -8.00485325e+00 -7.97702885e+00 -7.98991871e+00 -8.07402420e+00 -8.13733387e+00 -7.88624811e+00 -7.61728573e+00 -7.71237564e+00 -8.00017166e+00 -8.26768875e+00 -8.05249214e+00 -8.29000187e+00 -8.58194923e+00 -8.49215603e+00 -7.83857107e+00 -7.13209009e+00 -6.97285604e+00 -7.26134396e+00 -7.39600801e+00 -7.37684011e+00 -7.57345486e+00 -7.79420948e+00 -7.96993065e+00 -7.89600468e+00 -7.89670563e+00 -7.84953833e+00 -7.60639954e+00 -7.60977697e+00 -7.84064579e+00 -8.21815205e+00 -8.10728645e+00 -7.86992073e+00 -7.86243343e+00 -8.17346573e+00 -8.07245350e+00 -7.78203964e+00 -7.98136282e+00 -8.66767025e+00 -9.08708096e+00 -8.84047604e+00 -8.57270813e+00 -8.70596600e+00 -9.07032108e+00 -9.05685139e+00 -8.88091373e+00 -8.72192860e+00 -8.96755886e+00 -9.11097813e+00 -9.06691551e+00 -8.86815453e+00 -8.53891563e+00 -8.19861317e+00 -8.01309776e+00 -8.05994892e+00 -8.57344723e+00 -9.01373768e+00 -9.19187260e+00 -8.97969723e+00 -8.76538372e+00 -8.73940754e+00 -8.75706863e+00 -8.85513973e+00 -9.21105289e+00 -9.19385910e+00 -8.92875576e+00 -8.63264465e+00 -8.55881882e+00 -8.60929871e+00 -8.41062832e+00 -8.21448231e+00 -8.25303173e+00 -8.53240013e+00 -8.74661922e+00 -8.80452919e+00 -8.76516914e+00 -8.79016113e+00 -8.72470188e+00 -8.70469093e+00 -8.73737717e+00 -8.79087257e+00 -8.91064548e+00 -8.98838520e+00 -9.07950974e+00 -9.04508495e+00 -8.87977314e+00 -8.56607437e+00 -8.60464859e+00 -8.67866135e+00 -8.72990799e+00 -8.48350143e+00 -8.55798626e+00 -8.75100517e+00 -8.96832085e+00 -8.79758835e+00 -8.67346859e+00 -8.71293259e+00 -8.94916821e+00 -9.16413403e+00 -9.19828987e+00 -9.17026615e+00 -9.03025532e+00 -8.88413429e+00 -8.88877869e+00 -9.01343536e+00 -9.00381851e+00 -8.83376980e+00 -8.83235359e+00 -8.93397141e+00 -9.12929249e+00 -8.99997616e+00 -8.89902115e+00 -8.92837334e+00 -9.13660145e+00 -9.27965355e+00 -9.20745850e+00 -9.06889534e+00 -9.01028538e+00 -9.02865410e+00 -9.13327694e+00 -9.19333839e+00 -9.14170456e+00 -9.10828972e+00 -9.00798702e+00 -8.95187378e+00 -9.03768921e+00 -9.10784531e+00 -9.17791271e+00 -9.09553432e+00 -9.10674095e+00 -9.16089725e+00 -9.22078991e+00 -9.25066090e+00 -9.24617100e+00 -9.26206303e+00 -9.26426792e+00 -9.24218845e+00 -9.38264847e+00 -9.43459892e+00 -9.39311123e+00 -9.30309486e+00 -9.39665222e+00 -9.55777359e+00 -9.43314648e+00 -9.32010746e+00 -9.27812386e+00 -9.39922810e+00 -9.43597126e+00 -9.59544849e+00 -9.86762047e+00 -9.99225616e+00 -1.01812162e+01 -1.25576105e+01 -2.99267654e+01 -3.72106972e+01 -2.94219284e+01 -3.08274612e+01 -8.46667557e+01 -3.35769875e+05 0. 0. 0. 0. 0. -252229952. -252229952. 20229712. 45908868. -11309393. 32765716. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -45045480. -7.74762192e+01 -2.76974258e+01 -2.20700130e+01 -1.99290047e+01 -2.19513340e+01 -2.18625011e+01 -2.12332325e+01 -2.04871330e+01 -2.03676395e+01 -2.03614731e+01 -2.03330593e+01 -2.03570976e+01 -2.04091434e+01 -2.04539623e+01 -2.03672771e+01 -2.02233753e+01 -2.01187096e+01 -2.01703644e+01 -2.04721889e+01 -2.07513027e+01 -2.08603878e+01 -2.07988777e+01 -2.05770397e+01 -2.05033703e+01 -2.04823151e+01 -2.02935619e+01 -2.02041473e+01 -2.03309307e+01 -2.06269798e+01 -2.08984375e+01 -2.08241100e+01 -2.05533867e+01 -2.01209488e+01 -2.00045967e+01 -2.00678596e+01 -2.01465302e+01 -2.01617470e+01 -2.02038498e+01 -2.03504982e+01 -2.05359726e+01 -2.02768841e+01 -2.01089973e+01 -1.98652802e+01 -2.01916637e+01 -2.02626915e+01 -2.03710384e+01 -2.05610046e+01 -2.04087334e+01 -2.03455963e+01 -1.99566994e+01 -1.96004124e+01 -1.92648563e+01 -1.92255077e+01 -1.97885857e+01 -2.05311489e+01 -2.07294674e+01 -2.03021832e+01 -1.94686661e+01 -1.91631794e+01 -1.94912567e+01 -1.97565079e+01 -2.00440884e+01 -1.99605350e+01 -2.01327229e+01 -1.99708500e+01 -1.98434448e+01 -1.95363617e+01 -1.92294807e+01 -1.94049473e+01 -1.94781551e+01 -1.96735134e+01 -1.97195530e+01 -1.97197666e+01 -1.97718964e+01 -1.95378208e+01 -1.90811806e+01 -1.85620708e+01 -1.85893688e+01 -1.92038479e+01 -1.95979996e+01 -2.00686131e+01 -1.98315544e+01 -1.93285275e+01 -1.89381657e+01 -1.87396870e+01 -1.85619946e+01 -1.80476742e+01 -1.83190365e+01 -1.89804516e+01 -1.99012413e+01 -1.98480682e+01 -1.92897205e+01 -1.83185253e+01 -1.81289520e+01 -1.82412281e+01 -1.81446953e+01 -1.81796494e+01 -1.82596111e+01 -1.84806595e+01 -1.89160385e+01 -1.87316074e+01 -1.86224594e+01 -1.85790291e+01 -1.93374996e+01 -1.99359493e+01 -2.00789146e+01 -1.96060123e+01 -1.87309532e+01 -1.80848312e+01 -1.83708096e+01 -1.82899895e+01 -1.75807419e+01 -1.67936058e+01 -1.76917934e+01 -1.93201504e+01 -1.94535141e+01 -1.83180561e+01 -1.67824593e+01 -1.66607094e+01 -1.71944103e+01 -1.81016865e+01 -1.88058319e+01 -1.89194870e+01 -1.82439823e+01 -1.78426361e+01 -1.73703194e+01 -1.69187698e+01 -1.63896484e+01 -1.63452473e+01 -1.69357014e+01 -1.76059780e+01 -1.77291927e+01 -1.77266197e+01 -1.72447643e+01 -1.69104977e+01 -1.63416290e+01 -1.65284481e+01 -1.62892342e+01 -1.66181183e+01 -1.74318695e+01 -1.90110283e+01 -1.96853790e+01 -1.92229881e+01 -1.82303982e+01 -1.85005703e+01 -1.78334427e+01 -1.75542908e+01 -1.70165615e+01 -1.72704353e+01 -1.83969879e+01 -1.87210503e+01 -1.80059166e+01 -1.66819038e+01 -1.59407291e+01 -1.68797379e+01 -1.77524700e+01 -1.73518524e+01 -1.64169483e+01 -1.55378590e+01 -1.65915165e+01 -1.74079323e+01 -1.70390205e+01 -1.68236866e+01 -1.67533703e+01 -1.82753258e+01 -1.93092079e+01 -1.99245701e+01 -1.79870720e+01 -1.56614466e+01 -1.46953611e+01 -1.50134964e+01 -1.54215479e+01 -1.57140760e+01 -1.59107456e+01 -1.67648182e+01 -1.72421360e+01 -1.66041603e+01 -1.56522112e+01 -1.51681242e+01 -1.57297382e+01 -1.74975758e+01 -1.71904926e+01 -1.73114967e+01 -1.62676849e+01 -1.73038750e+01 -1.75051193e+01 -1.69645004e+01 -1.58452158e+01 -1.56762552e+01 -1.51343365e+01 -1.49060364e+01 -1.50153942e+01 -1.46550522e+01 -1.38306217e+01 -1.35128698e+01 -1.38722630e+01 -1.44684830e+01 -1.53130894e+01 -1.55855064e+01 -1.55482931e+01 -1.52659492e+01 -1.40963783e+01 -1.34702673e+01 -1.23669815e+01 -1.37282705e+01 -1.45186281e+01 -1.52512360e+01 -1.49134731e+01 -1.50920010e+01 -1.50306053e+01 -1.47623034e+01 -1.37190208e+01 -1.29891777e+01 -1.29568796e+01 -1.35956678e+01 -1.48314695e+01 -1.47363291e+01 -1.45585041e+01 -1.36552477e+01 -1.30615339e+01 -1.30649271e+01 -1.35093060e+01 -1.42001305e+01 -1.37105026e+01 -1.30106602e+01 -1.27381430e+01 -1.27942514e+01 -1.30327816e+01 -1.27364731e+01 -1.24733849e+01 -1.32447844e+01 -1.22135925e+01 -1.39135180e+01 -1.28790073e+01 -1.44326982e+01 -1.36369743e+01 -1.35274601e+01 -1.15228558e+01 -1.11943979e+01 -1.25506754e+01 -1.39573679e+01 -1.30398922e+01 -1.11699400e+01 -1.10543795e+01 -1.15638885e+01 -1.31604948e+01 -1.20987625e+01 -1.15208998e+01 -1.10008202e+01 -1.13435965e+01 -1.15850096e+01 -1.06360588e+01 -1.28164368e+01 -1.19534216e+01 -1.14592485e+01 -9.16166878e+00 -1.09192276e+01 -1.28829489e+01 -1.50682297e+01 -1.44927368e+01 -1.37345352e+01 -1.10478554e+01 -1.09842615e+01 -9.54261780e+00 -1.08714008e+01 -1.26707430e+01 -1.43150482e+01 -1.34931412e+01 -1.26856232e+01 -1.23839884e+01 -1.25383043e+01 -1.09236174e+01 -1.02865658e+01 -1.00055008e+01 -1.05054331e+01 -9.91450024e+00 -9.09826469e+00 -1.00461884e+01 -1.05187664e+01 -1.04698677e+01 -1.00425596e+01 -9.41322231e+00 -8.51396561e+00 -7.88627672e+00 -8.54896259e+00 -9.93469429e+00 -1.06928101e+01 -1.02195368e+01 -1.06934071e+01 -1.11121550e+01 -1.20428514e+01 -1.17261944e+01 -9.66989517e+00 -1.01472931e+01 -1.03387318e+01 -1.10932198e+01 -9.88405609e+00 -1.04726772e+01 -1.08778582e+01 -1.10791168e+01 -9.45720100e+00 -8.10519028e+00 -7.53070974e+00 -8.40765858e+00 -8.44918633e+00 -6.93808889e+00 -5.66116571e+00 -5.73093510e+00 -6.90532970e+00 -8.35554600e+00 -8.83705616e+00 -9.03308296e+00 -7.70409012e+00 -6.56366062e+00 -7.30488443e+00 -9.60179806e+00 -9.63250637e+00 -7.95287895e+00 -7.00351572e+00 -1.00003214e+01 -1.12303629e+01 -9.48632526e+00 -7.02487898e+00 -5.07877254e+00 -5.43772125e+00 -4.19854546e+00 -4.60811901e+00 -5.25943422e+00 -5.75610590e+00 -5.75660324e+00 -5.46511030e+00 -6.30381346e+00 -6.05783892e+00 -4.86700630e+00 -5.11728525e+00 -6.75903368e+00 -7.64911079e+00 -6.49284220e+00 -5.07970953e+00 -5.50440502e+00 -7.27926111e+00 -7.47573233e+00 -6.87156773e+00 -5.94472313e+00 -6.87459660e+00 -6.98344326e+00 -6.56419277e+00 -6.30962229e+00 -6.35086584e+00 -5.45930767e+00 -2.94244647e+00 -2.24950528e+00 -2.39694405e+00 -4.34018230e+00 -4.96245193e+00 -5.54891348e+00 -6.08294916e+00 -6.04922056e+00 -4.66682053e+00 -4.31334019e+00 -6.41551542e+00 -8.02368355e+00 -7.88349390e+00 -5.55167866e+00 -5.28624487e+00 -6.18383265e+00 -6.55969334e+00 -7.70981646e+00 -5.95698929e+00 -6.34547853e+00 -4.93753958e+00 -5.79973173e+00 -7.43498898e+00 -8.54605770e+00 -8.80743885e+00 -6.08488083e+00 -2.95733953e+00 -3.43930316e+00 -4.80648708e+00 -6.48504257e+00 -4.81038713e+00 -2.92321348e+00 -2.34453535e+00 -9.89782751e-01 -3.13193107e+00 -4.71417713e+00 -6.28620720e+00 -5.00070381e+00 -3.40566730e+00 -2.51831198e+00 -2.91812229e+00 -3.49566960e+00 -5.21336746e+00 -5.87188673e+00 -6.19040346e+00 -4.26789427e+00 -1.90491211e+00 -2.05013776e+00 -3.12864542e+00 -3.37115526e+00 -1.62017417e+00 -1.74506354e+00 -4.69486094e+00 -6.66082191e+00 -5.65478182e+00 -3.42774820e+00 -2.31535769e+00 -2.54389405e+00 -1.30035925e+00 -1.33920062e+00 -2.62907743e+00 -3.48101616e+00 -4.74091578e+00 -2.84157586e+00 -3.66640162e+00 -3.69579911e+00 -4.45222378e+00 -4.23382854e+00 -1.23055303e+00 3.46965432e-01 -2.14828476e-01 -2.06724524e+00 -5.00617790e+00 -4.64031553e+00 -3.76850247e+00 -1.11580920e+00 8.19844782e-01 1.52394390e+00 -3.44684929e-01 -2.29312301e+00 -2.54326677e+00 -5.91105968e-02 -2.87672162e-01 3.47088933e-01 2.87167311e-01 8.81189525e-01 6.53375328e-01 -1.38270348e-01 1.55605423e+00 2.50613093e+00 2.36766553e+00 9.55984056e-01 -1.89262342e+00 -3.05555534e+00 -2.88004518e+00 -6.31676972e-01 1.69417882e+00 2.12032485e+00 -1.87554762e-01 -1.09065580e+00 6.89409792e-01 2.77578259e+00 2.59187675e+00 4.97846127e-01 2.63452858e-01 -5.76050095e-02 6.61703348e-01 -2.28666440e-01 -1.16568275e-01 2.75362015e-01 -1.64725792e+00 -5.17615266e-02 -4.22630042e-01 1.24019635e+00 7.73557007e-01 1.39555478e+00 3.20886517e+00 1.32178819e+00 1.49057674e+00 1.53906608e+00 3.64784980e+00 3.41830564e+00 1.27252567e+00 9.55774216e-04 9.33959335e-02 2.61490774e+00 3.81367612e+00 3.54268312e+00 2.59166002e+00 1.71628296e+00 2.79946613e+00 4.03599691e+00 5.36605740e+00 5.92332411e+00 4.98921013e+00 2.98475456e+00 1.10144532e+00 2.19310856e+00 4.31316710e+00 6.01927948e+00 5.87707424e+00 5.01321125e+00 3.34870386e+00 2.39017224e+00 2.45394015e+00 4.44017744e+00 6.10881376e+00 5.68722010e+00 3.92530084e+00 2.60393810e+00 3.07380223e+00 4.64564276e+00 4.81165218e+00 5.05881834e+00 3.24481797e+00 1.84644949e+00 1.91069925e+00 2.45978117e+00 4.37048721e+00 5.33800507e+00 5.68598890e+00 5.29203749e+00 3.58209085e+00 3.73558569e+00 5.10501480e+00 5.95227146e+00 6.65048218e+00 4.97959089e+00 5.12432194e+00 5.74131012e+00 7.02968597e+00 7.15547800e+00 4.79188871e+00 3.49611616e+00 3.84040999e+00 6.47688866e+00 8.10601711e+00 8.64472294e+00 8.50973225e+00 7.35140705e+00 6.08553982e+00 5.63024759e+00 5.54660463e+00 6.47594166e+00 6.59095812e+00 6.13051701e+00 6.82107019e+00 7.07300377e+00 8.61901665e+00 8.06827545e+00 8.21088314e+00 7.98997498e+00 6.90360498e+00 6.71736288e+00 7.69159937e+00 9.97244930e+00 1.06451721e+01 9.92791653e+00 9.10411358e+00 8.35490799e+00 8.91442013e+00 9.87510681e+00 1.02041578e+01 1.01847506e+01 8.73352814e+00 7.98645782e+00 7.82026815e+00 8.37815952e+00 8.65110683e+00 8.07825565e+00 8.37681389e+00 8.47306538e+00 7.11638689e+00 6.78495169e+00 7.32289505e+00 8.39496040e+00 7.52968121e+00 5.91947174e+00 5.93804598e+00 7.28491306e+00 9.59422016e+00 1.07691507e+01 9.56912327e+00 8.95591831e+00 8.68577671e+00 9.50948048e+00 9.84533215e+00 9.12203407e+00 9.26590443e+00 8.59511566e+00 8.69148827e+00 8.67867661e+00 8.55916500e+00 9.22681904e+00 9.68363571e+00 9.37212181e+00 9.25969505e+00 8.47212124e+00 9.46032524e+00 9.45393753e+00 1.05661583e+01 1.02318649e+01 9.13826752e+00 8.91434479e+00 9.10787964e+00 1.00210752e+01 1.05122204e+01 9.75372028e+00 9.22847652e+00 7.60429096e+00 8.84070015e+00 1.07056570e+01 1.21250801e+01 1.21946106e+01 1.10245733e+01 1.12116175e+01 1.20072536e+01 1.27948132e+01 1.46300716e+01 1.54321241e+01 1.57748289e+01 1.55919170e+01 1.46098614e+01 1.02816153e+01 1.15416565e+01 2.11523609e+01 2.99039307e+01 6.05035324e+01 4.29589539e+01 6.06867859e+02 3.59162427e+03 -53644572. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -79591544. -21474200. 3.50486255e+03 1.45045264e+03 1.80839554e+02 -3.94389557e+02 -2.97661896e+02 -2.58194675e+01 -6.62359285e+00 8.23569870e+00 1.30937462e+01 1.23527994e+01 1.20587883e+01 1.23581285e+01 1.42642469e+01 1.49692039e+01 1.56077232e+01 1.55925722e+01 1.54547749e+01 1.50094824e+01 1.48301353e+01 1.45175104e+01 1.50408764e+01 1.59104176e+01 1.61373749e+01 1.50358458e+01 1.48933420e+01 1.57599926e+01 1.71912975e+01 1.63412666e+01 1.52028246e+01 1.51006765e+01 1.57309523e+01 1.60696144e+01 1.59274960e+01 1.56494761e+01 1.62279510e+01 1.61893463e+01 1.58191366e+01 1.53696299e+01 1.54537497e+01 1.64438877e+01 1.59718285e+01 1.58229761e+01 1.54293146e+01 1.49839220e+01 1.53851957e+01 1.62771091e+01 1.79623566e+01 1.79514179e+01 1.66012211e+01 1.66101513e+01 1.67857037e+01 1.82396698e+01 1.77228985e+01 1.69277592e+01 1.61680965e+01 1.63254223e+01 1.71760941e+01 1.72754536e+01 1.69764194e+01 1.69118519e+01 1.64756184e+01 1.58507042e+01 1.61045074e+01 1.68025150e+01 1.76800861e+01 1.69644890e+01 1.67964420e+01 1.64120045e+01 1.62964268e+01 1.66238976e+01 1.70301361e+01 1.76551800e+01 1.74267883e+01 1.69929047e+01 1.74393711e+01 1.81309433e+01 1.94483833e+01 1.92560139e+01 1.82164917e+01 1.79435081e+01 1.76162548e+01 1.77405949e+01 1.78828468e+01 1.83130836e+01 1.88980637e+01 1.85366840e+01 1.84170265e+01 1.85885735e+01 1.84654140e+01 1.79790478e+01 1.72252979e+01 1.75664577e+01 1.82706776e+01 1.83095627e+01 1.83663540e+01 1.81566772e+01 1.83312645e+01 1.85263519e+01 1.78194084e+01 1.81348209e+01 1.85909843e+01 1.94435253e+01 1.94393501e+01 1.88178806e+01 1.86702652e+01 1.84208202e+01 1.81128788e+01 1.81962433e+01 1.80658779e+01 1.85402527e+01 1.82830219e+01 1.83191128e+01 1.83270321e+01 1.84393749e+01 1.88818092e+01 1.92197514e+01 1.93257198e+01 2.00539837e+01 1.98269157e+01 1.98067284e+01 1.94307365e+01 1.94608421e+01 1.99426556e+01 1.90903473e+01 1.91022320e+01 1.92594109e+01 2.01256142e+01 2.01487789e+01 1.94776154e+01 1.93939381e+01 1.93517723e+01 1.93675556e+01 1.93877888e+01 1.94980373e+01 1.97960377e+01 1.96142006e+01 1.95676003e+01 1.96034641e+01 1.97263432e+01 1.99465942e+01 1.96761112e+01 1.94928207e+01 1.94254551e+01 1.95049419e+01 1.94174500e+01 1.91542950e+01 1.89003410e+01 1.91875343e+01 1.93807735e+01 1.96082039e+01 1.95112038e+01 1.97946396e+01 2.01639042e+01 2.02477493e+01 2.02305355e+01 1.99061985e+01 1.98118935e+01 1.97161293e+01 1.96137810e+01 1.93208599e+01 1.94398804e+01 1.95423374e+01 1.97205143e+01 1.95368538e+01 1.96848812e+01 2.00914440e+01 2.04075756e+01 2.04951591e+01 2.00435638e+01 1.98889961e+01 2.00117779e+01 2.02305679e+01 2.02362766e+01 2.00366764e+01 2.00944710e+01 2.00302505e+01 2.00122604e+01 2.00994091e+01 2.01988564e+01 2.02878342e+01 2.01700459e+01 2.00861015e+01 2.02257442e+01 2.01695957e+01 2.01683483e+01 2.00228615e+01 1.99744339e+01 1.98756428e+01 1.98404408e+01 2.01187687e+01 2.03365631e+01 2.04656258e+01 2.04363461e+01 2.02551556e+01 2.02534122e+01 2.03478718e+01 2.05447559e+01 2.06062412e+01 2.04928455e+01 2.04382343e+01 2.03615780e+01 2.03942604e+01 2.03343601e+01 2.02937756e+01 2.03098812e+01 2.03358097e+01 2.03687973e+01 2.03828983e+01 2.04424419e+01 2.05015469e+01 2.05014133e+01 2.05361443e+01 2.05287571e+01 2.04550705e+01 2.04094181e+01 2.04335155e+01 2.04959602e+01 2.05237293e+01 2.05159359e+01 2.05246601e+01 2.05283146e+01 2.05298080e+01 2.05239449e+01 2.05175343e+01 2.05174809e+01 2.05316944e+01 2.05526028e+01 2.05326443e+01 2.05119591e+01 2.04917450e+01 2.05170879e+01 2.05152111e+01 2.05024643e+01 2.05004959e+01 2.05149059e+01 2.04858990e+01 2.04655228e+01 2.04595814e+01 2.04998341e+01 2.05329075e+01 2.05172920e+01 2.04834347e+01 2.04472370e+01 2.04679947e+01 2.04893360e+01 2.05110550e+01 2.04726906e+01 2.04438496e+01 2.04392643e+01 2.04506264e+01 2.05363274e+01 2.06017208e+01 2.05477581e+01 2.04397030e+01 2.02765045e+01 2.03170376e+01 2.03552971e+01 2.03915195e+01 2.03488941e+01 2.04723434e+01 2.04326096e+01 2.04419765e+01 2.02490330e+01 2.03179607e+01 2.03121681e+01 2.02886848e+01 2.01848831e+01 2.01880856e+01 2.01497841e+01 2.01696148e+01 2.00322762e+01 2.00099258e+01 2.00738125e+01 2.01477146e+01 2.02772121e+01 2.00788765e+01 2.00491848e+01 2.00325432e+01 2.02646370e+01 2.02836647e+01 2.00577888e+01 2.01265259e+01 2.01885872e+01 2.02817230e+01 1.99031944e+01 1.97546787e+01 1.96701336e+01 1.96624737e+01 1.96298866e+01 1.97471504e+01 1.99071026e+01 1.98449802e+01 1.98791885e+01 1.97431583e+01 1.96741161e+01 1.96009560e+01 1.96869564e+01 1.98450489e+01 1.97335796e+01 1.98233280e+01 1.98439274e+01 1.99080200e+01 1.97207470e+01 1.96774731e+01 1.96614723e+01 1.97412186e+01 1.95191936e+01 1.92771225e+01 1.90124302e+01 1.92245274e+01 1.95030556e+01 1.98155746e+01 1.98881016e+01 1.97160282e+01 1.94945393e+01 1.92664661e+01 1.93312435e+01 1.94555035e+01 1.93104267e+01 1.91229038e+01 1.90426617e+01 1.94221630e+01 1.97202053e+01 1.98839931e+01 1.97929230e+01 1.96845169e+01 1.93503513e+01 1.88689785e+01 1.86202526e+01 1.85825272e+01 1.88749428e+01 1.88431797e+01 1.88912182e+01 1.89134312e+01 1.90776176e+01 1.90023251e+01 1.89314880e+01 1.88972168e+01 1.90377350e+01 1.89096069e+01 1.91645775e+01 1.92273693e+01 1.96987000e+01 1.98079624e+01 1.95785255e+01 1.92361393e+01 1.88012905e+01 1.91486664e+01 1.93368702e+01 1.91915569e+01 1.88147945e+01 1.89845009e+01 1.92876472e+01 1.95772209e+01 1.90313644e+01 1.89437618e+01 1.86649990e+01 1.88505402e+01 1.87450714e+01 1.86198940e+01 1.84544048e+01 1.77600212e+01 1.71532860e+01 1.71284676e+01 1.73662567e+01 1.79056911e+01 1.76643581e+01 1.76425304e+01 1.75332298e+01 1.74781113e+01 1.78621845e+01 1.79982185e+01 1.82478409e+01 1.81110191e+01 1.80445099e+01 1.78943119e+01 1.77309837e+01 1.76165981e+01 1.72444077e+01 1.73101501e+01 1.74596157e+01 1.73059788e+01 1.69431534e+01 1.64916954e+01 1.63446579e+01 1.65677166e+01 1.71166630e+01 1.73456974e+01 1.73900490e+01 1.71674557e+01 1.72285538e+01 1.72653160e+01 1.70598297e+01 1.71006947e+01 1.69125900e+01 1.68576336e+01 1.58598328e+01 1.61669102e+01 1.65396996e+01 1.70193768e+01 1.70131855e+01 1.70174828e+01 1.75846519e+01 1.79171028e+01 1.75487118e+01 1.72500248e+01 1.68026695e+01 1.69591389e+01 1.66850052e+01 1.67860374e+01 1.61750050e+01 1.60136318e+01 1.59185114e+01 1.64471817e+01 1.65860615e+01 1.67187080e+01 1.68983135e+01 1.69546146e+01 1.67938766e+01 1.65063744e+01 1.64014206e+01 1.60967808e+01 1.54934082e+01 1.51275940e+01 1.50183592e+01 1.56427956e+01 1.58030205e+01 1.55699520e+01 1.52905321e+01 1.52261734e+01 1.51237755e+01 1.51104040e+01 1.50491104e+01 1.51704597e+01 1.49217615e+01 1.47979584e+01 1.46493149e+01 1.45352802e+01 1.43443155e+01 1.48766727e+01 1.48716593e+01 1.50085430e+01 1.48021841e+01 1.48621807e+01 1.47152815e+01 1.40416832e+01 1.35805635e+01 1.11142387e+01 1.06423626e+01 1.15166254e+01 1.58772736e+01 1.55514011e+01 1.32926006e+01 1.50409813e+01 8.66489792e+00 -2.14953899e+00 -4.17864847e+00 -1.73628902e+01 -8.28491116e+00 1.39113068e+02 2.92742090e+03 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. 0. 0. 0. 0. 0. 0. 0. 81798760. -9.84515625e+03 -1.76396680e+03 -2.02457779e+02 -4.65064850e+01 2.65666389e+01 5.70033569e+02 4.19501160e+02 9.51424103e+01 4.89609756e+01 2.41954727e+01 1.96839237e+01 1.57756128e+01 1.36511831e+01 1.07101259e+01 1.05806112e+01 1.01973248e+01 9.66465092e+00 9.10827446e+00 9.11841583e+00 9.30256939e+00 1.06159592e+01 1.20855417e+01 1.21842003e+01 1.17685966e+01 1.07204170e+01 1.09274683e+01 1.06932545e+01 1.03996334e+01 1.00616970e+01 9.62080574e+00 1.01270466e+01 1.05417910e+01 1.08284283e+01 1.06612196e+01 1.09232168e+01 1.00768185e+01 9.85638714e+00 9.44097328e+00 9.96228600e+00 9.48955536e+00 9.23699188e+00 9.22325611e+00 8.93338776e+00 9.22079468e+00 9.28727055e+00 9.77440453e+00 9.80843544e+00 9.14289951e+00 7.60255766e+00 7.32550097e+00 8.31714249e+00 9.70500946e+00 9.81167698e+00 9.28192711e+00 8.81831360e+00 8.71415806e+00 9.01070499e+00 9.49916649e+00 9.64236355e+00 9.33202457e+00 8.84168434e+00 7.13718557e+00 6.26823235e+00 5.96852303e+00 5.81217384e+00 5.76494074e+00 5.20699024e+00 6.13199472e+00 7.15109539e+00 7.80782700e+00 8.51689911e+00 8.57972527e+00 8.17450905e+00 8.54820347e+00 8.97276115e+00 1.05132980e+01 1.07399254e+01 1.04024057e+01 8.86908627e+00 7.44592905e+00 7.01397657e+00 6.93240499e+00 5.95122194e+00 6.42317200e+00 5.06072378e+00 5.26804018e+00 4.72506571e+00 6.01399183e+00 6.89738894e+00 7.10810184e+00 6.53946590e+00 5.34532070e+00 3.80337667e+00 3.56618381e+00 4.72272778e+00 5.30252695e+00 5.19909143e+00 4.36789274e+00 4.49733353e+00 4.12450600e+00 4.39212799e+00 5.07505274e+00 5.35474014e+00 5.78136921e+00 4.84737778e+00 4.61167526e+00 3.92468739e+00 3.22374368e+00 2.91428924e+00 1.74791598e+00 1.88181746e+00 2.03385878e+00 3.72745585e+00 5.52770710e+00 6.37925768e+00 6.45062780e+00 6.11801815e+00 5.55093765e+00 5.10161161e+00 4.99795532e+00 5.17599249e+00 4.47514582e+00 3.72894287e+00 3.21465087e+00 3.83086991e+00 4.11103439e+00 3.38188720e+00 2.01789021e+00 9.53599393e-01 1.30970800e+00 1.64726484e+00 1.41871619e+00 1.15769482e+00 6.67145908e-01 3.61703485e-01 1.50878504e-01 9.44639504e-01 1.96376598e+00 2.74469757e+00 3.21788430e+00 3.26684833e+00 3.12796950e+00 2.89728665e+00 2.49414372e+00 2.79639125e+00 2.51658535e+00 2.09798121e+00 1.30693305e+00 1.41682303e+00 1.58516240e+00 1.64235270e+00 1.65471625e+00 1.27376115e+00 5.30241549e-01 3.14303368e-01 8.12046289e-01 1.10184801e+00 6.41522944e-01 -5.11385202e-01 -2.97959328e-01 -9.70747113e-01 -7.73781538e-01 -1.40682006e+00 -4.39388573e-01 2.04763785e-01 7.67414331e-01 8.43065858e-01 7.01711655e-01 8.54742169e-01 -2.54090820e-02 -2.61570901e-01 -2.06454024e-01 -4.97797579e-01 -1.09409249e+00 -1.00317430e+00 1.03014207e+00 2.71673799e+00 2.52109075e+00 1.23993278e+00 4.24651317e-02 -4.91553620e-02 2.83614427e-01 8.56009126e-01 5.18106163e-01 -3.23867708e-01 -1.97829461e+00 -1.95962012e+00 -8.46330822e-01 -3.80667709e-02 -5.88828325e-01 -2.15482903e+00 -2.19586778e+00 -1.57223046e+00 -1.36782038e+00 -1.80556285e+00 -2.77883577e+00 -2.44594955e+00 -1.94034302e+00 -1.96182334e+00 -2.24779987e+00 -1.21098685e+00 7.55110532e-02 7.00327680e-02 -1.04808557e+00 -1.88445878e+00 -2.28415966e+00 -2.46707582e+00 -2.82136965e+00 -2.39792442e+00 -2.84142995e+00 -2.98299265e+00 -3.41211987e+00 -2.80531836e+00 -3.22068334e+00 -2.91662049e+00 -3.50340629e+00 -3.47632551e+00 -3.79585004e+00 -3.17362046e+00 -3.34519172e+00 -3.38337827e+00 -3.57459974e+00 -3.32763910e+00 -3.09666872e+00 -3.36361313e+00 -2.72419977e+00 -2.15875101e+00 -2.43124366e+00 -2.90092278e+00 -3.86337447e+00 -3.63244748e+00 -3.63577962e+00 -3.26648116e+00 -3.02540183e+00 -2.94711757e+00 -3.70839047e+00 -3.55412078e+00 -3.41113210e+00 -3.20283008e+00 -4.24306488e+00 -4.63191271e+00 -4.87211370e+00 -4.54590893e+00 -4.12129354e+00 -3.58660221e+00 -3.63711667e+00 -4.35137749e+00 -6.19840240e+00 -7.07019615e+00 -7.18372154e+00 -6.33189011e+00 -4.73893785e+00 -5.23975325e+00 -6.84614372e+00 -8.26667213e+00 -7.94942331e+00 -5.96213770e+00 -5.48609114e+00 -5.62478018e+00 -6.00154638e+00 -5.99468279e+00 -5.79614830e+00 -5.70602846e+00 -5.48575544e+00 -5.67509270e+00 -6.18208313e+00 -5.89780426e+00 -5.92977381e+00 -5.85591221e+00 -7.09562016e+00 -6.93668890e+00 -6.90334654e+00 -5.48466921e+00 -5.58761215e+00 -5.63079929e+00 -6.79545784e+00 -7.58464575e+00 -8.26450157e+00 -9.18833828e+00 -8.94510651e+00 -8.32516289e+00 -6.70681906e+00 -6.70870972e+00 -7.03272820e+00 -7.63580418e+00 -7.79871082e+00 -7.49132204e+00 -7.26768684e+00 -7.90362072e+00 -8.13398361e+00 -8.78059864e+00 -8.70844173e+00 -8.93018627e+00 -9.38008308e+00 -9.42391109e+00 -9.86197376e+00 -1.04967251e+01 -9.90739250e+00 -8.80712700e+00 -7.89835835e+00 -8.60505295e+00 -9.42263889e+00 -9.19470406e+00 -9.56866646e+00 -1.02243290e+01 -1.10227909e+01 -1.11179228e+01 -1.09573841e+01 -1.03514347e+01 -1.03489676e+01 -1.01490564e+01 -9.56706429e+00 -9.29565430e+00 -8.98949718e+00 -8.90742111e+00 -1.02561808e+01 -9.99060917e+00 -1.01375456e+01 -9.26448727e+00 -9.47739220e+00 -9.70584106e+00 -9.41415691e+00 -9.64314842e+00 -9.74204731e+00 -1.01330175e+01 -1.07260647e+01 -1.17721586e+01 -1.28357248e+01 -1.34853697e+01 -1.32000952e+01 -1.32843466e+01 -1.18578596e+01 -1.12494278e+01 -1.03350801e+01 -1.08081074e+01 -1.11178741e+01 -1.18460779e+01 -1.24368258e+01 -1.21875906e+01 -1.18356504e+01 -1.07860079e+01 -1.00339031e+01 -9.91325855e+00 -1.01805220e+01 -1.08105021e+01 -1.13966579e+01 -1.17543001e+01 -1.21970339e+01 -1.29166994e+01 -1.25529966e+01 -1.20717211e+01 -1.08883820e+01 -1.13708639e+01 -1.22288647e+01 -1.25893011e+01 -1.27215986e+01 -1.22508812e+01 -1.18739023e+01 -1.09879417e+01 -1.13483057e+01 -1.13050394e+01 -1.17069092e+01 -1.15444927e+01 -1.14945984e+01 -1.18791142e+01 -1.22210360e+01 -1.23263721e+01 -1.18329992e+01 -1.20013037e+01 -1.26545563e+01 -1.35480080e+01 -1.47485847e+01 -1.36990538e+01 -1.29700928e+01 -1.23574562e+01 -1.37672682e+01 -1.37132044e+01 -1.43540440e+01 -1.40332699e+01 -1.51367579e+01 -1.49847660e+01 -1.50987606e+01 -1.46604567e+01 -1.38757305e+01 -1.40549040e+01 -1.42717466e+01 -1.51484423e+01 -1.50770330e+01 -1.50445604e+01 -1.44101372e+01 -1.42932892e+01 -1.42048082e+01 -1.45567799e+01 -1.44763184e+01 -1.47929029e+01 -1.54390888e+01 -1.65148163e+01 -1.57744265e+01 -1.39766245e+01 -1.36146460e+01 -1.51079979e+01 -1.60293121e+01 -1.54441624e+01 -1.46705418e+01 -1.46000862e+01 -1.44213505e+01 -1.41413546e+01 -1.37672138e+01 -1.43480473e+01 -1.44933786e+01 -1.43266392e+01 -1.38373022e+01 -1.48024445e+01 -1.52284012e+01 -1.52315693e+01 -1.51071072e+01 -1.61434231e+01 -1.60149651e+01 -1.54812670e+01 -1.46641665e+01 -1.52923479e+01 -1.52856998e+01 -1.47014112e+01 -1.46258631e+01 -1.48532572e+01 -1.54652891e+01 -1.55440960e+01 -1.53159285e+01 -1.55166616e+01 -1.63042755e+01 -1.65980320e+01 -1.65593128e+01 -1.59985056e+01 -1.57961655e+01 -1.53858881e+01 -1.56961279e+01 -1.66037006e+01 -1.73427067e+01 -1.73687477e+01 -1.70415363e+01 -1.73016014e+01 -1.78671932e+01 -1.78487511e+01 -1.73102341e+01 -1.60505009e+01 -1.51642065e+01 -1.52663040e+01 -1.56166124e+01 -1.61478729e+01 -1.65824966e+01 -1.73490086e+01 -1.77052765e+01 -1.72898502e+01 -1.71111107e+01 -1.72336063e+01 -1.72175636e+01 -1.70349903e+01 -1.69972839e+01 -1.69730740e+01 -1.72409286e+01 -1.70907059e+01 -1.78417759e+01 -1.81255398e+01 -1.79898129e+01 -1.73827133e+01 -1.67932091e+01 -1.73335419e+01 -1.71179752e+01 -1.71523914e+01 -1.75193958e+01 -1.85648746e+01 -1.95460472e+01 -1.96041603e+01 -1.91943398e+01 -1.87831173e+01 -1.87523327e+01 -1.86477528e+01 -1.86194477e+01 -1.84588280e+01 -1.85440407e+01 -1.85874996e+01 -1.88543549e+01 -1.91772346e+01 -1.90876503e+01 -1.85815620e+01 -1.79599609e+01 -1.81342049e+01 -1.85685863e+01 -1.88718357e+01 -1.85083637e+01 -1.85150261e+01 -1.88005333e+01 -1.85854607e+01 -1.78175011e+01 -1.73513260e+01 -1.75701180e+01 -1.81055050e+01 -1.78759804e+01 -1.75392437e+01 -1.75233803e+01 -1.77736149e+01 -1.82400513e+01 -1.83745003e+01 -1.83229599e+01 -1.81948013e+01 -1.80757599e+01 -1.86101017e+01 -1.93275185e+01 -1.97894821e+01 -1.98871384e+01 -1.94180412e+01 -1.90252228e+01 -1.87780819e+01 -1.89574013e+01 -1.90200005e+01 -1.89992695e+01 -1.88002892e+01 -1.87035007e+01 -1.82688141e+01 -1.86731644e+01 -1.90366383e+01 -1.98031330e+01 -1.97468395e+01 -1.95801907e+01 -1.97886581e+01 -2.00002823e+01 -2.00059719e+01 -1.96717548e+01 -1.94205055e+01 -1.95128002e+01 -1.94361305e+01 -1.95444584e+01 -1.96223202e+01 -1.97272396e+01 -1.98175068e+01 -1.97441578e+01 -1.98023529e+01 -1.97687073e+01 -1.96773205e+01 -1.95016823e+01 -1.95685787e+01 -1.97285461e+01 -1.99104500e+01 -1.98999519e+01 -1.99750042e+01 -2.00239048e+01 -1.98760738e+01 -1.97041225e+01 -1.96669712e+01 -2.00360661e+01 -2.01999397e+01 -2.00989571e+01 -1.98293209e+01 -1.96929874e+01 -1.98111820e+01 -1.99962940e+01 -2.02205734e+01 -2.02565422e+01 -2.01618176e+01 -1.97555504e+01 -1.98723850e+01 -2.01384716e+01 -2.03722115e+01 -2.03966942e+01 -2.00175495e+01 -2.02969170e+01 -2.04069939e+01 -2.04131508e+01 -2.00554771e+01 -1.98452435e+01 -2.01250172e+01 -2.03222637e+01 -2.02617607e+01 -2.01979580e+01 -2.01702290e+01 -2.02551289e+01 -2.03511066e+01 -2.05100250e+01 -2.07154350e+01 -2.06661510e+01 -2.04950237e+01 -2.03693676e+01 -2.03906384e+01 -2.04741554e+01 -2.04393368e+01 -2.04501438e+01 -2.04680729e+01 -2.04190998e+01 -2.04458122e+01 -2.03228054e+01 -2.03932838e+01 -2.03616142e+01 -2.03438778e+01 -2.03143711e+01 -2.04206944e+01 -2.05857830e+01 -2.07119808e+01 -2.05868301e+01 -2.04554214e+01 -2.03763084e+01 -2.04141102e+01 -2.05392590e+01 -2.06822510e+01 -2.08130093e+01 -2.10067272e+01 -2.07645073e+01 -2.06834145e+01 -2.08147030e+01 -2.44961567e+01 -2.92043591e+01 -9.87035370e+01 -2.09306580e+02 19313596. 70713560. 0. 0. 0. 0. 0. -252229952. 1.63276025e+06 -1.68809509e+02 -1.36874536e+03 -11309393. 32765716. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 407427488. 7.45190674e+02 -2.28827477e+00 -3.82274895e+01 -4.10569115e+01 -3.84589310e+01 -3.91496201e+01 -3.81649857e+01 -3.82942657e+01 -3.83990707e+01 -3.84078712e+01 -3.83756332e+01 -3.83194847e+01 -3.81282692e+01 -3.79576416e+01 -3.78389282e+01 -3.79761543e+01 -3.81930923e+01 -3.82312698e+01 -3.82476616e+01 -3.79386597e+01 -3.77250710e+01 -3.74008751e+01 -3.74545364e+01 -3.76195831e+01 -3.78028641e+01 -3.78107452e+01 -3.82207565e+01 -3.83363037e+01 -3.80865326e+01 -3.73485985e+01 -3.69017639e+01 -3.71215591e+01 -3.74212151e+01 -3.79084129e+01 -3.79539146e+01 -3.78768921e+01 -3.77382774e+01 -3.74974518e+01 -3.74066429e+01 -3.71562271e+01 -3.68848114e+01 -3.69937706e+01 -3.72726898e+01 -3.74288139e+01 -3.71754761e+01 -3.71603775e+01 -3.73806076e+01 -3.72024460e+01 -3.69937668e+01 -3.70199203e+01 -3.70805931e+01 -3.75819550e+01 -3.76808815e+01 -3.77241974e+01 -3.68085747e+01 -3.60126877e+01 -3.57981911e+01 -3.63538361e+01 -3.70571175e+01 -3.69033432e+01 -3.66136246e+01 -3.62601051e+01 -3.64776649e+01 -3.65271339e+01 -3.61621780e+01 -3.57713470e+01 -3.57971382e+01 -3.63937874e+01 -3.70234642e+01 -3.67038040e+01 -3.66163483e+01 -3.66233978e+01 -3.64480057e+01 -3.62379456e+01 -3.59478416e+01 -3.62322998e+01 -3.69149132e+01 -3.72494202e+01 -3.74949493e+01 -3.64976883e+01 -3.58475838e+01 -3.45911102e+01 -3.48666115e+01 -3.56496010e+01 -3.60783119e+01 -3.58471870e+01 -3.58814468e+01 -3.69655952e+01 -3.64396515e+01 -3.53964767e+01 -3.39588280e+01 -3.43254509e+01 -3.57793198e+01 -3.65563927e+01 -3.63772011e+01 -3.54240379e+01 -3.62507896e+01 -3.58628464e+01 -3.58257675e+01 -3.46838608e+01 -3.48582726e+01 -3.52950020e+01 -3.58302498e+01 -3.62757950e+01 -3.53111115e+01 -3.45778694e+01 -3.37965736e+01 -3.38282051e+01 -3.47884140e+01 -3.52970352e+01 -3.51566200e+01 -3.47498207e+01 -3.53089790e+01 -3.55291405e+01 -3.52174149e+01 -3.42968254e+01 -3.40838814e+01 -3.42341080e+01 -3.48537827e+01 -3.53298836e+01 -3.50984764e+01 -3.47843895e+01 -3.33670959e+01 -3.29110069e+01 -3.32472076e+01 -3.36563988e+01 -3.40161552e+01 -3.50098915e+01 -3.54823380e+01 -3.52291641e+01 -3.42332954e+01 -3.38054314e+01 -3.31332512e+01 -3.25121651e+01 -3.24764099e+01 -3.32937164e+01 -3.33437271e+01 -3.37766266e+01 -3.43621407e+01 -3.46735954e+01 -3.32080650e+01 -3.15103092e+01 -2.99431839e+01 -3.04642963e+01 -3.06773949e+01 -3.15972710e+01 -3.18719883e+01 -3.18657646e+01 -3.12188110e+01 -3.13876381e+01 -3.15489082e+01 -3.14647331e+01 -3.20506783e+01 -3.27221756e+01 -3.29401169e+01 -3.19072514e+01 -3.09876633e+01 -3.14752312e+01 -3.10487614e+01 -3.10366573e+01 -2.98695965e+01 -2.95772953e+01 -3.03879776e+01 -3.07334576e+01 -3.15184402e+01 -2.99065437e+01 -2.88158073e+01 -2.74270267e+01 -2.91532574e+01 -3.07115364e+01 -3.15744324e+01 -3.18239613e+01 -3.18994732e+01 -3.16958542e+01 -3.01972294e+01 -2.79564342e+01 -2.79602585e+01 -2.93078060e+01 -3.21686668e+01 -3.17474728e+01 -2.96837902e+01 -2.86195984e+01 -2.73023796e+01 -2.79348030e+01 -2.65911160e+01 -2.76500149e+01 -2.71091805e+01 -2.90167427e+01 -2.90975704e+01 -2.94737968e+01 -2.83750210e+01 -2.88562469e+01 -2.82602997e+01 -2.94355755e+01 -3.04612331e+01 -3.06552429e+01 -3.06609688e+01 -3.04164925e+01 -3.12879524e+01 -2.90349388e+01 -2.74693394e+01 -2.67986164e+01 -2.85691605e+01 -3.15212097e+01 -3.06723995e+01 -3.03864861e+01 -2.71902580e+01 -2.87016926e+01 -2.86253548e+01 -2.85110569e+01 -2.72130928e+01 -2.80558453e+01 -2.87484913e+01 -2.92096634e+01 -2.73675518e+01 -2.65654888e+01 -2.41677189e+01 -2.54306316e+01 -2.75772171e+01 -3.05725651e+01 -2.96851101e+01 -2.77086029e+01 -2.57146969e+01 -2.51410618e+01 -2.46612034e+01 -2.65590649e+01 -2.71570072e+01 -2.76886787e+01 -2.66911983e+01 -2.63391361e+01 -2.55581932e+01 -2.66421909e+01 -2.69472504e+01 -2.69063072e+01 -2.49492817e+01 -2.46092339e+01 -2.45863018e+01 -2.50580387e+01 -2.61936588e+01 -2.66269093e+01 -2.42668266e+01 -2.19064388e+01 -2.24309330e+01 -2.50978851e+01 -2.61964989e+01 -2.62333107e+01 -2.47926044e+01 -2.38547077e+01 -2.18827839e+01 -2.10766525e+01 -2.08504581e+01 -2.13363476e+01 -2.43298950e+01 -2.19265690e+01 -2.29994373e+01 -2.12803841e+01 -2.46249084e+01 -2.28574581e+01 -2.21626835e+01 -2.02263298e+01 -1.87648830e+01 -2.01420822e+01 -2.09738331e+01 -2.25861931e+01 -2.36793785e+01 -2.13233204e+01 -1.90503426e+01 -1.74323978e+01 -2.00399609e+01 -1.95881214e+01 -1.84874287e+01 -1.68882046e+01 -2.01001148e+01 -2.12121925e+01 -2.21535225e+01 -2.14538517e+01 -2.12864017e+01 -2.14184780e+01 -1.97010155e+01 -1.98443317e+01 -1.84395409e+01 -2.14526386e+01 -2.22008896e+01 -2.27911587e+01 -2.21631927e+01 -2.02713356e+01 -2.11558762e+01 -2.00496731e+01 -1.99995289e+01 -1.83670807e+01 -1.69505882e+01 -1.51695843e+01 -1.58857403e+01 -1.51686993e+01 -1.53415766e+01 -1.45725689e+01 -1.76895676e+01 -1.84924030e+01 -1.90878315e+01 -1.51506557e+01 -1.56447449e+01 -1.62357864e+01 -1.85384693e+01 -1.71898174e+01 -1.56466265e+01 -1.45474319e+01 -1.59398470e+01 -1.54973717e+01 -1.64782314e+01 -1.53718538e+01 -1.64825115e+01 -1.57801542e+01 -1.71347103e+01 -1.78078232e+01 -1.92189064e+01 -1.68918381e+01 -1.32797909e+01 -1.19235859e+01 -1.36962423e+01 -1.46650896e+01 -1.33219452e+01 -1.16144276e+01 -1.45905113e+01 -1.56448641e+01 -1.53227444e+01 -1.47975721e+01 -1.51438160e+01 -1.56016445e+01 -1.36151981e+01 -1.35520163e+01 -1.43109226e+01 -1.40665712e+01 -1.36126957e+01 -1.31928616e+01 -1.46156464e+01 -1.33132696e+01 -1.23139277e+01 -1.07020445e+01 -1.18047333e+01 -1.03281755e+01 -9.72921467e+00 -7.95305920e+00 -1.14215183e+01 -1.17988939e+01 -1.13729315e+01 -8.09591770e+00 -8.00433731e+00 -9.95946503e+00 -1.15404234e+01 -1.04512062e+01 -1.11464357e+01 -1.22308445e+01 -1.42782679e+01 -1.30631094e+01 -1.10867710e+01 -1.00400724e+01 -9.81682396e+00 -1.06071234e+01 -1.05026064e+01 -1.21458063e+01 -1.28246222e+01 -9.80579281e+00 -7.17225170e+00 -4.54870844e+00 -7.29938698e+00 -7.52812147e+00 -9.11263847e+00 -9.11153030e+00 -9.37839508e+00 -9.82407951e+00 -9.63410282e+00 -8.79543495e+00 -6.44976521e+00 -3.06110024e+00 -1.80620432e+00 -2.66523242e+00 -7.04766226e+00 -9.31522560e+00 -8.84921455e+00 -6.51932430e+00 -8.31296253e+00 -1.10156918e+01 -1.24609184e+01 -9.53498554e+00 -9.01126575e+00 -8.59341049e+00 -7.45525742e+00 -4.64652157e+00 -2.36954165e+00 -1.74371028e+00 -4.24900055e+00 -5.34829473e+00 -6.35164022e+00 -4.54440975e+00 -2.29746652e+00 -1.52603865e+00 -3.95077229e-01 -3.41897702e+00 -3.55398536e+00 -4.77103424e+00 -5.41292763e+00 -7.76559973e+00 -6.63304186e+00 -1.63436043e+00 9.87384319e-01 9.46679354e-01 -1.55670440e+00 -2.61301994e+00 -2.83657455e+00 -4.61747599e+00 -3.31179261e+00 -1.37821949e+00 1.77633852e-01 1.38060480e-01 -9.35398042e-03 -5.13479412e-01 2.29170823e+00 1.93524289e+00 3.75448275e+00 2.90587127e-01 -1.68761104e-01 -1.89138520e+00 -4.60385501e-01 1.81047952e+00 4.25091839e+00 3.97131371e+00 6.01400495e-01 -2.92031908e+00 -1.90964532e+00 -1.41186941e+00 1.98265815e+00 -4.50973272e-01 -4.27211225e-01 -1.10889065e+00 -1.42472792e+00 -1.56621993e+00 -2.28590012e+00 2.26489305e-01 1.01237416e+00 8.61215234e-01 -1.07195604e+00 -1.52612829e+00 4.11863565e-01 3.42815781e+00 4.77796316e+00 2.91529369e+00 5.95524251e-01 -1.21728778e+00 -9.35955346e-01 3.44173932e+00 5.42023087e+00 5.75463486e+00 1.12219787e+00 6.14841104e-01 4.55647886e-01 2.80896997e+00 2.92385364e+00 8.65021348e-01 2.13150167e+00 3.14470172e+00 5.39897156e+00 3.29239821e+00 2.90656805e+00 7.54350519e+00 7.53628683e+00 6.51518202e+00 3.46628618e+00 3.99455810e+00 6.51969194e+00 4.45376778e+00 3.82006025e+00 2.71876216e+00 4.45360327e+00 6.33357286e+00 6.52583265e+00 6.57095909e+00 5.23979616e+00 4.19965553e+00 4.79840565e+00 5.04822731e+00 5.95933342e+00 6.44533443e+00 5.29635811e+00 5.77466822e+00 4.83296919e+00 5.41548681e+00 7.64369059e+00 9.69043827e+00 1.08839445e+01 8.35594463e+00 6.23756075e+00 5.04507303e+00 6.05220222e+00 8.24734688e+00 1.04523926e+01 1.00472670e+01 8.35751057e+00 7.04781055e+00 8.36800194e+00 1.07660532e+01 1.15463867e+01 9.10952950e+00 6.84629965e+00 7.31287813e+00 7.98275995e+00 8.92830944e+00 1.12345238e+01 1.21417627e+01 1.43039837e+01 1.08473005e+01 1.04275646e+01 9.33215237e+00 1.12748718e+01 1.27702312e+01 1.43249407e+01 1.25356178e+01 1.23139505e+01 8.59420776e+00 1.15556765e+01 1.04249744e+01 1.03159580e+01 7.60454273e+00 9.25027466e+00 1.54922476e+01 1.86310329e+01 1.71499405e+01 1.18305492e+01 8.09379387e+00 8.58092976e+00 8.11546898e+00 1.08374043e+01 1.16569777e+01 1.37240696e+01 1.39544401e+01 1.27638979e+01 1.29243126e+01 1.44813662e+01 1.50602846e+01 1.49331942e+01 1.36270332e+01 1.30478220e+01 1.31016636e+01 1.23440037e+01 1.47746286e+01 1.42888565e+01 1.29513245e+01 1.09659967e+01 1.08514719e+01 1.21579657e+01 1.25031300e+01 1.42339573e+01 1.44569416e+01 1.31574879e+01 1.18224115e+01 1.19447680e+01 1.41412849e+01 1.55714979e+01 1.49090567e+01 1.48678665e+01 1.52062778e+01 1.53307590e+01 1.61979980e+01 1.81875267e+01 1.83995171e+01 1.65011311e+01 1.36030111e+01 1.51321325e+01 1.56750431e+01 1.80911560e+01 1.84228153e+01 1.82480755e+01 1.54099922e+01 1.43144636e+01 1.54413338e+01 1.49284239e+01 1.58744307e+01 1.58243189e+01 1.73070278e+01 1.79649830e+01 1.88320580e+01 2.12485695e+01 2.15063496e+01 2.10338097e+01 1.91938362e+01 1.83876781e+01 1.93891926e+01 2.26364822e+01 2.05084324e+01 2.18751087e+01 1.95881271e+01 2.13591232e+01 1.93401470e+01 1.86766014e+01 2.01737137e+01 1.96826420e+01 2.02648716e+01 1.93580894e+01 1.97567234e+01 2.16515636e+01 2.29999962e+01 2.44165344e+01 2.28838692e+01 2.01844540e+01 1.85450153e+01 1.89910316e+01 2.04704189e+01 2.06522217e+01 1.91523933e+01 2.05737572e+01 1.56154289e+01 1.79298115e+01 1.60134830e+01 2.01645298e+01 2.08249493e+01 3.12347126e+01 1.76158752e+01 4.42107430e+01 2.38293896e+01 -2.67170925e+01 -3.22650909e+02 14296129. -632457472. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.27612750e+05 -2.88287903e+02 -4.53333664e+01 1.42855997e+01 1.95233459e+01 -1.19266987e+01 -2.24630489e+01 1.28953943e+01 1.98214397e+01 2.28640804e+01 2.69668732e+01 2.70611649e+01 2.80451679e+01 2.92447891e+01 3.00638313e+01 2.97082806e+01 2.83933678e+01 2.89149818e+01 2.94158592e+01 3.03691311e+01 2.93838730e+01 2.94116116e+01 2.82690983e+01 2.78843346e+01 2.75430069e+01 2.92519779e+01 3.13574429e+01 3.15805359e+01 3.10847931e+01 3.10472660e+01 3.13725033e+01 3.09906712e+01 3.07633476e+01 2.97265549e+01 2.92257671e+01 2.88241444e+01 3.00800533e+01 3.09902077e+01 3.22338829e+01 3.27653236e+01 3.28719254e+01 3.17727814e+01 3.23277779e+01 3.29035225e+01 3.35058708e+01 3.43518181e+01 3.34102783e+01 3.20100746e+01 3.01804352e+01 3.00294056e+01 3.15386143e+01 3.12808094e+01 3.17187347e+01 3.07155476e+01 3.07111511e+01 3.09184990e+01 3.17479954e+01 3.29580688e+01 3.37045593e+01 3.37287979e+01 3.30526772e+01 3.22083092e+01 3.28271179e+01 3.38804474e+01 3.35084763e+01 3.24358673e+01 3.13267212e+01 3.18664970e+01 3.33444290e+01 3.45184975e+01 3.54579124e+01 3.58732491e+01 3.58135185e+01 3.47854309e+01 3.38852234e+01 3.41229401e+01 3.31085701e+01 3.23382874e+01 3.11924076e+01 3.21799622e+01 3.40429001e+01 3.46265297e+01 3.54444199e+01 3.46438789e+01 3.47111511e+01 3.42643318e+01 3.44824371e+01 3.52894135e+01 3.51552124e+01 3.50349083e+01 3.50218048e+01 3.56838646e+01 3.62061615e+01 3.57253113e+01 3.49964790e+01 3.52737007e+01 3.52333527e+01 3.54869919e+01 3.49844971e+01 3.50269547e+01 3.54282990e+01 3.58705521e+01 3.57659874e+01 3.46041412e+01 3.36767120e+01 3.41753998e+01 3.47019501e+01 3.59519691e+01 3.57292595e+01 3.65617294e+01 3.63552094e+01 3.61098442e+01 3.56462212e+01 3.58686180e+01 3.61697159e+01 3.62624702e+01 3.54624481e+01 3.57748947e+01 3.57740479e+01 3.57243385e+01 3.61040344e+01 3.58997231e+01 3.56413116e+01 3.46889954e+01 3.49701042e+01 3.61886101e+01 3.69356766e+01 3.66257324e+01 3.59211922e+01 3.56757851e+01 3.66604881e+01 3.66956329e+01 3.68296852e+01 3.61161995e+01 3.59545364e+01 3.56109543e+01 3.55310822e+01 3.64397697e+01 3.70513954e+01 3.72458763e+01 3.68145561e+01 3.64026184e+01 3.69100723e+01 3.69699440e+01 3.69908791e+01 3.70257759e+01 3.74847450e+01 3.78490906e+01 3.79172668e+01 3.77625275e+01 3.80452003e+01 3.78441620e+01 3.76150513e+01 3.67475281e+01 3.62534752e+01 3.63371124e+01 3.68446808e+01 3.74139671e+01 3.75577316e+01 3.76523094e+01 3.76917229e+01 3.76590309e+01 3.75407372e+01 3.76101875e+01 3.78205528e+01 3.80839500e+01 3.78265648e+01 3.73123131e+01 3.70033989e+01 3.70489731e+01 3.77646713e+01 3.79987373e+01 3.78784065e+01 3.74510002e+01 3.74974022e+01 3.76900291e+01 3.76192436e+01 3.76224861e+01 3.77046738e+01 3.78639069e+01 3.78955231e+01 3.78822365e+01 3.79609261e+01 3.80274696e+01 3.79544258e+01 3.80675964e+01 3.81401215e+01 3.82920494e+01 3.82423401e+01 3.83465347e+01 3.85688858e+01 3.84420738e+01 3.82733688e+01 3.80366554e+01 3.80500565e+01 3.82731285e+01 3.82989426e+01 3.82717247e+01 3.79734840e+01 3.79786415e+01 3.80292892e+01 3.82124634e+01 3.83180084e+01 3.82903824e+01 3.82959595e+01 3.82484207e+01 3.82388382e+01 3.81889763e+01 3.82063484e+01 3.81985855e+01 3.82225037e+01 3.81667023e+01 3.82085381e+01 3.80906792e+01 3.81136742e+01 3.81721077e+01 3.82475243e+01 3.82177620e+01 3.81284409e+01 3.81049652e+01 3.81110306e+01 3.81184311e+01 3.81278191e+01 3.81332207e+01 3.81415176e+01 3.81477051e+01 3.81505470e+01 3.81328735e+01 3.81217880e+01 3.81351700e+01 3.81468849e+01 3.81558609e+01 3.81275330e+01 3.81312141e+01 3.81240807e+01 3.80899315e+01 3.80720596e+01 3.81114845e+01 3.80796814e+01 3.80584908e+01 3.80082283e+01 3.80326004e+01 3.80832596e+01 3.80964813e+01 3.81106224e+01 3.82571068e+01 3.82607193e+01 3.82543297e+01 3.79959412e+01 3.80142059e+01 3.79465027e+01 3.80253220e+01 3.78004532e+01 3.77966042e+01 3.77694702e+01 3.79185257e+01 3.78798752e+01 3.77450562e+01 3.77684669e+01 3.77902489e+01 3.78790970e+01 3.77537956e+01 3.78066406e+01 3.77459297e+01 3.77703476e+01 3.80125351e+01 3.78833580e+01 3.78288574e+01 3.75799294e+01 3.75868874e+01 3.78259354e+01 3.77320518e+01 3.77296257e+01 3.76752930e+01 3.77868462e+01 3.77139091e+01 3.75668221e+01 3.73612823e+01 3.74679871e+01 3.75597267e+01 3.76309471e+01 3.75601234e+01 3.74092712e+01 3.78457870e+01 3.79054451e+01 3.82076950e+01 3.80007439e+01 3.79001274e+01 3.77232018e+01 3.73422623e+01 3.71814728e+01 3.70110321e+01 3.69901848e+01 3.70417023e+01 3.70681496e+01 3.67186966e+01 3.65223656e+01 3.64937553e+01 3.61391296e+01 3.66890297e+01 3.66338196e+01 3.69828339e+01 3.67108002e+01 3.70675850e+01 3.73051796e+01 3.69309044e+01 3.63522377e+01 3.63767090e+01 3.67382126e+01 3.68883247e+01 3.64906616e+01 3.61437035e+01 3.52617226e+01 3.55423965e+01 3.53111343e+01 3.62159805e+01 3.59925842e+01 3.63379669e+01 3.59690399e+01 3.60475502e+01 3.64736595e+01 3.73220253e+01 3.71721687e+01 3.63931923e+01 3.55330544e+01 3.52821198e+01 3.53222008e+01 3.51720772e+01 3.52010078e+01 3.56279182e+01 3.58706512e+01 3.59268303e+01 3.54890976e+01 3.52394028e+01 3.54004478e+01 3.54926262e+01 3.55064850e+01 3.50249634e+01 3.48520317e+01 3.47010689e+01 3.50919418e+01 3.49669266e+01 3.49759750e+01 3.43047333e+01 3.38630257e+01 3.40638771e+01 3.42157593e+01 3.43992577e+01 3.37914276e+01 3.38071327e+01 3.35642052e+01 3.43313637e+01 3.46759453e+01 3.49587326e+01 3.34746399e+01 3.27247772e+01 3.22905540e+01 3.33772316e+01 3.41423264e+01 3.39088020e+01 3.39571686e+01 3.29732513e+01 3.32716713e+01 3.43120384e+01 3.56079865e+01 3.56345901e+01 3.45179291e+01 3.37718277e+01 3.32392731e+01 3.31928329e+01 3.29971886e+01 3.28095093e+01 3.29679985e+01 3.32305756e+01 3.38512383e+01 3.36920395e+01 3.36719208e+01 3.23141251e+01 3.13024902e+01 3.09780998e+01 3.14535484e+01 3.22445488e+01 3.25712662e+01 3.25506134e+01 3.25716515e+01 3.31089134e+01 3.28621101e+01 3.25179672e+01 3.16824169e+01 3.24075813e+01 3.27198830e+01 3.26168633e+01 3.14767227e+01 3.14759235e+01 3.12726727e+01 3.15448055e+01 3.14017563e+01 3.16725349e+01 3.17235203e+01 3.22836761e+01 3.19015198e+01 3.15949974e+01 3.01930637e+01 2.87229176e+01 2.79795303e+01 2.84367752e+01 2.98282070e+01 3.01516571e+01 2.99992962e+01 3.00762844e+01 3.00949459e+01 2.97724724e+01 2.89798737e+01 2.88318462e+01 2.92948208e+01 3.01750851e+01 3.04787941e+01 3.02747841e+01 2.94220638e+01 2.91357574e+01 2.88310108e+01 2.91959209e+01 2.90716953e+01 2.88384609e+01 2.93656979e+01 3.01486473e+01 3.11951504e+01 3.12901173e+01 3.05478134e+01 2.96873856e+01 2.90364494e+01 2.85784092e+01 2.86398048e+01 2.88278923e+01 2.88264904e+01 2.89904804e+01 2.96632614e+01 3.00027771e+01 3.01275902e+01 2.92862816e+01 2.82385521e+01 2.78627052e+01 2.69991684e+01 2.73404083e+01 2.71564465e+01 2.76379871e+01 2.63167458e+01 2.45047779e+01 2.55477848e+01 2.87962456e+01 3.50669174e+01 3.56341438e+01 3.69849014e+01 3.51742477e+01 3.38260956e+01 4.51157227e+01 4.99135818e+01 4.24219971e+01 2.27659340e+01 4.77895050e+02 5.01916473e+02 -1.87108184e+04 -138219504. 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. 0. 0. 0. 0. 0. 0. 0. 81798760. 7.88300049e+03 1.44549255e+03 1.07394402e+02 3.22111397e+01 1.13723593e+01 9.08708420e+01 9.41955795e+01 4.26246719e+01 2.95304470e+01 2.52248859e+01 2.68242435e+01 2.58337173e+01 2.44755936e+01 2.18062649e+01 2.26072865e+01 2.28308010e+01 2.25913048e+01 2.17787266e+01 2.09876900e+01 2.01456604e+01 1.97436695e+01 1.93789196e+01 1.91835995e+01 2.01028557e+01 2.09146442e+01 2.04752750e+01 1.87079277e+01 1.80673351e+01 1.84616394e+01 1.93006191e+01 1.89943562e+01 1.73975849e+01 1.69308910e+01 1.64399414e+01 1.82811356e+01 1.84745064e+01 1.91302795e+01 1.84049702e+01 1.82773056e+01 1.80146751e+01 1.73988113e+01 1.69583588e+01 1.68197689e+01 1.71350479e+01 1.66618652e+01 1.59825106e+01 1.56793089e+01 1.56067677e+01 1.51624870e+01 1.53039799e+01 1.47747965e+01 1.48146257e+01 1.34784365e+01 1.42212124e+01 1.42597122e+01 1.49389267e+01 1.41343851e+01 1.42643528e+01 1.36217270e+01 1.39208879e+01 1.31333046e+01 1.53059349e+01 1.68722382e+01 1.79277687e+01 1.66282291e+01 1.52965555e+01 1.49875584e+01 1.55898972e+01 1.49749174e+01 1.53281450e+01 1.45804882e+01 1.39517355e+01 1.36486664e+01 1.26952848e+01 1.16599903e+01 9.16912556e+00 7.22321224e+00 7.78931761e+00 1.06571293e+01 1.27289972e+01 1.29977398e+01 1.18386316e+01 1.36661062e+01 1.47847195e+01 1.57234468e+01 1.45587673e+01 1.39900904e+01 1.30432968e+01 1.29855509e+01 1.31375790e+01 1.29238462e+01 1.35826225e+01 1.38160477e+01 1.36391096e+01 1.19589672e+01 1.06814909e+01 1.09896746e+01 1.09846210e+01 1.09534483e+01 1.06703005e+01 1.01110573e+01 9.05222416e+00 8.61145878e+00 8.35793495e+00 9.36802006e+00 9.52078438e+00 8.99598217e+00 9.66460609e+00 1.03514338e+01 1.20651503e+01 1.14327793e+01 9.77384281e+00 7.38749886e+00 6.68293428e+00 6.74077606e+00 7.56234312e+00 8.01338768e+00 8.05674648e+00 7.79487848e+00 7.08394718e+00 7.71166801e+00 7.44069195e+00 6.85619259e+00 5.92952919e+00 5.85758495e+00 6.46589518e+00 6.30028582e+00 7.81737232e+00 8.40098953e+00 8.84231853e+00 7.14109278e+00 5.64264250e+00 5.61976576e+00 5.95695066e+00 7.97645044e+00 9.13006306e+00 8.74421501e+00 6.73791790e+00 5.60979128e+00 4.68460560e+00 4.14809656e+00 3.30885649e+00 3.54505038e+00 3.37110662e+00 3.59563589e+00 3.33761525e+00 3.67541718e+00 3.57610655e+00 3.23211956e+00 2.66643953e+00 2.36434340e+00 2.53199697e+00 3.51573086e+00 5.06048298e+00 4.88984108e+00 4.59434128e+00 2.91744947e+00 4.54853392e+00 5.03328991e+00 5.04526377e+00 5.22136688e+00 5.38171625e+00 5.96049833e+00 4.53179502e+00 3.73702598e+00 2.38577056e+00 2.08534122e+00 1.07120824e+00 9.35910344e-01 1.45797288e+00 1.83403587e+00 2.40064597e+00 1.81426728e+00 2.05957103e+00 6.20800674e-01 -1.07926202e+00 -3.22218418e+00 -2.83463740e+00 -1.44727361e+00 -3.33585769e-01 -5.35946667e-01 -6.31109297e-01 -6.45336688e-01 -2.18957400e+00 -2.11224437e+00 -1.72662497e+00 -7.69496143e-01 -1.13181102e+00 -1.63277185e+00 -9.47118104e-01 -1.52270472e+00 -1.39493620e+00 -1.87290525e+00 -1.63366628e+00 -1.65525150e+00 -2.74425173e+00 -3.39936495e+00 -3.73175240e+00 -3.27997398e+00 -2.42343640e+00 -3.18542838e+00 -4.25594425e+00 -4.50889635e+00 -4.00124931e+00 -3.09162283e+00 -3.88706803e+00 -3.34873176e+00 -3.90681767e+00 -4.80301428e+00 -4.98075247e+00 -4.28719425e+00 -3.70457816e+00 -4.53517962e+00 -4.16299295e+00 -4.19183540e+00 -4.99330139e+00 -5.25235462e+00 -4.58317614e+00 -3.54896593e+00 -4.40847445e+00 -4.92821836e+00 -4.92403841e+00 -4.38408566e+00 -4.30915022e+00 -4.73510408e+00 -6.56495333e+00 -7.61324692e+00 -8.20683002e+00 -7.96368170e+00 -8.69667530e+00 -8.52938652e+00 -8.80538559e+00 -8.75903606e+00 -9.57379818e+00 -9.85767460e+00 -9.49651241e+00 -8.70956039e+00 -9.11489964e+00 -9.05331516e+00 -8.50465870e+00 -8.24797344e+00 -8.46630955e+00 -8.75142288e+00 -8.75411510e+00 -9.41660595e+00 -1.12394743e+01 -1.25830956e+01 -1.02642460e+01 -7.38082933e+00 -6.28342104e+00 -6.92861319e+00 -8.14507580e+00 -6.52039671e+00 -6.99972963e+00 -7.78147268e+00 -9.40266132e+00 -1.01936445e+01 -9.72950554e+00 -1.06693554e+01 -1.12975054e+01 -1.18633585e+01 -1.10797663e+01 -9.72331715e+00 -9.31653500e+00 -8.92559147e+00 -9.85096645e+00 -1.01625690e+01 -1.05553312e+01 -1.14400101e+01 -1.27116833e+01 -1.38481741e+01 -1.33088760e+01 -1.35604982e+01 -1.35685558e+01 -1.35145254e+01 -1.28674622e+01 -1.22253485e+01 -1.20338879e+01 -1.10862751e+01 -1.17544489e+01 -1.23751316e+01 -1.45870314e+01 -1.49303675e+01 -1.60479965e+01 -1.60614891e+01 -1.48136320e+01 -1.46334743e+01 -1.57619009e+01 -1.71763172e+01 -1.65152702e+01 -1.58507175e+01 -1.59001122e+01 -1.62370224e+01 -1.58185072e+01 -1.60508251e+01 -1.58832769e+01 -1.52765436e+01 -1.46459732e+01 -1.52293777e+01 -1.51168594e+01 -1.54039745e+01 -1.56076193e+01 -1.65844498e+01 -1.66550694e+01 -1.52333536e+01 -1.42097254e+01 -1.36487465e+01 -1.48863554e+01 -1.68407688e+01 -1.75262260e+01 -1.73484955e+01 -1.76579113e+01 -1.91275654e+01 -1.87111073e+01 -1.80360165e+01 -1.71677761e+01 -1.79126987e+01 -1.84276505e+01 -1.77360840e+01 -1.68684978e+01 -1.74591103e+01 -1.77524319e+01 -1.81797886e+01 -1.84352913e+01 -1.88470783e+01 -1.86095200e+01 -1.79095154e+01 -1.71770821e+01 -1.68223782e+01 -1.70962772e+01 -1.78428822e+01 -1.89475174e+01 -1.91197586e+01 -1.92762489e+01 -2.00551395e+01 -2.05711479e+01 -2.02975616e+01 -1.93929729e+01 -1.88630886e+01 -2.11237316e+01 -2.25878067e+01 -2.35716305e+01 -2.22495270e+01 -2.24040661e+01 -2.14721012e+01 -2.11789703e+01 -2.06047153e+01 -2.04569092e+01 -2.04038258e+01 -2.05833740e+01 -2.18106499e+01 -2.31840000e+01 -2.36227112e+01 -2.19221401e+01 -2.13082504e+01 -2.10222759e+01 -2.20031967e+01 -2.24990749e+01 -2.35036526e+01 -2.43181438e+01 -2.40606480e+01 -2.41693192e+01 -2.37858467e+01 -2.39600735e+01 -2.32888279e+01 -2.33369408e+01 -2.28953419e+01 -2.35737591e+01 -2.38136692e+01 -2.46110401e+01 -2.31177464e+01 -2.18353748e+01 -2.20788345e+01 -2.37509670e+01 -2.41729069e+01 -2.23585205e+01 -2.19861488e+01 -2.25011959e+01 -2.38011112e+01 -2.31556129e+01 -2.25964317e+01 -2.32726498e+01 -2.38547287e+01 -2.50264473e+01 -2.50690269e+01 -2.59561062e+01 -2.57512054e+01 -2.54434242e+01 -2.48918171e+01 -2.56612434e+01 -2.60044270e+01 -2.66763039e+01 -2.63765926e+01 -2.61370392e+01 -2.57139778e+01 -2.55365887e+01 -2.43290176e+01 -2.53586998e+01 -2.67987404e+01 -2.75151005e+01 -2.66323338e+01 -2.56987019e+01 -2.67949467e+01 -2.66272717e+01 -2.70507374e+01 -2.68532104e+01 -2.76652946e+01 -2.81718826e+01 -2.93135700e+01 -2.94763126e+01 -3.00118961e+01 -2.87334709e+01 -2.73914700e+01 -2.70600853e+01 -2.75082245e+01 -2.83713894e+01 -2.72409916e+01 -2.78058167e+01 -2.81526604e+01 -2.89678898e+01 -2.87079849e+01 -2.91689644e+01 -2.95096264e+01 -3.04711971e+01 -2.96832218e+01 -2.90701561e+01 -2.84580269e+01 -2.88709202e+01 -2.94740772e+01 -2.94075241e+01 -2.97035580e+01 -2.98131657e+01 -2.95910892e+01 -2.95453739e+01 -2.96671467e+01 -2.99696770e+01 -2.94104385e+01 -2.86754112e+01 -2.91575699e+01 -2.96416531e+01 -2.92118645e+01 -2.78470535e+01 -2.85787411e+01 -3.05780163e+01 -3.19374828e+01 -3.16795044e+01 -3.11360970e+01 -3.09828053e+01 -3.16224937e+01 -3.10397339e+01 -3.08734455e+01 -3.03806992e+01 -3.06922607e+01 -3.12320690e+01 -3.15691547e+01 -3.22664642e+01 -3.26829300e+01 -3.25735512e+01 -3.20615997e+01 -3.21534996e+01 -3.24386559e+01 -3.17223892e+01 -3.16518784e+01 -3.19281521e+01 -3.32093506e+01 -3.29464111e+01 -3.25546417e+01 -3.22198105e+01 -3.29619904e+01 -3.28933945e+01 -3.25928345e+01 -3.13087521e+01 -3.12217598e+01 -3.14365864e+01 -3.15183315e+01 -3.14869499e+01 -3.19731407e+01 -3.23938599e+01 -3.29332047e+01 -3.24688759e+01 -3.26980858e+01 -3.29259262e+01 -3.29555321e+01 -3.31185913e+01 -3.35537834e+01 -3.43196030e+01 -3.39562454e+01 -3.32805939e+01 -3.31095924e+01 -3.36423836e+01 -3.40011902e+01 -3.33698502e+01 -3.42282410e+01 -3.53629532e+01 -3.63976555e+01 -3.58746071e+01 -3.49100609e+01 -3.51323242e+01 -3.52087173e+01 -3.55343475e+01 -3.53591385e+01 -3.57072525e+01 -3.60799942e+01 -3.57587776e+01 -3.52827263e+01 -3.48957329e+01 -3.45912819e+01 -3.43568497e+01 -3.40302277e+01 -3.41686592e+01 -3.49492264e+01 -3.55616722e+01 -3.62150688e+01 -3.58838463e+01 -3.60513992e+01 -3.59481735e+01 -3.57401962e+01 -3.59958000e+01 -3.66943741e+01 -3.65337448e+01 -3.58400421e+01 -3.53316727e+01 -3.55842781e+01 -3.55640068e+01 -3.50174446e+01 -3.48943863e+01 -3.52067871e+01 -3.58218689e+01 -3.59618721e+01 -3.58198967e+01 -3.59717407e+01 -3.59011421e+01 -3.58962479e+01 -3.58737869e+01 -3.58104782e+01 -3.60003815e+01 -3.61737976e+01 -3.64353027e+01 -3.61287308e+01 -3.59582291e+01 -3.54552460e+01 -3.51624527e+01 -3.52159157e+01 -3.59336586e+01 -3.62429161e+01 -3.61850967e+01 -3.58454895e+01 -3.61325607e+01 -3.64559708e+01 -3.64053154e+01 -3.61860847e+01 -3.62700233e+01 -3.65719452e+01 -3.73752632e+01 -3.72896271e+01 -3.75139961e+01 -3.70991287e+01 -3.67358322e+01 -3.65367622e+01 -3.69821129e+01 -3.69048271e+01 -3.66267090e+01 -3.63793678e+01 -3.71139946e+01 -3.73396912e+01 -3.71576576e+01 -3.65466576e+01 -3.68123703e+01 -3.71957092e+01 -3.77802582e+01 -3.76573830e+01 -3.73923988e+01 -3.73742714e+01 -3.73260765e+01 -3.71697502e+01 -3.71162643e+01 -3.72085037e+01 -3.74106293e+01 -3.73448792e+01 -3.72681732e+01 -3.72376785e+01 -3.73207626e+01 -3.76304436e+01 -3.77995033e+01 -3.80142097e+01 -3.79930611e+01 -3.79560699e+01 -3.78866577e+01 -3.78576050e+01 -3.77308464e+01 -3.76779099e+01 -3.77703285e+01 -3.79991455e+01 -3.82425728e+01 -3.81656418e+01 -3.77055092e+01 -3.71402969e+01 -3.68891945e+01 -3.76429291e+01 -3.80439529e+01 -3.85459557e+01 -3.81220474e+01 -3.81141396e+01 -3.72953987e+01 -3.69790154e+01 -3.93899040e+01 -4.22436638e+01 -3.10573750e+01 2.97200751e+00 5.55083389e+01 -2.95024353e+02 6.20418050e+06 0. 0. 0. 0. 0. 28417318. 318329024. -1.58831619e+02 -1.32433182e+02 -9.10525970e+01 -163128064. 0. 0. -233982096. -233982096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 407427488. 727483392. -1.11670341e+02 -1.22102859e+02 -1.13190765e+02 -6.22863770e+01 -6.52985458e+01 -7.13521042e+01 -7.04735413e+01 -6.35803871e+01 -5.98219261e+01 -5.75046883e+01 -5.82119293e+01 -6.16460495e+01 -6.29482117e+01 -6.30428085e+01 -6.28630600e+01 -6.33619804e+01 -6.28860626e+01 -6.03378372e+01 -5.90849533e+01 -6.04690094e+01 -6.49001617e+01 -6.92108994e+01 -6.87193298e+01 -6.75845947e+01 -6.61987534e+01 -6.39278336e+01 -6.37485847e+01 -6.35305099e+01 -6.61222534e+01 -6.84708405e+01 -7.04740143e+01 -6.97891846e+01 -6.40734940e+01 -5.90372047e+01 -5.58260498e+01 -5.39711609e+01 -5.58599358e+01 -5.62066345e+01 -5.73288269e+01 -6.29640961e+01 -6.70470352e+01 -6.68926849e+01 -5.99266205e+01 -5.33980026e+01 -5.08625984e+01 -5.44622726e+01 -6.22742119e+01 -6.54133072e+01 -6.51295242e+01 -6.21224289e+01 -5.82680817e+01 -5.67271309e+01 -5.42073517e+01 -5.39507332e+01 -5.70017624e+01 -6.25430908e+01 -6.50768738e+01 -5.87886276e+01 -5.38039093e+01 -5.21907921e+01 -5.40338135e+01 -5.80571785e+01 -5.75171051e+01 -5.72907600e+01 -6.20504951e+01 -6.89468842e+01 -6.95710373e+01 -5.96959953e+01 -5.08469849e+01 -4.95845604e+01 -5.65374413e+01 -6.70585327e+01 -6.66332855e+01 -6.29092865e+01 -5.99033356e+01 -5.78537292e+01 -5.35894966e+01 -4.85310097e+01 -4.52841949e+01 -5.05572433e+01 -6.16968536e+01 -7.42674026e+01 -7.17831726e+01 -6.59155197e+01 -6.01161156e+01 -5.57441444e+01 -5.30025787e+01 -5.15516739e+01 -5.81983643e+01 -6.66916504e+01 -7.45732727e+01 -7.21657715e+01 -5.97169342e+01 -4.66437340e+01 -3.81117477e+01 -3.65416641e+01 -4.53071251e+01 -5.04107742e+01 -5.63021889e+01 -6.53184433e+01 -7.29697495e+01 -7.11580963e+01 -5.94018669e+01 -4.97106476e+01 -5.09324036e+01 -6.08753319e+01 -7.10371017e+01 -7.13408661e+01 -6.84043732e+01 -6.81042404e+01 -6.48013687e+01 -6.17785072e+01 -5.68214340e+01 -5.28099594e+01 -5.36250000e+01 -5.97652283e+01 -6.38769379e+01 -5.88635750e+01 -4.85289688e+01 -4.19805374e+01 -4.53532867e+01 -6.22387009e+01 -7.58397446e+01 -6.94002762e+01 -6.42833710e+01 -6.80410461e+01 -7.37314148e+01 -6.13934364e+01 -4.48950844e+01 -3.89863319e+01 -5.14725990e+01 -6.88230972e+01 -7.61507874e+01 -6.90262451e+01 -5.95627556e+01 -5.32459641e+01 -4.82309761e+01 -5.15374260e+01 -5.23502884e+01 -5.58353577e+01 -6.46756287e+01 -7.38370895e+01 -7.48609085e+01 -6.70689850e+01 -5.61009369e+01 -4.94043312e+01 -5.29202461e+01 -6.57784042e+01 -7.09939728e+01 -6.93186798e+01 -6.79237442e+01 -7.00103378e+01 -6.52742081e+01 -5.33430443e+01 -3.67887955e+01 -3.47039680e+01 -4.54101982e+01 -5.31459694e+01 -5.11239777e+01 -5.05247421e+01 -5.75872879e+01 -5.59002342e+01 -5.23968086e+01 -4.29096489e+01 -4.69216881e+01 -5.53455887e+01 -6.54050674e+01 -6.02023163e+01 -4.42093887e+01 -2.92085609e+01 -2.21360931e+01 -2.54184723e+01 -3.74745331e+01 -4.14807243e+01 -4.00247459e+01 -4.68012199e+01 -4.17306786e+01 -3.15104504e+01 -1.48850775e+01 -5.70054007e+00 -7.56870317e+00 -2.50978203e+01 -5.35617218e+01 -6.18909340e+01 -6.51558990e+01 -6.61504288e+01 -6.77909393e+01 -6.09403534e+01 -4.54376640e+01 -3.84670525e+01 -4.75398331e+01 -6.48482132e+01 -6.55430603e+01 -4.92909050e+01 -3.61540718e+01 -2.91365833e+01 -1.81101360e+01 -1.81333351e+01 -1.99631844e+01 -3.22744980e+01 -4.04243584e+01 -3.89448433e+01 -3.38916321e+01 -1.81982670e+01 -8.62761974e+00 -4.27373934e+00 -2.24540653e+01 -5.23372307e+01 -6.26752014e+01 -5.73211098e+01 -4.96337280e+01 -4.70702095e+01 -4.40307350e+01 -3.12229710e+01 -2.52234573e+01 -4.30580177e+01 -6.34903488e+01 -7.13388748e+01 -5.63627434e+01 -3.99184456e+01 -3.31678009e+01 -3.17532387e+01 -3.79827919e+01 -3.58740501e+01 -2.78849506e+01 -3.76778908e+01 -4.74727097e+01 -4.62918854e+01 -3.15443783e+01 -1.91421185e+01 -1.83041134e+01 -2.80541039e+01 -4.49901619e+01 -5.63821983e+01 -5.57217979e+01 -5.53585663e+01 -5.41509743e+01 -5.06616325e+01 -3.16789570e+01 -1.97825356e+01 -1.86508846e+01 -2.57318897e+01 -4.10146675e+01 -4.72700806e+01 -5.87856598e+01 -5.77749710e+01 -3.79444046e+01 -3.50539322e+01 -3.76872902e+01 -4.97552299e+01 -5.47088089e+01 -5.63963509e+01 -6.40716476e+01 -3.84703636e+01 -1.11051226e+01 -3.58461916e-01 -2.33305893e+01 -3.94336166e+01 -4.13570251e+01 -3.59833908e+01 -5.15868416e+01 -5.77978859e+01 -4.44197998e+01 -2.12787628e+01 -1.45912399e+01 -3.84684639e+01 -4.10497208e+01 -4.32808228e+01 -4.42072678e+01 -5.68959122e+01 -4.94774895e+01 -3.03498878e+01 -2.06846123e+01 -1.29974089e+01 -4.18909788e+00 4.17767143e+00 -1.70126476e+01 -4.20400620e+01 -4.07838707e+01 -8.42070198e+00 -1.09743583e+00 -1.59174290e+01 -2.07654419e+01 -8.60159111e+00 -4.48926258e+00 -2.88793488e+01 -3.12535973e+01 -1.92579384e+01 -4.72108459e+00 -9.95920658e+00 -3.10428753e+01 -3.02813568e+01 -4.22720604e+01 -5.30938759e+01 -6.42210007e+01 -4.29112663e+01 -2.64285698e+01 -2.71014442e+01 -3.05367603e+01 -3.02616196e+01 -2.50594120e+01 -4.03645859e+01 -5.57467499e+01 -5.27566147e+01 -2.30991344e+01 -4.20581627e+00 -1.15996447e+01 -2.22703018e+01 -1.32753391e+01 1.03132558e+00 -7.84224081e+00 -1.61678810e+01 -2.37243290e+01 -1.95508213e+01 -3.28333054e+01 -4.59124870e+01 -4.07485771e+01 -3.71776123e+01 -3.89807472e+01 -4.72106667e+01 -4.46784630e+01 -4.15712051e+01 -4.19156265e+01 -2.57403431e+01 -8.92456245e+00 1.13297307e+00 -1.70906487e+01 -3.51947365e+01 -3.13457947e+01 -6.49916697e+00 -4.08435535e+00 -1.63477974e+01 -2.23784599e+01 -3.66207838e+00 -1.11557317e+00 -2.82118568e+01 -4.33727379e+01 -5.60866241e+01 -5.68851929e+01 -6.83259506e+01 -6.25832291e+01 -4.29091949e+01 -4.23981743e+01 -5.29316635e+01 -5.99923363e+01 -3.57920532e+01 -1.69610043e+01 -1.77911110e+01 -5.76662159e+00 1.58150434e+01 3.26174850e+01 1.84818001e+01 2.08870173e+00 -1.67389750e+00 -1.52400389e-01 -1.21554251e+01 -1.55005941e+01 -1.34946012e+01 2.18202472e+00 -6.08621264e+00 -3.08351116e+01 -4.58371239e+01 -5.56493301e+01 -5.34857330e+01 -6.10142059e+01 -4.93684158e+01 -2.22702389e+01 -1.75387306e+01 -2.40423584e+01 -4.01231346e+01 -2.52408218e+01 -1.37683954e+01 -2.97178516e+01 -2.39607315e+01 2.25209332e+00 3.82819633e+01 4.47620888e+01 1.74354172e+01 3.92176366e+00 6.05886078e+00 1.21791210e+01 2.46227322e+01 8.89149475e+00 6.95469713e+00 -3.52676940e+00 -2.26892304e+00 2.68575726e+01 2.20225143e+01 7.27650785e+00 -3.53549690e+01 -3.50011520e+01 1.20317659e+01 2.35199432e+01 9.55455399e+00 -3.60279388e+01 -3.57406197e+01 8.56607056e+00 3.52367134e+01 4.92879715e+01 3.58312798e+01 2.45505009e+01 1.46412134e+01 -1.49018784e+01 -1.66839504e+01 6.72592354e+00 3.24886665e+01 3.38538895e+01 -2.22339082e+00 -2.66016369e+01 -4.10500298e+01 -3.07552605e+01 6.85438633e+00 1.84601231e+01 2.35269523e+00 -3.71921616e+01 -3.35652237e+01 1.26772213e+01 5.40899811e+01 6.96925125e+01 3.33453026e+01 -6.01210117e+00 -1.81718731e+01 -2.07822094e+01 -5.23225975e+00 7.62844801e+00 2.21093655e+01 3.97204704e+01 3.10025673e+01 1.81217461e+01 1.07149124e+00 8.77457917e-01 1.29287930e+01 -8.61566365e-01 -8.56664658e+00 -7.90371561e+00 2.50143886e+00 3.14974594e+01 2.95869923e+01 2.07382526e+01 -1.87419128e+01 -3.33729897e+01 -2.17395363e+01 -1.07213125e+01 1.86005747e+00 -4.41097856e-01 1.22155466e+01 3.94764557e+01 3.83929710e+01 2.03784962e+01 1.05187445e+01 1.10168829e+01 2.05359917e+01 -3.20178151e+00 -1.49631548e+01 -1.91948719e+01 5.90710938e-01 2.63899078e+01 1.47369223e+01 -7.48017931e+00 -2.51948357e+01 -2.24651337e+01 5.23185205e+00 1.38436699e+01 1.30256729e+01 -8.39295387e+00 -1.38020811e+01 1.15172958e+01 2.62207470e+01 3.96708145e+01 3.06836472e+01 2.33863792e+01 1.55400848e+01 3.05175614e+00 -1.74626005e+00 7.68483496e+00 1.85623798e+01 3.26874313e+01 2.53450947e+01 1.41118412e+01 -7.51670790e+00 -1.47504549e+01 1.25852623e+01 1.37286997e+01 1.76342621e+01 7.49472666e+00 4.34797907e+00 1.34150515e+01 1.95066795e+01 3.94988594e+01 1.78754463e+01 -4.33286285e+00 -9.63547230e+00 -3.44222188e-01 1.78810196e+01 2.99179382e+01 3.29204216e+01 2.87800827e+01 1.07467318e+01 8.91832161e+00 1.63365211e+01 2.77110500e+01 3.50478706e+01 1.41553736e+01 -2.35705256e+00 -1.99492912e+01 -1.16293173e+01 9.96540833e+00 1.13775702e+01 5.45766735e+00 -9.95807266e+00 -1.25418625e+01 7.86938667e+00 1.25965042e+01 1.81296501e+01 1.86282501e-01 -6.97833729e+00 1.58767920e+01 1.38598995e+01 1.76218567e+01 2.12982273e+01 3.36517754e+01 3.61146431e+01 4.17041016e+00 -1.27484493e+01 -4.58563471e+00 1.74570789e+01 3.29691391e+01 1.64079304e+01 -4.37447166e+00 -1.50033884e+01 -1.87139778e+01 4.10316801e+00 1.80178432e+01 2.25195370e+01 7.31462908e+00 -6.30050421e+00 2.07054176e+01 4.21714020e+01 6.44637909e+01 5.17182808e+01 2.50931587e+01 1.34913387e+01 2.12462366e-01 1.44129839e+01 3.03927555e+01 4.31292725e+01 3.70536003e+01 9.02208138e+00 -8.61651993e+00 -3.06717396e+00 8.10049915e+00 2.18436394e+01 1.20375223e+01 2.56354904e+00 -8.11413383e+00 -2.44595647e+00 2.67730789e+01 3.82988853e+01 3.10421066e+01 2.25207281e+00 -8.23701477e+00 1.08801353e+00 1.15569706e+01 2.71550789e+01 2.45320110e+01 1.83089256e+01 1.07379665e+01 9.82237530e+00 1.96996040e+01 2.85030689e+01 3.36590767e+01 2.82431793e+01 8.77036953e+00 -3.59214091e+00 -4.84299183e+00 1.55869274e+01 3.68246918e+01 2.87856464e+01 1.29618397e+01 -1.59883022e+00 5.52650642e+00 3.51118164e+01 4.32088051e+01 3.60281563e+01 7.83720827e+00 -4.57041121e+00 1.95999527e+01 3.79335518e+01 5.06348114e+01 3.28867683e+01 1.43603411e+01 2.00759964e+01 2.15018559e+01 3.14847946e+01 3.15827961e+01 3.08953609e+01 3.33193893e+01 1.91743984e+01 2.12637062e+01 1.44187098e+01 2.13318844e+01 3.65770111e+01 3.20461617e+01 2.49898453e+01 7.26167440e-01 1.16218166e+01 4.02431221e+01 5.53933525e+01 4.76326675e+01 2.01269627e+01 1.71680183e+01 3.54330826e+01 3.88414154e+01 5.44850693e+01 4.74491806e+01 3.02808323e+01 1.80934830e+01 3.64242592e+01 7.67127914e+01 -1.37503528e+03 -4.22304443e+03 46472784. -264798400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -358400512. 51028948. -294265280. 54792452. -5.93773527e+10 3.50984802e+02 1.28295578e+02 3.00364456e+01 4.73357086e+01 4.46813927e+01 2.76356487e+01 2.77472343e+01 2.50898514e+01 2.97826900e+01 5.21211853e+01 6.09385529e+01 5.44361916e+01 2.78380108e+01 2.13123627e+01 4.06715240e+01 5.52807350e+01 6.30582008e+01 4.86654358e+01 3.25295105e+01 3.07216492e+01 3.32415619e+01 5.03997726e+01 6.03441887e+01 6.25133247e+01 5.44832878e+01 4.72301216e+01 4.66367340e+01 4.56231079e+01 4.50573044e+01 4.61754379e+01 3.94317322e+01 3.16191082e+01 2.62855606e+01 3.60556526e+01 5.88466415e+01 6.63497620e+01 6.07372131e+01 3.95899811e+01 3.33264503e+01 3.84328537e+01 4.33399658e+01 4.98683014e+01 4.52043343e+01 4.18464546e+01 4.49515953e+01 4.93564034e+01 5.87454376e+01 6.40821381e+01 6.57883606e+01 6.26071854e+01 4.68283424e+01 4.15279846e+01 4.04451180e+01 5.49189072e+01 6.80023880e+01 6.15588684e+01 4.68397980e+01 3.26693420e+01 3.37988281e+01 5.02615051e+01 5.99780693e+01 6.20605392e+01 4.71080017e+01 3.65640717e+01 4.16251640e+01 4.75984421e+01 5.69125633e+01 4.88019638e+01 4.09166260e+01 4.17145195e+01 5.01142464e+01 6.84840927e+01 7.57491379e+01 7.58232040e+01 6.68686523e+01 5.86620598e+01 6.08556900e+01 5.75970612e+01 5.68090897e+01 6.15947647e+01 6.09666138e+01 5.55994873e+01 4.72745056e+01 5.40041199e+01 7.28947067e+01 7.60343552e+01 6.84119186e+01 4.88844414e+01 4.28390884e+01 4.81967163e+01 5.03686790e+01 5.96692772e+01 5.87536278e+01 5.54872513e+01 5.12061920e+01 4.99495583e+01 6.02379379e+01 6.58490524e+01 6.55836411e+01 6.15804443e+01 5.26270065e+01 5.02238235e+01 4.70685959e+01 4.97286072e+01 5.85976410e+01 5.74931526e+01 5.40351028e+01 4.57561111e+01 4.54231224e+01 5.35887184e+01 5.83527565e+01 5.91573830e+01 5.09166603e+01 4.60609398e+01 5.11164780e+01 5.51503258e+01 6.38930168e+01 6.84632721e+01 6.78852234e+01 6.30413475e+01 5.48980141e+01 5.47181587e+01 6.12562103e+01 6.53478470e+01 6.70079803e+01 5.81934090e+01 5.33971710e+01 5.03177795e+01 5.25950089e+01 6.48553619e+01 6.81759262e+01 6.66311722e+01 5.57558098e+01 5.17993813e+01 5.77822418e+01 6.09218826e+01 6.06270599e+01 5.42163544e+01 4.84019852e+01 5.19808769e+01 5.49038544e+01 6.05547523e+01 5.83765411e+01 5.40895309e+01 5.34042473e+01 5.24350052e+01 5.38682823e+01 5.54336357e+01 5.82472992e+01 6.03455162e+01 5.62885361e+01 5.30941315e+01 5.19258957e+01 5.53505783e+01 6.03253860e+01 6.05675125e+01 5.92594452e+01 5.68924828e+01 5.70588875e+01 6.16379967e+01 6.44515381e+01 6.53636780e+01 6.27845573e+01 6.18322411e+01 6.34496880e+01 6.28575172e+01 6.42783127e+01 6.55452347e+01 6.57829514e+01 6.42815933e+01 6.26833076e+01 6.23122063e+01 6.19853287e+01 6.21983490e+01 6.25099258e+01 6.11956291e+01 5.89016571e+01 5.67957230e+01 5.66207314e+01 5.95632591e+01 6.18791275e+01 6.17953224e+01 5.93316498e+01 5.70312042e+01 5.83993416e+01 5.97588425e+01 6.24467201e+01 6.17858658e+01 6.07489662e+01 6.05609474e+01 6.07474594e+01 6.18085289e+01 6.30609703e+01 6.41312103e+01 6.42667542e+01 6.31288719e+01 6.29448013e+01 6.34666595e+01 6.44251785e+01 6.49916687e+01 6.34937248e+01 6.19828072e+01 6.10200081e+01 6.13106003e+01 6.26450424e+01 6.33060570e+01 6.33845367e+01 6.24800415e+01 6.23363457e+01 6.29632378e+01 6.32438889e+01 6.33795052e+01 6.31698875e+01 6.31425972e+01 6.33546906e+01 6.35609207e+01 6.38140373e+01 6.38704948e+01 6.37675858e+01 6.36327438e+01 6.36133461e+01 6.37013588e+01 6.39618187e+01 6.39158401e+01 6.32366219e+01 6.25235329e+01 6.24383774e+01 6.31550713e+01 6.35951843e+01 6.32754745e+01 6.36355171e+01 6.41815720e+01 6.44525986e+01 6.41933441e+01 6.33947449e+01 6.31470833e+01 6.29689369e+01 6.32247086e+01 6.36126938e+01 6.32423820e+01 6.25933151e+01 6.20654678e+01 6.23270073e+01 6.29352989e+01 6.30950165e+01 6.32855911e+01 6.30000725e+01 6.39351234e+01 6.49447556e+01 6.54357452e+01 6.45298538e+01 6.32618942e+01 6.35220604e+01 6.41644058e+01 6.43923340e+01 6.41619797e+01 6.39013329e+01 6.41691742e+01 6.45382690e+01 6.43126678e+01 6.40148087e+01 6.28563614e+01 6.24276695e+01 6.28755112e+01 6.31895485e+01 6.38393059e+01 6.29338875e+01 6.30047569e+01 6.23985100e+01 6.34619789e+01 6.36367836e+01 6.39375191e+01 6.28885078e+01 6.24312630e+01 6.28787117e+01 6.37850342e+01 6.36812401e+01 6.23864746e+01 6.05603371e+01 6.07668610e+01 6.00489235e+01 5.97652130e+01 5.98803406e+01 6.16739502e+01 6.30903358e+01 6.29178123e+01 6.31033821e+01 6.29946823e+01 6.29342079e+01 6.13069725e+01 6.12063217e+01 6.19712982e+01 6.35010109e+01 6.26696129e+01 6.29703064e+01 6.22442856e+01 6.31334114e+01 6.24701118e+01 6.21486549e+01 6.24177475e+01 6.21209335e+01 6.27157974e+01 6.23149529e+01 6.10717163e+01 5.88006668e+01 5.78877754e+01 5.91021118e+01 6.19127769e+01 6.24032631e+01 6.32059326e+01 6.11664696e+01 6.00722466e+01 5.88550034e+01 6.04158249e+01 6.35263596e+01 6.43059769e+01 6.24901848e+01 6.20122719e+01 6.28368073e+01 6.40135193e+01 6.28918266e+01 6.16308861e+01 6.15066566e+01 5.97258568e+01 5.86630821e+01 5.74017372e+01 5.74262276e+01 5.74308052e+01 5.75258560e+01 5.91197128e+01 5.87697220e+01 5.87037201e+01 5.85134697e+01 5.89133301e+01 5.77503319e+01 5.48718948e+01 5.60676689e+01 5.91601830e+01 6.10438080e+01 6.08791313e+01 5.82096329e+01 5.76973534e+01 5.69582901e+01 5.86718025e+01 5.93557701e+01 5.89995079e+01 5.66937523e+01 5.28583336e+01 4.88051033e+01 4.67867851e+01 4.57909584e+01 4.88206482e+01 5.19380684e+01 5.73628883e+01 5.93678627e+01 5.76692734e+01 5.58811760e+01 5.38865700e+01 4.94544792e+01 4.38191566e+01 4.65323601e+01 5.16408920e+01 5.61867485e+01 5.27830086e+01 4.84380379e+01 4.56490822e+01 4.94417191e+01 5.55872002e+01 5.89190865e+01 5.28990707e+01 4.48818703e+01 4.30681572e+01 4.77915573e+01 5.56733437e+01 5.62926750e+01 5.45674248e+01 5.21609306e+01 5.16896706e+01 5.26789055e+01 5.41341591e+01 4.97928467e+01 4.35613480e+01 4.48123589e+01 4.97976952e+01 5.42589531e+01 5.33175964e+01 5.35061951e+01 5.46004105e+01 5.49009476e+01 5.53563843e+01 5.12216072e+01 4.61148529e+01 4.59151840e+01 4.89252052e+01 5.30408211e+01 5.10572777e+01 5.04166832e+01 5.29840126e+01 5.71402321e+01 6.56135101e+01 7.09518051e+01 6.43689728e+01 5.52953529e+01 4.91322403e+01 5.13624916e+01 5.36771812e+01 5.45660286e+01 5.76857567e+01 5.76766129e+01 5.64962921e+01 5.42107201e+01 5.23608780e+01 5.18906212e+01 5.36439247e+01 5.41433716e+01 5.54140968e+01 5.41350441e+01 5.47344246e+01 5.34659958e+01 5.15593834e+01 4.61003761e+01 4.27592850e+01 4.50267982e+01 5.38105469e+01 6.05776863e+01 6.21986351e+01 5.73488960e+01 4.72313118e+01 4.33706741e+01 4.58211060e+01 4.85292130e+01 4.97026749e+01 4.70218849e+01 5.43487282e+01 6.25019417e+01 6.42669373e+01 5.63363838e+01 4.80165024e+01 4.73052368e+01 5.24020309e+01 5.64357300e+01 5.63694725e+01 5.30623322e+01 4.57346954e+01 4.65051727e+01 4.60588150e+01 4.72850533e+01 4.54010048e+01 5.05549660e+01 5.72089462e+01 5.83016052e+01 5.28756676e+01 4.67467308e+01 1.90494556e+01 2.36423378e+01 4.96879730e+01 1.37204834e+03 1.10407295e+04 -353220768. 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. 0. 0. 0. 0. 0. 0. 0. 119250520. -71518888. -17341892. -55024388. 1.02433662e+04 -7.76585266e+02 -9.05373291e+02 -7.68064041e+01 -1.94594421e+01 2.68733368e+01 1.50523539e+01 1.89152660e+01 1.90609207e+01 1.93373394e+01 1.77290478e+01 1.91154308e+01 2.18213520e+01 2.41349144e+01 3.33213463e+01 4.16737862e+01 3.70503922e+01 2.67592869e+01 2.36218357e+01 3.12679749e+01 3.82105103e+01 3.95050507e+01 4.43610954e+01 4.84949150e+01 5.51785583e+01 5.62390785e+01 5.34778709e+01 4.81088066e+01 4.54406281e+01 4.71479568e+01 4.75356560e+01 4.74424820e+01 3.68819656e+01 2.33155746e+01 2.04264927e+01 2.21370354e+01 2.72603550e+01 2.35991096e+01 2.45910053e+01 2.84693203e+01 2.87103157e+01 2.96273880e+01 2.33680801e+01 2.61551075e+01 3.00395813e+01 3.57704697e+01 3.03238697e+01 2.30098972e+01 1.98195992e+01 2.54512863e+01 2.64901390e+01 2.40915565e+01 1.81553860e+01 1.44716454e+01 1.32312145e+01 1.58392096e+01 2.59955807e+01 2.52669659e+01 1.89991398e+01 1.02738295e+01 6.44015646e+00 4.68248415e+00 2.81391811e+00 3.37607741e+00 6.58488989e+00 5.42926884e+00 8.81946659e+00 1.03082113e+01 1.31054945e+01 1.63060760e+01 1.74875565e+01 3.49258804e+01 5.02998276e+01 5.14435043e+01 3.72423897e+01 2.12785721e+01 2.13735065e+01 2.03501453e+01 1.00471945e+01 -2.46866083e+00 -1.70012875e+01 -2.34589367e+01 -1.33729420e+01 -3.74915689e-01 1.43676500e+01 1.12988997e+01 7.56088352e+00 5.20563507e+00 7.98456001e+00 1.06827183e+01 1.39110832e+01 1.32650356e+01 1.28620234e+01 1.30811729e+01 1.68387337e+01 1.58899488e+01 2.18417854e+01 2.25696163e+01 2.68724670e+01 2.49271832e+01 2.79780102e+01 2.98571377e+01 2.45737762e+01 8.96842861e+00 -5.83122206e+00 -1.28548679e+01 -1.53627291e+01 1.24434434e-01 1.34147720e+01 3.42679024e+01 3.21586037e+01 2.56210575e+01 2.58893948e+01 3.27152748e+01 3.84135857e+01 3.17042313e+01 2.03778172e+01 1.55523758e+01 9.29733372e+00 5.87187433e+00 -1.14206052e+00 -3.99413252e+00 -5.59067106e+00 -3.10750294e+00 -1.11810005e+00 2.94835325e-02 4.41368192e-01 1.18248796e+00 -1.18872185e+01 -2.52621460e+01 -3.97348480e+01 -4.03085403e+01 -2.92046204e+01 -1.68269920e+01 1.33038771e+00 5.58169603e+00 6.52350092e+00 6.72330952e+00 8.32732677e+00 1.16225662e+01 1.41106501e+01 1.04050589e+01 7.86025381e+00 8.43206978e+00 1.23008652e+01 1.20120611e+01 1.19570704e+01 6.46237612e+00 -7.66236496e+00 -2.90826626e+01 -2.90387077e+01 -1.73807888e+01 -1.34438944e+00 -1.62703819e+01 -3.26305466e+01 -4.78404922e+01 -4.35010262e+01 -2.68735065e+01 -1.52774811e+01 -3.37960577e+00 -1.73241007e+00 4.43242168e+00 5.88884974e+00 6.29908991e+00 6.59740400e+00 3.65602326e+00 3.54408336e+00 2.63378978e+00 3.75488782e+00 1.03754425e+00 -8.05849493e-01 3.95035148e+00 7.60426760e+00 -3.26119637e+00 -1.88719959e+01 -2.21275368e+01 -1.29921885e+01 -2.24220395e+00 -4.33213025e-01 6.79079056e+00 -4.80980873e+00 -1.95564690e+01 -2.52701492e+01 -1.38925028e+01 -3.49582219e+00 -8.95253086e+00 -8.15390110e+00 -7.16870928e+00 -5.49620008e+00 -1.05762663e+01 -1.21047945e+01 -7.23456860e+00 -5.13333464e+00 -4.04126120e+00 -6.09127140e+00 -9.46508312e+00 -1.25179863e+01 -1.58924170e+01 -2.40988846e+01 -3.13100605e+01 -3.90122948e+01 -3.48098984e+01 -2.57732048e+01 -1.71855659e+01 -6.52328873e+00 -4.43186045e+00 -3.17440772e+00 -4.11093044e+00 -5.55349064e+00 -5.03503561e+00 -5.06532907e+00 -2.48111653e+00 -7.02308714e-01 -2.83130527e+00 -3.64581561e+00 -4.72981977e+00 9.30018711e+00 2.03706646e+01 1.48438587e+01 1.20303762e+00 -9.68214321e+00 -6.36150026e+00 -5.49741554e+00 -1.59423723e+01 -2.92421455e+01 -3.20941391e+01 -2.31385956e+01 -1.02059698e+01 -1.20466423e+01 -1.30671005e+01 -1.58323851e+01 -1.53081989e+01 -1.64775066e+01 -1.56350527e+01 -1.61281414e+01 -1.64810104e+01 -1.72645817e+01 -1.97916832e+01 -2.17945919e+01 -2.15875893e+01 -2.03868084e+01 -2.81676674e+01 -4.43820610e+01 -5.05194168e+01 -4.50662804e+01 -3.13172264e+01 -2.32308636e+01 -2.44481411e+01 -3.80849991e+01 -5.26301575e+01 -4.74612541e+01 -3.22474289e+01 -1.78526840e+01 -1.59411154e+01 -1.38768806e+01 -1.66552105e+01 -1.80968819e+01 -7.99066114e+00 8.44748783e+00 1.03169613e+01 -1.63305497e+00 -1.72965870e+01 -1.65111389e+01 -1.50174503e+01 -1.49238014e+01 -1.91673317e+01 -2.92092896e+01 -3.86407738e+01 -3.96877518e+01 -3.27933693e+01 -2.35190735e+01 -2.32844181e+01 -2.20119991e+01 -3.14453716e+01 -4.06676636e+01 -3.73157768e+01 -2.74302731e+01 -1.26292362e+01 -1.26034460e+01 -1.00391521e+01 -1.45436411e+01 -1.89031944e+01 -2.13389091e+01 -2.13874302e+01 -2.04787045e+01 -2.03073540e+01 -1.90305080e+01 -1.88127327e+01 -1.91667271e+01 -2.23139477e+01 -2.84208527e+01 -4.38918915e+01 -5.73902016e+01 -6.37016449e+01 -5.91898270e+01 -4.17556763e+01 -2.91088200e+01 -1.93408966e+01 -2.22196369e+01 -2.59169750e+01 -2.72866211e+01 -3.01949692e+01 -2.92600536e+01 -2.88494530e+01 -2.46767349e+01 -2.61831207e+01 -2.53925934e+01 -2.69116249e+01 -2.68773327e+01 -3.07702103e+01 -3.17145634e+01 -2.98042450e+01 -2.98371773e+01 -2.82408218e+01 -2.84821625e+01 -2.58273773e+01 -2.42762794e+01 -2.33294621e+01 -3.13017921e+01 -3.90069847e+01 -4.08870506e+01 -4.52639122e+01 -5.35120659e+01 -6.48112183e+01 -6.48290863e+01 -5.95596466e+01 -6.00363808e+01 -5.59964561e+01 -5.91463242e+01 -5.19657936e+01 -4.43262520e+01 -3.55966415e+01 -4.36180267e+01 -5.74469604e+01 -5.51861229e+01 -4.77407684e+01 -3.84271507e+01 -4.06616631e+01 -4.06541595e+01 -3.92804413e+01 -3.69262161e+01 -3.82252998e+01 -4.16794815e+01 -5.46767883e+01 -6.46369247e+01 -6.04646606e+01 -5.13874893e+01 -3.95980377e+01 -4.84337158e+01 -5.22080765e+01 -5.66148262e+01 -5.89064789e+01 -6.45815659e+01 -7.43783569e+01 -6.51207809e+01 -5.25872231e+01 -3.92979736e+01 -3.43562698e+01 -3.02586517e+01 -3.22043037e+01 -3.70683060e+01 -5.25904236e+01 -6.18354683e+01 -7.48539429e+01 -7.84606781e+01 -7.05796661e+01 -7.02087631e+01 -6.97921143e+01 -7.01710663e+01 -5.93381386e+01 -4.64505272e+01 -4.39775620e+01 -4.53858795e+01 -4.81898613e+01 -4.83345337e+01 -5.58386688e+01 -6.14825439e+01 -6.16891823e+01 -5.16724319e+01 -4.01435432e+01 -3.93094215e+01 -4.02134972e+01 -4.35270805e+01 -4.36863365e+01 -4.12086754e+01 -3.64078217e+01 -3.55389748e+01 -3.65213165e+01 -4.67512131e+01 -5.60363426e+01 -5.92435799e+01 -5.46366692e+01 -5.10550499e+01 -5.03546677e+01 -4.57915382e+01 -4.05358162e+01 -3.94538994e+01 -5.06453934e+01 -6.22406921e+01 -6.52418060e+01 -6.13222847e+01 -5.46947441e+01 -5.36983719e+01 -5.37496033e+01 -5.05691948e+01 -4.75621567e+01 -3.91978226e+01 -4.71967087e+01 -6.05128670e+01 -6.09582520e+01 -4.96908989e+01 -3.91860847e+01 -4.55996857e+01 -5.63007050e+01 -6.35585327e+01 -6.03173523e+01 -5.28677368e+01 -4.70358543e+01 -4.92266159e+01 -4.95115623e+01 -5.77673492e+01 -6.32993851e+01 -6.47109451e+01 -6.18339424e+01 -5.93437614e+01 -6.16257401e+01 -5.83087807e+01 -6.34220467e+01 -7.11284180e+01 -7.18972397e+01 -6.44433746e+01 -5.46646996e+01 -5.85384865e+01 -6.57191925e+01 -6.81611099e+01 -6.45195160e+01 -5.62351990e+01 -5.39151230e+01 -5.32288094e+01 -5.44548111e+01 -5.15734215e+01 -4.66151199e+01 -4.60721436e+01 -5.02393074e+01 -5.70065002e+01 -6.04086266e+01 -6.19930115e+01 -5.97053528e+01 -5.71902809e+01 -5.16657410e+01 -4.87442932e+01 -4.53793526e+01 -4.56734543e+01 -4.83631096e+01 -5.30274200e+01 -5.36143532e+01 -5.13208008e+01 -5.37321739e+01 -5.79011192e+01 -5.53308487e+01 -5.01244698e+01 -4.23200989e+01 -4.14940300e+01 -4.39079514e+01 -5.09409676e+01 -5.98184242e+01 -6.72358704e+01 -7.52556000e+01 -7.31665497e+01 -6.50028839e+01 -6.18969727e+01 -6.65953217e+01 -6.65463257e+01 -6.04593582e+01 -5.67548561e+01 -5.68982239e+01 -5.71338158e+01 -5.65249596e+01 -5.89064827e+01 -5.81956062e+01 -5.49476547e+01 -4.98196182e+01 -5.20489082e+01 -5.64976006e+01 -5.59301758e+01 -5.34430161e+01 -5.76357117e+01 -6.65385513e+01 -6.56461792e+01 -5.64379692e+01 -4.79156837e+01 -4.98132668e+01 -5.67906418e+01 -6.44696732e+01 -6.46873779e+01 -6.01453476e+01 -5.73601418e+01 -6.18558960e+01 -6.46825790e+01 -6.39781380e+01 -5.97225494e+01 -6.01551895e+01 -6.65666733e+01 -7.49138947e+01 -7.97415771e+01 -8.04695663e+01 -6.89646912e+01 -5.75041504e+01 -5.55686607e+01 -6.61315689e+01 -7.35167007e+01 -6.92752380e+01 -6.29115944e+01 -5.92094154e+01 -5.69291420e+01 -5.43331375e+01 -5.37601357e+01 -5.54404793e+01 -5.85431938e+01 -6.25234795e+01 -6.65181351e+01 -7.11879654e+01 -7.05610809e+01 -6.54899979e+01 -6.09333649e+01 -6.09555931e+01 -6.18507385e+01 -6.05995636e+01 -6.07409821e+01 -6.09205170e+01 -6.15518761e+01 -6.13449821e+01 -5.99240227e+01 -6.23635941e+01 -6.56282730e+01 -6.66481323e+01 -6.74168320e+01 -6.87512054e+01 -6.77314377e+01 -6.40659866e+01 -6.03387909e+01 -6.06780128e+01 -6.06709824e+01 -6.02807121e+01 -6.05980072e+01 -6.50489807e+01 -6.90029831e+01 -7.21852036e+01 -7.22432327e+01 -6.70784454e+01 -6.28422546e+01 -6.02957115e+01 -6.35463066e+01 -6.68502884e+01 -6.57862015e+01 -6.36452980e+01 -6.23501472e+01 -6.31056900e+01 -6.51918945e+01 -6.63297958e+01 -6.61202698e+01 -6.68516769e+01 -7.05879974e+01 -7.43081131e+01 -7.27843170e+01 -6.72374725e+01 -6.40257568e+01 -6.62528763e+01 -6.89377441e+01 -6.94563904e+01 -6.65570831e+01 -6.40828171e+01 -6.52929077e+01 -6.71259308e+01 -6.97332535e+01 -7.02170792e+01 -6.76671906e+01 -6.44368973e+01 -6.14211655e+01 -6.13018150e+01 -6.17197647e+01 -6.14732857e+01 -6.18107452e+01 -6.29273300e+01 -6.47171631e+01 -6.48203735e+01 -6.35591202e+01 -6.21374397e+01 -6.11825447e+01 -6.15168076e+01 -6.36431122e+01 -6.58609467e+01 -6.53868942e+01 -6.37394676e+01 -6.27979355e+01 -6.28747597e+01 -6.29990730e+01 -6.28346939e+01 -6.28078690e+01 -6.31945343e+01 -6.31268425e+01 -6.37227211e+01 -6.50906982e+01 -6.57338943e+01 -6.53324127e+01 -6.53678284e+01 -1.00797569e+02 -6.00051086e+02 0. 0. 0. 0. 0. 28417318. 318329024. -60604248. -2.08527786e+02 -1.11213264e+02 -1.10601082e+02 28972150. -78539936. -233982096. -233982096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 407427488. 727483392. -82024408. -1.44853198e+03 -4.11141327e+02 -1.72964005e+02 -9.01162567e+01 -1.02619133e+02 -9.65799561e+01 -9.88565521e+01 -9.82319107e+01 -9.60714645e+01 -9.44666290e+01 -9.30431519e+01 -9.25260239e+01 -9.16623306e+01 -9.35085144e+01 -9.62391968e+01 -9.91143875e+01 -9.88491821e+01 -9.34311600e+01 -8.82725830e+01 -8.51772614e+01 -8.34866791e+01 -8.60506287e+01 -8.65371246e+01 -8.80745010e+01 -9.20752716e+01 -9.46277466e+01 -9.26966400e+01 -8.62820740e+01 -7.93278351e+01 -7.97026443e+01 -8.48087463e+01 -9.58214035e+01 -9.81948700e+01 -9.61661072e+01 -9.41698914e+01 -9.39547958e+01 -9.26949234e+01 -8.66082001e+01 -8.25096512e+01 -8.53354950e+01 -9.15271606e+01 -9.39401321e+01 -8.83240891e+01 -8.71186447e+01 -8.89316330e+01 -8.62244720e+01 -8.66790161e+01 -8.62258148e+01 -8.99334869e+01 -9.42927551e+01 -9.82948074e+01 -9.93900757e+01 -8.86548080e+01 -7.53107758e+01 -7.19184036e+01 -7.96988754e+01 -9.34241180e+01 -9.50135422e+01 -8.91289215e+01 -8.44614029e+01 -8.64735413e+01 -8.84668503e+01 -8.53571854e+01 -8.27445755e+01 -8.32021866e+01 -9.07474442e+01 -1.00349091e+02 -9.67895203e+01 -9.40414581e+01 -8.97976227e+01 -8.67248688e+01 -8.52584991e+01 -8.10211716e+01 -8.70168076e+01 -9.54912186e+01 -1.05390747e+02 -1.03082672e+02 -9.17138901e+01 -7.95975876e+01 -7.26487579e+01 -7.21386337e+01 -8.23922577e+01 -8.67150421e+01 -8.70312653e+01 -9.49683685e+01 -1.05393715e+02 -1.06194618e+02 -8.81265259e+01 -7.16859360e+01 -7.23958282e+01 -8.77953262e+01 -1.04207939e+02 -1.05319687e+02 -1.02205933e+02 -1.02151329e+02 -1.02599655e+02 -9.67270355e+01 -8.66965714e+01 -8.17097092e+01 -8.81089401e+01 -9.91492996e+01 -9.92686996e+01 -8.87248840e+01 -7.58865051e+01 -7.11948395e+01 -7.20196991e+01 -8.50091171e+01 -9.69957581e+01 -9.45249100e+01 -9.43168106e+01 -9.98190842e+01 -1.03582939e+02 -9.36277313e+01 -7.55859070e+01 -7.62831192e+01 -9.44846268e+01 -1.12708618e+02 -1.15750069e+02 -1.00095818e+02 -8.48146210e+01 -7.32588730e+01 -6.77500687e+01 -7.59412079e+01 -8.19965057e+01 -8.61610260e+01 -9.95246353e+01 -1.12631752e+02 -1.12966583e+02 -1.00532928e+02 -8.38946304e+01 -7.66616058e+01 -7.70857010e+01 -8.75207214e+01 -9.36112366e+01 -9.47875900e+01 -9.67216187e+01 -1.03354904e+02 -1.05839645e+02 -9.12967072e+01 -6.97182159e+01 -5.73652573e+01 -6.16447220e+01 -7.16392288e+01 -7.29467087e+01 -8.20158997e+01 -8.64717484e+01 -8.24107361e+01 -7.83571930e+01 -6.55992737e+01 -6.24919853e+01 -6.53113708e+01 -7.92464523e+01 -8.40155487e+01 -7.21040039e+01 -5.98624611e+01 -6.72111282e+01 -8.64786377e+01 -9.56748352e+01 -8.10200195e+01 -6.44905396e+01 -6.63818970e+01 -6.85869751e+01 -6.64222794e+01 -4.51130943e+01 -2.96480980e+01 -2.84225044e+01 -5.84857483e+01 -9.32042007e+01 -9.90494308e+01 -9.41200485e+01 -9.24961777e+01 -9.16715164e+01 -8.07666702e+01 -5.86472740e+01 -4.81660271e+01 -6.74826050e+01 -8.87448502e+01 -9.48669205e+01 -7.16636658e+01 -5.42686043e+01 -5.46111221e+01 -5.63521309e+01 -6.27287064e+01 -5.30166016e+01 -5.18731003e+01 -5.93845482e+01 -6.14757957e+01 -5.72445107e+01 -3.79550819e+01 -2.77810535e+01 -2.92019234e+01 -6.31640587e+01 -9.63393784e+01 -1.03315811e+02 -9.00800858e+01 -8.33716125e+01 -7.96959076e+01 -7.04086380e+01 -4.82805710e+01 -4.60898895e+01 -7.39563599e+01 -1.02265488e+02 -1.08545799e+02 -8.09866409e+01 -6.87223740e+01 -6.66753693e+01 -6.80130844e+01 -6.76060028e+01 -5.83990669e+01 -4.65184021e+01 -6.28114777e+01 -8.44547424e+01 -9.45074463e+01 -7.21099091e+01 -4.78539848e+01 -4.37027168e+01 -6.62649384e+01 -8.40927353e+01 -8.61266174e+01 -7.61918945e+01 -7.91412888e+01 -7.97789154e+01 -8.29425888e+01 -7.63517303e+01 -7.64202118e+01 -7.94142380e+01 -8.72453690e+01 -9.78677444e+01 -9.66870651e+01 -9.17717438e+01 -8.52248306e+01 -6.06414490e+01 -4.90439034e+01 -3.08598595e+01 -4.36307182e+01 -6.37159653e+01 -8.15570297e+01 -9.84535522e+01 -6.63539429e+01 -4.11506386e+01 -3.53581963e+01 -6.57293854e+01 -8.30359497e+01 -6.90861282e+01 -5.31626625e+01 -6.65765381e+01 -8.36691055e+01 -7.54232025e+01 -4.77947121e+01 -3.39623985e+01 -4.77456779e+01 -5.09038124e+01 -5.41430016e+01 -5.27675552e+01 -6.65493240e+01 -5.67167664e+01 -4.76139679e+01 -3.82767410e+01 -2.56102867e+01 -2.72089157e+01 -3.41891823e+01 -6.25423965e+01 -8.13380737e+01 -6.48834000e+01 -2.20048847e+01 -6.16789961e+00 -2.33842411e+01 -3.42016068e+01 -2.75321751e+01 -1.61825886e+01 -3.79357147e+01 -5.10459061e+01 -5.23527451e+01 -4.50341148e+01 -4.64145088e+01 -5.15963554e+01 -4.24240494e+01 -4.19205170e+01 -5.90977669e+01 -7.32901688e+01 -6.70580902e+01 -7.30564728e+01 -9.44345779e+01 -9.35453110e+01 -6.40423355e+01 -3.43900261e+01 -3.76364403e+01 -4.55440483e+01 -3.94489021e+01 -2.03192272e+01 -3.00673084e+01 -4.79089012e+01 -5.02094650e+01 -3.09943371e+01 -1.17306910e+01 -2.03714943e+01 -2.64494591e+01 -4.01348724e+01 -3.70865364e+01 -5.34162903e+01 -6.98061829e+01 -6.56845474e+01 -5.13666992e+01 -3.78395805e+01 -4.65881233e+01 -5.35478439e+01 -6.61048126e+01 -8.40337143e+01 -7.87521286e+01 -6.71373367e+01 -4.87475662e+01 -6.29959602e+01 -7.71176834e+01 -6.27125893e+01 -2.65308151e+01 -2.26962433e+01 -4.59526863e+01 -6.25887680e+01 -3.85904465e+01 -1.70626431e+01 -2.72305489e+01 -4.20512505e+01 -6.28695335e+01 -6.58455124e+01 -8.03475647e+01 -8.33215485e+01 -7.23793411e+01 -6.17823715e+01 -5.71752319e+01 -6.17117538e+01 -5.42346230e+01 -5.99432449e+01 -7.06546860e+01 -6.37586555e+01 -3.34264336e+01 -1.32968569e+01 -1.72329369e+01 -2.49524193e+01 -1.61936417e+01 -3.79340982e+00 -1.59727755e+01 -2.48978138e+01 -2.86876259e+01 -9.69889641e+00 -1.29356050e+01 -2.60538883e+01 -2.62319183e+01 -3.09316444e+01 -3.30226860e+01 -6.34475403e+01 -7.47152176e+01 -6.55189362e+01 -4.06929741e+01 -1.27561016e+01 -1.72265606e+01 -2.80599365e+01 -4.99682274e+01 -8.25181198e+01 -7.66705856e+01 -2.87533684e+01 2.86159210e+01 4.71105690e+01 1.63592167e+01 -3.54626799e+00 5.63734436e+00 9.95756721e+00 2.98413849e+01 5.76899481e+00 3.84114194e+00 -1.10431528e+01 -9.86333561e+00 3.08858376e+01 4.41795807e+01 4.50104370e+01 -9.33636761e+00 -4.56455002e+01 -2.34075165e+01 6.73482561e+00 2.12252655e+01 -1.69534473e+01 -4.90520096e+01 -4.43477974e+01 -4.30605507e+01 -2.03356495e+01 -3.64316392e+00 1.62386017e+01 2.90623016e+01 1.16108665e+01 -6.76673412e+00 -2.17989864e+01 -2.29350300e+01 1.43074112e+01 3.19978352e+01 5.24489250e+01 3.28029404e+01 -4.18460846e+00 -8.21528816e+00 -8.93019485e+00 -1.28771610e+01 -4.73953476e+01 -4.48125229e+01 1.69056988e+01 5.70753784e+01 6.02507324e+01 2.51031952e+01 5.67671156e+00 -3.84372473e-01 -1.96681499e+01 -1.84162560e+01 5.25972700e+00 2.34157581e+01 4.61442261e+01 3.30472145e+01 2.92354240e+01 2.79496784e+01 2.38941441e+01 2.53879166e+01 -1.48383970e+01 -1.80733109e+01 -1.17491360e+01 3.02102494e+00 3.86147079e+01 5.12650490e+01 5.28722191e+01 2.62086701e+00 -3.51101875e+01 -3.57822990e+01 8.07893336e-01 3.59987755e+01 1.29108591e+01 -2.52214317e+01 -4.20719414e+01 -3.08279266e+01 -1.29258766e+01 5.66784525e+00 1.63529797e+01 3.05603657e+01 7.66628504e+00 -1.18868017e+01 -2.66813869e+01 -8.18047810e+00 4.54636078e+01 7.03171082e+01 5.91413116e+01 1.76296425e+01 -1.94646397e+01 3.50778639e-01 3.14986572e+01 4.89119911e+01 1.70024223e+01 -1.27964230e+01 -6.84687710e+00 9.03762531e+00 2.47770348e+01 2.12211456e+01 1.53485889e+01 2.64053249e+01 2.66592522e+01 2.41591167e+01 2.72039909e+01 2.78625546e+01 4.52642860e+01 3.18582821e+01 2.55912151e+01 1.74842129e+01 1.17443209e+01 3.49509392e+01 2.02170525e+01 6.54906178e+00 -2.63058453e+01 -1.88916912e+01 2.76529732e+01 6.15873795e+01 7.34868546e+01 2.32025700e+01 -1.39482050e+01 -2.58153877e+01 -3.50800776e+00 2.73593102e+01 2.99138794e+01 1.07520971e+01 -7.35100222e+00 -2.34095516e+01 -5.41156006e+00 2.89059124e+01 6.88815308e+01 6.89632492e+01 1.94146519e+01 -2.10564079e+01 -3.61498451e+01 -2.08922005e+01 2.44572849e+01 6.02936592e+01 6.55768280e+01 2.49819927e+01 -1.40762024e+01 -2.87880397e+00 3.46665611e+01 6.01191101e+01 3.38284492e+01 -6.49705839e+00 -1.30425653e+01 1.86750913e+00 3.58400955e+01 5.89145241e+01 6.15753784e+01 5.49144669e+01 3.00296078e+01 9.57104015e+00 7.78714228e+00 1.78317833e+01 5.29046707e+01 4.75446625e+01 3.27276421e+01 2.02533607e+01 1.43811107e+00 2.73951492e+01 2.90654373e+01 3.60079613e+01 9.67112541e+00 1.79918563e+00 4.76112709e+01 7.12448044e+01 7.31045761e+01 2.86760483e+01 -2.07596517e+00 -6.56073046e+00 8.76116180e+00 4.16337090e+01 6.38770523e+01 6.25129623e+01 5.74236221e+01 3.41197662e+01 2.53167725e+01 3.21732635e+01 3.32298775e+01 4.28669548e+01 1.30144958e+01 1.27776079e+01 1.06976738e+01 1.91743317e+01 5.10288162e+01 5.29188347e+01 4.07116814e+01 -4.43380928e+00 -1.93393974e+01 -8.54837799e+00 1.52322245e+01 4.05067749e+01 2.50545158e+01 -5.43057024e-02 -1.53286781e+01 -6.00631142e+00 1.68839054e+01 3.11437817e+01 3.87705193e+01 4.41577339e+01 4.58072548e+01 4.53401375e+01 4.57452507e+01 5.22508430e+01 7.72353973e+01 5.51879463e+01 2.66340675e+01 3.16213036e+00 2.46923389e+01 6.55166245e+01 8.38464966e+01 7.45347519e+01 3.99218292e+01 1.68669071e+01 2.91013794e+01 4.62350121e+01 5.57175140e+01 4.68912735e+01 4.02085381e+01 5.23228111e+01 5.93831787e+01 6.86714859e+01 7.38149796e+01 7.62721100e+01 8.08416367e+01 6.30280800e+01 5.31048088e+01 5.19456329e+01 5.03943634e+01 6.59514999e+01 5.83068352e+01 5.65384064e+01 4.04480095e+01 3.10971260e+01 5.50362206e+01 5.81412697e+01 6.56568832e+01 4.53627510e+01 3.50384407e+01 5.09748001e+01 5.62202606e+01 8.61539841e+01 7.25651245e+01 5.46938133e+01 3.00207634e+01 1.98638382e+01 5.22243614e+01 6.28169937e+01 6.71755447e+01 7.05080643e+01 7.15297546e+01 6.81002960e+01 3.06521873e+01 2.40694237e+01 6.10661507e+01 5.44610939e+01 2.12975235e+01 -5.02754211e+01 -8.92772293e+00 -8.79815186e+02 -1.51508887e+03 4.20615820e+03 1.25005635e+04 46472784. -264798400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -358400512. 51028948. -4.02889844e+03 -1.45717896e+03 -2.84292278e+01 -1.44486679e+02 -1.96141663e+02 -3.70976715e+01 2.95455418e+01 4.22804909e+01 5.41221542e+01 5.39766502e+01 6.71897202e+01 7.69838638e+01 7.89676895e+01 7.03799667e+01 6.91000443e+01 8.43911667e+01 9.44434204e+01 9.22547302e+01 8.85288849e+01 8.04354782e+01 7.55918579e+01 5.88724174e+01 5.52248764e+01 7.83603363e+01 8.98366165e+01 8.00566101e+01 5.82808952e+01 7.23379135e+01 1.01250595e+02 1.05061996e+02 8.88610992e+01 7.10058670e+01 7.01673813e+01 7.40714722e+01 7.22918091e+01 7.74722519e+01 8.53892822e+01 9.05953751e+01 8.62424088e+01 7.48507004e+01 8.12169647e+01 8.91311340e+01 1.01581635e+02 1.17987480e+02 1.06043800e+02 8.43249817e+01 5.31159592e+01 5.49762383e+01 8.32235413e+01 8.79201584e+01 8.15232162e+01 6.07781372e+01 6.20525475e+01 7.81603928e+01 8.64082413e+01 9.36320953e+01 8.18939896e+01 7.95671158e+01 7.99593201e+01 8.49471130e+01 9.91823273e+01 1.08177475e+02 1.08731621e+02 9.73220367e+01 8.68717575e+01 9.02681961e+01 9.26090469e+01 1.03609055e+02 1.18111565e+02 1.25438835e+02 1.24677528e+02 1.08140923e+02 1.00833908e+02 1.08074600e+02 9.99787064e+01 8.69553146e+01 6.37978935e+01 6.98612061e+01 8.65826721e+01 9.24010544e+01 9.34623260e+01 9.51865768e+01 9.76035309e+01 9.08554459e+01 8.00883408e+01 8.24719467e+01 8.85071564e+01 8.97125931e+01 9.19573822e+01 9.66230545e+01 1.05597977e+02 1.00093216e+02 9.16697083e+01 1.01089951e+02 1.03141594e+02 1.00562820e+02 8.57604065e+01 8.08058701e+01 9.95629883e+01 1.00685577e+02 9.45490799e+01 7.33897095e+01 6.94878006e+01 8.28420639e+01 8.99721832e+01 9.68471069e+01 9.82501297e+01 1.02744118e+02 1.04920181e+02 9.68129425e+01 9.73030930e+01 9.83461227e+01 1.01436226e+02 9.80247192e+01 9.01976852e+01 9.24605713e+01 9.11076355e+01 8.86805038e+01 9.54660110e+01 9.62889786e+01 9.31938324e+01 7.86709213e+01 7.63266296e+01 9.52737961e+01 9.98289185e+01 9.34700089e+01 7.76144485e+01 7.72194366e+01 8.91074066e+01 9.20653152e+01 9.37678986e+01 9.47234497e+01 9.29144440e+01 8.97007141e+01 8.18279190e+01 8.72308350e+01 9.31727142e+01 9.43884659e+01 9.03511581e+01 8.32359314e+01 8.69280701e+01 8.95991745e+01 9.24069672e+01 9.75229034e+01 9.93053284e+01 1.01141029e+02 9.91131363e+01 9.78274460e+01 1.01945732e+02 9.97456589e+01 9.59258652e+01 8.67315521e+01 8.06563110e+01 8.37111969e+01 8.63283463e+01 9.31265335e+01 9.48004837e+01 9.74650803e+01 1.00481819e+02 1.00315918e+02 9.84698868e+01 9.75116501e+01 9.93357239e+01 1.01727066e+02 9.75420914e+01 9.01394882e+01 8.47157745e+01 8.34836121e+01 9.26787415e+01 9.55285339e+01 9.33775864e+01 8.86396027e+01 8.98354187e+01 9.44026794e+01 9.39632416e+01 9.48487244e+01 9.54655609e+01 9.53628082e+01 9.27864380e+01 9.06257248e+01 9.29400787e+01 9.56918259e+01 9.51938782e+01 9.55910797e+01 9.56082687e+01 9.76027679e+01 1.00036179e+02 1.01892807e+02 1.03449310e+02 9.85117722e+01 9.47023239e+01 9.20110855e+01 9.18698502e+01 9.52572021e+01 9.48032303e+01 9.31762466e+01 8.89634857e+01 8.94164886e+01 9.29097290e+01 9.53534698e+01 9.60849228e+01 9.51830063e+01 9.60195007e+01 9.67496643e+01 9.59588318e+01 9.53747940e+01 9.50786972e+01 9.53127213e+01 9.45660858e+01 9.34315720e+01 9.32099915e+01 9.23689728e+01 9.23759308e+01 9.37886734e+01 9.48711014e+01 9.45048752e+01 9.33348923e+01 9.29127655e+01 9.30491562e+01 9.28455505e+01 9.27330551e+01 9.27534637e+01 9.29060364e+01 9.29951553e+01 9.29408722e+01 9.25885315e+01 9.23332062e+01 9.25598755e+01 9.30757141e+01 9.33084564e+01 9.28569870e+01 9.24856110e+01 9.27552872e+01 9.28103638e+01 9.29372482e+01 9.29227219e+01 9.30091629e+01 9.27227173e+01 9.26966476e+01 9.24447708e+01 9.23911362e+01 9.26723862e+01 9.34988251e+01 9.36784058e+01 9.31611176e+01 9.23586197e+01 9.25115128e+01 9.32520752e+01 9.31069717e+01 9.29687881e+01 9.11388626e+01 8.97988663e+01 8.96322861e+01 9.08937607e+01 9.30288620e+01 9.25266418e+01 9.23533936e+01 9.18127823e+01 9.18982010e+01 9.10722580e+01 9.11348801e+01 9.12175369e+01 9.18651657e+01 9.10933914e+01 9.20439606e+01 9.27888184e+01 9.26866760e+01 9.24433746e+01 9.31750336e+01 9.39815063e+01 9.32220459e+01 9.26948090e+01 9.28200455e+01 9.27840347e+01 9.17971878e+01 9.29180832e+01 9.31791382e+01 9.30315399e+01 9.13437576e+01 9.17275391e+01 9.33364029e+01 9.35895462e+01 9.23157501e+01 9.31278000e+01 9.48433075e+01 9.55845032e+01 9.28821182e+01 9.16095657e+01 9.17081833e+01 9.27671738e+01 9.26171570e+01 9.26745605e+01 9.11553421e+01 8.87597275e+01 8.62232056e+01 8.60948944e+01 8.85274963e+01 8.88747482e+01 9.05876465e+01 8.95697250e+01 8.94167252e+01 8.78394394e+01 8.78215408e+01 8.89243469e+01 8.83470154e+01 8.87859344e+01 9.25013885e+01 9.50821686e+01 9.50534897e+01 9.19224396e+01 9.18349304e+01 8.88984528e+01 8.59239655e+01 8.34679642e+01 8.55869293e+01 8.80773697e+01 8.79174118e+01 8.59618378e+01 8.94479294e+01 9.37121735e+01 9.45096588e+01 9.02299271e+01 8.47401199e+01 8.35169754e+01 8.23083496e+01 8.31061630e+01 9.10768280e+01 9.76329422e+01 9.88682251e+01 9.32442322e+01 8.76487885e+01 8.76490250e+01 8.69429779e+01 8.53496780e+01 8.37918320e+01 8.36803055e+01 8.43408890e+01 8.39938889e+01 8.53058243e+01 8.56755981e+01 8.41881485e+01 7.98252945e+01 7.37545166e+01 6.92832565e+01 7.06658401e+01 7.63262482e+01 8.20290909e+01 7.92801514e+01 7.73959198e+01 7.97143936e+01 8.44472809e+01 8.85171127e+01 8.49426880e+01 8.12225800e+01 7.78118439e+01 7.93523636e+01 8.10654907e+01 8.10787430e+01 7.91877670e+01 7.20744171e+01 6.32618561e+01 7.35368118e+01 9.16120911e+01 9.82175217e+01 8.90073776e+01 7.70508575e+01 7.88065567e+01 8.10632706e+01 8.37055130e+01 8.20895996e+01 7.98033600e+01 7.97661819e+01 8.42409210e+01 8.85934677e+01 8.40400238e+01 7.35322647e+01 6.70706177e+01 7.30419159e+01 8.07075882e+01 8.38429871e+01 8.27833328e+01 8.30023956e+01 8.50733948e+01 9.21534958e+01 9.86544876e+01 9.32905273e+01 8.45172882e+01 7.89154587e+01 8.37623062e+01 8.23006439e+01 7.86172943e+01 7.69915543e+01 7.80785904e+01 7.84568329e+01 7.95781326e+01 8.21835556e+01 8.86601944e+01 8.55873871e+01 8.14188309e+01 7.60561905e+01 7.39669418e+01 6.70688858e+01 5.33471222e+01 4.52721138e+01 4.99816399e+01 6.06044846e+01 6.83662872e+01 7.15728912e+01 7.02927246e+01 6.61268692e+01 6.39638176e+01 6.58586273e+01 6.92457733e+01 6.95805435e+01 7.27957458e+01 6.46815948e+01 5.51246796e+01 5.21967735e+01 5.98629837e+01 6.91329269e+01 6.84901505e+01 7.16915512e+01 7.44314880e+01 7.84084244e+01 7.47077408e+01 7.30954285e+01 7.34420471e+01 7.49797516e+01 7.38401718e+01 7.18436050e+01 7.66298218e+01 7.75234070e+01 7.78373260e+01 7.46528931e+01 7.22550964e+01 7.52812347e+01 7.78512878e+01 8.09816208e+01 7.85103760e+01 7.05010147e+01 6.37325554e+01 6.13750954e+01 6.39375992e+01 7.00213318e+01 8.07679291e+01 8.65296021e+01 7.32702713e+01 6.10520401e+01 4.86873627e+01 4.82872391e+01 4.41228943e+01 4.57464333e+01 5.65001221e+01 8.25431290e+01 1.09518272e+02 1.41750687e+02 1.96154556e+02 2.27067352e+02 1.08220520e+03 1.17936499e+03 -2.76302461e+04 -353220768. 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. 0. 0. 0. 0. 0. 0. 0. 119250520. -71518888. -17341892. -55024388. 1.02433662e+04 4.55917334e+03 2.17828687e+03 1.46625146e+03 4.03425232e+02 2.63890411e+02 2.04470337e+02 1.36016983e+02 1.12700294e+02 1.08101036e+02 1.24297401e+02 1.15813423e+02 4.74911575e+01 -2.22124119e+01 -1.56407957e+01 5.31905518e+01 1.51677277e+02 1.51640686e+02 2.24807236e+02 2.69568481e+02 2.84426483e+02 2.15897812e+02 1.94134048e+02 2.44468323e+02 2.59900024e+02 2.58934326e+02 2.47929733e+02 2.10278152e+02 1.16633667e+02 7.84144363e+01 5.76407394e+01 5.90626984e+01 5.24569664e+01 4.49291115e+01 3.62334290e+01 3.97754745e+01 4.58549767e+01 4.52369614e+01 3.85471268e+01 3.10153332e+01 2.50409946e+01 1.88178749e+01 2.14651203e+01 1.81458530e+01 1.59693642e+01 1.58233767e+01 2.09488506e+01 2.95698872e+01 2.66928215e+01 2.43265457e+01 2.55699406e+01 2.76090164e+01 3.01748371e+01 2.76406937e+01 2.59149284e+01 3.21879692e+01 3.55886650e+01 5.21723289e+01 6.30155830e+01 6.45956955e+01 6.02027435e+01 5.49261742e+01 6.73322906e+01 7.42285461e+01 6.35230980e+01 4.71381454e+01 2.95908222e+01 2.50596962e+01 2.18450089e+01 1.08108826e+01 -3.87427926e+00 -1.38851357e+01 -1.17833300e+01 3.15550804e+00 1.47454176e+01 2.33108654e+01 2.48598499e+01 2.20373020e+01 3.55521545e+01 4.87849121e+01 6.82754517e+01 7.41951904e+01 6.52812729e+01 5.15040970e+01 3.68519478e+01 3.23696136e+01 3.53435707e+01 5.32362480e+01 6.96127014e+01 6.48747177e+01 4.48811989e+01 3.05797367e+01 3.27781563e+01 3.87044182e+01 4.28395805e+01 4.90377998e+01 2.86042767e+01 7.88096476e+00 -2.04733086e+00 7.22865152e+00 2.52618065e+01 2.45503597e+01 2.98556099e+01 3.68393631e+01 4.35319061e+01 5.26709938e+01 5.07498894e+01 3.61945534e+01 1.65275040e+01 -3.95340943e+00 -3.81554246e+00 2.47615647e+00 9.19265556e+00 9.64502621e+00 1.42550421e+00 -7.47632012e-02 8.65291953e-01 3.43456268e+00 6.70535326e+00 1.23006334e+01 1.60904560e+01 1.43230438e+01 1.69962692e+01 3.60562286e+01 5.93980637e+01 5.97786674e+01 4.39715652e+01 2.72432632e+01 3.46075363e+01 4.41024094e+01 5.68824234e+01 6.19107361e+01 5.08253975e+01 3.14948807e+01 1.35078583e+01 7.20525408e+00 4.84918213e+00 5.41085196e+00 6.64541817e+00 4.53806734e+00 -2.36905992e-01 -1.13505185e+00 5.53571081e+00 8.11573029e+00 7.30954790e+00 6.72684431e+00 9.77239609e+00 1.74418640e+01 3.57312813e+01 5.14736328e+01 4.69303551e+01 2.56209393e+01 7.26972342e+00 2.29642220e+01 4.08223610e+01 5.33804245e+01 5.29622955e+01 5.77370911e+01 6.14145813e+01 4.66869698e+01 3.28776283e+01 1.39019041e+01 1.17667551e+01 6.33393812e+00 2.98353958e+00 9.06092167e+00 8.59154415e+00 7.54379034e+00 4.02642059e+00 5.99429464e+00 5.25852633e+00 -2.07786312e+01 -4.24588547e+01 -4.24454117e+01 -2.00264797e+01 8.76456201e-01 5.69508266e+00 5.72158623e+00 -3.75303566e-01 -7.90869856e+00 3.20976973e+00 2.47481098e+01 2.44461784e+01 1.03173323e+01 -9.74423313e+00 -5.79085350e+00 -2.07130814e+00 9.17786360e-01 -4.98252487e+00 -3.92076039e+00 -4.49206686e+00 2.40712237e+00 4.04352522e+00 4.95458508e+00 1.74450183e+00 -9.10739839e-01 -1.74470692e+01 -3.42287407e+01 -3.42084885e+01 -2.21673717e+01 -6.60142803e+00 -1.57500668e+01 -1.56439390e+01 -9.77397823e+00 -2.45846176e+00 -1.29974627e+00 -6.77752256e+00 -1.04769621e+01 -1.18868971e+01 -1.03736057e+01 -5.46652365e+00 -7.12608099e+00 -1.02551460e+01 -1.25225134e+01 -1.53442183e+01 -1.42522821e+01 -1.88874187e+01 -1.57790613e+01 -1.64857216e+01 -1.51017733e+01 -1.85167580e+01 -3.03338909e+01 -3.92471390e+01 -4.01419067e+01 -3.35745888e+01 -2.36160851e+01 -2.63710194e+01 -2.38179417e+01 -2.95535984e+01 -3.25953903e+01 -3.11683941e+01 -3.01537952e+01 -2.63345146e+01 -3.37492485e+01 -3.48636284e+01 -3.38773842e+01 -2.63385010e+01 -1.94321327e+01 -1.90129414e+01 -3.54393539e+01 -5.28907471e+01 -5.69858055e+01 -4.32968559e+01 -5.11315489e+00 1.64412785e+01 1.54759426e+01 -8.84734058e+00 -2.63191833e+01 -6.78446102e+00 9.04688549e+00 7.70219803e+00 -1.31025410e+01 -3.00985565e+01 -3.24513283e+01 -3.40548630e+01 -3.19406719e+01 -2.93564930e+01 -3.19818516e+01 -3.63883820e+01 -3.45400352e+01 -2.82004128e+01 -1.95207787e+01 -3.28618507e+01 -4.37689400e+01 -4.91395798e+01 -3.23607330e+01 -1.64863758e+01 -1.29863968e+01 -1.61593609e+01 -1.72876625e+01 -1.98224392e+01 -1.90002174e+01 -2.24628620e+01 -1.18870974e+01 -3.98230290e+00 -9.10849571e+00 -2.84511375e+01 -4.29837456e+01 -4.18447990e+01 -3.44382095e+01 -2.82584209e+01 -2.74643459e+01 -4.17089958e+01 -6.03396187e+01 -5.91276817e+01 -4.68997917e+01 -3.19988194e+01 -3.80236435e+01 -3.89836578e+01 -4.10434380e+01 -3.59756432e+01 -2.22661247e+01 -6.05306053e+00 -9.19049072e+00 -2.27605648e+01 -4.16999474e+01 -3.98627701e+01 -3.69307327e+01 -3.52617264e+01 -3.72131500e+01 -2.79231548e+01 -1.18283281e+01 -7.64445305e+00 -1.35132780e+01 -3.05273418e+01 -2.90426979e+01 -3.37377281e+01 -3.60007858e+01 -4.00081215e+01 -3.87650223e+01 -3.33345451e+01 -2.90704517e+01 -3.05218353e+01 -3.55780334e+01 -3.93682137e+01 -4.34844131e+01 -4.84563026e+01 -5.35485382e+01 -5.42266006e+01 -5.46160355e+01 -5.16666718e+01 -3.79994354e+01 -2.06391811e+01 -1.01949434e+01 -7.20364046e+00 -7.14837694e+00 -7.22922754e+00 -2.94019375e+01 -4.25015831e+01 -5.58063889e+01 -4.98273048e+01 -4.91857109e+01 -3.76589546e+01 -2.47581062e+01 -2.94894791e+01 -3.62519455e+01 -5.83008308e+01 -7.06140137e+01 -7.42281265e+01 -6.68036194e+01 -5.48549919e+01 -5.49918556e+01 -4.65338821e+01 -3.12960682e+01 -2.10394859e+01 -3.22560616e+01 -4.86369324e+01 -6.74264984e+01 -5.62580299e+01 -4.38936195e+01 -3.52106552e+01 -3.73087921e+01 -4.84915161e+01 -5.75759087e+01 -7.00157776e+01 -6.90938110e+01 -6.71972046e+01 -6.83277359e+01 -6.74583511e+01 -6.56012650e+01 -6.50695877e+01 -6.49624405e+01 -6.60475388e+01 -6.47611313e+01 -6.32001343e+01 -5.79615059e+01 -4.43409691e+01 -2.90085144e+01 -4.21472130e+01 -6.57228088e+01 -6.77182465e+01 -4.64668312e+01 -3.11763535e+01 -4.38156395e+01 -5.79348564e+01 -4.90352173e+01 -4.06513100e+01 -3.83906212e+01 -4.75847435e+01 -5.82230835e+01 -5.59319344e+01 -5.35310974e+01 -4.90451889e+01 -5.38213501e+01 -5.79710045e+01 -6.26009521e+01 -6.33761749e+01 -6.35315323e+01 -5.99767532e+01 -6.01806526e+01 -5.60814629e+01 -5.02629318e+01 -3.93327065e+01 -5.15121689e+01 -7.48725662e+01 -7.27230453e+01 -5.03321190e+01 -3.68410759e+01 -5.49834290e+01 -6.96487427e+01 -6.37605782e+01 -5.50794487e+01 -6.41196518e+01 -8.21023483e+01 -9.25376740e+01 -8.76762772e+01 -8.13256073e+01 -7.02551041e+01 -5.83615379e+01 -5.93232994e+01 -7.50379333e+01 -7.60047455e+01 -5.93833275e+01 -5.56369362e+01 -6.86292572e+01 -8.28032379e+01 -8.23313675e+01 -7.92441025e+01 -8.64024048e+01 -9.55636978e+01 -8.93620224e+01 -7.41163406e+01 -6.03360786e+01 -6.64346466e+01 -7.17335052e+01 -7.34239883e+01 -7.28060150e+01 -7.15117569e+01 -7.28852692e+01 -7.57835541e+01 -8.33125992e+01 -8.23322601e+01 -7.02868195e+01 -5.65172310e+01 -5.35064926e+01 -6.06488800e+01 -5.70322876e+01 -4.46604652e+01 -4.92935638e+01 -6.91661835e+01 -8.87341309e+01 -9.08228989e+01 -8.25165710e+01 -8.52924957e+01 -8.81946259e+01 -8.63316040e+01 -7.91759949e+01 -7.19584656e+01 -7.22978134e+01 -7.69204712e+01 -7.92049103e+01 -8.60775909e+01 -8.69536209e+01 -8.57532578e+01 -8.47205887e+01 -8.49120483e+01 -8.51083908e+01 -7.71701965e+01 -6.84280930e+01 -6.94178467e+01 -7.63685074e+01 -7.97552567e+01 -7.54673920e+01 -8.14311676e+01 -9.23262863e+01 -9.15950623e+01 -7.27768021e+01 -5.17750511e+01 -4.79606056e+01 -5.61857643e+01 -5.97894249e+01 -5.60959816e+01 -5.98209877e+01 -6.56098099e+01 -7.22920685e+01 -7.02810898e+01 -7.17955933e+01 -7.00470352e+01 -6.69544601e+01 -6.78314819e+01 -7.56760483e+01 -8.59426727e+01 -8.21787109e+01 -7.33341141e+01 -7.13200607e+01 -7.98372879e+01 -7.89665604e+01 -7.06085663e+01 -7.63086700e+01 -9.48594437e+01 -1.07269897e+02 -1.00365219e+02 -9.17489548e+01 -9.58335266e+01 -1.05198921e+02 -1.05653130e+02 -1.00035957e+02 -9.48764572e+01 -9.90017014e+01 -1.01174179e+02 -9.97050858e+01 -9.41436386e+01 -8.41551666e+01 -7.47715073e+01 -6.95410767e+01 -6.98333588e+01 -8.17262573e+01 -9.23979950e+01 -9.83765335e+01 -9.31361237e+01 -8.79940186e+01 -8.82936859e+01 -8.89203796e+01 -9.40425797e+01 -1.01814522e+02 -9.94655685e+01 -9.30178757e+01 -8.64621048e+01 -8.62754974e+01 -8.59195938e+01 -7.91921997e+01 -7.36983337e+01 -7.50131226e+01 -8.10048370e+01 -8.61809540e+01 -8.66101761e+01 -8.75270309e+01 -8.74346237e+01 -8.54315186e+01 -8.32622910e+01 -8.36476059e+01 -8.62808304e+01 -8.79500427e+01 -8.95774307e+01 -8.98205032e+01 -9.00476456e+01 -8.52695999e+01 -7.84191132e+01 -7.74632492e+01 -8.11535797e+01 -8.20559845e+01 -7.73815308e+01 -7.86836700e+01 -8.23522415e+01 -8.64628067e+01 -8.17318039e+01 -7.82338028e+01 -8.04082565e+01 -8.53320923e+01 -9.19072037e+01 -9.23713989e+01 -9.22250595e+01 -8.80760498e+01 -8.38862381e+01 -8.38287354e+01 -8.76386337e+01 -8.73212280e+01 -8.33576965e+01 -8.32514648e+01 -8.63891754e+01 -9.18753510e+01 -8.88204727e+01 -8.57953644e+01 -8.64119720e+01 -9.22306671e+01 -9.59051514e+01 -9.30428696e+01 -8.88698578e+01 -8.85987015e+01 -8.88759689e+01 -9.02796249e+01 -8.96749878e+01 -8.89991379e+01 -8.87358627e+01 -8.57880173e+01 -8.42944260e+01 -8.48219833e+01 -8.75407791e+01 -9.02413940e+01 -9.01825409e+01 -9.06342316e+01 -9.05684662e+01 -9.03524780e+01 -9.11249313e+01 -9.11272964e+01 -9.21054382e+01 -9.18752289e+01 -9.23849258e+01 -9.42759628e+01 -9.60274429e+01 -9.37009964e+01 -9.02202225e+01 -8.90820618e+01 -9.16083221e+01 -9.33345413e+01 -9.36021576e+01 -9.28958359e+01 -9.29494095e+01 -9.27181625e+01 -9.25517197e+01 -9.10008163e+01 -8.52802811e+01 -7.78394623e+01 -9.05938873e+01 -1.05798599e+02 -1.19898659e+02 -2.22913986e+02 3.66559131e+03 0. 0. 0. 0. 0. 28417318. 318329024. -60604248. -1.53969727e+03 -1.66814771e+03 37697876. 28972150. -78539936. -233982096. -233982096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 99733608. 129633552. 77189736. 5.08419914e+01 6.60054255e+00 -9.93518066e+01 -8.98532028e+01 -8.55165253e+01 -8.62035522e+01 -9.36662827e+01 -9.90387573e+01 -1.03903099e+02 -1.04225052e+02 -1.00794846e+02 -9.92237625e+01 -1.00336075e+02 -9.87680664e+01 -9.52300644e+01 -9.24483414e+01 -9.60103607e+01 -1.03627205e+02 -1.08042946e+02 -1.05509331e+02 -9.97573547e+01 -9.58906631e+01 -9.65876694e+01 -9.82351608e+01 -9.65783997e+01 -9.38900604e+01 -9.55456390e+01 -1.00767242e+02 -1.03688324e+02 -1.01626495e+02 -9.69378281e+01 -9.49801178e+01 -9.88821869e+01 -1.05182579e+02 -1.08342514e+02 -1.05019730e+02 -1.05695740e+02 -1.10388794e+02 -1.06814140e+02 -9.73903809e+01 -9.07520142e+01 -9.84307556e+01 -1.14130341e+02 -1.19201897e+02 -1.11707001e+02 -1.03368416e+02 -9.81559982e+01 -9.71339264e+01 -9.71930847e+01 -9.71772919e+01 -9.56621628e+01 -9.78082733e+01 -1.11034889e+02 -1.21969604e+02 -1.16920624e+02 -1.04115509e+02 -9.67613907e+01 -1.02993019e+02 -1.11723106e+02 -1.14896072e+02 -1.05796013e+02 -1.03448654e+02 -1.07513954e+02 -1.04756851e+02 -9.46892929e+01 -8.34276886e+01 -8.59026642e+01 -1.03222595e+02 -1.08899551e+02 -1.02331558e+02 -8.94863663e+01 -9.19855270e+01 -1.02037346e+02 -9.87957306e+01 -9.13423920e+01 -8.67384186e+01 -9.40093536e+01 -1.10096268e+02 -1.15698357e+02 -1.09918991e+02 -9.21096954e+01 -8.35003433e+01 -8.66737289e+01 -9.51577606e+01 -9.17526932e+01 -8.26684875e+01 -8.28202896e+01 -9.43232422e+01 -1.00522377e+02 -8.79848175e+01 -7.34318924e+01 -7.19472961e+01 -9.01577225e+01 -1.05840591e+02 -1.07031517e+02 -9.40268402e+01 -9.00023270e+01 -9.28162155e+01 -8.37644653e+01 -6.57284927e+01 -5.59186172e+01 -7.22949142e+01 -9.91255264e+01 -1.13030701e+02 -1.04767181e+02 -8.88555832e+01 -7.14714813e+01 -6.04750710e+01 -6.45116196e+01 -7.03570862e+01 -7.06639862e+01 -7.10280380e+01 -8.79796448e+01 -1.04680244e+02 -9.50414200e+01 -6.66517258e+01 -5.37421455e+01 -6.48248672e+01 -9.26630325e+01 -1.04164619e+02 -9.36404037e+01 -8.08204803e+01 -8.06465225e+01 -8.17041550e+01 -7.01454315e+01 -4.30327072e+01 -4.42753792e+01 -6.62313385e+01 -9.11628494e+01 -9.02067261e+01 -7.54864807e+01 -6.31057816e+01 -6.06258812e+01 -6.40607605e+01 -7.33229370e+01 -7.89842453e+01 -6.52717743e+01 -5.98102341e+01 -7.15895081e+01 -8.53079376e+01 -8.88130951e+01 -8.04152756e+01 -7.91260605e+01 -8.72746735e+01 -8.72483063e+01 -7.84608536e+01 -6.68280411e+01 -6.10131798e+01 -7.35849228e+01 -8.01453629e+01 -7.59262466e+01 -6.48262405e+01 -7.41550369e+01 -1.10551079e+02 -1.27825706e+02 -1.00303314e+02 -6.91016083e+01 -6.34753647e+01 -8.38196640e+01 -9.30942764e+01 -9.21849747e+01 -9.23068848e+01 -1.04902649e+02 -1.22735764e+02 -1.29385895e+02 -1.16902122e+02 -9.04624176e+01 -6.98568192e+01 -8.39716797e+01 -9.56310043e+01 -9.39618073e+01 -7.59235992e+01 -8.63091583e+01 -1.18500168e+02 -1.18774086e+02 -1.02304573e+02 -8.63985901e+01 -1.04492393e+02 -1.44917877e+02 -1.61221558e+02 -1.37085541e+02 -9.06921005e+01 -7.10563354e+01 -7.63721619e+01 -7.50617828e+01 -6.22380676e+01 -7.00657806e+01 -9.78952866e+01 -1.29120972e+02 -1.22454872e+02 -9.49488449e+01 -5.53428574e+01 -3.77496109e+01 -4.62774849e+01 -7.45970688e+01 -9.77061844e+01 -9.96798553e+01 -1.07401466e+02 -1.22194916e+02 -1.14324577e+02 -8.30193176e+01 -4.90916290e+01 -6.59349899e+01 -1.08519875e+02 -1.34765259e+02 -1.06740021e+02 -5.79264221e+01 -4.32234306e+01 -6.35929298e+01 -9.02801056e+01 -7.70583725e+01 -5.70503349e+01 -6.27514534e+01 -8.83957443e+01 -9.49546280e+01 -6.89890518e+01 -3.20130463e+01 -2.42246704e+01 -4.16205635e+01 -6.41369400e+01 -6.31343269e+01 -5.32722702e+01 -5.59351959e+01 -7.26214981e+01 -5.79009056e+01 -3.91441994e+01 -3.27017212e+01 -3.91638145e+01 -5.82216072e+01 -6.50418396e+01 -6.10544930e+01 -6.07346992e+01 -5.97675629e+01 -7.70462799e+01 -6.10896645e+01 -3.69599609e+01 -2.48966217e+01 -3.76736565e+01 -9.01252823e+01 -1.17340439e+02 -1.09674278e+02 -5.25065689e+01 -1.89598618e+01 -1.57637949e+01 -3.97391663e+01 -5.66050148e+01 -4.14295921e+01 -4.62288666e+01 -6.19789314e+01 -7.17958679e+01 -5.17188225e+01 -3.78367577e+01 -6.85098190e+01 -1.04353958e+02 -9.69606705e+01 -7.51749878e+01 -6.40427551e+01 -7.50996552e+01 -9.76186676e+01 -7.05583572e+01 -5.07957878e+01 -3.44399948e+01 -5.05880928e+01 -8.02896347e+01 -9.17231064e+01 -9.65317688e+01 -6.60040359e+01 -5.57611961e+01 -5.04448776e+01 -7.80160065e+01 -7.64228439e+01 -7.48973465e+01 -7.95977707e+01 -9.80428467e+01 -1.06845459e+02 -7.06766968e+01 -5.05129051e+01 -4.84206238e+01 -7.74763565e+01 -6.61173401e+01 -5.50365372e+01 -3.93885193e+01 -3.54383469e+01 -3.76119957e+01 -3.86415367e+01 -6.72774734e+01 -8.27844849e+01 -8.77848282e+01 -8.15340500e+01 -7.00394897e+01 -5.71713753e+01 -2.53753548e+01 -9.25494957e+00 -2.07660370e+01 -7.06926498e+01 -8.17609558e+01 -7.24742661e+01 -5.37768745e+01 -5.38693466e+01 -3.71258812e+01 3.05044866e+00 2.16352558e+01 -5.65282106e-01 -4.95381050e+01 -6.60759506e+01 -4.85239449e+01 -2.38946381e+01 -1.74948578e+01 -3.72526398e+01 -3.63269997e+01 -4.13804169e+01 -1.74920940e+01 -2.84201121e+00 -2.35158587e+00 -2.55758648e+01 -4.04076385e+01 -1.51402655e+01 1.14200191e+01 -3.64678478e+00 -3.81294250e+01 -3.10621929e+01 -6.12037516e+00 -5.14714479e+00 -2.64933052e+01 -2.78996754e+01 5.64252377e+00 1.92729244e+01 6.45614004e+00 -3.19150963e+01 -2.90518265e+01 -1.77065926e+01 8.13150823e-01 -1.07039995e+01 -2.71506691e+01 -1.97030354e+01 -2.15910702e+01 4.08425760e+00 8.08591938e+00 1.15593605e+01 -6.10704231e+00 -1.36180525e+01 -5.23913920e-01 1.47732334e+01 4.17005634e+00 -2.53210392e+01 -3.13371658e+01 -2.90250130e+01 -4.20941315e+01 -7.69136353e+01 -6.80447617e+01 -3.86662064e+01 -2.46325054e+01 -4.44231567e+01 -6.84610138e+01 -3.85413704e+01 -2.11784782e+01 -3.19203645e-01 1.45109053e+01 1.70808487e+01 -1.00598252e+00 -4.90750275e+01 -5.69953232e+01 -2.45090675e+01 1.17052908e+01 -1.00345068e+01 -5.47377663e+01 -8.28353119e+01 -5.01936455e+01 -2.21193352e+01 -2.61334648e+01 -4.15189934e+01 -6.36947403e+01 -8.81394730e+01 -1.24751694e+02 -1.13818039e+02 -7.61756210e+01 -6.21534615e+01 -8.17365494e+01 -1.00995430e+02 -5.75667839e+01 -3.24481926e+01 -1.65354919e+01 -2.27679939e+01 -3.01082172e+01 -5.23677063e+01 -1.10430588e+02 -1.22381828e+02 -7.75157471e+01 1.02918301e+01 3.01208439e+01 -3.59112663e+01 -9.70296402e+01 -1.01661255e+02 -5.70500908e+01 -3.35454521e+01 -4.67399521e+01 -8.01673203e+01 -1.00597664e+02 -7.37156143e+01 -1.79094296e+01 -3.97670865e+00 -3.32136459e+01 -7.29650269e+01 -1.11404648e+02 -1.09848221e+02 -8.94232330e+01 -3.26523247e+01 2.70119934e+01 4.72738991e+01 8.53026295e+00 -6.77024384e+01 -1.10323082e+02 -7.02929306e+01 -1.13289871e+01 -1.21335621e+01 -7.32891998e+01 -1.32400406e+02 -1.09533302e+02 -4.49621315e+01 1.10855398e+01 1.30648165e+01 -2.78636761e+01 -6.06842079e+01 -7.96942749e+01 -4.13684540e+01 -2.29127865e+01 -1.02389650e+01 -3.45521507e+01 -5.00818710e+01 -2.11255608e+01 7.29652691e+00 4.18884010e+01 4.26974449e+01 2.69786129e+01 -4.09459352e+00 -5.97356033e+01 -7.53875198e+01 -3.72700539e+01 4.57444267e+01 8.45621643e+01 5.36429214e+01 -2.21157646e+01 -6.81931686e+01 -5.30611267e+01 -2.16476040e+01 -1.87556438e+01 -4.22924423e+01 -5.54156189e+01 -6.25620461e+01 -2.43047237e+01 4.60224539e-01 3.12201424e+01 3.62919312e+01 2.08923569e+01 -8.42365399e-02 -3.46132622e+01 -2.81193504e+01 -2.83938026e+00 3.03781776e+01 3.13934746e+01 -6.62343562e-01 -4.03776054e+01 -2.80406284e+01 6.79023790e+00 2.98473988e+01 2.94460565e-01 -4.44668961e+01 -4.18635063e+01 -7.71692610e+00 4.16632538e+01 3.99327049e+01 2.97959477e-01 -3.07721596e+01 -5.51991348e+01 -1.36591578e+01 6.21245813e+00 2.82243042e+01 2.58456306e+01 2.90477676e+01 3.70436058e+01 1.74618664e+01 2.67519608e+01 4.60599937e+01 4.41458778e+01 1.26715298e+01 -4.22115593e+01 -5.62703171e+01 -2.64048901e+01 4.43620796e+01 1.01625740e+02 9.44195633e+01 2.91820698e+01 -3.82845306e+01 -6.01418037e+01 -1.41715460e+01 3.88326302e+01 5.13427582e+01 1.19030399e+01 -3.03871117e+01 -1.47499228e+01 2.28908558e+01 5.94322205e+01 6.55414047e+01 5.12147179e+01 1.98802147e+01 -1.17792120e+01 -6.37223005e+00 2.88045845e+01 7.52502289e+01 8.34708786e+01 4.74290161e+01 4.45381498e+00 1.33463907e+00 4.06549225e+01 6.78503494e+01 5.92260323e+01 3.41853714e+01 2.36948776e+01 1.53154469e+01 2.84030113e+01 3.82828751e+01 2.78489304e+01 2.18557034e+01 6.58650017e+00 2.99036884e+01 4.92791786e+01 7.58659286e+01 9.37595596e+01 7.07089539e+01 5.26053734e+01 1.54000587e+01 2.68996549e+00 1.93460674e+01 5.44151649e+01 6.48551865e+01 3.01813641e+01 -8.18297958e+00 -4.91551256e+00 1.72379036e+01 5.84933052e+01 6.91375580e+01 5.34506798e+01 2.94108810e+01 2.10734196e+01 5.37810059e+01 8.44682541e+01 1.13799927e+02 1.09856171e+02 7.05713654e+01 7.15313263e+01 8.61082535e+01 1.22518204e+02 1.26115982e+02 1.13199425e+02 8.72226715e+01 3.83331223e+01 1.77032413e+01 2.81667786e+01 7.06780396e+01 8.71200180e+01 5.77219696e+01 2.17320766e+01 2.38512840e+01 6.66984634e+01 9.82612457e+01 8.88550034e+01 4.64238319e+01 7.69075918e+00 3.55000520e+00 3.96376190e+01 7.97532120e+01 9.04762421e+01 9.10719147e+01 7.98482437e+01 6.65797119e+01 4.05904846e+01 3.87914276e+01 5.16163635e+01 6.01295586e+01 4.45288849e+01 7.82014418e+00 -1.21616583e+01 1.78635731e+01 6.57114029e+01 8.80911102e+01 6.11051407e+01 1.59532890e+01 6.85120630e+00 3.47012863e+01 7.98941650e+01 8.88047791e+01 6.17022934e+01 4.62692070e+01 3.90979118e+01 6.41769485e+01 7.51944199e+01 7.32273483e+01 6.40725174e+01 3.86559677e+01 4.55823975e+01 5.10837097e+01 9.34377594e+01 1.30657181e+02 1.50107666e+02 1.38161026e+02 9.71683197e+01 5.91391335e+01 4.64756546e+01 9.51076965e+01 1.97798660e+02 1.80999817e+02 3.88376770e+01 8.44831238e+02 1.52336487e+03 3.10982513e+02 3.47845886e+02 4.73280548e+02 2.53022568e+02 4.20615820e+03 1.25005635e+04 46472784. -264798400. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -581454912. 7.36337402e+03 2.59627832e+03 -6.99805527e+01 1.81375977e+03 1.40909448e+03 2.34261337e+02 1.28888962e+02 8.38021622e+01 9.31762314e+01 1.04771393e+02 1.01574944e+02 8.74869080e+01 4.92183037e+01 4.93296013e+01 6.79220963e+01 9.94790573e+01 9.63794785e+01 6.70946884e+01 4.10761261e+01 3.55026398e+01 5.81529732e+01 9.76808701e+01 1.05410629e+02 7.79786301e+01 4.52264099e+01 4.40640640e+01 7.03037262e+01 7.31670990e+01 5.75393105e+01 5.39228020e+01 7.02346573e+01 8.96921234e+01 8.83155823e+01 9.25411301e+01 1.00465912e+02 1.02812798e+02 8.20093765e+01 4.82124405e+01 4.31956100e+01 6.63479538e+01 9.00186462e+01 9.14959564e+01 6.86801529e+01 4.13729935e+01 4.40803604e+01 7.89446030e+01 1.21821724e+02 1.21107300e+02 8.17902603e+01 6.03136940e+01 5.68595886e+01 7.90705948e+01 8.85945435e+01 9.40255814e+01 9.55360794e+01 9.01558228e+01 7.70267410e+01 5.72690849e+01 6.45800018e+01 8.57469635e+01 9.03896255e+01 7.45962372e+01 4.96974716e+01 5.18950119e+01 6.52389145e+01 8.49376602e+01 9.43179016e+01 7.47478867e+01 5.05996780e+01 2.93831234e+01 4.14631310e+01 6.91549835e+01 7.95052338e+01 6.18873749e+01 4.87736893e+01 5.24084511e+01 7.94824142e+01 8.56545563e+01 7.92770767e+01 6.63928757e+01 6.93515854e+01 6.86409760e+01 6.17403374e+01 6.94235611e+01 8.84889221e+01 9.79924164e+01 8.09695969e+01 5.29421272e+01 4.68880730e+01 5.57162018e+01 7.51830521e+01 8.87956009e+01 9.08084335e+01 7.71049500e+01 6.58577499e+01 6.85106583e+01 9.14657364e+01 1.01386772e+02 8.48644409e+01 6.82887650e+01 6.89974365e+01 9.28899612e+01 1.05934044e+02 1.02235687e+02 9.86167908e+01 9.31195908e+01 8.70036087e+01 6.87157364e+01 7.02182159e+01 8.50405045e+01 9.82821198e+01 9.71635208e+01 8.37466965e+01 8.13620224e+01 8.99513397e+01 9.72773895e+01 1.04542297e+02 1.00649452e+02 8.83992157e+01 7.54983368e+01 7.39067078e+01 9.32547989e+01 1.03116554e+02 9.49353867e+01 8.76765289e+01 8.71358261e+01 9.73025665e+01 9.61553726e+01 9.49790955e+01 9.94095840e+01 1.01577950e+02 9.80728836e+01 8.23977432e+01 8.27001495e+01 9.44769211e+01 1.04359322e+02 1.02801544e+02 9.24789352e+01 9.29155350e+01 1.02208252e+02 1.06583496e+02 1.12342697e+02 1.05207001e+02 9.59084244e+01 8.63065186e+01 8.78750839e+01 9.74463196e+01 9.95255890e+01 9.51957932e+01 9.48586655e+01 9.73941879e+01 1.04807877e+02 1.09589333e+02 1.12721527e+02 1.14115486e+02 1.08411781e+02 1.01975769e+02 9.10436401e+01 8.69868011e+01 8.92382278e+01 9.50076523e+01 9.58363495e+01 8.83107147e+01 8.21902542e+01 8.62648010e+01 9.80132751e+01 1.06083771e+02 1.06315536e+02 9.62725906e+01 9.11074905e+01 9.14508362e+01 9.75265045e+01 9.88047867e+01 9.53900833e+01 9.63452911e+01 9.60951157e+01 9.55262604e+01 9.52514267e+01 9.98160629e+01 1.05923363e+02 1.06730110e+02 1.04409981e+02 1.00614937e+02 9.69814758e+01 9.65760803e+01 9.79794159e+01 9.84947891e+01 9.46746140e+01 9.09369583e+01 9.28074341e+01 9.84507828e+01 1.03463615e+02 1.04108292e+02 9.99952011e+01 9.90224075e+01 9.86756210e+01 1.02291985e+02 1.01809708e+02 9.99403763e+01 9.69323349e+01 9.50013428e+01 9.47757874e+01 9.35392151e+01 9.51583328e+01 9.80547562e+01 1.00082802e+02 9.99496307e+01 9.80266190e+01 9.80068817e+01 9.94191895e+01 1.00928093e+02 1.02262955e+02 1.01239021e+02 9.92711945e+01 9.78576202e+01 9.85864792e+01 9.99729004e+01 1.00169395e+02 9.97903137e+01 9.96658020e+01 9.97419357e+01 9.98771896e+01 9.98820114e+01 9.97786102e+01 9.96788635e+01 9.97182312e+01 1.00022812e+02 1.00708984e+02 1.01081924e+02 1.00915749e+02 1.00411240e+02 1.00261078e+02 1.00402321e+02 9.98306427e+01 9.87938156e+01 9.83177414e+01 9.85985107e+01 9.99992142e+01 1.00508270e+02 1.00911690e+02 1.00354309e+02 9.91938019e+01 9.85585403e+01 9.88774872e+01 1.00192520e+02 1.00951187e+02 1.00282310e+02 9.95536423e+01 9.93438034e+01 9.99372177e+01 1.00555870e+02 9.99918365e+01 9.94863434e+01 9.87725449e+01 9.85260468e+01 9.85613251e+01 9.77886353e+01 9.80799408e+01 9.81365280e+01 9.92189865e+01 9.85533752e+01 9.76528244e+01 9.74003754e+01 9.80883255e+01 9.85531998e+01 9.78164368e+01 9.73839493e+01 9.67177963e+01 9.46134109e+01 9.50244293e+01 9.61997223e+01 9.79939880e+01 9.58543549e+01 9.55002747e+01 9.57074966e+01 9.58761292e+01 9.54002304e+01 9.46877136e+01 9.47897263e+01 9.45254745e+01 9.52790298e+01 9.61366196e+01 9.66272049e+01 9.51947556e+01 9.49480515e+01 9.31587372e+01 9.40426483e+01 9.42681656e+01 9.53277893e+01 9.36344147e+01 9.36366577e+01 9.31411591e+01 9.66387787e+01 9.95682144e+01 1.01660133e+02 9.91044769e+01 9.75746765e+01 9.53405380e+01 9.49958572e+01 9.41117249e+01 9.53548508e+01 9.66097565e+01 9.51582413e+01 9.52441025e+01 9.55067749e+01 9.49849014e+01 9.22399673e+01 9.09171524e+01 9.23597412e+01 9.37050781e+01 9.30257034e+01 9.34949722e+01 9.47346649e+01 9.70234222e+01 9.72093506e+01 9.69736862e+01 9.45438080e+01 9.27657776e+01 8.68428650e+01 8.38398209e+01 8.28628922e+01 8.68911972e+01 9.07876434e+01 9.26789627e+01 9.48693695e+01 9.38609314e+01 8.81649628e+01 8.21155014e+01 8.30628738e+01 8.87988052e+01 9.36312790e+01 9.40528030e+01 9.32522583e+01 9.52315521e+01 9.51584702e+01 9.45705795e+01 9.26349335e+01 9.42179031e+01 9.49843140e+01 9.36618576e+01 9.15843353e+01 9.34326553e+01 9.89721756e+01 1.06079712e+02 1.06264824e+02 1.01321205e+02 9.32420959e+01 9.37033691e+01 9.58029480e+01 9.37464752e+01 9.23191147e+01 9.07194290e+01 9.89753571e+01 1.03384972e+02 1.05306244e+02 9.71690063e+01 9.01720810e+01 8.49379044e+01 9.00410233e+01 1.02017784e+02 1.15456894e+02 1.07995827e+02 9.21790771e+01 8.24813080e+01 8.67122269e+01 9.36871948e+01 9.46364975e+01 9.92668381e+01 1.01320862e+02 9.82030258e+01 8.92885818e+01 8.24903183e+01 8.16486588e+01 8.50840225e+01 9.17640839e+01 1.00419594e+02 9.83357239e+01 9.26187897e+01 8.48431168e+01 8.26894989e+01 8.22662735e+01 8.14074707e+01 7.68145142e+01 7.42056732e+01 7.41544952e+01 8.02014999e+01 8.31582794e+01 8.12444382e+01 7.62567139e+01 7.67260590e+01 8.04663925e+01 8.03075180e+01 7.63660278e+01 8.30721664e+01 8.86397324e+01 8.64506226e+01 7.42524796e+01 6.98727570e+01 7.60754013e+01 8.05787888e+01 8.25417252e+01 8.69694901e+01 9.16477966e+01 9.20156326e+01 9.23850861e+01 8.95793915e+01 8.65634918e+01 7.98078384e+01 7.88919601e+01 8.35458832e+01 8.15608292e+01 7.74825439e+01 7.46624680e+01 7.57643204e+01 7.67610168e+01 8.50857162e+01 9.39267654e+01 9.45747833e+01 8.30446701e+01 7.25017319e+01 7.13775253e+01 7.15071869e+01 7.11342926e+01 7.30316162e+01 7.58026276e+01 7.33714294e+01 6.32600632e+01 5.42116241e+01 5.37473412e+01 5.98569260e+01 6.65547638e+01 6.78334122e+01 6.44157104e+01 6.41136246e+01 6.67513809e+01 6.77205734e+01 5.28186684e+01 3.69212265e+01 3.73335991e+01 5.71318779e+01 7.40993652e+01 7.43841782e+01 5.67150421e+01 1.34173985e+01 -4.97219810e+01 -1.27328110e+02 -1.44719772e+02 -6.69417496e+01 -8.37789490e+02 -1.39203503e+03 2.81688171e+02 2.70554108e+02 2.57490326e+02 2.70968170e+02 3.11656830e+02 3.01536621e+02 2.45698914e+02 8.30172119e+01 -7.89437408e+01 -4.30957764e+03 -2.76302461e+04 -353220768. 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. 0. 0. 0. 0. 0. 0. 0. 0. 92172128. 55503048. 34729552. -6.12898877e+03 -2.57863892e+03 -1.23962532e+02 -5.73759613e+01 3.08448830e+01 1.26170111e+01 9.47824001e+00 9.46557713e+00 2.36285572e+01 4.68214760e+01 4.28217812e+01 3.96291161e+01 3.65091286e+01 3.77061348e+01 2.85706005e+01 1.46580286e+01 2.53701611e+01 4.92057762e+01 5.51331635e+01 4.01240273e+01 2.36613598e+01 3.37070160e+01 3.35245056e+01 2.88434391e+01 1.82815380e+01 1.41653614e+01 1.37816315e+01 1.88349171e+01 3.13911705e+01 3.50672684e+01 3.56351357e+01 3.11944103e+01 4.63600731e+01 6.85207520e+01 7.39414368e+01 6.19654961e+01 4.74016190e+01 5.16659775e+01 5.72441597e+01 5.75428200e+01 6.19179878e+01 6.60312195e+01 6.93361511e+01 7.09867172e+01 7.14047852e+01 6.45947266e+01 6.14516678e+01 5.61500778e+01 6.31943016e+01 5.93221359e+01 5.61219254e+01 5.75595779e+01 6.14297333e+01 6.67073288e+01 6.68599167e+01 5.87747192e+01 4.37243729e+01 2.38327045e+01 1.29494781e+01 1.76433201e+01 2.97507648e+01 3.89655266e+01 2.73471432e+01 1.43806944e+01 1.98156071e+01 3.77678833e+01 5.51638107e+01 5.56226425e+01 5.64429855e+01 6.61051407e+01 8.24252548e+01 6.79055786e+01 4.29879265e+01 2.16743908e+01 2.86898766e+01 4.00380783e+01 3.56317635e+01 3.58913231e+01 3.47043419e+01 3.79709320e+01 3.78321800e+01 3.86683922e+01 2.85377769e+01 2.55210552e+01 2.17774391e+01 2.86642265e+01 2.71266708e+01 8.67993927e+00 -1.11790934e+01 -7.04264593e+00 9.09820843e+00 2.74792614e+01 2.04897099e+01 1.19677401e+01 -1.58873987e+00 -5.40123606e+00 7.67199469e+00 2.90834885e+01 3.37747879e+01 2.47404823e+01 1.75666296e+00 -8.98031414e-01 1.77275467e+00 1.30155153e+01 2.33587685e+01 1.83895760e+01 2.47680035e+01 2.13019066e+01 2.72734356e+01 1.98072701e+01 1.95139980e+01 2.15621490e+01 1.17107821e+01 3.07876557e-01 1.17370200e+00 1.14851818e+01 2.56685047e+01 2.59314060e+01 2.97497177e+01 3.10170269e+01 3.52848663e+01 3.77192612e+01 3.37082710e+01 9.69915867e+00 -1.69749851e+01 -2.04808674e+01 -4.58064842e+00 1.64666729e+01 2.62216339e+01 3.53132477e+01 3.40531082e+01 2.34843349e+01 1.74484959e+01 2.54073792e+01 2.44375725e+01 2.28238544e+01 1.95931530e+01 1.87294369e+01 1.61824913e+01 1.34527731e+01 1.10616169e+01 1.40109844e+01 1.09798040e+01 6.96524143e+00 3.02750683e+00 2.71012354e+00 -1.11030281e-01 -2.61399174e+00 -3.67324877e+00 2.39598036e+00 7.06425047e+00 1.23155613e+01 1.18479147e+01 1.22772598e+01 1.61008396e+01 1.87447720e+01 1.09302702e+01 -2.17240524e+01 -3.97149391e+01 -4.11475258e+01 -2.95238590e+01 -1.70869007e+01 -1.68344326e+01 -9.70422268e+00 -6.92429638e+00 -8.94147682e+00 -1.14671307e+01 -1.15401869e+01 -8.20928574e+00 -5.83946705e+00 -1.31048691e+00 2.08547764e+01 3.68772621e+01 4.95413170e+01 4.44858322e+01 2.83532104e+01 7.69904375e+00 -1.27042122e+01 -1.11466389e+01 -8.69522381e+00 -4.17219687e+00 -5.16538239e+00 -1.90752423e+00 -4.48179674e+00 -4.78629112e+00 -1.91892779e+00 -5.59949303e+00 -7.86404276e+00 -8.71493435e+00 -5.08847189e+00 -3.20038748e+00 -1.41489191e+01 -1.92913895e+01 -2.42815361e+01 -2.13476696e+01 -1.24481020e+01 9.82992935e+00 3.50659294e+01 4.37567978e+01 4.08163986e+01 3.25969620e+01 3.75931168e+01 2.20438538e+01 2.95890141e+00 -2.06795692e+01 -2.45933952e+01 -2.43081989e+01 -1.99001350e+01 -1.80610619e+01 -1.94446812e+01 -2.73859043e+01 -2.81775303e+01 -2.66788540e+01 -1.99951267e+01 -1.92649021e+01 -1.90240917e+01 -3.79680862e+01 -5.83435249e+01 -5.33408089e+01 -3.55477524e+01 -1.54032984e+01 -7.13252020e+00 1.32348740e+00 1.81431828e+01 2.97300377e+01 2.25441208e+01 1.11751890e+01 -1.34525738e+01 -7.74770737e+00 -1.38382626e+00 6.55922794e+00 4.54659653e+00 -4.07967138e+00 -1.95422029e+00 -1.90695012e+00 -2.66159797e+00 -1.23068590e+01 -1.96184120e+01 -1.70071926e+01 -1.46223038e-01 1.98850899e+01 3.60661125e+01 4.32530937e+01 4.52292967e+00 -3.37835693e+01 -5.46323318e+01 -3.77259407e+01 -1.71526794e+01 -1.97924004e+01 -1.66778889e+01 -2.07119522e+01 -1.84869061e+01 -2.29905262e+01 -2.71463814e+01 -3.17163429e+01 -2.81806545e+01 -2.73531208e+01 -4.02793427e+01 -6.43780518e+01 -6.99213333e+01 -5.94192429e+01 -4.28980484e+01 -3.11612167e+01 -2.00880756e+01 -1.96871033e+01 -3.13020420e+01 -3.56705742e+01 -2.50156441e+01 -2.45341320e+01 -3.28851509e+01 -4.48219604e+01 -4.54916077e+01 -4.47439346e+01 -4.40596619e+01 -4.03072357e+01 -4.19649925e+01 -3.62234306e+01 -3.80874405e+01 -3.93876266e+01 -5.00698166e+01 -5.33947029e+01 -5.20038414e+01 -3.36114845e+01 -1.10946369e+01 -1.29930124e+01 -2.92022934e+01 -5.15048866e+01 -4.48993530e+01 -3.90796738e+01 -3.22281952e+01 -3.05489159e+01 -2.83399849e+01 -2.95937347e+01 -2.06336861e+01 -1.56983938e+01 -2.02881336e+01 -3.83817368e+01 -5.39691048e+01 -5.40779572e+01 -5.09827156e+01 -6.06374626e+01 -7.52312469e+01 -8.05631638e+01 -7.62839508e+01 -6.23646049e+01 -6.30648994e+01 -6.11833000e+01 -5.89900017e+01 -5.34426651e+01 -5.11540070e+01 -5.56128044e+01 -6.60031052e+01 -6.37026939e+01 -6.00871582e+01 -5.55108681e+01 -5.85463486e+01 -5.72898407e+01 -5.41538239e+01 -4.15766373e+01 -2.88601418e+01 -3.06302166e+01 -3.97973976e+01 -4.97408295e+01 -4.87990494e+01 -5.50528030e+01 -6.27707901e+01 -5.95262527e+01 -3.57777443e+01 -1.79256248e+01 -1.69333038e+01 -3.65615349e+01 -5.04759674e+01 -5.04737015e+01 -4.86837502e+01 -4.93978577e+01 -5.20032883e+01 -3.86035309e+01 -2.13319836e+01 -1.77857857e+01 -3.21783981e+01 -5.26784668e+01 -5.09030495e+01 -5.09722595e+01 -5.12513733e+01 -5.41521912e+01 -5.27267570e+01 -4.47386742e+01 -3.85270729e+01 -3.83416901e+01 -4.59938011e+01 -5.31157074e+01 -4.93039322e+01 -3.10847454e+01 -8.66795349e+00 -7.70012474e+00 -2.53333931e+01 -4.44615440e+01 -5.14473114e+01 -5.87697830e+01 -5.96585541e+01 -5.28628922e+01 -3.35711975e+01 -1.98453789e+01 -4.70544577e+00 -1.96080494e+00 -1.96661453e+01 -3.67596359e+01 -5.71300049e+01 -4.35352402e+01 -3.14519138e+01 -4.63117332e+01 -7.68452454e+01 -9.30934372e+01 -7.70927353e+01 -6.20291290e+01 -6.43379898e+01 -6.76226349e+01 -6.81073837e+01 -7.09422379e+01 -7.34399567e+01 -7.66346664e+01 -7.75912628e+01 -7.94388428e+01 -8.01160126e+01 -7.85025330e+01 -8.16560516e+01 -8.03748398e+01 -8.14663925e+01 -7.06210251e+01 -5.80913391e+01 -5.79132729e+01 -6.98472595e+01 -8.83796692e+01 -7.55955582e+01 -5.58565712e+01 -6.75060349e+01 -9.62374115e+01 -9.62534485e+01 -6.10691414e+01 -4.05185661e+01 -5.42242088e+01 -7.30980835e+01 -6.45939178e+01 -4.88697319e+01 -4.42121773e+01 -5.39453049e+01 -6.86776276e+01 -6.93011322e+01 -6.67318726e+01 -6.70845566e+01 -6.70891647e+01 -7.91919479e+01 -8.98288498e+01 -7.71536255e+01 -5.22396240e+01 -4.10137138e+01 -5.18451080e+01 -6.28015480e+01 -5.06625938e+01 -4.15619049e+01 -3.93939857e+01 -5.06747284e+01 -6.35279198e+01 -6.25047836e+01 -6.17503281e+01 -5.99776649e+01 -6.48215942e+01 -5.98077087e+01 -4.93416138e+01 -4.60997963e+01 -4.87105789e+01 -6.32554283e+01 -7.14560394e+01 -7.82371521e+01 -7.99189301e+01 -7.76819153e+01 -9.35717316e+01 -1.12983727e+02 -1.09238434e+02 -8.49151840e+01 -6.35260811e+01 -7.06333923e+01 -8.08647461e+01 -7.38481293e+01 -5.90075531e+01 -5.87152672e+01 -6.79576416e+01 -7.95891876e+01 -8.26105118e+01 -8.40041809e+01 -8.57045441e+01 -8.32579117e+01 -8.15765152e+01 -7.91393585e+01 -7.41290970e+01 -7.22473907e+01 -7.55224609e+01 -8.27728119e+01 -8.66326370e+01 -8.88653030e+01 -8.83001251e+01 -9.76556549e+01 -1.06404579e+02 -9.69296494e+01 -7.51145477e+01 -6.40233994e+01 -7.61293640e+01 -8.83237000e+01 -9.51302795e+01 -9.80926514e+01 -9.97800446e+01 -9.74766541e+01 -9.49518890e+01 -9.76982727e+01 -9.60505447e+01 -9.73402023e+01 -9.44751205e+01 -9.67485046e+01 -9.85102539e+01 -1.00594772e+02 -9.72678528e+01 -9.35542450e+01 -9.49042511e+01 -9.97545853e+01 -1.01792572e+02 -9.63633575e+01 -9.12650986e+01 -8.90462799e+01 -8.43963089e+01 -7.62653656e+01 -7.50028381e+01 -8.00157242e+01 -8.09262009e+01 -6.49296951e+01 -5.54821587e+01 -6.20359268e+01 -7.33262558e+01 -7.09789734e+01 -6.21475945e+01 -6.15280914e+01 -7.20821228e+01 -7.90721893e+01 -8.16423721e+01 -8.11663132e+01 -8.07536392e+01 -7.98177338e+01 -8.06718216e+01 -8.45889587e+01 -8.02069626e+01 -7.27115555e+01 -6.84260788e+01 -7.55428314e+01 -8.41171951e+01 -8.44757538e+01 -7.86466064e+01 -8.55174942e+01 -9.64632034e+01 -1.02486519e+02 -9.74086380e+01 -9.12102356e+01 -9.45250015e+01 -9.48381271e+01 -9.44773865e+01 -9.45513535e+01 -9.54121552e+01 -9.47096558e+01 -9.21079254e+01 -9.35980759e+01 -9.60996475e+01 -9.85846100e+01 -9.77899017e+01 -9.55880051e+01 -9.51234741e+01 -8.99534073e+01 -8.54946136e+01 -8.62549133e+01 -9.27556076e+01 -1.00648514e+02 -1.01685486e+02 -1.01684319e+02 -1.05177948e+02 -1.10750183e+02 -1.11113678e+02 -1.06855484e+02 -1.00245216e+02 -9.90763245e+01 -9.87902985e+01 -9.29715271e+01 -8.63462830e+01 -8.47428665e+01 -9.06395874e+01 -9.52961884e+01 -9.57642288e+01 -9.69433899e+01 -9.91537094e+01 -9.84641037e+01 -1.00596115e+02 -1.04857681e+02 -1.03238373e+02 -9.69929733e+01 -9.21069260e+01 -9.37536240e+01 -9.29844894e+01 -8.62104950e+01 -8.22319107e+01 -8.53869858e+01 -9.28900757e+01 -9.46132355e+01 -9.21787643e+01 -9.19288025e+01 -9.52981262e+01 -9.97156219e+01 -9.88937683e+01 -9.65617828e+01 -9.61351700e+01 -9.77276840e+01 -1.00632355e+02 -1.02212318e+02 -1.03101639e+02 -1.03410530e+02 -1.02106224e+02 -1.02768669e+02 -1.02379364e+02 -1.00477783e+02 -9.78191223e+01 -9.73254013e+01 -9.90911942e+01 -1.00504997e+02 -9.96394119e+01 -1.03604843e+02 -1.19263885e+02 -1.22516037e+02 -1.32837708e+02 -2.92733795e+02 -4.42322601e+02 -4.29718964e+02 -4.29814392e+02 -1.66540203e+01 -8.37271500e+00 -7.03445663e+01 -6.88856812e+01 -2.07908279e+02 -3.29049652e+02 -4.19949554e+02 -4.25139618e+02 -4.49646362e+02 -8.16741211e+02 -4.68411650e+06 0. 0. 0. 0. 0. 0. 0. 0. -602414912. -58188716. 37697876. 28972150. -78539936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.39530163e+09 -56100592. -2.50368384e+03 -1.35071228e+03 -1.27881250e+03 -1.25158362e+03 -1.53402267e+02 -9.87318115e+01 -1.53091629e+02 -1.37602570e+02 -1.49409515e+02 -1.46647049e+02 -1.45772415e+02 -1.47996628e+02 -1.49354065e+02 -1.48010010e+02 -1.46213928e+02 -1.47511703e+02 -1.51017868e+02 -1.52461792e+02 -1.48036636e+02 -1.41521118e+02 -1.41933395e+02 -1.49098022e+02 -1.57993454e+02 -1.62030014e+02 -1.58109924e+02 -1.58021545e+02 -1.59818924e+02 -1.58275757e+02 -1.54149597e+02 -1.51765762e+02 -1.57283875e+02 -1.71015213e+02 -1.72001877e+02 -1.62692307e+02 -1.47972412e+02 -1.43074142e+02 -1.44353958e+02 -1.43262970e+02 -1.39352127e+02 -1.37705231e+02 -1.44835403e+02 -1.62023087e+02 -1.71357407e+02 -1.65466370e+02 -1.52743423e+02 -1.45829269e+02 -1.45431488e+02 -1.48947800e+02 -1.54081329e+02 -1.52396347e+02 -1.55462433e+02 -1.58096191e+02 -1.53296082e+02 -1.38356201e+02 -1.23981911e+02 -1.30207016e+02 -1.55166199e+02 -1.65776291e+02 -1.56881485e+02 -1.38347763e+02 -1.39824829e+02 -1.53405716e+02 -1.55561020e+02 -1.43181503e+02 -1.29195450e+02 -1.33291885e+02 -1.54778885e+02 -1.68869080e+02 -1.61893204e+02 -1.45738815e+02 -1.42335815e+02 -1.44285858e+02 -1.45636002e+02 -1.38988434e+02 -1.32428635e+02 -1.38183167e+02 -1.41297134e+02 -1.36408600e+02 -1.23255455e+02 -1.21430389e+02 -1.28460007e+02 -1.41511353e+02 -1.51510696e+02 -1.55002640e+02 -1.44182404e+02 -1.38435898e+02 -1.40285095e+02 -1.27282623e+02 -1.06921944e+02 -9.84169846e+01 -1.21119095e+02 -1.54209259e+02 -1.69167908e+02 -1.54828110e+02 -1.25405609e+02 -1.00232407e+02 -9.20461273e+01 -9.84096451e+01 -1.04934395e+02 -1.04146599e+02 -1.13236305e+02 -1.36149948e+02 -1.51672379e+02 -1.43244446e+02 -1.23109749e+02 -1.16382957e+02 -1.24864708e+02 -1.41428665e+02 -1.48068054e+02 -1.32699326e+02 -1.21361809e+02 -1.22440086e+02 -1.26161636e+02 -1.12361397e+02 -9.03663406e+01 -9.00983810e+01 -1.12826370e+02 -1.34547409e+02 -1.29235016e+02 -1.07636749e+02 -9.18680115e+01 -9.38846893e+01 -1.11326996e+02 -1.30923065e+02 -1.40374756e+02 -1.28252487e+02 -1.28053894e+02 -1.39927551e+02 -1.40088974e+02 -1.19409073e+02 -1.00432472e+02 -1.02777496e+02 -1.25128616e+02 -1.37124619e+02 -1.25139496e+02 -1.10888748e+02 -1.02636658e+02 -1.13567131e+02 -1.09232086e+02 -8.91005020e+01 -8.11367111e+01 -1.07289589e+02 -1.55971893e+02 -1.79940475e+02 -1.63117523e+02 -1.34533432e+02 -1.27177490e+02 -1.30089493e+02 -1.38243988e+02 -1.35678360e+02 -1.37436752e+02 -1.52085876e+02 -1.72799881e+02 -1.77685928e+02 -1.52447586e+02 -1.05608734e+02 -8.87242432e+01 -1.13566147e+02 -1.39945129e+02 -1.35281479e+02 -1.21119469e+02 -1.36076675e+02 -1.69849274e+02 -1.64116196e+02 -1.33855591e+02 -1.06167931e+02 -1.35062149e+02 -1.90904358e+02 -2.19371719e+02 -1.89827484e+02 -1.39671448e+02 -1.16998436e+02 -1.20363197e+02 -1.14568520e+02 -1.05062538e+02 -1.16465240e+02 -1.51118423e+02 -1.91290649e+02 -1.65586365e+02 -1.25693710e+02 -8.85279541e+01 -1.03005066e+02 -1.23015099e+02 -1.39106522e+02 -1.46076157e+02 -1.44345367e+02 -1.58805817e+02 -1.74597351e+02 -1.62391891e+02 -1.23156334e+02 -9.16710281e+01 -1.11793205e+02 -1.58294342e+02 -1.88762497e+02 -1.61939514e+02 -1.15729507e+02 -9.32419815e+01 -9.89558258e+01 -9.87189636e+01 -6.82596588e+01 -5.59400635e+01 -8.71887589e+01 -1.33755142e+02 -1.35585068e+02 -1.04800079e+02 -6.90176468e+01 -6.47973785e+01 -7.15171280e+01 -8.92078094e+01 -1.05303429e+02 -1.08182777e+02 -1.20634178e+02 -1.38316284e+02 -1.21563339e+02 -8.69797821e+01 -7.13226395e+01 -7.74639587e+01 -1.07754684e+02 -1.10469978e+02 -9.74447098e+01 -8.73378906e+01 -8.99236374e+01 -1.11726677e+02 -9.41971664e+01 -7.10913467e+01 -5.62294197e+01 -5.82972794e+01 -9.19630508e+01 -1.08102875e+02 -8.80594711e+01 -4.31436386e+01 -3.95299683e+01 -7.16938858e+01 -1.08223526e+02 -1.09902031e+02 -9.08714600e+01 -9.36268539e+01 -1.08552246e+02 -1.08804482e+02 -7.40535507e+01 -5.30910568e+01 -8.04970703e+01 -1.07415314e+02 -8.75099335e+01 -6.31479378e+01 -6.87352753e+01 -9.22830658e+01 -1.14166550e+02 -9.85035400e+01 -1.06998024e+02 -1.13820656e+02 -1.22296471e+02 -1.28145264e+02 -1.38201843e+02 -1.42755814e+02 -1.02358101e+02 -8.15004959e+01 -6.95419846e+01 -1.09824593e+02 -1.02928444e+02 -1.03503975e+02 -1.18008072e+02 -1.44017792e+02 -1.53341782e+02 -9.87528076e+01 -6.25524635e+01 -5.84537392e+01 -1.09383514e+02 -1.21621391e+02 -1.11685371e+02 -9.58160553e+01 -9.63241425e+01 -1.29278320e+02 -1.06778008e+02 -8.55956421e+01 -3.99783287e+01 -2.76125526e+01 -3.23868294e+01 -6.04478188e+01 -9.11744843e+01 -7.59998703e+01 -4.61081047e+01 -2.34093952e+01 -3.80088043e+01 -2.06703300e+01 -1.56670704e+01 -4.48761520e+01 -9.27571945e+01 -9.97080536e+01 -4.54353447e+01 -2.30956974e+01 -5.06788445e+01 -9.80486450e+01 -8.21850662e+01 -5.19880104e+01 -4.14453354e+01 -5.33383904e+01 -7.64940567e+01 -7.34738235e+01 -8.35982285e+01 -5.59686737e+01 -4.21305695e+01 -3.90443611e+01 -5.38340111e+01 -6.34015846e+01 -4.52687416e+01 -3.04600220e+01 -2.43982849e+01 -1.22440739e+01 3.01432476e+01 5.60109291e+01 4.93557816e+01 2.49016476e+01 2.47450047e+01 5.29454193e+01 6.74903793e+01 3.85386162e+01 -1.52848959e+01 -2.58554993e+01 -1.40600672e+01 -1.39613066e+01 -3.64578247e+01 -7.55472260e+01 -8.10837479e+01 -7.98540726e+01 -4.74536667e+01 -2.79235210e+01 -2.00827160e+01 -1.96778545e+01 -1.59571123e+01 -3.10692334e+00 1.24381361e+01 1.33919697e+01 7.86620998e+00 3.35408249e+01 6.50495300e+01 5.28403320e+01 7.15228081e+00 -1.59746780e+01 -1.58668594e+01 -3.87394180e+01 -6.20566826e+01 -7.80348740e+01 -3.42762337e+01 -3.05668468e+01 -2.32015553e+01 -1.69558525e+01 -1.56550913e+01 -3.14397984e+01 -7.99897079e+01 -8.43759995e+01 -4.06149673e+01 1.17349377e+01 1.25090075e+01 -2.13497696e+01 -5.74769173e+01 -4.79534683e+01 -2.24387417e+01 1.29655571e+01 1.91055927e+01 1.56257057e+00 -2.54879551e+01 -7.60775299e+01 -9.36462784e+01 -1.00858063e+02 -9.65001144e+01 -9.21111908e+01 -9.28120728e+01 -5.04619217e+01 -5.19318428e+01 -4.48537331e+01 -4.59731445e+01 -4.66244202e+01 -6.99169083e+01 -1.46930984e+02 -1.67630920e+02 -1.22293869e+02 -1.37969980e+01 4.52944679e+01 -1.35469646e+01 -9.59892807e+01 -1.00729958e+02 -1.07183018e+01 8.67874527e+01 6.58146744e+01 -6.70151186e+00 -6.49890442e+01 -6.62039490e+01 -1.96312943e+01 -2.68060055e+01 -5.51298790e+01 -8.34095764e+01 -8.21829376e+01 -3.33668785e+01 -4.08162193e+01 -7.08372955e+01 -9.81558456e+01 -8.91014252e+01 -4.56912460e+01 -5.90170250e+01 -6.14348030e+01 -1.13528624e+01 5.64236412e+01 5.32770271e+01 -6.54268570e+01 -1.40277740e+02 -1.18575294e+02 -2.77179813e+01 2.25164223e+01 9.22529411e+00 -3.30523720e+01 -5.85218697e+01 -7.32584076e+01 -3.07052937e+01 -2.84586678e+01 -3.11804314e+01 -5.08165398e+01 -6.54123077e+01 -2.40794449e+01 -7.83474982e-01 5.38012276e+01 4.43703728e+01 1.54314804e+01 -2.84778709e+01 -9.32927933e+01 -1.12937706e+02 -6.92858963e+01 3.85789604e+01 1.01931145e+02 5.76667862e+01 -4.35330505e+01 -8.47264786e+01 -3.20117378e+00 9.93080750e+01 1.00643173e+02 1.14465942e+01 -3.66872406e+01 -3.17512722e+01 1.37152729e+01 1.15916815e+01 -6.83784580e+00 -3.78799210e+01 -6.01553574e+01 -5.94664116e+01 -8.91515961e+01 -9.66533966e+01 -5.55456963e+01 7.61907578e+00 4.39853783e+01 -5.78676891e+00 -5.40809288e+01 -4.48735237e+01 2.30466385e+01 9.14404907e+01 6.62252655e+01 -3.53285646e+00 -2.84777088e+01 2.85478020e+00 6.15844269e+01 4.86094017e+01 1.92383230e+00 -4.32422981e+01 -7.29889145e+01 -4.01705132e+01 -4.35070953e+01 -1.45839062e+01 -1.39305544e+01 -1.36893167e+01 -2.56627197e+01 -5.81560860e+01 -2.81175938e+01 1.13336477e+01 6.00715599e+01 4.23905907e+01 -2.55318737e+01 -7.75840683e+01 -5.41541939e+01 2.23066177e+01 7.98013916e+01 8.07579422e+01 3.28707466e+01 8.98530579e+00 3.41277003e+00 3.14646263e+01 1.73836365e+01 -4.64372587e+00 -3.15230904e+01 -7.03616257e+01 -6.97746353e+01 -2.68914471e+01 3.76925926e+01 5.36102715e+01 3.67800789e+01 7.12297630e+00 -3.47572250e+01 -5.87194939e+01 -1.57759399e+01 6.94185410e+01 1.07322266e+02 5.84587440e+01 -1.22149076e+01 -1.90345592e+01 5.78750000e+01 1.40866089e+02 1.33055923e+02 4.62108040e+01 -4.79881477e+01 -8.22391739e+01 -3.23878517e+01 1.69956169e+01 2.72200623e+01 1.12962408e+01 -5.34996605e+00 2.19165020e+01 1.02663050e+01 2.07564507e+01 4.70424500e+01 5.97576561e+01 6.33212967e+01 1.54648113e+01 1.74810677e+01 6.31356964e+01 1.26630394e+02 1.23100296e+02 2.49898586e+01 -4.28725090e+01 -2.20727825e+01 6.09852066e+01 1.16472160e+02 1.18551895e+02 5.60621109e+01 -8.51340199e+00 -3.84285774e+01 1.07896652e+01 4.39769478e+01 7.80535736e+01 7.69042664e+01 6.26514931e+01 6.89050064e+01 6.74220428e+01 1.16752518e+02 1.35247726e+02 1.35534485e+02 1.06682251e+02 3.79512520e+01 2.04195938e+01 5.66524010e+01 1.26226067e+02 1.43860352e+02 1.06344452e+02 5.08392754e+01 4.67103539e+01 8.96102905e+01 1.47119720e+02 1.58373306e+02 1.01857941e+02 4.80201340e+01 2.97961597e+01 7.12875595e+01 1.08516144e+02 1.01760460e+02 7.09879837e+01 3.54759712e+01 2.87712193e+01 2.57565346e+01 5.27037125e+01 9.57810745e+01 1.11823021e+02 7.17080536e+01 8.72850537e-01 -2.79856701e+01 1.78618717e+01 7.72472382e+01 1.13223381e+02 8.74152603e+01 4.21351814e+01 1.91864376e+01 3.21500626e+01 7.00594788e+01 6.94502716e+01 4.53050346e+01 1.30422812e+01 7.76740885e+00 4.79360657e+01 7.70284500e+01 7.52427750e+01 4.47962570e+01 5.47954798e+00 1.31714230e+01 1.23977566e+01 3.60135422e+01 6.12597046e+01 7.95259628e+01 8.45802612e+01 4.14054337e+01 1.86012497e+01 2.79182472e+01 6.36973267e+01 1.00153160e+02 7.69686737e+01 4.69073563e+01 1.88261528e+01 6.08190804e+01 1.33186768e+02 1.71064316e+02 1.44144913e+02 8.57535706e+01 6.57220078e+01 1.24959541e+02 2.02872650e+02 2.59203430e+02 4.73049866e+02 6.55744568e+02 1.83446143e+03 1.84103333e+03 3.38255200e+03 8.68585742e+03 -91836320. -38148644. -21558220. -24492244. -131928816. -469972736. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -262827248. 49404384. 1.41000371e+04 3.87960791e+03 1.25261963e+03 2.50515991e+02 3.62231293e+02 4.07277588e+02 2.80660034e+02 1.91889648e+02 1.79458160e+02 1.41350952e+02 1.00889977e+02 7.83106461e+01 8.25201950e+01 1.22716660e+02 1.53147522e+02 1.41372040e+02 9.15172424e+01 4.91411934e+01 5.79829750e+01 8.68066101e+01 1.08558746e+02 1.17510666e+02 1.24842171e+02 1.39927094e+02 1.14426033e+02 1.06851845e+02 1.30495636e+02 1.50409378e+02 1.21259834e+02 5.78409920e+01 3.56292343e+01 8.33906708e+01 1.41516129e+02 1.69597565e+02 1.50885391e+02 9.77815323e+01 5.82196884e+01 3.85207405e+01 7.36827240e+01 9.84453583e+01 1.04473419e+02 8.02763748e+01 6.32536354e+01 7.71540375e+01 7.51770935e+01 9.56510239e+01 1.16980728e+02 1.36663376e+02 1.20049004e+02 6.54803009e+01 5.96214828e+01 9.84451752e+01 1.53660477e+02 1.66625839e+02 1.25880775e+02 8.77461243e+01 8.33072891e+01 1.15673965e+02 1.32005295e+02 1.07071350e+02 6.27670975e+01 4.48728180e+01 6.08146820e+01 1.06694199e+02 1.42406403e+02 1.43316513e+02 1.11903351e+02 7.56322937e+01 5.04468117e+01 3.79203186e+01 4.75295181e+01 6.88033905e+01 9.70759888e+01 1.10000587e+02 1.00366623e+02 1.06885956e+02 1.35660736e+02 1.66533768e+02 1.64620193e+02 1.29954330e+02 1.07156624e+02 1.10081383e+02 1.23625725e+02 1.42530685e+02 1.57758316e+02 1.48503372e+02 1.17120224e+02 9.76927948e+01 1.15747276e+02 1.37984406e+02 1.32052872e+02 1.15710678e+02 1.13119087e+02 1.25822647e+02 1.19070709e+02 1.19829369e+02 1.30221573e+02 1.42040070e+02 1.37333176e+02 1.04328606e+02 1.00878548e+02 1.27472412e+02 1.72239029e+02 1.89214935e+02 1.63671570e+02 1.33463791e+02 1.18586761e+02 1.25685837e+02 1.34119690e+02 1.34025925e+02 1.28657532e+02 1.15625923e+02 1.09342056e+02 1.22894531e+02 1.49179367e+02 1.59152191e+02 1.50793381e+02 1.42074036e+02 1.41939743e+02 1.30985764e+02 1.31142029e+02 1.51849762e+02 1.77389587e+02 1.78055435e+02 1.41443726e+02 1.27560074e+02 1.44328766e+02 1.72818710e+02 1.76466049e+02 1.50449692e+02 1.29607391e+02 1.23734329e+02 1.30460464e+02 1.47906158e+02 1.61841415e+02 1.61931488e+02 1.42867981e+02 1.28968063e+02 1.39454636e+02 1.58523087e+02 1.67179459e+02 1.59682602e+02 1.49801559e+02 1.42858307e+02 1.32398026e+02 1.28087311e+02 1.33114609e+02 1.41195587e+02 1.43212692e+02 1.31333450e+02 1.28322876e+02 1.39799088e+02 1.62386642e+02 1.76982346e+02 1.69602661e+02 1.50294891e+02 1.34349594e+02 1.35605515e+02 1.43891678e+02 1.46402664e+02 1.44226776e+02 1.44402008e+02 1.39620010e+02 1.40248642e+02 1.41083878e+02 1.47804016e+02 1.59084213e+02 1.62757675e+02 1.64421371e+02 1.50825745e+02 1.46390610e+02 1.53290314e+02 1.60242111e+02 1.56857422e+02 1.42376099e+02 1.37333008e+02 1.41872650e+02 1.48395706e+02 1.53012512e+02 1.53702271e+02 1.51043549e+02 1.48730179e+02 1.47057739e+02 1.53616806e+02 1.51506744e+02 1.47998154e+02 1.41587616e+02 1.36971939e+02 1.33575577e+02 1.30183334e+02 1.36244125e+02 1.45428665e+02 1.51415817e+02 1.51380798e+02 1.46460114e+02 1.46295166e+02 1.51596985e+02 1.57929962e+02 1.59805817e+02 1.52650406e+02 1.45013565e+02 1.41948624e+02 1.43996887e+02 1.46688034e+02 1.47430847e+02 1.47615768e+02 1.47150604e+02 1.46254227e+02 1.47400909e+02 1.49739136e+02 1.51077866e+02 1.49987823e+02 1.49826462e+02 1.49722946e+02 1.48960846e+02 1.48472626e+02 1.49161072e+02 1.50167755e+02 1.50477203e+02 1.50532364e+02 1.50924637e+02 1.51180374e+02 1.51165100e+02 1.50922348e+02 1.50765244e+02 1.50852493e+02 1.51478714e+02 1.51892288e+02 1.51396774e+02 1.50336945e+02 1.49715256e+02 1.50520172e+02 1.51214783e+02 1.50952011e+02 1.50902878e+02 1.50952545e+02 1.50795090e+02 1.50799240e+02 1.50898972e+02 1.50970581e+02 1.50905045e+02 1.50247742e+02 1.49740295e+02 1.48424973e+02 1.48136398e+02 1.48266693e+02 1.49425171e+02 1.49602127e+02 1.48781937e+02 1.48741943e+02 1.48854797e+02 1.51229233e+02 1.52756561e+02 1.53004822e+02 1.52226852e+02 1.50250824e+02 1.50670654e+02 1.50434677e+02 1.50205307e+02 1.49217697e+02 1.49561127e+02 1.49890076e+02 1.49596191e+02 1.48279129e+02 1.47991257e+02 1.48086334e+02 1.47757935e+02 1.47236816e+02 1.45594574e+02 1.43986404e+02 1.43468674e+02 1.45801285e+02 1.46724808e+02 1.46801758e+02 1.45408447e+02 1.45105515e+02 1.43360901e+02 1.43426559e+02 1.44080353e+02 1.47180893e+02 1.47092606e+02 1.45543213e+02 1.43461044e+02 1.45128769e+02 1.44779861e+02 1.44606812e+02 1.43491150e+02 1.45889526e+02 1.46329575e+02 1.44847626e+02 1.43844284e+02 1.44572372e+02 1.44598755e+02 1.42913651e+02 1.44390228e+02 1.48852249e+02 1.49913879e+02 1.47891571e+02 1.45533142e+02 1.44965881e+02 1.46729523e+02 1.47038254e+02 1.47709183e+02 1.45736557e+02 1.44697754e+02 1.45493118e+02 1.46693069e+02 1.43470383e+02 1.40708282e+02 1.38214523e+02 1.40046066e+02 1.38380356e+02 1.33872253e+02 1.35706329e+02 1.39174728e+02 1.45217163e+02 1.43854477e+02 1.43814682e+02 1.44851196e+02 1.41789169e+02 1.42863861e+02 1.42598999e+02 1.44419144e+02 1.46288513e+02 1.48385376e+02 1.50780319e+02 1.47290741e+02 1.43283340e+02 1.41138290e+02 1.39372879e+02 1.39310196e+02 1.41902710e+02 1.44133026e+02 1.44196289e+02 1.46618622e+02 1.47602539e+02 1.45579620e+02 1.40308746e+02 1.37883240e+02 1.39534897e+02 1.42555359e+02 1.44882278e+02 1.46476425e+02 1.44182495e+02 1.40564178e+02 1.39965485e+02 1.41050293e+02 1.43704727e+02 1.43928757e+02 1.41786255e+02 1.36495529e+02 1.34992966e+02 1.30472443e+02 1.32468201e+02 1.28853638e+02 1.31943314e+02 1.31317047e+02 1.35226364e+02 1.33773865e+02 1.30136719e+02 1.34516998e+02 1.40221100e+02 1.35840103e+02 1.23366364e+02 1.19510162e+02 1.24050209e+02 1.30474167e+02 1.28361618e+02 1.17883018e+02 1.05151405e+02 1.06339127e+02 1.19213234e+02 1.31657822e+02 1.23373985e+02 1.12422935e+02 1.10590385e+02 1.19856682e+02 1.31346313e+02 1.25933167e+02 1.16535645e+02 1.10948875e+02 1.13274406e+02 1.17062225e+02 1.13113098e+02 1.02717850e+02 9.58078995e+01 1.04960449e+02 1.20004753e+02 1.25959030e+02 1.18160477e+02 1.16400589e+02 1.19327286e+02 1.23562454e+02 1.22464600e+02 1.14540733e+02 1.03346436e+02 1.04867058e+02 1.12196892e+02 1.25712677e+02 1.25394447e+02 1.25630508e+02 1.24551857e+02 1.37033661e+02 1.55282455e+02 1.59930008e+02 1.44065491e+02 1.25792892e+02 1.17946259e+02 1.14853012e+02 1.03505661e+02 1.02688713e+02 1.24390564e+02 1.47961548e+02 1.50954773e+02 1.33995834e+02 1.14230003e+02 1.16839348e+02 1.19415932e+02 1.31618317e+02 1.36961639e+02 1.30493301e+02 1.16807259e+02 9.99340286e+01 9.85923233e+01 9.63795700e+01 1.16035332e+02 1.38538223e+02 1.40493500e+02 1.27038971e+02 1.06717300e+02 9.51381607e+01 8.24901810e+01 8.46590805e+01 1.02044952e+02 1.09584244e+02 1.14435112e+02 1.11819550e+02 1.10456627e+02 1.09944908e+02 1.14940285e+02 1.22596634e+02 1.21196899e+02 1.00686333e+02 3.78610954e+01 -1.31558704e+01 -2.38298855e+01 2.00145550e+01 4.31891212e+01 -8.23849670e+02 -3.87872241e+03 -8.28658496e+03 100345072. -27297106. 37546556. 159366480. 174401680. 495519616. 29042484. -45076500. 52400016. -48749412. 1504559616. 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. 0. 0. 0. 0. 0. 0. 0. -105792512. 89272640. -2.92394121e+04 -1.21588125e+04 -1.30308606e+03 5.39682198e+01 4.13091705e+02 -3.76169067e+03 -2.23543018e+03 -4.97840515e+02 -2.40595169e+02 -1.40806320e+02 -2.42602482e+01 -4.79946470e+00 -9.25275135e+00 -3.62517357e+01 -2.78099823e+01 8.53267136e+01 1.96440765e+02 1.92709412e+02 7.88653336e+01 -9.55193710e+01 -1.19704308e+02 -2.41962921e+02 -2.99299164e+02 -3.00293518e+02 -1.98771439e+02 -1.67115097e+02 -2.56399689e+02 -2.76647705e+02 -2.66891083e+02 -2.39573151e+02 -1.66614746e+02 -2.37956963e+01 3.63553276e+01 5.73835602e+01 6.05407143e+01 6.90800476e+01 8.32578125e+01 9.63213959e+01 9.44788589e+01 8.38690796e+01 9.01602173e+01 9.63430405e+01 1.02224998e+02 1.05616508e+02 1.08323853e+02 1.00590347e+02 7.32994080e+01 5.20606575e+01 4.64028435e+01 5.97895317e+01 7.24990463e+01 8.08933487e+01 8.36163330e+01 7.56198273e+01 6.41778717e+01 6.42456589e+01 7.38807144e+01 8.27182617e+01 8.47464676e+01 9.20746384e+01 7.87616196e+01 5.83979149e+01 4.36441917e+01 3.61795845e+01 3.39235420e+01 2.75441742e+01 3.41328163e+01 4.47620201e+01 4.86064529e+01 5.34508553e+01 7.25349045e+01 8.21871338e+01 8.44603043e+01 7.31688919e+01 6.89073105e+01 7.09069138e+01 4.98659439e+01 2.43390827e+01 2.09967499e+01 3.08290443e+01 5.06595116e+01 1.43417101e+01 -1.82503319e+01 -3.06685810e+01 -1.07810764e+01 7.20473003e+00 6.06043386e+00 8.57393742e+00 1.68971119e+01 1.55204258e+01 -1.02767220e+01 -3.32720184e+01 -2.52716465e+01 1.09418163e+01 3.74094009e+01 4.60611877e+01 3.80563278e+01 3.39617538e+01 2.32421608e+01 4.47956696e+01 6.33535004e+01 5.69623299e+01 3.00621986e+01 1.90624733e+01 3.48369789e+01 4.67061348e+01 1.75999851e+01 -4.28893757e+00 -6.63426685e+00 1.96274338e+01 4.61138268e+01 5.88552628e+01 6.40683517e+01 6.17700768e+01 5.24297409e+01 4.53330383e+01 4.31196480e+01 5.01113815e+01 4.77891998e+01 3.70172348e+01 3.35039749e+01 3.30663185e+01 3.64101181e+01 2.84646931e+01 2.80448742e+01 2.29913502e+01 -5.50633335e+00 -3.86767120e+01 -3.32784576e+01 -5.90761852e+00 1.83295517e+01 -6.53545094e+00 -3.59617958e+01 -4.14690857e+01 -2.70787373e+01 -5.41288328e+00 4.63346291e+00 1.30901890e+01 2.36146946e+01 1.82781506e+01 1.17109537e+01 7.79951286e+00 1.72854443e+01 3.11167088e+01 3.30072823e+01 2.19556007e+01 8.80261612e+00 8.40844059e+00 7.53359985e+00 8.47586823e+00 -6.80219746e+00 -3.80729141e+01 -7.20306396e+01 -6.69962311e+01 -4.09775467e+01 -1.26931801e+01 -4.08634377e+01 -6.82259750e+01 -6.54879532e+01 -3.71743507e+01 -1.17340832e+01 -1.76871033e+01 -1.70287590e+01 -1.84693794e+01 -1.21130848e+01 -1.18992891e+01 -8.29794216e+00 -4.19229126e+00 -3.69033146e+00 -1.91662216e+01 -3.35208702e+01 -2.93909798e+01 -1.56308918e+01 9.50498521e-01 9.48265266e+00 1.62236767e+01 -6.13976002e+00 -3.56243362e+01 -4.06300774e+01 -2.61273994e+01 -1.29234571e+01 -1.31051445e+01 -5.42898607e+00 -2.56355000e+01 -5.89373665e+01 -6.64147568e+01 -4.45291481e+01 -1.34452915e+01 -1.49755478e+01 -1.79650707e+01 -1.89947376e+01 -1.40473528e+01 -2.13975811e+01 -2.19051952e+01 -4.81061592e+01 -6.95957031e+01 -7.32544403e+01 -4.76783333e+01 -2.47522049e+01 -2.55209084e+01 -2.44049091e+01 -4.82993889e+01 -6.96341476e+01 -7.30774155e+01 -3.87104149e+01 -1.15025396e+01 -1.80625134e+01 -2.82992687e+01 -3.25137558e+01 -2.65333061e+01 -1.72970581e+01 -1.49155750e+01 -1.39631720e+01 -1.84761562e+01 -1.95757961e+01 -1.68919907e+01 -1.88186703e+01 -5.62593555e+00 -1.71101391e+00 5.62198544e+00 1.88131356e+00 -4.83622742e+00 -3.83079934e+00 -4.09274769e+00 -8.84604275e-01 -4.75366640e+00 -9.88804913e+00 -8.61422443e+00 -1.59275446e+01 -1.46668386e+01 -1.22834635e+01 -2.93838739e+00 -1.64902759e+00 -1.20524645e+01 -1.64968624e+01 -2.25100899e+01 -1.27094374e+01 -1.90231247e+01 -1.55749598e+01 -2.91832142e+01 -3.47156334e+01 -3.85593147e+01 -1.88357811e+01 3.06136680e+00 -1.12271442e+01 -4.85110397e+01 -8.15200882e+01 -7.82516708e+01 -6.39862404e+01 -5.37972488e+01 -5.05423317e+01 -5.94428444e+01 -6.96388168e+01 -7.32960129e+01 -6.46321716e+01 -5.15214996e+01 -4.08878326e+01 -3.18803787e+01 -2.91864014e+01 -3.42500916e+01 -4.55258102e+01 -5.24992638e+01 -5.88546562e+01 -5.84332733e+01 -6.16021538e+01 -4.67226524e+01 -4.24193878e+01 -3.63964348e+01 -5.08589363e+01 -7.15820618e+01 -9.05786285e+01 -8.51562119e+01 -7.25051880e+01 -5.88661118e+01 -5.90021896e+01 -5.76599388e+01 -7.32351074e+01 -9.27352371e+01 -9.95228424e+01 -9.39812393e+01 -7.34516220e+01 -6.15999451e+01 -4.69478226e+01 -5.64553719e+01 -6.64962616e+01 -6.92573853e+01 -5.87263336e+01 -5.43862038e+01 -5.38196487e+01 -6.43523102e+01 -7.00002670e+01 -7.02314606e+01 -7.33452759e+01 -7.24511337e+01 -1.00189087e+02 -1.21116005e+02 -1.17424698e+02 -8.90189056e+01 -6.33629112e+01 -7.29653015e+01 -8.23083801e+01 -8.13971634e+01 -7.85262527e+01 -9.53233185e+01 -1.17537888e+02 -1.18126526e+02 -9.70491638e+01 -7.39958801e+01 -8.19736862e+01 -8.30218353e+01 -7.73925323e+01 -6.40128555e+01 -6.44641266e+01 -7.21680222e+01 -8.46082230e+01 -8.18421402e+01 -6.87693634e+01 -6.42132950e+01 -6.68361893e+01 -7.05424652e+01 -6.26515884e+01 -7.51623459e+01 -9.24900894e+01 -9.77075348e+01 -1.09190071e+02 -1.28645355e+02 -1.49705231e+02 -1.54460632e+02 -1.45902008e+02 -1.49039810e+02 -1.25198143e+02 -1.15754105e+02 -9.13114929e+01 -7.81487427e+01 -5.47701302e+01 -5.67475395e+01 -6.64595566e+01 -7.26135254e+01 -7.14953690e+01 -7.03677063e+01 -7.10338211e+01 -6.87897491e+01 -6.25679131e+01 -8.11419449e+01 -1.07566116e+02 -1.25657440e+02 -1.25919006e+02 -1.08795990e+02 -1.01839149e+02 -9.53827438e+01 -8.27150421e+01 -9.88552399e+01 -1.05003021e+02 -1.16454453e+02 -1.16454933e+02 -1.20297981e+02 -1.31343689e+02 -1.13470413e+02 -9.84330444e+01 -9.26702728e+01 -1.10468857e+02 -1.18648079e+02 -1.09668007e+02 -9.24064560e+01 -1.06771851e+02 -1.21064491e+02 -1.27896805e+02 -1.16794327e+02 -1.07859528e+02 -1.29174271e+02 -1.47987549e+02 -1.40584518e+02 -1.08751366e+02 -9.51981659e+01 -1.15522263e+02 -1.32373367e+02 -1.09365944e+02 -8.08004684e+01 -9.77128677e+01 -1.28628265e+02 -1.43411453e+02 -1.34048279e+02 -1.24640503e+02 -1.29397278e+02 -1.41503754e+02 -1.54293594e+02 -1.45205856e+02 -1.20074089e+02 -9.86336060e+01 -1.00335129e+02 -1.05683945e+02 -1.11977043e+02 -1.09237045e+02 -1.10217026e+02 -1.16854942e+02 -1.32407410e+02 -1.29739716e+02 -1.11567680e+02 -1.07783432e+02 -1.15093178e+02 -1.34951202e+02 -1.36090118e+02 -1.28045822e+02 -1.24133713e+02 -1.16385696e+02 -1.15813751e+02 -1.06838051e+02 -9.65527954e+01 -9.26152573e+01 -9.70591736e+01 -1.29055786e+02 -1.50504715e+02 -1.33157349e+02 -9.41243134e+01 -9.16390381e+01 -1.26426125e+02 -1.39406326e+02 -1.19919174e+02 -1.08211746e+02 -1.20520447e+02 -1.28872864e+02 -1.23137680e+02 -1.07236427e+02 -1.16561844e+02 -1.28480148e+02 -1.36947632e+02 -1.27349510e+02 -1.14476738e+02 -1.14182991e+02 -1.15891342e+02 -1.30292206e+02 -1.39373245e+02 -1.39831818e+02 -1.25397652e+02 -1.26102066e+02 -1.57140030e+02 -1.77888031e+02 -1.71659485e+02 -1.44176025e+02 -1.43188324e+02 -1.55000854e+02 -1.41543106e+02 -1.11893753e+02 -9.86291809e+01 -1.16103973e+02 -1.31883575e+02 -1.31376053e+02 -1.26076241e+02 -1.30497192e+02 -1.28812973e+02 -1.31361099e+02 -1.30675980e+02 -1.27417320e+02 -1.21464287e+02 -1.16145676e+02 -1.21736053e+02 -1.27111801e+02 -1.36881134e+02 -1.38219376e+02 -1.40424484e+02 -1.47875336e+02 -1.52903580e+02 -1.47656403e+02 -1.36162674e+02 -1.36023270e+02 -1.48632492e+02 -1.50666824e+02 -1.44696014e+02 -1.51466217e+02 -1.78291977e+02 -1.97591995e+02 -1.87337265e+02 -1.60187057e+02 -1.52493866e+02 -1.61426743e+02 -1.62026627e+02 -1.49662186e+02 -1.39414719e+02 -1.38060333e+02 -1.34992599e+02 -1.36994705e+02 -1.41667877e+02 -1.41099533e+02 -1.31813049e+02 -1.27965256e+02 -1.45267044e+02 -1.56361038e+02 -1.49806824e+02 -1.36932022e+02 -1.49170593e+02 -1.59983795e+02 -1.50316269e+02 -1.25011169e+02 -1.09820564e+02 -1.13899162e+02 -1.17346817e+02 -1.21243813e+02 -1.18930984e+02 -1.22401337e+02 -1.21560005e+02 -1.29290512e+02 -1.31683395e+02 -1.32087097e+02 -1.24426781e+02 -1.30173737e+02 -1.51640533e+02 -1.66093414e+02 -1.71521576e+02 -1.65934555e+02 -1.57050446e+02 -1.46586288e+02 -1.38056320e+02 -1.39907578e+02 -1.39775635e+02 -1.39539993e+02 -1.39809982e+02 -1.40830032e+02 -1.38348038e+02 -1.39732635e+02 -1.42617996e+02 -1.43442917e+02 -1.43797058e+02 -1.41863083e+02 -1.52955688e+02 -1.63188690e+02 -1.64293396e+02 -1.54601074e+02 -1.46649628e+02 -1.47520294e+02 -1.48208511e+02 -1.47760620e+02 -1.48075821e+02 -1.50126022e+02 -1.51759232e+02 -1.55324905e+02 -1.60432449e+02 -1.56481293e+02 -1.49790848e+02 -1.46074463e+02 -1.60692322e+02 -1.70312363e+02 -1.66506485e+02 -1.53461700e+02 -1.52294327e+02 -1.59303970e+02 -1.58618927e+02 -1.53341156e+02 -1.47489716e+02 -1.54783539e+02 -1.59508881e+02 -1.63772629e+02 -1.64523056e+02 -1.56812973e+02 -1.51448868e+02 -1.51456253e+02 -1.65722656e+02 -1.72451569e+02 -1.65795700e+02 -1.53755478e+02 -1.55392029e+02 -1.62837616e+02 -1.63470581e+02 -1.58011124e+02 -1.51692413e+02 -1.56011017e+02 -1.60542786e+02 -1.62599152e+02 -1.58931076e+02 -1.54011780e+02 -1.52577682e+02 -1.57412384e+02 -1.61977890e+02 -1.63349640e+02 -1.58684143e+02 -1.52779816e+02 -1.55012756e+02 -1.58665924e+02 -1.60316833e+02 -1.57532700e+02 -1.56789581e+02 -1.60037674e+02 -1.58576080e+02 -1.54510788e+02 -1.49677856e+02 -1.49199707e+02 -1.49380188e+02 -1.51916641e+02 -1.55310013e+02 -1.56037659e+02 -1.55194412e+02 -1.53119400e+02 -1.59457977e+02 -1.75859253e+02 -1.83155960e+02 -2.00466415e+02 -4.04627563e+02 -1.16426526e+03 -2.57557544e+03 -33968180. 49141656. 4.67992365e-01 -7.91602554e+01 -2.87347382e+02 -2.77945435e+02 -8.35924316e+02 -1.79519519e+03 -39407868. 330658784. -243484976. 86649528. 166590096. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.39530163e+09 -56100592. -2.50368384e+03 -1.35071228e+03 -1.27881250e+03 -8.86966125e+02 -5.20909973e+02 -2.90581146e+02 -3.03537842e+02 -3.39996399e+02 -3.52282501e+02 -3.26281128e+02 -3.15035553e+02 -3.04008606e+02 -3.03222107e+02 -3.10760284e+02 -3.14180145e+02 -3.11313324e+02 -3.14361755e+02 -3.20337433e+02 -3.27101807e+02 -3.19550598e+02 -3.03983459e+02 -2.94850891e+02 -2.99164978e+02 -3.10598633e+02 -3.18326141e+02 -3.16769775e+02 -3.13944092e+02 -3.17938812e+02 -3.22994141e+02 -3.18800507e+02 -3.07288635e+02 -3.00977112e+02 -3.04621918e+02 -3.14976715e+02 -3.18511597e+02 -3.09517578e+02 -2.95236542e+02 -2.88877441e+02 -2.95507629e+02 -2.94105469e+02 -2.85678253e+02 -2.91419067e+02 -3.08405853e+02 -3.22714417e+02 -3.05305695e+02 -2.75818329e+02 -2.65150208e+02 -2.80625031e+02 -2.97282257e+02 -3.07228851e+02 -3.09258698e+02 -3.07556427e+02 -3.05754547e+02 -3.09297180e+02 -3.04559265e+02 -2.79149719e+02 -2.57761932e+02 -2.64089874e+02 -2.89222229e+02 -3.04987885e+02 -2.93835022e+02 -2.74891724e+02 -2.66781372e+02 -2.82697327e+02 -2.88674255e+02 -2.82006042e+02 -2.87308014e+02 -3.05342163e+02 -3.25562103e+02 -3.20012970e+02 -2.84017609e+02 -2.73278870e+02 -2.86289154e+02 -3.14867065e+02 -3.10596283e+02 -2.87384003e+02 -2.90827209e+02 -3.04745453e+02 -3.16445404e+02 -3.02191895e+02 -2.69926056e+02 -2.54727020e+02 -2.65596954e+02 -2.98823395e+02 -3.17641266e+02 -3.08888458e+02 -2.92260345e+02 -2.97601074e+02 -3.16003235e+02 -3.14008301e+02 -2.89504913e+02 -2.78732269e+02 -3.04386200e+02 -3.36192200e+02 -3.35929688e+02 -2.97677185e+02 -2.64934296e+02 -2.64222015e+02 -2.87635132e+02 -2.93294922e+02 -2.87234131e+02 -3.07513672e+02 -3.44860474e+02 -3.64157104e+02 -3.27229675e+02 -2.71542114e+02 -2.41070770e+02 -2.59195251e+02 -2.90004395e+02 -3.25408417e+02 -3.46843475e+02 -3.40208313e+02 -3.31768829e+02 -3.29339996e+02 -3.22209534e+02 -2.85552887e+02 -2.52510986e+02 -2.73016907e+02 -3.30692932e+02 -3.56302185e+02 -3.30628204e+02 -2.71078125e+02 -2.46240372e+02 -2.68713989e+02 -2.94054138e+02 -2.99938751e+02 -2.92655334e+02 -3.16172852e+02 -3.64846527e+02 -3.64051361e+02 -3.17200958e+02 -2.66090057e+02 -2.70543915e+02 -2.97749298e+02 -3.22965393e+02 -3.25243866e+02 -3.18490509e+02 -2.96177246e+02 -2.83879089e+02 -3.11273315e+02 -3.24993073e+02 -2.98542816e+02 -2.72958954e+02 -2.64042328e+02 -2.80093842e+02 -2.80709717e+02 -2.62601807e+02 -2.61079010e+02 -2.75304260e+02 -2.96799164e+02 -3.10970703e+02 -2.88483765e+02 -2.77228485e+02 -2.80941711e+02 -3.00092163e+02 -2.76417755e+02 -2.06928650e+02 -1.74487961e+02 -2.27515564e+02 -2.89826324e+02 -2.99389008e+02 -2.62921173e+02 -2.41593765e+02 -2.40205139e+02 -2.37358536e+02 -2.10737579e+02 -1.80612885e+02 -1.69810135e+02 -1.88107635e+02 -2.37257401e+02 -2.67806244e+02 -2.36546158e+02 -2.14608444e+02 -2.24080246e+02 -2.63173859e+02 -2.35903824e+02 -1.76559265e+02 -1.74767258e+02 -2.03627335e+02 -2.30924530e+02 -1.91090271e+02 -1.22954033e+02 -8.32719421e+01 -1.25710060e+02 -1.99919800e+02 -2.43364914e+02 -2.35660507e+02 -2.42867065e+02 -2.64349792e+02 -2.49889954e+02 -1.95942871e+02 -1.34620148e+02 -1.49175156e+02 -1.95926743e+02 -2.76385925e+02 -3.06038666e+02 -2.88767883e+02 -2.30099274e+02 -1.77483292e+02 -1.76802917e+02 -1.57282623e+02 -1.37329590e+02 -1.42422394e+02 -2.07470657e+02 -2.72501343e+02 -2.44126022e+02 -1.45649124e+02 -9.05012054e+01 -1.44792725e+02 -2.46866226e+02 -2.83964508e+02 -2.38940567e+02 -1.85626648e+02 -2.06295624e+02 -2.45063553e+02 -2.33746338e+02 -1.77576096e+02 -1.62859039e+02 -2.11877777e+02 -2.90817993e+02 -3.06683929e+02 -2.66524811e+02 -2.19296860e+02 -2.20819519e+02 -2.40788635e+02 -2.38552322e+02 -2.05009216e+02 -2.19533905e+02 -2.61743011e+02 -2.74572540e+02 -2.74069214e+02 -2.18147537e+02 -2.07277695e+02 -2.11992584e+02 -2.18861511e+02 -2.17301712e+02 -1.77448257e+02 -2.07012161e+02 -2.58005829e+02 -2.81510742e+02 -2.52441605e+02 -1.44214203e+02 -9.13276062e+01 -9.79698639e+01 -2.18550995e+02 -2.79244446e+02 -2.87414001e+02 -2.37768677e+02 -2.04706985e+02 -2.35036423e+02 -2.20894928e+02 -1.88939362e+02 -1.67206741e+02 -2.05571045e+02 -2.38725098e+02 -1.82374130e+02 -1.09731621e+02 -1.21247856e+02 -1.54414795e+02 -1.74147781e+02 -1.49025970e+02 -1.01304146e+02 -1.53404709e+02 -1.88787491e+02 -2.24357529e+02 -1.95093628e+02 -1.34074173e+02 -1.09505836e+02 -9.10301971e+01 -1.44632858e+02 -1.73592804e+02 -1.86204391e+02 -1.34520645e+02 -1.29268250e+02 -1.35649719e+02 -1.25369202e+02 -8.22557526e+01 -6.39913826e+01 -1.33030716e+02 -1.75545898e+02 -1.76964111e+02 -1.17690712e+02 -1.35139908e+02 -1.54426132e+02 -1.83252228e+02 -1.96248337e+02 -1.84134949e+02 -1.89357162e+02 -1.24779854e+02 -9.64631729e+01 -7.80633774e+01 -8.60277100e+01 -1.06859764e+02 -1.30129181e+02 -1.98490616e+02 -2.26423401e+02 -1.98128967e+02 -9.73588486e+01 -6.42215805e+01 -8.39205780e+01 -1.21380569e+02 -1.25574326e+02 -1.43537811e+02 -2.23341736e+02 -2.64138794e+02 -2.32662460e+02 -1.30591919e+02 -9.45778427e+01 -1.35006821e+02 -1.84520248e+02 -1.88826111e+02 -1.36905518e+02 -1.36795502e+02 -1.28392380e+02 -1.87904037e+02 -2.06043961e+02 -2.09155762e+02 -1.50973083e+02 -1.33721588e+02 -1.79751770e+02 -2.26645920e+02 -1.90146835e+02 -1.12775543e+02 -1.28457047e+02 -1.76994904e+02 -1.88653458e+02 -1.44494171e+02 -1.39855988e+02 -2.01180069e+02 -2.30746445e+02 -2.05608963e+02 -1.27334801e+02 -1.33115616e+02 -1.55392090e+02 -1.84997849e+02 -1.59950790e+02 -1.24089287e+02 -1.35378845e+02 -1.24993668e+02 -1.71580841e+02 -1.75912628e+02 -1.91384842e+02 -1.55159851e+02 -1.46052917e+02 -1.67363358e+02 -1.96359695e+02 -1.68716934e+02 -1.07372650e+02 -9.73935242e+01 -1.00302376e+02 -6.75635529e+01 9.11299324e+00 -9.47773075e+00 -7.32099991e+01 -9.57688370e+01 -5.77552032e+01 2.42067289e+00 -6.25529099e+01 -9.14926529e+01 -1.35981445e+02 -1.62481201e+02 -1.68792297e+02 -1.33877716e+02 -3.02081833e+01 -1.19760008e+01 -7.95811157e+01 -1.55019699e+02 -1.11720238e+02 -1.98369236e+01 3.90630875e+01 -2.64502106e+01 -7.22352829e+01 -6.43402481e+01 -3.39289513e+01 5.68630409e+00 5.80256920e+01 1.44055893e+02 1.25462563e+02 4.76523933e+01 1.36344242e+01 4.77191277e+01 9.48610916e+01 1.09055042e+01 -3.95406532e+01 -6.65616608e+01 -6.02626991e+01 -4.44948006e+01 -2.49503446e+00 1.24537659e+02 1.50553391e+02 5.60799026e+01 -1.04808960e+02 -1.39192215e+02 -2.64332557e+00 1.12655487e+02 1.17992111e+02 3.53236389e+01 -1.10262241e+01 2.00694885e+01 9.57744598e+01 1.41980560e+02 9.70630341e+01 -2.23767414e+01 -5.97778664e+01 -9.79139519e+00 7.13496475e+01 1.60039078e+02 1.51881668e+02 1.07726646e+02 3.60091734e+00 -1.06443695e+02 -1.45986221e+02 -7.63070984e+01 7.86597595e+01 1.71144180e+02 9.66002731e+01 -1.65426579e+01 -1.30604706e+01 1.09868225e+02 2.26516937e+02 1.81856873e+02 5.97050781e+01 -4.37601280e+01 -4.92854462e+01 2.75466461e+01 9.78535843e+01 1.41156021e+02 6.93836746e+01 3.24442863e+01 3.84645867e+00 5.32351799e+01 9.11807404e+01 3.77982101e+01 -2.65684547e+01 -9.23025970e+01 -9.18512955e+01 -6.13151665e+01 5.06729746e+00 1.17370712e+02 1.54595947e+02 8.04652405e+01 -7.80054092e+01 -1.56588211e+02 -9.19185333e+01 6.39033928e+01 1.60974991e+02 1.33891708e+02 6.77733307e+01 5.12339935e+01 1.06450600e+02 1.36954071e+02 1.53573074e+02 7.85097580e+01 2.17701874e+01 -3.63464012e+01 -4.71473999e+01 -1.32295961e+01 3.28972321e+01 1.01400887e+02 9.28509445e+01 5.61352005e+01 -2.11211605e+01 -2.05012608e+01 4.38156586e+01 1.21885368e+02 9.39821701e+01 1.99278126e+01 -1.53519135e+01 4.69853096e+01 1.39847427e+02 1.40792938e+02 7.35311432e+01 -2.73661308e+01 -2.05552464e+01 5.70078201e+01 1.28702820e+02 1.81582184e+02 9.85176926e+01 6.51923981e+01 2.40987015e+01 2.08094902e+01 4.40440512e+00 -1.01465197e+01 3.65622482e+01 2.51005611e+01 -1.66504936e+01 -1.20202694e+01 4.80720406e+01 1.52043381e+02 1.91410309e+02 1.33259247e+02 -3.25218010e+00 -1.07716125e+02 -9.62646332e+01 4.08865776e+01 1.80559967e+02 2.24086700e+02 1.31403336e+02 1.83696594e+01 -7.41779089e+00 6.54972305e+01 1.58441071e+02 1.32485352e+02 6.48334808e+01 3.96903872e+00 -5.01320422e-01 2.78535271e+01 7.88602753e+01 1.46741333e+02 1.40416656e+02 7.77587738e+01 -1.41348791e+01 -3.53009911e+01 3.68776321e+01 1.34260788e+02 1.37702988e+02 5.35710449e+01 -2.24264455e+00 1.68136768e+01 7.45842209e+01 1.02120827e+02 1.24878967e+02 1.00028938e+02 7.52166977e+01 8.56327820e+01 1.00385544e+02 1.34276993e+02 9.71818161e+01 5.57768059e+01 1.25259838e+01 -1.72476254e+01 3.25464363e+01 6.52565155e+01 1.43325989e+02 1.71082275e+02 1.36334946e+02 6.49671707e+01 5.04753227e+01 1.19637566e+02 1.99691818e+02 1.83081299e+02 1.36046692e+02 5.29531898e+01 3.14839020e+01 7.41070938e+01 1.22595474e+02 1.50085999e+02 7.98344650e+01 2.77465954e+01 -2.53256454e+01 -1.67294178e+01 5.53933640e+01 4.68272667e+01 2.30966434e+01 -4.98960037e+01 -4.82489281e+01 -1.94144688e+01 3.45482254e+01 1.34439606e+02 1.74978851e+02 1.51770340e+02 6.77490616e+01 4.05474358e+01 9.62099380e+01 1.80076462e+02 1.68911575e+02 9.08618088e+01 1.96385975e+01 5.40503883e+01 1.38807007e+02 2.21098022e+02 2.26168991e+02 1.56244171e+02 7.34651184e+01 5.46811829e+01 5.50969124e+01 7.73767242e+01 1.06742805e+02 1.59971329e+02 1.68431458e+02 1.40652786e+02 1.23094093e+02 1.56776047e+02 2.40099777e+02 2.75251495e+02 2.11475830e+02 1.14312042e+02 7.01830902e+01 1.29022522e+02 2.20640182e+02 2.41678955e+02 1.92044952e+02 1.03950172e+02 9.23350143e+01 1.40775528e+02 1.72228027e+02 1.89380707e+02 1.41175415e+02 1.20749596e+02 1.34428146e+02 1.50524536e+02 2.02588821e+02 1.87366257e+02 1.84794815e+02 1.09230392e+02 3.14171333e+01 -5.89642906e+00 6.58452320e+00 9.76800308e+01 1.72705475e+02 1.99628540e+02 9.62305450e+01 -1.29904846e+02 -9.07666321e+01 2.26528549e+02 -2.69561743e+03 -7.56222900e+03 -198983744. -617869120. -49712756. -192484304. 579302528. -29793058. -195099296. 783052096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -262827248. 49404384. 1.41000371e+04 6.22114600e+03 -2.52528857e+03 -2.14856689e+03 -5.50155457e+02 -4.12316498e+02 -7.76336288e+01 5.66329117e+01 1.72603958e+02 2.07219223e+02 1.72004227e+02 1.52700577e+02 1.89785141e+02 2.76399811e+02 2.79355011e+02 2.39857620e+02 1.81119492e+02 1.91885345e+02 2.51816437e+02 3.11194366e+02 3.19135834e+02 2.72148865e+02 1.93208572e+02 1.83085464e+02 2.39473236e+02 3.06041565e+02 3.06759155e+02 2.54622208e+02 2.51395889e+02 2.85857300e+02 2.97918823e+02 2.64977417e+02 2.27825272e+02 2.30304794e+02 2.26607864e+02 2.07148026e+02 2.06543030e+02 2.47287598e+02 3.18539093e+02 3.24067627e+02 2.74657715e+02 2.29114136e+02 2.29162262e+02 2.79751129e+02 3.39305908e+02 3.32052368e+02 2.64309143e+02 1.74768066e+02 1.79489502e+02 2.54617325e+02 3.03633972e+02 3.11560303e+02 2.68674164e+02 2.50902283e+02 2.45436951e+02 2.41369354e+02 2.51759689e+02 2.75670502e+02 3.15966522e+02 3.05302338e+02 2.59902985e+02 2.52036453e+02 2.82709564e+02 3.38608002e+02 3.36811859e+02 3.05388611e+02 2.64035217e+02 2.41064636e+02 2.87093567e+02 3.43973846e+02 3.90740143e+02 3.64674591e+02 3.04279449e+02 2.82807098e+02 3.16082672e+02 3.45196228e+02 3.44463043e+02 2.89166779e+02 2.79883270e+02 2.87886322e+02 3.18963287e+02 3.11394592e+02 3.14553497e+02 3.26362549e+02 3.10647705e+02 2.76458313e+02 2.62504791e+02 3.01272827e+02 3.60920319e+02 3.66948151e+02 3.44504913e+02 3.01358215e+02 2.74074524e+02 2.74745453e+02 3.07669434e+02 3.32927704e+02 3.29583282e+02 2.79506500e+02 2.63314545e+02 2.95287323e+02 3.36719666e+02 3.31880890e+02 2.86574493e+02 2.60856842e+02 2.66678467e+02 2.72685944e+02 2.82678833e+02 2.99834747e+02 3.33981079e+02 3.30979828e+02 3.03681183e+02 2.82384430e+02 2.86031250e+02 3.13886566e+02 3.17266846e+02 2.99087799e+02 2.85106110e+02 2.71488037e+02 2.76349396e+02 3.01105682e+02 3.23867188e+02 3.32148743e+02 2.93159363e+02 2.76877319e+02 2.91767426e+02 3.03893341e+02 3.06620331e+02 2.89655457e+02 2.94671478e+02 2.97654053e+02 2.87610992e+02 2.83731476e+02 2.91102966e+02 3.22935669e+02 3.22837189e+02 2.99173950e+02 2.82372528e+02 2.84033600e+02 3.06545166e+02 3.04184998e+02 2.88545197e+02 2.80936768e+02 2.71955414e+02 2.86130066e+02 3.04838593e+02 3.24725159e+02 3.22636749e+02 3.03061035e+02 2.99726074e+02 3.06309723e+02 3.07338470e+02 3.00248260e+02 2.87296143e+02 2.79431519e+02 2.75639282e+02 2.75794830e+02 2.87847565e+02 2.98877502e+02 3.20551086e+02 3.26058868e+02 3.24187469e+02 3.11545441e+02 3.11941833e+02 3.23852356e+02 3.37332611e+02 3.28215393e+02 3.08353363e+02 2.92502960e+02 2.91764587e+02 3.11535645e+02 3.23194702e+02 3.21402039e+02 3.09393799e+02 3.05752380e+02 3.13901245e+02 3.13158783e+02 3.14876190e+02 3.15671112e+02 3.15680359e+02 3.06281891e+02 2.95258514e+02 2.94150299e+02 2.99243835e+02 3.08052643e+02 3.14209412e+02 3.15703796e+02 3.13655090e+02 3.13884796e+02 3.20950562e+02 3.28276489e+02 3.25329559e+02 3.13911346e+02 3.03978821e+02 3.02430908e+02 3.10671997e+02 3.13271515e+02 3.14123444e+02 3.07018097e+02 3.08539062e+02 3.12962524e+02 3.18796783e+02 3.22500854e+02 3.22867218e+02 3.25872345e+02 3.22358887e+02 3.16679596e+02 3.12617920e+02 3.13074249e+02 3.17127075e+02 3.17155640e+02 3.14444672e+02 3.11506134e+02 3.09208435e+02 3.11228058e+02 3.15204834e+02 3.18101288e+02 3.16588867e+02 3.13749207e+02 3.13455505e+02 3.14351013e+02 3.14567169e+02 3.14357971e+02 3.14001740e+02 3.14009735e+02 3.14278381e+02 3.14487244e+02 3.14489471e+02 3.13839081e+02 3.12388092e+02 3.11566681e+02 3.11761230e+02 3.12731537e+02 3.12781281e+02 3.12546478e+02 3.13723938e+02 3.15772034e+02 3.16604431e+02 3.15891571e+02 3.13124207e+02 3.11986053e+02 3.11241302e+02 3.12244324e+02 3.14378296e+02 3.15809021e+02 3.15345123e+02 3.13023468e+02 3.10939941e+02 3.11926300e+02 3.13088654e+02 3.12556183e+02 3.10646729e+02 3.09332153e+02 3.11018555e+02 3.12137482e+02 3.13127899e+02 3.13378113e+02 3.12567444e+02 3.14122040e+02 3.12964111e+02 3.12520538e+02 3.10025452e+02 3.11101196e+02 3.12847198e+02 3.12714600e+02 3.11612366e+02 3.10953461e+02 3.12970856e+02 3.12970825e+02 3.14076721e+02 3.17401215e+02 3.15571289e+02 3.12925110e+02 3.09461060e+02 3.13335999e+02 3.13676727e+02 3.13457825e+02 3.13804260e+02 3.14282104e+02 3.14263031e+02 3.13085083e+02 3.13546112e+02 3.12445374e+02 3.10722321e+02 3.08941254e+02 3.10766937e+02 3.10008698e+02 3.14702667e+02 3.11539337e+02 3.12727661e+02 3.09615692e+02 3.14775696e+02 3.13900024e+02 3.13279846e+02 3.05999573e+02 3.00958405e+02 2.96468414e+02 2.99197418e+02 3.03317688e+02 3.06765320e+02 3.06740936e+02 3.06199890e+02 3.01793549e+02 2.99844696e+02 3.03395050e+02 3.03946594e+02 3.01849701e+02 3.01133087e+02 3.06707153e+02 3.10024078e+02 3.06578217e+02 3.02933777e+02 3.03033752e+02 3.00074463e+02 2.95630981e+02 2.92050354e+02 2.91207458e+02 2.94245972e+02 2.99183502e+02 3.02004211e+02 3.10965118e+02 3.13859680e+02 3.18158752e+02 3.08666260e+02 3.01936920e+02 2.95252197e+02 2.89560272e+02 2.88616211e+02 2.99633118e+02 3.14082794e+02 3.12176331e+02 3.00226379e+02 2.88504028e+02 2.89090057e+02 2.90945709e+02 2.85608063e+02 2.82910370e+02 2.81836334e+02 2.87311127e+02 2.83889343e+02 2.83302032e+02 2.86752167e+02 2.91108368e+02 2.85901367e+02 2.71803162e+02 2.56490326e+02 2.53927887e+02 2.63096405e+02 2.78994202e+02 2.77778717e+02 2.71025299e+02 2.71357086e+02 2.75866028e+02 2.82796234e+02 2.66400757e+02 2.56514160e+02 2.49100128e+02 2.65364075e+02 2.78675049e+02 2.89994080e+02 2.77239746e+02 2.54632950e+02 2.32094223e+02 2.47410248e+02 2.75687347e+02 2.87191833e+02 2.77836792e+02 2.66452240e+02 2.63564911e+02 2.52521698e+02 2.41608826e+02 2.48356033e+02 2.65593140e+02 2.78464600e+02 2.81138123e+02 2.72197571e+02 2.59229065e+02 2.42410461e+02 2.45257065e+02 2.58733582e+02 2.71750854e+02 2.74857178e+02 2.74161224e+02 2.75591431e+02 2.81861267e+02 2.88340759e+02 2.88418762e+02 2.76888306e+02 2.65405304e+02 2.68735504e+02 2.75611877e+02 2.74244446e+02 2.65403076e+02 2.64971893e+02 2.74262634e+02 2.59912537e+02 2.47649551e+02 2.49033157e+02 2.76429840e+02 2.85562103e+02 2.68969208e+02 2.56016724e+02 2.49330261e+02 2.41279022e+02 2.29475845e+02 2.29559326e+02 2.26010651e+02 2.25764481e+02 2.29433289e+02 2.46601776e+02 2.50633759e+02 2.42489929e+02 2.40233246e+02 2.49996017e+02 2.52297256e+02 2.49438278e+02 2.48802658e+02 2.30662323e+02 2.15037399e+02 2.12251541e+02 2.35619385e+02 2.58376251e+02 2.52697296e+02 2.51963058e+02 2.47484482e+02 2.47589188e+02 2.38805969e+02 2.46080704e+02 2.63039307e+02 2.77531433e+02 2.76787933e+02 2.65987335e+02 2.49756638e+02 2.46769211e+02 2.51569305e+02 2.55719604e+02 2.45583618e+02 2.43387695e+02 2.70234344e+02 3.01859680e+02 3.02611572e+02 2.63500763e+02 2.27433151e+02 2.25609512e+02 2.63446381e+02 3.49406464e+02 4.63290436e+02 6.06494324e+02 6.44994568e+02 5.66735168e+02 3.72084302e+03 9.56298926e+03 90718984. 46596104. 255343664. 40227700. 515740128. -505740128. -84828240. 56905364. -35013028. -87598776. -177720176. -470063296. 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. 0. 0. 0. 0. 0. 0. -105792512. 89272640. -2.92394121e+04 -1.21588125e+04 -1.30308606e+03 4.75519922e+03 3.46452173e+03 9.67197876e+02 4.67022064e+02 2.81846008e+02 2.43233032e+02 2.75060303e+02 2.73528290e+02 2.42123154e+02 1.97583176e+02 1.95347168e+02 1.88374298e+02 1.87763947e+02 1.87104034e+02 2.09831345e+02 2.39645782e+02 2.10618057e+02 1.64079163e+02 1.51096024e+02 1.85473236e+02 2.06779984e+02 1.87913574e+02 1.82111618e+02 1.87448486e+02 2.01314713e+02 2.13066879e+02 2.16221390e+02 2.09048615e+02 1.81405380e+02 1.71194443e+02 1.63569473e+02 1.76251099e+02 1.43637161e+02 1.01328590e+02 9.14057770e+01 1.14175430e+02 1.44058273e+02 1.31457535e+02 1.16651077e+02 1.10610298e+02 1.00032005e+02 9.55676727e+01 8.75357971e+01 8.22348557e+01 8.03336945e+01 9.05767670e+01 9.59491272e+01 9.80020370e+01 8.46788330e+01 8.87218552e+01 9.72483597e+01 9.44390106e+01 8.62008438e+01 7.20171661e+01 7.42223053e+01 8.92010345e+01 1.19321793e+02 1.53668381e+02 1.69948318e+02 1.53539398e+02 1.27054565e+02 1.10661743e+02 1.35197449e+02 1.59785812e+02 1.48698364e+02 1.10364967e+02 7.02373886e+01 6.52023773e+01 6.57681580e+01 4.77441711e+01 1.70344753e+01 3.97755775e+01 9.02007065e+01 1.27383911e+02 1.11064903e+02 8.72728882e+01 9.03437881e+01 8.69069290e+01 8.62193222e+01 8.08819122e+01 8.06759644e+01 8.03367996e+01 9.59392166e+01 9.99592667e+01 1.05224617e+02 8.78990250e+01 9.19359741e+01 1.28315109e+02 1.72254089e+02 1.57254028e+02 1.17925369e+02 7.88894653e+01 9.53448792e+01 1.12133896e+02 1.33568039e+02 1.45461151e+02 1.20934708e+02 7.90086594e+01 6.58326111e+01 7.98696365e+01 1.24016373e+02 1.21256721e+02 1.10530426e+02 8.25729523e+01 6.44130783e+01 7.65866470e+01 6.77591324e+01 6.97825317e+01 5.37976646e+01 6.64494247e+01 6.92450562e+01 6.53427505e+01 8.18330917e+01 1.05656830e+02 9.98657150e+01 7.32985535e+01 4.25880737e+01 3.91587868e+01 3.50875816e+01 3.26625748e+01 2.95452118e+01 1.48479223e+01 1.61219463e+01 5.99058113e+01 1.14031334e+02 1.16670380e+02 8.26288605e+01 3.82656517e+01 1.27172575e+01 -5.23509979e+00 1.66977882e+00 2.25757713e+01 2.97798023e+01 1.02820892e+01 1.22404661e+01 1.52131453e+01 2.32744923e+01 2.73459988e+01 3.10145874e+01 2.86643143e+01 2.60523338e+01 2.35475998e+01 2.79879971e+01 3.64318199e+01 3.73200417e+01 3.56425209e+01 4.04089165e+01 4.45061760e+01 4.83938332e+01 3.38903580e+01 2.49641132e+01 1.38077574e+01 1.13481684e+01 6.42112303e+00 -7.45682812e+00 -1.13151102e+01 3.05115318e+00 6.86474304e+01 1.01694313e+02 1.03190353e+02 7.80964737e+01 5.55714569e+01 5.09998322e+01 3.65439034e+01 2.70654831e+01 3.08314552e+01 3.58351250e+01 3.42513809e+01 3.04098988e+01 2.08945160e+01 1.07347498e+01 -3.68186646e+01 -7.32473297e+01 -1.02200912e+02 -9.73603516e+01 -6.10154991e+01 -2.19104424e+01 1.70014153e+01 1.60379848e+01 6.81495571e+00 1.90767813e+00 -1.16916525e+00 -8.53311062e+00 -1.27320633e+01 -1.51182508e+01 -2.48468189e+01 -1.94027920e+01 -1.70568199e+01 -1.32965279e+01 -1.98436203e+01 -2.40046406e+01 -7.83623743e+00 6.34913146e-01 6.60601091e+00 -1.43980670e+00 -1.94943924e+01 -5.83353043e+01 -1.10263206e+02 -1.29918976e+02 -1.31150269e+02 -1.13822487e+02 -1.27913795e+02 -9.57911148e+01 -5.87627602e+01 -1.45941582e+01 -1.29529791e+01 -1.55988369e+01 -2.56992683e+01 -3.14325848e+01 -2.54754066e+01 -1.10153780e+01 -1.38918715e+01 -2.15035534e+01 -3.89936333e+01 -4.04011803e+01 -4.47788849e+01 -6.68234587e+00 3.86531029e+01 2.32210712e+01 -1.86079216e+01 -6.31730270e+01 -7.80401764e+01 -9.23076630e+01 -1.38400574e+02 -1.62960068e+02 -1.52396347e+02 -1.23877823e+02 -7.72135696e+01 -8.41084747e+01 -9.82926559e+01 -1.17193626e+02 -1.22004120e+02 -1.05411507e+02 -1.04783607e+02 -1.03903587e+02 -1.08020012e+02 -9.27394333e+01 -7.92168503e+01 -8.31420670e+01 -1.19093567e+02 -1.65535461e+02 -2.02022766e+02 -2.15951065e+02 -1.34496277e+02 -5.79927101e+01 -1.61667080e+01 -5.23564262e+01 -9.41124039e+01 -9.65964127e+01 -1.06370865e+02 -1.03151344e+02 -1.05624969e+02 -9.38066864e+01 -9.06888657e+01 -8.29112473e+01 -9.04277191e+01 -9.24110794e+01 -6.74419632e+01 -2.55970364e+01 -1.48096905e+01 -4.04254417e+01 -7.15754700e+01 -9.57702560e+01 -1.20574242e+02 -1.24659233e+02 -1.03844444e+02 -1.00804092e+02 -1.27034775e+02 -1.27163269e+02 -1.07198700e+02 -8.32861023e+01 -7.96797638e+01 -8.94986420e+01 -9.51566315e+01 -1.03298019e+02 -1.00940651e+02 -1.09019516e+02 -1.08381714e+02 -1.07014313e+02 -9.09840317e+01 -8.89059525e+01 -9.34412231e+01 -1.30599136e+02 -1.73243668e+02 -1.64750061e+02 -1.34701248e+02 -1.01354042e+02 -1.16286972e+02 -1.20022522e+02 -1.29734055e+02 -1.41125595e+02 -1.51708862e+02 -1.55490845e+02 -1.76734222e+02 -1.87868683e+02 -1.85096039e+02 -1.46253784e+02 -1.15259285e+02 -1.12377831e+02 -1.22971733e+02 -1.03372078e+02 -7.66546555e+01 -6.92892227e+01 -7.83923492e+01 -1.07762939e+02 -1.04034111e+02 -1.10976555e+02 -1.16002937e+02 -1.31542480e+02 -1.39128204e+02 -1.34894226e+02 -1.16344559e+02 -1.21352173e+02 -1.27134369e+02 -1.34764236e+02 -1.30236221e+02 -1.36121460e+02 -1.44449768e+02 -1.71868500e+02 -1.99621262e+02 -1.97400696e+02 -1.85836243e+02 -1.68656036e+02 -1.70708527e+02 -1.54716370e+02 -1.40569077e+02 -1.50621506e+02 -2.03116699e+02 -2.37232285e+02 -2.38434692e+02 -1.93547409e+02 -1.69319031e+02 -1.75438416e+02 -1.87388016e+02 -1.88291092e+02 -1.75967224e+02 -1.93609009e+02 -2.29183777e+02 -2.42453934e+02 -2.17448883e+02 -1.78582504e+02 -1.83339096e+02 -1.85638367e+02 -1.87953613e+02 -1.83903320e+02 -1.87261169e+02 -2.00404541e+02 -2.10531143e+02 -2.18685211e+02 -2.02262878e+02 -1.93412109e+02 -1.94306854e+02 -2.33774582e+02 -2.79969635e+02 -2.85893402e+02 -2.52689560e+02 -2.13407394e+02 -2.07032257e+02 -1.94370804e+02 -1.90813141e+02 -2.01386124e+02 -2.49606369e+02 -2.82448364e+02 -3.16485565e+02 -3.18697540e+02 -2.87931305e+02 -2.54179428e+02 -2.14994888e+02 -2.44644821e+02 -2.66853882e+02 -2.36258377e+02 -1.73253021e+02 -1.45279327e+02 -1.79230042e+02 -2.13212723e+02 -2.07907974e+02 -2.00820450e+02 -1.97327454e+02 -1.96444046e+02 -1.93906738e+02 -1.92161804e+02 -1.89289627e+02 -1.88707825e+02 -1.87728668e+02 -1.90950378e+02 -1.86566391e+02 -1.92657944e+02 -1.96239212e+02 -2.21249557e+02 -2.42666443e+02 -2.39925873e+02 -2.14578125e+02 -1.82595047e+02 -2.12843201e+02 -2.51771835e+02 -2.30164841e+02 -1.69060623e+02 -1.67463165e+02 -2.38260117e+02 -2.81745880e+02 -2.56497742e+02 -2.23285919e+02 -2.39278931e+02 -2.73937805e+02 -2.83289948e+02 -2.68296967e+02 -2.40218262e+02 -2.40663239e+02 -2.43173340e+02 -2.41950760e+02 -2.43039154e+02 -2.20569061e+02 -2.02066650e+02 -2.26028488e+02 -2.74549774e+02 -2.99831024e+02 -2.87335327e+02 -2.64212433e+02 -2.88219666e+02 -3.09033295e+02 -3.14942291e+02 -2.94886353e+02 -2.65448029e+02 -2.69368622e+02 -2.72267548e+02 -2.79043274e+02 -2.65659088e+02 -2.72657349e+02 -2.93118286e+02 -3.02801788e+02 -3.01871765e+02 -2.72850006e+02 -2.58826355e+02 -2.47840714e+02 -2.49255234e+02 -2.53794617e+02 -2.18845520e+02 -1.80528976e+02 -1.92743011e+02 -2.44491714e+02 -2.85598083e+02 -2.73376068e+02 -2.53095856e+02 -2.68787933e+02 -2.96505157e+02 -2.98250732e+02 -2.80172119e+02 -2.59324280e+02 -2.52914322e+02 -2.52213852e+02 -2.51561798e+02 -2.60462402e+02 -2.63968262e+02 -2.68362976e+02 -2.79229889e+02 -2.85293884e+02 -2.80446075e+02 -2.68110321e+02 -2.58896576e+02 -2.57135071e+02 -2.58925842e+02 -2.43500122e+02 -2.25319901e+02 -2.47744324e+02 -2.90678741e+02 -3.12533173e+02 -2.87389221e+02 -2.63352997e+02 -2.51505539e+02 -2.46919922e+02 -2.44224869e+02 -2.50576859e+02 -2.58068604e+02 -2.54383179e+02 -2.56202850e+02 -2.54059158e+02 -2.57874268e+02 -2.53803329e+02 -2.53075363e+02 -2.49831253e+02 -2.60205017e+02 -2.68007355e+02 -2.64092041e+02 -2.53571808e+02 -2.49501633e+02 -2.62539185e+02 -2.75280548e+02 -2.82876709e+02 -2.94512665e+02 -3.11643616e+02 -3.13400055e+02 -3.01867310e+02 -3.00940948e+02 -3.34891266e+02 -3.55759460e+02 -3.41262299e+02 -3.17091980e+02 -3.21475098e+02 -3.40970398e+02 -3.44443573e+02 -3.25847656e+02 -3.10143219e+02 -3.05961700e+02 -3.03998749e+02 -3.08893799e+02 -3.10186798e+02 -3.09796997e+02 -3.02455841e+02 -3.15217133e+02 -3.28632599e+02 -3.36789978e+02 -3.21873352e+02 -3.08366241e+02 -3.11612549e+02 -3.25332611e+02 -3.14093903e+02 -2.90182556e+02 -2.78526642e+02 -2.86935608e+02 -3.00184906e+02 -2.95630615e+02 -2.96696228e+02 -2.96346741e+02 -2.95541565e+02 -2.93448029e+02 -2.95080261e+02 -3.01746674e+02 -3.00461395e+02 -2.97042542e+02 -2.91958954e+02 -2.93955383e+02 -2.98637451e+02 -2.98074799e+02 -3.08001862e+02 -3.18123016e+02 -3.18443115e+02 -3.07439819e+02 -2.91401154e+02 -2.88674011e+02 -2.87843628e+02 -2.80464447e+02 -2.70263947e+02 -2.71432190e+02 -2.81387390e+02 -2.94130127e+02 -2.97129700e+02 -2.97579102e+02 -3.10809204e+02 -3.24479248e+02 -3.27860657e+02 -3.17015717e+02 -3.09337555e+02 -3.09156372e+02 -3.07322937e+02 -3.02876495e+02 -3.03858704e+02 -2.99268097e+02 -2.91586639e+02 -2.95982178e+02 -3.08936096e+02 -3.17985474e+02 -3.14491272e+02 -3.16349701e+02 -3.31526978e+02 -3.39975952e+02 -3.35074768e+02 -3.19364471e+02 -3.16266388e+02 -3.20854034e+02 -3.22323853e+02 -3.15443268e+02 -3.06427460e+02 -3.07773376e+02 -3.13094849e+02 -3.14814209e+02 -3.11583984e+02 -3.05735443e+02 -3.02552551e+02 -3.00999115e+02 -3.01573425e+02 -3.04655731e+02 -3.04162994e+02 -3.03518158e+02 -3.07381805e+02 -3.12943085e+02 -3.15290680e+02 -3.11938538e+02 -3.08892242e+02 -3.11212067e+02 -3.02924744e+02 -2.73447205e+02 -2.65489960e+02 -2.31841522e+02 9.50462112e+01 4.98334869e+02 -63534160. -51011248. -1.99611206e+03 -9.82385620e+02 -4.08544128e+02 -4.17672607e+02 -1.06506805e+02 -1.96730053e+00 -44103736. -500997376. -95892992. -58033076. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -669568320. -669568320. -334784160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.39530163e+09 -56100592. -69213064. 231219792. -1.48288586e+03 -7.30297607e+02 -3.90970184e+02 -5.77277344e+02 -3.03167877e+02 -3.08818268e+02 -2.85638947e+02 -2.87961609e+02 -2.90482147e+02 -2.87603790e+02 -2.85677338e+02 -2.88873810e+02 -2.93370605e+02 -2.90934448e+02 -2.82860260e+02 -2.78859161e+02 -2.84334045e+02 -2.96327026e+02 -2.97028900e+02 -2.87158569e+02 -2.73758606e+02 -2.69806213e+02 -2.75083893e+02 -2.73411743e+02 -2.67156342e+02 -2.67292908e+02 -2.73034454e+02 -2.78069000e+02 -2.69515778e+02 -2.53464478e+02 -2.49293976e+02 -2.61605621e+02 -2.75818268e+02 -2.83717194e+02 -2.84156555e+02 -2.88916290e+02 -2.96605469e+02 -3.00020966e+02 -2.89348450e+02 -2.61034454e+02 -2.42346497e+02 -2.48560883e+02 -2.69232025e+02 -2.85635864e+02 -2.85314545e+02 -2.77045410e+02 -2.67787598e+02 -2.70546356e+02 -2.66228943e+02 -2.59610229e+02 -2.65568634e+02 -2.88032501e+02 -3.12984650e+02 -3.07996613e+02 -2.70304047e+02 -2.55013733e+02 -2.66154968e+02 -2.90866516e+02 -2.86799316e+02 -2.62805542e+02 -2.60834686e+02 -2.81187744e+02 -3.05966492e+02 -2.99439728e+02 -2.63702393e+02 -2.37311600e+02 -2.44855804e+02 -2.65339294e+02 -2.74505890e+02 -2.69159821e+02 -2.69737579e+02 -2.84940918e+02 -3.00181396e+02 -2.91456818e+02 -2.79720154e+02 -2.83498627e+02 -2.98821350e+02 -3.05091309e+02 -2.96351379e+02 -2.80209290e+02 -2.62567810e+02 -2.55617584e+02 -2.66001526e+02 -2.74230896e+02 -2.72311920e+02 -2.89119568e+02 -3.18781006e+02 -3.33036530e+02 -3.03166046e+02 -2.53601685e+02 -2.26466660e+02 -2.40012527e+02 -2.79078888e+02 -3.22599304e+02 -3.36428497e+02 -3.26192871e+02 -3.16123413e+02 -3.23701965e+02 -3.10928162e+02 -2.73049347e+02 -2.42050018e+02 -2.50920853e+02 -2.83087769e+02 -2.94201996e+02 -2.83095337e+02 -2.56774567e+02 -2.49329803e+02 -2.67236938e+02 -2.79525787e+02 -2.78850708e+02 -2.73043549e+02 -2.92271027e+02 -3.31210876e+02 -3.38272156e+02 -3.05077057e+02 -2.63504974e+02 -2.62283722e+02 -2.90044647e+02 -3.15584473e+02 -3.18003052e+02 -2.91853119e+02 -2.61424164e+02 -2.47550110e+02 -2.63151428e+02 -2.59370880e+02 -2.36903778e+02 -2.32828339e+02 -2.63565460e+02 -2.95858398e+02 -2.94504944e+02 -2.63310547e+02 -2.47593430e+02 -2.64104431e+02 -2.80050690e+02 -2.90296478e+02 -2.74142181e+02 -2.82469025e+02 -3.06415588e+02 -3.17801819e+02 -2.79749542e+02 -2.01262970e+02 -1.63606384e+02 -1.91153931e+02 -2.40808212e+02 -2.53514420e+02 -2.40842911e+02 -2.21006012e+02 -2.29433136e+02 -2.26830856e+02 -2.04997940e+02 -1.66912094e+02 -1.56800598e+02 -1.96160172e+02 -2.70573395e+02 -3.09088501e+02 -2.64111694e+02 -2.19245316e+02 -2.15216919e+02 -2.38452103e+02 -2.15107834e+02 -1.57940979e+02 -1.64254684e+02 -2.16625351e+02 -2.69499359e+02 -2.33111084e+02 -1.52018829e+02 -1.02281990e+02 -1.30856369e+02 -1.88737030e+02 -2.22639145e+02 -2.21614822e+02 -2.33542343e+02 -2.44810959e+02 -2.30614349e+02 -1.79159378e+02 -1.20739067e+02 -1.54048553e+02 -2.08245102e+02 -2.60795532e+02 -2.48689209e+02 -2.17838043e+02 -1.89018372e+02 -1.73728455e+02 -1.67571472e+02 -1.47471207e+02 -1.15781410e+02 -1.36785583e+02 -1.95269180e+02 -2.51787659e+02 -2.31913940e+02 -1.60485718e+02 -1.20144897e+02 -1.37338196e+02 -1.97912704e+02 -2.20729126e+02 -2.15783737e+02 -2.21554367e+02 -2.79470093e+02 -3.02436188e+02 -2.58802826e+02 -1.79640198e+02 -1.61107803e+02 -1.88803635e+02 -2.49323563e+02 -2.76029785e+02 -2.66988617e+02 -2.36422943e+02 -2.08440781e+02 -2.09700211e+02 -1.86438354e+02 -1.57379990e+02 -1.77885849e+02 -2.24513885e+02 -2.43306625e+02 -2.36047272e+02 -1.89786896e+02 -1.83345383e+02 -1.95842453e+02 -2.12388336e+02 -2.14189651e+02 -1.84395660e+02 -2.06560364e+02 -2.42748154e+02 -2.66299866e+02 -2.67445465e+02 -2.04977753e+02 -1.67812485e+02 -2.01247635e+02 -2.70774445e+02 -2.81763397e+02 -2.20446136e+02 -1.61108795e+02 -1.64138992e+02 -2.05396729e+02 -2.06058456e+02 -1.75075272e+02 -1.63225800e+02 -2.05857285e+02 -2.26766464e+02 -1.91737686e+02 -1.64806091e+02 -2.07745468e+02 -2.29222458e+02 -2.05006607e+02 -1.77566360e+02 -1.41296997e+02 -1.67490219e+02 -1.35707840e+02 -1.28886612e+02 -1.26769463e+02 -1.26499474e+02 -1.01262405e+02 -8.24442825e+01 -1.40702713e+02 -1.73519669e+02 -1.87248123e+02 -1.35858749e+02 -1.54257141e+02 -1.53300461e+02 -1.23292290e+02 -7.52954483e+01 -6.51149445e+01 -1.45977386e+02 -1.99554764e+02 -2.05819366e+02 -1.34310684e+02 -1.06164894e+02 -1.12527855e+02 -1.36991714e+02 -1.48441788e+02 -9.88494034e+01 -1.18778343e+02 -1.50069656e+02 -2.29399811e+02 -2.58953552e+02 -2.41333694e+02 -1.82042084e+02 -1.32232224e+02 -1.64034836e+02 -2.09188904e+02 -2.31490784e+02 -2.00707581e+02 -2.20837219e+02 -2.18154892e+02 -1.66608459e+02 -1.12447281e+02 -1.10471634e+02 -2.07672379e+02 -2.29717941e+02 -1.86014404e+02 -1.14941635e+02 -1.37099915e+02 -1.80320328e+02 -1.93236603e+02 -1.79244293e+02 -1.40290421e+02 -1.50971130e+02 -1.25574203e+02 -1.63684677e+02 -1.76610474e+02 -1.79550858e+02 -1.44116394e+02 -1.29024139e+02 -1.61019348e+02 -1.98044525e+02 -1.99269241e+02 -2.12952866e+02 -2.82935852e+02 -3.17418884e+02 -3.08815186e+02 -2.69522003e+02 -2.69603882e+02 -2.99879486e+02 -3.22774109e+02 -2.89796234e+02 -2.27706177e+02 -1.93298126e+02 -1.94549942e+02 -1.72595093e+02 -1.48845139e+02 -9.54755325e+01 -8.60414810e+01 -7.14677963e+01 -1.19844818e+02 -1.50514389e+02 -1.61143448e+02 -1.41289215e+02 -1.54534836e+02 -1.81595963e+02 -2.11172592e+02 -2.03391602e+02 -1.98348053e+02 -2.41336639e+02 -2.81730225e+02 -2.57819763e+02 -1.90971542e+02 -1.68438873e+02 -1.70238205e+02 -1.23550797e+02 -8.07333984e+01 -5.22358971e+01 -1.11841248e+02 -1.11878853e+02 -1.25692970e+02 -1.57928802e+02 -1.62494812e+02 -1.17815430e+02 -1.94038391e+01 -1.28340542e+00 -8.12989044e+01 -1.59952469e+02 -1.49494049e+02 -9.16565247e+01 -4.10019722e+01 -7.52232895e+01 -1.16790779e+02 -1.66494690e+02 -1.60288986e+02 -1.13569679e+02 -7.25747147e+01 -1.09713173e+01 -5.53365183e+00 -1.57978761e+00 6.67615604e+00 1.48422775e+01 8.62587357e+00 -6.67242126e+01 -7.76441193e+01 -7.55385666e+01 -7.29665070e+01 -6.01415787e+01 -1.73029938e+01 1.01333626e+02 1.35658524e+02 5.71463318e+01 -1.02122314e+02 -1.81857544e+02 -8.68037415e+01 4.04292831e+01 4.09555855e+01 -9.52771225e+01 -2.38472824e+02 -2.09825897e+02 -7.50487595e+01 1.30598640e+01 1.36095505e+01 -7.99429092e+01 -6.97294235e+01 -1.68111916e+01 3.77261810e+01 4.44178352e+01 -2.60618439e+01 -2.73546066e+01 1.38535976e+01 4.92510414e+01 4.59113045e+01 -1.04633999e+00 2.62381020e+01 3.16532135e+01 -5.08853989e+01 -1.51473251e+02 -1.51556976e+02 1.80072346e+01 1.36555588e+02 1.07111542e+02 -2.95202770e+01 -1.17606667e+02 -9.23108368e+01 3.48292637e+00 5.88688354e+01 6.99693146e+01 -1.78099499e+01 -2.26222858e+01 -1.70788708e+01 2.13556576e+01 4.98099785e+01 -1.90138733e+00 -4.18547630e+01 -1.16980530e+02 -1.06037010e+02 -6.63193970e+01 5.41135740e+00 1.05636475e+02 1.34726120e+02 6.45054855e+01 -9.31891632e+01 -1.77313644e+02 -1.08109947e+02 5.10957756e+01 1.09133423e+02 -2.01031876e+01 -1.66667389e+02 -1.67473877e+02 -1.50164614e+01 5.70633926e+01 4.84902763e+01 -3.64761734e+01 -3.53119659e+01 1.30375271e+01 7.75238953e+01 1.24845726e+02 1.25746887e+02 1.61220657e+02 1.55795197e+02 9.45743561e+01 8.76522720e-01 -3.63045959e+01 3.85120049e+01 1.10748207e+02 8.66647415e+01 -1.47241507e+01 -1.13982170e+02 -8.04965591e+01 3.48324280e+01 7.57118759e+01 3.27498436e+01 -6.91274567e+01 -5.27016869e+01 3.70639648e+01 1.00725105e+02 1.56913696e+02 9.08869629e+01 1.06685051e+02 6.72441330e+01 7.19647675e+01 8.68114090e+01 1.07824013e+02 1.53454453e+02 1.01736343e+02 5.13212318e+01 -1.96142807e+01 1.46568089e+01 1.05589775e+02 1.91875793e+02 1.35263428e+02 3.11328888e+01 -4.36635056e+01 -4.69056931e+01 1.70637093e+01 5.08712769e+01 7.27761536e+01 4.26418762e+01 6.49485626e+01 1.03367195e+02 1.57170334e+02 2.03839218e+02 1.87577621e+02 9.81054840e+01 2.76999397e+01 2.50330124e+01 6.73742142e+01 1.06676544e+02 1.64973450e+02 1.87854935e+02 1.05344582e+02 -2.49559498e+01 -6.80611267e+01 1.65370483e+01 1.32007950e+02 1.33684235e+02 2.18002338e+01 -9.16475677e+01 -7.06778107e+01 6.70768814e+01 2.03394302e+02 2.51111618e+02 1.71000549e+02 9.68212967e+01 1.02066788e+02 1.35983994e+02 1.68637451e+02 1.04341743e+02 1.13480270e+02 9.64830322e+01 7.04783478e+01 4.92619934e+01 6.16248550e+01 1.36295471e+02 1.26129776e+02 3.75356712e+01 -5.99510765e+01 -4.22160950e+01 1.02857422e+02 2.08431717e+02 1.70290085e+02 5.41530914e+01 -2.31901245e+01 -1.52728834e+01 9.12383881e+01 1.88958023e+02 2.33410965e+02 1.47559402e+02 1.01701691e+02 5.72695312e+01 6.23834152e+01 7.11761322e+01 5.63190880e+01 6.01335602e+01 2.15198755e+00 -2.64618320e+01 -2.60089188e+01 1.85294952e+01 1.12681412e+02 1.51072556e+02 9.50844879e+01 1.15372314e+01 -1.68495121e+01 4.66072197e+01 1.30433960e+02 1.26409721e+02 6.22018204e+01 -1.67928505e+01 -2.72999420e+01 6.79866486e+01 1.48761307e+02 1.72756989e+02 9.70896072e+01 3.48029556e+01 5.47450066e+01 1.05741989e+02 1.74056396e+02 1.85394165e+02 1.77413193e+02 1.34325455e+02 7.10473633e+01 6.68602753e+01 1.33003128e+02 2.40580658e+02 2.72601288e+02 1.96652603e+02 1.13418709e+02 6.49908447e+01 1.07262062e+02 1.79061172e+02 2.15962372e+02 1.98082474e+02 1.38573685e+02 1.43181549e+02 1.83218262e+02 2.25674026e+02 2.29102951e+02 1.60689026e+02 1.15245964e+02 1.25968597e+02 1.75396454e+02 2.52056168e+02 2.49913666e+02 2.47831192e+02 2.09891602e+02 1.71926773e+02 1.49679672e+02 1.37650879e+02 1.94547958e+02 2.35060211e+02 2.19610092e+02 1.70745956e+02 1.19070595e+02 1.55425446e+02 2.17212952e+02 2.56046722e+02 1.97619858e+02 8.47172928e+01 2.23147697e+01 8.33466644e+01 1.74735870e+02 2.14736237e+02 1.10028961e+02 -3.61218605e+01 -1.35326233e+02 -4.80897034e+02 -7.17505981e+02 -2.95759253e+03 -4.05863550e+03 4.74496246e+02 5.68807251e+02 7.45609192e+02 1.02593872e+03 1.34492847e+03 6.48419128e+02 7.80030762e+03 2.15313691e+04 -195099296. 783052096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -262827248. 49404384. -287266112. 74028328. -2.31381582e+04 -9.24226660e+03 -2.94832153e+03 -4.31397766e+02 -9.27642059e+00 4.74778671e+01 8.31040878e+01 1.42813034e+02 2.36869354e+02 2.70830627e+02 2.53525681e+02 1.86955963e+02 1.50062561e+02 1.60448517e+02 2.14824936e+02 2.81169952e+02 2.82683472e+02 2.61420380e+02 2.38852295e+02 2.38701004e+02 2.41997986e+02 2.20781067e+02 2.49438080e+02 2.43564209e+02 1.93992477e+02 1.57969574e+02 1.91147354e+02 2.85747253e+02 3.31049255e+02 2.73210693e+02 1.99901886e+02 1.56829453e+02 1.82178513e+02 2.69173218e+02 3.37667175e+02 3.72043152e+02 3.01526337e+02 2.56027618e+02 2.51270370e+02 3.00798218e+02 3.27437927e+02 3.03972595e+02 2.99976013e+02 2.69350464e+02 2.37890900e+02 2.23352692e+02 2.52053162e+02 3.40066895e+02 3.43853851e+02 2.77674286e+02 1.90693375e+02 1.72463303e+02 2.38707825e+02 3.06370361e+02 3.05264679e+02 2.55304474e+02 2.34446869e+02 2.76765015e+02 3.50073303e+02 3.76201202e+02 3.48739410e+02 2.68745789e+02 2.14959915e+02 2.17621857e+02 2.66750488e+02 3.29254730e+02 3.71298828e+02 3.92484100e+02 3.71389221e+02 3.34559601e+02 2.91858673e+02 2.73956146e+02 2.86034851e+02 2.83820953e+02 2.41411499e+02 2.01147644e+02 1.99585876e+02 2.51709137e+02 2.88950409e+02 2.85594269e+02 2.62380096e+02 2.29156891e+02 2.06820190e+02 2.28335648e+02 2.83684937e+02 3.15005219e+02 2.81152832e+02 2.41868271e+02 2.49775528e+02 2.75488831e+02 2.81182892e+02 2.66156738e+02 2.78749573e+02 2.74864044e+02 2.56191193e+02 2.41295700e+02 2.53963394e+02 3.06879913e+02 3.07677246e+02 2.62262360e+02 2.00689392e+02 1.80398941e+02 2.22739136e+02 2.66957825e+02 2.90829468e+02 2.78599976e+02 2.63932800e+02 2.60576050e+02 2.73997040e+02 2.97239899e+02 3.09957367e+02 2.85380005e+02 2.43502747e+02 2.29412140e+02 2.43736359e+02 2.59391235e+02 2.62586121e+02 2.82726471e+02 2.82603271e+02 2.50562149e+02 2.11872971e+02 2.12503922e+02 2.61197388e+02 2.82056488e+02 2.55698593e+02 2.19530579e+02 2.17209747e+02 2.56323425e+02 2.91969818e+02 3.01819122e+02 2.89751801e+02 2.61165222e+02 2.38425613e+02 2.44126770e+02 2.72919281e+02 2.95420929e+02 2.78450073e+02 2.48701813e+02 2.38429398e+02 2.49310837e+02 2.66141174e+02 2.75946136e+02 2.93516815e+02 2.99456879e+02 2.91566284e+02 2.77649841e+02 2.76599823e+02 2.96607544e+02 3.04910095e+02 2.87193817e+02 2.51099228e+02 2.29705231e+02 2.39222916e+02 2.73834015e+02 2.98803864e+02 2.94912689e+02 2.78295471e+02 2.71869141e+02 2.78597961e+02 2.79535278e+02 2.89117065e+02 2.85478973e+02 2.82781921e+02 2.73733276e+02 2.60527130e+02 2.56910187e+02 2.53881683e+02 2.73202911e+02 2.80300751e+02 2.69679779e+02 2.60794983e+02 2.65826691e+02 2.90713043e+02 2.98386658e+02 2.92260132e+02 2.80128632e+02 2.73500275e+02 2.72985260e+02 2.79177338e+02 2.82227570e+02 2.83616638e+02 2.73398956e+02 2.76853790e+02 2.83238831e+02 2.93619537e+02 3.02635498e+02 3.08718842e+02 3.13064819e+02 3.03504364e+02 2.89263916e+02 2.80974884e+02 2.81408142e+02 2.88204254e+02 2.89239532e+02 2.81298370e+02 2.72833435e+02 2.69311035e+02 2.79145508e+02 2.92113586e+02 2.97760925e+02 2.95115448e+02 2.90008484e+02 2.87770477e+02 2.87882416e+02 2.88954742e+02 2.91297302e+02 2.89228210e+02 2.85916077e+02 2.84293762e+02 2.86476685e+02 2.87293610e+02 2.87715485e+02 2.88440735e+02 2.88505676e+02 2.87175720e+02 2.86198029e+02 2.86198517e+02 2.86092194e+02 2.85523926e+02 2.85120972e+02 2.85234131e+02 2.85568573e+02 2.85709351e+02 2.85569122e+02 2.84771973e+02 2.84190247e+02 2.84830231e+02 2.86366913e+02 2.87070923e+02 2.85694092e+02 2.84459320e+02 2.84803864e+02 2.84878357e+02 2.84774902e+02 2.84997559e+02 2.84999054e+02 2.84787445e+02 2.84771149e+02 2.84758179e+02 2.86205994e+02 2.86415771e+02 2.88738892e+02 2.88342133e+02 2.88450378e+02 2.85553772e+02 2.85838654e+02 2.85795227e+02 2.85294739e+02 2.85027466e+02 2.82563477e+02 2.81427521e+02 2.79519501e+02 2.80276215e+02 2.82548492e+02 2.82160248e+02 2.82712769e+02 2.83788177e+02 2.85420593e+02 2.83934143e+02 2.82197021e+02 2.81287781e+02 2.84241760e+02 2.84114655e+02 2.84379639e+02 2.83763062e+02 2.85897858e+02 2.87388885e+02 2.88804962e+02 2.90236053e+02 2.87462311e+02 2.86593201e+02 2.84145966e+02 2.86743835e+02 2.87366272e+02 2.88815704e+02 2.87518494e+02 2.85644775e+02 2.80798828e+02 2.78983887e+02 2.82150726e+02 2.85922394e+02 2.84656006e+02 2.81546295e+02 2.80264679e+02 2.82111328e+02 2.79244446e+02 2.79211761e+02 2.81062469e+02 2.83299011e+02 2.81748932e+02 2.80218903e+02 2.83046021e+02 2.79757019e+02 2.73774597e+02 2.70344208e+02 2.74585144e+02 2.77128601e+02 2.75903473e+02 2.72115051e+02 2.72956421e+02 2.72279419e+02 2.74058228e+02 2.74136993e+02 2.72664551e+02 2.68302094e+02 2.69790924e+02 2.70455048e+02 2.75035706e+02 2.73617096e+02 2.79655212e+02 2.88907745e+02 2.85819122e+02 2.79393097e+02 2.65071777e+02 2.68075348e+02 2.68985840e+02 2.67991180e+02 2.67791199e+02 2.61924042e+02 2.62002533e+02 2.62779663e+02 2.62564453e+02 2.59466125e+02 2.56461914e+02 2.62728638e+02 2.63808685e+02 2.63853912e+02 2.62620148e+02 2.67018921e+02 2.63169403e+02 2.60691681e+02 2.57994690e+02 2.51386093e+02 2.49398621e+02 2.52080109e+02 2.63252350e+02 2.66404358e+02 2.61860840e+02 2.54775146e+02 2.50831406e+02 2.51793289e+02 2.62006439e+02 2.73859131e+02 2.70446411e+02 2.60217896e+02 2.45197571e+02 2.45328812e+02 2.48656891e+02 2.56199524e+02 2.61760010e+02 2.64886292e+02 2.67765503e+02 2.70700775e+02 2.67550018e+02 2.64447388e+02 2.53881073e+02 2.55029358e+02 2.60636078e+02 2.62003937e+02 2.57153687e+02 2.56936157e+02 2.61758789e+02 2.64489532e+02 2.61710876e+02 2.59164001e+02 2.58638855e+02 2.71639252e+02 2.88126678e+02 2.86260071e+02 2.65406860e+02 2.43309799e+02 2.54657608e+02 2.71463165e+02 2.75800964e+02 2.65882294e+02 2.47874466e+02 2.55924057e+02 2.63999786e+02 2.71225311e+02 2.66831116e+02 2.59141876e+02 2.65068207e+02 2.80252869e+02 2.92787292e+02 2.77926941e+02 2.49680481e+02 2.39042801e+02 2.49139694e+02 2.54577194e+02 2.52796661e+02 2.45558090e+02 2.41452850e+02 2.53141556e+02 2.65642731e+02 2.63811005e+02 2.47441345e+02 2.28364059e+02 2.30932449e+02 2.34638489e+02 2.39668579e+02 2.22299484e+02 1.94205246e+02 1.84708008e+02 2.07412949e+02 2.31173203e+02 2.39182312e+02 2.35116089e+02 2.52419678e+02 2.53167511e+02 2.19060516e+02 1.79149200e+02 1.71394547e+02 2.00416885e+02 2.29207138e+02 2.28729462e+02 2.28752609e+02 2.08147705e+02 1.93670181e+02 1.99799133e+02 2.23952271e+02 2.48673340e+02 2.43757843e+02 2.45006546e+02 2.14773041e+02 1.75742126e+02 1.72210800e+02 1.91407913e+02 2.27356415e+02 2.48367981e+02 2.63605072e+02 2.62679626e+02 2.32332779e+02 2.20430191e+02 2.09613617e+02 2.09669495e+02 2.09661224e+02 2.00711761e+02 1.86666840e+02 1.79150879e+02 1.85407364e+02 2.18384674e+02 3.22925262e+02 3.87735229e+02 3.81647888e+02 2.75821564e+02 2.29171967e+02 2.02439673e+03 3.45158252e+03 7.62473389e+02 6.98943176e+02 6.73149658e+02 6.78500305e+02 6.54582214e+02 4.18550415e+02 6.68868042e+02 2.07419174e+02 -2.08526169e+02 -8.95540039e+03 -2.30549746e+04 -177720176. -470063296. 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. 0. 0. 0. 0. 0. 0. -105792512. 89272640. -35849148. -31183894. -633875520. 3.12474316e+04 1.24188984e+04 3.82409814e+03 6.55268616e+02 2.94908142e+02 2.04974396e+02 2.14562927e+02 2.10431213e+02 2.11983475e+02 2.08075668e+02 2.15128983e+02 2.20920776e+02 2.21461075e+02 2.18777466e+02 1.86864258e+02 1.76637100e+02 1.82099838e+02 2.10743851e+02 2.05750290e+02 1.81609100e+02 1.45682449e+02 1.30524811e+02 1.33302460e+02 1.28962524e+02 1.25459984e+02 1.05733574e+02 9.59161835e+01 8.63001785e+01 8.93167725e+01 8.46248245e+01 8.61192245e+01 8.80405884e+01 8.76607666e+01 8.22694397e+01 7.61625443e+01 8.59189453e+01 9.31220932e+01 9.05323944e+01 8.18139572e+01 7.33943024e+01 6.83432236e+01 6.85409622e+01 8.23835602e+01 1.17409492e+02 1.44223465e+02 1.47773102e+02 1.31149689e+02 1.07249741e+02 9.20180054e+01 8.04402695e+01 9.42398300e+01 1.12956314e+02 1.15230309e+02 9.70698776e+01 7.99168167e+01 7.12981186e+01 5.98695488e+01 7.27206039e+01 9.90543442e+01 1.15246880e+02 1.30325043e+02 1.35713058e+02 1.35168442e+02 1.21072876e+02 1.05238434e+02 1.10947693e+02 1.04340157e+02 6.60061264e+01 5.04496651e+01 5.53371582e+01 8.06529770e+01 8.99045792e+01 8.25803070e+01 1.10555672e+02 1.50649811e+02 1.46166046e+02 1.23750885e+02 9.19569016e+01 1.48015991e+02 1.96358215e+02 2.03673599e+02 1.61135925e+02 1.37190842e+02 1.38554108e+02 1.45673599e+02 1.28412949e+02 1.28807617e+02 1.59444122e+02 1.91249527e+02 1.79845276e+02 1.25059349e+02 8.22557144e+01 6.36685867e+01 7.32022781e+01 8.60711746e+01 9.79985657e+01 6.12489624e+01 3.05891209e+01 4.64721603e+01 8.99569092e+01 9.65229034e+01 6.73187866e+01 4.30744743e+01 8.92348709e+01 1.23000641e+02 1.23970398e+02 7.57663879e+01 3.51014328e+01 1.98811703e+01 2.09384174e+01 2.08053989e+01 2.98549423e+01 3.80283241e+01 4.42814217e+01 3.74922714e+01 3.80648956e+01 4.83654900e+01 5.46379471e+01 5.38532372e+01 4.23071442e+01 4.45413437e+01 4.14292221e+01 4.66655121e+01 8.38555145e+01 1.27113945e+02 1.19527351e+02 8.07790833e+01 3.98113976e+01 7.80123749e+01 1.22694046e+02 1.20864738e+02 9.05319977e+01 5.42143402e+01 5.39211044e+01 4.90278854e+01 3.41347084e+01 4.58587265e+01 5.38642616e+01 5.35921478e+01 2.75305252e+01 1.81757963e+00 2.13580203e+00 1.88607025e+01 4.35195351e+01 3.77490387e+01 3.64075737e+01 3.01624260e+01 4.64420395e+01 8.74022598e+01 1.33110474e+02 1.35988632e+02 1.02193359e+02 5.83185081e+01 9.03715820e+01 1.27016190e+02 1.20585709e+02 6.99449768e+01 2.33349323e+01 2.37309608e+01 2.88102016e+01 3.20360489e+01 3.16354866e+01 3.32374878e+01 3.06110134e+01 2.46067524e+01 1.73934860e+01 4.50352898e+01 7.11163559e+01 6.82351074e+01 3.38433113e+01 -1.36644733e+00 -4.64977407e+00 -7.25152016e+00 2.45805683e+01 5.67977562e+01 5.52720871e+01 2.81233444e+01 6.31131887e+00 9.42052078e+00 -6.08109570e+00 2.01675892e+01 6.40199509e+01 7.87668915e+01 4.37477226e+01 2.61695409e+00 2.05396485e+00 3.62841558e+00 -1.39454496e+00 -6.46057081e+00 5.35400391e+00 8.71389198e+00 4.87517395e+01 8.48506165e+01 8.30308990e+01 3.43142128e+01 -9.92799950e+00 3.13715959e+00 6.03906155e+00 4.42100868e+01 7.04007492e+01 7.02296066e+01 1.54665194e+01 -3.57656250e+01 -3.50401459e+01 -2.55771656e+01 -1.45923920e+01 -2.06943512e+01 -3.29189644e+01 -4.33751373e+01 -4.71783638e+01 -4.69663315e+01 -4.78132019e+01 -5.65030937e+01 -5.41913185e+01 -7.21343231e+01 -8.19690933e+01 -9.47946701e+01 -9.26993484e+01 -8.29481049e+01 -8.90051193e+01 -9.04799728e+01 -8.88542099e+01 -7.89215164e+01 -7.20229263e+01 -8.19129639e+01 -7.68658600e+01 -7.78319321e+01 -8.25773315e+01 -1.02193939e+02 -1.10700989e+02 -1.00892876e+02 -9.09019241e+01 -8.03750305e+01 -8.95469513e+01 -7.49938660e+01 -8.20497360e+01 -6.27028656e+01 -6.00044174e+01 -5.41183815e+01 -8.06409073e+01 -1.13421356e+02 -9.56916428e+01 -4.82058983e+01 -1.16945686e+01 -2.46793232e+01 -4.51854515e+01 -5.41075325e+01 -5.15779610e+01 -4.79400749e+01 -3.91941948e+01 -4.14651985e+01 -4.98191338e+01 -6.19262314e+01 -7.29378510e+01 -9.05046158e+01 -9.73725357e+01 -9.15977478e+01 -7.23977509e+01 -6.41635742e+01 -6.17588387e+01 -6.95802917e+01 -7.42857590e+01 -9.00202713e+01 -9.55560913e+01 -1.02281952e+02 -8.46165924e+01 -5.28551216e+01 -2.13293285e+01 -3.21582069e+01 -5.39032288e+01 -8.66817398e+01 -9.12475357e+01 -9.79524307e+01 -7.32406082e+01 -5.05352783e+01 -3.50201912e+01 -3.70173950e+01 -6.12119789e+01 -8.51105652e+01 -1.21692375e+02 -1.10797813e+02 -9.76102295e+01 -8.74193954e+01 -9.82663498e+01 -1.08882004e+02 -1.18741356e+02 -1.13076424e+02 -1.02978874e+02 -9.70568008e+01 -8.80059509e+01 -8.77314301e+01 -5.07152138e+01 -2.45760689e+01 -4.05646477e+01 -8.32187195e+01 -1.22631699e+02 -1.05399017e+02 -8.91451874e+01 -9.55235443e+01 -1.00977394e+02 -8.54940414e+01 -5.49521599e+01 -5.67923431e+01 -8.81713104e+01 -1.23421440e+02 -1.07644997e+02 -1.04513649e+02 -1.11214981e+02 -1.38445251e+02 -1.42729248e+02 -1.38457764e+02 -1.23224350e+02 -1.34057739e+02 -1.52270996e+02 -1.53201797e+02 -1.49110123e+02 -1.41174271e+02 -1.54689377e+02 -1.31477615e+02 -1.05486153e+02 -1.02481697e+02 -9.08090591e+01 -6.43121109e+01 -3.24924774e+01 -3.11152897e+01 -5.51145058e+01 -5.31742325e+01 -7.99384842e+01 -8.66408157e+01 -1.19637878e+02 -1.48025742e+02 -1.90935196e+02 -1.98419464e+02 -1.89303253e+02 -1.78134491e+02 -1.76075623e+02 -1.70353394e+02 -1.67270874e+02 -1.69802139e+02 -1.85828217e+02 -1.59231277e+02 -1.21754555e+02 -1.03027550e+02 -1.10981659e+02 -1.40896454e+02 -1.42824234e+02 -1.50310135e+02 -1.68334656e+02 -1.51057007e+02 -1.52229523e+02 -1.40791977e+02 -1.45857788e+02 -1.28787567e+02 -9.97230682e+01 -1.20861008e+02 -1.52970642e+02 -1.67373428e+02 -1.34407364e+02 -1.21368828e+02 -1.37893265e+02 -1.77026749e+02 -1.55293076e+02 -1.29898224e+02 -1.19255653e+02 -1.39205032e+02 -1.59264420e+02 -1.28688629e+02 -1.04943214e+02 -1.08915298e+02 -1.52156250e+02 -1.85244141e+02 -1.70312637e+02 -1.49944504e+02 -1.78415665e+02 -2.17846191e+02 -1.95862808e+02 -1.49205521e+02 -1.24543518e+02 -1.38949738e+02 -1.49653458e+02 -1.51016190e+02 -1.30740479e+02 -1.11264511e+02 -1.18855629e+02 -1.62761841e+02 -1.99981400e+02 -1.97389587e+02 -1.88776031e+02 -1.82929520e+02 -1.91691208e+02 -1.89754654e+02 -1.84908737e+02 -1.75906113e+02 -1.78060455e+02 -1.95000488e+02 -1.99061752e+02 -1.94744980e+02 -1.69521378e+02 -1.58540726e+02 -1.67929764e+02 -1.74681030e+02 -1.93056122e+02 -1.90923157e+02 -1.92530106e+02 -2.04470398e+02 -2.13472198e+02 -2.18846619e+02 -1.74961853e+02 -1.47060760e+02 -1.78942917e+02 -2.38989090e+02 -2.44087570e+02 -1.93353760e+02 -1.74649765e+02 -2.01027832e+02 -2.16699509e+02 -1.93727798e+02 -1.86874985e+02 -1.92301743e+02 -2.18346359e+02 -2.01138977e+02 -1.93838547e+02 -1.87442322e+02 -2.05593277e+02 -2.28969345e+02 -2.27527298e+02 -2.24811630e+02 -1.99216629e+02 -1.83884979e+02 -1.81210022e+02 -2.02898407e+02 -2.03372787e+02 -1.61199158e+02 -1.33901443e+02 -1.49961899e+02 -1.92470581e+02 -1.95244873e+02 -1.79800430e+02 -2.01503540e+02 -2.43941437e+02 -2.60525482e+02 -2.37232681e+02 -2.17904449e+02 -2.17516022e+02 -2.24346436e+02 -2.13456635e+02 -2.15411972e+02 -2.15713028e+02 -2.23597031e+02 -2.30329376e+02 -2.40888260e+02 -2.47718765e+02 -2.40209595e+02 -2.34701035e+02 -2.20667252e+02 -2.19301529e+02 -2.16143036e+02 -2.08058151e+02 -2.06413757e+02 -2.17086349e+02 -2.35604752e+02 -2.28813080e+02 -2.06126358e+02 -1.99362396e+02 -2.06940063e+02 -2.00495087e+02 -1.67462250e+02 -1.45647125e+02 -1.66113876e+02 -2.08964172e+02 -2.19905487e+02 -2.12107880e+02 -2.10181961e+02 -2.28652588e+02 -2.40581131e+02 -2.43378830e+02 -2.46784271e+02 -2.51658661e+02 -2.45372772e+02 -2.46938644e+02 -2.53520889e+02 -2.55934280e+02 -2.30772095e+02 -2.18160309e+02 -2.33744720e+02 -2.50692566e+02 -2.31953918e+02 -2.20104980e+02 -2.35237762e+02 -2.70091675e+02 -2.88258881e+02 -2.87622131e+02 -2.86959412e+02 -2.80017273e+02 -2.77408661e+02 -2.71556274e+02 -2.76730499e+02 -2.68362366e+02 -2.66276642e+02 -2.63900513e+02 -2.77783234e+02 -2.66356018e+02 -2.37048599e+02 -2.14952072e+02 -2.11423141e+02 -2.20265091e+02 -2.31238708e+02 -2.44486465e+02 -2.56720520e+02 -2.56640076e+02 -2.61262695e+02 -2.63959473e+02 -2.65353790e+02 -2.60633484e+02 -2.62068970e+02 -2.61600952e+02 -2.60585358e+02 -2.63354797e+02 -2.63544098e+02 -2.69215759e+02 -2.52259857e+02 -2.37532578e+02 -2.34591019e+02 -2.50449570e+02 -2.61751495e+02 -2.59868652e+02 -2.59477448e+02 -2.61174652e+02 -2.62711548e+02 -2.61934540e+02 -2.61746735e+02 -2.53841095e+02 -2.43326324e+02 -2.49150665e+02 -2.62846344e+02 -2.66962097e+02 -2.44236008e+02 -2.31013931e+02 -2.41302734e+02 -2.63311066e+02 -2.64524170e+02 -2.56445251e+02 -2.57067413e+02 -2.64312561e+02 -2.72573242e+02 -2.63254517e+02 -2.57108459e+02 -2.49668747e+02 -2.46333923e+02 -2.57874237e+02 -2.66205139e+02 -2.66415710e+02 -2.46016083e+02 -2.37892853e+02 -2.49630020e+02 -2.69053070e+02 -2.66551361e+02 -2.55919098e+02 -2.52897247e+02 -2.61931366e+02 -2.71129486e+02 -2.66366913e+02 -2.60233154e+02 -2.56846069e+02 -2.62040009e+02 -2.68000397e+02 -2.72273834e+02 -2.65947510e+02 -2.59368500e+02 -2.57194214e+02 -2.64915314e+02 -2.74901276e+02 -2.70819092e+02 -2.65322906e+02 -2.65311737e+02 -2.71888794e+02 -2.71991608e+02 -2.65788086e+02 -2.66880737e+02 -2.73829346e+02 -2.82062042e+02 -2.82759125e+02 -2.83335022e+02 -2.78653961e+02 -2.73616150e+02 -2.71834473e+02 -2.74255005e+02 -2.77562408e+02 -2.66089447e+02 -2.41571915e+02 -2.40721420e+02 -2.14055634e+02 -4.01986160e+01 -6.60145950e+01 -1.09732666e+03 -1.09530627e+03 -1.09115759e+03 -1.08935547e+03 -1.08798145e+03 -1.08606250e+03 -1.10253113e+03 -1.11606006e+03 -1.13043054e+03 -1.15519812e+03 -1.03125879e+03 -9.03267822e+02 2.68783960e+03 -1244824576. 0. 0. 0. 0. 0. 0. 0. -276036416. -777565376. 45655232. -3.29351465e+03 -3.52398853e+03 -5.42480859e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 431099104. -114127752. -1.59339404e+03 -1.21532387e+02 -1.93593521e+02 -2.81831116e+02 -2.66858521e+02 -2.28960464e+02 -2.21174545e+02 -2.44448502e+02 -2.55626236e+02 -2.65745087e+02 -2.65988800e+02 -2.58322906e+02 -2.55704727e+02 -2.59095795e+02 -2.56037384e+02 -2.49302841e+02 -2.41969498e+02 -2.48792465e+02 -2.65026917e+02 -2.73756378e+02 -2.68320862e+02 -2.55507431e+02 -2.49073593e+02 -2.50540466e+02 -2.53033173e+02 -2.49034180e+02 -2.42846436e+02 -2.47254700e+02 -2.58935425e+02 -2.65735291e+02 -2.60964417e+02 -2.49323502e+02 -2.44925522e+02 -2.52997543e+02 -2.67898346e+02 -2.75872467e+02 -2.69289185e+02 -2.69753479e+02 -2.78588654e+02 -2.74772736e+02 -2.56112000e+02 -2.39353394e+02 -2.53807312e+02 -2.85039490e+02 -2.96651520e+02 -2.79568787e+02 -2.59802124e+02 -2.49525208e+02 -2.49065170e+02 -2.52722488e+02 -2.54555237e+02 -2.48679825e+02 -2.51051437e+02 -2.77014801e+02 -3.00616699e+02 -2.91984650e+02 -2.65039612e+02 -2.48653137e+02 -2.58884705e+02 -2.76508148e+02 -2.85648254e+02 -2.68929199e+02 -2.65332886e+02 -2.71126587e+02 -2.63973145e+02 -2.40626923e+02 -2.18335541e+02 -2.23273605e+02 -2.61874573e+02 -2.74407593e+02 -2.61033722e+02 -2.31272964e+02 -2.33723358e+02 -2.56865417e+02 -2.51727386e+02 -2.37698822e+02 -2.25953064e+02 -2.41489151e+02 -2.75999817e+02 -2.92708252e+02 -2.81053986e+02 -2.42464798e+02 -2.18843948e+02 -2.26987518e+02 -2.45724945e+02 -2.43063110e+02 -2.24000244e+02 -2.24273682e+02 -2.49764893e+02 -2.61024536e+02 -2.35429657e+02 -1.99788208e+02 -1.96570648e+02 -2.32462708e+02 -2.66115448e+02 -2.65374512e+02 -2.40059998e+02 -2.32239182e+02 -2.40929504e+02 -2.22214111e+02 -1.88322922e+02 -1.70423645e+02 -2.03972855e+02 -2.58389160e+02 -2.87230988e+02 -2.67612183e+02 -2.32770264e+02 -1.97859924e+02 -1.76540909e+02 -1.79013306e+02 -1.85114365e+02 -1.83627762e+02 -1.90654022e+02 -2.25587463e+02 -2.60305573e+02 -2.38846619e+02 -1.77622910e+02 -1.51784393e+02 -1.78350403e+02 -2.40601501e+02 -2.67193085e+02 -2.39154846e+02 -2.12771896e+02 -2.03096909e+02 -2.09839127e+02 -1.83139938e+02 -1.39368622e+02 -1.42292221e+02 -1.91468170e+02 -2.39091156e+02 -2.33768219e+02 -2.00504761e+02 -1.76511826e+02 -1.73480728e+02 -1.80087234e+02 -2.01011368e+02 -2.08999054e+02 -1.82379059e+02 -1.66213943e+02 -1.90826080e+02 -2.17243912e+02 -2.23969940e+02 -2.08405365e+02 -2.09285248e+02 -2.28594467e+02 -2.29472321e+02 -2.10926575e+02 -1.83968231e+02 -1.67914612e+02 -1.88610840e+02 -1.99199432e+02 -1.92352570e+02 -1.76516586e+02 -2.00109177e+02 -2.72108154e+02 -3.08555786e+02 -2.54770279e+02 -1.84068451e+02 -1.70631363e+02 -2.05910950e+02 -2.28949463e+02 -2.25787308e+02 -2.27767883e+02 -2.54949509e+02 -2.89639313e+02 -2.99728882e+02 -2.75962097e+02 -2.25364090e+02 -1.93838638e+02 -2.25261597e+02 -2.45630966e+02 -2.32711121e+02 -1.95126709e+02 -2.14371384e+02 -2.78749481e+02 -2.74025482e+02 -2.45162872e+02 -2.21443497e+02 -2.57257416e+02 -3.25959625e+02 -3.57746368e+02 -3.19768677e+02 -2.44236252e+02 -2.04039185e+02 -2.11161194e+02 -1.99810089e+02 -1.76072937e+02 -1.87565033e+02 -2.36980453e+02 -3.01954987e+02 -2.83494049e+02 -2.38099899e+02 -1.55487930e+02 -1.25653938e+02 -1.43660873e+02 -2.02380081e+02 -2.53540131e+02 -2.56600281e+02 -2.66928406e+02 -2.87434540e+02 -2.67190643e+02 -2.02987289e+02 -1.44160858e+02 -1.70587387e+02 -2.66750641e+02 -3.15305603e+02 -2.64307922e+02 -1.61060211e+02 -1.25025269e+02 -1.70199051e+02 -2.21473099e+02 -2.00464523e+02 -1.54671021e+02 -1.62915695e+02 -2.18571777e+02 -2.36360046e+02 -1.81419220e+02 -9.72564392e+01 -8.70498352e+01 -1.24772888e+02 -1.74009048e+02 -1.66119125e+02 -1.48623932e+02 -1.45090469e+02 -1.72888947e+02 -1.55027817e+02 -1.13442963e+02 -1.02576202e+02 -9.85653458e+01 -1.59571671e+02 -1.70524872e+02 -1.61239822e+02 -1.47954010e+02 -1.55037292e+02 -1.99018890e+02 -1.61647400e+02 -1.13332520e+02 -8.11887360e+01 -1.06292038e+02 -2.09303711e+02 -2.73091522e+02 -2.63643799e+02 -1.56432526e+02 -8.94431152e+01 -8.01281281e+01 -1.12657921e+02 -1.44086105e+02 -1.12179405e+02 -1.21320534e+02 -1.48023743e+02 -1.68401245e+02 -1.31616074e+02 -1.01777412e+02 -1.59923294e+02 -2.33555145e+02 -2.21895065e+02 -1.84311813e+02 -1.63674911e+02 -1.80861420e+02 -2.28770569e+02 -1.77990784e+02 -1.44891678e+02 -1.02921242e+02 -1.23732887e+02 -1.81954498e+02 -2.12023682e+02 -2.31820419e+02 -1.76036667e+02 -1.46988541e+02 -1.37225708e+02 -1.81112244e+02 -1.85164337e+02 -1.74585220e+02 -1.84294083e+02 -2.23358887e+02 -2.41870285e+02 -1.78933594e+02 -1.31626419e+02 -1.30858368e+02 -1.82601593e+02 -1.68296463e+02 -1.44578262e+02 -1.15800133e+02 -9.72680588e+01 -1.10738441e+02 -9.76432266e+01 -1.56808304e+02 -1.69168091e+02 -1.91849152e+02 -1.89096985e+02 -1.69132812e+02 -1.47751358e+02 -8.20753708e+01 -6.05215721e+01 -7.48782806e+01 -1.70372620e+02 -1.93019318e+02 -1.75474319e+02 -1.38575897e+02 -1.44007370e+02 -1.26998367e+02 -3.68771362e+01 5.09290361e+00 -2.44223156e+01 -1.33609482e+02 -1.64729233e+02 -1.27004234e+02 -7.21862946e+01 -5.62996445e+01 -1.13927162e+02 -1.11208664e+02 -1.18155258e+02 -4.41342468e+01 -2.97315311e+01 -1.82730255e+01 -7.92977524e+01 -8.67416229e+01 -4.82180672e+01 -1.16666298e+01 -5.49700050e+01 -1.26303223e+02 -9.42240372e+01 -3.71073990e+01 -3.01247597e+01 -6.24945602e+01 -7.22189789e+01 -7.08574355e-02 2.35274658e+01 -2.56625009e+00 -8.18115997e+01 -7.54748993e+01 -4.75264130e+01 -1.27893543e+01 -3.59737206e+01 -6.85254669e+01 -6.63525009e+01 -7.22780609e+01 -2.52755985e+01 -7.98628283e+00 2.67088413e+00 -3.73018036e+01 -4.30890198e+01 -2.28580494e+01 2.15787182e+01 -1.05989418e+01 -6.78199921e+01 -8.42647171e+01 -7.31796722e+01 -9.73603973e+01 -1.63220428e+02 -1.51287598e+02 -8.18845825e+01 -6.33314209e+01 -1.03891930e+02 -1.63083527e+02 -1.00979858e+02 -6.31203957e+01 -2.33949604e+01 1.76598854e+01 2.77014847e+01 -7.88636637e+00 -1.15156021e+02 -1.34975281e+02 -6.09851341e+01 2.03806534e+01 -2.14913311e+01 -1.11989891e+02 -1.66628159e+02 -1.06376152e+02 -6.03372269e+01 -7.25805588e+01 -9.45485229e+01 -1.30727707e+02 -1.75131561e+02 -2.47550934e+02 -2.30284119e+02 -1.59648499e+02 -1.29202530e+02 -1.57438995e+02 -1.97812546e+02 -1.17648056e+02 -7.36511230e+01 -3.89476318e+01 -5.07844162e+01 -5.41396027e+01 -9.92197037e+01 -2.02767944e+02 -2.37759338e+02 -1.45283691e+02 -9.56062913e-01 4.56853485e+01 -8.74277649e+01 -2.00905762e+02 -2.10683121e+02 -1.13471275e+02 -5.42732010e+01 -8.35220642e+01 -1.71020294e+02 -2.16627136e+02 -1.72288208e+02 -3.83999939e+01 -2.94811487e+00 -6.06542015e+01 -1.48107849e+02 -2.30245407e+02 -2.15174057e+02 -1.75604935e+02 -6.74851761e+01 4.45087814e+01 8.92758255e+01 2.37017498e+01 -1.30225891e+02 -2.17851166e+02 -1.47601395e+02 -2.74477253e+01 -3.09784126e+01 -1.49389496e+02 -2.61240570e+02 -2.19749893e+02 -9.36009064e+01 1.30090494e+01 2.35440598e+01 -5.47327652e+01 -1.22769623e+02 -1.74724670e+02 -1.02858383e+02 -5.84241982e+01 -1.86953583e+01 -7.12945709e+01 -1.03480934e+02 -5.30254021e+01 1.18720255e+01 8.89990768e+01 9.66099930e+01 5.43696671e+01 -1.49223003e+01 -1.30796387e+02 -1.62260071e+02 -8.55620804e+01 7.74491806e+01 1.58240982e+02 8.49212418e+01 -6.79076843e+01 -1.61805008e+02 -1.17010323e+02 -5.49840546e+01 -4.98682480e+01 -1.01095253e+02 -1.18206490e+02 -1.19874199e+02 -4.49813271e+01 8.27818298e+00 7.27433167e+01 8.27999039e+01 4.49156837e+01 -5.27425289e+00 -7.63752213e+01 -7.08357849e+01 -2.36542702e+01 5.10051613e+01 5.72526245e+01 -5.14353132e+00 -7.69597931e+01 -4.95169830e+01 2.37904167e+01 6.27993011e+01 4.49848509e+00 -9.13699036e+01 -8.54813538e+01 -1.35331497e+01 1.04921547e+02 1.01116776e+02 1.81769753e+01 -5.88792343e+01 -1.00280357e+02 -1.33526373e+01 2.83437691e+01 6.09438972e+01 6.36816406e+01 6.98020782e+01 8.07442398e+01 4.20716629e+01 6.11212692e+01 1.04834450e+02 9.38513412e+01 4.00553970e+01 -5.35908241e+01 -8.63849640e+01 -3.17212658e+01 1.05717758e+02 2.18978088e+02 2.06413071e+02 6.82209320e+01 -6.20528259e+01 -9.85431747e+01 1.96755219e+00 1.13439247e+02 1.40614075e+02 6.62561035e+01 -1.80177345e+01 -1.43380344e+00 5.60668640e+01 1.21071564e+02 1.35940842e+02 1.15025215e+02 5.95564041e+01 -5.15019846e+00 1.33415759e+00 6.57238083e+01 1.66092743e+02 1.89075684e+02 1.10522591e+02 2.72433338e+01 3.46754951e+01 1.16783058e+02 1.62368088e+02 1.30605911e+02 8.59287338e+01 6.54288025e+01 4.99059219e+01 7.60961990e+01 1.02273262e+02 9.38199692e+01 7.91786575e+01 4.84255028e+01 8.49584122e+01 1.25852661e+02 1.76603287e+02 2.07148346e+02 1.59995544e+02 1.16577843e+02 4.35964622e+01 1.93300343e+01 5.87315102e+01 1.30193512e+02 1.45915298e+02 7.60729675e+01 -3.80743623e+00 1.21994600e+01 6.52920990e+01 1.46578995e+02 1.72058624e+02 1.31707062e+02 8.95060349e+01 6.28630981e+01 1.36179611e+02 1.92066498e+02 2.51679764e+02 2.39494385e+02 1.63962601e+02 1.69107498e+02 1.96583176e+02 2.77669830e+02 2.88425537e+02 2.57606506e+02 1.96566772e+02 9.53508987e+01 5.04882088e+01 7.52626266e+01 1.60206146e+02 2.03878235e+02 1.40144363e+02 6.14003067e+01 5.86634712e+01 1.54691757e+02 2.17832581e+02 1.98576553e+02 1.09967445e+02 4.23797684e+01 3.94712296e+01 1.10610260e+02 1.95966980e+02 2.19169235e+02 2.16128616e+02 1.89665039e+02 1.58365601e+02 1.06818657e+02 1.00575974e+02 1.25050301e+02 1.48481857e+02 1.15483109e+02 4.32427101e+01 1.02571380e+00 6.88693466e+01 1.61806320e+02 2.11082809e+02 1.56629288e+02 7.23079758e+01 5.77152061e+01 1.02306755e+02 1.88766541e+02 1.99122314e+02 1.50940399e+02 1.24681435e+02 1.16595879e+02 1.73280151e+02 1.87294128e+02 1.79600037e+02 1.55743729e+02 1.11990074e+02 1.26709312e+02 1.29237976e+02 1.98909439e+02 2.56382233e+02 2.47088669e+02 2.04714569e+02 1.34942078e+02 8.86955719e+01 8.20619583e+01 1.35047150e+02 2.56815063e+02 2.79378601e+02 2.63440887e+02 2.97863373e+02 6.55706726e+02 3.12222095e+03 4.81795361e+03 1.34492847e+03 6.48419128e+02 7.80030762e+03 2.15313691e+04 -195099296. 783052096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -554315968. 3.57637539e+04 5.60117920e+03 1.35608716e+03 9.33015869e+02 4.85899902e+02 3.46249390e+02 2.54880157e+02 2.23340591e+02 2.60390808e+02 2.73763214e+02 2.34839005e+02 1.49087631e+02 1.45954269e+02 1.91630295e+02 2.50636765e+02 2.33500031e+02 1.65208160e+02 1.12212234e+02 1.08054146e+02 1.63142914e+02 2.45486221e+02 2.65265198e+02 2.10899994e+02 1.41638947e+02 1.42944656e+02 1.94656708e+02 1.97402618e+02 1.58300598e+02 1.43100861e+02 1.76581390e+02 2.12361099e+02 2.15499451e+02 2.24483032e+02 2.50203445e+02 2.49791931e+02 2.08194717e+02 1.37867920e+02 1.32263412e+02 1.84003586e+02 2.30550232e+02 2.29280106e+02 1.77750763e+02 1.23482895e+02 1.32427307e+02 2.02567337e+02 2.86369415e+02 2.79639221e+02 2.04700974e+02 1.64143478e+02 1.61062164e+02 2.00649368e+02 2.12988083e+02 2.17469589e+02 2.25313873e+02 2.14856781e+02 2.02197525e+02 1.68780258e+02 1.79737000e+02 2.19892105e+02 2.26399460e+02 2.05157196e+02 1.56347382e+02 1.54287048e+02 1.80669159e+02 2.23965668e+02 2.45620758e+02 1.99932922e+02 1.41834351e+02 1.01674820e+02 1.28715668e+02 1.90411621e+02 2.12335861e+02 1.76706970e+02 1.47560226e+02 1.54981216e+02 2.11002884e+02 2.23495087e+02 2.09195587e+02 1.81654221e+02 1.88135498e+02 1.85734192e+02 1.76604950e+02 1.94898834e+02 2.33376389e+02 2.46715225e+02 2.08165634e+02 1.54525497e+02 1.45021332e+02 1.68873367e+02 2.04644363e+02 2.34916306e+02 2.35778992e+02 2.13272125e+02 1.85886017e+02 1.94368332e+02 2.41566345e+02 2.60354523e+02 2.20876160e+02 1.80303421e+02 1.86866440e+02 2.34621399e+02 2.60687897e+02 2.56708527e+02 2.50235947e+02 2.43457565e+02 2.25725677e+02 1.90297165e+02 1.91078705e+02 2.22932892e+02 2.48803223e+02 2.46333191e+02 2.17633545e+02 2.13428741e+02 2.31371338e+02 2.47850998e+02 2.62527405e+02 2.58471558e+02 2.32290329e+02 2.07955902e+02 2.02470657e+02 2.42932449e+02 2.61605225e+02 2.43818893e+02 2.32070084e+02 2.31380356e+02 2.51022736e+02 2.47023712e+02 2.44249496e+02 2.55391693e+02 2.60999634e+02 2.53504410e+02 2.23449905e+02 2.21987228e+02 2.45324783e+02 2.61656708e+02 2.61053101e+02 2.38107651e+02 2.44005234e+02 2.59053925e+02 2.71695038e+02 2.79304657e+02 2.67317688e+02 2.45170227e+02 2.26049362e+02 2.26294754e+02 2.47104431e+02 2.51408417e+02 2.46219818e+02 2.46411453e+02 2.53101288e+02 2.69113708e+02 2.76240906e+02 2.80640045e+02 2.77669434e+02 2.65974823e+02 2.54014328e+02 2.35143921e+02 2.31908905e+02 2.35648315e+02 2.49100861e+02 2.48883514e+02 2.36390182e+02 2.22577042e+02 2.30163147e+02 2.52434845e+02 2.69576233e+02 2.70674896e+02 2.50509720e+02 2.39823502e+02 2.40659454e+02 2.51939606e+02 2.55678757e+02 2.50976883e+02 2.53787933e+02 2.50738144e+02 2.48610184e+02 2.48963242e+02 2.59845215e+02 2.71287567e+02 2.70769196e+02 2.65874512e+02 2.57938354e+02 2.51375793e+02 2.49290344e+02 2.51521851e+02 2.53873947e+02 2.47409180e+02 2.40454086e+02 2.43796494e+02 2.55077957e+02 2.65562958e+02 2.67064575e+02 2.58583557e+02 2.56143341e+02 2.55232544e+02 2.62087006e+02 2.60535553e+02 2.55962265e+02 2.50465317e+02 2.47836090e+02 2.48388367e+02 2.45406509e+02 2.48085159e+02 2.53449493e+02 2.57929474e+02 2.57694672e+02 2.53698181e+02 2.53677155e+02 2.56649994e+02 2.60003296e+02 2.62358856e+02 2.60370758e+02 2.56483856e+02 2.53966751e+02 2.55402756e+02 2.58013031e+02 2.58361755e+02 2.57458466e+02 2.57322418e+02 2.57558197e+02 2.57903076e+02 2.57875732e+02 2.57637299e+02 2.57497375e+02 2.57481384e+02 2.58066742e+02 2.59348053e+02 2.60251038e+02 2.59988251e+02 2.58832184e+02 2.58702972e+02 2.58770050e+02 2.57596313e+02 2.55559082e+02 2.54621841e+02 2.55270279e+02 2.57692505e+02 2.58828278e+02 2.59375641e+02 2.58272491e+02 2.55927872e+02 2.54541107e+02 2.54955200e+02 2.57757172e+02 2.58577393e+02 2.58200806e+02 2.55880478e+02 2.56853302e+02 2.57746765e+02 2.58984741e+02 2.57693451e+02 2.56094055e+02 2.55927475e+02 2.55268631e+02 2.55651428e+02 2.53429504e+02 2.54259964e+02 2.54615051e+02 2.56162567e+02 2.54470291e+02 2.52439697e+02 2.53656723e+02 2.54611374e+02 2.54737442e+02 2.51493851e+02 2.52137955e+02 2.51979599e+02 2.49657990e+02 2.52071640e+02 2.54468384e+02 2.56902740e+02 2.50120819e+02 2.48106842e+02 2.49208847e+02 2.50053925e+02 2.48234604e+02 2.47146729e+02 2.48072052e+02 2.47814102e+02 2.50283539e+02 2.50234680e+02 2.51317261e+02 2.47128082e+02 2.49957428e+02 2.45284195e+02 2.47063828e+02 2.45289444e+02 2.48413589e+02 2.44122055e+02 2.42777664e+02 2.41378021e+02 2.48070221e+02 2.51936554e+02 2.55741608e+02 2.48714172e+02 2.45733398e+02 2.42102020e+02 2.44749435e+02 2.44497665e+02 2.46963486e+02 2.49422729e+02 2.46200729e+02 2.46602814e+02 2.47068054e+02 2.46256836e+02 2.40134933e+02 2.36893585e+02 2.39597366e+02 2.42921494e+02 2.40917221e+02 2.43729614e+02 2.47157654e+02 2.52901215e+02 2.50469574e+02 2.46734772e+02 2.40326126e+02 2.38046143e+02 2.28688751e+02 2.24661118e+02 2.18669479e+02 2.27051575e+02 2.32223862e+02 2.40579956e+02 2.44970505e+02 2.46369308e+02 2.31214722e+02 2.15492828e+02 2.16730316e+02 2.31219955e+02 2.43680634e+02 2.44401138e+02 2.39486389e+02 2.44237930e+02 2.45941803e+02 2.46940460e+02 2.40943878e+02 2.41289352e+02 2.43816574e+02 2.37804962e+02 2.33466263e+02 2.35102783e+02 2.47486862e+02 2.59163055e+02 2.61665649e+02 2.52880051e+02 2.38639893e+02 2.37603668e+02 2.43661789e+02 2.43952682e+02 2.38172165e+02 2.33710999e+02 2.44392014e+02 2.54820526e+02 2.57024292e+02 2.43788239e+02 2.30248581e+02 2.21639969e+02 2.31363693e+02 2.55906677e+02 2.75455597e+02 2.59521088e+02 2.25701218e+02 2.12841339e+02 2.23510788e+02 2.35430313e+02 2.38302673e+02 2.47156693e+02 2.54706573e+02 2.45487198e+02 2.30741821e+02 2.20224670e+02 2.21142273e+02 2.24588440e+02 2.37981995e+02 2.53571640e+02 2.52445602e+02 2.34672958e+02 2.17925766e+02 2.14079926e+02 2.15177673e+02 2.09668213e+02 1.99544220e+02 1.91350067e+02 1.94373993e+02 2.05689301e+02 2.15240723e+02 2.09612030e+02 2.01226028e+02 1.99276886e+02 2.09118500e+02 2.07779236e+02 2.02282623e+02 2.12313705e+02 2.24544052e+02 2.19725235e+02 1.88464310e+02 1.74674301e+02 1.91153946e+02 2.04768524e+02 2.14860382e+02 2.24251526e+02 2.35906586e+02 2.33509140e+02 2.34616470e+02 2.33947891e+02 2.29123276e+02 2.07953323e+02 2.00707840e+02 2.06599945e+02 2.09143951e+02 2.05876541e+02 2.03355576e+02 2.01674164e+02 1.97271133e+02 2.13221954e+02 2.32056183e+02 2.35757034e+02 2.11491211e+02 1.86166992e+02 1.88165268e+02 1.84792221e+02 1.92381378e+02 1.96016235e+02 2.05583038e+02 1.92245972e+02 1.70146759e+02 1.49744385e+02 1.47468628e+02 1.61950012e+02 1.81803375e+02 1.84999222e+02 1.78325424e+02 1.72405441e+02 1.78629684e+02 1.80112488e+02 1.47056091e+02 1.17743599e+02 1.15440071e+02 1.51977081e+02 1.82402420e+02 1.80767792e+02 1.57774796e+02 1.12286560e+02 4.22507362e+01 1.24265203e+01 -9.01045380e+01 -2.13622570e+01 -1.38483047e+02 -1.95623340e+03 -6.07578674e+02 -9.88912231e+02 -3.51771533e+03 6.54582214e+02 4.18550415e+02 6.68868042e+02 2.07419174e+02 -2.08526169e+02 -8.95540039e+03 -2.30549746e+04 -177720176. -470063296. 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. 0. 0. 0. 0. 0. 0. 0. 0. -711993856. 95752328. -50690692. -1.54831104e+04 -5.84260498e+03 -9.10345764e+02 -2.26164886e+02 6.58670521e+00 5.67432251e+01 4.10392876e+01 3.61991539e+01 6.92352753e+01 1.06393616e+02 1.06940552e+02 1.10197350e+02 1.10437866e+02 1.03778214e+02 8.43267365e+01 5.85958366e+01 9.03892822e+01 1.36406494e+02 1.47298401e+02 1.09847290e+02 8.33936462e+01 9.79333267e+01 1.12578476e+02 1.06496635e+02 9.28064423e+01 6.94899216e+01 5.97478790e+01 5.99822388e+01 8.21939545e+01 9.14912338e+01 9.66205444e+01 8.51693497e+01 1.15634743e+02 1.58495071e+02 1.69898422e+02 1.45652954e+02 1.14253700e+02 1.18194870e+02 1.36882751e+02 1.41441177e+02 1.51232040e+02 1.55383835e+02 1.64431793e+02 1.74354630e+02 1.74996384e+02 1.59841492e+02 1.44338120e+02 1.37711441e+02 1.54857605e+02 1.51141479e+02 1.42318481e+02 1.38998444e+02 1.48848480e+02 1.59311432e+02 1.57541229e+02 1.37401443e+02 9.37625275e+01 5.01307945e+01 3.38019104e+01 5.96293335e+01 9.02468262e+01 1.07289200e+02 7.87223740e+01 4.93966751e+01 5.87739906e+01 9.37239075e+01 1.28115265e+02 1.28728546e+02 1.26290955e+02 1.47012787e+02 1.82338623e+02 1.52268356e+02 9.88077240e+01 5.38346672e+01 7.50774536e+01 1.02831367e+02 1.03638885e+02 1.05672211e+02 1.05543884e+02 1.11643646e+02 1.08356392e+02 1.00053360e+02 7.97653275e+01 6.75227585e+01 6.34388542e+01 7.11747055e+01 6.95302658e+01 3.18266926e+01 -1.43935089e+01 -2.87880361e-01 3.61073914e+01 7.77465439e+01 6.15025368e+01 4.28559494e+01 2.01554260e+01 6.69583797e+00 3.18228321e+01 7.30354614e+01 8.21342392e+01 6.08163109e+01 1.37327490e+01 1.15392189e+01 2.53025551e+01 5.22328835e+01 7.04808960e+01 5.44273453e+01 5.78738136e+01 5.39790001e+01 6.90306168e+01 5.46722488e+01 5.13967285e+01 5.36368980e+01 3.24892616e+01 7.07155526e-01 5.53144503e+00 3.69446373e+01 7.01164856e+01 7.34004822e+01 7.67956009e+01 7.53842239e+01 7.42782364e+01 8.25059738e+01 8.41873856e+01 4.03081169e+01 -1.53160934e+01 -2.39338207e+01 7.94364309e+00 4.87837372e+01 6.90844955e+01 8.22255402e+01 7.48225861e+01 5.96297150e+01 4.82972450e+01 6.40646057e+01 5.93061523e+01 5.92230339e+01 5.12884140e+01 4.26595383e+01 3.18856640e+01 3.15663548e+01 3.22174950e+01 3.84355278e+01 3.25455551e+01 2.34031258e+01 2.25861664e+01 1.51879730e+01 8.88202477e+00 -1.07818820e-01 -5.46201849e+00 8.65928650e+00 1.16628895e+01 1.84506302e+01 2.08402805e+01 2.49289417e+01 4.18199234e+01 4.28612061e+01 3.12348442e+01 -3.14097595e+01 -6.90613251e+01 -7.70605850e+01 -5.46169815e+01 -3.18856850e+01 -2.33232059e+01 -1.37894220e+01 -8.11522388e+00 -1.70253201e+01 -1.98613033e+01 -1.77565937e+01 -1.87581177e+01 -2.04601040e+01 -1.81256084e+01 2.66997147e+01 7.14892426e+01 1.02715775e+02 9.86264420e+01 5.62112274e+01 8.94138908e+00 -3.14494801e+01 -2.90343266e+01 -2.05131855e+01 -1.63766613e+01 -1.87523804e+01 -1.47077837e+01 -1.28722019e+01 -8.04764462e+00 2.41199470e+00 -7.03348684e+00 -1.38931065e+01 -1.81403294e+01 -1.45595093e+01 -1.23993130e+01 -2.97730789e+01 -3.83578835e+01 -4.12938957e+01 -3.86691284e+01 -2.64200268e+01 4.64407253e+00 5.14621925e+01 7.18116302e+01 7.48152313e+01 5.98795509e+01 7.33820801e+01 3.44698753e+01 -1.38010550e+01 -5.73049278e+01 -5.44015961e+01 -4.40481606e+01 -4.36107597e+01 -4.70310555e+01 -5.18934937e+01 -6.64015121e+01 -6.48910141e+01 -6.67704239e+01 -5.40314636e+01 -5.05234451e+01 -4.66072121e+01 -8.67983322e+01 -1.36288467e+02 -1.22086182e+02 -7.99718323e+01 -3.42048798e+01 -1.68196754e+01 -6.17374992e+00 3.67370338e+01 5.78804321e+01 4.67475510e+01 1.38665733e+01 -4.10995102e+01 -3.17494488e+01 -2.25913239e+01 -1.88219714e+00 -5.89581680e+00 -1.79133034e+01 -1.66837921e+01 -1.92679863e+01 -1.59592495e+01 -3.28218231e+01 -4.61871986e+01 -4.68890114e+01 -1.26791143e+01 2.68734875e+01 6.35204315e+01 7.16033859e+01 -2.23053885e+00 -8.65769196e+01 -1.28145828e+02 -9.92949829e+01 -5.28799667e+01 -5.03728943e+01 -3.95145798e+01 -4.57274017e+01 -5.05974693e+01 -6.08292923e+01 -7.00344543e+01 -7.95058823e+01 -7.83351135e+01 -7.84183731e+01 -1.02266785e+02 -1.46183060e+02 -1.53703751e+02 -1.32708740e+02 -1.02074875e+02 -8.22064285e+01 -6.23929405e+01 -5.71165390e+01 -7.88463669e+01 -8.01414566e+01 -6.05228806e+01 -6.21246223e+01 -8.15630341e+01 -1.05563103e+02 -1.11437462e+02 -1.03123741e+02 -1.00670044e+02 -9.72533112e+01 -9.89776077e+01 -9.28279572e+01 -9.58301315e+01 -9.87952194e+01 -1.16612900e+02 -1.18535011e+02 -1.19166222e+02 -8.21054611e+01 -4.52699203e+01 -5.27292061e+01 -8.67438126e+01 -1.17448082e+02 -1.01866310e+02 -1.00514580e+02 -1.01391518e+02 -9.98567200e+01 -9.02695236e+01 -8.52497940e+01 -6.71260910e+01 -5.56209526e+01 -6.02472038e+01 -9.67910919e+01 -1.28358536e+02 -1.33160706e+02 -1.22394127e+02 -1.41544403e+02 -1.67247482e+02 -1.84218719e+02 -1.70637009e+02 -1.42695816e+02 -1.46552979e+02 -1.46382721e+02 -1.45209625e+02 -1.31003784e+02 -1.25807976e+02 -1.36460220e+02 -1.46693436e+02 -1.47718597e+02 -1.42904343e+02 -1.46426132e+02 -1.50164017e+02 -1.40760880e+02 -1.32977600e+02 -1.05908302e+02 -8.39826355e+01 -8.80778580e+01 -1.04794548e+02 -1.21750038e+02 -1.19875618e+02 -1.33424866e+02 -1.49357529e+02 -1.44440872e+02 -1.02853920e+02 -7.02824020e+01 -6.84010773e+01 -1.06074913e+02 -1.33819519e+02 -1.31070038e+02 -1.19484726e+02 -1.19083122e+02 -1.32202438e+02 -1.14631577e+02 -8.34825821e+01 -6.99496002e+01 -9.45525894e+01 -1.34829773e+02 -1.32319336e+02 -1.34241882e+02 -1.31803635e+02 -1.38963547e+02 -1.41049362e+02 -1.31469986e+02 -1.24404205e+02 -1.16308121e+02 -1.30566422e+02 -1.39539841e+02 -1.41109619e+02 -1.01070786e+02 -5.39985542e+01 -4.93322220e+01 -8.99413300e+01 -1.33419083e+02 -1.38967758e+02 -1.55653412e+02 -1.56168488e+02 -1.51993271e+02 -1.03210365e+02 -7.54886627e+01 -3.70120277e+01 -4.03005066e+01 -6.70291138e+01 -1.05126152e+02 -1.44929062e+02 -1.20375999e+02 -9.75906372e+01 -1.27942596e+02 -1.94042847e+02 -2.22206848e+02 -1.91813995e+02 -1.61146255e+02 -1.66443176e+02 -1.71381943e+02 -1.76552948e+02 -1.77276230e+02 -1.86298859e+02 -1.89345032e+02 -1.91906876e+02 -1.94613007e+02 -1.99451355e+02 -2.06378494e+02 -2.09016937e+02 -1.99762924e+02 -1.93435333e+02 -1.69042419e+02 -1.51368164e+02 -1.54347702e+02 -1.82387573e+02 -2.15136749e+02 -1.85949310e+02 -1.47893692e+02 -1.73291443e+02 -2.35782990e+02 -2.41683975e+02 -1.70678299e+02 -1.29143082e+02 -1.50671021e+02 -1.90322815e+02 -1.75325974e+02 -1.42958221e+02 -1.33978317e+02 -1.46765396e+02 -1.77509857e+02 -1.76789200e+02 -1.75817429e+02 -1.79019699e+02 -1.80805420e+02 -2.04670563e+02 -2.27899292e+02 -2.07210831e+02 -1.60273315e+02 -1.35051971e+02 -1.50650681e+02 -1.71774002e+02 -1.48515228e+02 -1.27522987e+02 -1.23156593e+02 -1.47216431e+02 -1.79257828e+02 -1.75011978e+02 -1.69627731e+02 -1.61077316e+02 -1.78391068e+02 -1.70903656e+02 -1.48251404e+02 -1.38578568e+02 -1.44051407e+02 -1.80519562e+02 -1.96606354e+02 -2.06217270e+02 -1.99940018e+02 -1.95977402e+02 -2.30306244e+02 -2.73874542e+02 -2.64270142e+02 -2.12984955e+02 -1.74811188e+02 -1.88140747e+02 -2.14660797e+02 -1.99171783e+02 -1.72261368e+02 -1.69782257e+02 -1.88887344e+02 -2.10872910e+02 -2.19862076e+02 -2.20358032e+02 -2.19867783e+02 -2.12796310e+02 -2.11597763e+02 -2.06001358e+02 -1.98085175e+02 -1.91412384e+02 -1.98702133e+02 -2.11696518e+02 -2.21988998e+02 -2.21565552e+02 -2.19484207e+02 -2.38490295e+02 -2.61523926e+02 -2.41784210e+02 -1.99959366e+02 -1.77813400e+02 -2.02876938e+02 -2.28713974e+02 -2.44618408e+02 -2.52002960e+02 -2.52566193e+02 -2.45054932e+02 -2.37137482e+02 -2.41281494e+02 -2.41345245e+02 -2.46016724e+02 -2.44531021e+02 -2.51505844e+02 -2.51913574e+02 -2.54622559e+02 -2.39358246e+02 -2.31189789e+02 -2.36798630e+02 -2.51730942e+02 -2.58729614e+02 -2.46396225e+02 -2.34902115e+02 -2.27332169e+02 -2.15459335e+02 -1.96044418e+02 -1.96355408e+02 -2.12131363e+02 -2.17754822e+02 -1.85841354e+02 -1.64509567e+02 -1.79121231e+02 -2.03911560e+02 -1.97583389e+02 -1.78055603e+02 -1.75725830e+02 -1.96465240e+02 -2.12244583e+02 -2.16401169e+02 -2.18646683e+02 -2.14306381e+02 -2.14703888e+02 -2.15227249e+02 -2.25362778e+02 -2.16589218e+02 -2.02738510e+02 -1.94942459e+02 -2.07073593e+02 -2.21911896e+02 -2.19741623e+02 -2.09235001e+02 -2.19590775e+02 -2.42955963e+02 -2.53654541e+02 -2.48878601e+02 -2.36355515e+02 -2.41355560e+02 -2.39716751e+02 -2.40571564e+02 -2.40701553e+02 -2.44751877e+02 -2.43496902e+02 -2.40588150e+02 -2.42086243e+02 -2.45300537e+02 -2.50325943e+02 -2.47895813e+02 -2.45256866e+02 -2.47089310e+02 -2.37829239e+02 -2.28310303e+02 -2.28247467e+02 -2.40791473e+02 -2.56278870e+02 -2.60265106e+02 -2.61283142e+02 -2.69256622e+02 -2.79453644e+02 -2.77920746e+02 -2.66766724e+02 -2.54923660e+02 -2.53367371e+02 -2.54202148e+02 -2.40794174e+02 -2.29049698e+02 -2.27444763e+02 -2.38936279e+02 -2.46770370e+02 -2.46327042e+02 -2.47532211e+02 -2.52621933e+02 -2.52383667e+02 -2.58564911e+02 -2.67156158e+02 -2.61696289e+02 -2.48148331e+02 -2.38664948e+02 -2.44684738e+02 -2.44573639e+02 -2.31605438e+02 -2.22256287e+02 -2.26556747e+02 -2.41897797e+02 -2.47625534e+02 -2.43965240e+02 -2.40795639e+02 -2.47354797e+02 -2.56963959e+02 -2.56908722e+02 -2.51116241e+02 -2.50289856e+02 -2.52854858e+02 -2.58896851e+02 -2.61277008e+02 -2.63378815e+02 -2.63380096e+02 -2.61323914e+02 -2.61830353e+02 -2.63030762e+02 -2.59591888e+02 -2.54959915e+02 -2.52219208e+02 -2.55451431e+02 -2.58262360e+02 -2.55516403e+02 -2.50844437e+02 -2.51187927e+02 -2.55587677e+02 -2.67991699e+02 -2.85344299e+02 -2.96923370e+02 -3.09125854e+02 -3.06714050e+02 -2.63983917e+02 -2.41630783e+02 -2.22842880e+02 -2.53672729e+02 -2.72425629e+02 -2.69593353e+02 -2.46960052e+02 -4.12043671e+02 -5.45339111e+02 2.68783960e+03 -1244824576. 0. 0. 0. 0. 357199328. 357199328. -692914048. -145753472. -7.42732080e+03 45655232. -3.29351465e+03 -3.52398853e+03 -5.42480859e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 663051200. 105610992. -1.33806714e+03 -9.84275635e+02 -2.70593628e+02 -3.70289673e+02 -2.65216644e+02 -1.11190308e+02 -2.07629501e+02 -2.04393112e+02 -2.26674103e+02 -2.24049149e+02 -2.22427628e+02 -2.25173386e+02 -2.27215561e+02 -2.23526321e+02 -2.19083160e+02 -2.21532516e+02 -2.29905411e+02 -2.33947525e+02 -2.27411469e+02 -2.14930237e+02 -2.14326447e+02 -2.23537033e+02 -2.37634995e+02 -2.41018677e+02 -2.34851776e+02 -2.36239456e+02 -2.42815689e+02 -2.43055435e+02 -2.35729080e+02 -2.29230118e+02 -2.37354630e+02 -2.54769974e+02 -2.58755157e+02 -2.46094284e+02 -2.30889481e+02 -2.22118668e+02 -2.22802338e+02 -2.17380707e+02 -2.09634811e+02 -2.04620148e+02 -2.15782333e+02 -2.45362411e+02 -2.63464447e+02 -2.54990540e+02 -2.33281235e+02 -2.16509140e+02 -2.16922852e+02 -2.23683044e+02 -2.33636063e+02 -2.31823517e+02 -2.37084473e+02 -2.43193405e+02 -2.36343597e+02 -2.11481018e+02 -1.85996674e+02 -1.89319595e+02 -2.27611710e+02 -2.45885681e+02 -2.36723709e+02 -2.11602844e+02 -2.14738129e+02 -2.34557022e+02 -2.34107574e+02 -2.15415268e+02 -1.93411133e+02 -2.01212692e+02 -2.31590225e+02 -2.58097015e+02 -2.48712784e+02 -2.29635117e+02 -2.18719589e+02 -2.25444138e+02 -2.23110016e+02 -2.06592575e+02 -1.89852112e+02 -1.97085281e+02 -2.06129929e+02 -2.00545563e+02 -1.85749100e+02 -1.79575882e+02 -1.88005051e+02 -2.02217682e+02 -2.20947952e+02 -2.27053467e+02 -2.20181458e+02 -2.11013351e+02 -2.12317184e+02 -1.91443253e+02 -1.59622513e+02 -1.47879471e+02 -1.76988907e+02 -2.27161911e+02 -2.53451889e+02 -2.39893692e+02 -1.98869873e+02 -1.60225296e+02 -1.43074493e+02 -1.50205399e+02 -1.56653793e+02 -1.49966431e+02 -1.63254913e+02 -2.01218063e+02 -2.32265167e+02 -2.22107056e+02 -1.89312347e+02 -1.79312988e+02 -1.91937103e+02 -2.19574036e+02 -2.24012375e+02 -2.03729706e+02 -1.88685257e+02 -1.90331070e+02 -1.93414795e+02 -1.72931931e+02 -1.34217850e+02 -1.27164764e+02 -1.62129669e+02 -2.01958694e+02 -2.02702301e+02 -1.68425354e+02 -1.43413422e+02 -1.40583511e+02 -1.65429932e+02 -1.94786194e+02 -2.09907440e+02 -1.94116852e+02 -1.94210297e+02 -2.12843826e+02 -2.17324326e+02 -1.86697937e+02 -1.51617676e+02 -1.52797241e+02 -1.82636948e+02 -2.01203934e+02 -1.83031097e+02 -1.67900787e+02 -1.58977325e+02 -1.73337570e+02 -1.59264206e+02 -1.35728027e+02 -1.26544304e+02 -1.64213577e+02 -2.39043594e+02 -2.75080597e+02 -2.44163452e+02 -1.89886520e+02 -1.76740311e+02 -1.92680740e+02 -2.14637604e+02 -2.10389633e+02 -2.09333359e+02 -2.28935104e+02 -2.62366943e+02 -2.80245361e+02 -2.44580536e+02 -1.71851730e+02 -1.30668320e+02 -1.70320435e+02 -2.09448090e+02 -2.08398804e+02 -1.81009857e+02 -2.05583023e+02 -2.62900269e+02 -2.57695801e+02 -2.01466904e+02 -1.52744507e+02 -1.87151138e+02 -2.67042419e+02 -3.08984650e+02 -2.79483398e+02 -2.19280762e+02 -1.88418411e+02 -1.87280151e+02 -1.76282867e+02 -1.59771286e+02 -1.75744049e+02 -2.24012695e+02 -2.84462860e+02 -2.52946884e+02 -1.93000061e+02 -1.47112473e+02 -1.52619537e+02 -1.90429504e+02 -2.11135696e+02 -2.27680634e+02 -2.28967773e+02 -2.46609558e+02 -2.79840607e+02 -2.57787476e+02 -1.97305756e+02 -1.49544220e+02 -1.55424469e+02 -2.24229019e+02 -2.65440369e+02 -2.55016663e+02 -1.90024399e+02 -1.59754623e+02 -1.65640137e+02 -1.60069366e+02 -1.02639450e+02 -7.87265015e+01 -1.28450226e+02 -2.04595245e+02 -2.18812088e+02 -1.85819229e+02 -1.27704857e+02 -9.68508835e+01 -1.02596489e+02 -1.33513885e+02 -1.66204483e+02 -1.62102341e+02 -1.82229355e+02 -2.06835876e+02 -1.81512787e+02 -1.32539688e+02 -1.12705284e+02 -1.20156845e+02 -1.67034241e+02 -1.76998245e+02 -1.63720261e+02 -1.45187347e+02 -1.39237167e+02 -1.66166336e+02 -1.41195328e+02 -9.99771805e+01 -7.91525345e+01 -7.23834457e+01 -1.42572403e+02 -1.85957123e+02 -1.59687668e+02 -9.08310547e+01 -6.84503860e+01 -1.19860817e+02 -1.62448486e+02 -1.61894821e+02 -1.24683014e+02 -1.26312103e+02 -1.56971115e+02 -1.67241119e+02 -1.17685860e+02 -1.00414703e+02 -1.29059799e+02 -1.59755798e+02 -1.12298759e+02 -9.71943970e+01 -1.21229050e+02 -1.50441467e+02 -1.66448334e+02 -1.38327225e+02 -1.60802383e+02 -1.77572021e+02 -1.84571289e+02 -1.97616104e+02 -2.11578293e+02 -2.23709579e+02 -1.62145538e+02 -1.36720184e+02 -1.22802261e+02 -1.66880142e+02 -1.49848404e+02 -1.46222473e+02 -1.73180222e+02 -2.16307953e+02 -2.27069870e+02 -1.47333359e+02 -9.63067017e+01 -9.63173828e+01 -1.61729477e+02 -1.90361572e+02 -1.78921188e+02 -1.46967453e+02 -1.28035278e+02 -1.68710373e+02 -1.50423904e+02 -1.17620720e+02 -4.98796768e+01 -2.57792435e+01 -4.08231010e+01 -9.45823212e+01 -1.43826157e+02 -1.08989319e+02 -5.65998535e+01 -2.74511986e+01 -5.38979683e+01 -3.16483498e+01 -4.09700241e+01 -8.14573822e+01 -1.41749878e+02 -1.33561920e+02 -3.87887077e+01 -1.34121284e+01 -5.66537781e+01 -1.31499313e+02 -1.08149750e+02 -6.74359665e+01 -5.87166710e+01 -7.48735886e+01 -1.11361603e+02 -9.96088257e+01 -1.17519539e+02 -6.07004242e+01 -4.63385201e+01 -3.97168045e+01 -8.70675201e+01 -9.62753677e+01 -6.52782898e+01 -2.40262814e+01 -3.23177223e+01 -2.15683861e+01 4.01270981e+01 8.03113403e+01 7.99806824e+01 5.15695190e+01 5.70769234e+01 8.69587936e+01 1.09524406e+02 8.37022858e+01 1.52819748e+01 -2.44217930e+01 -3.37655563e+01 -2.75518932e+01 -4.23597450e+01 -8.80858078e+01 -1.16779915e+02 -1.42292099e+02 -8.94438324e+01 -5.73977242e+01 -2.71748562e+01 -3.75036812e+01 -2.25997829e+01 1.37370378e-01 2.89872551e+01 2.02567520e+01 1.69121990e+01 5.66589508e+01 9.84860077e+01 7.54189301e+01 1.27547169e+01 -1.44110107e+00 -9.28939247e+00 -5.72508583e+01 -1.01102982e+02 -1.20726395e+02 -5.52382965e+01 -5.08800774e+01 -3.82437820e+01 -2.58527803e+00 1.94773841e+00 -4.06840935e+01 -1.40817276e+02 -1.56277298e+02 -6.94921799e+01 1.29008875e+01 1.06484642e+01 -5.22658195e+01 -1.02617546e+02 -7.41802444e+01 -2.82422409e+01 2.42056980e+01 1.99806957e+01 -2.49489880e+01 -6.37134857e+01 -1.22927612e+02 -1.20330605e+02 -1.21038361e+02 -1.31665802e+02 -1.31213821e+02 -1.39433167e+02 -5.84755478e+01 -4.94630547e+01 -3.61638069e+01 -3.41643600e+01 -5.23359070e+01 -9.89267731e+01 -2.21461700e+02 -2.41197952e+02 -1.60204895e+02 -1.51290762e+00 8.20604401e+01 -1.06843014e+01 -1.26262329e+02 -1.33214249e+02 8.16254234e+00 1.45663330e+02 1.12307190e+02 -2.94486980e+01 -1.15827431e+02 -1.01785271e+02 -1.55929327e+01 -1.98153973e+01 -7.67773514e+01 -1.17605522e+02 -1.24333061e+02 -6.00402603e+01 -5.74395599e+01 -1.00237625e+02 -1.31507599e+02 -1.22599625e+02 -6.56375656e+01 -8.65870438e+01 -9.75599823e+01 -1.38298264e+01 8.58972397e+01 8.91167221e+01 -8.08397827e+01 -1.95320297e+02 -1.69431564e+02 -2.74098549e+01 5.61167107e+01 3.60252380e+01 -6.28386078e+01 -1.03470436e+02 -1.07517860e+02 -2.73796806e+01 -2.63112202e+01 -3.29018211e+01 -5.46438103e+01 -8.91706924e+01 -3.64168053e+01 -1.37423098e+00 9.10113983e+01 8.39535751e+01 4.18478661e+01 -3.08743572e+01 -1.34951355e+02 -1.64074951e+02 -9.44889984e+01 6.19896126e+01 1.47047592e+02 7.69205627e+01 -7.87374496e+01 -1.31796143e+02 -1.53223455e+00 1.55525146e+02 1.54145142e+02 -2.38215852e+00 -6.78051758e+01 -5.79679298e+01 3.15831280e+01 2.58939743e+01 -1.48290386e+01 -8.50202713e+01 -1.21661812e+02 -1.20880592e+02 -1.46285431e+02 -1.46203201e+02 -7.94302521e+01 3.25905418e+01 7.28413239e+01 -5.34725375e-02 -7.90926743e+01 -5.36724167e+01 5.96121559e+01 1.51464691e+02 1.08853729e+02 -1.15187616e+01 -4.82348595e+01 2.67253423e+00 9.83454971e+01 8.65956039e+01 6.13160074e-01 -5.13505707e+01 -1.06008072e+02 -4.09710388e+01 -6.08087807e+01 -1.87943802e+01 -2.10341091e+01 -2.58047047e+01 -5.40220032e+01 -1.04154678e+02 -6.82411728e+01 -5.70242357e+00 7.02761078e+01 4.65776863e+01 -3.52431679e+01 -1.14625671e+02 -6.18847351e+01 4.59113045e+01 1.18572182e+02 1.12170303e+02 4.28589897e+01 2.21103001e+01 1.07836514e+01 4.04473686e+01 1.08976383e+01 -3.27558403e+01 -8.39518204e+01 -1.28083221e+02 -1.08110428e+02 -8.83042145e+00 6.61990814e+01 8.09261703e+01 3.89194756e+01 -1.53158712e+00 -6.19904175e+01 -8.84718552e+01 -3.71167469e+00 1.33173248e+02 1.80559296e+02 9.20665054e+01 -2.50437660e+01 -2.77990875e+01 8.23516617e+01 2.02893799e+02 1.84853836e+02 4.83615494e+01 -8.42148209e+01 -1.26455307e+02 -4.21594887e+01 3.28688889e+01 2.51261826e+01 -1.59873629e+01 -4.66010208e+01 1.69077454e+01 1.86520615e+01 3.67621803e+01 7.39720383e+01 9.54870224e+01 9.02291260e+01 1.28145752e+01 2.59816742e+01 1.10072067e+02 2.09933563e+02 1.87083496e+02 4.40278702e+01 -6.34850349e+01 -1.77697983e+01 1.03124413e+02 1.93771912e+02 1.88620926e+02 8.26825027e+01 -1.29127722e+01 -5.73602524e+01 2.87935295e+01 7.45132599e+01 1.15689972e+02 1.11360016e+02 9.97232971e+01 1.16690277e+02 1.14651512e+02 1.73114151e+02 2.09923401e+02 2.13656906e+02 1.73296783e+02 7.81807327e+01 3.65615349e+01 9.47431335e+01 1.80355270e+02 2.10773758e+02 1.50908569e+02 6.83225174e+01 7.92458725e+01 1.37363907e+02 2.26618042e+02 2.35938995e+02 1.51043045e+02 6.74081497e+01 3.18282108e+01 9.88592377e+01 1.65107620e+02 1.59390579e+02 1.13292053e+02 4.10744362e+01 3.24426422e+01 4.37612610e+01 8.98259583e+01 1.53587296e+02 1.49610184e+02 8.75651169e+01 -1.11738195e+01 -4.05566254e+01 2.99870796e+01 1.15010880e+02 1.73541534e+02 1.33786774e+02 5.88111076e+01 2.12533875e+01 4.57442856e+01 1.03555931e+02 1.00648514e+02 6.03109169e+01 1.89253254e+01 2.25091553e+01 8.65667191e+01 1.36119278e+02 1.21095367e+02 8.23268814e+01 8.32170868e+00 1.68678703e+01 1.49369431e+01 4.84793282e+01 8.83746643e+01 1.12875580e+02 1.30731354e+02 7.69917908e+01 3.77102585e+01 6.12268906e+01 1.17166672e+02 1.68458862e+02 1.29912567e+02 6.64570694e+01 2.73764687e+01 8.97508621e+01 2.06139069e+02 2.60167542e+02 1.96597122e+02 7.92906570e+01 1.43485231e+01 5.68953667e+01 1.39305939e+02 2.02123657e+02 2.61611938e+02 3.21579895e+02 3.15551849e+02 2.88753021e+02 2.47288379e+03 4.90176123e+03 1.33909424e+04 2.88836836e+04 -281970400. -68863568. 121455656. -295212160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 832060288. -590784000. 59325776. 254382512. 143809264. 2.32940859e+04 1.03033408e+04 4.75208691e+03 2.86068823e+03 7.43706848e+02 3.84446991e+02 3.39254608e+02 3.03989105e+02 2.31816711e+02 1.32789566e+02 1.01037285e+02 1.26935532e+02 2.00125809e+02 2.37262665e+02 2.28018478e+02 1.71437088e+02 1.05009132e+02 1.05298882e+02 1.24417709e+02 1.45278778e+02 1.45867050e+02 1.51856064e+02 1.76766312e+02 1.46097839e+02 1.40730804e+02 1.93155029e+02 2.37466476e+02 2.05500031e+02 1.10936852e+02 6.05485535e+01 1.21168930e+02 1.96160614e+02 2.40380051e+02 2.17769348e+02 1.32820572e+02 6.83240509e+01 3.50783195e+01 1.05224411e+02 1.55208649e+02 1.64381546e+02 1.19469696e+02 9.01680145e+01 1.14440514e+02 1.20035149e+02 1.45538116e+02 1.75001205e+02 1.91580872e+02 1.67526840e+02 8.63813858e+01 8.04910812e+01 1.51681702e+02 2.37817581e+02 2.56585052e+02 1.88591675e+02 1.22264839e+02 1.22282593e+02 1.75068726e+02 1.96341309e+02 1.56806885e+02 8.26286316e+01 6.35878525e+01 8.86272583e+01 1.66581482e+02 2.23568558e+02 2.27638199e+02 1.79034531e+02 1.19126358e+02 7.80611038e+01 6.23901978e+01 7.76466904e+01 1.10906982e+02 1.51138260e+02 1.69701202e+02 1.61261749e+02 1.64295074e+02 2.07415527e+02 2.48004562e+02 2.47899338e+02 1.96893295e+02 1.61899704e+02 1.66150452e+02 1.86346954e+02 2.22714096e+02 2.47384201e+02 2.31072281e+02 1.78008255e+02 1.52094925e+02 1.82873016e+02 2.21712769e+02 2.12994156e+02 1.90783600e+02 1.82063934e+02 1.97051208e+02 1.85533844e+02 1.89010651e+02 2.10081329e+02 2.26962463e+02 2.12427246e+02 1.62741302e+02 1.59407730e+02 2.08774567e+02 2.70440521e+02 2.86858276e+02 2.44655945e+02 2.04866348e+02 1.85940918e+02 1.95946854e+02 2.08174088e+02 2.13569885e+02 1.99355316e+02 1.76341599e+02 1.64236938e+02 1.92904282e+02 2.35469269e+02 2.49140533e+02 2.31830444e+02 2.16378006e+02 2.14967285e+02 1.99204651e+02 2.00209137e+02 2.31564056e+02 2.72026794e+02 2.66712067e+02 2.21264908e+02 2.01721512e+02 2.32147049e+02 2.67757355e+02 2.69751068e+02 2.33288177e+02 1.97464508e+02 1.87305984e+02 2.00427094e+02 2.28710648e+02 2.51331375e+02 2.46085892e+02 2.18303696e+02 1.97313980e+02 2.13058243e+02 2.41598175e+02 2.53651108e+02 2.44432739e+02 2.28492218e+02 2.18987289e+02 2.02528473e+02 1.97750397e+02 2.06023590e+02 2.19831192e+02 2.20948486e+02 2.01042496e+02 1.93475754e+02 2.10223740e+02 2.47708954e+02 2.69791992e+02 2.59479614e+02 2.24714264e+02 2.01153702e+02 2.05394501e+02 2.23626358e+02 2.30724655e+02 2.25096313e+02 2.23330795e+02 2.13561981e+02 2.18915924e+02 2.21742477e+02 2.30770309e+02 2.44144867e+02 2.48655167e+02 2.52606445e+02 2.32861038e+02 2.24722412e+02 2.35212097e+02 2.44841278e+02 2.40421036e+02 2.16840958e+02 2.09518692e+02 2.15149048e+02 2.26183777e+02 2.33423508e+02 2.34791458e+02 2.29027100e+02 2.25482758e+02 2.24270172e+02 2.33981216e+02 2.31315186e+02 2.26271515e+02 2.17656693e+02 2.08453293e+02 2.02747742e+02 1.98685715e+02 2.08074753e+02 2.22383957e+02 2.30137497e+02 2.29830902e+02 2.22772797e+02 2.22044891e+02 2.30361908e+02 2.39509232e+02 2.42107162e+02 2.31736832e+02 2.19037933e+02 2.14333267e+02 2.17555191e+02 2.23135086e+02 2.25468521e+02 2.25053421e+02 2.23837921e+02 2.21642456e+02 2.24101593e+02 2.27373611e+02 2.29610474e+02 2.27394272e+02 2.26635422e+02 2.26139648e+02 2.25499069e+02 2.25551132e+02 2.26875305e+02 2.28008026e+02 2.27925964e+02 2.28050339e+02 2.28540985e+02 2.29031067e+02 2.28950333e+02 2.28651718e+02 2.28434265e+02 2.28475388e+02 2.29326401e+02 2.29997086e+02 2.29400635e+02 2.27697601e+02 2.26954346e+02 2.28169495e+02 2.29491608e+02 2.29049332e+02 2.28711395e+02 2.28396790e+02 2.28054520e+02 2.28081909e+02 2.28325027e+02 2.28370361e+02 2.28332108e+02 2.26896896e+02 2.26386353e+02 2.23954620e+02 2.24676025e+02 2.25126221e+02 2.26857330e+02 2.26090668e+02 2.25965439e+02 2.27914871e+02 2.28174164e+02 2.29870209e+02 2.30884628e+02 2.32342422e+02 2.31014679e+02 2.27808655e+02 2.27665466e+02 2.27405441e+02 2.26148285e+02 2.23812683e+02 2.24415466e+02 2.25205780e+02 2.25385712e+02 2.23905243e+02 2.24637100e+02 2.25173706e+02 2.24198090e+02 2.21136383e+02 2.20373291e+02 2.17812531e+02 2.17255280e+02 2.18760361e+02 2.20217651e+02 2.22197220e+02 2.19606903e+02 2.18990326e+02 2.17477554e+02 2.18810928e+02 2.19414597e+02 2.23324051e+02 2.22733139e+02 2.21989441e+02 2.16927429e+02 2.18959686e+02 2.18564774e+02 2.19313004e+02 2.18573242e+02 2.22971985e+02 2.23647003e+02 2.20085114e+02 2.16358994e+02 2.18374039e+02 2.18875748e+02 2.15368591e+02 2.17659958e+02 2.23981110e+02 2.27434830e+02 2.24977707e+02 2.23895905e+02 2.22663162e+02 2.24307785e+02 2.20680771e+02 2.22798553e+02 2.21324738e+02 2.23017288e+02 2.24707870e+02 2.26566406e+02 2.23529160e+02 2.20203018e+02 2.16568283e+02 2.20497818e+02 2.14233978e+02 2.02862915e+02 1.98953888e+02 2.06614670e+02 2.20803421e+02 2.21314606e+02 2.19390442e+02 2.18207169e+02 2.18737167e+02 2.22764908e+02 2.24066208e+02 2.22249283e+02 2.22133301e+02 2.24023987e+02 2.27420090e+02 2.19580353e+02 2.15697662e+02 2.14833603e+02 2.16569031e+02 2.13307770e+02 2.13144592e+02 2.13734818e+02 2.15428482e+02 2.22325241e+02 2.25666336e+02 2.22958694e+02 2.13346786e+02 2.06662262e+02 2.08777206e+02 2.14682999e+02 2.19986053e+02 2.18704651e+02 2.05532623e+02 1.92704575e+02 1.94138977e+02 2.04048782e+02 2.19030380e+02 2.18713745e+02 2.17143585e+02 2.08791992e+02 2.01734573e+02 1.94484879e+02 1.87215393e+02 1.85239243e+02 1.85454666e+02 1.88431961e+02 1.98562164e+02 2.02459381e+02 2.00758026e+02 1.97052933e+02 2.00411774e+02 1.97806335e+02 1.91477890e+02 1.89155029e+02 1.91249954e+02 1.97309296e+02 1.94480621e+02 1.81155243e+02 1.62116348e+02 1.64230148e+02 1.86065918e+02 2.03517990e+02 1.93217804e+02 1.71878525e+02 1.68824646e+02 1.74494263e+02 1.91815231e+02 1.85581818e+02 1.77196228e+02 1.69541718e+02 1.69960281e+02 1.74347107e+02 1.67213852e+02 1.51036163e+02 1.35284561e+02 1.50523163e+02 1.80217255e+02 1.90855743e+02 1.78506958e+02 1.73141632e+02 1.78430832e+02 1.85781891e+02 1.89040298e+02 1.79146347e+02 1.63578552e+02 1.57008255e+02 1.73540497e+02 1.96269760e+02 1.95351700e+02 1.86815414e+02 1.79782013e+02 1.95864639e+02 2.24159088e+02 2.33403717e+02 2.06966766e+02 1.81741226e+02 1.72531815e+02 1.76948822e+02 1.60912689e+02 1.54830170e+02 1.82671555e+02 2.20880066e+02 2.28618805e+02 2.01156876e+02 1.71243607e+02 1.69723297e+02 1.69301819e+02 1.86724472e+02 2.00577667e+02 1.92651566e+02 1.73258240e+02 1.47513718e+02 1.51601654e+02 1.47954285e+02 1.77985886e+02 2.18542892e+02 2.20143326e+02 1.97706390e+02 1.71221497e+02 1.63177429e+02 1.48007736e+02 1.34941605e+02 1.49979080e+02 1.66546249e+02 1.75604477e+02 1.74270706e+02 1.69023010e+02 1.75312164e+02 1.82336639e+02 1.87893814e+02 1.86788589e+02 1.89629837e+02 1.17767715e+02 2.02057037e+02 -3.99332161e+01 -1.49364975e+02 -3.67199341e+02 -2.06787891e+03 -3.43265088e+03 -8.15973486e+03 -1.89022998e+03 -5.35594629e+03 -2.18023730e+04 80638648. 162401248. -72514064. 94560432. -166013808. -56322572. 782541056. 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. 0. 0. -859660928. -859660928. -859660928. 0. 0. 1923205760. -120397120. -65511108. -2.33428320e+04 -1.08983770e+04 -1.13037952e+03 -4.03780579e+02 -4.19740869e+03 -2.65745605e+03 -3.34979919e+02 -6.79073191e+00 7.40276108e+01 6.07411003e+01 5.80992126e+01 6.13595810e+01 7.14981003e+01 6.27901764e+01 5.30764580e+01 4.84902267e+01 5.34568672e+01 8.09849548e+01 9.35453491e+01 8.69994354e+01 5.79953384e+01 5.73199005e+01 7.86518784e+01 1.14566841e+02 1.22486916e+02 1.27652428e+02 1.34969650e+02 1.42763245e+02 1.49173706e+02 1.51576950e+02 1.56040344e+02 1.58105560e+02 1.59657333e+02 1.56629456e+02 1.46548080e+02 1.49760010e+02 1.48916153e+02 1.56703094e+02 1.39352142e+02 1.35245483e+02 1.39965851e+02 1.53580536e+02 1.58542847e+02 1.59065826e+02 1.54278824e+02 1.41387421e+02 1.03789459e+02 7.26013641e+01 6.50217743e+01 8.16351852e+01 1.04051125e+02 1.15834267e+02 1.28051682e+02 1.17473526e+02 9.73491287e+01 9.57590866e+01 1.09680534e+02 1.25711884e+02 1.24174538e+02 1.36285294e+02 1.21247498e+02 9.64310379e+01 7.91447449e+01 6.40847321e+01 5.91620941e+01 5.56438484e+01 6.93614960e+01 8.02290726e+01 7.51519165e+01 7.54497528e+01 1.06017647e+02 1.17738609e+02 1.13365211e+02 8.93729553e+01 8.41012573e+01 9.22110367e+01 6.31423492e+01 1.89323330e+01 2.09398651e+01 3.73037338e+01 6.31509438e+01 6.40006113e+00 -3.76004219e+01 -4.38766632e+01 -5.10848951e+00 1.86240768e+01 1.50528336e+01 9.22678185e+00 2.68343906e+01 2.46379738e+01 -9.79915333e+00 -4.99121056e+01 -3.71011124e+01 1.07966471e+01 5.27175636e+01 6.60183716e+01 5.69210510e+01 4.69069519e+01 3.20084114e+01 6.55984268e+01 9.53841553e+01 7.88205032e+01 3.77097054e+01 3.02425365e+01 6.16686783e+01 8.20411148e+01 3.53157768e+01 7.74248302e-01 1.42268252e+00 4.45082664e+01 8.45470276e+01 9.07869949e+01 8.83462067e+01 8.00565491e+01 7.26757584e+01 6.07605057e+01 5.96136436e+01 5.91613770e+01 5.26505013e+01 4.22510872e+01 3.37791519e+01 3.81256180e+01 4.48077393e+01 4.73348618e+01 4.52423515e+01 4.24789009e+01 6.61735058e+00 -3.29079933e+01 -3.36125526e+01 -2.27187562e+00 3.12476654e+01 -1.04008474e+01 -5.22896538e+01 -5.40080490e+01 -2.11789036e+01 6.79572058e+00 5.95429468e+00 1.48343668e+01 3.41206627e+01 2.77662334e+01 1.63514576e+01 1.28215971e+01 2.79526443e+01 5.04450073e+01 5.00138779e+01 3.60089264e+01 1.03336849e+01 8.46475315e+00 1.98258305e+00 5.19193459e+00 -9.31449699e+00 -5.17086372e+01 -9.93400421e+01 -1.02498795e+02 -6.81676407e+01 -2.18514633e+01 -5.30237999e+01 -8.75441132e+01 -8.91332169e+01 -4.32861481e+01 -4.88345051e+00 -8.31669331e+00 -1.35162725e+01 -1.64106731e+01 -1.48659573e+01 -2.02840347e+01 -1.86456566e+01 -1.50908928e+01 -9.42728901e+00 -3.62485046e+01 -6.01360435e+01 -5.84697495e+01 -2.75793209e+01 6.82081223e-01 2.21639490e+00 4.74387026e+00 -2.65703049e+01 -6.01715317e+01 -6.40369034e+01 -4.49152832e+01 -2.10451088e+01 -1.86408024e+01 -1.83920026e+00 -3.18902016e+01 -8.40775986e+01 -9.69285049e+01 -6.18927155e+01 -2.23752155e+01 -2.91768723e+01 -3.78692856e+01 -3.02396603e+01 -2.67790279e+01 -4.11984367e+01 -4.55688515e+01 -8.78946609e+01 -1.24713730e+02 -1.25328888e+02 -8.18567657e+01 -4.15021706e+01 -5.95240097e+01 -6.14771690e+01 -9.43222885e+01 -1.20326912e+02 -1.14116501e+02 -6.23667793e+01 -1.65946369e+01 -2.38939629e+01 -3.45813522e+01 -4.54105186e+01 -3.54618797e+01 -2.75505047e+01 -1.73252602e+01 -1.47840776e+01 -2.39528427e+01 -2.90784473e+01 -2.76518650e+01 -3.03341160e+01 -1.11063328e+01 -1.72260538e-01 1.56297693e+01 1.48474646e+01 2.55210817e-01 -2.63164783e+00 -3.01386428e+00 -3.01209760e+00 -1.31794128e+01 -1.94618950e+01 -1.13370657e+01 -2.14838409e+01 -2.63712730e+01 -2.67780266e+01 -8.06751633e+00 -4.07479763e+00 -1.40301266e+01 -2.51858425e+01 -3.28548279e+01 -2.94589100e+01 -4.07898788e+01 -4.00091934e+01 -5.86175766e+01 -6.15424309e+01 -6.27888031e+01 -3.65870743e+01 -4.12889242e+00 -2.33410683e+01 -7.50771866e+01 -1.14434006e+02 -1.03266907e+02 -8.01213760e+01 -7.06668930e+01 -8.24540863e+01 -9.04503403e+01 -1.00767372e+02 -9.61230469e+01 -9.05373077e+01 -8.32561569e+01 -6.94184952e+01 -5.58938828e+01 -4.94382019e+01 -6.15606194e+01 -7.77583618e+01 -9.21862030e+01 -9.12640991e+01 -8.27008743e+01 -7.44340134e+01 -6.56381607e+01 -6.43263168e+01 -6.38551331e+01 -7.99266052e+01 -1.14581665e+02 -1.44927795e+02 -1.48207138e+02 -1.26738815e+02 -9.72245712e+01 -8.51474686e+01 -8.58874969e+01 -1.06673630e+02 -1.34688919e+02 -1.49801987e+02 -1.58274078e+02 -1.35005737e+02 -1.14154701e+02 -8.03443527e+01 -8.82376404e+01 -9.44512024e+01 -9.57693481e+01 -8.40312958e+01 -7.96429825e+01 -7.32184525e+01 -8.20307693e+01 -9.27907944e+01 -1.09360924e+02 -1.19662979e+02 -1.22103783e+02 -1.53973282e+02 -1.80712769e+02 -1.69276230e+02 -1.27971535e+02 -9.42087097e+01 -1.13567673e+02 -1.32856506e+02 -1.26568001e+02 -1.18148438e+02 -1.37749496e+02 -1.75917404e+02 -1.77395401e+02 -1.44816696e+02 -1.06047890e+02 -1.20607384e+02 -1.29848236e+02 -1.24312584e+02 -1.04472328e+02 -1.00845955e+02 -1.08052032e+02 -1.14349060e+02 -1.01823242e+02 -8.01239319e+01 -8.07014694e+01 -8.69645004e+01 -9.99762650e+01 -9.53278580e+01 -1.18982735e+02 -1.46017731e+02 -1.59661697e+02 -1.71896881e+02 -1.95732788e+02 -2.23633240e+02 -2.30160889e+02 -2.09583221e+02 -2.05536743e+02 -1.85413849e+02 -1.83912674e+02 -1.54565475e+02 -1.13414383e+02 -6.54901581e+01 -5.72606468e+01 -7.45996704e+01 -8.94862747e+01 -9.63935318e+01 -1.00552544e+02 -1.09319756e+02 -1.06966202e+02 -9.97245178e+01 -1.22357552e+02 -1.62579163e+02 -1.77467712e+02 -1.70586487e+02 -1.43759308e+02 -1.38278748e+02 -1.34403625e+02 -1.18897049e+02 -1.41720016e+02 -1.49633820e+02 -1.61275345e+02 -1.59048248e+02 -1.75420959e+02 -2.07220047e+02 -1.90725220e+02 -1.59227661e+02 -1.45045090e+02 -1.80919067e+02 -1.91042648e+02 -1.76327164e+02 -1.39910141e+02 -1.67533569e+02 -1.94781952e+02 -2.05436508e+02 -1.87739532e+02 -1.66057709e+02 -1.97882385e+02 -2.25622162e+02 -2.20708374e+02 -1.84020340e+02 -1.52953934e+02 -1.78218994e+02 -1.94707184e+02 -1.67241165e+02 -1.24694351e+02 -1.44433746e+02 -1.91825562e+02 -2.17028198e+02 -2.08952576e+02 -1.94702209e+02 -1.92823212e+02 -2.15516815e+02 -2.40345474e+02 -2.35196503e+02 -1.88713120e+02 -1.56392227e+02 -1.57271164e+02 -1.67718338e+02 -1.69129364e+02 -1.65411514e+02 -1.62241928e+02 -1.63404877e+02 -1.75649567e+02 -1.78877823e+02 -1.65579407e+02 -1.63912689e+02 -1.69132721e+02 -1.95904465e+02 -2.09774933e+02 -2.02001511e+02 -1.94087097e+02 -1.77373718e+02 -1.79146805e+02 -1.76464233e+02 -1.67709991e+02 -1.58669266e+02 -1.61568512e+02 -2.04491821e+02 -2.38297104e+02 -2.04286819e+02 -1.43923431e+02 -1.39743027e+02 -1.93982483e+02 -2.12305374e+02 -1.83428848e+02 -1.64166626e+02 -1.84429214e+02 -2.00128311e+02 -1.98034576e+02 -1.78081161e+02 -1.90156631e+02 -1.97796173e+02 -2.03792664e+02 -1.88582001e+02 -1.69622101e+02 -1.75017120e+02 -1.76989044e+02 -2.01369110e+02 -2.17373047e+02 -2.22879593e+02 -1.98092575e+02 -1.98352188e+02 -2.39356812e+02 -2.68730896e+02 -2.50604950e+02 -2.12672989e+02 -2.13097321e+02 -2.32058121e+02 -2.13043320e+02 -1.69674683e+02 -1.50266418e+02 -1.73861679e+02 -1.95430481e+02 -1.96747711e+02 -1.94652328e+02 -2.07189758e+02 -2.08988892e+02 -2.07947266e+02 -2.00060867e+02 -1.92468536e+02 -1.82739853e+02 -1.78170563e+02 -1.82753738e+02 -1.93373962e+02 -2.08418289e+02 -2.14780762e+02 -2.16519592e+02 -2.24131317e+02 -2.26131958e+02 -2.17230804e+02 -2.02128433e+02 -2.06440781e+02 -2.29300812e+02 -2.34524124e+02 -2.28814835e+02 -2.38169510e+02 -2.70936737e+02 -2.89977448e+02 -2.70956696e+02 -2.32598038e+02 -2.25045822e+02 -2.33316772e+02 -2.35625931e+02 -2.17948456e+02 -2.04671875e+02 -2.00337875e+02 -1.99412186e+02 -1.96224869e+02 -2.04541199e+02 -2.02575455e+02 -1.97895050e+02 -1.97307999e+02 -2.24952759e+02 -2.40705154e+02 -2.23374527e+02 -2.07970245e+02 -2.28077759e+02 -2.45978119e+02 -2.27837982e+02 -1.90918533e+02 -1.68490509e+02 -1.72116150e+02 -1.76676575e+02 -1.87299637e+02 -1.88328400e+02 -1.91159592e+02 -1.86449249e+02 -1.97080353e+02 -2.01064941e+02 -2.04488983e+02 -1.90764954e+02 -2.04081573e+02 -2.33291962e+02 -2.55373505e+02 -2.58830536e+02 -2.52132507e+02 -2.42154465e+02 -2.30808655e+02 -2.16818298e+02 -2.17525101e+02 -2.14141846e+02 -2.15149979e+02 -2.13764572e+02 -2.18631653e+02 -2.15986465e+02 -2.16521896e+02 -2.17955841e+02 -2.15956161e+02 -2.16603088e+02 -2.13108521e+02 -2.31909317e+02 -2.47329422e+02 -2.49366013e+02 -2.33972534e+02 -2.22684357e+02 -2.25869904e+02 -2.27360809e+02 -2.27454926e+02 -2.25554001e+02 -2.26143661e+02 -2.25826263e+02 -2.34156281e+02 -2.45176590e+02 -2.40830048e+02 -2.27746750e+02 -2.25715622e+02 -2.47760773e+02 -2.61898529e+02 -2.50792206e+02 -2.30210449e+02 -2.29232330e+02 -2.39619904e+02 -2.39049057e+02 -2.32455200e+02 -2.23571259e+02 -2.33676208e+02 -2.41806885e+02 -2.48514648e+02 -2.52577972e+02 -2.40749832e+02 -2.33791260e+02 -2.32656357e+02 -2.51737198e+02 -2.58724854e+02 -2.44680878e+02 -2.27999115e+02 -2.31421219e+02 -2.45726685e+02 -2.48111588e+02 -2.40707047e+02 -2.32000061e+02 -2.38217484e+02 -2.45395676e+02 -2.48727081e+02 -2.43357224e+02 -2.36887268e+02 -2.33370605e+02 -2.40568848e+02 -2.48063065e+02 -2.50057266e+02 -2.43177628e+02 -2.32395920e+02 -2.36607254e+02 -2.41691986e+02 -2.42191162e+02 -2.35866943e+02 -2.35947083e+02 -2.42913712e+02 -2.41225052e+02 -2.34286179e+02 -2.26769394e+02 -2.25929367e+02 -2.25349213e+02 -2.30074158e+02 -2.35543854e+02 -2.38572632e+02 -2.35494431e+02 -2.31130951e+02 -2.29344559e+02 -2.30003799e+02 -2.32972351e+02 -2.36984909e+02 -2.51446976e+02 -2.62912231e+02 -2.50553757e+02 -2.60723602e+02 -2.81704590e+02 -2.86325165e+02 -2.90171326e+02 -2.60250427e+02 -2.51821594e+02 -5.02887390e+02 -7.42067993e+02 -8.90290710e+02 -1.67442798e+03 -3.55834717e+03 297563104. -1244824576. 0. 0. 0. 0. 357199328. 357199328. -692914048. -145753472. -7.42732080e+03 45655232. 111135896. 281210752. 155932272. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 663051200. 105610992. -1.33806714e+03 -9.84275635e+02 -1.01729419e+03 -8.41887390e+02 -7.92404785e+02 -6.60970581e+02 -4.86126923e+02 -2.51540054e+02 -2.50893524e+02 -2.14610291e+02 -2.01736435e+02 -1.92012451e+02 -1.91292969e+02 -1.98095490e+02 -1.99861664e+02 -1.96102264e+02 -1.98533920e+02 -2.06503784e+02 -2.13741165e+02 -2.06331711e+02 -1.90028442e+02 -1.81785828e+02 -1.86829559e+02 -1.99001266e+02 -2.04897308e+02 -2.02292603e+02 -1.98781830e+02 -2.02549881e+02 -2.09578491e+02 -2.05327682e+02 -1.94857834e+02 -1.88274185e+02 -1.92063507e+02 -2.03210434e+02 -2.06481430e+02 -1.97308777e+02 -1.80956390e+02 -1.73866394e+02 -1.80425903e+02 -1.81380814e+02 -1.73356110e+02 -1.77643417e+02 -1.95681015e+02 -2.10949829e+02 -1.97052292e+02 -1.61999084e+02 -1.53113327e+02 -1.69210815e+02 -1.89175705e+02 -1.98825897e+02 -1.96811615e+02 -1.92325684e+02 -1.89435333e+02 -1.94997086e+02 -1.93272476e+02 -1.66804840e+02 -1.47367004e+02 -1.52728439e+02 -1.77039490e+02 -1.92137589e+02 -1.83821136e+02 -1.69130478e+02 -1.60340103e+02 -1.73246445e+02 -1.74478287e+02 -1.67766129e+02 -1.75747284e+02 -1.96827835e+02 -2.20931931e+02 -2.18000946e+02 -1.83274658e+02 -1.68325043e+02 -1.77685135e+02 -2.02709854e+02 -1.97850616e+02 -1.74190445e+02 -1.80331635e+02 -1.96002365e+02 -2.06752228e+02 -1.92476761e+02 -1.57540207e+02 -1.43884171e+02 -1.52442123e+02 -1.89724884e+02 -2.12345169e+02 -2.05497086e+02 -1.87940140e+02 -1.86404312e+02 -2.05306061e+02 -2.05215271e+02 -1.82149582e+02 -1.69913254e+02 -1.90917496e+02 -2.27727188e+02 -2.30762100e+02 -1.96238800e+02 -1.60796600e+02 -1.59805862e+02 -1.84411026e+02 -1.91413940e+02 -1.83371979e+02 -1.98273087e+02 -2.30354492e+02 -2.49462296e+02 -2.18338699e+02 -1.68209824e+02 -1.38006485e+02 -1.53076630e+02 -1.82720932e+02 -2.21873093e+02 -2.41839890e+02 -2.36614044e+02 -2.24856781e+02 -2.29374374e+02 -2.23756363e+02 -1.88233322e+02 -1.52128647e+02 -1.70169556e+02 -2.29503403e+02 -2.52341263e+02 -2.25074081e+02 -1.66217010e+02 -1.40450638e+02 -1.68828186e+02 -1.94678177e+02 -2.02689743e+02 -1.93018478e+02 -2.15338089e+02 -2.61006775e+02 -2.59167114e+02 -2.09652359e+02 -1.66946365e+02 -1.68235291e+02 -2.02334854e+02 -2.23827240e+02 -2.29089462e+02 -2.15353088e+02 -1.91274445e+02 -1.78826218e+02 -2.09376282e+02 -2.21562195e+02 -1.95224457e+02 -1.73190552e+02 -1.70269836e+02 -1.86881683e+02 -1.86278534e+02 -1.61132462e+02 -1.63044434e+02 -1.85143326e+02 -2.13533401e+02 -2.24294876e+02 -1.92965225e+02 -1.78888626e+02 -1.88830765e+02 -2.11026245e+02 -1.91077423e+02 -1.12069679e+02 -7.75038300e+01 -1.18529068e+02 -1.87712524e+02 -2.00717804e+02 -1.66506363e+02 -1.45841248e+02 -1.50607697e+02 -1.47618347e+02 -1.20131767e+02 -8.36176605e+01 -7.51829147e+01 -9.14359131e+01 -1.41943420e+02 -1.78055542e+02 -1.51291794e+02 -1.28573761e+02 -1.35316589e+02 -1.67443665e+02 -1.47510529e+02 -8.03596954e+01 -8.84824448e+01 -1.16365585e+02 -1.41911926e+02 -1.05765038e+02 -2.98419800e+01 3.31406236e+00 -3.44228096e+01 -1.09001556e+02 -1.54906281e+02 -1.43275528e+02 -1.56209091e+02 -1.71957031e+02 -1.60864624e+02 -1.09635704e+02 -4.78736992e+01 -5.42548561e+01 -9.95031891e+01 -1.85611526e+02 -2.25544998e+02 -2.01387711e+02 -1.38212479e+02 -9.03742371e+01 -8.71529846e+01 -7.50860062e+01 -4.93878288e+01 -6.79526672e+01 -1.16947815e+02 -1.78716904e+02 -1.43954391e+02 -6.20233307e+01 -2.70376320e+01 -7.23228531e+01 -1.70740250e+02 -1.95036942e+02 -1.56827744e+02 -9.57327423e+01 -1.18676903e+02 -1.63885895e+02 -1.59573105e+02 -1.02190498e+02 -8.15074234e+01 -1.37967453e+02 -2.20185608e+02 -2.26741318e+02 -1.85909637e+02 -1.42184814e+02 -1.45622055e+02 -1.64739136e+02 -1.62015884e+02 -1.37589828e+02 -1.58730515e+02 -1.90156509e+02 -1.99991638e+02 -1.88341797e+02 -1.36633423e+02 -1.21629776e+02 -1.29520920e+02 -1.33121628e+02 -1.35376221e+02 -1.00236740e+02 -1.38514740e+02 -1.78238205e+02 -2.08826721e+02 -1.84377655e+02 -8.76718979e+01 -2.01035976e+01 -3.16887646e+01 -1.40394852e+02 -2.04971680e+02 -2.05902420e+02 -1.58042221e+02 -1.28969788e+02 -1.62492752e+02 -1.67978897e+02 -1.41777557e+02 -1.14095650e+02 -1.41529800e+02 -1.65089798e+02 -1.07837410e+02 -3.29164505e+01 -4.90708389e+01 -8.88632812e+01 -1.13441750e+02 -9.26373901e+01 -4.82294464e+01 -9.90532455e+01 -1.33926010e+02 -1.74854752e+02 -1.45782455e+02 -7.83376617e+01 -4.11118546e+01 -1.52444410e+01 -6.92995529e+01 -1.00430382e+02 -1.09450386e+02 -6.68823776e+01 -5.91814499e+01 -6.63279343e+01 -5.05225639e+01 -1.61610851e+01 6.56894922e-01 -6.65919266e+01 -1.07797455e+02 -1.04542549e+02 -5.13545647e+01 -6.46975327e+01 -9.32528687e+01 -1.22182907e+02 -1.39401276e+02 -1.24690826e+02 -1.31729080e+02 -7.13071823e+01 -4.92053719e+01 -2.38633175e+01 -3.19969425e+01 -5.07909698e+01 -7.07270126e+01 -1.34599106e+02 -1.59183640e+02 -1.48025177e+02 -5.62180481e+01 -3.77268143e+01 -5.24769974e+01 -8.21426773e+01 -6.15023041e+01 -8.53841324e+01 -1.69433105e+02 -2.14168808e+02 -1.77507599e+02 -6.57259521e+01 -3.67581100e+01 -7.36870651e+01 -1.37591965e+02 -1.52071915e+02 -9.17993927e+01 -8.45689926e+01 -7.61144791e+01 -1.45285126e+02 -1.67036530e+02 -1.78336456e+02 -1.15847839e+02 -9.49218445e+01 -1.26905403e+02 -1.72953461e+02 -1.41456223e+02 -7.15610962e+01 -9.88858490e+01 -1.39486893e+02 -1.39302429e+02 -9.69388199e+01 -9.60691452e+01 -1.65264389e+02 -1.96819504e+02 -1.73395065e+02 -8.45900040e+01 -8.70004959e+01 -1.12774185e+02 -1.57823792e+02 -1.34394028e+02 -9.27469330e+01 -9.97602997e+01 -8.72318420e+01 -1.33613541e+02 -1.45174438e+02 -1.54597473e+02 -1.19325150e+02 -1.10033081e+02 -1.36723373e+02 -1.71676407e+02 -1.47453033e+02 -8.22990646e+01 -6.25385590e+01 -5.71307869e+01 -3.66567879e+01 2.16888008e+01 4.97566253e-01 -6.10858955e+01 -6.74949951e+01 -2.51694546e+01 2.81715107e+01 -3.29401894e+01 -6.45812759e+01 -9.57772217e+01 -1.36212769e+02 -1.48117722e+02 -1.10973885e+02 -6.34425306e+00 1.67474060e+01 -5.03924026e+01 -1.28221405e+02 -8.97670898e+01 -4.09389734e+00 5.29677467e+01 -2.63156700e+00 -4.79297485e+01 -3.56059189e+01 -1.31648111e+01 2.85549660e+01 7.90717239e+01 1.50101791e+02 1.25726295e+02 5.37144470e+01 3.41631470e+01 6.28693123e+01 1.09143562e+02 2.21693745e+01 -1.36037502e+01 -4.30290489e+01 -2.79539375e+01 -2.43708267e+01 1.91951599e+01 1.31657761e+02 1.67783951e+02 8.19245911e+01 -6.76661377e+01 -1.20489769e+02 4.49724913e+00 1.23624619e+02 1.32728928e+02 4.85678520e+01 -9.56038094e+00 2.09577713e+01 1.01508186e+02 1.43580490e+02 1.06558022e+02 -1.91844788e+01 -4.35132332e+01 1.60080261e+01 1.01097832e+02 1.91798019e+02 1.84581268e+02 1.47262711e+02 3.37578545e+01 -8.39907303e+01 -1.35700089e+02 -6.36025467e+01 9.76424408e+01 1.81049942e+02 1.03161964e+02 -1.36022558e+01 -6.95109320e+00 1.15720749e+02 2.25885666e+02 1.82421310e+02 5.71324883e+01 -4.31589851e+01 -5.08141785e+01 3.06200123e+01 1.00736389e+02 1.58057693e+02 8.69103699e+01 4.80236130e+01 6.21283722e+00 5.48521118e+01 8.85180435e+01 4.71156044e+01 -2.50082626e+01 -1.01160469e+02 -1.10096832e+02 -5.39437370e+01 2.40012341e+01 1.35096512e+02 1.59663742e+02 7.56487350e+01 -8.40547485e+01 -1.58509171e+02 -7.94490356e+01 7.85738220e+01 1.62936707e+02 1.18601425e+02 4.94014778e+01 5.28120270e+01 1.09337975e+02 1.34136810e+02 1.39143143e+02 6.01182709e+01 1.74573860e+01 -4.10515060e+01 -4.19870529e+01 6.05873632e+00 5.53736954e+01 1.16234024e+02 9.24260406e+01 4.60033302e+01 -2.23516674e+01 -1.87255363e+01 3.87590370e+01 1.19284500e+02 8.54485626e+01 2.25882397e+01 -1.82456913e+01 4.13558655e+01 1.38241135e+02 1.39252167e+02 6.73860626e+01 -5.51410828e+01 -5.05881844e+01 4.17392540e+01 1.19500923e+02 1.59356598e+02 6.73752365e+01 3.55838470e+01 3.86311769e+00 7.76140165e+00 4.54880857e+00 3.59167480e+00 4.30826797e+01 1.72344742e+01 -1.60154343e+01 -1.49826276e+00 5.63045006e+01 1.57028946e+02 1.84460831e+02 1.21569733e+02 -2.12506523e+01 -1.31141968e+02 -1.11064461e+02 1.97326870e+01 1.50833359e+02 1.95927078e+02 9.64868698e+01 -9.65571499e+00 -2.98538933e+01 4.88967476e+01 1.38726151e+02 1.12752419e+02 4.80594444e+01 -2.59254112e+01 -3.76863365e+01 -1.39719009e+01 5.17499847e+01 1.23726929e+02 1.18829819e+02 4.38044090e+01 -5.91599846e+01 -8.31376419e+01 7.32640409e+00 1.01649117e+02 9.53943024e+01 1.13835926e+01 -3.61738892e+01 -8.12853241e+00 3.86073494e+01 5.96599236e+01 7.85501175e+01 5.69565735e+01 2.97862740e+01 5.62793236e+01 6.29353752e+01 1.00085670e+02 5.64362106e+01 2.61799107e+01 -3.06935902e+01 -5.67216492e+01 -1.83689480e+01 3.50239105e+01 1.11431084e+02 1.43762634e+02 1.00869537e+02 2.24648781e+01 9.69300842e+00 8.73731384e+01 1.80492035e+02 1.70862305e+02 1.12901733e+02 1.95432148e+01 7.47604907e-01 3.76872368e+01 8.29841919e+01 9.67695847e+01 2.28834000e+01 -3.62130432e+01 -8.72256927e+01 -6.57703018e+01 1.71536694e+01 1.77580490e+01 -1.07250824e+01 -8.64401169e+01 -9.74649658e+01 -7.23410492e+01 -1.49070120e+01 8.81128006e+01 1.36163635e+02 1.14628197e+02 3.61141243e+01 -9.54710770e+00 5.33016701e+01 1.34827850e+02 1.35291214e+02 4.55498085e+01 -2.40098248e+01 3.30208635e+00 8.84824677e+01 1.57960358e+02 1.68423050e+02 9.36688614e+01 8.02186108e+00 -1.20316648e+01 2.01153731e+00 3.41254501e+01 6.22135429e+01 1.09113678e+02 1.15802361e+02 9.48779678e+01 7.30617447e+01 1.06152954e+02 1.77751648e+02 2.24646896e+02 1.65552780e+02 7.04049149e+01 2.05079765e+01 6.53761902e+01 1.60647980e+02 1.75403214e+02 1.33701492e+02 4.91960983e+01 4.33033867e+01 9.51448975e+01 1.20125816e+02 1.24726593e+02 6.88794174e+01 5.51889839e+01 6.72942276e+01 9.13594131e+01 1.37272034e+02 1.26419289e+02 1.19604469e+02 5.20937500e+01 -5.20174578e-02 1.43979397e+01 5.82533150e+01 1.29852036e+02 1.82118103e+02 1.83932693e+02 1.26976318e+02 3.24144673e+00 -2.36646557e+01 3.98831797e+00 -6.87098846e+01 -5.05289246e+02 -5.75851904e+03 -1.27426934e+04 50594832. -247784640. 147008224. -182095648. 273444416. 211863024. 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. 0. 0. 0. 0. 0. 0. 0. 0. 832060288. -590784000. 59325776. 254382512. 143809264. 2.32940859e+04 1.03033408e+04 1.59178491e+03 -2.89435278e+03 -2.03084888e+03 -1.85243546e+02 3.61312561e+01 1.04903656e+02 1.15047554e+02 7.49936752e+01 7.59126663e+01 1.05994553e+02 1.97546753e+02 1.95153030e+02 1.55257462e+02 9.31686249e+01 1.09953911e+02 1.79578644e+02 2.30929108e+02 2.35603104e+02 1.82197372e+02 1.02960014e+02 8.84068604e+01 1.41445908e+02 2.10197769e+02 2.10382675e+02 1.63560913e+02 1.60315857e+02 1.97091980e+02 2.10466278e+02 1.83215179e+02 1.47220169e+02 1.45865891e+02 1.34450546e+02 1.15270683e+02 1.15150642e+02 1.54420090e+02 2.28469452e+02 2.36540192e+02 1.89791000e+02 1.48607071e+02 1.48539948e+02 1.97007309e+02 2.43095108e+02 2.35995926e+02 1.66753143e+02 8.93345795e+01 9.69433060e+01 1.73650925e+02 2.13640533e+02 2.21473663e+02 1.76968811e+02 1.63678131e+02 1.59107880e+02 1.53104156e+02 1.64131424e+02 1.79431381e+02 2.16358780e+02 2.01403687e+02 1.65576889e+02 1.58830231e+02 1.85288101e+02 2.35142822e+02 2.34487381e+02 2.09941971e+02 1.72134415e+02 1.55200592e+02 1.95369507e+02 2.49683411e+02 2.92256683e+02 2.65818665e+02 2.06161865e+02 1.85514801e+02 2.23589890e+02 2.49876526e+02 2.44218796e+02 1.89069092e+02 1.78725250e+02 1.93951660e+02 2.19700714e+02 2.15711441e+02 2.17817642e+02 2.31214233e+02 2.09874435e+02 1.73941620e+02 1.55922104e+02 1.97825470e+02 2.51367935e+02 2.64670624e+02 2.44198486e+02 2.15263138e+02 1.83331177e+02 1.79188965e+02 2.01660675e+02 2.27347534e+02 2.19487289e+02 1.74385574e+02 1.53659546e+02 1.95693726e+02 2.26872894e+02 2.28914139e+02 1.77016953e+02 1.57302628e+02 1.63580902e+02 1.71499771e+02 1.78785187e+02 1.94155579e+02 2.29321991e+02 2.28716034e+02 1.98501770e+02 1.73519608e+02 1.76757553e+02 2.05171143e+02 2.11515854e+02 1.92542709e+02 1.78050369e+02 1.60411835e+02 1.68348221e+02 1.96813644e+02 2.26618546e+02 2.34592484e+02 1.93400162e+02 1.73182114e+02 1.89501099e+02 2.01695770e+02 2.03531067e+02 1.83665924e+02 1.86349075e+02 1.90161011e+02 1.81232559e+02 1.74650818e+02 1.80093384e+02 2.09014755e+02 2.12886429e+02 1.90691391e+02 1.76415131e+02 1.76702850e+02 1.99047501e+02 1.94647568e+02 1.79118210e+02 1.66429916e+02 1.57792557e+02 1.72281647e+02 1.96668091e+02 2.16017288e+02 2.14092117e+02 1.94172150e+02 1.90184479e+02 1.96174240e+02 1.95126770e+02 1.89199356e+02 1.76320053e+02 1.69407532e+02 1.65820663e+02 1.64742645e+02 1.74114349e+02 1.89586105e+02 2.08700500e+02 2.13171539e+02 2.06434967e+02 1.96737305e+02 1.98610519e+02 2.11307251e+02 2.24925919e+02 2.15455276e+02 1.94477188e+02 1.77042053e+02 1.78561401e+02 1.98718323e+02 2.09563965e+02 2.10764114e+02 1.98896606e+02 1.96917160e+02 1.99269455e+02 1.98181717e+02 2.00939713e+02 2.04359436e+02 2.04405243e+02 1.94619690e+02 1.83821472e+02 1.84092438e+02 1.88684113e+02 1.97333069e+02 2.03992355e+02 2.05762131e+02 2.03273132e+02 2.00693344e+02 2.07954712e+02 2.15832428e+02 2.12503647e+02 2.00617264e+02 1.89729904e+02 1.89177673e+02 1.97077484e+02 1.99363220e+02 2.00531281e+02 1.93968307e+02 1.95496155e+02 1.99614700e+02 2.05809647e+02 2.09082016e+02 2.09245499e+02 2.12088333e+02 2.09500870e+02 2.03485275e+02 1.98750656e+02 1.99076309e+02 2.03764282e+02 2.04246307e+02 2.01064026e+02 1.97673477e+02 1.95088028e+02 1.97138107e+02 2.01030457e+02 2.03933289e+02 2.02691071e+02 2.00013474e+02 1.99620285e+02 2.00421295e+02 2.00557083e+02 2.00422333e+02 2.00090683e+02 2.00108612e+02 2.00305176e+02 2.00405731e+02 2.00361450e+02 1.99930588e+02 1.98687592e+02 1.97709915e+02 1.98077972e+02 1.98995605e+02 1.99157700e+02 1.98833084e+02 1.99917679e+02 2.01690643e+02 2.02695786e+02 2.02035370e+02 1.99793106e+02 1.98531754e+02 1.97730133e+02 1.98701141e+02 2.00979828e+02 2.02069061e+02 2.01227097e+02 1.98166122e+02 1.97042053e+02 1.98254578e+02 2.00674881e+02 2.01022537e+02 1.99420639e+02 1.97413223e+02 1.97648560e+02 1.99024307e+02 1.99994110e+02 2.00880676e+02 2.00714676e+02 2.02681381e+02 2.01526871e+02 2.00690094e+02 1.97937286e+02 1.99703690e+02 2.01080261e+02 2.00816086e+02 1.99318176e+02 1.99564529e+02 2.01882812e+02 2.02202408e+02 2.02324127e+02 2.03900131e+02 2.02112000e+02 1.97897018e+02 1.96378860e+02 2.00579559e+02 2.02631775e+02 2.00738602e+02 1.99695541e+02 2.01659927e+02 2.03133530e+02 2.02341843e+02 2.01680878e+02 2.00382278e+02 1.99279831e+02 1.98446274e+02 2.00646851e+02 2.00413254e+02 2.05160294e+02 2.04361237e+02 2.03763306e+02 1.98673355e+02 2.01236420e+02 2.01697998e+02 2.01993942e+02 1.94139847e+02 1.89404709e+02 1.87361298e+02 1.93275467e+02 1.98477676e+02 2.01147354e+02 2.00079895e+02 1.97503265e+02 1.93480286e+02 1.89888565e+02 1.94184967e+02 1.94696121e+02 1.96300476e+02 1.95698853e+02 1.99552078e+02 1.99566895e+02 1.96926529e+02 1.94713242e+02 1.96535934e+02 1.93046417e+02 1.85696960e+02 1.78106186e+02 1.81355530e+02 1.84415466e+02 1.91461960e+02 1.92567169e+02 2.05835129e+02 2.09265366e+02 2.13380493e+02 2.03948578e+02 1.98785492e+02 1.89493439e+02 1.84436920e+02 1.84946106e+02 2.01312119e+02 2.15556580e+02 2.11116409e+02 1.95653030e+02 1.80583572e+02 1.77926300e+02 1.80250565e+02 1.78127991e+02 1.75912277e+02 1.73890625e+02 1.77701767e+02 1.80707809e+02 1.77591583e+02 1.83064941e+02 1.84960464e+02 1.79763824e+02 1.71304199e+02 1.62157211e+02 1.62957382e+02 1.66327133e+02 1.75560455e+02 1.73229233e+02 1.68325912e+02 1.70647507e+02 1.77783676e+02 1.82165314e+02 1.69894684e+02 1.56690948e+02 1.51066772e+02 1.66473846e+02 1.80605728e+02 1.89287766e+02 1.77786636e+02 1.50867081e+02 1.29587402e+02 1.44288239e+02 1.79846649e+02 1.94354904e+02 1.83559708e+02 1.67398163e+02 1.62348724e+02 1.50544022e+02 1.45441711e+02 1.51254013e+02 1.65869888e+02 1.75446045e+02 1.73906784e+02 1.69295502e+02 1.53900543e+02 1.38620728e+02 1.39983795e+02 1.55801254e+02 1.74360382e+02 1.79235107e+02 1.79032074e+02 1.80410522e+02 1.87496460e+02 1.94024002e+02 1.91562668e+02 1.77954742e+02 1.69923340e+02 1.74384186e+02 1.82192673e+02 1.82974838e+02 1.73506577e+02 1.70584427e+02 1.76415359e+02 1.62230209e+02 1.53363113e+02 1.54293259e+02 1.86456223e+02 1.98727859e+02 1.85648666e+02 1.67638718e+02 1.59563370e+02 1.48382431e+02 1.38052673e+02 1.35624817e+02 1.25418564e+02 1.26562088e+02 1.34864487e+02 1.60404587e+02 1.66577332e+02 1.56585800e+02 1.51926544e+02 1.54931473e+02 1.59927032e+02 1.60759933e+02 1.58411880e+02 1.39385742e+02 1.19437248e+02 1.16405685e+02 1.34994217e+02 1.56043579e+02 1.60684158e+02 1.64964615e+02 1.59759903e+02 1.54313766e+02 1.46533539e+02 1.56688644e+02 1.76120178e+02 1.95352158e+02 1.98549942e+02 1.85582367e+02 1.61786453e+02 1.56871674e+02 1.62577866e+02 1.64630814e+02 1.61754517e+02 1.57647980e+02 1.89563309e+02 2.11634323e+02 2.15801468e+02 1.81092087e+02 1.49313095e+02 1.47377487e+02 1.68688278e+02 2.08360916e+02 2.91491730e+02 3.33273529e+02 4.12205597e+02 3.79939423e+02 5.17547363e+02 4.72308203e+03 1.58778857e+03 3.77022998e+03 1.26752607e+04 114522296. 111852504. -453658336. 82206544. 179536304. -67716808. -679112128. -474933664. 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. 0. -859660928. -859660928. -859660928. 0. 0. 1923205760. -120397120. -65511108. -2.33428320e+04 -1.08983770e+04 -1.13037952e+03 -4.03780579e+02 4.40108154e+03 2.88851636e+03 5.59165039e+02 2.34485794e+02 1.77161713e+02 2.02413498e+02 1.98310287e+02 1.72554184e+02 1.38188995e+02 1.41644485e+02 1.40870926e+02 1.35961502e+02 1.37363480e+02 1.57087738e+02 1.81120865e+02 1.53347763e+02 1.00126503e+02 8.26294632e+01 1.18913651e+02 1.46819244e+02 1.29910065e+02 1.14329803e+02 1.25638298e+02 1.38107025e+02 1.56695007e+02 1.60230820e+02 1.51891754e+02 1.31429153e+02 1.20420731e+02 1.21306442e+02 1.34242462e+02 1.00606873e+02 6.00379791e+01 4.33182068e+01 6.61469574e+01 9.16382980e+01 8.96385574e+01 7.58963928e+01 7.06115494e+01 5.32131081e+01 4.17247314e+01 3.25704384e+01 2.22447910e+01 2.15398884e+01 3.65893059e+01 5.53606644e+01 6.16304398e+01 4.50789566e+01 4.02629089e+01 4.47759438e+01 4.78886032e+01 4.39203339e+01 3.29256287e+01 2.53357563e+01 3.63415031e+01 7.94012527e+01 1.23732635e+02 1.46066437e+02 1.14310455e+02 7.99991455e+01 6.13780136e+01 8.86508255e+01 1.17230278e+02 1.04683380e+02 7.21044693e+01 3.74324303e+01 3.72605171e+01 3.62050438e+01 1.60760136e+01 -2.73181839e+01 8.23693037e-01 4.96542282e+01 1.00719749e+02 8.17189407e+01 5.21488266e+01 5.21906357e+01 4.85055466e+01 4.56509438e+01 3.25913849e+01 3.44730034e+01 4.28158836e+01 5.95993042e+01 6.72616730e+01 6.45677872e+01 5.65867691e+01 5.97220039e+01 9.46317139e+01 1.38085312e+02 1.17753288e+02 8.78792801e+01 4.87117119e+01 6.85091782e+01 8.47325439e+01 1.01047028e+02 1.09359116e+02 8.17800674e+01 4.49851799e+01 3.29314880e+01 5.24889565e+01 9.52328339e+01 9.53786545e+01 8.71246490e+01 5.85606804e+01 3.97977905e+01 4.70490189e+01 4.43805237e+01 4.97656937e+01 4.00500870e+01 4.65382843e+01 4.31575699e+01 3.42868843e+01 5.67033920e+01 8.99149933e+01 8.33166733e+01 5.04313431e+01 1.38058519e+01 1.20460033e+01 8.60269165e+00 9.46250725e+00 8.45651054e+00 1.48485017e+00 -1.89553642e+00 3.93568459e+01 9.08734818e+01 9.75234451e+01 6.37222748e+01 1.68102303e+01 -6.88857138e-01 -1.42522507e+01 -5.15383625e+00 6.03469467e+00 1.45957775e+01 -1.87868750e+00 4.16368818e+00 8.51799488e-01 4.12888908e+00 5.20440626e+00 1.33938408e+01 2.01459370e+01 2.34794407e+01 1.67717075e+01 1.72826595e+01 2.25682793e+01 2.31790447e+01 2.60767651e+01 2.26037331e+01 2.97448273e+01 3.78759842e+01 3.00572758e+01 2.50090599e+01 1.57549686e+01 1.53408833e+01 2.18938541e+00 -1.43023596e+01 -1.88114548e+01 -7.80602694e+00 4.80282631e+01 8.44207611e+01 9.03387222e+01 6.65804291e+01 3.66474876e+01 3.04438400e+01 1.73559361e+01 8.54663754e+00 1.90275841e+01 2.20865822e+01 2.18443089e+01 1.75610962e+01 1.83586617e+01 1.41793375e+01 -3.36025925e+01 -8.15200119e+01 -1.14554039e+02 -1.07802956e+02 -6.34311028e+01 -2.05125751e+01 2.06552391e+01 1.42931004e+01 3.98323631e+00 -8.91244411e+00 -2.10085964e+00 -5.02860451e+00 -2.87380099e+00 -1.06891251e+01 -2.53727016e+01 -1.73324528e+01 -9.27715015e+00 -7.69808674e+00 -1.30595274e+01 -2.46720104e+01 -7.67268944e+00 -2.55380297e+00 7.80492067e+00 8.72281170e+00 -3.46661568e+00 -4.57809486e+01 -9.32013550e+01 -1.17648880e+02 -1.20985275e+02 -1.13707458e+02 -1.22271225e+02 -8.94143524e+01 -3.61856766e+01 8.90018940e+00 1.55294285e+01 8.47563088e-01 -8.84737778e+00 -1.17018852e+01 -1.13940639e+01 1.01537123e-01 -2.56725955e+00 -4.17498541e+00 -1.21491880e+01 -1.55255070e+01 -1.80771809e+01 1.96900234e+01 6.33612900e+01 5.27426033e+01 1.18235998e+01 -3.22337341e+01 -5.26678276e+01 -7.05707855e+01 -1.14984344e+02 -1.39809525e+02 -1.31353577e+02 -9.82225418e+01 -4.55035858e+01 -6.13072319e+01 -7.13658142e+01 -9.58332901e+01 -9.01251373e+01 -8.09665680e+01 -8.42082901e+01 -8.84440384e+01 -8.83759689e+01 -6.98273697e+01 -5.73001099e+01 -6.03266983e+01 -9.63397141e+01 -1.36374405e+02 -1.75130325e+02 -1.85581619e+02 -1.16720337e+02 -3.75100670e+01 2.65981585e-01 -1.96624432e+01 -6.59271393e+01 -6.74253998e+01 -8.33885574e+01 -7.96608047e+01 -7.50134201e+01 -6.69311218e+01 -5.99767075e+01 -6.34633408e+01 -6.93876572e+01 -7.08507156e+01 -3.70261116e+01 8.61327553e+00 1.42068110e+01 -6.47587442e+00 -4.05347672e+01 -6.23977013e+01 -8.95395508e+01 -9.88491440e+01 -7.90176926e+01 -7.60395813e+01 -9.07755432e+01 -8.76407700e+01 -6.21531982e+01 -4.48866196e+01 -4.41321869e+01 -5.17102852e+01 -5.61653748e+01 -6.52681198e+01 -6.62655716e+01 -7.53220596e+01 -7.37077332e+01 -7.21899414e+01 -5.28481331e+01 -4.24290504e+01 -4.32769737e+01 -7.69576187e+01 -1.22724457e+02 -1.27794510e+02 -9.64526825e+01 -5.90962715e+01 -7.23231735e+01 -8.20647964e+01 -8.91944122e+01 -8.38780823e+01 -8.60945740e+01 -9.21603012e+01 -1.10912949e+02 -1.29702408e+02 -1.28066986e+02 -9.89903717e+01 -7.08403397e+01 -6.95140457e+01 -8.55025406e+01 -6.80087128e+01 -3.93526802e+01 -2.19081039e+01 -3.73212738e+01 -6.49488525e+01 -6.35700417e+01 -6.58348312e+01 -6.70549469e+01 -7.89458389e+01 -7.91486282e+01 -7.04026184e+01 -5.88779297e+01 -6.44879150e+01 -7.27253342e+01 -7.35994949e+01 -7.03297119e+01 -8.15020752e+01 -9.34254761e+01 -1.19049423e+02 -1.37169556e+02 -1.33148392e+02 -1.18093117e+02 -1.00985107e+02 -1.01021927e+02 -9.26242676e+01 -8.09483109e+01 -8.70347824e+01 -1.27540047e+02 -1.64787506e+02 -1.75659500e+02 -1.44572342e+02 -1.13020065e+02 -1.07582626e+02 -1.18114845e+02 -1.23770256e+02 -1.17204903e+02 -1.37896622e+02 -1.78268661e+02 -1.90192184e+02 -1.65826233e+02 -1.17639030e+02 -1.20858818e+02 -1.20385384e+02 -1.28955826e+02 -1.23252449e+02 -1.21851952e+02 -1.30405975e+02 -1.46090790e+02 -1.55150146e+02 -1.48538589e+02 -1.35064560e+02 -1.39426620e+02 -1.73464554e+02 -2.21038544e+02 -2.20924103e+02 -1.84796173e+02 -1.45231689e+02 -1.41331772e+02 -1.31351608e+02 -1.36483047e+02 -1.41679352e+02 -1.83866913e+02 -2.08554199e+02 -2.39100601e+02 -2.38514786e+02 -2.10090530e+02 -1.76701828e+02 -1.39398987e+02 -1.66184799e+02 -1.92779022e+02 -1.64911667e+02 -1.03367874e+02 -7.16600571e+01 -9.98385239e+01 -1.37051941e+02 -1.32269913e+02 -1.34652313e+02 -1.28108978e+02 -1.27028816e+02 -1.17922997e+02 -1.14086334e+02 -1.12694252e+02 -1.09022484e+02 -1.05036499e+02 -1.02189262e+02 -1.05335899e+02 -1.10934845e+02 -1.14695992e+02 -1.35306686e+02 -1.62525574e+02 -1.60396027e+02 -1.36380783e+02 -1.04913460e+02 -1.32773682e+02 -1.68394547e+02 -1.41812424e+02 -8.38066559e+01 -8.38518677e+01 -1.55409286e+02 -1.96934616e+02 -1.73550674e+02 -1.39912598e+02 -1.55097702e+02 -1.91038086e+02 -1.98602509e+02 -1.85784607e+02 -1.56723068e+02 -1.59285233e+02 -1.62552856e+02 -1.61102448e+02 -1.61021042e+02 -1.37772522e+02 -1.13771027e+02 -1.36829590e+02 -1.82587128e+02 -2.12939789e+02 -1.92902771e+02 -1.75124161e+02 -1.96533340e+02 -2.19796265e+02 -2.24928436e+02 -2.03353745e+02 -1.75458008e+02 -1.80203720e+02 -1.85034775e+02 -1.92770874e+02 -1.78925964e+02 -1.90491653e+02 -2.16573105e+02 -2.26964233e+02 -2.20326294e+02 -1.83378326e+02 -1.64098358e+02 -1.54474106e+02 -1.61512665e+02 -1.70945099e+02 -1.39483215e+02 -9.66923981e+01 -1.06047173e+02 -1.52598007e+02 -1.96214478e+02 -1.86303207e+02 -1.62812943e+02 -1.76988098e+02 -2.04330521e+02 -2.08011581e+02 -1.90206284e+02 -1.64052139e+02 -1.60581146e+02 -1.60535629e+02 -1.60609344e+02 -1.62395996e+02 -1.63862244e+02 -1.73138580e+02 -1.87691925e+02 -1.95049942e+02 -1.85625702e+02 -1.70283127e+02 -1.64708206e+02 -1.64512604e+02 -1.68346115e+02 -1.46007141e+02 -1.24138664e+02 -1.45826385e+02 -1.89107910e+02 -2.15976135e+02 -1.90319305e+02 -1.65031570e+02 -1.48912308e+02 -1.46325302e+02 -1.46545898e+02 -1.53479446e+02 -1.58195602e+02 -1.54807556e+02 -1.58508469e+02 -1.57587402e+02 -1.59442917e+02 -1.51484711e+02 -1.49044693e+02 -1.49511429e+02 -1.65767105e+02 -1.72831207e+02 -1.66433731e+02 -1.54779068e+02 -1.49178406e+02 -1.60575165e+02 -1.69559113e+02 -1.76691254e+02 -1.91761658e+02 -2.08500961e+02 -2.11685486e+02 -1.97401505e+02 -1.96196762e+02 -2.26648987e+02 -2.48646179e+02 -2.36495819e+02 -2.14320602e+02 -2.18891266e+02 -2.38293549e+02 -2.39218231e+02 -2.20042389e+02 -2.06929535e+02 -2.05243988e+02 -2.06970230e+02 -2.06998322e+02 -2.07823975e+02 -2.07189133e+02 -1.97456329e+02 -2.03486588e+02 -2.16994064e+02 -2.27606110e+02 -2.18079056e+02 -2.02268112e+02 -2.03243164e+02 -2.13871979e+02 -2.01541550e+02 -1.80519348e+02 -1.71432587e+02 -1.77281281e+02 -1.90260193e+02 -1.85412674e+02 -1.88209839e+02 -1.87382462e+02 -1.88968582e+02 -1.87189392e+02 -1.87378052e+02 -1.89832123e+02 -1.88196762e+02 -1.86436188e+02 -1.82929855e+02 -1.86254425e+02 -1.90245758e+02 -1.89923676e+02 -1.99540390e+02 -2.09041321e+02 -2.09261856e+02 -1.96199814e+02 -1.81277542e+02 -1.78028854e+02 -1.79196503e+02 -1.71688980e+02 -1.62281616e+02 -1.64653351e+02 -1.75377975e+02 -1.85885452e+02 -1.85886810e+02 -1.85597229e+02 -1.98846466e+02 -2.13320419e+02 -2.15633972e+02 -2.05647964e+02 -1.97554947e+02 -1.97882950e+02 -1.96325714e+02 -1.92746017e+02 -1.93206665e+02 -1.88412598e+02 -1.79599564e+02 -1.85589249e+02 -1.99277054e+02 -2.08538971e+02 -2.03498474e+02 -2.03363785e+02 -2.16658493e+02 -2.25582886e+02 -2.22223572e+02 -2.06888626e+02 -2.02227707e+02 -2.07283646e+02 -2.09714630e+02 -2.03698456e+02 -1.92976425e+02 -1.94430527e+02 -2.00185120e+02 -2.00967270e+02 -1.98045380e+02 -1.93172302e+02 -1.91897705e+02 -1.90623383e+02 -1.89171616e+02 -1.91624466e+02 -1.91179535e+02 -1.90713699e+02 -1.94549728e+02 -1.98932983e+02 -2.01812286e+02 -1.99336212e+02 -1.97494263e+02 -2.00773788e+02 -2.05278564e+02 -2.04823059e+02 -2.00673813e+02 -1.89079865e+02 -1.72803543e+02 -1.64285355e+02 -1.49246780e+02 -1.46562546e+02 -1.92576111e+02 -2.20475372e+02 -2.50260086e+02 -2.28062408e+02 -2.33855057e+02 -2.15513611e+02 -2.14492325e+02 -1.15300369e+01 3.30610748e+02 -83640960. -1301312768. 0. 0. 0. 0. 357199328. 357199328. -692914048. 249883472. -61330512. -132356048. -132356048. -488244768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 663051200. 105610992. 152648112. -515747552. 72426760. -1.66019897e+03 -8.06047485e+02 -1.83763657e+02 -3.07047058e+02 -4.69853241e+02 -2.00223618e+02 -1.76850739e+02 -1.76736465e+02 -1.74886612e+02 -1.73252304e+02 -1.76442184e+02 -1.79439026e+02 -1.76834549e+02 -1.68560822e+02 -1.64530594e+02 -1.71155548e+02 -1.83933502e+02 -1.83994293e+02 -1.73142792e+02 -1.59120407e+02 -1.56767990e+02 -1.62424057e+02 -1.60777267e+02 -1.53389816e+02 -1.52849503e+02 -1.60594238e+02 -1.67319595e+02 -1.59880219e+02 -1.42087646e+02 -1.38404831e+02 -1.49205002e+02 -1.63314255e+02 -1.71430466e+02 -1.72041885e+02 -1.77921677e+02 -1.85259369e+02 -1.88282089e+02 -1.77144424e+02 -1.47676651e+02 -1.31799866e+02 -1.38556915e+02 -1.59674164e+02 -1.75544724e+02 -1.74938644e+02 -1.68343765e+02 -1.58365082e+02 -1.59651413e+02 -1.53025665e+02 -1.46075119e+02 -1.53020966e+02 -1.79531296e+02 -2.06885345e+02 -2.04277802e+02 -1.63940186e+02 -1.43890717e+02 -1.51190994e+02 -1.73897888e+02 -1.71365494e+02 -1.53664688e+02 -1.54968323e+02 -1.73225510e+02 -1.92491104e+02 -1.85573273e+02 -1.53509827e+02 -1.29577637e+02 -1.37023605e+02 -1.56766190e+02 -1.65067810e+02 -1.56949463e+02 -1.56931274e+02 -1.70913940e+02 -1.87771011e+02 -1.83190323e+02 -1.74162201e+02 -1.76166183e+02 -1.90799759e+02 -1.96296661e+02 -1.88096558e+02 -1.70042358e+02 -1.51852615e+02 -1.50383606e+02 -1.57984344e+02 -1.66816101e+02 -1.61947556e+02 -1.81984253e+02 -2.14153198e+02 -2.28237976e+02 -1.97803070e+02 -1.42450882e+02 -1.16594742e+02 -1.32389923e+02 -1.75547745e+02 -2.15645142e+02 -2.29413162e+02 -2.19693115e+02 -2.13021133e+02 -2.16492935e+02 -2.02618423e+02 -1.60919495e+02 -1.32324539e+02 -1.41568314e+02 -1.76505707e+02 -1.86720612e+02 -1.71377792e+02 -1.45785217e+02 -1.40890518e+02 -1.61533859e+02 -1.75756287e+02 -1.74314255e+02 -1.69506882e+02 -1.86100967e+02 -2.23407578e+02 -2.30710693e+02 -1.96747345e+02 -1.58714920e+02 -1.58782562e+02 -1.89715820e+02 -2.15859528e+02 -2.18155548e+02 -1.91834198e+02 -1.60677292e+02 -1.46626862e+02 -1.64902176e+02 -1.65886368e+02 -1.45574020e+02 -1.38977509e+02 -1.67014191e+02 -2.02791214e+02 -2.01044250e+02 -1.69388046e+02 -1.50279236e+02 -1.66546555e+02 -1.81434708e+02 -1.88524445e+02 -1.71898331e+02 -1.84903397e+02 -2.12030777e+02 -2.20940338e+02 -1.79844879e+02 -1.03696495e+02 -6.92357101e+01 -1.00100937e+02 -1.51100693e+02 -1.67765701e+02 -1.54738693e+02 -1.36726120e+02 -1.36793610e+02 -1.31558365e+02 -1.05940613e+02 -7.05436935e+01 -5.91212997e+01 -9.37806168e+01 -1.69898972e+02 -2.08610001e+02 -1.69766663e+02 -1.22640526e+02 -1.21818863e+02 -1.46985718e+02 -1.26425415e+02 -7.05212097e+01 -7.37821350e+01 -1.25898056e+02 -1.76035950e+02 -1.36423935e+02 -4.89992561e+01 -2.99201608e+00 -3.62647324e+01 -1.06544914e+02 -1.40757767e+02 -1.40930969e+02 -1.46272339e+02 -1.55748459e+02 -1.37420227e+02 -8.71266022e+01 -3.07923260e+01 -6.25572739e+01 -1.16961876e+02 -1.63668640e+02 -1.57700165e+02 -1.27959984e+02 -1.08923149e+02 -8.93948441e+01 -8.68899231e+01 -6.19905205e+01 -3.94764023e+01 -5.44869766e+01 -1.18047287e+02 -1.66762573e+02 -1.60849899e+02 -9.82344894e+01 -4.81469727e+01 -5.79477959e+01 -1.08726730e+02 -1.38266388e+02 -1.37349594e+02 -1.46676804e+02 -2.05351944e+02 -2.23780792e+02 -1.60212158e+02 -9.28238373e+01 -7.44145355e+01 -1.16886299e+02 -1.63981369e+02 -1.87874893e+02 -1.81976074e+02 -1.53986481e+02 -1.25367805e+02 -1.26847656e+02 -1.07661980e+02 -7.74019623e+01 -1.03822266e+02 -1.49859009e+02 -1.78985352e+02 -1.72167099e+02 -1.24506630e+02 -1.08288528e+02 -1.17607597e+02 -1.28871246e+02 -1.31244751e+02 -9.66864395e+01 -1.24191437e+02 -1.72153931e+02 -2.00281937e+02 -2.08552658e+02 -1.34908966e+02 -9.22686996e+01 -1.06160278e+02 -1.72384293e+02 -1.88042084e+02 -1.48094086e+02 -1.02506508e+02 -1.09428612e+02 -1.37934525e+02 -1.32213501e+02 -9.13545074e+01 -8.17551498e+01 -1.45843628e+02 -1.71041458e+02 -1.40700317e+02 -8.89024963e+01 -1.29362152e+02 -1.45746338e+02 -1.33493195e+02 -1.07501411e+02 -9.82072830e+01 -1.17019379e+02 -9.10734253e+01 -6.75666504e+01 -6.17769928e+01 -4.12463074e+01 -2.50226231e+01 -1.34075232e+01 -8.34562912e+01 -1.11601479e+02 -1.13660866e+02 -5.86443481e+01 -7.15180435e+01 -7.86341858e+01 -6.01171761e+01 -1.91395054e+01 -3.46964407e+00 -7.17915192e+01 -1.10755669e+02 -1.13386688e+02 -4.66081085e+01 -3.35563431e+01 -3.92942162e+01 -7.09403305e+01 -8.24518127e+01 -4.59832458e+01 -6.52675476e+01 -9.26133118e+01 -1.52814011e+02 -1.77222366e+02 -1.60955963e+02 -1.11837692e+02 -6.59741821e+01 -9.65128326e+01 -1.48700623e+02 -1.73210205e+02 -1.57484268e+02 -1.80044220e+02 -1.68226379e+02 -1.21880997e+02 -5.49621849e+01 -5.92593689e+01 -1.54026230e+02 -1.77616272e+02 -1.39499039e+02 -5.92949333e+01 -8.78210144e+01 -1.27039291e+02 -1.37853195e+02 -1.14300758e+02 -7.52714081e+01 -7.43950882e+01 -6.79576187e+01 -1.19897102e+02 -1.40056015e+02 -1.35014664e+02 -8.90894928e+01 -6.93776855e+01 -1.05193214e+02 -1.39753159e+02 -1.39643723e+02 -1.40244705e+02 -2.05076187e+02 -2.49709854e+02 -2.44592941e+02 -2.16628204e+02 -2.19682327e+02 -2.61843170e+02 -2.75904358e+02 -2.44608765e+02 -1.61168655e+02 -1.28169296e+02 -1.17559166e+02 -1.41755661e+02 -1.31007401e+02 -8.04699020e+01 -4.22445679e+01 -1.23851738e+01 -5.82570152e+01 -8.75798569e+01 -1.24028534e+02 -1.18774910e+02 -1.33823074e+02 -1.53463272e+02 -1.80452209e+02 -1.68705765e+02 -1.61861938e+02 -2.01663757e+02 -2.41373947e+02 -2.20290939e+02 -1.58315872e+02 -1.43971100e+02 -1.33038086e+02 -7.93361053e+01 -3.17644520e+01 -1.55997324e+01 -8.04985123e+01 -8.48478622e+01 -8.96033478e+01 -1.30675400e+02 -1.32395874e+02 -9.32974472e+01 4.36582375e+00 2.86291981e+01 -4.91394806e+01 -1.23136177e+02 -1.23688812e+02 -6.63357773e+01 -1.01705847e+01 -3.23566551e+01 -7.77235870e+01 -1.30426727e+02 -1.39571381e+02 -8.54518509e+01 -4.81862183e+01 1.35739117e+01 6.17661476e+00 5.76593924e+00 3.17039146e+01 3.57211418e+01 5.13732643e+01 -3.26002846e+01 -4.33857155e+01 -5.55681992e+01 -6.33565102e+01 -4.29182320e+01 1.36475086e+01 1.40415161e+02 1.64442719e+02 7.21754837e+01 -8.65555038e+01 -1.69746414e+02 -7.86850128e+01 5.13984909e+01 6.23923378e+01 -7.29379959e+01 -2.19972961e+02 -1.88489609e+02 -4.70919037e+01 3.36648903e+01 2.36192703e+01 -6.19429359e+01 -4.92409286e+01 5.78268051e+00 4.45954628e+01 5.71674042e+01 -6.00061893e+00 -7.29050875e-01 3.81117744e+01 7.59009781e+01 6.80536575e+01 1.87809792e+01 3.38930397e+01 4.50991707e+01 -4.17974930e+01 -1.27148170e+02 -1.26782570e+02 4.79707794e+01 1.52120255e+02 1.18814316e+02 -1.69082985e+01 -8.99091187e+01 -7.49978638e+01 7.01282549e+00 4.02547073e+01 6.17399864e+01 -6.56726646e+00 -5.95768309e+00 7.59926701e+00 2.62366924e+01 6.20226974e+01 8.10712039e-01 -2.59312382e+01 -1.11360207e+02 -1.08973351e+02 -8.15174179e+01 -6.68623734e+00 1.10169655e+02 1.41222534e+02 7.39323959e+01 -8.43649368e+01 -1.61362366e+02 -9.98708420e+01 5.96400871e+01 1.12203651e+02 -9.78309345e+00 -1.67651489e+02 -1.64872406e+02 -1.38418894e+01 5.86590652e+01 5.29638023e+01 -2.74913158e+01 -1.81142693e+01 3.07461166e+01 9.46082230e+01 1.32431946e+02 1.28802216e+02 1.52652740e+02 1.51646927e+02 7.98164139e+01 -2.28188648e+01 -6.41574097e+01 9.01949120e+00 8.60963745e+01 6.22445221e+01 -5.03298798e+01 -1.39080032e+02 -9.10865173e+01 3.04016399e+01 6.99126129e+01 1.73534241e+01 -6.88564835e+01 -4.91204948e+01 3.35949211e+01 9.37707520e+01 1.44362228e+02 7.76326523e+01 9.22924805e+01 5.36367149e+01 6.00847664e+01 6.34278755e+01 9.50262527e+01 1.56983368e+02 1.16285980e+02 4.45210609e+01 -3.56995621e+01 -7.75108910e+00 8.61335068e+01 1.68217575e+02 1.15257484e+02 5.53401709e+00 -7.37310028e+01 -5.04016342e+01 2.48242798e+01 5.05876999e+01 6.28750114e+01 4.32877998e+01 6.63489456e+01 9.40271683e+01 1.40572357e+02 1.97932831e+02 1.75110825e+02 8.18957138e+01 7.68832064e+00 -9.75255966e-01 3.54920311e+01 7.72468338e+01 1.44087677e+02 1.78817566e+02 9.38198318e+01 -3.65037842e+01 -8.90913010e+01 -3.19139004e+00 1.15800262e+02 1.15263596e+02 4.79306364e+00 -1.21122993e+02 -9.79328690e+01 3.96712227e+01 1.81808289e+02 2.21629578e+02 1.34258179e+02 5.93299599e+01 6.49449005e+01 1.08257393e+02 1.33743179e+02 8.69254379e+01 8.08521805e+01 7.75254669e+01 3.03070145e+01 1.38377600e+01 1.73396091e+01 8.49868622e+01 7.70721130e+01 -7.29964828e+00 -9.41582489e+01 -6.89820786e+01 7.03294830e+01 1.88226562e+02 1.48460724e+02 2.04635944e+01 -6.99604950e+01 -6.89907227e+01 3.85411148e+01 1.35096863e+02 1.76408005e+02 9.64754181e+01 4.85218735e+01 7.65438080e+00 1.76731777e+01 3.55518494e+01 2.51703968e+01 2.95209446e+01 -2.85920906e+01 -6.06290627e+01 -6.77190018e+01 -2.20332203e+01 7.98376846e+01 1.13282875e+02 5.20770607e+01 -4.08591499e+01 -6.47234879e+01 -8.33073902e+00 8.15311203e+01 7.47164154e+01 2.19594002e+01 -7.27169495e+01 -8.36755371e+01 2.13856027e-01 9.40474472e+01 1.34917953e+02 6.71819153e+01 -2.73133612e+00 -6.49431586e-01 5.08246384e+01 1.25049812e+02 1.34024475e+02 1.23339584e+02 8.97066498e+01 2.72897320e+01 1.80980186e+01 6.61732483e+01 1.73009964e+02 2.23382599e+02 1.57840698e+02 7.16438522e+01 1.41074953e+01 5.23903694e+01 1.25006744e+02 1.56183517e+02 1.33166565e+02 7.81252975e+01 8.47494125e+01 1.27226067e+02 1.81300125e+02 1.82986359e+02 1.23311729e+02 6.70244980e+01 8.25128403e+01 1.20933434e+02 1.97606445e+02 1.89109512e+02 1.88063385e+02 1.50873795e+02 1.16702408e+02 9.41808395e+01 8.05875702e+01 1.35442215e+02 1.72931534e+02 1.48179642e+02 8.97060623e+01 3.83141289e+01 7.46248932e+01 1.35662552e+02 1.71072906e+02 1.16683411e+02 6.09851718e-01 -4.03343201e+01 1.77273045e+01 1.44926361e+02 2.17315765e+02 1.75611710e+02 9.63501587e+01 3.36265297e+01 -1.12969952e+01 -6.13100586e+01 -7.11988525e+01 -5.70125084e+01 -2.06793359e+03 -3.37039209e+03 5.32515991e+02 7.64335510e+02 8.24194031e+02 1.47319275e+02 6.40329980e+03 1.80019297e+04 273444416. 211863024. 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. 0. 0. 0. 0. 0. 0. 0. 0. 832060288. -590784000. 59325776. 254382512. 143809264. -214572256. -490165120. -1.13133955e+04 -4.47679199e+03 -6.29822632e+02 -1.21560509e+02 -3.76215820e+01 -5.87029517e-01 6.48265915e+01 1.55661224e+02 1.87720718e+02 1.64518448e+02 9.73931961e+01 5.51893082e+01 6.94530334e+01 1.24156364e+02 2.00606674e+02 2.01983444e+02 1.81625229e+02 1.63903381e+02 1.58509323e+02 1.53955276e+02 1.23138725e+02 1.60852844e+02 1.66028671e+02 1.18988747e+02 7.67878799e+01 1.09056534e+02 2.07233826e+02 2.56153442e+02 1.95769852e+02 1.18937355e+02 7.43364410e+01 1.00382561e+02 1.84947235e+02 2.52131546e+02 2.80477478e+02 2.12571014e+02 1.64595093e+02 1.60417328e+02 2.08085754e+02 2.39564011e+02 2.12249039e+02 2.03907745e+02 1.79299637e+02 1.51036255e+02 1.37159821e+02 1.58841293e+02 2.40424423e+02 2.47557739e+02 1.78670944e+02 9.90097885e+01 8.05645294e+01 1.46674377e+02 2.09655014e+02 2.04801727e+02 1.57649582e+02 1.36401321e+02 1.81949493e+02 2.53548569e+02 2.78216370e+02 2.52434448e+02 1.70925049e+02 1.15286957e+02 1.13509743e+02 1.62251495e+02 2.25446228e+02 2.67809204e+02 2.85876770e+02 2.61917023e+02 2.27431870e+02 1.95246353e+02 1.80539658e+02 1.90783432e+02 1.80650131e+02 1.38731979e+02 1.00894325e+02 1.02015709e+02 1.56780746e+02 1.93717285e+02 1.88652039e+02 1.67972870e+02 1.29065735e+02 1.09428535e+02 1.28486206e+02 1.86782242e+02 2.15810684e+02 1.82450043e+02 1.40529999e+02 1.46071350e+02 1.71824951e+02 1.80747757e+02 1.65837433e+02 1.71875900e+02 1.71466202e+02 1.53657166e+02 1.42692963e+02 1.56079956e+02 2.05832016e+02 2.11583969e+02 1.60760513e+02 1.02306931e+02 8.17779541e+01 1.25001678e+02 1.64649414e+02 1.82463013e+02 1.73624039e+02 1.61829742e+02 1.55281647e+02 1.67163437e+02 1.92529327e+02 2.05439590e+02 1.79449005e+02 1.35093414e+02 1.22148705e+02 1.37676468e+02 1.54610046e+02 1.59353195e+02 1.77177551e+02 1.76116516e+02 1.42878235e+02 1.04557632e+02 1.08217484e+02 1.58704742e+02 1.79215912e+02 1.50538788e+02 1.10403831e+02 1.05877052e+02 1.44201385e+02 1.78491379e+02 1.88440308e+02 1.73974228e+02 1.48437454e+02 1.29121536e+02 1.36655838e+02 1.65894531e+02 1.86227966e+02 1.69701996e+02 1.41704895e+02 1.34950211e+02 1.44855667e+02 1.57829697e+02 1.65217926e+02 1.82545090e+02 1.90263565e+02 1.81271057e+02 1.67593781e+02 1.64785233e+02 1.84960846e+02 1.92558609e+02 1.78762131e+02 1.41372757e+02 1.20448311e+02 1.30435806e+02 1.66261108e+02 1.89001312e+02 1.82858917e+02 1.66527512e+02 1.60032166e+02 1.68518417e+02 1.69116684e+02 1.80546814e+02 1.74825562e+02 1.72316711e+02 1.61536423e+02 1.49591705e+02 1.44568130e+02 1.41582108e+02 1.61331207e+02 1.71103348e+02 1.61288132e+02 1.51231049e+02 1.55136520e+02 1.78426941e+02 1.87153015e+02 1.80384705e+02 1.69669495e+02 1.62272659e+02 1.62720596e+02 1.68790787e+02 1.72264816e+02 1.72664169e+02 1.63505005e+02 1.65664536e+02 1.71865891e+02 1.78633545e+02 1.87797775e+02 1.93607117e+02 1.98596191e+02 1.88146912e+02 1.74321655e+02 1.67807724e+02 1.69147873e+02 1.76706863e+02 1.77083954e+02 1.68746674e+02 1.60271652e+02 1.57549118e+02 1.68341171e+02 1.80962784e+02 1.86034317e+02 1.82236328e+02 1.76727585e+02 1.74520325e+02 1.75213364e+02 1.76777069e+02 1.78968155e+02 1.76641724e+02 1.72970642e+02 1.70899414e+02 1.72939575e+02 1.73795853e+02 1.74329971e+02 1.75281006e+02 1.75187637e+02 1.73844269e+02 1.72709854e+02 1.72834152e+02 1.72698898e+02 1.72146957e+02 1.71685837e+02 1.71816864e+02 1.72137909e+02 1.72334641e+02 1.72359756e+02 1.71398438e+02 1.70691895e+02 1.71118057e+02 1.73029938e+02 1.73821350e+02 1.72549011e+02 1.70921768e+02 1.71265686e+02 1.71652054e+02 1.72065109e+02 1.72168610e+02 1.71923401e+02 1.71769730e+02 1.71810928e+02 1.71820526e+02 1.72600998e+02 1.73003372e+02 1.75647369e+02 1.75323151e+02 1.74672562e+02 1.72229965e+02 1.73072815e+02 1.73843430e+02 1.72140427e+02 1.71962555e+02 1.68783859e+02 1.66749176e+02 1.65077744e+02 1.66446243e+02 1.70410858e+02 1.70130310e+02 1.70217529e+02 1.70167816e+02 1.72112259e+02 1.72064987e+02 1.72671051e+02 1.72900482e+02 1.73163727e+02 1.71691208e+02 1.70284119e+02 1.71909180e+02 1.75065308e+02 1.73393738e+02 1.76631927e+02 1.76530624e+02 1.77439056e+02 1.74271317e+02 1.72155746e+02 1.72824005e+02 1.72950043e+02 1.74982712e+02 1.74702148e+02 1.73637558e+02 1.68882660e+02 1.69732605e+02 1.68179443e+02 1.74205627e+02 1.71706039e+02 1.75517334e+02 1.73601318e+02 1.70515549e+02 1.64406555e+02 1.65695358e+02 1.70991364e+02 1.73494659e+02 1.69300568e+02 1.68296631e+02 1.72764038e+02 1.70337006e+02 1.64209137e+02 1.57632202e+02 1.58876465e+02 1.60532654e+02 1.64446548e+02 1.62390076e+02 1.64727081e+02 1.63866058e+02 1.65031693e+02 1.64153900e+02 1.60914261e+02 1.58560257e+02 1.61613098e+02 1.65256683e+02 1.69051758e+02 1.62138641e+02 1.68660660e+02 1.77393112e+02 1.81702667e+02 1.74428513e+02 1.58575516e+02 1.58729935e+02 1.57374634e+02 1.62546677e+02 1.66049301e+02 1.58350677e+02 1.56361938e+02 1.52908203e+02 1.57201004e+02 1.51987167e+02 1.49372925e+02 1.55377060e+02 1.58275665e+02 1.58138824e+02 1.57376007e+02 1.60271454e+02 1.57168198e+02 1.55598053e+02 1.53486359e+02 1.47816895e+02 1.42472580e+02 1.44565903e+02 1.51897614e+02 1.56945328e+02 1.55900467e+02 1.52541321e+02 1.47780090e+02 1.50344879e+02 1.60996002e+02 1.74017548e+02 1.69790085e+02 1.61440933e+02 1.43294601e+02 1.42719177e+02 1.45199310e+02 1.55603241e+02 1.59405457e+02 1.65245239e+02 1.70269455e+02 1.72040222e+02 1.69527084e+02 1.66716141e+02 1.59604782e+02 1.55814728e+02 1.52325256e+02 1.55797195e+02 1.51256210e+02 1.55913910e+02 1.54900620e+02 1.54931137e+02 1.54912613e+02 1.49990997e+02 1.56730927e+02 1.65922012e+02 1.89014282e+02 1.79803329e+02 1.59307434e+02 1.39838120e+02 1.50627625e+02 1.71594681e+02 1.74503143e+02 1.65231705e+02 1.48505173e+02 1.52539154e+02 1.64672455e+02 1.72782013e+02 1.72312607e+02 1.67321762e+02 1.70686295e+02 1.86834610e+02 1.97787796e+02 1.83368134e+02 1.56928177e+02 1.46094376e+02 1.55908508e+02 1.61212830e+02 1.56432739e+02 1.49520493e+02 1.43441910e+02 1.53080032e+02 1.70446457e+02 1.69425262e+02 1.53999252e+02 1.28676559e+02 1.29895020e+02 1.38296875e+02 1.44213989e+02 1.28682037e+02 9.73001862e+01 8.56842651e+01 1.11047615e+02 1.39682220e+02 1.48078033e+02 1.43818848e+02 1.63927780e+02 1.72242035e+02 1.39888474e+02 9.22899323e+01 7.97214355e+01 1.10535049e+02 1.45172272e+02 1.53300629e+02 1.48926300e+02 1.25827072e+02 1.12108742e+02 1.19522705e+02 1.42784775e+02 1.60865356e+02 1.58485184e+02 1.56957260e+02 1.26479652e+02 8.27204666e+01 7.90065994e+01 1.00259735e+02 1.30111206e+02 1.40132492e+02 1.57558228e+02 1.63080948e+02 1.43627991e+02 1.25008484e+02 1.17506126e+02 1.20982887e+02 1.21441032e+02 1.13067162e+02 1.07548920e+02 1.03588089e+02 1.03737373e+02 1.00386871e+02 1.71044510e+02 8.83398743e+01 3.25196167e+02 4.34794708e+02 6.42896118e+02 2.41158838e+03 3.63460864e+03 4.76111084e+02 3.91101135e+02 2.57060211e+02 -1.07522802e+01 8.07991257e+01 4.18175537e+02 1.57941467e+02 -4.05560638e+02 -9.45770898e+03 -2.42044238e+04 -679112128. -474933664. 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. 0. -859660928. -859660928. -859660928. 0. 0. 1923205760. -120397120. -65511108. -74777120. 350898656. -136748576. -83981680. 1.42022559e+04 5.97002148e+03 8.45539185e+02 3.34228699e+02 1.60819321e+02 1.51877945e+02 1.49635849e+02 1.48453522e+02 1.45331833e+02 1.48972748e+02 1.61090607e+02 1.65997711e+02 1.63459503e+02 1.35869812e+02 1.28125519e+02 1.31051407e+02 1.59115326e+02 1.49373001e+02 1.26230408e+02 9.23612747e+01 8.85760956e+01 8.28294296e+01 6.78457489e+01 5.28141479e+01 4.88684235e+01 3.94758606e+01 2.72939949e+01 2.55839558e+01 2.80457973e+01 3.94181900e+01 4.53347740e+01 3.44575157e+01 2.18190575e+01 9.06124973e+00 3.12494850e+01 4.37415886e+01 3.87576599e+01 2.34607067e+01 1.87933636e+01 1.59697599e+01 1.89760380e+01 2.61208534e+01 5.93921814e+01 8.64702530e+01 9.88795624e+01 8.46351700e+01 7.01410828e+01 5.89522400e+01 4.85513000e+01 5.21553879e+01 6.66403961e+01 6.45152206e+01 5.37735138e+01 3.45391426e+01 3.08255348e+01 1.42075891e+01 3.00362377e+01 5.68047829e+01 7.48477707e+01 9.05240021e+01 8.92257385e+01 9.81436539e+01 8.14944305e+01 7.12164459e+01 7.19297180e+01 6.53827438e+01 3.73920746e+01 1.89022579e+01 2.38867893e+01 4.03273354e+01 5.08868637e+01 4.32001648e+01 7.08831100e+01 1.11922050e+02 1.10843163e+02 9.45224686e+01 7.03322372e+01 1.18828148e+02 1.63974335e+02 1.64232330e+02 1.27986221e+02 1.02236504e+02 1.04238548e+02 1.11486359e+02 9.27446060e+01 9.95504303e+01 1.28144730e+02 1.68311478e+02 1.59749313e+02 1.09008980e+02 6.39166489e+01 3.97748604e+01 4.93489609e+01 5.14337540e+01 6.72409363e+01 3.70313072e+01 1.29621515e+01 3.28393326e+01 7.05677719e+01 7.78188324e+01 4.03037834e+01 1.46646366e+01 6.13602829e+01 9.27540283e+01 8.48330536e+01 3.87392464e+01 3.09827256e+00 -4.43221092e+00 -5.05316067e+00 3.40744519e+00 1.18071260e+01 2.16271992e+01 1.77115536e+01 1.59004717e+01 2.10309353e+01 3.16186256e+01 3.81038704e+01 3.76942940e+01 3.10365028e+01 3.26075516e+01 3.02032623e+01 3.33354492e+01 6.75430222e+01 1.02497749e+02 1.04873451e+02 6.59936523e+01 3.00534496e+01 6.69999466e+01 1.07567978e+02 1.09130913e+02 7.54898453e+01 4.71602364e+01 4.53995018e+01 3.30128288e+01 9.14840317e+00 1.48439112e+01 2.73827286e+01 3.56678543e+01 2.42264614e+01 2.42805719e+00 -1.43774462e+00 5.97973251e+00 2.34596157e+01 2.85103855e+01 3.46075935e+01 2.89031258e+01 4.17731895e+01 8.42003326e+01 1.33647766e+02 1.31899887e+02 9.52829666e+01 5.21022110e+01 7.91555023e+01 1.12818275e+02 1.05438354e+02 6.00609589e+01 1.72954941e+01 2.22047577e+01 2.69107895e+01 3.03628407e+01 2.91964378e+01 3.34790268e+01 3.75866928e+01 3.32486382e+01 2.87297344e+01 4.58618546e+01 6.88344345e+01 6.25215645e+01 3.62626991e+01 2.93751287e+00 2.97550142e-01 -3.39502501e+00 2.56364231e+01 6.35967407e+01 6.29509964e+01 4.26377563e+01 1.44851685e+01 1.17313528e+01 -7.44679308e+00 2.01849880e+01 7.07566071e+01 7.99022446e+01 4.56946793e+01 5.40285969e+00 1.42972221e+01 2.16461849e+01 1.31309767e+01 9.80076408e+00 2.34160023e+01 2.56845455e+01 6.17060394e+01 9.06480331e+01 9.02913818e+01 5.20219116e+01 1.33672819e+01 2.64739971e+01 2.52129173e+01 5.81295738e+01 8.07995148e+01 7.07360535e+01 1.68668022e+01 -2.72419109e+01 -2.09243259e+01 -1.31318550e+01 -5.87754154e+00 -1.85236015e+01 -2.74960346e+01 -3.58570557e+01 -3.77394295e+01 -2.93431168e+01 -2.54905434e+01 -2.76626034e+01 -2.65341778e+01 -4.99608040e+01 -6.05357704e+01 -7.56409302e+01 -7.64670105e+01 -6.46526031e+01 -6.45645218e+01 -6.21814384e+01 -6.38167877e+01 -6.36903648e+01 -6.05959358e+01 -6.93992691e+01 -5.62326241e+01 -5.02140694e+01 -5.15901260e+01 -7.02656326e+01 -6.94242554e+01 -6.11491394e+01 -5.21269302e+01 -5.33608894e+01 -5.89831886e+01 -5.05404396e+01 -5.15611534e+01 -3.16742783e+01 -2.95579166e+01 -3.19253101e+01 -6.45043640e+01 -1.00705551e+02 -7.41313629e+01 -1.25573521e+01 2.95388947e+01 1.17130957e+01 -2.31779766e+01 -2.66371555e+01 -2.21795349e+01 -1.71687317e+01 -1.77644234e+01 -1.84120483e+01 -2.17642975e+01 -2.90816555e+01 -4.98513489e+01 -6.46560822e+01 -7.61420898e+01 -6.21208000e+01 -4.94763756e+01 -3.24208984e+01 -3.01035595e+01 -4.27789612e+01 -5.31992950e+01 -6.59029999e+01 -6.30261993e+01 -6.74068298e+01 -5.46973076e+01 -2.01952000e+01 1.24872932e+01 1.43838701e+01 -1.54200897e+01 -3.91031723e+01 -5.35409851e+01 -5.09495506e+01 -4.03452377e+01 -1.53616076e+01 -1.76186323e+00 8.42506027e+00 -1.43574352e+01 -3.65976067e+01 -6.90524979e+01 -6.08620377e+01 -5.48939934e+01 -4.84474030e+01 -6.14555550e+01 -6.96415253e+01 -8.14791489e+01 -6.93758621e+01 -5.61983566e+01 -4.56002121e+01 -4.14907684e+01 -4.70698280e+01 -1.54421272e+01 1.10932331e+01 4.64390421e+00 -4.13373795e+01 -7.54388275e+01 -6.07661514e+01 -3.90000916e+01 -4.65181541e+01 -5.36724281e+01 -3.36648903e+01 -2.22414827e+00 -2.91283989e+00 -4.17327538e+01 -7.95102997e+01 -6.55616074e+01 -5.35346222e+01 -6.05301590e+01 -7.17091827e+01 -7.93711929e+01 -7.37034760e+01 -6.92086334e+01 -8.31370850e+01 -1.10253204e+02 -1.18123795e+02 -1.12882637e+02 -9.47772141e+01 -9.73663712e+01 -7.20372467e+01 -4.21043625e+01 -3.43516808e+01 -2.67946491e+01 -1.28305225e+01 1.70407829e+01 2.04888210e+01 8.09650135e+00 4.75321740e-01 -1.79535103e+01 -2.30728493e+01 -5.46555862e+01 -9.96762238e+01 -1.48752197e+02 -1.56889389e+02 -1.42502869e+02 -1.29514908e+02 -1.20425667e+02 -1.18154366e+02 -1.09559151e+02 -1.14752045e+02 -1.20772568e+02 -9.99316330e+01 -5.74828110e+01 -4.53875008e+01 -5.59507217e+01 -8.08747711e+01 -8.55490875e+01 -9.07690353e+01 -1.12028175e+02 -9.25290756e+01 -8.95967712e+01 -7.81388321e+01 -7.41883698e+01 -5.70696411e+01 -2.40978909e+01 -5.01044273e+01 -8.39702072e+01 -9.77033615e+01 -6.27448120e+01 -5.75890808e+01 -7.16910477e+01 -1.05156952e+02 -7.53701477e+01 -4.96234703e+01 -4.42136002e+01 -6.62515869e+01 -8.84322968e+01 -5.75407867e+01 -2.65904007e+01 -3.38758163e+01 -7.36531906e+01 -1.06873978e+02 -8.36463013e+01 -6.60169296e+01 -9.20926895e+01 -1.33329910e+02 -1.17602844e+02 -7.38293076e+01 -5.20876274e+01 -5.95486717e+01 -7.48110352e+01 -7.21934891e+01 -5.25019608e+01 -2.65265980e+01 -3.43602867e+01 -8.07155304e+01 -1.15222748e+02 -1.18637634e+02 -1.07613640e+02 -1.00789467e+02 -1.05163712e+02 -1.11649429e+02 -1.14718071e+02 -9.84608917e+01 -9.42533493e+01 -1.12299850e+02 -1.20496918e+02 -1.16453545e+02 -8.53355026e+01 -7.39102402e+01 -8.27423019e+01 -9.24178467e+01 -1.10477760e+02 -1.09353470e+02 -1.17224861e+02 -1.29020386e+02 -1.40388809e+02 -1.35573471e+02 -8.83862534e+01 -5.66717644e+01 -9.11393738e+01 -1.52389709e+02 -1.54243561e+02 -1.05388718e+02 -8.51273041e+01 -1.16229774e+02 -1.35495132e+02 -1.19791130e+02 -1.03705399e+02 -1.07275528e+02 -1.27730476e+02 -1.21338463e+02 -1.14785477e+02 -1.07770126e+02 -1.20175522e+02 -1.40098709e+02 -1.40191315e+02 -1.38188965e+02 -1.14776611e+02 -9.75292587e+01 -9.76109085e+01 -1.21185905e+02 -1.22699959e+02 -8.11685944e+01 -5.17196808e+01 -6.88701019e+01 -1.10407852e+02 -1.13335915e+02 -9.55667496e+01 -1.11954155e+02 -1.50633591e+02 -1.65131958e+02 -1.36836563e+02 -1.18913567e+02 -1.23611908e+02 -1.34390457e+02 -1.17873077e+02 -1.14151642e+02 -1.12179695e+02 -1.23567116e+02 -1.33362076e+02 -1.46490829e+02 -1.51022995e+02 -1.49216019e+02 -1.39993744e+02 -1.23953384e+02 -1.14732704e+02 -1.12155159e+02 -1.07020432e+02 -1.04378777e+02 -1.13486008e+02 -1.26673965e+02 -1.29788177e+02 -1.13168404e+02 -1.10580704e+02 -1.14179466e+02 -1.05445679e+02 -7.44530792e+01 -5.36134987e+01 -7.24517899e+01 -1.10545349e+02 -1.21911484e+02 -1.11702019e+02 -1.09520500e+02 -1.27727478e+02 -1.43136810e+02 -1.51123276e+02 -1.52200470e+02 -1.52405090e+02 -1.38594116e+02 -1.40982788e+02 -1.52006668e+02 -1.55754745e+02 -1.26943230e+02 -1.08532639e+02 -1.25687050e+02 -1.43793793e+02 -1.27522812e+02 -1.12518333e+02 -1.30643600e+02 -1.68691422e+02 -1.92892685e+02 -1.87669357e+02 -1.85546341e+02 -1.75450577e+02 -1.75903336e+02 -1.72768295e+02 -1.74992691e+02 -1.65304779e+02 -1.58810806e+02 -1.60278854e+02 -1.74179398e+02 -1.64490723e+02 -1.34092896e+02 -1.14274002e+02 -1.12566269e+02 -1.17326164e+02 -1.30142746e+02 -1.41038651e+02 -1.55527252e+02 -1.52480927e+02 -1.55858521e+02 -1.57985336e+02 -1.60988907e+02 -1.56536758e+02 -1.58908707e+02 -1.54861359e+02 -1.54370087e+02 -1.57570328e+02 -1.58845367e+02 -1.60632156e+02 -1.43695404e+02 -1.29320389e+02 -1.28035736e+02 -1.42376495e+02 -1.54452744e+02 -1.53631332e+02 -1.52594666e+02 -1.52880981e+02 -1.55650711e+02 -1.57601913e+02 -1.57261963e+02 -1.47952682e+02 -1.36047836e+02 -1.40783096e+02 -1.53834122e+02 -1.57926193e+02 -1.37724472e+02 -1.24509483e+02 -1.33622345e+02 -1.53588135e+02 -1.54205002e+02 -1.42931763e+02 -1.44907242e+02 -1.54178162e+02 -1.64542419e+02 -1.53462036e+02 -1.44545425e+02 -1.36782669e+02 -1.33306625e+02 -1.46833237e+02 -1.56214035e+02 -1.57318481e+02 -1.37827011e+02 -1.31376694e+02 -1.46037811e+02 -1.62982773e+02 -1.61134338e+02 -1.46030106e+02 -1.44271515e+02 -1.50925018e+02 -1.60936234e+02 -1.54863556e+02 -1.46894318e+02 -1.44494766e+02 -1.49926361e+02 -1.57800125e+02 -1.59634979e+02 -1.53436600e+02 -1.46277710e+02 -1.46044189e+02 -1.52309464e+02 -1.63395370e+02 -1.60243118e+02 -1.55514664e+02 -1.55032349e+02 -1.60320450e+02 -1.61118988e+02 -1.54923203e+02 -1.56614624e+02 -1.63150635e+02 -1.69816833e+02 -1.71062271e+02 -1.72272049e+02 -1.68620865e+02 -1.63158585e+02 -1.60659714e+02 -1.63236237e+02 -1.67989365e+02 -1.69560089e+02 -1.69326126e+02 -1.66375198e+02 -1.62428665e+02 -1.48584778e+02 -1.37538651e+02 -1.48180939e+02 -1.39206909e+02 -1.24327042e+02 -1.22632011e+02 -1.29867401e+02 -1.66529999e+02 -1.78995453e+02 -5.13177338e+01 -4.73158302e+01 -5.25906128e+02 -4.88884216e+02 -3.74624634e+02 1.50361420e+02 28971730. 0. 0. 0. 0. 0. 0. -276646528. -276646528. -2.33673926e+03 -2.83143140e+03 -2.83143140e+03 -488244768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 8910349. -3.75655762e+02 1.03373161e+02 4.00264206e+01 -8.17296371e+01 -9.22418823e+01 -1.28731705e+02 -1.39451889e+02 -1.49585419e+02 -1.51478363e+02 -1.45481003e+02 -1.43100250e+02 -1.46416214e+02 -1.43467850e+02 -1.35571503e+02 -1.29335327e+02 -1.35966324e+02 -1.51398285e+02 -1.58713943e+02 -1.53769272e+02 -1.42126144e+02 -1.36628311e+02 -1.38721878e+02 -1.41929337e+02 -1.36663147e+02 -1.30189850e+02 -1.34001801e+02 -1.46343521e+02 -1.52787415e+02 -1.47830475e+02 -1.36601364e+02 -1.32277206e+02 -1.41846741e+02 -1.55332855e+02 -1.61702148e+02 -1.53882294e+02 -1.54229507e+02 -1.63809387e+02 -1.58038803e+02 -1.39337326e+02 -1.25768417e+02 -1.41253876e+02 -1.72878952e+02 -1.80882858e+02 -1.64522293e+02 -1.48211044e+02 -1.38687073e+02 -1.39879700e+02 -1.40382141e+02 -1.42878860e+02 -1.39235291e+02 -1.42948242e+02 -1.68713013e+02 -1.85997452e+02 -1.79139313e+02 -1.53253937e+02 -1.39002502e+02 -1.46217392e+02 -1.63322708e+02 -1.71726486e+02 -1.58613342e+02 -1.53867798e+02 -1.59546524e+02 -1.51351166e+02 -1.33687256e+02 -1.12889122e+02 -1.14909386e+02 -1.46012177e+02 -1.58281403e+02 -1.49376587e+02 -1.25206184e+02 -1.33947891e+02 -1.56577621e+02 -1.50534454e+02 -1.28857666e+02 -1.19726387e+02 -1.32965744e+02 -1.65478806e+02 -1.75260498e+02 -1.67468292e+02 -1.35423492e+02 -1.17336159e+02 -1.22076187e+02 -1.34554443e+02 -1.31376160e+02 -1.15308029e+02 -1.18554665e+02 -1.42525406e+02 -1.54222733e+02 -1.30993393e+02 -9.44615860e+01 -8.78771744e+01 -1.20898880e+02 -1.54436874e+02 -1.58075394e+02 -1.30971924e+02 -1.23766487e+02 -1.31242889e+02 -1.16664192e+02 -8.23741684e+01 -6.25165215e+01 -9.27411957e+01 -1.42048050e+02 -1.71520538e+02 -1.59676697e+02 -1.31673141e+02 -9.43735580e+01 -7.22774277e+01 -7.78333893e+01 -9.00991135e+01 -8.53618927e+01 -8.85730438e+01 -1.22259186e+02 -1.56635864e+02 -1.38602859e+02 -8.37126617e+01 -6.08189583e+01 -8.16340179e+01 -1.35529251e+02 -1.59346573e+02 -1.36785461e+02 -1.11427818e+02 -1.08905533e+02 -1.11646141e+02 -9.16194763e+01 -4.51158333e+01 -5.07369499e+01 -9.47178574e+01 -1.39712036e+02 -1.37997803e+02 -1.05590263e+02 -7.99963150e+01 -7.67702332e+01 -8.86626434e+01 -1.12278603e+02 -1.18928726e+02 -8.97193146e+01 -7.70023956e+01 -9.75734024e+01 -1.20699753e+02 -1.21736694e+02 -1.05432343e+02 -1.05116776e+02 -1.29919495e+02 -1.29974777e+02 -1.08012215e+02 -8.16875916e+01 -7.41280594e+01 -1.06241821e+02 -1.15676140e+02 -1.05429596e+02 -7.94619217e+01 -9.82032242e+01 -1.69987549e+02 -2.07602386e+02 -1.63399857e+02 -9.42130432e+01 -7.92662735e+01 -1.11404839e+02 -1.34392303e+02 -1.31423279e+02 -1.33391052e+02 -1.58011368e+02 -1.96221481e+02 -2.04527222e+02 -1.88655212e+02 -1.35469620e+02 -9.72992630e+01 -1.18712715e+02 -1.34189972e+02 -1.29540024e+02 -9.40851212e+01 -1.22000145e+02 -1.86104797e+02 -1.78427582e+02 -1.45071167e+02 -1.17809074e+02 -1.60628204e+02 -2.37665573e+02 -2.72706055e+02 -2.33969284e+02 -1.63064667e+02 -1.12264008e+02 -1.21908470e+02 -1.04988297e+02 -9.57798920e+01 -1.01129082e+02 -1.50868332e+02 -2.11707443e+02 -2.12060959e+02 -1.62178680e+02 -6.97192993e+01 -3.07076759e+01 -5.45532379e+01 -1.17344269e+02 -1.63580566e+02 -1.58418945e+02 -1.77767792e+02 -2.02924347e+02 -1.90261078e+02 -1.33924744e+02 -7.07756729e+01 -1.02989685e+02 -1.78977951e+02 -2.25723557e+02 -1.73651932e+02 -7.99761581e+01 -4.99291649e+01 -9.32418365e+01 -1.47144073e+02 -1.21360275e+02 -7.30503540e+01 -8.44883728e+01 -1.40113312e+02 -1.65322906e+02 -1.11148338e+02 -3.24943466e+01 -1.25999126e+01 -5.45917473e+01 -9.87463150e+01 -9.50242844e+01 -7.17330627e+01 -6.88583374e+01 -8.91380234e+01 -6.64515915e+01 -3.21532326e+01 -3.57839508e+01 -4.95383987e+01 -9.44927139e+01 -1.11326111e+02 -9.07840118e+01 -9.00082245e+01 -8.03994598e+01 -1.14039078e+02 -7.79531860e+01 -4.17034798e+01 -2.39634800e+01 -4.29086609e+01 -1.37046844e+02 -1.84925034e+02 -1.76187759e+02 -6.41666183e+01 -1.28337622e+01 -7.99010706e+00 -6.01897926e+01 -7.76578217e+01 -4.82735252e+01 -4.53296318e+01 -7.86911621e+01 -1.01135071e+02 -6.37822304e+01 -3.81978111e+01 -9.44377213e+01 -1.73692139e+02 -1.56836960e+02 -1.13479240e+02 -8.33102722e+01 -1.05512848e+02 -1.48109833e+02 -9.10201950e+01 -5.51162720e+01 -1.66905975e+01 -4.83527985e+01 -1.09170235e+02 -1.42338531e+02 -1.70432114e+02 -1.16093437e+02 -8.00787201e+01 -6.13343582e+01 -1.08449547e+02 -1.27882477e+02 -1.20020004e+02 -1.36993881e+02 -1.65316086e+02 -1.87536163e+02 -1.10304306e+02 -6.83419113e+01 -7.20705032e+01 -1.28923553e+02 -1.16414169e+02 -8.60603943e+01 -5.25671730e+01 -2.66583519e+01 -4.18784752e+01 -3.28072395e+01 -9.79882431e+01 -1.25319023e+02 -1.58713150e+02 -1.54099777e+02 -1.28414215e+02 -9.50442352e+01 -3.03678875e+01 -9.13802236e-02 -1.60748501e+01 -1.07912033e+02 -1.24836769e+02 -1.08555466e+02 -7.96450806e+01 -9.81776733e+01 -7.55646744e+01 8.45489216e+00 5.49119339e+01 1.65655975e+01 -8.34317627e+01 -1.05451027e+02 -6.50429382e+01 -3.79628778e+00 9.17348576e+00 -4.11450272e+01 -4.68678551e+01 -6.09245338e+01 -9.75945175e-01 2.23389187e+01 3.86023369e+01 -2.30623188e+01 -4.64110107e+01 -6.75211668e+00 4.61482277e+01 1.08935928e+01 -5.16143112e+01 -3.31505203e+01 -6.64673686e-01 -2.75313711e+00 -5.38341789e+01 -4.30710335e+01 2.27599773e+01 6.02761269e+01 3.84377899e+01 -4.94743156e+01 -3.54880295e+01 -1.21241789e+01 3.31094780e+01 7.87114763e+00 -3.49551086e+01 -1.92981319e+01 -2.03266029e+01 3.42878304e+01 4.67797585e+01 4.67217674e+01 9.41602325e+00 -5.24237776e+00 2.31948738e+01 5.21884079e+01 3.10973778e+01 -3.05911617e+01 -4.38141518e+01 -5.34200554e+01 -8.00558014e+01 -1.30502029e+02 -1.06499390e+02 -3.47162514e+01 -2.63723030e+01 -6.23149529e+01 -1.16965683e+02 -5.06349907e+01 -2.69989738e+01 -1.80754387e+00 3.25300407e+01 5.17315407e+01 2.04799843e+01 -8.22334747e+01 -1.05443420e+02 -3.89232597e+01 3.31968880e+01 -5.80697536e-01 -9.19188156e+01 -1.40755875e+02 -8.95066910e+01 -3.09937744e+01 -4.14056244e+01 -6.50631027e+01 -1.13427803e+02 -1.58136993e+02 -2.20331619e+02 -1.90861084e+02 -1.29166565e+02 -1.13624687e+02 -1.47418121e+02 -1.85306107e+02 -9.36990204e+01 -5.59383354e+01 -2.47316017e+01 -4.46949425e+01 -4.68034134e+01 -8.37937698e+01 -1.95269043e+02 -2.26586426e+02 -1.44452942e+02 1.46099787e+01 6.04567871e+01 -6.05753822e+01 -1.79511612e+02 -1.92279297e+02 -1.03873146e+02 -4.57328644e+01 -7.98279190e+01 -1.52678680e+02 -1.86545013e+02 -1.35862061e+02 -2.00263615e+01 2.18004942e+00 -5.99356499e+01 -1.42794540e+02 -2.30472458e+02 -2.20231705e+02 -1.81294312e+02 -6.54521942e+01 5.60243797e+01 9.91624069e+01 3.04423561e+01 -1.23344955e+02 -2.04179382e+02 -1.31431610e+02 -2.69972591e+01 -2.80853252e+01 -1.44916672e+02 -2.47623337e+02 -2.08337112e+02 -7.83139648e+01 2.60082417e+01 3.30509529e+01 -5.35261726e+01 -1.13097748e+02 -1.56374634e+02 -8.60015106e+01 -5.69656563e+01 -3.14922523e+01 -7.36028366e+01 -1.04857658e+02 -4.93891373e+01 1.71006451e+01 1.03954414e+02 1.12176498e+02 5.22015343e+01 -1.99375801e+01 -1.33074814e+02 -1.51147491e+02 -6.99397354e+01 9.57031021e+01 1.69783905e+02 9.80372849e+01 -6.23231888e+01 -1.45022202e+02 -1.13051987e+02 -4.11060791e+01 -4.00973282e+01 -8.82406387e+01 -1.16663170e+02 -1.21993950e+02 -4.63778038e+01 -2.50969028e+00 5.06366272e+01 5.00628281e+01 1.11042280e+01 -2.83610172e+01 -7.86923828e+01 -5.59619484e+01 -5.18934202e+00 5.78386040e+01 5.80415497e+01 -2.04110551e+00 -7.21484070e+01 -4.05651321e+01 2.34141426e+01 6.10490494e+01 1.51940882e+00 -8.94823151e+01 -9.76691132e+01 -3.62560234e+01 6.86861877e+01 7.54185104e+01 -2.87625480e+00 -7.16803513e+01 -1.10813461e+02 -2.35778351e+01 9.60054755e-01 4.55132904e+01 4.28865204e+01 4.91748161e+01 5.95088730e+01 2.63192348e+01 5.34727135e+01 7.43927765e+01 5.85564728e+01 4.68283129e+00 -9.19550018e+01 -1.18070259e+02 -6.29793320e+01 8.29681854e+01 1.92498764e+02 1.70776428e+02 4.12063065e+01 -8.90050430e+01 -1.18902672e+02 -2.86036682e+01 7.46933823e+01 9.95917130e+01 2.53754597e+01 -6.68744507e+01 -3.82050171e+01 2.66405220e+01 1.07118866e+02 1.21876038e+02 9.21714706e+01 2.71239834e+01 -4.52958641e+01 -3.80902786e+01 4.07977333e+01 1.43954819e+02 1.56184647e+02 7.21819153e+01 -3.52885208e+01 -1.64858875e+01 7.47307129e+01 1.35070084e+02 1.08952690e+02 4.87992477e+01 3.06925964e+01 1.34748812e+01 3.98814087e+01 6.23816109e+01 3.14957733e+01 2.75112782e+01 1.95027500e-01 4.82997665e+01 7.90020065e+01 1.37779556e+02 1.70451080e+02 1.36581207e+02 8.23445511e+01 6.01119661e+00 -2.89463539e+01 1.46723289e+01 9.05374680e+01 1.07257278e+02 2.76668262e+01 -5.61116447e+01 -4.86117401e+01 1.39244194e+01 1.04307121e+02 1.25518448e+02 8.79960556e+01 4.32767296e+01 3.66826477e+01 1.04725372e+02 1.62161133e+02 2.11282608e+02 1.93483948e+02 1.11883698e+02 1.20867119e+02 1.48613998e+02 2.25674438e+02 2.31500275e+02 2.08290283e+02 1.59732178e+02 5.54217491e+01 1.50104427e+01 2.92908974e+01 1.14531693e+02 1.54416077e+02 9.38078842e+01 1.13017082e+01 1.15563316e+01 1.03407372e+02 1.75723114e+02 1.51788040e+02 6.59044800e+01 -1.38849795e+00 -1.06811037e+01 5.93260078e+01 1.45945602e+02 1.71343826e+02 1.59458588e+02 1.25803192e+02 1.00201332e+02 5.05540810e+01 4.52633705e+01 6.80001373e+01 9.51184464e+01 6.70407028e+01 -5.01730394e+00 -5.16781349e+01 2.17374182e+00 1.02579613e+02 1.57973709e+02 1.06842873e+02 8.19921684e+00 -1.33676453e+01 3.76710014e+01 1.27688286e+02 1.37771881e+02 8.27462921e+01 5.43083344e+01 5.09251404e+01 1.06038681e+02 1.22856819e+02 1.12134666e+02 8.91319656e+01 4.02960815e+01 5.05585327e+01 5.56810036e+01 1.35119049e+02 1.88796356e+02 1.79658936e+02 1.37352386e+02 6.49830551e+01 3.44280128e+01 3.54465942e+01 1.18958412e+02 2.56224915e+02 3.14139801e+02 2.90699982e+02 1.18036430e+02 7.01541290e+01 -4.97430468e+00 -3.60630112e+01 1.90333923e+03 2.98563647e+03 6.40329980e+03 1.80019297e+04 273444416. 211863024. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 260286800. 184363616. 208756752. -209869424. 3.00213496e+04 1.01439209e+04 2.90452393e+03 4.03635864e+02 1.84709412e+02 1.22161682e+02 1.14996490e+02 1.55716660e+02 1.63796021e+02 1.40780899e+02 5.83408089e+01 6.02645950e+01 1.03199028e+02 1.66911530e+02 1.56771347e+02 9.48212280e+01 3.89846153e+01 2.34494419e+01 7.27286987e+01 1.51251907e+02 1.67432526e+02 1.13911240e+02 5.25383797e+01 5.40427094e+01 1.00935768e+02 1.02513412e+02 6.84680252e+01 6.08011627e+01 9.27195053e+01 1.28963135e+02 1.31214813e+02 1.41711273e+02 1.57205048e+02 1.56266357e+02 1.16214050e+02 4.74277992e+01 4.16367836e+01 8.67739029e+01 1.33722076e+02 1.35115585e+02 8.94437561e+01 4.15089111e+01 4.78917694e+01 1.16040939e+02 1.93382111e+02 1.86506058e+02 1.08266762e+02 7.01239319e+01 6.56066360e+01 1.10482552e+02 1.27483833e+02 1.38466507e+02 1.43287445e+02 1.28982697e+02 1.04478600e+02 6.13719940e+01 7.64026184e+01 1.17488861e+02 1.31756073e+02 1.03628426e+02 5.53904381e+01 5.60459862e+01 8.26425400e+01 1.25020958e+02 1.42673676e+02 1.00491737e+02 4.64424744e+01 4.71468353e+00 2.95682411e+01 8.95066071e+01 1.09821083e+02 7.77239304e+01 5.45740089e+01 6.25725670e+01 1.13355911e+02 1.22459618e+02 1.09436729e+02 8.69155350e+01 9.05827713e+01 9.08330154e+01 7.49748764e+01 9.53488388e+01 1.29833862e+02 1.48242966e+02 1.09332565e+02 5.63808937e+01 4.67810783e+01 6.30526505e+01 1.01847221e+02 1.34207306e+02 1.37591293e+02 1.06994072e+02 7.83260422e+01 8.61962280e+01 1.34884598e+02 1.58660477e+02 1.18787445e+02 8.65729065e+01 8.51887741e+01 1.35402756e+02 1.57881638e+02 1.54033798e+02 1.46107254e+02 1.36108429e+02 1.23560974e+02 8.97145996e+01 9.35886307e+01 1.19624687e+02 1.44151138e+02 1.38925491e+02 1.11341095e+02 1.06353302e+02 1.26219322e+02 1.42128906e+02 1.59298767e+02 1.52002396e+02 1.23466011e+02 9.62844925e+01 8.86632462e+01 1.30273468e+02 1.47860062e+02 1.34859100e+02 1.21337273e+02 1.21365791e+02 1.38825745e+02 1.35838562e+02 1.34009003e+02 1.43893570e+02 1.50043304e+02 1.43868576e+02 1.14984871e+02 1.15079056e+02 1.36591507e+02 1.52085342e+02 1.48840836e+02 1.28095657e+02 1.32699066e+02 1.49209213e+02 1.59813919e+02 1.69966858e+02 1.55540558e+02 1.32620331e+02 1.13892395e+02 1.16308708e+02 1.36440720e+02 1.40516998e+02 1.36253448e+02 1.37072769e+02 1.43223984e+02 1.53047440e+02 1.62029388e+02 1.67704544e+02 1.71429153e+02 1.62073883e+02 1.46158630e+02 1.25890465e+02 1.19719147e+02 1.27749565e+02 1.38772141e+02 1.36961227e+02 1.23621613e+02 1.11980026e+02 1.21019653e+02 1.42527084e+02 1.58123856e+02 1.56281036e+02 1.36188049e+02 1.26367867e+02 1.27134987e+02 1.40495941e+02 1.42273071e+02 1.39380829e+02 1.38337418e+02 1.36832886e+02 1.34326187e+02 1.33822998e+02 1.44162643e+02 1.55898056e+02 1.56158951e+02 1.50928009e+02 1.42680481e+02 1.36594757e+02 1.35919556e+02 1.37673386e+02 1.39285507e+02 1.31294632e+02 1.24654556e+02 1.28383148e+02 1.40865356e+02 1.51265747e+02 1.51646362e+02 1.43246323e+02 1.40875977e+02 1.40651611e+02 1.48183777e+02 1.47198029e+02 1.42939178e+02 1.36230835e+02 1.32993439e+02 1.32925079e+02 1.30005585e+02 1.33309570e+02 1.39905731e+02 1.44532669e+02 1.44061066e+02 1.39298996e+02 1.39090042e+02 1.41967300e+02 1.45422226e+02 1.48019196e+02 1.46076477e+02 1.42178085e+02 1.39186935e+02 1.40248306e+02 1.42944550e+02 1.43470856e+02 1.42815262e+02 1.42584198e+02 1.42689819e+02 1.42984985e+02 1.43004120e+02 1.42821411e+02 1.42723572e+02 1.42740555e+02 1.43204803e+02 1.44421844e+02 1.45512207e+02 1.45196014e+02 1.44196579e+02 1.43831848e+02 1.44064575e+02 1.42927307e+02 1.40932129e+02 1.40121384e+02 1.40406342e+02 1.42786301e+02 1.43716003e+02 1.44828888e+02 1.44076416e+02 1.41714767e+02 1.40819031e+02 1.41223328e+02 1.43958115e+02 1.44612289e+02 1.43207062e+02 1.41804291e+02 1.41518646e+02 1.44419876e+02 1.45617249e+02 1.45589020e+02 1.43078461e+02 1.41370728e+02 1.39971817e+02 1.39799759e+02 1.38710434e+02 1.39886566e+02 1.40740829e+02 1.42975616e+02 1.41119049e+02 1.40303284e+02 1.39186951e+02 1.39593063e+02 1.37917252e+02 1.35530319e+02 1.36054718e+02 1.34415405e+02 1.33614151e+02 1.34439255e+02 1.39787018e+02 1.41258362e+02 1.36882263e+02 1.34114319e+02 1.35784821e+02 1.36994934e+02 1.35243469e+02 1.32885437e+02 1.33041824e+02 1.32816818e+02 1.35418213e+02 1.36786957e+02 1.37873352e+02 1.34587799e+02 1.34334610e+02 1.30134567e+02 1.29383041e+02 1.31599548e+02 1.35578751e+02 1.33976791e+02 1.30912964e+02 1.29998444e+02 1.37200272e+02 1.43073196e+02 1.45976959e+02 1.40202820e+02 1.35446533e+02 1.31799667e+02 1.33269501e+02 1.35990662e+02 1.38528137e+02 1.39504074e+02 1.33468658e+02 1.32994690e+02 1.32188675e+02 1.33304443e+02 1.28853928e+02 1.28612930e+02 1.30458588e+02 1.30398239e+02 1.31732040e+02 1.34523010e+02 1.39990463e+02 1.45062897e+02 1.41394150e+02 1.40854996e+02 1.33366318e+02 1.30486679e+02 1.16210838e+02 1.06424400e+02 1.07600899e+02 1.18608086e+02 1.28550201e+02 1.32332016e+02 1.39252533e+02 1.38831467e+02 1.25175423e+02 1.09378326e+02 1.12695351e+02 1.27236763e+02 1.39888107e+02 1.41335968e+02 1.38258347e+02 1.40070877e+02 1.40043594e+02 1.43161194e+02 1.37813248e+02 1.36319031e+02 1.36179733e+02 1.30841263e+02 1.26938774e+02 1.32350372e+02 1.39391113e+02 1.51857880e+02 1.47402573e+02 1.47186111e+02 1.30538040e+02 1.33250748e+02 1.36156235e+02 1.37119659e+02 1.30096481e+02 1.27644913e+02 1.41555649e+02 1.56616989e+02 1.57936600e+02 1.39568924e+02 1.24367722e+02 1.18253410e+02 1.26856522e+02 1.51907608e+02 1.68651703e+02 1.57556961e+02 1.20867981e+02 1.06477745e+02 1.17010048e+02 1.26671577e+02 1.36847260e+02 1.47012573e+02 1.62779678e+02 1.52797928e+02 1.38777100e+02 1.20491211e+02 1.22887566e+02 1.24552299e+02 1.39369675e+02 1.44588242e+02 1.40111206e+02 1.24005630e+02 1.13360130e+02 1.09393227e+02 1.11911423e+02 1.11133881e+02 1.06610191e+02 1.00787354e+02 1.00130836e+02 1.10531891e+02 1.21641930e+02 1.15089951e+02 1.08961281e+02 1.05665581e+02 1.12154068e+02 1.13575890e+02 1.03844887e+02 1.21206787e+02 1.35938217e+02 1.35983078e+02 1.10559631e+02 9.37587509e+01 1.06060944e+02 1.12969109e+02 1.19058876e+02 1.27857635e+02 1.38959702e+02 1.39476837e+02 1.46450562e+02 1.46426620e+02 1.41108414e+02 1.17710930e+02 1.10904022e+02 1.17679832e+02 1.19484116e+02 1.16523430e+02 1.12379013e+02 1.14622551e+02 1.14885361e+02 1.36041901e+02 1.53543274e+02 1.54459366e+02 1.33261902e+02 1.13870087e+02 1.08381805e+02 1.03351654e+02 1.02637917e+02 1.04137154e+02 1.07963928e+02 1.03900291e+02 9.07594452e+01 7.04608917e+01 6.35170326e+01 7.16514435e+01 9.48363037e+01 9.70379257e+01 8.98293533e+01 8.58473587e+01 9.01757278e+01 9.62622528e+01 6.63333359e+01 3.38372612e+01 2.78024254e+01 6.21647797e+01 9.86534882e+01 1.03268044e+02 7.97430038e+01 4.29785538e+01 -7.06493607e+01 -2.43928329e+02 -4.69297455e+02 -2.31390405e+03 -3.34074072e+03 4.76111084e+02 3.91101135e+02 2.57060211e+02 -1.07522802e+01 8.07991257e+01 4.18175537e+02 1.57941467e+02 -4.05560638e+02 -9.45770898e+03 -2.42044238e+04 -679112128. -474933664. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1845488128. 137870960. 354110240. -1.35753594e+04 -4.96951123e+03 -3.93579071e+02 -3.96113930e+01 2.59349174e+01 1.77124843e-01 5.12929630e+00 3.28951263e+01 6.45783386e+01 5.48461304e+01 4.64223824e+01 4.63925858e+01 4.55262718e+01 2.55063515e+01 2.74483705e+00 2.73366661e+01 7.71980133e+01 8.95187302e+01 5.41667099e+01 2.26285210e+01 4.34250908e+01 4.64393921e+01 3.85290031e+01 2.07982216e+01 1.38610449e+01 1.08242016e+01 1.89118156e+01 3.76888313e+01 4.50514526e+01 4.25015068e+01 3.14230194e+01 6.19122543e+01 9.77471008e+01 1.03916985e+02 8.13082962e+01 6.03112259e+01 6.80240250e+01 8.24766464e+01 8.43994141e+01 9.80514221e+01 1.08503151e+02 1.13760078e+02 1.19247650e+02 1.17353233e+02 1.08540611e+02 9.71648102e+01 8.64591293e+01 9.32261887e+01 9.46527481e+01 9.18301163e+01 9.24387894e+01 9.16076965e+01 1.03084076e+02 1.10122055e+02 9.92428818e+01 6.31141777e+01 1.86200542e+01 -4.94748163e+00 1.43288603e+01 4.28671036e+01 6.22022972e+01 3.29602623e+01 7.62180519e+00 1.92927361e+01 5.78534889e+01 9.11679916e+01 9.14623032e+01 9.00973969e+01 1.08475609e+02 1.49318985e+02 1.23190239e+02 7.14766312e+01 2.32453098e+01 2.96771240e+01 5.58547554e+01 5.33247681e+01 6.32790527e+01 5.69780083e+01 6.28539886e+01 5.13251534e+01 4.98753891e+01 3.82730904e+01 3.32423897e+01 3.63982468e+01 4.49303474e+01 4.20392265e+01 6.90061855e+00 -3.77530975e+01 -1.47020197e+01 1.32912350e+01 4.91087379e+01 2.61412640e+01 1.29865646e+01 -8.25415325e+00 -2.73355103e+01 -1.03048277e+00 4.12376518e+01 5.86040459e+01 3.72898788e+01 -8.43186092e+00 -1.00429029e+01 -6.84867811e+00 1.76896191e+01 3.20181885e+01 3.06929111e+01 3.40655403e+01 3.14173222e+01 3.78948479e+01 2.74157543e+01 2.97555866e+01 3.56928101e+01 1.14902897e+01 -1.79153805e+01 -1.71078873e+01 1.24917994e+01 3.97728348e+01 4.04232407e+01 5.28705139e+01 5.11765251e+01 5.82310028e+01 5.61028633e+01 5.82848511e+01 1.42694073e+01 -2.69648037e+01 -3.17405910e+01 1.85305250e+00 3.49627495e+01 5.61799889e+01 7.05602722e+01 6.92721329e+01 5.07138214e+01 3.81538239e+01 5.11937790e+01 3.15461235e+01 2.46504765e+01 2.30096989e+01 3.36422195e+01 3.26256561e+01 2.12195873e+01 1.79366951e+01 2.02642059e+01 1.92413998e+01 1.00819016e+01 1.12356548e+01 9.35125256e+00 8.07094383e+00 -6.91268563e-01 -7.54279661e+00 1.56662956e-01 8.50637150e+00 1.45016174e+01 1.68014030e+01 2.42634373e+01 3.33079834e+01 3.55793266e+01 2.52767677e+01 -2.92432594e+01 -6.60222778e+01 -7.07850647e+01 -5.02016220e+01 -2.30338688e+01 -2.19785938e+01 -2.12106919e+00 7.64300871e+00 2.03930044e+00 -7.38345861e+00 -1.19381294e+01 -1.30123072e+01 -8.58810902e+00 8.65231216e-01 4.86419258e+01 8.73021240e+01 1.09351562e+02 1.00568344e+02 5.56452293e+01 1.47684393e+01 -2.77174416e+01 -1.57075825e+01 -9.24856186e+00 6.44225061e-01 -8.48178387e+00 -1.15253544e+00 -9.62098658e-01 4.03241777e+00 8.50987053e+00 -2.31233621e+00 -8.98021793e+00 -7.51931953e+00 9.59594250e-01 7.58908558e+00 -1.74755001e+01 -3.03355389e+01 -4.13513069e+01 -3.89251595e+01 -2.51852646e+01 1.38972788e+01 6.01237602e+01 8.13810349e+01 8.32974472e+01 7.59530334e+01 8.53395691e+01 5.23934326e+01 3.50181198e+00 -5.15292015e+01 -6.31125488e+01 -5.42099075e+01 -3.63635979e+01 -3.33367577e+01 -3.65054092e+01 -5.18029099e+01 -5.09638672e+01 -4.77136574e+01 -3.66298561e+01 -3.74437981e+01 -4.03509178e+01 -7.61464386e+01 -1.14014297e+02 -1.02984444e+02 -7.22572479e+01 -3.50349655e+01 -1.74801731e+01 2.53337288e+00 4.52234612e+01 7.27753906e+01 5.76155052e+01 2.93387222e+01 -2.26106339e+01 -5.57364750e+00 5.99195385e+00 2.85754089e+01 2.58548355e+01 1.37619801e+01 1.27705679e+01 1.46530886e+01 1.18295383e+01 -4.76495886e+00 -1.98804493e+01 -1.92220478e+01 1.27606268e+01 5.13493576e+01 8.85523148e+01 1.00083969e+02 3.21812096e+01 -4.46463776e+01 -8.53151169e+01 -6.33173447e+01 -2.16275330e+01 -2.47433281e+01 -1.24128733e+01 -1.92607880e+01 -2.13875618e+01 -3.34302254e+01 -3.79272270e+01 -3.50216179e+01 -2.42443695e+01 -2.62332954e+01 -6.26135826e+01 -1.09625702e+02 -1.18178703e+02 -9.80908127e+01 -7.02234726e+01 -4.97715378e+01 -2.34115620e+01 -1.95308037e+01 -3.73019142e+01 -4.20924301e+01 -2.46242809e+01 -2.09355221e+01 -4.33807220e+01 -6.22687340e+01 -7.16420441e+01 -6.66935883e+01 -6.14512901e+01 -5.17430725e+01 -5.64418259e+01 -5.04834251e+01 -5.28652039e+01 -5.41055603e+01 -7.45493698e+01 -8.75463867e+01 -8.44767914e+01 -5.39274940e+01 -4.44446516e+00 -1.56812537e+00 -3.38159828e+01 -7.46924133e+01 -6.43765869e+01 -5.60665665e+01 -5.52735786e+01 -6.18404083e+01 -6.21398125e+01 -5.18335190e+01 -2.99055614e+01 -1.00440397e+01 -1.53925295e+01 -4.92706566e+01 -7.86059418e+01 -8.07743530e+01 -6.59517212e+01 -8.46349487e+01 -1.19746109e+02 -1.32732162e+02 -1.21581322e+02 -8.99743729e+01 -9.44030685e+01 -9.02900543e+01 -9.22159119e+01 -7.78440475e+01 -7.98383484e+01 -8.23837738e+01 -1.00060135e+02 -9.16918411e+01 -9.24692154e+01 -8.94860764e+01 -9.56874008e+01 -8.46627197e+01 -7.44848328e+01 -5.13838959e+01 -3.12274456e+01 -3.54632378e+01 -5.20516739e+01 -7.11333008e+01 -6.92738419e+01 -7.95991592e+01 -9.20880661e+01 -9.03664246e+01 -4.78691673e+01 -1.27410107e+01 -7.21235752e+00 -3.92853966e+01 -6.71957397e+01 -6.64750900e+01 -6.23449631e+01 -6.12231293e+01 -6.77037430e+01 -4.77815170e+01 -6.76100874e+00 -5.78961313e-01 -2.79722691e+01 -7.46566849e+01 -7.16591339e+01 -7.19200516e+01 -6.86450653e+01 -7.47090378e+01 -6.97633133e+01 -6.09562798e+01 -4.71657028e+01 -4.36257324e+01 -5.49932747e+01 -6.79676819e+01 -6.32279205e+01 -3.05097160e+01 1.50640421e+01 1.70838108e+01 -1.92832222e+01 -6.11249619e+01 -6.88981323e+01 -7.62076187e+01 -7.64568405e+01 -7.11724625e+01 -3.09009476e+01 -7.21616220e+00 2.89942532e+01 3.20999641e+01 -1.76858580e+00 -3.72024117e+01 -7.81980438e+01 -5.10716705e+01 -2.61012936e+01 -5.67814598e+01 -1.19023170e+02 -1.55030609e+02 -1.26893448e+02 -8.61915665e+01 -9.01460800e+01 -9.02489853e+01 -9.76637726e+01 -9.88809814e+01 -1.10910103e+02 -1.19110703e+02 -1.23748299e+02 -1.25972923e+02 -1.23574699e+02 -1.19644600e+02 -1.17592628e+02 -1.20690247e+02 -1.18022820e+02 -1.02377785e+02 -7.10937195e+01 -7.91935501e+01 -1.00538383e+02 -1.33640793e+02 -1.04272453e+02 -7.25078735e+01 -1.01289383e+02 -1.59153076e+02 -1.57127838e+02 -8.84320831e+01 -4.70585785e+01 -7.40407715e+01 -1.05825417e+02 -8.91852493e+01 -5.46191254e+01 -4.98213959e+01 -6.34191170e+01 -9.30995941e+01 -9.04458847e+01 -8.87566986e+01 -9.39933243e+01 -9.55935745e+01 -1.18918892e+02 -1.37705399e+02 -1.10831329e+02 -6.38953514e+01 -3.76665993e+01 -6.19486542e+01 -8.09680786e+01 -6.05931015e+01 -4.17379341e+01 -3.71162796e+01 -6.01487961e+01 -8.73850327e+01 -8.47616119e+01 -8.18212967e+01 -7.66875076e+01 -8.95078506e+01 -7.72640991e+01 -5.57915802e+01 -4.98170242e+01 -5.66778297e+01 -8.63103790e+01 -1.05391502e+02 -1.13134293e+02 -1.13104080e+02 -1.00115089e+02 -1.37401611e+02 -1.75037811e+02 -1.71101044e+02 -1.24985245e+02 -8.73819962e+01 -9.71161423e+01 -1.15000160e+02 -9.99785767e+01 -7.33819809e+01 -7.32928391e+01 -9.19060745e+01 -1.15590347e+02 -1.21179260e+02 -1.21739822e+02 -1.22833199e+02 -1.21322632e+02 -1.20685905e+02 -1.13120438e+02 -9.66401215e+01 -9.06704788e+01 -9.79952164e+01 -1.14551140e+02 -1.22931564e+02 -1.28456345e+02 -1.26067825e+02 -1.48099396e+02 -1.69900421e+02 -1.51136047e+02 -1.04322968e+02 -7.86007462e+01 -1.02900276e+02 -1.31001190e+02 -1.44541000e+02 -1.49256302e+02 -1.50523544e+02 -1.46138779e+02 -1.41191284e+02 -1.44035843e+02 -1.40278442e+02 -1.41317734e+02 -1.38752136e+02 -1.46789230e+02 -1.48527954e+02 -1.50463959e+02 -1.38390884e+02 -1.36255569e+02 -1.43023270e+02 -1.53632156e+02 -1.57065979e+02 -1.45099152e+02 -1.34593338e+02 -1.27798027e+02 -1.11709869e+02 -9.73908997e+01 -9.31091156e+01 -1.08063553e+02 -1.08790382e+02 -7.93820953e+01 -6.02756500e+01 -7.41028061e+01 -9.77269363e+01 -9.49936523e+01 -7.50320206e+01 -7.47062302e+01 -9.35108337e+01 -1.08758965e+02 -1.10652977e+02 -1.08900902e+02 -1.08337128e+02 -1.06677185e+02 -1.08563103e+02 -1.16835197e+02 -1.10361160e+02 -9.70330124e+01 -8.75193634e+01 -9.97712784e+01 -1.16139183e+02 -1.16102379e+02 -1.05864151e+02 -1.18795090e+02 -1.39019424e+02 -1.50961456e+02 -1.42339920e+02 -1.31183105e+02 -1.36626495e+02 -1.35553711e+02 -1.35125549e+02 -1.32521255e+02 -1.35149734e+02 -1.35660645e+02 -1.33088654e+02 -1.35387619e+02 -1.38008560e+02 -1.44271118e+02 -1.41346405e+02 -1.36486832e+02 -1.34042435e+02 -1.25950562e+02 -1.17629189e+02 -1.19768196e+02 -1.32338623e+02 -1.46849899e+02 -1.50827896e+02 -1.49011368e+02 -1.56409668e+02 -1.65079483e+02 -1.65695358e+02 -1.58095795e+02 -1.48323090e+02 -1.48268967e+02 -1.47983856e+02 -1.33181793e+02 -1.19189659e+02 -1.16694260e+02 -1.27187752e+02 -1.34146118e+02 -1.33020813e+02 -1.35904037e+02 -1.41564560e+02 -1.41108231e+02 -1.47479492e+02 -1.55903976e+02 -1.52154953e+02 -1.38449615e+02 -1.29212891e+02 -1.33227844e+02 -1.32028580e+02 -1.18089432e+02 -1.10170006e+02 -1.15072144e+02 -1.30887375e+02 -1.35315643e+02 -1.30386536e+02 -1.29624817e+02 -1.35079147e+02 -1.44944778e+02 -1.43123322e+02 -1.38169907e+02 -1.37824890e+02 -1.40985229e+02 -1.46433060e+02 -1.48741516e+02 -1.49730988e+02 -1.50676270e+02 -1.47956116e+02 -1.48622116e+02 -1.48996994e+02 -1.44617767e+02 -1.40534485e+02 -1.38452072e+02 -1.42344498e+02 -1.45314346e+02 -1.42918579e+02 -1.39480164e+02 -1.41290878e+02 -1.61970245e+02 -1.77401123e+02 -1.81978622e+02 -4.63170135e+02 -7.16678467e+02 -6.52877625e+02 -6.86634949e+02 -6.92765869e+02 -3.61652679e+01 -7.75777435e+01 -4.32663544e+02 -5.55817566e+02 -5.25906128e+02 -4.88884216e+02 -3.74624634e+02 1.50361420e+02 28971730. 0. 0. 0. 0. 0. 0. -276646528. -276646528. -2.33673926e+03 -2.83143140e+03 -2.83143140e+03 -488244768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 569779712. 179301872. -134445168. 7.08827393e+02 2.88070038e+02 -1.90117096e+02 -8.32542953e+01 5.98496399e+01 -8.89950714e+01 -1.09370277e+02 -1.09225372e+02 -1.11162590e+02 -1.12360184e+02 -1.09140244e+02 -1.05258347e+02 -1.07678001e+02 -1.15859131e+02 -1.20075615e+02 -1.13602783e+02 -1.01641945e+02 -1.02097961e+02 -1.12522774e+02 -1.26010193e+02 -1.28325287e+02 -1.22205826e+02 -1.23517479e+02 -1.29267761e+02 -1.30488083e+02 -1.23989342e+02 -1.18167610e+02 -1.24431030e+02 -1.40475769e+02 -1.44041397e+02 -1.33762955e+02 -1.20218239e+02 -1.12182877e+02 -1.10085358e+02 -1.03694359e+02 -9.56815567e+01 -9.30124283e+01 -1.03691803e+02 -1.33442352e+02 -1.49643616e+02 -1.41873322e+02 -1.20585831e+02 -1.05588036e+02 -1.06677155e+02 -1.12604279e+02 -1.22676300e+02 -1.18927063e+02 -1.23371536e+02 -1.29694168e+02 -1.23989723e+02 -1.00937592e+02 -7.45784988e+01 -7.84224472e+01 -1.14277092e+02 -1.33059479e+02 -1.24032761e+02 -1.03019615e+02 -1.06468079e+02 -1.23307060e+02 -1.23257858e+02 -1.03341866e+02 -8.26831512e+01 -8.65065765e+01 -1.19461540e+02 -1.42730942e+02 -1.36130569e+02 -1.14639900e+02 -1.08343742e+02 -1.16986748e+02 -1.17224014e+02 -1.02860069e+02 -8.20947952e+01 -8.76727524e+01 -9.87775269e+01 -9.80406113e+01 -8.39496918e+01 -7.75404205e+01 -8.63938217e+01 -1.03418381e+02 -1.20517067e+02 -1.24505295e+02 -1.12843018e+02 -1.01649445e+02 -1.02647583e+02 -8.64958878e+01 -5.92127457e+01 -4.96552582e+01 -7.73593369e+01 -1.28850830e+02 -1.52135513e+02 -1.35239182e+02 -9.25156174e+01 -5.11699142e+01 -3.58684807e+01 -4.38669930e+01 -5.40713158e+01 -5.05777931e+01 -6.22396011e+01 -9.93122101e+01 -1.29521332e+02 -1.17551620e+02 -8.89931183e+01 -7.50164413e+01 -8.57349930e+01 -1.10796860e+02 -1.16773643e+02 -1.01614647e+02 -8.34869614e+01 -8.66087799e+01 -8.99419708e+01 -7.27753754e+01 -3.28538513e+01 -2.62468109e+01 -5.51886711e+01 -9.53988342e+01 -9.54916611e+01 -6.64961319e+01 -4.32998848e+01 -4.23953209e+01 -6.83887482e+01 -9.69407349e+01 -1.07422058e+02 -9.15930710e+01 -9.19815674e+01 -1.15519836e+02 -1.18529182e+02 -8.96610107e+01 -6.08995018e+01 -5.96669006e+01 -8.91127014e+01 -1.04069344e+02 -8.84517136e+01 -7.08148575e+01 -6.13113289e+01 -7.34107437e+01 -6.44170761e+01 -3.43930702e+01 -2.57714024e+01 -6.59691620e+01 -1.39448685e+02 -1.80094757e+02 -1.48764877e+02 -9.66501846e+01 -7.36303635e+01 -8.44070129e+01 -1.01923653e+02 -1.03675911e+02 -1.07528008e+02 -1.33958603e+02 -1.66596878e+02 -1.71751770e+02 -1.26362495e+02 -5.10372276e+01 -2.14247456e+01 -6.62179947e+01 -1.15801567e+02 -1.14453186e+02 -9.11571808e+01 -1.10810707e+02 -1.67273300e+02 -1.64453079e+02 -1.05320442e+02 -5.02622452e+01 -8.88195267e+01 -1.84393295e+02 -2.39266083e+02 -1.99307159e+02 -1.24490868e+02 -8.31896210e+01 -8.48712769e+01 -7.93638763e+01 -6.67345734e+01 -8.18217697e+01 -1.29812851e+02 -1.94656372e+02 -1.65808289e+02 -1.13354912e+02 -5.75473022e+01 -7.02737122e+01 -9.41266632e+01 -1.22397102e+02 -1.32434082e+02 -1.32368134e+02 -1.51243500e+02 -1.83325562e+02 -1.68018936e+02 -1.02767555e+02 -4.02182922e+01 -5.24057426e+01 -1.20600441e+02 -1.77369888e+02 -1.66268600e+02 -1.18221107e+02 -8.49826126e+01 -7.91002960e+01 -6.59190445e+01 -1.39471073e+01 1.11535702e+01 -4.20807686e+01 -1.14816689e+02 -1.45242859e+02 -1.03721725e+02 -5.20812569e+01 -2.70337181e+01 -3.96984978e+01 -5.96475716e+01 -8.13762131e+01 -7.39856262e+01 -9.41893082e+01 -1.23828400e+02 -9.51314545e+01 -4.89536972e+01 -2.28100948e+01 -3.54119720e+01 -7.65000153e+01 -8.38255386e+01 -6.68103790e+01 -5.91796570e+01 -6.61154556e+01 -1.05641212e+02 -7.67184525e+01 -3.35767593e+01 -1.11653216e-01 4.86127806e+00 -5.90104332e+01 -1.00370567e+02 -8.83647232e+01 -1.86540012e+01 -3.12155008e+00 -4.09236526e+01 -9.40857239e+01 -8.28750229e+01 -4.96144142e+01 -5.33207321e+01 -9.61966095e+01 -1.06867783e+02 -4.42005997e+01 -7.83249331e+00 -4.09108467e+01 -8.06595078e+01 -5.11201210e+01 -2.64286900e+01 -4.40781708e+01 -6.39478149e+01 -8.02301254e+01 -6.20948982e+01 -9.58219681e+01 -1.13504807e+02 -1.13442482e+02 -1.28121613e+02 -1.48621872e+02 -1.54785522e+02 -8.04088669e+01 -5.16878242e+01 -5.01591415e+01 -1.08945793e+02 -9.30447235e+01 -8.53321686e+01 -9.94989395e+01 -1.43382004e+02 -1.60714050e+02 -9.24550781e+01 -4.37750320e+01 -4.06308937e+01 -1.08824921e+02 -1.14128296e+02 -9.64310303e+01 -5.96804199e+01 -6.25241776e+01 -1.16578003e+02 -1.02001320e+02 -6.53959885e+01 6.51170349e+00 3.29918404e+01 1.43061390e+01 -3.55579758e+01 -7.79368668e+01 -4.66805420e+01 2.81510258e+00 2.41999989e+01 5.49533188e-01 2.65511894e+01 2.97221737e+01 -1.61509724e+01 -8.30966110e+01 -8.96952667e+01 5.66159534e+00 3.26592751e+01 -5.38164759e+00 -8.38538895e+01 -5.12080421e+01 -1.01174583e+01 1.47162807e+00 -2.67528992e+01 -6.32293320e+01 -5.58938065e+01 -6.98085251e+01 -2.24488754e+01 1.26578796e+00 6.78319836e+00 -3.90280037e+01 -6.44038696e+01 -2.12303905e+01 1.58065195e+01 2.86730099e+01 2.52099628e+01 9.73357468e+01 1.35904236e+02 1.30473404e+02 9.98574219e+01 9.99922867e+01 1.43309219e+02 1.60455139e+02 1.24808434e+02 4.19348488e+01 1.01321487e+01 5.07147837e+00 2.78889160e+01 9.75288677e+00 -4.16287766e+01 -8.21991882e+01 -9.94965134e+01 -3.87384453e+01 -9.52284813e+00 1.51345119e+01 -4.72877264e+00 7.75705814e+00 2.91492577e+01 6.01511536e+01 5.27541122e+01 5.47484360e+01 9.64352951e+01 1.34682037e+02 1.11600632e+02 5.84396057e+01 5.57544594e+01 4.45271873e+01 -1.54567804e+01 -7.24985733e+01 -9.37083664e+01 -2.95866261e+01 -1.73219700e+01 -6.85808086e+00 3.48638306e+01 3.55980682e+01 -2.78726673e+00 -9.53961334e+01 -1.16570961e+02 -3.80662766e+01 2.98107796e+01 2.75787678e+01 -2.93180561e+01 -7.42320557e+01 -4.26218452e+01 1.63687382e+01 6.41328583e+01 6.70801239e+01 1.10827465e+01 -2.19482594e+01 -7.44059906e+01 -6.79922333e+01 -6.70368347e+01 -9.79416428e+01 -1.14421791e+02 -1.24507172e+02 -3.10514450e+01 -1.65413589e+01 -9.40338612e+00 -1.57713537e+01 -3.13619137e+01 -8.94114609e+01 -2.09911530e+02 -2.27606995e+02 -1.28306168e+02 3.30496674e+01 1.03329018e+02 6.15991688e+00 -1.24773941e+02 -1.26792404e+02 8.51664162e+00 1.57775650e+02 1.19225319e+02 -8.82404518e+00 -8.38514709e+01 -7.61608887e+01 8.44676495e+00 -8.18435192e+00 -5.46654778e+01 -9.70963516e+01 -1.08578796e+02 -3.49414787e+01 -3.83699684e+01 -6.75296402e+01 -1.17314407e+02 -1.12360916e+02 -6.93811874e+01 -8.32301941e+01 -9.83106003e+01 -1.74602585e+01 8.41816177e+01 7.82166443e+01 -7.82202682e+01 -1.83486206e+02 -1.39543655e+02 -9.84454727e+00 6.23453255e+01 3.94376030e+01 -5.08901482e+01 -9.47081375e+01 -1.08398544e+02 -2.55949516e+01 -1.23932676e+01 -2.27503681e+01 -6.37651787e+01 -9.27254257e+01 -2.94872131e+01 1.39867477e+01 9.23444519e+01 8.84798813e+01 6.70854797e+01 -1.51852942e+00 -1.04173729e+02 -1.45485901e+02 -7.19331665e+01 8.07521667e+01 1.56220444e+02 8.93636322e+01 -7.07337723e+01 -1.18671730e+02 7.55057573e-01 1.66167984e+02 1.61224792e+02 1.79562550e+01 -5.41130333e+01 -4.44360542e+01 2.78170738e+01 2.91816044e+01 -2.07738972e+01 -8.34321442e+01 -1.33226379e+02 -1.23259468e+02 -1.53103546e+02 -1.53531494e+02 -8.71518707e+01 1.91188107e+01 6.62574997e+01 -7.04376602e+00 -7.80620346e+01 -5.69317513e+01 4.62071495e+01 1.34798050e+02 9.41381149e+01 -1.93432331e+01 -4.66836472e+01 -1.65060878e-01 9.50377808e+01 6.74659729e+01 -1.43854427e+01 -7.87603683e+01 -1.25466843e+02 -5.95491486e+01 -6.03113022e+01 -2.67169685e+01 -2.99712429e+01 -4.90793953e+01 -6.90708389e+01 -1.18840012e+02 -6.88875046e+01 6.95858300e-01 7.62943573e+01 4.40702133e+01 -4.94245148e+01 -1.25455818e+02 -7.17016830e+01 3.43411140e+01 1.10505188e+02 8.84114456e+01 2.17593803e+01 -1.22028713e+01 -2.15234852e+01 3.95094013e+00 -8.67634773e+00 -3.58005867e+01 -8.35066299e+01 -1.40971863e+02 -1.20649719e+02 -2.44851036e+01 4.77836189e+01 5.55391273e+01 6.90651703e+00 -2.94450970e+01 -8.68873138e+01 -1.17518044e+02 -2.43094234e+01 1.04483635e+02 1.62662216e+02 6.69293289e+01 -4.95300255e+01 -5.70680923e+01 4.96858940e+01 1.83401855e+02 1.66652817e+02 3.68398857e+01 -1.05909760e+02 -1.53740448e+02 -7.48720322e+01 -2.98096871e+00 2.65742993e+00 -3.32667542e+01 -5.99235840e+01 -1.44703436e+01 -1.57600317e+01 -2.08019829e+00 3.82364311e+01 5.14370461e+01 5.33340950e+01 -1.18089123e+01 8.18766499e+00 8.72387924e+01 1.81726761e+02 1.63314972e+02 1.58638363e+01 -9.19160767e+01 -6.67516327e+01 6.24534302e+01 1.48328705e+02 1.55087982e+02 5.29282341e+01 -4.14287300e+01 -8.22567749e+01 -7.58996773e+00 3.99935722e+01 8.16052704e+01 7.80257339e+01 6.32112999e+01 7.28618927e+01 7.67844696e+01 1.41780045e+02 1.76289932e+02 1.73232864e+02 1.22538620e+02 2.51016541e+01 -7.30983591e+00 4.77177086e+01 1.43305420e+02 1.70500366e+02 1.13920128e+02 2.39239254e+01 2.93180866e+01 8.85984650e+01 1.82772522e+02 1.93141113e+02 1.10613342e+02 1.85362968e+01 -2.38728943e+01 4.75628090e+01 1.18954796e+02 1.24088890e+02 6.65001678e+01 6.07881594e+00 1.02475595e+00 5.62741661e+00 3.25805283e+01 9.96949463e+01 1.16709854e+02 6.65744781e+01 -4.98300629e+01 -9.25986862e+01 -2.69081573e+01 6.50871964e+01 1.30441040e+02 8.59017029e+01 1.25618515e+01 -2.95660305e+01 -2.69745851e+00 6.04623070e+01 5.52606544e+01 5.94650364e+00 -4.88711624e+01 -4.91057205e+01 2.39631767e+01 7.55904999e+01 6.19463348e+01 6.25325871e+00 -5.81071205e+01 -4.75701714e+01 -3.67503471e+01 -9.78071117e+00 2.79760475e+01 5.38469048e+01 7.13440399e+01 1.25235882e+01 -2.56998558e+01 -9.10822105e+00 5.08023529e+01 1.05609962e+02 6.55953064e+01 6.54613590e+00 -3.01452847e+01 3.03763561e+01 1.50976685e+02 2.12998260e+02 1.52625763e+02 1.33096685e+01 -6.77338638e+01 -2.75898933e+01 5.49848328e+01 9.17775269e+01 9.44562607e+01 1.08021210e+02 1.56337799e+02 8.52729111e+01 2.27505295e+02 3.36633392e+02 2.56777539e+03 3.46949756e+03 6.51618750e+03 1.62634033e+04 -113888552. 2.29388518e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.00599859e+10 -368908384. 7.37914697e+03 1.88488135e+03 -4.15241974e+02 1.50659839e+03 5.43239453e+03 2.94695703e+03 6.85092896e+02 3.07070435e+02 2.32652267e+02 1.96523941e+02 1.39274811e+02 5.41960297e+01 2.55599041e+01 4.36793022e+01 1.04605537e+02 1.42627502e+02 1.35479584e+02 8.50916672e+01 1.44040785e+01 1.50805168e+01 3.60067825e+01 5.95316582e+01 6.11659203e+01 6.18145866e+01 8.80240402e+01 6.24252281e+01 6.21691933e+01 1.09338997e+02 1.44686493e+02 1.12133385e+02 2.02620735e+01 -2.94235249e+01 2.94924507e+01 1.04357811e+02 1.52765549e+02 1.28525970e+02 4.70901756e+01 -1.89698105e+01 -4.69188728e+01 1.65312233e+01 6.18464127e+01 6.68798752e+01 2.20981770e+01 -7.95912266e+00 1.88666115e+01 2.31324539e+01 5.30462074e+01 8.33203964e+01 1.00529884e+02 7.80348816e+01 -1.26324677e+00 -7.56550074e+00 5.74107475e+01 1.38293839e+02 1.56242538e+02 8.82533417e+01 2.61890488e+01 3.12362251e+01 8.14049988e+01 1.04160263e+02 6.01027031e+01 -1.06940374e+01 -3.07227879e+01 -3.25097585e+00 7.43349686e+01 1.27213066e+02 1.29105286e+02 8.43861465e+01 2.09892960e+01 -1.94079857e+01 -3.93039856e+01 -1.69815178e+01 2.00641060e+01 5.59723892e+01 7.33922653e+01 6.09906540e+01 7.01871185e+01 1.12581070e+02 1.52846329e+02 1.47233688e+02 9.27647400e+01 5.41188545e+01 6.54887543e+01 8.96794434e+01 1.25542931e+02 1.44746902e+02 1.25455948e+02 7.39135284e+01 4.60343819e+01 7.70689392e+01 1.16110039e+02 1.11321548e+02 8.61590805e+01 7.89724426e+01 9.33167267e+01 8.46058960e+01 8.59865799e+01 1.05654678e+02 1.17731354e+02 1.03713890e+02 5.17838020e+01 4.81798172e+01 9.55692978e+01 1.58247253e+02 1.80630737e+02 1.38249893e+02 9.47900162e+01 7.74727707e+01 8.81891556e+01 1.04922005e+02 1.08136772e+02 9.87770920e+01 7.49907227e+01 6.16845970e+01 8.51343384e+01 1.27269760e+02 1.40934631e+02 1.25830093e+02 1.10608994e+02 1.06410561e+02 9.00184250e+01 8.96811295e+01 1.23698227e+02 1.62632294e+02 1.60632492e+02 1.10427834e+02 8.89519424e+01 1.16992615e+02 1.56646927e+02 1.62497177e+02 1.26704834e+02 9.27374496e+01 8.57715683e+01 9.88561096e+01 1.27322510e+02 1.47379425e+02 1.39002106e+02 1.07003853e+02 8.46450424e+01 1.02055038e+02 1.31901367e+02 1.41177902e+02 1.31110260e+02 1.19045967e+02 1.10404129e+02 9.21045303e+01 8.30797348e+01 9.16367493e+01 1.07179893e+02 1.08697403e+02 9.11021576e+01 8.33950577e+01 1.02477196e+02 1.35890045e+02 1.57849304e+02 1.44952148e+02 1.12323616e+02 9.06372452e+01 9.64029083e+01 1.13434021e+02 1.20147202e+02 1.11014816e+02 1.09560349e+02 9.86274796e+01 1.05026924e+02 1.07289101e+02 1.17071739e+02 1.29602600e+02 1.34841553e+02 1.37210403e+02 1.20212067e+02 1.11968933e+02 1.21349335e+02 1.31879684e+02 1.26739128e+02 1.05794365e+02 9.62242203e+01 1.03875084e+02 1.13176552e+02 1.20095543e+02 1.19925026e+02 1.14534279e+02 1.11627167e+02 1.10169273e+02 1.20187912e+02 1.18688408e+02 1.13447266e+02 1.04791229e+02 9.59093246e+01 9.10571976e+01 8.67653656e+01 9.58265152e+01 1.09252518e+02 1.16580009e+02 1.16699188e+02 1.09624908e+02 1.09525101e+02 1.16529350e+02 1.24828842e+02 1.28037674e+02 1.17695465e+02 1.05715805e+02 1.00306137e+02 1.03911400e+02 1.09215981e+02 1.11584579e+02 1.11147293e+02 1.09485085e+02 1.07578186e+02 1.09534172e+02 1.13319313e+02 1.15059807e+02 1.13214874e+02 1.12575195e+02 1.12140549e+02 1.11474312e+02 1.11546700e+02 1.12810074e+02 1.13850784e+02 1.13922554e+02 1.13851250e+02 1.14377983e+02 1.14771248e+02 1.14757088e+02 1.14426979e+02 1.14191162e+02 1.14238174e+02 1.15108582e+02 1.15817955e+02 1.15266472e+02 1.13661186e+02 1.12737282e+02 1.14180145e+02 1.15682983e+02 1.15467667e+02 1.14895050e+02 1.14682922e+02 1.14462654e+02 1.14165779e+02 1.14054161e+02 1.14057381e+02 1.14312073e+02 1.13389137e+02 1.12553177e+02 1.10039871e+02 1.10117027e+02 1.10928429e+02 1.13681816e+02 1.13371101e+02 1.12032944e+02 1.11793518e+02 1.12373291e+02 1.16415642e+02 1.19410469e+02 1.20247795e+02 1.18500549e+02 1.14341621e+02 1.14388100e+02 1.14282127e+02 1.14684708e+02 1.12576996e+02 1.12743942e+02 1.12948357e+02 1.13123482e+02 1.10174644e+02 1.10644165e+02 1.10402702e+02 1.09941490e+02 1.07275833e+02 1.07279716e+02 1.06639656e+02 1.06110306e+02 1.08004601e+02 1.09563560e+02 1.12019203e+02 1.10045891e+02 1.09870911e+02 1.06888855e+02 1.06570618e+02 1.07332024e+02 1.12765244e+02 1.11899445e+02 1.12609032e+02 1.09033928e+02 1.11943047e+02 1.07329948e+02 1.07974007e+02 1.08258560e+02 1.13263687e+02 1.11525764e+02 1.09792648e+02 1.08859245e+02 1.11224480e+02 1.11296280e+02 1.06467133e+02 1.07746117e+02 1.12308998e+02 1.18132927e+02 1.17878075e+02 1.18962784e+02 1.17659096e+02 1.15707184e+02 1.13586426e+02 1.15826019e+02 1.14351967e+02 1.12831375e+02 1.12420189e+02 1.18321404e+02 1.14480476e+02 1.11215553e+02 1.06336403e+02 1.10321297e+02 1.01724709e+02 9.27958832e+01 9.14527206e+01 9.86806946e+01 1.09215454e+02 1.09884621e+02 1.07715195e+02 1.05451431e+02 1.00157875e+02 1.07576683e+02 1.09128258e+02 1.10960434e+02 1.10471176e+02 1.18089729e+02 1.19821060e+02 1.10684547e+02 1.07327606e+02 1.09610809e+02 1.10739189e+02 1.06827271e+02 1.09363922e+02 1.13586456e+02 1.15810638e+02 1.16390068e+02 1.20319748e+02 1.16665466e+02 1.13032600e+02 1.08356979e+02 1.09231400e+02 1.10486328e+02 1.15554047e+02 1.12263611e+02 1.03365585e+02 8.70861435e+01 9.36097107e+01 1.02963997e+02 1.15923904e+02 1.15457359e+02 1.07986191e+02 1.03335930e+02 9.86662064e+01 9.45041199e+01 8.87600327e+01 8.31021729e+01 9.26480103e+01 9.33197174e+01 9.97444229e+01 9.46285858e+01 9.85146103e+01 1.01356163e+02 1.05570557e+02 9.86482162e+01 9.43682327e+01 9.25915222e+01 9.66777496e+01 1.00220741e+02 9.45727386e+01 8.29474716e+01 6.14255104e+01 6.71693954e+01 8.56426468e+01 1.12614304e+02 1.00674713e+02 8.34417648e+01 7.02495270e+01 8.16043091e+01 9.65157318e+01 9.49567413e+01 8.10652161e+01 6.86609039e+01 6.75124207e+01 7.52319717e+01 7.08886719e+01 5.66913490e+01 4.74332848e+01 6.31173744e+01 8.84019165e+01 9.56665039e+01 8.39952850e+01 7.80924072e+01 7.84378815e+01 9.05704575e+01 9.49267960e+01 8.49352875e+01 6.65037537e+01 6.99245682e+01 8.29218979e+01 1.06379631e+02 1.02544441e+02 1.00395905e+02 9.27803268e+01 1.07805931e+02 1.33888794e+02 1.46066559e+02 1.21202278e+02 9.30449753e+01 8.15440445e+01 8.20092926e+01 6.66444702e+01 5.98572578e+01 9.72271423e+01 1.44777496e+02 1.50605728e+02 1.15224648e+02 8.11582870e+01 7.82478790e+01 8.50818710e+01 1.05355110e+02 1.19054436e+02 1.09584511e+02 8.44419785e+01 6.67057190e+01 6.60996323e+01 6.08274612e+01 8.62270584e+01 1.25745979e+02 1.33612976e+02 1.08045113e+02 7.74297638e+01 6.28477516e+01 5.39303780e+01 5.22210960e+01 7.51371689e+01 8.41750031e+01 8.95995026e+01 8.98168640e+01 9.58631821e+01 1.02539635e+02 1.06172516e+02 1.03589081e+02 1.01628860e+02 1.00977119e+02 1.09885872e+02 1.13701607e+02 9.81230774e+01 7.96773071e+01 -1.71139374e+01 -7.95595322e+01 -9.00100327e+00 5.04742012e+01 2.95631714e+02 -2.91444580e+03 -7.90668164e+03 -265973216. -129420576. -128813800. 261197248. -433912480. 679879680. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.46511590e+09 -162604928. -3.49388828e+04 -1.36611895e+04 -2.30558057e+03 -5.20950537e+03 -3.15437378e+03 -6.26938110e+02 -1.73125931e+02 -5.38984299e+00 1.20615091e+01 1.63697453e+01 1.75444126e+01 6.43736219e+00 -1.39654338e+00 -1.13353682e+01 -1.02859545e+01 -5.92596054e+00 2.12053604e+01 2.81997318e+01 2.06383705e+01 -9.26960850e+00 -4.26288986e+00 1.91957798e+01 5.41336594e+01 5.82560501e+01 6.25187340e+01 6.84906464e+01 8.40903397e+01 9.24708557e+01 9.74761429e+01 1.06002022e+02 1.02730247e+02 1.05696732e+02 9.44538727e+01 9.27804184e+01 1.05385254e+02 1.14537560e+02 1.18799004e+02 9.39859619e+01 8.16932831e+01 8.19258347e+01 9.55080948e+01 1.01782471e+02 1.13797752e+02 1.16918961e+02 1.09791344e+02 6.72159042e+01 3.36213226e+01 1.58518524e+01 3.14914856e+01 4.50496788e+01 5.74714317e+01 7.16081924e+01 7.07262650e+01 5.98057709e+01 5.10258789e+01 5.40360680e+01 6.86361389e+01 7.43281784e+01 9.29189911e+01 7.45197449e+01 5.74197998e+01 4.07240715e+01 2.39415588e+01 1.42768126e+01 4.19924545e+00 2.06566753e+01 3.27778969e+01 2.98109970e+01 3.92115440e+01 6.51074371e+01 8.12757263e+01 6.93323593e+01 5.07504158e+01 4.70645370e+01 5.43944588e+01 3.03284950e+01 -1.08842258e+01 -6.69542408e+00 7.71994925e+00 2.70420227e+01 -2.47178860e+01 -7.05700760e+01 -6.86297760e+01 -4.22997017e+01 -2.08333988e+01 -2.70701466e+01 -3.04886398e+01 -1.14710608e+01 -2.08761158e+01 -4.25324173e+01 -8.32086792e+01 -7.23393555e+01 -3.16933041e+01 1.38401642e+01 3.58873596e+01 3.46762962e+01 3.03774776e+01 1.81653576e+01 3.75261230e+01 5.88723717e+01 3.64829483e+01 -1.26647961e+00 -1.19473124e+01 2.61214523e+01 5.09307098e+01 3.97283912e+00 -3.00261822e+01 -1.99320736e+01 3.04793339e+01 6.12691307e+01 6.39133072e+01 6.40034561e+01 6.17252083e+01 5.37182655e+01 3.63165092e+01 3.66991997e+01 4.40238380e+01 4.58547554e+01 3.23546562e+01 2.26625118e+01 2.13406620e+01 2.52150612e+01 2.04260712e+01 1.79825706e+01 1.56309662e+01 -2.26927299e+01 -6.09572601e+01 -5.69647675e+01 -1.83591442e+01 1.78471699e+01 -2.24983177e+01 -6.40154114e+01 -6.91848602e+01 -3.67319717e+01 -4.00570107e+00 8.98703218e-01 7.82849836e+00 2.66675873e+01 1.69155178e+01 9.58214760e+00 3.21676284e-02 1.65736961e+01 3.30888519e+01 3.23804626e+01 1.69450035e+01 -9.86126587e-02 7.85206020e-01 2.28872800e+00 4.20341873e+00 -1.02031984e+01 -5.52471085e+01 -1.02805672e+02 -1.04143242e+02 -6.90606918e+01 -3.29935112e+01 -6.47141571e+01 -1.02024223e+02 -9.37478180e+01 -4.28909836e+01 5.66781235e+00 5.50992441e+00 -6.33201122e+00 -1.42488937e+01 -1.84607925e+01 -1.69115772e+01 -2.01174850e+01 -1.45240870e+01 -1.51618938e+01 -3.60299683e+01 -6.63531036e+01 -5.80270996e+01 -3.20301208e+01 4.78846550e+00 7.85110092e+00 8.66696930e+00 -2.81302547e+01 -6.93686752e+01 -6.66854401e+01 -4.27896957e+01 -2.03778725e+01 -2.14270039e+01 -2.84951901e+00 -2.87508507e+01 -7.63655472e+01 -8.90414963e+01 -5.67373047e+01 -2.16274166e+01 -2.92522259e+01 -3.44164009e+01 -2.55484600e+01 -1.82464314e+01 -3.01311893e+01 -3.48182144e+01 -7.25260162e+01 -1.05024651e+02 -1.06543808e+02 -6.95913849e+01 -3.44158516e+01 -4.48912964e+01 -4.92862663e+01 -8.24459000e+01 -1.07789551e+02 -1.02389244e+02 -5.21409111e+01 -9.64980030e+00 -1.65947533e+01 -2.30021057e+01 -3.18741550e+01 -1.98802872e+01 -1.13822470e+01 -2.88456893e+00 -5.82990170e+00 -9.21352386e+00 -9.95144272e+00 -3.57421637e+00 -5.61370182e+00 1.16903076e+01 2.69560738e+01 3.46719475e+01 3.49625664e+01 1.81891460e+01 1.97468014e+01 1.91846790e+01 1.68353500e+01 1.35764675e+01 7.56111097e+00 1.74892998e+01 2.32528877e+00 -7.14792967e+00 -8.05160141e+00 1.42448969e+01 1.54876595e+01 8.33348179e+00 -2.87756395e+00 -1.81770396e+00 3.75519824e+00 -9.13235569e+00 -4.56748581e+00 -2.89845505e+01 -3.52232857e+01 -4.46609802e+01 -1.05113316e+01 2.86750584e+01 6.43492413e+00 -5.73352470e+01 -1.04531487e+02 -8.91149521e+01 -5.87245674e+01 -4.99594536e+01 -5.16901131e+01 -4.86709633e+01 -5.10071182e+01 -5.29865189e+01 -5.61541672e+01 -5.02399025e+01 -3.44715614e+01 -1.91635895e+01 -1.26472597e+01 -2.49469814e+01 -3.90065956e+01 -5.38135643e+01 -5.66477013e+01 -4.94776421e+01 -4.41176567e+01 -3.27294197e+01 -3.00856400e+01 -1.81745872e+01 -3.40680656e+01 -7.20000458e+01 -1.11119202e+02 -1.03015381e+02 -7.60531769e+01 -4.29546623e+01 -3.83441544e+01 -3.74655571e+01 -5.58312263e+01 -7.99721756e+01 -9.44209518e+01 -1.04466187e+02 -7.92569809e+01 -5.45188560e+01 -2.41839027e+01 -3.94484062e+01 -5.33695717e+01 -6.36013374e+01 -4.90237427e+01 -4.34954185e+01 -3.22591553e+01 -4.70073357e+01 -6.28401375e+01 -7.27716293e+01 -7.78713074e+01 -7.43340607e+01 -1.10604813e+02 -1.36195160e+02 -1.28612869e+02 -8.43499603e+01 -5.12916565e+01 -5.94397469e+01 -7.75021896e+01 -7.20528259e+01 -7.29897919e+01 -9.37153244e+01 -1.27383873e+02 -1.23483925e+02 -8.35084991e+01 -4.53130035e+01 -6.46510544e+01 -8.76246185e+01 -8.13136673e+01 -5.85143623e+01 -4.84499779e+01 -6.02603531e+01 -7.40092392e+01 -6.04889755e+01 -3.35734634e+01 -2.81355400e+01 -3.37123871e+01 -5.01337471e+01 -3.86257782e+01 -6.43263550e+01 -9.68031845e+01 -1.04897743e+02 -1.15785820e+02 -1.32492264e+02 -1.62843262e+02 -1.62000198e+02 -1.49580505e+02 -1.52234879e+02 -1.34530624e+02 -1.28847183e+02 -9.75407944e+01 -6.49158249e+01 -2.13279686e+01 -1.19986010e+01 -2.17105217e+01 -3.27411919e+01 -4.00548439e+01 -4.55882225e+01 -4.84980125e+01 -4.05040817e+01 -3.32727547e+01 -6.05261497e+01 -1.03770172e+02 -1.18084084e+02 -1.13639046e+02 -9.24013748e+01 -8.40991745e+01 -7.85914383e+01 -5.65134811e+01 -6.89311981e+01 -7.01994247e+01 -8.72460022e+01 -1.03300385e+02 -1.20628487e+02 -1.48893463e+02 -1.20671921e+02 -8.87711945e+01 -7.53261108e+01 -1.10441963e+02 -1.17172356e+02 -1.03580963e+02 -7.05653381e+01 -9.77438812e+01 -1.26172905e+02 -1.36989151e+02 -1.13166458e+02 -8.68295135e+01 -1.16027420e+02 -1.46985977e+02 -1.39913071e+02 -9.67400589e+01 -6.41877670e+01 -8.78328018e+01 -1.08884361e+02 -8.33692474e+01 -4.74016304e+01 -6.61892700e+01 -1.15371002e+02 -1.36612381e+02 -1.24608253e+02 -1.09564613e+02 -1.21206451e+02 -1.42113968e+02 -1.61605286e+02 -1.47223862e+02 -1.06830688e+02 -7.37720032e+01 -7.42911758e+01 -8.41442947e+01 -9.05992889e+01 -8.69541931e+01 -8.36032715e+01 -8.97127380e+01 -1.07545380e+02 -1.07280754e+02 -8.85111465e+01 -8.25729904e+01 -9.07088318e+01 -1.19659904e+02 -1.33193573e+02 -1.23434029e+02 -1.11988571e+02 -9.04564972e+01 -9.69806137e+01 -9.31736755e+01 -8.60671082e+01 -7.02008743e+01 -7.04669952e+01 -1.13966270e+02 -1.44696228e+02 -1.12124481e+02 -5.22066956e+01 -5.13895226e+01 -1.01486221e+02 -1.21137611e+02 -9.46950607e+01 -8.13287506e+01 -1.00578728e+02 -1.10957748e+02 -1.07010910e+02 -8.38405151e+01 -9.60578156e+01 -1.01429054e+02 -1.11329025e+02 -9.98420792e+01 -7.64921494e+01 -7.78877335e+01 -7.73343735e+01 -1.05379166e+02 -1.24437195e+02 -1.26415619e+02 -1.02701653e+02 -1.00723686e+02 -1.45574158e+02 -1.75396118e+02 -1.60142563e+02 -1.17513931e+02 -1.14186745e+02 -1.31536636e+02 -1.14884682e+02 -7.95773392e+01 -6.63020172e+01 -9.76571808e+01 -1.15731491e+02 -1.11272972e+02 -9.84264450e+01 -1.13141060e+02 -1.21458435e+02 -1.24005051e+02 -1.14876617e+02 -1.03537743e+02 -9.23189087e+01 -8.53547287e+01 -9.21747131e+01 -1.01107765e+02 -1.13653610e+02 -1.17437744e+02 -1.20308212e+02 -1.34090561e+02 -1.38125229e+02 -1.26867119e+02 -1.13243172e+02 -1.13366982e+02 -1.30174103e+02 -1.31371262e+02 -1.28672409e+02 -1.38595108e+02 -1.71948288e+02 -1.93563217e+02 -1.77670792e+02 -1.37762817e+02 -1.25056000e+02 -1.35335068e+02 -1.39784286e+02 -1.23696945e+02 -1.11085732e+02 -1.03481033e+02 -9.80224915e+01 -1.00166618e+02 -1.11680420e+02 -1.11381592e+02 -1.00661575e+02 -9.88662033e+01 -1.27817360e+02 -1.42391342e+02 -1.29365295e+02 -1.10085197e+02 -1.24244705e+02 -1.33995300e+02 -1.18135757e+02 -8.56176300e+01 -6.33839188e+01 -6.81560974e+01 -7.03143387e+01 -7.95490417e+01 -8.61588058e+01 -9.10261536e+01 -9.24445496e+01 -9.65874557e+01 -1.01854988e+02 -9.99483871e+01 -8.78279419e+01 -9.81736145e+01 -1.27445831e+02 -1.46738281e+02 -1.49011322e+02 -1.44809235e+02 -1.32116440e+02 -1.22004974e+02 -1.09574234e+02 -1.13899567e+02 -1.09965851e+02 -1.04290154e+02 -1.02094742e+02 -1.07601799e+02 -1.11373985e+02 -1.14822273e+02 -1.13980515e+02 -1.10571365e+02 -1.08387199e+02 -1.06909363e+02 -1.22473297e+02 -1.39199921e+02 -1.41990738e+02 -1.30524811e+02 -1.17676201e+02 -1.18557816e+02 -1.17388634e+02 -1.18354866e+02 -1.14329453e+02 -1.13776108e+02 -1.15330635e+02 -1.27108406e+02 -1.38758652e+02 -1.31874054e+02 -1.18854813e+02 -1.15999680e+02 -1.37545609e+02 -1.50194855e+02 -1.41657364e+02 -1.20989922e+02 -1.22362724e+02 -1.30401260e+02 -1.30263870e+02 -1.20714249e+02 -1.12960083e+02 -1.23888725e+02 -1.31472610e+02 -1.38915726e+02 -1.42553818e+02 -1.30892014e+02 -1.21298737e+02 -1.20184494e+02 -1.40719788e+02 -1.49094543e+02 -1.35964569e+02 -1.19041176e+02 -1.21412888e+02 -1.34516724e+02 -1.35165039e+02 -1.27959557e+02 -1.20355453e+02 -1.25716354e+02 -1.32590103e+02 -1.33642868e+02 -1.29538940e+02 -1.23161942e+02 -1.21619423e+02 -1.27752281e+02 -1.34378220e+02 -1.34467880e+02 -1.28336304e+02 -1.18093140e+02 -1.22209816e+02 -1.26883415e+02 -1.27081352e+02 -1.21456566e+02 -1.21105057e+02 -1.28436234e+02 -1.27542336e+02 -1.20871002e+02 -1.13494850e+02 -1.12846680e+02 -1.12502327e+02 -1.16538391e+02 -1.21843697e+02 -1.24358269e+02 -1.21880592e+02 -1.16710922e+02 -1.14127419e+02 -1.13721031e+02 -1.16919540e+02 -1.19776527e+02 -1.19507294e+02 -1.39010773e+02 -1.63798752e+02 -1.59743698e+02 -1.32730255e+02 -1.02949760e+02 -1.28922928e+02 -1.30202499e+02 -1.45208313e+02 -5.15707397e+02 -1.14250586e+03 346091712. 152486128. 121745680. -315469920. 4.43371233e+10 0. 0. 0. 0. 0. 0. -276646528. -276646528. 575466752. -272882528. -272882528. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 569779712. 179301872. -134445168. 8.47798157e+02 3.48325073e+02 -2.67269684e+02 -5.28902039e+02 -3.94354218e+02 -1.75049026e+02 -1.38158096e+02 -1.05542038e+02 -8.08455582e+01 -7.91304092e+01 -8.45802307e+01 -8.66191101e+01 -8.25237732e+01 -8.53274994e+01 -9.26142044e+01 -9.91554184e+01 -9.20375900e+01 -7.60909424e+01 -6.88835602e+01 -7.44532547e+01 -8.64619598e+01 -9.21431808e+01 -8.99176865e+01 -8.69255219e+01 -9.07564163e+01 -9.57101135e+01 -9.03731918e+01 -7.84315796e+01 -7.23110580e+01 -7.73086243e+01 -8.88708725e+01 -9.30420227e+01 -8.47826385e+01 -7.22868423e+01 -6.59591751e+01 -7.26517105e+01 -7.08814850e+01 -6.27062302e+01 -6.95008240e+01 -8.79055786e+01 -1.00551682e+02 -8.19661102e+01 -5.04012451e+01 -4.22586975e+01 -5.88728294e+01 -7.49730072e+01 -8.55925980e+01 -8.67312164e+01 -8.56556091e+01 -8.35059204e+01 -8.42578278e+01 -7.94739151e+01 -5.31241112e+01 -3.51899948e+01 -4.24413490e+01 -6.85849533e+01 -8.73088837e+01 -7.81077271e+01 -6.08298645e+01 -4.83250389e+01 -6.33381615e+01 -6.84375687e+01 -6.31517906e+01 -7.02151871e+01 -8.87353058e+01 -1.12187859e+02 -1.06529869e+02 -7.26529770e+01 -6.07572098e+01 -7.16512909e+01 -9.90962601e+01 -9.05788879e+01 -6.94285583e+01 -7.24839401e+01 -9.16886215e+01 -1.00712257e+02 -8.60192642e+01 -5.33336868e+01 -3.85499077e+01 -4.81415825e+01 -7.93279343e+01 -1.00319519e+02 -9.39855423e+01 -7.97908936e+01 -8.39676666e+01 -1.01026115e+02 -9.77943039e+01 -7.41165466e+01 -6.16827621e+01 -8.57175217e+01 -1.19850807e+02 -1.25648895e+02 -8.90534897e+01 -5.79278870e+01 -5.62633934e+01 -8.32572937e+01 -9.01932678e+01 -8.27204742e+01 -9.74676132e+01 -1.32015869e+02 -1.50973969e+02 -1.23174721e+02 -6.92285843e+01 -4.03241272e+01 -5.08058929e+01 -8.20213242e+01 -1.16473297e+02 -1.40429688e+02 -1.33709976e+02 -1.26200607e+02 -1.26459114e+02 -1.19677147e+02 -8.41315689e+01 -5.26975403e+01 -7.35799866e+01 -1.32053131e+02 -1.56612930e+02 -1.33753494e+02 -7.57171249e+01 -4.67480927e+01 -6.27500343e+01 -8.55925446e+01 -9.16151123e+01 -9.22007904e+01 -1.15111427e+02 -1.63085129e+02 -1.61459335e+02 -1.14870087e+02 -6.25488052e+01 -6.25772629e+01 -9.71291046e+01 -1.25345039e+02 -1.25518814e+02 -1.11178947e+02 -8.85323486e+01 -7.75315094e+01 -1.07359367e+02 -1.22791397e+02 -1.02545998e+02 -7.51845016e+01 -7.09095917e+01 -8.75552292e+01 -8.88209991e+01 -6.65252914e+01 -6.62644577e+01 -8.57236557e+01 -1.10510277e+02 -1.19659584e+02 -9.18628159e+01 -8.07031708e+01 -8.94542923e+01 -1.16743385e+02 -9.61615829e+01 -2.39679985e+01 1.41985798e+01 -3.41331444e+01 -1.02562607e+02 -1.15012657e+02 -7.61309814e+01 -4.98484192e+01 -5.29452095e+01 -5.35045280e+01 -2.45547028e+01 1.41947794e+01 2.48238354e+01 6.86336756e+00 -4.87933655e+01 -8.53721390e+01 -6.36970177e+01 -4.82593689e+01 -5.67614899e+01 -8.99353790e+01 -6.31706734e+01 4.84258747e+00 -1.91824877e+00 -2.98289585e+01 -6.18349152e+01 -2.06961040e+01 5.90163765e+01 9.48894501e+01 5.76083870e+01 -2.57606640e+01 -7.13814545e+01 -5.66570892e+01 -6.69738617e+01 -8.28289108e+01 -7.51634369e+01 -1.49862022e+01 5.40253448e+01 4.94604034e+01 -7.06400681e+00 -1.05407394e+02 -1.38422882e+02 -1.02730888e+02 -3.93952408e+01 -3.99072558e-01 -9.39106274e+00 8.01609707e+00 2.84870586e+01 2.18989029e+01 -4.59681282e+01 -1.09759270e+02 -8.16883011e+01 1.30567331e+01 6.31805458e+01 7.84705114e+00 -8.81738892e+01 -1.19879814e+02 -7.50650177e+01 -2.19899998e+01 -4.52318115e+01 -9.07048187e+01 -7.65129318e+01 -2.37296715e+01 -3.50107288e+00 -4.87221107e+01 -1.23781700e+02 -1.36512650e+02 -1.05132149e+02 -5.75361862e+01 -5.73195686e+01 -7.78262100e+01 -8.62301254e+01 -6.87257690e+01 -9.08341064e+01 -1.27215385e+02 -1.29538773e+02 -1.16098083e+02 -7.37209854e+01 -5.44342041e+01 -7.42993469e+01 -6.97334137e+01 -7.05468903e+01 -3.47964935e+01 -6.63082733e+01 -1.10355331e+02 -1.28778305e+02 -1.06391212e+02 -9.82635593e+00 4.56996078e+01 4.25068893e+01 -7.17989883e+01 -1.25779846e+02 -1.40652832e+02 -9.27550354e+01 -7.29247284e+01 -9.72584152e+01 -8.85323410e+01 -5.65098572e+01 -3.42233124e+01 -7.23481445e+01 -1.01692879e+02 -3.85435104e+01 3.93443680e+01 2.97750587e+01 -1.60954514e+01 -4.53649330e+01 -1.68857059e+01 3.17982578e+01 -1.83828678e+01 -5.74197769e+01 -1.04429420e+02 -7.85423813e+01 -2.30760975e+01 1.12094069e+01 2.64053135e+01 -3.28768463e+01 -6.21297455e+01 -6.47900391e+01 -6.47197008e+00 9.87500095e+00 9.99962711e+00 2.15529728e+01 5.06951637e+01 6.90205841e+01 -8.03227806e+00 -5.49447250e+01 -5.54627075e+01 2.00927067e+01 2.38913631e+01 -9.41238022e+00 -5.56835403e+01 -9.14921646e+01 -7.40491333e+01 -7.00416260e+01 -1.18767099e+01 1.75930767e+01 4.36199608e+01 3.91740837e+01 2.23402100e+01 -1.08274622e+01 -6.79795456e+01 -1.00531563e+02 -8.35748749e+01 3.13390207e+00 1.90191135e+01 1.66289687e+00 -2.04945087e+01 -7.68341589e+00 -2.89724445e+01 -1.21338745e+02 -1.57603500e+02 -1.13046165e+02 -2.72925258e+00 2.24160690e+01 -1.65565300e+01 -7.87751465e+01 -1.00639534e+02 -6.27346230e+01 -5.75202293e+01 -3.25506363e+01 -8.56710968e+01 -1.07440224e+02 -1.17553635e+02 -6.96625137e+01 -4.78739738e+01 -8.60837250e+01 -1.31228104e+02 -9.02499313e+01 -3.07716656e+01 -4.84272995e+01 -8.79507065e+01 -8.14901199e+01 -3.93520279e+01 -4.36838379e+01 -1.15996086e+02 -1.39279022e+02 -1.19316696e+02 -4.44723663e+01 -5.04400215e+01 -7.07619095e+01 -9.74294281e+01 -7.98259201e+01 -4.00964737e+01 -5.46507416e+01 -6.41123734e+01 -1.24979271e+02 -1.43523773e+02 -1.34568344e+02 -9.17688828e+01 -6.54091873e+01 -8.65434799e+01 -1.18050911e+02 -1.03648216e+02 -4.29397507e+01 -2.61854725e+01 -2.43369522e+01 8.41560936e+00 6.49912186e+01 4.55072899e+01 -3.29040375e+01 -4.51964912e+01 2.38927618e-01 5.68856468e+01 -9.04574299e+00 -4.05774879e+01 -6.39095840e+01 -9.48544540e+01 -1.06665833e+02 -7.19145660e+01 3.66446114e+01 6.07873802e+01 -1.91361084e+01 -9.19311981e+01 -5.93643875e+01 4.02060547e+01 8.75608826e+01 3.09800682e+01 -2.32792835e+01 -1.06096210e+01 2.28346367e+01 6.89151382e+01 1.09957268e+02 1.74544250e+02 1.50352219e+02 8.08418427e+01 5.92726974e+01 9.43937073e+01 1.46827728e+02 6.36235809e+01 1.72940178e+01 -2.57792187e+01 -2.47473645e+00 -7.99197197e-01 5.28156509e+01 1.54099869e+02 1.84000458e+02 9.79124680e+01 -5.94860535e+01 -1.01817421e+02 2.77888813e+01 1.58411499e+02 1.68496445e+02 7.37617950e+01 1.06346779e+01 4.64466858e+01 1.23471359e+02 1.64665588e+02 1.16588234e+02 -5.97839451e+00 -3.07180767e+01 2.84083328e+01 1.12954216e+02 2.06219543e+02 1.98035889e+02 1.57475525e+02 4.21357880e+01 -7.54214096e+01 -1.15461319e+02 -4.39283409e+01 1.10214241e+02 1.86179886e+02 1.12962357e+02 1.09850187e+01 1.62685108e+01 1.41009018e+02 2.46400131e+02 1.96006256e+02 5.20161552e+01 -4.74218636e+01 -5.13314018e+01 3.72115173e+01 9.08171310e+01 1.50052521e+02 7.76764526e+01 4.97435036e+01 2.49064903e+01 6.90113373e+01 1.05842972e+02 4.37639999e+01 -1.52688770e+01 -9.90992737e+01 -1.10427376e+02 -5.93728180e+01 1.10271654e+01 1.34954147e+02 1.45368912e+02 7.04474411e+01 -9.13495636e+01 -1.63391510e+02 -9.01525040e+01 6.88693924e+01 1.59064621e+02 1.30754471e+02 6.23116531e+01 6.44865417e+01 1.04510513e+02 1.33094559e+02 1.38691025e+02 6.19213028e+01 6.57940769e+00 -5.28066025e+01 -4.91006126e+01 -1.92087059e+01 2.97061806e+01 8.78907166e+01 8.18255310e+01 1.93644390e+01 -4.22741203e+01 -4.68767548e+01 2.22286434e+01 9.81556549e+01 6.70979385e+01 -3.34129000e+00 -3.76465797e+01 2.70149765e+01 1.28319138e+02 1.26551704e+02 6.24202118e+01 -4.21671448e+01 -4.88476219e+01 1.91441345e+01 8.87340775e+01 1.43655228e+02 7.01566086e+01 3.65527802e+01 -8.30033302e+00 -1.57637739e+01 -2.24474106e+01 -3.75936623e+01 7.08910656e+00 -8.99886703e+00 -3.61988640e+01 -2.60049171e+01 3.00193329e+01 1.25428131e+02 1.69171371e+02 1.11071281e+02 -2.14919815e+01 -1.46611359e+02 -1.30201324e+02 -2.46852804e-02 1.36658646e+02 1.76318741e+02 8.21324615e+01 -2.63034782e+01 -5.43571892e+01 1.02605858e+01 1.01500198e+02 7.96609039e+01 1.73433533e+01 -5.30196877e+01 -6.48438339e+01 -3.08226814e+01 3.53143425e+01 1.03672470e+02 8.95724258e+01 1.66527863e+01 -8.00631866e+01 -9.02111740e+01 -1.53212414e+01 8.87335587e+01 6.89658279e+01 -1.78838749e+01 -7.93428268e+01 -4.69549217e+01 1.17704687e+01 3.65390320e+01 5.72246399e+01 1.92792263e+01 -3.56059837e+00 2.36985245e+01 4.18607903e+01 7.24152374e+01 2.52405682e+01 -1.14340410e+01 -6.54652634e+01 -1.02899673e+02 -6.36422806e+01 -1.85915356e+01 5.43627090e+01 8.27985535e+01 3.93148766e+01 -2.62970486e+01 -3.71047516e+01 4.66730728e+01 1.27755287e+02 1.22559906e+02 6.41655426e+01 -1.76974411e+01 -4.43200645e+01 -1.46173315e+01 2.80683613e+01 4.76044693e+01 -1.13462200e+01 -6.53554688e+01 -1.18722145e+02 -1.01721298e+02 -2.58300877e+01 -2.35283928e+01 -5.75243340e+01 -1.30165939e+02 -1.43041138e+02 -1.10681625e+02 -6.43232498e+01 3.47941589e+01 7.25653610e+01 5.33195152e+01 -2.56170483e+01 -6.17760735e+01 9.02580643e+00 7.92294769e+01 8.53793793e+01 -1.59773302e+01 -7.14694214e+01 -5.08960609e+01 3.71751595e+01 1.06783386e+02 1.13642570e+02 4.43511009e+01 -3.79164772e+01 -6.09435997e+01 -5.32026672e+01 -2.76541882e+01 2.77676821e+00 5.77499809e+01 5.99323616e+01 3.80391884e+01 1.44569921e+01 5.21799583e+01 1.23714188e+02 1.71029846e+02 1.03265121e+02 1.33233137e+01 -3.68187981e+01 2.12987690e+01 1.14581169e+02 1.30805618e+02 7.88449860e+01 -1.33499651e+01 -2.92211399e+01 3.01629658e+01 5.95154686e+01 6.89908981e+01 1.04799099e+01 8.40876341e-01 8.37141609e+00 3.28057747e+01 8.08516006e+01 7.65531311e+01 7.27979813e+01 -7.41017818e-01 -5.44770927e+01 -4.60173874e+01 -1.15091591e+01 6.89321594e+01 1.04001137e+02 1.02325172e+02 2.42978668e+01 -1.04676048e+02 -1.55647552e+02 -1.37524307e+02 2.58642750e+01 7.71717987e+01 1.53751266e+02 1.86323730e+02 -3.44904077e+03 -9.26673047e+03 383080544. 427584608. -1181876096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.00599859e+10 -368908384. 7.37914697e+03 1.88488135e+03 -4.15241974e+02 1.50659839e+03 2.45236743e+03 1.05044495e+03 -2.93400610e+03 -1.93834705e+03 -1.99512787e+02 -1.45040878e+02 -7.60080109e+01 -3.10642223e+01 -6.00371718e-01 2.53220577e+01 1.00755959e+02 1.04868614e+02 6.23886032e+01 5.43423796e+00 1.35272083e+01 7.68234711e+01 1.34331635e+02 1.49801666e+02 9.65981522e+01 2.15470963e+01 5.74955130e+00 6.94139099e+01 1.28765137e+02 1.28146912e+02 7.29373093e+01 7.55510254e+01 1.15146759e+02 1.24495705e+02 9.19953461e+01 4.51932716e+01 4.46122932e+01 3.33522835e+01 1.83077297e+01 2.00448380e+01 6.29812813e+01 1.40594650e+02 1.45688065e+02 9.54724808e+01 4.42734833e+01 4.68341904e+01 9.66589127e+01 1.48741547e+02 1.38592499e+02 7.06195908e+01 -8.64381313e+00 1.57427263e+00 7.61704941e+01 1.17990280e+02 1.26012016e+02 8.31114120e+01 6.67345963e+01 5.35176392e+01 4.87804375e+01 6.44727783e+01 9.04454422e+01 1.31986984e+02 1.15044724e+02 7.65341797e+01 6.06949234e+01 9.01367035e+01 1.41080826e+02 1.39363037e+02 1.14261101e+02 6.78287277e+01 5.25642433e+01 9.28431931e+01 1.50959473e+02 1.93165192e+02 1.66934143e+02 1.06418953e+02 8.61876755e+01 1.20239265e+02 1.44232925e+02 1.38795425e+02 8.60383682e+01 7.47380295e+01 9.00467682e+01 1.13754013e+02 1.14107887e+02 1.10873398e+02 1.26894180e+02 1.09201126e+02 7.78353119e+01 6.05819626e+01 9.36339951e+01 1.48095230e+02 1.57071335e+02 1.39041122e+02 1.01039925e+02 7.01965256e+01 6.85553284e+01 9.60716629e+01 1.23386360e+02 1.16527359e+02 6.84366302e+01 4.88586578e+01 8.37248306e+01 1.20433853e+02 1.21862663e+02 7.33143005e+01 5.25013809e+01 5.45320091e+01 6.17915192e+01 7.06673126e+01 8.98139648e+01 1.24811134e+02 1.20980179e+02 9.12212982e+01 6.91999283e+01 7.26346283e+01 1.03056595e+02 1.07802109e+02 8.98470459e+01 7.32096405e+01 5.59470215e+01 6.30433807e+01 9.30272903e+01 1.19972824e+02 1.25952080e+02 8.24241409e+01 6.59008102e+01 8.13261108e+01 9.49092407e+01 9.78689575e+01 7.95371475e+01 8.19920120e+01 8.22393188e+01 7.19573746e+01 6.65134048e+01 7.19600983e+01 1.04465012e+02 1.04539726e+02 8.29238434e+01 6.54600525e+01 6.81239014e+01 8.84625626e+01 8.59194717e+01 6.98584824e+01 5.95343933e+01 4.80219421e+01 6.19082947e+01 8.43720856e+01 1.05052422e+02 1.03301765e+02 8.29598312e+01 7.80003738e+01 8.62943573e+01 8.58879929e+01 8.33124161e+01 6.57572479e+01 5.91943932e+01 5.21702385e+01 5.40146370e+01 6.34966202e+01 7.72709885e+01 9.94449387e+01 1.04896271e+02 9.88676529e+01 8.47295685e+01 8.40373459e+01 9.89382629e+01 1.12726990e+02 1.05805687e+02 8.17145691e+01 6.65836029e+01 6.75560989e+01 8.85088730e+01 9.74158478e+01 9.72806015e+01 8.52018661e+01 8.42257690e+01 8.89046936e+01 8.87508698e+01 8.99483337e+01 9.14538727e+01 9.17134323e+01 8.20077591e+01 7.10364075e+01 7.12731857e+01 7.58218689e+01 8.41338120e+01 9.03902664e+01 9.21434631e+01 8.88181839e+01 8.80337372e+01 9.62276077e+01 1.03158630e+02 9.78224640e+01 8.51551132e+01 7.62054214e+01 7.66528473e+01 8.48280029e+01 8.74789734e+01 8.78099670e+01 8.04958115e+01 8.18212357e+01 8.63085403e+01 9.17648697e+01 9.44673462e+01 9.48627167e+01 9.84128571e+01 9.56043472e+01 8.97087326e+01 8.52968521e+01 8.55549927e+01 8.96979904e+01 8.92532120e+01 8.66074677e+01 8.31252213e+01 8.07447586e+01 8.26132202e+01 8.67861404e+01 9.00117493e+01 8.87978363e+01 8.60293198e+01 8.55582047e+01 8.62100449e+01 8.64334030e+01 8.63499146e+01 8.61017914e+01 8.61038284e+01 8.63181915e+01 8.64582367e+01 8.63937302e+01 8.57128143e+01 8.43895035e+01 8.35814972e+01 8.39740677e+01 8.49376602e+01 8.52844772e+01 8.51200943e+01 8.61758118e+01 8.80643082e+01 8.86593399e+01 8.81606979e+01 8.52968445e+01 8.45835800e+01 8.34991760e+01 8.41755447e+01 8.63576736e+01 8.75959930e+01 8.74055405e+01 8.48860397e+01 8.37874908e+01 8.50981827e+01 8.65702515e+01 8.64860535e+01 8.38576889e+01 8.28437042e+01 8.29329300e+01 8.46063766e+01 8.45245514e+01 8.55321808e+01 8.53765717e+01 8.71489105e+01 8.66094131e+01 8.66832581e+01 8.49434586e+01 8.63561096e+01 8.68348007e+01 8.80835419e+01 8.69858704e+01 8.77473679e+01 8.98294144e+01 8.92236633e+01 8.94597626e+01 9.16428223e+01 9.06454163e+01 8.85035782e+01 8.44006195e+01 9.03176804e+01 9.05036850e+01 8.93492126e+01 8.68756256e+01 8.85399628e+01 9.04196243e+01 9.04831772e+01 9.21735840e+01 9.04567795e+01 8.91675034e+01 8.68552017e+01 8.85334167e+01 8.77266159e+01 8.88773041e+01 8.89205780e+01 8.91495819e+01 8.95918503e+01 9.14640198e+01 9.20354004e+01 9.20255585e+01 8.60408325e+01 7.93994980e+01 7.51117249e+01 7.88937531e+01 8.45565948e+01 9.05980530e+01 8.82291260e+01 8.47975082e+01 8.12600708e+01 8.36899719e+01 8.89633789e+01 8.87667770e+01 8.51455002e+01 8.50962753e+01 8.97215042e+01 9.13021469e+01 8.86579819e+01 8.64007874e+01 8.66588135e+01 8.42843475e+01 8.23816071e+01 7.72610550e+01 7.56343613e+01 7.54908752e+01 8.28900452e+01 9.20398026e+01 1.02990173e+02 1.13225372e+02 1.07644760e+02 9.59549561e+01 8.48691711e+01 8.41891632e+01 8.02984390e+01 7.44246979e+01 8.66325836e+01 1.01015724e+02 1.00512917e+02 8.61893005e+01 7.60093231e+01 7.72312164e+01 7.93095627e+01 7.32360306e+01 7.23024216e+01 7.10885849e+01 7.73812332e+01 7.48473129e+01 7.45559235e+01 7.92915039e+01 8.51592255e+01 8.21597290e+01 6.83062973e+01 5.21099701e+01 5.14576187e+01 5.83478127e+01 7.39918747e+01 7.23355713e+01 6.76554337e+01 6.94146042e+01 7.03965988e+01 7.48166199e+01 5.85166473e+01 4.44151382e+01 4.45189133e+01 6.15192604e+01 7.71340332e+01 8.17076340e+01 7.36614456e+01 5.47867546e+01 3.70865326e+01 4.86935081e+01 7.78028793e+01 8.85919266e+01 7.90512543e+01 6.73512344e+01 6.33075485e+01 4.81351852e+01 3.57620583e+01 4.14615822e+01 5.34710579e+01 7.33369370e+01 7.49970398e+01 7.74738693e+01 6.08699875e+01 5.25655594e+01 5.29876518e+01 6.90682526e+01 7.85660248e+01 8.41349564e+01 7.97974167e+01 8.15936127e+01 8.54977341e+01 9.11641006e+01 8.67266312e+01 7.93155289e+01 6.98718414e+01 7.78196030e+01 8.26327515e+01 7.97971039e+01 7.05771255e+01 7.52347488e+01 8.44828415e+01 6.72535095e+01 4.91662788e+01 5.56318398e+01 8.19885712e+01 9.62031555e+01 7.96401672e+01 7.60821457e+01 6.75736542e+01 6.25540504e+01 4.82043800e+01 5.13542633e+01 4.59925842e+01 4.72072411e+01 4.47917747e+01 6.12337418e+01 6.81145554e+01 6.17400932e+01 6.25155411e+01 6.40587692e+01 6.95477524e+01 6.93485565e+01 7.27459183e+01 4.99851036e+01 3.01440392e+01 2.11725140e+01 4.68290138e+01 6.52125320e+01 7.35846558e+01 7.60474777e+01 7.71413803e+01 7.36639099e+01 6.75734940e+01 7.18828735e+01 8.81417694e+01 1.06401817e+02 1.08734978e+02 9.86698456e+01 7.88618546e+01 7.78605499e+01 8.34169617e+01 8.60116425e+01 7.83862610e+01 7.28293152e+01 1.02934616e+02 1.33109055e+02 1.37348312e+02 1.02596687e+02 6.96399689e+01 6.87608566e+01 8.74017334e+01 1.22957359e+02 2.27897583e+02 4.05610626e+02 6.47975220e+02 2.65897485e+03 3.56887158e+03 2.46699158e+02 -2.08974396e+02 6.45676611e+03 1.62303662e+04 -842406336. -2.92679066e+09 -3.45275264e+09 -452864768. -773293056. -5.49951642e+09 -238931136. -2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -2.46511590e+09 -162604928. -3.49388828e+04 -1.36611895e+04 -2.30558057e+03 -8.95491150e+02 4.01293262e+03 2.81534766e+03 6.18066650e+02 4.26478882e+02 2.01405273e+02 1.50710159e+02 1.02948112e+02 6.25735893e+01 6.70166092e+01 7.38146667e+01 7.95425034e+01 8.23353348e+01 1.01347374e+02 1.25759445e+02 9.59241562e+01 4.67011604e+01 3.75575638e+01 6.94583282e+01 1.02568611e+02 8.42232971e+01 7.94269028e+01 7.45450668e+01 8.58476562e+01 9.82475815e+01 1.04191605e+02 9.62381516e+01 7.08127060e+01 6.78721466e+01 6.03073654e+01 6.51697693e+01 3.08696537e+01 -2.74105525e+00 -4.44149828e+00 1.68432808e+01 3.89179001e+01 2.87249546e+01 1.42377234e+01 9.07164669e+00 5.75848043e-01 -8.06781578e+00 -1.14651031e+01 -2.20560246e+01 -2.07209492e+01 -1.42558327e+01 -4.29222727e+00 3.60049677e+00 -2.48240471e+00 -5.53404570e-01 -1.88342285e+00 -4.61494398e+00 -8.04895973e+00 -1.60463657e+01 -2.29233665e+01 -8.95156670e+00 2.57109547e+01 7.37570648e+01 9.55460434e+01 8.30959854e+01 5.65318108e+01 3.29399757e+01 5.17203827e+01 7.23910980e+01 6.50394363e+01 2.43303356e+01 -1.04448643e+01 -1.43769341e+01 -8.85248470e+00 -2.78613873e+01 -6.33695221e+01 -3.77359047e+01 1.11727591e+01 5.52363281e+01 4.85328598e+01 2.29719276e+01 2.34605236e+01 6.91776800e+00 1.19770498e+01 6.98964977e+00 2.00966129e+01 2.12669373e+01 4.07014732e+01 4.65809059e+01 4.82887878e+01 3.42805443e+01 3.31348419e+01 6.79532013e+01 1.06305344e+02 8.82871399e+01 5.64230690e+01 1.98327980e+01 3.58282967e+01 5.19463158e+01 7.82093887e+01 9.37984009e+01 5.95736542e+01 1.18315725e+01 2.75957823e-01 2.04992905e+01 6.49289322e+01 6.23658676e+01 5.68086052e+01 3.37354813e+01 1.88695107e+01 2.93580818e+01 2.35477352e+01 2.60894432e+01 1.08858242e+01 2.18599148e+01 2.18870335e+01 2.17772141e+01 4.25698700e+01 7.12887268e+01 7.04786301e+01 4.26718407e+01 3.21014452e+00 -4.78449821e+00 -1.95972328e+01 -1.22889500e+01 -1.96650372e+01 -2.05738220e+01 -2.56188717e+01 1.57433672e+01 5.86447639e+01 6.70452194e+01 3.86584167e+01 8.97418499e+00 -2.05602570e+01 -3.91605377e+01 -4.75442162e+01 -2.24600868e+01 -8.82653713e+00 -1.88014736e+01 -4.17882156e+00 7.65324736e+00 9.07066822e+00 -2.56309032e+00 -5.82951212e+00 -2.03886300e-01 4.00603104e+00 -1.07476330e+00 4.23221493e+00 1.22724781e+01 1.44301500e+01 1.90636120e+01 2.41626205e+01 2.40848083e+01 2.27423935e+01 8.73113346e+00 -2.53204608e+00 -7.21049833e+00 -5.73328209e+00 -3.47034645e+00 -1.19588299e+01 -2.25782986e+01 -1.36342192e+01 4.00335541e+01 7.87348328e+01 8.38393097e+01 6.58836823e+01 4.17780266e+01 3.44804459e+01 1.55346937e+01 6.08363867e+00 1.43069849e+01 1.61256390e+01 1.38982868e+01 1.24942713e+01 1.43088179e+01 5.76716566e+00 -4.00720482e+01 -7.79903946e+01 -1.02894371e+02 -9.69059448e+01 -5.20810928e+01 -1.20687933e+01 2.97040939e+01 1.73120594e+01 8.75275517e+00 -3.20771646e+00 -1.92611694e+00 -9.19092560e+00 -3.35337877e+00 -6.51527262e+00 -1.16742325e+01 -1.00935526e+01 -5.62898397e+00 -5.96770239e+00 -1.28016233e+01 -1.24493980e+01 1.15475025e+01 2.21465702e+01 2.16451511e+01 1.54042063e+01 4.89734554e+00 -2.76677017e+01 -7.67891617e+01 -9.88759918e+01 -1.00215424e+02 -8.77721024e+01 -1.00593246e+02 -6.80909271e+01 -2.31795540e+01 2.40283546e+01 2.62876759e+01 1.76235085e+01 5.26581573e+00 3.64281297e+00 6.46793032e+00 2.23349133e+01 1.75176468e+01 1.13364048e+01 -3.08690929e+00 -1.53914452e+00 5.35512686e+00 3.77321968e+01 7.51376266e+01 5.84731979e+01 2.97151337e+01 -7.87002993e+00 -2.96288338e+01 -5.19025116e+01 -8.93563766e+01 -1.14507545e+02 -1.00460747e+02 -7.88186722e+01 -2.44093971e+01 -3.86702499e+01 -5.06212730e+01 -6.74245834e+01 -6.44305649e+01 -4.97047844e+01 -5.71968193e+01 -6.11319733e+01 -6.13402557e+01 -4.68820686e+01 -3.13975945e+01 -3.17619286e+01 -6.11672401e+01 -1.02240685e+02 -1.41126831e+02 -1.59853302e+02 -8.95518341e+01 -1.73486328e+01 2.66413860e+01 3.73110962e+00 -3.68942604e+01 -3.33763313e+01 -4.75138245e+01 -3.50169830e+01 -3.59177170e+01 -2.36453037e+01 -2.31998386e+01 -1.90708904e+01 -2.90977974e+01 -2.92251492e+01 3.80515027e+00 4.86339417e+01 5.39085999e+01 2.48544044e+01 -2.99875998e+00 -1.89341240e+01 -3.83683395e+01 -4.47712746e+01 -3.32582130e+01 -3.21166496e+01 -5.31158257e+01 -5.99384003e+01 -4.19112129e+01 -1.72825623e+01 -5.70827627e+00 -7.73538399e+00 -1.30111332e+01 -1.83699780e+01 -1.77153225e+01 -2.70432758e+01 -2.48226624e+01 -1.80577087e+01 -1.97857690e+00 4.28357172e+00 -3.78580117e+00 -4.06508942e+01 -8.96768799e+01 -8.35036469e+01 -4.94424744e+01 -1.09121742e+01 -2.88091145e+01 -3.53513031e+01 -3.33730431e+01 -2.92222347e+01 -3.70508842e+01 -4.70738487e+01 -7.54126892e+01 -9.27324982e+01 -8.96567612e+01 -4.67783432e+01 -1.08396368e+01 -1.06664820e+01 -2.15386791e+01 -6.02767706e+00 2.85165520e+01 3.15252953e+01 1.96936951e+01 -1.02818527e+01 -4.14046526e+00 -7.23398972e+00 -1.03440409e+01 -2.14067707e+01 -2.52374001e+01 -2.35031090e+01 -1.42313623e+01 -1.88390446e+01 -2.24734020e+01 -2.09912319e+01 -1.91127968e+01 -2.40403976e+01 -3.18476105e+01 -5.88762894e+01 -8.59636765e+01 -8.39628448e+01 -6.58910828e+01 -4.81338882e+01 -5.54185715e+01 -4.76724930e+01 -2.77478294e+01 -2.62402515e+01 -6.61647263e+01 -1.03819946e+02 -1.06377350e+02 -7.36518860e+01 -5.23381042e+01 -5.57891235e+01 -5.70430756e+01 -5.73539047e+01 -5.34943962e+01 -7.94628830e+01 -1.15757599e+02 -1.21768585e+02 -9.70526657e+01 -5.61696930e+01 -6.26390343e+01 -6.12430496e+01 -6.16882248e+01 -5.41750526e+01 -5.75612793e+01 -6.74024658e+01 -8.11093674e+01 -8.58051453e+01 -7.26551208e+01 -6.54792099e+01 -6.52125778e+01 -1.00887573e+02 -1.42698120e+02 -1.47776047e+02 -1.12516159e+02 -7.20455627e+01 -6.33971634e+01 -5.70050354e+01 -5.73620949e+01 -6.46378098e+01 -1.06464233e+02 -1.36371643e+02 -1.72259262e+02 -1.78956604e+02 -1.41992859e+02 -1.08094902e+02 -6.62842026e+01 -9.59507980e+01 -1.16899849e+02 -9.12008820e+01 -3.00723515e+01 2.86963868e+00 -2.26870613e+01 -6.02542686e+01 -5.86155701e+01 -5.71325378e+01 -5.08285561e+01 -5.00630379e+01 -4.26463394e+01 -3.85750732e+01 -3.30802383e+01 -2.90156155e+01 -3.38556786e+01 -3.73100739e+01 -3.98991928e+01 -3.87996254e+01 -4.17808723e+01 -5.56228600e+01 -8.40553131e+01 -7.91315155e+01 -5.93745651e+01 -2.63082581e+01 -5.67589569e+01 -9.11799164e+01 -6.60421448e+01 -3.99918365e+00 -3.01748133e+00 -7.11438293e+01 -1.17983978e+02 -9.49377518e+01 -6.36525002e+01 -8.09433365e+01 -1.14090820e+02 -1.17517029e+02 -1.02695442e+02 -7.64763489e+01 -7.87984924e+01 -8.29769211e+01 -7.36125488e+01 -7.35715714e+01 -4.95563545e+01 -3.40520248e+01 -6.54770126e+01 -1.12287720e+02 -1.40672913e+02 -1.16734329e+02 -9.42622528e+01 -1.15653465e+02 -1.30343384e+02 -1.38723846e+02 -1.14386147e+02 -8.84314880e+01 -8.70166626e+01 -9.19434128e+01 -1.00025490e+02 -9.11827316e+01 -1.03914398e+02 -1.25523064e+02 -1.30009155e+02 -1.22400482e+02 -9.46193771e+01 -7.89876251e+01 -7.06626358e+01 -7.07507172e+01 -7.82452011e+01 -3.92813530e+01 -9.54564095e-01 -8.70940971e+00 -5.94068146e+01 -9.72103806e+01 -8.59770203e+01 -6.81724091e+01 -8.43459396e+01 -1.15201370e+02 -1.15553955e+02 -9.66602631e+01 -7.17940521e+01 -6.67594910e+01 -6.62445450e+01 -6.68334122e+01 -7.29922104e+01 -7.38992538e+01 -7.92871628e+01 -9.08754654e+01 -9.64909515e+01 -9.19971008e+01 -7.74253082e+01 -7.03169403e+01 -6.22693405e+01 -6.54392395e+01 -4.66236725e+01 -2.99954910e+01 -4.67601433e+01 -9.35371017e+01 -1.17947891e+02 -9.55803299e+01 -6.55363388e+01 -5.22824249e+01 -4.49503784e+01 -4.31058578e+01 -4.64126930e+01 -5.44487419e+01 -5.22764893e+01 -5.83100700e+01 -5.63453560e+01 -5.87777481e+01 -5.32443047e+01 -5.15886803e+01 -4.98861275e+01 -6.15549049e+01 -6.67531738e+01 -6.37220154e+01 -5.23636017e+01 -5.00947571e+01 -6.11777802e+01 -7.41380386e+01 -7.82447739e+01 -9.29846954e+01 -1.08785194e+02 -1.12595474e+02 -9.96760712e+01 -9.49317551e+01 -1.28321014e+02 -1.47790314e+02 -1.31918488e+02 -1.05459297e+02 -1.11458046e+02 -1.33022308e+02 -1.35221329e+02 -1.15286736e+02 -9.92853622e+01 -9.79927368e+01 -9.74986649e+01 -1.03171806e+02 -1.05488388e+02 -1.04237808e+02 -9.64132233e+01 -1.03025459e+02 -1.20238976e+02 -1.28437134e+02 -1.17760422e+02 -1.00066315e+02 -1.01273155e+02 -1.12560425e+02 -9.85619507e+01 -7.58243103e+01 -6.35242348e+01 -7.32194138e+01 -8.21824951e+01 -7.63338318e+01 -7.63967438e+01 -7.95525055e+01 -8.24415817e+01 -8.09396973e+01 -8.22280807e+01 -8.64302139e+01 -8.36252289e+01 -8.07944412e+01 -7.45128098e+01 -7.72827377e+01 -8.05209351e+01 -8.10753784e+01 -9.15636139e+01 -9.88687820e+01 -9.92018738e+01 -8.52464600e+01 -7.29834976e+01 -7.02177124e+01 -7.15911407e+01 -6.43949585e+01 -5.44156189e+01 -5.37740669e+01 -6.05785408e+01 -7.07438354e+01 -7.25927124e+01 -7.46189728e+01 -8.94273453e+01 -1.03404602e+02 -1.05686363e+02 -9.57764206e+01 -8.75656204e+01 -8.83314285e+01 -8.57105179e+01 -8.18273010e+01 -8.41467514e+01 -7.90722504e+01 -7.09785919e+01 -7.37892075e+01 -8.56235886e+01 -9.49872131e+01 -9.07693558e+01 -9.18714600e+01 -1.06233902e+02 -1.14553444e+02 -1.11285912e+02 -9.47344360e+01 -9.04290237e+01 -9.54080963e+01 -9.62841187e+01 -9.05387878e+01 -8.07040253e+01 -8.24471741e+01 -8.82548523e+01 -8.98036499e+01 -8.68230362e+01 -8.04154053e+01 -7.72301941e+01 -7.58283768e+01 -7.59679031e+01 -7.79749527e+01 -7.86814728e+01 -7.79701080e+01 -8.32080154e+01 -8.72799454e+01 -8.99685440e+01 -8.55911255e+01 -8.23255005e+01 -8.31432343e+01 -8.70488052e+01 -8.54142838e+01 -6.68476791e+01 -5.17609749e+01 -4.44363136e+01 1.90807831e+02 2.79120483e+02 -2.35222641e+02 -2.84354767e+02 -2.49195480e+02 -4.23894714e+02 -1.60091812e+02 2.87934814e+02 1.98967957e+03 -1510672640. -9642282. 2.78443069e+10 2.78443069e+10 -2.51446886e+09 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. 569779712. 179301872. -134445168. -95973960. -172146704. -215503696. -7.76854370e+02 -3.08276306e+02 -3.67273254e+01 -7.45573883e+01 -8.70114365e+01 -1.28222549e+02 -1.21041565e+02 -1.04388359e+02 -7.66985092e+01 -7.15185699e+01 -8.15755997e+01 -8.67098999e+01 -1.12566574e+02 -1.32084885e+02 -1.06181000e+02 -7.04108124e+01 -5.49287643e+01 -4.93779259e+01 -5.21669464e+01 -4.90609131e+01 -4.11246567e+01 -4.06311493e+01 -4.67557640e+01 -5.18698921e+01 -4.41378021e+01 -2.81615582e+01 -2.44236050e+01 -3.62923622e+01 -5.08806229e+01 -5.93871918e+01 -5.95108223e+01 -6.42634506e+01 -7.20035629e+01 -7.59618073e+01 -6.46001511e+01 -3.42519722e+01 -1.87653313e+01 -2.55814056e+01 -4.65973701e+01 -6.12929840e+01 -5.95734253e+01 -5.42481842e+01 -4.37498627e+01 -4.96448898e+01 -4.63429756e+01 -4.17277336e+01 -4.53845253e+01 -6.60701523e+01 -9.07427750e+01 -8.83804550e+01 -5.19249382e+01 -3.38350525e+01 -4.11084251e+01 -6.22973328e+01 -5.92082481e+01 -4.12822609e+01 -4.08995590e+01 -6.01278038e+01 -8.24301605e+01 -7.81258545e+01 -4.43107834e+01 -2.10682812e+01 -2.74937820e+01 -4.88589935e+01 -5.34958801e+01 -4.62112617e+01 -4.89770699e+01 -6.57759171e+01 -8.53146591e+01 -7.59109421e+01 -6.38124886e+01 -6.74844208e+01 -8.05996094e+01 -8.57439194e+01 -7.70472565e+01 -6.28421021e+01 -4.72792244e+01 -3.93686256e+01 -4.90053787e+01 -6.09778862e+01 -6.27995224e+01 -7.69122162e+01 -1.01512314e+02 -1.10916733e+02 -8.37178497e+01 -3.36591873e+01 -1.05334978e+01 -2.45203915e+01 -6.56357422e+01 -1.10151527e+02 -1.26621445e+02 -1.15390312e+02 -1.03785088e+02 -1.11024338e+02 -9.84041138e+01 -6.07202492e+01 -2.91258793e+01 -4.18153534e+01 -7.03457718e+01 -8.28033981e+01 -7.15623550e+01 -4.23987274e+01 -3.61699905e+01 -5.01517067e+01 -7.01697006e+01 -6.60770798e+01 -6.15339012e+01 -8.08598557e+01 -1.22297928e+02 -1.32566116e+02 -1.00647713e+02 -6.13271599e+01 -6.05953789e+01 -9.06343613e+01 -1.15628555e+02 -1.14566574e+02 -8.64032745e+01 -5.86328239e+01 -4.88404388e+01 -6.35515633e+01 -6.31693344e+01 -3.97714806e+01 -3.25644264e+01 -5.86719856e+01 -9.11490479e+01 -9.27183685e+01 -6.01192741e+01 -4.09741707e+01 -6.24014778e+01 -8.01987457e+01 -8.99370880e+01 -7.27009735e+01 -7.91720886e+01 -1.10423271e+02 -1.19994774e+02 -8.44748764e+01 -8.82548332e+00 3.00416012e+01 -1.62462687e+00 -4.98782120e+01 -6.97142410e+01 -5.57414551e+01 -3.94440155e+01 -4.23767776e+01 -4.06713066e+01 -1.72114773e+01 1.45237694e+01 2.30756321e+01 -2.59478416e+01 -9.82732620e+01 -1.29611176e+02 -7.64003143e+01 -2.89741364e+01 -3.30964432e+01 -5.45657234e+01 -3.14313984e+01 2.60925350e+01 1.94050102e+01 -4.04218864e+01 -9.37189255e+01 -5.36947403e+01 3.81996498e+01 9.04421921e+01 5.33549500e+01 -1.13730097e+01 -4.90482941e+01 -4.55008087e+01 -5.74489326e+01 -7.10751419e+01 -5.59405556e+01 -6.68506479e+00 5.47019997e+01 2.48729115e+01 -2.39059143e+01 -8.30679779e+01 -7.04376526e+01 -4.39505348e+01 -6.96058941e+00 5.23258924e+00 9.71779060e+00 2.08626881e+01 5.48268280e+01 3.36542053e+01 -2.30062904e+01 -8.98109970e+01 -6.42331848e+01 2.79802370e+00 5.11024895e+01 2.87650337e+01 -1.87953625e+01 -4.82195930e+01 -4.35306015e+01 -5.95280991e+01 -1.12546295e+02 -1.43195847e+02 -9.18882828e+01 -1.35555601e+00 2.15639534e+01 -1.29639845e+01 -8.59161911e+01 -1.00815674e+02 -9.19215546e+01 -6.58408051e+01 -5.02948112e+01 -4.63254852e+01 -2.38893127e+01 5.34169960e+00 -2.38716316e+01 -6.88207550e+01 -9.26157303e+01 -8.71370316e+01 -5.44548225e+01 -4.31798439e+01 -5.01984863e+01 -5.11028481e+01 -4.89606895e+01 -1.85518017e+01 -4.89755058e+01 -9.23490143e+01 -1.21306076e+02 -1.19671974e+02 -4.92642212e+01 -1.14374323e+01 -3.11336021e+01 -1.02883629e+02 -1.14404640e+02 -6.67206955e+01 -1.63722076e+01 -2.53190422e+01 -6.77031097e+01 -6.15549393e+01 -2.39645653e+01 -5.09054756e+00 -5.52372856e+01 -9.01174698e+01 -6.65791245e+01 -4.16524391e+01 -6.76963196e+01 -8.23402634e+01 -5.28821373e+01 -2.60336056e+01 -5.55223608e+00 -3.82967377e+01 -1.22387180e+01 6.30664587e-01 1.28517838e+01 2.96795483e+01 5.28801689e+01 6.15059700e+01 -1.62544880e+01 -4.76049995e+01 -5.07682953e+01 7.42694378e+00 -8.02556324e+00 -1.74256687e+01 -1.99809387e-01 4.03536873e+01 5.38615913e+01 -1.66883869e+01 -6.91698456e+01 -7.62790833e+01 -7.34585810e+00 3.70016003e+00 -1.00526857e+01 -3.82174530e+01 -3.07145500e+01 3.00305653e+01 1.42102852e+01 -2.26441765e+01 -9.84034882e+01 -1.22264351e+02 -9.72882843e+01 -4.04093513e+01 5.27391255e-01 -3.58658180e+01 -8.69244537e+01 -1.02965103e+02 -7.22780609e+01 -1.09509392e+02 -1.15870689e+02 -7.59077606e+01 -6.80658281e-01 2.09221959e+00 -8.52863007e+01 -1.20108459e+02 -8.06903610e+01 -9.02426434e+00 -2.49261932e+01 -6.06668015e+01 -7.00967407e+01 -5.17805061e+01 -1.50630198e+01 -1.52929296e+01 1.02527499e+00 -4.77749977e+01 -7.84397812e+01 -8.86281357e+01 -4.39644890e+01 -2.35868664e+01 -5.26056824e+01 -9.01425705e+01 -9.45129242e+01 -1.04686554e+02 -1.74631516e+02 -2.17516068e+02 -2.15549408e+02 -1.85145401e+02 -1.78385315e+02 -2.16292877e+02 -2.26055023e+02 -1.94561600e+02 -1.13039970e+02 -7.77918243e+01 -7.07545624e+01 -8.93362656e+01 -6.92704544e+01 -1.56699142e+01 2.67841969e+01 3.26847115e+01 -3.18700008e+01 -6.05165291e+01 -6.89799118e+01 -4.81258659e+01 -6.59733582e+01 -9.45814285e+01 -1.20560402e+02 -1.06946144e+02 -1.11874496e+02 -1.52144257e+02 -1.87660141e+02 -1.67264328e+02 -1.11830780e+02 -1.05552956e+02 -1.00656532e+02 -4.02431526e+01 1.74278412e+01 5.18267174e+01 -1.23014479e+01 -2.22893314e+01 -4.60944214e+01 -8.46375427e+01 -9.13803940e+01 -4.80345726e+01 3.58316803e+01 6.16180725e+01 -2.06283741e+01 -8.00471115e+01 -7.60045700e+01 -1.64430122e+01 2.43702583e+01 -1.97801895e+01 -7.81268997e+01 -1.25906807e+02 -1.14557060e+02 -5.63512115e+01 -1.44599075e+01 4.34830132e+01 4.25405884e+01 3.50847549e+01 5.18978386e+01 6.45924606e+01 7.74520721e+01 -1.53387499e+01 -2.68482590e+01 -3.10903740e+01 -1.67083378e+01 -3.97018266e+00 4.44462128e+01 1.66111496e+02 1.89241653e+02 1.00703812e+02 -5.81248322e+01 -1.31113861e+02 -3.82270851e+01 8.78337860e+01 1.00870277e+02 -3.83625145e+01 -1.82527832e+02 -1.50837326e+02 -1.49260902e+01 6.77638016e+01 5.99232864e+01 -2.54702892e+01 -1.28028345e+01 3.28584671e+01 7.88435669e+01 8.54264145e+01 7.48188543e+00 -7.14681685e-01 3.47793579e+01 8.16623459e+01 7.92077179e+01 3.03736515e+01 4.90269508e+01 5.99856949e+01 -1.21576157e+01 -1.13541626e+02 -1.06511292e+02 5.56644707e+01 1.64875870e+02 1.26206650e+02 -9.67012882e+00 -7.19229660e+01 -4.93875656e+01 3.77390938e+01 7.93831558e+01 9.54037857e+01 1.84727898e+01 1.14505730e+01 1.82750340e+01 5.72080078e+01 7.92706299e+01 2.75413132e+01 -2.32986107e+01 -9.51775818e+01 -9.39251099e+01 -5.85312920e+01 1.19528084e+01 1.08859016e+02 1.48161865e+02 6.99240723e+01 -7.84764175e+01 -1.61425125e+02 -9.11195679e+01 7.97319565e+01 1.31028183e+02 9.03176212e+00 -1.60883957e+02 -1.64536423e+02 -2.27972622e+01 5.70559731e+01 5.46119537e+01 -2.39215031e+01 -3.08220387e+01 9.24817848e+00 7.45638428e+01 1.34895172e+02 1.34948166e+02 1.66303040e+02 1.49776871e+02 8.49580612e+01 -1.74053955e+01 -5.28177986e+01 2.74329052e+01 1.00367790e+02 7.88021851e+01 -3.25229607e+01 -1.22014488e+02 -9.23599243e+01 1.83238163e+01 4.79048691e+01 7.24761152e+00 -7.57502747e+01 -5.24814949e+01 1.94474697e+01 8.70764160e+01 1.39703674e+02 8.46964264e+01 7.90507202e+01 4.47392044e+01 5.03759575e+01 7.00380630e+01 9.05235672e+01 1.40514053e+02 9.08554611e+01 2.13435535e+01 -4.84818840e+01 -1.33287420e+01 9.31052475e+01 1.60320908e+02 1.00854050e+02 -1.40300856e+01 -7.86700668e+01 -6.90455856e+01 8.24514580e+00 3.27847939e+01 4.55144157e+01 7.59091091e+00 3.06678982e+01 7.54869461e+01 1.33020432e+02 1.88908295e+02 1.63605316e+02 6.96668396e+01 -6.50729895e+00 -1.67105274e+01 2.11709042e+01 6.00965691e+01 1.20073341e+02 1.48351120e+02 6.14481087e+01 -6.26814461e+01 -1.18854263e+02 -3.14308910e+01 8.60673981e+01 9.73193436e+01 -1.76859035e+01 -1.46552292e+02 -1.31912537e+02 7.09595585e+00 1.50290527e+02 2.05891678e+02 1.21146858e+02 4.29625931e+01 3.41335182e+01 7.23484421e+01 1.06689789e+02 5.67352180e+01 5.85566788e+01 3.34468956e+01 6.30358505e+00 -9.43549538e+00 -4.53729677e+00 6.18839722e+01 4.83255615e+01 -2.45404034e+01 -1.20258057e+02 -1.03816513e+02 3.92640991e+01 1.43635666e+02 1.12204033e+02 -9.64770508e+00 -9.44351501e+01 -9.84501953e+01 -8.33539486e-01 9.80809784e+01 1.40712204e+02 6.67323074e+01 1.93576508e+01 -2.25724106e+01 -2.89006634e+01 -1.41926460e+01 -1.99983768e+01 -1.94641228e+01 -8.66775436e+01 -1.21854088e+02 -1.12764862e+02 -6.45698013e+01 3.16412086e+01 6.29520798e+01 1.62808266e+01 -7.48747177e+01 -1.00680817e+02 -4.66804466e+01 3.83457756e+01 3.70514755e+01 -2.25010509e+01 -1.02401703e+02 -1.15478386e+02 -3.54752808e+01 5.52450371e+01 9.44896469e+01 1.74551506e+01 -5.76833878e+01 -5.71276550e+01 1.07192383e+01 6.52292175e+01 7.25117493e+01 6.21046867e+01 4.01892662e+01 -1.60138454e+01 -2.95763435e+01 2.21818256e+01 1.28204575e+02 1.64801910e+02 9.68388977e+01 1.26670980e+01 -5.36132927e+01 -1.05543003e+01 6.16659508e+01 1.08683167e+02 9.18054352e+01 3.33821869e+01 3.12012711e+01 7.10547256e+01 1.21175606e+02 1.33435593e+02 5.78820877e+01 9.00754356e+00 2.61005554e+01 7.79276886e+01 1.39567139e+02 1.25820618e+02 1.20209412e+02 9.71565323e+01 5.70363770e+01 3.28294907e+01 1.99754086e+01 8.56644135e+01 1.24729630e+02 9.76279602e+01 3.77813148e+01 -1.16254234e+01 3.31850243e+01 9.27843323e+01 1.29215500e+02 6.29369583e+01 -5.45370750e+01 -1.17937408e+02 -4.76773338e+01 9.70019531e+01 1.82241760e+02 1.34841949e+02 5.18923569e+01 1.75913239e+01 7.91109085e+00 -3.04152274e+00 -5.05916176e+01 4.76360512e+01 -7.44389877e+01 -1.88387161e+02 -2.34830298e+03 -3.57317749e+03 8.98205811e+02 -1.20042084e+02 6.23405322e+03 2.10859531e+04 -1181876096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.00599859e+10 -368908384. 229960080. -631162048. 733718848. -255099600. -957214848. -465375296. -1.80225840e+04 -8.50500293e+03 -2.39819141e+03 -4.15225586e+02 -2.86547333e+02 1.41915125e+03 2.05167198e+01 -1.25471729e+03 1.81555191e+02 1.26996126e+01 -1.73604950e+02 -1.76769913e+02 -1.05085159e+02 -1.16555222e+02 -7.05642090e+01 -1.24706306e+01 3.60129395e+01 4.12365265e+01 2.37235947e+01 5.52690315e+01 6.25456734e+01 1.43853922e+01 -1.98256664e+01 1.90992146e+01 1.14636124e+02 1.66206558e+02 1.04743484e+02 3.01355457e+01 -2.05115299e+01 7.12538958e+00 9.06883087e+01 1.60477280e+02 1.92328430e+02 1.26605377e+02 7.55862503e+01 6.70863037e+01 1.11496727e+02 1.44920929e+02 1.18338242e+02 1.14138924e+02 7.86165085e+01 4.97708969e+01 3.39370995e+01 6.22876358e+01 1.44818298e+02 1.49987183e+02 8.50530701e+01 4.35668039e+00 -1.38496389e+01 5.24546585e+01 1.13012207e+02 1.07673683e+02 5.82854309e+01 3.88897247e+01 8.90787354e+01 1.53644302e+02 1.73109070e+02 1.39675919e+02 6.72565613e+01 1.68450451e+01 1.80920620e+01 6.23010330e+01 1.22376183e+02 1.63632401e+02 1.84177124e+02 1.64393555e+02 1.24125168e+02 8.89295731e+01 7.16916428e+01 8.83271332e+01 7.78039932e+01 3.58113899e+01 -3.87304449e+00 1.76784790e+00 5.29800301e+01 9.36424866e+01 8.04053802e+01 5.76944122e+01 2.25132618e+01 6.12553644e+00 2.53837147e+01 7.25133438e+01 1.01192902e+02 7.42674103e+01 3.96474228e+01 4.90150604e+01 6.84918823e+01 7.67360992e+01 5.99211502e+01 7.11587372e+01 6.85480881e+01 4.87465858e+01 3.62871208e+01 5.16499481e+01 1.05545372e+02 1.10797119e+02 6.12560844e+01 2.45197010e+00 -2.52804737e+01 1.40326519e+01 5.87020264e+01 8.09866028e+01 7.20281067e+01 5.38594284e+01 5.14643936e+01 6.13073006e+01 8.63664246e+01 1.00138115e+02 7.53155289e+01 3.09912815e+01 1.99056244e+01 3.81220741e+01 5.46575432e+01 5.56814423e+01 6.87879868e+01 6.72659683e+01 3.48690834e+01 -1.06423211e+00 2.75515771e+00 5.21742325e+01 7.52522507e+01 4.62477112e+01 7.66601658e+00 7.90617824e-01 3.69867134e+01 7.43840790e+01 8.24529724e+01 7.16567688e+01 4.11005211e+01 2.05722866e+01 2.80452957e+01 5.74949188e+01 8.06544418e+01 6.22555428e+01 3.19211044e+01 2.08467922e+01 2.92275581e+01 4.36082687e+01 5.47256279e+01 7.36695862e+01 8.01008530e+01 7.11603317e+01 5.77553558e+01 5.66876068e+01 7.39502792e+01 8.15926743e+01 6.21633644e+01 3.08672009e+01 8.92111301e+00 2.10887089e+01 5.20500565e+01 7.45951233e+01 7.29443283e+01 5.47042274e+01 4.89431992e+01 5.44867706e+01 5.75887070e+01 6.72996445e+01 6.32862015e+01 6.25184669e+01 5.34818878e+01 4.00915031e+01 3.16064377e+01 2.85807190e+01 4.51684799e+01 5.41876144e+01 4.58426208e+01 3.57152672e+01 4.01562004e+01 6.12350197e+01 7.18610458e+01 6.50862961e+01 5.54442253e+01 4.86287994e+01 4.99073944e+01 5.37933578e+01 5.77501945e+01 6.00100327e+01 5.09293556e+01 5.22978210e+01 5.66232719e+01 6.65517349e+01 7.56397400e+01 8.06367188e+01 8.45623322e+01 7.47057877e+01 6.18873100e+01 5.46240349e+01 5.36654205e+01 6.11613312e+01 6.09917336e+01 5.50617943e+01 4.65587654e+01 4.30284615e+01 5.27713318e+01 6.47285461e+01 7.02457275e+01 6.68882294e+01 6.17615318e+01 5.94762230e+01 5.99426193e+01 6.17286491e+01 6.38464508e+01 6.18184433e+01 5.82685204e+01 5.63563728e+01 5.80730858e+01 5.86655540e+01 5.93611450e+01 6.00529366e+01 6.00543137e+01 5.87380447e+01 5.78546410e+01 5.77440948e+01 5.77903824e+01 5.72720451e+01 5.68940277e+01 5.69082642e+01 5.72637367e+01 5.74354744e+01 5.72597160e+01 5.64303207e+01 5.58993874e+01 5.65217628e+01 5.80070000e+01 5.88634758e+01 5.73628464e+01 5.61627655e+01 5.63453026e+01 5.68875465e+01 5.67025604e+01 5.71417503e+01 5.71999855e+01 5.71550827e+01 5.65116959e+01 5.65950203e+01 5.77527313e+01 5.90031586e+01 6.07867661e+01 6.05274048e+01 5.95017891e+01 5.75191078e+01 5.78284569e+01 5.90461922e+01 5.89476013e+01 5.78188019e+01 5.43699913e+01 5.15612373e+01 5.15279198e+01 5.23285294e+01 5.63642197e+01 5.59425697e+01 5.66343460e+01 5.66481972e+01 5.91771660e+01 5.89651985e+01 5.82194557e+01 5.72746964e+01 6.01891708e+01 6.00959015e+01 5.97479134e+01 5.90242538e+01 6.11193199e+01 6.35670242e+01 6.33231163e+01 6.40006638e+01 6.13151169e+01 6.05668907e+01 5.82454109e+01 5.86522942e+01 5.89116440e+01 6.21212044e+01 6.19633789e+01 6.15463066e+01 5.62981606e+01 5.70608749e+01 5.90740929e+01 6.01978149e+01 5.71452065e+01 5.58014526e+01 5.78751106e+01 6.14507446e+01 5.78922768e+01 5.76753159e+01 5.87134399e+01 6.08057518e+01 5.70546684e+01 5.50929871e+01 5.98485832e+01 6.04003220e+01 5.36463089e+01 4.79457741e+01 4.83365250e+01 4.72409859e+01 4.51100731e+01 4.80137825e+01 4.68415337e+01 4.47831039e+01 4.34863548e+01 4.97443962e+01 5.27546921e+01 5.00036469e+01 5.27550316e+01 5.70643883e+01 5.91213150e+01 5.63400040e+01 6.28930473e+01 7.29505920e+01 7.22309799e+01 6.49688644e+01 5.66930275e+01 5.30981522e+01 5.58105583e+01 5.54925652e+01 6.09977913e+01 5.62090988e+01 5.24726105e+01 4.86208458e+01 4.53645935e+01 3.80355949e+01 3.85264740e+01 4.73964005e+01 5.34432373e+01 5.14351082e+01 4.94064865e+01 5.10760803e+01 5.07381058e+01 4.51579590e+01 4.41498718e+01 4.06497040e+01 4.04869995e+01 4.55844650e+01 5.17892723e+01 5.79544678e+01 5.39849243e+01 5.02034492e+01 4.35351982e+01 4.14158669e+01 5.23296204e+01 6.05377960e+01 5.73585739e+01 4.59592514e+01 4.29691505e+01 4.31175003e+01 5.21057320e+01 5.19355621e+01 5.24269409e+01 5.15908012e+01 5.65592651e+01 7.31457825e+01 6.43206100e+01 6.44980392e+01 5.31572342e+01 6.14372368e+01 5.93197365e+01 5.40962791e+01 4.35417252e+01 4.94807968e+01 6.18220444e+01 6.60305252e+01 5.47133789e+01 4.76173859e+01 5.06884232e+01 6.68388214e+01 8.67351303e+01 8.53328781e+01 6.77966995e+01 3.98215103e+01 5.17776070e+01 7.14628983e+01 8.45146255e+01 7.07086258e+01 5.14873085e+01 5.05951767e+01 6.51971512e+01 7.54061508e+01 7.80355682e+01 7.09137421e+01 7.76484909e+01 9.03488922e+01 9.57399139e+01 7.93781662e+01 5.44123344e+01 4.86949844e+01 6.04616127e+01 6.49413757e+01 5.53902359e+01 4.47668152e+01 4.52118034e+01 6.58286972e+01 8.12613220e+01 8.03790741e+01 6.38951797e+01 4.09896698e+01 3.83232574e+01 4.05621834e+01 4.33708344e+01 3.11631260e+01 6.22377777e+00 1.35459673e+00 1.85034809e+01 4.11745949e+01 5.48768005e+01 6.02398529e+01 7.23281860e+01 7.23601532e+01 3.31160278e+01 -7.21032429e+00 -7.73126030e+00 2.19380951e+01 5.31975746e+01 4.96192627e+01 4.83677063e+01 2.97723274e+01 9.70837498e+00 1.28347054e+01 3.90280151e+01 6.48487778e+01 6.91783066e+01 7.57228317e+01 4.61784210e+01 1.24148655e+01 2.16887212e+00 2.79466209e+01 5.51622238e+01 7.06474152e+01 8.06910324e+01 8.61096725e+01 6.19325218e+01 5.00397415e+01 3.65563126e+01 3.40037613e+01 3.23734703e+01 2.83961868e+01 2.79297009e+01 2.79978371e+01 2.94154377e+01 2.36355705e+01 1.25884485e+01 8.20805168e+00 2.45750751e+01 4.59956474e+01 1.38936768e+02 1.75586563e+02 1.05453537e+02 3.14646626e+01 -2.06327377e+02 1.44113232e+03 2.54019824e+03 3.29325348e+02 -2.75204803e+02 -8.86899023e+03 -2.12220195e+04 -773293056. -5.49951642e+09 -238931136. -2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -2.46511590e+09 -162604928. -411763936. -674604352. -257204592. 69439952. 2.54077715e+04 1.18186709e+04 2.05919116e+03 1.35393542e+03 5.50576477e+02 3.58879974e+02 2.66666382e+02 2.18505920e+02 2.18814301e+02 2.40351883e+02 4.67941992e+03 3.21381055e+03 7.42064575e+02 3.16614227e+02 2.20831497e+02 1.81183777e+02 1.60631104e+02 1.26185966e+02 6.21248322e+01 4.19721527e+01 1.71590862e+01 1.65186501e+01 1.33334160e+00 6.77884281e-01 -3.11141038e+00 -1.00644293e+01 -1.74748993e+01 -2.62762737e+01 -1.72844162e+01 -1.56768322e+01 -2.38403854e+01 -2.82167740e+01 -3.29022179e+01 -1.64963856e+01 -7.39597893e+00 -3.14468384e+00 -1.37826729e+01 -2.20101604e+01 -3.48600159e+01 -3.78143921e+01 -2.61361485e+01 1.81013508e+01 5.31899109e+01 5.93482971e+01 3.74399071e+01 2.07405281e+01 1.17163906e+01 -2.32993937e+00 -1.97935060e-01 9.35696983e+00 1.52757053e+01 9.88239574e+00 -1.92855847e+00 -5.85589504e+00 -3.01324711e+01 -1.19161406e+01 6.52841139e+00 2.82365093e+01 4.36486740e+01 5.35530968e+01 6.01042938e+01 3.95206261e+01 2.52454243e+01 2.90367756e+01 1.87680912e+01 -1.00056524e+01 -2.09412899e+01 -1.15361919e+01 1.09642019e+01 9.95849895e+00 7.26188564e+00 2.93980217e+01 6.92930984e+01 6.67298660e+01 5.18651123e+01 2.95022717e+01 8.10818253e+01 1.25111023e+02 1.25514748e+02 9.43239594e+01 7.24031372e+01 8.26552048e+01 8.80786362e+01 7.35726471e+01 7.72892303e+01 9.60281677e+01 1.27013992e+02 1.12465607e+02 6.77160416e+01 2.18772469e+01 7.48359060e+00 6.83165216e+00 1.80424156e+01 3.30709763e+01 1.63370934e+01 -1.14648256e+01 5.78959846e+00 4.18038101e+01 5.49048424e+01 1.72137127e+01 -8.90955830e+00 3.85296402e+01 7.40836334e+01 6.95141144e+01 1.48308477e+01 -2.85524750e+01 -3.16215000e+01 -3.14795055e+01 -2.49067688e+01 -2.32766552e+01 -6.08692026e+00 -2.85447288e+00 -1.05512104e+01 -1.24297104e+01 2.04186916e+00 1.55155697e+01 1.42162266e+01 1.03637695e+01 8.20102024e+00 1.18171053e+01 9.07284737e+00 4.77550278e+01 8.93571930e+01 8.60590897e+01 4.82322845e+01 3.70747590e+00 4.64329071e+01 8.45825500e+01 8.97310486e+01 5.47743950e+01 2.70046139e+01 2.09000435e+01 1.38198547e+01 -4.22118950e+00 6.29008341e+00 1.08258429e+01 1.70072517e+01 -3.20113111e+00 -1.85821171e+01 -1.44492960e+01 7.67019844e+00 2.18494396e+01 1.56486988e+01 8.52379608e+00 1.37969484e+01 3.24404869e+01 7.90582962e+01 1.26858231e+02 1.23551056e+02 8.66664047e+01 4.11789703e+01 7.90862045e+01 1.18305962e+02 1.10882034e+02 5.13594170e+01 1.90477252e+00 8.56350422e+00 2.43499660e+01 3.12694302e+01 2.64031639e+01 2.47103500e+01 2.44887466e+01 1.45923166e+01 1.26694736e+01 3.88846855e+01 7.08647232e+01 6.46622391e+01 3.35158310e+01 -7.62987554e-01 -7.60222387e+00 -6.62310219e+00 3.00442200e+01 6.39564896e+01 5.83369865e+01 3.14631634e+01 1.47075682e+01 1.58400564e+01 -2.34303331e+00 2.29618511e+01 6.93953705e+01 8.25194855e+01 5.16139030e+01 1.68441734e+01 2.07054729e+01 2.44263515e+01 1.26585159e+01 3.87790370e+00 1.05138493e+01 1.41148205e+01 5.70912781e+01 9.35007172e+01 9.44250412e+01 4.94474602e+01 1.53226709e+01 2.94502048e+01 3.76767883e+01 6.78406143e+01 9.67361603e+01 9.08505707e+01 3.98257561e+01 -6.55553865e+00 1.70041764e+00 6.86554623e+00 1.33600330e+01 -6.27272427e-01 -1.22917671e+01 -1.93876305e+01 -1.95074959e+01 -1.39691601e+01 -1.57929945e+01 -1.83438187e+01 -1.55755119e+01 -3.89337387e+01 -6.23374748e+01 -7.39430466e+01 -7.01547318e+01 -4.86483040e+01 -4.63212662e+01 -4.32626572e+01 -4.53286133e+01 -4.11684570e+01 -3.46443214e+01 -4.36247826e+01 -3.50398445e+01 -2.71120472e+01 -2.77809010e+01 -4.66668015e+01 -5.22130928e+01 -4.56374817e+01 -3.61156807e+01 -3.65733566e+01 -3.81919746e+01 -2.68469143e+01 -2.93858242e+01 -1.12797079e+01 -2.67465210e+00 3.55653262e+00 -2.84965744e+01 -6.75122223e+01 -4.74886818e+01 1.35880165e+01 5.01616974e+01 4.01860275e+01 1.38768415e+01 1.95268905e+00 2.56546092e+00 1.82942963e+00 1.32575922e+01 1.28434658e+01 1.12713442e+01 3.74424386e+00 -7.28560448e+00 -2.04097710e+01 -2.73523216e+01 -1.79544468e+01 -5.07266665e+00 5.32318068e+00 3.72437406e+00 -1.26127768e+00 -4.05303526e+00 -1.62546024e+01 -2.09471378e+01 -2.91071339e+01 -1.32812977e+01 2.10356960e+01 5.65183983e+01 5.10156670e+01 2.79968338e+01 -9.69853878e+00 -1.51749630e+01 -2.29452457e+01 4.61068201e+00 2.86012478e+01 4.26877441e+01 4.82695351e+01 2.23275547e+01 1.06773138e+00 -3.09502716e+01 -2.11156254e+01 -1.21633463e+01 -7.43890095e+00 -1.64499645e+01 -2.01164036e+01 -2.94555111e+01 -1.96237621e+01 -4.86307764e+00 4.47792053e+00 1.07644329e+01 6.64114952e+00 4.15750809e+01 6.23825264e+01 5.34251366e+01 1.12703257e+01 -1.85778561e+01 -5.73846865e+00 5.60579443e+00 1.03013599e+00 -2.82823277e+00 2.00543041e+01 5.23087730e+01 5.04914589e+01 1.05644855e+01 -3.08905735e+01 -1.59896193e+01 1.89632252e-01 -1.84243369e+00 -2.54676628e+01 -3.10843735e+01 -2.43556271e+01 -7.41987848e+00 -1.82771072e+01 -4.11936455e+01 -4.88561935e+01 -4.34893990e+01 -3.39487839e+01 -4.82940559e+01 -2.62787857e+01 5.96103621e+00 1.49492645e+01 2.61995010e+01 4.63368073e+01 7.50394592e+01 7.16495514e+01 5.57054367e+01 6.03247948e+01 4.44133492e+01 3.74794044e+01 4.59101534e+00 -2.89087315e+01 -7.28158264e+01 -8.10256577e+01 -6.97586823e+01 -5.94629173e+01 -5.18438492e+01 -4.71741180e+01 -4.69151573e+01 -5.43680534e+01 -6.30243988e+01 -3.65002937e+01 5.74336863e+00 2.15203037e+01 1.39953690e+01 -1.43860130e+01 -2.63822746e+01 -2.79664154e+01 -4.49558411e+01 -2.97773800e+01 -3.07657185e+01 -1.34567747e+01 -2.77482486e+00 1.52966337e+01 4.20105705e+01 1.79561329e+01 -1.07638216e+01 -2.55984039e+01 7.01272917e+00 1.57301588e+01 4.12464237e+00 -3.08580265e+01 -7.17567968e+00 1.95219040e+01 3.35775452e+01 1.11430321e+01 -1.34117680e+01 1.33327684e+01 4.03965759e+01 3.12813320e+01 -1.46130657e+01 -4.12915955e+01 -1.43403835e+01 5.14453411e+00 -2.63043785e+01 -6.47147369e+01 -4.23070984e+01 1.20171824e+01 3.26888161e+01 1.80634022e+01 -3.06870770e+00 2.31100535e+00 2.50922260e+01 4.66161804e+01 3.27773094e+01 -7.78086042e+00 -4.44567375e+01 -4.12655830e+01 -3.37550049e+01 -2.85031872e+01 -3.34228973e+01 -3.35240860e+01 -2.54801998e+01 -7.18407726e+00 -5.00917101e+00 -2.44529037e+01 -3.16246834e+01 -2.85860233e+01 1.88259995e+00 1.27568378e+01 -2.49602318e+00 -1.58260393e+01 -3.60861740e+01 -3.11736679e+01 -3.62718430e+01 -4.15209618e+01 -5.22630310e+01 -4.93139725e+01 -9.79885960e+00 2.21199474e+01 -1.31944160e+01 -7.22905426e+01 -7.64643402e+01 -2.30860786e+01 -4.12016058e+00 -3.56668320e+01 -5.30487289e+01 -3.10093155e+01 -2.02996712e+01 -2.52793331e+01 -4.88402405e+01 -3.72407722e+01 -2.67268810e+01 -2.03149281e+01 -3.13756237e+01 -5.40077362e+01 -5.22131462e+01 -5.22686882e+01 -2.81676598e+01 -1.02509022e+01 -6.62455845e+00 -3.33975983e+01 -3.31437149e+01 1.21631899e+01 4.37347488e+01 2.99536324e+01 -1.62309208e+01 -1.85458221e+01 -5.48316193e+00 -1.97247753e+01 -6.07177124e+01 -7.29612961e+01 -4.63241653e+01 -2.11642780e+01 -2.69636459e+01 -3.50552750e+01 -2.70756092e+01 -2.21223984e+01 -2.45932884e+01 -3.00458164e+01 -4.42719307e+01 -5.38890800e+01 -6.19058418e+01 -4.90881424e+01 -4.02407646e+01 -3.01379604e+01 -2.93248844e+01 -2.41325302e+01 -1.02362852e+01 -1.01826468e+01 -2.37917843e+01 -4.05378113e+01 -3.49127045e+01 -1.47888803e+01 -1.29384546e+01 -1.40620947e+01 -8.02668190e+00 2.69904575e+01 4.44425430e+01 2.85179577e+01 -1.26549063e+01 -2.45928631e+01 -1.81897583e+01 -1.31961870e+01 -2.85692596e+01 -3.63498726e+01 -4.58615532e+01 -5.31645889e+01 -5.39222679e+01 -4.56455956e+01 -4.49334717e+01 -5.68998032e+01 -5.65704727e+01 -2.97083626e+01 -1.76190720e+01 -2.94867401e+01 -4.61572227e+01 -2.61463051e+01 -1.61303387e+01 -3.36551781e+01 -6.77407913e+01 -8.81769562e+01 -8.67220612e+01 -8.54315948e+01 -7.69921265e+01 -6.65046234e+01 -6.06447754e+01 -6.37639313e+01 -6.05747261e+01 -5.50740128e+01 -5.41569290e+01 -6.63114319e+01 -5.78777580e+01 -2.98715553e+01 -1.21973095e+01 -1.03595495e+01 -1.51493359e+01 -2.49940872e+01 -3.65482292e+01 -4.96125755e+01 -4.99953537e+01 -5.24461899e+01 -5.49420128e+01 -5.46901550e+01 -4.98410683e+01 -4.84015961e+01 -4.56759338e+01 -4.80000305e+01 -5.29859619e+01 -5.58098831e+01 -5.64987488e+01 -3.87150002e+01 -2.13176594e+01 -1.90525703e+01 -3.22114410e+01 -4.57278099e+01 -4.43313484e+01 -4.49792938e+01 -4.39681473e+01 -4.85552559e+01 -4.70669861e+01 -4.63873482e+01 -3.40814934e+01 -2.51186409e+01 -3.10747356e+01 -4.46874771e+01 -4.84861336e+01 -2.81024742e+01 -1.61609135e+01 -2.44188347e+01 -4.45867157e+01 -4.42894821e+01 -3.77214775e+01 -3.65594902e+01 -4.47406158e+01 -5.19067726e+01 -4.21505699e+01 -3.62368202e+01 -2.89457417e+01 -2.61653004e+01 -3.72061729e+01 -4.55130081e+01 -4.60550537e+01 -2.63588047e+01 -1.72462215e+01 -3.08318062e+01 -4.81924171e+01 -4.61814461e+01 -3.35535660e+01 -3.08944187e+01 -3.79249077e+01 -4.59759865e+01 -4.16574440e+01 -3.71462440e+01 -3.47338066e+01 -3.93908806e+01 -4.52129745e+01 -4.85847168e+01 -4.14453354e+01 -3.37558365e+01 -3.28344345e+01 -3.96157150e+01 -5.07285538e+01 -4.65580826e+01 -4.16837654e+01 -4.12674484e+01 -4.73686218e+01 -4.83932343e+01 -4.11728592e+01 -4.16611328e+01 -4.78881340e+01 -5.59661026e+01 -5.81766930e+01 -5.82805634e+01 -5.36540985e+01 -4.69330635e+01 -4.51435928e+01 -4.79897385e+01 -5.37160492e+01 -5.58944588e+01 -5.61727715e+01 -5.39282646e+01 -5.20550232e+01 -5.34333725e+01 -3.58220367e+01 -2.36136665e+01 -3.14509716e+01 -6.15985641e+01 -7.59395905e+01 -5.35344315e+01 -4.76816330e+01 -3.93508186e+01 2.82116528e+01 6.42539597e+01 -2.01881866e+01 -235291968. -9.32597852e+03 2.78443069e+10 -2.51446886e+09 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. 0. 0. 0. 1.05792151e+03 4.04661713e+02 5.35920792e+01 2.04015636e+01 -1.15044031e+01 -3.46831665e+01 -3.61384697e+01 -2.96637707e+01 -2.76397285e+01 -3.18435726e+01 -2.81826591e+01 -2.03269691e+01 -1.40366440e+01 -2.11138115e+01 -3.77452049e+01 -4.61858406e+01 -4.01470947e+01 -2.90130444e+01 -2.30788937e+01 -2.49863873e+01 -2.77530270e+01 -2.41891613e+01 -1.81703873e+01 -2.28292027e+01 -3.30354080e+01 -3.95315781e+01 -3.52344360e+01 -2.52392159e+01 -2.20992565e+01 -2.95721111e+01 -4.21542778e+01 -4.86954498e+01 -4.24991493e+01 -4.41674423e+01 -5.34654160e+01 -4.58016777e+01 -2.53006954e+01 -1.05704823e+01 -2.72322769e+01 -5.96625252e+01 -6.97702866e+01 -5.40408897e+01 -3.60574722e+01 -2.54197197e+01 -2.36535587e+01 -2.83452301e+01 -2.98252506e+01 -2.98156662e+01 -3.26841240e+01 -6.07402954e+01 -8.00055466e+01 -7.02746735e+01 -4.29907875e+01 -2.43266888e+01 -3.57053680e+01 -5.33475113e+01 -6.52833557e+01 -4.85403976e+01 -4.37724991e+01 -5.02080879e+01 -4.39214859e+01 -2.39870949e+01 -8.66708696e-01 -4.45294333e+00 -3.65974159e+01 -4.86057472e+01 -3.95293045e+01 -1.35585709e+01 -1.82017193e+01 -3.65782890e+01 -3.50770454e+01 -2.01700745e+01 -9.26382065e+00 -2.25326138e+01 -5.60765305e+01 -7.39935837e+01 -6.51139755e+01 -3.01127415e+01 -7.54775763e+00 -1.25092344e+01 -2.85586357e+01 -2.60257473e+01 -7.55684376e+00 -9.12752438e+00 -3.30996399e+01 -4.69617043e+01 -2.24766197e+01 1.07537832e+01 1.36601124e+01 -2.22077541e+01 -5.32269554e+01 -5.13518600e+01 -2.64912624e+01 -2.22384396e+01 -3.19190083e+01 -1.35448790e+01 2.43554802e+01 4.24668083e+01 1.49681416e+01 -3.69457664e+01 -6.77466202e+01 -5.39423523e+01 -2.13620720e+01 1.57771320e+01 4.05959702e+01 3.35033684e+01 2.44627495e+01 2.13911819e+01 1.53474197e+01 -2.03479710e+01 -5.32100372e+01 -3.32041359e+01 2.19571819e+01 4.82328987e+01 2.60220699e+01 -2.92432671e+01 -6.13281784e+01 -4.23550377e+01 -1.82330284e+01 -8.08132076e+00 -1.04695520e+01 1.34901018e+01 5.92238426e+01 6.22657242e+01 1.66331043e+01 -3.29669914e+01 -3.41431007e+01 -3.28987241e-01 2.29560986e+01 2.80723209e+01 1.35447035e+01 -5.70330143e+00 -2.16925659e+01 8.89800835e+00 2.30571404e+01 1.22871530e+00 -2.48443966e+01 -3.00664978e+01 -1.53427277e+01 -1.43755550e+01 -3.38557129e+01 -2.83901367e+01 -1.17200413e+01 1.05209484e+01 1.96060638e+01 -5.21796799e+00 -1.95884209e+01 -9.40711975e+00 1.68097706e+01 -1.09293044e+00 -7.46430511e+01 -1.11513626e+02 -5.86152878e+01 9.05090332e+00 1.21344357e+01 -2.71676350e+01 -5.07956314e+01 -4.00182266e+01 -4.01239777e+01 -6.71528931e+01 -1.02855156e+02 -1.09438065e+02 -8.77972717e+01 -4.08548164e+01 -8.81573582e+00 -3.26926346e+01 -5.15642891e+01 -4.40685768e+01 -1.45638123e+01 -3.12447472e+01 -9.98694077e+01 -8.99430389e+01 -6.16082535e+01 -2.32220192e+01 -6.19343147e+01 -1.43897568e+02 -1.85285843e+02 -1.49667618e+02 -6.16944885e+01 -2.18246441e+01 -2.86933842e+01 -2.23254509e+01 -6.48347616e-01 -1.54509268e+01 -7.67085571e+01 -1.44863052e+02 -1.43815109e+02 -8.32825394e+01 1.14563341e+01 4.63635674e+01 1.58387890e+01 -4.47543640e+01 -7.55423813e+01 -7.10519409e+01 -9.29976807e+01 -1.17787254e+02 -1.08311935e+02 -3.35501518e+01 1.91179523e+01 -5.39485741e+00 -1.04778450e+02 -1.43927689e+02 -9.17422638e+01 4.51348400e+00 3.36917381e+01 -1.12554588e+01 -6.34082222e+01 -3.78904343e+01 3.31051540e+00 -4.10973692e+00 -5.51209412e+01 -6.58860550e+01 -1.46215792e+01 5.54674644e+01 6.62501221e+01 2.88389397e+01 -2.08818741e+01 -2.15397625e+01 2.96838284e+00 1.35134315e+01 -1.09126873e+01 3.71870470e+00 3.55497398e+01 4.39507370e+01 3.86247520e+01 -7.16174126e-01 -1.49915981e+01 -1.87650347e+00 -1.56198406e+00 -5.93407011e+00 -4.16192894e+01 -1.29710827e+01 3.30805092e+01 5.71282578e+01 4.10844421e+01 -5.71168976e+01 -1.15410454e+02 -1.07730820e+02 6.35658932e+00 6.44008179e+01 7.05190201e+01 1.95351696e+01 -2.74460959e+00 2.52697601e+01 2.27787991e+01 -8.74672127e+00 -3.44638824e+01 -1.60527599e+00 2.70003395e+01 -2.80527935e+01 -1.04500824e+02 -9.65889053e+01 -5.03052940e+01 -2.11735210e+01 -4.83592796e+01 -1.06853241e+02 -5.73780479e+01 -1.46293001e+01 3.34203110e+01 1.32144480e+01 -4.78351517e+01 -8.05831375e+01 -9.78418503e+01 -3.28725014e+01 -1.21336861e+01 -7.84154224e+00 -6.66484909e+01 -6.68546219e+01 -6.59353027e+01 -7.13254471e+01 -1.04687744e+02 -1.23710632e+02 -5.36428108e+01 -5.31458330e+00 -1.32343292e+00 -7.17835464e+01 -7.43403625e+01 -4.10071869e+01 2.00045085e+00 3.24614563e+01 1.67289467e+01 1.88030682e+01 -4.02103958e+01 -7.21947479e+01 -9.73347168e+01 -8.77428055e+01 -6.73350296e+01 -3.74524422e+01 2.42470951e+01 6.05556335e+01 3.68788414e+01 -5.16416740e+01 -7.04315262e+01 -4.98096542e+01 -3.93633270e+01 -4.78975258e+01 -2.11543236e+01 7.97502518e+01 1.08525612e+02 5.92183266e+01 -4.90429535e+01 -7.36215286e+01 -3.66487007e+01 2.40640373e+01 4.63729553e+01 6.59467459e+00 1.62138712e+00 -1.99915180e+01 3.65835762e+01 6.54391479e+01 7.10894318e+01 2.27981377e+01 -9.14060020e+00 2.81973267e+01 7.65313034e+01 4.86007195e+01 -1.02657290e+01 5.64290905e+00 4.92622108e+01 5.36651001e+01 2.27538128e+01 2.52703056e+01 9.21571579e+01 1.11208473e+02 7.33434296e+01 4.36094046e+00 -3.68650764e-01 2.98674355e+01 5.29873505e+01 4.17159004e+01 6.74042797e+00 1.44135637e+01 1.63185425e+01 6.82619553e+01 9.41909103e+01 9.50032349e+01 6.19024467e+01 4.35696411e+01 7.19598923e+01 1.05064110e+02 8.03754349e+01 1.07758760e+01 -1.07245407e+01 -9.09498882e+00 -2.72090855e+01 -8.45603409e+01 -6.56567230e+01 -9.14354146e-01 1.06035385e+01 -3.69463730e+01 -1.00572411e+02 -3.58966293e+01 3.09905624e+00 3.26190681e+01 6.45074539e+01 7.05996170e+01 3.83781738e+01 -6.42918243e+01 -8.25073547e+01 -4.26448059e+00 6.45692673e+01 2.96699429e+01 -6.28072433e+01 -1.11671028e+02 -5.17731514e+01 -3.42801523e+00 -1.53067818e+01 -5.07379074e+01 -9.76907043e+01 -1.39260681e+02 -2.00879898e+02 -1.77615555e+02 -1.08132523e+02 -8.61878357e+01 -1.16792007e+02 -1.57153412e+02 -7.79819870e+01 -3.28020477e+01 3.92898893e+00 -9.35221577e+00 -1.77574635e+01 -7.12630234e+01 -1.82569000e+02 -2.13427521e+02 -1.20673668e+02 4.59361191e+01 8.81586227e+01 -4.49743118e+01 -1.69902405e+02 -1.79797775e+02 -8.68254700e+01 -3.28898659e+01 -6.30118675e+01 -1.36275513e+02 -1.77372742e+02 -1.32224182e+02 -2.10998306e+01 1.13874664e+01 -4.34202805e+01 -1.22371666e+02 -2.10131653e+02 -2.11434174e+02 -1.76780365e+02 -6.25524139e+01 5.17863159e+01 9.48486862e+01 2.51421452e+01 -1.20374893e+02 -1.97937851e+02 -1.25883797e+02 -1.25765409e+01 -2.19171772e+01 -1.45738586e+02 -2.48278336e+02 -1.94264572e+02 -5.21668739e+01 4.68738861e+01 4.95064354e+01 -3.68469009e+01 -1.00080025e+02 -1.56362091e+02 -8.82054291e+01 -5.47027130e+01 -1.75168247e+01 -6.58691025e+01 -9.78949738e+01 -4.33746109e+01 1.28701792e+01 1.01246651e+02 1.13688759e+02 6.44296265e+01 -1.59017849e+01 -1.38475082e+02 -1.56728134e+02 -8.26635742e+01 8.12344971e+01 1.51888748e+02 7.99934311e+01 -7.80194626e+01 -1.64572144e+02 -1.25138771e+02 -5.52887497e+01 -5.46962585e+01 -1.03227066e+02 -1.37533127e+02 -1.40960571e+02 -5.71378899e+01 1.29321346e+01 7.45850983e+01 7.01147537e+01 2.53038158e+01 -2.27233620e+01 -7.84603424e+01 -6.98503494e+01 -1.11623230e+01 5.05581589e+01 4.80214233e+01 -1.84099331e+01 -9.67849503e+01 -5.87734604e+01 1.47935562e+01 5.05801315e+01 -1.45832891e+01 -1.24905396e+02 -1.17754639e+02 -4.69076118e+01 6.26879120e+01 6.56529922e+01 -1.81274796e+01 -8.59659882e+01 -1.37406570e+02 -5.64558067e+01 -2.28806286e+01 2.26148739e+01 3.60058441e+01 4.53967705e+01 5.17492638e+01 3.14243722e+00 2.36941757e+01 6.64902267e+01 6.13312454e+01 3.62602162e+00 -9.26153259e+01 -1.36063766e+02 -8.19250259e+01 4.99024429e+01 1.67724106e+02 1.52563293e+02 1.66233044e+01 -1.17141449e+02 -1.57963028e+02 -6.25788727e+01 5.84011612e+01 8.31374512e+01 9.71205330e+00 -7.96297455e+01 -4.71183777e+01 1.97766781e+01 7.68184509e+01 8.65721130e+01 5.77080688e+01 3.29246879e+00 -6.23000374e+01 -5.45071297e+01 1.01307878e+01 1.11843254e+02 1.28569855e+02 5.24937592e+01 -5.17597275e+01 -4.31661453e+01 3.77873917e+01 9.63636322e+01 6.52879791e+01 1.87502041e+01 -5.57175827e+00 -1.75837212e+01 1.85981979e+01 4.23162575e+01 1.22487402e+01 -1.49554644e+01 -4.63906212e+01 3.52222323e+00 4.55475540e+01 1.01587708e+02 1.37855499e+02 9.54891129e+01 5.24582329e+01 -2.25320892e+01 -5.11630669e+01 -8.02947140e+00 6.09954643e+01 7.22178040e+01 -6.80680561e+00 -8.43963699e+01 -7.61664886e+01 -3.01618671e+01 5.24174805e+01 7.61442871e+01 5.27544975e+01 9.01027298e+00 -1.84024429e+01 4.19634705e+01 9.74208298e+01 1.64690216e+02 1.47144485e+02 7.27875061e+01 6.65111923e+01 9.88272552e+01 1.69935135e+02 1.89797943e+02 1.60828796e+02 1.07516884e+02 9.85518837e+00 -2.73046684e+01 -2.12862182e+00 7.71592560e+01 1.11145729e+02 4.93624420e+01 -2.48042164e+01 -2.34714165e+01 6.29004440e+01 1.28574661e+02 1.06792152e+02 1.89740334e+01 -5.55483551e+01 -6.03983269e+01 6.36878347e+00 9.00453720e+01 1.12514488e+02 1.04509293e+02 7.81034470e+01 4.85151672e+01 5.22455215e+00 4.26015794e-01 2.35849075e+01 3.98982124e+01 4.06682777e+00 -7.60905075e+01 -1.17162674e+02 -5.03696709e+01 4.93126068e+01 9.80636749e+01 3.41709557e+01 -5.54476013e+01 -7.31139526e+01 -1.76507015e+01 7.52173309e+01 9.07103729e+01 3.45448036e+01 3.82800150e+00 -1.10783958e+01 4.26231613e+01 5.43202477e+01 4.87075653e+01 3.10243378e+01 -1.55323019e+01 1.85745239e-01 1.36983814e+01 8.34559479e+01 1.41210648e+02 1.16253845e+02 8.17242279e+01 2.52108359e+00 -1.27423429e+01 -1.02639747e+00 8.51336060e+01 1.73651642e+02 1.82956406e+02 1.11931442e+02 5.13374672e+01 2.58663605e+02 2.61807648e+02 1.16233101e+02 1.91789404e+03 2.69793237e+03 6.23405322e+03 2.10859531e+04 -1181876096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 9.54779688e+03 3.64835889e+03 3.75939423e+02 2.74183167e+02 1.82649750e+02 1.61292313e+02 9.44191818e+01 6.82328110e+01 -1.69039841e+01 -1.62241974e+01 2.07127113e+01 7.86139450e+01 6.71061707e+01 -6.74936354e-01 -5.82386017e+01 -6.82577286e+01 -6.41853809e+00 6.88895493e+01 8.43264542e+01 1.96210384e+01 -3.85324669e+01 -4.03453255e+01 1.11315804e+01 7.41955757e+00 -2.64106750e+01 -3.27028847e+01 -2.95361471e+00 3.83653564e+01 4.06554680e+01 5.22916832e+01 7.20885849e+01 6.79148865e+01 3.14917641e+01 -4.18931122e+01 -4.27743454e+01 9.22959685e-01 4.65802765e+01 4.20460358e+01 -7.27324724e+00 -6.09385185e+01 -5.21146927e+01 1.96718216e+01 1.05724327e+02 9.64938278e+01 1.57314348e+01 -2.87149239e+01 -3.01960239e+01 1.46678247e+01 2.91217556e+01 3.68586617e+01 4.45656166e+01 3.23625793e+01 1.31801176e+01 -3.65288658e+01 -1.75581017e+01 2.39347134e+01 4.30501862e+01 1.12698250e+01 -4.09154129e+01 -4.11194382e+01 -1.58078337e+01 2.86110821e+01 4.60701218e+01 4.07191849e+00 -5.43787498e+01 -9.62317429e+01 -7.04226379e+01 -9.13049221e+00 1.15697765e+01 -2.21306915e+01 -4.67393799e+01 -3.98432388e+01 1.22520885e+01 2.30233212e+01 8.34300327e+00 -1.60433788e+01 -1.34593830e+01 -1.04572992e+01 -2.36263180e+01 -5.74873161e+00 2.53052025e+01 4.08844223e+01 5.46963978e+00 -4.74987907e+01 -5.54476585e+01 -3.60557518e+01 4.69277334e+00 3.20692062e+01 3.63544083e+01 5.35312176e+00 -1.91443539e+01 -1.49226208e+01 3.39517555e+01 5.25087852e+01 1.74642086e+01 -1.56594429e+01 -1.36591187e+01 3.27888336e+01 5.08545837e+01 4.54582100e+01 3.98637505e+01 3.30773048e+01 1.71455688e+01 -1.97589951e+01 -1.67964630e+01 1.24199505e+01 3.51922455e+01 3.45754662e+01 7.46361303e+00 4.86614466e+00 2.11577110e+01 3.42583847e+01 5.11084137e+01 4.49493408e+01 1.97744980e+01 -8.29396439e+00 -1.45645800e+01 2.30994682e+01 4.14181976e+01 2.57674751e+01 1.58074074e+01 1.26748295e+01 3.08762379e+01 2.81574821e+01 2.68289547e+01 3.76194229e+01 4.05951233e+01 3.61759605e+01 3.82038093e+00 3.93255687e+00 2.48642330e+01 4.45711403e+01 4.19238815e+01 2.33535786e+01 2.25222988e+01 3.82601204e+01 4.82006264e+01 6.26066132e+01 4.92982063e+01 2.78117161e+01 7.75624514e+00 1.14474983e+01 3.19547749e+01 3.47757988e+01 2.58762112e+01 2.49749832e+01 3.05952759e+01 4.68120384e+01 5.41350937e+01 6.07419701e+01 6.11227150e+01 4.90615005e+01 3.48751717e+01 1.41074753e+01 8.56686592e+00 1.26294632e+01 2.49189987e+01 2.54293365e+01 1.18542242e+01 -4.93676543e-01 7.44276333e+00 3.07397881e+01 4.69402847e+01 4.55515099e+01 2.44884109e+01 1.35550718e+01 1.52897882e+01 2.76422901e+01 3.00846596e+01 2.43024559e+01 2.51603470e+01 2.38037491e+01 2.24121532e+01 2.16543598e+01 3.05304317e+01 4.21470222e+01 4.11605530e+01 3.62641983e+01 2.79153214e+01 2.31696415e+01 2.12327728e+01 2.55855446e+01 2.60317440e+01 1.88043652e+01 1.10236492e+01 1.63221970e+01 2.77167664e+01 3.72655182e+01 3.71521034e+01 2.93300209e+01 2.67036915e+01 2.56713810e+01 3.23432922e+01 3.15307617e+01 2.68889332e+01 2.14659882e+01 1.87707653e+01 1.93243389e+01 1.63596497e+01 1.89493179e+01 2.46435490e+01 2.92789860e+01 2.94267731e+01 2.56470375e+01 2.53927193e+01 2.78167648e+01 3.13911076e+01 3.40140266e+01 3.19914551e+01 2.77393150e+01 2.48124619e+01 2.62459488e+01 2.89107876e+01 2.91555748e+01 2.82532749e+01 2.81011925e+01 2.82737770e+01 2.86078129e+01 2.86137447e+01 2.84118919e+01 2.82635479e+01 2.83283577e+01 2.89195156e+01 3.03097134e+01 3.11281414e+01 3.08466091e+01 2.97676315e+01 2.93595867e+01 2.95627232e+01 2.84011002e+01 2.67935867e+01 2.60689774e+01 2.66745396e+01 2.93015366e+01 2.96990833e+01 3.04594841e+01 2.97948208e+01 2.79522781e+01 2.71971760e+01 2.74463692e+01 3.07746525e+01 3.17796936e+01 3.00220699e+01 2.73060608e+01 2.73420830e+01 2.93679447e+01 3.11250229e+01 3.00839939e+01 2.84166489e+01 2.82225761e+01 2.78004189e+01 2.87408581e+01 2.66054134e+01 2.74115753e+01 2.69707222e+01 2.96515160e+01 2.74059296e+01 2.55601063e+01 2.45487957e+01 2.56078606e+01 2.68003101e+01 2.42003307e+01 2.23373966e+01 2.28261681e+01 2.16133728e+01 2.22064648e+01 2.32804565e+01 2.69325848e+01 2.51672802e+01 2.46699333e+01 2.38000889e+01 2.50231953e+01 2.32849216e+01 2.19604549e+01 2.23980675e+01 2.18557281e+01 2.25947781e+01 2.48666286e+01 2.55987854e+01 2.40921612e+01 2.27823238e+01 2.08619347e+01 2.19937782e+01 1.80296555e+01 2.04020576e+01 1.81883793e+01 2.08869343e+01 2.03936386e+01 2.58684063e+01 3.37985268e+01 3.66841278e+01 3.30782967e+01 2.74080448e+01 2.34061737e+01 2.71538372e+01 2.62000408e+01 3.00288029e+01 2.71668377e+01 2.29209270e+01 2.10752754e+01 2.48234997e+01 2.84427414e+01 2.55099411e+01 2.39932747e+01 2.70468941e+01 2.68738575e+01 2.07470951e+01 2.34863739e+01 2.86796761e+01 3.60525894e+01 3.41340027e+01 3.45022240e+01 2.55108585e+01 1.65300255e+01 3.52340102e+00 5.91382623e-01 5.71889639e+00 1.54927702e+01 2.14232788e+01 2.39360905e+01 2.41575165e+01 2.80177231e+01 1.73290825e+01 5.45323324e+00 7.18616009e+00 1.94297085e+01 3.04071274e+01 2.84600410e+01 2.55646038e+01 2.98100357e+01 3.23805428e+01 3.20922394e+01 3.00517445e+01 3.21665878e+01 3.34860458e+01 2.53064022e+01 2.05080147e+01 2.62223587e+01 4.17771225e+01 5.73410645e+01 5.78275681e+01 4.97155075e+01 3.35592041e+01 3.68640671e+01 4.00154266e+01 4.08310089e+01 3.83454285e+01 3.33038406e+01 4.50084915e+01 5.21975174e+01 5.51748161e+01 3.57569733e+01 2.10089760e+01 1.41240845e+01 2.93677101e+01 4.88627281e+01 6.78852234e+01 5.30822372e+01 2.46939411e+01 1.47697191e+01 2.05699577e+01 3.69887619e+01 3.82181854e+01 5.71282921e+01 6.43826828e+01 5.93068886e+01 4.32018127e+01 2.90674133e+01 2.14746704e+01 2.55201893e+01 3.67422905e+01 5.27964439e+01 5.29794044e+01 3.79783859e+01 2.65796509e+01 1.77180119e+01 1.95544720e+01 1.61136818e+01 1.08315935e+01 8.81567669e+00 1.47204132e+01 2.05326900e+01 2.58683147e+01 1.97112637e+01 1.64717865e+01 1.66652489e+01 2.65445862e+01 2.12157803e+01 1.25036116e+01 2.33201046e+01 3.69805183e+01 3.21886902e+01 4.41619205e+00 -6.65588570e+00 1.01734123e+01 2.18688431e+01 2.57265301e+01 2.91366959e+01 4.38307800e+01 4.55828743e+01 5.36481590e+01 4.76253891e+01 4.51088715e+01 2.73010349e+01 2.53645039e+01 3.48099289e+01 3.18670902e+01 2.63524990e+01 1.69812565e+01 1.48078289e+01 1.11697941e+01 3.83295593e+01 6.31775665e+01 7.33635406e+01 4.24013367e+01 2.63711090e+01 1.69281063e+01 1.64662247e+01 1.11152163e+01 1.00431852e+01 1.90832996e+01 9.02765274e+00 -7.75781441e+00 -2.79142590e+01 -2.58216152e+01 -1.34205523e+01 9.17588234e+00 8.74879837e+00 4.53037071e+00 -3.37463951e+00 -8.01548302e-01 6.58337784e+00 -2.06952839e+01 -4.88297844e+01 -4.86439514e+01 -1.45730505e+01 2.69918823e+01 2.99131908e+01 4.27263308e+00 -3.74316864e+01 -1.36854935e+02 -4.07835449e+02 -5.74423279e+02 -6.10184387e+02 -7.69916992e+02 -2.84964917e+03 -4.11768750e+03 -3.16083221e+02 -2.96124783e+01 3.29325348e+02 -2.75204803e+02 -8.86899023e+03 -2.12220195e+04 -773293056. -5.49951642e+09 -238931136. -2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.22521787e+04 -5.72014111e+03 -8.77440674e+02 -5.78614563e+02 -2.38433914e+02 -1.58199478e+02 -9.11446609e+01 -1.97648087e+01 -2.45637169e+01 -2.52340508e+01 -1.58508902e+01 -2.06552753e+01 -4.39435387e+01 -7.32193298e+01 -4.22319756e+01 3.60656905e+00 1.10533466e+01 -2.43756618e+01 -5.62304649e+01 -3.41675758e+01 -2.32390480e+01 -2.08269939e+01 -2.89411392e+01 -4.57229347e+01 -4.44354630e+01 -3.94279099e+01 -2.03450527e+01 -2.09273930e+01 -1.33449335e+01 -1.24208145e+01 2.30273609e+01 5.51873970e+01 5.67818413e+01 3.30472488e+01 1.16707373e+01 1.81712551e+01 3.78391685e+01 4.50635796e+01 5.85875664e+01 6.32385902e+01 6.10464401e+01 7.07136383e+01 7.14669495e+01 6.50952225e+01 5.37339821e+01 4.41844978e+01 5.00645866e+01 4.49265137e+01 4.21839027e+01 4.60467415e+01 4.79779091e+01 6.14074974e+01 6.82979584e+01 5.82520599e+01 1.68276901e+01 -3.33942261e+01 -5.29891243e+01 -3.58786201e+01 -8.26216316e+00 1.07700472e+01 -7.67935848e+00 -3.19606476e+01 -2.45047836e+01 1.04280529e+01 4.96201324e+01 4.98336716e+01 4.63703423e+01 6.03344345e+01 1.00414619e+02 7.31590271e+01 2.53133030e+01 -2.42337971e+01 -1.45280275e+01 1.22197056e+01 1.38358841e+01 2.59061718e+01 3.30057411e+01 4.22968369e+01 3.22174492e+01 1.65948391e+01 -9.04789925e+00 -1.42135525e+01 -1.43740396e+01 4.22833443e+00 1.48523641e+00 -3.04878159e+01 -7.13823471e+01 -6.06988716e+01 -2.75371914e+01 4.23852825e+00 -6.40671301e+00 -2.65083523e+01 -4.98956947e+01 -6.13474159e+01 -3.15261307e+01 1.76010933e+01 2.22205811e+01 1.04623928e+01 -3.48017120e+01 -2.18384304e+01 -1.88408546e+01 7.04172754e+00 1.81406040e+01 7.83734989e+00 7.33956242e+00 2.64156151e+00 1.35596876e+01 2.76688409e+00 2.55926275e+00 2.63303566e+00 -1.59516535e+01 -4.99796371e+01 -5.08333588e+01 -1.96149254e+01 2.51471863e+01 3.59751358e+01 4.33434105e+01 3.26174316e+01 3.89434814e+01 4.76742058e+01 5.46191978e+01 1.05109453e+01 -5.04242134e+01 -6.48798523e+01 -3.82398872e+01 8.00533390e+00 3.05995312e+01 4.79304771e+01 4.97349281e+01 2.83491611e+01 1.84776058e+01 2.87895775e+01 2.02417278e+01 1.76768112e+01 1.13024664e+01 1.82295513e+01 1.24508352e+01 1.03295765e+01 -2.16411591e-01 2.08028650e+00 -1.77367246e+00 1.00984955e+00 -4.10353374e+00 -6.97308969e+00 -1.18081694e+01 -1.00519257e+01 -9.55738926e+00 5.20446539e+00 1.08014307e+01 1.78968525e+01 1.05037909e+01 1.61748028e+01 2.08236713e+01 3.13561611e+01 1.48615713e+01 -4.29265823e+01 -7.81502686e+01 -8.40872269e+01 -6.33628044e+01 -4.08737221e+01 -3.24687004e+01 -1.69642925e+01 -7.97806358e+00 -2.19314537e+01 -2.11530113e+01 -2.43065128e+01 -1.16048574e+01 -1.57846680e+01 -6.73455191e+00 3.97334099e+01 8.07926025e+01 1.06660080e+02 9.39984055e+01 4.87191620e+01 7.94957829e+00 -3.54886093e+01 -2.51994209e+01 -1.59694281e+01 2.44283819e+00 -6.02794945e-01 3.47993541e+00 -8.07318401e+00 -1.58218062e+00 1.23078156e+00 -1.67569682e-01 -9.45049095e+00 -8.52441597e+00 -3.70991302e+00 -1.04503942e+00 -1.63878632e+01 -2.33065205e+01 -2.64174728e+01 -2.46008835e+01 -1.83309155e+01 2.00848618e+01 6.37195702e+01 9.10269699e+01 8.86553116e+01 8.28139725e+01 8.81090546e+01 5.54411926e+01 9.33486557e+00 -3.52560921e+01 -4.41580124e+01 -3.38846092e+01 -1.95705853e+01 -1.54636936e+01 -2.46551037e+01 -4.29270782e+01 -3.33514137e+01 -2.46538048e+01 -1.14975796e+01 -1.46666965e+01 -2.05185204e+01 -5.39896088e+01 -9.60015106e+01 -7.90527267e+01 -4.72122917e+01 -3.61528659e+00 1.17292185e+01 2.95876141e+01 6.57101135e+01 9.28308029e+01 8.45033493e+01 5.55144386e+01 8.39370155e+00 2.38902931e+01 3.65119362e+01 4.28816299e+01 3.29771004e+01 2.02022572e+01 3.20480614e+01 3.68454018e+01 3.76309166e+01 2.39749393e+01 6.17811155e+00 7.66255426e+00 3.31361427e+01 7.68270340e+01 1.11415085e+02 1.30078644e+02 5.78950386e+01 -1.45091085e+01 -5.89630394e+01 -3.44523811e+01 2.93550825e+00 -9.99094427e-01 1.57266569e+01 2.83653116e+00 7.15245157e-02 -1.35526934e+01 -1.57417850e+01 -1.36491432e+01 -1.09788446e+01 -8.37767601e+00 -4.29884529e+01 -8.48065491e+01 -9.62714996e+01 -6.66981735e+01 -3.75774384e+01 -1.16002245e+01 1.19184589e+01 2.06981697e+01 1.67550755e+00 -5.01486349e+00 9.90779877e+00 1.20191660e+01 -8.72367477e+00 -3.16409512e+01 -3.53279381e+01 -3.50265236e+01 -3.31030045e+01 -2.52255993e+01 -2.06378918e+01 -9.53299141e+00 -1.87255459e+01 -2.65747890e+01 -4.14836884e+01 -4.34559097e+01 -3.65341797e+01 4.16948199e-01 4.65082970e+01 3.90257378e+01 3.92719388e+00 -3.56932831e+01 -1.71867752e+01 -9.16623402e+00 -2.59310484e+00 -3.18095565e+00 6.31353807e+00 8.09231091e+00 3.29605827e+01 4.70399513e+01 4.38144531e+01 4.04246712e+00 -3.19497910e+01 -3.09921188e+01 -2.38723640e+01 -4.04589043e+01 -7.62027817e+01 -8.29375153e+01 -7.15613556e+01 -4.18475800e+01 -4.73835030e+01 -4.76779022e+01 -4.33434753e+01 -3.71265182e+01 -2.91287708e+01 -3.49908257e+01 -4.12668953e+01 -3.75155258e+01 -3.15086708e+01 -3.46539154e+01 -4.16515427e+01 -4.06340942e+01 -3.18280926e+01 -2.40666509e+00 2.71965504e+01 2.29405842e+01 4.17905617e+00 -1.49811983e+01 -7.89835310e+00 -1.61783028e+01 -3.50807571e+01 -3.39209175e+01 6.02063227e+00 4.34588966e+01 4.77619705e+01 1.31899853e+01 -1.16331825e+01 -9.78919506e+00 -4.32867956e+00 -5.04490376e+00 -8.53150463e+00 1.40421133e+01 5.12945595e+01 5.33816719e+01 2.69723454e+01 -2.03242397e+01 -1.43034763e+01 -1.22924213e+01 -3.28170109e+00 -1.15875788e+01 -1.15114708e+01 -3.17162323e+00 9.09413052e+00 1.48173351e+01 5.46637630e+00 3.12781006e-01 -7.62280762e-01 3.18055477e+01 7.38144684e+01 8.10552444e+01 4.80172691e+01 4.81862593e+00 -6.37932348e+00 -1.44172201e+01 -1.01621132e+01 1.55593741e+00 4.06111259e+01 6.75128555e+01 9.69858170e+01 9.97249451e+01 6.44236298e+01 3.57146149e+01 -5.94058132e+00 2.16680470e+01 4.20098801e+01 1.66134872e+01 -4.32190666e+01 -7.48658066e+01 -5.00452271e+01 -1.52726641e+01 -1.94286423e+01 -1.99687634e+01 -2.59951630e+01 -2.81059952e+01 -3.35413971e+01 -3.45747833e+01 -3.69829826e+01 -4.25254097e+01 -3.97477684e+01 -3.86864929e+01 -3.77041473e+01 -4.06280823e+01 -3.77463303e+01 -2.04971638e+01 4.92445517e+00 2.75423503e+00 -2.14745312e+01 -5.33554802e+01 -2.81119709e+01 9.05647087e+00 -1.36092281e+01 -7.22997360e+01 -7.85530472e+01 -1.10026779e+01 3.62194977e+01 1.68235664e+01 -1.66155357e+01 5.59611440e-01 3.14527626e+01 3.63105392e+01 2.02162380e+01 -4.88074684e+00 -4.65964222e+00 -8.07385683e-01 -1.04589128e+01 -1.12560139e+01 -3.58947334e+01 -5.29984093e+01 -2.26871471e+01 2.39278336e+01 5.08064232e+01 2.99329853e+01 9.62246799e+00 2.75084915e+01 4.19768410e+01 4.78232117e+01 3.16183987e+01 4.28492403e+00 2.79301739e+00 3.40791798e+00 1.25653744e+01 3.43871522e+00 1.45424738e+01 3.30750694e+01 4.06783867e+01 3.44163589e+01 4.98861504e+00 -1.25325584e+01 -2.51682281e+01 -2.37535362e+01 -1.66098309e+01 -5.22021713e+01 -9.15256958e+01 -8.47702866e+01 -3.39087219e+01 4.01143980e+00 -5.08837605e+00 -2.43386135e+01 -6.10230494e+00 2.19928493e+01 2.34620628e+01 5.68574286e+00 -2.20819740e+01 -2.71483669e+01 -2.61849918e+01 -2.37284737e+01 -1.91331234e+01 -2.19945660e+01 -1.56700478e+01 -5.56546354e+00 9.43906128e-01 -7.01374578e+00 -1.85775013e+01 -2.45610790e+01 -2.90706005e+01 -2.77686348e+01 -4.86653862e+01 -6.63034821e+01 -4.95748520e+01 -2.80933428e+00 1.94559460e+01 -2.40746331e+00 -3.14529877e+01 -4.83836746e+01 -5.62661781e+01 -5.59056625e+01 -5.04475975e+01 -4.20610123e+01 -4.46515884e+01 -3.76075745e+01 -4.07904472e+01 -4.22955818e+01 -4.80352173e+01 -5.36542778e+01 -5.45433540e+01 -4.38951721e+01 -3.22506371e+01 -3.43730698e+01 -4.70711594e+01 -5.36686478e+01 -4.13875427e+01 -3.02527618e+01 -2.34433880e+01 -1.39492493e+01 5.95027637e+00 6.49982882e+00 -2.57348442e+00 -8.49670219e+00 2.33053894e+01 4.43566132e+01 2.94065361e+01 2.96067309e+00 5.75849295e+00 2.70930214e+01 3.25873299e+01 1.35714312e+01 -4.07117271e+00 -7.50464344e+00 -7.61710072e+00 -2.26164317e+00 -1.10433951e-01 -6.42743051e-01 -8.29527283e+00 -2.35843587e+00 1.42089577e+01 2.07149105e+01 1.10443020e+01 -7.83675766e+00 -5.46728373e+00 5.75176191e+00 -7.10788918e+00 -2.88759747e+01 -4.31778221e+01 -3.40916672e+01 -2.52045670e+01 -2.92002831e+01 -2.94158955e+01 -2.82717552e+01 -2.74727173e+01 -2.96935940e+01 -2.79932137e+01 -2.54073086e+01 -2.79508953e+01 -3.12022305e+01 -3.42456207e+01 -3.27570877e+01 -2.85848618e+01 -2.98109055e+01 -1.78336372e+01 -9.73954964e+00 -1.01242151e+01 -2.40522957e+01 -3.72444229e+01 -3.97160149e+01 -3.84090691e+01 -4.61997490e+01 -5.69531937e+01 -5.78050156e+01 -5.05884476e+01 -4.02013321e+01 -3.78046608e+01 -3.53539162e+01 -2.15265331e+01 -8.04987144e+00 -4.45356083e+00 -1.32670498e+01 -2.24827442e+01 -2.34108715e+01 -2.63756790e+01 -2.83733864e+01 -2.55953465e+01 -3.05312405e+01 -4.03449402e+01 -3.76173630e+01 -2.59423008e+01 -1.68632355e+01 -2.26055431e+01 -2.21302299e+01 -7.34201813e+00 2.42836356e+00 -1.39197445e+00 -1.73901215e+01 -2.20179195e+01 -1.70817795e+01 -1.52530060e+01 -2.02497787e+01 -3.03945980e+01 -2.89654655e+01 -2.37342396e+01 -2.09152050e+01 -2.39542370e+01 -3.04207535e+01 -3.41176224e+01 -3.63244858e+01 -3.62669334e+01 -3.36913109e+01 -3.36600151e+01 -3.49157906e+01 -3.04902515e+01 -2.58298206e+01 -2.31411514e+01 -2.70265503e+01 -3.07355671e+01 -2.98073158e+01 -2.60272198e+01 -2.89698830e+01 -4.63548317e+01 -5.82360573e+01 -7.67257919e+01 -7.31645508e+01 -3.32907806e+02 -5.20019348e+02 3.08823090e+02 1.61219818e+02 -2.47894379e+02 -1.19210823e+02 -2.80282745e+02 -2.28746143e+03 -2.01881866e+01 -235291968. -9.32597852e+03 2.78443069e+10 -2.51446886e+09 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. 2.45095987e+09 3.12392163e+03 9.21575562e+02 1.50072800e+02 1.18151878e+02 2.41381729e+02 1.37861237e+02 -2.01631241e+01 1.59348984e+01 2.69002171e+01 6.96721497e+01 6.49804840e+01 4.77839241e+01 1.94057312e+01 1.40688591e+01 2.47564621e+01 2.99009056e+01 5.53621063e+01 7.22340851e+01 4.75311775e+01 1.22892923e+01 -3.52356219e+00 -9.09428024e+00 -6.22231245e+00 -8.64434242e+00 -1.84333668e+01 -1.82782001e+01 -1.16679983e+01 -4.15941191e+00 -1.20271997e+01 -2.98901501e+01 -3.37360420e+01 -2.05194340e+01 -4.96627045e+00 2.24137592e+00 4.60089684e-01 5.30655098e+00 1.33604183e+01 1.79199104e+01 6.59465742e+00 -2.42548637e+01 -4.13203392e+01 -3.32776833e+01 -1.09533520e+01 3.40763235e+00 2.84741497e+00 -3.45908117e+00 -1.38092661e+01 -7.85573339e+00 -1.24274607e+01 -1.57725248e+01 -1.34286213e+01 8.12330246e+00 3.32159843e+01 3.08615627e+01 -4.27890396e+00 -2.44305439e+01 -1.64944477e+01 6.31381321e+00 4.37183523e+00 -1.47467060e+01 -1.61940289e+01 3.89658141e+00 2.61871033e+01 2.01728153e+01 -1.53242636e+01 -3.89990082e+01 -2.95965176e+01 -9.05066395e+00 -4.04387045e+00 -1.18715858e+01 -1.04013424e+01 6.95793533e+00 2.36573715e+01 1.58007545e+01 4.81744576e+00 9.09819794e+00 2.50886307e+01 3.03112354e+01 2.35450096e+01 7.22904921e+00 -9.46548843e+00 -1.59457293e+01 -4.65189409e+00 5.13483763e+00 5.74447346e+00 2.23050556e+01 5.27454147e+01 6.34700165e+01 3.40686073e+01 -1.73637581e+01 -4.32266769e+01 -2.67301350e+01 1.41115160e+01 5.61782799e+01 7.08006592e+01 6.02105980e+01 4.78785439e+01 5.21838646e+01 4.08243484e+01 1.01689875e+00 -2.83214970e+01 -1.56495247e+01 1.64777565e+01 2.87286549e+01 1.56074495e+01 -1.08996677e+01 -1.78364124e+01 1.29937196e+00 1.78724785e+01 1.22004433e+01 7.59701681e+00 3.03684864e+01 7.28901215e+01 7.90589066e+01 4.57163582e+01 8.78878784e+00 9.32928371e+00 3.49763794e+01 6.07672195e+01 6.13983536e+01 4.05078125e+01 8.89132309e+00 -2.36062193e+00 1.14117880e+01 1.34347162e+01 -8.60525227e+00 -1.51726170e+01 1.12244234e+01 4.59888077e+01 4.56818657e+01 1.33300619e+01 -7.93422270e+00 1.71124973e+01 3.30904617e+01 3.98230400e+01 1.92804604e+01 3.14035664e+01 6.41089478e+01 7.20203400e+01 3.39500465e+01 -4.15069618e+01 -7.84382706e+01 -4.73553429e+01 -2.92294860e+00 1.56354761e+01 1.24243021e-01 -1.51478548e+01 -1.07396183e+01 -1.21537590e+01 -3.40299072e+01 -6.49544830e+01 -7.84721527e+01 -3.91912804e+01 3.22812271e+01 6.96886444e+01 3.05986423e+01 -1.64459705e+01 -1.55153790e+01 9.31632042e+00 -1.19124451e+01 -6.88417511e+01 -6.16027985e+01 -8.10652351e+00 4.40988464e+01 3.21015048e+00 -8.42773132e+01 -1.31696228e+02 -9.97389526e+01 -3.85525932e+01 -6.42759705e+00 -9.57532597e+00 7.03717899e+00 1.86400394e+01 3.55438733e+00 -4.76352310e+01 -1.04993309e+02 -7.24001160e+01 -1.69069424e+01 4.02058449e+01 3.12054310e+01 1.31201351e+00 -3.80234184e+01 -5.89600945e+01 -6.21509933e+01 -7.16926270e+01 -1.01625771e+02 -7.83743286e+01 -1.89590702e+01 4.21796150e+01 1.97623444e+01 -4.31730423e+01 -9.14338074e+01 -6.59712906e+01 -1.76349106e+01 6.95872164e+00 -1.57429206e+00 1.92849064e+01 7.46933517e+01 9.83496323e+01 4.43381348e+01 -4.49954109e+01 -6.03742714e+01 -3.40991325e+01 4.04792786e+01 5.01002388e+01 4.95011406e+01 2.12561035e+01 2.35151482e+00 1.43934160e-01 -2.43616085e+01 -5.23146667e+01 -2.93591537e+01 1.86868401e+01 4.83568535e+01 4.39107437e+01 5.93705893e+00 -1.24009886e+01 -5.84504604e+00 7.06275940e-01 6.36781883e+00 -1.44782667e+01 1.83886051e+01 6.17312317e+01 8.22925186e+01 8.40292282e+01 1.38986912e+01 -2.49345036e+01 -2.63194036e+00 6.56792831e+01 7.76971817e+01 3.13523865e+01 -1.46110582e+01 -2.57779551e+00 2.88520832e+01 2.53145390e+01 -1.51426668e+01 -2.82122459e+01 2.01728344e+01 5.36403656e+01 3.18160706e+01 2.92984486e+00 3.31188126e+01 4.44491081e+01 1.83658695e+01 -9.26031494e+00 -3.16767693e+01 -4.65605736e+00 -2.94253139e+01 -3.63680801e+01 -3.42052536e+01 -5.38333588e+01 -7.99310303e+01 -1.00500587e+02 -2.90144272e+01 1.80348003e+00 7.23467541e+00 -4.60161629e+01 -2.73896027e+01 -1.76041565e+01 -3.84525795e+01 -8.00672073e+01 -9.83020172e+01 -2.16549339e+01 2.77897968e+01 4.47345161e+01 -1.88010578e+01 -3.65267029e+01 -3.54088211e+01 -1.24966946e+01 -8.19902611e+00 -5.79493294e+01 -3.91047287e+01 -1.24878483e+01 5.77686729e+01 8.11991501e+01 6.45096130e+01 7.30535221e+00 -3.72783165e+01 -2.02117026e-01 5.05965500e+01 7.29795532e+01 4.43561707e+01 7.47438507e+01 7.79761810e+01 3.56988716e+01 -3.08262234e+01 -2.84412956e+01 5.26791115e+01 8.46072540e+01 4.31708374e+01 -2.87146130e+01 -1.01983080e+01 3.20805702e+01 5.12213974e+01 3.47200851e+01 -4.92935944e+00 -1.64387875e+01 -2.99891510e+01 1.86452694e+01 5.86383476e+01 6.55177536e+01 1.78580093e+01 -8.72838020e+00 1.63351517e+01 5.62414436e+01 6.63934937e+01 8.61176529e+01 1.49769394e+02 1.84596100e+02 1.76611282e+02 1.60922668e+02 1.64136810e+02 2.00369980e+02 2.02707977e+02 1.70761414e+02 9.01780472e+01 5.84305115e+01 4.64352722e+01 6.16831398e+01 5.04960518e+01 9.76881218e+00 -2.29653435e+01 -3.95026627e+01 1.91952343e+01 4.85450706e+01 6.24105644e+01 4.19407921e+01 6.33346329e+01 8.39014206e+01 1.09279633e+02 9.49537506e+01 1.00346657e+02 1.42926208e+02 1.69576584e+02 1.45394379e+02 8.84564133e+01 8.23234177e+01 8.71888123e+01 2.57540760e+01 -2.16656933e+01 -5.67915955e+01 7.61124182e+00 1.66395702e+01 4.09200096e+01 8.18119202e+01 8.83888626e+01 4.43026886e+01 -4.50960464e+01 -6.77202148e+01 8.31303883e+00 7.07762375e+01 6.30040512e+01 2.62806034e+00 -4.55310364e+01 -8.53546715e+00 4.29579926e+01 1.01379608e+02 9.08118134e+01 3.89117088e+01 -9.71448803e+00 -6.95058289e+01 -7.17691116e+01 -7.16428833e+01 -8.49317551e+01 -8.74772644e+01 -8.74418793e+01 -2.95139837e+00 4.49005651e+00 1.00907068e+01 4.05195904e+00 -7.62891960e+00 -4.97418556e+01 -1.76980255e+02 -1.98033447e+02 -1.20999535e+02 4.14743385e+01 1.25027687e+02 3.15541019e+01 -8.49903564e+01 -1.02014053e+02 3.66540680e+01 1.73698837e+02 1.39070160e+02 9.32119465e+00 -7.24157333e+01 -6.28179359e+01 1.92923641e+01 1.30944920e+01 -4.22853699e+01 -9.23751450e+01 -9.96900864e+01 -1.60636959e+01 -8.08983231e+00 -4.71831551e+01 -9.12207184e+01 -9.47068253e+01 -4.33982773e+01 -6.15616379e+01 -6.13880615e+01 1.68772221e+01 1.18093605e+02 1.07130898e+02 -5.92125702e+01 -1.74626419e+02 -1.35496445e+02 -2.16534138e+00 6.99147644e+01 5.08616791e+01 -2.82804966e+01 -6.48727875e+01 -8.66901169e+01 -1.89601765e+01 -2.16193542e+01 -2.99585991e+01 -6.34217682e+01 -7.90999680e+01 -2.66578865e+01 2.08966312e+01 9.80563660e+01 1.02987244e+02 6.04543495e+01 -1.28797665e+01 -1.18957253e+02 -1.54170639e+02 -7.90052261e+01 8.50201111e+01 1.74717422e+02 1.00024765e+02 -7.13197403e+01 -1.24829353e+02 4.12992060e-01 1.72889832e+02 1.73960007e+02 3.28650894e+01 -5.59202347e+01 -5.79041214e+01 1.21876049e+01 2.21048431e+01 -1.85600624e+01 -7.74872894e+01 -1.32651260e+02 -1.27858772e+02 -1.61268326e+02 -1.48312592e+02 -8.81753845e+01 1.53302364e+01 5.06797867e+01 -2.37375393e+01 -9.88861694e+01 -7.47004089e+01 4.21810455e+01 1.36255447e+02 1.02647804e+02 -6.18116665e+00 -4.64376488e+01 -7.84019089e+00 7.54673767e+01 6.34049835e+01 -1.24034967e+01 -8.49300156e+01 -1.34782333e+02 -7.57694016e+01 -7.97795410e+01 -4.52449837e+01 -5.18167381e+01 -6.11037979e+01 -7.93587799e+01 -1.30711594e+02 -8.12299500e+01 -1.49297428e+01 6.64628143e+01 2.16569347e+01 -8.34235382e+01 -1.62665802e+02 -9.39998856e+01 2.54882069e+01 1.02495331e+02 9.39315720e+01 8.19127655e+00 -2.41194153e+01 -4.59081573e+01 -5.58533144e+00 -2.50757084e+01 -6.61172791e+01 -1.15727707e+02 -1.69997711e+02 -1.46872391e+02 -6.27249069e+01 1.65445595e+01 2.95719490e+01 4.54054445e-01 -3.94152184e+01 -9.95965958e+01 -1.35014847e+02 -6.24351807e+01 6.51768646e+01 1.25187187e+02 3.94236412e+01 -7.41430206e+01 -7.48710938e+01 5.15381012e+01 1.82494370e+02 1.51103683e+02 4.28959990e+00 -1.34964554e+02 -1.80675568e+02 -9.62135620e+01 -2.54086246e+01 -2.00311813e+01 -5.49832840e+01 -8.33042068e+01 -3.39987755e+01 -4.32790070e+01 -2.79816990e+01 9.34990788e+00 3.28101616e+01 3.05923843e+01 -3.52687569e+01 -3.01194534e+01 4.74730453e+01 1.37744354e+02 1.23859398e+02 -1.74335003e+01 -1.27789200e+02 -9.40852814e+01 3.05859451e+01 1.20009209e+02 1.17304703e+02 1.09201651e+01 -8.76778412e+01 -1.29051819e+02 -5.26214256e+01 2.40559578e-01 4.80476837e+01 5.24795990e+01 3.60872116e+01 3.94430389e+01 3.44132500e+01 9.97744751e+01 1.35775894e+02 1.31456100e+02 8.11812515e+01 -1.59464560e+01 -4.16201820e+01 1.02431755e+01 1.04193054e+02 1.26295296e+02 7.30373688e+01 -1.05704746e+01 -7.40975618e+00 4.99996414e+01 1.35179214e+02 1.46015396e+02 5.69636192e+01 -3.64727478e+01 -7.22677689e+01 5.71330881e+00 8.00860443e+01 7.62411575e+01 1.87463932e+01 -4.49884300e+01 -5.09326401e+01 -4.47644157e+01 -1.44404192e+01 3.89761581e+01 5.00800209e+01 1.29175615e+00 -9.66014633e+01 -1.39915909e+02 -7.75000687e+01 2.26738167e+00 6.06640549e+01 2.39330616e+01 -3.49678345e+01 -7.38329773e+01 -6.16712227e+01 -1.48492947e+01 -6.24789953e+00 -3.79490623e+01 -8.36184387e+01 -9.56939468e+01 -3.20616798e+01 2.23174152e+01 1.14526100e+01 -3.24491882e+01 -1.03463547e+02 -9.48157043e+01 -9.17239914e+01 -6.35418053e+01 -2.37295666e+01 -2.46841741e+00 5.34386110e+00 -5.70005722e+01 -9.83998718e+01 -6.74393234e+01 -1.26887646e+01 3.49326439e+01 -8.79062462e+00 -6.80670013e+01 -9.55113678e+01 -3.45146904e+01 9.26144028e+01 1.40354446e+02 7.79693985e+01 -6.71018982e+01 -1.35546631e+02 -8.23020935e+01 2.00557842e+01 6.13955307e+01 1.03238541e+02 1.88373322e+02 1.11049408e+02 -1.91495346e+02 -2.04356766e+02 1.57828766e+02 2.71481616e+03 3.49682202e+03 5.99845410e+03 1.40377344e+04 -8.38895411e+09 5.06882816e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.52564122e+09 -415164064. 2.36061445e+04 8.28300488e+03 6.68530273e+02 2.30033665e+01 3.82297119e+02 9.65521164e+01 -2.27549992e+01 3.56271411e+03 2.32470679e+03 4.48664001e+02 3.17640656e+02 -1.41280981e+03 7.85855293e+00 1.26327869e+03 -1.35734390e+02 3.41607056e+01 2.22876724e+02 2.24743652e+02 1.49263321e+02 1.56483368e+02 1.13461243e+02 5.64371147e+01 1.09333696e+01 6.40034008e+00 2.54771881e+01 -1.01738529e+01 -2.46285839e+01 2.47916851e+01 6.61386795e+01 2.92731018e+01 -6.97514267e+01 -1.24589676e+02 -6.05259781e+01 1.72700157e+01 6.34044075e+01 3.57345428e+01 -4.69033241e+01 -1.13576607e+02 -1.37731232e+02 -7.38092041e+01 -2.46586781e+01 -1.95019665e+01 -6.61376419e+01 -9.37539673e+01 -6.64456482e+01 -5.61747093e+01 -2.94611397e+01 -1.52459157e+00 1.25451775e+01 -1.62055626e+01 -9.57886810e+01 -1.04155396e+02 -3.60734329e+01 4.55183907e+01 6.61576080e+01 -1.33096948e-01 -6.31806946e+01 -6.02757988e+01 -1.24241095e+01 9.39440727e+00 -4.14482498e+01 -1.09432915e+02 -1.26716301e+02 -9.22943344e+01 -1.82771549e+01 3.21804504e+01 2.88527660e+01 -1.67896576e+01 -7.57598267e+01 -1.13686798e+02 -1.31624954e+02 -1.16927490e+02 -7.77707825e+01 -4.15515213e+01 -2.34971409e+01 -4.01314964e+01 -3.19851856e+01 9.77819443e+00 5.11462708e+01 4.89037666e+01 -1.52086413e+00 -4.26777191e+01 -3.16646843e+01 -7.93054867e+00 2.92284031e+01 4.77255287e+01 2.68125381e+01 -2.40798416e+01 -5.30783882e+01 -2.40464134e+01 1.20146532e+01 5.43590879e+00 -9.15852356e+00 -1.79497948e+01 -3.18030906e+00 -1.80035172e+01 -1.52021227e+01 2.47737908e+00 1.52549400e+01 4.89540577e-01 -5.01232605e+01 -5.75841026e+01 -8.21909904e+00 5.36708565e+01 7.99379349e+01 3.77398224e+01 -6.83441067e+00 -2.61415348e+01 -1.52245874e+01 6.66732788e-01 4.69579130e-01 -1.21202850e+01 -3.76691093e+01 -5.00128174e+01 -2.39638424e+01 2.20737095e+01 3.48417358e+01 1.64367390e+01 -9.28435445e-01 -2.49817157e+00 -1.69978676e+01 -1.39433270e+01 1.73972359e+01 5.67760544e+01 5.21493034e+01 2.76277852e+00 -2.10699596e+01 7.96285629e+00 4.82185097e+01 5.49785194e+01 1.63704967e+01 -2.11466084e+01 -2.98211861e+01 -1.67087116e+01 1.30216646e+01 3.58090134e+01 2.91698818e+01 -1.51409793e+00 -2.47878571e+01 -6.44692135e+00 2.44192257e+01 3.52041435e+01 2.57522984e+01 1.09213171e+01 1.37886560e+00 -1.67578182e+01 -2.41596756e+01 -1.52659616e+01 -1.21416128e+00 2.34252095e+00 -1.73006115e+01 -2.59865913e+01 -1.00433769e+01 2.61393738e+01 4.94955597e+01 3.90625381e+01 6.06869221e+00 -1.87015476e+01 -1.61120949e+01 2.03431576e-01 6.58862352e+00 6.02642596e-01 -2.40368652e+00 -1.19535198e+01 -7.46516418e+00 -5.01852226e+00 5.45977736e+00 1.81648750e+01 2.54147377e+01 2.77841835e+01 1.06532497e+01 2.32107544e+00 1.22000570e+01 2.27369194e+01 1.64988785e+01 -5.41885233e+00 -1.67082214e+01 -8.15694237e+00 8.12368572e-01 7.88998699e+00 6.42712879e+00 1.21220732e+00 -2.00449896e+00 -3.29838085e+00 6.74847555e+00 5.31221390e+00 -8.84097099e-01 -1.00864010e+01 -1.96631393e+01 -2.41756802e+01 -2.85071678e+01 -1.88015060e+01 -4.48642445e+00 2.61956072e+00 2.76956129e+00 -4.73353100e+00 -4.59391499e+00 1.52695787e+00 9.50436306e+00 1.32142658e+01 3.68824315e+00 -7.33476353e+00 -1.31399288e+01 -9.76706028e+00 -4.77424145e+00 -2.93014932e+00 -3.19536853e+00 -4.34543562e+00 -6.05841780e+00 -3.85425162e+00 -5.89072764e-01 1.63301325e+00 -3.42138529e-01 -1.15370274e+00 -1.74828970e+00 -2.52447724e+00 -2.73089600e+00 -1.53684568e+00 -4.94293451e-01 -4.73304152e-01 -4.25212502e-01 9.46048647e-02 4.92295682e-01 3.76624346e-01 -1.78927705e-02 -1.83704004e-01 -5.21617420e-02 7.39968121e-01 1.06457949e+00 4.86895770e-01 -1.13729072e+00 -1.74382699e+00 -4.12635148e-01 7.20439076e-01 5.10382295e-01 2.71132439e-01 3.52123231e-01 -1.72454804e-01 -3.97576511e-01 -4.05336112e-01 1.75018102e-01 2.74097323e-01 -4.47656721e-01 -1.21792173e+00 -2.79756951e+00 -2.73978925e+00 -2.49425197e+00 -6.50264800e-01 -1.98519433e+00 -3.05969501e+00 -2.85718775e+00 -6.23618662e-01 3.11088967e+00 5.25592947e+00 4.48853636e+00 3.02267647e+00 -5.26686966e-01 9.95643616e-01 6.43008173e-01 7.87784338e-01 -1.85900366e+00 -2.28396463e+00 -1.75712895e+00 2.81900942e-01 -1.84703135e+00 -2.20960474e+00 -3.24498725e+00 -1.80926430e+00 -3.84971547e+00 -4.20612955e+00 -6.61092997e+00 -8.34465313e+00 -8.35509396e+00 -5.42613697e+00 -1.68410814e+00 -1.64235151e+00 -3.46092391e+00 -7.45491314e+00 -6.61963129e+00 -5.53652048e+00 -3.94845128e-01 2.03623819e+00 -1.83873379e+00 -4.99522448e+00 -4.60565901e+00 1.11806774e+00 1.45948565e+00 -8.93967688e-01 1.02516818e+00 1.37119329e+00 -2.06146479e+00 -5.67684269e+00 -2.48402023e+00 1.12122148e-01 -4.43731403e+00 -3.86833501e+00 1.71568835e+00 9.57382774e+00 7.15603542e+00 5.91794109e+00 5.99882269e+00 5.99032879e+00 7.57727957e+00 6.95368814e+00 7.97856712e+00 2.68561864e+00 2.06920815e+00 4.99379635e+00 4.05995035e+00 1.32991922e+00 -3.05159473e+00 -7.41253734e-01 -9.06726170e+00 -1.83775234e+01 -1.57657337e+01 -7.87216330e+00 2.67736268e+00 2.26746488e+00 1.90227437e+00 6.92999601e-01 -3.15873885e+00 2.10052299e+00 4.77347326e+00 7.65382481e+00 6.26374197e+00 1.21313248e+01 1.23902225e+01 5.44602489e+00 1.99816799e+00 1.06229246e+00 2.46486759e+00 -7.64865637e-01 1.70856094e+00 7.20224285e+00 7.78783083e+00 1.33340235e+01 1.31903830e+01 9.63714504e+00 1.23029673e+00 -6.54712296e+00 -4.28008509e+00 -1.04018998e+00 7.19247198e+00 1.05215969e+01 1.04086554e+00 -4.78826523e+00 -2.81658101e+00 6.95940590e+00 9.96997356e+00 5.38690424e+00 -2.54808009e-01 -5.09532785e+00 -6.09516740e-01 -1.70124745e+00 -4.45059061e+00 -1.81260586e+01 -1.53368902e+01 -1.19581642e+01 -1.13703573e+00 -2.82407570e+00 -3.44846177e+00 -4.53771830e+00 3.81289768e+00 -1.69674575e+00 -8.06966209e+00 -1.46599302e+01 -8.18637180e+00 -2.52128392e-01 -2.19752407e+00 -1.66117249e+01 -3.78160019e+01 -3.33705978e+01 -1.68335209e+01 5.59388304e+00 -9.34107590e+00 -2.55601921e+01 -3.19439468e+01 -1.91878109e+01 -3.21499610e+00 -6.85587263e+00 -2.03520355e+01 -2.85956631e+01 -2.87053699e+01 -2.28626385e+01 -2.78879623e+01 -3.86207657e+01 -4.26326141e+01 -2.96900520e+01 -1.00049658e+01 -3.31550527e+00 -1.33612013e+01 -1.91811562e+01 -1.19058647e+01 -2.00626826e+00 -5.74465930e-01 -2.40991459e+01 -4.26529922e+01 -4.26013412e+01 -2.19750652e+01 1.64005868e-02 4.44089234e-01 -6.93729162e+00 -4.27647924e+00 1.33890371e+01 4.21459923e+01 3.98317566e+01 1.81226387e+01 -4.27507782e+00 -8.62762833e+00 -1.02871952e+01 -2.74808025e+01 -3.54180527e+01 7.22908080e-01 4.17951813e+01 4.80822525e+01 1.54671774e+01 -1.44631062e+01 -1.00946722e+01 -5.20229387e+00 1.50638990e+01 2.96531410e+01 2.38341541e+01 1.66205490e+00 -2.43566074e+01 -2.37275066e+01 -3.10442238e+01 -3.73421133e-01 3.59691620e+01 4.46666603e+01 2.30445442e+01 -1.11541214e+01 -3.53228645e+01 -5.24024544e+01 -5.66259575e+01 -2.90444546e+01 -1.41574163e+01 -9.03920472e-01 1.87690049e-01 -4.40861955e-02 8.77322865e+00 1.10437613e+01 9.90914631e+00 8.82711124e+00 1.27237642e+00 -3.84166794e+01 -1.44025665e+02 -2.49853210e+02 -2.41952469e+02 -2.34638580e+02 -1.99455750e+02 -3.72797302e+02 -1.84015106e+02 -2.01933842e+01 5.36335632e+02 -2.37358740e+03 -5.27603027e+02 -3.51101343e+03 -4.60387734e+04 -415372064. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1442105088. 1442105088. -694983616. -3.84125430e+04 -1.12075137e+04 -1.33510620e+03 -9.87401428e+02 -2.86893188e+02 -2.03578461e+02 -1.72294220e+02 -1.69675339e+02 -7.18097458e+01 3.72853928e+01 9.98049927e+01 4.73974991e+01 -2.01897907e+01 -1.68792760e+00 -8.96152592e+00 -4.55325928e+03 -3.16192700e+03 -7.20650330e+02 -2.98135559e+02 -1.96619064e+02 -1.56039856e+02 -1.33708633e+02 -1.00234138e+02 -3.59595604e+01 -2.20982838e+01 -1.02331781e+00 -1.28426182e+00 1.74613075e+01 2.07517128e+01 3.52683029e+01 4.13163719e+01 4.50266342e+01 4.79689522e+01 4.01051369e+01 4.27505455e+01 4.76121559e+01 5.98157005e+01 7.30745239e+01 6.08570786e+01 4.13364639e+01 3.29216270e+01 3.61564903e+01 4.72090111e+01 5.42949867e+01 6.31682510e+01 5.44839859e+01 1.63904324e+01 -2.36206303e+01 -2.81537170e+01 -1.01931057e+01 6.60774374e+00 1.10073709e+01 2.67116795e+01 2.73464069e+01 1.73039970e+01 1.19873114e+01 1.90759010e+01 2.87389793e+01 3.42684746e+01 5.83244781e+01 3.75581398e+01 1.60253925e+01 -6.88198996e+00 -1.69511185e+01 -2.88581314e+01 -3.75344658e+01 -2.06624737e+01 -6.53357077e+00 -4.82016897e+00 7.19039679e+00 4.10951424e+01 5.26245155e+01 4.25080948e+01 1.45755119e+01 4.40809727e+00 3.71195316e+00 -2.56150074e+01 -6.25916862e+01 -5.93684158e+01 -3.94387474e+01 -1.62501507e+01 -6.79846802e+01 -1.09647766e+02 -1.08475502e+02 -7.19640427e+01 -4.57245522e+01 -5.49718475e+01 -6.09689255e+01 -5.14660187e+01 -5.54138565e+01 -7.92437668e+01 -1.07566887e+02 -9.62959137e+01 -4.62721977e+01 -2.74100304e+00 1.69958191e+01 6.40345144e+00 -4.66825628e+00 -2.12246132e+01 5.26856184e+00 3.69615555e+01 2.03577328e+01 -2.02521572e+01 -3.49885025e+01 -1.51572955e+00 2.38270130e+01 -2.62576847e+01 -6.11677818e+01 -5.97189598e+01 -5.05412340e+00 4.35225105e+01 5.27864990e+01 4.47058830e+01 3.01787395e+01 2.29755325e+01 1.29896774e+01 7.47509098e+00 1.52531128e+01 1.41337194e+01 1.07363176e+00 -1.29710159e+01 -5.18157911e+00 4.93495321e+00 9.43658733e+00 5.89678717e+00 4.22209501e+00 -3.88442688e+01 -8.24403610e+01 -7.73896408e+01 -3.40767670e+01 6.62746763e+00 -3.68479004e+01 -7.81023865e+01 -8.26955872e+01 -4.90363083e+01 -1.80009651e+01 -1.58148575e+01 -1.12367802e+01 4.22035599e+00 -6.53895140e+00 -1.04979668e+01 -1.46315222e+01 5.60215664e+00 2.26338272e+01 1.54708586e+01 1.54712892e+00 -1.03292656e+01 -7.56790113e+00 -5.71500921e+00 -1.03816376e+01 -2.77637405e+01 -6.85489349e+01 -1.15973190e+02 -1.13366402e+02 -8.10598679e+01 -3.17859497e+01 -6.66377869e+01 -1.06821426e+02 -1.08727493e+02 -4.88218727e+01 -6.63772523e-01 -8.69024467e+00 -2.46443672e+01 -3.49999962e+01 -2.65818977e+01 -2.57970181e+01 -2.37298698e+01 -1.21039200e+01 -9.98850727e+00 -3.34457436e+01 -7.17392197e+01 -6.94233170e+01 -4.10651474e+01 -4.78653336e+00 4.00737476e+00 2.52514791e+00 -2.96555004e+01 -6.42856522e+01 -6.06902962e+01 -3.51583138e+01 -1.76278400e+01 -1.97195911e+01 -3.67804885e+00 -2.45922985e+01 -6.89048920e+01 -8.62704468e+01 -5.95143051e+01 -1.78550911e+01 -1.31694784e+01 -1.73820515e+01 -1.40192165e+01 -1.20945816e+01 -2.26753216e+01 -2.58609734e+01 -7.25157928e+01 -1.08463737e+02 -1.03798309e+02 -5.73684387e+01 -1.95943604e+01 -3.74711761e+01 -3.72596893e+01 -7.06600952e+01 -1.00784615e+02 -9.52895432e+01 -4.22345963e+01 8.06468487e+00 -6.38480997e+00 -1.83466587e+01 -2.60776958e+01 -1.23376226e+01 2.98035812e+00 9.01012230e+00 1.15190468e+01 5.10586691e+00 1.57925856e+00 6.27418137e+00 4.01686049e+00 3.24038620e+01 4.80547447e+01 6.05471916e+01 5.34781799e+01 3.70331268e+01 3.20897636e+01 3.05304413e+01 3.33020592e+01 3.30132713e+01 2.57971592e+01 3.48391533e+01 2.88467293e+01 2.28029842e+01 2.26702156e+01 4.13787117e+01 4.62441978e+01 3.49125519e+01 2.09595833e+01 2.04151573e+01 2.53607445e+01 1.32806444e+01 1.27059622e+01 -4.42919445e+00 -5.63127708e+00 -5.46438122e+00 1.95925350e+01 4.92368736e+01 2.57289715e+01 -2.93155899e+01 -6.43160400e+01 -5.15600243e+01 -2.31939831e+01 -1.46851501e+01 -1.97477665e+01 -2.38254528e+01 -3.63946838e+01 -3.83549843e+01 -3.18241329e+01 -2.34936008e+01 -1.07100325e+01 -4.58247773e-02 8.23968601e+00 -2.42990837e-01 -1.38045378e+01 -2.07975330e+01 -1.82468414e+01 -1.45963564e+01 -1.71026478e+01 -6.67639637e+00 -6.32400703e+00 4.72471535e-01 -1.26081114e+01 -4.32868805e+01 -7.74662628e+01 -7.89475098e+01 -5.61829987e+01 -2.28105183e+01 -1.23996153e+01 -6.15151024e+00 -2.90065269e+01 -5.03005981e+01 -6.20516243e+01 -6.49850159e+01 -4.12664413e+01 -2.07455521e+01 9.28434658e+00 -3.56375217e-01 -1.13468819e+01 -1.34800415e+01 -6.83565378e+00 3.73813105e+00 8.90999985e+00 -6.85511947e-01 -2.29976749e+01 -3.38215561e+01 -3.57824287e+01 -2.97887287e+01 -5.90297737e+01 -8.68117065e+01 -7.28873291e+01 -3.48441505e+01 -3.74792290e+00 -2.52326469e+01 -3.67195625e+01 -3.26309395e+01 -2.54191971e+01 -4.80940590e+01 -7.86989899e+01 -7.39743958e+01 -3.20032463e+01 1.03602896e+01 1.39808512e+00 -1.68726940e+01 -1.89270229e+01 -1.25848579e+00 5.20189238e+00 1.03058958e+00 -1.60681610e+01 -5.06911278e+00 1.27803040e+01 1.88516235e+01 1.39407864e+01 7.71948671e+00 1.86882668e+01 -9.77717686e+00 -4.23659363e+01 -4.59078789e+01 -5.39415054e+01 -7.23318481e+01 -1.04523819e+02 -1.06166588e+02 -8.76531219e+01 -9.07661972e+01 -6.81125259e+01 -6.44815292e+01 -3.31275482e+01 -2.27051735e+00 3.59386864e+01 4.45506516e+01 3.18695965e+01 2.48805180e+01 1.60253601e+01 1.62224865e+01 1.43191929e+01 1.94951859e+01 2.40317383e+01 -3.82961297e+00 -4.60707932e+01 -6.11877136e+01 -4.72549133e+01 -1.80092621e+01 -8.54739952e+00 -4.18670273e+00 1.01608019e+01 -6.35678005e+00 -8.43859005e+00 -2.03700294e+01 -2.46877079e+01 -4.53462372e+01 -7.39743729e+01 -5.42505302e+01 -2.35979557e+01 -1.33879919e+01 -4.81146049e+01 -5.73508110e+01 -4.07834206e+01 -4.25804615e+00 -2.99110508e+01 -5.62992249e+01 -7.18704071e+01 -4.91419373e+01 -2.62045250e+01 -5.43319778e+01 -7.68655396e+01 -6.67353897e+01 -2.17497196e+01 5.37467146e+00 -2.14877148e+01 -3.64239426e+01 -8.97903538e+00 2.83598175e+01 4.65694189e-01 -5.24810944e+01 -7.18257980e+01 -5.47906952e+01 -3.23256302e+01 -3.70691071e+01 -6.30629883e+01 -9.07653046e+01 -8.10734940e+01 -3.66029320e+01 2.26383567e+00 4.33180141e+00 -4.15137100e+00 -1.07425709e+01 -9.99762535e+00 -1.18758345e+01 -1.58950157e+01 -3.28498001e+01 -3.54691505e+01 -1.54408407e+01 -4.55243969e+00 2.39471102e+00 -2.70790386e+01 -3.93617783e+01 -3.37419968e+01 -2.20545654e+01 -4.45479345e+00 -7.94274616e+00 -2.99762559e+00 7.65950012e+00 1.62048569e+01 1.20719852e+01 -3.51230278e+01 -7.01648483e+01 -3.26095581e+01 3.13147659e+01 3.80222740e+01 -1.79898930e+01 -3.91256294e+01 -9.71058750e+00 4.57002783e+00 -1.64212704e+01 -2.78305302e+01 -2.04848194e+01 -4.79461461e-01 -1.18001137e+01 -2.12705975e+01 -2.84049072e+01 -1.85589828e+01 -2.53283882e+00 -2.21968579e+00 -2.37207413e+00 -2.02137203e+01 -3.57971573e+01 -3.82342339e+01 -1.52145805e+01 -1.37782183e+01 -6.32704735e+01 -9.25916901e+01 -8.11791458e+01 -3.27665596e+01 -2.90855007e+01 -4.24543648e+01 -2.67192116e+01 1.24117317e+01 2.35849247e+01 -1.15786684e+00 -2.36928864e+01 -1.69917927e+01 -7.43590021e+00 -2.00291252e+01 -2.63756580e+01 -2.69813480e+01 -1.89396057e+01 -1.70763803e+00 9.17141342e+00 1.45577602e+01 4.10932732e+00 -4.27293158e+00 -1.66114330e+01 -2.16745491e+01 -3.05318851e+01 -3.95702934e+01 -3.90392036e+01 -2.43180218e+01 -5.47273684e+00 -9.46999168e+00 -2.98664703e+01 -3.52828560e+01 -3.17392082e+01 -4.03034668e+01 -7.30768433e+01 -9.27648697e+01 -7.77736130e+01 -3.97398338e+01 -2.82039814e+01 -3.43844948e+01 -3.62791824e+01 -2.21575642e+01 -1.17884550e+01 -5.25613880e+00 1.67489827e+00 1.09055316e+00 -8.33060265e+00 -1.05621500e+01 5.57093906e+00 7.75601101e+00 -1.69765701e+01 -3.22547798e+01 -1.99797516e+01 -6.29969883e+00 -2.88310013e+01 -4.39303665e+01 -2.38732738e+01 1.09036341e+01 3.36816864e+01 3.17990379e+01 2.97121964e+01 2.16310425e+01 1.83242397e+01 1.40252171e+01 1.72889671e+01 8.10544586e+00 -1.45638347e-01 1.19858384e+00 1.60425358e+01 9.34111500e+00 -2.49157028e+01 -4.40056877e+01 -4.74689026e+01 -3.83874512e+01 -2.91898994e+01 -1.52143955e+01 -2.34292006e+00 2.86570370e-01 2.81728911e+00 3.26395345e+00 9.61832285e-01 -3.86332941e+00 -2.50787640e+00 -5.78052950e+00 -6.09586525e+00 -1.79531598e+00 1.38678059e-01 4.08441015e-03 -1.76056271e+01 -3.34068069e+01 -3.37140961e+01 -1.96280270e+01 -7.14892483e+00 -8.11134434e+00 -8.66113663e+00 -9.14394760e+00 -5.05102062e+00 -6.82891417e+00 -7.71918774e+00 -1.92828674e+01 -2.87272205e+01 -2.48670387e+01 -1.18553724e+01 -7.58303213e+00 -2.78251648e+01 -4.10673485e+01 -3.30174217e+01 -1.15451536e+01 -9.89893436e+00 -1.78787270e+01 -1.70740566e+01 -8.08762932e+00 3.38363588e-01 -1.01597118e+01 -1.81915989e+01 -2.63988190e+01 -2.94809151e+01 -2.05719719e+01 -9.97389317e+00 -9.44557762e+00 -2.84124374e+01 -3.80946312e+01 -2.44701843e+01 -5.91710472e+00 -7.69188929e+00 -2.10529900e+01 -2.50935993e+01 -1.85048428e+01 -1.02302036e+01 -1.35497093e+01 -1.81041584e+01 -2.05857906e+01 -1.58268700e+01 -1.07103300e+01 -7.46539211e+00 -1.46577463e+01 -2.24143753e+01 -2.25254383e+01 -1.62122002e+01 -4.69423008e+00 -9.73745823e+00 -1.48031549e+01 -1.67058983e+01 -1.10415154e+01 -9.29584026e+00 -1.45465202e+01 -1.35943060e+01 -7.82220840e+00 -1.30738533e+00 9.32699621e-01 1.72870278e+00 -2.55945230e+00 -9.02153778e+00 -1.13621416e+01 -8.16000175e+00 -3.32818341e+00 -1.43034995e+00 -1.33727062e+00 -7.14432859e+00 -3.03576698e+01 -4.91474648e+01 -5.96623764e+01 -4.53206635e+01 -4.50658386e+02 -1.28890173e+03 1.37678735e+03 4.05575867e+02 -6.32332336e+02 -2.66430725e+02 -3.06222717e+02 -8.02185742e+03 3.20020429e+09 -4.62466458e+09 -4.62466458e+09 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. 2.45095987e+09 3.12392163e+03 9.21575562e+02 1.50072800e+02 1.18151878e+02 -2.76845459e+02 -2.16643173e+02 -3.68128395e+01 -9.92798710e+00 2.53639412e+01 3.68342285e+01 3.76195641e+01 3.09699459e+01 2.86441193e+01 3.16542492e+01 2.78784828e+01 1.88178997e+01 1.26704054e+01 2.09359684e+01 3.79439888e+01 4.57217598e+01 4.07494774e+01 2.99157066e+01 2.43250065e+01 2.70093479e+01 2.96500111e+01 2.57549820e+01 1.88565636e+01 2.28628960e+01 3.27473145e+01 3.74489098e+01 3.33173485e+01 2.30744057e+01 2.02505875e+01 2.75806561e+01 4.08038216e+01 4.80679855e+01 4.14373779e+01 4.29373245e+01 5.16785164e+01 4.63423233e+01 2.60543861e+01 1.03866014e+01 2.47911510e+01 5.87134247e+01 6.84261322e+01 5.45718002e+01 3.57112846e+01 2.70862789e+01 2.60249844e+01 3.07303143e+01 3.07880440e+01 2.90811653e+01 3.24938393e+01 5.99514656e+01 7.63333054e+01 6.84973602e+01 4.09556694e+01 2.41811829e+01 3.60810051e+01 5.58330154e+01 6.54976807e+01 4.76616974e+01 4.28959885e+01 4.99921570e+01 4.44902611e+01 2.34012089e+01 1.35390425e+00 3.35384369e+00 3.58243752e+01 4.73486252e+01 3.96284943e+01 1.40294552e+01 2.00639668e+01 3.91034431e+01 3.48599968e+01 1.72390156e+01 6.35476828e+00 2.13809853e+01 5.44503174e+01 7.04610062e+01 6.10097160e+01 2.74788723e+01 6.03019428e+00 1.07739735e+01 2.47671967e+01 1.98459187e+01 4.25949287e+00 9.23494816e+00 3.54410744e+01 4.68897247e+01 2.21042309e+01 -1.25374060e+01 -1.62950630e+01 2.02809334e+01 5.14990387e+01 5.22416916e+01 2.57494812e+01 2.25190239e+01 3.12731209e+01 1.41750422e+01 -2.41053524e+01 -4.50043907e+01 -1.20735540e+01 4.04299011e+01 6.93207626e+01 5.47094498e+01 2.24536133e+01 -1.36790714e+01 -3.71753387e+01 -3.15506115e+01 -2.41008701e+01 -2.42390213e+01 -1.57915878e+01 1.95986328e+01 5.20712013e+01 3.50396500e+01 -1.52698565e+01 -4.24150581e+01 -2.27375317e+01 2.99071445e+01 5.77884445e+01 3.70826530e+01 1.19609823e+01 5.27222776e+00 8.95316410e+00 -1.48721085e+01 -6.07035599e+01 -6.07021599e+01 -1.40720205e+01 3.52373772e+01 3.54298668e+01 3.43417835e+00 -2.35580616e+01 -2.92577724e+01 -1.35239391e+01 8.50015831e+00 1.95123997e+01 -1.19200888e+01 -2.68893833e+01 -4.42152452e+00 2.07710152e+01 2.75026093e+01 1.65234356e+01 1.60882854e+01 3.61803207e+01 3.14020748e+01 1.55522451e+01 -9.27372837e+00 -1.50167036e+01 1.09468250e+01 2.60748959e+01 1.45652905e+01 -1.00013571e+01 7.18116283e+00 7.89173889e+01 1.09805450e+02 5.95221405e+01 -1.14691954e+01 -1.63189220e+01 2.10344391e+01 4.75606689e+01 3.98506775e+01 3.95205078e+01 6.27517433e+01 9.45837631e+01 1.07043358e+02 8.91477661e+01 4.24569397e+01 7.70699310e+00 3.80900650e+01 5.85281944e+01 5.04928246e+01 1.56183853e+01 3.18152695e+01 9.52706299e+01 9.04744110e+01 6.31928864e+01 2.65688591e+01 6.48582993e+01 1.43990662e+02 1.83089157e+02 1.48263733e+02 6.39294243e+01 2.19510231e+01 2.31635056e+01 1.87405586e+01 5.46393573e-01 1.36356411e+01 6.56968002e+01 1.22591751e+02 1.12890785e+02 6.41601257e+01 -2.49503765e+01 -5.26270180e+01 -3.25353737e+01 2.97794552e+01 6.72774353e+01 7.13125458e+01 9.24892731e+01 1.19247749e+02 1.00055557e+02 3.28352394e+01 -1.77304535e+01 1.80877476e+01 1.03754448e+02 1.43341995e+02 9.31294403e+01 4.88901043e+00 -3.26166306e+01 1.28662691e+01 5.93389130e+01 3.58040695e+01 -1.05106812e+01 9.03052151e-01 5.29140129e+01 6.84715805e+01 1.58723259e+01 -5.96980133e+01 -6.88643188e+01 -2.95637817e+01 1.54941301e+01 1.27516937e+01 -8.07465267e+00 -4.37676525e+00 2.16644535e+01 5.35428905e+00 -3.41561737e+01 -4.41662636e+01 -3.96722870e+01 7.10156965e+00 1.69601078e+01 3.80041957e+00 7.47837782e-01 -3.06084841e-01 3.87160721e+01 4.90667963e+00 -3.08051128e+01 -5.66830254e+01 -3.52893333e+01 5.44583778e+01 1.03926285e+02 9.56963272e+01 -1.19607143e+01 -6.37541237e+01 -6.89403534e+01 -2.57951298e+01 -2.17847013e+00 -3.38444061e+01 -3.06174297e+01 5.55752420e+00 3.04331913e+01 -7.97527075e+00 -3.66650696e+01 1.94076366e+01 1.03674431e+02 8.64650345e+01 4.05689545e+01 1.29375553e+01 3.81333389e+01 9.72881851e+01 4.37933121e+01 8.49127865e+00 -3.41304588e+01 -6.52228785e+00 5.90359001e+01 8.64820938e+01 1.09627258e+02 4.88653717e+01 2.54154224e+01 1.20857706e+01 5.89716148e+01 5.98247299e+01 5.74248848e+01 6.00782127e+01 9.24017487e+01 1.14139580e+02 4.91429977e+01 7.31136751e+00 -1.50465310e+00 5.74934158e+01 4.59892006e+01 2.34476128e+01 -5.92006779e+00 -2.25428028e+01 -8.66322899e+00 -1.70929203e+01 4.22977715e+01 6.67205658e+01 8.47037811e+01 7.09417038e+01 5.30220833e+01 2.69876747e+01 -4.13601799e+01 -6.94092789e+01 -4.38154793e+01 5.39886398e+01 7.17487793e+01 5.11009865e+01 3.12868843e+01 3.94721107e+01 1.26999283e+01 -8.01341476e+01 -1.17139877e+02 -7.96622772e+01 2.66179886e+01 5.04861526e+01 1.53766031e+01 -4.27050171e+01 -5.65942154e+01 -5.86600828e+00 -1.15028596e+00 1.43822060e+01 -4.23484573e+01 -7.09865570e+01 -6.82042694e+01 -1.37694254e+01 1.58268175e+01 -3.17589760e+01 -8.59502258e+01 -5.98467903e+01 9.57454109e+00 -5.04029655e+00 -5.05144234e+01 -6.21336555e+01 -2.48641930e+01 -2.73222427e+01 -8.65429840e+01 -1.15040459e+02 -7.78777847e+01 -7.27199125e+00 -3.36996126e+00 -3.11639748e+01 -6.27632294e+01 -4.76373329e+01 -2.24867306e+01 -2.50432987e+01 -1.65884895e+01 -5.73263130e+01 -7.79258881e+01 -8.70191422e+01 -5.23825951e+01 -4.08311653e+01 -7.21566696e+01 -1.04492340e+02 -6.84216385e+01 2.73617816e+00 2.13012924e+01 1.30380335e+01 2.86055527e+01 8.45347214e+01 6.84243011e+01 8.18586254e+00 -9.61797535e-01 3.73204498e+01 9.88009109e+01 3.26459961e+01 -5.16446733e+00 -4.16496315e+01 -7.75476379e+01 -9.03037720e+01 -5.66983757e+01 4.57092171e+01 7.19384842e+01 -2.67143655e+00 -6.41682053e+01 -2.68426952e+01 6.59425049e+01 1.17082092e+02 5.87546844e+01 1.28291626e+01 2.06984043e+01 5.10489082e+01 9.36649628e+01 1.35916092e+02 2.11033051e+02 1.83739594e+02 1.15966461e+02 8.98353043e+01 1.24887161e+02 1.68067291e+02 8.19231873e+01 3.50739708e+01 -1.13322115e+00 1.22607775e+01 3.16635742e+01 8.12871170e+01 1.95143829e+02 2.11129120e+02 1.11304695e+02 -5.49997253e+01 -9.43666534e+01 4.64975586e+01 1.62897064e+02 1.65451675e+02 7.53971481e+01 2.80229015e+01 5.39001808e+01 1.32193069e+02 1.76676498e+02 1.36604507e+02 1.59980841e+01 -2.50917149e+01 2.96519909e+01 1.11295456e+02 2.18622879e+02 2.15522812e+02 1.77634232e+02 6.02621803e+01 -5.11694908e+01 -9.79596176e+01 -3.11265945e+01 1.14381340e+02 1.94235489e+02 1.21319023e+02 1.10336723e+01 1.84882698e+01 1.39555573e+02 2.56016327e+02 2.04790146e+02 6.68548813e+01 -3.79640656e+01 -4.42949677e+01 4.50664253e+01 1.11069862e+02 1.65710632e+02 9.12787170e+01 4.71296577e+01 8.75122547e+00 5.71164780e+01 9.56681442e+01 4.45597610e+01 -1.10230513e+01 -9.83009796e+01 -1.02038857e+02 -6.15906334e+01 1.87426510e+01 1.29286774e+02 1.50063004e+02 7.64926834e+01 -7.91105347e+01 -1.55314392e+02 -8.76225204e+01 6.93012848e+01 1.55194519e+02 1.18807190e+02 4.78924255e+01 4.64112968e+01 9.80863724e+01 1.29103592e+02 1.36859421e+02 5.40163956e+01 -9.46014214e+00 -6.17160683e+01 -5.92791023e+01 -2.44042740e+01 1.90937881e+01 7.82399292e+01 7.54546738e+01 1.60472088e+01 -4.75104599e+01 -5.08249741e+01 1.91632481e+01 9.87312469e+01 6.48892212e+01 -6.04494047e+00 -4.71961784e+01 1.04750404e+01 1.13904488e+02 1.07654686e+02 4.67251740e+01 -6.30468483e+01 -5.80526237e+01 2.16525669e+01 8.72910919e+01 1.36460037e+02 4.64684219e+01 1.14408522e+01 -2.91687393e+01 -3.49900513e+01 -3.93596039e+01 -4.60733223e+01 -3.23888922e+00 -2.84270668e+01 -7.02075272e+01 -7.02399063e+01 -1.30913448e+01 7.87615738e+01 1.31895096e+02 7.44112930e+01 -5.77065086e+01 -1.70910873e+02 -1.49759598e+02 -9.44208145e+00 1.19298401e+02 1.60692627e+02 5.81866760e+01 -5.39481239e+01 -7.33365021e+01 1.40302181e-01 8.59394684e+01 5.26342316e+01 -8.01708317e+00 -5.53869896e+01 -6.30023270e+01 -4.63700562e+01 -2.85096908e+00 6.03944168e+01 4.96793594e+01 -1.82205582e+01 -1.14590828e+02 -1.28055252e+02 -5.14318657e+01 4.75464897e+01 3.63722725e+01 -4.19989395e+01 -9.35208130e+01 -5.09244423e+01 -4.13051128e+00 1.85381260e+01 2.77977333e+01 -9.62172604e+00 -3.60330963e+01 -1.04458084e+01 1.44112406e+01 5.15610313e+01 -4.66745675e-01 -4.01501350e+01 -9.78767166e+01 -1.30177612e+02 -8.74430542e+01 -3.95550346e+01 4.40255737e+01 6.70857697e+01 2.13824978e+01 -5.38807564e+01 -6.15926208e+01 1.16640673e+01 8.67640533e+01 7.05540695e+01 2.03203621e+01 -6.00572891e+01 -8.11421356e+01 -4.88700790e+01 -5.47369337e+00 2.61654873e+01 -3.77146339e+01 -9.14764786e+01 -1.57381485e+02 -1.43312317e+02 -7.28857117e+01 -7.60553131e+01 -9.62300034e+01 -1.64130783e+02 -1.70972687e+02 -1.54439911e+02 -1.04222267e+02 -2.81473947e+00 3.16218987e+01 6.43324661e+00 -7.56914368e+01 -1.11158768e+02 -5.09973450e+01 2.94437485e+01 3.58487434e+01 -5.04783821e+01 -1.19957855e+02 -9.72254105e+01 -1.34961796e+01 5.48902168e+01 6.14654541e+01 -1.20128298e+01 -9.86938171e+01 -1.20229599e+02 -1.05136391e+02 -7.39149399e+01 -4.55191345e+01 -6.86955070e+00 -2.10784483e+00 -2.58553905e+01 -4.26308441e+01 -1.39080706e+01 6.18746109e+01 1.01645744e+02 4.30612297e+01 -5.07434692e+01 -9.52657547e+01 -3.67752914e+01 5.46787415e+01 7.17914581e+01 2.14985313e+01 -6.97907257e+01 -7.84688034e+01 -3.03237419e+01 1.15829870e-01 1.13975554e+01 -4.06718788e+01 -5.80350494e+01 -5.01237297e+01 -2.95342770e+01 1.88055210e+01 1.50660858e-01 -1.28620548e+01 -8.27088242e+01 -1.30086136e+02 -1.07744812e+02 -7.56715851e+01 -4.39839554e+00 5.06444407e+00 -1.67277355e+01 -1.02637062e+02 -1.82671509e+02 -1.62680222e+02 -7.29034042e+01 -2.19245148e+01 -2.70492615e+02 -2.95917328e+02 -1.11939636e+02 -3.43269238e+03 -7.53721875e+03 -651326016. -408989312. -2.73790259e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.52564122e+09 -415164064. 2.36061445e+04 8.28300488e+03 6.68530273e+02 2.30033665e+01 3.82297119e+02 9.65521164e+01 -3.09627441e+03 -2.05959204e+03 -2.90612335e+02 -2.61656830e+02 -1.42512177e+02 -1.09442429e+02 -9.36800919e+01 -6.63111191e+01 1.60484276e+01 1.79210186e+01 -1.72739792e+01 -7.78927460e+01 -6.66484680e+01 -1.43535960e+00 5.72878227e+01 6.65689621e+01 1.10421696e+01 -6.74648590e+01 -8.56977921e+01 -2.48334942e+01 3.58635101e+01 4.35911369e+01 -1.13914404e+01 -1.31259346e+01 1.45761557e+01 2.49171619e+01 -1.39341366e+00 -3.75400391e+01 -3.70387039e+01 -4.48510628e+01 -6.47600555e+01 -6.48316650e+01 -3.28769989e+01 3.91590233e+01 3.83520699e+01 -3.56865191e+00 -4.69309692e+01 -4.20000458e+01 4.61993599e+00 5.77222290e+01 5.16764793e+01 -1.97876186e+01 -1.03489677e+02 -9.44843674e+01 -1.34441051e+01 2.64062290e+01 2.76625748e+01 -2.10408878e+01 -3.29222107e+01 -3.79937744e+01 -4.58567390e+01 -3.54441071e+01 -1.65323524e+01 3.56787872e+01 1.76463985e+01 -2.40180054e+01 -4.50885811e+01 -1.19350348e+01 4.26019592e+01 4.34219093e+01 1.54266052e+01 -2.52991524e+01 -4.55715714e+01 -4.85222054e+00 5.02740479e+01 9.41968384e+01 7.36922531e+01 1.03160257e+01 -1.25562363e+01 1.84093552e+01 4.68388596e+01 4.38475647e+01 -1.06240911e+01 -2.41700439e+01 -1.12315178e+01 1.32316418e+01 1.14194269e+01 1.10364218e+01 2.27731552e+01 2.91924930e+00 -3.00383015e+01 -4.39336014e+01 -7.21499920e+00 4.75568962e+01 5.52158089e+01 3.51082611e+01 -6.62924147e+00 -3.01815319e+01 -3.65630722e+01 -3.01264620e+00 1.84913177e+01 1.80595894e+01 -3.34360237e+01 -5.23072853e+01 -1.79159298e+01 1.79692745e+01 1.67826939e+01 -3.07470970e+01 -5.02661819e+01 -4.42435455e+01 -4.01480827e+01 -3.42398682e+01 -1.94734077e+01 1.69934883e+01 1.62981358e+01 -1.29463577e+01 -3.67683411e+01 -3.80093880e+01 -1.04920177e+01 -7.13874292e+00 -2.31914864e+01 -3.64640694e+01 -5.23681221e+01 -4.55364075e+01 -1.97956982e+01 7.98982668e+00 1.57193832e+01 -2.26920586e+01 -4.22068672e+01 -2.67366505e+01 -1.56851015e+01 -1.31758528e+01 -3.30546875e+01 -3.09388256e+01 -2.68888474e+01 -3.68130302e+01 -3.87957458e+01 -3.31140327e+01 -1.49724090e+00 -5.02546549e+00 -2.81836605e+01 -4.43721695e+01 -4.00933952e+01 -2.05413570e+01 -2.12882557e+01 -3.64742241e+01 -4.57920532e+01 -5.81895142e+01 -4.55568352e+01 -2.56014194e+01 -7.64338255e+00 -1.00494041e+01 -3.16493073e+01 -3.35441628e+01 -2.84873123e+01 -2.61511574e+01 -3.28579712e+01 -4.49049225e+01 -5.21457214e+01 -5.73001595e+01 -5.82736015e+01 -4.84962082e+01 -3.48842506e+01 -1.46360178e+01 -7.51355028e+00 -1.29256802e+01 -2.49238625e+01 -2.60468254e+01 -1.16687145e+01 1.37837958e+00 -6.97502947e+00 -2.93271599e+01 -4.52875938e+01 -4.24035149e+01 -2.19875908e+01 -1.03901329e+01 -1.32067585e+01 -2.70923805e+01 -3.04721470e+01 -2.35564671e+01 -2.37639008e+01 -2.23322506e+01 -2.20762444e+01 -2.20811577e+01 -3.14427776e+01 -4.42104073e+01 -4.27408180e+01 -3.84795723e+01 -2.91568508e+01 -2.46024437e+01 -2.22277737e+01 -2.51731300e+01 -2.63870544e+01 -2.05634651e+01 -1.29784155e+01 -1.65717182e+01 -2.72242870e+01 -3.77694016e+01 -3.82918930e+01 -3.01943607e+01 -2.76965656e+01 -2.67323666e+01 -3.36275940e+01 -3.21879959e+01 -2.74680882e+01 -2.19302807e+01 -1.90122490e+01 -1.91890450e+01 -1.65095482e+01 -1.94487476e+01 -2.51313267e+01 -2.97889423e+01 -2.97658844e+01 -2.58832474e+01 -2.54460869e+01 -2.81502209e+01 -3.13266850e+01 -3.40806503e+01 -3.19254818e+01 -2.81419315e+01 -2.49445763e+01 -2.61985970e+01 -2.87647209e+01 -2.91429214e+01 -2.83242626e+01 -2.81052666e+01 -2.82969036e+01 -2.86162548e+01 -2.86127110e+01 -2.83999805e+01 -2.82155571e+01 -2.84013424e+01 -2.88031731e+01 -3.02308083e+01 -3.09671059e+01 -3.07268791e+01 -2.97321663e+01 -2.93413239e+01 -2.93155499e+01 -2.80688381e+01 -2.61754913e+01 -2.54334373e+01 -2.60021420e+01 -2.85487118e+01 -2.91209641e+01 -2.98376102e+01 -2.94432335e+01 -2.77445755e+01 -2.75156269e+01 -2.76778584e+01 -3.12333107e+01 -3.15897026e+01 -3.06684036e+01 -2.77784977e+01 -2.82958813e+01 -2.97793121e+01 -3.12031765e+01 -2.98253250e+01 -2.79111481e+01 -2.79160690e+01 -2.69561806e+01 -2.77098579e+01 -2.62112617e+01 -2.77751331e+01 -2.82614384e+01 -3.06010113e+01 -2.79920864e+01 -2.57153797e+01 -2.40909538e+01 -2.50367489e+01 -2.57308025e+01 -2.39647312e+01 -2.36026096e+01 -2.40245171e+01 -2.33400822e+01 -2.38793983e+01 -2.49422359e+01 -2.68062840e+01 -2.46087837e+01 -2.39951534e+01 -2.42272892e+01 -2.47314816e+01 -2.36434612e+01 -2.22983379e+01 -2.29957294e+01 -2.18291912e+01 -2.38291092e+01 -2.59555473e+01 -2.69209156e+01 -2.31313534e+01 -2.24422073e+01 -2.02627106e+01 -2.28277664e+01 -1.92940884e+01 -2.13868389e+01 -1.85964546e+01 -1.91523457e+01 -1.88181496e+01 -2.59494686e+01 -3.58697586e+01 -4.16730423e+01 -3.65413818e+01 -3.01900158e+01 -2.57813492e+01 -2.87361736e+01 -2.69756031e+01 -3.15601482e+01 -3.11093102e+01 -2.70937996e+01 -2.26900845e+01 -2.43398342e+01 -2.74393616e+01 -2.49295597e+01 -2.38547649e+01 -2.65842876e+01 -2.79968834e+01 -2.22007084e+01 -2.39054203e+01 -2.82596874e+01 -3.54504585e+01 -3.39957733e+01 -3.38540916e+01 -2.47909927e+01 -1.55521345e+01 -4.48601186e-01 3.21807718e+00 -2.82848477e+00 -1.52379379e+01 -2.37483044e+01 -2.64776993e+01 -2.61313896e+01 -2.90684929e+01 -2.04046974e+01 -8.37899590e+00 -8.25606918e+00 -2.01966915e+01 -3.32532578e+01 -3.35185814e+01 -2.84742737e+01 -3.23784790e+01 -3.24280739e+01 -3.31628571e+01 -3.25818100e+01 -3.39327698e+01 -3.69420433e+01 -2.93442631e+01 -2.58428288e+01 -3.14802780e+01 -3.79511833e+01 -5.11618156e+01 -5.16283455e+01 -4.97460594e+01 -3.70558510e+01 -4.07619514e+01 -4.17848091e+01 -4.05322762e+01 -3.44904251e+01 -2.98301888e+01 -3.96035004e+01 -4.81431580e+01 -5.44882393e+01 -3.79422836e+01 -2.35450935e+01 -1.67348328e+01 -3.36019135e+01 -5.19326134e+01 -6.83732452e+01 -5.16886940e+01 -2.57129078e+01 -1.55995531e+01 -2.04799023e+01 -3.34076614e+01 -3.37735481e+01 -5.44981155e+01 -6.36192932e+01 -5.65954247e+01 -4.05499039e+01 -2.62210350e+01 -2.12397537e+01 -2.27123451e+01 -3.40888176e+01 -5.11703568e+01 -5.37393532e+01 -3.85163231e+01 -2.76765785e+01 -2.23041573e+01 -2.33451710e+01 -1.79125557e+01 -9.27836609e+00 -7.69635677e+00 -8.98576832e+00 -1.43677740e+01 -2.20759583e+01 -1.97447548e+01 -1.94850006e+01 -1.89922199e+01 -2.88117085e+01 -2.16784306e+01 -1.17650938e+01 -2.30175610e+01 -3.59355469e+01 -3.14577026e+01 -6.48681819e-02 1.16505423e+01 -4.74383545e+00 -2.04382362e+01 -2.03778534e+01 -2.35796032e+01 -4.43373566e+01 -5.74759445e+01 -6.52232819e+01 -5.44530373e+01 -4.31372528e+01 -2.77763233e+01 -2.62018871e+01 -3.65084991e+01 -3.24609222e+01 -2.76019268e+01 -1.96395283e+01 -2.22536316e+01 -1.59958677e+01 -4.24394150e+01 -6.39964333e+01 -7.23709106e+01 -4.77934151e+01 -2.96647320e+01 -2.33631210e+01 -2.09183121e+01 -2.08088131e+01 -1.70152836e+01 -2.77816486e+01 -1.13777580e+01 1.50635433e+00 2.54637299e+01 2.13989773e+01 7.70150185e+00 -1.08828115e+01 -7.83934784e+00 -5.87747514e-01 5.44847441e+00 9.76267636e-01 -5.62866116e+00 2.07959309e+01 5.11120415e+01 5.33309059e+01 1.91947575e+01 -2.52588673e+01 -2.98284092e+01 -2.33423305e+00 4.42561111e+01 1.50275681e+02 4.10463196e+02 5.83328064e+02 6.24543884e+02 7.97037781e+02 2.65315356e+03 3.68780566e+03 -7.42011292e+02 5.46947314e+03 5.44294434e+02 5.33073877e+03 2.05273613e+04 -355944800. -804032064. -290804128. -543421312. 2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 1442105088. 1442105088. -694983616. -3.84125430e+04 -1.12075137e+04 -1.33510620e+03 4.00486694e+03 2.82696484e+03 7.56350098e+02 6.62917358e+02 5.00213989e+02 1.75460358e+02 7.08590240e+01 6.71460190e+01 3.41834221e+01 -1.17179489e+00 3.37878752e+00 5.58774042e+00 6.19800234e+00 5.61842871e+00 3.35412979e+01 5.85077972e+01 3.43822823e+01 -1.26960907e+01 -1.91766987e+01 9.65725708e+00 3.24332047e+01 1.33440771e+01 1.08074856e+01 2.07628193e+01 3.08589001e+01 3.94463005e+01 4.07079124e+01 3.92696381e+01 2.63576050e+01 2.39618320e+01 1.40654860e+01 1.58450832e+01 -2.04224072e+01 -4.98562241e+01 -5.62067146e+01 -3.32576599e+01 -1.44623194e+01 -2.07626381e+01 -3.88850937e+01 -4.21730042e+01 -5.87094154e+01 -6.47480087e+01 -7.12159348e+01 -7.71718445e+01 -8.14565353e+01 -6.99225845e+01 -5.61184082e+01 -4.41901436e+01 -4.88296471e+01 -4.63377457e+01 -4.04631195e+01 -4.68210640e+01 -5.07938156e+01 -6.54857483e+01 -7.02539978e+01 -5.41360550e+01 -1.17821655e+01 3.49887238e+01 5.30428696e+01 2.81987362e+01 1.40559840e+00 -1.79194660e+01 9.57976055e+00 3.41815758e+01 2.07951241e+01 -1.72005253e+01 -5.19921951e+01 -5.01650772e+01 -4.58607635e+01 -6.70764160e+01 -1.06505928e+02 -8.15250626e+01 -3.01735897e+01 2.13660011e+01 1.32165174e+01 -9.89957333e+00 -9.15797615e+00 -2.01950531e+01 -2.65048752e+01 -3.96976509e+01 -3.21617699e+01 -2.15005684e+01 2.20872879e+00 9.50795650e+00 9.52772903e+00 -1.16569185e+01 -9.14842224e+00 2.31963577e+01 7.29356079e+01 6.02706223e+01 2.88087044e+01 -8.50399208e+00 2.15965891e+00 2.27905025e+01 4.76960945e+01 5.85741806e+01 2.82987652e+01 -1.84997959e+01 -2.53193073e+01 -1.09850073e+01 3.47363930e+01 2.52778225e+01 2.29144726e+01 -3.80213451e+00 -1.15083075e+01 -7.15380955e+00 -2.34926128e+00 -3.17977858e+00 -6.92969275e+00 -3.83427072e+00 -4.08294678e+00 -1.11831589e+01 1.26055384e+01 4.95036469e+01 5.57165031e+01 2.17180653e+01 -1.69326897e+01 -2.78463135e+01 -3.42608986e+01 -3.24564552e+01 -4.02788773e+01 -4.55887108e+01 -5.09890518e+01 -4.94080591e+00 5.20860443e+01 6.38047371e+01 3.64676666e+01 -8.55687046e+00 -2.91905174e+01 -4.38911819e+01 -3.79676094e+01 -1.99179211e+01 -1.20541277e+01 -2.39505672e+01 -1.42235394e+01 -1.33235855e+01 -1.00482273e+01 -1.57902651e+01 -9.56170273e+00 -6.41743517e+00 4.14973021e+00 -2.29165539e-01 1.70188797e+00 -1.38786256e+00 3.28800470e-01 2.37384245e-01 6.00135231e+00 1.25302105e+01 1.36170969e+01 -5.10409594e+00 -1.09966545e+01 -1.59642143e+01 -9.89185429e+00 -1.71493607e+01 -2.29955730e+01 -2.38846836e+01 -9.40143776e+00 5.07301941e+01 8.19461746e+01 8.74903870e+01 6.74986420e+01 4.73050613e+01 4.14780388e+01 1.99384251e+01 9.89862537e+00 1.97604980e+01 2.31144924e+01 2.43611794e+01 1.39650497e+01 1.23346643e+01 1.67371035e+00 -4.53106995e+01 -8.27705994e+01 -1.07869415e+02 -9.42323303e+01 -4.97212257e+01 -1.14652300e+01 3.14086761e+01 2.11920452e+01 1.69232273e+01 -8.36262703e-01 4.28925037e+00 -2.65877366e+00 5.71062279e+00 -3.43567044e-01 -1.56557524e+00 5.61332417e+00 1.39632339e+01 5.66611290e+00 -4.66528606e+00 -9.53667641e+00 6.99618530e+00 1.80395622e+01 2.34204216e+01 2.36745682e+01 1.20841255e+01 -2.98486309e+01 -6.64481354e+01 -9.23894806e+01 -8.73578873e+01 -8.34185715e+01 -8.68494263e+01 -5.56022797e+01 -9.10566711e+00 3.63033562e+01 4.77200966e+01 3.79755936e+01 2.24552212e+01 1.67519913e+01 2.26019993e+01 4.34480095e+01 3.84197960e+01 3.59307556e+01 2.23948421e+01 1.89460754e+01 2.00906887e+01 5.46382523e+01 9.55121841e+01 8.12933273e+01 4.59113579e+01 6.67619801e+00 -1.29300919e+01 -3.18984127e+01 -7.11850967e+01 -9.40049820e+01 -7.99159775e+01 -4.81888885e+01 -3.03129387e+00 -2.32962513e+01 -3.83684616e+01 -5.00886993e+01 -3.99440956e+01 -3.24771729e+01 -3.81454048e+01 -4.39248543e+01 -4.13033905e+01 -2.98988647e+01 -1.33434143e+01 -1.41478109e+01 -4.29364357e+01 -7.83218994e+01 -1.15354347e+02 -1.25820923e+02 -5.07766266e+01 2.41832638e+01 6.28741379e+01 3.27905655e+01 -5.25949621e+00 8.44534338e-01 -1.31951513e+01 -3.34580803e+00 -1.79845482e-01 8.60179138e+00 1.32050982e+01 1.07602949e+01 9.86630440e+00 6.47296381e+00 3.92068939e+01 8.05014725e+01 9.44176331e+01 7.01840591e+01 3.88678780e+01 1.32728996e+01 -1.57089405e+01 -1.98728027e+01 1.48893106e+00 1.12345905e+01 -6.14353514e+00 -8.77560139e+00 1.03008947e+01 2.84476986e+01 3.02319756e+01 2.68950653e+01 2.52639465e+01 1.85531254e+01 1.89589577e+01 1.30949802e+01 2.00840855e+01 2.17666931e+01 3.67365456e+01 3.85102730e+01 3.36054878e+01 -4.30156565e+00 -4.54460258e+01 -3.66388359e+01 -2.03204584e+00 3.17494335e+01 1.48047228e+01 5.41755438e+00 -1.26103067e+00 -1.62065312e-01 -7.66414261e+00 -1.12857847e+01 -3.52635422e+01 -4.70256844e+01 -4.49311447e+01 -5.46709347e+00 2.64440708e+01 3.17239246e+01 1.95692825e+01 3.88492241e+01 6.93200760e+01 8.20162888e+01 7.10924530e+01 4.01328545e+01 3.83666878e+01 3.58673019e+01 3.58846664e+01 3.37207603e+01 2.87744961e+01 3.66811943e+01 4.67355881e+01 4.37167549e+01 3.89314575e+01 3.82348328e+01 4.46506882e+01 3.73907089e+01 2.86736660e+01 -4.00453107e-03 -2.72383347e+01 -2.25223351e+01 -6.60190392e+00 1.14528217e+01 5.47217131e+00 1.29675589e+01 3.10025024e+01 2.50193176e+01 -1.19190664e+01 -4.62498093e+01 -4.33851204e+01 -7.35862303e+00 1.64722824e+01 9.53171158e+00 -1.23065257e+00 -3.63144588e+00 3.93136668e+00 -1.90663910e+01 -5.28361855e+01 -6.11362228e+01 -3.19265709e+01 1.47825842e+01 1.24746847e+01 1.01215296e+01 2.00858307e+00 1.04256248e+01 1.33243742e+01 3.24703908e+00 -6.65348387e+00 -1.37388411e+01 -3.85719967e+00 3.62951946e+00 -3.24643040e+00 -3.79355736e+01 -8.44882965e+01 -8.53236694e+01 -5.03115768e+01 -1.05317974e+01 -8.22090149e-01 7.31301832e+00 6.13224220e+00 -3.55648398e+00 -4.11398506e+01 -6.84353485e+01 -9.72493591e+01 -1.01022896e+02 -7.36856613e+01 -4.63832397e+01 -4.81838369e+00 -2.50210094e+01 -4.50269737e+01 -2.28278885e+01 3.54212990e+01 6.83329620e+01 4.37286110e+01 7.18004417e+00 9.35366631e+00 1.23323669e+01 2.10315266e+01 2.45100002e+01 3.52957420e+01 3.77011528e+01 3.86806183e+01 3.56227150e+01 3.20018463e+01 3.34724236e+01 4.16633148e+01 4.67990913e+01 4.09867287e+01 1.56195641e+01 -1.00189915e+01 -2.63040566e+00 2.16153469e+01 5.07358627e+01 2.18728905e+01 -1.31544828e+01 1.52870731e+01 7.49119720e+01 8.16783981e+01 6.84170341e+00 -3.53836861e+01 -1.66862450e+01 1.91467133e+01 1.37634897e+00 -3.15833015e+01 -3.60588646e+01 -1.98875389e+01 7.46694279e+00 4.71930647e+00 1.89837396e+00 1.07709198e+01 1.35331650e+01 3.61230392e+01 5.52102318e+01 2.65084801e+01 -1.94321918e+01 -4.58223991e+01 -2.75758667e+01 -8.98637962e+00 -2.81313019e+01 -4.57998772e+01 -4.79189758e+01 -3.04529705e+01 -1.73558205e-01 -9.28484023e-01 -5.96564341e+00 -1.53920593e+01 -1.65491045e+00 -1.11740732e+01 -2.91996651e+01 -4.01541939e+01 -3.68146706e+01 -7.79387569e+00 9.56128979e+00 2.59010487e+01 2.68378334e+01 2.21933613e+01 5.41224174e+01 8.93284912e+01 8.00144958e+01 3.11121464e+01 -4.81767559e+00 2.17528200e+00 2.19124146e+01 1.37999284e+00 -2.19251461e+01 -2.34414330e+01 -3.95008636e+00 1.84034958e+01 2.35566692e+01 2.09972649e+01 2.40357208e+01 1.84661331e+01 2.27918663e+01 1.45957203e+01 6.23779821e+00 -7.16709495e-01 6.98967028e+00 1.81950474e+01 2.37399445e+01 2.68045330e+01 2.50159073e+01 4.83325844e+01 6.85467529e+01 5.20114822e+01 4.31109810e+00 -1.97178650e+01 2.56075311e+00 3.23978004e+01 4.80878448e+01 5.39459991e+01 5.32105331e+01 4.67217369e+01 4.15060196e+01 4.39405327e+01 3.68871040e+01 3.99154968e+01 4.10778465e+01 4.85267067e+01 5.30752678e+01 5.42254791e+01 4.55401649e+01 3.45388794e+01 3.65525017e+01 4.71008453e+01 5.42462082e+01 4.23814583e+01 3.31100311e+01 2.24751930e+01 1.30902376e+01 -5.68832111e+00 -6.13583231e+00 3.69027472e+00 6.01424551e+00 -2.56074142e+01 -4.61118240e+01 -3.34409561e+01 -8.21478462e+00 -1.11001987e+01 -3.01210308e+01 -3.40611076e+01 -1.68238468e+01 -1.52723157e+00 4.98686743e+00 6.17822504e+00 4.24329758e+00 9.53692198e-01 2.59962916e+00 1.04467993e+01 2.40107751e+00 -1.30763760e+01 -1.92954807e+01 -7.94411755e+00 1.03755360e+01 9.71115112e+00 -4.79345322e-01 9.93344307e+00 2.75513802e+01 3.92274399e+01 3.15205669e+01 2.32364979e+01 2.79041862e+01 2.84292622e+01 2.75030823e+01 2.58160915e+01 2.77341518e+01 2.71533852e+01 2.65060177e+01 2.92835026e+01 3.28218193e+01 3.61711044e+01 3.51761131e+01 2.99745750e+01 2.97048302e+01 1.83471947e+01 8.63061333e+00 9.07846069e+00 2.16930237e+01 3.77047844e+01 4.06986351e+01 3.94497757e+01 4.67015419e+01 5.62637291e+01 5.71107292e+01 4.93337669e+01 3.78411942e+01 3.46882591e+01 3.35699768e+01 2.03409863e+01 8.26093769e+00 4.78063393e+00 1.47011757e+01 2.25102386e+01 2.21439686e+01 2.40381222e+01 2.70608139e+01 2.63205166e+01 3.20952339e+01 4.12998276e+01 3.65334244e+01 2.39895592e+01 1.62136612e+01 2.22494946e+01 2.19320679e+01 6.39982891e+00 -3.04313970e+00 1.33704376e+00 1.63999634e+01 2.15004826e+01 1.65513878e+01 1.71815300e+01 2.24643574e+01 3.17073555e+01 2.96300468e+01 2.40940437e+01 2.21576939e+01 2.42612152e+01 2.94323902e+01 3.20670700e+01 3.40466309e+01 3.44034042e+01 3.14687004e+01 3.22141953e+01 3.36198387e+01 3.03126755e+01 2.53424702e+01 2.32713890e+01 2.79969063e+01 3.15655918e+01 2.98394794e+01 2.47638664e+01 2.78455639e+01 4.67035446e+01 5.95080833e+01 7.54950638e+01 7.13542862e+01 5.07517395e+02 1.36055737e+03 -9.70214905e+02 -3.67093048e+02 5.72902954e+02 1.10127876e+02 1.77400116e+02 1.66850232e+03 1552127104. 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. 0. 0. 2.45095987e+09 -4.46136576e+09 2.64844467e+09 777280384. -8.24539490e+02 -3.36793030e+02 -2.66646862e+00 3.63917503e+01 5.06885643e+01 5.35803833e+01 5.59487648e+01 5.79297752e+01 5.35414124e+01 4.92518272e+01 5.19398117e+01 6.03911552e+01 6.52175980e+01 5.94972687e+01 4.89932785e+01 5.68940659e+01 7.14092636e+01 8.75450668e+01 9.09232635e+01 8.61266403e+01 7.17024689e+01 6.50643311e+01 5.93942680e+01 6.72567215e+01 6.46756592e+01 6.93582764e+01 8.24796753e+01 8.61656189e+01 7.43648300e+01 6.05459251e+01 5.47877007e+01 5.54637032e+01 4.93963051e+01 4.08441315e+01 3.77593842e+01 4.93931122e+01 7.89494781e+01 9.45715332e+01 8.68368835e+01 6.57046890e+01 5.12658997e+01 5.19934196e+01 5.80983925e+01 6.79890366e+01 6.35915298e+01 6.80353012e+01 7.33452682e+01 6.99636307e+01 4.93131409e+01 2.05246334e+01 2.35590153e+01 5.83347473e+01 7.93546143e+01 7.00615234e+01 4.76824074e+01 4.98067398e+01 6.85898743e+01 6.88609238e+01 5.05788498e+01 3.01683617e+01 3.69201393e+01 7.03092346e+01 9.11494598e+01 8.23565369e+01 6.13204041e+01 5.79166336e+01 6.59360886e+01 6.48144531e+01 4.68626442e+01 2.78432198e+01 3.50608864e+01 4.70597496e+01 4.32514305e+01 2.72924690e+01 2.02154121e+01 2.63461170e+01 4.59913177e+01 6.37717438e+01 7.02089005e+01 5.65228653e+01 4.60308876e+01 4.83457947e+01 3.25313072e+01 4.28926182e+00 -1.02430506e+01 1.93134365e+01 6.75444412e+01 9.20042648e+01 7.51679916e+01 3.58669891e+01 -6.20717525e+00 -2.08098049e+01 -6.66823244e+00 2.75397158e+00 -6.84281886e-01 5.30478334e+00 4.66950035e+01 7.77403412e+01 6.96420822e+01 3.41632614e+01 1.36839991e+01 2.69465504e+01 5.23458138e+01 6.24831886e+01 4.38691139e+01 3.06971836e+01 3.50229759e+01 3.90699577e+01 1.61843014e+01 -2.73389530e+01 -3.39308434e+01 1.55638695e+00 4.37336578e+01 4.33098373e+01 1.93572540e+01 -7.93708754e+00 -8.94862461e+00 1.31539745e+01 4.38726616e+01 5.62841721e+01 4.26185646e+01 4.06612816e+01 6.27069511e+01 6.41945190e+01 3.80753670e+01 1.85633886e+00 5.33766794e+00 3.86474037e+01 5.66202278e+01 3.50040894e+01 1.68887291e+01 8.43644810e+00 2.37407417e+01 1.08372250e+01 -1.68718758e+01 -2.53121815e+01 1.25869169e+01 8.81422348e+01 1.24966888e+02 9.69949265e+01 5.24624100e+01 3.64274483e+01 5.27905045e+01 7.30609283e+01 7.12785950e+01 7.29445267e+01 8.57287598e+01 1.17334885e+02 1.28649216e+02 9.90158615e+01 2.42201385e+01 -1.77329998e+01 1.54158592e+01 6.13648033e+01 6.14132729e+01 3.86992912e+01 5.86318016e+01 1.16940613e+02 1.10845940e+02 6.19511490e+01 8.43244839e+00 5.10857697e+01 1.38403412e+02 1.85855652e+02 1.50797241e+02 8.46990204e+01 5.44641609e+01 5.12201729e+01 3.76985207e+01 2.03361435e+01 3.45585442e+01 9.02559967e+01 1.51728134e+02 1.25077652e+02 6.61628799e+01 8.91950512e+00 1.61412354e+01 4.88281364e+01 7.84664764e+01 9.72842865e+01 9.45210495e+01 1.08103943e+02 1.35381790e+02 1.22341537e+02 5.53492661e+01 -4.50870991e+00 1.49979286e+01 9.10809402e+01 1.42364594e+02 1.16392586e+02 6.49762344e+01 2.84566822e+01 3.63545456e+01 2.10495720e+01 -2.36590996e+01 -4.58716583e+01 3.15756512e+00 8.23263779e+01 1.03190826e+02 7.64900665e+01 8.00792217e+00 -1.47697363e+01 -5.91579247e+00 2.53376637e+01 5.02279091e+01 4.47152901e+01 6.85762482e+01 9.23271027e+01 6.89416656e+01 1.77162781e+01 -9.12745857e+00 4.30393964e-01 4.25147820e+01 5.55294952e+01 4.16929131e+01 3.65230713e+01 3.32155495e+01 5.77517738e+01 2.64722137e+01 -1.33023806e+01 -3.52212868e+01 -4.05113792e+01 2.37241802e+01 6.23786049e+01 4.21569633e+01 -2.58094845e+01 -4.27999992e+01 2.90262985e+00 5.12856026e+01 4.63324356e+01 1.72621231e+01 1.57778921e+01 5.82586899e+01 5.94143867e+01 1.42655420e+01 -2.71844387e+01 3.39063549e+00 3.00006809e+01 2.56650829e+00 -1.35518942e+01 9.18744278e+00 3.16739578e+01 5.05968666e+01 3.40457230e+01 6.59156799e+01 7.57639542e+01 6.75104141e+01 7.67610245e+01 1.02616806e+02 1.24954948e+02 6.14903336e+01 2.98615837e+01 1.79437656e+01 7.07965851e+01 5.73956375e+01 5.26314087e+01 6.98145828e+01 1.09193138e+02 1.30260971e+02 5.37830620e+01 8.77416039e+00 -6.72432232e+00 6.21412926e+01 7.40511093e+01 6.01700592e+01 3.27276840e+01 2.53221817e+01 8.17868958e+01 6.14301605e+01 3.65788078e+01 -3.59084854e+01 -6.16238899e+01 -4.70082397e+01 9.57686329e+00 5.60128670e+01 2.33668213e+01 -2.63650494e+01 -5.02855911e+01 -1.74590206e+01 -4.65150261e+01 -4.56976662e+01 -8.85746861e+00 6.35849915e+01 6.53325500e+01 -2.11526051e+01 -5.66690674e+01 -1.74851761e+01 5.85823631e+01 3.27819557e+01 -1.35984688e+01 -3.51928825e+01 -1.73226910e+01 2.50016899e+01 2.76586437e+01 4.51385612e+01 -4.67402124e+00 -3.80239334e+01 -4.57405243e+01 2.75750089e+00 2.79319649e+01 -2.65670323e+00 -4.22254601e+01 -4.86220322e+01 -6.48553925e+01 -1.33318420e+02 -1.64505753e+02 -1.53015503e+02 -1.34024826e+02 -1.39847733e+02 -1.77030701e+02 -1.79917084e+02 -1.50371475e+02 -6.85449066e+01 -4.16551819e+01 -2.68425655e+01 -4.15651321e+01 -2.51983585e+01 2.22389717e+01 4.78393822e+01 6.11124458e+01 2.29715943e+00 -2.53467731e+01 -3.50656128e+01 -1.42591219e+01 -3.00609112e+01 -5.10731888e+01 -8.26424637e+01 -7.41521378e+01 -7.93735428e+01 -1.26327049e+02 -1.54823532e+02 -1.38659302e+02 -7.39874573e+01 -6.08856163e+01 -5.88252716e+01 -7.42513037e+00 3.13757076e+01 5.69002380e+01 -1.17917681e+01 -1.65688858e+01 -2.79683609e+01 -6.27126312e+01 -6.50286179e+01 -2.49363632e+01 6.69954453e+01 8.52744446e+01 1.03620720e+01 -5.62794342e+01 -4.88284798e+01 1.64721813e+01 6.87012939e+01 3.81810989e+01 -2.17041245e+01 -7.79581375e+01 -7.30416183e+01 -2.63962307e+01 1.62487869e+01 7.32951202e+01 8.15897141e+01 8.37882614e+01 9.94823685e+01 9.88922577e+01 1.02774994e+02 1.97263737e+01 1.54720354e+01 1.17105579e+01 1.33774080e+01 1.95785275e+01 6.01823273e+01 1.84963669e+02 2.09045609e+02 1.26115082e+02 -3.79195786e+01 -1.13412086e+02 -2.67075195e+01 9.35216141e+01 1.03826775e+02 -2.97920742e+01 -1.61650375e+02 -1.34303848e+02 -5.33004427e+00 7.50158615e+01 6.45773926e+01 -2.47911625e+01 -2.68604088e+01 3.14939213e+01 8.26795959e+01 1.07195457e+02 2.26295509e+01 2.02497635e+01 5.53800850e+01 9.87179794e+01 1.00123207e+02 4.84373894e+01 8.02237778e+01 8.40653839e+01 -1.05815494e+00 -1.09569016e+02 -9.89168777e+01 6.89767456e+01 1.83694382e+02 1.35278198e+02 4.66804504e+00 -6.97060242e+01 -4.53015366e+01 3.74225121e+01 7.59691391e+01 9.51849365e+01 1.66412945e+01 9.70064545e+00 2.01388702e+01 6.32788010e+01 9.52828903e+01 3.51544724e+01 -1.50576935e+01 -8.70089569e+01 -9.00161972e+01 -5.59478455e+01 1.10025492e+01 1.25046478e+02 1.67156937e+02 8.87506409e+01 -7.44014053e+01 -1.68146896e+02 -9.76904373e+01 7.12180176e+01 1.23076965e+02 6.25749901e-02 -1.59178116e+02 -1.61921921e+02 -2.34873848e+01 5.78816071e+01 5.25844078e+01 -1.97777882e+01 -3.31275139e+01 1.16444035e+01 6.97441177e+01 1.28948853e+02 1.25240265e+02 1.63818054e+02 1.51278580e+02 8.95255280e+01 -1.65328293e+01 -5.47352562e+01 2.04237347e+01 9.48905640e+01 7.12460022e+01 -4.00157204e+01 -1.28965790e+02 -9.72578964e+01 1.74930096e+01 5.37407074e+01 8.09217644e+00 -8.52782669e+01 -7.22487335e+01 1.56796336e+00 7.67228317e+01 1.26981369e+02 7.14086914e+01 6.25788155e+01 3.38304787e+01 4.70195808e+01 5.88888779e+01 7.61035843e+01 1.19743195e+02 7.48655701e+01 5.44601679e+00 -7.13511581e+01 -3.57254066e+01 6.53850021e+01 1.39170212e+02 7.71153488e+01 -3.17289467e+01 -1.02004921e+02 -9.68190613e+01 -1.86931896e+01 1.59046698e+01 3.35662651e+01 -7.11970520e+00 1.26986313e+01 4.87347755e+01 9.45266647e+01 1.42877289e+02 1.17906700e+02 3.78989487e+01 -4.00171089e+01 -4.44562531e+01 -1.25549583e+01 2.69579983e+01 8.89297791e+01 1.22467293e+02 4.54966431e+01 -7.89343109e+01 -1.40256699e+02 -5.32000656e+01 4.92516060e+01 4.97168541e+01 -6.90745392e+01 -1.83780136e+02 -1.60386475e+02 -2.26916237e+01 1.21009598e+02 1.74737976e+02 8.67552872e+01 1.42930174e+01 8.11688709e+00 4.75338058e+01 7.68401184e+01 3.49314270e+01 4.38205261e+01 2.24484043e+01 -2.03091183e+01 -4.37973633e+01 -4.86708984e+01 2.26448040e+01 1.58570557e+01 -6.03520966e+01 -1.53131317e+02 -1.45755280e+02 3.65662026e+00 1.10379807e+02 8.23870163e+01 -4.55247345e+01 -1.32396072e+02 -1.36354904e+02 -3.35983696e+01 6.52577133e+01 1.05241234e+02 3.28898468e+01 -2.54814434e+01 -6.99755859e+01 -6.80278244e+01 -4.98607101e+01 -5.18144646e+01 -5.79979706e+01 -1.21314247e+02 -1.61265335e+02 -1.59390656e+02 -1.06496056e+02 -1.01651821e+01 2.32601528e+01 -3.30463028e+01 -1.24389893e+02 -1.48253860e+02 -9.71408844e+01 -5.87842417e+00 -5.99875736e+00 -7.04578552e+01 -1.60140366e+02 -1.78822601e+02 -8.37007446e+01 1.01634579e+01 4.78596802e+01 -1.94532356e+01 -8.90566559e+01 -8.77812958e+01 -4.82488022e+01 4.88082981e+00 1.70973015e+01 2.26687870e+01 -7.78398180e+00 -6.70708313e+01 -8.61453018e+01 -2.90945282e+01 7.56781921e+01 1.11551552e+02 4.85229836e+01 -3.07525940e+01 -8.55164108e+01 -5.35769730e+01 8.22526741e+00 5.25630150e+01 3.63646698e+01 -1.91622486e+01 -2.94994087e+01 8.07964230e+00 5.66958580e+01 6.56809921e+01 -6.06753540e+00 -5.79475670e+01 -5.10465698e+01 6.29289722e+00 7.52574387e+01 7.81770935e+01 6.80952911e+01 3.87657623e+01 -2.80046463e+00 -2.38973560e+01 -3.49959221e+01 2.72264633e+01 6.80761032e+01 4.96673737e+01 -8.69573236e-01 -5.07550621e+01 -1.11599646e+01 4.12136116e+01 6.93910294e+01 3.94405055e+00 -1.24360443e+02 -1.77105072e+02 -1.11778717e+02 4.17263031e+01 1.12555550e+02 5.11082916e+01 -5.58757439e+01 -7.80188293e+01 -1.01410843e+02 -1.66265259e+02 -1.11671341e+02 1.51180069e+02 1.63426331e+02 -1.54051773e+02 -2.62460425e+03 -4.06496436e+03 1.36677887e+02 7.91347046e+02 8.27101172e+03 8.05724766e+04 -2.73790259e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.52564122e+09 -415164064. 531736864. -1362843520. -1.25140419e+10 252639600. 662267456. -1.07171924e+04 -4.42431445e+03 -4.70909882e+02 -1.66125854e+02 -2.47973755e+02 -1.58099594e+02 -4.20115433e+01 1.15637712e+01 4.93909740e+00 -6.41960526e+01 -1.03731834e+02 -9.03728714e+01 -1.53414297e+01 4.88347549e+01 4.08779716e+01 -5.52028227e+00 -2.01180058e+01 -2.27069016e+01 -2.84008350e+01 -5.88541870e+01 -3.59059563e+01 -2.22462234e+01 -7.04449463e+01 -1.04877899e+02 -7.78417816e+01 1.33070917e+01 6.03168297e+01 -1.53003538e+00 -7.15177002e+01 -1.16919983e+02 -8.73664017e+01 -5.29754019e+00 5.93422241e+01 8.95868912e+01 2.66896229e+01 -1.86922626e+01 -2.35896130e+01 2.28819618e+01 4.92751083e+01 2.03787041e+01 1.07940645e+01 -1.59708147e+01 -4.17237511e+01 -5.31920967e+01 -2.64802513e+01 5.19160423e+01 5.48086700e+01 -1.50367775e+01 -9.55295486e+01 -1.19089111e+02 -4.95752525e+01 1.48733683e+01 1.52840881e+01 -3.06308975e+01 -5.29001656e+01 -9.80926132e+00 5.70238953e+01 7.99547958e+01 5.18465614e+01 -2.64986839e+01 -7.86835861e+01 -7.66030579e+01 -3.16156483e+01 3.05469952e+01 7.08508911e+01 9.00532150e+01 6.86847076e+01 2.82492352e+01 -8.07120609e+00 -2.53003693e+01 -7.72542000e+00 -1.37590990e+01 -5.69151993e+01 -9.78219223e+01 -9.83045120e+01 -4.82558289e+01 -1.11013346e+01 -1.99418392e+01 -4.22437668e+01 -7.68993683e+01 -9.75993195e+01 -7.68602524e+01 -2.68311768e+01 5.55186510e+00 -2.40364990e+01 -6.25973701e+01 -5.94771843e+01 -4.28714561e+01 -3.09841938e+01 -4.29588165e+01 -2.95719471e+01 -3.59195175e+01 -5.41195602e+01 -6.90325012e+01 -5.42368469e+01 -2.75276542e+00 1.86185110e+00 -4.61625977e+01 -1.08738892e+02 -1.28347748e+02 -8.95806274e+01 -4.27388992e+01 -2.78608456e+01 -3.57274437e+01 -5.26160851e+01 -5.20330276e+01 -4.09827461e+01 -1.79263439e+01 -4.84080410e+00 -2.95669022e+01 -7.41281509e+01 -8.46086197e+01 -6.72569351e+01 -5.02766380e+01 -5.07148819e+01 -3.69018784e+01 -3.75377083e+01 -7.01977844e+01 -1.07992317e+02 -1.06450035e+02 -5.68264694e+01 -3.48207703e+01 -6.34540100e+01 -1.03369705e+02 -1.08499474e+02 -7.15136185e+01 -3.38969765e+01 -2.42624683e+01 -3.65010071e+01 -6.63522491e+01 -9.05669861e+01 -8.08915100e+01 -5.11544724e+01 -2.74999676e+01 -4.80925560e+01 -7.97144699e+01 -8.93125610e+01 -7.88889618e+01 -6.46189957e+01 -5.50261078e+01 -3.76204987e+01 -3.12348804e+01 -4.08521042e+01 -5.56781616e+01 -5.69865913e+01 -3.95643005e+01 -2.92640133e+01 -4.65340080e+01 -8.00935745e+01 -1.05228104e+02 -9.46106262e+01 -6.11683426e+01 -3.63320885e+01 -3.86091995e+01 -5.55728493e+01 -6.40788116e+01 -5.91073074e+01 -5.56612968e+01 -4.48980637e+01 -4.82185707e+01 -5.22440605e+01 -6.14665909e+01 -7.30184937e+01 -8.03491669e+01 -8.18517075e+01 -6.63975525e+01 -5.77350006e+01 -6.77296066e+01 -7.80229645e+01 -7.09112930e+01 -5.06891632e+01 -3.92618027e+01 -4.76156960e+01 -5.59357834e+01 -6.43322449e+01 -6.44577103e+01 -5.89498596e+01 -5.59093285e+01 -5.47543678e+01 -6.54415894e+01 -6.29385223e+01 -5.65485649e+01 -4.70196686e+01 -3.78248405e+01 -3.28321495e+01 -2.91485939e+01 -3.95237312e+01 -5.31735344e+01 -5.96512413e+01 -5.94061737e+01 -5.21244583e+01 -5.26716728e+01 -5.89291039e+01 -6.66808624e+01 -7.10341873e+01 -6.12140694e+01 -4.99430885e+01 -4.37353020e+01 -4.74639397e+01 -5.27317200e+01 -5.46866989e+01 -5.43902473e+01 -5.31369629e+01 -5.13225517e+01 -5.35329170e+01 -5.67999496e+01 -5.91156235e+01 -5.70615883e+01 -5.62830544e+01 -5.55486412e+01 -5.47843857e+01 -5.45419731e+01 -5.56692619e+01 -5.66193352e+01 -5.68053856e+01 -5.68205681e+01 -5.73877182e+01 -5.77346687e+01 -5.76366692e+01 -5.72261200e+01 -5.70086899e+01 -5.71018486e+01 -5.80038300e+01 -5.83065987e+01 -5.77013931e+01 -5.60830574e+01 -5.54325867e+01 -5.67693939e+01 -5.76991806e+01 -5.76787567e+01 -5.74154015e+01 -5.77079773e+01 -5.72664604e+01 -5.70132027e+01 -5.68656311e+01 -5.68452911e+01 -5.71609802e+01 -5.69735069e+01 -5.62631264e+01 -5.44790154e+01 -5.41043777e+01 -5.51225014e+01 -5.62294197e+01 -5.51285477e+01 -5.34774437e+01 -5.43717384e+01 -5.66274071e+01 -6.05417290e+01 -6.23803062e+01 -6.12350502e+01 -5.95803490e+01 -5.65168381e+01 -5.77869301e+01 -5.78437042e+01 -5.75905304e+01 -5.55660286e+01 -5.58035660e+01 -5.58877525e+01 -5.64124031e+01 -5.38966522e+01 -5.34693756e+01 -5.29487419e+01 -5.48968620e+01 -5.27193642e+01 -5.14062538e+01 -4.77258377e+01 -4.75554085e+01 -4.99912071e+01 -5.24548759e+01 -5.46325264e+01 -5.31612854e+01 -5.15404854e+01 -4.77659454e+01 -4.90277901e+01 -4.87503433e+01 -5.51991692e+01 -5.75109215e+01 -5.48986740e+01 -5.18507233e+01 -5.20390778e+01 -5.54840622e+01 -5.50013809e+01 -5.28447685e+01 -5.56203575e+01 -5.50424118e+01 -5.23490829e+01 -5.04836578e+01 -5.34961548e+01 -5.57388611e+01 -5.29997826e+01 -5.56902657e+01 -6.26758919e+01 -6.48410797e+01 -6.02342262e+01 -5.81530075e+01 -6.24681396e+01 -6.32658310e+01 -6.36325073e+01 -6.15955200e+01 -6.01998634e+01 -5.58884506e+01 -5.48039360e+01 -5.86232872e+01 -5.72852516e+01 -5.56148415e+01 -5.53924141e+01 -5.60767746e+01 -4.82255020e+01 -3.71538811e+01 -3.94436531e+01 -4.65504646e+01 -5.31418610e+01 -5.34806252e+01 -5.34848938e+01 -5.54321022e+01 -5.40237541e+01 -5.85715523e+01 -6.15979729e+01 -6.12787857e+01 -6.30296898e+01 -6.55902481e+01 -6.82730865e+01 -5.28770065e+01 -5.21851158e+01 -5.10042686e+01 -5.56422348e+01 -5.16507492e+01 -5.28904800e+01 -5.77408867e+01 -5.90488129e+01 -6.17808495e+01 -6.58589401e+01 -6.27007408e+01 -5.85091896e+01 -4.83651619e+01 -5.33913307e+01 -5.51589508e+01 -6.41385803e+01 -6.39967880e+01 -5.41352386e+01 -4.70392532e+01 -4.54657135e+01 -5.88463860e+01 -6.06876869e+01 -5.58106537e+01 -5.04102135e+01 -4.50967712e+01 -4.59393845e+01 -4.15659485e+01 -3.99930458e+01 -3.24037933e+01 -3.25034332e+01 -4.02996140e+01 -5.26381378e+01 -5.67033691e+01 -5.28737030e+01 -4.72663231e+01 -4.69175720e+01 -4.26854897e+01 -3.96121635e+01 -3.46051788e+01 -3.69870949e+01 -4.61743546e+01 -4.38749619e+01 -2.41322403e+01 -3.62221599e-01 -7.73624182e+00 -2.97752838e+01 -5.59784317e+01 -4.12293320e+01 -2.85930099e+01 -1.88311920e+01 -2.98363171e+01 -4.41410751e+01 -3.64050751e+01 -2.64026108e+01 -1.86334286e+01 -2.36540451e+01 -2.74309444e+01 -1.79569206e+01 -6.54801369e+00 -3.95555615e+00 -1.82835541e+01 -3.80546951e+01 -4.19749718e+01 -3.31458817e+01 -2.82972507e+01 -2.82907848e+01 -4.38815842e+01 -3.88658829e+01 -2.54118195e+01 -1.50178266e+00 -1.17239122e+01 -2.94604607e+01 -4.95301933e+01 -4.09767265e+01 -3.72123070e+01 -4.14132462e+01 -6.21200294e+01 -8.92845230e+01 -8.63394470e+01 -6.58031769e+01 -3.84513321e+01 -3.44324303e+01 -2.96940060e+01 -1.53385668e+01 -6.06876707e+00 -3.99322090e+01 -8.14804535e+01 -8.97008286e+01 -5.81679268e+01 -3.09600410e+01 -3.81420898e+01 -4.67133026e+01 -5.99379158e+01 -6.88853760e+01 -5.88528557e+01 -4.44832230e+01 -2.19030762e+01 -2.33891563e+01 -1.30032606e+01 -4.16765823e+01 -8.21820450e+01 -9.48296432e+01 -7.48885269e+01 -3.73479729e+01 -1.24425907e+01 5.15264368e+00 6.77121830e+00 -1.69153404e+01 -3.10774746e+01 -4.05027657e+01 -4.41661263e+01 -4.37873116e+01 -5.06124268e+01 -5.38356934e+01 -5.24683914e+01 -5.13791313e+01 -3.69843521e+01 3.78011322e+00 1.07628281e+02 2.05790894e+02 1.91285294e+02 1.98884247e+02 1.79521622e+02 3.29605316e+02 1.37679718e+02 6.84404144e+01 -2.71728973e+02 1.35235242e+03 1.35402115e+02 8.26049377e+02 3.28034888e+03 -3.04405518e+03 -1.54466230e+04 -3.51511484e+04 -543421312. 2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 1442105088. 1442105088. -694983616. -1072801600. -869534464. -362033504. 2.58184141e+04 1.00313115e+04 2.89760132e+03 5.01285797e+02 4.01540161e+02 1.06397682e+02 3.64837151e+01 1.21772394e+01 1.06280518e+01 1.13609180e+01 1.25136375e+01 1.52341337e+01 -3.48336029e+01 -1.52752563e+02 -2.31468994e+02 -1.91242966e+02 -1.48134766e+02 -7.67276077e+01 8.55315628e+01 1.77136414e+02 1.62524277e+02 1.26575661e+02 1.67518097e+02 2.54961411e+02 1.42297607e+02 1.87194748e+02 1.63646881e+02 1.22956818e+02 1.34929895e+01 -2.31948929e+01 -4.17216187e+01 -5.75873489e+01 -7.40924301e+01 -8.98047714e+01 -9.62666473e+01 -8.55513763e+01 -6.48688354e+01 -6.01861343e+01 -5.90458641e+01 -6.90635757e+01 -7.70476227e+01 -8.91562500e+01 -8.00650558e+01 -4.32624893e+01 3.19015026e+00 1.46527863e+01 2.93194383e-01 -2.31558380e+01 -2.98725109e+01 -4.86298828e+01 -4.66043930e+01 -3.92768974e+01 -3.36255035e+01 -4.48441620e+01 -5.52416534e+01 -5.55998344e+01 -7.06162262e+01 -4.89028854e+01 -3.26496887e+01 -1.57606087e+01 -1.71384850e+01 -7.37946749e+00 -1.39973831e+00 -9.31684208e+00 -2.16709213e+01 -2.01234798e+01 -2.55310555e+01 -5.60465813e+01 -6.67376862e+01 -6.14609451e+01 -3.35945969e+01 -2.45119705e+01 -2.28539143e+01 2.05492878e+00 4.06694031e+01 2.90485554e+01 1.42371349e+01 -7.44469929e+00 5.51472549e+01 9.65405579e+01 9.21581268e+01 5.61205177e+01 2.97532196e+01 3.90272446e+01 4.23815384e+01 3.17938747e+01 3.81255150e+01 6.11162643e+01 9.37554474e+01 8.37130661e+01 3.36794930e+01 -1.15893373e+01 -2.81697388e+01 -1.57212067e+01 -7.19747353e+00 3.95560312e+00 -2.67054539e+01 -5.65066833e+01 -3.79852295e+01 6.71241331e+00 2.04449539e+01 -1.30065622e+01 -3.92182350e+01 1.07427607e+01 5.05459175e+01 4.47102203e+01 -9.54226303e+00 -5.59374313e+01 -5.79073029e+01 -5.07556190e+01 -4.13960152e+01 -3.89736977e+01 -2.31441803e+01 -1.48295803e+01 -1.85764256e+01 -2.11460781e+01 -1.29356861e+01 -3.35918903e+00 -1.40185881e+01 -2.56061306e+01 -2.56188583e+01 -1.61486626e+01 -8.47488689e+00 3.13969021e+01 6.86974716e+01 6.27477341e+01 2.22425098e+01 -8.21844578e+00 3.71184883e+01 8.46754761e+01 8.55926132e+01 5.01676903e+01 1.39261541e+01 8.12246799e+00 5.60915709e+00 -1.26138544e+01 -2.28131938e+00 2.27096200e+00 7.49988747e+00 -6.87812233e+00 -2.61024265e+01 -2.09122219e+01 -1.21309166e+01 3.54106545e+00 -1.54149961e+00 -2.42060566e+00 1.37331414e+00 2.34581203e+01 6.39665565e+01 1.06106880e+02 1.01607681e+02 7.25046768e+01 2.69269657e+01 5.66861038e+01 9.32351151e+01 9.19292755e+01 4.18106155e+01 -5.60079241e+00 -3.75427008e-01 1.26495275e+01 2.48650589e+01 2.07486210e+01 1.97827530e+01 1.36158009e+01 4.07392836e+00 4.48656607e+00 2.76668606e+01 6.60686188e+01 6.40674591e+01 4.16848106e+01 5.47325468e+00 -4.05472469e+00 -2.17745137e+00 3.14076385e+01 7.03197708e+01 6.65743790e+01 4.23169403e+01 1.98371468e+01 2.18314590e+01 7.10608768e+00 3.03618183e+01 7.65950851e+01 9.18462448e+01 6.42086945e+01 2.20015697e+01 1.66049442e+01 2.31452789e+01 1.78470688e+01 1.77655735e+01 2.38312073e+01 2.63935204e+01 6.89714355e+01 1.10638977e+02 1.09664917e+02 6.83945312e+01 2.75042477e+01 4.20061874e+01 4.11299057e+01 7.34939117e+01 1.02795662e+02 9.64606018e+01 4.42223129e+01 -2.23953247e+00 1.48662481e+01 2.74336281e+01 3.36085510e+01 1.62756977e+01 5.50854206e+00 -1.55260897e+00 4.17085588e-01 4.34793234e+00 1.04236660e+01 5.55321264e+00 3.77227378e+00 -1.91009369e+01 -3.15838184e+01 -4.06258316e+01 -3.55696716e+01 -2.76038971e+01 -2.60498524e+01 -2.78566055e+01 -2.68219414e+01 -2.00392952e+01 -1.14978933e+01 -2.19848766e+01 -1.49210091e+01 -1.13510914e+01 -1.08637857e+01 -2.93373528e+01 -3.26714211e+01 -1.37238474e+01 -3.12783575e+00 -3.53438663e+00 -1.38409605e+01 -1.51380372e+00 6.62316620e-01 1.59271946e+01 1.53570461e+01 1.53374062e+01 -8.38717651e+00 -3.54664841e+01 -1.25476017e+01 4.15616112e+01 7.37446594e+01 5.96542358e+01 3.41759377e+01 2.63046665e+01 3.38841476e+01 4.07615166e+01 5.37000465e+01 5.70951271e+01 5.14244843e+01 4.14271774e+01 2.56633415e+01 1.47432432e+01 1.41369972e+01 2.02701015e+01 3.11898117e+01 3.50732422e+01 3.54145737e+01 3.28150864e+01 3.43208122e+01 2.76879406e+01 2.50353832e+01 1.40275030e+01 2.64501324e+01 6.34549675e+01 1.01774071e+02 9.81407471e+01 6.77485123e+01 3.53988190e+01 2.61059742e+01 2.40578632e+01 3.85583725e+01 6.34650307e+01 7.81599960e+01 8.70328445e+01 6.00285645e+01 3.51348190e+01 7.35233927e+00 2.19133530e+01 3.41933289e+01 3.60958939e+01 2.65461178e+01 1.91346951e+01 1.20067425e+01 2.15124969e+01 3.73586159e+01 5.13509560e+01 5.31554985e+01 5.24074059e+01 8.35783615e+01 1.13681015e+02 1.01161354e+02 5.77434235e+01 2.39600544e+01 4.44875107e+01 6.28392181e+01 5.80904961e+01 4.96643639e+01 6.92848816e+01 1.02604332e+02 1.00342560e+02 5.97810173e+01 1.92113152e+01 3.15386410e+01 4.90621414e+01 4.75096130e+01 2.57932396e+01 2.25416927e+01 2.87104092e+01 4.50042953e+01 3.33366928e+01 1.25123072e+01 9.95386791e+00 1.53264151e+01 2.29247646e+01 1.12798281e+01 3.93342514e+01 7.36886902e+01 7.65038910e+01 8.44189529e+01 1.04360718e+02 1.36768097e+02 1.39583130e+02 1.18512619e+02 1.24160194e+02 1.01515030e+02 9.74246368e+01 6.72104263e+01 3.70653572e+01 -3.84660721e+00 -1.81749058e+01 -5.10226631e+00 4.24621391e+00 1.49308271e+01 1.45930738e+01 1.88230286e+01 1.42687740e+01 6.20278025e+00 3.21600075e+01 7.62738953e+01 9.64288330e+01 8.57704391e+01 5.53787613e+01 4.84558105e+01 4.04334221e+01 2.52434444e+01 4.21722450e+01 4.88976784e+01 6.24689751e+01 6.65158920e+01 8.18149490e+01 1.07906425e+02 8.21228561e+01 5.49251747e+01 4.42548523e+01 8.02049255e+01 8.88101349e+01 7.36145706e+01 3.83552628e+01 6.77335358e+01 9.58275604e+01 1.08259300e+02 8.23885651e+01 5.56802635e+01 8.24744263e+01 1.10377022e+02 1.02581940e+02 5.95931435e+01 2.84620476e+01 5.60445023e+01 7.44509964e+01 5.25381660e+01 1.10036125e+01 3.79224281e+01 8.50437393e+01 1.07593956e+02 8.65351944e+01 7.18775864e+01 7.76164703e+01 1.03888168e+02 1.25976379e+02 1.14450546e+02 6.69237823e+01 3.20717888e+01 3.43759537e+01 4.59815788e+01 4.67945290e+01 4.40943718e+01 4.82792320e+01 5.81102333e+01 7.47097778e+01 7.39446564e+01 5.37279587e+01 3.91558495e+01 3.33962517e+01 5.87513771e+01 7.71457748e+01 7.37083588e+01 6.28660774e+01 4.37788506e+01 5.20420418e+01 5.27038345e+01 4.48087044e+01 2.55721531e+01 2.61742878e+01 7.22832413e+01 1.09557793e+02 7.64253464e+01 1.56205101e+01 1.21311150e+01 6.26710129e+01 8.13795242e+01 5.10550308e+01 4.05142593e+01 6.05415039e+01 7.11222839e+01 6.26134491e+01 4.29215965e+01 5.65473824e+01 6.84503021e+01 7.82358398e+01 6.59020844e+01 4.67126923e+01 4.75574150e+01 4.83798332e+01 6.89504929e+01 8.31763153e+01 8.33706741e+01 6.34463348e+01 6.27123756e+01 1.11014832e+02 1.34726898e+02 1.21892319e+02 7.85495529e+01 7.54070129e+01 8.86226196e+01 7.10819168e+01 3.25289650e+01 2.30784969e+01 4.97610588e+01 6.98528824e+01 6.25524788e+01 5.13077812e+01 6.43180695e+01 7.09658508e+01 7.50729599e+01 6.77901154e+01 5.22436523e+01 3.99784508e+01 3.47099075e+01 4.34198494e+01 5.34611778e+01 6.66220398e+01 7.22894058e+01 7.60276337e+01 8.67351685e+01 8.70077744e+01 6.85007782e+01 4.89428673e+01 5.36466446e+01 7.57967453e+01 8.19470215e+01 7.73130112e+01 8.95861893e+01 1.22401596e+02 1.42937378e+02 1.29435150e+02 8.87479935e+01 7.74750137e+01 8.39405136e+01 8.77923126e+01 7.25484238e+01 5.57695694e+01 5.23140373e+01 4.62750740e+01 5.24564743e+01 5.93313560e+01 5.97266388e+01 4.60822487e+01 4.42792282e+01 7.30023880e+01 8.74569168e+01 7.41667557e+01 5.64673271e+01 7.42062225e+01 8.72554932e+01 6.94655914e+01 3.59918823e+01 1.40825043e+01 2.14426975e+01 2.49078922e+01 3.36124229e+01 3.29140892e+01 3.59938278e+01 3.46643066e+01 4.43190193e+01 5.44309006e+01 5.27205658e+01 3.62890739e+01 4.36325798e+01 7.76545334e+01 9.92962112e+01 1.03950676e+02 9.40892563e+01 8.22770462e+01 6.52094803e+01 5.35501137e+01 5.36795921e+01 5.14836655e+01 5.07480545e+01 5.26458168e+01 5.75197830e+01 5.63312263e+01 5.70295830e+01 5.80126381e+01 5.64112473e+01 5.63103981e+01 5.68229370e+01 7.18042145e+01 8.71745377e+01 8.62914581e+01 7.29076843e+01 6.22629967e+01 6.32934151e+01 6.21298141e+01 6.27259521e+01 6.13032227e+01 6.32936897e+01 6.35817184e+01 7.27310791e+01 8.33469467e+01 7.86017761e+01 6.46065140e+01 6.12506561e+01 8.33503189e+01 9.87048798e+01 8.91185760e+01 6.73232880e+01 6.57093124e+01 7.41699753e+01 7.39212875e+01 6.42405167e+01 5.51623459e+01 6.43670578e+01 7.29487534e+01 8.20837784e+01 8.47079544e+01 7.42970200e+01 6.35471687e+01 6.43411255e+01 8.38706512e+01 9.23502350e+01 7.95386810e+01 6.20333786e+01 6.53669205e+01 7.77513733e+01 8.05757217e+01 7.30407104e+01 6.53172302e+01 7.03213120e+01 7.56749878e+01 7.79334106e+01 7.23656387e+01 6.59396515e+01 6.24698601e+01 7.01012878e+01 7.84480667e+01 7.89228516e+01 7.25879974e+01 6.17003670e+01 6.66974182e+01 7.16177368e+01 7.37517319e+01 6.81530457e+01 6.72397842e+01 7.28354111e+01 7.12221375e+01 6.47090759e+01 5.64299583e+01 5.55298462e+01 5.44803276e+01 5.97922592e+01 6.54118423e+01 6.78448715e+01 6.45049667e+01 6.00298996e+01 5.72231827e+01 5.80211601e+01 6.47910309e+01 8.84159927e+01 1.08039192e+02 1.20033089e+02 1.08659149e+02 3.53159698e+02 5.27462158e+02 -3.12614075e+02 -2.07209549e+01 3.73411774e+02 4.20712799e+02 4.62951782e+02 1.42356653e+03 3.47438745e+03 386115904. 594307968. 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. 0. -297227584. 586463040. 563237184. 3.53333301e+03 1.18422192e+03 4.42879364e+02 1.57196335e+02 1.25612206e+02 9.01758041e+01 7.96190796e+01 7.87538528e+01 8.44520264e+01 8.67079544e+01 8.36076202e+01 8.72023926e+01 9.56209793e+01 1.02242111e+02 9.43170319e+01 7.62873840e+01 6.81355133e+01 7.41672287e+01 8.52520752e+01 9.09938126e+01 8.73963928e+01 8.58438263e+01 8.84597168e+01 9.43991928e+01 8.98195648e+01 7.92929688e+01 7.47151031e+01 7.93197021e+01 9.05184326e+01 9.36045303e+01 8.50130386e+01 7.07402420e+01 6.46953049e+01 7.27227249e+01 7.23131180e+01 6.23505363e+01 6.65229416e+01 8.62737732e+01 9.99900970e+01 8.51279984e+01 5.10821762e+01 4.13906593e+01 5.69862709e+01 7.66639328e+01 8.44275436e+01 8.40430527e+01 8.06434555e+01 8.04579620e+01 8.28655777e+01 7.98524399e+01 5.36746826e+01 3.61438904e+01 4.46094971e+01 7.03480606e+01 8.51980591e+01 7.39269028e+01 5.64704170e+01 4.84906731e+01 6.55396881e+01 7.01260147e+01 6.17547073e+01 6.75359116e+01 8.72895050e+01 1.06947678e+02 1.04806854e+02 7.13956833e+01 6.11530380e+01 7.01986542e+01 9.54746780e+01 8.99493179e+01 6.90943756e+01 7.55784149e+01 9.27968826e+01 1.03307999e+02 8.74265747e+01 5.46345253e+01 3.77907104e+01 4.94957962e+01 8.39613876e+01 1.04745750e+02 9.76051865e+01 8.35128708e+01 8.79276505e+01 1.04720734e+02 9.91855621e+01 7.56965637e+01 6.43092880e+01 8.92614365e+01 1.23332512e+02 1.26109123e+02 8.83074493e+01 5.67444458e+01 5.23996849e+01 8.00948639e+01 8.27716827e+01 7.77281876e+01 9.54342651e+01 1.31763504e+02 1.48092957e+02 1.15968971e+02 6.23062897e+01 3.50424728e+01 4.88721428e+01 8.12799377e+01 1.13979225e+02 1.36850296e+02 1.33503998e+02 1.27777557e+02 1.30005264e+02 1.19242424e+02 8.34379654e+01 4.85275269e+01 6.87666473e+01 1.20559570e+02 1.47001022e+02 1.26020798e+02 6.90507126e+01 4.13583565e+01 6.30016365e+01 9.08861084e+01 9.53792191e+01 9.49167633e+01 1.17999352e+02 1.66094849e+02 1.62395187e+02 1.18361664e+02 6.86977615e+01 6.85814209e+01 1.03066246e+02 1.27450554e+02 1.31392929e+02 1.13236893e+02 8.92395859e+01 7.78260727e+01 1.09366447e+02 1.24455528e+02 1.03609627e+02 7.50311203e+01 6.79232178e+01 8.39270248e+01 8.64159088e+01 6.98908005e+01 7.06597748e+01 8.74932022e+01 1.09753983e+02 1.11787437e+02 8.58634491e+01 7.60710068e+01 9.46933289e+01 1.15013275e+02 9.05472565e+01 1.29414673e+01 -2.45489883e+01 2.62500572e+01 9.39697342e+01 1.06605843e+02 7.29914703e+01 4.92673035e+01 5.43547173e+01 5.45565948e+01 3.02103157e+01 -8.79529095e+00 -2.65074158e+01 -7.86938667e+00 4.55193825e+01 8.20000153e+01 5.44229393e+01 3.22961197e+01 4.19999084e+01 7.75860519e+01 5.74296455e+01 -5.85446501e+00 -7.16462517e+00 1.69087887e+01 4.57342987e+01 1.71070194e+01 -5.72977676e+01 -9.49061356e+01 -5.66108475e+01 3.07658691e+01 6.76191177e+01 5.87728424e+01 6.04804726e+01 8.79369812e+01 7.44465256e+01 2.20689106e+01 -3.95639267e+01 -2.58371391e+01 2.46516304e+01 1.11867371e+02 1.39441925e+02 1.21401520e+02 5.82883415e+01 1.84220982e+01 1.58593779e+01 -6.64041400e-01 -2.62684269e+01 -9.98664665e+00 4.54530220e+01 1.00650871e+02 6.25938034e+01 -1.92826843e+01 -6.94920731e+01 -1.20512562e+01 8.17052612e+01 1.18788712e+02 7.63969116e+01 2.26019230e+01 4.75299454e+01 9.09225845e+01 8.24718094e+01 2.03366165e+01 -3.96569133e+00 4.75456772e+01 1.26519775e+02 1.40879791e+02 1.04989975e+02 6.60684662e+01 7.13861771e+01 8.76343994e+01 7.82126694e+01 4.92576866e+01 7.24305801e+01 1.12903664e+02 1.20862976e+02 1.09455185e+02 6.63087463e+01 5.27756081e+01 6.91077728e+01 6.54917145e+01 7.24145584e+01 3.24094009e+01 7.05585632e+01 1.01580124e+02 1.26014900e+02 1.00955269e+02 8.16598797e+00 -3.90250702e+01 -2.85497875e+01 7.86530914e+01 1.32263672e+02 1.42306641e+02 1.00505219e+02 7.40052032e+01 1.00768585e+02 9.94124680e+01 6.40616913e+01 4.19457626e+01 7.38796539e+01 1.02544746e+02 4.20548515e+01 -3.58538017e+01 -2.39178448e+01 2.41481819e+01 4.87016602e+01 2.49193306e+01 -3.24647446e+01 2.14898319e+01 5.38332329e+01 9.52191391e+01 6.90563660e+01 6.12541819e+00 -2.51924496e+01 -5.05534706e+01 3.10032129e+00 2.82041512e+01 4.39573479e+01 9.26252902e-01 -3.18386459e+00 -2.35260129e+00 -1.00396185e+01 -3.98939476e+01 -6.05376396e+01 7.00507975e+00 5.05810394e+01 5.55351257e+01 -3.88167810e+00 4.77689171e+00 2.84991608e+01 5.57281075e+01 7.90403442e+01 6.36071091e+01 6.90460434e+01 7.58297539e+00 -1.67359314e+01 -3.05197468e+01 -2.30461979e+01 1.09712803e+00 1.96419258e+01 8.70380707e+01 1.15392570e+02 9.98125534e+01 -4.00538445e+00 -2.45664711e+01 -1.39458311e+00 2.68985386e+01 2.30198822e+01 4.50882645e+01 1.39635529e+02 1.73426605e+02 1.36240952e+02 2.74492836e+01 2.00315022e+00 3.80809250e+01 9.50842514e+01 1.04247047e+02 4.78910828e+01 4.25046959e+01 3.14188900e+01 8.85774994e+01 1.14620216e+02 1.15198120e+02 6.77003479e+01 4.42649460e+01 9.04037781e+01 1.35161896e+02 1.05596481e+02 3.42658730e+01 5.43105888e+01 9.09055481e+01 9.46923828e+01 5.77262154e+01 6.20102615e+01 1.29341721e+02 1.54980743e+02 1.30444153e+02 5.35549965e+01 5.29685478e+01 6.86095047e+01 1.02372269e+02 8.31255646e+01 5.61410446e+01 6.47179947e+01 6.00608826e+01 1.04317329e+02 1.21249367e+02 1.22598991e+02 7.99490662e+01 7.21431732e+01 9.50269547e+01 1.30916275e+02 1.02483742e+02 4.12528381e+01 2.64282646e+01 2.04360142e+01 -2.37712622e+00 -6.05989227e+01 -4.29506989e+01 1.32442617e+01 2.51274490e+01 -1.00078621e+01 -5.80287933e+01 6.83111000e+00 3.49830971e+01 6.91131744e+01 1.06720268e+02 1.26113106e+02 8.66072464e+01 -1.71327019e+01 -4.61062393e+01 3.35800247e+01 1.00495941e+02 5.73576241e+01 -3.44292870e+01 -9.19561768e+01 -2.67962112e+01 2.02918243e+01 9.77841568e+00 -2.41958313e+01 -6.49776382e+01 -1.05721390e+02 -1.71769180e+02 -1.54266434e+02 -8.77746964e+01 -7.01238937e+01 -1.00079758e+02 -1.40324326e+02 -4.85784454e+01 -5.51503038e+00 2.15571938e+01 7.66192722e+00 -1.10298166e+01 -5.62477798e+01 -1.72331894e+02 -1.95194443e+02 -9.72334213e+01 6.64220047e+01 1.00335243e+02 -3.47162857e+01 -1.47981796e+02 -1.47815262e+02 -5.44838219e+01 -1.18235950e+01 -4.18343697e+01 -1.22411049e+02 -1.63281494e+02 -1.17153854e+02 2.35823154e+00 3.70337753e+01 -2.01408997e+01 -1.02859917e+02 -1.95579483e+02 -1.92219589e+02 -1.60242920e+02 -4.40727425e+01 6.65435104e+01 1.11466492e+02 3.82915993e+01 -1.08766701e+02 -1.91179886e+02 -1.13964348e+02 -6.39909554e+00 -1.03393068e+01 -1.30545700e+02 -2.36177216e+02 -1.94262070e+02 -6.63869629e+01 3.87289925e+01 4.96285515e+01 -3.39659653e+01 -9.90815506e+01 -1.51218323e+02 -7.31614685e+01 -3.90450592e+01 -4.67619610e+00 -5.75474129e+01 -9.28095093e+01 -4.06367760e+01 8.27199459e+00 8.91221771e+01 9.45440140e+01 5.91690903e+01 -1.23936596e+01 -1.18520554e+02 -1.47212616e+02 -7.27375107e+01 8.12117386e+01 1.62667053e+02 9.45853806e+01 -6.04587135e+01 -1.51480103e+02 -1.05564941e+02 -3.64087868e+01 -3.74833641e+01 -9.73265305e+01 -1.25009407e+02 -1.28041336e+02 -5.66711502e+01 -1.84385502e+00 5.54540253e+01 5.91989517e+01 2.71082954e+01 -2.00249157e+01 -8.32404785e+01 -8.16597748e+01 -2.50980072e+01 3.72596703e+01 3.77093430e+01 -3.36687012e+01 -1.13398430e+02 -8.33524628e+01 -8.39325428e+00 3.71984406e+01 -2.11041107e+01 -1.20013977e+02 -1.12778053e+02 -4.72281761e+01 5.66587143e+01 5.45166206e+01 -2.37839146e+01 -9.05752411e+01 -1.38423355e+02 -5.28870773e+01 -1.61965981e+01 2.11741505e+01 1.83401337e+01 1.29799767e+01 1.83115139e+01 -2.25539169e+01 1.09477453e+01 5.53338928e+01 5.83759003e+01 -9.08104229e+00 -1.12399063e+02 -1.63647690e+02 -1.07299919e+02 3.25578957e+01 1.46435928e+02 1.31895447e+02 -4.94898748e+00 -1.33697281e+02 -1.78485291e+02 -8.32527542e+01 1.36361761e+01 4.46959610e+01 -2.60058022e+01 -1.10735512e+02 -8.55833282e+01 -2.80502014e+01 3.51856194e+01 4.36436386e+01 2.07990093e+01 -3.41499214e+01 -9.49604111e+01 -8.53410873e+01 -1.29646206e+01 8.26849060e+01 9.43171005e+01 1.51675615e+01 -8.11952362e+01 -6.39793587e+01 2.12570591e+01 7.20174026e+01 3.32349625e+01 -2.05576210e+01 -3.93413620e+01 -5.82473831e+01 -2.74823074e+01 -1.43805075e+00 -2.23114624e+01 -3.34296074e+01 -7.30837936e+01 -2.52181110e+01 5.35080147e+00 6.27400169e+01 9.62746811e+01 5.31789742e+01 4.27239370e+00 -7.60350876e+01 -9.98016739e+01 -5.58735580e+01 2.11380177e+01 2.95261097e+01 -4.80582542e+01 -1.30668137e+02 -1.13845207e+02 -5.93192635e+01 2.49515724e+01 4.30157623e+01 1.01822643e+01 -3.17661152e+01 -5.87706642e+01 3.42846918e+00 5.73677177e+01 1.20078484e+02 1.07291138e+02 2.81471863e+01 2.97633324e+01 5.42268295e+01 1.27916794e+02 1.33797424e+02 1.09887215e+02 5.37787895e+01 -4.27577171e+01 -7.67084732e+01 -5.21940613e+01 3.16959763e+01 6.64650574e+01 -6.04439545e+00 -8.40299530e+01 -9.21067276e+01 7.19726562e+00 7.10918198e+01 5.19421043e+01 -3.84186096e+01 -1.08401253e+02 -1.18133331e+02 -4.26111832e+01 4.36981201e+01 6.53374252e+01 5.56193199e+01 2.10490704e+01 -9.05213451e+00 -5.80871506e+01 -6.20691605e+01 -3.54594955e+01 -1.07682619e+01 -4.09371452e+01 -1.06717545e+02 -1.52477951e+02 -9.61131668e+01 -5.45054388e+00 3.61571884e+01 -1.85337315e+01 -1.13013245e+02 -1.26930626e+02 -7.81030426e+01 1.02234411e+01 2.13898849e+01 -3.11040840e+01 -5.93278313e+01 -6.82276306e+01 -1.38256607e+01 -1.56886682e-01 -7.73100281e+00 -3.44994125e+01 -8.02788620e+01 -6.02848206e+01 -4.88422470e+01 2.27447586e+01 7.70598755e+01 5.97087402e+01 2.49334316e+01 -4.71123505e+01 -2.25163460e+01 6.54939270e+01 1.52807159e+02 1.87991547e+02 1.94001968e+02 6.78486755e+02 3.10959717e+03 1.36303101e+03 1.62572668e+03 4.82515039e+03 1.36677887e+02 7.91347046e+02 8.27101172e+03 8.05724766e+04 -2.73790259e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1953833344. 247863776. -391067040. 1030631616. 2.09693574e+04 8.27801758e+03 2.18763159e+03 1.78367065e+02 1.65574448e+02 4.90323868e+01 1.70680161e+01 5.06236076e+00 -1.87227478e+01 -9.86515732e+01 -1.04321632e+02 -7.51295700e+01 -1.27739315e+01 -2.21775398e+01 -8.35478516e+01 -1.39902176e+02 -1.49223312e+02 -9.27606735e+01 -1.23835955e+01 3.57872057e+00 -5.63558846e+01 -1.23449112e+02 -1.25005638e+02 -7.25063705e+01 -6.73219604e+01 -1.04369766e+02 -1.15166061e+02 -8.95069504e+01 -5.10750275e+01 -5.42075920e+01 -4.30621796e+01 -2.22653828e+01 -2.18665142e+01 -6.15178680e+01 -1.36975372e+02 -1.39848267e+02 -9.34557724e+01 -4.67423248e+01 -4.98605080e+01 -9.85674973e+01 -1.48006042e+02 -1.43670609e+02 -7.53878403e+01 3.37757683e+00 -3.20123649e+00 -8.11448364e+01 -1.18226700e+02 -1.19440529e+02 -7.58947525e+01 -6.07602310e+01 -5.01426468e+01 -4.39985886e+01 -5.90489464e+01 -7.99220200e+01 -1.26737289e+02 -1.08272316e+02 -6.95822296e+01 -5.44508820e+01 -8.46330566e+01 -1.36574036e+02 -1.36079956e+02 -1.11170425e+02 -7.01178436e+01 -5.10555534e+01 -9.28954239e+01 -1.48307266e+02 -1.89987595e+02 -1.69985229e+02 -1.09353294e+02 -8.69900513e+01 -1.23239433e+02 -1.55385117e+02 -1.52008591e+02 -9.26611404e+01 -7.26568375e+01 -8.52759781e+01 -1.10496101e+02 -1.09639435e+02 -1.09238937e+02 -1.23778130e+02 -1.02800011e+02 -7.11034317e+01 -5.58146172e+01 -9.41917038e+01 -1.47417603e+02 -1.60221680e+02 -1.45479492e+02 -1.00628250e+02 -7.69168015e+01 -6.76234055e+01 -1.02128105e+02 -1.18712189e+02 -1.18179024e+02 -6.84884186e+01 -5.08149834e+01 -8.46277466e+01 -1.20003143e+02 -1.19903976e+02 -7.62221603e+01 -5.57384148e+01 -5.82171440e+01 -6.49492493e+01 -7.29072571e+01 -8.94886932e+01 -1.22979424e+02 -1.22885132e+02 -9.25212631e+01 -6.96782990e+01 -7.04196854e+01 -9.92511063e+01 -1.05602631e+02 -8.82542877e+01 -7.13016815e+01 -5.23921127e+01 -5.99036217e+01 -8.99087906e+01 -1.18848785e+02 -1.23778282e+02 -8.31609726e+01 -6.30809555e+01 -7.90087585e+01 -9.26086578e+01 -9.62499771e+01 -7.90250778e+01 -7.95734787e+01 -8.20020523e+01 -7.20417786e+01 -6.99815903e+01 -7.51438751e+01 -1.05625877e+02 -1.00279732e+02 -7.89599838e+01 -6.15708542e+01 -6.80154800e+01 -8.68822861e+01 -8.52435532e+01 -6.90417328e+01 -6.17247429e+01 -5.14508629e+01 -6.59908676e+01 -8.48059998e+01 -1.02376274e+02 -9.99735565e+01 -7.99507217e+01 -7.61125031e+01 -8.31850891e+01 -8.55364761e+01 -8.24938660e+01 -6.77642517e+01 -5.92049255e+01 -5.26750107e+01 -5.26950226e+01 -6.28497543e+01 -7.51826096e+01 -9.58976974e+01 -1.03374084e+02 -9.90455627e+01 -8.61376343e+01 -8.44889526e+01 -9.91482239e+01 -1.12437584e+02 -1.06137627e+02 -8.40498886e+01 -6.87909622e+01 -7.07864151e+01 -9.10365295e+01 -1.00863037e+02 -9.83620224e+01 -8.56639481e+01 -8.29417725e+01 -8.96030960e+01 -8.83038025e+01 -9.10741882e+01 -9.13121033e+01 -9.09877930e+01 -8.12517242e+01 -6.84437790e+01 -7.00383072e+01 -7.31534653e+01 -8.26897888e+01 -8.80707932e+01 -9.15354385e+01 -8.96625137e+01 -8.90012512e+01 -9.48510208e+01 -1.01751671e+02 -9.71775970e+01 -8.73586044e+01 -7.67477036e+01 -7.63105621e+01 -8.35007172e+01 -8.60118637e+01 -8.66144714e+01 -8.12864761e+01 -8.23969727e+01 -8.75288391e+01 -9.23661957e+01 -9.55178070e+01 -9.53602905e+01 -9.87078934e+01 -9.55059128e+01 -8.94718246e+01 -8.48590622e+01 -8.53938675e+01 -8.95123520e+01 -8.95941544e+01 -8.64892273e+01 -8.34763184e+01 -8.08749084e+01 -8.29910660e+01 -8.65103226e+01 -8.96710205e+01 -8.84626007e+01 -8.60321579e+01 -8.55252228e+01 -8.62024918e+01 -8.63660507e+01 -8.63266830e+01 -8.60985641e+01 -8.61091690e+01 -8.63337402e+01 -8.65828629e+01 -8.63513794e+01 -8.59565964e+01 -8.45163193e+01 -8.37426758e+01 -8.39200134e+01 -8.49231567e+01 -8.53034668e+01 -8.53790588e+01 -8.66312332e+01 -8.88328323e+01 -8.93215485e+01 -8.84700851e+01 -8.54876251e+01 -8.46453094e+01 -8.40212708e+01 -8.47284241e+01 -8.60989761e+01 -8.71882706e+01 -8.68028107e+01 -8.44218597e+01 -8.30891800e+01 -8.35501022e+01 -8.59777527e+01 -8.56610336e+01 -8.47456512e+01 -8.27732849e+01 -8.34492874e+01 -8.41883469e+01 -8.43846130e+01 -8.55884018e+01 -8.58358917e+01 -8.74523163e+01 -8.64977951e+01 -8.55072937e+01 -8.41683960e+01 -8.60991440e+01 -8.78133163e+01 -8.96948318e+01 -8.71367264e+01 -8.66202545e+01 -8.62469406e+01 -8.61046829e+01 -8.60002670e+01 -8.71217194e+01 -8.57314529e+01 -8.62959595e+01 -8.69522858e+01 -9.25238419e+01 -9.23941116e+01 -9.01825943e+01 -8.87069702e+01 -8.87736053e+01 -8.89682083e+01 -8.89048309e+01 -9.13615646e+01 -9.12314072e+01 -8.98367157e+01 -8.76985550e+01 -8.93862991e+01 -8.92461319e+01 -8.87778397e+01 -8.59262772e+01 -8.60614853e+01 -8.76334610e+01 -9.14875412e+01 -9.21924438e+01 -9.13285294e+01 -8.56235428e+01 -7.69682312e+01 -7.17628403e+01 -7.27916183e+01 -8.16286774e+01 -8.66174774e+01 -8.80773697e+01 -8.48655472e+01 -7.82001877e+01 -7.94874954e+01 -8.27613831e+01 -8.80447693e+01 -8.58320084e+01 -8.59077301e+01 -8.96443634e+01 -8.94073105e+01 -8.61615753e+01 -8.16861343e+01 -8.62345352e+01 -8.47830048e+01 -8.11257401e+01 -7.43576431e+01 -7.35429001e+01 -7.86551895e+01 -8.55617142e+01 -9.18317566e+01 -1.03227867e+02 -1.09714752e+02 -1.08147255e+02 -9.62664108e+01 -8.40714035e+01 -8.03797760e+01 -7.75417404e+01 -7.65827332e+01 -8.62811203e+01 -1.00782379e+02 -1.01764343e+02 -8.99345169e+01 -7.58329697e+01 -7.47979813e+01 -7.79275970e+01 -7.29886856e+01 -7.29870682e+01 -7.38596802e+01 -7.62115631e+01 -7.38062286e+01 -7.15427933e+01 -7.54474411e+01 -7.79745178e+01 -7.25641708e+01 -6.57301102e+01 -5.54265633e+01 -4.88870316e+01 -5.54557457e+01 -6.19867859e+01 -6.14800262e+01 -5.73691635e+01 -6.67306595e+01 -7.41671906e+01 -7.64642563e+01 -6.27563515e+01 -5.23672066e+01 -4.46113663e+01 -5.73255615e+01 -6.96408768e+01 -8.11511765e+01 -7.07105637e+01 -5.35625954e+01 -3.32804146e+01 -5.12117996e+01 -7.12307129e+01 -8.52121811e+01 -7.40541763e+01 -6.70171432e+01 -6.24744415e+01 -4.77363396e+01 -4.12633171e+01 -4.66383400e+01 -5.91343422e+01 -7.52374420e+01 -7.82580719e+01 -7.86568375e+01 -6.15776787e+01 -4.50870857e+01 -4.09910164e+01 -5.78314514e+01 -6.93930054e+01 -7.51683197e+01 -7.29744339e+01 -7.91100464e+01 -8.91695633e+01 -9.19607925e+01 -9.05999069e+01 -8.24688263e+01 -7.54894333e+01 -7.69786072e+01 -7.75541534e+01 -7.28739853e+01 -6.44835587e+01 -7.27027130e+01 -8.20211334e+01 -6.89256592e+01 -5.49152832e+01 -6.05451355e+01 -9.07048035e+01 -1.03822250e+02 -8.97713242e+01 -7.89946442e+01 -7.67620239e+01 -7.26186371e+01 -4.81991234e+01 -4.21998329e+01 -3.32368317e+01 -3.95380554e+01 -4.38185425e+01 -5.67365227e+01 -6.80207291e+01 -5.95795288e+01 -6.29431381e+01 -6.41518173e+01 -6.75140457e+01 -6.29841995e+01 -6.91379013e+01 -4.62601509e+01 -3.09550362e+01 -1.97533131e+01 -3.81709671e+01 -5.69068222e+01 -6.37430687e+01 -6.98997726e+01 -6.54289780e+01 -6.63166809e+01 -5.53719826e+01 -7.40377502e+01 -8.90058746e+01 -1.13974747e+02 -1.11506645e+02 -9.39537582e+01 -7.44998093e+01 -7.40913467e+01 -8.24758072e+01 -8.41350784e+01 -7.57948837e+01 -7.04455261e+01 -9.85443726e+01 -1.28122452e+02 -1.32297607e+02 -9.43543015e+01 -5.80094376e+01 -5.50889816e+01 -7.33175659e+01 -1.19257179e+02 -2.43214371e+02 -1.71213959e+02 -3.59901489e+02 -2.03809113e+02 -2.01270569e+03 -3.12772632e+03 -2.19800095e+02 -2.64205933e+02 -3.99961884e+02 -2.18669815e+02 -4.65699188e+02 -8.45272095e+02 -3.04405518e+03 -1.54466230e+04 -3.51511484e+04 -543421312. 2.72317696e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1682441600. 613805696. -635087040. -1.38181318e+04 -5.34608740e+03 -9.75133728e+02 -7.70844666e+02 -6.25215820e+02 -2.55323257e+02 -1.38184219e+02 -1.31061508e+02 -9.25014572e+01 -5.77466774e+01 -5.74364815e+01 -6.08053551e+01 -6.79035187e+01 -6.97285309e+01 -9.68575058e+01 -1.13475960e+02 -8.94326706e+01 -4.07878532e+01 -3.10047970e+01 -6.33380127e+01 -8.12323456e+01 -6.26174812e+01 -5.91984329e+01 -7.07178574e+01 -8.17771149e+01 -8.85553818e+01 -1.03515663e+02 -1.03327827e+02 -8.09710999e+01 -6.97025299e+01 -6.05066071e+01 -7.39352951e+01 -3.74076996e+01 -4.54406834e+00 8.72116566e+00 -1.05320368e+01 -3.44688911e+01 -2.56921520e+01 -1.47245779e+01 -7.73425055e+00 7.07462788e+00 1.54822931e+01 2.63346138e+01 3.12418804e+01 3.77333298e+01 2.32982578e+01 6.46493435e+00 -2.97227931e+00 9.00636387e+00 9.24582958e+00 -2.09214568e+00 -1.64495850e+00 8.15715373e-01 1.47707405e+01 1.87277718e+01 7.50475836e+00 -3.00639820e+01 -7.01606979e+01 -9.35923309e+01 -6.98677902e+01 -4.72440758e+01 -2.33469105e+01 -5.37187462e+01 -6.98461990e+01 -5.86786461e+01 -1.85080376e+01 1.51055002e+01 1.66576061e+01 1.37654371e+01 3.31187897e+01 7.09321518e+01 4.27017174e+01 -1.96763382e+01 -6.52945251e+01 -5.55210381e+01 -2.11965466e+01 -2.56997051e+01 -1.24542637e+01 -1.38055515e+01 -2.31133509e+00 -8.13181782e+00 -1.14599876e+01 -3.33766251e+01 -3.69911041e+01 -3.78189697e+01 -1.44843826e+01 -1.67598019e+01 -5.06305580e+01 -1.01190559e+02 -9.22501755e+01 -5.67971077e+01 -1.82845402e+01 -2.94383564e+01 -5.23587418e+01 -7.49728088e+01 -8.88175659e+01 -5.49941063e+01 -1.15685940e+01 -2.42748141e+00 -2.36137390e+01 -7.01764755e+01 -6.05171204e+01 -5.15652695e+01 -3.03798466e+01 -2.39436722e+01 -3.67168350e+01 -3.38813896e+01 -3.53870926e+01 -2.10841999e+01 -1.94733810e+01 -1.42527018e+01 -1.35197926e+01 -4.24114647e+01 -7.94104233e+01 -7.91924973e+01 -4.37647247e+01 -4.90250969e+00 2.56761265e+00 9.27252674e+00 1.18657732e+01 1.96823673e+01 2.28049812e+01 2.56021938e+01 -1.85106792e+01 -6.70448074e+01 -7.84699936e+01 -4.40752144e+01 -2.96262169e+00 1.43224564e+01 1.89487915e+01 1.74585438e+01 4.67166376e+00 2.12014461e+00 1.37595606e+01 5.91410220e-01 -2.59704638e+00 -6.08513308e+00 3.60679366e-02 -4.01358891e+00 -4.65521526e+00 -6.81417131e+00 2.29701877e+00 -1.49986267e+00 -6.04931259e+00 -7.16483879e+00 -4.75351524e+00 -7.80989838e+00 -2.14703426e+01 -2.43413696e+01 -6.37047195e+00 3.32504797e+00 7.36078453e+00 3.29133153e-01 9.37032795e+00 1.71490364e+01 2.22575874e+01 5.32332706e+00 -5.43992004e+01 -8.82855911e+01 -8.94259796e+01 -6.95291824e+01 -5.27200165e+01 -4.50296173e+01 -2.05775928e+01 -8.95623779e+00 -1.86485062e+01 -2.45878677e+01 -2.07000904e+01 -1.23317480e+01 -1.66621437e+01 -7.06999779e+00 3.53836021e+01 7.82148514e+01 1.03319580e+02 9.45690231e+01 5.51244926e+01 1.60309811e+01 -2.37040901e+01 -1.57008028e+01 -6.92397594e+00 6.02230453e+00 5.76775503e+00 1.32695284e+01 3.35219216e+00 6.88606548e+00 1.14494219e+01 9.89656448e+00 1.15442920e+00 3.26520324e+00 1.05217390e+01 1.74773159e+01 -2.17706060e+00 -1.10589867e+01 -1.91323280e+01 -1.84938412e+01 -3.99378371e+00 3.50759964e+01 7.75504990e+01 9.89131927e+01 9.37835007e+01 8.79873886e+01 9.62218628e+01 6.91671524e+01 2.92915001e+01 -1.36727800e+01 -2.34400349e+01 -1.92362537e+01 -8.53446198e+00 -1.60943949e+00 -1.34497142e+00 -2.12585735e+01 -2.27488155e+01 -2.32143955e+01 -1.47726479e+01 -8.34576797e+00 -8.47566223e+00 -3.89309273e+01 -8.00790710e+01 -6.56986694e+01 -2.65637283e+01 9.58920956e+00 3.12752666e+01 5.22096367e+01 9.65572815e+01 1.19457680e+02 1.01733185e+02 7.36494598e+01 2.48764687e+01 4.51838760e+01 5.89643250e+01 7.66763000e+01 6.76109238e+01 5.98649368e+01 6.12104836e+01 6.66169052e+01 5.95786781e+01 4.80089684e+01 3.34445686e+01 3.63383484e+01 6.96594315e+01 1.09754868e+02 1.44222198e+02 1.54770462e+02 7.94897385e+01 3.02225780e+00 -3.52054977e+01 -4.38497448e+00 4.19839706e+01 3.51584282e+01 4.14944992e+01 3.14260330e+01 3.46294670e+01 3.34750175e+01 2.88763542e+01 2.58800182e+01 2.93941288e+01 3.18517056e+01 5.86828701e-02 -4.28912430e+01 -5.32036552e+01 -3.61274872e+01 -3.59285450e+00 1.50926304e+01 4.88525429e+01 5.16504250e+01 3.78163605e+01 2.88841553e+01 5.02648277e+01 4.86947899e+01 2.91487617e+01 6.14456797e+00 5.63790655e+00 1.32987995e+01 1.68610783e+01 2.08341904e+01 1.92747459e+01 2.52437572e+01 2.40906677e+01 2.35331516e+01 1.15240660e+01 8.61697578e+00 1.11372766e+01 4.68899422e+01 8.66188965e+01 8.14740143e+01 4.79349594e+01 1.57788048e+01 2.83329067e+01 3.73087502e+01 4.29798584e+01 4.78884315e+01 5.58099556e+01 6.12828941e+01 8.75510406e+01 9.64014130e+01 9.28792191e+01 5.12821808e+01 2.29654865e+01 1.79534302e+01 3.01398239e+01 1.14804859e+01 -1.53674440e+01 -2.88974609e+01 -2.03926506e+01 1.32688751e+01 1.45614729e+01 1.91939507e+01 1.57165022e+01 1.81389065e+01 2.47073097e+01 1.93246994e+01 1.33475084e+01 1.51709385e+01 1.24984751e+01 1.14272470e+01 1.03386278e+01 2.69832764e+01 3.40756416e+01 5.97033157e+01 8.51925888e+01 8.59732361e+01 6.94657059e+01 4.94454918e+01 5.34210472e+01 4.83383751e+01 3.01648464e+01 3.66707344e+01 7.14188766e+01 1.05624290e+02 1.04087646e+02 6.68759308e+01 4.18251419e+01 4.50143433e+01 5.73450928e+01 6.55334320e+01 6.34617577e+01 8.96475830e+01 1.21400047e+02 1.25021332e+02 9.37816238e+01 4.75585251e+01 5.25865479e+01 5.76244545e+01 6.67290344e+01 5.79626999e+01 5.17081566e+01 6.26446190e+01 7.38165436e+01 8.25582581e+01 7.12669220e+01 6.55733032e+01 7.10741806e+01 1.03911911e+02 1.49532928e+02 1.52613907e+02 1.21008209e+02 7.84375076e+01 6.77480850e+01 5.98839302e+01 6.22677612e+01 7.06075821e+01 1.12474991e+02 1.41466568e+02 1.75404037e+02 1.75081894e+02 1.44487305e+02 1.14254883e+02 7.80588913e+01 9.86298141e+01 1.22609497e+02 1.00484390e+02 4.25102272e+01 9.47735977e+00 2.66755028e+01 6.83700714e+01 6.58202057e+01 6.43001633e+01 5.12797546e+01 4.94856911e+01 3.64285774e+01 4.07383614e+01 3.68112526e+01 3.89647064e+01 3.47738533e+01 3.56793213e+01 3.38080673e+01 3.50238304e+01 4.07141151e+01 6.16066628e+01 8.94373550e+01 8.53252640e+01 6.64680252e+01 3.37635231e+01 6.31814842e+01 9.82230682e+01 6.83621902e+01 7.49312925e+00 2.07381153e+00 7.80780029e+01 1.17844223e+02 9.17897873e+01 5.66884499e+01 7.61748123e+01 1.11250824e+02 1.16068886e+02 9.53911896e+01 6.76705704e+01 6.94542770e+01 7.79867401e+01 7.32653503e+01 7.50770035e+01 5.43131866e+01 3.32343864e+01 5.65589485e+01 1.02783401e+02 1.28424377e+02 1.08201080e+02 8.66023254e+01 1.10675812e+02 1.33243805e+02 1.41184219e+02 1.16330048e+02 8.61122818e+01 8.65649033e+01 9.56756058e+01 1.01753174e+02 8.69850159e+01 9.59391937e+01 1.18247192e+02 1.30056686e+02 1.26907921e+02 9.76787720e+01 8.49531097e+01 6.94622498e+01 6.59443359e+01 6.57597961e+01 3.41061974e+01 -8.54444563e-01 1.03390636e+01 6.12052612e+01 9.98674850e+01 9.09406357e+01 6.82014999e+01 8.59419556e+01 1.11917290e+02 1.14965538e+02 9.58630142e+01 7.19181213e+01 6.85994110e+01 6.97337112e+01 6.66500168e+01 7.11124191e+01 7.31488724e+01 8.01595535e+01 8.82378616e+01 9.05242615e+01 8.38083725e+01 7.18679123e+01 6.71002274e+01 6.34398994e+01 6.99805069e+01 5.03191109e+01 3.07812519e+01 4.73670235e+01 9.45981598e+01 1.20801010e+02 9.69120331e+01 6.65195999e+01 5.02737083e+01 4.65635986e+01 4.70875282e+01 5.26129341e+01 5.57132072e+01 5.40336456e+01 6.02517052e+01 5.65940819e+01 5.79639359e+01 5.33262062e+01 5.36884804e+01 5.24897995e+01 5.91340408e+01 6.80194473e+01 6.45409775e+01 5.51953392e+01 5.14315948e+01 6.23519936e+01 7.23386002e+01 7.82114792e+01 8.98872452e+01 1.06351524e+02 1.08331009e+02 9.84780350e+01 9.83069229e+01 1.33147537e+02 1.53114899e+02 1.39516266e+02 1.13825562e+02 1.19814240e+02 1.41273926e+02 1.45174973e+02 1.25625504e+02 1.08301926e+02 1.02511276e+02 1.03497803e+02 1.04354034e+02 1.05345230e+02 1.00908363e+02 9.42002869e+01 1.01716492e+02 1.19138405e+02 1.25670952e+02 1.14164490e+02 9.62456284e+01 9.78871765e+01 1.08218307e+02 9.67200394e+01 7.79796066e+01 6.87744751e+01 7.65311279e+01 8.59587555e+01 8.11473389e+01 8.22032089e+01 8.24482346e+01 8.23187180e+01 7.99907227e+01 8.03587189e+01 8.34997101e+01 7.94485626e+01 7.66615829e+01 7.25230789e+01 7.50492554e+01 7.93068466e+01 7.87527237e+01 8.93748703e+01 1.00572899e+02 1.01541756e+02 9.04500351e+01 7.24181900e+01 6.77148514e+01 6.78545914e+01 6.26132660e+01 5.30075226e+01 5.12369461e+01 5.98338737e+01 7.22402115e+01 7.40855103e+01 7.50613098e+01 8.81276550e+01 1.02843246e+02 1.06595657e+02 9.56511383e+01 8.76096802e+01 8.97648163e+01 8.89333725e+01 8.48781204e+01 8.44150848e+01 8.08873520e+01 7.29207687e+01 7.63699951e+01 8.70881042e+01 9.56517792e+01 9.09801712e+01 9.26633377e+01 1.07300011e+02 1.16219841e+02 1.10863892e+02 9.54111404e+01 9.19666672e+01 9.68201065e+01 9.70788727e+01 8.97118073e+01 8.02952347e+01 8.23207474e+01 8.84013977e+01 8.96651077e+01 8.75944977e+01 8.28646240e+01 8.06629486e+01 7.88893967e+01 7.83043442e+01 8.11721191e+01 8.01448364e+01 7.91453934e+01 8.24196472e+01 8.76805954e+01 8.90414963e+01 8.51311188e+01 8.25634155e+01 8.52662964e+01 8.88042755e+01 8.83891449e+01 8.71361923e+01 8.19406128e+01 7.53840332e+01 6.15574608e+01 5.07091064e+01 4.25312691e+01 2.79750843e+01 4.07873802e+01 7.85759430e+01 1.23348877e+02 1.67597107e+02 3.16600677e+02 8.94131836e+02 386115904. 594307968. 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. 1143110144. 446722944. 4.02959302e+03 1.74277026e+03 6.52376099e+02 5.90466919e+02 3.96424377e+02 1.64719315e+02 1.33331436e+02 1.19833481e+02 1.17943817e+02 1.15530907e+02 1.13703110e+02 1.17743423e+02 1.21222443e+02 1.19091682e+02 1.10801392e+02 1.06164948e+02 1.10376984e+02 1.20899384e+02 1.13220222e+02 1.00139229e+02 8.34212952e+01 8.14666290e+01 8.63939743e+01 9.98327179e+01 1.05127792e+02 1.10146713e+02 1.02396629e+02 1.04918739e+02 1.00509789e+02 8.74209366e+01 8.37965317e+01 9.50566940e+01 1.07845062e+02 1.13360130e+02 1.13427940e+02 1.19974174e+02 1.29079941e+02 1.31308121e+02 1.19476318e+02 8.92561264e+01 7.23067780e+01 8.03824921e+01 1.02522484e+02 1.16570236e+02 1.16239670e+02 1.09417000e+02 9.97987900e+01 1.04281700e+02 9.91314468e+01 9.43528214e+01 9.76098633e+01 1.18766495e+02 1.44740082e+02 1.40489975e+02 1.06280579e+02 8.68367462e+01 9.71103745e+01 1.18967857e+02 1.14852142e+02 9.52018738e+01 9.41709137e+01 1.12602066e+02 1.34701721e+02 1.28652573e+02 9.67392960e+01 7.48973160e+01 8.53224716e+01 1.07752899e+02 1.09616310e+02 1.01708603e+02 1.01199852e+02 1.21302315e+02 1.39482025e+02 1.32819000e+02 1.19632622e+02 1.20362267e+02 1.34884277e+02 1.43555817e+02 1.38444397e+02 1.18856056e+02 9.87704620e+01 9.17209091e+01 1.05400642e+02 1.16019569e+02 1.10938309e+02 1.26219276e+02 1.55934692e+02 1.70607407e+02 1.43106476e+02 9.43978806e+01 6.96419067e+01 8.30016632e+01 1.21456116e+02 1.59037842e+02 1.74347137e+02 1.64088715e+02 1.55387466e+02 1.60697815e+02 1.52130203e+02 1.12708946e+02 8.10548172e+01 8.87639008e+01 1.24107506e+02 1.42784210e+02 1.33960495e+02 1.06081039e+02 9.45207367e+01 1.10030228e+02 1.23594826e+02 1.21581505e+02 1.16353020e+02 1.36688385e+02 1.76089142e+02 1.83821411e+02 1.53494873e+02 1.12163467e+02 1.12870125e+02 1.35993637e+02 1.61321838e+02 1.62306244e+02 1.38848618e+02 1.07604271e+02 9.18403854e+01 1.09238487e+02 1.08621094e+02 8.79122314e+01 8.53185272e+01 1.13622536e+02 1.46701309e+02 1.43795990e+02 1.13021545e+02 9.62599869e+01 1.14493469e+02 1.31287201e+02 1.39532486e+02 1.26203133e+02 1.39650726e+02 1.67195969e+02 1.73573395e+02 1.31322189e+02 5.55694771e+01 1.90227375e+01 5.09099808e+01 9.48101044e+01 1.07372086e+02 9.14115448e+01 7.28743515e+01 7.73582764e+01 7.58192825e+01 6.32032547e+01 2.89517536e+01 1.64019871e+01 4.89405785e+01 1.25334061e+02 1.63644135e+02 1.27396446e+02 7.70856247e+01 7.64749451e+01 9.86357880e+01 8.12566910e+01 2.31312389e+01 2.92755814e+01 7.69764786e+01 1.30640915e+02 8.97598267e+01 6.75067282e+00 -4.44694099e+01 -1.27268496e+01 5.01469116e+01 8.54327698e+01 9.01359558e+01 1.03747208e+02 1.23045860e+02 1.06647850e+02 5.18853302e+01 -1.67891464e+01 8.71562672e+00 6.32745285e+01 1.15407089e+02 1.08196320e+02 8.50834274e+01 5.93152847e+01 4.18197060e+01 4.28467941e+01 2.80628834e+01 2.53146924e-02 1.22887325e+01 7.36604156e+01 1.33645355e+02 1.08274384e+02 3.34936562e+01 -2.15651264e+01 7.49672604e+00 5.86826553e+01 9.64065628e+01 9.14610901e+01 1.08191650e+02 1.54488632e+02 1.75469543e+02 1.25663956e+02 4.59054871e+01 3.07381401e+01 6.27952423e+01 1.25543594e+02 1.44946091e+02 1.42160324e+02 1.07195473e+02 7.50871735e+01 7.32066269e+01 5.33361855e+01 3.43874245e+01 6.26440811e+01 1.14553917e+02 1.32610825e+02 1.16194565e+02 7.48748169e+01 6.23837471e+01 7.81272354e+01 8.10404663e+01 8.23862076e+01 5.67983360e+01 8.73297348e+01 1.32889816e+02 1.57593796e+02 1.68169876e+02 9.70102158e+01 5.59092636e+01 7.23854675e+01 1.40108002e+02 1.54069870e+02 1.03382378e+02 5.51862679e+01 5.65169792e+01 8.94882660e+01 8.74204330e+01 4.64515915e+01 4.12765923e+01 8.42615280e+01 1.20897377e+02 9.01399307e+01 7.32781830e+01 1.02347206e+02 1.14227699e+02 8.53131256e+01 6.16672287e+01 4.35064926e+01 6.21191826e+01 2.82536602e+01 1.87532997e+01 2.24411545e+01 1.74128437e+01 -6.21430254e+00 -2.30462837e+01 4.91072044e+01 7.65654984e+01 8.89358902e+01 3.05394745e+01 4.56837654e+01 4.99739647e+01 2.77596340e+01 -1.86009712e+01 -3.74825745e+01 4.32561150e+01 8.39507141e+01 8.48562469e+01 1.32845984e+01 3.97742927e-01 3.08875484e+01 6.18898010e+01 7.73565903e+01 1.88850060e+01 3.44539604e+01 5.85993996e+01 1.25189949e+02 1.50996902e+02 1.37405762e+02 8.00917969e+01 3.27158012e+01 6.54877014e+01 1.15731209e+02 1.38143066e+02 1.04978256e+02 1.36447433e+02 1.36573563e+02 1.02038742e+02 3.14507904e+01 3.29465790e+01 1.14361122e+02 1.43434875e+02 1.09478508e+02 2.91437950e+01 5.56174049e+01 9.07529984e+01 1.18985481e+02 9.58300934e+01 5.75112343e+01 5.48631363e+01 3.44751778e+01 8.59396896e+01 1.10782364e+02 1.25051277e+02 7.70912628e+01 5.31362839e+01 8.04987411e+01 1.12654495e+02 1.21674721e+02 1.35903885e+02 2.01123108e+02 2.37821808e+02 2.23268326e+02 2.05397049e+02 2.06137390e+02 2.46880890e+02 2.57196320e+02 2.26928558e+02 1.47616425e+02 1.18956696e+02 1.10578087e+02 1.21299232e+02 9.38926849e+01 3.84452324e+01 1.02726984e+01 6.83843422e+00 6.32674828e+01 8.88370285e+01 9.38456039e+01 7.38993073e+01 8.81357193e+01 1.14235756e+02 1.45828674e+02 1.46207352e+02 1.41691772e+02 1.85053635e+02 2.19996933e+02 1.99688858e+02 1.39815781e+02 1.17161369e+02 1.19074890e+02 6.29588318e+01 2.23309307e+01 1.05972600e+00 6.68573608e+01 7.31635513e+01 7.78696747e+01 1.09309273e+02 1.09081367e+02 7.07867050e+01 -1.28979073e+01 -3.16736012e+01 3.52846107e+01 1.00259964e+02 9.70227509e+01 3.76928101e+01 -1.32754145e+01 1.38989906e+01 6.95841446e+01 1.22454895e+02 1.21270554e+02 7.16431885e+01 2.84743748e+01 -2.53512955e+01 -3.00678978e+01 -2.98832359e+01 -5.12099113e+01 -4.66921005e+01 -5.18106194e+01 2.66345081e+01 2.88495636e+01 2.89877319e+01 2.71624584e+01 1.80710983e+01 -2.05408802e+01 -1.38835297e+02 -1.61235092e+02 -8.41642227e+01 7.71056213e+01 1.56810699e+02 6.10826950e+01 -6.53604507e+01 -7.37226334e+01 6.70254059e+01 2.09491425e+02 1.68673126e+02 4.23499146e+01 -4.94889755e+01 -3.54373322e+01 5.87952232e+01 6.40764008e+01 9.14818859e+00 -4.86158867e+01 -6.30723915e+01 1.62669430e+01 1.42037153e+01 -2.62390423e+01 -6.64105148e+01 -6.33715820e+01 -1.57640572e+01 -4.52051010e+01 -4.58067627e+01 3.78154259e+01 1.35557068e+02 1.17097084e+02 -4.94977531e+01 -1.53781616e+02 -1.11006401e+02 1.50500259e+01 8.20725937e+01 5.36847687e+01 -3.67658653e+01 -6.90973663e+01 -8.14128265e+01 6.60721958e-01 7.46408367e+00 -9.88657570e+00 -5.01766396e+01 -8.76332092e+01 -2.42759590e+01 1.92787457e+01 9.35542984e+01 9.45483170e+01 6.24199600e+01 -4.20212328e-01 -1.08572838e+02 -1.46845612e+02 -7.76542816e+01 8.51712036e+01 1.72003433e+02 9.38777466e+01 -7.56262436e+01 -1.25496681e+02 9.98093319e+00 1.63601089e+02 1.63843735e+02 1.87623329e+01 -4.48434029e+01 -4.01379509e+01 3.52051735e+01 4.41722527e+01 -5.62211323e+00 -6.99520950e+01 -1.27921394e+02 -1.20348839e+02 -1.53989044e+02 -1.48536469e+02 -8.58520355e+01 1.79354935e+01 5.07636032e+01 -2.81134644e+01 -1.06946762e+02 -8.31584702e+01 3.34519196e+01 1.27925079e+02 8.92691956e+01 -3.13977547e+01 -6.15181999e+01 -1.60531063e+01 7.82325821e+01 5.46661263e+01 -1.53946609e+01 -9.31867065e+01 -1.38268082e+02 -8.04970779e+01 -7.90871582e+01 -4.71302719e+01 -6.47114716e+01 -7.24679565e+01 -9.15504074e+01 -1.39352005e+02 -9.85540771e+01 -3.36593285e+01 4.55046387e+01 1.13833780e+01 -9.23178864e+01 -1.67918381e+02 -1.08446342e+02 2.24616623e+00 7.32132568e+01 6.61571198e+01 -8.05342484e+00 -3.94014893e+01 -5.53110466e+01 -1.60450325e+01 -4.12836380e+01 -7.66914444e+01 -1.24943184e+02 -1.71152603e+02 -1.52148300e+02 -6.80456467e+01 7.91620874e+00 1.40239925e+01 -2.78956661e+01 -7.01619873e+01 -1.29136902e+02 -1.59494370e+02 -8.10663681e+01 4.86034470e+01 1.08626518e+02 2.03482304e+01 -7.99797974e+01 -9.19145889e+01 1.90795803e+01 1.36715210e+02 1.23752098e+02 -1.64168777e+01 -1.64944504e+02 -2.18535904e+02 -1.26435410e+02 -5.28641281e+01 -5.04032593e+01 -9.09020767e+01 -1.18001518e+02 -6.97321091e+01 -6.57122879e+01 -5.09182854e+01 -1.08943377e+01 -2.10158420e+00 -2.68619323e+00 -7.29125671e+01 -6.38788643e+01 9.64600372e+00 1.02631767e+02 8.86417236e+01 -5.62109222e+01 -1.64309906e+02 -1.30618515e+02 -7.79444933e+00 7.89236374e+01 8.06275940e+01 -1.71416588e+01 -1.14696945e+02 -1.60612137e+02 -8.48141098e+01 -2.75787735e+01 2.10474930e+01 1.08453131e+01 -1.29363174e+01 -8.16314220e+00 -4.90234995e+00 6.17863846e+01 9.90717010e+01 9.86032257e+01 4.73407478e+01 -5.34170914e+01 -9.29301605e+01 -3.75977211e+01 5.96177444e+01 8.97945938e+01 2.90559025e+01 -6.72871475e+01 -6.74713440e+01 -6.90028965e-01 9.31210251e+01 1.11299812e+02 1.58808651e+01 -7.65569763e+01 -1.18117485e+02 -4.35355873e+01 2.69793034e+01 3.00202694e+01 -1.51590099e+01 -7.49946060e+01 -8.84054337e+01 -9.70888824e+01 -6.08719101e+01 1.19155111e+01 3.12920399e+01 -3.28126144e+01 -1.42627457e+02 -1.78749207e+02 -1.18184296e+02 -3.14633560e+01 2.48408318e+01 -1.33640480e+01 -9.42014008e+01 -1.37866714e+02 -1.15243881e+02 -5.84190521e+01 -5.68810272e+01 -9.47727890e+01 -1.37906708e+02 -1.38715607e+02 -7.20750351e+01 -2.53824635e+01 -4.73705368e+01 -9.98510208e+01 -1.69131287e+02 -1.62429520e+02 -1.62450027e+02 -1.31942535e+02 -9.14561996e+01 -6.58799896e+01 -5.85067177e+01 -1.16999023e+02 -1.54242615e+02 -1.32791000e+02 -7.91130981e+01 -2.80208683e+01 -6.44830246e+01 -1.17758965e+02 -1.50399979e+02 -8.03972244e+01 3.44030228e+01 8.76540680e+01 2.26480980e+01 -1.11281975e+02 -1.41576996e+02 -2.11158905e+01 1.13707062e+02 -2.25062618e+01 1.71927509e+01 -2.09800529e+01 -2.46603851e+01 -6.07530884e+02 1.48394189e+03 2.97750049e+03 8.42532910e+03 3.03255820e+04 -4.30840986e+09 199014400. 4.81494426e+09 438012832. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 395975776. 1039180928. 1.53886475e+04 5.42511670e+03 -1.27893341e+02 6.27001526e+02 3.49654102e+03 2.18134131e+03 2.68785492e+02 3.52806511e+01 1.02881317e+02 2.50385838e+01 -7.92679291e+01 -1.29669373e+02 -1.25620796e+02 -6.17225494e+01 -2.38184757e+01 -3.72728119e+01 -1.15183487e+02 -1.78147018e+02 -1.66698013e+02 -1.22058235e+02 -1.12915382e+02 -1.13071136e+02 -1.09372314e+02 -7.19980774e+01 -1.00745712e+02 -1.08510315e+02 -6.31611023e+01 -2.23829975e+01 -5.24812050e+01 -1.45223297e+02 -1.92967194e+02 -1.34348343e+02 -6.12904663e+01 -1.66019688e+01 -4.36729546e+01 -1.27813744e+02 -1.94347855e+02 -2.28940491e+02 -1.67245041e+02 -1.21341988e+02 -1.11837120e+02 -1.56007339e+02 -1.84145355e+02 -1.57658737e+02 -1.50817520e+02 -1.23549057e+02 -9.84483185e+01 -8.81336212e+01 -1.15025429e+02 -1.89558716e+02 -1.94630692e+02 -1.31362518e+02 -5.53253479e+01 -3.32228241e+01 -9.51387482e+01 -1.57404999e+02 -1.56838196e+02 -1.10477455e+02 -8.94833069e+01 -1.37153412e+02 -2.11690781e+02 -2.28388855e+02 -1.97833740e+02 -1.18133003e+02 -6.52758789e+01 -6.46713791e+01 -1.14432922e+02 -1.77437317e+02 -2.15980392e+02 -2.33072601e+02 -2.16300201e+02 -1.80663940e+02 -1.41042969e+02 -1.22837288e+02 -1.36582199e+02 -1.32219208e+02 -9.06214066e+01 -5.15062332e+01 -5.48290939e+01 -1.03141464e+02 -1.39669708e+02 -1.28653809e+02 -1.09050720e+02 -7.49864807e+01 -5.52897339e+01 -7.45498505e+01 -1.26968666e+02 -1.60738678e+02 -1.30038712e+02 -9.40565796e+01 -9.53083954e+01 -1.20457596e+02 -1.25999146e+02 -1.14729546e+02 -1.22752663e+02 -1.19387436e+02 -9.97553864e+01 -8.61254654e+01 -1.01905945e+02 -1.52247681e+02 -1.57673462e+02 -1.10097260e+02 -4.77565346e+01 -2.97218132e+01 -6.96554642e+01 -1.16928406e+02 -1.31944214e+02 -1.25448906e+02 -1.07376991e+02 -1.06935013e+02 -1.15820854e+02 -1.40341553e+02 -1.52953751e+02 -1.29398819e+02 -8.60671997e+01 -7.48322372e+01 -9.12091141e+01 -1.09214409e+02 -1.10687119e+02 -1.26619698e+02 -1.26383095e+02 -9.08263397e+01 -5.29249344e+01 -5.46625290e+01 -1.06037659e+02 -1.27582314e+02 -9.92792969e+01 -5.89509926e+01 -5.26958580e+01 -9.18720932e+01 -1.31014603e+02 -1.40889465e+02 -1.25107025e+02 -9.58866653e+01 -7.32440414e+01 -8.26121368e+01 -1.13817863e+02 -1.35446014e+02 -1.15213776e+02 -8.28668518e+01 -7.32576981e+01 -8.58481827e+01 -1.02054695e+02 -1.12385376e+02 -1.28788574e+02 -1.32382019e+02 -1.22941795e+02 -1.09990479e+02 -1.10647049e+02 -1.27296638e+02 -1.36532761e+02 -1.19424141e+02 -8.65844116e+01 -6.20101814e+01 -7.40749969e+01 -1.07033699e+02 -1.30192871e+02 -1.27483589e+02 -1.10436378e+02 -1.04869606e+02 -1.08268463e+02 -1.12332405e+02 -1.19835594e+02 -1.18238106e+02 -1.14273582e+02 -1.06925980e+02 -9.48695221e+01 -8.79207764e+01 -8.68919754e+01 -1.01968407e+02 -1.11253616e+02 -1.00506233e+02 -9.03576889e+01 -9.59180756e+01 -1.17834641e+02 -1.29930130e+02 -1.23543365e+02 -1.12626381e+02 -1.04191605e+02 -1.03029427e+02 -1.08288330e+02 -1.11308983e+02 -1.11837029e+02 -1.03474045e+02 -1.05788620e+02 -1.13914261e+02 -1.23062027e+02 -1.32117523e+02 -1.36381378e+02 -1.39960464e+02 -1.30165131e+02 -1.17351082e+02 -1.10519875e+02 -1.12230568e+02 -1.18808868e+02 -1.19435204e+02 -1.12035980e+02 -1.03200012e+02 -9.97820282e+01 -1.09093506e+02 -1.21650024e+02 -1.26667000e+02 -1.23553169e+02 -1.18150429e+02 -1.16532272e+02 -1.17025345e+02 -1.18124184e+02 -1.19903221e+02 -1.17887627e+02 -1.14973663e+02 -1.12949562e+02 -1.14960999e+02 -1.15377594e+02 -1.16116692e+02 -1.16547211e+02 -1.17069649e+02 -1.16021194e+02 -1.15238739e+02 -1.15230301e+02 -1.15080002e+02 -1.14474457e+02 -1.14008209e+02 -1.14082710e+02 -1.14470421e+02 -1.14674026e+02 -1.14577026e+02 -1.13699532e+02 -1.13268318e+02 -1.13846306e+02 -1.15430542e+02 -1.16244164e+02 -1.14820732e+02 -1.13800194e+02 -1.13877533e+02 -1.14201408e+02 -1.13688095e+02 -1.13810402e+02 -1.13513451e+02 -1.13747749e+02 -1.14057800e+02 -1.14192436e+02 -1.14192535e+02 -1.14791718e+02 -1.16705513e+02 -1.17188988e+02 -1.15893356e+02 -1.14343506e+02 -1.15047432e+02 -1.16908264e+02 -1.15651230e+02 -1.14723618e+02 -1.11017403e+02 -1.09585136e+02 -1.09060783e+02 -1.10125206e+02 -1.13587456e+02 -1.13351486e+02 -1.13086197e+02 -1.13008820e+02 -1.14614105e+02 -1.15026581e+02 -1.15118156e+02 -1.15683350e+02 -1.16471840e+02 -1.16438705e+02 -1.14476265e+02 -1.15533356e+02 -1.16284172e+02 -1.19483490e+02 -1.20465500e+02 -1.21884308e+02 -1.18638680e+02 -1.17802513e+02 -1.16732742e+02 -1.17751007e+02 -1.17740189e+02 -1.19078735e+02 -1.19131973e+02 -1.19288521e+02 -1.14700157e+02 -1.14073898e+02 -1.16486259e+02 -1.17956444e+02 -1.17205559e+02 -1.15898354e+02 -1.17374466e+02 -1.17363686e+02 -1.12127747e+02 -1.12331635e+02 -1.14798744e+02 -1.17123108e+02 -1.13634727e+02 -1.11181992e+02 -1.14457481e+02 -1.10762054e+02 -1.05375092e+02 -1.00959335e+02 -1.06325554e+02 -1.06493477e+02 -1.06076447e+02 -1.03263405e+02 -9.98470612e+01 -9.87486725e+01 -1.01065849e+02 -1.08503586e+02 -1.09720230e+02 -1.09419922e+02 -1.09963173e+02 -1.14467888e+02 -1.12373360e+02 -1.10832794e+02 -1.15709518e+02 -1.26905296e+02 -1.26048714e+02 -1.18530518e+02 -1.07209099e+02 -1.05736839e+02 -1.05697289e+02 -1.05972237e+02 -1.06685684e+02 -1.02538124e+02 -9.95798111e+01 -9.97758179e+01 -9.66325378e+01 -9.47666626e+01 -9.21926346e+01 -1.06338150e+02 -1.08420387e+02 -1.07640991e+02 -1.04089943e+02 -1.05351601e+02 -1.04392120e+02 -1.00868660e+02 -1.00283577e+02 -9.71989975e+01 -9.14953842e+01 -9.30276489e+01 -9.74756393e+01 -1.04744812e+02 -1.01515518e+02 -9.86511154e+01 -9.28009033e+01 -9.27882004e+01 -1.04565063e+02 -1.09846840e+02 -1.13009583e+02 -9.69356613e+01 -9.22646790e+01 -8.81595230e+01 -9.88886414e+01 -1.07269447e+02 -1.14444534e+02 -1.13551155e+02 -1.17874207e+02 -1.20068695e+02 -1.21277016e+02 -1.11901848e+02 -1.01403793e+02 -9.85545654e+01 -1.04198448e+02 -1.06963341e+02 -1.08810028e+02 -1.08006798e+02 -1.12781158e+02 -1.11286171e+02 -1.08409004e+02 -9.84432526e+01 -1.00897797e+02 -1.25028542e+02 -1.49327805e+02 -1.45522171e+02 -1.17579590e+02 -9.29002686e+01 -1.04576393e+02 -1.21453636e+02 -1.29161285e+02 -1.18930283e+02 -1.03677551e+02 -1.11849335e+02 -1.21274872e+02 -1.24101593e+02 -1.19954643e+02 -1.18504440e+02 -1.28101715e+02 -1.36933289e+02 -1.38574615e+02 -1.20797760e+02 -1.01174850e+02 -9.76659012e+01 -1.12542397e+02 -1.16486969e+02 -1.12438354e+02 -1.01947716e+02 -1.07203201e+02 -1.20931587e+02 -1.36045471e+02 -1.27999611e+02 -1.04088036e+02 -8.45829010e+01 -8.64646835e+01 -9.09039307e+01 -8.72125397e+01 -6.71853790e+01 -4.27438087e+01 -4.02610893e+01 -6.27689018e+01 -8.99080582e+01 -1.00796745e+02 -1.07242371e+02 -1.22651207e+02 -1.26092079e+02 -9.25719910e+01 -5.17336502e+01 -4.21797676e+01 -7.38532867e+01 -1.04334259e+02 -1.02542274e+02 -9.39526596e+01 -8.01407700e+01 -6.64848938e+01 -7.30267563e+01 -8.64785233e+01 -1.12643723e+02 -1.14361786e+02 -1.19297432e+02 -8.95373535e+01 -4.80589523e+01 -3.90491714e+01 -5.67378960e+01 -9.28829346e+01 -1.10294456e+02 -1.34630371e+02 -1.32880447e+02 -1.12242569e+02 -9.06977386e+01 -7.70026855e+01 -7.40863800e+01 -7.92605591e+01 -7.29497070e+01 -7.04724808e+01 -6.56205826e+01 -7.00528183e+01 -7.24670258e+01 -8.24290161e+01 -1.64754318e+02 -2.38493362e+02 -3.36167511e+02 -2.75075348e+02 -1.91731537e+02 -7.85052872e+01 -1.38907883e+02 -2.31797943e+02 -1.18373184e+02 -3.89139954e+02 -4.74562061e+03 -1.12432539e+04 439682080. 157521280. 251309312. -2.69313126e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1878641536. -270095360. -3.07232441e+04 -1.18383350e+04 -1.71753357e+03 -1.06965588e+03 -4.26706445e+03 -2.85845215e+03 -5.86991089e+02 -4.46305969e+02 -1.84470139e+02 -1.23131264e+02 -1.08078850e+02 -1.05332817e+02 -1.07420113e+02 -1.06339355e+02 -1.11066574e+02 -5.35240211e+01 6.80089264e+01 1.54665955e+02 1.14085907e+02 7.20670090e+01 7.51147413e+00 -1.57360413e+02 -2.47548416e+02 -2.40892029e+02 -2.05976822e+02 -2.45534027e+02 -3.27886963e+02 -2.14611588e+02 -2.74211304e+02 -2.46936600e+02 -2.08276169e+02 -8.67159271e+01 -5.18385391e+01 -2.92364273e+01 -1.67089100e+01 -2.16460538e+00 5.90515566e+00 1.10439510e+01 -4.69231319e+00 -1.79221230e+01 -1.79815769e+01 -9.88741207e+00 1.78352821e+00 8.33902454e+00 1.45756550e+01 -3.04522991e+00 -3.80935707e+01 -7.21358185e+01 -8.00040894e+01 -6.27546844e+01 -4.56888924e+01 -3.50888710e+01 -2.08131695e+01 -3.11583672e+01 -4.00949135e+01 -3.86581459e+01 -1.89642906e+01 -2.47553706e+00 -9.05165672e+00 6.52912807e+00 -1.72089748e+01 -3.30228271e+01 -4.94512672e+01 -5.05954094e+01 -5.62498398e+01 -6.31558838e+01 -5.51793404e+01 -4.36054916e+01 -4.63567162e+01 -4.43066711e+01 -1.34030523e+01 -1.44580150e+00 -1.66406500e+00 -2.86935043e+01 -3.33616714e+01 -2.86033268e+01 -4.67759552e+01 -8.65920181e+01 -8.24825058e+01 -6.57389679e+01 -4.61637955e+01 -9.98255844e+01 -1.43259277e+02 -1.43272446e+02 -1.11501694e+02 -8.77449341e+01 -9.01397781e+01 -9.39288712e+01 -8.14761047e+01 -8.98527222e+01 -1.12094872e+02 -1.46037735e+02 -1.32693787e+02 -8.14489746e+01 -3.58152275e+01 -1.93725357e+01 -2.63455658e+01 -3.42772980e+01 -4.68053436e+01 -2.32421017e+01 2.10532379e+00 -1.42523851e+01 -5.01304245e+01 -5.56924057e+01 -2.22292194e+01 -9.74152923e-01 -5.38784065e+01 -9.15795822e+01 -8.47210388e+01 -3.04192791e+01 1.22400150e+01 1.58163490e+01 1.15960178e+01 3.62880969e+00 6.74210072e-01 -1.23911877e+01 -1.27497644e+01 -6.71611166e+00 -6.41456032e+00 -1.37015457e+01 -1.81351433e+01 -1.18334551e+01 -2.28901172e+00 -1.19853868e+01 -1.37611904e+01 -1.86648235e+01 -5.44907799e+01 -9.60328064e+01 -9.45274353e+01 -5.67189293e+01 -2.35594940e+01 -6.87192078e+01 -1.15450546e+02 -1.17144196e+02 -7.58221817e+01 -3.54808235e+01 -2.77009792e+01 -2.18837795e+01 -5.12578726e+00 -8.89514351e+00 -1.53600092e+01 -1.98434410e+01 -1.02119255e+01 5.97524405e+00 1.33273530e+00 -1.00033255e+01 -2.33760319e+01 -1.46189728e+01 -9.58636570e+00 -1.32100239e+01 -3.62771378e+01 -7.86653290e+01 -1.21053085e+02 -1.12405083e+02 -8.01433792e+01 -3.49288864e+01 -6.94852295e+01 -1.06543091e+02 -1.00338921e+02 -5.12297935e+01 -8.31250548e-01 -4.84682226e+00 -9.42883301e+00 -1.91900921e+01 -1.53383570e+01 -1.78589325e+01 -1.45952387e+01 -1.08373909e+01 -1.09997063e+01 -3.59935722e+01 -6.73502274e+01 -6.93977127e+01 -4.64500008e+01 -1.12182932e+01 -1.92738414e-01 1.93022072e-01 -3.47169456e+01 -6.90742645e+01 -6.49374619e+01 -4.00461807e+01 -1.52465124e+01 -1.04071522e+01 7.21547508e+00 -1.96417503e+01 -6.68167038e+01 -7.85485992e+01 -5.31669273e+01 -2.15018921e+01 -1.81842003e+01 -1.92348137e+01 -8.23403740e+00 -9.31493664e+00 -1.50885983e+01 -1.59056807e+01 -5.44386940e+01 -9.20869904e+01 -9.19600296e+01 -5.03607635e+01 -1.54563541e+01 -2.31171780e+01 -2.34476089e+01 -5.00387039e+01 -8.17317810e+01 -7.47438736e+01 -2.37344494e+01 2.35939369e+01 9.02185917e+00 1.92409664e-01 -5.43220234e+00 1.21325598e+01 2.10807877e+01 2.67782192e+01 2.10488911e+01 1.34382515e+01 1.40918617e+01 1.96604652e+01 2.52889614e+01 4.18597374e+01 5.78100510e+01 6.84733963e+01 6.80954056e+01 5.58442345e+01 5.51972923e+01 5.35138206e+01 5.79524803e+01 4.75243912e+01 4.07504349e+01 4.78265457e+01 4.49024544e+01 4.08198242e+01 4.22573929e+01 5.54076424e+01 5.75319443e+01 4.44730072e+01 4.39322701e+01 4.99883766e+01 5.64655685e+01 3.84574585e+01 3.44518814e+01 1.95025158e+01 2.25431328e+01 1.98953323e+01 4.93545723e+01 7.75640869e+01 5.73682365e+01 -1.53682458e+00 -3.27541084e+01 -1.60640697e+01 1.94413643e+01 1.91281528e+01 1.10386763e+01 -2.45516634e+00 -8.65647030e+00 -7.06259727e+00 3.73579085e-01 1.14229774e+01 2.57217426e+01 3.76421394e+01 3.77294998e+01 2.89238796e+01 2.13255863e+01 2.09623280e+01 2.01273823e+01 2.01913738e+01 1.98947563e+01 3.19357929e+01 3.56268997e+01 4.63594284e+01 3.00553417e+01 -5.24982119e+00 -4.45678673e+01 -3.95718193e+01 -6.18313408e+00 2.70230846e+01 3.44409103e+01 3.49980850e+01 1.99671898e+01 -8.73692513e+00 -2.87429180e+01 -3.37861176e+01 -1.11238897e+00 2.47516422e+01 5.29507751e+01 3.77051849e+01 3.16853714e+01 2.75561562e+01 3.38015633e+01 3.42558174e+01 4.32099762e+01 3.67464447e+01 2.86858196e+01 2.14932709e+01 1.80960712e+01 2.03097382e+01 -1.47927971e+01 -3.42910957e+01 -2.64834232e+01 1.94240208e+01 5.09781609e+01 3.45546761e+01 1.71092510e+01 2.02347851e+01 2.81275597e+01 1.05340843e+01 -1.98719997e+01 -1.88303699e+01 1.31974192e+01 4.78549767e+01 3.46225433e+01 2.57328587e+01 2.97471981e+01 5.75350838e+01 5.81860657e+01 5.27137566e+01 3.55349083e+01 4.49244576e+01 6.75918503e+01 6.77689819e+01 6.31826248e+01 5.50263443e+01 6.90283737e+01 5.24397507e+01 2.47060566e+01 1.97451248e+01 4.00881529e+00 -1.98281670e+01 -5.14950142e+01 -5.29883575e+01 -3.27333488e+01 -3.57437019e+01 -1.36874189e+01 -5.42057848e+00 2.81835098e+01 6.95857697e+01 1.18499779e+02 1.26545509e+02 1.07588837e+02 8.72328644e+01 8.23500671e+01 7.73154984e+01 7.25584183e+01 7.46205063e+01 9.08311920e+01 6.65892334e+01 2.15631542e+01 1.14861560e+00 6.78760099e+00 4.01556892e+01 5.00942688e+01 6.04420776e+01 7.89909439e+01 5.40872993e+01 5.28025246e+01 3.48014069e+01 3.32818489e+01 1.73184566e+01 -1.00411434e+01 1.49758768e+01 4.28292007e+01 6.10458794e+01 3.13379536e+01 2.24566441e+01 3.73178177e+01 6.77080688e+01 4.12744827e+01 1.14638071e+01 2.23433495e+00 2.68291645e+01 5.26783943e+01 2.14703217e+01 -6.02470255e+00 -6.50651217e-01 4.45318604e+01 7.47702560e+01 4.79099998e+01 2.92012138e+01 5.74976730e+01 1.00584908e+02 7.54848557e+01 2.93848095e+01 4.83219528e+00 2.31794968e+01 3.43593063e+01 3.56311188e+01 1.30273457e+01 -4.70233297e+00 3.62628031e+00 5.06726570e+01 8.25733414e+01 7.99724579e+01 7.22416458e+01 7.03433533e+01 8.00937500e+01 7.71300507e+01 7.07938690e+01 4.92606773e+01 4.90183334e+01 6.53348465e+01 7.63379745e+01 7.67774811e+01 5.28086319e+01 3.71744957e+01 4.16553879e+01 5.33827133e+01 7.82067871e+01 7.25320511e+01 7.08543243e+01 7.50644836e+01 9.24526520e+01 9.41025162e+01 5.32252884e+01 1.92425556e+01 5.11021271e+01 1.11119446e+02 1.15553123e+02 6.39647141e+01 4.31237450e+01 7.09815445e+01 8.62459793e+01 6.50760498e+01 5.67109871e+01 6.50647278e+01 8.45667953e+01 7.22326050e+01 6.05566750e+01 5.51870041e+01 6.83340378e+01 8.79747238e+01 8.96375198e+01 9.10746841e+01 6.80961456e+01 5.16960945e+01 4.95025673e+01 6.98973618e+01 7.12364731e+01 2.63547421e+01 4.45593166e+00 1.89804688e+01 5.78166504e+01 5.95693779e+01 4.66242218e+01 6.33827744e+01 1.01960800e+02 1.16181999e+02 9.24302750e+01 7.36788864e+01 7.59735336e+01 8.62558670e+01 7.55689468e+01 7.50974731e+01 7.45579376e+01 8.13268204e+01 8.97853012e+01 1.01732857e+02 1.05103844e+02 9.86466980e+01 8.90174866e+01 7.47628250e+01 7.01093903e+01 6.92368698e+01 6.10186806e+01 5.92478409e+01 7.45967255e+01 9.36263580e+01 8.82587967e+01 6.67323456e+01 6.28434372e+01 6.77120056e+01 5.51810837e+01 2.22978439e+01 5.88643026e+00 2.26106834e+01 6.35695038e+01 7.45016479e+01 6.68861389e+01 6.25258865e+01 8.13757477e+01 9.55787354e+01 1.00300232e+02 1.04465233e+02 1.01366302e+02 9.46960373e+01 9.39199753e+01 1.04270966e+02 1.04435036e+02 7.61668320e+01 6.20631371e+01 7.76770477e+01 9.57583160e+01 7.83568726e+01 6.47167130e+01 8.03825455e+01 1.18969795e+02 1.40207596e+02 1.35821686e+02 1.29262680e+02 1.22622810e+02 1.23579254e+02 1.21151474e+02 1.24259834e+02 1.14744354e+02 1.06251976e+02 1.03189529e+02 1.19882591e+02 1.12842262e+02 8.50261383e+01 6.33288498e+01 5.86780663e+01 6.45483856e+01 7.66355438e+01 9.22769165e+01 1.06000458e+02 1.01689697e+02 1.01954964e+02 1.02289619e+02 1.05230705e+02 1.02753922e+02 1.03817291e+02 1.02544250e+02 1.01898582e+02 1.04468262e+02 1.04889496e+02 1.06750938e+02 9.16231308e+01 7.66202087e+01 7.46616364e+01 8.72261429e+01 9.87436142e+01 9.75329819e+01 9.94146347e+01 9.82700043e+01 9.92098389e+01 9.92262421e+01 9.95778885e+01 9.21641083e+01 7.95451736e+01 8.54907379e+01 1.00290359e+02 1.05060081e+02 8.19715805e+01 6.71376877e+01 7.75248947e+01 9.90057602e+01 9.90748672e+01 8.79361115e+01 8.87943344e+01 9.67093201e+01 1.06366119e+02 9.69676285e+01 9.03382492e+01 8.39770813e+01 8.32998810e+01 9.50213318e+01 1.03277496e+02 1.01252754e+02 8.24786377e+01 7.40035629e+01 8.77425232e+01 1.04913383e+02 1.02274170e+02 8.94505463e+01 8.75633621e+01 9.49296112e+01 1.02534874e+02 9.69831390e+01 9.16424179e+01 8.87710190e+01 9.25239105e+01 9.98321381e+01 1.04976082e+02 9.91164627e+01 9.09189835e+01 8.87233810e+01 9.44492950e+01 1.05154419e+02 1.01180176e+02 9.76952286e+01 9.67680283e+01 1.02893723e+02 1.03477020e+02 9.69415894e+01 9.83928299e+01 1.04446663e+02 1.13653397e+02 1.14938553e+02 1.15495331e+02 1.09635384e+02 1.03513069e+02 1.01419670e+02 1.04120422e+02 1.08893478e+02 1.11570015e+02 1.11102760e+02 1.08599678e+02 1.03954910e+02 1.03227043e+02 9.25179291e+01 8.92999954e+01 6.82340012e+01 9.32725220e+01 -9.76824722e+01 1.54276306e+02 2.68354279e+02 -8.38790817e+01 -6.23262787e+01 2.26467972e+02 -4.01385269e+01 386115904. 594307968. 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. 1143110144. 446722944. 4.02959302e+03 1.74277026e+03 6.52376099e+02 -7.65899048e+01 -3.59101372e+01 5.98281593e+01 6.60506516e+01 6.14269905e+01 7.31973801e+01 8.55740585e+01 6.86367340e+01 2.21373459e+02 3.85738068e+02 5.30489258e+02 -3.04683502e+02 -2.09579712e+02 -2.03199368e+01 4.13091993e+00 2.79497852e+01 6.15418396e+01 6.97383499e+01 7.12408676e+01 6.76469727e+01 6.86526871e+01 6.98601074e+01 6.55439682e+01 6.14601135e+01 6.28821182e+01 7.38936310e+01 8.28121490e+01 8.50277405e+01 7.69568863e+01 6.44673386e+01 5.88503990e+01 6.01829109e+01 5.96971436e+01 5.85995674e+01 5.88263817e+01 6.80182190e+01 7.78144684e+01 7.65406113e+01 6.77030258e+01 6.15964584e+01 6.63457794e+01 6.67053070e+01 6.54780273e+01 7.05918198e+01 7.05981598e+01 7.19791260e+01 6.76072922e+01 6.03128242e+01 5.13766747e+01 4.58968201e+01 6.03289337e+01 8.04451828e+01 8.80316238e+01 7.76725693e+01 5.70920029e+01 5.60550537e+01 6.59438782e+01 7.33027267e+01 6.90546112e+01 6.10914764e+01 6.55049591e+01 7.42601852e+01 7.85277634e+01 6.67428513e+01 4.97229805e+01 5.38021164e+01 5.87697830e+01 6.39147987e+01 6.38018303e+01 6.24544449e+01 6.78462601e+01 6.28193436e+01 5.25095673e+01 4.02546616e+01 3.88466568e+01 5.09797935e+01 6.80810776e+01 8.35446701e+01 8.53642197e+01 6.96912231e+01 6.23249168e+01 6.11715851e+01 5.01822739e+01 3.06696033e+01 2.97120075e+01 5.40827980e+01 8.23920670e+01 8.53979721e+01 6.42269516e+01 3.65179100e+01 3.10248604e+01 3.24295082e+01 3.35389938e+01 3.45180855e+01 3.89059715e+01 5.12567368e+01 6.19495010e+01 5.95679131e+01 4.64079704e+01 4.05432816e+01 5.43768616e+01 7.38645401e+01 8.18336487e+01 7.96910248e+01 6.07142868e+01 4.52339172e+01 5.05997429e+01 5.06929474e+01 4.08586349e+01 2.79772301e+01 3.70998726e+01 6.11931076e+01 6.60442352e+01 4.38108521e+01 1.88292751e+01 1.23902855e+01 3.31759567e+01 5.39615784e+01 7.32352753e+01 8.00991669e+01 6.77506561e+01 5.86020966e+01 5.67587509e+01 3.98911552e+01 2.07855740e+01 1.23469782e+01 2.72424812e+01 4.96509857e+01 6.19942017e+01 6.04255562e+01 4.59861336e+01 3.71191177e+01 3.49921989e+01 3.11906567e+01 1.66151104e+01 1.64892063e+01 3.95870934e+01 7.89300919e+01 9.91923447e+01 8.66852493e+01 6.69057922e+01 5.87111092e+01 4.99217606e+01 4.74312935e+01 5.46571312e+01 6.26098022e+01 7.67702560e+01 8.53452072e+01 7.95292053e+01 5.59373817e+01 3.83073463e+01 5.06529846e+01 7.38140488e+01 7.13724442e+01 4.87413292e+01 3.39172821e+01 5.45900345e+01 8.31916885e+01 7.45814133e+01 6.13878059e+01 5.08038712e+01 8.57563553e+01 1.20806862e+02 1.36520447e+02 9.50593262e+01 3.92076759e+01 2.19508057e+01 2.32377968e+01 2.42458134e+01 2.32592754e+01 4.40173645e+01 7.66188736e+01 9.89079132e+01 7.15640335e+01 3.77917824e+01 2.19060898e+01 4.73270111e+01 6.82531662e+01 7.69881058e+01 7.28881378e+01 7.92713928e+01 8.99721375e+01 1.00718170e+02 7.99855118e+01 6.72053146e+01 5.95275040e+01 7.95245438e+01 1.03339676e+02 1.08633698e+02 6.49336395e+01 1.22893467e+01 6.47000492e-01 1.74403343e+01 2.02747021e+01 1.49497681e+01 2.01126099e+01 5.53279762e+01 7.18082581e+01 4.39605980e+01 1.66530108e+00 -1.45044270e+01 1.49180775e+01 3.64326782e+01 4.45871849e+01 4.41535072e+01 4.59327774e+01 5.41445923e+01 7.10574265e+01 4.84137115e+01 1.74317398e+01 2.38208413e+00 2.76483860e+01 7.10926056e+01 7.82526627e+01 4.79082947e+01 1.77457886e+01 1.42193451e+01 2.81286411e+01 1.99796562e+01 1.23349428e+01 8.09166336e+00 4.74831200e+00 1.81411343e+01 1.97981472e+01 1.86350613e+01 -4.11635351e+00 -6.35693121e+00 3.36154699e+00 1.53280706e+01 4.80594559e+01 5.75680313e+01 7.55963974e+01 6.12176704e+01 4.37761230e+01 1.54535952e+01 -4.51124334e+00 3.42974243e+01 6.77551498e+01 6.53970108e+01 2.59375114e+01 6.61158037e+00 2.40517025e+01 4.46691055e+01 2.63204651e+01 1.55866394e+01 2.57415657e+01 5.99993362e+01 7.37830276e+01 6.11708565e+01 6.64679565e+01 4.95561295e+01 4.12695274e+01 1.21376114e+01 3.46589508e+01 4.58938408e+01 6.10115814e+01 8.01847992e+01 8.75664368e+01 8.15017090e+01 2.90425949e+01 -6.11207581e+00 1.47414637e+01 8.05956268e+01 1.07246605e+02 7.75030441e+01 6.16451035e+01 6.79246674e+01 8.72145233e+01 5.33139496e+01 3.37124405e+01 1.84689503e+01 2.36437283e+01 1.93650990e+01 2.59544106e+01 5.03130074e+01 4.90986671e+01 2.39622612e+01 -3.06996250e+00 9.36176014e+00 -1.74233830e+00 -2.99354839e+01 -2.72739697e+01 1.40558443e+01 5.15534439e+01 3.73427048e+01 2.22348614e+01 3.52732162e+01 6.42924194e+01 5.05086746e+01 2.66924019e+01 2.49763927e+01 4.77236061e+01 6.54993973e+01 5.09889793e+01 5.11983528e+01 3.82889557e+01 3.66669998e+01 9.12012196e+00 -8.58526039e+00 7.93864071e-01 2.14158573e+01 2.51494617e+01 7.38359213e+00 -1.17458963e+01 -3.06865158e+01 -4.75503502e+01 -3.83558884e+01 -2.06916351e+01 -7.97755098e+00 -3.15417614e+01 -5.43134232e+01 -2.80629978e+01 2.87630844e+01 3.82754173e+01 1.12534103e+01 -8.71693325e+00 2.79651260e+01 6.38034706e+01 5.37152977e+01 3.15052166e+01 -4.64555883e+00 -1.58683624e+01 -3.57477989e+01 -4.14825096e+01 -3.06653824e+01 -2.33146954e+01 -1.96390877e+01 -2.52354794e+01 -1.62680473e+01 -3.03386517e+01 -5.33755722e+01 -3.99460449e+01 8.12303829e+00 3.56824760e+01 3.09889374e+01 2.62473488e+01 5.17989044e+01 7.47193832e+01 4.24848938e+01 3.02056408e+01 1.96105366e+01 3.57532806e+01 2.69856586e+01 1.41461744e+01 3.42467766e+01 2.85988102e+01 1.69803791e+01 -2.88000813e+01 -3.71845627e+01 -1.80285416e+01 1.33049488e+01 2.89506397e+01 1.50930166e+01 7.49821544e-01 -1.56999578e+01 -5.28006325e+01 -4.85812988e+01 1.87627888e+01 9.34654312e+01 1.21141098e+02 7.90003128e+01 5.93403816e+01 6.77039871e+01 6.42516556e+01 8.09649124e+01 5.39901047e+01 4.72288094e+01 3.14130745e+01 3.90308533e+01 1.04655449e+02 1.21487640e+02 1.04890213e+02 1.71525536e+01 -4.51348267e+01 -2.51906657e+00 5.34941139e+01 7.63650589e+01 5.60527325e+00 -6.13668861e+01 -3.89165306e+01 -2.27553673e+01 1.49661617e+01 2.97834816e+01 3.90856361e+01 6.11268425e+01 4.30332260e+01 3.11813641e+01 1.35806236e+01 -1.02649137e-01 4.45037384e+01 7.51330032e+01 1.03712158e+02 8.07419205e+01 2.05417500e+01 2.23171692e+01 1.93822670e+01 4.14631397e-01 -5.50361824e+01 -4.61354027e+01 5.52791595e+01 1.14032867e+02 1.11013428e+02 4.74768677e+01 1.36409473e+01 1.60435925e+01 1.05576611e+01 2.01034966e+01 4.32481422e+01 4.82152863e+01 7.30013046e+01 5.85709000e+01 7.01885071e+01 6.68033218e+01 4.77593231e+01 2.95013351e+01 -2.58102570e+01 -2.86486588e+01 -1.16265802e+01 1.53272686e+01 7.28014908e+01 9.01731339e+01 8.43859863e+01 -2.35700536e+00 -6.07549171e+01 -5.32257195e+01 1.60996017e+01 6.49828033e+01 2.69356537e+01 -4.60641747e+01 -6.02438278e+01 -3.58701363e+01 -9.09529972e+00 9.00403786e+00 1.29395723e+01 3.08288841e+01 1.17917252e+01 -4.06776381e+00 -1.24412193e+01 -1.20512925e-01 6.48214645e+01 9.73501740e+01 8.24456177e+01 1.44301720e+01 -3.86838188e+01 -1.02939043e+01 4.20101166e+01 6.09662056e+01 9.48320293e+00 -4.99291916e+01 -4.68605118e+01 -1.26169796e+01 2.15096645e+01 8.62037373e+00 -1.71982803e+01 -3.90919518e+00 2.51067848e+01 3.89992676e+01 4.61233749e+01 2.75936222e+01 4.22206345e+01 2.95345631e+01 2.77591839e+01 1.77624245e+01 4.12027788e+00 3.63027382e+01 6.85189438e+00 -1.67339382e+01 -6.66196671e+01 -4.56750069e+01 2.03444080e+01 6.86973495e+01 7.11364822e+01 1.93371281e-01 -5.50626793e+01 -6.30287132e+01 -3.17674026e+01 1.74394951e+01 2.52574520e+01 -8.05311775e+00 -3.00901775e+01 -4.45599060e+01 -1.81520557e+01 3.25561066e+01 7.11861267e+01 6.55390778e+01 -1.00258980e+01 -5.54122162e+01 -6.63357391e+01 -4.62377892e+01 1.39375505e+01 5.39337158e+01 5.11984406e+01 -1.85232658e+01 -7.19777756e+01 -4.48696976e+01 1.53670282e+01 5.15562744e+01 2.74888301e+00 -7.00700912e+01 -7.60029221e+01 -3.44025993e+01 2.45546741e+01 5.72836266e+01 4.55833778e+01 3.21425667e+01 -5.95576048e-01 -2.23379974e+01 -2.20150719e+01 -1.59311523e+01 2.12285213e+01 1.21119928e+01 -9.48641682e+00 -2.24934521e+01 -5.22842484e+01 -1.76458778e+01 -1.86502075e+01 -2.72784023e+01 -6.87050858e+01 -7.38870850e+01 1.16976309e+01 5.43834839e+01 5.02784805e+01 -3.03193512e+01 -8.07306137e+01 -8.31837769e+01 -4.90069733e+01 -9.79648232e-01 2.90424404e+01 2.35687332e+01 8.58643723e+00 -1.94536705e+01 -2.96146259e+01 -1.10089331e+01 -1.47262716e+01 -1.00685120e+01 -6.18875313e+01 -7.46068649e+01 -7.33862000e+01 -5.46702309e+01 -7.07606268e+00 -3.30803204e+00 -2.57447147e+01 -9.09081726e+01 -1.12348717e+02 -9.29335022e+01 -4.67579689e+01 -1.56427507e+01 -4.19297523e+01 -9.55032806e+01 -1.14163864e+02 -9.07882996e+01 -4.73726883e+01 -2.58903313e+01 -3.05588932e+01 -3.58617439e+01 -3.54187431e+01 -2.25037556e+01 -1.32245626e+01 3.58352280e+00 2.71983910e+01 -1.18140197e+00 -5.14399376e+01 -8.11716385e+01 -5.34499435e+01 4.54690266e+00 3.50621338e+01 2.13747540e+01 -3.29873276e+01 -7.90810089e+01 -5.13984070e+01 -2.37913857e+01 2.13193512e+00 -1.79795189e+01 -2.69882278e+01 -1.11238852e+01 3.72639704e+00 1.70324841e+01 1.95156517e+01 6.00333643e+00 7.50606346e+00 -5.62337542e+00 -5.84825087e+00 -1.79614305e+00 -1.01763954e+01 4.82952833e+00 -4.92375422e+00 -1.36493721e+01 -3.34766922e+01 -4.94861794e+01 -1.32172852e+01 -8.71905231e+00 -8.49032974e+00 -4.34879799e+01 -6.01335907e+01 -3.07271175e+01 -1.31663990e+01 2.54870720e+01 -1.19853282e+00 -4.98336525e+01 -9.32058945e+01 -9.47977982e+01 -2.91595592e+01 -1.70580349e+01 -4.99799995e+01 -1.16318481e+02 -1.29310120e+02 -1.40699554e+02 -1.48710144e+02 -1.74115662e+02 -3.14827393e+02 -2.92996216e+03 -1.70210498e+03 -3.25527661e+03 -9.80472949e+03 -91476496. 136346288. -104345336. -644055360. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 395975776. 1039180928. 1.53886475e+04 5.42511670e+03 -1.27893341e+02 6.27001526e+02 -1.20489645e+01 -1.93621497e+03 -4.95431213e+02 1.47282288e+02 1.54077072e+02 9.15923691e+01 4.05415192e+02 2.40439133e+02 9.72676468e+00 -1.61194611e+02 -2.60539612e+02 -2.32884537e+02 -2.63822845e+02 -2.13392059e+02 -1.79205536e+02 -1.02889786e+02 -9.37627258e+01 -7.64596634e+01 -8.46581345e+01 -8.12368240e+01 -4.25137138e+01 -2.76080437e+01 -4.77125244e+01 -7.79972992e+01 -5.98555603e+01 -1.73588810e+01 -6.31002092e+00 -2.91341324e+01 -5.61956291e+01 -6.18061981e+01 -5.39719810e+01 -4.01059036e+01 -2.25525589e+01 -1.08796606e+01 -1.87302513e+01 -3.44038658e+01 -5.22085075e+01 -3.47995796e+01 -2.07928028e+01 -8.20028782e+00 7.93117094e+00 -1.16506538e+01 -4.20738678e+01 -8.01294327e+01 -7.44861603e+01 -3.12949657e+01 -2.49776382e+01 -4.19477577e+01 -7.98884659e+01 -8.39344330e+01 -5.62203217e+01 -4.02822304e+01 -3.42763252e+01 -5.16385994e+01 -5.22450638e+01 -4.17550659e+01 -2.79151306e+01 -9.55771828e+00 -8.00594807e-01 -1.33047762e+01 -3.70508499e+01 -5.34068413e+01 -4.33198357e+01 -2.79443645e+01 -6.61250782e+00 1.38706732e+01 1.77785053e+01 1.12100048e+01 -1.35223007e+01 -2.86682434e+01 -1.76074944e+01 -2.98675880e+01 -5.09824371e+01 -8.97693634e+01 -8.35806961e+01 -5.58664627e+01 -4.08720627e+01 -3.84997177e+01 -4.00748482e+01 -4.33879852e+01 -5.32101364e+01 -6.03331909e+01 -4.96047783e+01 -3.64249954e+01 -4.26596832e+01 -4.48634071e+01 -4.04684563e+01 -2.56225300e+01 -3.20312614e+01 -4.71425247e+01 -3.64385452e+01 -3.74342232e+01 -4.10263481e+01 -6.12424622e+01 -6.33660812e+01 -3.76468201e+01 -3.53306847e+01 -5.08634605e+01 -8.31949387e+01 -9.05327148e+01 -6.80695801e+01 -5.28157845e+01 -4.04511337e+01 -3.95670166e+01 -3.71041718e+01 -3.39739990e+01 -4.21933556e+01 -4.10758476e+01 -3.85515251e+01 -3.87922440e+01 -4.93297729e+01 -6.23631248e+01 -5.80864944e+01 -5.68647766e+01 -6.03082962e+01 -4.85130043e+01 -4.83241081e+01 -5.78568115e+01 -8.37765274e+01 -8.49832458e+01 -5.56696358e+01 -4.60384750e+01 -5.75199738e+01 -8.04709091e+01 -8.25090256e+01 -6.35732117e+01 -5.56597404e+01 -5.15057907e+01 -5.33215675e+01 -5.97599678e+01 -7.03700714e+01 -7.63509750e+01 -6.49283066e+01 -5.19233246e+01 -5.59008942e+01 -6.64566727e+01 -7.72046661e+01 -6.83997498e+01 -6.24149132e+01 -5.85275383e+01 -5.36325607e+01 -5.29184723e+01 -5.10325775e+01 -5.50911522e+01 -5.59546661e+01 -4.82703896e+01 -4.65522804e+01 -5.27387924e+01 -7.04992447e+01 -8.38448715e+01 -7.88646393e+01 -6.98661041e+01 -5.80177078e+01 -5.70501633e+01 -5.61643333e+01 -5.19817352e+01 -4.86887856e+01 -5.20407410e+01 -5.46850166e+01 -5.54781227e+01 -5.20675774e+01 -5.73595772e+01 -6.71287231e+01 -7.54295120e+01 -7.63434830e+01 -6.39179230e+01 -6.04308472e+01 -6.47092133e+01 -7.30682297e+01 -7.02094269e+01 -6.17875061e+01 -6.03652802e+01 -5.94110413e+01 -6.01567612e+01 -6.13059998e+01 -6.41409302e+01 -6.65343246e+01 -6.31796074e+01 -6.01387672e+01 -6.22403679e+01 -6.21319923e+01 -6.08430405e+01 -5.56705055e+01 -5.10757179e+01 -4.95966682e+01 -4.82231674e+01 -5.58768082e+01 -6.16146164e+01 -6.55480270e+01 -6.55474091e+01 -6.09854584e+01 -6.17864799e+01 -6.42743912e+01 -6.99678192e+01 -7.06553879e+01 -6.48300629e+01 -6.05485764e+01 -5.82205315e+01 -6.04900551e+01 -6.06288490e+01 -6.05959053e+01 -6.09760094e+01 -6.16793938e+01 -6.13703918e+01 -6.16108589e+01 -6.28042946e+01 -6.48535156e+01 -6.46182938e+01 -6.56412735e+01 -6.54097214e+01 -6.41359482e+01 -6.30522346e+01 -6.35165329e+01 -6.47500076e+01 -6.52553787e+01 -6.52012711e+01 -6.56152878e+01 -6.57269363e+01 -6.56919403e+01 -6.54526901e+01 -6.52982330e+01 -6.53877258e+01 -6.60138321e+01 -6.62812119e+01 -6.57381744e+01 -6.48766632e+01 -6.46033936e+01 -6.53800278e+01 -6.59606476e+01 -6.54561539e+01 -6.54896622e+01 -6.53516998e+01 -6.52214432e+01 -6.52802887e+01 -6.53015442e+01 -6.54407043e+01 -6.55323486e+01 -6.56326218e+01 -6.51845627e+01 -6.37632370e+01 -6.29969559e+01 -6.39252510e+01 -6.51816864e+01 -6.52265930e+01 -6.42090836e+01 -6.45222015e+01 -6.50538254e+01 -6.81827240e+01 -6.98512497e+01 -7.00650635e+01 -6.77361450e+01 -6.49515305e+01 -6.54267883e+01 -6.55657501e+01 -6.59528732e+01 -6.57515335e+01 -6.66305771e+01 -6.66784668e+01 -6.66857986e+01 -6.50597382e+01 -6.57482376e+01 -6.45587997e+01 -6.39466476e+01 -6.30023346e+01 -6.21922646e+01 -6.17563744e+01 -6.17273293e+01 -6.32732582e+01 -6.15947571e+01 -6.04418907e+01 -5.95475426e+01 -6.21679688e+01 -6.13969498e+01 -6.05925102e+01 -6.13096390e+01 -6.35989075e+01 -6.41136475e+01 -6.01549034e+01 -5.80121040e+01 -5.88746681e+01 -5.88424606e+01 -5.62345085e+01 -5.63947105e+01 -5.94576530e+01 -6.35340729e+01 -6.31173782e+01 -6.28953285e+01 -6.30462646e+01 -6.22462463e+01 -6.17719612e+01 -6.44963760e+01 -6.91699295e+01 -6.94165039e+01 -6.58884430e+01 -6.27473335e+01 -6.44399414e+01 -6.28414078e+01 -6.44288635e+01 -6.31864624e+01 -6.47875595e+01 -6.33660660e+01 -6.45722046e+01 -6.43529587e+01 -5.94781799e+01 -5.46609192e+01 -5.56260414e+01 -5.88562851e+01 -5.97329559e+01 -6.04759903e+01 -6.39516563e+01 -6.59764862e+01 -6.24897728e+01 -5.95784988e+01 -6.11293449e+01 -6.62064590e+01 -6.24548073e+01 -5.64415016e+01 -5.46937943e+01 -6.06237183e+01 -6.81525421e+01 -6.97100067e+01 -6.96382523e+01 -6.69195175e+01 -5.75425072e+01 -4.88876152e+01 -4.57089882e+01 -5.12786827e+01 -5.74698639e+01 -5.92957230e+01 -6.03046417e+01 -6.21653290e+01 -6.30012283e+01 -6.13793526e+01 -5.96686897e+01 -5.98838234e+01 -5.88789024e+01 -5.90604210e+01 -6.29234734e+01 -6.91426544e+01 -7.38597412e+01 -7.53966141e+01 -7.75401840e+01 -7.28263855e+01 -6.86626663e+01 -6.59524994e+01 -6.82848206e+01 -6.06791077e+01 -5.67307625e+01 -5.24115181e+01 -5.96518631e+01 -5.80181236e+01 -6.21179314e+01 -5.79709930e+01 -6.20651321e+01 -5.72326508e+01 -5.96821175e+01 -6.69876022e+01 -8.05759964e+01 -6.35569458e+01 -4.21438522e+01 -3.37675209e+01 -4.93388977e+01 -6.38790321e+01 -6.09533920e+01 -5.73775177e+01 -5.23669624e+01 -5.51557961e+01 -5.78937378e+01 -6.02553673e+01 -5.18467865e+01 -4.69194298e+01 -4.82885246e+01 -6.16922607e+01 -7.24083328e+01 -6.37692642e+01 -5.41882172e+01 -4.40033951e+01 -4.58887520e+01 -4.43672562e+01 -4.05839615e+01 -3.07725239e+01 -2.36727371e+01 -3.15304031e+01 -4.52795258e+01 -5.20245285e+01 -4.84790344e+01 -5.01296692e+01 -5.20100250e+01 -5.55144196e+01 -5.13817368e+01 -5.27007179e+01 -4.53625984e+01 -4.82695923e+01 -4.03974457e+01 -4.69544868e+01 -4.49288177e+01 -4.81975594e+01 -5.41999741e+01 -6.70593643e+01 -9.12786865e+01 -9.93174210e+01 -9.08602905e+01 -7.41027222e+01 -6.44527969e+01 -5.98723717e+01 -5.60753174e+01 -5.97635880e+01 -6.60007553e+01 -6.92122192e+01 -6.75621796e+01 -5.96581917e+01 -5.38001900e+01 -6.24344940e+01 -7.67658539e+01 -8.23326416e+01 -7.67680664e+01 -6.52753830e+01 -6.13913269e+01 -5.30492744e+01 -4.65365219e+01 -3.70195236e+01 -4.21252823e+01 -4.82200775e+01 -5.15360107e+01 -4.35183868e+01 -4.04079933e+01 -4.16509933e+01 -3.78919220e+01 -3.55600700e+01 -4.10191994e+01 -4.49559021e+01 -4.96814613e+01 -4.34502182e+01 -3.85783348e+01 -3.61600800e+01 -4.09024963e+01 -5.20900841e+01 -5.77910767e+01 -5.82587128e+01 -5.35368118e+01 -2.88419476e+01 4.98120384e+01 2.75160007e+01 1.35335007e+02 4.96358795e+01 9.86383606e+02 1.45051172e+03 6.83872604e+01 -2.27103615e+01 3.50025116e+02 4.64831934e+03 1.12340645e+04 -166160512. -43137324. -74817408. 43299144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1878641536. -270095360. -3.07232441e+04 -1.18383350e+04 -1.71753357e+03 -1.06965588e+03 -5.99261108e+02 -4.90482086e+02 -3.83915375e+02 -3.34544708e+02 -2.47815964e+02 -1.74515915e+02 -1.48604660e+02 -2.15685959e+02 -2.83141357e+02 -2.77921204e+02 -2.82373383e+02 -2.53394012e+02 3.91945483e+03 2.26062207e+03 3.68163818e+02 8.04377747e+01 4.00598602e+01 1.69698029e+01 1.56289549e+01 1.14022815e+00 -2.32341499e+01 -4.14139938e+01 -5.17245636e+01 -5.17488518e+01 -4.57373390e+01 -3.68386345e+01 -3.82889748e+01 -4.78246880e+01 -5.52541771e+01 -5.55160713e+01 -4.60383263e+01 -4.40480080e+01 -4.04082489e+01 -4.45393600e+01 -3.87866173e+01 -3.20195198e+01 -3.15247822e+01 -3.79362297e+01 -5.01284485e+01 -6.06534309e+01 -6.83478622e+01 -6.01102333e+01 -6.26670151e+01 -6.55102158e+01 -6.57538986e+01 -5.26606789e+01 -4.07875633e+01 -4.43486633e+01 -5.01874733e+01 -4.44736748e+01 -3.80288467e+01 -3.08310223e+01 -3.68283806e+01 -4.12031288e+01 -3.84535370e+01 -3.53822212e+01 -1.30375490e+01 7.04943323e+00 1.40305805e+01 1.63635063e+01 1.18440866e+01 2.74301720e+01 3.12981663e+01 1.67164516e+01 -1.58131003e+00 -2.78345089e+01 -3.49848671e+01 -4.11380005e+01 -5.23523903e+01 -6.93321304e+01 -8.00192337e+01 -7.54501495e+01 -5.44086494e+01 -3.23699074e+01 -2.53089027e+01 -2.18997269e+01 -2.91701527e+01 -4.30650234e+00 1.72681561e+01 4.24894753e+01 5.41680489e+01 4.45863304e+01 2.65658264e+01 -5.97285666e-02 -2.05793881e+00 1.95779061e+00 3.01075516e+01 4.97586288e+01 4.35764313e+01 1.11166315e+01 -1.07909422e+01 -8.35990429e+00 2.88564634e+00 1.08383427e+01 2.00397816e+01 -4.99724817e+00 -3.49831772e+01 -4.50684395e+01 -2.89240017e+01 -7.35205126e+00 -1.45998354e+01 -1.35688868e+01 8.47711563e+00 2.70049648e+01 4.67334023e+01 3.93735008e+01 1.56881466e+01 -1.89795551e+01 -4.97545967e+01 -5.11366272e+01 -3.80658226e+01 -2.43724461e+01 -1.77931080e+01 -3.05337486e+01 -3.50491028e+01 -3.06580048e+01 -2.49164486e+01 -1.97675247e+01 -1.94315014e+01 -8.85326195e+00 -8.91315460e+00 -7.54728365e+00 1.86981449e+01 5.13691940e+01 5.50123863e+01 2.64691734e+01 -3.81113917e-01 1.98115025e+01 4.32589188e+01 6.15194664e+01 6.17947998e+01 4.61932907e+01 2.02932873e+01 -3.68399763e+00 -1.43726807e+01 -1.12090473e+01 -1.32070360e+01 -1.45855789e+01 -2.19593067e+01 -3.00416584e+01 -2.54220657e+01 -1.10566912e+01 -5.44231033e+00 -1.24104280e+01 -1.35507383e+01 -8.24988556e+00 8.88344193e+00 3.48283882e+01 6.30543213e+01 6.12501144e+01 3.40511780e+01 4.42156029e+00 2.50439396e+01 5.33921242e+01 7.27314453e+01 7.48051300e+01 7.54565048e+01 7.88914719e+01 5.43601456e+01 3.99720764e+01 1.58176155e+01 1.27370014e+01 3.32402372e+00 -2.14172959e+00 5.88476276e+00 9.28004169e+00 1.55798960e+01 1.20344734e+01 1.76716499e+01 6.28291321e+00 -2.56882668e+01 -5.56062317e+01 -4.78066826e+01 -1.29488707e+01 1.31160412e+01 1.94187202e+01 1.88172169e+01 9.55707645e+00 -7.03975582e+00 9.17728996e+00 4.18089409e+01 4.56939201e+01 2.60354042e+01 1.69768429e+00 8.85664368e+00 1.40705481e+01 1.68994598e+01 1.22703247e+01 1.28668966e+01 1.09755039e+01 2.80202274e+01 3.69739227e+01 3.70674171e+01 2.79466286e+01 2.06888332e+01 8.49585629e+00 -1.38567600e+01 -1.03161278e+01 7.80126810e+00 2.74750175e+01 1.11415682e+01 4.55985934e-01 5.27984476e+00 1.28737640e+01 1.77158718e+01 1.35231533e+01 1.02506676e+01 8.27353287e+00 1.00495882e+01 1.81374702e+01 1.74847527e+01 1.41190872e+01 1.45083399e+01 8.09734821e+00 6.00051546e+00 -2.22807908e+00 7.71128416e-01 3.76409984e+00 4.15709639e+00 4.68663168e+00 -8.25460529e+00 -1.85023232e+01 -1.93091850e+01 -1.15325270e+01 1.91293907e+00 -1.69256353e+00 5.67324936e-01 -8.30861568e+00 -1.17495918e+01 -1.41425238e+01 -7.46858311e+00 -2.32372594e+00 -5.44329262e+00 -5.60477638e+00 1.79268026e+00 1.43378382e+01 2.56025143e+01 2.39402924e+01 3.94740731e-01 -2.53632317e+01 -2.99672565e+01 -5.02679920e+00 4.52243805e+01 7.63402252e+01 7.35759354e+01 4.47407188e+01 1.99233341e+01 4.84304733e+01 6.97210846e+01 6.95746002e+01 3.88687134e+01 1.53240690e+01 1.48331556e+01 1.38830242e+01 1.67005844e+01 2.18286896e+01 1.89806004e+01 1.48390818e+01 1.13351822e+01 2.40558186e+01 3.61228828e+01 2.54929676e+01 1.08898811e+01 2.41970229e+00 2.17799110e+01 3.99202232e+01 5.14739227e+01 5.03990021e+01 4.95514107e+01 4.03487701e+01 3.85473595e+01 3.52139397e+01 5.34829636e+01 6.53644714e+01 5.92912636e+01 3.83708000e+01 1.64493942e+01 2.03497887e+01 2.14155960e+01 3.36551094e+01 3.60631638e+01 1.94725590e+01 -2.49494219e+00 -3.06948137e+00 1.07669640e+01 3.06475182e+01 2.21394596e+01 2.06585598e+01 2.25322685e+01 2.89428730e+01 5.59982262e+01 7.76497040e+01 7.51411514e+01 5.57677040e+01 2.88998604e+01 3.17705498e+01 3.25380783e+01 3.32237282e+01 3.26654663e+01 5.05181198e+01 7.38870163e+01 8.03428192e+01 6.98231277e+01 3.99462395e+01 4.14851494e+01 3.97600060e+01 4.43724022e+01 3.47564354e+01 3.64180679e+01 4.13020973e+01 4.85627403e+01 4.13702621e+01 3.33919182e+01 3.18735294e+01 3.68861160e+01 3.43452415e+01 2.66959915e+01 2.71057835e+01 2.89864006e+01 3.52161751e+01 4.82693977e+01 7.48059158e+01 9.28359985e+01 9.97778473e+01 9.57627869e+01 9.40442276e+01 6.77566986e+01 5.49427834e+01 4.13426704e+01 4.07430687e+01 3.26237259e+01 4.41489716e+01 6.31604462e+01 6.06860199e+01 5.12533951e+01 2.30603333e+01 7.80926228e+00 5.91567373e+00 1.43139496e+01 3.91161118e+01 4.58775024e+01 5.55334129e+01 6.93565674e+01 7.87221298e+01 6.95227509e+01 4.79289055e+01 2.10825558e+01 3.15394268e+01 4.29938736e+01 5.62534599e+01 5.70546722e+01 5.42349358e+01 5.03211555e+01 3.51400375e+01 2.62249374e+01 2.67832088e+01 2.99006844e+01 3.11021633e+01 2.75176392e+01 2.39915085e+01 2.73490505e+01 3.37710228e+01 4.33832626e+01 5.04412651e+01 5.15732803e+01 7.21660919e+01 9.22445374e+01 8.14481659e+01 4.43343773e+01 3.31842003e+01 6.14423599e+01 8.04427338e+01 6.78923721e+01 4.52411079e+01 6.41891785e+01 8.20226059e+01 8.71029816e+01 7.16688461e+01 5.86149178e+01 5.74542885e+01 6.32539558e+01 7.21991272e+01 7.50639343e+01 6.31548157e+01 4.53588257e+01 4.32124290e+01 4.48248405e+01 5.36401558e+01 5.22392311e+01 5.78209381e+01 6.52583008e+01 8.09723816e+01 6.24284096e+01 2.98287697e+01 3.22099228e+01 6.05761757e+01 8.45941696e+01 6.69999008e+01 5.37640610e+01 6.02604141e+01 6.65056686e+01 5.56289864e+01 3.75036697e+01 2.52586117e+01 2.92415924e+01 3.32493019e+01 5.26863480e+01 7.39740067e+01 6.70278168e+01 4.18205147e+01 3.70882416e+01 6.74515076e+01 7.45270538e+01 5.63975677e+01 3.57784462e+01 3.82515182e+01 4.29279060e+01 3.24897385e+01 1.62803574e+01 2.74295597e+01 5.01031342e+01 6.78896103e+01 5.74945831e+01 4.92135277e+01 5.02161140e+01 5.37804947e+01 5.89244232e+01 6.24729805e+01 6.00340080e+01 4.96178627e+01 4.82232246e+01 6.54960938e+01 8.35534439e+01 8.30032120e+01 7.14079285e+01 7.74040604e+01 9.76614304e+01 8.74828186e+01 5.78049011e+01 3.12944908e+01 3.32077522e+01 4.62608833e+01 4.33084335e+01 3.83941154e+01 4.50744896e+01 5.60163193e+01 6.57400055e+01 6.11875801e+01 5.27543793e+01 4.79241676e+01 4.26398277e+01 4.25261421e+01 4.59200745e+01 4.80886497e+01 4.85517998e+01 4.81518135e+01 6.04056969e+01 7.10426941e+01 6.59207840e+01 5.03392792e+01 4.66214943e+01 5.85017929e+01 5.50235901e+01 4.32482872e+01 4.69494820e+01 7.55149689e+01 1.05290932e+02 1.07251183e+02 9.12800522e+01 8.71465149e+01 9.19449615e+01 8.78324585e+01 7.41420746e+01 6.56196136e+01 6.87187729e+01 6.77574844e+01 6.74173203e+01 7.39181290e+01 7.39286957e+01 6.25134811e+01 4.92993736e+01 5.70599022e+01 7.23051682e+01 7.11024704e+01 6.02709579e+01 6.36385002e+01 7.84795303e+01 6.87240753e+01 3.81972656e+01 1.97717876e+01 2.83533707e+01 4.33425255e+01 3.94838409e+01 2.96587505e+01 2.90440502e+01 3.67458992e+01 4.28523140e+01 3.83756714e+01 3.61378098e+01 3.76730461e+01 4.72592392e+01 6.41327972e+01 7.86017456e+01 8.75610504e+01 8.83064880e+01 7.11985397e+01 5.36644630e+01 4.59721985e+01 5.26515884e+01 5.85200729e+01 5.60129280e+01 5.69105453e+01 5.13439484e+01 4.24930305e+01 4.46403694e+01 5.27115364e+01 6.09971619e+01 6.09785995e+01 6.27444000e+01 7.50454559e+01 8.36170731e+01 8.09740524e+01 7.11362305e+01 6.43552475e+01 6.51393051e+01 6.32215347e+01 6.37821426e+01 6.74047241e+01 7.04586639e+01 6.95330276e+01 6.71620255e+01 6.59966354e+01 6.42175293e+01 6.14810982e+01 6.22446251e+01 7.22701187e+01 8.50283890e+01 8.32261734e+01 7.48785172e+01 7.16838531e+01 7.89863281e+01 7.92419281e+01 7.33351135e+01 6.71894836e+01 7.39369202e+01 8.10509491e+01 8.04915161e+01 7.33604507e+01 6.21793442e+01 6.01695213e+01 6.07313690e+01 6.90039902e+01 7.60383606e+01 7.45862274e+01 6.70188293e+01 6.68387451e+01 7.44511566e+01 7.71534958e+01 7.31324310e+01 6.51973495e+01 6.88089447e+01 7.35433121e+01 7.37679749e+01 6.70211945e+01 6.09122734e+01 6.33433380e+01 6.95745239e+01 7.20775528e+01 7.22379456e+01 6.97829666e+01 6.88846664e+01 7.05820541e+01 7.11771164e+01 7.47083893e+01 7.52088089e+01 7.44304352e+01 7.14483109e+01 6.81675110e+01 6.74822464e+01 6.56970978e+01 6.61457443e+01 6.61700058e+01 6.69251175e+01 6.74301529e+01 6.76374664e+01 6.71912537e+01 6.59753647e+01 6.30809479e+01 6.20380783e+01 6.57430191e+01 7.00321274e+01 7.15156097e+01 7.36175232e+01 7.97968979e+01 9.00294037e+01 9.05676498e+01 1.33709488e+02 9.72742691e+01 7.73547516e+01 1.05188232e+02 6.41510620e+01 1.94640320e+02 4.49489166e+02 -125723448. -403240896. 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. -8.71589500e+05 -7.99744568e+01 6.75911427e+00 1.17215147e+01 2.40529575e+01 3.71536369e+01 3.93797951e+01 3.47054024e+01 3.57675552e+01 3.69063301e+01 3.52915535e+01 3.42013168e+01 3.46291161e+01 2.52996254e+01 2.18515472e+01 3.00101013e+01 4.86635323e+01 5.47346725e+01 4.53525085e+01 3.95153351e+01 3.24264984e+01 2.92456818e+01 3.06622124e+01 3.12086868e+01 3.20881004e+01 3.27989120e+01 3.60805359e+01 4.01853142e+01 4.06197815e+01 3.64352570e+01 3.20080566e+01 3.25873146e+01 3.30828400e+01 3.29953270e+01 3.61869469e+01 3.63868217e+01 3.59898109e+01 3.31323013e+01 3.01503086e+01 2.72531357e+01 2.57816124e+01 3.20817108e+01 4.09908524e+01 4.42393951e+01 3.89820824e+01 2.90898819e+01 2.80084648e+01 3.15964870e+01 3.16999073e+01 3.02511787e+01 3.32873878e+01 3.90312233e+01 4.23327637e+01 3.73329926e+01 2.92771149e+01 2.12711487e+01 2.21493816e+01 2.48074512e+01 2.72936935e+01 3.21664810e+01 3.54898453e+01 3.83114777e+01 3.36531754e+01 2.76560764e+01 2.17931957e+01 2.15250340e+01 3.05501423e+01 3.90655251e+01 4.28752975e+01 4.49516068e+01 4.02302780e+01 4.00793762e+01 3.56451797e+01 2.62255230e+01 1.86808624e+01 1.74015179e+01 2.64712200e+01 3.50260468e+01 3.77348518e+01 3.40352325e+01 2.59694366e+01 2.30564747e+01 2.08537083e+01 2.17433357e+01 2.49118290e+01 2.61524067e+01 2.89985981e+01 3.07827415e+01 3.03462067e+01 2.52868671e+01 1.87299232e+01 2.13859482e+01 3.07379379e+01 4.07151718e+01 4.10556488e+01 2.75917091e+01 1.95356083e+01 2.50564423e+01 2.87265339e+01 2.25079632e+01 1.73745880e+01 2.61161652e+01 4.17854805e+01 4.68915634e+01 3.55890007e+01 2.02942734e+01 1.16031237e+01 1.67269936e+01 2.13837852e+01 2.79824657e+01 3.42073402e+01 3.33693428e+01 3.35532150e+01 3.10363369e+01 2.05354404e+01 8.81767941e+00 5.65293694e+00 1.92905025e+01 3.64458466e+01 4.29981384e+01 3.59861259e+01 2.27822990e+01 1.73567200e+01 1.72293377e+01 1.67326069e+01 1.84949627e+01 2.48082962e+01 3.62153282e+01 5.02902603e+01 5.18143044e+01 4.23994904e+01 3.08926620e+01 2.79387608e+01 2.43726254e+01 1.73460827e+01 1.92676678e+01 2.26582394e+01 3.10873680e+01 2.96482830e+01 2.65611820e+01 2.40428200e+01 2.48960781e+01 3.21053429e+01 3.35596886e+01 2.74674854e+01 1.92405834e+01 1.68392811e+01 3.02080288e+01 4.13800049e+01 3.49301872e+01 3.01045532e+01 2.74609776e+01 3.65020409e+01 4.44385185e+01 4.41427689e+01 2.26878643e+01 7.14802027e-01 4.46877718e+00 2.99329433e+01 4.63909950e+01 4.61301956e+01 3.82786751e+01 4.19335823e+01 4.05583191e+01 2.54359798e+01 7.33791876e+00 3.28575277e+00 1.92572746e+01 3.28350487e+01 4.83420067e+01 5.81530151e+01 5.21501579e+01 4.93005905e+01 4.26161461e+01 3.48404465e+01 3.00572014e+01 2.76420784e+01 4.32338562e+01 5.02462044e+01 5.06376190e+01 3.71739159e+01 1.90342159e+01 1.52480431e+01 2.20436516e+01 2.55949879e+01 2.85326385e+01 2.68566227e+01 3.99252548e+01 4.39011536e+01 2.45793610e+01 -8.28089118e-01 -9.58002186e+00 8.00828171e+00 2.90368099e+01 4.87664070e+01 5.98140182e+01 5.16589966e+01 4.24384613e+01 3.22013474e+01 1.13889036e+01 -8.17270660e+00 -1.14261580e+01 1.61605530e+01 4.76093063e+01 6.37232933e+01 5.01104927e+01 1.87236557e+01 3.33868170e+00 9.73955822e+00 2.31119442e+01 2.43930302e+01 2.19089088e+01 1.93757496e+01 2.39051819e+01 2.61411591e+01 2.66214790e+01 1.49101372e+01 5.12738848e+00 6.02529526e+00 1.98121052e+01 4.07189331e+01 4.53049812e+01 4.54098816e+01 3.19833298e+01 1.46514616e+01 1.00879354e+01 7.97581100e+00 3.30492210e+01 4.53614006e+01 4.27675400e+01 2.66911640e+01 2.57568340e+01 3.95647125e+01 5.13928719e+01 2.52152576e+01 2.39600703e-01 -1.06101913e+01 1.61410141e+01 3.72484512e+01 3.74320908e+01 4.08692093e+01 2.19343433e+01 6.51881838e+00 -1.13365107e+01 1.27200451e+01 3.82646294e+01 3.73015785e+01 2.99867725e+01 3.52227516e+01 5.71911201e+01 5.49245796e+01 2.87806988e+01 2.03760185e+01 4.09179420e+01 4.60620842e+01 2.71726933e+01 1.86410656e+01 2.81844273e+01 3.66037674e+01 1.82556629e+01 7.14056349e+00 5.95387030e+00 2.62507896e+01 3.95106354e+01 3.64432564e+01 3.60511742e+01 2.12275219e+01 8.06954098e+00 2.99488378e+00 9.57797432e+00 8.41589546e+00 -5.53393936e+00 5.65798664e+00 2.05339184e+01 2.46175308e+01 3.36520600e+00 -1.13691139e+01 -5.54657364e+00 1.65329285e+01 2.27439060e+01 1.04339256e+01 6.61525297e+00 1.38200817e+01 1.84489136e+01 1.36674738e+01 2.93985844e+01 4.44447746e+01 4.54819641e+01 1.65867710e+01 -1.25416985e+01 -1.66163311e+01 -7.97820520e+00 3.80543709e+00 3.80390882e+00 5.63482952e+00 -2.86466861e+00 -1.52790108e+01 -1.53600492e+01 -7.71183157e+00 3.67370963e+00 -7.99142170e+00 -1.78910522e+01 -3.08403921e+00 2.98774223e+01 3.30304375e+01 7.64621258e+00 -1.33493176e+01 -3.16746807e+00 -2.97436857e+00 -1.29103928e+01 -1.58701839e+01 -1.57173233e+01 -1.98912640e+01 -3.32017517e+01 -3.65211525e+01 -2.83754311e+01 -3.39354362e+01 -3.80030556e+01 -3.14850159e+01 -1.15222788e+01 -2.77404642e+00 -1.47749376e+01 -1.06620436e+01 1.64923172e+01 3.46410713e+01 3.43078384e+01 2.81189384e+01 3.57283974e+01 4.31208267e+01 2.55226154e+01 6.20069504e+00 -6.18437815e+00 -1.07668376e+00 -4.02508593e+00 -1.74392109e+01 -1.78769321e+01 -1.82648392e+01 -2.78747520e+01 -3.84462357e+01 -3.47622108e+01 -5.42908382e+00 -3.30482626e+00 -6.65883684e+00 -1.29555502e+01 -6.02934027e+00 -6.50600576e+00 -3.45662842e+01 -3.24864731e+01 -4.10706234e+00 2.88242798e+01 4.08762741e+01 1.85759354e+01 1.82747173e+01 2.74729843e+01 3.79251671e+01 3.51763573e+01 4.75886822e+00 -1.03156557e+01 -2.24827614e+01 -5.69060230e+00 4.48186646e+01 5.67609253e+01 3.46525383e+01 -2.02652187e+01 -3.99606209e+01 -4.18955660e+00 1.19516573e+01 8.38503838e+00 -2.39702816e+01 -4.05369759e+01 -2.07047787e+01 -1.52229471e+01 1.63832986e+00 1.80024986e+01 2.28922653e+01 1.90081902e+01 -9.15470314e+00 -1.58151970e+01 -1.02335882e+01 4.76459646e+00 1.82852936e+01 4.01569796e+00 -1.08053637e+01 -3.05038261e+01 -1.78568325e+01 2.01724491e+01 3.77640114e+01 1.54564676e+01 -2.76815300e+01 -4.39501343e+01 -7.38527632e+00 2.98672428e+01 4.59025421e+01 1.76246357e+01 -1.79307079e+01 -2.07903748e+01 -2.30466576e+01 -4.52511644e+00 1.54271450e+01 2.71797047e+01 3.08814106e+01 5.32114458e+00 -5.30068815e-01 -6.81033897e+00 3.15473825e-01 7.87610435e+00 -5.92745352e+00 -2.17158184e+01 -3.18926010e+01 -1.87303581e+01 2.72066975e+01 3.75342407e+01 2.30081501e+01 -2.15689907e+01 -4.53620949e+01 -2.96684532e+01 -1.51655397e+01 1.57547784e+00 -1.62350597e+01 -3.17712421e+01 -2.64889679e+01 -1.61668587e+01 -7.39346838e+00 3.39081430e+00 2.96468401e+00 2.18373299e+00 -2.54207420e+01 -3.53872452e+01 -2.53080158e+01 5.06386280e+00 3.43713226e+01 1.42638445e+01 -1.66590862e+01 -4.20659523e+01 -3.07915249e+01 1.51902027e+01 2.72834911e+01 1.54774094e+01 -2.41464500e+01 -3.89767876e+01 -2.87071800e+00 4.12839470e+01 7.36397400e+01 5.39958496e+01 1.45476980e+01 -9.14904118e+00 -2.46748753e+01 -1.96550751e+01 7.28013158e-01 1.26198597e+01 9.68385887e+00 -1.92746296e+01 -3.17423725e+01 -3.63529091e+01 -2.55305386e+01 3.02034974e+00 -3.06842494e+00 -1.18383999e+01 -3.97821350e+01 -3.98283653e+01 -1.76602840e+01 7.69478130e+00 2.56438351e+01 7.83475733e+00 -1.30287278e+00 -9.34727573e+00 -5.66008139e+00 4.20520115e+00 2.16269627e+01 2.38630333e+01 2.39181747e+01 1.13256426e+01 1.19037628e+01 1.34016323e+01 8.42558002e+00 8.18954086e+00 -2.09081306e+01 -1.47650919e+01 -1.19853563e+01 -9.64163184e-01 8.96204758e+00 -6.99184465e+00 -8.19886303e+00 -5.38953924e+00 1.96042080e+01 5.28117485e+01 5.40382538e+01 4.18249283e+01 2.88769770e+00 -3.24700699e+01 -1.72202873e+01 1.02071924e+01 4.41575661e+01 4.79707794e+01 2.69776554e+01 5.21016502e+00 -3.05817528e+01 -3.88209686e+01 -2.57236500e+01 -5.85577011e+00 5.33281326e+00 -1.17753792e+01 -3.21617012e+01 -4.17920456e+01 -4.01277695e+01 -1.76529005e-01 2.27938404e+01 2.65827808e+01 -6.23498583e+00 -3.01082649e+01 -8.90313148e+00 2.38073235e+01 3.57240868e+01 9.78249645e+00 -2.08410511e+01 -2.00338898e+01 -2.53262997e+01 -1.71024475e+01 -2.40296674e+00 6.93350506e+00 -5.38625836e-01 -2.73334408e+01 -4.10039482e+01 -2.87291794e+01 -2.16890755e+01 -3.74037051e+00 -1.59809847e+01 -1.72471790e+01 -1.93645267e+01 -1.98992119e+01 5.06176472e+00 1.12273092e+01 9.49035740e+00 -2.37023983e+01 -3.70012131e+01 -3.89748268e+01 -2.95504436e+01 -2.97128105e+01 -2.79437771e+01 -2.86020679e+01 -2.51798611e+01 -3.60242882e+01 -3.73844604e+01 -2.88057537e+01 -1.79368916e+01 -6.39524889e+00 -1.71944141e+01 -1.42340612e+01 -1.09651537e+01 2.73522687e+00 1.13185940e+01 -1.54176140e+01 -2.49003029e+01 -3.12953701e+01 -2.29312458e+01 4.52812386e+00 1.81399727e+01 2.04416771e+01 -1.35446424e+01 -4.47399406e+01 -4.56581192e+01 -3.07025757e+01 -6.76086044e+00 -1.34486704e+01 -3.20801430e+01 -3.10516148e+01 -2.58088779e+01 -1.42150497e+01 -7.55263710e+00 -3.49073315e+00 -4.59545708e+00 -2.09863682e+01 -2.12351398e+01 -1.89607372e+01 -2.22476692e+01 -4.19111204e+00 1.40211856e+00 8.42831516e+00 -7.84940434e+00 -2.01957779e+01 -1.64070797e+01 -1.20780983e+01 -1.78140697e+01 -3.66729851e+01 -6.13525772e+01 -3.65225410e+01 -1.46449718e+01 1.32697477e+01 1.45887156e+01 2.46234012e+00 8.26352298e-01 -1.48324776e+01 -1.14442358e+01 -5.25604582e+00 -1.63478208e+00 1.23981924e+01 -2.83952534e-01 -3.60489011e+00 -1.57184181e+01 -2.22939377e+01 -7.35312176e+00 -2.05580521e+01 -3.38881340e+01 -5.30502930e+01 -4.75453300e+01 -1.81240864e+01 -5.04081774e+00 -4.16279078e+00 -4.55444221e+01 -9.50364532e+01 -5.46248131e+01 -6.19191895e+01 -8.15718293e-01 3.53203506e+01 2.35254517e+02 -1.70838242e+02 -2.65638000e+02 4.27060986e+03 8.75749902e+03 -91476496. 136346288. -104345336. -644055360. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 395975776. 1039180928. -5.57784326e+03 -2.16308740e+03 -3.47946442e+02 -2.00372299e+02 -8.68497086e+01 2.09152699e+01 -1.79849396e+01 -5.52301941e+01 -6.03597527e+01 -4.40100288e+01 -3.65014343e+01 -2.17027931e+01 -1.85480595e+01 -3.19265060e+01 -3.37993622e+01 -2.91717224e+01 -1.37837820e+01 -6.88782036e-01 -6.96697426e+00 -2.26007137e+01 -2.53906269e+01 -2.41583500e+01 -1.32012119e+01 -2.08825779e+01 -2.83177605e+01 -3.40534058e+01 -3.97417793e+01 -3.34020386e+01 -3.13579216e+01 -1.75956879e+01 -4.21160173e+00 -1.58531075e+01 -3.17917557e+01 -4.84291687e+01 -4.25036964e+01 -1.18288679e+01 5.92285872e+00 1.11143761e+01 -1.50946569e+01 -2.53388119e+01 -1.78183422e+01 -8.62256050e+00 -4.57778215e+00 -2.58100681e+01 -4.16066055e+01 -4.49631920e+01 -3.21370087e+01 -9.80596924e+00 3.91516894e-01 2.13620853e+00 -1.51731598e+00 -1.97950783e+01 -2.84136066e+01 -3.55257874e+01 -2.76382198e+01 -1.10091047e+01 -1.67343521e+01 -2.56363087e+01 -3.31111069e+01 -1.71002026e+01 6.48266268e+00 1.92750946e-01 -2.20172920e+01 -4.96203842e+01 -5.67551308e+01 -4.60688896e+01 -3.08421173e+01 -1.16141224e+01 -5.96467447e+00 -1.23110886e+01 -2.61041203e+01 -3.95705528e+01 -4.13574142e+01 -3.94297028e+01 -3.92524796e+01 -2.91250668e+01 -3.12094593e+01 -2.38645325e+01 -2.88691616e+01 -2.75603523e+01 -2.01392193e+01 -2.93588028e+01 -3.75919724e+01 -5.15822525e+01 -5.19580231e+01 -3.71944542e+01 -2.30621281e+01 -1.77570591e+01 -2.94469604e+01 -4.32933807e+01 -4.52402229e+01 -4.45410309e+01 -3.90330238e+01 -3.45940437e+01 -3.77519379e+01 -3.74476929e+01 -4.42694550e+01 -3.63155136e+01 -2.89768505e+01 -2.49629955e+01 -2.42147446e+01 -3.44692802e+01 -3.91935730e+01 -4.39239120e+01 -4.24535065e+01 -3.13869438e+01 -3.34653664e+01 -3.71048393e+01 -4.68115997e+01 -4.82256088e+01 -3.80084229e+01 -2.86190224e+01 -2.56636829e+01 -3.67948494e+01 -4.96630898e+01 -4.66756325e+01 -4.35530586e+01 -3.67879944e+01 -3.28639488e+01 -3.16040459e+01 -3.23279343e+01 -4.20283661e+01 -4.29690971e+01 -4.10885735e+01 -3.87671356e+01 -3.54394150e+01 -3.86893234e+01 -3.95562248e+01 -4.09615517e+01 -3.79935951e+01 -2.74313850e+01 -2.67813206e+01 -3.24093208e+01 -4.07849312e+01 -4.41125793e+01 -3.58093681e+01 -3.06494350e+01 -2.92860184e+01 -3.59853897e+01 -4.26953354e+01 -4.06961670e+01 -4.11402931e+01 -3.74253273e+01 -3.33429527e+01 -3.01554565e+01 -3.01273937e+01 -3.71281281e+01 -4.05178299e+01 -3.99031982e+01 -3.66582565e+01 -3.28686523e+01 -3.56906013e+01 -3.82581711e+01 -4.17758484e+01 -3.95499649e+01 -3.17322598e+01 -2.78603077e+01 -3.13689899e+01 -3.89071388e+01 -4.38560753e+01 -4.20607109e+01 -3.95838966e+01 -3.56404839e+01 -3.72241669e+01 -4.04365044e+01 -3.96675797e+01 -3.77733688e+01 -3.43468285e+01 -3.40377846e+01 -3.64252625e+01 -3.67223701e+01 -3.90354347e+01 -3.82364273e+01 -3.65578423e+01 -3.27754936e+01 -2.80113640e+01 -3.21635056e+01 -3.62880211e+01 -3.92724800e+01 -3.76396637e+01 -3.32564430e+01 -3.48572578e+01 -3.63435287e+01 -3.90060158e+01 -3.82817497e+01 -3.59172974e+01 -3.52808380e+01 -3.39904099e+01 -3.33190689e+01 -3.28449821e+01 -3.15828228e+01 -3.36065865e+01 -3.41934433e+01 -3.39666939e+01 -3.44963722e+01 -3.35422554e+01 -3.53339577e+01 -3.48725891e+01 -3.60812111e+01 -3.53676300e+01 -3.25450172e+01 -3.18696365e+01 -3.19836464e+01 -3.46257935e+01 -3.56291428e+01 -3.49547462e+01 -3.39008827e+01 -3.30942612e+01 -3.39636650e+01 -3.46420250e+01 -3.40948830e+01 -3.31984711e+01 -3.22065506e+01 -3.21499825e+01 -3.30587387e+01 -3.38350334e+01 -3.39997101e+01 -3.33318138e+01 -3.29014206e+01 -3.30480232e+01 -3.30698891e+01 -3.31555862e+01 -3.31440964e+01 -3.31512794e+01 -3.31670723e+01 -3.31858406e+01 -3.31300774e+01 -3.31816254e+01 -3.32366829e+01 -3.31442299e+01 -3.29885941e+01 -3.29387856e+01 -3.31173859e+01 -3.33239136e+01 -3.32362366e+01 -3.33512726e+01 -3.32852364e+01 -3.34433937e+01 -3.31229630e+01 -3.30213852e+01 -3.27780647e+01 -3.27543716e+01 -3.28470802e+01 -3.30801468e+01 -3.33131981e+01 -3.31364288e+01 -3.28857536e+01 -3.23790627e+01 -3.25306358e+01 -3.25140953e+01 -3.30252495e+01 -3.24182091e+01 -3.20292053e+01 -3.19132500e+01 -3.28572617e+01 -3.33772812e+01 -3.31911850e+01 -3.32863884e+01 -3.29114647e+01 -3.22429161e+01 -3.10041027e+01 -3.16026764e+01 -3.17650852e+01 -3.25317726e+01 -3.18899193e+01 -3.30390778e+01 -3.29836159e+01 -3.27643700e+01 -3.13540802e+01 -3.16403713e+01 -3.13101692e+01 -3.23992844e+01 -3.27897797e+01 -3.31080170e+01 -3.20348473e+01 -3.02993450e+01 -3.09731007e+01 -3.16287460e+01 -3.24037056e+01 -3.19299831e+01 -3.15945454e+01 -3.18739872e+01 -3.21910629e+01 -3.23488197e+01 -3.42362442e+01 -3.55730400e+01 -3.64273834e+01 -3.50343361e+01 -3.40501518e+01 -3.27751312e+01 -3.30599022e+01 -3.26289330e+01 -3.25780830e+01 -2.88027077e+01 -2.79554977e+01 -2.69047508e+01 -3.14060555e+01 -3.25204010e+01 -3.52432518e+01 -3.35341721e+01 -3.47665291e+01 -3.41348839e+01 -3.39494095e+01 -3.21730576e+01 -3.16336212e+01 -3.11053467e+01 -3.30246735e+01 -3.60160942e+01 -3.73840981e+01 -3.54436874e+01 -3.39447517e+01 -2.93154354e+01 -2.40008144e+01 -2.11876698e+01 -2.48109932e+01 -3.20439606e+01 -3.40222664e+01 -3.40511208e+01 -3.09450264e+01 -3.28351517e+01 -3.76103020e+01 -3.89040489e+01 -3.52418327e+01 -3.01850262e+01 -3.06827087e+01 -3.06300602e+01 -2.88147488e+01 -3.44386711e+01 -4.13503380e+01 -4.27185631e+01 -3.79252243e+01 -3.43839226e+01 -3.51724854e+01 -3.39745522e+01 -3.33874969e+01 -3.38672218e+01 -3.21072617e+01 -3.05001945e+01 -2.88545971e+01 -3.36657944e+01 -3.50436020e+01 -3.43921356e+01 -2.91757565e+01 -2.01445103e+01 -1.40961800e+01 -1.49463282e+01 -2.42312965e+01 -3.11366844e+01 -3.05308704e+01 -2.54212456e+01 -2.61307678e+01 -2.81021671e+01 -3.12828159e+01 -2.41580524e+01 -2.09582005e+01 -1.79664192e+01 -2.31956120e+01 -2.53464413e+01 -2.71191502e+01 -2.60734406e+01 -2.08429527e+01 -1.47484732e+01 -2.38401337e+01 -3.70665359e+01 -4.08515968e+01 -3.22746201e+01 -2.62101002e+01 -2.72460823e+01 -2.01106167e+01 -1.27719698e+01 -1.24526701e+01 -2.08022327e+01 -2.92713718e+01 -2.98570518e+01 -2.73943233e+01 -2.01821442e+01 -1.29111748e+01 -1.02740984e+01 -1.45962963e+01 -1.89183960e+01 -2.26053772e+01 -2.24051037e+01 -2.44017429e+01 -2.41959000e+01 -2.77910862e+01 -3.01672211e+01 -3.20869408e+01 -2.87829247e+01 -2.84279652e+01 -2.64374561e+01 -2.67807102e+01 -2.34673138e+01 -2.45524349e+01 -2.48196831e+01 -1.88298664e+01 -1.26657515e+01 -1.54065723e+01 -3.26942253e+01 -4.30352211e+01 -3.89277992e+01 -3.22875938e+01 -2.63825741e+01 -2.94309216e+01 -2.20235748e+01 -1.78810368e+01 -1.25047665e+01 -1.55709000e+01 -2.06730232e+01 -2.09500580e+01 -1.18876266e+01 -3.89407492e+00 -1.65342979e+01 -3.61060524e+01 -4.16558609e+01 -2.89491940e+01 -1.93326664e+01 -1.31358032e+01 -7.19474840e+00 -1.14407444e+01 -2.44359379e+01 -3.02228794e+01 -2.33623943e+01 -1.48422022e+01 -1.72902908e+01 -1.96936512e+01 -3.04604225e+01 -4.56107483e+01 -4.71610146e+01 -4.10524139e+01 -2.63510647e+01 -1.88854790e+01 -1.30053339e+01 -1.70510902e+01 -2.45595398e+01 -2.84233875e+01 -3.02444477e+01 -3.25104141e+01 -3.47217598e+01 -3.79469070e+01 -3.77670059e+01 -3.40422745e+01 -2.77644978e+01 -2.63342075e+01 -2.37506962e+01 3.84702373e+00 2.43071232e+01 6.15597115e+01 3.10844650e+01 -2.72997284e+00 -5.69187469e+01 -5.82676964e+01 -5.30810242e+01 -6.15313416e+01 -3.27185559e+00 5.55705261e+02 -1.77477379e+01 -9.22697656e+03 -43137324. -74817408. 43299144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1878641536. 8.88214258e+03 1.80150659e+03 1.05283440e+02 1.74584702e+02 4.27959747e+01 3.02686214e+01 1.98043270e+01 5.60543203e+00 -2.74921346e+00 -2.69160271e+01 -4.45779915e+01 -4.87891197e+01 -3.19880581e+01 -1.89409676e+01 -2.29818859e+01 -2.16239986e+01 -2.52786140e+01 -1.38438187e+02 -1.48196579e+02 -5.92991791e+01 -2.79683514e+01 -1.10398884e+01 -8.98388767e+00 -1.93702602e+01 -2.92803249e+01 -2.12392807e+01 -1.60872955e+01 -1.52110348e+01 -2.16856823e+01 -2.35957108e+01 -2.90658150e+01 -3.08274288e+01 -2.75593739e+01 -2.19902020e+01 -1.91542320e+01 -2.20044918e+01 -2.82045765e+01 -3.14685173e+01 -3.14139519e+01 -2.72110729e+01 -2.57359142e+01 -3.10284653e+01 -2.96230850e+01 -2.68754139e+01 -2.28327999e+01 -1.91127930e+01 -1.73749428e+01 3.05871749e+00 1.88030624e+01 2.20584335e+01 6.22658873e+00 -7.84642935e+00 -1.16906853e+01 -1.14165821e+01 -1.14773273e+01 -7.05395460e+00 -9.60657406e+00 -1.41800499e+01 -2.01601429e+01 -2.41554871e+01 -3.17987823e+01 -4.00492249e+01 -4.70339508e+01 -4.15196877e+01 -3.53283386e+01 -2.71925144e+01 -3.41944275e+01 -4.42802925e+01 -3.99040718e+01 -2.88953094e+01 -1.12331562e+01 -1.80217686e+01 -1.90243664e+01 -6.11784363e+00 1.95744514e+01 3.57537117e+01 3.31309662e+01 2.65070953e+01 2.56098728e+01 1.41081171e+01 4.60967636e+00 -1.25370932e+00 3.09359050e+00 7.32240725e+00 -9.35740566e+00 -2.39160919e+01 -2.71189594e+01 -1.36002932e+01 1.08333433e+00 -1.09007895e+00 -1.86136794e+00 -1.04284134e+01 -1.15299263e+01 -9.47979355e+00 -8.01873112e+00 -1.13872643e+01 -2.20971737e+01 -2.75058289e+01 -3.07243099e+01 -3.14612350e+01 -2.01350040e+01 -6.76407623e+00 8.52556896e+00 1.21603842e+01 -3.58360672e+00 -1.26817141e+01 -2.30950470e+01 -1.34138308e+01 -9.54764843e+00 -2.23070431e+01 -3.77896538e+01 -3.76124191e+01 -2.30352745e+01 -1.00580558e-01 3.41044712e+00 3.54287338e+00 -6.07304335e-01 -1.70704544e+00 -1.51949702e-02 2.89249444e+00 4.55388689e+00 1.62346661e+00 -1.65404487e+00 -8.15289402e+00 -5.03954077e+00 -7.94959450e+00 -1.06530542e+01 -1.54063225e+01 -1.69791298e+01 -1.69308357e+01 -1.77467175e+01 -1.57013159e+01 -5.89118862e+00 4.43527651e+00 -7.90694141e+00 -2.99184093e+01 -3.61863708e+01 -1.96624393e+01 -2.70367908e+00 -3.59787226e+00 -2.87307358e+00 -2.16472015e-01 1.33727944e+00 2.30213553e-01 -1.68612719e+00 -1.57667410e+00 -2.05089951e+00 2.18436074e+00 4.21006775e+00 2.54490137e+00 -1.70070446e+00 -4.42598295e+00 -3.34577942e+00 -2.80532694e+00 -8.55889618e-01 5.13147259e+00 7.44272804e+00 5.69695902e+00 2.02595353e+00 -1.16212368e+01 -3.03670921e+01 -5.24657974e+01 -5.34383965e+01 -3.68235283e+01 -2.35913048e+01 -7.46138859e+00 -5.30593443e+00 1.66965032e+00 2.01859927e+00 -3.95530701e+00 3.30078793e+00 1.47271433e+01 1.74890175e+01 6.49418640e+00 -4.34696627e+00 1.72009125e+01 3.64228706e+01 5.01193962e+01 4.21916695e+01 2.26438770e+01 6.69710016e+00 -2.24771023e+00 2.22575951e+00 6.10061121e+00 5.05117464e+00 2.72587347e+00 4.58454037e+00 9.61412239e+00 1.21771326e+01 8.72350216e+00 4.78120899e+00 2.08096457e+00 4.16476107e+00 5.83355379e+00 3.76387310e+00 1.38918447e+01 2.54788971e+01 2.80265522e+01 1.48937101e+01 5.44874620e+00 2.08606300e+01 3.54575539e+01 4.53326759e+01 4.61036110e+01 3.03568115e+01 1.86860142e+01 2.09079170e+00 2.44214487e+00 2.00574279e+00 2.24494576e+00 2.04510188e+00 -1.44412231e+00 -1.50017059e+00 -3.41711140e+00 -4.45637035e+00 -1.03949332e+00 -6.99762166e-01 7.73453534e-01 -4.29843330e+00 -9.02392673e+00 -8.24829674e+00 -1.09169283e+01 -5.90991497e+00 -5.65125799e+00 -2.28059840e+00 8.86100388e+00 2.04291039e+01 2.19850864e+01 1.23275204e+01 5.60815573e+00 1.18518715e+01 9.10016918e+00 8.46164989e+00 1.17068605e+01 1.45140591e+01 1.29106016e+01 6.76845264e+00 9.11418152e+00 1.44672194e+01 1.25588083e+01 1.29610157e+01 6.27532244e+00 7.61188745e+00 9.79190922e+00 1.53116875e+01 2.93156586e+01 3.92454338e+01 1.77349548e+01 -1.25868511e+01 -2.51857872e+01 -4.29686546e+00 1.35598059e+01 1.34644723e+00 -9.76930141e+00 -7.25728559e+00 1.04990988e+01 2.11889591e+01 1.66235142e+01 1.21570234e+01 9.64126778e+00 1.18474379e+01 1.90822411e+01 2.32865963e+01 2.30462914e+01 1.44923725e+01 8.78529644e+00 1.39573879e+01 2.29764709e+01 2.34794750e+01 1.77675190e+01 1.47019720e+01 2.30344563e+01 2.30005817e+01 1.72952900e+01 1.13944473e+01 5.50646162e+00 4.96530056e+00 1.23023045e+00 7.29274797e+00 2.16716232e+01 3.85643501e+01 4.11786079e+01 2.95913754e+01 1.31372843e+01 9.99324894e+00 1.06868229e+01 2.43703384e+01 3.92808571e+01 3.83600349e+01 2.65879478e+01 1.75311642e+01 2.63496304e+01 2.49619465e+01 2.70448837e+01 1.82177219e+01 2.12726936e+01 1.53925734e+01 1.61565514e+01 1.32044611e+01 1.64055252e+01 2.23178291e+01 2.52694893e+01 2.41028194e+01 2.17789001e+01 1.83405018e+01 1.34777880e+01 9.92157650e+00 5.33440733e+00 8.55684280e+00 1.29191141e+01 1.73212242e+01 1.39728279e+01 8.71088314e+00 6.86303329e+00 5.93766499e+00 8.99620628e+00 8.10805130e+00 6.89197636e+00 5.74987936e+00 8.64373684e+00 1.40103321e+01 1.39671268e+01 1.84726906e+01 3.00616703e+01 3.11730900e+01 2.77867260e+01 1.77184658e+01 1.62462482e+01 1.27345676e+01 1.14730577e+01 1.69964676e+01 2.96735840e+01 3.58725052e+01 3.23778152e+01 1.31866789e+01 -3.38064241e+00 -1.53453407e+01 -2.25570526e+01 -1.34907389e+01 -4.01878738e+00 2.16085835e+01 3.39146118e+01 3.41168022e+01 2.19574203e+01 2.07506752e+01 3.76214027e+01 3.56031036e+01 1.88197956e+01 -2.54009175e+00 8.25476408e-01 1.42848730e+01 2.64140301e+01 2.83497181e+01 1.57095394e+01 1.44418907e+01 1.68989811e+01 3.38082886e+01 4.87753143e+01 4.97559700e+01 3.90735016e+01 3.16178894e+01 4.30727310e+01 4.67556305e+01 4.03302383e+01 2.90562534e+01 3.57103729e+01 4.60349426e+01 4.86096191e+01 3.97741776e+01 2.77416134e+01 2.57581940e+01 2.05414925e+01 3.04330864e+01 3.65978928e+01 3.30179901e+01 2.32392826e+01 1.66098690e+01 1.23679705e+01 5.25579262e+00 3.34954548e+00 1.28235674e+01 2.07523270e+01 2.71286545e+01 3.41798210e+01 3.54054031e+01 4.21236649e+01 4.36531677e+01 4.17572250e+01 2.72300110e+01 2.10520573e+01 2.27915440e+01 2.55530739e+01 2.25139885e+01 1.84694366e+01 1.38540449e+01 1.04851208e+01 7.05387783e+00 2.04902973e+01 3.52614746e+01 3.18317623e+01 1.18416023e+01 9.16799927e+00 2.90352306e+01 3.83498688e+01 2.89061832e+01 1.37869225e+01 2.37224445e+01 3.80050583e+01 4.43336143e+01 3.60232239e+01 3.29310493e+01 3.90158844e+01 3.79907150e+01 2.52519455e+01 1.52152138e+01 1.61765003e+01 2.07732086e+01 2.75347328e+01 2.84716129e+01 3.46865807e+01 4.22844429e+01 4.41707344e+01 4.93450546e+01 5.03697548e+01 4.83550835e+01 3.70317955e+01 2.68753529e+01 2.73622246e+01 2.53518219e+01 2.45803719e+01 2.22434998e+01 3.01432972e+01 3.61543579e+01 4.01670837e+01 3.96418571e+01 4.04279938e+01 4.64090118e+01 4.19016724e+01 3.30825806e+01 2.31045151e+01 1.86505413e+01 1.35251741e+01 1.25734949e+01 1.53717432e+01 2.81552277e+01 3.96906853e+01 3.97417870e+01 3.95922203e+01 3.97854500e+01 4.12060356e+01 3.25945587e+01 2.51822643e+01 2.30713043e+01 2.74202118e+01 2.64119358e+01 3.25681572e+01 3.56010437e+01 3.77066612e+01 4.17311363e+01 4.41483002e+01 4.50843315e+01 3.82486801e+01 3.21041870e+01 2.99881744e+01 3.17955494e+01 3.49959717e+01 3.67376938e+01 4.32423401e+01 5.09865723e+01 5.40682526e+01 4.94410591e+01 3.77760468e+01 2.81777687e+01 2.02848473e+01 1.96928291e+01 2.08501472e+01 2.49039860e+01 2.35529194e+01 2.29612408e+01 2.04812851e+01 2.02352943e+01 1.98607082e+01 1.87115326e+01 1.96013603e+01 2.30881767e+01 3.08981075e+01 3.65740891e+01 3.49853821e+01 2.93764477e+01 3.09416866e+01 3.67260094e+01 3.47146225e+01 3.53533516e+01 3.77988014e+01 3.96054535e+01 3.32476959e+01 2.71016102e+01 3.32386398e+01 4.10500870e+01 4.17398338e+01 3.52800140e+01 3.56101189e+01 4.24349632e+01 4.51133766e+01 3.73049507e+01 3.44067612e+01 3.64594879e+01 3.43816109e+01 3.17862263e+01 2.84436378e+01 3.77548561e+01 4.35630341e+01 4.38027115e+01 3.88819695e+01 3.30690994e+01 3.26435738e+01 3.26896019e+01 3.82294922e+01 4.65731544e+01 4.50466995e+01 3.94144974e+01 3.13418827e+01 3.09320221e+01 2.94152050e+01 2.86425571e+01 2.91147671e+01 3.08495064e+01 3.23532982e+01 3.19904480e+01 3.34325638e+01 3.34471855e+01 3.41495514e+01 3.16880798e+01 3.02203331e+01 3.09791470e+01 3.60431290e+01 4.20100784e+01 4.09480362e+01 3.62220230e+01 3.43007431e+01 3.75819664e+01 3.59344139e+01 3.21775780e+01 2.78505650e+01 2.89550838e+01 2.91720161e+01 2.98888969e+01 3.04153843e+01 3.01905651e+01 2.93101311e+01 2.83295860e+01 3.25371819e+01 3.89540291e+01 4.19696350e+01 3.85756569e+01 3.79509163e+01 4.05176201e+01 4.04637337e+01 3.61506996e+01 3.34529114e+01 3.32890472e+01 3.32266350e+01 3.30971718e+01 3.40186768e+01 3.62687874e+01 3.54445457e+01 3.39153442e+01 3.53638725e+01 3.95515137e+01 4.13945389e+01 3.74941902e+01 3.53674126e+01 3.73487968e+01 3.78757629e+01 3.69341087e+01 3.31227036e+01 3.40097847e+01 3.53352318e+01 3.25505943e+01 2.90819397e+01 2.93515129e+01 3.43902168e+01 3.66900826e+01 3.45703888e+01 3.23185616e+01 3.17187862e+01 3.13907909e+01 3.36663895e+01 3.60465508e+01 3.74665108e+01 3.58887253e+01 3.44137650e+01 3.55403709e+01 3.75284424e+01 3.62559967e+01 3.43490601e+01 3.35083084e+01 3.95097771e+01 4.22256737e+01 5.04154396e+01 4.17393723e+01 1.20688889e+02 3.76490364e+01 -7.51835155e+00 1.31408249e+02 1.68303024e+02 -1.49896500e+02 -3.44644836e+02 -125723448. -403240896. 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. -499717472. -6.37376648e+02 -8.24172287e+01 5.41437798e+01 6.57274170e+01 1.11095451e+02 7.84886856e+01 2.81442795e+01 2.39132023e+01 2.29086323e+01 1.81481724e+01 1.37342129e+01 2.11934757e+01 -1.71415958e+01 -2.81880226e+01 8.67278748e+01 1.76018356e+02 1.30933960e+02 5.29399300e+01 4.26868286e+01 3.66449852e+01 2.72793026e+01 2.66591663e+01 2.67308407e+01 2.57410011e+01 2.53031750e+01 2.47398033e+01 2.41552696e+01 2.36801033e+01 2.36361370e+01 2.41161423e+01 2.48675289e+01 2.45513859e+01 2.40435905e+01 2.30698128e+01 2.36122665e+01 2.38348465e+01 2.41380806e+01 2.34714355e+01 2.38744717e+01 2.37935143e+01 2.47100964e+01 2.45793877e+01 2.45416298e+01 2.40543861e+01 2.38058414e+01 2.36763916e+01 2.32712727e+01 2.35856819e+01 2.35194778e+01 2.32930641e+01 2.30172157e+01 2.32814980e+01 2.32583752e+01 2.34533691e+01 2.35505657e+01 2.41520252e+01 2.39441376e+01 2.34702778e+01 2.25686073e+01 2.26012363e+01 2.28740215e+01 2.29283867e+01 2.24994354e+01 2.25224209e+01 2.26103592e+01 2.34032688e+01 2.32269173e+01 2.34781094e+01 2.28845882e+01 2.28545494e+01 2.32394218e+01 2.42079239e+01 2.50353603e+01 2.45917053e+01 2.44272957e+01 2.36979599e+01 2.26437283e+01 2.12369766e+01 2.13892708e+01 2.25586071e+01 2.29860687e+01 2.33779926e+01 2.30963326e+01 2.30349846e+01 2.31699982e+01 2.28426571e+01 2.22444057e+01 2.13120003e+01 2.17921486e+01 2.29321079e+01 2.37068462e+01 2.36289024e+01 2.22686806e+01 2.08179722e+01 1.95303688e+01 2.01257477e+01 2.04322052e+01 2.10361900e+01 2.15296898e+01 2.18356304e+01 2.24606342e+01 2.25302353e+01 2.29399014e+01 2.22392406e+01 2.12887592e+01 2.06824837e+01 2.19007721e+01 2.25005417e+01 2.20474110e+01 2.07541714e+01 1.97354546e+01 1.95774937e+01 1.86927662e+01 1.89833622e+01 2.02399559e+01 2.17397747e+01 2.21388836e+01 2.12840347e+01 2.00527439e+01 1.99721718e+01 1.94668427e+01 2.09446945e+01 2.20310249e+01 2.25457973e+01 2.18259544e+01 2.11156902e+01 2.17416592e+01 2.07114105e+01 1.92539577e+01 1.87869053e+01 2.00901928e+01 2.19260025e+01 2.21169720e+01 2.20587101e+01 2.13086586e+01 2.12837086e+01 2.15420341e+01 2.12160301e+01 2.03977718e+01 1.86663532e+01 1.98620358e+01 2.23192043e+01 2.41249695e+01 2.37239075e+01 2.12305565e+01 1.97813892e+01 1.84973850e+01 1.92428818e+01 2.04872532e+01 2.13724060e+01 2.17261543e+01 2.16582890e+01 2.07621498e+01 2.06860886e+01 2.07439384e+01 2.00883274e+01 1.96178875e+01 1.86095276e+01 1.94241352e+01 1.87605991e+01 1.84566345e+01 1.94056778e+01 2.10533619e+01 2.23725071e+01 2.28922672e+01 2.22710400e+01 2.18979988e+01 2.16658936e+01 2.01501255e+01 1.80938072e+01 1.60435257e+01 1.71817131e+01 1.82357559e+01 1.90878258e+01 1.75866337e+01 2.03792515e+01 2.08847141e+01 2.05821629e+01 1.62580776e+01 1.51252823e+01 1.75956135e+01 2.05036373e+01 2.29203720e+01 2.32903500e+01 2.16713562e+01 2.01458836e+01 1.96941223e+01 1.84277992e+01 1.83996563e+01 1.73878574e+01 1.90984268e+01 2.26249561e+01 2.36056118e+01 2.16192818e+01 1.71686974e+01 1.64724350e+01 1.74071407e+01 1.77493725e+01 1.86498566e+01 2.02692146e+01 2.19905853e+01 1.96915092e+01 1.70334110e+01 1.51254778e+01 1.70509624e+01 1.86645832e+01 1.87628841e+01 1.50911417e+01 1.53615131e+01 1.60292149e+01 1.92256489e+01 1.80515518e+01 1.74939270e+01 1.75918617e+01 1.63637104e+01 1.89309063e+01 1.76415157e+01 1.94798336e+01 1.45535364e+01 1.51187696e+01 1.56359291e+01 1.71256466e+01 1.63742294e+01 1.59820623e+01 1.48338137e+01 1.84821224e+01 1.53247061e+01 1.70191307e+01 1.24443541e+01 1.43580399e+01 1.59894304e+01 1.55967722e+01 1.51171074e+01 1.60892620e+01 1.65847473e+01 1.81198101e+01 1.58078566e+01 1.40969677e+01 1.14628630e+01 1.12026348e+01 1.62204151e+01 1.75465813e+01 1.76481400e+01 1.35858660e+01 1.48785744e+01 1.51064453e+01 1.66464729e+01 1.43878098e+01 1.33030853e+01 1.26018982e+01 1.41141329e+01 1.61612759e+01 1.54857998e+01 1.44516850e+01 1.34899988e+01 1.27377167e+01 1.36491718e+01 1.29858999e+01 1.50921631e+01 1.52951393e+01 1.66133766e+01 1.57758436e+01 1.59524326e+01 1.54380560e+01 1.69028511e+01 1.53534784e+01 1.49943886e+01 1.24865055e+01 1.30996990e+01 1.35332861e+01 1.41193590e+01 1.43074989e+01 1.49608393e+01 1.40913048e+01 1.52560253e+01 1.33562603e+01 1.31473274e+01 9.97867775e+00 1.05654125e+01 1.12435398e+01 1.15400333e+01 1.06185017e+01 1.13682127e+01 1.02705374e+01 9.88510418e+00 8.05066872e+00 1.04069967e+01 1.05197554e+01 1.04571571e+01 1.03050337e+01 1.16256981e+01 1.24700527e+01 1.03386812e+01 9.27010345e+00 1.04095325e+01 1.17544012e+01 1.22419777e+01 1.14502916e+01 1.06328115e+01 8.41584492e+00 8.46827316e+00 8.05782890e+00 9.39961624e+00 9.35103989e+00 6.92003250e+00 7.61237144e+00 7.83934402e+00 1.26230707e+01 1.28869085e+01 9.07631493e+00 1.02447510e+01 1.02606297e+01 1.12782555e+01 7.67261362e+00 6.15648127e+00 8.68913746e+00 9.35303497e+00 8.72433853e+00 6.08239651e+00 6.28390884e+00 7.98599529e+00 1.02806463e+01 7.67589140e+00 6.10890627e+00 5.94977140e+00 7.30344057e+00 7.60810709e+00 8.90703392e+00 1.07087221e+01 1.02961607e+01 8.64359665e+00 7.81695509e+00 7.99757957e+00 8.32477951e+00 7.61430740e+00 8.77570343e+00 8.58493519e+00 9.69051552e+00 9.31268406e+00 6.22765064e+00 4.59952068e+00 3.17346215e+00 5.73275995e+00 5.57939434e+00 7.16812992e+00 5.91256857e+00 4.60994911e+00 6.23310375e+00 8.09007359e+00 7.99602365e+00 6.06086159e+00 3.96904588e+00 3.27331567e+00 3.78593946e+00 3.87269378e+00 5.81118107e+00 5.18403769e+00 5.86117744e+00 4.88573217e+00 3.83868027e+00 5.45921326e+00 9.08473110e+00 1.04341869e+01 1.09119654e+01 8.01113415e+00 5.67252970e+00 4.99541998e+00 4.72489357e+00 7.43022633e+00 6.14824438e+00 7.50837803e+00 6.43707657e+00 6.95898008e+00 8.88531590e+00 9.37711906e+00 8.82449722e+00 6.65030003e+00 5.14658689e+00 4.79116344e+00 5.00117636e+00 4.87536860e+00 2.25563288e+00 1.35773396e+00 -1.77862144e+00 3.26298475e+00 5.65350151e+00 1.22058144e+01 1.11891460e+01 7.97513247e+00 6.07609177e+00 4.23127317e+00 6.40202522e+00 2.85767055e+00 2.74062848e+00 3.64087224e+00 6.47508383e+00 6.58213758e+00 2.19254589e+00 1.14474785e+00 1.82919651e-01 1.69181824e+00 -7.06303358e-01 2.21623302e+00 2.37467027e+00 3.97922230e+00 1.43177247e+00 2.38743591e+00 3.91505361e+00 4.21103811e+00 3.71216035e+00 3.03107858e+00 4.38419819e+00 5.58444881e+00 7.37751436e+00 8.62969685e+00 8.26990509e+00 7.80653811e+00 6.52073812e+00 6.55480671e+00 3.78974199e+00 -1.61728406e+00 -2.88517928e+00 -2.05642104e+00 3.47513390e+00 2.48216176e+00 1.44144511e+00 -6.41302764e-01 -1.84643686e+00 5.94727218e-01 2.76039362e-01 3.39593911e+00 -1.37899470e+00 1.30822286e-01 -1.23232174e+00 -1.31776440e+00 -3.52939272e+00 -3.52054787e+00 1.11710906e-01 1.71087503e+00 1.33298182e+00 -2.01916359e-02 -1.54544115e+00 1.05891302e-01 3.49409962e+00 5.50064659e+00 1.45074868e+00 -3.01715899e+00 -5.46817684e+00 -2.56348491e+00 1.07836115e+00 1.99221325e+00 -1.66158450e+00 -2.95690227e+00 6.27154857e-02 4.21754265e+00 1.94634783e+00 3.08049709e-01 -6.18621469e-01 1.94848776e+00 -2.12113166e+00 -3.30199391e-01 -3.00519061e+00 -3.49479365e+00 -3.78380370e+00 -4.48826647e+00 -2.54336643e+00 -4.85639381e+00 -2.14394116e+00 -1.61064327e-01 4.37228948e-01 -3.22317076e+00 -4.56453466e+00 -6.56443596e+00 -7.41205692e-01 4.52579796e-01 1.77306974e+00 -3.71189356e+00 -5.44496679e+00 -5.80584288e+00 -4.46106958e+00 -4.84454727e+00 -4.98080015e+00 -4.14074612e+00 -4.96830177e+00 -6.82225275e+00 -6.19521952e+00 -6.66088676e+00 -5.47958517e+00 -4.07294703e+00 -3.92384839e+00 -6.04949141e+00 -1.20279512e+01 -8.66901493e+00 -4.64289618e+00 -6.30786479e-01 -1.50805092e+00 -4.41961813e+00 -5.88667393e+00 -6.35733891e+00 -4.39632559e+00 -3.62168717e+00 -3.93698287e+00 -5.40582657e+00 -3.10692143e+00 -4.62280512e+00 -1.48894489e+00 -3.55349398e+00 -4.05077648e+00 -4.07961845e+00 -6.09063482e+00 -5.01853561e+00 -6.86841488e+00 -4.13253069e+00 -3.20618606e+00 -5.52479792e+00 -8.38794041e+00 -1.08230972e+01 -8.77685928e+00 -6.83023596e+00 -5.80095816e+00 -6.60872269e+00 -8.20636749e+00 -1.00236158e+01 -8.83748722e+00 -7.45147371e+00 -5.71222973e+00 -6.88032627e+00 -8.32670212e+00 -8.74475288e+00 -8.19358826e+00 -6.23693562e+00 -2.12539458e+00 -2.67579460e+00 -3.21444082e+00 -7.53262234e+00 -9.34095860e+00 -1.09415426e+01 -1.04949942e+01 -9.43636227e+00 -9.49140072e+00 -7.57315826e+00 -7.08886242e+00 -7.22819519e+00 -7.03489923e+00 -7.53088856e+00 -7.92515516e+00 -1.04003391e+01 -1.17197027e+01 -1.21621361e+01 -1.15208874e+01 -1.10969391e+01 -1.16698637e+01 -1.19128971e+01 -1.38240013e+01 -1.31447420e+01 -1.29835215e+01 -9.51056480e+00 -8.30225277e+00 -7.63265657e+00 -9.14076328e+00 -1.05449381e+01 -1.22495966e+01 -8.53971863e+00 -1.08844452e+01 -1.15742264e+01 -1.81774540e+01 -1.51392088e+01 -1.32392960e+01 -8.10092449e+00 -7.20076990e+00 -7.94195938e+00 -9.89430904e+00 -1.19443130e+01 -1.32367420e+01 -1.26728687e+01 -1.23471193e+01 -1.21695337e+01 -1.39414730e+01 -1.36358519e+01 -1.18526783e+01 -1.00790110e+01 -8.51282215e+00 -1.11725826e+01 -9.33137608e+00 -1.19980431e+01 -1.22105427e+01 -1.19354458e+01 -1.12529583e+01 -8.74976540e+00 -1.25058842e+01 -1.23482256e+01 -1.37737875e+01 -1.34188490e+01 -1.23720112e+01 -1.03371210e+01 -9.49396610e+00 -1.04993925e+01 -1.26293430e+01 -1.24296589e+01 -1.32888975e+01 -1.18335629e+01 -1.43440037e+01 -1.71999245e+01 -1.89200935e+01 -2.08729687e+01 -1.84606705e+01 -1.73821640e+01 -1.37839632e+01 -1.24450884e+01 -1.35748444e+01 -1.90635834e+01 -2.15185966e+01 -2.52836876e+01 -2.58257046e+01 -4.39296188e+01 -5.45811501e+01 -1.03048080e+02 -7.10837402e+01 7.80495605e+01 3.35772369e+02 1.66695044e+03 -1.33444838e+06 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -260495952. -50067192. -7.09379688e+03 -3.33353125e+03 -6.07727722e+02 4.44541229e+02 1.19508659e+02 -9.96046219e+01 -1.00453117e+02 -7.54847946e+01 -1.91930008e+02 -1.18181129e+02 -2.74450130e+01 3.32303543e+01 6.13645172e+01 4.85440941e+01 6.71273651e+01 5.80984497e+01 4.46619606e+01 1.49540272e+01 8.71984005e+00 2.63901681e-01 -2.78332090e+00 -8.17605209e+00 -1.29665194e+01 -1.59315205e+01 -1.62759361e+01 -1.83704872e+01 -1.77899494e+01 -1.74432487e+01 -1.57720566e+01 -1.59766607e+01 -1.72945156e+01 -1.83702660e+01 -1.92172890e+01 -2.05463161e+01 -2.10882797e+01 -2.02256775e+01 -1.84187374e+01 -1.80906639e+01 -1.94508896e+01 -1.94673748e+01 -2.01913757e+01 -2.03720112e+01 -2.05989513e+01 -1.87028084e+01 -1.95445156e+01 -2.08033962e+01 -2.15378742e+01 -1.89941101e+01 -1.87241611e+01 -1.83101501e+01 -1.92593060e+01 -1.91278267e+01 -1.99750195e+01 -2.07782478e+01 -2.02345486e+01 -2.01746674e+01 -1.97097836e+01 -1.97710037e+01 -1.99408245e+01 -1.93154469e+01 -1.83323860e+01 -1.87053814e+01 -2.04727097e+01 -2.24206276e+01 -2.14803944e+01 -2.02234364e+01 -1.99060440e+01 -1.94294453e+01 -1.89132595e+01 -1.73563900e+01 -1.77527790e+01 -1.84136944e+01 -1.91014385e+01 -1.90148830e+01 -1.94823055e+01 -2.08082390e+01 -2.08414249e+01 -1.96958313e+01 -1.95974903e+01 -2.07001877e+01 -2.12915440e+01 -2.10333366e+01 -2.10481701e+01 -2.27223835e+01 -2.28098869e+01 -2.30098076e+01 -2.15670605e+01 -2.11042423e+01 -2.00577450e+01 -2.00295448e+01 -1.92579803e+01 -2.01516895e+01 -1.93563061e+01 -2.06634026e+01 -2.00410042e+01 -2.07322216e+01 -2.03078117e+01 -1.99883099e+01 -2.08302307e+01 -2.14858093e+01 -2.33398933e+01 -2.37704830e+01 -2.29371643e+01 -2.18242435e+01 -2.03087902e+01 -2.03122120e+01 -2.05281544e+01 -2.11000996e+01 -2.18323917e+01 -2.18982105e+01 -2.12072182e+01 -2.16038494e+01 -2.13247662e+01 -2.19687920e+01 -2.10592690e+01 -2.08404789e+01 -2.15069599e+01 -2.23146057e+01 -2.23033600e+01 -2.27213440e+01 -2.30139217e+01 -2.43527088e+01 -2.38107071e+01 -2.30834522e+01 -2.34576740e+01 -2.35267639e+01 -2.30342445e+01 -2.20174885e+01 -2.20062981e+01 -2.23347473e+01 -2.21484203e+01 -2.22703552e+01 -2.31722126e+01 -2.41102619e+01 -2.39958973e+01 -2.35212173e+01 -2.28868675e+01 -2.30535603e+01 -2.29155617e+01 -2.26406841e+01 -2.19560471e+01 -2.21140099e+01 -2.12283363e+01 -2.16200542e+01 -2.13695469e+01 -2.20951653e+01 -2.20886707e+01 -2.17717743e+01 -2.22975616e+01 -2.25407734e+01 -2.33657570e+01 -2.32216167e+01 -2.33954258e+01 -2.23663425e+01 -2.26869164e+01 -2.25117283e+01 -2.32248993e+01 -2.28988800e+01 -2.31181431e+01 -2.23966103e+01 -2.26277695e+01 -2.26286945e+01 -2.29490128e+01 -2.27022038e+01 -2.33401165e+01 -2.38629742e+01 -2.39250717e+01 -2.32572155e+01 -2.25955639e+01 -2.26374950e+01 -2.27149487e+01 -2.30907040e+01 -2.30094223e+01 -2.34503574e+01 -2.32793274e+01 -2.35946655e+01 -2.36528130e+01 -2.39913559e+01 -2.37525330e+01 -2.32600822e+01 -2.32906303e+01 -2.35521278e+01 -2.34138241e+01 -2.31129780e+01 -2.29860516e+01 -2.34508591e+01 -2.35305882e+01 -2.30931759e+01 -2.32059917e+01 -2.33713493e+01 -2.38759251e+01 -2.37352982e+01 -2.35509472e+01 -2.35120506e+01 -2.35243778e+01 -2.38816357e+01 -2.37650471e+01 -2.36234493e+01 -2.34577560e+01 -2.36717415e+01 -2.37425690e+01 -2.36971893e+01 -2.35620022e+01 -2.37646294e+01 -2.37294216e+01 -2.38349552e+01 -2.37650299e+01 -2.38505802e+01 -2.39203320e+01 -2.38952656e+01 -2.39915142e+01 -2.39319134e+01 -2.38884773e+01 -2.37999249e+01 -2.38647099e+01 -2.39408379e+01 -2.39641323e+01 -2.39358253e+01 -2.39398613e+01 -2.39454021e+01 -2.39365063e+01 -2.39258976e+01 -2.39195747e+01 -2.39063931e+01 -2.39244289e+01 -2.39276352e+01 -2.39110413e+01 -2.39050026e+01 -2.38897915e+01 -2.39765511e+01 -2.39800987e+01 -2.38658962e+01 -2.38277016e+01 -2.38071728e+01 -2.39338779e+01 -2.39008751e+01 -2.39935207e+01 -2.39539776e+01 -2.38495293e+01 -2.37327442e+01 -2.37696648e+01 -2.37577019e+01 -2.38666477e+01 -2.39495792e+01 -2.39485855e+01 -2.41111984e+01 -2.40872383e+01 -2.43937302e+01 -2.41512661e+01 -2.39659767e+01 -2.36584301e+01 -2.36746044e+01 -2.36248169e+01 -2.37523918e+01 -2.36916351e+01 -2.37082863e+01 -2.36584988e+01 -2.34136620e+01 -2.32525768e+01 -2.30320683e+01 -2.31196632e+01 -2.29732857e+01 -2.30132275e+01 -2.31692200e+01 -2.33308392e+01 -2.35748768e+01 -2.37692089e+01 -2.39296703e+01 -2.38554821e+01 -2.36758900e+01 -2.35510902e+01 -2.35082645e+01 -2.34934349e+01 -2.38982315e+01 -2.37396755e+01 -2.37219276e+01 -2.32917480e+01 -2.35195332e+01 -2.35089359e+01 -2.38859940e+01 -2.36345787e+01 -2.37329884e+01 -2.26477985e+01 -2.32123756e+01 -2.30269547e+01 -2.39104519e+01 -2.35415764e+01 -2.33853054e+01 -2.32291985e+01 -2.27836304e+01 -2.29944859e+01 -2.31373692e+01 -2.39683895e+01 -2.42762470e+01 -2.38567276e+01 -2.34748116e+01 -2.37573376e+01 -2.38184872e+01 -2.39597797e+01 -2.31210938e+01 -2.37269497e+01 -2.27846661e+01 -2.31211739e+01 -2.29951916e+01 -2.34715519e+01 -2.29237881e+01 -2.27369900e+01 -2.27301044e+01 -2.32834702e+01 -2.32530060e+01 -2.31385231e+01 -2.30544605e+01 -2.30556812e+01 -2.30568447e+01 -2.27871666e+01 -2.26405487e+01 -2.29661846e+01 -2.26797829e+01 -2.21998787e+01 -2.19656658e+01 -2.22914639e+01 -2.28241787e+01 -2.25666943e+01 -2.27295761e+01 -2.19893856e+01 -2.19470978e+01 -2.11147881e+01 -2.20296249e+01 -2.17681999e+01 -2.25408459e+01 -2.22375259e+01 -2.25120792e+01 -2.24179878e+01 -2.20648460e+01 -2.15517788e+01 -2.16259842e+01 -2.15895462e+01 -2.17966309e+01 -2.14387455e+01 -2.16793194e+01 -2.22548428e+01 -2.27792950e+01 -2.30008144e+01 -2.31613522e+01 -2.28184204e+01 -2.27333069e+01 -2.27981377e+01 -2.28430386e+01 -2.20335217e+01 -2.04822750e+01 -1.93354168e+01 -2.02563305e+01 -1.99638844e+01 -2.13613415e+01 -2.09249611e+01 -2.20263958e+01 -2.24506168e+01 -2.13169861e+01 -2.19160328e+01 -2.17526360e+01 -2.18488770e+01 -1.99556732e+01 -1.95142231e+01 -1.98236675e+01 -2.05084381e+01 -2.07254086e+01 -2.03428097e+01 -1.98890266e+01 -1.91781349e+01 -2.05391655e+01 -1.98788662e+01 -1.99132977e+01 -1.82799644e+01 -2.02710762e+01 -2.08927021e+01 -2.21460876e+01 -2.18164101e+01 -2.04373074e+01 -2.01453724e+01 -1.98164139e+01 -2.05626812e+01 -2.01668644e+01 -1.92080956e+01 -1.89816170e+01 -1.99934845e+01 -2.12365818e+01 -2.05864296e+01 -2.07135239e+01 -1.96257877e+01 -2.05773945e+01 -1.97433910e+01 -1.94953575e+01 -1.85278549e+01 -1.89038239e+01 -1.99191456e+01 -2.05127220e+01 -1.81932163e+01 -1.75348969e+01 -1.85725021e+01 -2.06592445e+01 -2.16849823e+01 -2.20311584e+01 -2.18877277e+01 -2.01855259e+01 -1.90678844e+01 -1.73694763e+01 -1.78439217e+01 -1.70900269e+01 -1.74046574e+01 -1.70882416e+01 -1.69408360e+01 -1.84133282e+01 -2.01485386e+01 -2.08530369e+01 -2.00665359e+01 -2.00593929e+01 -1.97736816e+01 -1.93702698e+01 -1.82715855e+01 -1.76784458e+01 -1.78696556e+01 -1.69723358e+01 -1.72776241e+01 -1.68449783e+01 -1.72128525e+01 -1.69214535e+01 -1.63783436e+01 -1.63613892e+01 -1.69437160e+01 -1.71385155e+01 -1.74777412e+01 -1.73374786e+01 -1.79246998e+01 -1.72980194e+01 -1.76748543e+01 -1.88363762e+01 -1.84439926e+01 -1.84750843e+01 -1.73724117e+01 -1.80128212e+01 -1.69762554e+01 -1.69160366e+01 -1.61381416e+01 -1.52712746e+01 -1.48432045e+01 -1.21589470e+01 -1.32761993e+01 -1.16205177e+01 -1.64864025e+01 -1.99129944e+01 -1.99359398e+01 -1.58299618e+01 -1.02666817e+01 2.99897614e+01 6.54227600e+01 6.69443970e+01 1.28239404e+03 2.69988599e+03 -200268336. -294410496. 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. 0. 0. 0. 0. 0. 0. 0. 0. -72111200. 101329312. -26924798. -36491876. 6.44787158e+03 2.87962354e+03 2.90795349e+02 2.19291134e+01 -3.09376373e+01 -1.95212135e+01 1.19909258e+01 2.11187840e+01 3.00443029e+00 -1.36981382e+01 -5.91383314e+00 -4.78177643e+00 -4.81495571e+00 -1.10154602e+03 -7.85656311e+02 -1.54127502e+02 -4.76084976e+01 -3.64005966e+01 -2.77634583e+01 -2.44319897e+01 -1.72509155e+01 -1.19544830e+01 -1.20111046e+01 -1.11854019e+01 -1.18816128e+01 -9.91406345e+00 -8.91867924e+00 -8.76017761e+00 -9.44051170e+00 -1.19586353e+01 -1.23734055e+01 -1.29784031e+01 -1.26525660e+01 -1.49364023e+01 -1.44444361e+01 -1.46528912e+01 -1.24008627e+01 -1.27047663e+01 -1.22330418e+01 -1.12010860e+01 -1.02746525e+01 -9.79393101e+00 -9.66800785e+00 -8.85601330e+00 -8.97264194e+00 -8.57339478e+00 -9.92573643e+00 -1.00918493e+01 -1.00213327e+01 -1.19961433e+01 -1.17369318e+01 -1.31577902e+01 -1.20248251e+01 -1.15556145e+01 -1.04857845e+01 -9.92965031e+00 -1.04408407e+01 -9.08167267e+00 -6.70132399e+00 -6.69576883e+00 -9.05067444e+00 -1.09854231e+01 -8.73892975e+00 -7.76935768e+00 -7.25536776e+00 -7.26051998e+00 -8.90405369e+00 -8.71580219e+00 -9.02802277e+00 -8.75624657e+00 -1.02361155e+01 -1.28155842e+01 -1.19363756e+01 -1.17663908e+01 -9.60059071e+00 -9.74482441e+00 -8.71432972e+00 -9.92893600e+00 -7.72455549e+00 -7.02721596e+00 -3.41004086e+00 -5.11839342e+00 -3.86751390e+00 -6.23164749e+00 -5.10679960e+00 -7.93880987e+00 -6.87040138e+00 -5.89978933e+00 -2.10497665e+00 -3.66189981e+00 -4.55900335e+00 -6.52945232e+00 -6.09379482e+00 -6.26454639e+00 -6.88238525e+00 -5.16409588e+00 -7.34641790e+00 -8.29047775e+00 -9.73036480e+00 -8.65509415e+00 -5.48577452e+00 -5.55374384e+00 -3.85313249e+00 -3.97669125e+00 -4.56837988e+00 -4.09141588e+00 -5.12317181e+00 -5.63731766e+00 -7.68262434e+00 -8.65861130e+00 -7.78253222e+00 -6.96626997e+00 -6.80108213e+00 -7.94760132e+00 -7.08099985e+00 -6.13459826e+00 -5.91344595e+00 -6.37716627e+00 -7.91587973e+00 -6.89728260e+00 -8.15948582e+00 -5.36937523e+00 -4.06272697e+00 -2.75394154e+00 -3.23629785e+00 -4.42712784e+00 -2.50389981e+00 -9.21654403e-01 4.68328483e-02 1.09132670e-01 1.14082289e+00 1.97168899e+00 3.71663272e-01 -1.00849032e+00 -2.46370053e+00 -2.67495823e+00 -3.51099753e+00 -3.25691223e+00 -2.24834871e+00 -2.69169760e+00 -2.26974392e+00 -3.87297773e+00 -3.58704376e+00 -3.52187562e+00 -1.38765562e+00 -1.42649782e+00 -9.43301916e-01 3.21921408e-01 1.39126706e+00 1.83155990e+00 -1.43836010e+00 -2.62868118e+00 -3.11193967e+00 7.88192078e-03 1.53304517e+00 1.19032824e+00 -7.22769380e-01 -9.92179155e-01 -7.20026672e-01 -5.23873940e-02 -9.91770566e-01 -1.51580954e+00 -2.34551287e+00 -2.39520860e+00 -2.30409193e+00 -1.41243887e+00 -3.22939038e-01 -6.01733804e-01 8.29492927e-01 1.32599354e+00 2.44686294e+00 -5.43802202e-01 -1.60237491e+00 -1.95968592e+00 4.18934643e-01 8.63605022e-01 9.62572575e-01 -4.04073268e-01 -1.17094982e+00 -2.33012724e+00 -9.47319806e-01 8.75793099e-01 2.12931824e+00 3.06549764e+00 2.05419970e+00 2.43210006e+00 5.98651469e-01 7.30092645e-01 1.51839018e-01 1.94710457e+00 2.01595998e+00 7.68338859e-01 -8.32188487e-01 -1.98433474e-01 1.64996290e+00 3.49009490e+00 1.71652842e+00 6.58221006e-01 -8.21678102e-01 9.37307298e-01 2.24026227e+00 2.30432940e+00 2.44855785e+00 2.92132902e+00 3.31040049e+00 3.05259800e+00 3.27542448e+00 2.16826582e+00 2.85390043e+00 2.48370123e+00 2.88637042e+00 2.60022116e+00 2.45735002e+00 2.34271002e+00 1.78652966e+00 2.02846408e+00 2.17907381e+00 2.78534102e+00 3.34301877e+00 3.32208610e+00 2.89133263e+00 1.29551911e+00 1.23335445e+00 1.75752330e+00 2.39371490e+00 3.69682002e+00 2.99711347e+00 2.86036587e+00 3.43615556e+00 2.39773631e+00 3.21417093e+00 2.52535701e+00 2.59154510e+00 3.52524185e+00 4.94410992e+00 5.66378927e+00 5.55456066e+00 5.51875544e+00 6.05277538e+00 6.05665779e+00 3.84995699e+00 5.94641447e+00 7.38422871e+00 1.10163507e+01 1.04958925e+01 9.23847866e+00 7.31528044e+00 7.53862953e+00 8.24450016e+00 9.39856815e+00 8.15889549e+00 7.02995443e+00 5.75656176e+00 5.47621250e+00 6.22828674e+00 7.43116570e+00 5.10321093e+00 4.57677746e+00 4.39732981e+00 7.48719025e+00 5.67072010e+00 7.13482046e+00 6.21096420e+00 5.50061750e+00 4.26998949e+00 5.87222672e+00 9.85238361e+00 8.31866074e+00 7.65831041e+00 7.36102009e+00 1.07337675e+01 1.17580738e+01 1.04715948e+01 8.75019360e+00 1.15142374e+01 1.36358976e+01 1.33251457e+01 1.02015619e+01 7.16030455e+00 6.99318743e+00 7.87763643e+00 8.95944023e+00 1.06576853e+01 9.42060852e+00 1.00382051e+01 9.70184517e+00 9.82996845e+00 1.16429710e+01 1.11509018e+01 1.04240189e+01 9.56865692e+00 1.12593155e+01 1.31021385e+01 1.27410536e+01 1.20090380e+01 1.16709986e+01 1.27445507e+01 1.16603136e+01 1.13646841e+01 1.14870539e+01 1.27475405e+01 1.34077549e+01 1.11032696e+01 9.93710518e+00 1.09022169e+01 1.27516260e+01 1.12872801e+01 1.02926826e+01 1.10761719e+01 1.31772022e+01 1.32693043e+01 1.33898201e+01 1.43138161e+01 1.55767231e+01 1.38973398e+01 1.11723299e+01 7.35870075e+00 9.27886868e+00 1.02363873e+01 1.19265375e+01 1.05770702e+01 1.29054146e+01 1.39080811e+01 1.56576061e+01 1.42087460e+01 1.54880171e+01 1.53439198e+01 1.45002823e+01 1.32432032e+01 1.04618425e+01 1.05298834e+01 1.10261250e+01 1.26138687e+01 1.30277824e+01 1.28976517e+01 1.19954529e+01 1.04671917e+01 1.13013620e+01 1.21404362e+01 1.42610044e+01 1.35307722e+01 1.35342150e+01 1.32849827e+01 1.47064800e+01 1.70518665e+01 1.70450115e+01 1.61498623e+01 1.36150017e+01 1.42392778e+01 1.49958372e+01 1.58228674e+01 1.75706940e+01 1.60147781e+01 1.47378550e+01 1.17775059e+01 1.19310408e+01 1.29785757e+01 1.37645073e+01 1.53594561e+01 1.45094948e+01 1.48022776e+01 1.56007557e+01 1.72489109e+01 1.54550009e+01 1.46366568e+01 1.44071016e+01 1.63259430e+01 1.72359886e+01 1.58297987e+01 1.54864998e+01 1.43743582e+01 1.58096418e+01 1.62931786e+01 1.59349594e+01 1.62750301e+01 1.60757713e+01 1.61125355e+01 1.69244289e+01 1.63246117e+01 1.54471989e+01 1.49288673e+01 1.55247250e+01 1.65756912e+01 1.60452290e+01 1.65374870e+01 1.71026306e+01 1.59676352e+01 1.56475134e+01 1.56523685e+01 1.65629025e+01 1.63700886e+01 1.52088757e+01 1.59874744e+01 1.62338696e+01 1.70848904e+01 1.84627266e+01 2.09194832e+01 2.09409275e+01 1.98588638e+01 1.78892078e+01 2.02786293e+01 2.20889988e+01 1.97069378e+01 1.62722797e+01 1.44890938e+01 1.71672916e+01 1.78885403e+01 1.77917061e+01 1.75743351e+01 1.80442238e+01 1.63963509e+01 1.65150070e+01 1.70306244e+01 1.70836239e+01 1.67519665e+01 1.67596684e+01 1.82104359e+01 1.87911186e+01 1.88723106e+01 1.80515156e+01 1.80179806e+01 1.78900795e+01 1.87403831e+01 1.87148170e+01 1.95595570e+01 1.95543461e+01 1.86218281e+01 1.78260441e+01 1.74795933e+01 1.83448868e+01 1.79752483e+01 1.81063576e+01 1.88721428e+01 1.95363483e+01 2.11526928e+01 2.13161564e+01 2.20688877e+01 2.20774002e+01 2.17623672e+01 2.05219517e+01 1.87759304e+01 1.79736652e+01 1.94079533e+01 1.96063461e+01 2.04693680e+01 1.93053150e+01 1.97301636e+01 1.97113762e+01 2.05034523e+01 2.15193157e+01 2.12792683e+01 1.99485455e+01 1.93359680e+01 1.92296410e+01 2.07196465e+01 2.02358379e+01 1.99400330e+01 1.98999004e+01 2.09935074e+01 2.22055645e+01 2.22716122e+01 2.11761990e+01 2.16187496e+01 2.14590397e+01 2.11513958e+01 2.05752773e+01 2.13431911e+01 2.25793362e+01 2.33308773e+01 2.33634510e+01 2.20385704e+01 2.16076794e+01 2.12272587e+01 2.27031212e+01 2.22572079e+01 2.19688377e+01 2.17709789e+01 2.20260773e+01 2.25295868e+01 2.26803131e+01 2.28572025e+01 2.15551109e+01 2.19368305e+01 2.26015320e+01 2.37907047e+01 2.26133003e+01 2.16356926e+01 2.14834118e+01 2.10599728e+01 2.04634819e+01 2.08070469e+01 2.14767818e+01 2.15070591e+01 2.07104912e+01 2.04153500e+01 2.12475262e+01 2.13984890e+01 2.14099979e+01 2.12836304e+01 2.11247540e+01 2.09122162e+01 2.11369953e+01 2.16137161e+01 2.23571320e+01 2.23989601e+01 2.21606483e+01 2.13945065e+01 2.07187729e+01 2.07175503e+01 2.15586777e+01 2.25745201e+01 2.30638962e+01 2.24590549e+01 2.23582153e+01 2.18219185e+01 2.23553753e+01 2.30740509e+01 2.38523197e+01 2.40977821e+01 2.31285973e+01 2.29741440e+01 2.32041931e+01 2.40027523e+01 2.35839672e+01 2.32736301e+01 2.30588932e+01 2.36549149e+01 2.33313560e+01 2.27321663e+01 2.21869183e+01 2.22412376e+01 2.24668961e+01 2.27519112e+01 2.25975666e+01 2.29285069e+01 2.31327229e+01 2.34760132e+01 2.37156944e+01 2.40957623e+01 2.39719906e+01 2.38802032e+01 2.39680099e+01 2.36698112e+01 2.34429779e+01 2.29746151e+01 2.35159531e+01 2.36056881e+01 2.32615051e+01 2.28280792e+01 2.27366886e+01 2.33470936e+01 2.33275986e+01 2.34792690e+01 2.32882385e+01 2.33463421e+01 2.32962341e+01 2.34464397e+01 2.38609600e+01 2.38469048e+01 2.37052402e+01 2.33257313e+01 2.37684612e+01 2.38842564e+01 2.41546574e+01 2.33511276e+01 2.32619171e+01 2.33889008e+01 2.37469177e+01 2.39080696e+01 2.37502995e+01 2.36336632e+01 2.34607658e+01 2.37630463e+01 2.40985394e+01 2.42765388e+01 2.42050629e+01 2.38693180e+01 2.40178032e+01 2.37127476e+01 2.37376862e+01 2.35667400e+01 2.34631100e+01 2.37612896e+01 2.37341290e+01 2.39127712e+01 2.36568241e+01 2.37813377e+01 2.37997627e+01 2.36713486e+01 2.36398296e+01 2.37520027e+01 2.41613655e+01 2.44301739e+01 2.44491882e+01 2.42534046e+01 2.38856640e+01 2.37955551e+01 2.41078434e+01 2.44478760e+01 2.52663403e+01 2.64715099e+01 2.82768974e+01 3.24984093e+01 3.25694199e+01 1.35569046e+02 6.51642761e+02 -85511624. 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. 114288424. 4.86762024e+02 1.00006088e+02 3.23734093e+01 2.22219067e+01 1.65808792e+01 1.38985033e+01 1.35976152e+01 1.36015768e+01 1.38793488e+01 1.41267815e+01 1.41719465e+01 1.40957832e+01 1.39456177e+01 1.36980791e+01 1.37740259e+01 1.37066126e+01 1.39440947e+01 1.38863058e+01 1.39497910e+01 1.38263607e+01 1.36812639e+01 1.34481764e+01 1.31658468e+01 1.29537630e+01 1.30958309e+01 1.31872501e+01 1.33481293e+01 1.37644920e+01 1.40376434e+01 1.36621056e+01 1.29969711e+01 1.24913225e+01 1.26843014e+01 1.32380199e+01 1.38990812e+01 1.42532434e+01 1.40330286e+01 1.38488741e+01 1.35878239e+01 1.33487072e+01 1.31042595e+01 1.29158154e+01 1.32576532e+01 1.34769983e+01 1.37582493e+01 1.34548807e+01 1.33937721e+01 1.33043299e+01 1.30424376e+01 1.32408438e+01 1.29220695e+01 1.33467035e+01 1.37133808e+01 1.40546827e+01 1.39556246e+01 1.30699730e+01 1.26622086e+01 1.23278751e+01 1.28744755e+01 1.37362413e+01 1.37904463e+01 1.33183374e+01 1.29693594e+01 1.33154068e+01 1.31937485e+01 1.25707560e+01 1.22000542e+01 1.23300838e+01 1.31824923e+01 1.36022234e+01 1.31230965e+01 1.27618895e+01 1.27462711e+01 1.28476973e+01 1.27299652e+01 1.26531382e+01 1.32080374e+01 1.36107874e+01 1.39388742e+01 1.40600863e+01 1.35764151e+01 1.26111279e+01 1.17099972e+01 1.19195080e+01 1.28844357e+01 1.33905888e+01 1.29162455e+01 1.32956495e+01 1.39542360e+01 1.43795977e+01 1.36087685e+01 1.26733427e+01 1.27890978e+01 1.38668785e+01 1.48854265e+01 1.50307121e+01 1.44216433e+01 1.41871986e+01 1.35541115e+01 1.31462173e+01 1.29160938e+01 1.29647713e+01 1.33088036e+01 1.34101496e+01 1.32697001e+01 1.24161263e+01 1.18858652e+01 1.15055437e+01 1.18385496e+01 1.24967165e+01 1.29627390e+01 1.24610100e+01 1.24362316e+01 1.32721558e+01 1.37728386e+01 1.35285120e+01 1.20994081e+01 1.23312540e+01 1.36570187e+01 1.52824678e+01 1.51824293e+01 1.37966013e+01 1.31280394e+01 1.18601141e+01 1.16037979e+01 1.13688393e+01 1.16799641e+01 1.17532978e+01 1.28799171e+01 1.43455353e+01 1.41603680e+01 1.32290983e+01 1.14563065e+01 1.11386347e+01 1.08054266e+01 1.19329891e+01 1.30216913e+01 1.32317810e+01 1.31412621e+01 1.31567373e+01 1.31049328e+01 1.21071634e+01 1.04149790e+01 9.64424324e+00 1.04379711e+01 1.16778650e+01 1.23942795e+01 1.29368591e+01 1.24655180e+01 1.21890574e+01 1.20785694e+01 1.10859261e+01 1.04092445e+01 1.04221220e+01 1.20692797e+01 1.26906958e+01 1.18608084e+01 1.01186209e+01 1.00117798e+01 1.02553921e+01 1.08219862e+01 9.15692139e+00 8.67970276e+00 9.40226078e+00 9.90427780e+00 9.93619061e+00 8.97490883e+00 7.92088556e+00 6.84079027e+00 7.59756231e+00 1.10423164e+01 1.23857279e+01 1.26365080e+01 1.25241776e+01 1.23757858e+01 1.16017437e+01 8.83933258e+00 8.34681702e+00 9.71010017e+00 1.28630219e+01 1.29043083e+01 1.12627316e+01 8.28607750e+00 8.05804825e+00 8.27245331e+00 1.01563578e+01 9.99582958e+00 9.34718895e+00 8.15347099e+00 8.88914776e+00 9.98018074e+00 1.07207880e+01 8.93629074e+00 8.74777126e+00 1.12527952e+01 1.44300823e+01 1.39347982e+01 1.19425030e+01 1.12497759e+01 1.11656694e+01 1.06944838e+01 9.13445663e+00 8.88754940e+00 1.10575857e+01 1.14925528e+01 1.15759211e+01 9.23686695e+00 9.99964905e+00 1.15341969e+01 1.23501854e+01 1.29001484e+01 1.05670347e+01 9.46350479e+00 8.61775208e+00 1.05127172e+01 1.10996933e+01 1.05868769e+01 9.38041210e+00 7.58949566e+00 8.51932144e+00 8.31378841e+00 9.41502953e+00 9.08704376e+00 1.10044384e+01 1.03369207e+01 1.06678171e+01 9.85731697e+00 1.02065868e+01 9.97250557e+00 9.74502850e+00 1.05231705e+01 9.88576031e+00 1.04814816e+01 1.11719294e+01 9.83289623e+00 8.50244045e+00 6.07148552e+00 6.04957342e+00 8.01980114e+00 1.05074120e+01 1.07446480e+01 8.90075493e+00 6.60094833e+00 8.51672459e+00 9.94898510e+00 1.02744732e+01 9.73648262e+00 9.23113060e+00 1.13712912e+01 1.09748163e+01 9.45297623e+00 6.62288523e+00 6.15769672e+00 6.92254162e+00 6.80956554e+00 7.22951889e+00 7.78429604e+00 9.66188431e+00 1.02908859e+01 9.20310879e+00 8.43687153e+00 6.59842443e+00 7.35842896e+00 7.74436188e+00 1.01471815e+01 1.22075777e+01 1.08638391e+01 8.22602463e+00 4.87845087e+00 5.25722504e+00 4.24716091e+00 4.33961964e+00 5.37304258e+00 7.69300985e+00 8.53210831e+00 8.09545231e+00 7.92159796e+00 8.67992210e+00 9.05754662e+00 7.47587585e+00 7.48280001e+00 9.07151222e+00 9.78401089e+00 8.15175533e+00 7.43844652e+00 9.32695484e+00 8.98769093e+00 6.70554829e+00 5.34260941e+00 6.45958757e+00 8.67465019e+00 8.28571796e+00 6.71568441e+00 5.86669016e+00 6.50557947e+00 5.42592430e+00 4.56829214e+00 4.26303673e+00 7.55106163e+00 8.11765957e+00 8.71837044e+00 7.15317917e+00 8.18585777e+00 8.23454094e+00 7.56606150e+00 6.80279684e+00 7.97054338e+00 9.10236263e+00 9.61626530e+00 8.41667843e+00 1.03165312e+01 8.89652157e+00 8.94104290e+00 7.17323065e+00 9.32925510e+00 1.00315065e+01 8.86662483e+00 4.80156660e+00 4.47083616e+00 6.80219221e+00 9.46248245e+00 6.91739702e+00 5.05896568e+00 4.85246849e+00 5.87176466e+00 6.01677179e+00 4.56165934e+00 6.68698406e+00 7.08229303e+00 7.71403360e+00 5.95139122e+00 6.14205647e+00 7.01899862e+00 6.61843729e+00 7.53057623e+00 8.72402000e+00 7.32489443e+00 4.88933706e+00 2.56072259e+00 4.15956354e+00 6.85100412e+00 5.96207047e+00 5.62030840e+00 2.69673872e+00 2.91471052e+00 2.26850486e+00 1.86033571e+00 2.71807981e+00 3.00087714e+00 3.92221045e+00 4.97814226e+00 4.95627832e+00 6.40368652e+00 6.78130674e+00 5.61126041e+00 5.00484705e+00 3.40824652e+00 5.58495569e+00 5.58559370e+00 6.02444983e+00 9.14614964e+00 9.03389835e+00 6.16115999e+00 2.19300255e-01 -9.71019804e-01 7.52352059e-01 2.38768148e+00 2.89036131e+00 3.11507225e+00 1.86950040e+00 1.00922859e+00 -8.96133840e-01 1.79829538e-01 -1.25178897e+00 -3.12812543e+00 -3.56634498e+00 -9.30295944e-01 3.67934370e+00 5.90524483e+00 1.80119872e+00 -5.47414362e-01 -8.53517652e-01 2.74161363e+00 4.41037512e+00 3.45371962e+00 4.70943642e+00 2.34086943e+00 2.57153010e+00 -1.41484118e+00 -6.72566354e-01 -1.84611106e+00 1.65209234e+00 3.23915410e+00 3.73645878e+00 6.45798862e-01 -2.29232931e+00 -4.98163557e+00 -3.11247921e+00 1.46572900e+00 3.16342044e+00 4.18370533e+00 1.97557604e+00 5.07657146e+00 4.70528555e+00 2.57057333e+00 -1.41458046e+00 -1.90642810e+00 -1.77183077e-01 6.76258147e-01 9.46312308e-01 1.41363060e+00 1.60380113e+00 -6.16076350e-01 -1.29976058e+00 -3.28295827e+00 -2.35918617e+00 -3.32047820e+00 -2.93481898e+00 -9.84652519e-01 -3.94575238e-01 2.70409799e+00 2.18650892e-01 6.30545080e-01 -2.06095171e+00 -4.81749105e+00 -5.44581079e+00 -2.75702000e+00 1.98359263e+00 2.16765833e+00 2.31210375e+00 -8.83243918e-01 -1.81575584e+00 -1.74127054e+00 1.46853554e+00 2.43652964e+00 1.98897982e+00 1.13297653e+00 -1.16435421e+00 -6.24943852e-01 -2.34962016e-01 1.89285982e+00 1.05738819e+00 -2.08063275e-01 -1.47135723e+00 -2.14332891e+00 -4.17513371e+00 -1.91548109e+00 -1.12251699e+00 4.83737975e-01 -1.99158347e+00 -3.84918070e+00 -2.66980410e+00 2.43447721e-01 1.28891325e+00 1.14348722e+00 -1.34635937e+00 -9.60971832e-01 -2.83248711e+00 -2.39369750e+00 -4.20221615e+00 -3.68615270e+00 -3.07114553e+00 -2.97246480e+00 -2.10472155e+00 -3.69162822e+00 -2.40576696e+00 -1.24118388e+00 -7.36730099e-01 -1.22776949e+00 -4.91990995e+00 -3.08344054e+00 -9.45583284e-01 8.16769838e-01 -3.31636786e-01 -4.38833427e+00 -4.96572971e+00 -6.35589886e+00 -2.97784686e+00 -6.23375893e-01 7.79871702e-01 -8.41380179e-01 -3.39150572e+00 -3.50545716e+00 -8.43060672e-01 -4.53425139e-01 -6.23702824e-01 -3.87818837e+00 -3.81050825e+00 -5.84902763e+00 -5.89920998e+00 -3.66050911e+00 -1.42145514e-01 1.07379985e+00 -1.05078542e+00 -2.95121908e+00 -4.62616205e+00 -4.47805548e+00 -1.71563268e+00 2.42295170e+00 5.72422445e-01 -1.98778689e+00 -6.78267241e+00 -5.17145824e+00 -3.82654262e+00 -1.62089014e+00 -1.45921099e+00 -3.99946594e+00 -4.81328106e+00 -5.19680309e+00 -5.13536119e+00 -5.16541481e+00 -4.33841038e+00 -3.62084723e+00 -4.28996992e+00 -4.99954319e+00 -4.00532246e+00 -3.49007535e+00 -3.70331144e+00 -1.41834784e+00 -2.44935703e+00 -2.10046387e+00 -4.21068668e+00 -2.41684890e+00 -1.22685456e+00 -3.28137231e+00 -5.91417885e+00 -7.55076742e+00 -4.82609034e+00 -2.05741072e+00 -1.49471045e+00 -3.75770044e+00 -6.38567209e+00 -8.90506172e+00 -8.74032974e+00 -8.11477280e+00 -4.36189938e+00 -3.79107666e+00 -4.60678816e+00 -6.09935379e+00 -5.93082571e+00 -3.39374542e+00 -3.21940136e+00 -3.44776154e+00 -4.34245300e+00 -6.14015961e+00 -6.69630051e+00 -4.22900677e+00 -1.01121493e-01 1.36275721e+00 -1.23215604e+00 -4.44272757e+00 -5.85069656e+00 -4.73660994e+00 -3.15160322e+00 -3.00678968e+00 -3.60415721e+00 -6.00925159e+00 -6.45155621e+00 -7.01975632e+00 -6.11055756e+00 -4.70951605e+00 -4.76562643e+00 -6.32432890e+00 -9.03824520e+00 -9.96914291e+00 -6.81850481e+00 -4.19138288e+00 -2.14522243e+00 -3.29551125e+00 -6.98548365e+00 -9.28188419e+00 -9.59842873e+00 -5.77369070e+00 -3.23375535e+00 -2.48471785e+00 -4.31865692e+00 -5.72785950e+00 -6.47178745e+00 -5.85718822e+00 -6.92213249e+00 -7.71323252e+00 -8.96876621e+00 -8.46943569e+00 -9.41588593e+00 -8.72245407e+00 -8.44848537e+00 -6.31402445e+00 -7.42915344e+00 -7.91451120e+00 -9.66411209e+00 -8.81668186e+00 -8.40802956e+00 -7.44580173e+00 -7.53372145e+00 -8.41083336e+00 -8.57017136e+00 -8.64439201e+00 -7.74355841e+00 -6.79232073e+00 -7.31740189e+00 -8.10749340e+00 -9.76289654e+00 -9.53190899e+00 -8.58308792e+00 -7.69525480e+00 -8.30521488e+00 -1.05192232e+01 -9.90719509e+00 -8.76738262e+00 -7.35178089e+00 -1.12193937e+01 -1.87651310e+01 -2.71460285e+01 -3.54757347e+01 -4.56322746e+01 -6.57003937e+01 -1.29790039e+02 -4.80516083e+02 -5.75902771e+02 8.87774124e+01 1.53328967e+03 6.98745361e+03 121238904. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 352181728. -363439936. 2.45572632e+03 9.33637146e+02 1.36098953e+02 1.05252190e+02 2.75908546e+01 5.91981554e+00 -5.99184561e+00 -7.19846535e+00 -6.83929729e+00 -7.42556572e+00 -8.41037178e+00 -1.13991613e+01 -1.35289488e+01 -1.38545122e+01 -1.36024933e+01 -1.05856409e+01 -9.85431671e+00 -1.03407488e+01 -1.20540638e+01 -1.26810923e+01 -1.27903328e+01 -1.17059412e+01 -1.08551369e+01 -1.12094259e+01 -1.24005661e+01 -1.28552151e+01 -1.20059147e+01 -1.08142405e+01 -1.15311203e+01 -1.17451239e+01 -1.19957447e+01 -1.14693766e+01 -1.14682751e+01 -1.14829063e+01 -1.18520718e+01 -1.22667418e+01 -1.17184429e+01 -1.14890375e+01 -1.09932404e+01 -1.15185947e+01 -1.23445148e+01 -1.36460400e+01 -1.40057554e+01 -1.40641127e+01 -1.46462126e+01 -1.41367054e+01 -1.23889542e+01 -8.95243168e+00 -8.90793324e+00 -1.02329693e+01 -1.08911295e+01 -1.02707167e+01 -9.11656284e+00 -9.53066826e+00 -1.12599907e+01 -1.21150112e+01 -1.26279249e+01 -1.16236935e+01 -1.13738756e+01 -1.11449575e+01 -1.12153273e+01 -1.25916891e+01 -1.38387575e+01 -1.38304577e+01 -1.27641602e+01 -1.19861622e+01 -1.27035055e+01 -1.38650742e+01 -1.36888351e+01 -1.39053822e+01 -1.34560575e+01 -1.44732084e+01 -1.36628504e+01 -1.34283142e+01 -1.41560907e+01 -1.44495506e+01 -1.41224747e+01 -1.26038494e+01 -1.26908407e+01 -1.31332455e+01 -1.28150406e+01 -1.25637455e+01 -1.29255743e+01 -1.38124771e+01 -1.35701914e+01 -1.27999458e+01 -1.18479061e+01 -1.24108000e+01 -1.21918507e+01 -1.31208324e+01 -1.31780186e+01 -1.40241299e+01 -1.36724720e+01 -1.35157566e+01 -1.43850546e+01 -1.46757803e+01 -1.40634604e+01 -1.34262247e+01 -1.25645685e+01 -1.38579721e+01 -1.31361809e+01 -1.29304056e+01 -1.19571409e+01 -1.21490803e+01 -1.31523848e+01 -1.29504290e+01 -1.39120436e+01 -1.39795122e+01 -1.45348520e+01 -1.42690916e+01 -1.30133829e+01 -1.31770086e+01 -1.32449446e+01 -1.38101807e+01 -1.35671434e+01 -1.31935339e+01 -1.34918671e+01 -1.37124557e+01 -1.31730385e+01 -1.37360392e+01 -1.34123144e+01 -1.31487646e+01 -1.23758163e+01 -1.22986822e+01 -1.38337107e+01 -1.38982239e+01 -1.36816511e+01 -1.26959782e+01 -1.30322704e+01 -1.41609888e+01 -1.40504007e+01 -1.38806629e+01 -1.32379045e+01 -1.32520638e+01 -1.32709637e+01 -1.28725376e+01 -1.31457462e+01 -1.31209211e+01 -1.34182959e+01 -1.31345930e+01 -1.27529020e+01 -1.27959967e+01 -1.29337177e+01 -1.34997301e+01 -1.40001316e+01 -1.39514513e+01 -1.35908213e+01 -1.32233982e+01 -1.33294954e+01 -1.38140125e+01 -1.40184374e+01 -1.38406153e+01 -1.34449701e+01 -1.26865997e+01 -1.28802748e+01 -1.29300432e+01 -1.35640163e+01 -1.36997051e+01 -1.38234339e+01 -1.39670353e+01 -1.38455734e+01 -1.36219387e+01 -1.36088419e+01 -1.39704065e+01 -1.43277302e+01 -1.42572184e+01 -1.36823635e+01 -1.32212152e+01 -1.32608137e+01 -1.36626511e+01 -1.37656698e+01 -1.34527836e+01 -1.31487427e+01 -1.33903341e+01 -1.36755848e+01 -1.36355534e+01 -1.34984856e+01 -1.35457106e+01 -1.36540651e+01 -1.36976957e+01 -1.37333336e+01 -1.38672190e+01 -1.41730394e+01 -1.39688683e+01 -1.40038958e+01 -1.41163540e+01 -1.44232941e+01 -1.44979658e+01 -1.43136520e+01 -1.44096756e+01 -1.42107191e+01 -1.39288902e+01 -1.36844807e+01 -1.35727863e+01 -1.38643751e+01 -1.37681770e+01 -1.36349993e+01 -1.32648344e+01 -1.32579508e+01 -1.35594015e+01 -1.37747278e+01 -1.39223175e+01 -1.38728428e+01 -1.39113951e+01 -1.39478083e+01 -1.39575577e+01 -1.39721031e+01 -1.39190741e+01 -1.39098635e+01 -1.38763342e+01 -1.38427067e+01 -1.38423452e+01 -1.37081947e+01 -1.37443600e+01 -1.38087654e+01 -1.39022169e+01 -1.38678141e+01 -1.38243809e+01 -1.38083382e+01 -1.38169355e+01 -1.37871494e+01 -1.37718439e+01 -1.37700987e+01 -1.37855778e+01 -1.37935867e+01 -1.37858496e+01 -1.37524548e+01 -1.37591457e+01 -1.37946157e+01 -1.38425198e+01 -1.38450937e+01 -1.37983160e+01 -1.37573357e+01 -1.37531834e+01 -1.37779007e+01 -1.37871923e+01 -1.38638105e+01 -1.38533926e+01 -1.38640203e+01 -1.37974234e+01 -1.37853184e+01 -1.37645330e+01 -1.37306108e+01 -1.37210751e+01 -1.37077723e+01 -1.37155848e+01 -1.38258057e+01 -1.38255091e+01 -1.38565922e+01 -1.37719574e+01 -1.38583899e+01 -1.37666874e+01 -1.36631088e+01 -1.36422548e+01 -1.37212801e+01 -1.38362617e+01 -1.36815119e+01 -1.36512794e+01 -1.36024818e+01 -1.36587524e+01 -1.34177694e+01 -1.35079975e+01 -1.34903841e+01 -1.37360630e+01 -1.33889217e+01 -1.34166374e+01 -1.34302826e+01 -1.36801748e+01 -1.36764946e+01 -1.37603502e+01 -1.38002138e+01 -1.37755003e+01 -1.38418674e+01 -1.38457727e+01 -1.38481331e+01 -1.35692577e+01 -1.36063967e+01 -1.35739756e+01 -1.37347193e+01 -1.37417955e+01 -1.36318693e+01 -1.41315250e+01 -1.39204311e+01 -1.40703735e+01 -1.36106987e+01 -1.35860786e+01 -1.35285606e+01 -1.33881540e+01 -1.34496374e+01 -1.36999912e+01 -1.36187229e+01 -1.37555342e+01 -1.37824478e+01 -1.40756407e+01 -1.36030359e+01 -1.33002224e+01 -1.28985672e+01 -1.31165676e+01 -1.28992453e+01 -1.27097702e+01 -1.30184526e+01 -1.30921717e+01 -1.36657677e+01 -1.38755836e+01 -1.39747057e+01 -1.32159014e+01 -1.29564085e+01 -1.29818115e+01 -1.35782423e+01 -1.32318268e+01 -1.27370462e+01 -1.29342899e+01 -1.30266676e+01 -1.29932470e+01 -1.25604725e+01 -1.25520592e+01 -1.30179415e+01 -1.31483164e+01 -1.29479961e+01 -1.26541185e+01 -1.26150970e+01 -1.25570478e+01 -1.23214741e+01 -1.24824133e+01 -1.25659304e+01 -1.31647606e+01 -1.31605101e+01 -1.39934607e+01 -1.45413609e+01 -1.41438084e+01 -1.34350166e+01 -1.28882971e+01 -1.27374868e+01 -1.27526960e+01 -1.29004107e+01 -1.34792776e+01 -1.40008669e+01 -1.36452074e+01 -1.32551537e+01 -1.19772768e+01 -1.19433937e+01 -1.16372690e+01 -1.14816437e+01 -1.21227131e+01 -1.18177767e+01 -1.24807224e+01 -1.18190126e+01 -1.25802336e+01 -1.24467926e+01 -1.23998156e+01 -1.25745916e+01 -1.27960157e+01 -1.30236635e+01 -1.23643856e+01 -1.29938774e+01 -1.21504583e+01 -1.28309479e+01 -1.19972439e+01 -1.24522638e+01 -1.19646854e+01 -1.17620440e+01 -1.04073744e+01 -1.14710331e+01 -1.20802326e+01 -1.34866838e+01 -1.26950932e+01 -1.18504944e+01 -1.21228714e+01 -1.21140099e+01 -1.27931252e+01 -1.23561859e+01 -1.20735226e+01 -1.11092043e+01 -1.21963444e+01 -1.24733095e+01 -1.35645180e+01 -1.23251925e+01 -1.18085060e+01 -1.17543344e+01 -1.24672575e+01 -1.25552855e+01 -1.22191648e+01 -1.16649475e+01 -1.20521889e+01 -1.30856848e+01 -1.31761789e+01 -1.31178579e+01 -1.19267273e+01 -1.19298630e+01 -1.15713034e+01 -1.14112282e+01 -1.12310705e+01 -1.11221180e+01 -1.21117077e+01 -1.19275265e+01 -1.21766605e+01 -1.11498127e+01 -1.16027040e+01 -1.06630449e+01 -1.05897055e+01 -9.86349678e+00 -9.77135372e+00 -9.07965374e+00 -8.64261341e+00 -8.90162849e+00 -8.90404797e+00 -9.44999027e+00 -9.71158504e+00 -1.06633034e+01 -1.05244732e+01 -1.01052275e+01 -9.24639606e+00 -8.80687141e+00 -9.20206928e+00 -1.05794516e+01 -1.12682629e+01 -1.06331196e+01 -8.67763805e+00 -8.27361584e+00 -9.38801765e+00 -1.08034391e+01 -1.13125277e+01 -1.04896641e+01 -1.05484686e+01 -1.11988649e+01 -1.11796741e+01 -1.05608253e+01 -9.37063122e+00 -9.31429768e+00 -9.62713909e+00 -1.05253992e+01 -1.14295931e+01 -1.17462292e+01 -1.11936293e+01 -1.14728193e+01 -1.09672956e+01 -1.17802591e+01 -1.09650230e+01 -1.10897684e+01 -1.01124277e+01 -9.65601063e+00 -8.92614937e+00 -7.95508623e+00 -8.42403603e+00 -9.79299259e+00 -1.20054874e+01 -1.39781284e+01 -9.85376263e+00 -3.00093913e+00 7.19992161e+00 1.53997087e+01 2.35437984e+01 2.14008160e+01 3.02374725e+01 7.39825287e+01 3.81820984e+02 4.79243103e+02 -1.70295197e+02 -1.12002281e+02 -1.06465381e+03 -4.37048828e+03 -294410496. 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. 0. 0. 0. 0. 0. 0. 0. 90807680. -1.64786951e+03 -6.26042786e+02 1.62381878e+01 -6.20826340e+01 -8.42279053e+01 -8.09795380e+01 -2.71629238e+01 -1.26387358e+01 -9.20846176e+00 -8.52753258e+00 -9.92335320e+00 -1.05234947e+01 -1.07848978e+01 -1.09056797e+01 -1.10621910e+01 -1.00718565e+01 -8.42482948e+00 -8.09397984e+00 -8.36858940e+00 -9.93946648e+00 -9.93320656e+00 -9.06717396e+00 -8.32021809e+00 -8.14341354e+00 -8.57430935e+00 -7.92311430e+00 -8.15534592e+00 -7.24961519e+00 -6.53255701e+00 -5.45878839e+00 -5.36308146e+00 -5.75697184e+00 -6.63845921e+00 -7.03497076e+00 -6.41490889e+00 -6.12744379e+00 -4.43765783e+00 -4.11559010e+00 -4.05654669e+00 -5.49798441e+00 -6.59245586e+00 -5.47073174e+00 -4.86583662e+00 -4.45282221e+00 -4.29122782e+00 -4.42060995e+00 -5.36917162e+00 -4.88512754e+00 -4.82369709e+00 -3.51075339e+00 -4.26017380e+00 -3.83052683e+00 -3.85450697e+00 -3.50562286e+00 -3.75532174e+00 -4.03712416e+00 -4.42282438e+00 -4.70311308e+00 -4.32299137e+00 -4.90429497e+00 -5.79876423e+00 -7.37804747e+00 -7.93161106e+00 -7.97832775e+00 -6.95914888e+00 -5.66251183e+00 -6.15307426e+00 -7.10782099e+00 -6.26519680e+00 -4.45717525e+00 -2.93045115e+00 -2.81268620e+00 -3.45697761e+00 -3.30759048e+00 -2.96139860e+00 -2.35291529e+00 -2.25433898e+00 -2.81999087e+00 -3.14643478e+00 -3.29717135e+00 -4.01693916e+00 -4.26814699e+00 -6.08498192e+00 -6.46902418e+00 -7.22571898e+00 -6.65448809e+00 -6.16861963e+00 -5.00259638e+00 -4.89756775e+00 -4.36137152e+00 -5.48858738e+00 -5.40780401e+00 -6.48566723e+00 -6.38044930e+00 -5.74863529e+00 -5.28250551e+00 -4.48374224e+00 -3.84757853e+00 -3.45340967e+00 -3.55527520e+00 -3.13048005e+00 -2.54969192e+00 -2.19725037e+00 -2.71537137e+00 -2.93368101e+00 -3.09602833e+00 -3.67197514e+00 -4.44300508e+00 -4.71761322e+00 -5.71540737e+00 -5.59684753e+00 -4.22438765e+00 -1.46794248e+00 -7.10271478e-01 -1.03111482e+00 -2.62661076e+00 -3.54529476e+00 -4.65400600e+00 -3.29342580e+00 -1.67304492e+00 -7.76087523e-01 -7.45956123e-01 -2.55327201e+00 -3.24485469e+00 -3.41203308e+00 -2.17087173e+00 -1.04800653e+00 -2.25493979e+00 -4.04999828e+00 -5.35307503e+00 -3.73773932e+00 -1.91085839e+00 -1.05966067e+00 -1.92005312e+00 -3.84494615e+00 -4.83722067e+00 -5.43289423e+00 -3.12766600e+00 -1.91653776e+00 -1.93512750e+00 -1.67447996e+00 -1.95197618e+00 -6.93415165e-01 -9.83681142e-01 -6.54121816e-01 -8.38703334e-01 -1.44996750e+00 -1.66295755e+00 -1.23595107e+00 -9.94305193e-01 -8.26872110e-01 -1.08285713e+00 -2.53670835e+00 -3.88354325e+00 -4.76967049e+00 -3.52325010e+00 -2.80161572e+00 -3.02207899e+00 -3.36133313e+00 -3.40073776e+00 -3.58588171e+00 -4.66269732e+00 -5.09503603e+00 -4.31896305e+00 -2.37775159e+00 -1.21986377e+00 -4.78549331e-01 -4.36706960e-01 2.94698328e-01 -3.04038823e-01 -3.53407234e-01 -7.68328071e-01 -2.08566755e-01 -1.04031873e+00 -6.35792971e-01 9.10364568e-01 3.36791992e+00 2.97017360e+00 1.10447359e+00 -3.00589710e-01 -4.09964800e-01 -4.86931026e-01 3.13345850e-01 1.64227211e+00 1.72921264e+00 -6.89513147e-01 -1.17849362e+00 -8.14493716e-01 1.03488612e+00 5.76377153e-01 4.40017968e-01 -3.55730832e-01 3.29192519e-01 -9.00364891e-02 8.46277058e-01 -2.10794717e-01 8.00347269e-01 -5.17783351e-02 -3.74391794e-01 -9.22796905e-01 6.16375685e-01 2.45291805e+00 1.71795166e+00 8.30481648e-01 4.04125005e-01 1.88985312e+00 2.13653231e+00 1.73907304e+00 1.79726362e+00 2.44760370e+00 2.60988474e+00 2.99498820e+00 2.49999142e+00 2.55665255e+00 2.25790858e+00 1.56110370e+00 1.98707795e+00 1.70651770e+00 2.09505820e+00 1.94117916e+00 2.19529557e+00 2.64779425e+00 3.21493649e+00 2.87395835e+00 3.07598305e+00 2.50620031e+00 2.61768103e+00 3.01460409e+00 2.86102009e+00 2.70829439e+00 2.26391888e+00 2.56523561e+00 3.16118002e+00 3.91769075e+00 4.68590879e+00 4.65604401e+00 4.02596855e+00 4.65504456e+00 5.41920757e+00 5.32450342e+00 3.18723297e+00 2.06352592e+00 2.48192334e+00 4.36322069e+00 4.83194637e+00 4.78005838e+00 3.94814873e+00 1.97551942e+00 -2.53590584e-01 -3.25142294e-01 1.32685626e+00 3.36482120e+00 1.22973764e+00 -6.65648133e-02 9.05317426e-01 3.54891205e+00 5.19854927e+00 4.85548162e+00 4.66023111e+00 4.12276125e+00 3.49506307e+00 3.39410138e+00 4.52319860e+00 4.66738653e+00 5.41705561e+00 4.06008196e+00 4.33228779e+00 4.46898985e+00 4.40045404e+00 3.43774557e+00 4.36206627e+00 5.14656448e+00 5.03860617e+00 2.38211966e+00 2.17616677e+00 2.90392971e+00 4.04737186e+00 3.05202031e+00 2.48682022e+00 1.68261492e+00 2.41678548e+00 3.09234691e+00 3.43312049e+00 5.41044188e+00 5.45219278e+00 6.00953197e+00 5.63626146e+00 6.00267887e+00 6.27660656e+00 4.64693451e+00 3.92741370e+00 3.65205503e+00 5.85826731e+00 6.06390142e+00 7.72356653e+00 4.27053738e+00 2.27455401e+00 1.73005795e+00 3.52859282e+00 6.01998568e+00 5.55544281e+00 6.24237585e+00 5.83882475e+00 5.24244499e+00 4.44411087e+00 4.62824392e+00 4.41660833e+00 3.88702846e+00 4.42946577e+00 4.68338680e+00 5.94945765e+00 5.83626938e+00 6.13252640e+00 5.34095287e+00 4.80016947e+00 4.16940355e+00 5.05565262e+00 6.61201668e+00 7.47954178e+00 7.92893553e+00 7.91759872e+00 8.46017265e+00 7.84674454e+00 7.04362106e+00 6.34730864e+00 5.19072008e+00 5.60357237e+00 5.14460611e+00 6.26986980e+00 4.24271345e+00 3.76979756e+00 3.04431009e+00 4.77127552e+00 6.20517397e+00 7.11107874e+00 6.50069427e+00 6.19530582e+00 5.45202589e+00 6.65915060e+00 6.41225863e+00 6.54877043e+00 7.56154108e+00 8.04728889e+00 8.99591255e+00 7.13670969e+00 6.34143829e+00 6.68362856e+00 6.01278782e+00 5.14790726e+00 4.41823387e+00 5.59579706e+00 7.41347694e+00 5.94183731e+00 6.30306339e+00 5.14679146e+00 6.75898552e+00 6.65126324e+00 8.87530994e+00 1.04179525e+01 1.10641756e+01 1.08822355e+01 1.06520920e+01 1.05585260e+01 9.98392010e+00 9.88141823e+00 1.02611113e+01 1.00459328e+01 9.72754860e+00 9.13675499e+00 8.25373840e+00 7.42986679e+00 6.36816454e+00 7.59521484e+00 8.81273651e+00 9.47659302e+00 7.16133070e+00 6.20820045e+00 6.89775372e+00 8.54817486e+00 9.47965622e+00 8.08032417e+00 8.67177010e+00 8.13744068e+00 8.63645077e+00 7.86625862e+00 7.66497183e+00 7.84125566e+00 8.93226242e+00 9.86398506e+00 1.05060892e+01 9.76351166e+00 9.64005089e+00 9.81982803e+00 9.43699932e+00 9.32132244e+00 8.30356026e+00 8.93286991e+00 9.05294704e+00 1.07856941e+01 1.05346851e+01 8.94702816e+00 7.92586279e+00 9.11495590e+00 1.04601717e+01 9.61293983e+00 9.25005245e+00 9.75630665e+00 1.00890284e+01 1.10955420e+01 1.11116753e+01 1.17935305e+01 1.04621382e+01 1.00542212e+01 9.95318413e+00 1.03780336e+01 1.03142185e+01 9.74395275e+00 1.00341721e+01 1.09621725e+01 1.23931494e+01 1.21627655e+01 1.24195023e+01 1.17849588e+01 1.23342180e+01 1.09868298e+01 1.03291359e+01 9.36423588e+00 9.84434605e+00 1.09334946e+01 1.10872946e+01 1.15731812e+01 1.05843697e+01 1.13007011e+01 1.10834618e+01 1.12143221e+01 1.01477194e+01 9.45100880e+00 9.05219173e+00 9.59383678e+00 1.01246223e+01 9.77965355e+00 8.68737888e+00 9.07556915e+00 1.06614628e+01 1.16537914e+01 1.20016146e+01 1.10426493e+01 1.24001637e+01 1.23560734e+01 1.23166866e+01 1.16224842e+01 1.08824129e+01 1.14061804e+01 1.15175228e+01 1.27479067e+01 1.30482082e+01 1.29010172e+01 1.26010914e+01 1.23876085e+01 1.26186171e+01 1.24036140e+01 1.19887400e+01 1.15703821e+01 1.19262800e+01 1.25962973e+01 1.31010952e+01 1.25484467e+01 1.30222130e+01 1.29283991e+01 1.26783590e+01 1.07308130e+01 9.23646355e+00 8.91566563e+00 9.93285275e+00 1.04538326e+01 1.03587065e+01 1.05757437e+01 1.13212233e+01 1.26003504e+01 1.14201384e+01 1.08960314e+01 1.04401236e+01 1.12741852e+01 1.12793083e+01 1.12536364e+01 1.23707180e+01 1.28158064e+01 1.24876757e+01 1.14678535e+01 1.18743401e+01 1.17224865e+01 1.11066895e+01 1.10261383e+01 1.28018894e+01 1.41434040e+01 1.45053816e+01 1.33800678e+01 1.34264717e+01 1.35208998e+01 1.34958963e+01 1.31660604e+01 1.25881395e+01 1.28954506e+01 1.31476927e+01 1.34260836e+01 1.35471487e+01 1.28449030e+01 1.22143345e+01 1.16419964e+01 1.17668858e+01 1.25286779e+01 1.31677217e+01 1.35400810e+01 1.32155333e+01 1.33965130e+01 1.33407145e+01 1.31185770e+01 1.33972969e+01 1.40613747e+01 1.41747627e+01 1.32175407e+01 1.30619726e+01 1.30460682e+01 1.28678865e+01 1.18780794e+01 1.16612844e+01 1.21866169e+01 1.27841759e+01 1.32723122e+01 1.30747671e+01 1.31761675e+01 1.29361925e+01 1.25246792e+01 1.23815193e+01 1.23719501e+01 1.28901691e+01 1.29154978e+01 1.28735809e+01 1.28192730e+01 1.24091854e+01 1.21929684e+01 1.19027557e+01 1.23122749e+01 1.26643591e+01 1.26636171e+01 1.21811228e+01 1.25246582e+01 1.30505285e+01 1.37222538e+01 1.33948936e+01 1.30139599e+01 1.30636683e+01 1.30043030e+01 1.32720146e+01 1.35223875e+01 1.37318678e+01 1.35798082e+01 1.29427891e+01 1.25611715e+01 1.29050674e+01 1.29871416e+01 1.29666281e+01 1.30878124e+01 1.32236500e+01 1.34893188e+01 1.31002884e+01 1.29978447e+01 1.32969074e+01 1.37540140e+01 1.40286779e+01 1.36514912e+01 1.33396807e+01 1.33116541e+01 1.34183769e+01 1.34454556e+01 1.33566074e+01 1.34371767e+01 1.34281273e+01 1.32739964e+01 1.30096731e+01 1.30888023e+01 1.33018198e+01 1.35688562e+01 1.33751783e+01 1.34083071e+01 1.33457060e+01 1.35474997e+01 1.35844822e+01 1.35554571e+01 1.35076351e+01 1.37683735e+01 1.39388781e+01 1.43270006e+01 1.41836395e+01 1.40194759e+01 1.35988302e+01 1.36735373e+01 1.38099833e+01 1.39324217e+01 1.40446129e+01 1.40199213e+01 1.40194101e+01 1.40600805e+01 1.43715219e+01 1.71113091e+01 2.18824177e+01 5.26168976e+01 6.37492752e+01 -8.75705643e+01 -7.79700989e+02 -85511624. 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. 114288424. -1.94564255e+02 2.90143757e+01 3.14307632e+01 1.38840837e+01 1.16928120e+01 9.32452106e+00 8.66703510e+00 8.64570999e+00 8.55021095e+00 8.55402184e+00 8.50119972e+00 8.50951195e+00 8.48474216e+00 8.59119511e+00 8.63527966e+00 8.54467297e+00 8.37582493e+00 8.18939495e+00 8.15307140e+00 8.21282673e+00 8.41775322e+00 8.55101109e+00 8.67532158e+00 8.58107281e+00 8.49001694e+00 8.49080849e+00 8.53159046e+00 8.35500336e+00 8.26823616e+00 8.36442757e+00 8.61536407e+00 8.70217037e+00 8.75483608e+00 8.75783730e+00 8.64383888e+00 8.36419392e+00 8.23976612e+00 8.12859821e+00 8.38023758e+00 8.27900219e+00 8.51944542e+00 8.57903194e+00 8.71536922e+00 8.44156933e+00 8.27798557e+00 8.33321953e+00 8.43687916e+00 8.53294563e+00 8.49269962e+00 8.53125858e+00 8.30802917e+00 8.23822784e+00 7.91706991e+00 7.93668699e+00 7.75055027e+00 8.10885334e+00 8.51835442e+00 8.90633106e+00 8.86671066e+00 8.50782299e+00 8.32649803e+00 8.25514984e+00 8.31690598e+00 8.30447578e+00 8.12629414e+00 8.12786484e+00 8.15670490e+00 8.46614838e+00 8.16262341e+00 7.98837185e+00 7.90547037e+00 7.84568834e+00 7.86593151e+00 7.87199259e+00 7.94898081e+00 7.82229662e+00 7.87337160e+00 7.79749870e+00 7.84224033e+00 7.50598001e+00 7.66101885e+00 7.97102833e+00 8.02910709e+00 7.99972582e+00 7.53849125e+00 7.49848795e+00 7.61258411e+00 7.89012766e+00 7.78803062e+00 7.71434450e+00 8.02642155e+00 8.52496529e+00 8.41318130e+00 7.81813240e+00 7.50853586e+00 7.93950605e+00 8.12720680e+00 7.83093739e+00 7.47400856e+00 7.47793484e+00 7.80660677e+00 7.79568481e+00 7.44050217e+00 6.90281868e+00 6.97058201e+00 7.35398674e+00 8.10475254e+00 8.51106644e+00 8.74870968e+00 8.10018635e+00 7.42741966e+00 7.32870102e+00 7.78917599e+00 8.02427387e+00 8.16865158e+00 7.97919083e+00 8.49991512e+00 8.44439411e+00 7.62104464e+00 7.00709486e+00 6.63721514e+00 7.42593479e+00 7.66714478e+00 8.05998516e+00 8.37788773e+00 7.82571745e+00 7.42076445e+00 6.72371912e+00 6.59305811e+00 6.56424856e+00 6.81514549e+00 6.87620735e+00 6.76102161e+00 7.15987492e+00 7.49528790e+00 7.98230410e+00 7.69547367e+00 7.11782885e+00 6.21326160e+00 5.91050577e+00 6.33216238e+00 7.27305079e+00 7.69954300e+00 7.80103111e+00 7.41288090e+00 7.79717779e+00 7.78453302e+00 7.82636833e+00 6.94661903e+00 6.56312847e+00 5.98483181e+00 6.52772617e+00 7.07895231e+00 7.54528236e+00 7.05906963e+00 6.85764313e+00 7.33408308e+00 8.33455276e+00 8.07123375e+00 6.91975403e+00 6.54005575e+00 7.21912050e+00 8.02266502e+00 7.23033524e+00 7.05214834e+00 7.02832317e+00 7.92486048e+00 8.22736454e+00 7.57099819e+00 6.63010883e+00 5.63575935e+00 6.05152655e+00 5.77246714e+00 5.61143208e+00 6.33782864e+00 6.30905867e+00 7.10423040e+00 6.54696703e+00 6.62829828e+00 6.04236507e+00 5.39320469e+00 5.87853146e+00 6.18356943e+00 6.10471821e+00 6.39068079e+00 5.85963917e+00 6.98504114e+00 6.20342016e+00 6.27519178e+00 6.16678047e+00 7.18375111e+00 7.32627249e+00 6.01445007e+00 5.84851885e+00 4.92275190e+00 5.46357965e+00 4.81251287e+00 5.79937363e+00 5.60228252e+00 5.80991030e+00 5.89978361e+00 5.97735548e+00 6.58948088e+00 5.99472141e+00 6.79100513e+00 6.04427576e+00 6.43966436e+00 5.48007059e+00 6.17460108e+00 5.67124510e+00 5.93251371e+00 5.63005400e+00 6.84855652e+00 6.27047110e+00 5.30648422e+00 4.88238430e+00 4.91505527e+00 6.93939352e+00 7.09591866e+00 7.69526005e+00 6.10706615e+00 4.81197739e+00 4.75929546e+00 5.52441454e+00 6.28301859e+00 6.16486216e+00 4.77422237e+00 4.75645876e+00 4.41645432e+00 5.94024801e+00 5.68938875e+00 5.89579678e+00 5.51975584e+00 5.89471149e+00 5.78623629e+00 6.71246004e+00 6.79477072e+00 6.70796108e+00 5.61442614e+00 6.03124475e+00 5.75469303e+00 5.10078955e+00 5.70940065e+00 6.09107924e+00 6.50152493e+00 4.63362551e+00 4.82461977e+00 4.82561922e+00 5.32946396e+00 4.55403852e+00 4.57430840e+00 5.02231598e+00 5.49364948e+00 6.30055523e+00 6.42565918e+00 6.12191963e+00 6.08399630e+00 6.35306025e+00 6.05779219e+00 5.94243574e+00 5.11304092e+00 6.44369841e+00 5.51155949e+00 5.02113724e+00 4.35830212e+00 4.08113956e+00 5.56256580e+00 6.49412251e+00 6.77924490e+00 5.85951471e+00 6.46664619e+00 6.72670031e+00 7.70437956e+00 6.04982662e+00 5.59972906e+00 4.89316940e+00 5.19074869e+00 5.21659899e+00 5.67643833e+00 5.08158064e+00 4.32911062e+00 2.81302953e+00 3.61072731e+00 4.32408619e+00 4.29407310e+00 3.56939244e+00 3.97309971e+00 4.77450514e+00 5.95441818e+00 5.64513683e+00 5.41583776e+00 4.63451099e+00 5.25864697e+00 4.89764118e+00 4.29694033e+00 4.62161970e+00 4.60627079e+00 5.49832964e+00 4.68775892e+00 6.11277533e+00 6.75699520e+00 6.69207573e+00 5.39677382e+00 3.76089787e+00 4.17308807e+00 4.86666584e+00 4.74712944e+00 3.94077992e+00 3.50346303e+00 3.07212853e+00 3.53598452e+00 3.45693135e+00 4.35901356e+00 4.33388090e+00 3.76021290e+00 2.89181256e+00 3.16075540e+00 4.80069208e+00 5.44509935e+00 5.20387793e+00 4.07067251e+00 3.98004770e+00 4.85476017e+00 4.66430140e+00 4.28396606e+00 2.61489463e+00 1.15882468e+00 8.42953384e-01 1.06088388e+00 2.74183798e+00 2.92542315e+00 2.88610506e+00 2.51196098e+00 3.22504449e+00 3.18845606e+00 1.81784344e+00 1.81301105e+00 2.39711642e+00 3.12821960e+00 2.17831659e+00 2.32274771e+00 4.06235504e+00 5.63780212e+00 4.19007730e+00 2.96399927e+00 8.04792941e-01 2.05898046e+00 1.87577033e+00 2.29656744e+00 1.57304692e+00 2.76719570e+00 2.75358748e+00 1.75951850e+00 6.53166413e-01 1.81969976e+00 3.13976479e+00 3.77275920e+00 2.49489522e+00 1.54054976e+00 6.40295804e-01 -4.40944314e-01 2.43216947e-01 1.58957863e+00 3.13579321e+00 2.89856958e+00 3.26568246e+00 3.08976460e+00 3.61948633e+00 2.14505100e+00 2.24775243e+00 1.81743729e+00 2.05348682e+00 2.48208308e+00 2.33985472e+00 3.06746531e+00 3.45145321e+00 3.85985875e+00 2.53683376e+00 1.65849316e+00 2.54748988e+00 3.68010378e+00 3.50158095e+00 1.59563315e+00 1.69197536e+00 1.03822792e+00 2.12235427e+00 1.06484818e+00 1.75463331e+00 1.64646447e+00 3.54142261e+00 3.31902552e+00 1.73788929e+00 -1.19516945e+00 9.45640266e-01 3.86350250e+00 5.41468000e+00 4.26970530e+00 1.90376616e+00 9.88187194e-01 9.94577333e-02 8.64460230e-01 1.82502002e-01 3.94311309e-01 -1.15662837e+00 2.24594998e+00 2.80664515e+00 4.58110237e+00 2.12368989e+00 1.18731558e+00 5.85219800e-01 4.09722924e-01 1.11350298e+00 1.58991039e+00 2.09823537e+00 2.37496519e+00 1.17127848e+00 1.29320931e+00 7.07724631e-01 1.25766408e+00 1.53678441e+00 4.07462791e-02 -9.31443051e-02 -4.67104316e-01 5.49525678e-01 1.39008629e+00 2.27604270e+00 2.66020012e+00 5.97040772e-01 -8.22401404e-01 -1.16539526e+00 7.03907311e-01 8.19966018e-01 7.07033575e-01 -9.14463937e-01 -5.26051760e-01 -4.54131991e-01 8.57944787e-01 1.22047365e+00 4.97803092e-01 1.02259648e+00 -5.31455517e-01 -7.97686875e-01 -1.92895448e+00 -1.45129967e+00 2.49740764e-01 4.14782286e-01 1.00626028e+00 -9.00888629e-03 -6.55912519e-01 -5.87828994e-01 1.21542374e-02 7.34893203e-01 6.19061649e-01 -3.67123544e-01 1.80494159e-01 -5.75045168e-01 -6.58879876e-01 -1.33270109e+00 -9.29076195e-01 5.11501372e-01 5.67599237e-01 -5.31432271e-01 8.91896561e-02 -1.24924883e-01 1.44810891e+00 -2.56828278e-01 -1.15311742e-01 -7.68049061e-01 -7.70861566e-01 3.02402265e-02 -1.14321506e+00 -1.70263743e+00 -3.73324656e+00 -3.11831927e+00 -1.91951668e+00 -1.12928057e+00 -3.53434294e-01 -1.62178433e+00 -2.14358759e+00 -2.56931043e+00 -1.20547342e+00 -9.08904135e-01 -1.08610857e+00 -2.93429565e+00 -2.46239781e+00 -3.47585201e+00 -1.79130542e+00 -1.62003970e+00 5.41262567e-01 -5.18355489e-01 -1.08088267e+00 -1.51863635e+00 -9.94949758e-01 -1.30609882e+00 -1.15856659e+00 -7.24911511e-01 -2.13736087e-01 -1.57420814e+00 -2.51481867e+00 -1.56528091e+00 -1.43172491e+00 -9.69228864e-01 -2.34969997e+00 -2.55372882e+00 -3.73908114e+00 -3.45130610e+00 -3.22685814e+00 -1.74498415e+00 -1.46317160e+00 -1.27364516e+00 -1.22750247e+00 -2.43721390e+00 -2.15759110e+00 -2.81902218e+00 -1.33507657e+00 -1.53621340e+00 -2.05282235e+00 -2.69074583e+00 -2.90908742e+00 -2.44074178e+00 -2.13714385e+00 -1.78472006e+00 -2.40251827e+00 -1.98466575e+00 -1.55642951e+00 -6.61512494e-01 -1.80124187e+00 -2.34490108e+00 -3.49420500e+00 -3.15527487e+00 -4.18416023e+00 -2.69162893e+00 -2.46541095e+00 -1.43448508e+00 -1.85100651e+00 -1.99675393e+00 -2.68399954e+00 -1.59695303e+00 -2.01757050e+00 -2.07373619e+00 -3.64477730e+00 -4.66988564e+00 -4.82680750e+00 -3.83958530e+00 -2.11369872e+00 -1.00059891e+00 -2.58621383e+00 -4.66527081e+00 -6.00835419e+00 -5.25776768e+00 -3.61942196e+00 -1.75709915e+00 -2.65933418e+00 -3.90313363e+00 -4.37637520e+00 -4.33442163e+00 -3.15882969e+00 -3.67118382e+00 -3.23511386e+00 -3.24704623e+00 -3.38254046e+00 -3.74461675e+00 -4.28900003e+00 -4.06099701e+00 -2.01462364e+00 -6.57573521e-01 -1.38497281e+00 -2.87095547e+00 -4.03776741e+00 -3.16020226e+00 -2.78142977e+00 -2.57036161e+00 -5.00163651e+00 -5.51775026e+00 -4.46185923e+00 -2.64874935e+00 -3.28425384e+00 -4.78099155e+00 -4.93698978e+00 -4.14537096e+00 -3.40958285e+00 -2.76154494e+00 -2.72153807e+00 -3.82763028e+00 -3.79408979e+00 -3.94469285e+00 -3.18615341e+00 -3.41677475e+00 -3.76866984e+00 -3.38848019e+00 -3.34729242e+00 -3.99396706e+00 -4.52672243e+00 -4.82523298e+00 -3.09077001e+00 -3.51834917e+00 -4.12133503e+00 -5.14879465e+00 -4.21656847e+00 -3.31771350e+00 -3.15529799e+00 -2.94530630e+00 -3.27545404e+00 -3.80629706e+00 -4.98914623e+00 -5.46873665e+00 -4.01846409e+00 -4.22207975e+00 -5.32584429e+00 -6.57229042e+00 -6.44527435e+00 -6.11572599e+00 -6.98272228e+00 -6.39311552e+00 -5.53667307e+00 -5.98941612e+00 -8.05998611e+00 -1.19120083e+01 -1.07302341e+01 -2.18218060e+01 -7.15802078e+01 -5.89616882e+02 -1.38674927e+03 95212064. 119133344. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 352181728. -363439936. 891320448. -2.32750342e+03 1.21355385e+02 2.50605484e+02 6.20717316e+01 2.50689297e+01 6.29370642e+00 2.04523563e-01 -3.21984220e+00 -3.00429344e+00 -3.44271851e+00 -4.98286533e+00 -5.92036867e+00 -6.94493198e+00 -5.78839207e+00 -6.51868629e+00 -6.05456591e+00 -5.62122488e+00 -5.64117050e+00 -4.95504475e+00 -5.37886906e+00 -5.40559578e+00 -7.16454363e+00 -7.97252226e+00 -6.26862717e+00 -5.55333805e+00 -6.21398592e+00 -7.61252880e+00 -7.00715828e+00 -5.11215067e+00 -5.08562851e+00 -5.78786850e+00 -6.83079624e+00 -6.89826727e+00 -6.83968353e+00 -6.56094885e+00 -6.32591105e+00 -6.12560797e+00 -6.46002960e+00 -6.44837046e+00 -6.50907373e+00 -6.33070183e+00 -6.24288321e+00 -5.85241175e+00 -5.32911777e+00 -5.88443947e+00 -6.26262140e+00 -6.85777760e+00 -6.59564924e+00 -5.82439899e+00 -6.10610247e+00 -6.77185726e+00 -7.67187405e+00 -7.36378527e+00 -6.76107883e+00 -7.05852175e+00 -7.08863354e+00 -7.79769850e+00 -7.75312233e+00 -7.89684391e+00 -7.53864765e+00 -6.83026123e+00 -6.19584942e+00 -6.07441998e+00 -6.48610449e+00 -6.79555988e+00 -6.96029329e+00 -7.03936958e+00 -6.80866623e+00 -6.06619835e+00 -5.87017822e+00 -6.29073811e+00 -6.99297762e+00 -7.29584599e+00 -7.03189707e+00 -7.68775415e+00 -7.99900961e+00 -8.46271896e+00 -8.12669945e+00 -7.49799442e+00 -7.71427822e+00 -7.21627569e+00 -7.78173971e+00 -7.71042299e+00 -8.21947098e+00 -8.01674366e+00 -7.48369789e+00 -7.27275181e+00 -7.26471376e+00 -7.49829340e+00 -7.38722277e+00 -7.47007990e+00 -7.67084026e+00 -8.12091923e+00 -7.75161600e+00 -7.57405233e+00 -7.52252960e+00 -7.80971527e+00 -8.10668850e+00 -7.32849360e+00 -6.94162893e+00 -6.97326946e+00 -7.40430927e+00 -7.61017990e+00 -7.10630131e+00 -7.09286070e+00 -7.19463491e+00 -7.30484772e+00 -7.34610415e+00 -7.39775610e+00 -7.49339628e+00 -7.11252689e+00 -7.09032583e+00 -7.17651939e+00 -7.38408279e+00 -7.26412153e+00 -7.28351593e+00 -7.61304092e+00 -7.85965014e+00 -7.62917995e+00 -7.85785341e+00 -7.84989119e+00 -8.38803959e+00 -8.15134144e+00 -7.66655302e+00 -7.45713949e+00 -7.65473270e+00 -8.15577698e+00 -8.30457592e+00 -7.87957859e+00 -7.66525555e+00 -7.49989319e+00 -7.62476492e+00 -7.80871487e+00 -7.75912619e+00 -7.81269693e+00 -7.68723059e+00 -7.67516708e+00 -7.96392584e+00 -8.11334229e+00 -8.23955536e+00 -7.92316866e+00 -7.84791088e+00 -7.91193199e+00 -8.06567764e+00 -8.05898476e+00 -8.14529133e+00 -7.90779066e+00 -7.97505713e+00 -7.78708410e+00 -7.98341799e+00 -7.92978525e+00 -8.20516396e+00 -8.42605114e+00 -8.45959091e+00 -8.61313057e+00 -8.34042549e+00 -8.35020542e+00 -8.01411629e+00 -8.09999561e+00 -8.25636482e+00 -8.36705112e+00 -8.11738396e+00 -7.91650438e+00 -8.07169437e+00 -8.23524570e+00 -8.57555199e+00 -8.59235287e+00 -9.05908585e+00 -8.56549358e+00 -8.57434559e+00 -8.45897198e+00 -8.62880421e+00 -8.75092793e+00 -8.51648331e+00 -8.54532337e+00 -8.31074429e+00 -8.22954559e+00 -8.28000546e+00 -8.37485027e+00 -8.58634186e+00 -8.50788021e+00 -8.40358543e+00 -8.40924931e+00 -8.59308529e+00 -8.58208847e+00 -8.49309349e+00 -8.15930271e+00 -8.07465363e+00 -8.15811539e+00 -8.44000149e+00 -8.57856941e+00 -8.63623428e+00 -8.52758026e+00 -8.37635517e+00 -8.34305763e+00 -8.49927521e+00 -8.62852287e+00 -8.64141083e+00 -8.54956341e+00 -8.48650837e+00 -8.39150715e+00 -8.40782261e+00 -8.41342831e+00 -8.43455315e+00 -8.43668175e+00 -8.47111893e+00 -8.45784950e+00 -8.42735195e+00 -8.40350819e+00 -8.45085621e+00 -8.50387478e+00 -8.54834366e+00 -8.53813934e+00 -8.47626400e+00 -8.44150734e+00 -8.46051407e+00 -8.49159145e+00 -8.50314426e+00 -8.50791264e+00 -8.52717209e+00 -8.53707123e+00 -8.54084587e+00 -8.53355026e+00 -8.52692509e+00 -8.53072262e+00 -8.53912544e+00 -8.54230404e+00 -8.53393364e+00 -8.52318382e+00 -8.50687408e+00 -8.49705601e+00 -8.50351906e+00 -8.50136375e+00 -8.51115608e+00 -8.50231075e+00 -8.50887680e+00 -8.46259308e+00 -8.46078682e+00 -8.46318817e+00 -8.53597641e+00 -8.55503464e+00 -8.42824364e+00 -8.42041874e+00 -8.35943985e+00 -8.46587276e+00 -8.45099640e+00 -8.46223450e+00 -8.41783333e+00 -8.36929226e+00 -8.38870525e+00 -8.47576904e+00 -8.60217190e+00 -8.65307522e+00 -8.63734341e+00 -8.58258247e+00 -8.51484394e+00 -8.51159763e+00 -8.50041580e+00 -8.62023163e+00 -8.68815613e+00 -8.64433575e+00 -8.39246178e+00 -8.43493366e+00 -8.55053329e+00 -8.71787071e+00 -8.26052189e+00 -8.24524117e+00 -8.15992832e+00 -8.41559029e+00 -8.37846565e+00 -8.27781391e+00 -8.45572758e+00 -8.42827034e+00 -8.45158863e+00 -8.21159649e+00 -8.20017147e+00 -8.31999111e+00 -8.53548622e+00 -8.55922794e+00 -8.21325302e+00 -8.16694450e+00 -8.22718811e+00 -8.45105553e+00 -8.21345711e+00 -8.03587532e+00 -8.10565662e+00 -8.35353279e+00 -8.48454285e+00 -8.42684364e+00 -8.32130527e+00 -8.37491512e+00 -8.34402561e+00 -8.28464031e+00 -8.05709267e+00 -8.12844086e+00 -8.00760269e+00 -8.09945488e+00 -8.07653522e+00 -7.64013958e+00 -7.96998787e+00 -7.90626669e+00 -8.33871937e+00 -8.14817333e+00 -8.21853542e+00 -8.54553318e+00 -8.38979340e+00 -8.19128418e+00 -8.08576584e+00 -8.15660000e+00 -8.02506447e+00 -8.16781044e+00 -8.39027786e+00 -8.31063557e+00 -8.24382305e+00 -7.88617373e+00 -8.17292786e+00 -7.94447660e+00 -7.86342096e+00 -7.90876007e+00 -7.83790636e+00 -8.16725922e+00 -7.86200905e+00 -7.97929525e+00 -7.85381556e+00 -8.11790562e+00 -8.25274372e+00 -7.85955620e+00 -7.79599762e+00 -7.65831327e+00 -7.85872555e+00 -7.74988747e+00 -7.76385117e+00 -7.64813614e+00 -7.94154501e+00 -8.07974815e+00 -8.40274906e+00 -8.24982929e+00 -8.42295647e+00 -7.47559738e+00 -7.76579857e+00 -7.63954449e+00 -8.26646042e+00 -8.37979603e+00 -8.98639297e+00 -8.20023060e+00 -8.02200222e+00 -7.30233479e+00 -8.10269737e+00 -7.96834993e+00 -8.42939758e+00 -7.90888882e+00 -8.11197090e+00 -7.11384106e+00 -7.62028551e+00 -7.07702160e+00 -7.34229517e+00 -7.36207056e+00 -7.65338802e+00 -7.34216261e+00 -7.72584629e+00 -7.42925501e+00 -7.54240561e+00 -6.61434364e+00 -6.86167240e+00 -7.67184782e+00 -7.53916311e+00 -7.95537615e+00 -7.05987024e+00 -7.64047766e+00 -7.24890471e+00 -7.76270247e+00 -7.74121952e+00 -7.29329109e+00 -6.52851057e+00 -6.40168858e+00 -7.16698027e+00 -7.27001524e+00 -6.88108778e+00 -6.78761530e+00 -7.24930763e+00 -7.50235510e+00 -7.16706467e+00 -6.80277538e+00 -6.58978939e+00 -6.46166420e+00 -6.62282896e+00 -7.15359163e+00 -7.35291529e+00 -7.54529333e+00 -7.03097343e+00 -7.01898146e+00 -6.49396801e+00 -7.04541826e+00 -6.61475277e+00 -7.25185156e+00 -5.79849434e+00 -6.59985971e+00 -6.25978327e+00 -7.49357700e+00 -6.36381054e+00 -6.42046833e+00 -6.42935038e+00 -8.18691158e+00 -9.06163502e+00 -8.63062763e+00 -7.65881205e+00 -6.66120481e+00 -6.42877197e+00 -6.60845041e+00 -6.70519257e+00 -6.92113829e+00 -6.66368294e+00 -6.39117336e+00 -6.30947018e+00 -5.88609457e+00 -6.71641493e+00 -7.00161171e+00 -7.32098913e+00 -6.43806934e+00 -6.39102077e+00 -6.67314005e+00 -7.26646471e+00 -7.48142672e+00 -7.33615923e+00 -7.11588335e+00 -6.37223816e+00 -6.39156246e+00 -6.54791880e+00 -7.18471622e+00 -7.18940020e+00 -6.83880758e+00 -6.07119274e+00 -5.69502640e+00 -6.07960081e+00 -6.24119091e+00 -6.45617247e+00 -5.74435520e+00 -5.99067688e+00 -6.16464806e+00 -6.51473522e+00 -6.78226423e+00 -6.26469803e+00 -6.02769804e+00 -5.23822880e+00 -4.95000505e+00 -5.17367887e+00 -6.32275534e+00 -6.79472160e+00 -7.25919580e+00 -5.92743778e+00 -5.40048790e+00 -5.71856117e+00 -6.08358335e+00 -4.50123215e+00 -4.40492582e+00 -1.52209747e+00 1.18311071e+01 1.15653067e+01 4.32849159e+01 4.65023224e+02 3.80194580e+03 -148975744. 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. 0. 0. 0. 0. 0. 0. 90807680. -25646524. 1.47703650e+03 1.06099341e+03 9.18728485e+01 -3.96147369e+02 -2.85201477e+02 -4.72141609e+01 -1.24143782e+01 -6.34460497e+00 -3.38753247e+00 -3.24539280e+00 -4.41833925e+00 -4.49934959e+00 -3.95838261e+00 -3.81144667e+00 -3.77588439e+00 -2.81853366e+00 -2.11711693e+00 -2.54492283e+00 -3.25280857e+00 -3.90439987e+00 -3.66526389e+00 -4.12565088e+00 -4.09305096e+00 -4.51042271e+00 -4.77519417e+00 -4.60115576e+00 -4.07914162e+00 -3.96994710e+00 -4.77592564e+00 -5.29716682e+00 -4.95957851e+00 -4.55950212e+00 -4.51606512e+00 -4.55378819e+00 -4.10379744e+00 -3.85602427e+00 -3.61187601e+00 -4.06670523e+00 -3.03670526e+00 -2.94557762e+00 -2.60339046e+00 -3.22638130e+00 -4.04643822e+00 -4.17395353e+00 -4.43178129e+00 -4.40926361e+00 -5.03714943e+00 -5.14412022e+00 -5.17592192e+00 -4.77021074e+00 -3.93917751e+00 -3.70664811e+00 -3.37993550e+00 -3.40309882e+00 -3.50324512e+00 -3.41282392e+00 -4.15796566e+00 -3.22025204e+00 -3.84387064e+00 -3.57860970e+00 -2.94393444e+00 -1.78306925e+00 -1.54015279e+00 -2.36634278e+00 -2.60706353e+00 -2.09115219e+00 -1.60074854e+00 -1.33497179e+00 -2.50040793e+00 -2.88893580e+00 -3.87202263e+00 -3.73387647e+00 -4.52171516e+00 -4.83032465e+00 -4.45142317e+00 -4.36828709e+00 -3.37099266e+00 -3.23334360e+00 -2.58994555e+00 -2.17031717e+00 -2.26876426e+00 -2.39946961e+00 -2.27619100e+00 -1.95836020e+00 -1.23970556e+00 -2.12216139e+00 -2.26908994e+00 -2.56018782e+00 -1.84117794e+00 -1.94992208e+00 -1.80205536e+00 -1.55541313e+00 -1.22379506e+00 -1.45867395e+00 -1.87315774e+00 -2.54089069e+00 -2.17878556e+00 -1.46284449e+00 -4.87279296e-01 -6.25500202e-01 -1.40909123e+00 -1.57714272e+00 -1.65254271e+00 -1.33030570e+00 -2.09876156e+00 -1.95642161e+00 -1.46959054e+00 -6.53665289e-02 3.99081588e-01 -4.83220816e-01 -1.30921412e+00 -1.58987319e+00 -1.42575812e+00 -9.38487709e-01 -1.46178544e+00 -1.40599322e+00 -2.18675280e+00 -2.83507037e+00 -3.14348292e+00 -2.95577788e+00 -1.30301321e+00 -6.07277811e-01 -1.91404030e-01 -7.92382479e-01 -1.18422890e+00 -8.98003519e-01 1.85099095e-01 1.29246294e+00 9.85311806e-01 6.68033734e-02 -1.17637455e+00 -9.47124600e-01 -1.03973305e+00 3.31440419e-02 -7.83251673e-02 -8.38986933e-02 -1.12318039e+00 -1.16888273e+00 -8.62303019e-01 -4.02833313e-01 -6.65973663e-01 -9.85313416e-01 -8.13915968e-01 -7.70849049e-01 -2.34571785e-01 -7.11549878e-01 -3.72827291e-01 -8.81819487e-01 -5.93737006e-01 -1.28080547e+00 -1.75608814e+00 -9.48041320e-01 5.18625796e-01 7.29162812e-01 6.43997341e-02 -5.63788474e-01 3.29666585e-01 9.70007122e-01 1.36436307e+00 1.75495660e+00 1.90950668e+00 1.87408125e+00 6.77117646e-01 -1.27480403e-01 -4.12584037e-01 2.84044981e-01 1.99523374e-01 -4.10644598e-02 1.55323833e-01 7.75093660e-02 4.23463017e-01 -2.63798125e-02 2.44566455e-01 2.15506390e-01 -6.24157563e-02 -5.07936358e-01 -2.96577781e-01 -1.59613296e-01 2.59099036e-01 3.15515310e-01 5.29675543e-01 1.03649747e+00 5.51134109e-01 8.97720993e-01 8.29796612e-01 8.85165632e-01 -5.76723576e-01 -2.67560810e-01 -3.95924836e-01 6.52444661e-01 -2.28592932e-01 6.67394698e-01 9.04268384e-01 1.36406541e+00 1.12068558e+00 1.31248689e+00 1.54698193e+00 1.16684759e+00 3.15326571e-01 2.08245162e-02 -2.18105197e-01 6.79527760e-01 9.11117315e-01 8.94237041e-01 2.29343653e-01 3.50327611e-01 1.07531095e+00 1.90062571e+00 1.23399043e+00 1.03708124e+00 9.09613788e-01 1.45351064e+00 1.56273544e+00 1.44936121e+00 1.29430437e+00 1.33807278e+00 1.59891725e+00 2.03554845e+00 2.12816668e+00 1.79231739e+00 1.27416444e+00 8.53798866e-01 1.04470921e+00 1.55117357e+00 1.77608740e+00 1.61810791e+00 1.01235032e+00 1.05281866e+00 1.22415113e+00 1.46775043e+00 1.91428137e+00 1.02019989e+00 9.82754350e-01 5.01423955e-01 1.00844681e+00 1.24747682e+00 7.58818328e-01 7.66655266e-01 1.10727811e+00 1.55427527e+00 1.77045691e+00 1.46941113e+00 8.66503000e-01 6.12747610e-01 -4.95271273e-02 1.54573470e-01 1.12100053e+00 2.68684983e+00 2.52401495e+00 2.00658703e+00 1.06632197e+00 2.33615994e+00 2.96026707e+00 3.07129741e+00 1.80930722e+00 1.19077289e+00 4.77924019e-01 6.17732048e-01 7.05696404e-01 2.32694554e+00 3.00765729e+00 3.09781575e+00 2.25863743e+00 3.63023353e+00 2.56109834e+00 2.36212659e+00 8.42925787e-01 1.64541590e+00 1.43459058e+00 1.72995734e+00 1.89699960e+00 2.03806543e+00 2.16576290e+00 1.69667614e+00 2.17919374e+00 2.60541439e+00 3.79291582e+00 3.74641943e+00 3.26108623e+00 2.35448837e+00 1.61862206e+00 1.99191952e+00 2.69657779e+00 3.20374179e+00 2.76662469e+00 2.20200586e+00 1.76952183e+00 2.00564122e+00 2.59735727e+00 3.10003400e+00 2.53954697e+00 2.63757825e+00 2.71660471e+00 2.80161858e+00 2.58359194e+00 3.16081500e+00 4.07381487e+00 3.85957336e+00 3.30230641e+00 2.56658673e+00 3.75106645e+00 3.92081666e+00 4.53421879e+00 3.74294901e+00 4.39744425e+00 4.60921478e+00 5.26884604e+00 5.02304840e+00 5.00929737e+00 4.99290752e+00 4.62826586e+00 4.55327797e+00 4.08995295e+00 4.56896400e+00 4.06647968e+00 3.97996640e+00 2.94158101e+00 3.86954308e+00 3.40672612e+00 4.57153416e+00 3.74264073e+00 3.97913575e+00 3.74732614e+00 4.11425018e+00 4.97762728e+00 5.64879990e+00 6.12385416e+00 6.46974421e+00 5.69173098e+00 5.53693438e+00 4.14400196e+00 3.96416759e+00 3.54704261e+00 4.11747503e+00 3.74996042e+00 4.39601755e+00 5.31177378e+00 5.77120161e+00 5.20269918e+00 4.17622042e+00 3.17759109e+00 3.22292161e+00 3.18555856e+00 4.11678982e+00 4.32081223e+00 4.48966551e+00 5.16731310e+00 5.34528255e+00 5.23879671e+00 4.58961296e+00 4.22948265e+00 5.32111740e+00 6.57318497e+00 6.57581091e+00 5.94780922e+00 5.30081940e+00 5.39646912e+00 4.86637306e+00 5.37190485e+00 5.15509176e+00 5.60304785e+00 5.21851730e+00 5.82470322e+00 5.54749727e+00 5.56372738e+00 5.03031969e+00 4.35233736e+00 3.71730447e+00 3.91348457e+00 5.09073019e+00 6.27704763e+00 5.94765472e+00 4.74841452e+00 4.03072882e+00 4.42986393e+00 5.30810022e+00 5.30927324e+00 5.35748005e+00 6.15362597e+00 6.59890270e+00 6.64211464e+00 6.11491632e+00 5.62900543e+00 6.10984135e+00 6.09967613e+00 6.66988897e+00 6.05881596e+00 5.83366537e+00 5.72339201e+00 6.20265484e+00 6.48142624e+00 6.50731230e+00 5.94323206e+00 5.66482115e+00 5.87315559e+00 6.56505728e+00 6.39793587e+00 5.59347630e+00 5.46745825e+00 5.81268263e+00 6.35981798e+00 5.70662260e+00 5.86130381e+00 5.38534832e+00 5.22486258e+00 5.04456854e+00 5.82453346e+00 6.08710957e+00 6.12694073e+00 5.13374424e+00 6.13724995e+00 6.44879198e+00 6.67836618e+00 5.95424080e+00 5.77043724e+00 6.53331137e+00 6.58628225e+00 6.61964560e+00 6.07617903e+00 5.78592300e+00 5.67511892e+00 5.08548784e+00 5.43086529e+00 5.41680908e+00 6.59333229e+00 6.53525209e+00 6.75442553e+00 6.31851578e+00 6.34200287e+00 6.79335070e+00 6.90480375e+00 7.23373079e+00 6.60900354e+00 6.39997339e+00 6.10930014e+00 6.71980810e+00 7.17812347e+00 7.51403618e+00 7.31262922e+00 7.45545435e+00 7.60592747e+00 7.30222654e+00 6.81889153e+00 5.88598013e+00 6.06194353e+00 5.90470743e+00 6.57903242e+00 6.57596827e+00 7.05383062e+00 6.92664623e+00 6.95513439e+00 6.81600046e+00 6.75170803e+00 6.66442823e+00 6.52220058e+00 6.50076246e+00 7.02768373e+00 6.69486475e+00 6.92142725e+00 6.75970221e+00 7.57098627e+00 7.18796158e+00 6.78151941e+00 6.13577175e+00 7.05686808e+00 7.34141636e+00 7.78304338e+00 7.10501051e+00 7.16779709e+00 7.07182074e+00 7.52518559e+00 7.34533978e+00 7.51819801e+00 7.82510090e+00 8.07305908e+00 8.22598743e+00 7.23024035e+00 6.75967216e+00 6.70131063e+00 7.54729033e+00 8.41374683e+00 8.53860092e+00 8.23072910e+00 7.30783749e+00 7.32926893e+00 7.41021299e+00 7.78393745e+00 7.39639378e+00 7.51356936e+00 8.24122047e+00 9.18847752e+00 9.28108597e+00 8.88162804e+00 7.73875809e+00 7.50024223e+00 7.51169634e+00 7.78176451e+00 7.87311506e+00 7.62921906e+00 8.00174904e+00 8.30171299e+00 8.28321743e+00 8.16075039e+00 7.67870855e+00 7.55858326e+00 7.60112476e+00 8.03391266e+00 8.37489510e+00 8.49992085e+00 8.21305561e+00 8.33448696e+00 8.04135895e+00 8.23311806e+00 8.04865170e+00 8.07825661e+00 7.96546698e+00 7.71733236e+00 7.49825716e+00 7.61834908e+00 7.90199137e+00 7.94317245e+00 7.77774477e+00 7.73811769e+00 8.05969429e+00 8.28838730e+00 8.31510448e+00 8.25415325e+00 8.02739811e+00 8.05681896e+00 8.16091251e+00 8.20785904e+00 8.16837883e+00 8.25831223e+00 8.40962315e+00 8.52588463e+00 8.31472111e+00 8.16279793e+00 7.87263489e+00 7.90821314e+00 8.05164242e+00 8.44945335e+00 8.36779594e+00 8.29769039e+00 8.42419052e+00 8.57084179e+00 8.35691929e+00 8.14822197e+00 8.16915321e+00 8.46487522e+00 8.51034641e+00 8.37666225e+00 8.23616314e+00 7.89350605e+00 7.82652330e+00 7.91752958e+00 8.00397778e+00 8.27332306e+00 8.24674702e+00 8.36492443e+00 8.47162247e+00 8.63829803e+00 8.73738956e+00 8.52393723e+00 8.34757328e+00 8.44888115e+00 8.58879852e+00 8.48470402e+00 8.26881886e+00 8.07984447e+00 8.32816887e+00 8.42523670e+00 8.54226685e+00 8.44904041e+00 8.42800236e+00 8.45990658e+00 8.47783661e+00 8.46732807e+00 8.53562260e+00 8.60869789e+00 8.77841759e+00 8.67554188e+00 8.61468983e+00 8.51876450e+00 8.49990940e+00 8.52764606e+00 8.43922520e+00 8.52412605e+00 8.59480190e+00 8.66391373e+00 8.51374626e+00 8.49393272e+00 8.42964935e+00 8.45472145e+00 8.47502995e+00 8.63164902e+00 8.74092960e+00 8.68767929e+00 8.62708378e+00 8.67585945e+00 8.65178585e+00 8.49622345e+00 8.38552189e+00 8.37565994e+00 8.59020615e+00 8.68761444e+00 8.71854782e+00 8.36289215e+00 7.97305965e+00 5.25890732e+00 -1.25315138e+06 0. 0. 0. 0. 0. 0. 0. 0. 64076936. -20606844. -20606844. -85423088. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -46614904. -81055048. 8.86864853e+01 3.33803215e+01 9.33198261e+00 6.83561325e+00 6.33526373e+00 6.21583939e+00 6.31591702e+00 6.32232237e+00 6.29353952e+00 6.30945635e+00 6.33868504e+00 6.29869938e+00 6.22479343e+00 6.21096659e+00 6.22431278e+00 6.16965103e+00 6.11059666e+00 6.09713125e+00 6.25072432e+00 6.36556387e+00 6.39481783e+00 6.27852821e+00 6.20407963e+00 6.17569256e+00 6.08555555e+00 6.05215549e+00 5.99477100e+00 5.98373842e+00 6.07463646e+00 6.13033342e+00 6.20189524e+00 6.10336113e+00 5.97148418e+00 5.95124769e+00 5.98219252e+00 6.16158199e+00 6.12763691e+00 6.12250233e+00 6.19498587e+00 6.26857519e+00 6.35571432e+00 6.10024548e+00 5.91397619e+00 5.86333418e+00 6.04222012e+00 6.05883312e+00 5.91734028e+00 5.95783949e+00 6.12469530e+00 6.06909609e+00 5.94075727e+00 5.94788551e+00 5.93468428e+00 5.92844439e+00 5.97177410e+00 6.17281675e+00 5.99799156e+00 5.52956200e+00 5.33664799e+00 5.60723543e+00 5.97800159e+00 6.08249521e+00 6.04192066e+00 5.99183750e+00 5.88095999e+00 5.92343092e+00 6.02965069e+00 6.07509327e+00 5.94405413e+00 5.84158897e+00 6.01611090e+00 5.98715687e+00 5.95775461e+00 5.83209324e+00 5.79834747e+00 5.90951300e+00 5.74390078e+00 5.90340710e+00 6.16383171e+00 6.53150654e+00 6.40094614e+00 6.09911394e+00 5.80716276e+00 5.57894182e+00 5.47887087e+00 5.82451630e+00 6.06940794e+00 6.20044136e+00 6.29163265e+00 6.37236357e+00 6.15489388e+00 5.54823589e+00 4.99969006e+00 4.76024866e+00 5.20691061e+00 5.70208311e+00 5.93945837e+00 5.98324347e+00 6.16337824e+00 6.43039846e+00 6.16507816e+00 5.85878277e+00 5.34852362e+00 5.75696850e+00 5.97249794e+00 6.26882410e+00 5.91021585e+00 5.64623976e+00 5.52904749e+00 5.38060045e+00 5.82138252e+00 5.99069166e+00 5.92820740e+00 5.89321804e+00 5.84413433e+00 5.98498249e+00 5.72616720e+00 5.59493494e+00 5.53580284e+00 5.54961634e+00 5.86649370e+00 6.01304054e+00 5.82167959e+00 5.55892086e+00 5.11673403e+00 5.05955839e+00 5.32994413e+00 5.84250879e+00 6.02666378e+00 6.06272316e+00 6.24763107e+00 6.16099882e+00 5.93873596e+00 5.96053314e+00 6.05523396e+00 6.03865433e+00 5.84143400e+00 5.57178831e+00 5.65793562e+00 5.87596560e+00 5.96587706e+00 6.16167307e+00 5.65636253e+00 5.65235996e+00 4.81644440e+00 4.48063374e+00 4.42409468e+00 4.92311954e+00 5.53253651e+00 5.77462530e+00 5.51726961e+00 5.34430647e+00 4.98431587e+00 5.07315874e+00 5.34505415e+00 5.62120914e+00 5.50456810e+00 5.09383917e+00 5.04251146e+00 4.99324417e+00 5.43465662e+00 5.90568304e+00 6.01126051e+00 5.77506065e+00 5.48317051e+00 5.36196661e+00 5.13900518e+00 4.37242365e+00 4.21002102e+00 3.99940777e+00 5.00958109e+00 5.27825594e+00 5.59665966e+00 5.58844757e+00 5.61008883e+00 5.29398584e+00 4.28240538e+00 4.14838219e+00 4.11034822e+00 5.08056831e+00 5.49296904e+00 5.45325327e+00 4.68093252e+00 4.94526291e+00 4.65187120e+00 4.80457163e+00 4.18147850e+00 3.99191332e+00 4.09261513e+00 4.10255766e+00 4.19220781e+00 3.25563407e+00 2.12968016e+00 2.07296681e+00 2.78767776e+00 4.31482458e+00 4.86109161e+00 5.16885948e+00 4.82575369e+00 4.97143507e+00 4.89950943e+00 5.18943596e+00 4.11393881e+00 3.99763083e+00 3.51846981e+00 4.56083345e+00 4.46861362e+00 4.68236923e+00 4.65937185e+00 4.63374424e+00 4.35009670e+00 3.81524396e+00 4.08772373e+00 3.06857657e+00 3.35202718e+00 4.38124418e+00 4.74618292e+00 5.09623051e+00 2.76521730e+00 3.15192747e+00 3.48488140e+00 4.67204571e+00 4.61361408e+00 4.23333168e+00 3.83745503e+00 4.45849466e+00 3.86563540e+00 4.38102913e+00 4.53491259e+00 5.20840931e+00 5.34865808e+00 4.98673868e+00 4.82884455e+00 4.42905378e+00 3.79105973e+00 3.68747163e+00 3.48231411e+00 4.07620621e+00 4.32929850e+00 4.42170429e+00 4.07546568e+00 4.11453009e+00 3.71805406e+00 3.23668003e+00 2.65303111e+00 3.80707574e+00 4.32651711e+00 4.09519958e+00 3.53761768e+00 3.80014968e+00 4.83981943e+00 4.66533470e+00 4.81963778e+00 4.08805323e+00 4.12012291e+00 3.39253950e+00 3.77549100e+00 4.26736689e+00 5.23808098e+00 4.31339025e+00 4.51544285e+00 4.13927650e+00 3.99032974e+00 3.03966331e+00 2.64545774e+00 2.83841729e+00 2.91916060e+00 2.55584812e+00 1.93828940e+00 1.93196607e+00 3.16850734e+00 3.72289205e+00 3.31031513e+00 1.31258416e+00 1.52777243e+00 1.82689404e+00 2.64812326e+00 2.93023467e+00 3.03018832e+00 2.87448478e+00 2.71182799e+00 2.64848948e+00 3.26026368e+00 3.30568266e+00 3.70962620e+00 4.07297945e+00 4.55103493e+00 4.63901949e+00 3.91153097e+00 3.32133389e+00 3.27004504e+00 3.39329886e+00 3.14675713e+00 2.32884049e+00 2.74254847e+00 3.51994276e+00 3.78650618e+00 3.79221320e+00 2.90432858e+00 2.33885503e+00 1.83590388e+00 2.38926363e+00 3.22385359e+00 3.34707403e+00 4.44762182e+00 4.06283617e+00 3.85886312e+00 2.51550651e+00 2.87493229e+00 3.00053430e+00 3.55022430e+00 3.40332055e+00 3.45818567e+00 2.90074182e+00 2.91034365e+00 2.86603713e+00 3.40585780e+00 2.92133546e+00 2.10897875e+00 2.06243277e+00 2.36452174e+00 3.09443951e+00 1.71910644e+00 1.02242625e+00 1.09281576e+00 2.78399754e+00 2.71255589e+00 2.86811471e+00 2.55380273e+00 3.56957722e+00 3.31672406e+00 3.58667254e+00 3.71429443e+00 3.99579501e+00 3.86966944e+00 3.30967712e+00 3.44099736e+00 2.93956923e+00 2.32706523e+00 2.19144964e+00 2.19562268e+00 2.16352963e+00 1.79412401e+00 1.03193092e+00 2.37471390e+00 2.52606702e+00 3.34962726e+00 2.52058339e+00 3.53310513e+00 3.18243313e+00 2.60832357e+00 9.25897777e-01 1.85303605e+00 3.44184971e+00 4.15515280e+00 3.65275979e+00 1.97432661e+00 1.41512787e+00 9.33792770e-01 1.64097536e+00 2.40158963e+00 2.45844960e+00 2.00282669e+00 7.12516129e-01 2.94491082e-01 -3.11420202e-01 6.03030205e-01 9.80289221e-01 1.23959005e+00 8.34239900e-01 5.84559917e-01 1.26905966e+00 1.91569436e+00 2.29693031e+00 2.59648347e+00 1.55462122e+00 6.11401021e-01 -3.54948431e-01 5.66181600e-01 1.48792326e+00 1.64089632e+00 9.93651628e-01 6.47632897e-01 1.22386956e+00 2.56513238e+00 2.21040964e+00 1.61494625e+00 8.54817748e-01 -4.87412177e-02 8.30579519e-01 -1.55780151e-01 1.20573962e+00 6.39370322e-01 9.63597834e-01 1.88341546e+00 1.80357885e+00 9.26156640e-01 -2.25566819e-01 -2.24282086e-01 7.56115377e-01 3.96516621e-01 -3.58674049e-01 4.07268673e-01 8.43667746e-01 1.46866739e+00 -6.74675465e-01 -1.03878736e+00 -1.44199026e+00 -2.49932140e-01 1.10372579e+00 1.48306739e+00 2.35826111e+00 1.26300585e+00 1.02179098e+00 3.14359754e-01 2.99716443e-01 -3.22049260e-01 -3.46581303e-02 -2.89104342e-01 -8.44736993e-01 -1.17360342e+00 2.82966405e-01 1.54893088e+00 7.40089238e-01 1.48929358e-01 3.02890748e-01 4.05638844e-01 -8.21600020e-01 -1.18268836e+00 4.20361347e-02 -1.25058308e-01 -8.21893990e-01 -1.77217531e+00 -1.08411896e+00 4.65388209e-01 8.18372369e-01 1.77191645e-01 -5.59866667e-01 -7.43709803e-01 -6.23522162e-01 -1.92261946e+00 -1.74313104e+00 -8.72854173e-01 1.02556206e-01 -2.56699204e-01 -2.02774048e+00 -1.82919812e+00 -2.01512218e+00 -8.24453115e-01 4.08452392e-01 1.54125616e-01 -6.39255643e-01 -1.77894771e+00 -1.11813557e+00 -2.91015863e-01 -5.43842435e-01 -2.51056645e-02 -2.78480709e-01 6.21137209e-02 -1.66670848e-02 -1.78251579e-01 -4.78644103e-01 -2.75156319e-01 -2.67101467e-01 1.56636059e-01 -5.83238900e-01 -1.02183974e+00 -1.68021512e+00 -1.36072385e+00 -6.93118989e-01 -1.11642528e+00 -6.13317847e-01 -5.61818242e-01 7.76670635e-01 9.24898684e-02 -6.17153943e-01 -2.06140471e+00 -1.54404294e+00 -1.05894125e+00 -4.99502063e-01 -1.12858355e+00 -4.92273778e-01 -5.53533673e-01 -2.56217152e-01 -8.57815385e-01 -6.14537656e-01 -8.17431688e-01 2.54446507e-01 -8.66329014e-01 -9.49336708e-01 -1.57387459e+00 -5.55496216e-01 -3.11699450e-01 -1.05222948e-01 1.43744290e-01 -6.46840215e-01 -1.90866077e+00 -2.38524961e+00 -2.02747154e+00 -1.80355513e+00 -2.01777387e+00 -3.06106400e+00 -2.51070786e+00 -1.87370682e+00 -4.27797556e-01 -9.78315413e-01 -9.35194075e-01 -1.70199430e+00 -2.16088462e+00 -2.43210602e+00 -2.20299840e+00 -1.24570155e+00 -1.19393766e+00 -1.22942352e+00 -1.27111018e+00 -2.06600881e+00 -3.02332711e+00 -2.36733723e+00 -1.47054768e+00 -5.72622240e-01 -1.71178198e+00 -2.50361443e+00 -2.23948574e+00 -1.13212633e+00 -8.20954859e-01 -1.49650013e+00 -2.29039741e+00 -2.08264804e+00 -1.40413237e+00 -1.32472444e+00 -1.11216187e+00 -9.33747470e-01 -1.08428013e+00 -1.75678468e+00 -1.78217518e+00 -1.57461667e+00 -1.00827360e+00 -8.08037460e-01 -1.26378441e+00 -1.16935337e+00 -2.15744638e+00 -1.27100515e+00 -1.39297843e+00 -7.70248413e-01 -9.57555950e-01 -1.82743442e+00 -1.80650198e+00 -1.69627130e+00 -1.28390157e+00 -1.31852913e+00 -1.88084197e+00 -1.63097894e+00 -2.18431282e+00 -1.94404614e+00 -1.36647475e+00 -1.01052940e+00 -1.25102651e+00 -1.94977188e+00 -2.67938781e+00 -3.05648565e+00 -3.42105484e+00 -3.84205818e+00 -3.59870434e+00 -2.91430736e+00 -2.37031889e+00 -2.86586499e+00 -3.41382599e+00 -3.14000964e+00 -2.97581911e+00 -3.24015450e+00 -3.46975493e+00 -3.51037288e+00 -3.11199880e+00 -2.46351314e+00 -2.95848703e+00 -4.05866718e+00 -4.81060266e+00 -4.26208305e+00 -3.60260081e+00 -4.49941969e+00 -4.55330181e+00 -4.49819279e+00 -3.79035640e+00 -4.19254971e+00 -3.91443992e+00 -4.01264858e+00 -3.49270296e+00 -3.73367882e+00 -3.25222921e+00 -3.13222814e+00 -3.09836030e+00 -3.17192745e+00 -3.07490516e+00 -2.76766276e+00 -2.09638500e+00 -3.03211761e+00 -3.47684789e+00 -4.38835812e+00 -3.76554418e+00 -3.40012050e+00 -3.67738795e+00 -4.28655434e+00 -5.36542988e+00 -4.80755234e+00 -4.38567686e+00 -3.52971220e+00 -3.80709004e+00 -3.63741302e+00 -4.18459892e+00 -3.60047936e+00 -4.63464546e+00 -4.01809263e+00 -4.58849335e+00 -3.33341455e+00 -3.75520825e+00 -5.71987391e+00 -7.55150700e+00 -1.13752155e+01 -1.07205772e+01 -2.29304962e+01 -4.09081421e+01 -2.05924576e+02 -2.76429657e+02 7.83736450e+02 3.42581543e+03 119133344. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -267719120. 2.75938989e+03 4.91176605e+02 7.49199295e+01 3.36793442e+01 1.66897411e+01 2.75484848e+00 -1.63865495e+00 -3.68710876e+00 -4.00007296e+00 -4.07700014e+00 -4.38188744e+00 -4.66165781e+00 -4.37766552e+00 -4.29248619e+00 -4.31084919e+00 -4.30814028e+00 -4.02851343e+00 -4.42689276e+00 -4.63965321e+00 -5.16099644e+00 -4.85203266e+00 -5.36141109e+00 -5.03188515e+00 -5.11114836e+00 -4.89060402e+00 -4.42586946e+00 -4.84310961e+00 -4.78269196e+00 -4.83732367e+00 -3.95476604e+00 -3.69754529e+00 -4.63840389e+00 -5.25160837e+00 -5.32585573e+00 -5.01821804e+00 -5.15473890e+00 -5.05072021e+00 -4.92798853e+00 -4.88573217e+00 -5.12157917e+00 -5.02911806e+00 -5.12241936e+00 -4.76499510e+00 -4.97866392e+00 -5.46246338e+00 -5.80427217e+00 -6.34633112e+00 -5.62328959e+00 -5.77258968e+00 -5.19533730e+00 -5.23482370e+00 -5.51177931e+00 -5.51374292e+00 -5.45127630e+00 -5.00065851e+00 -5.21324825e+00 -5.39959335e+00 -5.48476601e+00 -5.55005646e+00 -5.83220148e+00 -6.08177471e+00 -6.26785278e+00 -5.98563766e+00 -6.07936144e+00 -6.06622076e+00 -5.83191109e+00 -5.48613167e+00 -5.20057154e+00 -5.36704826e+00 -5.53402472e+00 -5.99406624e+00 -6.60633326e+00 -6.81101942e+00 -6.60313797e+00 -5.84805679e+00 -5.50262165e+00 -5.60836315e+00 -5.44841242e+00 -5.15715218e+00 -4.84228992e+00 -5.34277964e+00 -6.01587772e+00 -5.93081141e+00 -5.77142668e+00 -5.44614697e+00 -5.39178324e+00 -5.48214626e+00 -5.45246410e+00 -5.71519423e+00 -5.44872093e+00 -5.38460875e+00 -5.20790672e+00 -5.77259111e+00 -6.34592819e+00 -6.21480703e+00 -5.92883539e+00 -5.86331224e+00 -5.88210011e+00 -5.73697186e+00 -5.39473438e+00 -5.48002386e+00 -5.84619331e+00 -5.93374348e+00 -5.81426239e+00 -5.50212479e+00 -5.37052536e+00 -5.57597351e+00 -5.51257277e+00 -5.54789209e+00 -5.55072498e+00 -5.78760624e+00 -6.01098251e+00 -6.24950886e+00 -6.04904175e+00 -5.84539795e+00 -5.74025297e+00 -5.67937708e+00 -5.47398996e+00 -5.29958391e+00 -5.37519741e+00 -5.51468706e+00 -5.70123434e+00 -5.65262461e+00 -5.52781820e+00 -5.17669630e+00 -5.10758972e+00 -5.43569899e+00 -5.79344177e+00 -5.72327662e+00 -5.60192823e+00 -5.50566006e+00 -5.70505714e+00 -5.81317949e+00 -5.93720961e+00 -6.23669481e+00 -6.17302847e+00 -6.00620842e+00 -5.74168158e+00 -5.81105328e+00 -6.10074282e+00 -6.08315039e+00 -6.01533937e+00 -5.77054262e+00 -5.93046904e+00 -6.08225965e+00 -6.21755934e+00 -6.29754019e+00 -6.33129549e+00 -6.37052822e+00 -6.32557631e+00 -6.15064287e+00 -6.18393660e+00 -6.15205908e+00 -6.22577953e+00 -6.05834103e+00 -5.87135172e+00 -5.83062649e+00 -5.71213818e+00 -6.03507757e+00 -6.05565786e+00 -6.29507589e+00 -6.31142473e+00 -6.38091564e+00 -6.31465006e+00 -6.23165083e+00 -6.18349314e+00 -6.23314619e+00 -6.08560181e+00 -6.10123253e+00 -5.95607090e+00 -5.89668608e+00 -6.08416796e+00 -6.22345829e+00 -6.29724407e+00 -6.18565655e+00 -6.11603212e+00 -6.14540625e+00 -6.12719965e+00 -6.15671873e+00 -6.17346811e+00 -6.08687210e+00 -6.02819109e+00 -5.93319464e+00 -6.07819223e+00 -6.10837460e+00 -6.22806263e+00 -6.20765686e+00 -6.13689613e+00 -6.02093363e+00 -6.17493963e+00 -6.38763142e+00 -6.37923527e+00 -6.21053457e+00 -6.07135963e+00 -6.07550287e+00 -6.14860773e+00 -6.24710417e+00 -6.28138018e+00 -6.18504429e+00 -6.11040640e+00 -6.16212511e+00 -6.21792173e+00 -6.23107862e+00 -6.21297789e+00 -6.18464231e+00 -6.23987770e+00 -6.26708937e+00 -6.25463724e+00 -6.21962881e+00 -6.23381805e+00 -6.25116634e+00 -6.22263718e+00 -6.19952822e+00 -6.20919323e+00 -6.21698570e+00 -6.20376873e+00 -6.22490883e+00 -6.23090553e+00 -6.22018003e+00 -6.20211840e+00 -6.19686985e+00 -6.19205332e+00 -6.20105267e+00 -6.21016121e+00 -6.21369934e+00 -6.21309423e+00 -6.21490860e+00 -6.21096945e+00 -6.20475006e+00 -6.18298435e+00 -6.18239260e+00 -6.19875717e+00 -6.20716763e+00 -6.20786858e+00 -6.19082355e+00 -6.19479942e+00 -6.14774799e+00 -6.12415981e+00 -6.09052324e+00 -6.10758114e+00 -6.11627102e+00 -6.17203951e+00 -6.18799114e+00 -6.19458675e+00 -6.25526524e+00 -6.22535515e+00 -6.24957657e+00 -6.14524937e+00 -6.13616848e+00 -6.12454557e+00 -6.15857697e+00 -6.14648914e+00 -6.10392666e+00 -6.08288527e+00 -6.07354355e+00 -6.08073282e+00 -6.09302330e+00 -6.16133165e+00 -6.20071125e+00 -6.19456244e+00 -6.20497322e+00 -6.20825958e+00 -6.24723768e+00 -6.18104124e+00 -6.20377159e+00 -6.10183191e+00 -6.26445103e+00 -6.22511005e+00 -6.26780558e+00 -6.09676933e+00 -6.16811562e+00 -6.24466991e+00 -6.29329729e+00 -6.14439917e+00 -6.05610991e+00 -6.11000252e+00 -6.14974546e+00 -6.15351820e+00 -6.11801815e+00 -6.16745996e+00 -6.14316368e+00 -6.08733225e+00 -6.28327227e+00 -6.20794344e+00 -6.31592894e+00 -6.03432560e+00 -6.11271572e+00 -6.24283695e+00 -6.35963011e+00 -6.40710115e+00 -6.25970888e+00 -6.15329218e+00 -6.03167009e+00 -5.99289703e+00 -5.95596981e+00 -5.84940624e+00 -5.78465319e+00 -5.60537100e+00 -5.93791389e+00 -5.86748362e+00 -5.94174862e+00 -6.09968615e+00 -5.97768784e+00 -6.16478586e+00 -5.91155720e+00 -6.00923634e+00 -5.97042561e+00 -6.16245556e+00 -6.22152233e+00 -6.32722807e+00 -5.98100805e+00 -6.00201035e+00 -5.76740742e+00 -5.77614164e+00 -5.59923315e+00 -5.55668640e+00 -5.49648905e+00 -5.80390787e+00 -5.91985273e+00 -5.87474489e+00 -5.85319996e+00 -6.36806297e+00 -6.59209871e+00 -6.41569614e+00 -6.02381563e+00 -5.97269773e+00 -6.07231998e+00 -5.91170740e+00 -5.72160673e+00 -5.61976337e+00 -5.62166214e+00 -5.88735819e+00 -5.82209587e+00 -5.75182343e+00 -5.73807096e+00 -5.86273909e+00 -5.69724751e+00 -5.50333071e+00 -5.22289467e+00 -5.52634764e+00 -5.65793991e+00 -5.84998512e+00 -5.60769749e+00 -5.51811504e+00 -5.51406240e+00 -5.58826399e+00 -5.71158266e+00 -5.63991213e+00 -5.47982597e+00 -5.22234678e+00 -5.08780098e+00 -5.13509321e+00 -5.20856714e+00 -5.59103775e+00 -5.85191822e+00 -6.01854229e+00 -5.72157478e+00 -6.11425877e+00 -5.83012819e+00 -5.83458996e+00 -5.52792597e+00 -5.41818619e+00 -5.28287935e+00 -5.40024662e+00 -5.62202978e+00 -6.20694923e+00 -5.92836905e+00 -6.09633350e+00 -5.91777420e+00 -5.56572008e+00 -5.53600788e+00 -4.99929094e+00 -5.15790892e+00 -4.88137960e+00 -5.53504133e+00 -5.70241165e+00 -6.26911926e+00 -5.80810022e+00 -5.62676668e+00 -5.19198275e+00 -5.25239229e+00 -5.29794931e+00 -5.70213270e+00 -5.57358837e+00 -5.66241074e+00 -5.21853638e+00 -5.46938562e+00 -5.63754845e+00 -5.73249006e+00 -5.79998159e+00 -5.49628019e+00 -5.34767675e+00 -5.06330252e+00 -5.35066128e+00 -5.48139715e+00 -5.12665224e+00 -5.20297956e+00 -5.60857868e+00 -6.14399290e+00 -5.57247734e+00 -5.40151691e+00 -5.21773911e+00 -5.44714260e+00 -5.11238909e+00 -4.60430193e+00 -4.29935408e+00 -4.14017677e+00 -5.11963320e+00 -5.39310980e+00 -5.33025885e+00 -4.83096027e+00 -4.96427250e+00 -5.18947744e+00 -5.24108982e+00 -4.76481724e+00 -4.92117882e+00 -4.50251055e+00 -4.72122622e+00 -4.23638487e+00 -4.39844275e+00 -4.40134859e+00 -4.46666908e+00 -4.65480185e+00 -4.70817089e+00 -4.98968744e+00 -5.25417995e+00 -5.30477047e+00 -5.31912041e+00 -5.14288712e+00 -5.23977804e+00 -5.29773617e+00 -5.17058468e+00 -4.96403885e+00 -4.80287218e+00 -4.75511742e+00 -4.61971283e+00 -4.25766325e+00 -4.18585539e+00 -4.17894983e+00 -4.52236462e+00 -4.63222027e+00 -4.71952438e+00 -4.38838720e+00 -4.33810949e+00 -4.61393166e+00 -4.80240059e+00 -4.59829283e+00 -5.07979918e+00 -5.96345997e+00 -6.51173830e+00 -5.78015709e+00 -4.80735493e+00 -3.64470053e+00 -3.58906960e+00 -3.43454266e+00 -3.69141960e+00 -1.92867351e+00 -9.64956701e-01 1.08589134e+01 1.87335587e+01 1.28292637e+01 1.35115158e+02 4.99129333e+01 -4.24520557e+03 -148975744. 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. 0. 0. 0. 0. 0. 0. 5.67918062e+05 2.23162888e+02 2.64486370e+01 -4.39610634e+01 -8.93550491e+00 -6.09193850e+00 -4.38489437e+00 -3.19431829e+00 -4.15485477e+00 -4.25527668e+00 -4.32081938e+00 -3.91432381e+00 -3.51467133e+00 -3.47306418e+00 -3.27118850e+00 -3.24773335e+00 -3.73097968e+00 -3.96187449e+00 -4.00453186e+00 -3.34263134e+00 -2.96176577e+00 -2.49167705e+00 -2.80265951e+00 -3.54936695e+00 -3.69132996e+00 -3.41315937e+00 -2.60746336e+00 -2.52179718e+00 -2.69483232e+00 -2.98479342e+00 -3.40885520e+00 -3.54730678e+00 -3.57654548e+00 -3.08502817e+00 -2.95336056e+00 -3.03480864e+00 -2.87451148e+00 -2.80747151e+00 -2.75087094e+00 -2.77660179e+00 -2.80086875e+00 -2.72733593e+00 -3.09067273e+00 -3.11964059e+00 -2.90515995e+00 -2.64381719e+00 -2.50789618e+00 -2.42337584e+00 -2.41722059e+00 -1.82298696e+00 -1.93241191e+00 -1.72700191e+00 -2.74077964e+00 -2.56150723e+00 -2.63313556e+00 -2.22774816e+00 -2.07181025e+00 -2.21238375e+00 -2.27218771e+00 -2.33580804e+00 -2.18183613e+00 -1.83710074e+00 -2.23130870e+00 -2.84870839e+00 -3.09421492e+00 -3.22274780e+00 -3.11146021e+00 -3.23690176e+00 -3.08169436e+00 -2.59807611e+00 -2.52984667e+00 -2.39427042e+00 -2.34766150e+00 -2.38794470e+00 -2.13614941e+00 -1.56126177e+00 -1.47436833e+00 -1.60944057e+00 -2.13714767e+00 -2.18526983e+00 -1.87520087e+00 -1.80356610e+00 -1.31467748e+00 -1.40400255e+00 -1.67630637e+00 -2.09132409e+00 -2.52455449e+00 -2.52005005e+00 -2.31368780e+00 -1.81774831e+00 -1.95822096e+00 -1.85774493e+00 -2.54320812e+00 -2.74002409e+00 -2.58488059e+00 -2.11265159e+00 -1.61278009e+00 -1.97094190e+00 -1.93187964e+00 -2.26807690e+00 -2.40562868e+00 -2.32299685e+00 -1.51835990e+00 -1.15376031e+00 -9.02959764e-01 -1.26728189e+00 -1.54188764e+00 -1.77796841e+00 -2.04118562e+00 -1.98593593e+00 -2.11269498e+00 -1.86603129e+00 -1.58249795e+00 -1.35415936e+00 -1.27448845e+00 -1.31034625e+00 -9.18901622e-01 -6.05843961e-01 -4.38306421e-01 -1.15097034e+00 -1.59757936e+00 -1.57847822e+00 -1.27119780e+00 -6.00607336e-01 -6.94308341e-01 -8.49762380e-01 -1.12945569e+00 -1.48055816e+00 -1.51302660e+00 -1.76599908e+00 -1.30950677e+00 -8.91039729e-01 -5.46336889e-01 -1.16712677e+00 -2.01699162e+00 -2.24648881e+00 -2.12373686e+00 -1.44400513e+00 -1.41278732e+00 -7.94359446e-01 -3.83072644e-01 -3.66051435e-01 -3.24844241e-01 -1.33010224e-01 7.78203830e-03 1.44510493e-01 -1.45905033e-01 -2.76143670e-01 -4.19068575e-01 -5.39227128e-01 -4.93031219e-02 8.70757457e-03 -9.82477609e-03 -9.03627515e-01 -1.29358673e+00 -7.32108176e-01 -4.37250048e-01 1.21199444e-01 -6.74588740e-01 -9.50288951e-01 -1.67280328e+00 -1.95125437e+00 -1.72791171e+00 -1.44732952e+00 -6.49776578e-01 -1.23609141e-01 2.73044199e-01 2.46662602e-01 -7.21924081e-02 -3.29273164e-01 -5.24409950e-01 -3.50860655e-01 5.82582830e-03 -1.85764819e-01 -4.98133093e-01 -6.75895989e-01 -6.08986244e-03 7.83207059e-01 9.64956820e-01 2.57614195e-01 -1.02324530e-01 -2.91625053e-01 2.07931012e-01 -2.53673494e-01 -1.90904513e-01 -6.51384115e-01 -5.90863347e-01 -2.26746991e-01 1.35434285e-01 4.92013603e-01 -1.17710028e-02 1.49708286e-01 -3.84409726e-02 3.97471517e-01 6.35205269e-01 8.26373160e-01 9.99137938e-01 6.59565508e-01 9.96214807e-01 1.12703860e+00 1.10834742e+00 1.03723121e+00 1.23008907e+00 1.51028085e+00 1.56434727e+00 1.06526768e+00 9.38232780e-01 4.03298467e-01 4.78905082e-01 5.02296686e-01 4.42589760e-01 5.56620538e-01 6.06510520e-01 9.33453560e-01 5.91240168e-01 3.42405736e-01 3.67764711e-01 6.24846160e-01 8.02522480e-01 1.11213589e+00 1.24127388e+00 1.65961099e+00 1.64698577e+00 1.23087835e+00 9.33599412e-01 5.93751609e-01 8.96170497e-01 1.30459392e+00 1.50502169e+00 1.49224901e+00 1.49582160e+00 1.75137889e+00 1.72251689e+00 1.68177116e+00 1.55467463e+00 1.51821315e+00 1.56188238e+00 1.64491296e+00 1.72685719e+00 1.46513379e+00 1.34840846e+00 1.30368483e+00 1.28023899e+00 1.14002633e+00 1.78228974e+00 2.54325318e+00 2.81283522e+00 2.44981599e+00 1.43370092e+00 1.35912156e+00 1.44775450e+00 2.08775020e+00 2.32100987e+00 1.60909736e+00 8.48589122e-01 6.05691671e-01 8.72665644e-01 1.56023443e+00 1.33234537e+00 1.58837163e+00 1.57763171e+00 1.80092680e+00 1.85487986e+00 1.63036823e+00 1.69965696e+00 1.39114404e+00 1.35947454e+00 1.26798940e+00 1.09313178e+00 1.10946202e+00 1.19224620e+00 1.03567624e+00 1.41111159e+00 1.47644484e+00 2.18426466e+00 1.89935696e+00 1.82855773e+00 2.05778933e+00 1.13489449e+00 1.01513362e+00 5.32540023e-01 1.59458232e+00 2.06075120e+00 2.63816142e+00 1.92931151e+00 1.78984320e+00 1.71895850e+00 2.63473988e+00 3.04430580e+00 2.80049872e+00 2.87820125e+00 2.60338902e+00 3.21069980e+00 3.31583500e+00 3.37939405e+00 2.51323199e+00 2.11558485e+00 1.87876749e+00 2.06191969e+00 2.21336508e+00 2.74637914e+00 2.88409257e+00 2.79822016e+00 2.61754513e+00 3.10570669e+00 2.91588593e+00 2.08646846e+00 1.90296745e+00 1.91785145e+00 2.69653654e+00 2.43295383e+00 2.68855596e+00 2.64581037e+00 2.97842026e+00 2.90199590e+00 3.20348716e+00 3.11511326e+00 2.93469501e+00 2.39734292e+00 2.42791033e+00 2.50374794e+00 2.99796581e+00 3.08550882e+00 3.09253836e+00 2.94088602e+00 2.83665943e+00 2.72231269e+00 2.55900574e+00 2.07035756e+00 1.98584044e+00 2.19927716e+00 2.54142523e+00 3.39244175e+00 3.26658702e+00 3.54354143e+00 3.04802513e+00 3.64082575e+00 3.36782789e+00 3.09732556e+00 2.84532690e+00 3.44810843e+00 4.43959332e+00 4.49225092e+00 4.29500103e+00 3.57766628e+00 3.61403346e+00 3.89721036e+00 3.75918341e+00 3.35865831e+00 2.99538112e+00 3.81099272e+00 4.31124687e+00 4.62748909e+00 4.56047010e+00 4.31187391e+00 4.46220779e+00 3.71642947e+00 3.88542056e+00 3.64142346e+00 4.11524105e+00 4.00154877e+00 3.88298297e+00 3.94442964e+00 3.97729039e+00 4.02740002e+00 4.07294416e+00 3.63215971e+00 3.41666746e+00 3.23517561e+00 3.74214530e+00 4.14824390e+00 3.72848558e+00 3.24068713e+00 3.10525179e+00 3.71494436e+00 3.70077825e+00 3.54346704e+00 3.54334736e+00 3.55782819e+00 3.97673845e+00 3.55384183e+00 4.09648418e+00 3.73703551e+00 3.85894489e+00 4.06704664e+00 4.22995615e+00 4.09983492e+00 3.76520705e+00 3.64984751e+00 4.06365442e+00 3.89908624e+00 3.97994781e+00 3.79229355e+00 3.91133761e+00 4.06895542e+00 3.91001010e+00 4.03022099e+00 3.71859598e+00 4.31515789e+00 4.57880211e+00 4.44935799e+00 3.90103865e+00 3.76551771e+00 4.14515066e+00 4.25453234e+00 4.15851545e+00 4.01666355e+00 4.21065664e+00 4.76991463e+00 4.94431734e+00 5.25669718e+00 4.94393826e+00 4.96621895e+00 4.48747587e+00 4.48916674e+00 4.79866886e+00 4.77763271e+00 4.31440973e+00 4.24164820e+00 4.30052376e+00 4.46746635e+00 4.54861116e+00 4.59950876e+00 4.95509624e+00 4.88511181e+00 5.06791067e+00 4.71372700e+00 4.75070715e+00 4.96933079e+00 4.99722958e+00 4.88643169e+00 4.64437962e+00 5.03676271e+00 4.90025377e+00 5.05785465e+00 5.05522966e+00 5.54704523e+00 5.31259966e+00 5.05708981e+00 4.91400528e+00 5.03499746e+00 5.20582533e+00 4.68012619e+00 4.78276110e+00 4.83983374e+00 5.20232248e+00 5.13496351e+00 5.41440153e+00 5.58146095e+00 5.74814510e+00 5.37971783e+00 5.08497238e+00 5.21780968e+00 5.32264900e+00 5.50139380e+00 5.21606636e+00 5.04912710e+00 5.04508257e+00 4.81523800e+00 4.82609177e+00 4.80616617e+00 5.25612450e+00 5.45791483e+00 5.28450489e+00 5.28659010e+00 5.46721601e+00 5.51513529e+00 5.27920198e+00 5.13050413e+00 5.43842506e+00 5.38270807e+00 5.39015579e+00 5.22202206e+00 5.22690105e+00 5.31869173e+00 5.04105091e+00 5.08351135e+00 4.96420670e+00 5.20907354e+00 5.14044809e+00 5.48381472e+00 5.79293966e+00 5.91966343e+00 5.40125751e+00 5.43096972e+00 5.70069504e+00 5.96345663e+00 5.73941517e+00 5.38812923e+00 5.80753613e+00 5.77088976e+00 5.99595213e+00 5.72354984e+00 6.14705944e+00 6.34357738e+00 6.49627399e+00 6.05181599e+00 5.69345617e+00 5.81508160e+00 6.26127481e+00 6.75818062e+00 6.67480040e+00 6.55071163e+00 6.57902575e+00 6.44725800e+00 6.44045401e+00 5.97847271e+00 5.68760633e+00 5.45800257e+00 5.33442020e+00 5.24068880e+00 5.39311886e+00 5.77545595e+00 6.03812313e+00 5.98663425e+00 5.69291306e+00 5.80429840e+00 5.92858267e+00 6.13599205e+00 6.24494410e+00 6.27712202e+00 6.31020021e+00 6.09119034e+00 5.81410408e+00 5.77259731e+00 5.87352800e+00 5.97438478e+00 6.05483150e+00 5.92085600e+00 5.91560268e+00 5.94342422e+00 6.11137486e+00 6.16178036e+00 6.11615181e+00 6.05655050e+00 5.96904039e+00 5.99285412e+00 6.00866938e+00 6.27290583e+00 6.36635160e+00 6.43212891e+00 5.97575665e+00 5.70431805e+00 5.53713226e+00 5.86661434e+00 5.90912294e+00 5.95362520e+00 5.64103794e+00 5.63028431e+00 5.73189640e+00 5.88062143e+00 5.97607470e+00 5.91652536e+00 5.92095184e+00 6.06293201e+00 6.08223963e+00 6.10348797e+00 5.98474455e+00 5.86505842e+00 6.04908228e+00 6.07230043e+00 6.08218622e+00 5.97979784e+00 5.95609951e+00 6.02284050e+00 6.07813454e+00 6.11349106e+00 6.04624987e+00 6.00603008e+00 5.95973349e+00 6.02049160e+00 6.05056190e+00 6.09622335e+00 6.20039368e+00 6.13315582e+00 6.06633568e+00 5.93047476e+00 5.86444902e+00 5.89428806e+00 5.95973301e+00 6.10200644e+00 6.15187836e+00 6.20254517e+00 6.14392376e+00 6.13126659e+00 6.09011459e+00 6.17370844e+00 6.22007656e+00 6.18240595e+00 6.11023951e+00 6.16339540e+00 6.17606258e+00 6.20434856e+00 6.17905569e+00 6.28915644e+00 6.23972368e+00 6.23498440e+00 6.16129017e+00 6.29369164e+00 6.32414532e+00 6.41645670e+00 6.35774136e+00 6.29230070e+00 6.15915918e+00 6.15246105e+00 6.17113638e+00 6.14438200e+00 5.23421574e+00 5.55842018e+00 4.95704746e+00 1.64827824e+01 -81505232. 0. 0. 0. 0. 22237478. -42227944. 90862520. 16297160. 1.91553059e+01 -5.01517181e+01 -1.38811462e+02 -85423088. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -46614904. -81055048. -59658888. 1.31698624e+02 5.85512886e+01 1.90352879e+01 1.79404411e+01 1.57537651e+01 1.51433964e+01 1.45911045e+01 1.44016991e+01 1.53552990e+01 1.64665108e+01 1.65320358e+01 1.61428185e+01 1.58335800e+01 1.53279419e+01 1.50767794e+01 1.47340298e+01 1.53180523e+01 1.62392082e+01 1.71744499e+01 1.71572914e+01 1.55633430e+01 1.39790268e+01 1.29100008e+01 1.26910095e+01 1.35575981e+01 1.35136480e+01 1.36155882e+01 1.51411877e+01 1.62031040e+01 1.56732435e+01 1.31725159e+01 1.11826200e+01 1.11209965e+01 1.25640249e+01 1.52347479e+01 1.61948242e+01 1.60055027e+01 1.59136705e+01 1.58263760e+01 1.55517559e+01 1.36116028e+01 1.18646822e+01 1.24567585e+01 1.43729858e+01 1.54473038e+01 1.41023045e+01 1.39176922e+01 1.43839817e+01 1.33991613e+01 1.32608576e+01 1.34945650e+01 1.46965866e+01 1.62097588e+01 1.72117481e+01 1.78320084e+01 1.45524540e+01 1.02659111e+01 8.84111500e+00 1.11884193e+01 1.55465345e+01 1.61804829e+01 1.47191858e+01 1.33183489e+01 1.37178507e+01 1.45130539e+01 1.37645836e+01 1.26592464e+01 1.22942533e+01 1.44763002e+01 1.75288391e+01 1.66460934e+01 1.57112236e+01 1.42414112e+01 1.35055799e+01 1.33739767e+01 1.24293747e+01 1.40413733e+01 1.67823505e+01 1.96296635e+01 1.98356209e+01 1.65816936e+01 1.30351677e+01 9.93225670e+00 9.65191841e+00 1.30268822e+01 1.46215267e+01 1.48921089e+01 1.66822929e+01 1.99702606e+01 1.99395180e+01 1.43795471e+01 8.64882851e+00 8.60504818e+00 1.40182676e+01 1.93161659e+01 1.96542702e+01 1.84971657e+01 1.92087288e+01 1.94912872e+01 1.78399277e+01 1.48989582e+01 1.30245857e+01 1.52507210e+01 1.79140186e+01 1.86557732e+01 1.51242237e+01 1.09998198e+01 9.01757145e+00 9.03984642e+00 1.36384802e+01 1.73395824e+01 1.68421822e+01 1.59574099e+01 1.73006134e+01 1.86064358e+01 1.61930790e+01 1.12594728e+01 1.12589388e+01 1.67060165e+01 2.23798580e+01 2.35441399e+01 1.86355896e+01 1.44189720e+01 9.85398769e+00 8.04561424e+00 1.08032780e+01 1.34808817e+01 1.51777706e+01 1.87887058e+01 2.28292847e+01 2.30646973e+01 1.93361893e+01 1.51691055e+01 1.26769361e+01 1.20075388e+01 1.35705080e+01 1.53882141e+01 1.68504143e+01 1.87839680e+01 2.09879761e+01 2.12680683e+01 1.58370333e+01 9.14763451e+00 4.55310774e+00 6.16619349e+00 8.76830006e+00 1.08763609e+01 1.41193113e+01 1.60229034e+01 1.44652548e+01 1.33245134e+01 9.44664478e+00 7.79856825e+00 8.83052063e+00 1.34823465e+01 1.52918615e+01 1.19298840e+01 7.39263248e+00 9.41233540e+00 1.48488169e+01 1.86055145e+01 1.42513151e+01 8.65974140e+00 9.47154331e+00 1.01754951e+01 9.99374104e+00 2.93524766e+00 -1.46859026e+00 -2.33136916e+00 7.01346922e+00 1.75001125e+01 2.06171055e+01 2.00448360e+01 1.95230732e+01 1.76107979e+01 1.36311712e+01 5.74687672e+00 3.99157524e+00 1.03254709e+01 1.85981827e+01 2.04534798e+01 1.25846977e+01 7.65676403e+00 5.92957401e+00 6.09292269e+00 6.81499958e+00 4.39613438e+00 5.02856874e+00 7.14187336e+00 8.51015091e+00 6.38025284e+00 1.22728539e+00 -1.67005908e+00 -4.67638910e-01 1.11082516e+01 2.08155251e+01 2.29348717e+01 1.73844662e+01 1.63659153e+01 1.52971268e+01 1.31432505e+01 5.11967421e+00 4.32923460e+00 1.19209270e+01 1.95377884e+01 2.12895432e+01 1.38808422e+01 1.17670441e+01 1.16454048e+01 1.26992865e+01 1.17543039e+01 8.97729015e+00 3.71490669e+00 7.48619652e+00 1.50669413e+01 1.84655762e+01 1.42119150e+01 2.57751393e+00 7.41583169e-01 7.14112616e+00 1.49067965e+01 1.76611462e+01 1.40496092e+01 1.36998978e+01 1.37014723e+01 1.40945930e+01 1.55932636e+01 1.66323013e+01 1.73260670e+01 1.72423038e+01 1.85881672e+01 1.80804081e+01 1.73934212e+01 1.53556662e+01 8.82714939e+00 4.15373039e+00 6.86407983e-01 5.01933908e+00 1.11354914e+01 1.57425442e+01 1.90875111e+01 1.04837170e+01 2.11615705e+00 1.00588155e+00 1.03681984e+01 1.68088741e+01 1.34289351e+01 8.62861156e+00 1.27867765e+01 1.77225647e+01 1.54785900e+01 8.15681839e+00 3.45251298e+00 6.13271332e+00 4.63884926e+00 7.63424635e+00 9.26111889e+00 1.48648424e+01 1.14150028e+01 8.34260178e+00 5.87595987e+00 5.44542253e-01 6.80997789e-01 2.29739952e+00 1.04598875e+01 1.54757824e+01 9.89483356e+00 -1.77055526e+00 -5.64003849e+00 8.91661167e-01 2.60965133e+00 -1.76231228e-02 -5.81502008e+00 2.00737238e+00 6.35393906e+00 8.32810497e+00 7.51805592e+00 8.69234657e+00 9.30441189e+00 5.89749765e+00 5.99774122e+00 1.24340992e+01 1.57545223e+01 1.33477526e+01 1.46917877e+01 2.11091022e+01 2.19679565e+01 1.27930145e+01 3.94095111e+00 5.08239603e+00 7.87386513e+00 6.60117006e+00 -5.75895309e-02 3.45861197e+00 8.73349762e+00 8.01505756e+00 3.00884962e+00 -2.11329985e+00 1.51363945e+00 4.28427815e-01 2.95473242e+00 3.20262980e+00 9.57232285e+00 1.61004562e+01 1.36267586e+01 9.30979633e+00 5.83368492e+00 1.07051430e+01 1.18860121e+01 1.51939316e+01 1.88621616e+01 1.71867065e+01 1.25931072e+01 8.65406322e+00 1.38741264e+01 1.95721149e+01 1.33904371e+01 4.20236260e-01 -1.18791211e+00 5.49216127e+00 1.18801861e+01 3.15902662e+00 -4.20070982e+00 -4.82076071e-02 7.57311010e+00 1.37769079e+01 1.52463408e+01 1.87654591e+01 2.05628777e+01 1.58555231e+01 1.32466955e+01 1.34319315e+01 1.58681002e+01 1.34940109e+01 1.36883125e+01 1.90023556e+01 1.55626287e+01 5.64902020e+00 -9.23624575e-01 1.93092489e+00 6.05497074e+00 4.21437263e-01 -4.85654831e+00 -8.53182375e-02 3.86376452e+00 7.30675840e+00 1.38843215e+00 4.53269958e+00 5.90231085e+00 5.67580366e+00 3.62928534e+00 6.37965918e+00 1.64517670e+01 2.09825287e+01 1.64111137e+01 7.61601734e+00 6.84395254e-01 3.14496446e+00 6.34241009e+00 1.22176208e+01 2.25961151e+01 2.03603058e+01 5.01551533e+00 -1.30835943e+01 -1.86494255e+01 -9.89749336e+00 -4.09404039e+00 -4.77124023e+00 -4.67830944e+00 -9.36531734e+00 -3.87106776e+00 -3.12477398e+00 2.25260407e-01 -1.21502899e-01 -1.23474388e+01 -1.67164803e+01 -1.64860916e+01 1.54134557e-01 1.16206636e+01 4.88669205e+00 -5.76890898e+00 -9.43133926e+00 3.52867746e+00 1.37720747e+01 1.32551527e+01 9.79417229e+00 4.09395075e+00 -3.29451680e+00 -6.61376047e+00 -1.24970665e+01 -6.49653482e+00 6.14588976e-01 7.23368359e+00 7.91884136e+00 -5.02376461e+00 -1.41009197e+01 -2.04355793e+01 -1.26555243e+01 1.73049307e+00 3.51846671e+00 2.86505747e+00 4.25231743e+00 1.33995943e+01 1.30715971e+01 -7.10749674e+00 -1.73277111e+01 -1.86242447e+01 -7.15498877e+00 -9.01078701e-01 5.11789739e-01 5.10608387e+00 2.41382885e+00 -3.55662799e+00 -8.81130409e+00 -1.51835356e+01 -1.29079256e+01 -1.28232870e+01 -1.12782516e+01 -9.64603519e+00 -9.72737694e+00 3.07990122e+00 6.99739456e+00 5.28145552e+00 -1.12709558e+00 -1.31855001e+01 -1.61349621e+01 -1.66909695e+01 -1.86237705e+00 1.02154226e+01 1.03012867e+01 -1.62691236e+00 -1.23707399e+01 -5.88861465e+00 6.59991646e+00 1.01626692e+01 7.34525108e+00 1.99433839e+00 -2.45456338e+00 -4.61807966e+00 -1.02558823e+01 -3.19078517e+00 2.83075881e+00 8.05193233e+00 2.74264431e+00 -1.38676891e+01 -2.05075760e+01 -1.78230724e+01 -4.52597237e+00 6.95549297e+00 1.42131555e+00 -9.49307632e+00 -1.55379772e+01 -5.68218994e+00 4.38061810e+00 2.30732703e+00 -1.72938108e+00 -5.38986778e+00 -3.18498588e+00 -1.66796696e+00 -6.94131279e+00 -8.19961929e+00 -7.32130432e+00 -6.81429911e+00 -4.02936125e+00 -9.91815567e+00 -7.05045033e+00 -8.13319016e+00 -4.54779387e+00 -2.13810587e+00 -9.74306774e+00 -3.44551325e+00 9.60896492e-01 1.27361517e+01 8.62272644e+00 -5.99686050e+00 -1.60603161e+01 -1.82899418e+01 -3.58156300e+00 6.24128819e+00 8.17000294e+00 3.04707789e+00 -4.99029064e+00 -5.61192226e+00 1.51564613e-01 3.99849892e+00 8.59787750e+00 3.28541589e+00 -5.20979118e+00 -1.55476027e+01 -1.62311478e+01 -3.63102794e+00 6.57126474e+00 1.20661087e+01 8.65210438e+00 -4.16861343e+00 -1.54502640e+01 -1.76471844e+01 -5.04019928e+00 6.07835150e+00 1.43228269e+00 -9.28985405e+00 -1.61249332e+01 -7.97304678e+00 3.89400935e+00 4.51864815e+00 1.91195917e+00 -8.31591702e+00 -1.36752052e+01 -1.45027008e+01 -1.37386866e+01 -6.90403414e+00 -1.09791970e+00 2.77202092e-02 -2.56132698e+00 -1.24025097e+01 -1.17844458e+01 -7.14652395e+00 -2.13789320e+00 3.97823477e+00 -2.67594314e+00 -5.15067434e+00 -5.68879747e+00 2.39874339e+00 5.09453249e+00 -8.23435879e+00 -1.70649681e+01 -1.61460533e+01 -3.74939275e+00 5.72955799e+00 5.92719364e+00 3.24090481e+00 -6.57914448e+00 -1.45289984e+01 -1.61501904e+01 -1.35686846e+01 -5.90699434e+00 -2.81438637e+00 -6.79169273e+00 -6.27215385e+00 -8.10956764e+00 2.55581236e+00 3.85603142e+00 4.37804747e+00 9.06053662e-01 -9.22233677e+00 -1.06166391e+01 -5.42115641e+00 8.31613827e+00 1.41075344e+01 9.35796452e+00 4.50664371e-01 -8.43013763e+00 -3.71393681e+00 5.64994907e+00 1.00743542e+01 7.76459455e+00 -4.18142796e-01 -5.12673330e+00 -7.90094709e+00 -9.33790398e+00 -8.74682617e+00 -8.52987194e+00 -7.53469086e+00 -1.15960045e+01 -1.80196381e+01 -1.45924206e+01 -3.74307609e+00 1.80398023e+00 -1.72726429e+00 -1.40651941e+01 -1.93934135e+01 -1.76697903e+01 -4.98835087e+00 1.97429669e+00 -3.91888714e+00 -1.06569815e+01 -1.23088379e+01 -6.99736643e+00 -6.91767979e+00 -1.10076218e+01 -1.47057514e+01 -1.74295826e+01 -1.92711201e+01 -1.65295372e+01 -1.82766857e+01 -1.35328617e+01 -1.23838158e+01 -1.17144012e+01 -1.03222504e+01 -1.45897636e+01 -1.14519606e+01 -1.06983318e+01 -6.12799120e+00 -3.06412005e+00 -1.11076918e+01 -1.19366922e+01 -1.36281347e+01 -7.13775921e+00 -4.75534296e+00 -1.05438824e+01 -1.31640358e+01 -2.18725891e+01 -1.74935932e+01 -1.05164480e+01 -2.01549459e+00 -2.81187177e-01 -1.06314964e+01 -1.29385300e+01 -1.03438520e+01 -9.85271358e+00 -1.17307386e+01 -1.33699312e+01 -4.14082098e+00 -2.03122306e+00 -1.27502728e+01 -1.72311440e+01 -1.73112259e+01 -1.17050810e+01 -1.27696962e+01 -2.38495350e+01 -4.16509771e+00 3.24882278e+01 4.17818787e+02 1.71607434e+03 59566672. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -267719120. 74284096. -9019003. -19971854. 1.53249133e+03 5.45930542e+02 4.37559738e+01 1.05962467e+01 -1.07389116e+01 -1.79617538e+01 -1.21064377e+01 -1.03881149e+01 -1.14376574e+01 -1.15976677e+01 -1.38180714e+01 -1.65512714e+01 -1.58492031e+01 -1.37264023e+01 -1.03308535e+01 -1.26097803e+01 -1.66650639e+01 -1.78280067e+01 -1.96518002e+01 -1.81510124e+01 -1.69971600e+01 -1.22590551e+01 -9.44706154e+00 -1.63284607e+01 -1.82189598e+01 -1.47246714e+01 -6.21895552e+00 -9.27839947e+00 -1.76492786e+01 -2.01974297e+01 -1.69265480e+01 -1.24471426e+01 -1.23428888e+01 -1.29575634e+01 -1.30017691e+01 -1.40493107e+01 -1.61341724e+01 -1.63028221e+01 -1.53000059e+01 -1.23189707e+01 -1.52397757e+01 -1.75166473e+01 -2.08812866e+01 -2.54648418e+01 -2.23100319e+01 -1.61467342e+01 -6.78312159e+00 -6.75388384e+00 -1.53516245e+01 -1.65653915e+01 -1.45245581e+01 -7.66416836e+00 -8.57065105e+00 -1.34192142e+01 -1.48340406e+01 -1.60748329e+01 -1.36537943e+01 -1.39488792e+01 -1.45586576e+01 -1.52946711e+01 -1.98900604e+01 -2.36640568e+01 -2.28453732e+01 -1.82046776e+01 -1.41963892e+01 -1.54658546e+01 -1.75520153e+01 -2.07247734e+01 -2.53040829e+01 -2.70009918e+01 -2.69182663e+01 -2.18448582e+01 -1.87823086e+01 -2.06745663e+01 -1.74726124e+01 -1.37370329e+01 -6.87533855e+00 -9.23100090e+00 -1.52275391e+01 -1.61303234e+01 -1.67240696e+01 -1.59173107e+01 -1.67347431e+01 -1.50489511e+01 -1.26553173e+01 -1.39692822e+01 -1.54230204e+01 -1.55076027e+01 -1.58967533e+01 -1.78694725e+01 -2.10017185e+01 -1.95477161e+01 -1.65174580e+01 -1.87353439e+01 -1.87485638e+01 -1.81566067e+01 -1.40897236e+01 -1.31058550e+01 -1.83564892e+01 -1.85878448e+01 -1.64141102e+01 -1.06951103e+01 -9.48194885e+00 -1.41150169e+01 -1.55378437e+01 -1.80644073e+01 -1.81367435e+01 -1.96103001e+01 -1.99478874e+01 -1.79735851e+01 -1.79734097e+01 -1.80571327e+01 -1.85126743e+01 -1.74947472e+01 -1.53257408e+01 -1.59063730e+01 -1.58263979e+01 -1.47654600e+01 -1.65780869e+01 -1.60789986e+01 -1.49211664e+01 -1.03671598e+01 -9.75981903e+00 -1.54191465e+01 -1.74071789e+01 -1.54215441e+01 -1.12824001e+01 -1.11142893e+01 -1.52047939e+01 -1.60849724e+01 -1.67530384e+01 -1.68069897e+01 -1.60723343e+01 -1.45740376e+01 -1.23924427e+01 -1.41959391e+01 -1.63430195e+01 -1.62281399e+01 -1.47610893e+01 -1.27865038e+01 -1.45352287e+01 -1.56886425e+01 -1.60611172e+01 -1.71890717e+01 -1.73344021e+01 -1.78838406e+01 -1.73209095e+01 -1.69005890e+01 -1.82891922e+01 -1.78929062e+01 -1.72050190e+01 -1.40524817e+01 -1.20244789e+01 -1.23554926e+01 -1.33284369e+01 -1.54994030e+01 -1.61138248e+01 -1.71041889e+01 -1.80218487e+01 -1.80189095e+01 -1.74805984e+01 -1.70134468e+01 -1.72976990e+01 -1.77669811e+01 -1.67256908e+01 -1.45494432e+01 -1.27405577e+01 -1.19598551e+01 -1.49732656e+01 -1.60429363e+01 -1.57025499e+01 -1.41787853e+01 -1.40904989e+01 -1.55907640e+01 -1.52875843e+01 -1.58749952e+01 -1.59306822e+01 -1.57995901e+01 -1.51337757e+01 -1.43657999e+01 -1.54479361e+01 -1.61754322e+01 -1.60270214e+01 -1.58621836e+01 -1.60288315e+01 -1.67260303e+01 -1.76645737e+01 -1.81137428e+01 -1.83468647e+01 -1.66103325e+01 -1.54530697e+01 -1.47158012e+01 -1.49619532e+01 -1.61514149e+01 -1.60553112e+01 -1.54325371e+01 -1.40970984e+01 -1.42026396e+01 -1.52295656e+01 -1.59076309e+01 -1.61797104e+01 -1.58285275e+01 -1.60939999e+01 -1.62557526e+01 -1.60925331e+01 -1.58818607e+01 -1.58421955e+01 -1.59112844e+01 -1.57406330e+01 -1.53650465e+01 -1.53198805e+01 -1.50237265e+01 -1.50750446e+01 -1.54403877e+01 -1.57473288e+01 -1.56215553e+01 -1.53172674e+01 -1.51960306e+01 -1.52149124e+01 -1.51503334e+01 -1.51301584e+01 -1.51374998e+01 -1.51866922e+01 -1.52198544e+01 -1.52014332e+01 -1.50816088e+01 -1.50143299e+01 -1.51140175e+01 -1.52854042e+01 -1.53464775e+01 -1.51909189e+01 -1.50742750e+01 -1.51849623e+01 -1.51069832e+01 -1.51002016e+01 -1.50538368e+01 -1.51524305e+01 -1.51137342e+01 -1.51511011e+01 -1.50792093e+01 -1.50953894e+01 -1.53725376e+01 -1.55298367e+01 -1.56807432e+01 -1.52392750e+01 -1.51066580e+01 -1.49990788e+01 -1.52341442e+01 -1.50748968e+01 -1.50977736e+01 -1.46136751e+01 -1.43028402e+01 -1.42092743e+01 -1.45915604e+01 -1.51392593e+01 -1.51252804e+01 -1.50977278e+01 -1.50102892e+01 -1.49861469e+01 -1.46596231e+01 -1.47896976e+01 -1.50459003e+01 -1.52775412e+01 -1.50856714e+01 -1.50074024e+01 -1.56818533e+01 -1.55213633e+01 -1.55776024e+01 -1.55174189e+01 -1.57289600e+01 -1.55453911e+01 -1.52936687e+01 -1.54814253e+01 -1.54667091e+01 -1.50385246e+01 -1.52487164e+01 -1.54206591e+01 -1.53990135e+01 -1.48451233e+01 -1.52435246e+01 -1.57403698e+01 -1.60506954e+01 -1.53749065e+01 -1.59993420e+01 -1.66075039e+01 -1.68307114e+01 -1.57345476e+01 -1.51030703e+01 -1.51262531e+01 -1.51756182e+01 -1.50135527e+01 -1.49279728e+01 -1.44874382e+01 -1.37835178e+01 -1.24853735e+01 -1.37111578e+01 -1.41438932e+01 -1.47893400e+01 -1.49301367e+01 -1.48805313e+01 -1.52115688e+01 -1.43911953e+01 -1.47173376e+01 -1.46704750e+01 -1.41403704e+01 -1.43329411e+01 -1.56110220e+01 -1.63313007e+01 -1.58300066e+01 -1.47018976e+01 -1.41803350e+01 -1.33487272e+01 -1.28904696e+01 -1.26071882e+01 -1.40727654e+01 -1.46146450e+01 -1.47746258e+01 -1.39766006e+01 -1.51038265e+01 -1.64487267e+01 -1.60121212e+01 -1.46743956e+01 -1.33337231e+01 -1.36432791e+01 -1.32617016e+01 -1.31582174e+01 -1.53190823e+01 -1.72408237e+01 -1.77362843e+01 -1.61298218e+01 -1.48551159e+01 -1.46342916e+01 -1.46615400e+01 -1.37697935e+01 -1.35961523e+01 -1.30202637e+01 -1.36000748e+01 -1.32848730e+01 -1.46010656e+01 -1.41762285e+01 -1.34638710e+01 -1.14134703e+01 -1.04566326e+01 -9.04393578e+00 -1.01150131e+01 -1.07031183e+01 -1.23476019e+01 -1.12603073e+01 -1.09927368e+01 -1.18203487e+01 -1.39727364e+01 -1.53696861e+01 -1.46375456e+01 -1.40195923e+01 -1.37181587e+01 -1.43839188e+01 -1.33543386e+01 -1.31159897e+01 -1.30526838e+01 -1.09565344e+01 -8.92704391e+00 -1.20523348e+01 -1.81363640e+01 -1.93998356e+01 -1.60279121e+01 -1.31757717e+01 -1.26758280e+01 -1.35307274e+01 -1.25989075e+01 -1.29399576e+01 -1.16156034e+01 -1.26583710e+01 -1.47590370e+01 -1.75920849e+01 -1.61869926e+01 -1.21308680e+01 -9.18920994e+00 -1.11149340e+01 -1.36924324e+01 -1.54534130e+01 -1.45026340e+01 -1.47140913e+01 -1.49407244e+01 -1.79104042e+01 -1.92919979e+01 -1.82508659e+01 -1.45937243e+01 -1.33711100e+01 -1.32508583e+01 -1.37708731e+01 -1.31913652e+01 -1.35685463e+01 -1.31245108e+01 -1.34897194e+01 -1.36232100e+01 -1.50635614e+01 -1.54772406e+01 -1.57977219e+01 -1.42026272e+01 -1.40877018e+01 -1.14109716e+01 -8.42301178e+00 -2.27038169e+00 -3.30448896e-01 -3.99383974e+00 -8.34398365e+00 -1.14981203e+01 -1.15393944e+01 -1.13997097e+01 -1.01246490e+01 -9.67327309e+00 -9.83106995e+00 -1.05866718e+01 -1.04587107e+01 -1.15027771e+01 -8.79836750e+00 -5.58433294e+00 -4.73462725e+00 -7.84145355e+00 -1.08903971e+01 -1.10488148e+01 -1.08069668e+01 -1.22114315e+01 -1.35699749e+01 -1.38396111e+01 -1.37156906e+01 -1.32378569e+01 -1.36253624e+01 -1.23538132e+01 -1.17972116e+01 -1.27982140e+01 -1.44296637e+01 -1.39733191e+01 -1.24320383e+01 -1.14466629e+01 -1.24592581e+01 -1.37716532e+01 -1.41364784e+01 -1.30613050e+01 -1.07688503e+01 -8.95637608e+00 -9.37871170e+00 -1.07406864e+01 -1.26200361e+01 -1.60718498e+01 -1.88078384e+01 -1.72928753e+01 -1.29776134e+01 -8.75806904e+00 -6.66487646e+00 -5.13250923e+00 -3.06005073e+00 -3.94122696e+00 -6.04789782e+00 -6.74556589e+00 -1.25631781e+01 -2.60873280e+01 -2.40873775e+01 -2.98041878e+01 -3.08094574e+02 -2.13640649e+03 -74487872. 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. 0. 0. 0. 0. 0. 0. -246017968. 136248832. -1.88674280e+03 -6.56216553e+02 -6.43630219e+01 -4.51408882e+01 -2.84656105e+01 -1.58028049e+01 -1.33662167e+01 -1.10118914e+01 -1.51060953e+01 -1.94939251e+01 -1.91510696e+01 -1.67498531e+01 -1.48203793e+01 -1.59631863e+01 -1.63334808e+01 -1.65904922e+01 -1.67858334e+01 -1.52034864e+01 -1.42356529e+01 -1.16596031e+01 -9.91070271e+00 -1.01691895e+01 -1.11104469e+01 -1.17181053e+01 -8.23998547e+00 -5.94547653e+00 -5.41321182e+00 -5.76563692e+00 -6.60874557e+00 -7.01117229e+00 -7.45881462e+00 -6.04726171e+00 -4.03304100e+00 -3.38748264e+00 -4.00098801e+00 -4.24868488e+00 -4.24809980e+00 -3.52954578e+00 -5.83632374e+00 -7.40951443e+00 -8.41713047e+00 -6.58083010e+00 -3.77129674e+00 -2.09626293e+00 -4.65728730e-01 -1.76831710e+00 3.10520381e-01 2.36270428e+00 3.10163736e+00 7.41349876e-01 -3.04715705e+00 -2.95659423e+00 -1.72455561e+00 -2.00615597e+00 -1.60293627e+00 -2.99241877e+00 -2.23817873e+00 -3.31253552e+00 -3.99087667e+00 -4.68265200e+00 -1.03136654e+01 -1.59613771e+01 -1.70965347e+01 -1.50831671e+01 -1.24599915e+01 -1.63990841e+01 -1.85865746e+01 -1.55864515e+01 -1.08352261e+01 -4.52321768e+00 -2.58263326e+00 -2.29728770e+00 1.15105832e+00 6.25735617e+00 9.78752232e+00 9.38243294e+00 4.13214970e+00 -9.21068564e-02 -2.49694943e+00 -3.99570608e+00 -2.29574966e+00 -6.66576862e+00 -1.00785389e+01 -1.63815022e+01 -1.83321629e+01 -1.63386116e+01 -1.18554039e+01 -7.41580868e+00 -7.28610563e+00 -8.40370941e+00 -1.37740746e+01 -1.83536396e+01 -1.69749794e+01 -1.11589346e+01 -6.35550165e+00 -6.88132763e+00 -8.34515381e+00 -1.02694550e+01 -1.31779957e+01 -7.98866653e+00 -7.64831185e-01 2.63877225e+00 8.93167078e-01 -4.61802292e+00 -4.13121367e+00 -6.26697493e+00 -9.53299809e+00 -1.24363756e+01 -1.63893890e+01 -1.44109926e+01 -9.01312351e+00 -2.20528078e+00 3.03589177e+00 2.04012156e+00 1.34195530e+00 -4.07027714e-02 3.51598233e-01 1.71042156e+00 2.08545589e+00 1.81653714e+00 2.98406035e-02 -7.51817584e-01 -2.39469838e+00 -2.62292480e+00 -2.95476604e+00 -4.00907516e+00 -9.73442173e+00 -1.58470039e+01 -1.55863686e+01 -1.03392096e+01 -4.74785995e+00 -7.29591608e+00 -1.05159988e+01 -1.61252460e+01 -1.82838364e+01 -1.56026249e+01 -8.75911808e+00 -2.48339963e+00 -1.02669644e+00 -1.30842745e+00 -1.02210546e+00 4.37024057e-01 1.40308547e+00 2.46074653e+00 1.28189635e+00 -6.95739210e-01 -1.57717478e+00 -7.02423215e-01 -1.95469245e-01 -5.96308708e-01 -2.59835458e+00 -8.63551235e+00 -1.49313059e+01 -1.33111153e+01 -7.16714191e+00 -1.06902885e+00 -7.30087948e+00 -1.26543856e+01 -1.72207928e+01 -1.80462513e+01 -1.91359768e+01 -1.91808262e+01 -1.28483572e+01 -7.79429579e+00 -2.23495579e+00 -2.11871958e+00 -7.61988163e-01 -1.28826320e-01 -2.35928178e+00 -2.53746009e+00 -2.45580602e+00 -2.15549159e+00 -4.16240311e+00 -3.74718785e+00 4.61368752e+00 1.22003183e+01 1.21940670e+01 4.80600452e+00 -1.07591712e+00 -3.11420631e+00 -2.37626433e+00 -1.66821671e+00 2.10125566e+00 -1.40221584e+00 -7.08665323e+00 -7.89085579e+00 -2.90745449e+00 1.68030202e+00 5.56200929e-02 -1.23824835e+00 -1.19208002e+00 -1.67114154e-01 -7.49550760e-01 -6.08608723e-01 -1.68018997e+00 -1.76485920e+00 -1.52281034e+00 -9.76401865e-01 -3.92860055e-01 3.45660019e+00 8.69650745e+00 8.34566975e+00 5.13278913e+00 7.03327835e-01 3.48169136e+00 2.99264669e+00 1.09664464e+00 -7.20066011e-01 -2.56482333e-01 1.10751688e+00 2.03034449e+00 1.87963629e+00 9.12930071e-01 -5.85736692e-01 1.00691766e-01 1.34677541e+00 1.60100520e+00 2.40488267e+00 2.48550034e+00 4.73085117e+00 4.88960552e+00 4.71176910e+00 3.84775782e+00 3.34637952e+00 6.45248985e+00 9.19064808e+00 1.00454130e+01 7.92373800e+00 5.20139742e+00 6.24373722e+00 5.82254267e+00 7.91322803e+00 9.10038471e+00 9.82312584e+00 8.85440063e+00 7.44545555e+00 9.01084042e+00 8.61928177e+00 7.18779802e+00 3.99856853e+00 1.77337825e+00 2.02025151e+00 7.68071651e+00 1.34247713e+01 1.52088461e+01 1.10663996e+01 -3.73055845e-01 -8.44004345e+00 -8.02721119e+00 -5.62077880e-01 5.16633892e+00 -2.20292234e+00 -7.81479883e+00 -6.97119474e+00 1.01794612e+00 7.23295975e+00 7.52201271e+00 7.34199190e+00 6.08451176e+00 4.59781647e+00 4.93857479e+00 6.09222364e+00 6.65036249e+00 3.90790009e+00 2.13041115e+00 4.44792843e+00 7.79191971e+00 8.53816032e+00 5.25140333e+00 1.76989365e+00 1.94902873e+00 2.32027864e+00 2.24378967e+00 2.35267591e+00 1.42196691e+00 2.46683025e+00 -2.66453195e+00 -4.71329069e+00 -3.97748518e+00 2.56817555e+00 8.02861214e+00 8.33959579e+00 6.37371206e+00 3.67798758e+00 4.00951767e+00 8.05533504e+00 1.32298193e+01 1.25885611e+01 9.35078716e+00 5.42580748e+00 7.77488947e+00 8.77370453e+00 9.04948235e+00 7.06904268e+00 1.78196800e+00 -3.51227212e+00 -3.90839458e+00 5.48762381e-01 6.70757771e+00 7.29938793e+00 6.47922611e+00 5.78364944e+00 5.56423330e+00 2.61719394e+00 -2.48418641e+00 -3.23663306e+00 -2.29120278e+00 2.92414260e+00 2.19181681e+00 4.01099873e+00 3.85702205e+00 5.43373442e+00 4.53979921e+00 3.44052124e+00 2.43235612e+00 3.32888412e+00 5.78604269e+00 6.14668036e+00 7.35898972e+00 8.21860027e+00 9.81524754e+00 8.91040707e+00 8.47076988e+00 7.54508638e+00 3.53045416e+00 -1.19728744e+00 -5.75411367e+00 -6.44382143e+00 -5.74585676e+00 -4.21870136e+00 2.63014650e+00 5.70279169e+00 9.66546345e+00 8.03494263e+00 9.21758842e+00 5.47321653e+00 7.03320742e-01 9.15851831e-01 4.18097210e+00 1.21814499e+01 1.61427441e+01 1.62906036e+01 1.35682802e+01 9.40703011e+00 9.28578281e+00 7.31796646e+00 2.57308078e+00 -1.39043784e+00 1.06719625e+00 7.04154587e+00 1.35401840e+01 1.02511806e+01 5.98789358e+00 3.56869411e+00 3.67794919e+00 6.84665489e+00 8.99761009e+00 1.34795618e+01 1.35404329e+01 1.28725023e+01 1.25079498e+01 1.25851669e+01 1.21641588e+01 1.24162903e+01 1.11809683e+01 1.05284929e+01 1.06834879e+01 1.12436857e+01 1.08629494e+01 5.21018887e+00 -3.79081070e-01 2.77541518e+00 1.08974152e+01 1.33045073e+01 7.18744230e+00 2.88007569e+00 5.21180201e+00 8.38642883e+00 5.08832645e+00 2.76244855e+00 2.04050279e+00 5.28765869e+00 8.98232841e+00 8.57913303e+00 7.88828135e+00 5.56040335e+00 6.65170860e+00 8.39951038e+00 1.01740942e+01 9.99597549e+00 9.60608006e+00 8.57700157e+00 8.83854008e+00 7.61554670e+00 6.25524855e+00 3.23900509e+00 7.36138487e+00 1.39569674e+01 1.29833956e+01 5.60900497e+00 1.55999434e+00 6.94271660e+00 1.06899757e+01 8.77227116e+00 6.53608751e+00 9.80559063e+00 1.41598177e+01 1.72728367e+01 1.61409969e+01 1.62554054e+01 1.25526352e+01 8.54144859e+00 8.23195553e+00 1.28330402e+01 1.32864819e+01 8.00174332e+00 7.47611332e+00 1.05845537e+01 1.50132742e+01 1.49797888e+01 1.49334049e+01 1.74546566e+01 1.92659683e+01 1.73150978e+01 1.22140064e+01 9.00891685e+00 1.06402674e+01 1.22897949e+01 1.22158270e+01 1.14680738e+01 1.15429163e+01 1.12077141e+01 1.22286482e+01 1.42027044e+01 1.48902531e+01 1.12360544e+01 7.41264105e+00 6.16468096e+00 7.94522333e+00 6.81304312e+00 2.59503913e+00 4.46623755e+00 9.97258377e+00 1.66303177e+01 1.71726322e+01 1.54569178e+01 1.58531170e+01 1.65789032e+01 1.51420660e+01 1.25849113e+01 1.09325657e+01 1.15880270e+01 1.28948097e+01 1.38349009e+01 1.55728064e+01 1.59245577e+01 1.44937458e+01 1.42827253e+01 1.45751085e+01 1.55582399e+01 1.26478090e+01 1.05992060e+01 1.13898392e+01 1.48135843e+01 1.50044336e+01 1.27097578e+01 1.31001253e+01 1.62547722e+01 1.58789883e+01 1.11963396e+01 5.25599051e+00 4.35615969e+00 6.41517353e+00 6.85807037e+00 6.21238470e+00 6.86139536e+00 9.75413799e+00 1.17946110e+01 1.16786470e+01 1.12950373e+01 1.02435589e+01 8.60327530e+00 8.90940571e+00 1.18908005e+01 1.51326780e+01 1.41918383e+01 1.12006531e+01 1.13468895e+01 1.32238388e+01 1.28127413e+01 9.39648533e+00 1.14301510e+01 1.72061806e+01 2.13902493e+01 1.94184608e+01 1.61859798e+01 1.71824951e+01 1.95497265e+01 2.04473362e+01 1.84367676e+01 1.68386917e+01 1.79312992e+01 1.85167198e+01 1.88139801e+01 1.69272614e+01 1.41134911e+01 1.06897249e+01 8.73207664e+00 8.39977837e+00 1.23890047e+01 1.57984657e+01 1.78723583e+01 1.59114723e+01 1.44448318e+01 1.44322863e+01 1.48422012e+01 1.65014362e+01 1.91563206e+01 1.85679226e+01 1.63502407e+01 1.41976385e+01 1.38948326e+01 1.38569069e+01 1.16909428e+01 1.03738251e+01 1.08028698e+01 1.24955502e+01 1.39462328e+01 1.39629393e+01 1.41673431e+01 1.42716331e+01 1.37195044e+01 1.32179737e+01 1.30690603e+01 1.36683369e+01 1.43033600e+01 1.50818014e+01 1.55135317e+01 1.52173653e+01 1.30593042e+01 1.04853592e+01 1.04769850e+01 1.21452570e+01 1.24667759e+01 1.12676363e+01 1.13150263e+01 1.26309853e+01 1.39464874e+01 1.26394339e+01 1.16764078e+01 1.22011232e+01 1.36586065e+01 1.59615965e+01 1.60118179e+01 1.58787479e+01 1.45582361e+01 1.30021524e+01 1.31991768e+01 1.41968374e+01 1.39989328e+01 1.24939184e+01 1.21434450e+01 1.33149929e+01 1.49885244e+01 1.40961809e+01 1.29697542e+01 1.31585331e+01 1.48701448e+01 1.62662563e+01 1.53188133e+01 1.41620750e+01 1.39719706e+01 1.40502672e+01 1.42947693e+01 1.40272541e+01 1.37104301e+01 1.36836567e+01 1.29878683e+01 1.27977304e+01 1.29491854e+01 1.38155012e+01 1.45219774e+01 1.45156345e+01 1.46487780e+01 1.47094755e+01 1.48442669e+01 1.47956038e+01 1.46114254e+01 1.48159618e+01 1.49531574e+01 1.51696253e+01 1.58534203e+01 1.63782425e+01 1.56549559e+01 1.44278946e+01 1.39591169e+01 1.48817167e+01 1.55024233e+01 1.56204481e+01 1.54989700e+01 1.54024515e+01 1.52697840e+01 1.49986334e+01 1.49069490e+01 1.47851486e+01 1.29658985e+01 9.91731834e+00 -1.65388832e+01 -1.63778412e+02 -40752616. 0. 0. 0. 0. 22237478. -42227944. 90862520. 16297160. 2.77294785e-01 -3.42984123e+01 -5.60767593e+01 -42711544. 0. 0.
================================================ FILE: config/m2dgr/ring32_M_7.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.10578227e+09 -5.11516750e+06 7.01195679e+02 2.66716797e+02 2.21020145e+01 -3.41211748e+00 -4.69468212e+00 -2.06839967e+00 -7.70714712e+00 -9.39793587e-02 8.72342587e+00 9.17176342e+00 7.20810223e+00 5.05704260e+00 1.85229635e+00 7.30749905e-01 -1.30416870e+00 1.52145612e+00 5.61498165e+00 9.60550785e+00 9.15071869e+00 2.11744976e+00 -4.50195122e+00 -8.85156059e+00 -9.25825500e+00 -4.93593121e+00 -4.03345823e+00 -3.61387014e+00 1.21251976e+00 4.04103136e+00 2.46347809e+00 -5.56232548e+00 -1.11630497e+01 -1.13936329e+01 -6.52159405e+00 1.88672292e+00 4.66362953e+00 4.06164694e+00 3.69359899e+00 3.64541912e+00 2.40020895e+00 -2.40666199e+00 -6.50123549e+00 -4.01304007e+00 7.82995641e-01 3.36918235e+00 -2.62913048e-01 -7.00109720e-01 2.83407301e-01 -2.02799988e+00 -1.92680466e+00 -1.68021786e+00 8.61986697e-01 4.19971943e+00 6.63720179e+00 7.33847427e+00 6.43667579e-01 -7.44274139e+00 -9.58809090e+00 -4.83426666e+00 4.06256819e+00 4.85214233e+00 1.24336302e+00 -2.80506706e+00 -1.97973537e+00 -3.15936238e-01 -1.30361164e+00 -2.84444976e+00 -2.74410939e+00 1.84420145e+00 7.33166742e+00 5.49478054e+00 3.89808464e+00 1.80583405e+00 4.72717345e-01 -1.61803409e-01 -1.79678333e+00 8.42422903e-01 5.00782442e+00 8.85848522e+00 8.79031849e+00 4.19357204e+00 -9.94300246e-01 -5.52403688e+00 -5.92181206e+00 -1.00799108e+00 1.14315736e+00 1.65887821e+00 4.78929472e+00 9.49841022e+00 9.39886951e+00 2.15604806e+00 -5.03498030e+00 -5.44350147e+00 1.10030389e+00 8.44040489e+00 9.10231686e+00 8.01552391e+00 8.39858723e+00 8.31644249e+00 6.86184263e+00 3.49101663e+00 1.53673434e+00 3.09953737e+00 6.19758654e+00 7.43063879e+00 4.75303793e+00 1.94005609e-01 -2.80948758e+00 -3.38249946e+00 1.25312781e+00 5.61993122e+00 5.01467896e+00 5.11482620e+00 6.98886633e+00 8.42857647e+00 5.58106470e+00 7.59285152e-01 7.01777220e-01 6.31055164e+00 1.13466043e+01 1.21733837e+01 7.94809818e+00 3.60328269e+00 -6.95683956e-01 -2.71138763e+00 -5.25753307e+00 -2.71181164e+01 -2.23590729e+02 -4.71761536e+02 3.55132725e+06 -4.16848775e+06 -5934468. 8995803. 5.37903687e+02 2.89024170e+02 5.83151703e+01 -6.58903408e+00 -3.96750679e+01 -2.27908249e+02 -4.21943481e+02 -31383032. 142039824. -4.23466850e+06 -70661560. -3.32204275e+06 4379297. -13451174. 9094321. 4.23635550e+06 -5.23359550e+06 4.68032318e+02 2.50168457e+02 4.90702095e+01 2.00801334e+01 6.77956760e-01 3.14148641e+00 8.80291462e-01 8.84113312e-01 1.66735435e+00 5.74180937e+00 7.95171690e+00 4.45952463e+00 6.77380681e-01 8.84270072e-01 1.51198554e+00 1.72004378e+00 -2.58097124e+00 -5.67328501e+00 -6.69422913e+00 -5.87508500e-01 7.05463171e+00 8.78747845e+00 8.36378288e+00 8.09116745e+00 7.49575949e+00 5.28805923e+00 5.02721429e-01 -1.16091144e+00 2.42668438e+00 7.03290653e+00 8.02275658e+00 4.24769163e+00 1.24917853e+00 5.20317972e-01 3.98100317e-02 8.57918978e-01 -4.89723951e-01 -4.59655553e-01 1.24274230e+00 1.71647561e+00 1.15965343e+00 -1.93259847e+00 -3.53051138e+00 -3.06481218e+00 2.77986145e+00 8.87972641e+00 9.86911869e+00 7.64843321e+00 6.85997391e+00 6.20204782e+00 4.57753897e+00 7.51004398e-01 4.28600430e-01 4.85724258e+00 9.49217892e+00 1.05891209e+01 6.89300680e+00 4.46608543e+00 4.15486431e+00 4.29474020e+00 4.48508358e+00 2.90377092e+00 1.21726000e+00 3.08009839e+00 6.06371355e+00 7.60660267e+00 5.10101557e+00 1.09370100e+00 8.27215314e-02 3.26110649e+00 6.79227018e+00 7.65855074e+00 6.32596874e+00 6.32739544e+00 5.88950682e+00 6.30756235e+00 6.63657713e+00 6.78641462e+00 6.91186762e+00 7.21559620e+00 8.88235188e+00 8.95684624e+00 8.48844719e+00 7.58659554e+00 4.41333055e+00 2.54300117e+00 4.15927052e-01 2.03591347e+00 4.56114149e+00 7.24452257e+00 9.13770866e+00 5.31417990e+00 2.11830211e+00 1.66796970e+00 5.37592888e+00 7.32256985e+00 5.97030401e+00 4.06196737e+00 5.87560797e+00 7.19776678e+00 6.39137650e+00 3.40691137e+00 2.04836464e+00 3.78291202e+00 3.54169917e+00 4.17460060e+00 4.18629074e+00 5.95118093e+00 4.81114483e+00 3.78364134e+00 2.69893765e+00 1.44853687e+00 1.62995195e+00 2.45062423e+00 5.55977535e+00 7.67438984e+00 5.90601969e+00 1.46251261e+00 -1.81021258e-01 1.85183239e+00 2.96704316e+00 1.92876971e+00 9.50533152e-01 3.50879455e+00 5.08544779e+00 5.48246145e+00 4.95233393e+00 5.16907740e+00 5.46107817e+00 4.13674307e+00 4.07729053e+00 5.41254711e+00 7.09090328e+00 6.49479914e+00 7.10797882e+00 8.66299438e+00 8.68449593e+00 6.23125410e+00 3.91041422e+00 4.17248249e+00 5.00529814e+00 4.74342346e+00 3.15803599e+00 3.98530936e+00 5.15881824e+00 5.16131830e+00 3.43532181e+00 2.27789664e+00 3.39088535e+00 3.85105157e+00 4.64217424e+00 4.28632355e+00 5.89792013e+00 7.16578627e+00 6.63518000e+00 5.49246693e+00 4.93448400e+00 5.97654581e+00 6.35487700e+00 7.07520533e+00 8.06991386e+00 7.77374601e+00 6.94063711e+00 5.92536068e+00 6.82132196e+00 7.94480133e+00 6.74022150e+00 4.18815422e+00 3.79754925e+00 5.42049170e+00 6.50322628e+00 4.90084028e+00 3.45562148e+00 4.35116768e+00 5.52302313e+00 6.84899664e+00 7.21651411e+00 8.10339928e+00 8.26035690e+00 7.42201424e+00 6.79477310e+00 6.66243362e+00 6.88386488e+00 6.39234066e+00 6.69618988e+00 7.59776831e+00 7.00572252e+00 5.24538422e+00 4.09606075e+00 4.58225203e+00 5.13975382e+00 4.53113937e+00 3.89900947e+00 4.69016027e+00 5.18772507e+00 5.26858330e+00 4.32041693e+00 4.61194897e+00 5.34521341e+00 5.37964439e+00 5.42315722e+00 5.66005898e+00 7.07146692e+00 7.47143459e+00 6.82152176e+00 5.73646355e+00 4.95112324e+00 5.23687363e+00 5.66914797e+00 6.44300747e+00 7.97010517e+00 7.71914148e+00 5.68507862e+00 3.31490326e+00 2.41285610e+00 3.73883843e+00 4.47580862e+00 4.44752979e+00 4.31850100e+00 3.71390820e+00 4.47048807e+00 4.58626509e+00 5.11902857e+00 5.01573801e+00 3.59388876e+00 3.20962715e+00 3.40002322e+00 5.37087250e+00 6.65421581e+00 5.89181137e+00 4.89137173e+00 4.48282623e+00 5.70797729e+00 6.69061613e+00 6.48700428e+00 6.35546589e+00 5.72844315e+00 5.18448544e+00 4.81236792e+00 4.44611359e+00 4.94310045e+00 5.43448973e+00 5.81733465e+00 5.83180618e+00 4.95549536e+00 4.43607569e+00 4.05768251e+00 4.56291914e+00 5.53255320e+00 5.59789610e+00 5.60295820e+00 5.67815447e+00 6.37518215e+00 6.30787420e+00 5.19088507e+00 4.54126549e+00 4.52783537e+00 5.12661028e+00 5.44635725e+00 5.48421431e+00 5.75894451e+00 5.72574615e+00 5.46114683e+00 5.26802778e+00 5.01534986e+00 5.17509651e+00 5.15456247e+00 5.19285488e+00 5.26314211e+00 5.30711126e+00 5.73337889e+00 5.82543707e+00 5.78385258e+00 5.64406252e+00 5.35639668e+00 5.30921936e+00 5.32959366e+00 5.65428829e+00 5.86327124e+00 5.84279299e+00 5.67997837e+00 5.54902887e+00 5.63499022e+00 5.74022675e+00 5.75869226e+00 5.73062038e+00 5.69987202e+00 5.68400574e+00 5.68418646e+00 5.69970655e+00 5.69183874e+00 5.66093731e+00 5.62729979e+00 5.65667343e+00 5.82328033e+00 5.93310547e+00 5.92638826e+00 5.73532391e+00 5.54674387e+00 5.63824940e+00 5.86894226e+00 6.01785707e+00 5.80904055e+00 5.52998686e+00 5.55913830e+00 5.69463158e+00 5.86018229e+00 5.81974411e+00 5.74766350e+00 5.88282728e+00 5.93840313e+00 5.92082071e+00 5.91951561e+00 5.83316278e+00 6.11799192e+00 6.01342535e+00 6.00115299e+00 5.84359503e+00 5.68695068e+00 6.04353762e+00 5.73491764e+00 5.48496103e+00 4.86608124e+00 5.07894278e+00 5.97875309e+00 6.63891792e+00 6.80570269e+00 5.77865934e+00 5.01496077e+00 4.82529402e+00 5.21245623e+00 5.87561941e+00 5.99388218e+00 5.56648970e+00 5.15976048e+00 4.64250326e+00 5.08452892e+00 5.89894962e+00 6.79152727e+00 6.88368130e+00 5.60568523e+00 4.65505552e+00 4.18365240e+00 4.62249756e+00 5.88502645e+00 6.83560753e+00 6.96803665e+00 5.61869097e+00 4.41610479e+00 4.87308073e+00 6.07014418e+00 6.96383476e+00 6.12488365e+00 4.72298908e+00 4.56215477e+00 4.96507788e+00 6.21358681e+00 6.90856171e+00 6.97696447e+00 6.83032846e+00 5.95009041e+00 5.17020130e+00 5.05964661e+00 5.36542892e+00 6.64505434e+00 6.45846033e+00 5.85823870e+00 5.27795744e+00 4.36316299e+00 5.31048250e+00 5.44827890e+00 5.52129936e+00 4.35834408e+00 3.99739981e+00 6.36851120e+00 7.74429035e+00 7.81029892e+00 5.42726135e+00 3.65613890e+00 3.63082695e+00 4.40761614e+00 6.10037327e+00 7.17402315e+00 7.16602659e+00 6.85732651e+00 5.79716015e+00 5.47323322e+00 5.86203337e+00 5.58112764e+00 5.81546688e+00 4.10360765e+00 4.02090597e+00 4.02724552e+00 4.43388319e+00 6.21565437e+00 6.27586412e+00 5.38743877e+00 2.73270583e+00 1.70428729e+00 2.50418544e+00 4.07999754e+00 5.63566589e+00 4.71034670e+00 2.83080578e+00 1.94452715e+00 2.51572895e+00 4.24897242e+00 5.12497330e+00 5.40202999e+00 5.56415129e+00 5.68091679e+00 5.85249901e+00 5.79115295e+00 6.59599209e+00 7.84247637e+00 6.59088707e+00 3.99578810e+00 2.71655631e+00 3.83014369e+00 6.75208807e+00 8.00167561e+00 7.42441750e+00 4.63518953e+00 2.94004822e+00 4.15574694e+00 5.33234882e+00 6.02174091e+00 4.97550106e+00 4.63817930e+00 5.64364004e+00 6.49777794e+00 7.52623415e+00 7.87589550e+00 7.44708252e+00 7.90530777e+00 6.60136700e+00 6.12567806e+00 6.07696438e+00 5.55144787e+00 6.86088324e+00 5.86422968e+00 6.06929159e+00 4.85328007e+00 4.19638395e+00 6.43197060e+00 6.34585476e+00 6.66307783e+00 4.43801498e+00 3.47318482e+00 5.02850819e+00 5.76627922e+00 8.82533932e+00 7.65955257e+00 5.22562265e+00 2.56571245e+00 1.86988437e+00 5.20467758e+00 5.68424606e+00 4.99055958e+00 5.14401102e+00 6.01897526e+00 6.62951899e+00 3.34961987e+00 2.31324553e+00 5.52666950e+00 6.85795212e+00 6.70642996e+00 1.31014478e+00 1.26703525e+00 -1.16049223e+01 -1.73756123e+01 -2.14717209e+02 -6.15338928e+02 16171671. 235114896. 8265405. 6.00705350e+06 -247559168. 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. 0. 0. 0. 0. 0. 0. 0. -213221008. -1.42785364e+03 -2.36642105e+02 -4.11480942e+01 -1.36156464e+01 -4.28868055e-01 7.34063911e+00 9.00866795e+00 9.93142414e+00 5.90546894e+00 4.28862906e+00 4.55357552e+00 4.18767691e+00 5.70491934e+00 6.65556765e+00 6.47666454e+00 4.59536362e+00 2.97856188e+00 4.17386723e+00 6.03832054e+00 6.87060356e+00 7.58429003e+00 7.07324505e+00 6.24598026e+00 3.68158937e+00 2.51641369e+00 6.35195446e+00 7.65841198e+00 5.48501301e+00 6.69263542e-01 2.38233566e+00 6.95862007e+00 8.16171074e+00 6.24626780e+00 3.67916465e+00 3.65956664e+00 4.19526958e+00 4.05538559e+00 4.86741638e+00 5.96274519e+00 6.36686373e+00 5.38428116e+00 3.03971243e+00 4.71270466e+00 6.23715830e+00 8.90420055e+00 1.22809010e+01 1.07147512e+01 4.86866283e+00 -2.88245821e+00 -2.90049362e+00 3.75700998e+00 5.49416256e+00 4.40063667e+00 -3.70490134e-01 -1.27385139e-01 3.21088815e+00 4.85106277e+00 5.89894295e+00 4.08691168e+00 4.44432449e+00 5.33035707e+00 5.73957109e+00 8.45308590e+00 1.07250147e+01 1.04598236e+01 7.34663343e+00 4.39211941e+00 5.45870829e+00 6.74541712e+00 9.31599236e+00 1.23540192e+01 1.39423895e+01 1.43146734e+01 1.07751760e+01 8.55309868e+00 1.00172815e+01 7.49399853e+00 3.84596276e+00 -3.18511939e+00 -2.28974438e+00 2.70217228e+00 4.80393696e+00 6.29296303e+00 6.34536552e+00 6.54438448e+00 4.81363010e+00 2.24461746e+00 3.89920616e+00 5.67042494e+00 5.19158506e+00 5.32054663e+00 6.62798309e+00 9.94349957e+00 8.55657768e+00 5.25900459e+00 7.52086830e+00 7.32376671e+00 7.19402742e+00 2.77837896e+00 1.82097864e+00 7.11721516e+00 7.24490404e+00 4.88933611e+00 -1.95226073e+00 -3.13620114e+00 1.82979691e+00 4.03316212e+00 6.86307049e+00 7.15668726e+00 8.71047974e+00 9.08269691e+00 6.56257248e+00 6.49208784e+00 6.91315126e+00 7.47048473e+00 6.13510752e+00 2.84042239e+00 3.78942227e+00 3.84962130e+00 2.85650182e+00 5.64257479e+00 5.54573774e+00 4.08395576e+00 -2.34223485e+00 -3.04331994e+00 4.45950222e+00 6.91178322e+00 3.79316068e+00 -2.45488667e+00 -2.88603950e+00 2.88137960e+00 4.75485134e+00 6.27624035e+00 5.85614538e+00 4.31436872e+00 1.72942436e+00 -1.71839452e+00 1.16237676e+00 4.46675158e+00 4.84221601e+00 2.61190152e+00 -9.19850469e-01 1.41676688e+00 2.94946861e+00 3.47268987e+00 5.71766663e+00 6.35314465e+00 8.19062996e+00 7.02262115e+00 6.28864336e+00 8.27676678e+00 7.46318007e+00 5.66634274e+00 -3.23690563e-01 -4.09468842e+00 -2.67991686e+00 -4.86370564e-01 3.55471063e+00 4.45875168e+00 6.33136654e+00 8.43972111e+00 8.70021057e+00 7.37021112e+00 6.49991369e+00 7.09500933e+00 8.70936203e+00 5.86013317e+00 5.48532009e-01 -3.90772176e+00 -5.18991709e+00 2.00776148e+00 4.41201401e+00 2.89847064e+00 -1.43449652e+00 -6.93942726e-01 3.31562567e+00 2.85585642e+00 3.89814925e+00 4.14810848e+00 4.29819584e+00 2.17226076e+00 3.09636921e-01 2.81716490e+00 5.10390282e+00 4.36325502e+00 4.54463720e+00 5.22754526e+00 7.81137705e+00 1.09288597e+01 1.30394897e+01 1.48460064e+01 8.16851807e+00 3.11716151e+00 -1.13179348e-02 2.76515096e-01 5.15966225e+00 4.53657675e+00 2.50644326e+00 -4.68087626e+00 -4.57138681e+00 6.61186278e-01 5.30412722e+00 7.36717319e+00 5.69140673e+00 7.30409384e+00 9.14405441e+00 8.58440685e+00 7.23878717e+00 6.86321545e+00 7.31571198e+00 5.74648380e+00 2.28383565e+00 2.20472908e+00 -1.21154487e+00 -1.21822643e+00 4.67838669e+00 1.07800045e+01 1.03827400e+01 3.45936918e+00 4.86034781e-01 1.57609761e+00 -7.83581734e-01 -3.79336953e+00 -6.76483536e+00 -7.99997044e+00 -4.65101862e+00 -1.55399561e+00 4.13353539e+00 5.51068306e+00 1.63992643e+00 -2.87806129e+00 -3.96180916e+00 -5.18488109e-01 1.41388392e+00 1.64020956e-01 2.86550075e-01 -7.25970641e-02 -2.96558142e-01 -7.25913346e-01 -6.63602725e-02 9.42889228e-02 5.00823915e-01 1.02239490e-01 -7.94875026e-01 -2.72452140e+00 -3.44108009e+00 -2.30427313e+00 -6.15325451e-01 -3.69892567e-01 -1.24462402e+00 -8.07477713e-01 -5.44211209e-01 2.09477568e+00 3.58136296e+00 3.61521959e+00 1.30427849e+00 -1.57026398e+00 -8.52530956e-01 -6.21925354e-01 -7.83903375e-02 -3.07847559e-01 9.09154356e-01 6.18684053e-01 3.98202926e-01 -7.09283113e-01 -3.61530751e-01 -1.41658092e+00 -2.34924412e+00 -2.03656292e+00 -1.43991601e+00 -2.20808768e+00 -2.61929131e+00 -2.39457440e+00 -1.85756195e+00 -2.15604687e+00 -1.99381709e+00 -9.86303508e-01 -1.60686362e+00 -2.20323706e+00 -2.35996270e+00 -1.28720355e+00 -1.33703506e+00 -2.45054650e+00 -3.30503654e+00 -2.78176236e+00 -3.34798884e+00 -4.19179916e+00 -4.62014008e+00 -3.24722672e+00 -2.23865485e+00 -2.14685202e+00 -2.40915036e+00 -2.42138362e+00 -2.58084297e+00 -1.97284842e+00 -1.99305043e-01 1.43340349e+00 1.21190000e+00 -3.66187915e-02 -9.55619037e-01 -1.47622514e+00 -1.38131726e+00 -1.26371694e+00 -9.47437346e-01 -1.45942295e+00 -1.61774075e+00 -1.20341146e+00 -1.31110585e+00 -3.08564520e+00 -4.41695881e+00 -4.39286900e+00 -2.83505011e+00 -1.86955309e+00 -9.93694901e-01 4.36589401e-03 9.72727314e-02 -8.08001757e-01 -2.00910020e+00 -1.86780274e+00 -6.57604516e-01 -1.89789987e+00 -4.11138010e+00 -4.58847237e+00 -2.91120434e+00 -5.80807984e-01 -5.63589454e-01 -3.17783087e-01 -2.31577680e-02 -1.78510964e+00 -4.53216171e+00 -5.60404301e+00 -4.71301031e+00 -2.79584932e+00 -2.67115784e+00 -2.45889783e+00 -2.00113583e+00 -1.68364048e+00 -1.45205760e+00 -1.64628732e+00 -1.59824848e+00 -2.38227630e+00 -2.51992488e+00 -1.82440770e+00 -4.04426962e-01 1.49056733e+00 2.44760823e+00 2.02869630e+00 3.90925735e-01 -8.47690344e-01 -1.80106498e-02 4.25084591e-01 -1.07578897e+00 -3.28080893e+00 -4.53639507e+00 -2.74634600e+00 -9.56384242e-01 -1.30736426e-01 -1.28880501e+00 -1.96785152e+00 -2.04661202e+00 -1.68060434e+00 6.14544928e-01 2.66465211e+00 -6.92654967e-01 -6.47618198e+00 -7.92843962e+00 -5.11001968e+00 -1.72564709e+00 -2.03207445e+00 -2.36878443e+00 -2.85221076e+00 -2.55163383e+00 -2.08519244e+00 -2.45159793e+00 -4.16459131e+00 -6.14336014e+00 -4.71173382e+00 -1.13571632e+00 1.29844809e+00 -4.05052423e-01 -2.95328331e+00 -4.06446075e+00 -3.98043466e+00 -4.06669235e+00 -4.67659521e+00 -6.46546221e+00 -7.68143034e+00 -6.38736200e+00 -4.27915239e+00 -3.50068617e+00 -4.45172834e+00 -4.45356846e+00 -3.43700814e+00 -3.36685085e+00 -3.64355779e+00 -3.88186812e+00 -4.25519276e+00 -4.83093309e+00 -5.64439297e+00 -4.70973158e+00 -3.85882282e+00 -3.30457950e+00 -2.18989611e+00 -2.44481698e-01 2.43402910e+00 3.58145547e+00 1.68016720e+00 -6.72972918e-01 -2.32772470e+00 -2.45401740e+00 -2.27793622e+00 -1.65878761e+00 -1.65187621e+00 -2.16261697e+00 -2.71697068e+00 -2.92098832e+00 -3.28961492e+00 -1.95068669e+00 -1.74853593e-01 3.46967638e-01 -1.31786335e+00 -3.44903708e+00 -3.66016507e+00 -3.77788925e+00 -4.08936977e+00 -4.86298370e+00 -5.04505014e+00 -4.66352844e+00 -4.02364254e+00 -3.45484757e+00 -3.22386146e+00 -3.39118242e+00 -4.81674862e+00 -5.55313063e+00 -5.54639196e+00 -5.05972290e+00 -4.46342659e+00 -4.75346899e+00 -5.25653267e+00 -5.64731312e+00 -5.20613289e+00 -4.15280914e+00 -3.27386403e+00 -3.02499580e+00 -3.29241467e+00 -4.28003168e+00 -5.52346516e+00 -6.12465763e+00 -4.90697718e+00 -3.69484401e+00 -2.90953135e+00 -2.65408444e+00 -2.07243848e+00 -1.51621437e+00 -1.88080990e+00 -1.92907727e+00 -6.84825325e+00 -1.64963112e+01 -3.05463409e+01 -1.64675293e+01 -2.05337433e+02 -1.09512488e+03 30641686. 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. 0. 0. 0. 0. 0. 0. 2.02376758e+04 -1.30890320e+02 -2.50810089e+01 -1.42645960e+01 -2.60341191e+00 -1.96548355e+00 -1.53889215e+00 -5.27680445e+00 -3.92426157e+00 -3.47100067e+00 -3.84042406e+00 -5.85618353e+00 -8.00586128e+00 -8.40532970e+00 -7.71567059e+00 -6.86207199e+00 -7.34355068e+00 -7.45540285e+00 -7.40580177e+00 -7.09832144e+00 -6.72417831e+00 -6.75550413e+00 -6.32301188e+00 -5.65638924e+00 -5.38226414e+00 -5.49087191e+00 -5.78789186e+00 -5.11111784e+00 -4.71016645e+00 -4.39397907e+00 -4.35145235e+00 -4.57876778e+00 -4.58974028e+00 -4.74154043e+00 -4.35315228e+00 -4.15757656e+00 -4.01544380e+00 -4.42774820e+00 -4.39840126e+00 -4.31833839e+00 -3.99789023e+00 -4.56878424e+00 -4.99269247e+00 -5.19085121e+00 -4.82718468e+00 -4.38376236e+00 -4.01864767e+00 -3.61621022e+00 -3.96039510e+00 -3.66144300e+00 -3.51939678e+00 -3.34990501e+00 -3.89391971e+00 -4.60866880e+00 -4.55136204e+00 -4.31666708e+00 -4.36499643e+00 -4.45447683e+00 -4.55096817e+00 -4.40037632e+00 -4.35504532e+00 -4.61522293e+00 -4.66971397e+00 -5.93869305e+00 -7.00083685e+00 -7.33304548e+00 -7.02339411e+00 -6.65514183e+00 -7.40956450e+00 -7.86162519e+00 -7.19091034e+00 -6.36852264e+00 -5.30126810e+00 -5.06157446e+00 -4.86543083e+00 -4.17741060e+00 -3.36878681e+00 -2.63882089e+00 -2.73782015e+00 -3.66113544e+00 -4.45714140e+00 -4.98936415e+00 -5.11561871e+00 -5.03685188e+00 -5.84294462e+00 -6.56097603e+00 -7.53465796e+00 -7.73343515e+00 -7.34624481e+00 -6.63862705e+00 -5.90526438e+00 -5.77732944e+00 -5.95348692e+00 -6.73928308e+00 -7.36063290e+00 -7.04498243e+00 -6.27550554e+00 -5.69170666e+00 -5.83655453e+00 -6.09533978e+00 -6.28417635e+00 -6.55588388e+00 -5.78149271e+00 -4.96477938e+00 -4.56712914e+00 -4.90854883e+00 -5.53613472e+00 -5.52509022e+00 -5.69617987e+00 -6.06172705e+00 -6.36461735e+00 -6.85564280e+00 -6.79387951e+00 -6.20157528e+00 -5.41503716e+00 -4.71061039e+00 -4.78481770e+00 -4.97630692e+00 -5.22001886e+00 -5.30333185e+00 -5.14877844e+00 -5.09993553e+00 -5.16060066e+00 -5.32569265e+00 -5.44742346e+00 -5.55830097e+00 -5.59091520e+00 -5.59428596e+00 -5.65044546e+00 -6.15791893e+00 -6.65953112e+00 -6.65844965e+00 -6.28095961e+00 -5.84060001e+00 -6.08686256e+00 -6.34970999e+00 -6.73214483e+00 -6.79143476e+00 -6.49686241e+00 -6.04717255e+00 -5.65245438e+00 -5.55302000e+00 -5.55399799e+00 -5.53754616e+00 -5.52378035e+00 -5.47318363e+00 -5.43534327e+00 -5.47142315e+00 -5.59149075e+00 -5.64191103e+00 -5.61428690e+00 -5.61739588e+00 -5.66467094e+00 -5.76949692e+00 -5.98080397e+00 -6.18641090e+00 -6.13008881e+00 -5.91290140e+00 -5.70937777e+00 -5.86805010e+00 -6.02135515e+00 -6.11931705e+00 -6.10176945e+00 -6.10282755e+00 -6.08867359e+00 -5.95850134e+00 -5.86459160e+00 -5.74428368e+00 -5.72386360e+00 -5.69558907e+00 -5.68790340e+00 -5.70765066e+00 -5.70434713e+00 -5.70176554e+00 -5.69397688e+00 -5.69526052e+00 -5.68768644e+00 -5.68411207e+00 -5.70770502e+00 -5.72931767e+00 -5.71354485e+00 -5.67984009e+00 -5.66331625e+00 -5.65560770e+00 -5.67131662e+00 -5.71485853e+00 -5.66677904e+00 -5.55156755e+00 -5.51437616e+00 -5.58936930e+00 -5.69949865e+00 -5.66761446e+00 -5.62906837e+00 -5.60931683e+00 -5.64041281e+00 -5.62450743e+00 -5.61589098e+00 -5.57479334e+00 -5.56505680e+00 -5.55606604e+00 -5.55287075e+00 -5.55382347e+00 -5.74274158e+00 -5.97361803e+00 -5.98638821e+00 -5.82377625e+00 -5.58549547e+00 -5.70221949e+00 -5.68232059e+00 -5.58890486e+00 -5.51049709e+00 -5.48261261e+00 -5.55018759e+00 -5.56833315e+00 -5.59872389e+00 -5.56420803e+00 -5.48949289e+00 -5.53680134e+00 -5.61047888e+00 -5.62058973e+00 -5.63970613e+00 -5.63000154e+00 -5.75560427e+00 -5.72012043e+00 -5.66550827e+00 -5.61552238e+00 -5.67322683e+00 -6.02467823e+00 -6.28154135e+00 -6.29120636e+00 -6.08518410e+00 -5.80076647e+00 -5.91262197e+00 -5.83010674e+00 -6.00817871e+00 -6.13285208e+00 -6.19402361e+00 -6.07334805e+00 -5.89415359e+00 -6.09338951e+00 -6.15326643e+00 -6.11052370e+00 -5.80224085e+00 -5.51838589e+00 -5.46673775e+00 -5.98992062e+00 -6.61654186e+00 -6.84381342e+00 -6.35563517e+00 -4.86078262e+00 -3.84206247e+00 -3.85439682e+00 -4.73303604e+00 -5.41909075e+00 -4.57406521e+00 -3.94382787e+00 -4.09095526e+00 -5.03321791e+00 -5.74949121e+00 -5.73383856e+00 -5.69809198e+00 -5.61616755e+00 -5.48731661e+00 -5.61877537e+00 -5.74998665e+00 -5.71880293e+00 -5.39766550e+00 -5.03803968e+00 -5.53546953e+00 -6.00812864e+00 -6.17358303e+00 -5.45162487e+00 -4.88147831e+00 -4.83165407e+00 -4.85979700e+00 -4.81016779e+00 -4.82389450e+00 -4.68411064e+00 -4.77751255e+00 -4.12889385e+00 -3.66432476e+00 -3.85556746e+00 -4.78229713e+00 -5.76456690e+00 -5.81239700e+00 -5.57830381e+00 -5.13395166e+00 -4.92981863e+00 -5.69444895e+00 -6.76163578e+00 -6.76622343e+00 -5.96052074e+00 -4.97124863e+00 -5.33396816e+00 -5.40797472e+00 -5.38406801e+00 -5.11012650e+00 -4.07365990e+00 -2.95599508e+00 -2.96895742e+00 -3.85060501e+00 -5.25351334e+00 -5.25596857e+00 -5.18247938e+00 -5.08973598e+00 -5.06539154e+00 -4.25722742e+00 -2.97698522e+00 -2.68782306e+00 -3.17305756e+00 -4.40770245e+00 -4.31699562e+00 -4.51048088e+00 -4.57703161e+00 -4.92129517e+00 -4.68618250e+00 -4.30625629e+00 -3.87332106e+00 -4.18165159e+00 -4.56857586e+00 -4.84119177e+00 -4.82435036e+00 -5.15026569e+00 -5.55157852e+00 -5.85952711e+00 -6.14569712e+00 -5.84700918e+00 -4.42089415e+00 -2.52289915e+00 -1.25962901e+00 -9.41817582e-01 -1.10824025e+00 -1.49058914e+00 -3.60107040e+00 -4.57068682e+00 -5.58610487e+00 -5.07778692e+00 -5.07827234e+00 -3.99330068e+00 -2.48885322e+00 -2.83664131e+00 -3.53105378e+00 -5.87502623e+00 -7.08565426e+00 -7.46249676e+00 -6.59885645e+00 -5.14597464e+00 -4.71481514e+00 -3.84593916e+00 -2.16744876e+00 -1.11369383e+00 -2.04441619e+00 -3.90907741e+00 -6.02351236e+00 -4.85301685e+00 -3.30606389e+00 -2.31551003e+00 -2.52725816e+00 -3.79390216e+00 -4.69382191e+00 -6.17019033e+00 -6.19173956e+00 -5.87229300e+00 -5.87185144e+00 -5.89380312e+00 -5.80867815e+00 -5.63352013e+00 -5.29411936e+00 -5.19603157e+00 -5.01735210e+00 -4.79258776e+00 -4.30238771e+00 -2.45480752e+00 -3.41530442e-01 -1.77499628e+00 -4.63033295e+00 -5.39949799e+00 -2.28721189e+00 -5.47118247e-01 -1.51738000e+00 -3.30677366e+00 -1.99918807e+00 -8.79859567e-01 -6.81217611e-01 -2.00876188e+00 -3.69429183e+00 -3.59977531e+00 -3.29572558e+00 -2.31780910e+00 -2.36514902e+00 -2.83399034e+00 -3.74484944e+00 -4.05499125e+00 -4.04144764e+00 -3.31094217e+00 -3.20257354e+00 -2.54948068e+00 -1.79507756e+00 -2.09904820e-01 -2.21739984e+00 -5.65047503e+00 -5.41736603e+00 -1.95058656e+00 2.83226371e-01 -2.12779832e+00 -3.90813279e+00 -2.97570062e+00 -1.83695114e+00 -3.32610464e+00 -5.87558460e+00 -7.29389524e+00 -6.69540405e+00 -6.17450142e+00 -4.45684004e+00 -2.19219398e+00 -2.03738070e+00 -4.27952147e+00 -4.61661577e+00 -1.58349037e+00 -1.19883132e+00 -3.02681899e+00 -5.68492365e+00 -5.66484690e+00 -5.46495962e+00 -6.72386980e+00 -8.13583946e+00 -6.64497042e+00 -3.76754904e+00 -1.43731368e+00 -2.59493065e+00 -3.47499561e+00 -3.45356226e+00 -3.36574769e+00 -3.26239920e+00 -3.21940589e+00 -3.49700308e+00 -4.79647827e+00 -4.74430418e+00 -3.01837850e+00 -6.85185671e-01 -1.27402335e-01 -1.02382827e+00 2.02442810e-01 2.83875632e+00 1.64314795e+00 -2.20810270e+00 -6.35044336e+00 -6.75858307e+00 -5.08681726e+00 -5.34712362e+00 -5.78567886e+00 -5.44186401e+00 -3.83855438e+00 -2.12068248e+00 -2.19581819e+00 -3.04763937e+00 -3.73489785e+00 -5.20789623e+00 -5.54147768e+00 -5.25657225e+00 -4.86182594e+00 -4.91677904e+00 -5.05699348e+00 -2.84407830e+00 -1.23489690e+00 -2.03153086e+00 -4.07488966e+00 -4.64570141e+00 -2.99351788e+00 -4.05505180e+00 -6.14515257e+00 -5.55438042e+00 -9.51579452e-01 4.27957964e+00 5.18160486e+00 3.34701920e+00 2.48348093e+00 3.30364418e+00 2.42493820e+00 7.97402263e-01 -7.18219161e-01 -2.47911379e-01 -4.47559208e-01 1.60924554e-01 1.89477539e+00 1.82492125e+00 -4.69500721e-01 -3.75265694e+00 -2.45414519e+00 4.98066604e-01 1.04609549e+00 -1.68180215e+00 -1.64290524e+00 1.00622153e+00 -8.57725501e-01 -6.62955332e+00 -1.04554920e+01 -8.18387413e+00 -4.91098976e+00 -5.98730183e+00 -8.50978470e+00 -9.04237175e+00 -7.17706871e+00 -5.91011477e+00 -7.35307121e+00 -8.04007244e+00 -7.32391024e+00 -5.14632893e+00 -1.78260958e+00 1.84579349e+00 3.79016066e+00 3.81627011e+00 -1.15442717e+00 -5.27933979e+00 -7.31463099e+00 -4.81481552e+00 -2.79709816e+00 -2.81692195e+00 -3.12837577e+00 -4.82720232e+00 -7.99801779e+00 -7.20817995e+00 -4.28602219e+00 -1.21893263e+00 -1.20988655e+00 -1.16837502e+00 1.90239275e+00 4.32308626e+00 3.77935600e+00 9.20263231e-01 -1.16334724e+00 -1.32937729e+00 -1.57765055e+00 -1.71401024e+00 -7.64542222e-01 -9.12772305e-03 -1.38108939e-01 -1.09717667e+00 -1.76415908e+00 -2.28811526e+00 -2.37238359e+00 -1.89483881e+00 9.18943167e-01 4.72718430e+00 4.73615074e+00 2.55886316e+00 1.98084986e+00 4.46661663e+00 4.14526367e+00 2.03256869e+00 -2.89801449e-01 2.49374247e+00 4.98319149e+00 4.17105341e+00 1.18719923e+00 -3.10083747e+00 -3.37231541e+00 -3.29079247e+00 -6.63727820e-01 2.24411154e+00 2.54148078e+00 1.13384694e-01 3.78876358e-01 3.45615745e+00 4.22116995e+00 1.91281140e+00 -1.63354981e+00 6.96835220e-01 3.66720057e+00 3.36863923e+00 -1.02317631e+00 -4.51252794e+00 -2.61804867e+00 9.56695378e-01 1.67113626e+00 1.68937862e+00 6.33233011e-01 8.55760396e-01 1.61963081e+00 1.90888369e+00 4.86843967e+00 6.41622829e+00 5.74756002e+00 3.30564833e+00 6.78811908e-01 9.65496302e-01 6.00242972e-01 5.99366307e-01 7.05547929e-01 2.32163221e-01 5.36985219e-01 -1.33948192e-01 -8.24735686e-02 -7.47437894e-01 -3.77897859e+00 -6.07269812e+00 -3.00095916e+00 2.54717255e+00 4.66524887e+00 1.17524004e+00 -1.77585363e+00 -1.89067090e+00 -1.54391444e+00 -1.21144354e+00 -1.61288011e+00 -6.74088001e-01 -8.28462243e-02 5.58476448e-01 2.33747125e+00 5.91212130e+00 1.72822819e+01 4.11068115e+01 2.61785221e+01 1.70237217e+01 3.49541290e+02 9.56964355e+02 -3.33246656e+05 652480832. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.21156454e+09 -10230335. 1.40187463e+03 8.91628563e-01 -1.19857407e+02 -3.02955780e+01 -2.03149567e+01 -8.30418396e+00 -3.44912267e+00 -5.70313394e-01 1.05757666e+00 1.28484881e+00 9.23941433e-01 5.27469397e-01 4.68256027e-02 -3.50969099e-03 -2.53926545e-01 2.91333914e-01 9.62750912e-01 1.61597478e+00 1.58093703e+00 5.73838770e-01 -3.57369155e-01 -1.01847780e+00 -1.13666153e+00 -4.87500221e-01 -3.63081098e-01 -2.15910733e-01 4.79341477e-01 8.60309899e-01 6.62218690e-01 -4.71695185e-01 -1.23342383e+00 -1.28337467e+00 -6.48267865e-01 5.20079136e-01 9.37658787e-01 8.89334738e-01 8.16332340e-01 7.65156984e-01 5.77365458e-01 -1.63272470e-01 -7.62111068e-01 -3.26337457e-01 4.60113078e-01 8.80305290e-01 4.13560361e-01 5.08791208e-01 7.59508729e-01 4.38539654e-01 3.06809485e-01 2.97146142e-01 6.01058543e-01 1.04548788e+00 1.32640123e+00 1.42137587e+00 4.84403551e-01 -7.34941065e-01 -1.00321352e+00 -3.21954489e-01 9.89348471e-01 1.12478745e+00 3.63726467e-01 -6.57719910e-01 -5.58649659e-01 3.32258306e-02 3.15980643e-01 7.64114410e-02 8.91736969e-02 7.90550232e-01 1.73299861e+00 1.38305163e+00 1.10484529e+00 8.85678530e-01 8.33920121e-01 8.68570507e-01 4.39495713e-01 7.64185548e-01 1.17598712e+00 1.80634606e+00 1.83515489e+00 1.16248631e+00 3.23033035e-01 -3.37617218e-01 -4.37070698e-01 3.31345469e-01 5.14549851e-01 6.52397811e-01 1.16527069e+00 1.94875038e+00 2.03941798e+00 9.64952946e-01 -1.06349140e-02 -9.92461480e-03 1.04241812e+00 2.09472680e+00 2.21136618e+00 2.05713725e+00 2.07318115e+00 2.13275123e+00 1.87236118e+00 1.42770958e+00 1.14624846e+00 1.40904534e+00 1.93505478e+00 2.59289026e+00 2.77440476e+00 2.06685758e+00 1.01217496e+00 1.59639433e-01 7.80309021e-01 1.60508657e+00 1.78929520e+00 1.81108510e+00 1.99334419e+00 1.95732403e+00 1.69796336e+00 1.29274869e+00 1.41441607e+00 2.13188100e+00 2.55393052e+00 2.77075934e+00 2.22643900e+00 1.68681574e+00 9.23630953e-01 5.02533257e-01 -2.80750918e+00 -2.00728912e+01 -1.58331528e+02 -2.85140350e+02 -1.55255833e+01 -1.56808262e+01 -4.15312767e+00 9.95179749e+00 3.28048553e+02 1.97400681e+02 4.07782860e+01 -7.56681871e+00 -3.19770088e+01 -1.62127686e+02 -2.68458313e+02 -8.18006516e+00 4.79857349e+00 2.52961750e+01 3.73847847e+01 3.20680122e+01 2.28051777e+01 1.92998390e+01 1.26473274e+01 1.01131449e+01 1.38951607e+01 2.82187439e+02 1.77031845e+02 3.86557007e+01 1.60009060e+01 -4.00144517e-01 5.04623175e-01 2.92726427e-01 2.11991882e+00 1.55082357e+00 2.19680977e+00 2.53652024e+00 2.05118489e+00 1.57216644e+00 1.48825955e+00 1.43407559e+00 1.36789143e+00 8.77934456e-01 5.49033344e-01 5.61625540e-01 1.43966842e+00 2.44377613e+00 2.62018228e+00 2.56964874e+00 2.62218547e+00 2.53482890e+00 2.36093473e+00 1.62065017e+00 1.43742990e+00 1.80193985e+00 2.56838298e+00 2.69203210e+00 2.22643685e+00 1.96344995e+00 1.79802287e+00 1.77727747e+00 1.75255752e+00 1.75526929e+00 1.68259728e+00 1.89714098e+00 1.75088906e+00 1.43897426e+00 6.46928191e-01 1.61642492e-01 5.29468119e-01 1.74235928e+00 2.93551660e+00 3.03958178e+00 2.74037957e+00 2.63737440e+00 2.54262376e+00 2.25477099e+00 1.59567082e+00 1.48285067e+00 2.18382335e+00 3.01617408e+00 3.22297049e+00 2.69800830e+00 2.29126811e+00 2.31930900e+00 2.29056573e+00 2.39269948e+00 2.22368240e+00 1.98293734e+00 2.23363328e+00 2.63429689e+00 3.04829645e+00 2.45021677e+00 2.02677989e+00 1.56452715e+00 2.31333780e+00 2.71743274e+00 2.93707442e+00 2.66765213e+00 2.50483823e+00 2.34999251e+00 2.32211542e+00 2.47556996e+00 2.72571969e+00 2.82471490e+00 2.85901403e+00 3.13762641e+00 3.24042559e+00 3.37779236e+00 2.96480989e+00 2.43366599e+00 1.89795077e+00 1.72490990e+00 1.92705560e+00 2.40494561e+00 2.91988420e+00 3.42253566e+00 2.63982511e+00 1.99833512e+00 1.81632400e+00 2.59959745e+00 3.17278600e+00 3.00482249e+00 2.80512953e+00 3.05531478e+00 3.16005516e+00 2.96279216e+00 2.42644906e+00 2.30875278e+00 2.55896020e+00 2.69527268e+00 2.69285846e+00 2.53766131e+00 2.52742577e+00 2.47627521e+00 2.55159068e+00 2.64038658e+00 2.33816147e+00 2.29057193e+00 2.13446808e+00 2.65563703e+00 2.96701884e+00 2.87721205e+00 2.13534045e+00 1.92516005e+00 2.17656755e+00 2.37035894e+00 2.15372038e+00 2.04685974e+00 2.43391633e+00 2.73696971e+00 2.81607819e+00 2.70544553e+00 2.67312598e+00 2.73312044e+00 2.50467992e+00 2.48203516e+00 2.64673209e+00 3.04222584e+00 2.90994310e+00 2.96393871e+00 3.09589720e+00 3.22376585e+00 2.86133862e+00 2.54793596e+00 2.59311819e+00 2.78367853e+00 2.74542761e+00 2.49307561e+00 2.61128879e+00 2.73281336e+00 2.80525756e+00 2.57858038e+00 2.50403714e+00 2.68431997e+00 2.75985074e+00 2.94444203e+00 2.84933472e+00 3.02858686e+00 3.13354945e+00 3.06191063e+00 2.94658995e+00 2.82014298e+00 2.90310121e+00 2.92509007e+00 3.07203746e+00 3.27603388e+00 3.22961187e+00 3.10892463e+00 2.99019718e+00 3.10365152e+00 3.24040627e+00 3.05383635e+00 2.67141819e+00 2.62825251e+00 2.87254071e+00 3.07807994e+00 2.88567185e+00 2.56854367e+00 2.59913731e+00 2.77239895e+00 3.06854582e+00 3.11950135e+00 3.19934201e+00 3.21998453e+00 3.19187641e+00 3.12520003e+00 3.15027785e+00 3.17735219e+00 3.08379340e+00 3.07827592e+00 3.19634986e+00 3.19176531e+00 2.91432834e+00 2.62329102e+00 2.65283108e+00 2.75801086e+00 2.79921174e+00 2.72641253e+00 2.88010097e+00 2.96402383e+00 2.95348835e+00 2.81345272e+00 2.85541773e+00 2.97201586e+00 2.99642968e+00 2.96152234e+00 2.97615719e+00 3.09267998e+00 3.22577333e+00 3.12294793e+00 3.00368047e+00 2.86600828e+00 2.98288178e+00 3.10178900e+00 3.27263641e+00 3.48400807e+00 3.44859910e+00 3.10997415e+00 2.72842383e+00 2.55837011e+00 2.73283005e+00 2.84301972e+00 2.86232281e+00 2.87535405e+00 2.79006219e+00 2.90309072e+00 2.93342996e+00 3.03177881e+00 3.01200557e+00 2.78337169e+00 2.72770238e+00 2.80776095e+00 3.12024045e+00 3.31111646e+00 3.20908308e+00 3.05159211e+00 2.99064517e+00 3.15951180e+00 3.30141854e+00 3.29278302e+00 3.24682570e+00 3.14849949e+00 3.06098771e+00 3.01309705e+00 2.95017147e+00 3.01887012e+00 3.10332942e+00 3.17176008e+00 3.17139578e+00 3.04203343e+00 2.95825386e+00 2.89562964e+00 2.94921947e+00 3.10066819e+00 3.11163235e+00 3.13898802e+00 3.15283513e+00 3.27084279e+00 3.26965594e+00 3.10801482e+00 3.00919271e+00 2.99650049e+00 3.07161427e+00 3.11545300e+00 3.12524104e+00 3.15877724e+00 3.16153431e+00 3.12662578e+00 3.10015988e+00 3.06672430e+00 3.08538771e+00 3.08887243e+00 3.09032416e+00 3.09777427e+00 3.10528588e+00 3.16054130e+00 3.17497349e+00 3.17596412e+00 3.15794945e+00 3.11652231e+00 3.10174870e+00 3.10381436e+00 3.14972830e+00 3.18250036e+00 3.17936659e+00 3.15906453e+00 3.13918281e+00 3.15319777e+00 3.16559291e+00 3.17240834e+00 3.16694593e+00 3.16006064e+00 3.15631938e+00 3.15677738e+00 3.15931296e+00 3.15901423e+00 3.15378571e+00 3.14870548e+00 3.15295053e+00 3.18036604e+00 3.19606090e+00 3.19181371e+00 3.16065168e+00 3.13253355e+00 3.15300298e+00 3.18804908e+00 3.21433258e+00 3.18221378e+00 3.13843942e+00 3.13116074e+00 3.14643764e+00 3.17290831e+00 3.16373706e+00 3.14946628e+00 3.17288113e+00 3.17996860e+00 3.17463231e+00 3.14508080e+00 3.14615583e+00 3.17497349e+00 3.17871356e+00 3.17261863e+00 3.16836834e+00 3.15860820e+00 3.19704318e+00 3.13507438e+00 3.09673977e+00 3.01380229e+00 3.04802465e+00 3.17547321e+00 3.27953672e+00 3.31242299e+00 3.16197038e+00 3.03704810e+00 2.99981356e+00 3.04134703e+00 3.14209294e+00 3.17006397e+00 3.13528490e+00 3.07768273e+00 2.99854779e+00 3.06183624e+00 3.16597509e+00 3.27511239e+00 3.27738547e+00 3.10192752e+00 2.96910596e+00 2.89355564e+00 2.95410371e+00 3.15067077e+00 3.30378056e+00 3.30935168e+00 3.10530162e+00 2.91860461e+00 2.98911786e+00 3.17068839e+00 3.28808784e+00 3.14226723e+00 2.92064953e+00 2.90132904e+00 2.97778463e+00 3.18421626e+00 3.28805351e+00 3.27833319e+00 3.25227976e+00 3.12809539e+00 3.03520536e+00 3.02277994e+00 3.07772374e+00 3.26426959e+00 3.21897411e+00 3.09052706e+00 2.97394371e+00 2.75694227e+00 2.92819095e+00 2.97114801e+00 3.05915451e+00 2.87820768e+00 2.80485868e+00 3.15484142e+00 3.30955243e+00 3.32331657e+00 2.98733664e+00 2.75251746e+00 2.77695775e+00 2.94608498e+00 3.23136425e+00 3.35316181e+00 3.27594495e+00 3.20217228e+00 3.03344679e+00 2.99179363e+00 3.05399203e+00 3.02943444e+00 3.06280160e+00 2.79879045e+00 2.77914739e+00 2.76739621e+00 2.83312678e+00 3.08618498e+00 3.14265180e+00 3.01250267e+00 2.64156890e+00 2.45601606e+00 2.56142282e+00 2.78866673e+00 2.97911072e+00 2.80365372e+00 2.50341868e+00 2.37280703e+00 2.48660398e+00 2.73236513e+00 2.84146070e+00 2.87804437e+00 2.93972516e+00 2.95448327e+00 2.98814511e+00 2.97144198e+00 3.09699059e+00 3.26588202e+00 3.01007271e+00 2.55491495e+00 2.25247860e+00 2.36585927e+00 2.83209944e+00 3.15512109e+00 3.15511918e+00 2.77250123e+00 2.49587250e+00 2.61793876e+00 2.84480238e+00 2.92799449e+00 2.79548621e+00 2.73335934e+00 2.88653421e+00 3.04683876e+00 3.23188877e+00 3.31046152e+00 3.25255442e+00 3.27980065e+00 3.08713508e+00 2.95555425e+00 2.91736650e+00 2.84209704e+00 3.05484700e+00 2.95147800e+00 2.95065832e+00 2.77499461e+00 2.79034591e+00 3.29682541e+00 3.24871135e+00 3.18956780e+00 2.73502755e+00 2.53857899e+00 2.59501863e+00 2.65268326e+00 3.20561600e+00 3.15297103e+00 2.75961089e+00 2.33449483e+00 2.21243167e+00 2.77662492e+00 2.84406567e+00 2.74200106e+00 2.78278518e+00 2.93369651e+00 3.06999040e+00 2.59878969e+00 2.48549604e+00 2.93697262e+00 2.24246311e+00 1.79791665e+00 7.59453833e-01 1.01299953e+00 -5.89039087e+00 -1.08827600e+01 -3.73794594e+01 -2.23169907e+02 -5.03847076e+02 235114896. 8265405. 6.00705350e+06 -247559168. 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. 0. 0. 0. 0. 0. 0. 0. -426442016. -2.87915088e+03 -4.31928650e+02 9.59239044e+01 8.51889114e+01 1.57318611e+01 7.94773197e+00 4.54367113e+00 5.72359800e+00 2.27513456e+00 2.07506728e+00 2.23025084e+00 2.16336060e+00 2.33259368e+00 2.44663119e+00 2.42311406e+00 2.23752236e+00 1.92366707e+00 1.96603847e+00 2.22679138e+00 2.34907722e+00 2.49813557e+00 2.32630873e+00 2.19165659e+00 1.75336850e+00 1.64962542e+00 2.26163650e+00 2.54994249e+00 2.16502142e+00 1.49673760e+00 1.75723732e+00 2.51217341e+00 2.62701797e+00 2.37283325e+00 1.98653638e+00 1.98100674e+00 1.89769602e+00 1.80354166e+00 1.84498644e+00 2.06092811e+00 2.23681188e+00 2.15802026e+00 1.87917602e+00 2.01751590e+00 2.26870537e+00 2.71135378e+00 3.24197364e+00 2.93530798e+00 1.68572843e+00 2.10561961e-01 1.88519552e-01 1.48996246e+00 2.11470103e+00 1.99295557e+00 1.33700001e+00 1.35270655e+00 1.73202562e+00 1.84929252e+00 1.96092749e+00 1.78505063e+00 1.88745987e+00 2.03137875e+00 2.07592273e+00 2.53580904e+00 2.87176871e+00 2.76843524e+00 2.31207538e+00 1.86552083e+00 2.00005269e+00 2.08547449e+00 2.47575259e+00 2.97795391e+00 3.28352451e+00 3.30510068e+00 2.75941229e+00 2.35657978e+00 2.61052799e+00 2.17825341e+00 1.65677953e+00 6.42874599e-01 7.40719199e-01 1.51262152e+00 1.81914937e+00 2.00710726e+00 2.00837135e+00 1.99110651e+00 1.78588665e+00 1.36303675e+00 1.76046360e+00 2.23509669e+00 2.21961093e+00 2.15681672e+00 2.37749767e+00 2.89888644e+00 2.57492304e+00 1.82029152e+00 2.06288767e+00 2.04237008e+00 2.03374553e+00 1.37094069e+00 1.24437439e+00 2.00282717e+00 2.03007126e+00 1.64512599e+00 6.86117053e-01 5.07480443e-01 1.22443080e+00 1.58842373e+00 2.00056291e+00 1.93386137e+00 2.16305733e+00 2.17152119e+00 1.90250015e+00 1.90376472e+00 1.96209955e+00 1.97254777e+00 1.71114421e+00 1.10889661e+00 1.16742039e+00 1.19614697e+00 1.42332423e+00 2.27985168e+00 2.20831728e+00 1.68394816e+00 4.01993841e-01 3.33742231e-01 1.45759594e+00 1.83647871e+00 1.36394525e+00 4.75879520e-01 3.72568250e-01 1.23027515e+00 1.83154881e+00 2.43405414e+00 2.30914164e+00 1.79596806e+00 1.01739860e+00 5.65247118e-01 1.10279620e+00 1.69462788e+00 1.67046797e+00 1.20899642e+00 6.40066683e-01 9.47124124e-01 1.16018617e+00 1.18722844e+00 1.57569611e+00 1.62692070e+00 1.93023014e+00 1.66989124e+00 1.57728910e+00 1.94889092e+00 1.86921620e+00 1.41462862e+00 4.20276344e-01 -1.20231561e-01 1.76761746e-01 5.48288286e-01 1.13042259e+00 1.22175491e+00 1.66348720e+00 2.10446572e+00 1.96803868e+00 1.53712785e+00 1.31804478e+00 1.55382299e+00 1.77108943e+00 1.34285688e+00 5.17226636e-01 -1.58312231e-01 -4.09492940e-01 6.76031768e-01 1.02709663e+00 8.32197130e-01 1.92821518e-01 3.04466844e-01 9.65799212e-01 8.97176862e-01 9.96775329e-01 9.64054406e-01 9.08888638e-01 5.94184160e-01 2.86370695e-01 7.38000154e-01 1.11419988e+00 1.02303731e+00 9.62250173e-01 9.82791662e-01 1.39258218e+00 1.99713016e+00 2.44996881e+00 2.43576145e+00 1.17072225e+00 3.43442291e-01 1.11173570e-01 3.31193745e-01 1.05233669e+00 8.59387994e-01 5.46518445e-01 -4.90421206e-01 -3.87491047e-01 4.60653782e-01 1.11125064e+00 1.33837211e+00 9.94363129e-01 1.25569332e+00 1.45922363e+00 1.33219552e+00 1.05067670e+00 1.10932338e+00 1.24751961e+00 1.16312969e+00 6.69268250e-01 5.48960149e-01 -4.62157726e-02 -1.30415976e-01 7.25281775e-01 1.63192284e+00 1.53971553e+00 5.90670347e-01 1.28788054e-01 2.49420777e-01 -1.42773494e-01 -6.20990515e-01 -1.07595372e+00 -1.21425235e+00 -6.60966754e-01 -1.55751973e-01 6.63255394e-01 8.05563271e-01 2.42909983e-01 -3.92668009e-01 -5.47581613e-01 -8.98084044e-02 1.75948381e-01 7.57833421e-02 2.04951525e-01 9.71738324e-02 1.28634684e-02 -1.61291465e-01 -2.82077659e-02 -1.34049460e-01 -1.23864822e-01 -1.99878782e-01 -3.07588786e-01 -5.70254862e-01 -6.86614871e-01 -5.28964579e-01 -3.04228842e-01 -2.72138596e-01 -4.00496483e-01 -3.32484365e-01 -3.20937514e-01 4.69651744e-02 2.25383192e-01 2.52061367e-01 -6.51904196e-02 -4.43787575e-01 -3.64738345e-01 -3.61584872e-01 -3.21244717e-01 -2.86166072e-01 6.17755391e-03 -1.40835755e-02 -1.30060643e-01 -4.12482738e-01 -3.38489532e-01 -5.72040439e-01 -6.49593771e-01 -6.33667767e-01 -5.09199679e-01 -7.25624979e-01 -7.70944595e-01 -7.18543172e-01 -6.22947991e-01 -7.12564349e-01 -7.28275716e-01 -5.57073891e-01 -6.38892710e-01 -7.10259795e-01 -7.67607629e-01 -6.14878178e-01 -6.44288540e-01 -8.22360456e-01 -9.21002865e-01 -8.62952232e-01 -9.76479530e-01 -1.12214375e+00 -1.19676065e+00 -9.56578910e-01 -8.05697441e-01 -8.75095665e-01 -9.82349634e-01 -1.00506175e+00 -9.31504250e-01 -7.84033895e-01 -2.71703124e-01 2.00605318e-01 1.44134760e-01 -3.54375869e-01 -7.45964348e-01 -8.49399030e-01 -8.06635737e-01 -8.40812743e-01 -7.96718776e-01 -8.84647012e-01 -8.65466416e-01 -7.84912109e-01 -8.19134235e-01 -1.16129088e+00 -1.25950491e+00 -1.10724020e+00 -8.62948477e-01 -9.15995896e-01 -9.60735917e-01 -8.42921734e-01 -7.23179758e-01 -8.26617837e-01 -9.64169502e-01 -1.01256478e+00 -8.88038278e-01 -1.09056282e+00 -1.45472181e+00 -1.50762415e+00 -1.28327107e+00 -8.94868374e-01 -8.98163974e-01 -8.77025068e-01 -8.27100039e-01 -1.03569663e+00 -1.37874067e+00 -1.54304874e+00 -1.48031855e+00 -1.22005260e+00 -1.31577396e+00 -1.31243980e+00 -1.29787374e+00 -1.17200518e+00 -1.07758117e+00 -1.08326054e+00 -1.06469941e+00 -1.23874927e+00 -1.30014515e+00 -1.25879252e+00 -1.03006768e+00 -7.47435212e-01 -5.43434262e-01 -6.44040585e-01 -8.32617462e-01 -9.41384077e-01 -8.69331896e-01 -8.51926744e-01 -1.22929764e+00 -1.62116957e+00 -1.93365681e+00 -1.40660906e+00 -7.27310598e-01 -4.41686571e-01 -9.21875894e-01 -1.42282116e+00 -1.51274073e+00 -1.45848942e+00 -1.00539100e+00 -4.85799730e-01 -1.00411439e+00 -1.99417400e+00 -2.36354160e+00 -1.88251460e+00 -1.35272038e+00 -1.42741311e+00 -1.55445743e+00 -1.64968050e+00 -1.60518873e+00 -1.51729202e+00 -1.55015278e+00 -1.98943210e+00 -2.38252091e+00 -2.11653876e+00 -1.39993453e+00 -9.26497102e-01 -1.24706686e+00 -1.62650740e+00 -1.81819212e+00 -1.75417554e+00 -1.84570432e+00 -1.96714282e+00 -2.17783380e+00 -2.27402687e+00 -2.08953214e+00 -1.89028561e+00 -1.88140559e+00 -2.02047849e+00 -1.99948585e+00 -1.85235286e+00 -1.87247300e+00 -1.91806149e+00 -1.92242682e+00 -1.99053526e+00 -2.03391695e+00 -2.16397715e+00 -2.01680136e+00 -1.89196229e+00 -1.79354894e+00 -1.65780795e+00 -1.48950994e+00 -1.25262785e+00 -1.11854184e+00 -1.23848045e+00 -1.40247726e+00 -1.59899247e+00 -1.59705412e+00 -1.57443273e+00 -1.58208025e+00 -1.62451982e+00 -1.73372734e+00 -1.78249156e+00 -1.86049092e+00 -1.92878556e+00 -1.73451376e+00 -1.49410868e+00 -1.44069231e+00 -1.87771761e+00 -2.37612176e+00 -2.38260245e+00 -2.25971699e+00 -2.13374043e+00 -2.25951505e+00 -2.21462059e+00 -2.15383673e+00 -1.82197297e+00 -1.48835933e+00 -1.44528949e+00 -1.69410646e+00 -2.16477346e+00 -2.35965180e+00 -2.40723515e+00 -2.38678527e+00 -2.24095488e+00 -2.27822804e+00 -2.33707857e+00 -2.45297718e+00 -2.38104868e+00 -2.30440664e+00 -2.11949277e+00 -2.13238168e+00 -2.15490627e+00 -2.33096838e+00 -2.47804642e+00 -2.37739754e+00 -2.04103446e+00 -1.89826262e+00 -1.99121034e+00 -2.17249084e+00 -2.15527821e+00 -2.16526914e+00 -2.32363677e+00 -3.87489033e+00 -4.21629620e+00 -5.43598270e+00 -3.59236789e+00 3.31931663e+00 -4.55438948e+00 2.33397675e+01 -1.68435527e+04 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. 0. 0. 0. 0. 0. 0. 4.19125469e+04 -2.02868484e+02 9.78915634e+01 7.97382431e+01 2.29051456e+01 9.63183784e+00 2.61885858e+00 -1.45083153e+00 -3.32256705e-01 -2.22820449e+00 -2.44013739e+00 -2.79408193e+00 -3.13818502e+00 -3.18761730e+00 -3.04612827e+00 -2.93591094e+00 -3.01618290e+00 -3.04180074e+00 -2.98848176e+00 -2.92318320e+00 -2.90376592e+00 -2.94938540e+00 -3.04816794e+00 -3.09598899e+00 -3.04539919e+00 -2.93530846e+00 -2.87035966e+00 -2.80013204e+00 -2.75192261e+00 -2.67028618e+00 -2.64586520e+00 -2.67693067e+00 -2.64813805e+00 -2.67103648e+00 -2.58000374e+00 -2.59325647e+00 -2.59300971e+00 -2.69372749e+00 -2.77954435e+00 -2.81045699e+00 -2.77776074e+00 -2.75512314e+00 -2.75422621e+00 -2.79880857e+00 -2.76731062e+00 -2.71527553e+00 -2.67105699e+00 -2.61723399e+00 -2.67475629e+00 -2.63018894e+00 -2.58455157e+00 -2.58716297e+00 -2.68324375e+00 -2.83141685e+00 -2.80587745e+00 -2.76355481e+00 -2.75640249e+00 -2.76133847e+00 -2.78658509e+00 -2.76380682e+00 -2.75980186e+00 -2.74434447e+00 -2.69017053e+00 -2.85715461e+00 -3.05663896e+00 -3.17409134e+00 -3.13651872e+00 -3.07169032e+00 -3.19775581e+00 -3.31665349e+00 -3.26071119e+00 -3.14296412e+00 -2.96951699e+00 -2.93457174e+00 -2.91596937e+00 -2.80669165e+00 -2.66361904e+00 -2.53804541e+00 -2.54336643e+00 -2.69433093e+00 -2.82132936e+00 -2.89544106e+00 -2.90625858e+00 -2.87853551e+00 -3.01060653e+00 -3.22796392e+00 -3.34982729e+00 -3.40451312e+00 -3.26354647e+00 -3.22415733e+00 -3.11678982e+00 -3.10603929e+00 -3.09150100e+00 -3.18167329e+00 -3.26673007e+00 -3.23867869e+00 -3.14351463e+00 -3.07060838e+00 -3.10584617e+00 -3.13977647e+00 -3.18278813e+00 -3.22781396e+00 -3.10981393e+00 -2.96239090e+00 -2.91200638e+00 -2.97620463e+00 -3.07789850e+00 -3.07591081e+00 -3.08567309e+00 -3.14037776e+00 -3.19180107e+00 -3.26888633e+00 -3.25195837e+00 -3.14518237e+00 -3.03203940e+00 -2.93424511e+00 -2.96470141e+00 -2.99949098e+00 -3.04331493e+00 -3.05002856e+00 -3.03154397e+00 -3.03450060e+00 -3.06624842e+00 -3.09025764e+00 -3.08980799e+00 -3.08669186e+00 -3.07326365e+00 -3.07729435e+00 -3.06297803e+00 -3.15315700e+00 -3.24535680e+00 -3.27042651e+00 -3.20010924e+00 -3.11441445e+00 -3.15203547e+00 -3.20277405e+00 -3.27127028e+00 -3.28852892e+00 -3.24691296e+00 -3.19344616e+00 -3.14096308e+00 -3.14240432e+00 -3.13451934e+00 -3.12092996e+00 -3.10340738e+00 -3.08731961e+00 -3.08683372e+00 -3.09828711e+00 -3.12746286e+00 -3.13622928e+00 -3.13931274e+00 -3.14092255e+00 -3.15744781e+00 -3.17162490e+00 -3.20445514e+00 -3.22565842e+00 -3.21740317e+00 -3.18687081e+00 -3.15536380e+00 -3.18148494e+00 -3.19926691e+00 -3.21918416e+00 -3.21943903e+00 -3.22553539e+00 -3.22644496e+00 -3.20479512e+00 -3.18672371e+00 -3.16230249e+00 -3.15972090e+00 -3.15805078e+00 -3.15982199e+00 -3.16191292e+00 -3.15885234e+00 -3.15837550e+00 -3.15737247e+00 -3.15810132e+00 -3.15702009e+00 -3.15670919e+00 -3.16006422e+00 -3.16296053e+00 -3.16090989e+00 -3.15638256e+00 -3.15217686e+00 -3.14812040e+00 -3.14652538e+00 -3.15403152e+00 -3.14687419e+00 -3.13009214e+00 -3.12333870e+00 -3.13544941e+00 -3.15921450e+00 -3.15760207e+00 -3.15833664e+00 -3.15538692e+00 -3.15909815e+00 -3.15685773e+00 -3.15535593e+00 -3.15101647e+00 -3.14901710e+00 -3.14646554e+00 -3.14705968e+00 -3.14319277e+00 -3.16610909e+00 -3.19672537e+00 -3.19828200e+00 -3.17099929e+00 -3.13002515e+00 -3.14331031e+00 -3.13887239e+00 -3.12419891e+00 -3.10315871e+00 -3.10420680e+00 -3.11406159e+00 -3.12235332e+00 -3.12807155e+00 -3.12928367e+00 -3.11995149e+00 -3.12830424e+00 -3.13819575e+00 -3.13866663e+00 -3.13073397e+00 -3.14554119e+00 -3.16861606e+00 -3.16175246e+00 -3.13832712e+00 -3.12058377e+00 -3.12458229e+00 -3.17545485e+00 -3.20343900e+00 -3.20623970e+00 -3.16331482e+00 -3.13196731e+00 -3.16362548e+00 -3.16307616e+00 -3.18057275e+00 -3.19743276e+00 -3.18754768e+00 -3.18634295e+00 -3.15023804e+00 -3.18255448e+00 -3.18674111e+00 -3.19920778e+00 -3.15201783e+00 -3.10379362e+00 -3.07325959e+00 -3.17292857e+00 -3.26074696e+00 -3.27177668e+00 -3.18217111e+00 -2.97555494e+00 -2.85169578e+00 -2.84835744e+00 -2.95965791e+00 -2.99864125e+00 -2.80260825e+00 -2.77572632e+00 -2.89375925e+00 -3.11014652e+00 -3.16200399e+00 -3.14076138e+00 -3.13008022e+00 -3.11070967e+00 -3.05643177e+00 -3.06022978e+00 -3.08164430e+00 -3.07492971e+00 -3.01520419e+00 -2.92645478e+00 -2.96126437e+00 -3.04096723e+00 -3.08426690e+00 -3.01575255e+00 -2.94246745e+00 -2.96256018e+00 -2.86718678e+00 -2.74254465e+00 -2.67988682e+00 -2.71912408e+00 -2.76930285e+00 -2.67348814e+00 -2.65005565e+00 -2.66164970e+00 -2.77242446e+00 -2.84313512e+00 -2.89634681e+00 -2.85255075e+00 -2.80398297e+00 -2.76411295e+00 -2.89692640e+00 -3.09451222e+00 -3.10498333e+00 -2.98179483e+00 -2.82728434e+00 -2.84352183e+00 -2.79766250e+00 -2.85510612e+00 -2.84411049e+00 -2.73320627e+00 -2.50364733e+00 -2.47798967e+00 -2.60763168e+00 -2.85463524e+00 -2.83521485e+00 -2.83828592e+00 -2.83166862e+00 -2.91400647e+00 -2.82332420e+00 -2.61329150e+00 -2.53273058e+00 -2.58060265e+00 -2.76416874e+00 -2.73308206e+00 -2.76982903e+00 -2.73255157e+00 -2.75612736e+00 -2.69231510e+00 -2.61558294e+00 -2.62097788e+00 -2.68453264e+00 -2.79736185e+00 -2.78524995e+00 -2.76415730e+00 -2.83432031e+00 -2.90172386e+00 -3.10174680e+00 -3.22487831e+00 -3.19998026e+00 -2.86012745e+00 -2.45026898e+00 -2.25066566e+00 -2.23922253e+00 -2.25396657e+00 -2.34734750e+00 -2.57127047e+00 -2.69546247e+00 -2.81770730e+00 -2.77768683e+00 -2.82399607e+00 -2.62804389e+00 -2.39488006e+00 -2.40117764e+00 -2.50546074e+00 -2.87476850e+00 -3.11595440e+00 -3.19668722e+00 -3.08318186e+00 -2.78702831e+00 -2.49505973e+00 -2.09625936e+00 -1.79256618e+00 -1.88795912e+00 -2.19355464e+00 -2.50623584e+00 -2.73880363e+00 -2.47918105e+00 -2.13742805e+00 -1.98176742e+00 -2.15443444e+00 -2.50092578e+00 -2.73631644e+00 -2.84262490e+00 -2.80968952e+00 -2.65322232e+00 -2.73133326e+00 -2.69654775e+00 -2.70319629e+00 -2.68240452e+00 -2.62513804e+00 -2.58596373e+00 -2.54981947e+00 -2.50890827e+00 -2.46245193e+00 -2.11639833e+00 -1.79588056e+00 -1.96006989e+00 -2.42603827e+00 -2.44135857e+00 -1.86671162e+00 -1.49735439e+00 -1.84724057e+00 -2.26312447e+00 -2.23734975e+00 -1.99007976e+00 -1.94708931e+00 -2.07884693e+00 -2.25812078e+00 -2.25840092e+00 -2.22467208e+00 -2.06547809e+00 -2.06263304e+00 -2.11323738e+00 -2.26363945e+00 -2.32363009e+00 -2.29424381e+00 -2.21823025e+00 -2.17083263e+00 -2.08195972e+00 -1.99087036e+00 -1.76936555e+00 -2.05597878e+00 -2.48121762e+00 -2.37860155e+00 -1.92159319e+00 -1.60138631e+00 -1.96317720e+00 -2.17523813e+00 -1.89113343e+00 -1.53245640e+00 -1.89021075e+00 -2.58443022e+00 -3.08436346e+00 -2.86326551e+00 -2.50189900e+00 -1.96545720e+00 -1.65562987e+00 -1.75525641e+00 -2.27296591e+00 -2.28991032e+00 -1.71819496e+00 -1.56236196e+00 -1.84008527e+00 -2.30181718e+00 -2.34996367e+00 -2.26297879e+00 -2.37243438e+00 -2.69545460e+00 -2.36775303e+00 -1.86684537e+00 -1.40173030e+00 -1.65694869e+00 -1.89030719e+00 -2.00757670e+00 -2.00644064e+00 -1.98534679e+00 -1.88431370e+00 -1.85960698e+00 -2.09031272e+00 -2.08343935e+00 -2.12544966e+00 -2.04131699e+00 -1.95920861e+00 -1.83115733e+00 -1.34257007e+00 -9.78077650e-01 -1.27947152e+00 -2.07268691e+00 -2.64975357e+00 -2.48813677e+00 -2.04438972e+00 -2.08517480e+00 -2.23982120e+00 -2.40024376e+00 -2.50310087e+00 -2.22638941e+00 -1.97361243e+00 -1.80873156e+00 -1.99267650e+00 -2.26434422e+00 -2.25427890e+00 -2.14563417e+00 -2.04761767e+00 -2.08303952e+00 -2.09265089e+00 -1.73511469e+00 -1.62021780e+00 -1.85485005e+00 -2.07411623e+00 -1.98809004e+00 -1.72297955e+00 -1.96994317e+00 -2.25454974e+00 -2.11573410e+00 -1.40896499e+00 -6.71879172e-01 -5.21197021e-01 -7.60413110e-01 -8.46186876e-01 -6.28007174e-01 -7.52202928e-01 -1.04590869e+00 -1.33115089e+00 -1.27283227e+00 -1.27149367e+00 -1.04669344e+00 -5.95280349e-01 -5.53740919e-01 -1.05952942e+00 -1.74417543e+00 -1.42069221e+00 -7.80904353e-01 -6.83559775e-01 -1.24430168e+00 -1.38476121e+00 -9.84327734e-01 -1.36338878e+00 -2.25667882e+00 -2.77831292e+00 -2.31506228e+00 -1.74602449e+00 -1.85653222e+00 -2.24556875e+00 -2.36926723e+00 -2.11046815e+00 -1.95406568e+00 -2.25679874e+00 -2.32371616e+00 -2.15735197e+00 -1.68759561e+00 -1.17689431e+00 -6.15093529e-01 -3.68208736e-01 -4.29304808e-01 -1.25681448e+00 -1.89796436e+00 -2.14956832e+00 -1.70456517e+00 -1.30011952e+00 -1.30579865e+00 -1.28393614e+00 -1.61518919e+00 -2.04076481e+00 -2.04249525e+00 -1.59708869e+00 -1.23659575e+00 -1.15711021e+00 -1.09248638e+00 -5.42091310e-01 -1.95544407e-01 -2.84881055e-01 -7.53588438e-01 -1.00336170e+00 -1.05858004e+00 -1.07859492e+00 -1.14523625e+00 -9.13863599e-01 -8.47077847e-01 -8.69206786e-01 -1.04906416e+00 -1.10439646e+00 -1.11264753e+00 -1.10966587e+00 -9.39113259e-01 -4.49885428e-01 1.68493405e-01 1.51351005e-01 -2.02027276e-01 -3.12542945e-01 3.67088057e-02 1.16626071e-02 -3.13728482e-01 -6.30376816e-01 -2.53776580e-01 1.20366648e-01 2.61034109e-02 -3.63039911e-01 -1.02390981e+00 -1.10365558e+00 -1.15711188e+00 -6.89143836e-01 -2.34391674e-01 -9.83426794e-02 -4.16064739e-01 -4.48221624e-01 -9.03607830e-02 -7.91946054e-02 -3.66365850e-01 -8.58513415e-01 -4.62225407e-01 4.19545807e-02 1.23767085e-01 -5.43004990e-01 -1.05662823e+00 -8.09859574e-01 -1.77713230e-01 -3.22032534e-02 5.58229759e-02 -1.59494832e-01 -1.99653864e-01 -2.08616674e-01 -2.16451049e-01 2.15198979e-01 5.18731713e-01 5.47029614e-01 2.40422502e-01 -1.37379736e-01 -1.91243678e-01 -1.69830710e-01 -1.97929412e-01 -1.26271725e-01 -2.02073485e-01 -1.20858580e-01 -1.99812725e-01 -2.12631986e-01 -2.66010493e-01 -7.08898187e-01 -1.12765348e+00 -6.65135384e-01 3.11077069e-02 3.71702731e-01 -2.54060924e-01 -5.64246297e-01 -4.55045193e-01 -3.27631027e-01 -2.31104597e-01 -3.06050122e-01 -1.82789370e-01 -1.67520940e-01 7.26792991e-01 1.41564369e+00 4.76160479e+00 1.09656639e+01 1.62407055e+01 3.19330482e+01 3.00455074e+01 3.14057892e+02 7.63517761e+02 -3.33246656e+05 652480832. 0. 0. 0. 0. 0. 5.59779277e+09 3.92038375e+05 -8.43279453e+04 2.13765312e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.21156454e+09 -10230335. -1.96937683e+03 -6.73846375e+02 -1.05680305e+02 -3.21287918e+01 -1.82566414e+01 -3.63983655e+00 8.87605175e-02 -1.05266623e-01 -1.84284759e+00 -1.52626145e+00 -1.02418494e+00 -6.16670132e-01 1.30936489e-01 3.67488712e-01 1.10033786e+00 7.38511741e-01 1.65131539e-02 -1.29035330e+00 -1.19786000e+00 5.42645633e-01 2.41091108e+00 3.35776830e+00 3.25521564e+00 2.10173297e+00 2.12143350e+00 2.64774203e+00 1.59497797e+00 8.60852361e-01 7.52134085e-01 2.90680695e+00 4.17091131e+00 4.58175659e+00 3.47920203e+00 1.57613397e+00 7.22498715e-01 7.04326332e-01 3.36985350e-01 4.56288047e-02 4.39853817e-01 2.04625058e+00 3.40493202e+00 2.78699136e+00 1.74228215e+00 9.81613517e-01 2.09345746e+00 2.09371758e+00 2.23316693e+00 2.71753407e+00 2.58504152e+00 2.44541645e+00 2.01085114e+00 1.39717972e+00 7.89184272e-01 5.07912099e-01 2.07446694e+00 4.05399227e+00 4.45504713e+00 3.41042542e+00 9.77509201e-01 8.43828619e-01 1.75035930e+00 2.85408688e+00 2.89779282e+00 2.71498394e+00 2.98130870e+00 3.34056568e+00 3.36153817e+00 2.11344600e+00 6.40703678e-01 1.06772089e+00 1.70626497e+00 2.64228678e+00 3.13234758e+00 3.71488690e+00 3.78685331e+00 3.18724132e+00 2.12622786e+00 1.49818122e+00 1.44219792e+00 2.07669735e+00 3.13203764e+00 4.19237041e+00 4.67179966e+00 3.60228300e+00 3.11670613e+00 2.90887666e+00 2.04259205e+00 1.14768052e+00 1.05564821e+00 2.82413602e+00 4.86083984e+00 5.83227873e+00 4.49102259e+00 2.08480215e+00 1.51127803e+00 1.76414311e+00 2.24271941e+00 2.06359553e+00 2.09577274e+00 2.19920707e+00 2.88026762e+00 3.21405029e+00 3.31864452e+00 3.27889299e+00 3.92923069e+00 4.97705364e+00 5.36344957e+00 5.06313372e+00 3.89466882e+00 3.01095152e+00 3.29682732e+00 3.15275931e+00 2.80913043e+00 2.45482540e+00 3.37274742e+00 4.33506727e+00 4.45898151e+00 2.90176344e+00 1.61265087e+00 1.59901702e+00 2.83749080e+00 4.10277033e+00 5.08496284e+00 5.60126352e+00 5.18640995e+00 4.70854712e+00 4.13037443e+00 3.12578559e+00 2.51770687e+00 2.62134314e+00 3.53938675e+00 4.59845257e+00 5.09581852e+00 4.62099218e+00 3.55685329e+00 3.33127642e+00 3.44799161e+00 3.73053575e+00 3.06206632e+00 3.09905577e+00 3.97178531e+00 5.37574625e+00 6.09781122e+00 5.70511150e+00 5.25017023e+00 5.03157425e+00 4.61210775e+00 4.45659590e+00 4.88455486e+00 5.36721849e+00 6.16656303e+00 6.37334394e+00 6.16886950e+00 5.06491947e+00 4.73540878e+00 5.32239151e+00 6.09487009e+00 5.42008686e+00 4.08816862e+00 3.34887362e+00 4.53135586e+00 5.63624525e+00 5.97618675e+00 5.71585369e+00 5.68139458e+00 6.64992094e+00 7.57768250e+00 7.98111057e+00 6.67958355e+00 4.43181419e+00 4.00826168e+00 4.10167360e+00 4.28602648e+00 4.17735958e+00 4.80890656e+00 5.96924591e+00 6.66538477e+00 5.67887402e+00 4.96497202e+00 4.64892721e+00 5.35561800e+00 6.23775673e+00 6.32088661e+00 7.47288132e+00 6.90313959e+00 7.66964483e+00 7.10117054e+00 6.86093140e+00 6.62283754e+00 6.77209091e+00 7.58491707e+00 8.32210827e+00 8.12933350e+00 6.90071630e+00 4.93008280e+00 4.75515318e+00 5.38135815e+00 5.78261709e+00 6.30250788e+00 6.22603607e+00 6.80045795e+00 6.58686924e+00 5.88937140e+00 5.50249910e+00 5.11392355e+00 6.11831522e+00 6.45711994e+00 6.93456459e+00 6.72807217e+00 6.44210148e+00 7.14302158e+00 8.22859001e+00 8.34118366e+00 7.39781380e+00 6.70109797e+00 6.67237759e+00 7.78416824e+00 8.07350349e+00 7.86082077e+00 6.82775021e+00 6.53480911e+00 6.49196196e+00 6.13312864e+00 6.09396887e+00 5.83143663e+00 5.67793465e+00 6.13925934e+00 6.58690977e+00 6.84818888e+00 6.17540789e+00 5.86832905e+00 6.23520279e+00 6.52248383e+00 7.31150007e+00 7.76944876e+00 8.29665947e+00 7.89248610e+00 7.18853617e+00 6.45331192e+00 6.23153734e+00 7.03762579e+00 7.76014853e+00 7.81353283e+00 7.36756849e+00 7.39026260e+00 7.78751993e+00 7.98474646e+00 7.24242401e+00 6.83771849e+00 6.96151590e+00 7.86021662e+00 8.34229660e+00 8.20979118e+00 7.99343538e+00 8.01690674e+00 7.81089973e+00 7.70354605e+00 7.79218960e+00 7.93613482e+00 8.01479244e+00 8.18772697e+00 8.34814644e+00 8.37189484e+00 7.63058138e+00 7.06806469e+00 7.41900206e+00 8.60568619e+00 8.83563709e+00 8.46183109e+00 8.13811207e+00 8.66695499e+00 8.69561005e+00 8.20271206e+00 7.82818556e+00 7.97015667e+00 8.03286076e+00 7.84259844e+00 7.72018337e+00 8.06148720e+00 8.26626015e+00 7.92081261e+00 7.59337616e+00 7.82984066e+00 7.59882975e+00 7.25170231e+00 6.98152924e+00 7.67077303e+00 8.24032688e+00 8.39408207e+00 8.02584267e+00 8.01008511e+00 8.22672844e+00 8.08629322e+00 7.72875071e+00 7.84244776e+00 8.45401382e+00 9.33537102e+00 9.06737328e+00 9.03874493e+00 8.40283680e+00 8.63759232e+00 8.05533600e+00 7.89091396e+00 7.98443985e+00 8.26772404e+00 8.28857422e+00 7.99973297e+00 7.86522055e+00 7.81342840e+00 7.59701300e+00 7.79488182e+00 8.03682137e+00 8.30029202e+00 8.19756413e+00 7.89389086e+00 8.14320660e+00 8.64102840e+00 8.72633457e+00 8.47528458e+00 8.30725098e+00 8.56507301e+00 8.61174107e+00 8.39771652e+00 8.34837627e+00 8.30715656e+00 8.09400654e+00 7.75628042e+00 7.51329660e+00 7.85155249e+00 8.19778442e+00 8.49132156e+00 8.50229549e+00 8.55431843e+00 8.40600204e+00 8.05278778e+00 8.37891960e+00 8.86532593e+00 8.94437027e+00 8.65792370e+00 8.33259296e+00 8.72663975e+00 8.78787804e+00 8.88276958e+00 8.80453968e+00 8.80548382e+00 8.89614868e+00 8.81650925e+00 8.78582859e+00 8.93560123e+00 8.90604019e+00 8.80020809e+00 8.42343807e+00 8.59842491e+00 8.78593636e+00 9.02851963e+00 9.03581238e+00 9.00988388e+00 8.92833138e+00 8.74596786e+00 8.24885273e+00 8.38769531e+00 8.89993477e+00 9.58417130e+00 9.85914040e+00 9.48652172e+00 9.26352978e+00 9.23855972e+00 9.41243172e+00 9.59372139e+00 9.44999218e+00 9.39664745e+00 9.32666397e+00 9.28388786e+00 9.59350491e+00 9.60462761e+00 9.56950569e+00 9.14092255e+00 8.89782715e+00 9.14164352e+00 9.40247250e+00 9.51558685e+00 9.23519421e+00 8.95427418e+00 9.02261925e+00 9.10182762e+00 9.26119041e+00 9.41931343e+00 9.41510582e+00 9.52962971e+00 9.32421589e+00 9.23020840e+00 9.14968967e+00 9.22154331e+00 9.50902367e+00 9.65518761e+00 9.68227959e+00 9.47165966e+00 9.26725101e+00 9.30648041e+00 9.36291027e+00 9.34158897e+00 9.17497921e+00 9.15987396e+00 9.37504768e+00 9.51216030e+00 9.54807377e+00 9.42660427e+00 9.36236382e+00 9.34574032e+00 9.29065323e+00 9.29057884e+00 9.33966732e+00 9.37781811e+00 9.45647621e+00 9.44862080e+00 9.48877811e+00 9.45832348e+00 9.43019772e+00 9.38085365e+00 9.27821827e+00 9.25500584e+00 9.29377174e+00 9.33149147e+00 9.40847969e+00 9.41275406e+00 9.41766548e+00 9.34325981e+00 9.30436802e+00 9.30732727e+00 9.35334682e+00 9.37598610e+00 9.35733128e+00 9.32414150e+00 9.32733440e+00 9.33117676e+00 9.33638287e+00 9.33883476e+00 9.33840466e+00 9.33249283e+00 9.33313370e+00 9.34202003e+00 9.35054779e+00 9.34702492e+00 9.30055237e+00 9.26918697e+00 9.26105785e+00 9.30246544e+00 9.35671997e+00 9.32531166e+00 9.28645420e+00 9.25735378e+00 9.32023525e+00 9.35532665e+00 9.32170582e+00 9.25908947e+00 9.23145103e+00 9.25683594e+00 9.26025677e+00 9.25708103e+00 9.22577190e+00 9.24456692e+00 9.18635750e+00 9.20435143e+00 9.17858887e+00 9.20103741e+00 9.19237232e+00 9.19975185e+00 9.25717545e+00 9.18581867e+00 9.26883030e+00 9.35953999e+00 9.52635574e+00 9.46102142e+00 9.19304848e+00 9.00841618e+00 8.97479153e+00 9.26029491e+00 9.46328831e+00 9.55151844e+00 9.41214085e+00 9.23341942e+00 9.14585018e+00 9.25967979e+00 9.34436417e+00 9.44824791e+00 9.35267830e+00 9.14340591e+00 8.96672344e+00 8.85661983e+00 9.18300724e+00 9.35436344e+00 9.49134827e+00 9.34973240e+00 9.03042412e+00 8.84801769e+00 8.79322720e+00 9.14601421e+00 9.40505028e+00 9.28261185e+00 9.02978325e+00 8.69786167e+00 8.82977772e+00 9.17977333e+00 9.36388206e+00 9.35042095e+00 8.96253014e+00 8.89450645e+00 8.93004131e+00 9.01194382e+00 8.98520660e+00 9.20656013e+00 9.20219612e+00 9.19435787e+00 8.96156693e+00 9.11050320e+00 9.13499069e+00 9.22066784e+00 9.19545555e+00 9.29297733e+00 9.09526157e+00 9.18703365e+00 9.24065399e+00 9.40402603e+00 8.94291210e+00 8.49327278e+00 8.37447643e+00 8.83571434e+00 9.20573235e+00 9.23267174e+00 8.93783951e+00 8.52371502e+00 8.23163795e+00 8.35948753e+00 8.44087791e+00 8.55570889e+00 8.56025314e+00 8.56586266e+00 8.79909325e+00 8.70808983e+00 9.15015793e+00 9.22718716e+00 9.25382423e+00 9.05667305e+00 8.55873966e+00 8.59455967e+00 8.77838135e+00 9.43782806e+00 9.68606186e+00 9.46932507e+00 8.91257572e+00 8.41166782e+00 8.64091110e+00 9.15361023e+00 9.35791779e+00 9.15057850e+00 8.76319313e+00 8.53802776e+00 8.40002823e+00 8.29666233e+00 8.25739288e+00 8.22955990e+00 8.31436443e+00 7.98817396e+00 7.75461340e+00 7.76704550e+00 8.52031517e+00 8.78123474e+00 8.63328838e+00 7.87832451e+00 7.64525127e+00 7.89115715e+00 8.45588207e+00 8.72702026e+00 8.26285934e+00 8.04171371e+00 7.98689985e+00 8.37588406e+00 8.49193382e+00 8.22265625e+00 7.87371826e+00 7.64104557e+00 7.55764246e+00 7.73960638e+00 7.24823856e+00 7.47796488e+00 7.70444489e+00 8.14108658e+00 8.01501083e+00 7.84063911e+00 8.03355312e+00 8.10451698e+00 7.94763184e+00 7.98642588e+00 7.58746243e+00 7.68946743e+00 7.73979568e+00 8.27044678e+00 8.48750019e+00 7.96319103e+00 7.63039303e+00 6.86782789e+00 7.16574097e+00 7.64553690e+00 8.14645576e+00 8.27243900e+00 7.64129305e+00 7.73918915e+00 7.86317110e+00 7.65687990e+00 5.53554296e+00 5.34756613e+00 6.04793692e+00 7.19253159e+00 6.50326490e+00 5.16155529e+00 -2.74259090e+00 -3.03350002e-01 -2.30399823e+00 -1.12409973e+02 -1.74468018e+02 4.93217590e+02 2.75730127e+03 101577368. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -426442016. 3.45783862e+03 5.05451874e+02 7.25331650e+01 4.99178658e+01 2.04391136e+01 1.02032595e+01 8.67888165e+00 5.28985500e+00 4.83933735e+00 5.20171547e+00 5.45521593e+00 5.67601633e+00 5.44258261e+00 5.53476238e+00 5.66768742e+00 6.23774481e+00 6.35134745e+00 5.74398756e+00 5.06079674e+00 4.44561672e+00 4.03872156e+00 4.16088676e+00 4.79718924e+00 5.67066145e+00 6.23874283e+00 5.34848070e+00 5.13922596e+00 5.49766588e+00 6.87938499e+00 6.57662821e+00 5.53264761e+00 4.89321804e+00 5.22416162e+00 5.82801962e+00 5.85074186e+00 5.37016916e+00 5.38069630e+00 5.30283976e+00 5.30861425e+00 5.42405605e+00 5.88718987e+00 6.32131243e+00 5.92317724e+00 5.85857296e+00 4.99574947e+00 3.75264812e+00 3.16516829e+00 4.98869228e+00 7.41244316e+00 7.62139654e+00 5.50623655e+00 4.48930216e+00 4.84051466e+00 5.92791462e+00 5.80372000e+00 5.13912678e+00 4.76309443e+00 4.71995878e+00 4.81191492e+00 4.09544182e+00 3.26559544e+00 3.28771663e+00 3.17096329e+00 3.04433560e+00 2.90149331e+00 3.61454201e+00 4.11465073e+00 3.82935977e+00 3.50999928e+00 2.90495181e+00 2.35703421e+00 1.98819208e+00 1.72277462e+00 2.39371133e+00 2.88273501e+00 2.18172479e+00 2.36345744e+00 3.37078190e+00 5.98004150e+00 6.98700714e+00 6.02922010e+00 4.98557234e+00 3.86094880e+00 3.56242919e+00 3.53546286e+00 3.96254635e+00 4.35984039e+00 3.95073533e+00 3.57528067e+00 3.79089808e+00 3.89434934e+00 3.70092201e+00 3.01873875e+00 2.97192717e+00 3.58060431e+00 2.73348045e+00 2.95554566e+00 2.95710158e+00 4.17354250e+00 4.33320189e+00 2.96732855e+00 2.89462399e+00 3.71399546e+00 5.37466145e+00 5.42564440e+00 3.85961151e+00 3.20547056e+00 2.55682945e+00 2.50600672e+00 2.07111287e+00 1.90350616e+00 2.21911955e+00 2.42438173e+00 2.42309976e+00 2.46067548e+00 2.81372428e+00 3.37617850e+00 3.08321214e+00 2.88206410e+00 3.28634763e+00 2.75916004e+00 2.64802504e+00 2.94182682e+00 4.35170031e+00 4.49680042e+00 2.79582930e+00 2.10532331e+00 3.05085325e+00 4.30685377e+00 4.35287619e+00 2.64473629e+00 2.24055362e+00 1.89383566e+00 1.94972837e+00 2.10932899e+00 2.63848233e+00 3.68839478e+00 3.29959631e+00 2.42828083e+00 2.35808349e+00 2.80733752e+00 3.77758121e+00 3.18007827e+00 2.68125153e+00 2.59795356e+00 1.91230404e+00 1.91618955e+00 1.45478690e+00 1.91561425e+00 1.99537456e+00 1.56958699e+00 1.47983384e+00 1.75629687e+00 2.74705553e+00 3.54766989e+00 3.09767699e+00 2.65849924e+00 1.82012820e+00 1.49867046e+00 1.18479371e+00 5.12574077e-01 4.22037840e-01 5.27041852e-01 9.26675498e-01 8.03223550e-01 4.89559948e-01 8.56256425e-01 2.00594831e+00 3.06847382e+00 3.49260640e+00 1.82549179e+00 1.08828390e+00 1.35362017e+00 2.20759177e+00 1.92768216e+00 9.98350620e-01 1.21315587e+00 7.85118639e-01 5.49153149e-01 2.43341327e-01 8.26097250e-01 1.28109896e+00 8.20141733e-01 3.65581930e-01 5.46067119e-01 4.61624503e-01 -5.02154231e-02 -7.33533442e-01 -1.67472756e+00 -1.97736168e+00 -2.47069478e+00 -7.60368645e-01 3.22622716e-01 8.99418712e-01 9.57780421e-01 -1.28481254e-01 1.91169783e-01 4.89847869e-01 2.07699490e+00 2.16013622e+00 9.39239085e-01 -8.72890279e-02 -7.49281645e-01 -5.32719076e-01 -1.09346581e+00 -1.71253562e+00 -1.54753530e+00 -1.19485402e+00 -9.39458966e-01 -1.02325022e+00 -6.04848862e-01 2.03821197e-01 7.19704330e-02 6.86663449e-01 5.17272651e-01 -9.18538034e-01 -2.21209621e+00 -2.10060334e+00 -4.71435398e-01 -8.81355330e-02 -5.44094205e-01 1.07104965e-01 1.06994987e+00 1.84542620e+00 2.10209751e+00 1.01503062e+00 9.92062166e-02 -1.32641542e+00 -1.59117246e+00 -4.85935092e-01 7.21023917e-01 1.02155757e+00 -1.41629800e-01 -7.75693715e-01 -4.10730630e-01 -1.88801274e-01 -1.41255066e-01 -3.47362548e-01 -3.43341887e-01 -6.02127969e-01 -6.07926011e-01 -7.66265750e-01 -6.62810385e-01 -3.62494707e-01 8.41194242e-02 1.97010145e-01 -2.55315393e-01 -8.81942868e-01 -7.94364572e-01 -5.56361794e-01 -4.25187796e-01 -7.94645309e-01 -1.39198649e+00 -1.91448283e+00 -2.00541019e+00 -1.53221381e+00 -8.70525539e-01 -9.71672654e-01 -1.09361899e+00 -1.20235848e+00 -1.19605255e+00 -1.43151379e+00 -1.42293978e+00 -1.34086096e+00 -1.17364025e+00 -1.24498737e+00 -9.79235888e-01 -6.57588601e-01 -8.29599321e-01 -1.09981036e+00 -1.15527165e+00 -1.17274535e+00 -1.20255005e+00 -1.52136958e+00 -1.42769563e+00 -1.64300156e+00 -2.05588365e+00 -2.14615083e+00 -2.11080289e+00 -1.87344313e+00 -1.90414393e+00 -1.87667823e+00 -1.62815177e+00 -1.46396565e+00 -1.68687499e+00 -1.86361527e+00 -2.02261591e+00 -1.75859737e+00 -1.84001160e+00 -1.88839924e+00 -2.09725380e+00 -2.05489945e+00 -1.86242294e+00 -1.76622713e+00 -1.96499503e+00 -2.40936923e+00 -2.69910383e+00 -2.53372622e+00 -2.48890090e+00 -2.46362305e+00 -2.54752278e+00 -2.44107890e+00 -2.54181767e+00 -2.71476722e+00 -2.55815721e+00 -2.31389546e+00 -2.18583894e+00 -2.45284915e+00 -2.46407175e+00 -2.21142507e+00 -2.12382102e+00 -2.35586739e+00 -2.70498133e+00 -3.18679762e+00 -3.49861789e+00 -3.70955777e+00 -3.34572029e+00 -2.99880219e+00 -2.90057826e+00 -3.77303338e+00 -4.14689779e+00 -3.81646252e+00 -3.46033311e+00 -3.16684628e+00 -3.40857959e+00 -3.10100627e+00 -3.45196033e+00 -4.40946293e+00 -5.00179672e+00 -4.27722263e+00 -3.18678284e+00 -2.69380260e+00 -3.05804420e+00 -3.36797285e+00 -3.44395709e+00 -3.67365742e+00 -3.63962340e+00 -3.67278218e+00 -3.62374353e+00 -3.65526652e+00 -3.51233530e+00 -3.61959887e+00 -4.02965307e+00 -4.36855268e+00 -4.92941856e+00 -5.21347380e+00 -5.16381168e+00 -4.68117762e+00 -4.34768963e+00 -4.66133881e+00 -4.80354500e+00 -4.45617819e+00 -3.97576499e+00 -3.69649053e+00 -4.03968191e+00 -4.04252148e+00 -4.29254770e+00 -4.17955208e+00 -4.51933336e+00 -4.25887871e+00 -4.42494678e+00 -5.13837576e+00 -5.76912355e+00 -5.13267803e+00 -3.59755039e+00 -3.34101462e+00 -3.89147925e+00 -4.76984406e+00 -4.92352724e+00 -5.12734127e+00 -5.09269333e+00 -5.12153959e+00 -5.12095261e+00 -4.85289526e+00 -4.44323635e+00 -3.70382786e+00 -4.81293488e+00 -6.36296940e+00 -7.02800226e+00 -6.00189400e+00 -4.57939434e+00 -4.41096354e+00 -4.45381308e+00 -4.61628771e+00 -4.48280668e+00 -4.23313999e+00 -3.87460184e+00 -4.14973116e+00 -4.67571068e+00 -5.05362654e+00 -4.84064770e+00 -4.85549498e+00 -5.04431581e+00 -5.07315874e+00 -5.03664684e+00 -4.89716434e+00 -4.66413403e+00 -4.46257448e+00 -4.89273977e+00 -6.05146885e+00 -6.31824303e+00 -6.19043303e+00 -6.42478085e+00 -7.25786543e+00 -8.09290409e+00 -8.01164246e+00 -7.09387875e+00 -6.25467110e+00 -5.70965958e+00 -5.80636978e+00 -6.01098728e+00 -6.20280170e+00 -5.75577927e+00 -5.48533487e+00 -5.47748804e+00 -5.92419195e+00 -5.96244764e+00 -6.50973654e+00 -6.98693180e+00 -7.21714401e+00 -6.52245569e+00 -5.90762281e+00 -5.75569344e+00 -5.91309547e+00 -5.99226427e+00 -5.97615194e+00 -5.99239969e+00 -5.97492027e+00 -5.83312845e+00 -5.68135023e+00 -5.87185717e+00 -5.98196268e+00 -5.92066479e+00 -5.63825512e+00 -5.77613640e+00 -5.97458649e+00 -6.47054863e+00 -6.49782944e+00 -6.42946529e+00 -6.08538628e+00 -6.00432825e+00 -6.32870340e+00 -6.65381098e+00 -6.93657112e+00 -6.99684715e+00 -6.92618275e+00 -6.58176994e+00 -6.24935818e+00 -6.76122427e+00 -7.85695505e+00 -9.56176758e+00 -9.65456676e+00 -1.00973158e+01 -1.06187124e+01 -1.16491995e+01 -2.07458782e+01 -1.95182037e+01 -1.41692295e+01 5.30399990e+00 -1.34680252e+02 -1.81718502e+01 3.00151611e+03 -282066272. 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. 0. 0. 0. 0. 0. 0. -81784528. 2.67599463e+03 3.97648926e+02 5.97523727e+01 1.93252048e+01 6.48943949e+00 -1.29447234e+00 -4.55261755e+00 -6.72727823e+00 -7.95745945e+00 -8.20499802e+00 -7.97051764e+00 -7.32353163e+00 -7.07227612e+00 -7.01866961e+00 -7.31046247e+00 -7.27217674e+00 -7.31872177e+00 -7.37237883e+00 -7.47170496e+00 -7.50063133e+00 -7.31789780e+00 -7.51994371e+00 -7.85989141e+00 -8.13168240e+00 -8.08845139e+00 -7.98810625e+00 -8.06961536e+00 -8.02643394e+00 -8.03628159e+00 -8.28120041e+00 -8.39977264e+00 -8.38978481e+00 -8.16441059e+00 -8.15606689e+00 -8.26526928e+00 -8.45618820e+00 -8.50301170e+00 -8.76762962e+00 -8.96575356e+00 -9.16871548e+00 -8.80249786e+00 -8.45151329e+00 -8.28831863e+00 -8.43832970e+00 -8.66089153e+00 -8.81126499e+00 -8.83521748e+00 -8.61297798e+00 -8.70248985e+00 -8.79564190e+00 -9.08059788e+00 -8.77377033e+00 -8.45651436e+00 -8.26308727e+00 -8.49071121e+00 -8.54310131e+00 -8.65589714e+00 -8.65666103e+00 -8.75029087e+00 -8.75417233e+00 -8.67777061e+00 -8.57039547e+00 -8.33060646e+00 -8.12491322e+00 -8.13849640e+00 -8.12813282e+00 -8.24044609e+00 -8.02072716e+00 -7.94686460e+00 -8.07596016e+00 -8.36652565e+00 -8.66833210e+00 -8.80544567e+00 -8.88066101e+00 -9.11565495e+00 -9.27369976e+00 -9.26732635e+00 -9.01556015e+00 -8.80389023e+00 -8.85740852e+00 -8.91005421e+00 -8.87961769e+00 -8.79202271e+00 -8.66277599e+00 -8.62042809e+00 -8.43533230e+00 -8.38102627e+00 -8.43832874e+00 -8.65948868e+00 -8.91318321e+00 -8.98802471e+00 -8.94019699e+00 -8.70591640e+00 -8.56530285e+00 -8.72073269e+00 -8.83345604e+00 -8.93312073e+00 -8.90005207e+00 -8.93019009e+00 -8.91049576e+00 -8.75849342e+00 -8.92977333e+00 -9.16195011e+00 -9.31468296e+00 -9.25164604e+00 -9.15253353e+00 -9.17388821e+00 -9.11863613e+00 -9.05967140e+00 -9.04466152e+00 -8.93659687e+00 -8.83232212e+00 -8.92528343e+00 -9.09712219e+00 -9.28885555e+00 -9.23453236e+00 -9.23135281e+00 -9.16299248e+00 -9.15978241e+00 -9.21356201e+00 -9.25183582e+00 -9.27300739e+00 -9.22047138e+00 -9.20351887e+00 -9.12712097e+00 -9.11040306e+00 -9.12803364e+00 -9.13193989e+00 -9.03547096e+00 -8.93438911e+00 -8.96928596e+00 -9.03290462e+00 -9.15976429e+00 -9.03341484e+00 -8.96778011e+00 -8.86725903e+00 -8.92874908e+00 -9.04051876e+00 -9.17576122e+00 -9.31546783e+00 -9.33316898e+00 -9.30621719e+00 -9.27677917e+00 -9.30068016e+00 -9.31706429e+00 -9.34170532e+00 -9.33421612e+00 -9.32462311e+00 -9.32066154e+00 -9.34343719e+00 -9.32588196e+00 -9.31419277e+00 -9.27338219e+00 -9.22729874e+00 -9.17977238e+00 -9.19909477e+00 -9.26280785e+00 -9.30205441e+00 -9.26936913e+00 -9.22274303e+00 -9.20301437e+00 -9.22033978e+00 -9.22904110e+00 -9.23978138e+00 -9.25825310e+00 -9.27153778e+00 -9.30260658e+00 -9.31328678e+00 -9.32646561e+00 -9.33141613e+00 -9.33159637e+00 -9.33257484e+00 -9.33515835e+00 -9.33448982e+00 -9.33408546e+00 -9.33641911e+00 -9.33847904e+00 -9.33352089e+00 -9.32730961e+00 -9.32956600e+00 -9.33946037e+00 -9.34599781e+00 -9.34563923e+00 -9.33222771e+00 -9.31825542e+00 -9.33065796e+00 -9.36160183e+00 -9.37352848e+00 -9.35044861e+00 -9.32644558e+00 -9.32044792e+00 -9.34014416e+00 -9.34843254e+00 -9.34791374e+00 -9.35167503e+00 -9.34482384e+00 -9.36008072e+00 -9.36601257e+00 -9.38674068e+00 -9.38770199e+00 -9.36306953e+00 -9.31391811e+00 -9.25817776e+00 -9.25327873e+00 -9.26653004e+00 -9.29422855e+00 -9.25988388e+00 -9.25059128e+00 -9.30175304e+00 -9.33784103e+00 -9.34923267e+00 -9.28100014e+00 -9.25934887e+00 -9.27560520e+00 -9.29474163e+00 -9.30467129e+00 -9.27753639e+00 -9.24551678e+00 -9.22158051e+00 -9.17177486e+00 -9.21045208e+00 -9.18183708e+00 -9.16129494e+00 -9.14422035e+00 -9.11845875e+00 -9.10840702e+00 -9.03284550e+00 -8.95316792e+00 -8.97156334e+00 -8.97586155e+00 -9.10114574e+00 -9.04263210e+00 -9.11720467e+00 -9.03920746e+00 -9.01340294e+00 -8.95668983e+00 -9.00980663e+00 -9.05406761e+00 -8.95530128e+00 -8.89670086e+00 -8.81943703e+00 -8.95977688e+00 -9.03777504e+00 -9.08848476e+00 -8.91620636e+00 -8.73620510e+00 -8.62447357e+00 -8.78868198e+00 -9.17504883e+00 -9.48351479e+00 -9.48850727e+00 -9.20202637e+00 -8.96728230e+00 -9.01826954e+00 -9.19071960e+00 -9.19632530e+00 -9.03830051e+00 -8.87537098e+00 -8.84183979e+00 -8.89715099e+00 -8.92632771e+00 -8.95862198e+00 -8.89835644e+00 -8.83466911e+00 -8.81347561e+00 -8.85422611e+00 -8.89382172e+00 -8.74174786e+00 -8.58250809e+00 -8.61861992e+00 -8.78676224e+00 -8.84756088e+00 -8.71752930e+00 -8.73167706e+00 -8.65337563e+00 -8.62701797e+00 -8.67229080e+00 -8.71589565e+00 -8.89425659e+00 -8.92172527e+00 -8.90371323e+00 -8.70139217e+00 -8.41315746e+00 -8.48304653e+00 -8.52220726e+00 -8.65693665e+00 -8.64323330e+00 -8.37335587e+00 -8.13881874e+00 -8.16511536e+00 -8.47177696e+00 -8.73323345e+00 -8.53727913e+00 -8.38566208e+00 -8.51180363e+00 -8.49821186e+00 -8.89984512e+00 -8.97311401e+00 -9.03114605e+00 -8.76575470e+00 -8.27778816e+00 -8.19210339e+00 -8.05211067e+00 -8.14368534e+00 -8.26042652e+00 -8.60784245e+00 -8.91569710e+00 -8.91439915e+00 -8.75400352e+00 -8.45038509e+00 -8.46726513e+00 -8.41682243e+00 -8.35484028e+00 -8.31239223e+00 -8.47988033e+00 -8.52237988e+00 -8.62605667e+00 -8.53734875e+00 -8.41859818e+00 -8.18540096e+00 -8.10798454e+00 -8.09405899e+00 -8.05520725e+00 -7.95708752e+00 -7.80103827e+00 -7.97957325e+00 -8.31418705e+00 -8.81967640e+00 -9.10202599e+00 -9.19496155e+00 -9.06057453e+00 -8.74959850e+00 -7.78854656e+00 -7.43774605e+00 -7.22952461e+00 -7.65829182e+00 -7.69808245e+00 -7.98971701e+00 -8.37861347e+00 -8.13988113e+00 -8.16491985e+00 -7.48267794e+00 -7.37700462e+00 -7.03385925e+00 -7.27243996e+00 -7.59931993e+00 -7.64340448e+00 -7.63775349e+00 -8.08024788e+00 -8.47109890e+00 -8.37324238e+00 -7.84550619e+00 -7.34344435e+00 -7.67368841e+00 -7.84873009e+00 -8.01759338e+00 -7.92170954e+00 -7.78300571e+00 -7.50472355e+00 -7.10361958e+00 -7.08237171e+00 -7.27817297e+00 -7.43913889e+00 -7.27400208e+00 -7.08399916e+00 -6.92237759e+00 -7.06574869e+00 -6.98105478e+00 -7.08068419e+00 -7.11792660e+00 -7.35028934e+00 -7.56124401e+00 -8.04927826e+00 -7.67140532e+00 -7.03002453e+00 -6.50645113e+00 -7.07929134e+00 -7.51042128e+00 -7.77597094e+00 -7.50146055e+00 -7.89540863e+00 -8.13285160e+00 -8.21219444e+00 -7.76272917e+00 -7.19617558e+00 -7.11083412e+00 -7.34459305e+00 -7.65100718e+00 -7.61151743e+00 -7.31716108e+00 -7.06587744e+00 -6.95555401e+00 -6.98089886e+00 -7.19975662e+00 -7.11447763e+00 -7.32268333e+00 -7.41800928e+00 -7.54842806e+00 -6.94055367e+00 -5.97464418e+00 -6.14073706e+00 -6.97261620e+00 -7.58799362e+00 -6.93809462e+00 -6.44643545e+00 -6.64096117e+00 -6.78405046e+00 -6.52513742e+00 -5.97810173e+00 -5.96771860e+00 -5.96101475e+00 -5.92428493e+00 -6.00492287e+00 -6.37390137e+00 -6.52369308e+00 -6.18834686e+00 -6.27534819e+00 -6.75308990e+00 -6.66501808e+00 -6.24332380e+00 -5.61088800e+00 -5.53580952e+00 -5.50442123e+00 -5.10463190e+00 -5.05768394e+00 -5.29558182e+00 -5.91206837e+00 -6.47141218e+00 -6.22128868e+00 -6.17501545e+00 -5.98516703e+00 -5.99769783e+00 -5.81427860e+00 -5.66745806e+00 -5.61745548e+00 -5.39689922e+00 -5.42660809e+00 -5.80720091e+00 -6.40484905e+00 -6.69555664e+00 -6.45379496e+00 -6.54403543e+00 -6.86874294e+00 -6.56050205e+00 -6.07691717e+00 -5.12294340e+00 -4.86265373e+00 -5.04712868e+00 -4.85080719e+00 -4.77518988e+00 -4.76501513e+00 -5.31011105e+00 -5.75865078e+00 -5.72592211e+00 -5.51110172e+00 -5.20203257e+00 -4.88708591e+00 -4.82931280e+00 -4.86853170e+00 -4.84668303e+00 -4.71611166e+00 -4.61565208e+00 -5.00191879e+00 -5.42226839e+00 -5.27546978e+00 -4.82054234e+00 -4.39121485e+00 -4.73420954e+00 -4.34682703e+00 -3.86422658e+00 -4.00469542e+00 -5.08604813e+00 -6.27394533e+00 -6.55526924e+00 -6.07794571e+00 -5.85744905e+00 -5.90004063e+00 -5.56678391e+00 -5.18579149e+00 -4.87873316e+00 -5.01356077e+00 -5.01625967e+00 -5.10617590e+00 -5.55740213e+00 -5.56026554e+00 -5.13935709e+00 -4.43549538e+00 -4.64629364e+00 -5.10300732e+00 -5.12410879e+00 -4.52619410e+00 -4.72677612e+00 -5.30626154e+00 -4.91782713e+00 -3.54161644e+00 -2.68395162e+00 -3.17683816e+00 -3.72287369e+00 -3.44166946e+00 -2.66868329e+00 -2.68549347e+00 -3.05137444e+00 -3.38747168e+00 -2.84588027e+00 -2.52014256e+00 -2.60604453e+00 -3.04130673e+00 -3.78076482e+00 -4.56034231e+00 -4.99725914e+00 -4.90053177e+00 -3.70227051e+00 -2.65529418e+00 -2.21793342e+00 -2.71914506e+00 -3.23638463e+00 -3.29792070e+00 -3.25187445e+00 -3.00204921e+00 -2.08915329e+00 -2.12022924e+00 -2.79803395e+00 -3.57218814e+00 -3.77167153e+00 -3.64121008e+00 -4.18573856e+00 -4.73576689e+00 -4.64550734e+00 -3.87723589e+00 -3.27685809e+00 -3.11276555e+00 -3.22775555e+00 -3.15677476e+00 -3.35330939e+00 -3.41790628e+00 -3.32416248e+00 -3.16453195e+00 -2.79488111e+00 -2.54921007e+00 -2.25487137e+00 -2.36001158e+00 -2.89589810e+00 -3.93789887e+00 -3.82438612e+00 -3.58790112e+00 -3.42412591e+00 -4.29469109e+00 -4.05453777e+00 -3.38351965e+00 -2.60652590e+00 -3.23705792e+00 -3.71203423e+00 -3.58143711e+00 -2.69116998e+00 -1.85837674e+00 -1.71696007e+00 -1.82125735e+00 -2.38494420e+00 -2.99188828e+00 -2.98466921e+00 -2.46658349e+00 -2.51366854e+00 -3.26974607e+00 -3.29610062e+00 -2.85480762e+00 -1.96545374e+00 -2.57413602e+00 -3.06942272e+00 -2.94743681e+00 -1.93329954e+00 -1.21231830e+00 -1.57315648e+00 -2.29666400e+00 -2.62083507e+00 -2.53832793e+00 -1.97376478e+00 -1.64029360e+00 -1.94025135e+00 -2.14575982e+00 -2.76502037e+00 -3.13913584e+00 -2.63507938e+00 -2.20894527e+00 -1.76424682e+00 -2.33147883e+00 -2.27792645e+00 -1.91681886e+00 -1.49590933e+00 -1.27872300e+00 -1.31444180e+00 -1.19237709e+00 -1.17545819e+00 -1.36248779e+00 -1.56190664e-01 3.36052626e-01 -1.76539621e-03 -8.25913489e-01 1.00648969e-01 1.77999568e+00 5.62052488e-01 -6.26685977e-01 -1.09783661e+00 3.30599248e-01 8.34816039e-01 2.98095345e+00 6.85705900e+00 9.00972748e+00 1.23485184e+01 5.02800713e+01 2.94248505e+02 3.59907684e+02 5.52438698e+01 8.66065216e+01 8.98959290e+02 7.17807250e+06 0. 0. 0. 0. 0. 1.20540652e+10 1.20540652e+10 -464729888. 3.92038375e+05 -8.43279453e+04 2.13765312e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1207435136. -3.15264465e+02 5.31466751e+01 -2.65683270e+01 1.05780821e+01 -2.18246269e+01 -1.93368587e+01 -9.38407230e+00 1.25488734e+00 2.81906486e+00 2.84479475e+00 3.13529682e+00 2.80621314e+00 2.19847488e+00 1.71357083e+00 2.60664725e+00 4.00179386e+00 4.93332815e+00 4.36725378e+00 1.61332822e+00 -7.72877216e-01 -1.59271502e+00 -9.75215316e-01 8.76724660e-01 1.49094903e+00 1.67979908e+00 3.08423018e+00 3.71319532e+00 2.81458783e+00 8.14976811e-01 -9.24788892e-01 -3.51984024e-01 1.43529904e+00 4.14227915e+00 4.82595253e+00 4.42108870e+00 3.94680643e+00 3.85173368e+00 3.61318302e+00 2.81611919e+00 1.84369016e+00 3.23895431e+00 4.11434889e+00 5.34082985e+00 3.69860268e+00 3.36054087e+00 2.85623741e+00 1.98749149e+00 2.73053956e+00 3.04462099e+00 4.80587435e+00 6.36840343e+00 7.79261732e+00 7.90996981e+00 5.49868488e+00 2.42126203e+00 1.65209234e+00 3.41324377e+00 6.72796202e+00 7.89205265e+00 6.59449244e+00 5.57188463e+00 4.49572420e+00 4.81457472e+00 4.19841909e+00 4.79463673e+00 5.25510406e+00 6.33040476e+00 7.37761450e+00 6.76028061e+00 6.50322104e+00 5.84887028e+00 5.70074081e+00 5.70391989e+00 5.54257822e+00 6.28767633e+00 7.70874882e+00 9.28900433e+00 9.17135906e+00 7.29339933e+00 6.11361027e+00 4.73770952e+00 5.44751596e+00 6.90557814e+00 8.01220512e+00 8.55671406e+00 9.03193092e+00 1.04223595e+01 9.64843941e+00 7.84411812e+00 5.38912058e+00 5.54853678e+00 7.02090740e+00 9.52711582e+00 9.98914528e+00 9.68057823e+00 9.90057755e+00 9.79168034e+00 9.57548523e+00 9.02163029e+00 7.96490812e+00 8.40333366e+00 8.65649796e+00 8.75202847e+00 6.99405336e+00 5.63617229e+00 5.33696222e+00 6.42634201e+00 8.39073563e+00 9.81506920e+00 9.17905903e+00 9.34818554e+00 1.08623972e+01 1.25147686e+01 1.05902033e+01 7.17720127e+00 6.91690731e+00 9.26204109e+00 1.23800611e+01 1.25961628e+01 1.15007706e+01 9.68566036e+00 8.30063438e+00 8.08864403e+00 9.40264225e+00 1.01708698e+01 1.10610304e+01 1.18981791e+01 1.28662672e+01 1.29219904e+01 1.18130016e+01 1.05781212e+01 1.03507576e+01 1.03523998e+01 1.12047577e+01 1.17839298e+01 1.27638693e+01 1.24201365e+01 1.28140697e+01 1.22339735e+01 1.08438168e+01 8.19251823e+00 7.08953571e+00 7.88041067e+00 9.52785873e+00 9.09812737e+00 1.01866817e+01 1.06383467e+01 1.14943857e+01 1.10905552e+01 9.32903671e+00 8.83970833e+00 9.95811367e+00 1.19907017e+01 1.31088228e+01 1.16821833e+01 1.03767662e+01 1.09786768e+01 1.23580570e+01 1.36359453e+01 1.20933418e+01 1.09161625e+01 1.14488974e+01 1.17569523e+01 1.18564310e+01 9.73190117e+00 8.31521702e+00 7.49595642e+00 1.01757412e+01 1.33436422e+01 1.46359625e+01 1.41935749e+01 1.36385870e+01 1.32441473e+01 1.29812965e+01 1.18689804e+01 1.12590189e+01 1.20849915e+01 1.32987041e+01 1.39048433e+01 1.31933842e+01 1.09931335e+01 1.13855381e+01 1.12483492e+01 1.25309534e+01 1.12826271e+01 1.10541849e+01 1.17131739e+01 1.30480032e+01 1.32479706e+01 1.38805838e+01 1.41414576e+01 1.40110664e+01 1.44189987e+01 1.53477154e+01 1.56929655e+01 1.52768602e+01 1.46038599e+01 1.36669550e+01 1.33696699e+01 1.34136581e+01 1.37222347e+01 1.49777555e+01 1.56377354e+01 1.67929592e+01 1.53451633e+01 1.45131674e+01 1.37529764e+01 1.41039095e+01 1.39232616e+01 1.39888010e+01 1.42621126e+01 1.53065701e+01 1.60257683e+01 1.60473347e+01 1.54121981e+01 1.42058506e+01 1.43016148e+01 1.44755487e+01 1.53380489e+01 1.58960619e+01 1.58862839e+01 1.54657917e+01 1.48233185e+01 1.52751474e+01 1.59129219e+01 1.61547680e+01 1.60980091e+01 1.58790455e+01 1.61382046e+01 1.63645763e+01 1.56829157e+01 1.65775452e+01 1.51034250e+01 1.59928999e+01 1.46684456e+01 1.53475771e+01 1.54419632e+01 1.71137142e+01 1.73757973e+01 1.62511501e+01 1.51019278e+01 1.58504658e+01 1.73543091e+01 1.74371395e+01 1.70235100e+01 1.57611408e+01 1.65930176e+01 1.70382214e+01 1.74329071e+01 1.71626244e+01 1.69734840e+01 1.76840134e+01 1.60444183e+01 1.66881618e+01 1.70510025e+01 1.87281189e+01 1.74359531e+01 1.60142193e+01 1.44553080e+01 1.48807917e+01 1.54290838e+01 1.73197803e+01 1.73601570e+01 1.83507652e+01 1.74304485e+01 1.62046318e+01 1.51021967e+01 1.56665583e+01 1.62135773e+01 1.64191074e+01 1.63238430e+01 1.73785152e+01 1.77878647e+01 1.79635468e+01 1.76414394e+01 1.80110950e+01 1.85159016e+01 1.79200993e+01 1.76259975e+01 1.76550369e+01 1.79126701e+01 1.82881413e+01 1.88186512e+01 1.91804810e+01 1.87798920e+01 1.79651432e+01 1.75262280e+01 1.77992573e+01 1.75305405e+01 1.72972450e+01 1.67824650e+01 1.69671078e+01 1.81051788e+01 1.78442516e+01 1.77425385e+01 1.73409672e+01 1.79897480e+01 1.76808014e+01 1.74733543e+01 1.73753452e+01 1.82158527e+01 1.89049187e+01 1.91899529e+01 1.87435646e+01 1.87197514e+01 1.94601421e+01 2.00738506e+01 2.00258369e+01 1.94496593e+01 1.87528934e+01 1.85245361e+01 1.84339027e+01 1.90494957e+01 1.95677528e+01 1.92233791e+01 1.81868477e+01 1.81782856e+01 1.89242077e+01 1.93376293e+01 1.80364704e+01 1.75172882e+01 1.82702732e+01 1.93110218e+01 2.01172981e+01 1.99578896e+01 2.04536343e+01 2.02739582e+01 2.00011921e+01 1.97952709e+01 1.97879524e+01 1.98939667e+01 1.95645199e+01 1.96539898e+01 2.00968266e+01 1.99945297e+01 1.93826714e+01 1.90575924e+01 1.94762974e+01 1.99777050e+01 1.98211327e+01 1.91983337e+01 1.91329651e+01 1.93418198e+01 1.96547565e+01 1.93433456e+01 1.93093834e+01 1.94478283e+01 1.95304966e+01 1.95176487e+01 1.97975922e+01 2.05739822e+01 2.07740211e+01 2.07154102e+01 2.01228790e+01 1.99341526e+01 1.97608376e+01 1.96072388e+01 1.96186352e+01 2.00063305e+01 2.01005077e+01 1.95254326e+01 1.90986996e+01 1.91460152e+01 1.97631855e+01 1.98328190e+01 1.96067028e+01 1.95174370e+01 1.92412148e+01 1.96755123e+01 1.95872040e+01 1.99234142e+01 1.97253876e+01 1.93585262e+01 1.91212997e+01 1.90790348e+01 1.96834984e+01 2.03540955e+01 2.02488480e+01 1.99658661e+01 1.96302853e+01 1.99706516e+01 2.03401508e+01 2.04469624e+01 2.06952991e+01 2.02922497e+01 2.00058327e+01 1.97329960e+01 1.99647617e+01 2.02399006e+01 2.03867416e+01 2.03192234e+01 2.02265301e+01 1.99621162e+01 1.98702793e+01 1.98333931e+01 2.01216984e+01 2.04583435e+01 2.04351349e+01 2.02888603e+01 2.02590179e+01 2.04827518e+01 2.04640274e+01 2.01101685e+01 1.98912125e+01 2.00195198e+01 2.02732067e+01 2.03941269e+01 2.03716335e+01 2.04952393e+01 2.04892635e+01 2.03701420e+01 2.02985439e+01 2.01990643e+01 2.03622284e+01 2.03031502e+01 2.03087063e+01 2.02638779e+01 2.02892551e+01 2.04873886e+01 2.05807838e+01 2.05443573e+01 2.04443111e+01 2.03047295e+01 2.03353615e+01 2.03849869e+01 2.04967194e+01 2.05651531e+01 2.05819950e+01 2.05226650e+01 2.04747601e+01 2.04760056e+01 2.05264149e+01 2.05222988e+01 2.05291138e+01 2.05267601e+01 2.05275192e+01 2.05241108e+01 2.05249557e+01 2.05137272e+01 2.04989624e+01 2.04931068e+01 2.05106354e+01 2.05688744e+01 2.06057758e+01 2.06135654e+01 2.05546474e+01 2.04774761e+01 2.04577007e+01 2.05504322e+01 2.05955257e+01 2.05153980e+01 2.04067783e+01 2.04113331e+01 2.05311661e+01 2.05485954e+01 2.05738239e+01 2.05283794e+01 2.05967808e+01 2.05944691e+01 2.05687656e+01 2.07357044e+01 2.06076641e+01 2.06481647e+01 2.04986992e+01 2.05471325e+01 2.04883747e+01 2.02999287e+01 2.05016975e+01 2.04860229e+01 2.04833832e+01 2.02345295e+01 2.02584972e+01 2.05268345e+01 2.06971302e+01 2.06943817e+01 2.03578739e+01 2.01898403e+01 2.02256927e+01 2.03643913e+01 2.04985294e+01 2.03357048e+01 2.01407776e+01 1.99223804e+01 1.98227577e+01 1.99718246e+01 2.03128185e+01 2.06471920e+01 2.04595718e+01 2.00753670e+01 1.97537479e+01 1.97731190e+01 1.99339466e+01 2.02598572e+01 2.04558544e+01 2.04490929e+01 2.00398884e+01 1.96840229e+01 1.97686882e+01 2.01517353e+01 2.04492493e+01 2.03494492e+01 1.99915180e+01 1.99526157e+01 1.98934383e+01 2.03315582e+01 2.06813679e+01 2.06769981e+01 2.05495033e+01 2.00681934e+01 1.98188248e+01 1.97263527e+01 1.98304482e+01 2.02955742e+01 2.02603149e+01 1.98841400e+01 1.96461487e+01 1.94443645e+01 1.99266224e+01 1.98869095e+01 1.97055264e+01 1.93169193e+01 1.92742729e+01 2.00021381e+01 2.04134407e+01 2.03146973e+01 1.94769440e+01 1.89466038e+01 1.87625027e+01 1.87989979e+01 1.91813183e+01 1.96095695e+01 1.97686634e+01 1.98021946e+01 1.94795380e+01 1.94399853e+01 1.96073017e+01 1.93591080e+01 1.92674332e+01 1.86922035e+01 1.88936729e+01 1.88362541e+01 1.89174747e+01 1.93366146e+01 1.94119129e+01 1.90291634e+01 1.81160545e+01 1.78346539e+01 1.81157093e+01 1.84468136e+01 1.87538471e+01 1.85167294e+01 1.81049519e+01 1.79562454e+01 1.79560394e+01 1.85819626e+01 1.89096527e+01 1.89851303e+01 1.87367306e+01 1.86129799e+01 1.88747196e+01 1.87388725e+01 1.86950073e+01 1.93347092e+01 1.94992638e+01 1.92501812e+01 1.87385960e+01 1.91631966e+01 1.99623127e+01 1.99670143e+01 1.93063965e+01 1.81479683e+01 1.75476360e+01 1.81583443e+01 1.84755726e+01 1.86192722e+01 1.81887112e+01 1.80104904e+01 1.83975887e+01 1.83223991e+01 1.86906624e+01 1.86435375e+01 1.86563473e+01 1.87291546e+01 1.83595676e+01 1.81040154e+01 1.82846775e+01 1.83535099e+01 1.88169422e+01 1.82459469e+01 1.82541389e+01 1.75959110e+01 1.77965813e+01 1.84609203e+01 1.86049690e+01 1.84944744e+01 1.79363689e+01 1.76331196e+01 1.81128101e+01 1.84521122e+01 1.94999905e+01 1.87203388e+01 1.75204372e+01 1.65937672e+01 1.65436325e+01 1.73166389e+01 1.71933689e+01 1.66577682e+01 1.61198254e+01 1.48564482e+01 1.42877073e+01 1.40301895e+01 1.41372194e+01 1.48101530e+01 1.78719101e+01 1.69788437e+01 1.00525875e+01 3.65278673e+00 -1.85717621e+01 -5.67441940e+00 -4.12129456e+02 -2.58943750e+03 101577368. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 438069216. -20963992. -3.31662964e+03 -1.36104004e+03 -9.78155823e+01 4.66088837e+02 3.52003510e+02 5.72480049e+01 3.70593834e+01 2.12657375e+01 1.60675640e+01 1.68882942e+01 1.72317009e+01 1.69262085e+01 1.48314476e+01 1.40507298e+01 1.33339405e+01 1.33493509e+01 1.35055132e+01 1.40179949e+01 1.42297983e+01 1.46007605e+01 1.39943771e+01 1.29706383e+01 1.26982298e+01 1.40173845e+01 1.41961594e+01 1.31491451e+01 1.13948011e+01 1.24334373e+01 1.38465099e+01 1.39815931e+01 1.31951141e+01 1.27682791e+01 1.29511671e+01 1.33117867e+01 1.25658808e+01 1.26168537e+01 1.31062260e+01 1.37083244e+01 1.36059856e+01 1.22820511e+01 1.29229460e+01 1.31324024e+01 1.36820440e+01 1.43119574e+01 1.37684717e+01 1.25266514e+01 1.01426373e+01 1.01455574e+01 1.20765953e+01 1.20665436e+01 1.18135653e+01 9.67558861e+00 1.04276876e+01 1.16081734e+01 1.27533760e+01 1.25257931e+01 1.12352753e+01 1.10825090e+01 1.15459261e+01 1.16503143e+01 1.23426485e+01 1.33464079e+01 1.29596415e+01 1.18499470e+01 1.04307909e+01 1.16011686e+01 1.18862286e+01 1.25364666e+01 1.27463350e+01 1.22106009e+01 1.15322485e+01 1.04678173e+01 1.08648949e+01 1.16279478e+01 1.08538656e+01 9.63233948e+00 7.27051115e+00 7.59498358e+00 9.46726227e+00 9.96505833e+00 1.05720119e+01 1.03474369e+01 1.00855904e+01 9.27318382e+00 8.15128326e+00 8.83746243e+00 9.06579971e+00 8.72642612e+00 8.96554279e+00 9.93485260e+00 1.14608107e+01 1.07881937e+01 9.35923672e+00 9.28236866e+00 9.16718578e+00 9.61179447e+00 9.24854279e+00 8.83485699e+00 1.03674259e+01 9.69471455e+00 8.69972038e+00 6.80434418e+00 6.79863024e+00 8.19390202e+00 8.53141403e+00 9.11141968e+00 9.84046650e+00 9.66150188e+00 9.98815823e+00 8.86802769e+00 9.50227451e+00 9.43147373e+00 9.42948818e+00 9.16637230e+00 8.06389141e+00 7.20681810e+00 6.93148613e+00 5.02887297e+00 5.60268879e+00 5.63903046e+00 6.63413906e+00 6.54668903e+00 5.21612740e+00 7.56539822e+00 7.53970957e+00 7.10089350e+00 4.61593723e+00 4.52384377e+00 6.47235107e+00 6.71992826e+00 6.84922266e+00 6.80629539e+00 6.74913073e+00 6.41100883e+00 5.47300148e+00 6.04470682e+00 6.19560099e+00 6.08005619e+00 5.67447805e+00 4.93187380e+00 5.83974266e+00 6.47200632e+00 6.71715689e+00 6.45081663e+00 6.77662849e+00 7.75036669e+00 8.71868801e+00 7.69303703e+00 6.99548054e+00 6.14676905e+00 6.54016924e+00 5.44131422e+00 3.96558309e+00 3.60893130e+00 3.66110754e+00 5.00600815e+00 5.41332006e+00 5.84033966e+00 6.31185818e+00 7.65223408e+00 7.16437340e+00 6.73725319e+00 5.94067526e+00 6.85061264e+00 6.17676497e+00 4.19619131e+00 2.60223579e+00 2.12539935e+00 4.46126652e+00 5.30108690e+00 4.66219950e+00 3.46520996e+00 3.42915702e+00 4.58395243e+00 4.26554346e+00 4.67285490e+00 4.81530809e+00 4.29978800e+00 3.68286777e+00 3.10679078e+00 3.90671515e+00 4.51377153e+00 3.56158710e+00 3.99066901e+00 4.03290129e+00 5.19053841e+00 5.64664364e+00 6.54169989e+00 6.96041727e+00 4.69343996e+00 2.82385707e+00 1.65395606e+00 1.91396224e+00 3.69371414e+00 3.77117276e+00 2.83829665e+00 7.08902895e-01 -4.24958728e-02 1.23428452e+00 1.89435089e+00 2.90778875e+00 2.52881765e+00 3.44149184e+00 4.15930939e+00 4.05867481e+00 3.78671503e+00 3.36228514e+00 3.24546528e+00 2.18242621e+00 9.67796028e-01 9.78187382e-01 9.09998491e-02 2.35510305e-01 2.54018855e+00 4.41920042e+00 3.98100042e+00 1.57380617e+00 2.17563853e-01 7.56910801e-01 9.80128273e-02 -4.90029663e-01 -1.53755832e+00 -2.14802551e+00 -1.89984560e+00 -1.03766513e+00 5.82724512e-01 1.84724700e+00 2.75349498e-01 -8.09690177e-01 -1.57790649e+00 -5.52470803e-01 -6.20372415e-01 -9.91704106e-01 -1.01785672e+00 -6.61800504e-01 -1.31656528e+00 -1.70535338e+00 -1.77196324e+00 -1.01319385e+00 -4.66026783e-01 -7.62004197e-01 -1.30063796e+00 -1.82191813e+00 -1.52087986e+00 -1.24438846e+00 -9.90852416e-01 -1.47848940e+00 -1.81818259e+00 -1.86879599e+00 -1.74886715e+00 -8.83117974e-01 -2.80343324e-01 -8.56477499e-01 -1.89307237e+00 -3.35789132e+00 -2.97578454e+00 -2.63772821e+00 -2.33913970e+00 -2.68141389e+00 -1.73082995e+00 -2.05243897e+00 -2.00192261e+00 -3.39437079e+00 -2.90509844e+00 -2.94482279e+00 -3.10359144e+00 -3.77249408e+00 -3.73955393e+00 -3.96429706e+00 -3.83094001e+00 -4.63278151e+00 -4.73741865e+00 -4.35016203e+00 -3.92476869e+00 -3.21448898e+00 -4.28542328e+00 -4.43114138e+00 -4.50653982e+00 -3.32490325e+00 -3.24269080e+00 -4.35761118e+00 -4.02563667e+00 -3.73733854e+00 -3.31749296e+00 -5.05502272e+00 -5.70949221e+00 -6.06167412e+00 -6.07200003e+00 -6.18806696e+00 -5.67357874e+00 -4.99913406e+00 -5.24996758e+00 -5.10866976e+00 -5.64401770e+00 -5.90437984e+00 -6.17426682e+00 -5.83537388e+00 -5.23782825e+00 -5.64991188e+00 -5.32075644e+00 -5.25007963e+00 -5.02719927e+00 -5.68750048e+00 -5.83635950e+00 -5.89017630e+00 -5.62231255e+00 -6.36057663e+00 -7.14630365e+00 -7.98757887e+00 -7.28830910e+00 -6.39752531e+00 -5.42265654e+00 -5.21022749e+00 -5.74663544e+00 -6.42011404e+00 -7.09877586e+00 -6.90287733e+00 -6.53915358e+00 -6.95797729e+00 -7.48791075e+00 -7.70679855e+00 -6.64416552e+00 -5.82963037e+00 -5.39779472e+00 -5.66084099e+00 -5.96510983e+00 -6.85851860e+00 -8.11660576e+00 -8.75037670e+00 -8.83294868e+00 -8.08162498e+00 -8.15567207e+00 -8.03211403e+00 -7.97457695e+00 -7.57458305e+00 -7.75843573e+00 -7.92822218e+00 -8.00959015e+00 -7.68197346e+00 -7.98212051e+00 -7.40090179e+00 -7.26658583e+00 -6.21849775e+00 -5.99542856e+00 -6.52331924e+00 -7.28948021e+00 -8.24216843e+00 -7.50145435e+00 -7.11211491e+00 -7.43274879e+00 -8.23149014e+00 -7.88674593e+00 -7.27515316e+00 -6.70266151e+00 -7.82229233e+00 -8.00858688e+00 -8.57055950e+00 -8.21308041e+00 -8.42796040e+00 -8.67792130e+00 -9.00074673e+00 -1.03225336e+01 -1.14572639e+01 -1.14888496e+01 -1.10341558e+01 -1.00347414e+01 -1.04719677e+01 -1.05072956e+01 -1.06983948e+01 -1.07907801e+01 -1.01091557e+01 -9.87250710e+00 -9.44301510e+00 -9.68484974e+00 -9.80316067e+00 -1.00621595e+01 -1.03395834e+01 -1.05317144e+01 -1.11465187e+01 -1.10348854e+01 -1.07894869e+01 -1.10377741e+01 -1.16165543e+01 -1.23277988e+01 -1.25485191e+01 -1.21886492e+01 -1.13285637e+01 -1.09747496e+01 -1.09087105e+01 -1.12489319e+01 -1.11575365e+01 -1.11043177e+01 -1.14115953e+01 -1.13522053e+01 -1.16284542e+01 -1.17078819e+01 -1.31432352e+01 -1.26945705e+01 -1.21597462e+01 -1.14824591e+01 -1.14943743e+01 -1.14918718e+01 -1.07153673e+01 -1.02716064e+01 -1.07850733e+01 -1.11973085e+01 -1.18029985e+01 -1.15989714e+01 -1.19657831e+01 -1.18369055e+01 -1.26349773e+01 -1.28423643e+01 -1.29624395e+01 -1.22885914e+01 -1.21165304e+01 -1.19550171e+01 -1.17383080e+01 -1.16769533e+01 -1.18828268e+01 -1.22404842e+01 -1.23732395e+01 -1.27440577e+01 -1.34661970e+01 -1.38973036e+01 -1.40211668e+01 -1.32877235e+01 -1.31027651e+01 -1.33732357e+01 -1.36933575e+01 -1.37651424e+01 -1.38792944e+01 -1.38927555e+01 -1.39595051e+01 -1.38245354e+01 -1.40966215e+01 -1.42296667e+01 -1.43878822e+01 -1.45076141e+01 -1.47074747e+01 -1.41403093e+01 -1.41452322e+01 -1.40029936e+01 -1.42180605e+01 -1.41568651e+01 -1.43079748e+01 -1.49916258e+01 -1.54521408e+01 -1.79110756e+01 -1.83560085e+01 -1.74671726e+01 -1.31774349e+01 -1.35051222e+01 -1.56949129e+01 -1.40124893e+01 -2.00916252e+01 -3.02932529e+01 -3.20973434e+01 -4.45365219e+01 -3.61876221e+01 8.52537384e+01 2.61013892e+03 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. 0. 0. 0. 0. 0. 0. 0. 182845424. -7.13839551e+03 -1.33769763e+03 -2.15376068e+02 -1.06947182e+02 -5.68253403e+01 3.37750580e+02 2.47708527e+02 3.84060326e+01 7.66376877e+00 -8.69993687e+00 -1.16915331e+01 -1.42511215e+01 -1.56325560e+01 -1.75116768e+01 -1.75920105e+01 -1.78299179e+01 -1.81570435e+01 -1.84939518e+01 -1.84800186e+01 -1.83610744e+01 -1.75657406e+01 -1.66901627e+01 -1.66394539e+01 -1.68914585e+01 -1.75082150e+01 -1.73905869e+01 -1.75279160e+01 -1.76970177e+01 -1.78887978e+01 -1.81353207e+01 -1.78531151e+01 -1.76259708e+01 -1.74729252e+01 -1.75680714e+01 -1.74317112e+01 -1.78873215e+01 -1.80058327e+01 -1.82243156e+01 -1.79540844e+01 -1.81992378e+01 -1.83286057e+01 -1.83352985e+01 -1.84803925e+01 -1.83368855e+01 -1.83047295e+01 -1.80682640e+01 -1.80552597e+01 -1.83780460e+01 -1.91107388e+01 -1.92362041e+01 -1.87679005e+01 -1.81253986e+01 -1.80811596e+01 -1.83268642e+01 -1.85390167e+01 -1.85871696e+01 -1.84580116e+01 -1.82476616e+01 -1.81912251e+01 -1.83305588e+01 -1.85438538e+01 -1.92639732e+01 -1.96223221e+01 -1.97393608e+01 -1.97956505e+01 -1.98069534e+01 -2.00223026e+01 -1.96464062e+01 -1.92416630e+01 -1.89858646e+01 -1.87153835e+01 -1.86963406e+01 -1.88539619e+01 -1.87190056e+01 -1.85684757e+01 -1.80155773e+01 -1.79479408e+01 -1.80832424e+01 -1.86369190e+01 -1.91405926e+01 -1.92919502e+01 -1.93212318e+01 -1.96527271e+01 -1.94936466e+01 -1.99413681e+01 -1.98688030e+01 -2.00390358e+01 -1.96244755e+01 -1.93470993e+01 -1.92850170e+01 -1.94629917e+01 -1.98256187e+01 -2.02828598e+01 -2.03450241e+01 -2.00008469e+01 -1.98310642e+01 -1.98589859e+01 -2.00896244e+01 -2.00497932e+01 -2.01477928e+01 -2.00715294e+01 -1.98878441e+01 -1.98144608e+01 -1.97057590e+01 -1.99446507e+01 -2.00028400e+01 -2.01703663e+01 -2.03364506e+01 -2.04043388e+01 -2.06713085e+01 -2.06295261e+01 -2.05851116e+01 -2.01974888e+01 -1.97992458e+01 -1.96195316e+01 -1.96121845e+01 -1.96896820e+01 -1.98131065e+01 -1.99088154e+01 -1.99333916e+01 -1.99026070e+01 -2.00408592e+01 -2.01830368e+01 -2.02771950e+01 -2.01647758e+01 -2.01161289e+01 -2.02441559e+01 -2.04746876e+01 -2.06458035e+01 -2.05796432e+01 -2.05191460e+01 -2.05492859e+01 -2.05827675e+01 -2.06484165e+01 -2.06842442e+01 -2.07047138e+01 -2.05865364e+01 -2.04441776e+01 -2.03402939e+01 -2.02810745e+01 -2.02775421e+01 -2.02969818e+01 -2.03262444e+01 -2.03732224e+01 -2.03413544e+01 -2.03730392e+01 -2.04169750e+01 -2.04947395e+01 -2.04818611e+01 -2.04650497e+01 -2.04590740e+01 -2.04576702e+01 -2.04882183e+01 -2.05441628e+01 -2.05566063e+01 -2.05177212e+01 -2.04965153e+01 -2.05247154e+01 -2.05907745e+01 -2.05730782e+01 -2.06032772e+01 -2.05867462e+01 -2.06092510e+01 -2.05606670e+01 -2.05316010e+01 -2.05101204e+01 -2.05080624e+01 -2.05128613e+01 -2.05096645e+01 -2.05293865e+01 -2.05321198e+01 -2.05293026e+01 -2.05307236e+01 -2.05322762e+01 -2.05278568e+01 -2.05243092e+01 -2.05341663e+01 -2.05428295e+01 -2.05387135e+01 -2.05271626e+01 -2.05267239e+01 -2.05349350e+01 -2.05515976e+01 -2.05468521e+01 -2.05244923e+01 -2.04677696e+01 -2.04641800e+01 -2.05068378e+01 -2.05437603e+01 -2.05201168e+01 -2.04396725e+01 -2.04336319e+01 -2.04672832e+01 -2.04789696e+01 -2.04497108e+01 -2.03801041e+01 -2.03999367e+01 -2.04358940e+01 -2.04329090e+01 -2.04079456e+01 -2.04968433e+01 -2.06162167e+01 -2.06227913e+01 -2.05201740e+01 -2.04386749e+01 -2.03973923e+01 -2.03771133e+01 -2.03365078e+01 -2.03837299e+01 -2.03310051e+01 -2.03124485e+01 -2.02564831e+01 -2.03324528e+01 -2.02764988e+01 -2.03165264e+01 -2.02337990e+01 -2.02355537e+01 -2.01864681e+01 -2.02778301e+01 -2.02509899e+01 -2.02443333e+01 -2.02128506e+01 -2.02530556e+01 -2.02922573e+01 -2.02474022e+01 -2.03606529e+01 -2.04656029e+01 -2.04212265e+01 -2.03379745e+01 -2.01574898e+01 -2.02024288e+01 -2.02030449e+01 -2.02789307e+01 -2.03314629e+01 -2.03518753e+01 -2.01947021e+01 -2.02303200e+01 -2.02648735e+01 -2.03150444e+01 -2.00834866e+01 -1.99950485e+01 -1.99387302e+01 -2.00159454e+01 -2.01194363e+01 -2.02535305e+01 -2.02460308e+01 -2.00703411e+01 -1.95986233e+01 -1.93673801e+01 -1.93306103e+01 -1.95516911e+01 -1.99810390e+01 -1.98455467e+01 -1.93977375e+01 -1.89909534e+01 -1.90719318e+01 -1.96409760e+01 -1.97802734e+01 -1.97402191e+01 -1.96274223e+01 -1.96295910e+01 -1.96912098e+01 -1.97206707e+01 -1.97921963e+01 -1.97343636e+01 -1.95720654e+01 -1.96663265e+01 -1.96578331e+01 -1.96848164e+01 -1.92654152e+01 -1.93184986e+01 -1.93293114e+01 -1.98287201e+01 -1.97973614e+01 -1.97871227e+01 -1.93682995e+01 -1.90789604e+01 -1.88243694e+01 -1.84728813e+01 -1.85574303e+01 -1.87887974e+01 -1.94130688e+01 -1.94151745e+01 -1.92901325e+01 -1.90511513e+01 -1.89855900e+01 -1.91107292e+01 -1.92041454e+01 -1.89415379e+01 -1.88448601e+01 -1.85698166e+01 -1.85976353e+01 -1.84993114e+01 -1.82995567e+01 -1.82754822e+01 -1.80758686e+01 -1.77844410e+01 -1.80432358e+01 -1.85410137e+01 -1.89601707e+01 -1.86335278e+01 -1.82492409e+01 -1.83546810e+01 -1.81739883e+01 -1.78541603e+01 -1.74592285e+01 -1.74036732e+01 -1.74745293e+01 -1.77702904e+01 -1.77666454e+01 -1.78638515e+01 -1.81594868e+01 -1.82995548e+01 -1.84603081e+01 -1.85061436e+01 -1.77920761e+01 -1.79318066e+01 -1.78511620e+01 -1.83257008e+01 -1.82113781e+01 -1.80867138e+01 -1.82510338e+01 -1.81249657e+01 -1.80707836e+01 -1.78488770e+01 -1.75069942e+01 -1.68960857e+01 -1.62654572e+01 -1.58696871e+01 -1.60257645e+01 -1.59623365e+01 -1.68136501e+01 -1.71792603e+01 -1.77394104e+01 -1.74481506e+01 -1.72548447e+01 -1.67951202e+01 -1.64157829e+01 -1.65681534e+01 -1.67896442e+01 -1.74681244e+01 -1.79624882e+01 -1.80481663e+01 -1.78776474e+01 -1.74621162e+01 -1.70699215e+01 -1.68273678e+01 -1.65233479e+01 -1.60238018e+01 -1.62704506e+01 -1.66030865e+01 -1.74367695e+01 -1.70986462e+01 -1.64870796e+01 -1.62258968e+01 -1.61267147e+01 -1.64679375e+01 -1.67454472e+01 -1.74054184e+01 -1.71425495e+01 -1.71805801e+01 -1.68813400e+01 -1.70098667e+01 -1.70535927e+01 -1.67610970e+01 -1.64979496e+01 -1.64176044e+01 -1.68110943e+01 -1.66818581e+01 -1.61612911e+01 -1.54390812e+01 -1.44563055e+01 -1.53083448e+01 -1.59075708e+01 -1.64190102e+01 -1.52405901e+01 -1.52830048e+01 -1.47349272e+01 -1.50036306e+01 -1.40473576e+01 -1.41690388e+01 -1.40598879e+01 -1.44366808e+01 -1.51269417e+01 -1.49653883e+01 -1.47681646e+01 -1.39697151e+01 -1.40264044e+01 -1.40482969e+01 -1.46290321e+01 -1.47350225e+01 -1.48165035e+01 -1.44825153e+01 -1.45564089e+01 -1.42507200e+01 -1.36228390e+01 -1.25689850e+01 -1.32790270e+01 -1.50425320e+01 -1.54054127e+01 -1.39179258e+01 -1.29862070e+01 -1.35692329e+01 -1.43536272e+01 -1.44261332e+01 -1.46125765e+01 -1.49073982e+01 -1.53057508e+01 -1.46993065e+01 -1.45488548e+01 -1.47313023e+01 -1.52652960e+01 -1.42248955e+01 -1.37608137e+01 -1.37567930e+01 -1.38954592e+01 -1.27375603e+01 -1.28758478e+01 -1.34758902e+01 -1.44092712e+01 -1.36927538e+01 -1.37023306e+01 -1.43862867e+01 -1.44824429e+01 -1.42219801e+01 -1.34996109e+01 -1.34074373e+01 -1.36853657e+01 -1.34453440e+01 -1.24828062e+01 -1.21169071e+01 -1.21595411e+01 -1.28574305e+01 -1.31131458e+01 -1.36373224e+01 -1.32473211e+01 -1.20817909e+01 -1.11184568e+01 -1.10742216e+01 -1.14955616e+01 -1.11440763e+01 -1.03795080e+01 -1.03906374e+01 -1.11076260e+01 -1.28215246e+01 -1.40473881e+01 -1.39206123e+01 -1.34453411e+01 -1.27088604e+01 -1.20988407e+01 -1.10063581e+01 -1.04880238e+01 -1.10812435e+01 -1.13383474e+01 -1.11564960e+01 -1.11778297e+01 -1.14485893e+01 -1.15061083e+01 -1.15438728e+01 -1.11366711e+01 -1.13672066e+01 -1.02035904e+01 -9.75279713e+00 -9.95681763e+00 -1.09130764e+01 -1.18565264e+01 -1.09930277e+01 -1.13450747e+01 -1.12935314e+01 -1.06926479e+01 -8.95317268e+00 -7.29416370e+00 -7.17042875e+00 -7.84304905e+00 -8.52966022e+00 -8.56849003e+00 -8.73795986e+00 -8.77614117e+00 -9.05042934e+00 -8.88982296e+00 -8.80268860e+00 -8.30772686e+00 -7.70232725e+00 -7.85053778e+00 -8.77895737e+00 -9.94079304e+00 -9.61286259e+00 -8.78219032e+00 -8.19117641e+00 -8.88853836e+00 -8.87150764e+00 -8.30249310e+00 -8.72359180e+00 -1.02672129e+01 -1.12251406e+01 -1.07962685e+01 -9.70516109e+00 -1.01918726e+01 -1.09130955e+01 -1.09660416e+01 -1.04501362e+01 -9.45710278e+00 -9.17137718e+00 -9.29074383e+00 -9.58387566e+00 -9.86330605e+00 -8.66633129e+00 -7.02734804e+00 -5.94767094e+00 -5.69922590e+00 -6.78192711e+00 -7.70490026e+00 -8.29688931e+00 -7.86605644e+00 -7.71340799e+00 -7.76475239e+00 -8.26371861e+00 -8.51495361e+00 -9.63474369e+00 -8.61443996e+00 -7.68016195e+00 -5.66579866e+00 -5.79874182e+00 -6.23235941e+00 -5.65585089e+00 -5.05856752e+00 -5.02106237e+00 -5.93935490e+00 -6.64330435e+00 -6.37654734e+00 -6.59521675e+00 -6.27638340e+00 -6.04215717e+00 -5.72088003e+00 -5.43788815e+00 -5.65228081e+00 -5.46288061e+00 -5.55981922e+00 -5.84360313e+00 -6.40839720e+00 -6.19438601e+00 -5.66707468e+00 -5.05344534e+00 -5.07897902e+00 -4.81217241e+00 -4.62972498e+00 -5.13941956e+00 -5.74918509e+00 -5.88745737e+00 -4.53587055e+00 -3.91277242e+00 -4.27582598e+00 -5.29745674e+00 -5.83138752e+00 -5.37563992e+00 -4.63844204e+00 -3.72006583e+00 -3.55319357e+00 -3.93239188e+00 -5.65311575e+00 -5.16326332e+00 -4.00068951e+00 -2.94629502e+00 -2.80997729e+00 -4.53831768e+00 -3.22767401e+00 -2.68302536e+00 -2.62599707e+00 -4.37408495e+00 -5.44269133e+00 -4.03071642e+00 -2.99925685e+00 -3.30727148e+00 -3.64598298e+00 -3.79969931e+00 -3.32357454e+00 -2.76320696e+00 -1.80782545e+00 -5.31944990e-01 -7.75305867e-01 -1.80046868e+00 -2.58006883e+00 -2.42754507e+00 -1.84689903e+00 -2.06083679e+00 -1.96349859e+00 -1.80949593e+00 -2.15243745e+00 -1.93262243e+00 -2.88826680e+00 -2.32354164e+00 -2.58552933e+00 -2.74440527e+00 -3.02154231e+00 -2.06620026e+00 -4.89707679e-01 8.10600638e-01 -3.65463316e-01 -1.69600224e+00 -2.55892205e+00 -2.15294480e+00 -6.78739250e-01 1.14450431e+00 2.97080970e+00 5.82051897e+00 2.72535038e+00 1.72136235e+00 3.95939755e+00 6.24109497e+01 1.42756332e+02 1.22131995e+03 2.69862695e+03 9.15784688e+05 -804432768. 0. 0. 0. 0. 0. 1.20540652e+10 2.93549184e+09 4.35707764e+03 5.76740391e+04 -8.43279453e+04 2.13765312e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.57624832e+09 1.88538379e+04 9.61059448e+02 3.26793146e+00 -5.00432358e+01 -4.15819645e+00 -1.47223024e+01 8.98588002e-01 -8.62737715e-01 -2.11111498e+00 -1.99459612e+00 -1.37488472e+00 -5.21415949e-01 1.80822158e+00 3.74407911e+00 4.98995972e+00 3.54372120e+00 1.41845787e+00 1.14163494e+00 1.08574009e+00 3.93432641e+00 5.78918219e+00 8.46823883e+00 7.91985416e+00 6.52111387e+00 5.06796551e+00 5.00576353e+00 2.01795125e+00 1.27954924e+00 3.11344695e+00 8.16462231e+00 1.10543146e+01 9.51481438e+00 7.54289675e+00 4.50616693e+00 4.26714706e+00 4.76532173e+00 5.60124874e+00 6.98501635e+00 7.48354959e+00 8.83271790e+00 1.02457314e+01 9.61480045e+00 8.13795567e+00 7.33705330e+00 8.59363174e+00 8.64729691e+00 7.58023167e+00 8.42418289e+00 9.37933445e+00 9.24050140e+00 8.95322609e+00 6.73912573e+00 6.33938360e+00 6.19216347e+00 1.00718737e+01 1.33399506e+01 1.41490231e+01 1.18477125e+01 9.03338528e+00 9.63704586e+00 1.07467890e+01 1.20697880e+01 1.12266283e+01 1.10281992e+01 1.23377438e+01 1.37076826e+01 1.35717287e+01 1.14519520e+01 9.27568150e+00 1.03791161e+01 1.06775713e+01 1.06584911e+01 1.12367220e+01 1.19154291e+01 1.28312626e+01 1.19194241e+01 9.79024696e+00 8.78583336e+00 8.07664108e+00 1.11175814e+01 1.30589476e+01 1.67380085e+01 1.58885212e+01 1.36039457e+01 1.23762712e+01 1.30281830e+01 1.29310007e+01 9.95626163e+00 1.14186211e+01 1.42423048e+01 1.80549183e+01 1.70423241e+01 1.32201824e+01 1.12239161e+01 1.17085619e+01 1.41368713e+01 1.20711079e+01 1.30528574e+01 1.31564474e+01 1.59379749e+01 1.55052929e+01 1.44595165e+01 1.32039871e+01 1.21823797e+01 1.44377956e+01 1.61225319e+01 1.78857784e+01 1.77922459e+01 1.56356716e+01 1.45154076e+01 1.48337851e+01 1.57244883e+01 1.45293589e+01 1.40762777e+01 1.47525253e+01 1.66880093e+01 1.71267605e+01 1.68143196e+01 1.55554438e+01 1.46094961e+01 1.50927935e+01 1.57320356e+01 1.85248260e+01 1.94018192e+01 1.87376251e+01 1.79450340e+01 1.72611237e+01 1.53972721e+01 1.45387335e+01 1.50365868e+01 1.68889866e+01 1.76790009e+01 1.88974476e+01 2.00052738e+01 2.00579987e+01 1.86096039e+01 1.85245514e+01 1.77788506e+01 1.67836819e+01 1.62733192e+01 1.87748394e+01 2.16281357e+01 2.42195778e+01 2.33235016e+01 2.29467030e+01 2.14282322e+01 2.09744663e+01 2.09784565e+01 2.20001831e+01 2.17224407e+01 2.14599800e+01 2.15839272e+01 2.06748981e+01 1.96504135e+01 1.93304081e+01 2.08977528e+01 2.22726974e+01 2.15424004e+01 2.21688824e+01 2.21818447e+01 2.38685665e+01 2.42729664e+01 2.30974503e+01 2.25991821e+01 2.14909611e+01 2.37462521e+01 2.52471046e+01 2.71372108e+01 2.47450924e+01 2.26166477e+01 2.14557991e+01 2.11319218e+01 2.10445976e+01 2.13271465e+01 2.32996082e+01 2.62072105e+01 2.61817112e+01 2.44375515e+01 2.07973518e+01 2.13493099e+01 2.39505730e+01 2.52723312e+01 2.68887215e+01 2.60939751e+01 2.77158260e+01 2.64111538e+01 2.70458622e+01 2.47553139e+01 2.46585617e+01 2.42166481e+01 2.55019646e+01 2.49402523e+01 2.56257496e+01 2.42796955e+01 2.31234913e+01 2.29205379e+01 2.29310570e+01 2.32203064e+01 2.22760372e+01 2.47660656e+01 2.64745884e+01 2.71944103e+01 2.52879810e+01 2.21511860e+01 2.30764866e+01 2.33989048e+01 2.67507801e+01 2.51841583e+01 2.52723255e+01 2.53984795e+01 2.67237930e+01 2.58760567e+01 2.51906281e+01 2.47462826e+01 2.65782375e+01 2.73678703e+01 2.96979942e+01 2.84627495e+01 2.63983669e+01 2.35556335e+01 2.44232521e+01 2.63018246e+01 2.81712360e+01 2.87007236e+01 2.91369400e+01 2.73976116e+01 2.68610134e+01 2.63924751e+01 2.72983742e+01 2.76190853e+01 2.83140564e+01 2.73677273e+01 2.71125469e+01 2.71600075e+01 2.88489246e+01 2.91390839e+01 2.91581364e+01 2.87626705e+01 2.78204231e+01 2.74732704e+01 2.94249954e+01 3.13501873e+01 3.09129066e+01 2.87604675e+01 2.78910141e+01 2.78759632e+01 2.90243607e+01 2.97637386e+01 3.12953854e+01 3.19075375e+01 3.20686150e+01 3.16875362e+01 2.94232960e+01 3.12287865e+01 3.04276829e+01 3.16962471e+01 2.92424297e+01 3.05374050e+01 3.10409813e+01 3.24264297e+01 3.34543991e+01 3.24660301e+01 3.18747826e+01 3.07501144e+01 3.00011330e+01 3.16239891e+01 3.31675301e+01 3.42465630e+01 3.24820900e+01 3.27769432e+01 3.34949532e+01 3.45289726e+01 3.24239807e+01 3.17050095e+01 3.11058712e+01 3.15577564e+01 3.16683083e+01 3.15908089e+01 3.26615524e+01 3.25718422e+01 3.34287758e+01 3.15981407e+01 3.11574478e+01 3.08177185e+01 3.12045135e+01 3.23271408e+01 3.18171234e+01 3.24653778e+01 3.24986191e+01 3.34306717e+01 3.42267113e+01 3.52138023e+01 3.48017807e+01 3.51844444e+01 3.50759659e+01 3.54788322e+01 3.37921295e+01 3.33639259e+01 3.30533180e+01 3.51170769e+01 3.48500137e+01 3.45381279e+01 3.33605843e+01 3.40470810e+01 3.48198242e+01 3.53590317e+01 3.46640663e+01 3.48761215e+01 3.43974037e+01 3.49271545e+01 3.43953400e+01 3.47268333e+01 3.40937424e+01 3.37871284e+01 3.31497040e+01 3.42189331e+01 3.58464127e+01 3.64404449e+01 3.56440544e+01 3.52143669e+01 3.57933350e+01 3.65176544e+01 3.52406616e+01 3.47971535e+01 3.49349442e+01 3.51542892e+01 3.50139122e+01 3.48324966e+01 3.56324348e+01 3.56556969e+01 3.53564529e+01 3.54527702e+01 3.56282463e+01 3.57880173e+01 3.52529869e+01 3.57418175e+01 3.61095390e+01 3.66928520e+01 3.62866058e+01 3.68085594e+01 3.70096436e+01 3.76165810e+01 3.64050522e+01 3.62730751e+01 3.64148026e+01 3.75018730e+01 3.75171623e+01 3.68670197e+01 3.63529396e+01 3.66979752e+01 3.64761009e+01 3.61398392e+01 3.55182533e+01 3.58973999e+01 3.64941597e+01 3.68029900e+01 3.68652496e+01 3.66361313e+01 3.66664314e+01 3.62082634e+01 3.60287399e+01 3.68589745e+01 3.75640984e+01 3.82469940e+01 3.75113411e+01 3.74446602e+01 3.70368042e+01 3.70363541e+01 3.69705582e+01 3.68639565e+01 3.69128685e+01 3.71125145e+01 3.76549034e+01 3.84169273e+01 3.86775475e+01 3.84648552e+01 3.74978218e+01 3.70128517e+01 3.71154366e+01 3.75977211e+01 3.72318726e+01 3.67005424e+01 3.64330254e+01 3.70093765e+01 3.71164246e+01 3.72002640e+01 3.74116554e+01 3.79090118e+01 3.82950554e+01 3.83866539e+01 3.79560051e+01 3.77710724e+01 3.76098328e+01 3.78911667e+01 3.82262611e+01 3.83280640e+01 3.84767990e+01 3.80347672e+01 3.80098000e+01 3.78422585e+01 3.77579651e+01 3.74631081e+01 3.76130905e+01 3.82156754e+01 3.85087357e+01 3.84850655e+01 3.81953964e+01 3.80758362e+01 3.80485535e+01 3.78706970e+01 3.79973412e+01 3.81725578e+01 3.83014946e+01 3.82856331e+01 3.82623062e+01 3.82133522e+01 3.84111366e+01 3.83682213e+01 3.84726677e+01 3.82334137e+01 3.81972923e+01 3.80944443e+01 3.81686783e+01 3.82740822e+01 3.83722954e+01 3.83397408e+01 3.81914215e+01 3.80623283e+01 3.80991287e+01 3.81161690e+01 3.82002373e+01 3.81395912e+01 3.81391602e+01 3.81289062e+01 3.81279144e+01 3.81307640e+01 3.81329651e+01 3.81400261e+01 3.81367302e+01 3.81349182e+01 3.81536446e+01 3.81657448e+01 3.81389465e+01 3.80766220e+01 3.80345230e+01 3.80736427e+01 3.81407814e+01 3.82067833e+01 3.82048988e+01 3.80291595e+01 3.79328613e+01 3.79039421e+01 3.81343918e+01 3.81659584e+01 3.81813889e+01 3.80391769e+01 3.80304985e+01 3.81734581e+01 3.80868759e+01 3.80111656e+01 3.78291283e+01 3.79983406e+01 3.80321007e+01 3.76108246e+01 3.75973778e+01 3.76839142e+01 3.79849243e+01 3.79308968e+01 3.76565666e+01 3.78803787e+01 3.79534416e+01 3.80870590e+01 3.78802147e+01 3.76433372e+01 3.76131821e+01 3.76015244e+01 3.77787552e+01 3.79254761e+01 3.78430252e+01 3.78087921e+01 3.76728210e+01 3.75969849e+01 3.77774162e+01 3.77023087e+01 3.78599777e+01 3.77664871e+01 3.73851013e+01 3.70199394e+01 3.67937927e+01 3.72433548e+01 3.76352692e+01 3.78660355e+01 3.76783485e+01 3.72480392e+01 3.68001366e+01 3.68730812e+01 3.72179565e+01 3.74949722e+01 3.72127419e+01 3.66842766e+01 3.64999046e+01 3.70426559e+01 3.75632133e+01 3.74603844e+01 3.73063622e+01 3.70805969e+01 3.65143280e+01 3.62804146e+01 3.57219582e+01 3.65919189e+01 3.66965179e+01 3.69841614e+01 3.64646912e+01 3.60530586e+01 3.56142349e+01 3.60989990e+01 3.61534805e+01 3.72134819e+01 3.63603096e+01 3.66900139e+01 3.67242813e+01 3.75459213e+01 3.70557480e+01 3.51299171e+01 3.41304092e+01 3.45729446e+01 3.62599869e+01 3.74751244e+01 3.73286476e+01 3.74968796e+01 3.65954170e+01 3.63222275e+01 3.56126518e+01 3.55270233e+01 3.59415359e+01 3.58843956e+01 3.53234062e+01 3.51070099e+01 3.51457481e+01 3.56249619e+01 3.58420677e+01 3.58228874e+01 3.61161346e+01 3.51784477e+01 3.53652267e+01 3.58940353e+01 3.66929512e+01 3.67526703e+01 3.62332039e+01 3.61003838e+01 3.53880882e+01 3.52963753e+01 3.58498917e+01 3.64299660e+01 3.63904533e+01 3.54436646e+01 3.48176689e+01 3.51124496e+01 3.51334801e+01 3.49835701e+01 3.49289970e+01 3.45309677e+01 3.36026764e+01 3.34939728e+01 3.43862152e+01 3.57753830e+01 3.50482521e+01 3.47902603e+01 3.36057320e+01 3.34363174e+01 3.35175362e+01 3.49465790e+01 3.55129662e+01 3.49472122e+01 3.52219429e+01 3.47395058e+01 3.47739754e+01 3.39948463e+01 3.36446266e+01 3.31763153e+01 3.18559303e+01 3.17008648e+01 3.19491329e+01 3.29659081e+01 3.34175453e+01 3.28506279e+01 3.09882603e+01 3.22003822e+01 3.13984890e+01 3.27279320e+01 3.16793041e+01 3.28740730e+01 3.32743301e+01 3.23722725e+01 3.26703186e+01 3.23133049e+01 3.28744125e+01 3.26293755e+01 3.14381905e+01 3.05766525e+01 2.96582718e+01 3.06272793e+01 3.23698959e+01 3.34457664e+01 3.31637268e+01 3.21906242e+01 3.20726013e+01 3.30873947e+01 3.21326675e+01 3.55342331e+01 3.39680367e+01 3.53206863e+01 3.24446411e+01 3.19891720e+01 2.45988388e+01 3.43020096e+01 1.51582088e+01 2.98394718e+01 8.99664612e+01 3.78081696e+02 19714370. 433851680. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.29760219e+05 3.77587646e+02 1.02142311e+02 4.11997757e+01 3.58651085e+01 6.83140717e+01 7.93192673e+01 4.18873253e+01 3.46133575e+01 3.14078979e+01 2.70130653e+01 2.69183960e+01 2.58489456e+01 2.45276299e+01 2.36104279e+01 2.39950104e+01 2.54663677e+01 2.48762379e+01 2.43019695e+01 2.32000828e+01 2.43287563e+01 2.42925282e+01 2.56318512e+01 2.60938625e+01 2.65120735e+01 2.44749222e+01 2.19302139e+01 2.16421547e+01 2.22317963e+01 2.22654934e+01 2.18483276e+01 2.23126545e+01 2.25896835e+01 2.39001598e+01 2.45438919e+01 2.50693684e+01 2.34506149e+01 2.22621326e+01 2.06173363e+01 1.98939991e+01 1.97293205e+01 2.11871967e+01 2.04242725e+01 1.96218662e+01 1.87714024e+01 1.75711193e+01 1.88516941e+01 2.07981377e+01 2.33834324e+01 2.36103516e+01 2.14517632e+01 2.18232841e+01 2.11857567e+01 2.26599827e+01 2.26759701e+01 2.23763580e+01 2.11368465e+01 1.93022976e+01 1.81484585e+01 1.80904789e+01 1.91195946e+01 2.04292850e+01 1.94541416e+01 1.77741737e+01 1.83491440e+01 2.00649681e+01 2.18684196e+01 2.09991970e+01 1.85679874e+01 1.66054668e+01 1.50052395e+01 1.42666140e+01 1.43282509e+01 1.60552654e+01 1.75901566e+01 1.71631355e+01 1.89352036e+01 2.03035469e+01 2.23694096e+01 2.06184387e+01 1.72454433e+01 1.61661091e+01 1.46370192e+01 1.61015892e+01 1.59583874e+01 1.67899628e+01 1.63642235e+01 1.47975721e+01 1.50353012e+01 1.52510138e+01 1.52586298e+01 1.39197512e+01 1.28413391e+01 1.37832870e+01 1.52517433e+01 1.46652584e+01 1.47324142e+01 1.41826897e+01 1.52321968e+01 1.51334181e+01 1.42555017e+01 1.32736101e+01 1.34804020e+01 1.60455341e+01 1.81348743e+01 1.70279694e+01 1.58391743e+01 1.29559908e+01 1.34545336e+01 1.14782972e+01 1.19358015e+01 1.24987259e+01 1.36040411e+01 1.30503788e+01 1.22909288e+01 1.20386639e+01 1.40388927e+01 1.32431517e+01 1.32391729e+01 1.33638144e+01 1.23614912e+01 1.28944330e+01 1.35840416e+01 1.61778469e+01 1.54387369e+01 1.20781755e+01 9.97078896e+00 1.08210173e+01 1.28241539e+01 1.35424519e+01 1.06600924e+01 1.05381155e+01 1.01183052e+01 1.22676601e+01 1.27705297e+01 1.38523741e+01 1.41312485e+01 1.12641430e+01 9.28697395e+00 8.62676811e+00 1.00235128e+01 1.13929434e+01 9.67750263e+00 9.45775509e+00 9.37127495e+00 9.23168945e+00 7.57335711e+00 6.21524763e+00 5.91052294e+00 6.43131638e+00 5.31213379e+00 6.02200317e+00 6.86435223e+00 1.02577858e+01 1.22549400e+01 1.19590368e+01 9.90551853e+00 7.53043222e+00 6.89912701e+00 6.45971918e+00 6.25294352e+00 6.36320496e+00 6.87142277e+00 6.52839899e+00 5.51405954e+00 4.21015549e+00 5.40141821e+00 7.91673946e+00 9.48541069e+00 9.29276276e+00 5.57714939e+00 4.29687166e+00 4.89961147e+00 7.23831940e+00 6.98506546e+00 5.87580776e+00 6.28502369e+00 6.26728106e+00 5.76161909e+00 4.75057650e+00 4.51526356e+00 4.57607412e+00 4.01875257e+00 3.52154064e+00 3.99265409e+00 3.13253951e+00 2.53449225e+00 1.29977465e+00 1.59398317e+00 6.54846013e-01 -1.32718396e+00 -4.08043504e-01 9.48102057e-01 3.02396059e+00 2.86469960e+00 6.27305865e-01 2.50482440e-01 4.09395546e-01 3.56708884e+00 3.51709747e+00 2.92133832e+00 6.39834166e-01 -8.39060664e-01 -6.39480054e-01 -8.92357886e-01 -3.63142699e-01 -3.66732180e-01 3.23257476e-01 -1.12709537e-01 -1.05622277e-01 -7.46311963e-01 2.85587162e-01 -8.24118555e-01 2.03148365e+00 1.44953370e+00 -3.98938179e-01 -3.30503249e+00 -2.69110370e+00 9.89178479e-01 2.37338209e+00 2.42082906e+00 2.32348633e+00 2.04900217e+00 2.31667519e+00 2.36945558e+00 1.88163042e+00 1.27594602e+00 -9.28043306e-01 -1.61449003e+00 -6.64603293e-01 -1.14037044e-01 1.50804207e-01 -1.01068342e+00 -8.97120118e-01 -1.14894998e+00 -2.04576325e+00 -2.44890881e+00 -1.51555765e+00 -2.18602085e+00 -2.56414819e+00 -3.42576385e+00 -2.94679379e+00 -2.11446595e+00 -1.93612790e+00 -1.76836944e+00 1.76593989e-01 9.08157229e-02 -1.21416546e-01 -3.32634592e+00 -3.11446428e+00 -3.86687160e+00 -3.02022147e+00 -5.33832836e+00 -5.32302761e+00 -5.53045416e+00 -4.11116505e+00 -4.45779800e+00 -5.61836815e+00 -5.38883591e+00 -5.19084787e+00 -4.47249556e+00 -5.44651127e+00 -5.03882694e+00 -5.48222876e+00 -5.30330992e+00 -3.62619042e+00 -4.54322243e+00 -4.93357325e+00 -6.55576706e+00 -6.49907207e+00 -5.01045179e+00 -5.60460901e+00 -5.63472033e+00 -5.96676254e+00 -5.34428310e+00 -5.77615881e+00 -6.59693575e+00 -7.70428753e+00 -7.13200712e+00 -6.66325331e+00 -6.31508350e+00 -6.68659544e+00 -7.43799543e+00 -5.35498047e+00 -5.11678028e+00 -3.77107978e+00 -4.78177023e+00 -5.28937435e+00 -6.11675835e+00 -7.80675268e+00 -8.50234127e+00 -9.22235966e+00 -9.30373192e+00 -9.08995819e+00 -8.98567104e+00 -1.03688688e+01 -1.11205435e+01 -1.12082176e+01 -1.25282774e+01 -1.04388857e+01 -1.06356716e+01 -9.36129284e+00 -1.03469524e+01 -9.08594799e+00 -8.27577782e+00 -9.59327888e+00 -1.15728483e+01 -1.14820833e+01 -1.02791080e+01 -9.79689503e+00 -1.10976200e+01 -1.22084789e+01 -1.49803219e+01 -1.40662594e+01 -1.47479963e+01 -1.19631691e+01 -1.26335030e+01 -1.16023121e+01 -1.26943598e+01 -1.24618177e+01 -1.12384987e+01 -8.84492397e+00 -9.30993366e+00 -1.15112505e+01 -1.38899298e+01 -1.45627098e+01 -1.44414778e+01 -1.48294430e+01 -1.47393465e+01 -1.36155605e+01 -1.29917631e+01 -1.28564892e+01 -1.39743843e+01 -1.45986137e+01 -1.41967916e+01 -1.39721031e+01 -1.39440279e+01 -1.51069384e+01 -1.55134335e+01 -1.58628998e+01 -1.49421358e+01 -1.52326145e+01 -1.52122517e+01 -1.67352943e+01 -1.77135143e+01 -1.72469025e+01 -1.68980389e+01 -1.64888477e+01 -1.77992439e+01 -1.77489796e+01 -1.82500343e+01 -1.66178055e+01 -1.58965693e+01 -1.53191109e+01 -1.83720112e+01 -1.98817406e+01 -2.07296219e+01 -1.85281563e+01 -1.70016994e+01 -1.74628010e+01 -1.73675938e+01 -1.92665672e+01 -1.86805820e+01 -1.67004223e+01 -1.42733841e+01 -1.42560730e+01 -1.63520336e+01 -1.77357025e+01 -1.87081280e+01 -1.87906628e+01 -1.91380558e+01 -1.94675255e+01 -1.91825657e+01 -1.87230015e+01 -1.76495571e+01 -1.79354172e+01 -1.79797173e+01 -2.02864380e+01 -2.19772053e+01 -2.24977226e+01 -2.16904316e+01 -2.03800373e+01 -1.98451290e+01 -1.98808517e+01 -1.98495255e+01 -1.89999123e+01 -1.93986282e+01 -1.99455376e+01 -2.12469769e+01 -2.01268940e+01 -1.96549263e+01 -1.98204689e+01 -2.15453014e+01 -2.15436172e+01 -2.18440113e+01 -2.14395618e+01 -2.16489029e+01 -2.12555408e+01 -2.11858864e+01 -2.03908386e+01 -2.09443703e+01 -2.13829556e+01 -2.33467884e+01 -2.53769207e+01 -2.63783417e+01 -2.57246361e+01 -2.38146687e+01 -2.33708267e+01 -2.35705833e+01 -2.34630928e+01 -2.34361401e+01 -2.38547916e+01 -2.48798141e+01 -2.50594311e+01 -2.44556732e+01 -2.33299484e+01 -2.29490929e+01 -2.32102814e+01 -2.42752533e+01 -2.46263409e+01 -2.49957581e+01 -2.45456104e+01 -2.46938210e+01 -2.49719601e+01 -2.43402042e+01 -2.34151821e+01 -2.21946011e+01 -2.21013584e+01 -2.29808445e+01 -2.39852390e+01 -2.47363625e+01 -2.52585602e+01 -2.51892471e+01 -2.49805050e+01 -2.49853725e+01 -2.48092556e+01 -2.40782776e+01 -2.37208672e+01 -2.36005344e+01 -2.45197372e+01 -2.56461258e+01 -2.60477943e+01 -2.69550743e+01 -2.65954914e+01 -2.67842159e+01 -2.62875633e+01 -2.76387081e+01 -2.94706078e+01 -2.84019070e+01 -2.51444302e+01 -1.89346752e+01 -1.84333172e+01 -1.71719818e+01 -1.90024490e+01 -2.03631935e+01 -9.59471798e+00 -5.15389299e+00 -1.23856506e+01 -3.09535980e+01 3.78691589e+02 3.51215637e+02 -1.84278516e+04 -197921888. 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. 0. 0. 0. 0. 0. 0. 0. 182845424. 5.30159521e+03 9.29069031e+02 2.66279812e+01 -2.51612434e+01 -3.93677559e+01 1.45871058e+01 1.67684498e+01 -1.74877510e+01 -2.62171192e+01 -2.90748653e+01 -2.80582619e+01 -2.87268353e+01 -2.96211090e+01 -3.13343468e+01 -3.08369656e+01 -3.07085209e+01 -3.08698921e+01 -3.13820400e+01 -3.18738098e+01 -3.23893089e+01 -3.26334190e+01 -3.28511696e+01 -3.29664459e+01 -3.24260750e+01 -3.19580441e+01 -3.22197685e+01 -3.32387428e+01 -3.36012878e+01 -3.33761940e+01 -3.29062080e+01 -3.30797768e+01 -3.39601936e+01 -3.42101898e+01 -3.44702911e+01 -3.34755096e+01 -3.33738213e+01 -3.30312386e+01 -3.34167023e+01 -3.34865646e+01 -3.36243286e+01 -3.39413109e+01 -3.41642380e+01 -3.42330933e+01 -3.40756340e+01 -3.43096237e+01 -3.46401176e+01 -3.47838631e+01 -3.48152809e+01 -3.50226860e+01 -3.49512825e+01 -3.51935692e+01 -3.51701431e+01 -3.57768974e+01 -3.54305229e+01 -3.54072723e+01 -3.50991173e+01 -3.54518471e+01 -3.53898315e+01 -3.56643181e+01 -3.55298691e+01 -3.58598061e+01 -3.49395027e+01 -3.42902260e+01 -3.38645439e+01 -3.44086075e+01 -3.49564133e+01 -3.50842285e+01 -3.48493156e+01 -3.50963249e+01 -3.49640121e+01 -3.52573509e+01 -3.55002975e+01 -3.56160431e+01 -3.59719925e+01 -3.63504677e+01 -3.72512398e+01 -3.79362907e+01 -3.77129440e+01 -3.66832733e+01 -3.59548264e+01 -3.58628006e+01 -3.62600365e+01 -3.56437149e+01 -3.52778435e+01 -3.49803810e+01 -3.53733482e+01 -3.55669365e+01 -3.58761024e+01 -3.59004669e+01 -3.58595924e+01 -3.59326591e+01 -3.57405853e+01 -3.56811371e+01 -3.57444534e+01 -3.62439194e+01 -3.66154289e+01 -3.65283546e+01 -3.65325508e+01 -3.65439911e+01 -3.66242218e+01 -3.67769737e+01 -3.70578346e+01 -3.71705093e+01 -3.72316513e+01 -3.69725800e+01 -3.69343948e+01 -3.70646324e+01 -3.69029884e+01 -3.67419891e+01 -3.63462524e+01 -3.65049400e+01 -3.68922958e+01 -3.74304466e+01 -3.75821419e+01 -3.75646248e+01 -3.73856468e+01 -3.72901039e+01 -3.72821884e+01 -3.73363953e+01 -3.74785004e+01 -3.73557816e+01 -3.74091759e+01 -3.75199585e+01 -3.76892014e+01 -3.76989479e+01 -3.75885429e+01 -3.76171608e+01 -3.73602600e+01 -3.72691803e+01 -3.72056122e+01 -3.74851646e+01 -3.77215805e+01 -3.77246246e+01 -3.76747017e+01 -3.73854485e+01 -3.72330971e+01 -3.72998466e+01 -3.75796623e+01 -3.77323837e+01 -3.78517838e+01 -3.79181824e+01 -3.80166626e+01 -3.79851265e+01 -3.80014610e+01 -3.79740829e+01 -3.79999580e+01 -3.79635353e+01 -3.79731445e+01 -3.80051537e+01 -3.80557213e+01 -3.80792160e+01 -3.80623016e+01 -3.79810600e+01 -3.78641167e+01 -3.78845291e+01 -3.79127197e+01 -3.80309067e+01 -3.79301491e+01 -3.79093056e+01 -3.79186172e+01 -3.79197769e+01 -3.79232330e+01 -3.79097862e+01 -3.79847069e+01 -3.80254250e+01 -3.80808754e+01 -3.80940971e+01 -3.81257668e+01 -3.81291924e+01 -3.81185074e+01 -3.81146278e+01 -3.81114616e+01 -3.81239471e+01 -3.81270332e+01 -3.81383972e+01 -3.81404724e+01 -3.81290779e+01 -3.81216202e+01 -3.81274796e+01 -3.81397781e+01 -3.81371651e+01 -3.81357460e+01 -3.81359177e+01 -3.80940590e+01 -3.80933533e+01 -3.81039238e+01 -3.81391487e+01 -3.81265869e+01 -3.81055374e+01 -3.81397934e+01 -3.81135483e+01 -3.81222610e+01 -3.80967102e+01 -3.81130524e+01 -3.81149788e+01 -3.80419235e+01 -3.79935417e+01 -3.79662895e+01 -3.79997139e+01 -3.80714188e+01 -3.80079346e+01 -3.79111252e+01 -3.78847733e+01 -3.79312782e+01 -3.80232544e+01 -3.79420776e+01 -3.80015221e+01 -3.79414291e+01 -3.78391762e+01 -3.78169594e+01 -3.79010162e+01 -3.79762039e+01 -3.78719177e+01 -3.79231644e+01 -3.79227600e+01 -3.78141441e+01 -3.77779121e+01 -3.78777504e+01 -3.80378494e+01 -3.79126968e+01 -3.78355064e+01 -3.78402100e+01 -3.79341660e+01 -3.79538155e+01 -3.78879814e+01 -3.75713272e+01 -3.73831787e+01 -3.72717018e+01 -3.73122139e+01 -3.71693649e+01 -3.71962395e+01 -3.71375771e+01 -3.71420670e+01 -3.69707108e+01 -3.69043884e+01 -3.69741783e+01 -3.71390686e+01 -3.70473671e+01 -3.70580750e+01 -3.71803551e+01 -3.72398109e+01 -3.71899834e+01 -3.71233177e+01 -3.71231232e+01 -3.69612465e+01 -3.65059013e+01 -3.61582375e+01 -3.67422981e+01 -3.74907494e+01 -3.77897148e+01 -3.76303291e+01 -3.73107872e+01 -3.77655525e+01 -3.76451721e+01 -3.74367714e+01 -3.69813766e+01 -3.67560081e+01 -3.68949394e+01 -3.66189461e+01 -3.64304657e+01 -3.62567368e+01 -3.64965286e+01 -3.69229774e+01 -3.70585976e+01 -3.71929474e+01 -3.69031982e+01 -3.68082619e+01 -3.66848793e+01 -3.63925514e+01 -3.59623566e+01 -3.55699081e+01 -3.57526360e+01 -3.56611862e+01 -3.56549835e+01 -3.56716499e+01 -3.59050407e+01 -3.61428375e+01 -3.62177162e+01 -3.65795059e+01 -3.63349876e+01 -3.61044807e+01 -3.52510376e+01 -3.51136360e+01 -3.46672211e+01 -3.46539917e+01 -3.51513062e+01 -3.52228737e+01 -3.47567635e+01 -3.41629219e+01 -3.44311028e+01 -3.47064400e+01 -3.46814194e+01 -3.45322151e+01 -3.47108765e+01 -3.46063271e+01 -3.46782608e+01 -3.49498634e+01 -3.52379684e+01 -3.49753799e+01 -3.50307922e+01 -3.49007111e+01 -3.48084183e+01 -3.43472366e+01 -3.43125496e+01 -3.49993591e+01 -3.55055542e+01 -3.57924843e+01 -3.51921883e+01 -3.42221680e+01 -3.38773651e+01 -3.39670639e+01 -3.38080292e+01 -3.30452042e+01 -3.32561302e+01 -3.36078873e+01 -3.40689468e+01 -3.36730537e+01 -3.33954582e+01 -3.37711411e+01 -3.42513657e+01 -3.39311180e+01 -3.37720871e+01 -3.35354385e+01 -3.33926239e+01 -3.31591911e+01 -3.32967377e+01 -3.37069359e+01 -3.41428223e+01 -3.43629036e+01 -3.42122345e+01 -3.37751083e+01 -3.31152725e+01 -3.30143738e+01 -3.29216881e+01 -3.24420166e+01 -3.21205254e+01 -3.22915459e+01 -3.28665848e+01 -3.32102928e+01 -3.17619667e+01 -3.08090038e+01 -3.01563606e+01 -3.10152340e+01 -3.09060307e+01 -3.15241184e+01 -3.17207279e+01 -3.21121788e+01 -3.22176514e+01 -3.22603798e+01 -3.21427650e+01 -3.12898769e+01 -3.03212433e+01 -3.00032215e+01 -3.12129879e+01 -3.16579990e+01 -3.18717022e+01 -3.11613503e+01 -3.07983589e+01 -3.00527306e+01 -2.94398956e+01 -2.96270370e+01 -2.95383224e+01 -2.98258495e+01 -2.96877918e+01 -3.02054005e+01 -3.01686440e+01 -3.05172119e+01 -2.99839897e+01 -2.97928886e+01 -2.91522255e+01 -3.03575420e+01 -3.14092884e+01 -3.12230682e+01 -2.98520794e+01 -2.95042915e+01 -3.10288353e+01 -3.13569527e+01 -3.09346886e+01 -2.98331413e+01 -3.03972893e+01 -3.08949528e+01 -3.03179398e+01 -2.98164501e+01 -2.87843704e+01 -2.87487450e+01 -2.79527187e+01 -2.81359768e+01 -2.84165249e+01 -2.89258060e+01 -2.82198296e+01 -2.79014091e+01 -2.72706871e+01 -2.75506630e+01 -2.77780895e+01 -2.81851311e+01 -2.83609562e+01 -2.95424309e+01 -2.85502357e+01 -2.71393890e+01 -2.64282990e+01 -2.73068409e+01 -2.82506561e+01 -2.71483097e+01 -2.73222961e+01 -2.68912525e+01 -2.70988121e+01 -2.62563286e+01 -2.57239265e+01 -2.45119705e+01 -2.43273945e+01 -2.37408466e+01 -2.51062603e+01 -2.65604115e+01 -2.69287777e+01 -2.64432812e+01 -2.54909019e+01 -2.67553692e+01 -2.61295471e+01 -2.57417545e+01 -2.48144302e+01 -2.51116085e+01 -2.45782223e+01 -2.41787128e+01 -2.30443020e+01 -2.39658337e+01 -2.46920815e+01 -2.54287415e+01 -2.49368877e+01 -2.42071400e+01 -2.42890167e+01 -2.39257011e+01 -2.37896271e+01 -2.40674076e+01 -2.41266346e+01 -2.39754963e+01 -2.35914383e+01 -2.43140068e+01 -2.52765827e+01 -2.46600571e+01 -2.40334206e+01 -2.46110039e+01 -2.64482384e+01 -2.54902172e+01 -2.27980518e+01 -2.09426899e+01 -2.12857056e+01 -2.20315132e+01 -2.22435493e+01 -2.13442841e+01 -2.21656399e+01 -2.24049091e+01 -2.31185722e+01 -2.26773205e+01 -2.18960114e+01 -2.14032288e+01 -2.03699551e+01 -1.97408466e+01 -1.98952656e+01 -2.06621552e+01 -2.05198612e+01 -2.00781269e+01 -2.11853676e+01 -2.13000584e+01 -2.08706741e+01 -1.88394566e+01 -1.92491875e+01 -1.98742294e+01 -2.04174213e+01 -1.92052917e+01 -1.93140564e+01 -1.98105450e+01 -2.19671555e+01 -2.21347351e+01 -2.17903099e+01 -2.16703568e+01 -2.17448940e+01 -2.09179668e+01 -2.01941299e+01 -1.92485085e+01 -2.00838909e+01 -1.96837654e+01 -1.92791176e+01 -1.92323933e+01 -1.89390202e+01 -1.81354218e+01 -1.66964970e+01 -1.73752689e+01 -1.86649609e+01 -1.90036068e+01 -1.79805946e+01 -1.72814884e+01 -1.85319614e+01 -1.68297005e+01 -1.45419197e+01 -1.24182644e+01 -1.34520416e+01 -1.54183550e+01 -1.49446268e+01 -1.47694502e+01 -1.40636377e+01 -1.44209089e+01 -1.36522541e+01 -1.28162718e+01 -1.34962435e+01 -1.45356903e+01 -1.53964291e+01 -1.60860233e+01 -1.66303463e+01 -1.73985691e+01 -1.70983448e+01 -1.52785225e+01 -1.38252678e+01 -1.22480755e+01 -1.30272799e+01 -1.26023741e+01 -1.28399649e+01 -1.33462009e+01 -1.26929026e+01 -1.08962851e+01 -1.12801590e+01 -1.30626173e+01 -1.43961411e+01 -1.37338867e+01 -1.37923088e+01 -1.52844620e+01 -1.56466436e+01 -1.48060741e+01 -1.31006927e+01 -1.27057314e+01 -1.31151848e+01 -1.26811428e+01 -1.28928976e+01 -1.29160547e+01 -1.29925232e+01 -1.31975269e+01 -1.26288414e+01 -1.20988817e+01 -1.12813768e+01 -1.22562551e+01 -1.28209143e+01 -1.44855623e+01 -1.54999800e+01 -1.53783798e+01 -1.29956055e+01 -1.19613008e+01 -1.21809521e+01 -1.34043083e+01 -1.24169321e+01 -1.12729893e+01 -1.14768620e+01 -1.23177509e+01 -1.20361595e+01 -1.09101210e+01 -7.79834938e+00 -8.11315823e+00 -7.19641495e+00 -8.85570621e+00 -1.03553524e+01 -1.12124205e+01 -9.35396671e+00 -9.70001411e+00 -1.09431496e+01 -1.20936632e+01 -8.81315708e+00 -7.78091288e+00 -8.63213158e+00 -1.15738945e+01 -1.03479643e+01 -8.49387836e+00 -5.55877876e+00 -6.15944338e+00 -7.52900553e+00 -7.63345432e+00 -7.90987682e+00 -8.79865170e+00 -9.14757347e+00 -8.66903400e+00 -7.51998234e+00 -7.94288731e+00 -8.45539379e+00 -8.70480919e+00 -8.23275661e+00 -6.24405146e+00 -5.10924149e+00 -3.61115885e+00 -3.71654463e+00 -3.94665956e+00 -4.43651533e+00 -4.64535761e+00 -5.64415693e+00 -6.10225153e+00 -5.37308121e+00 -3.42283368e+00 -1.22199082e+00 -1.83372760e+00 -6.14265394e+00 -1.17936020e+01 -1.46497202e+01 -7.06730127e+00 -2.79770875e+00 2.96318007e+00 -1.82959735e+00 -1.87608385e+00 -1.24977560e+01 -1.72845974e+01 1.64199963e+01 5.97973785e+01 -1.15805763e+02 -9.45617004e+02 -2.65993311e+03 -3.00736145e+02 -106367016. 0. 0. 0. 0. 0. -1.00518359e+10 6.88672050e+06 3.08426880e+03 2.16609180e+03 -1.56779700e+03 -1411763584. 0. 0. 1.98114714e+10 1.98114714e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.57624832e+09 -35889752. 1.12338916e+04 1.53975723e+02 -5.85378540e+02 2.45243454e+01 -2.40966434e+01 -1.11883133e+02 -9.41071625e+01 3.10824490e+00 5.21268730e+01 7.91178970e+01 6.74752274e+01 2.54710865e+01 1.03900070e+01 9.22809410e+00 1.09430981e+01 5.87629843e+00 1.04151707e+01 3.37864761e+01 4.41401825e+01 3.10080128e+01 -6.82855940e+00 -4.13322830e+01 -3.60850410e+01 -2.61975384e+01 -1.49468994e+01 2.18344975e+00 3.62535810e+00 5.26326227e+00 -1.21504059e+01 -2.71094284e+01 -3.91356277e+01 -3.37302704e+01 2.39867020e+00 3.29833641e+01 5.15327339e+01 6.14492416e+01 4.96688995e+01 4.69598389e+01 4.01345215e+01 9.46918964e+00 -1.18546352e+01 -1.06141033e+01 2.49448261e+01 5.71464996e+01 6.87443314e+01 5.04912224e+01 1.30685511e+01 -1.42295504e+00 1.14280939e-01 1.37742329e+01 3.07396984e+01 3.71538887e+01 4.75535316e+01 4.81248093e+01 3.49941101e+01 1.21287394e+01 2.02492452e+00 2.70547199e+01 4.63221092e+01 5.20902748e+01 4.45977097e+01 2.91729126e+01 3.09890137e+01 3.16138535e+01 1.43773270e+01 -9.91805077e+00 -1.17260332e+01 2.25990067e+01 5.26192627e+01 5.64186363e+01 3.28867264e+01 -1.67534745e+00 -4.76414710e-02 1.20469046e+01 2.16019535e+01 2.79538231e+01 4.09803009e+01 5.61360550e+01 6.54851303e+01 4.92733078e+01 1.62218437e+01 -2.01687183e+01 -1.25934305e+01 4.41095591e+00 2.08638611e+01 3.30100899e+01 4.04197311e+01 4.41666908e+01 2.60569515e+01 3.44358587e+00 -1.70669155e+01 -1.03949928e+01 2.19999676e+01 5.53771782e+01 7.66353531e+01 8.00301971e+01 5.77305565e+01 4.48779030e+01 3.03788624e+01 8.67759228e+00 -9.34342861e+00 -4.75203276e+00 2.29325428e+01 4.53471107e+01 4.23587189e+01 1.96600018e+01 -3.07616711e+00 -3.47813249e+00 3.25991964e+00 4.12685871e+00 1.14693327e+01 1.80847778e+01 2.86938896e+01 3.71296005e+01 3.53413086e+01 2.25719643e+01 1.41950226e+01 2.44974232e+01 4.53487396e+01 5.82848244e+01 5.13452873e+01 1.80165634e+01 -8.31695461e+00 4.40245819e+00 1.43925743e+01 7.40045691e+00 -3.09629226e+00 2.01614017e+01 5.07565613e+01 6.14321518e+01 3.84520798e+01 7.10983610e+00 -5.78455687e+00 7.13978100e+00 2.39784317e+01 3.50660057e+01 4.37237740e+01 3.79472504e+01 3.65163612e+01 3.05910606e+01 1.57869940e+01 6.90917194e-01 -7.42040932e-01 1.22697773e+01 3.02483807e+01 4.10706902e+01 3.53874817e+01 1.49667339e+01 6.90735912e+00 9.73379612e+00 1.20849876e+01 9.04613400e+00 1.64702492e+01 3.46953659e+01 5.96198273e+01 6.25532303e+01 4.64677124e+01 3.50032883e+01 3.79619102e+01 3.88183594e+01 2.86412106e+01 3.11065884e+01 3.61114998e+01 4.94673729e+01 4.37696991e+01 3.20439873e+01 1.82456264e+01 2.54897900e+01 4.72645226e+01 6.74060364e+01 7.66553802e+01 7.20161743e+01 5.58748245e+01 5.05101357e+01 5.23171692e+01 4.34839134e+01 4.99425430e+01 6.28580170e+01 8.36916733e+01 9.49002838e+01 9.21766739e+01 7.01288757e+01 3.50073547e+01 2.49137287e+01 2.10821857e+01 2.00281868e+01 1.82219524e+01 2.64802208e+01 4.47908325e+01 5.28963776e+01 4.23076782e+01 2.24048080e+01 2.17491894e+01 4.03118134e+01 5.51193695e+01 6.28809853e+01 7.49928131e+01 7.47416382e+01 7.25116730e+01 5.89098434e+01 4.99981499e+01 5.15374489e+01 5.68631859e+01 7.33762054e+01 8.32299500e+01 8.75012817e+01 6.83526001e+01 3.74544296e+01 2.69581261e+01 3.25048790e+01 4.03253441e+01 4.29196625e+01 4.59506073e+01 5.85773888e+01 6.43619690e+01 4.68856316e+01 2.71606770e+01 1.97757053e+01 3.42026329e+01 4.98285942e+01 5.61418190e+01 5.73930931e+01 5.15487938e+01 5.34552002e+01 6.07043419e+01 5.17306366e+01 4.28829842e+01 4.39695740e+01 5.70854416e+01 6.79572525e+01 6.85483398e+01 5.99255905e+01 4.52247696e+01 3.54909706e+01 3.61436958e+01 3.65377159e+01 3.76341133e+01 4.06181984e+01 5.63760262e+01 6.61003189e+01 6.69026184e+01 6.10408401e+01 4.86717567e+01 4.36889534e+01 3.46135292e+01 3.55170631e+01 5.11034622e+01 5.33398285e+01 5.12913551e+01 4.20643387e+01 3.83684998e+01 3.71883507e+01 3.15526943e+01 5.06903763e+01 7.08715134e+01 7.86025848e+01 6.17028046e+01 5.00142250e+01 4.86519547e+01 5.24900208e+01 4.14881630e+01 3.72203598e+01 4.66217766e+01 6.26255646e+01 6.71296082e+01 5.07942772e+01 4.90664177e+01 4.76025505e+01 4.70278244e+01 3.87172089e+01 4.36740799e+01 5.61615181e+01 6.23694038e+01 6.72188568e+01 7.27085037e+01 7.78352127e+01 6.44027634e+01 4.88083763e+01 4.96229973e+01 6.94096527e+01 7.37308426e+01 6.46701431e+01 6.16997223e+01 6.88417892e+01 7.11436310e+01 5.68163795e+01 5.54307289e+01 6.22978210e+01 7.05018692e+01 6.74255905e+01 5.55458755e+01 5.59678001e+01 4.93791199e+01 4.35392570e+01 3.76366539e+01 4.91990700e+01 5.80158806e+01 5.76455231e+01 5.58379745e+01 5.59866600e+01 5.86630287e+01 5.08538361e+01 4.31444397e+01 4.47592278e+01 5.95732117e+01 6.88509598e+01 6.51396255e+01 5.99102173e+01 6.41976776e+01 7.09335709e+01 6.66367416e+01 6.26702499e+01 5.91333542e+01 6.10310669e+01 5.49811821e+01 4.91376839e+01 5.15171967e+01 5.31527443e+01 5.24142075e+01 4.89154091e+01 5.00890999e+01 5.14867287e+01 5.14104004e+01 5.82096443e+01 6.51473236e+01 6.91905365e+01 6.17239151e+01 5.44581223e+01 5.60295105e+01 6.57960663e+01 6.66678162e+01 6.18837128e+01 5.95681801e+01 6.66041718e+01 6.74769135e+01 5.74256096e+01 5.19369507e+01 4.74551392e+01 4.73069725e+01 4.34300652e+01 4.56086159e+01 5.25307884e+01 5.27911568e+01 4.93392181e+01 4.71242867e+01 5.52193527e+01 6.13960762e+01 6.11192093e+01 6.49284592e+01 7.16481934e+01 7.67271652e+01 7.21990738e+01 6.71005020e+01 6.59014511e+01 6.62855377e+01 6.27313690e+01 6.17517014e+01 6.23117447e+01 6.66772079e+01 6.43256302e+01 5.75650406e+01 5.36045723e+01 5.11304512e+01 5.18388100e+01 5.00530357e+01 5.31593246e+01 6.00284767e+01 6.12158203e+01 5.96524086e+01 5.58633575e+01 5.94403076e+01 6.21272354e+01 5.85048866e+01 5.98474426e+01 6.56476593e+01 7.33958282e+01 7.45900116e+01 6.86529236e+01 6.57646866e+01 6.61343689e+01 6.72802048e+01 6.96153107e+01 6.64766006e+01 6.60405807e+01 6.40482254e+01 6.42472229e+01 6.93574677e+01 6.83833237e+01 6.57669678e+01 5.86526070e+01 5.87996864e+01 6.63336792e+01 6.80369492e+01 6.58005447e+01 5.90115776e+01 5.91484375e+01 6.54624023e+01 6.90654221e+01 7.07947083e+01 6.88305206e+01 6.72433243e+01 6.59095001e+01 6.23078575e+01 6.21281891e+01 6.47849503e+01 6.75417099e+01 6.75463181e+01 6.37324677e+01 6.13349152e+01 6.00503540e+01 6.11041145e+01 6.44744415e+01 6.54075165e+01 6.40264130e+01 6.09710732e+01 6.13492126e+01 6.46734467e+01 6.73830490e+01 6.81742096e+01 6.57308350e+01 6.33954887e+01 6.27721176e+01 6.26974525e+01 6.34612503e+01 6.40060654e+01 6.45281906e+01 6.50641861e+01 6.46416473e+01 6.41649094e+01 6.36759682e+01 6.36635551e+01 6.38652954e+01 6.36265068e+01 6.35486221e+01 6.35803719e+01 6.36413879e+01 6.36354218e+01 6.35318680e+01 6.34896927e+01 6.38385620e+01 6.41193848e+01 6.40305481e+01 6.38742104e+01 6.36059113e+01 6.36688728e+01 6.32787590e+01 6.22971153e+01 6.22101402e+01 6.28341827e+01 6.32186813e+01 6.31684761e+01 6.26424484e+01 6.39132118e+01 6.46393738e+01 6.49738770e+01 6.37342110e+01 6.19414864e+01 6.27205963e+01 6.43993301e+01 6.58783112e+01 6.57534332e+01 6.34181061e+01 6.26347313e+01 6.26841202e+01 6.47653580e+01 6.53686905e+01 6.27723579e+01 6.11582298e+01 5.95845299e+01 6.05050278e+01 6.12928200e+01 6.22016716e+01 6.37537956e+01 6.43964844e+01 6.31698112e+01 6.16816521e+01 5.96627121e+01 6.06366348e+01 6.22377396e+01 6.54979553e+01 6.66837616e+01 6.24318275e+01 6.22380638e+01 6.15783195e+01 6.32696609e+01 6.38254356e+01 6.22478180e+01 6.11439323e+01 5.74471169e+01 6.13910866e+01 6.56115799e+01 6.67044449e+01 6.49397812e+01 6.13072586e+01 5.88156281e+01 5.81268196e+01 5.89337234e+01 6.27791595e+01 6.31919632e+01 6.15503769e+01 5.89571533e+01 5.72145615e+01 6.20400848e+01 6.59815063e+01 7.03100128e+01 6.83902512e+01 6.30954971e+01 6.27597618e+01 6.42973480e+01 6.83605423e+01 6.91418076e+01 6.37710991e+01 6.25179787e+01 6.10076408e+01 6.60195007e+01 6.81142502e+01 6.16443596e+01 6.22373009e+01 6.11447449e+01 6.00489006e+01 5.63072853e+01 5.54977646e+01 6.53252258e+01 7.06929703e+01 6.82189331e+01 6.12256355e+01 5.61916046e+01 6.15894279e+01 6.85269470e+01 7.22052307e+01 7.36098099e+01 6.58899918e+01 6.11051903e+01 5.95310593e+01 6.49457474e+01 6.99113846e+01 6.01802826e+01 5.22848396e+01 4.39236526e+01 4.85396652e+01 5.85346642e+01 6.29825287e+01 6.81775436e+01 6.26989403e+01 5.64032135e+01 5.12818565e+01 5.36568260e+01 6.50503769e+01 7.23944321e+01 7.02129898e+01 6.56250534e+01 5.98548012e+01 6.40758820e+01 6.82349930e+01 7.30009460e+01 7.06368942e+01 5.77323799e+01 5.25488930e+01 5.57906227e+01 6.89614487e+01 7.39189758e+01 6.97125320e+01 6.48922119e+01 5.75477486e+01 5.88053322e+01 6.18290291e+01 6.55652161e+01 6.60913467e+01 6.12627373e+01 5.68896713e+01 5.42840958e+01 5.70241890e+01 6.70433121e+01 7.35511322e+01 7.43506927e+01 6.37202415e+01 5.24855537e+01 5.67671890e+01 6.53350067e+01 7.33619461e+01 6.95849609e+01 5.32895927e+01 4.87461624e+01 5.27368164e+01 6.87411728e+01 7.59668732e+01 6.21631165e+01 5.15465813e+01 4.40682678e+01 5.44764671e+01 6.55244446e+01 6.21767616e+01 6.13722458e+01 5.53311844e+01 5.52785416e+01 5.57138023e+01 5.42131195e+01 6.31270981e+01 6.18735085e+01 6.63176346e+01 6.19580154e+01 5.21177902e+01 5.50753746e+01 5.97449989e+01 7.59332352e+01 6.88044739e+01 4.96100159e+01 3.92954369e+01 4.45093575e+01 6.34311104e+01 6.55747757e+01 5.28797607e+01 5.04825439e+01 3.93594818e+01 4.43026276e+01 5.66286430e+01 6.55215912e+01 5.25016518e+01 2.32504234e+01 1.12862695e+03 3.35792554e+03 60965684. 25801794. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 301800640. 50986700. -285477376. 53173812. -5.63902710e+10 -9.36358719e+01 2.96261168e+00 6.08747444e+01 4.25586967e+01 4.54027443e+01 6.38367424e+01 6.38577423e+01 6.69140472e+01 6.19027634e+01 3.72130432e+01 2.73137665e+01 3.45301895e+01 6.46584702e+01 7.22827377e+01 5.02063713e+01 3.33411255e+01 2.42132530e+01 4.09989853e+01 6.01015091e+01 6.23971748e+01 5.95239258e+01 3.89064178e+01 2.67873955e+01 2.40308704e+01 3.38318138e+01 4.28114319e+01 4.35760345e+01 4.48801155e+01 4.56392288e+01 4.42540894e+01 5.29945221e+01 6.32510300e+01 7.04118042e+01 5.77561417e+01 2.76405697e+01 1.75380898e+01 2.49435101e+01 5.35385246e+01 6.22229156e+01 5.53700829e+01 4.86949158e+01 3.96552010e+01 4.62400932e+01 5.10728302e+01 4.67476921e+01 4.04844170e+01 2.69045544e+01 1.90418720e+01 1.64044342e+01 2.09746094e+01 4.44389534e+01 5.24919662e+01 5.42646294e+01 3.22837639e+01 1.21232061e+01 2.19449463e+01 4.48683090e+01 6.73013077e+01 6.57696686e+01 3.96445618e+01 2.40166187e+01 2.05609818e+01 4.49613800e+01 6.24834442e+01 5.42843895e+01 4.44290581e+01 2.87691364e+01 4.25686493e+01 5.62152786e+01 5.50293732e+01 4.05395470e+01 8.27735996e+00 -4.79569912e+00 -5.22614479e+00 1.06187620e+01 2.53804531e+01 2.13138962e+01 2.72620754e+01 2.87063789e+01 1.96923332e+01 2.08003616e+01 3.09981899e+01 4.70846519e+01 3.41318016e+01 -2.89332914e+00 -9.37920284e+00 5.49853849e+00 4.46465340e+01 5.70950279e+01 4.63540993e+01 4.20220108e+01 2.27285538e+01 2.46138306e+01 3.15339451e+01 4.07674866e+01 4.36179695e+01 2.12889996e+01 8.86993885e+00 9.29800224e+00 1.81341228e+01 3.83740883e+01 4.40015488e+01 5.14779930e+01 4.55196342e+01 2.48067970e+01 2.74361267e+01 3.57775803e+01 5.60022736e+01 5.71426735e+01 3.72373581e+01 2.54529896e+01 2.34416027e+01 4.44865646e+01 5.72498207e+01 4.44188423e+01 3.40171280e+01 1.08705597e+01 -1.54093921e+00 -2.27415666e-01 1.28393040e+01 3.53766441e+01 3.60370407e+01 1.76171322e+01 5.82957554e+00 8.40878367e-01 2.65143661e+01 4.08542862e+01 5.03630943e+01 4.37885323e+01 6.30678701e+00 -4.18867970e+00 3.96035492e-01 3.48822441e+01 4.78861275e+01 2.86492195e+01 1.83690033e+01 1.93630409e+01 4.11847534e+01 6.15550308e+01 4.96247559e+01 3.97011833e+01 1.97408981e+01 2.76869335e+01 4.36447411e+01 4.65975227e+01 5.07028580e+01 4.56815453e+01 3.99939346e+01 2.92140846e+01 2.09925594e+01 3.76318245e+01 5.12140999e+01 5.66910515e+01 4.27098312e+01 2.15747471e+01 2.06259079e+01 2.66014805e+01 3.75963020e+01 3.72392426e+01 1.60682411e+01 2.64951420e+00 -1.98079777e+00 1.05466852e+01 1.53262949e+01 7.06322765e+00 1.00762033e+01 2.44742298e+00 -4.63705206e+00 -6.27995968e+00 1.87986672e+00 1.09544230e+01 1.31563282e+01 1.51821136e+01 1.39684315e+01 1.20877733e+01 2.06445503e+01 3.61250877e+01 5.10848656e+01 5.33537369e+01 3.34523659e+01 1.71414928e+01 1.80107841e+01 3.72927094e+01 5.64402122e+01 4.66284027e+01 3.63356209e+01 1.39029665e+01 2.00277748e+01 3.00344658e+01 3.26373520e+01 3.16842403e+01 2.17384815e+01 9.02721500e+00 -2.61667538e+00 -4.48592615e+00 8.66599560e+00 1.11102190e+01 4.56572247e+00 -8.48827839e+00 -1.72299805e+01 4.17661762e+00 2.83016911e+01 4.61114502e+01 4.35717354e+01 2.05522289e+01 8.20268059e+00 6.88732386e+00 2.89302368e+01 3.51503639e+01 2.03249645e+01 1.33763971e+01 9.96352100e+00 1.97540951e+01 2.42067776e+01 1.65217037e+01 5.47941303e+00 -1.70696869e+01 -3.33186493e+01 -3.75455132e+01 -3.24655418e+01 -4.79520369e+00 9.58430862e+00 3.03486519e+01 1.95668850e+01 -2.31959381e+01 -5.41807518e+01 -5.00656738e+01 -1.78936386e+01 -2.15312099e+00 -1.12596140e+01 -1.10374653e+00 1.17706919e+01 1.65573139e+01 9.88758373e+00 -6.15712547e+00 -1.04204330e+01 -1.30312843e+01 -8.41839600e+00 -2.35041499e+00 -7.74547434e+00 -1.64526405e+01 -2.27981701e+01 -1.87662010e+01 -1.09214439e+01 -8.89388371e+00 -6.67710972e+00 -9.67758274e+00 -4.61526820e-03 9.67931557e+00 1.37927828e+01 4.80378532e+00 -6.84342813e+00 -4.60837126e+00 6.83965802e-01 2.30263543e+00 1.87668771e-01 -2.04146218e+00 -2.04888880e-01 2.26629877e+00 3.83436799e-01 -1.90923512e+00 -9.91802025e+00 -1.27301102e+01 -9.78156376e+00 -7.78874159e+00 -3.84733963e+00 -9.43652534e+00 -9.04993343e+00 -1.25806561e+01 -6.53025866e+00 -5.65104103e+00 -4.12839270e+00 -9.86404991e+00 -1.22988577e+01 -9.99452972e+00 -5.47340631e+00 -6.10866261e+00 -1.25278206e+01 -2.12689571e+01 -2.01610546e+01 -2.33626823e+01 -2.44984150e+01 -2.37987976e+01 -1.57525320e+01 -9.58847713e+00 -1.04078360e+01 -9.68857288e+00 -1.02176723e+01 -1.05355759e+01 -1.71295681e+01 -1.75074253e+01 -1.45039988e+01 -8.65470886e+00 -1.19041567e+01 -1.08432217e+01 -1.35921078e+01 -1.04104424e+01 -1.28716898e+01 -1.40675592e+01 -1.31746769e+01 -1.42565355e+01 -1.22817059e+01 -1.36941347e+01 -1.78677979e+01 -2.53068371e+01 -2.81756916e+01 -2.41898022e+01 -1.52666531e+01 -1.37894516e+01 -1.13902416e+01 -1.76896400e+01 -2.10047054e+01 -2.46119633e+01 -1.99752331e+01 -1.09557972e+01 -8.83051395e+00 -1.41229448e+01 -1.55364704e+01 -1.33171854e+01 -1.01735029e+01 -1.33507328e+01 -1.68295918e+01 -1.72189598e+01 -2.19556503e+01 -2.47335243e+01 -2.79634552e+01 -2.78564014e+01 -2.77946014e+01 -2.75184517e+01 -2.35346603e+01 -2.43961658e+01 -2.45540104e+01 -2.50054646e+01 -2.40526237e+01 -2.67979736e+01 -3.34971619e+01 -3.06532803e+01 -2.35246468e+01 -1.92770004e+01 -1.97108803e+01 -2.57055626e+01 -2.68393917e+01 -2.84458332e+01 -2.47207432e+01 -2.32744122e+01 -2.40685501e+01 -2.89493866e+01 -3.69408722e+01 -4.52434578e+01 -4.92295074e+01 -5.10638428e+01 -4.47598038e+01 -3.83903542e+01 -2.75679665e+01 -2.36417713e+01 -2.69945488e+01 -3.04632187e+01 -3.42705231e+01 -4.26362305e+01 -5.31319466e+01 -4.78722687e+01 -3.82757378e+01 -2.98727417e+01 -3.60712013e+01 -4.38656731e+01 -4.87517395e+01 -4.18724213e+01 -3.09724369e+01 -2.51590252e+01 -3.56384392e+01 -4.93835449e+01 -5.23409958e+01 -4.41903992e+01 -3.08726501e+01 -2.98577156e+01 -3.27308846e+01 -3.66760101e+01 -3.74162598e+01 -3.57862854e+01 -3.34418640e+01 -4.03379517e+01 -5.01130905e+01 -4.80331802e+01 -4.01907997e+01 -3.32788200e+01 -3.47289848e+01 -3.44459381e+01 -3.28055420e+01 -3.23743935e+01 -3.17194309e+01 -3.78324471e+01 -4.52744751e+01 -4.54980354e+01 -4.10971107e+01 -3.51872063e+01 -3.80071373e+01 -3.89016495e+01 -3.53011703e+01 -2.95546646e+01 -1.79560165e+01 -1.08151312e+01 -1.99314079e+01 -3.22699394e+01 -4.05464401e+01 -3.75715866e+01 -3.45276337e+01 -3.33965416e+01 -2.93841343e+01 -2.94643955e+01 -3.10435925e+01 -3.40075455e+01 -3.63785782e+01 -3.69906731e+01 -3.48281517e+01 -3.42506027e+01 -3.27343292e+01 -3.43458023e+01 -3.36630974e+01 -3.52342262e+01 -3.75438805e+01 -4.40290260e+01 -4.79345169e+01 -4.52442284e+01 -3.50410042e+01 -2.73083801e+01 -2.55618382e+01 -3.11754723e+01 -4.26430664e+01 -4.69572105e+01 -4.42046280e+01 -4.12064133e+01 -3.99354324e+01 -4.28700371e+01 -3.49620514e+01 -2.62818050e+01 -2.45268822e+01 -3.30392113e+01 -4.18488197e+01 -4.26017189e+01 -3.73389053e+01 -3.32396011e+01 -3.33854561e+01 -3.68154182e+01 -4.42464828e+01 -4.34860649e+01 -4.39445038e+01 -4.27503052e+01 -4.46148224e+01 -3.96106834e+01 -3.32324448e+01 -3.22742615e+01 -3.75313911e+01 -4.33819923e+01 -6.94338989e+01 -6.49885864e+01 -4.10402298e+01 1.14392493e+03 9.82107227e+03 24924678. 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. 0. 0. 0. 0. 0. 0. 0. 531313536. 101834000. 25236908. 79759368. 5.72096729e+03 -6.93767944e+02 -7.08361023e+02 -1.27531670e+02 -8.90819473e+01 -5.84684753e+01 -6.61067505e+01 -6.35153465e+01 -6.33442764e+01 -6.30930977e+01 -6.40345917e+01 -6.30894852e+01 -6.13401222e+01 -5.98603592e+01 -5.42086182e+01 -4.91530685e+01 -5.19720497e+01 -5.81276894e+01 -5.99558678e+01 -5.54290314e+01 -5.13843918e+01 -5.06679153e+01 -4.79247284e+01 -4.56383896e+01 -4.19538269e+01 -4.14719620e+01 -4.31165810e+01 -4.61687851e+01 -4.77019577e+01 -4.68469772e+01 -4.67161026e+01 -4.68436089e+01 -5.24875107e+01 -5.96115685e+01 -6.10830574e+01 -6.01653633e+01 -5.75243340e+01 -5.93667526e+01 -5.88486443e+01 -5.69067383e+01 -5.67891388e+01 -5.63444672e+01 -5.93787994e+01 -5.80248260e+01 -5.61763306e+01 -5.34922562e+01 -5.60700455e+01 -5.94625816e+01 -6.09095345e+01 -5.83260155e+01 -5.78552895e+01 -5.89264221e+01 -6.15370216e+01 -6.31167641e+01 -6.36082840e+01 -6.24395981e+01 -5.80916901e+01 -5.84014320e+01 -6.10144386e+01 -6.45895844e+01 -6.60993423e+01 -6.67369843e+01 -6.74061661e+01 -6.71007004e+01 -6.57628860e+01 -6.61457901e+01 -6.47725906e+01 -6.41518326e+01 -6.30517883e+01 -6.18244934e+01 -6.13670235e+01 -5.50049667e+01 -4.95305977e+01 -4.92376366e+01 -5.43513527e+01 -5.99677811e+01 -5.99391136e+01 -6.02896805e+01 -6.37569580e+01 -6.78833160e+01 -7.25797272e+01 -7.45401382e+01 -7.11301498e+01 -6.68771210e+01 -6.21794930e+01 -6.31123619e+01 -6.42265549e+01 -6.48949509e+01 -6.40171967e+01 -6.31847382e+01 -6.22193604e+01 -6.23898354e+01 -6.24902077e+01 -6.24129219e+01 -6.13634300e+01 -6.16199760e+01 -6.00229836e+01 -5.98519135e+01 -5.87554245e+01 -5.92965317e+01 -5.85595665e+01 -5.81396217e+01 -5.94878311e+01 -6.32969818e+01 -6.68032150e+01 -6.83770599e+01 -6.88550339e+01 -6.52245636e+01 -6.22035561e+01 -5.76224747e+01 -5.81522293e+01 -5.96077957e+01 -5.95986023e+01 -5.82482109e+01 -5.71749153e+01 -5.85931511e+01 -6.08606606e+01 -6.18121910e+01 -6.29951439e+01 -6.36165733e+01 -6.48582611e+01 -6.53180161e+01 -6.55398712e+01 -6.50597229e+01 -6.46826248e+01 -6.44556274e+01 -6.43551483e+01 -6.42061996e+01 -6.61543198e+01 -6.80589905e+01 -7.00292587e+01 -6.99353180e+01 -6.82321701e+01 -6.64421005e+01 -6.39934311e+01 -6.34317398e+01 -6.33072128e+01 -6.32797623e+01 -6.30923271e+01 -6.27283020e+01 -6.24731979e+01 -6.28874435e+01 -6.31600761e+01 -6.31091499e+01 -6.27539024e+01 -6.28007088e+01 -6.28291931e+01 -6.33126068e+01 -6.44535828e+01 -6.60636520e+01 -6.59410858e+01 -6.50035553e+01 -6.38598022e+01 -6.47822952e+01 -6.56899338e+01 -6.64220505e+01 -6.60125504e+01 -6.50250397e+01 -6.43901062e+01 -6.38277283e+01 -6.37450943e+01 -6.35152016e+01 -6.34780769e+01 -6.34799728e+01 -6.34902878e+01 -6.35683823e+01 -6.35792160e+01 -6.36007156e+01 -6.35958862e+01 -6.36265526e+01 -6.36338501e+01 -6.36304626e+01 -6.36577454e+01 -6.36083031e+01 -6.34374657e+01 -6.33289757e+01 -6.34130707e+01 -6.35977478e+01 -6.36400146e+01 -6.38469582e+01 -6.35102615e+01 -6.29859467e+01 -6.27078781e+01 -6.31048813e+01 -6.35380096e+01 -6.32694016e+01 -6.32901497e+01 -6.33291931e+01 -6.34161911e+01 -6.30915642e+01 -6.29667473e+01 -6.32797890e+01 -6.34249344e+01 -6.35076942e+01 -6.33471222e+01 -6.30593681e+01 -6.27790642e+01 -6.24474068e+01 -6.16375427e+01 -6.08697433e+01 -6.00019531e+01 -6.03257828e+01 -6.12064934e+01 -6.21024246e+01 -6.33019829e+01 -6.35532494e+01 -6.37186890e+01 -6.36179504e+01 -6.34441414e+01 -6.35239601e+01 -6.35307121e+01 -6.39073448e+01 -6.41887054e+01 -6.39032516e+01 -6.38046837e+01 -6.36575966e+01 -6.59011612e+01 -6.77684708e+01 -6.69604340e+01 -6.47409973e+01 -6.29002876e+01 -6.34919930e+01 -6.36641541e+01 -6.17672501e+01 -5.92646294e+01 -5.86580658e+01 -6.03249245e+01 -6.28452644e+01 -6.24834557e+01 -6.22758751e+01 -6.16979446e+01 -6.17975388e+01 -6.15382347e+01 -6.17129745e+01 -6.15966797e+01 -6.15077171e+01 -6.13172150e+01 -6.07148209e+01 -6.02186546e+01 -6.02442093e+01 -6.05147667e+01 -5.85565796e+01 -5.44111900e+01 -5.27300224e+01 -5.40196190e+01 -5.75398407e+01 -5.96503181e+01 -5.92947388e+01 -5.55108948e+01 -5.13780632e+01 -5.27045135e+01 -5.69491196e+01 -6.10752411e+01 -6.16377182e+01 -6.22617989e+01 -6.14387016e+01 -6.10039635e+01 -6.41373978e+01 -6.93398514e+01 -7.00423203e+01 -6.63119507e+01 -6.12861328e+01 -6.15537872e+01 -6.20643539e+01 -6.21175232e+01 -6.06926727e+01 -5.72405968e+01 -5.39249268e+01 -5.34860573e+01 -5.58676682e+01 -5.91604271e+01 -5.92408485e+01 -5.97030182e+01 -5.61956329e+01 -5.26946297e+01 -5.38927803e+01 -5.76272278e+01 -6.33538704e+01 -6.34064789e+01 -6.44652328e+01 -6.27159958e+01 -6.09900169e+01 -6.00175323e+01 -6.00096092e+01 -6.04008675e+01 -6.04881744e+01 -6.10481834e+01 -6.11669044e+01 -6.10396385e+01 -5.96912155e+01 -5.70099030e+01 -5.01133842e+01 -4.39778519e+01 -4.09868088e+01 -4.28927536e+01 -5.08027496e+01 -5.66356812e+01 -6.12232780e+01 -5.98906670e+01 -5.81403160e+01 -5.74847260e+01 -5.60673599e+01 -5.65184708e+01 -5.67190514e+01 -5.88072701e+01 -5.80618286e+01 -5.84756012e+01 -5.77114944e+01 -5.77399521e+01 -5.57157135e+01 -5.52115707e+01 -5.62181053e+01 -5.62021179e+01 -5.70664711e+01 -5.69461632e+01 -5.84136162e+01 -5.92975578e+01 -5.98576088e+01 -5.53993454e+01 -5.10226364e+01 -4.99107285e+01 -4.73422012e+01 -4.24824944e+01 -3.57591896e+01 -3.55965958e+01 -3.85805740e+01 -3.81677132e+01 -4.04822502e+01 -3.84500961e+01 -4.27397194e+01 -4.73856773e+01 -5.27881927e+01 -4.77277451e+01 -3.89071617e+01 -4.02399940e+01 -4.49340706e+01 -5.09167366e+01 -4.94354553e+01 -4.94117393e+01 -5.02969627e+01 -5.18517151e+01 -5.09683952e+01 -4.86081581e+01 -3.96828461e+01 -3.27226334e+01 -3.54710121e+01 -4.16963120e+01 -4.99351006e+01 -4.36419868e+01 -4.08819580e+01 -3.76245117e+01 -3.58575020e+01 -3.15910397e+01 -2.42311230e+01 -3.09038353e+01 -4.01278343e+01 -5.00596199e+01 -5.38072777e+01 -5.69647369e+01 -5.55154381e+01 -5.17761650e+01 -3.96623154e+01 -3.23153839e+01 -2.18786755e+01 -1.88030643e+01 -2.49102783e+01 -2.50352135e+01 -2.52016144e+01 -2.47179985e+01 -3.34985046e+01 -4.41195412e+01 -4.61608200e+01 -4.49542198e+01 -4.25429230e+01 -4.23779564e+01 -3.58602791e+01 -3.08678989e+01 -3.05666084e+01 -3.92734718e+01 -4.94509964e+01 -5.02090988e+01 -4.94139977e+01 -4.64255943e+01 -4.62742462e+01 -4.85515442e+01 -5.30091324e+01 -5.38661537e+01 -5.29955139e+01 -4.33644295e+01 -3.45048485e+01 -3.13497143e+01 -3.56954422e+01 -3.91076431e+01 -3.97480278e+01 -4.42080650e+01 -4.94202347e+01 -5.05342178e+01 -3.93017197e+01 -2.75097637e+01 -2.43267155e+01 -2.82138367e+01 -3.49597015e+01 -3.59354858e+01 -3.58244743e+01 -3.91339417e+01 -4.23034935e+01 -5.12677536e+01 -4.26826782e+01 -2.82003689e+01 -2.76102180e+01 -3.99260483e+01 -5.15740891e+01 -4.44650726e+01 -3.24264984e+01 -2.41301231e+01 -2.77011604e+01 -3.61694374e+01 -4.28895035e+01 -4.03438835e+01 -4.00022278e+01 -3.02246418e+01 -2.35567131e+01 -2.17412853e+01 -2.50810509e+01 -2.80041370e+01 -2.51187229e+01 -2.91032639e+01 -2.26680298e+01 -1.28946180e+01 -1.17355394e+01 -2.10035038e+01 -3.33839378e+01 -2.83485832e+01 -1.89488411e+01 -1.56167727e+01 -2.02451496e+01 -3.11037292e+01 -3.41532440e+01 -3.50492821e+01 -3.33669968e+01 -3.72696686e+01 -4.40961876e+01 -4.49009056e+01 -3.91359177e+01 -2.96280842e+01 -2.47525558e+01 -2.24013729e+01 -2.55873241e+01 -2.91531658e+01 -3.71710358e+01 -4.14796524e+01 -4.65132484e+01 -4.61603661e+01 -4.21907845e+01 -3.51711426e+01 -3.42741051e+01 -3.78045197e+01 -3.40844421e+01 -2.75630741e+01 -3.15644608e+01 -3.98155937e+01 -5.23586159e+01 -5.38388557e+01 -5.00720406e+01 -3.86775169e+01 -2.40584049e+01 -1.16493769e+01 1.95995343e+00 -1.29399574e+00 -1.49511127e+01 -2.01462440e+01 -1.19213190e+01 -1.18457136e+01 -2.23953533e+01 -2.88942719e+01 -2.86197643e+01 -2.81735573e+01 -2.92611465e+01 -2.48815975e+01 -2.61528759e+01 -3.21749191e+01 -4.18427010e+01 -3.77166023e+01 -2.92730408e+01 -3.03679066e+01 -3.52164803e+01 -2.70397606e+01 -9.40425014e+00 -1.10200548e+01 -2.94129887e+01 -4.67511711e+01 -4.30235977e+01 -2.87200985e+01 -1.27029762e+01 -1.21139565e+01 -2.16293297e+01 -2.75502834e+01 -1.78298359e+01 -1.15770779e+01 -1.29937811e+01 -2.23360271e+01 -2.13270817e+01 -6.75381136e+00 1.25160408e+01 2.40156898e+01 2.61825485e+01 -3.86894882e-01 -2.74052486e+01 -3.20838585e+01 -6.53446674e+00 1.17176132e+01 1.59405303e+00 -1.40502176e+01 -2.33032589e+01 -2.91278248e+01 -3.58829460e+01 -3.75169601e+01 -3.32476616e+01 -2.51045036e+01 -1.44272718e+01 -3.48888564e+00 9.53611183e+00 8.13449764e+00 -5.76777458e+00 -1.85367546e+01 -1.84425087e+01 -1.58181019e+01 -1.94360123e+01 -1.90010376e+01 -1.84525967e+01 -1.65152187e+01 -1.71117954e+01 -2.15099354e+01 -1.38427200e+01 -3.36809039e+00 1.22156411e-01 2.87127709e+00 7.55599928e+00 4.46775961e+00 -7.69297791e+00 -2.03862953e+01 -1.92427292e+01 -1.92894268e+01 -2.07184467e+01 -1.96121521e+01 -3.27058697e+00 1.16572571e+01 2.40804005e+01 2.48821201e+01 5.38074589e+00 -1.10403461e+01 -2.11915855e+01 -8.03838348e+00 5.71628714e+00 1.56622338e+00 -7.29797697e+00 -1.27926140e+01 -9.44854450e+00 -4.29540537e-02 5.35216713e+00 4.70871115e+00 8.45459843e+00 2.66784725e+01 4.54415131e+01 3.89606628e+01 1.19576178e+01 -4.09372759e+00 7.72035456e+00 2.24252968e+01 2.59037399e+01 1.05664339e+01 -2.99735975e+00 4.16776991e+00 1.53050880e+01 3.15676842e+01 3.54542198e+01 2.04453907e+01 3.05707663e-01 -1.94040127e+01 -2.04714565e+01 -1.78365440e+01 -1.98190804e+01 -1.76382389e+01 -9.50009918e+00 4.24162531e+00 5.40886784e+00 -4.47193480e+00 -1.63193474e+01 -2.48697090e+01 -2.24369030e+01 -3.32821059e+00 1.78763447e+01 1.40446148e+01 -2.00182891e+00 -1.18426676e+01 -1.12258577e+01 -1.00559721e+01 -1.22246017e+01 -1.29007215e+01 -8.25597286e+00 -9.37087059e+00 -1.09000111e+00 1.95980053e+01 3.11175251e+01 2.65282822e+01 2.88831863e+01 9.46967621e+01 7.57686621e+03 0. 0. 0. 0. 0. -1.00518359e+10 6.88672050e+06 -1.24118050e+06 9.57281860e+02 -3.14223584e+03 -3.96726831e+03 2.57269953e+05 2.57294008e+10 1.98114714e+10 1.98114714e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.57624832e+09 -35889752. 4.13504025e+06 -9.55014258e+03 -3.63270850e+03 -8.92118286e+02 4.69423180e+01 -1.40610870e+02 -4.91317825e+01 -7.70866089e+01 -6.53300934e+01 -3.56595383e+01 -1.48999224e+01 2.23559046e+00 8.13846874e+00 1.72853203e+01 -1.81375813e+00 -2.81874161e+01 -5.40693016e+01 -4.95848618e+01 3.10126901e-01 4.52137680e+01 7.02692566e+01 8.24026108e+01 5.99827271e+01 5.48896027e+01 4.21984444e+01 1.22133503e+01 -5.90283298e+00 7.93133402e+00 5.15341797e+01 9.68395233e+01 9.24767838e+01 5.83153915e+01 -1.06262808e+01 -2.43504715e+01 -1.15616293e+01 5.33186555e-01 2.06375003e+00 9.33802223e+00 4.26323738e+01 6.40844345e+01 4.83635597e+01 1.59242287e+01 3.78769708e+00 3.18709373e+01 3.75166779e+01 2.85057278e+01 4.10847321e+01 3.86122169e+01 4.03644333e+01 2.34516697e+01 4.23555613e+00 -1.27981157e+01 -1.69206505e+01 2.86491528e+01 8.37764130e+01 9.67177963e+01 6.43094101e+01 9.45005322e+00 3.46088290e+00 2.63076763e+01 4.39370232e+01 3.61464272e+01 2.86456833e+01 3.98759575e+01 4.90332832e+01 4.70948067e+01 2.05077267e+01 -1.24107285e+01 1.44517332e-01 9.68098450e+00 2.39358845e+01 3.40182266e+01 3.86702766e+01 5.20656013e+01 3.28750763e+01 6.45219517e+00 -2.36805305e+01 -1.60681629e+01 1.85631714e+01 5.46816101e+01 7.48311996e+01 7.58116074e+01 4.58312149e+01 3.33921585e+01 3.24758873e+01 1.04408855e+01 -1.79056759e+01 -1.95408478e+01 2.95044346e+01 7.32888565e+01 7.09925613e+01 3.04734955e+01 -1.17422352e+01 -1.41043186e+01 -5.77285624e+00 -5.23232460e+00 -5.93651772e+00 8.83265400e+00 3.34028893e+01 4.53994293e+01 3.00899200e+01 4.17137861e+00 4.20450258e+00 2.88484535e+01 5.83085632e+01 6.87532196e+01 6.66026382e+01 3.74358864e+01 1.10449085e+01 1.66862812e+01 1.73387604e+01 5.75653219e+00 -1.92489755e+00 1.93804951e+01 5.72018204e+01 5.56119804e+01 1.81800499e+01 -1.85848446e+01 -2.41706791e+01 7.58601999e+00 3.81019287e+01 6.08133240e+01 7.13821106e+01 5.53270683e+01 4.36381340e+01 3.57411041e+01 1.07002535e+01 -1.34204969e+01 -1.35624676e+01 9.67767811e+00 4.02002029e+01 5.32835083e+01 5.24590187e+01 3.38926239e+01 2.32769165e+01 2.14084778e+01 1.82597046e+01 7.10705423e+00 3.19522786e+00 2.81034241e+01 6.44435806e+01 8.48851929e+01 7.75206299e+01 6.09102821e+01 5.86888885e+01 4.39898300e+01 3.68991165e+01 4.34401588e+01 4.98730774e+01 6.98260574e+01 7.44985733e+01 6.99739075e+01 4.85304985e+01 4.13185005e+01 5.93162880e+01 7.75521545e+01 6.64613647e+01 3.80052032e+01 2.46958542e+01 4.61274643e+01 6.99605789e+01 6.71342392e+01 6.39052582e+01 6.68762894e+01 9.65654221e+01 1.17731834e+02 1.18960968e+02 7.73622284e+01 3.01211586e+01 2.24412231e+01 2.92628880e+01 3.16067772e+01 3.28706017e+01 4.72901192e+01 7.60779724e+01 8.94618454e+01 6.44956665e+01 3.74360237e+01 2.98635979e+01 5.91063194e+01 8.07379150e+01 8.01573410e+01 7.78677444e+01 6.99679337e+01 8.16322327e+01 8.28496475e+01 7.37286911e+01 7.11549759e+01 7.60476074e+01 9.84576492e+01 1.09991547e+02 1.08009117e+02 6.88616180e+01 3.12056980e+01 2.35739059e+01 3.86223259e+01 4.62281456e+01 5.03917236e+01 6.06399994e+01 8.47204742e+01 8.69367676e+01 5.68896599e+01 2.68242054e+01 2.04538803e+01 4.96533508e+01 6.25334206e+01 6.46656723e+01 6.32896385e+01 6.37160912e+01 7.30596390e+01 8.49735260e+01 6.85464630e+01 4.70486641e+01 3.72796059e+01 5.93897743e+01 8.30233002e+01 8.69196091e+01 6.51458359e+01 4.81960373e+01 4.64093513e+01 5.58763771e+01 5.32118835e+01 5.27252159e+01 4.99277496e+01 5.60700111e+01 5.60958099e+01 5.34922523e+01 4.66078377e+01 3.73508492e+01 3.86154022e+01 4.31319237e+01 4.90023956e+01 7.03551254e+01 8.02944565e+01 9.57065582e+01 8.47361221e+01 6.77888184e+01 5.29631157e+01 3.91352386e+01 6.57004395e+01 8.62963791e+01 9.08882523e+01 6.63383560e+01 5.25797424e+01 6.37688828e+01 7.63581848e+01 6.58594818e+01 5.26673088e+01 5.91600761e+01 8.03779984e+01 9.08336945e+01 8.03221588e+01 7.79169922e+01 7.54862671e+01 7.64957123e+01 6.64022369e+01 7.36032028e+01 8.01790161e+01 8.68289490e+01 9.57524796e+01 9.44760971e+01 8.94489899e+01 6.96493073e+01 5.67465744e+01 6.81484680e+01 9.73514175e+01 1.07892021e+02 9.61236115e+01 8.87908630e+01 9.31031265e+01 1.00418701e+02 8.61140976e+01 7.76032562e+01 7.67731018e+01 8.14278793e+01 8.05366745e+01 7.72856903e+01 8.29824905e+01 8.32630768e+01 7.27518616e+01 6.42165146e+01 6.80773926e+01 6.45985947e+01 5.20970192e+01 5.28393021e+01 7.02030487e+01 8.73962860e+01 8.54818802e+01 8.09519958e+01 8.43845901e+01 9.50497513e+01 8.95315170e+01 7.96562347e+01 7.84171906e+01 8.88308487e+01 9.91064148e+01 9.43668823e+01 9.10579987e+01 8.38280411e+01 8.53957977e+01 7.69841995e+01 6.86910400e+01 7.08914719e+01 7.81588593e+01 8.49138184e+01 8.05967255e+01 7.72298431e+01 7.12226791e+01 6.27592850e+01 6.54503479e+01 7.10731354e+01 7.97567139e+01 7.32214966e+01 6.68697357e+01 7.35558929e+01 8.99079514e+01 9.15686722e+01 8.12521133e+01 7.40269928e+01 8.45078583e+01 9.37428970e+01 8.93462524e+01 8.30801086e+01 7.44493027e+01 7.33371048e+01 6.75564957e+01 6.65428391e+01 7.11068268e+01 7.54495316e+01 7.73649063e+01 7.57009354e+01 7.86799088e+01 7.65982971e+01 7.26882858e+01 7.53990402e+01 8.66733780e+01 9.40070038e+01 9.25158539e+01 8.97114334e+01 9.27709885e+01 9.70358810e+01 9.27353363e+01 8.96419525e+01 8.83476639e+01 9.46619873e+01 9.35238419e+01 8.91975098e+01 8.91311874e+01 8.76335373e+01 8.69908676e+01 7.76067810e+01 7.43072281e+01 7.72594452e+01 8.47942276e+01 9.30689850e+01 9.17189178e+01 8.85795441e+01 8.23981400e+01 7.34258041e+01 7.52480469e+01 8.84377518e+01 1.03842720e+02 1.08548935e+02 1.00253151e+02 9.49855499e+01 9.72402115e+01 9.82129059e+01 1.02987091e+02 9.69606476e+01 9.63998947e+01 9.28146133e+01 9.30484543e+01 1.02283684e+02 1.05075897e+02 1.05024780e+02 9.30108643e+01 8.52645416e+01 8.99986801e+01 9.62047806e+01 9.90399857e+01 9.13312073e+01 8.50977020e+01 8.61060104e+01 8.64444199e+01 9.07021179e+01 9.37199707e+01 9.71833649e+01 9.92884674e+01 9.61689987e+01 9.30282440e+01 9.05644302e+01 9.04107361e+01 9.62081528e+01 9.87872391e+01 1.01656982e+02 9.85784607e+01 9.32074814e+01 9.26251984e+01 9.25143585e+01 9.19907608e+01 8.76465683e+01 8.80891495e+01 9.55584641e+01 1.00132599e+02 1.00252670e+02 9.61610565e+01 9.39906769e+01 9.33204575e+01 9.14034500e+01 9.15583420e+01 9.37453842e+01 9.52890320e+01 9.70970917e+01 9.58472519e+01 9.54108810e+01 9.51889038e+01 9.47838211e+01 9.47788849e+01 9.21363144e+01 9.19770584e+01 9.23722610e+01 9.31686249e+01 9.48897705e+01 9.53218842e+01 9.51962128e+01 9.30533142e+01 9.17269974e+01 9.18163300e+01 9.29414673e+01 9.37961655e+01 9.31743011e+01 9.24660797e+01 9.23228226e+01 9.25760345e+01 9.27980881e+01 9.29036484e+01 9.28828812e+01 9.27796631e+01 9.28319626e+01 9.30157700e+01 9.32748108e+01 9.30422363e+01 9.19570999e+01 9.12147903e+01 9.12807159e+01 9.23750687e+01 9.36275101e+01 9.29392395e+01 9.16460648e+01 9.07637329e+01 9.21628265e+01 9.36871033e+01 9.34138870e+01 9.25085068e+01 9.15072861e+01 9.16781235e+01 9.20376511e+01 9.11935120e+01 9.11066971e+01 9.12387085e+01 9.09254456e+01 9.07995987e+01 8.91513596e+01 9.02860794e+01 9.08182373e+01 9.15843506e+01 9.21586685e+01 8.96334763e+01 9.11968231e+01 9.27457352e+01 9.66963196e+01 9.59118958e+01 9.01252747e+01 8.56732788e+01 8.39171295e+01 9.05714722e+01 9.57677917e+01 9.75808487e+01 9.44129791e+01 8.97994614e+01 8.93576126e+01 9.23396912e+01 9.52927780e+01 9.80393600e+01 9.51242447e+01 8.92648163e+01 8.21826706e+01 8.19784851e+01 9.08726425e+01 9.84543686e+01 1.01484772e+02 9.86990128e+01 8.98424530e+01 8.26013031e+01 8.13670197e+01 8.96687088e+01 9.79651489e+01 9.56599274e+01 8.74777222e+01 8.17406158e+01 8.75627136e+01 9.68391266e+01 9.84792023e+01 9.50439072e+01 8.68907623e+01 8.11772537e+01 8.03783112e+01 8.19166412e+01 8.81857758e+01 9.34939957e+01 9.40172577e+01 9.13819275e+01 8.18746796e+01 8.32457199e+01 8.72961349e+01 9.08014374e+01 9.62234344e+01 8.87640076e+01 8.82676849e+01 8.61866760e+01 9.41101074e+01 9.65863800e+01 8.24914627e+01 7.50179901e+01 7.42629471e+01 8.83465500e+01 9.83523026e+01 9.99507065e+01 9.49795151e+01 8.39890823e+01 7.63754959e+01 7.67118454e+01 7.83568726e+01 8.64593964e+01 8.95837173e+01 8.71369553e+01 8.67492752e+01 8.31975708e+01 9.42663956e+01 9.44329300e+01 9.53049164e+01 9.21365662e+01 7.98321915e+01 7.90228958e+01 8.37783203e+01 1.01832718e+02 1.08028099e+02 1.03834801e+02 9.41922684e+01 8.37464523e+01 9.02286377e+01 1.00947456e+02 1.07660080e+02 1.03829552e+02 9.39908218e+01 8.77811737e+01 8.44101639e+01 8.19871979e+01 8.12134323e+01 8.13977280e+01 8.11820374e+01 7.81195908e+01 6.63173676e+01 7.66188812e+01 9.02383423e+01 1.01657341e+02 9.13021851e+01 7.12816620e+01 6.20869102e+01 6.65588760e+01 8.38953018e+01 9.56619339e+01 8.94793167e+01 8.06539383e+01 7.56824722e+01 8.02797546e+01 8.38175659e+01 7.73365936e+01 7.34826736e+01 6.83525620e+01 6.54188995e+01 6.39247475e+01 6.12307968e+01 7.10995941e+01 7.66551590e+01 7.72879410e+01 7.81559525e+01 6.90870361e+01 7.34798431e+01 7.44726639e+01 8.40247955e+01 8.96806335e+01 7.52566833e+01 7.33308334e+01 6.86616058e+01 8.11627960e+01 8.76355667e+01 7.76651840e+01 7.43278961e+01 5.51663551e+01 6.37384300e+01 7.52309418e+01 9.13655930e+01 9.81738892e+01 7.68173599e+01 6.97241135e+01 6.67290802e+01 6.43866043e+01 6.35925827e+01 6.58580399e+01 9.18109589e+01 9.65374527e+01 7.05763550e+01 7.52270737e+01 9.89781494e+01 1.50885269e+02 1.21322792e+02 7.92845520e+02 1.34213391e+03 -2.36623120e+03 -7.82761475e+03 60965684. 25801794. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 301800640. 50986700. 4.51143555e+03 1.69298975e+03 1.64395157e+02 2.86761292e+02 3.42492493e+02 1.74693542e+02 1.04269867e+02 9.08753891e+01 7.82637253e+01 7.85289764e+01 6.41625900e+01 5.33728828e+01 5.11076851e+01 6.06372604e+01 6.20699120e+01 4.47315483e+01 3.31369095e+01 3.54503784e+01 3.95856705e+01 4.88767738e+01 5.44861069e+01 7.42397995e+01 7.86923523e+01 5.10516396e+01 3.71251526e+01 4.88701363e+01 7.55085831e+01 5.82595253e+01 2.23138905e+01 1.72933197e+01 3.74225922e+01 5.99631081e+01 6.10575714e+01 5.60519409e+01 5.83570061e+01 5.15937042e+01 4.11324120e+01 3.41168785e+01 3.97765656e+01 5.49995117e+01 4.63621178e+01 3.54885902e+01 1.82200546e+01 -4.76333427e+00 1.14632950e+01 4.16861267e+01 8.58656616e+01 8.34438248e+01 4.30047073e+01 3.61251678e+01 4.53412933e+01 7.58331909e+01 7.41204605e+01 5.02129745e+01 3.77905312e+01 2.67389584e+01 4.44829788e+01 4.80189857e+01 4.73908997e+01 3.95697823e+01 1.70727463e+01 2.55068779e+00 1.29619193e+00 1.93038445e+01 3.60541153e+01 3.03940811e+01 2.63919334e+01 7.93116951e+00 -1.66729870e+01 -2.95471382e+01 -2.88691139e+01 -1.12160027e+00 1.11285973e+01 -1.78418481e+00 1.20646143e+01 3.48883743e+01 7.62673340e+01 6.55694351e+01 3.53075562e+01 2.45643272e+01 2.24357281e+01 1.90417824e+01 1.42853298e+01 2.68314610e+01 4.72933578e+01 4.27290955e+01 3.09852123e+01 2.85225983e+01 2.39616146e+01 1.44921341e+01 -3.80803227e+00 6.97242737e+00 2.39298668e+01 4.30793762e+00 -2.91247904e-01 4.77295446e+00 3.58981552e+01 4.64947739e+01 5.97193432e+00 3.22276211e+00 1.64096851e+01 6.33102379e+01 7.23304214e+01 4.23438988e+01 2.60664234e+01 1.00814896e+01 6.55327511e+00 -4.31748581e+00 -9.88277340e+00 9.12330627e+00 7.67311144e+00 4.84164047e+00 -3.10611439e+00 5.03406143e+00 2.45002537e+01 1.86266251e+01 2.19607086e+01 2.81655636e+01 1.02507534e+01 7.82246733e+00 1.58767653e+01 5.52011681e+01 6.19025688e+01 9.56762886e+00 -3.45049453e+00 1.42099104e+01 5.95926437e+01 6.10739670e+01 2.64643402e+01 1.76404152e+01 1.23856382e+01 9.27750587e+00 1.46102896e+01 2.44595890e+01 4.92541962e+01 3.22498894e+01 1.31099615e+01 8.95490646e+00 2.21027775e+01 4.59320984e+01 3.36212006e+01 2.45213776e+01 1.47086916e+01 -3.50418735e+00 -1.02627935e+01 -1.73935661e+01 -1.05220366e+01 -6.21792221e+00 -2.22090931e+01 -1.44264822e+01 -1.14717014e-01 3.58985939e+01 6.05135880e+01 4.86254768e+01 3.81860504e+01 9.89104939e+00 2.57599115e+00 -9.25600147e+00 -2.29962063e+01 -2.29651337e+01 -1.53042059e+01 -1.14719095e+01 -2.05660114e+01 -3.26733475e+01 -1.32396336e+01 2.28781948e+01 5.04180450e+01 5.73809242e+01 9.84493542e+00 -5.51308775e+00 5.75455284e+00 3.19011993e+01 2.54201851e+01 -8.30974817e-01 1.41537571e+00 -4.23704720e+00 -8.46253014e+00 -8.34984112e+00 7.76747847e+00 2.19191036e+01 6.43035698e+00 -1.28179369e+01 -9.94157600e+00 -1.34293375e+01 -1.42353954e+01 -3.02666092e+01 -5.06074829e+01 -6.74116821e+01 -8.26587982e+01 -4.31442719e+01 -1.10119104e+01 1.30646544e+01 1.45015669e+01 -1.86464748e+01 -1.50236273e+01 1.26967406e+00 4.74645653e+01 4.38135376e+01 3.57767510e+00 -2.69176102e+01 -3.78976707e+01 -2.78560905e+01 -4.14729729e+01 -5.48527565e+01 -4.57280807e+01 -3.90058708e+01 -3.65390434e+01 -4.37468605e+01 -3.20503845e+01 -9.96608639e+00 -5.82909966e+00 1.52244129e+01 1.62116337e+01 -2.72700768e+01 -6.88785858e+01 -6.41655807e+01 -2.04258404e+01 -8.74249578e-01 -1.12542791e+01 4.00911236e+00 2.22583370e+01 4.19173775e+01 4.93544922e+01 2.92651234e+01 7.88205624e+00 -2.88114986e+01 -4.05070076e+01 -1.93789158e+01 8.12117195e+00 1.60822678e+01 -2.20428181e+00 -1.40958204e+01 -5.27569675e+00 -3.64828849e+00 -6.42064929e-01 -1.20317936e+00 2.87191540e-01 -5.50589800e+00 -5.93672609e+00 -1.01451559e+01 -1.07306919e+01 -6.25477219e+00 5.51447630e+00 7.36315060e+00 4.27355208e-02 -1.02345848e+01 -8.29508686e+00 1.56481981e-01 -1.76334321e+00 -3.48663592e+00 -2.23220577e+01 -3.50857544e+01 -3.58038406e+01 -2.33337231e+01 -3.90030479e+00 -8.44210052e+00 -9.95403957e+00 -1.43934689e+01 -1.36304150e+01 -1.99447327e+01 -1.92633858e+01 -1.84781399e+01 -1.37359009e+01 -1.90702362e+01 -1.25122757e+01 -7.61748314e+00 -8.42514992e+00 -1.00855560e+01 -5.68252182e+00 -1.02243018e+00 -5.81075668e+00 -9.05602646e+00 -8.49333382e+00 -8.84976578e+00 -1.43713512e+01 -8.43518257e+00 -7.23811436e+00 -8.18975067e+00 -1.68862762e+01 -1.50074730e+01 -7.23889732e+00 -6.23042107e+00 -1.24380636e+01 -8.80821514e+00 -1.19830537e+00 1.80943882e+00 -1.04287930e+01 -1.60986423e+01 -1.57591276e+01 -1.13997345e+01 -1.21779566e+01 -1.20929775e+01 -1.83378639e+01 -2.78616123e+01 -3.76684036e+01 -3.79532166e+01 -2.85452862e+01 -2.71830425e+01 -2.08427887e+01 -2.45886555e+01 -2.51385384e+01 -3.07103329e+01 -3.07040634e+01 -2.68445320e+01 -2.87949677e+01 -2.72891197e+01 -1.49892063e+01 -6.71120405e+00 -7.05331516e+00 -1.72843227e+01 -1.76867943e+01 -2.69530602e+01 -3.61243172e+01 -4.35102158e+01 -3.69741096e+01 -2.94902687e+01 -2.99611225e+01 -3.56426735e+01 -2.55788956e+01 -1.35373402e+01 -1.14872885e+01 -2.35834827e+01 -3.87499084e+01 -4.20030861e+01 -4.51482887e+01 -4.28960915e+01 -2.18088932e+01 -4.86960220e+00 -1.98552573e+00 -1.66427116e+01 -3.09376278e+01 -3.09745541e+01 -3.27583504e+01 -3.66835632e+01 -4.04500847e+01 -4.06658630e+01 -3.90492935e+01 -3.98380280e+01 -3.67466049e+01 -3.58907967e+01 -3.93031273e+01 -4.91757660e+01 -6.27039528e+01 -7.24348450e+01 -6.90727081e+01 -5.64187164e+01 -4.39103165e+01 -4.97580948e+01 -5.36698227e+01 -4.86643181e+01 -3.87102013e+01 -3.03069553e+01 -3.77231445e+01 -4.53087883e+01 -5.21452751e+01 -4.89747467e+01 -4.55233459e+01 -4.54642601e+01 -4.91180420e+01 -6.27873039e+01 -7.94942932e+01 -5.96842766e+01 -2.55584946e+01 -1.34045849e+01 -3.06748219e+01 -5.27124786e+01 -4.94521332e+01 -4.53447800e+01 -4.06177979e+01 -4.35223770e+01 -4.75653191e+01 -4.76146469e+01 -3.98594437e+01 -3.24371338e+01 -4.03091545e+01 -5.81309319e+01 -6.88881989e+01 -5.87786636e+01 -4.60392990e+01 -4.09215736e+01 -4.27013359e+01 -4.23957291e+01 -3.91368523e+01 -2.79840240e+01 -1.79181728e+01 -2.65398235e+01 -4.03216133e+01 -4.90210342e+01 -4.16339378e+01 -4.39197731e+01 -4.95147362e+01 -5.19585114e+01 -5.03443680e+01 -4.98015366e+01 -4.81823654e+01 -4.44455452e+01 -3.51954498e+01 -3.97129936e+01 -4.57183228e+01 -5.33208351e+01 -5.62415848e+01 -6.57926559e+01 -8.46047897e+01 -9.54292603e+01 -8.87367859e+01 -7.41799545e+01 -6.36687202e+01 -5.93572807e+01 -6.10182304e+01 -6.64345779e+01 -6.91739349e+01 -6.66406097e+01 -6.22337341e+01 -6.17742119e+01 -5.76887474e+01 -6.78530426e+01 -7.96763229e+01 -8.31409912e+01 -7.35624695e+01 -6.21716385e+01 -6.29266014e+01 -5.90576057e+01 -5.57953568e+01 -5.11216202e+01 -5.55310097e+01 -5.74462471e+01 -5.70648308e+01 -5.53229866e+01 -5.66655273e+01 -5.89633446e+01 -5.35928459e+01 -5.26501045e+01 -5.23676414e+01 -5.59455986e+01 -5.86186981e+01 -5.53569908e+01 -5.26352768e+01 -4.93544617e+01 -5.20842590e+01 -6.06304550e+01 -6.77604599e+01 -7.01915665e+01 -6.75005722e+01 -6.12249794e+01 -5.02835159e+01 -4.45455017e+01 -5.80338020e+01 -7.02968140e+01 -8.25431137e+01 -8.28193130e+01 -8.67845612e+01 -8.50620346e+01 -7.45430908e+01 -4.95228729e+01 -2.39851437e+01 6.14920759e+00 5.66165962e+01 8.44484558e+01 8.34894470e+02 8.08708069e+02 -2.74765156e+04 24924678. 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. 0. 0. 0. 0. 0. 0. 0. 531313536. 101834000. 25236908. 79759368. 5.72096729e+03 2.46978638e+03 1.22397461e+03 8.17712402e+02 1.53224655e+02 6.11054153e+01 2.17246571e+01 -2.29391632e+01 -3.82312393e+01 -4.14504242e+01 -3.15600910e+01 -3.72121429e+01 -7.98399658e+01 -1.22775284e+02 -1.18417305e+02 -7.63772812e+01 -1.73616982e+01 -1.78769627e+01 2.46478672e+01 4.98513107e+01 5.74214401e+01 1.70466537e+01 3.86943460e+00 3.15963936e+01 3.93133659e+01 3.77796860e+01 3.07731934e+01 9.31594467e+00 -4.22559090e+01 -6.32018166e+01 -7.44851151e+01 -7.37928085e+01 -7.73440857e+01 -8.13201981e+01 -8.58367081e+01 -8.39891434e+01 -8.08807602e+01 -8.12095795e+01 -8.45746994e+01 -8.83018112e+01 -9.11994934e+01 -9.41682510e+01 -9.27932358e+01 -9.43019028e+01 -9.52422028e+01 -9.52070312e+01 -9.27169952e+01 -8.86551819e+01 -8.99352570e+01 -9.09581680e+01 -9.03402328e+01 -8.93799133e+01 -8.82063828e+01 -8.92854614e+01 -8.99930954e+01 -8.72580566e+01 -8.57977295e+01 -7.88300552e+01 -7.43890610e+01 -7.38502350e+01 -7.57593002e+01 -7.79911804e+01 -7.31198196e+01 -7.05295639e+01 -7.48779297e+01 -8.13431320e+01 -8.81317520e+01 -8.98389130e+01 -9.10174026e+01 -9.50799332e+01 -1.00404640e+02 -1.03910011e+02 -1.02973312e+02 -9.74758148e+01 -9.32821426e+01 -9.02356873e+01 -8.96746445e+01 -9.06151276e+01 -8.60380020e+01 -8.16634979e+01 -7.53434753e+01 -7.35766830e+01 -7.66068192e+01 -8.11113586e+01 -8.57895813e+01 -8.72119751e+01 -8.63218231e+01 -8.09599838e+01 -7.61907806e+01 -7.77450104e+01 -8.36886139e+01 -8.78583603e+01 -8.72566147e+01 -8.56337128e+01 -8.45466995e+01 -8.29331436e+01 -8.84949112e+01 -9.39880753e+01 -9.65165329e+01 -9.40404358e+01 -8.94175949e+01 -8.96065063e+01 -8.83113480e+01 -8.66527634e+01 -8.51170731e+01 -8.30611649e+01 -8.36200790e+01 -8.70315781e+01 -9.14803543e+01 -9.59736481e+01 -9.58577881e+01 -9.44331741e+01 -9.29676514e+01 -9.28391571e+01 -9.44656906e+01 -9.47023010e+01 -9.44530563e+01 -9.39025345e+01 -9.32395325e+01 -9.21760864e+01 -9.14795761e+01 -9.17896652e+01 -9.13224640e+01 -8.81090851e+01 -8.43312836e+01 -8.44288635e+01 -8.70834427e+01 -8.97730637e+01 -8.87080917e+01 -8.73860016e+01 -8.56608200e+01 -8.51160049e+01 -8.68029556e+01 -8.95085220e+01 -9.19093781e+01 -9.27113876e+01 -9.29849091e+01 -9.28945694e+01 -9.27338943e+01 -9.29558945e+01 -9.34556427e+01 -9.35137329e+01 -9.27979965e+01 -9.25321045e+01 -9.26060715e+01 -9.26539383e+01 -9.23840027e+01 -9.17484131e+01 -9.03188019e+01 -8.92157440e+01 -8.97014542e+01 -9.13220749e+01 -9.26043091e+01 -9.16251526e+01 -9.06326294e+01 -9.00633316e+01 -9.02544556e+01 -9.01947098e+01 -9.02182159e+01 -9.10265427e+01 -9.16973877e+01 -9.24557343e+01 -9.25604630e+01 -9.27421646e+01 -9.28380737e+01 -9.27142410e+01 -9.27486267e+01 -9.27874069e+01 -9.28464890e+01 -9.28449936e+01 -9.28649445e+01 -9.28839340e+01 -9.27449646e+01 -9.25969086e+01 -9.26800537e+01 -9.29034653e+01 -9.29987564e+01 -9.30254822e+01 -9.29031372e+01 -9.26991196e+01 -9.30314484e+01 -9.38116455e+01 -9.38991776e+01 -9.33991852e+01 -9.25358429e+01 -9.27111206e+01 -9.29010315e+01 -9.30800323e+01 -9.27500916e+01 -9.28201141e+01 -9.27905045e+01 -9.32794952e+01 -9.34311905e+01 -9.35405350e+01 -9.33265381e+01 -9.31350708e+01 -9.17104645e+01 -9.01548004e+01 -9.00654449e+01 -9.11541290e+01 -9.26902313e+01 -9.17382965e+01 -9.17300110e+01 -9.23701706e+01 -9.32197342e+01 -9.33874054e+01 -9.27483368e+01 -9.22983322e+01 -9.21189423e+01 -9.23227844e+01 -9.30024185e+01 -9.27950668e+01 -9.23641434e+01 -9.20405426e+01 -9.16182175e+01 -9.17837601e+01 -9.10499191e+01 -9.15381241e+01 -9.14182968e+01 -9.16483536e+01 -9.10597763e+01 -8.89674606e+01 -8.73160324e+01 -8.70694275e+01 -8.82132339e+01 -9.00531311e+01 -8.94963837e+01 -8.99696808e+01 -8.87938309e+01 -8.81297531e+01 -8.83775787e+01 -8.85485611e+01 -8.93356018e+01 -8.76811142e+01 -8.73834534e+01 -8.75549011e+01 -8.92463379e+01 -9.08464127e+01 -9.09540558e+01 -8.69889679e+01 -8.26582870e+01 -8.15250778e+01 -8.48564911e+01 -9.45881805e+01 -1.00282921e+02 -1.00175804e+02 -9.37918320e+01 -8.90986252e+01 -9.44795609e+01 -9.89741592e+01 -9.87210159e+01 -9.28712082e+01 -8.79795151e+01 -8.72714691e+01 -8.67708511e+01 -8.73811417e+01 -8.81515884e+01 -8.73313217e+01 -8.59326172e+01 -8.64871445e+01 -8.84990768e+01 -9.13221283e+01 -8.69697418e+01 -8.33271561e+01 -8.14647980e+01 -8.71012497e+01 -9.25614243e+01 -9.38341370e+01 -9.27858200e+01 -9.24428253e+01 -9.15845718e+01 -9.19316483e+01 -9.07077866e+01 -9.46845474e+01 -9.77397690e+01 -9.59063110e+01 -8.85712128e+01 -8.29522858e+01 -8.33621140e+01 -8.62629318e+01 -8.87353592e+01 -8.90815353e+01 -8.32982559e+01 -7.55953369e+01 -7.59991531e+01 -8.10414047e+01 -8.73212433e+01 -8.47575150e+01 -8.43361893e+01 -8.34300232e+01 -8.56493378e+01 -9.17635422e+01 -9.91235046e+01 -9.78339386e+01 -9.17391663e+01 -8.30513000e+01 -8.38970795e+01 -8.52737808e+01 -8.60806732e+01 -8.51650162e+01 -8.96727676e+01 -9.75848923e+01 -9.97742081e+01 -9.69996490e+01 -8.85938110e+01 -8.93925476e+01 -8.70563736e+01 -8.59308929e+01 -8.38814926e+01 -8.45448837e+01 -8.74281082e+01 -8.97417374e+01 -8.90303802e+01 -8.63556366e+01 -8.43282623e+01 -8.20874252e+01 -7.93373032e+01 -7.64765549e+01 -7.60579987e+01 -7.57980499e+01 -7.74462280e+01 -8.53149796e+01 -9.54665833e+01 -1.01724854e+02 -1.03671280e+02 -1.03893822e+02 -1.04036613e+02 -9.07871323e+01 -8.28763428e+01 -7.47197495e+01 -7.83943176e+01 -7.87909088e+01 -8.60551071e+01 -9.43073883e+01 -9.14015198e+01 -8.71397858e+01 -7.28882675e+01 -6.47964096e+01 -6.23170853e+01 -6.71321716e+01 -7.50519028e+01 -7.49438858e+01 -8.06792679e+01 -9.11497040e+01 -9.83400650e+01 -9.07014389e+01 -7.93323746e+01 -6.61023178e+01 -7.39684143e+01 -8.28115158e+01 -8.91303024e+01 -8.77073593e+01 -7.96120758e+01 -7.29481888e+01 -6.36986847e+01 -6.43106308e+01 -6.56645126e+01 -6.47467346e+01 -6.53427734e+01 -6.67140656e+01 -6.70775452e+01 -6.71150208e+01 -6.62191849e+01 -6.71904144e+01 -6.83973923e+01 -7.25803070e+01 -8.36163483e+01 -9.62139664e+01 -8.55851440e+01 -6.61752472e+01 -6.44755783e+01 -8.22659378e+01 -9.52810440e+01 -8.46842270e+01 -7.26767120e+01 -8.03771057e+01 -8.77421951e+01 -8.98502197e+01 -8.18785477e+01 -7.25167999e+01 -7.45871048e+01 -7.67898178e+01 -8.09157333e+01 -7.66375427e+01 -7.28781967e+01 -6.86204147e+01 -6.79012070e+01 -6.77559128e+01 -7.11200790e+01 -7.09533157e+01 -7.49117661e+01 -8.05902328e+01 -9.13230286e+01 -7.95599289e+01 -5.66142082e+01 -5.86828270e+01 -8.10306396e+01 -9.47376556e+01 -7.65287628e+01 -6.16287231e+01 -6.76640549e+01 -7.66768188e+01 -6.73330765e+01 -4.84704704e+01 -3.73333206e+01 -4.23229599e+01 -4.89834251e+01 -6.08365135e+01 -7.37593307e+01 -7.27824783e+01 -5.55205612e+01 -5.43999214e+01 -7.29410248e+01 -7.72406235e+01 -6.26088943e+01 -4.64266930e+01 -4.68658752e+01 -5.03423615e+01 -4.19207268e+01 -3.10347214e+01 -3.81625824e+01 -5.61718483e+01 -7.26941605e+01 -6.54124374e+01 -5.90055275e+01 -5.69321594e+01 -5.76828423e+01 -5.92885666e+01 -5.75757065e+01 -5.39178352e+01 -4.43258018e+01 -4.54858627e+01 -6.09329681e+01 -7.88563004e+01 -8.29638290e+01 -7.37349396e+01 -7.86689377e+01 -9.53915253e+01 -8.94357529e+01 -6.27072525e+01 -3.60282059e+01 -3.30166702e+01 -4.43725357e+01 -4.04231415e+01 -3.62418785e+01 -3.87523308e+01 -4.88599243e+01 -5.92149429e+01 -5.87686920e+01 -5.20640144e+01 -4.86986504e+01 -3.84868202e+01 -3.70772591e+01 -3.87715874e+01 -4.02453079e+01 -3.98699188e+01 -3.94839745e+01 -5.17199364e+01 -6.54052048e+01 -6.39657707e+01 -5.30336723e+01 -4.76426201e+01 -5.45486641e+01 -4.48948708e+01 -2.70237579e+01 -2.80621243e+01 -5.92276649e+01 -9.45958633e+01 -1.01435959e+02 -8.78249817e+01 -8.19532700e+01 -8.86429825e+01 -8.24691849e+01 -7.25616150e+01 -6.09135475e+01 -6.46421280e+01 -6.20683517e+01 -6.54005890e+01 -7.12497025e+01 -6.98504486e+01 -5.54230804e+01 -3.62083092e+01 -4.32875290e+01 -6.02186852e+01 -6.42536087e+01 -4.78551559e+01 -4.96139679e+01 -6.62409363e+01 -5.50581818e+01 -1.78110828e+01 7.58223057e+00 -6.12218952e+00 -2.36192188e+01 -1.49458294e+01 4.98407459e+00 6.34365177e+00 -5.26886368e+00 -1.61111908e+01 -6.89709663e+00 -1.82118046e+00 -4.74985600e+00 -1.69149380e+01 -3.93623924e+01 -6.08787880e+01 -7.32184601e+01 -7.28818207e+01 -4.51841087e+01 -1.98840160e+01 -5.37253046e+00 -1.77812004e+01 -3.02018166e+01 -2.94135399e+01 -2.77907753e+01 -1.47903519e+01 5.21982813e+00 -4.25528646e-01 -1.68646049e+01 -3.39505043e+01 -3.44622726e+01 -3.54387398e+01 -5.37747421e+01 -6.91370621e+01 -6.58884659e+01 -4.94160500e+01 -3.49100876e+01 -3.37204590e+01 -3.11000214e+01 -3.13806896e+01 -3.73557968e+01 -4.39739418e+01 -4.29740181e+01 -3.50328674e+01 -2.99068108e+01 -2.47971172e+01 -2.39849014e+01 -2.31999531e+01 -3.87928810e+01 -6.16696739e+01 -6.53292313e+01 -5.32675018e+01 -5.05128250e+01 -6.71801910e+01 -6.31176682e+01 -5.04629402e+01 -3.58701210e+01 -5.34670868e+01 -6.69659195e+01 -5.93321533e+01 -4.09036140e+01 -1.55321636e+01 -1.35886230e+01 -1.40377302e+01 -3.08179989e+01 -4.82984161e+01 -4.89476776e+01 -3.31109238e+01 -3.46892395e+01 -5.24024544e+01 -5.34001579e+01 -3.96470222e+01 -1.45837164e+01 -2.88871288e+01 -4.35562630e+01 -4.09890976e+01 -1.25034637e+01 6.13700867e+00 -8.12154579e+00 -2.98279781e+01 -3.15270596e+01 -3.02994213e+01 -2.27677765e+01 -2.63329182e+01 -3.04741116e+01 -3.23472862e+01 -5.05739594e+01 -6.06101456e+01 -5.83140717e+01 -4.17101631e+01 -2.44617939e+01 -2.51256161e+01 -2.22721462e+01 -2.29750309e+01 -2.48186035e+01 -1.93501358e+01 -1.95415344e+01 -1.19976816e+01 -1.38928499e+01 -9.69482994e+00 6.68973732e+00 2.27952957e+01 2.49683952e+00 -3.02614899e+01 -4.22373505e+01 -1.75568771e+01 4.08157587e-01 3.68527246e+00 -3.89750576e+00 -3.06335402e+00 -5.71687508e+00 -7.77822828e+00 -2.89480629e+01 -1.12842087e+02 -2.34545746e+02 -3.92028923e+01 2.09651062e+02 4.61481720e+02 1.48868604e+03 -7.52770625e+04 0. 0. 0. 0. 0. -1.00518359e+10 6.88672050e+06 -1.24118050e+06 -4.76051914e+04 -5.55621211e+04 4.10306281e+05 2.57269953e+05 2.57294008e+10 1.98114714e+10 1.98114714e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -159208016. -6352621. -3.79659125e+06 5.54782520e+03 2.49753540e+03 1.15740681e+01 1.64225204e+02 2.21915955e+02 2.01277283e+02 8.84983063e+01 1.47258501e+01 -4.56982880e+01 -4.72347107e+01 -6.04728556e+00 1.17534027e+01 -8.70933086e-02 1.62280674e+01 5.08991585e+01 7.61177216e+01 4.10423470e+01 -2.76752510e+01 -6.43796768e+01 -4.10433922e+01 7.13413095e+00 3.78686295e+01 3.18102646e+01 1.89662800e+01 3.09136715e+01 4.96328278e+01 3.72538300e+01 1.36125052e+00 -1.75852222e+01 -3.54772425e+00 2.64361515e+01 3.82796707e+01 1.42434340e+01 -2.28628979e+01 -4.02481956e+01 -2.03057404e+01 -2.32925339e+01 -4.79416008e+01 -2.76727257e+01 2.25043621e+01 5.66036873e+01 1.71196690e+01 -6.04275322e+01 -8.35555344e+01 -4.60919075e+01 -5.86202431e+00 1.86609859e+01 2.33453751e+01 2.30485764e+01 2.31038799e+01 2.96528111e+01 2.03977776e+01 -3.49504890e+01 -7.90482712e+01 -5.70486450e+01 -4.66779041e+00 2.47712803e+01 5.32107592e-01 -3.25466385e+01 -4.36916237e+01 -8.86725807e+00 2.38804176e-01 -1.41291475e+01 -3.73210597e+00 3.22084770e+01 7.14358063e+01 6.23278770e+01 3.07027102e+00 -1.56072912e+01 6.66600561e+00 4.89254341e+01 4.06037369e+01 8.42810345e+00 1.88932896e+01 4.22333908e+01 5.62711868e+01 3.38572044e+01 -1.44516916e+01 -3.05238018e+01 -1.28799648e+01 3.92770386e+01 6.39274597e+01 5.45686951e+01 3.05158195e+01 4.00040283e+01 6.49035110e+01 6.41602249e+01 3.29200134e+01 1.64658604e+01 4.96481209e+01 8.74353104e+01 9.07307510e+01 4.36750298e+01 4.03541994e+00 1.39678240e+00 3.39086990e+01 4.37995186e+01 3.69188156e+01 5.86734314e+01 1.01430244e+02 1.23984520e+02 8.48794174e+01 2.24441719e+01 -9.16722107e+00 1.00028210e+01 4.59937325e+01 8.46349335e+01 1.08506477e+02 9.90566483e+01 8.58709946e+01 8.48114624e+01 8.36519547e+01 4.75705147e+01 1.27036819e+01 3.28929596e+01 9.12089081e+01 1.17069908e+02 9.40672073e+01 3.80277214e+01 1.53410559e+01 3.62342224e+01 6.12509727e+01 6.14546089e+01 5.92995682e+01 8.11251526e+01 1.31902908e+02 1.28873032e+02 8.75192032e+01 4.14518738e+01 4.32443810e+01 6.98422775e+01 9.18317108e+01 9.58886795e+01 8.94533691e+01 7.29461899e+01 6.29561958e+01 8.64267502e+01 9.54570541e+01 7.51664276e+01 5.19579163e+01 4.61225777e+01 6.00280685e+01 6.20758514e+01 4.87550354e+01 4.88269730e+01 6.29198685e+01 8.13256073e+01 9.02764664e+01 7.03245926e+01 6.00167694e+01 6.64733810e+01 8.33511658e+01 6.89793701e+01 1.41307812e+01 -1.13129511e+01 2.99278984e+01 7.60223312e+01 8.40928497e+01 5.43929787e+01 4.10724030e+01 4.24885063e+01 4.24278564e+01 2.48369579e+01 2.14277238e-01 -8.56293201e+00 9.07812214e+00 4.55206947e+01 7.35606384e+01 5.44551582e+01 3.89203873e+01 4.12849045e+01 6.51767273e+01 5.15612793e+01 9.87886238e+00 9.89289284e+00 3.13101768e+01 5.17233849e+01 2.89890575e+01 -2.13053379e+01 -4.09180870e+01 -1.04685984e+01 4.68413849e+01 7.08510437e+01 6.43738556e+01 6.59421844e+01 8.12117691e+01 7.18301086e+01 3.90991592e+01 2.91414595e+00 1.10573616e+01 4.30335083e+01 8.84178162e+01 1.08228813e+02 9.83183670e+01 6.64169159e+01 4.07761917e+01 3.87860336e+01 3.05402870e+01 1.47386761e+01 2.35900784e+01 5.74305534e+01 9.36325912e+01 7.56407089e+01 3.09160767e+01 3.87155581e+00 3.32897034e+01 8.37010269e+01 9.86192169e+01 7.77581711e+01 5.08490982e+01 6.41963654e+01 8.41058273e+01 7.83910446e+01 5.32454987e+01 4.70017090e+01 7.22304153e+01 1.07692802e+02 1.14868919e+02 9.81085281e+01 7.67857819e+01 7.76933594e+01 8.67950058e+01 8.42504044e+01 6.89453430e+01 8.23232880e+01 9.91589966e+01 1.04748840e+02 9.87959137e+01 8.18219757e+01 7.58064728e+01 7.92674255e+01 7.95183487e+01 8.03194809e+01 6.55908203e+01 7.91423492e+01 9.93724594e+01 1.09269485e+02 9.84613724e+01 5.52410431e+01 3.32400780e+01 3.97532425e+01 8.59449844e+01 1.12678078e+02 1.14969681e+02 9.58241196e+01 8.25242386e+01 9.42697754e+01 9.04632950e+01 7.83429565e+01 7.09020309e+01 8.60907822e+01 9.64297867e+01 7.35347824e+01 4.71915970e+01 5.28352509e+01 6.88475952e+01 7.69610443e+01 6.90796432e+01 5.31908188e+01 7.24632874e+01 8.63645630e+01 9.76991501e+01 8.64400406e+01 6.60879745e+01 5.84489746e+01 5.53939781e+01 7.60140457e+01 8.28704224e+01 8.63758621e+01 6.83234863e+01 6.94752350e+01 7.05685577e+01 6.76709595e+01 5.61086807e+01 5.07957954e+01 7.36202240e+01 8.62015839e+01 8.74772415e+01 6.97399750e+01 7.67351761e+01 8.34573135e+01 9.28011017e+01 9.50808487e+01 9.37359390e+01 9.30748138e+01 7.64965668e+01 6.77085571e+01 6.50256653e+01 6.87217865e+01 7.52857285e+01 8.25121460e+01 1.00028069e+02 1.08720589e+02 1.02317970e+02 7.54371796e+01 6.96656342e+01 7.47120285e+01 8.45959473e+01 8.45807037e+01 9.32189331e+01 1.13659973e+02 1.22851379e+02 1.11425987e+02 8.69205399e+01 7.88109970e+01 8.74600372e+01 9.93870621e+01 1.02370468e+02 9.28798294e+01 9.32897339e+01 9.09106293e+01 1.01945282e+02 1.08554306e+02 1.08611839e+02 9.80074387e+01 9.13403778e+01 1.02485466e+02 1.13997116e+02 1.07255669e+02 9.23236847e+01 9.53197250e+01 1.05778542e+02 1.06051392e+02 9.71100388e+01 9.64919510e+01 1.10009415e+02 1.15297462e+02 1.09984482e+02 9.47698364e+01 9.58610001e+01 1.00189507e+02 1.07156639e+02 1.02681091e+02 9.64678574e+01 9.91747742e+01 9.84306335e+01 1.07630836e+02 1.08908615e+02 1.09969330e+02 1.03636101e+02 1.00946732e+02 1.05334839e+02 1.10366158e+02 1.06651100e+02 9.68127060e+01 9.48380737e+01 9.55841370e+01 9.14339066e+01 8.05841751e+01 8.35064011e+01 9.26226807e+01 9.68971405e+01 9.09834747e+01 8.39845123e+01 9.28151321e+01 9.78320999e+01 1.03714012e+02 1.07758797e+02 1.08314285e+02 1.03230408e+02 9.02619781e+01 8.82591171e+01 9.68300781e+01 1.06129539e+02 1.00487823e+02 8.93004761e+01 8.25336380e+01 9.06267319e+01 9.74043655e+01 9.64610672e+01 9.29262238e+01 8.79674225e+01 8.26779480e+01 7.49164352e+01 7.76451874e+01 8.59463425e+01 8.90688400e+01 8.52137833e+01 8.15783539e+01 9.04352875e+01 9.54455872e+01 9.85277481e+01 9.73523941e+01 9.60252533e+01 9.20691071e+01 8.20126190e+01 8.03015823e+01 8.82185364e+01 1.02945526e+02 1.06068474e+02 9.54408188e+01 8.60976639e+01 8.57001114e+01 9.25569763e+01 9.60818710e+01 9.43016891e+01 8.98640671e+01 8.73961639e+01 9.11756363e+01 9.84141083e+01 1.00141815e+02 9.66313858e+01 9.21332626e+01 8.80836868e+01 8.86099701e+01 9.10852051e+01 9.70858917e+01 1.03009483e+02 1.04806717e+02 1.01069771e+02 9.43683090e+01 9.10454025e+01 9.45804596e+01 9.93063431e+01 9.92602692e+01 9.50363617e+01 9.14200134e+01 9.32666245e+01 9.74008026e+01 1.00655243e+02 1.00701126e+02 9.86428223e+01 9.72521820e+01 9.66741333e+01 9.83792114e+01 9.91471710e+01 9.96097412e+01 9.89633636e+01 9.87071533e+01 9.94643707e+01 1.00023674e+02 1.00477608e+02 1.00335686e+02 1.00071213e+02 9.98657150e+01 9.99092407e+01 1.00188103e+02 1.00156281e+02 9.94119034e+01 9.87369843e+01 9.89668884e+01 1.00371506e+02 1.01617523e+02 1.01429962e+02 1.00617195e+02 1.00601067e+02 1.01598175e+02 1.02321625e+02 1.02864319e+02 1.01197899e+02 9.99937286e+01 9.82883530e+01 9.79003296e+01 9.87615585e+01 1.00106255e+02 1.02563576e+02 1.02228676e+02 1.00396141e+02 9.77566605e+01 9.75930099e+01 1.00321022e+02 1.03990211e+02 1.02989517e+02 9.96927490e+01 9.73602371e+01 1.00400475e+02 1.05325096e+02 1.05228127e+02 1.01445908e+02 9.56198273e+01 9.57265167e+01 1.00639893e+02 1.04734062e+02 1.08173523e+02 1.02693512e+02 9.99907837e+01 9.68416290e+01 9.71454468e+01 9.66216660e+01 9.53322754e+01 9.83589706e+01 9.68466949e+01 9.36133194e+01 9.38318405e+01 9.91697235e+01 1.08894478e+02 1.11654320e+02 1.06414322e+02 9.33097916e+01 8.23211365e+01 8.34191742e+01 9.60402069e+01 1.09638359e+02 1.14363922e+02 1.05012985e+02 9.38564758e+01 9.10867538e+01 9.96511993e+01 1.09165634e+02 1.05792229e+02 9.72209473e+01 8.86508636e+01 8.70636673e+01 9.03720398e+01 9.79655457e+01 1.05891655e+02 1.04653580e+02 9.57229462e+01 8.36159286e+01 8.12639923e+01 9.06930389e+01 1.02298935e+02 1.03241547e+02 9.23486786e+01 8.46037216e+01 8.69226074e+01 9.40764465e+01 9.71428833e+01 9.96628647e+01 9.57589645e+01 9.27393875e+01 9.59362106e+01 9.78209991e+01 1.02703293e+02 9.53003693e+01 8.90071182e+01 8.01990280e+01 7.40834351e+01 8.15922546e+01 8.76015091e+01 1.00339813e+02 1.04839584e+02 9.90839081e+01 8.66459351e+01 8.28063736e+01 9.53051529e+01 1.09460892e+02 1.08414558e+02 1.00233688e+02 8.46248550e+01 8.04480057e+01 8.63967972e+01 9.57513351e+01 9.90868301e+01 8.60606308e+01 7.36036072e+01 6.14617157e+01 6.27753029e+01 7.88141708e+01 7.82795715e+01 7.19631042e+01 5.61903381e+01 5.42949829e+01 5.95702934e+01 7.07036209e+01 9.22669678e+01 1.01557343e+02 9.69027481e+01 7.74958649e+01 6.97831955e+01 8.32899704e+01 1.00163353e+02 9.92475510e+01 7.87957840e+01 6.34509506e+01 6.77980728e+01 8.84733200e+01 1.07707756e+02 1.09948250e+02 9.18810425e+01 7.14668503e+01 6.58091202e+01 6.53039780e+01 7.09681015e+01 7.78100357e+01 9.15419464e+01 9.25358047e+01 8.56368256e+01 8.09783936e+01 8.94993362e+01 1.09884026e+02 1.21261192e+02 1.04592857e+02 7.75426559e+01 6.46578293e+01 8.00528183e+01 1.06294670e+02 1.11807526e+02 9.55237885e+01 6.86586227e+01 6.31710358e+01 7.94017715e+01 8.87760849e+01 9.32195129e+01 7.77301559e+01 7.07925644e+01 7.19237823e+01 7.76345596e+01 9.38429489e+01 8.94498520e+01 8.59224243e+01 5.82325630e+01 3.35366173e+01 2.02694740e+01 2.77739620e+01 5.49553528e+01 8.05734177e+01 8.92285614e+01 5.57412910e+01 -1.56361618e+01 -4.63960457e+00 9.48287277e+01 -4.41220886e+02 -8.49604065e+02 3.03847504e+02 2.76829102e+02 1.84871933e+02 3.45699524e+02 -2.36623120e+03 -7.82761475e+03 60965684. 25801794. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -28653518. -6.23179834e+03 -1.97039307e+03 6.07653625e+02 -1.61621497e+03 -1.28731250e+03 -1.02078293e+02 8.66894150e+00 5.65631142e+01 4.63656769e+01 3.36214142e+01 3.68868904e+01 5.22012711e+01 9.46212387e+01 9.46963196e+01 7.39371109e+01 3.82085266e+01 4.15491638e+01 7.50634613e+01 1.05300385e+02 1.12096687e+02 8.57869492e+01 3.91588516e+01 2.97718563e+01 6.24387856e+01 1.02051277e+02 1.03748947e+02 7.18354950e+01 6.83580170e+01 8.78475876e+01 9.25608368e+01 7.21898041e+01 4.75347977e+01 4.91927299e+01 4.36551857e+01 3.32441254e+01 2.99806976e+01 5.71572456e+01 1.02022423e+02 1.09047852e+02 7.81919403e+01 4.62178230e+01 4.41037025e+01 7.54055634e+01 1.13442238e+02 1.10063370e+02 6.13383484e+01 6.19571090e-01 1.21019447e+00 5.73285561e+01 8.84832535e+01 9.37781601e+01 6.13515053e+01 4.72677917e+01 3.90911598e+01 3.66949577e+01 4.47175217e+01 6.47039795e+01 9.52419205e+01 8.41921768e+01 5.13071518e+01 4.39773331e+01 6.89893723e+01 1.09021866e+02 1.05908707e+02 8.45964279e+01 5.25585899e+01 3.70718880e+01 6.95355301e+01 1.10244720e+02 1.46691162e+02 1.26816345e+02 7.97637024e+01 6.20588226e+01 9.29534225e+01 1.16437584e+02 1.10534248e+02 6.25248032e+01 5.14967155e+01 6.31278267e+01 8.69085693e+01 8.17626648e+01 8.33796921e+01 9.66979065e+01 8.25190964e+01 4.63180161e+01 2.79869785e+01 6.09648323e+01 1.16214081e+02 1.28857346e+02 1.11907341e+02 7.32028275e+01 4.57664452e+01 4.16558723e+01 7.00083618e+01 9.37582397e+01 8.86235046e+01 4.02062492e+01 1.89094925e+01 5.44617195e+01 9.08341827e+01 8.97371674e+01 3.69626465e+01 7.63120604e+00 1.57018490e+01 2.37531433e+01 3.63102188e+01 5.05494652e+01 9.38175354e+01 9.07731018e+01 5.56202011e+01 2.36610756e+01 2.62534981e+01 5.93696556e+01 6.55651321e+01 4.41325836e+01 2.55172195e+01 6.67766380e+00 1.65067520e+01 4.85623207e+01 8.30836258e+01 8.78998184e+01 3.58049545e+01 8.71770859e+00 3.11662674e+01 5.15343285e+01 5.32829781e+01 2.42922802e+01 2.75320797e+01 3.09333115e+01 1.77537098e+01 1.10779152e+01 2.14935284e+01 6.96803207e+01 6.92088165e+01 3.24971275e+01 1.00326419e+00 5.66924191e+00 3.91477394e+01 3.78314056e+01 6.75950909e+00 -8.36018848e+00 -2.86329651e+01 -4.52944994e+00 2.78973866e+01 6.23430023e+01 5.71269836e+01 2.22899113e+01 1.44717894e+01 3.07138252e+01 3.20752907e+01 2.23048077e+01 -7.02475166e+00 -2.66385059e+01 -4.01375465e+01 -4.68482590e+01 -2.40434380e+01 2.62468219e+00 4.96952896e+01 6.80528488e+01 5.86986923e+01 3.30303307e+01 2.93866386e+01 6.50170746e+01 9.52155457e+01 7.66151810e+01 1.92366180e+01 -2.15104218e+01 -2.34670696e+01 2.83657188e+01 5.62100105e+01 5.50899582e+01 2.20002041e+01 1.48303385e+01 3.45678596e+01 2.92882290e+01 3.10889282e+01 3.49504852e+01 3.71300545e+01 8.10652828e+00 -3.24085846e+01 -3.89576111e+01 -2.42171516e+01 1.75901365e+00 2.80119057e+01 3.14169521e+01 2.11112480e+01 1.72511959e+01 4.86060867e+01 8.12326508e+01 6.71184921e+01 1.83630219e+01 -2.75208015e+01 -3.49157333e+01 3.94211197e+00 1.36499071e+01 1.74965744e+01 -2.19337387e+01 -1.76718826e+01 3.46772718e+00 4.07639656e+01 6.76017990e+01 7.36591034e+01 9.50211716e+01 7.49583206e+01 3.22778320e+01 -4.01610136e-01 1.56936204e+00 3.82549210e+01 4.10450096e+01 1.24724550e+01 -2.27659378e+01 -5.94746170e+01 -3.69214134e+01 2.11498032e+01 7.51405563e+01 5.50837555e+01 -3.33476925e+00 -1.55104752e+01 7.28380775e+00 2.15546207e+01 2.13338089e+01 2.06564927e+00 -1.49164667e+01 -3.01657867e+01 -2.95361004e+01 -1.62154083e+01 9.32956791e+00 4.53872528e+01 5.48878860e+01 4.04163513e+01 1.73308926e+01 1.04282265e+01 1.30554485e+01 -3.26219893e+00 -2.81251221e+01 -3.67888641e+01 -2.86805553e+01 -3.81309330e-01 8.35963631e+00 1.42965269e+01 4.31626177e+00 -1.37028627e+01 -2.24174614e+01 -1.73151722e+01 1.88834831e-01 9.23318863e+00 5.33511519e-01 -8.13412952e+00 -1.04647160e+01 -4.12700176e+00 1.95624912e+00 -4.00070047e+00 -9.02334499e+00 -1.56115885e+01 -1.76788368e+01 -1.71772308e+01 -2.34880371e+01 -2.07838783e+01 -2.00929012e+01 -1.15642948e+01 -1.65914497e+01 -2.30760632e+01 -2.46321945e+01 -1.95967579e+01 -1.63208160e+01 -2.11727448e+01 -2.38147411e+01 -2.78444576e+01 -4.05575485e+01 -3.75551910e+01 -3.01468468e+01 -1.94996395e+01 -3.15704613e+01 -3.32616997e+01 -3.18308067e+01 -3.06763859e+01 -3.29342842e+01 -3.63368530e+01 -3.55027809e+01 -3.65271339e+01 -3.25641708e+01 -2.82522144e+01 -2.58118000e+01 -3.23556328e+01 -3.32866478e+01 -4.11094475e+01 -3.68986969e+01 -3.56981354e+01 -3.09668541e+01 -3.79587784e+01 -3.77304230e+01 -3.95341034e+01 -2.52750244e+01 -1.36899462e+01 -5.71168756e+00 -1.57894945e+01 -2.17025013e+01 -3.01003361e+01 -3.13101978e+01 -3.44554710e+01 -2.98980122e+01 -2.54279022e+01 -3.05142040e+01 -3.01756153e+01 -2.92583332e+01 -3.10017262e+01 -4.00635490e+01 -4.42442856e+01 -3.94005318e+01 -3.49932861e+01 -3.70754585e+01 -3.55328636e+01 -3.16639900e+01 -2.46953754e+01 -2.42132149e+01 -2.49983978e+01 -3.22206879e+01 -3.73794289e+01 -5.43359108e+01 -6.26310806e+01 -6.50613861e+01 -5.35146523e+01 -4.25997963e+01 -3.73673782e+01 -3.14528770e+01 -3.41704330e+01 -4.91805992e+01 -6.48054352e+01 -6.20601654e+01 -4.71523170e+01 -3.48456001e+01 -3.38086395e+01 -3.58248520e+01 -3.09934425e+01 -3.12391624e+01 -3.27221222e+01 -3.73792915e+01 -3.36681747e+01 -3.19318466e+01 -3.50605850e+01 -3.98618813e+01 -3.56748085e+01 -2.32856140e+01 -7.65178204e+00 -7.54891777e+00 -1.86510563e+01 -3.63372116e+01 -3.54008293e+01 -3.09997578e+01 -3.54314880e+01 -3.84794540e+01 -4.18318405e+01 -2.49300671e+01 -1.61498756e+01 -1.25278406e+01 -2.90385170e+01 -4.30176315e+01 -5.33119164e+01 -4.33118706e+01 -2.02455978e+01 5.21051121e+00 -9.35652256e+00 -3.93912010e+01 -5.75417633e+01 -4.96311951e+01 -3.68250847e+01 -3.51886024e+01 -2.69509678e+01 -2.34591770e+01 -2.91981030e+01 -4.50392036e+01 -5.69450188e+01 -5.83404503e+01 -5.23746834e+01 -4.09763374e+01 -2.64292393e+01 -3.01198788e+01 -3.97978630e+01 -5.27199974e+01 -5.62405891e+01 -5.68955917e+01 -5.82531242e+01 -6.55584106e+01 -6.96015930e+01 -6.95557175e+01 -5.99804993e+01 -5.53481903e+01 -5.82882729e+01 -6.58755646e+01 -6.50794449e+01 -5.93753967e+01 -5.95854912e+01 -6.54061890e+01 -5.54652977e+01 -4.73440666e+01 -5.05806274e+01 -6.81770401e+01 -7.43500366e+01 -6.54341888e+01 -5.90368919e+01 -5.62894173e+01 -5.01682358e+01 -4.37964630e+01 -4.34052467e+01 -4.30192680e+01 -4.69112854e+01 -5.10324745e+01 -6.00589752e+01 -6.12695885e+01 -5.51761894e+01 -5.77939568e+01 -6.30758133e+01 -6.66727295e+01 -6.52350540e+01 -6.39513855e+01 -5.35151100e+01 -4.25926628e+01 -4.19361000e+01 -5.62134171e+01 -6.90942001e+01 -7.04174576e+01 -7.02140884e+01 -7.06169052e+01 -6.83254929e+01 -6.50438385e+01 -6.78771515e+01 -7.95769348e+01 -8.98884430e+01 -9.02476654e+01 -8.31402130e+01 -7.54766617e+01 -7.39849472e+01 -7.77313690e+01 -7.79908447e+01 -7.50222473e+01 -7.39164658e+01 -8.99728851e+01 -1.06884911e+02 -1.06170914e+02 -8.49564819e+01 -6.70230331e+01 -6.67422562e+01 -8.50560532e+01 -1.29522797e+02 -1.93775101e+02 -2.72067566e+02 -2.88310883e+02 -2.08542038e+02 -1.02073541e+03 -1.65731738e+03 -3.23661652e+02 -3.34371094e+02 -3.46787170e+02 -3.33597443e+02 -2.94690704e+02 -3.04400513e+02 -3.56958344e+02 -5.08916260e+02 -6.58673157e+02 -4.83707666e+03 -2.74765156e+04 24924678. 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. 0. 0. 0. 0. 0. 0. 0. 0. 632492160. -82336936. -50741084. -4.49175049e+03 -1.91035181e+03 -2.03214905e+02 -1.57984009e+02 -9.92762146e+01 -1.11097542e+02 -1.12939774e+02 -1.12735535e+02 -1.03454933e+02 -8.85846939e+01 -9.10716553e+01 -9.30171509e+01 -9.48890991e+01 -9.40762939e+01 -9.95877762e+01 -1.07907059e+02 -1.01284676e+02 -8.69481812e+01 -8.34379349e+01 -9.22608261e+01 -1.01796394e+02 -9.58709259e+01 -9.59007034e+01 -9.84841385e+01 -1.04346085e+02 -1.06506783e+02 -1.06563400e+02 -1.03628410e+02 -9.66490555e+01 -9.45882721e+01 -9.42294006e+01 -9.65396500e+01 -8.84722519e+01 -7.68924942e+01 -7.41851959e+01 -8.04577942e+01 -8.79481888e+01 -8.58052292e+01 -8.30417557e+01 -8.29483643e+01 -8.08542557e+01 -7.89285812e+01 -7.74291382e+01 -7.67530975e+01 -7.66749344e+01 -8.00012436e+01 -8.15579071e+01 -8.40881348e+01 -8.09239655e+01 -8.27717285e+01 -8.42875900e+01 -8.37118607e+01 -8.20781403e+01 -7.98627930e+01 -7.99080734e+01 -8.34846725e+01 -8.99496307e+01 -9.83305054e+01 -1.02800507e+02 -1.00762970e+02 -9.57373123e+01 -9.19855423e+01 -9.66385651e+01 -1.01731102e+02 -9.95113754e+01 -9.24826355e+01 -8.58174896e+01 -8.57215195e+01 -8.54960556e+01 -8.19920959e+01 -7.61223526e+01 -8.15897827e+01 -9.06823196e+01 -9.83088913e+01 -9.57889252e+01 -9.18250198e+01 -9.33685684e+01 -9.32933960e+01 -9.37066650e+01 -9.26334152e+01 -9.27046890e+01 -9.24595184e+01 -9.57428360e+01 -9.66913376e+01 -9.78470688e+01 -9.56856537e+01 -9.61527863e+01 -1.01714622e+02 -1.07562248e+02 -1.06193939e+02 -1.01369240e+02 -9.60293427e+01 -9.80028687e+01 -1.00359344e+02 -1.04041817e+02 -1.04975586e+02 -1.01351440e+02 -9.56267319e+01 -9.44206161e+01 -9.67701416e+01 -1.02587372e+02 -1.03163887e+02 -1.02416473e+02 -9.96137848e+01 -9.71123810e+01 -9.82783585e+01 -9.67920685e+01 -9.75874863e+01 -9.62508545e+01 -9.79101791e+01 -9.79701233e+01 -9.75309601e+01 -9.95913773e+01 -1.01901100e+02 -1.01654640e+02 -9.95471497e+01 -9.67643127e+01 -9.67367783e+01 -9.60511017e+01 -9.58596268e+01 -9.51400833e+01 -9.47758942e+01 -9.55420685e+01 -9.96621399e+01 -1.04055779e+02 -1.04506790e+02 -1.01853004e+02 -9.85229568e+01 -9.70552902e+01 -9.57558975e+01 -9.60124588e+01 -9.75671768e+01 -9.84264603e+01 -9.73804169e+01 -9.75476761e+01 -9.77943420e+01 -9.82280655e+01 -9.83579559e+01 -9.86762009e+01 -9.89976349e+01 -9.92681503e+01 -9.89603500e+01 -9.92808075e+01 -9.96775894e+01 -1.00038902e+02 -1.00048431e+02 -1.00272263e+02 -1.00451607e+02 -1.00497375e+02 -9.99916000e+01 -9.96324844e+01 -9.92659454e+01 -9.93162994e+01 -9.93068771e+01 -9.91045990e+01 -9.89937515e+01 -9.94478607e+01 -1.01067581e+02 -1.01796486e+02 -1.01700455e+02 -1.01090981e+02 -1.00539886e+02 -1.00460258e+02 -1.00192154e+02 -1.00079506e+02 -1.00090599e+02 -1.00097092e+02 -1.00052361e+02 -9.99740143e+01 -9.99234390e+01 -9.98876266e+01 -9.98856735e+01 -1.00023056e+02 -1.00249474e+02 -1.00368912e+02 -1.00295959e+02 -1.00034668e+02 -9.96370316e+01 -9.96385574e+01 -9.96777496e+01 -9.98008194e+01 -9.97634201e+01 -9.98826141e+01 -9.97819214e+01 -9.97667084e+01 -9.99086914e+01 -9.97267456e+01 -9.95982895e+01 -9.95416107e+01 -9.97590790e+01 -9.98906479e+01 -9.91367188e+01 -9.87341461e+01 -9.83099976e+01 -9.84856339e+01 -9.91889496e+01 -1.01126862e+02 -1.03501076e+02 -1.04485008e+02 -1.04382889e+02 -1.03721298e+02 -1.04403603e+02 -1.02875320e+02 -1.00842834e+02 -9.81538544e+01 -9.76576233e+01 -9.76477966e+01 -9.81610718e+01 -9.83748322e+01 -9.81720352e+01 -9.70653229e+01 -9.69063110e+01 -9.70690155e+01 -9.80131302e+01 -9.81015854e+01 -9.81255264e+01 -9.51142197e+01 -9.17428436e+01 -9.24174576e+01 -9.52870026e+01 -9.87012634e+01 -1.00164948e+02 -1.01727509e+02 -1.04889816e+02 -1.07197166e+02 -1.05995911e+02 -1.03929581e+02 -9.91576691e+01 -1.00330673e+02 -1.01684258e+02 -1.03413948e+02 -1.03085236e+02 -1.01311768e+02 -1.01843185e+02 -1.01923737e+02 -1.01826370e+02 -9.96715851e+01 -9.79916306e+01 -9.86269836e+01 -1.02732368e+02 -1.07749382e+02 -1.11959991e+02 -1.14009331e+02 -1.04291283e+02 -9.44144821e+01 -8.88783188e+01 -9.32963257e+01 -9.88443985e+01 -9.81506271e+01 -9.90466690e+01 -9.79448547e+01 -9.86074600e+01 -9.73339157e+01 -9.61273270e+01 -9.47710648e+01 -9.58276978e+01 -9.60840149e+01 -9.20908966e+01 -8.45001907e+01 -8.26088257e+01 -8.58267517e+01 -9.10821915e+01 -9.48961182e+01 -9.85842438e+01 -9.87614746e+01 -9.48545227e+01 -9.33532181e+01 -9.70536804e+01 -9.72567596e+01 -9.43146439e+01 -9.00225449e+01 -8.97336578e+01 -8.99656601e+01 -9.01794586e+01 -9.15538483e+01 -9.09056625e+01 -9.30846024e+01 -9.23592300e+01 -9.18419952e+01 -8.76005173e+01 -8.62204514e+01 -8.67163849e+01 -9.41630554e+01 -1.03469078e+02 -1.02785782e+02 -9.60718307e+01 -8.66462631e+01 -8.94254684e+01 -9.19225693e+01 -9.49178391e+01 -9.56922531e+01 -9.67165527e+01 -9.62068787e+01 -1.00322189e+02 -1.02672607e+02 -1.00659500e+02 -9.23097610e+01 -8.49937439e+01 -8.48916855e+01 -8.63269958e+01 -8.16283875e+01 -7.44412155e+01 -7.16822891e+01 -7.36467743e+01 -8.04760513e+01 -8.00470352e+01 -8.09269562e+01 -8.19839706e+01 -8.48001404e+01 -8.59637299e+01 -8.35931244e+01 -7.80321350e+01 -7.91770859e+01 -8.10591736e+01 -8.34953918e+01 -8.17944565e+01 -8.24435043e+01 -8.41563492e+01 -9.12204285e+01 -9.84836884e+01 -9.75646820e+01 -9.23573456e+01 -8.66177902e+01 -8.71724701e+01 -8.34836044e+01 -7.88644943e+01 -8.07589951e+01 -9.51072693e+01 -1.06094666e+02 -1.06870880e+02 -9.48577271e+01 -8.62393417e+01 -8.62535934e+01 -8.74044113e+01 -8.69696732e+01 -8.53133850e+01 -9.40298157e+01 -1.05419960e+02 -1.07928833e+02 -9.85448456e+01 -8.49333649e+01 -8.61453323e+01 -8.61240387e+01 -8.59588623e+01 -8.39858856e+01 -8.49930801e+01 -9.06132660e+01 -9.50650406e+01 -9.52953568e+01 -8.99150467e+01 -8.48428421e+01 -8.76433945e+01 -1.01039589e+02 -1.17743248e+02 -1.18732025e+02 -1.05802811e+02 -9.15687256e+01 -8.63491669e+01 -8.07984848e+01 -8.01229858e+01 -8.54057312e+01 -1.00535530e+02 -1.11510834e+02 -1.23770493e+02 -1.26295616e+02 -1.12378433e+02 -9.87688675e+01 -8.22958145e+01 -9.35043564e+01 -1.03628189e+02 -9.14281082e+01 -6.59069595e+01 -5.21049309e+01 -6.55451202e+01 -7.83835220e+01 -7.64104385e+01 -7.35633087e+01 -7.31251526e+01 -7.06123657e+01 -6.83647079e+01 -6.54664307e+01 -6.45430450e+01 -6.27993584e+01 -6.21037788e+01 -6.35044327e+01 -6.05165215e+01 -6.16206055e+01 -6.05161705e+01 -7.06872787e+01 -8.26110916e+01 -8.28553009e+01 -7.14035873e+01 -5.33829994e+01 -6.57724991e+01 -8.52040939e+01 -7.37315979e+01 -4.50255699e+01 -4.48296509e+01 -8.03265533e+01 -1.01402359e+02 -8.75165024e+01 -6.80923767e+01 -7.69534454e+01 -9.35381699e+01 -9.86411209e+01 -8.84758835e+01 -7.28104782e+01 -7.21696472e+01 -7.49965744e+01 -7.46609650e+01 -7.47086563e+01 -6.13222160e+01 -4.93879890e+01 -6.35423393e+01 -9.17970581e+01 -1.04822342e+02 -9.26279449e+01 -8.01127319e+01 -9.43932724e+01 -1.05306183e+02 -1.08163979e+02 -9.50180359e+01 -7.97968063e+01 -8.11492462e+01 -8.21923523e+01 -8.45054474e+01 -7.86751328e+01 -8.50304718e+01 -9.83225555e+01 -1.02676666e+02 -9.96453705e+01 -8.12839661e+01 -7.08469620e+01 -6.21103973e+01 -5.99173737e+01 -6.28636208e+01 -4.17963181e+01 -1.57396841e+01 -2.04533310e+01 -5.31406364e+01 -8.23371658e+01 -7.27205353e+01 -5.86329117e+01 -6.84379501e+01 -8.94135818e+01 -9.00641327e+01 -7.70980911e+01 -6.05005951e+01 -5.61481171e+01 -5.41092262e+01 -5.15919991e+01 -5.51877556e+01 -5.76933022e+01 -6.13839035e+01 -6.90311279e+01 -7.20175018e+01 -6.71017838e+01 -5.59497871e+01 -4.99282990e+01 -4.63795395e+01 -4.72213402e+01 -3.22080231e+01 -1.79488029e+01 -3.30672798e+01 -6.86567535e+01 -8.71251602e+01 -6.72389755e+01 -4.69011574e+01 -3.53600121e+01 -3.01898232e+01 -2.71291142e+01 -3.09309368e+01 -3.51906776e+01 -3.02420979e+01 -3.30103455e+01 -3.05725784e+01 -3.55918579e+01 -3.13474770e+01 -2.79779015e+01 -2.39583073e+01 -2.99699059e+01 -3.68064079e+01 -3.41581917e+01 -2.47781734e+01 -2.06700153e+01 -3.10177193e+01 -4.08929520e+01 -4.52478981e+01 -5.45388222e+01 -7.10201340e+01 -7.38243484e+01 -6.38044052e+01 -6.21001205e+01 -9.57122421e+01 -1.16128983e+02 -1.02827263e+02 -7.91259918e+01 -8.45564270e+01 -1.04283890e+02 -1.06228004e+02 -8.33068924e+01 -6.79929428e+01 -6.24214439e+01 -6.37278633e+01 -6.49085083e+01 -6.73431091e+01 -6.55998077e+01 -5.65322037e+01 -6.72503128e+01 -8.57532120e+01 -9.67529297e+01 -7.97045822e+01 -5.86642532e+01 -5.79810486e+01 -7.30941696e+01 -5.57390709e+01 -2.74141102e+01 -1.14741802e+01 -2.47268143e+01 -4.12912292e+01 -3.23522873e+01 -3.14717388e+01 -3.24381638e+01 -3.22247581e+01 -2.97613335e+01 -3.17468491e+01 -3.92916603e+01 -3.49959145e+01 -2.76005440e+01 -2.00781879e+01 -2.23605156e+01 -2.90359402e+01 -3.04615211e+01 -4.67752991e+01 -6.12210121e+01 -5.91607246e+01 -3.82411003e+01 -1.22103348e+01 -8.52032089e+00 -8.27253056e+00 3.99898458e+00 2.38278599e+01 2.57785835e+01 1.12690697e+01 -1.21893721e+01 -1.62929668e+01 -1.72247791e+01 -3.91386414e+01 -6.48277817e+01 -7.16515503e+01 -4.89958267e+01 -3.06666298e+01 -2.88554802e+01 -2.40558929e+01 -1.47875471e+01 -1.76031246e+01 -8.28559208e+00 1.06916027e+01 3.99159145e+00 -2.39856377e+01 -4.66646233e+01 -3.93443947e+01 -4.33588448e+01 -7.68796997e+01 -9.77275391e+01 -8.31445694e+01 -4.56211433e+01 -3.70834656e+01 -5.04872932e+01 -5.24742699e+01 -3.44004135e+01 -9.68020725e+00 -1.42789278e+01 -2.80245056e+01 -3.08494968e+01 -2.13338375e+01 -3.12517834e+00 7.35938692e+00 1.37601738e+01 1.65560246e+01 8.27355576e+00 1.35407963e+01 1.14137497e+01 -2.16211677e+00 -2.23455639e+01 -2.65286560e+01 -1.25591288e+01 -7.08413541e-01 -7.85500813e+00 2.75522461e+01 1.71236450e+02 2.07371765e+02 3.13027863e+02 1.57762073e+03 2.43280029e+03 -5.83038807e+00 -3.10142612e+00 -2.27130688e+03 -1.64960571e+03 -4.01599701e+02 -4.40451599e+02 1.09485522e+03 1.93000952e+03 -1.47691376e+02 -6.72176895e+01 3.56904114e+02 3.04276733e+03 82858136. 0. 0. 0. 0. 0. 0. 0. 0. 4.70811402e+10 -7.49743688e+05 4.10306281e+05 2.57269953e+05 2.57294008e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.97151386e+10 2395078. 3.07521055e+04 1.12800479e+04 8.32711487e+02 1.36611731e+03 3.09711890e+03 1.75065393e+03 -2.97898960e+01 2.07326599e+02 2.67215118e+01 6.36181145e+01 7.26031799e+01 4.21551704e+01 2.47620010e+01 3.96463737e+01 5.84019928e+01 4.29921265e+01 6.22459555e+00 -7.65015936e+00 3.51525421e+01 9.47329559e+01 8.85649033e+01 2.43138142e+01 -5.01794205e+01 -8.08384399e+01 -4.72692032e+01 -4.47429543e+01 -5.64100647e+01 -4.32657700e+01 -1.24537344e+01 4.87944889e+00 -3.19257622e+01 -1.20701614e+02 -1.23724442e+02 -6.21881523e+01 3.02518253e+01 5.97254448e+01 5.13889771e+01 5.71636543e+01 7.87215347e+01 8.68541794e+01 4.67871323e+01 -4.51902275e+01 -9.24650497e+01 -6.01089554e+01 5.52554989e+00 4.02126808e+01 4.19714699e+01 2.49521694e+01 9.55410004e-01 9.24547672e+00 -4.28364038e+00 -1.54269533e+01 6.41191959e+00 7.15289688e+01 1.32386627e+02 1.04655167e+02 4.27915841e-01 -4.21028481e+01 -5.38474131e+00 6.83895187e+01 6.21967735e+01 9.76038361e+00 2.02415752e+00 4.86716652e+01 1.00064217e+02 8.43441544e+01 6.84304142e+00 -4.23499413e+01 -1.70127506e+01 3.92441902e+01 5.08419037e+01 4.42087784e+01 3.97251053e+01 6.15141678e+01 8.24969635e+01 6.36635361e+01 5.36334496e+01 6.87693863e+01 1.09022285e+02 1.13850288e+02 9.19115524e+01 5.26101227e+01 2.32240124e+01 1.33812037e+01 4.48172798e+01 6.11879539e+01 5.58709831e+01 9.19378433e+01 1.47552628e+02 1.69714172e+02 1.07256874e+02 1.86654530e+01 -2.02620049e+01 1.77768021e+01 9.39750366e+01 1.57924530e+02 1.77613434e+02 1.60415497e+02 1.43180527e+02 1.44248871e+02 1.21298012e+02 6.55901413e+01 2.86190052e+01 4.87428665e+01 9.58245544e+01 1.11036903e+02 9.11257324e+01 5.32841225e+01 3.84585381e+01 7.28472137e+01 9.77484360e+01 9.50680618e+01 8.67170868e+01 1.16120636e+02 1.62481445e+02 1.62169693e+02 1.13773865e+02 6.83928757e+01 7.92606201e+01 1.23070686e+02 1.54399765e+02 1.49602051e+02 1.14307739e+02 7.54399261e+01 5.69944496e+01 8.04760971e+01 8.07650833e+01 5.81607819e+01 5.79659042e+01 9.66338043e+01 1.31558578e+02 1.26755363e+02 8.56211624e+01 6.38846016e+01 8.53998413e+01 1.10612442e+02 1.24854591e+02 1.05345322e+02 1.12618324e+02 1.46954575e+02 1.59993805e+02 1.15040520e+02 3.30999336e+01 -6.35455132e+00 2.20239487e+01 6.92365265e+01 8.12632065e+01 7.65535965e+01 6.35359001e+01 6.77329941e+01 6.50623474e+01 4.23054314e+01 1.05270424e+01 3.55975008e+00 4.26519890e+01 1.13969467e+02 1.39175644e+02 1.01621445e+02 6.23907509e+01 6.94098129e+01 9.02047348e+01 6.85032959e+01 2.01056652e+01 2.87644463e+01 7.20379944e+01 1.11105637e+02 7.05821152e+01 -6.56717920e+00 -4.49170952e+01 -3.71308994e+00 6.48599167e+01 9.55528412e+01 9.10196075e+01 9.87042313e+01 1.11173546e+02 9.61181107e+01 5.11316605e+01 -2.52482086e-01 3.32324638e+01 8.42901154e+01 1.31252640e+02 1.12842110e+02 8.78280029e+01 6.80227127e+01 5.96774330e+01 6.20384369e+01 4.48285179e+01 2.62766800e+01 4.12882843e+01 8.80562744e+01 1.25118088e+02 1.01447807e+02 4.76128120e+01 1.29998035e+01 4.41717453e+01 9.69160995e+01 1.22265190e+02 1.15717857e+02 1.15877731e+02 1.49382416e+02 1.62558411e+02 1.28121765e+02 7.76728058e+01 7.58859406e+01 1.08834641e+02 1.46649323e+02 1.50788101e+02 1.43449188e+02 1.24852165e+02 1.08164055e+02 1.05205238e+02 9.25896454e+01 7.48972931e+01 9.18495483e+01 1.26287659e+02 1.41602707e+02 1.35347961e+02 1.05702461e+02 1.03100151e+02 1.15626060e+02 1.25205246e+02 1.22650322e+02 1.02091576e+02 1.18487770e+02 1.39831726e+02 1.53307068e+02 1.51123398e+02 1.20310844e+02 1.05725502e+02 1.23685677e+02 1.63516602e+02 1.66349915e+02 1.37793045e+02 1.05872345e+02 1.04483154e+02 1.20858063e+02 1.18470840e+02 1.05839859e+02 1.05692566e+02 1.34711044e+02 1.51932556e+02 1.29160019e+02 1.07124237e+02 1.23307419e+02 1.42856903e+02 1.38215408e+02 1.19407928e+02 1.02188553e+02 1.14537460e+02 1.07986816e+02 1.02820091e+02 9.64666901e+01 9.22027130e+01 8.48441849e+01 8.17014771e+01 1.11952156e+02 1.27389229e+02 1.36102325e+02 1.06743523e+02 1.11825165e+02 1.11492935e+02 1.01279861e+02 8.31254120e+01 7.69037399e+01 1.15138695e+02 1.40171249e+02 1.42860153e+02 1.08125977e+02 1.00008667e+02 1.06839447e+02 1.17514030e+02 1.17245293e+02 9.57734146e+01 1.10595932e+02 1.24358612e+02 1.53559647e+02 1.61210495e+02 1.57939896e+02 1.40166122e+02 1.21027710e+02 1.30412354e+02 1.48647583e+02 1.62250549e+02 1.53210968e+02 1.63369217e+02 1.66068726e+02 1.48627716e+02 1.20621040e+02 1.16690674e+02 1.47874985e+02 1.60438004e+02 1.44653030e+02 1.18083450e+02 1.26980598e+02 1.43618896e+02 1.49275208e+02 1.42704620e+02 1.30207275e+02 1.31839844e+02 1.26515900e+02 1.41017181e+02 1.48131958e+02 1.49596222e+02 1.41929688e+02 1.37034241e+02 1.46096436e+02 1.53353119e+02 1.56179993e+02 1.61932327e+02 1.82233841e+02 1.94252823e+02 1.90559921e+02 1.78531555e+02 1.78078995e+02 1.90774017e+02 1.96966187e+02 1.83237015e+02 1.58578369e+02 1.53672867e+02 1.58733414e+02 1.58583679e+02 1.48649857e+02 1.31800888e+02 1.29523041e+02 1.30128036e+02 1.43699493e+02 1.51710434e+02 1.54790283e+02 1.54805939e+02 1.56147888e+02 1.61077271e+02 1.66968872e+02 1.67070206e+02 1.64672470e+02 1.74205841e+02 1.85740723e+02 1.80713989e+02 1.63441925e+02 1.54777313e+02 1.54675278e+02 1.46389847e+02 1.38134521e+02 1.32624130e+02 1.47794678e+02 1.49001572e+02 1.51410477e+02 1.53392471e+02 1.53701706e+02 1.48450394e+02 1.32819168e+02 1.31562469e+02 1.45409470e+02 1.61609848e+02 1.61633423e+02 1.51184631e+02 1.40334473e+02 1.43188690e+02 1.50622772e+02 1.60715393e+02 1.62250473e+02 1.57118362e+02 1.49501572e+02 1.35714523e+02 1.31153854e+02 1.29460892e+02 1.30827530e+02 1.32166061e+02 1.32192093e+02 1.42943359e+02 1.42635696e+02 1.44404022e+02 1.44173172e+02 1.44061676e+02 1.38741730e+02 1.21451172e+02 1.17275162e+02 1.27676315e+02 1.51405365e+02 1.63924866e+02 1.51328873e+02 1.34379150e+02 1.33666245e+02 1.51705383e+02 1.70654205e+02 1.66218933e+02 1.52269058e+02 1.41505981e+02 1.41427567e+02 1.49768387e+02 1.48507416e+02 1.43728577e+02 1.39172134e+02 1.39578903e+02 1.47495605e+02 1.46383453e+02 1.41926544e+02 1.38087082e+02 1.39654861e+02 1.45971375e+02 1.44241531e+02 1.44058487e+02 1.50691956e+02 1.59251862e+02 1.58596756e+02 1.44189087e+02 1.35778595e+02 1.38618408e+02 1.48781296e+02 1.54098907e+02 1.52614044e+02 1.48390091e+02 1.46058945e+02 1.44883377e+02 1.48797119e+02 1.49047455e+02 1.48886902e+02 1.47453003e+02 1.46528442e+02 1.49590698e+02 1.51180328e+02 1.54591721e+02 1.53809967e+02 1.51998657e+02 1.49621490e+02 1.46571701e+02 1.46005692e+02 1.48159515e+02 1.52495529e+02 1.54597046e+02 1.52802155e+02 1.49758255e+02 1.48921875e+02 1.50865250e+02 1.52695114e+02 1.52363022e+02 1.51027878e+02 1.50658966e+02 1.50802094e+02 1.50899445e+02 1.50860107e+02 1.50955063e+02 1.51320663e+02 1.51786102e+02 1.51996155e+02 1.52865738e+02 1.53380768e+02 1.52540543e+02 1.50735474e+02 1.49459976e+02 1.51238632e+02 1.53333694e+02 1.53121048e+02 1.49952850e+02 1.46337997e+02 1.47446136e+02 1.51381790e+02 1.53004898e+02 1.51043594e+02 1.46965500e+02 1.47739594e+02 1.51200867e+02 1.54896255e+02 1.57615189e+02 1.55017975e+02 1.55513641e+02 1.52963394e+02 1.53002228e+02 1.53077179e+02 1.54448181e+02 1.58150238e+02 1.55023376e+02 1.50598022e+02 1.44806412e+02 1.46828659e+02 1.55347946e+02 1.62316360e+02 1.59508560e+02 1.49254318e+02 1.41176285e+02 1.40833008e+02 1.47684235e+02 1.51265060e+02 1.52175385e+02 1.47796463e+02 1.50052917e+02 1.53734238e+02 1.58404770e+02 1.65360321e+02 1.65600372e+02 1.58189835e+02 1.46500244e+02 1.43488800e+02 1.46604233e+02 1.52349564e+02 1.60748291e+02 1.65840012e+02 1.57307556e+02 1.39657455e+02 1.31478226e+02 1.41748215e+02 1.57212692e+02 1.58908249e+02 1.41596024e+02 1.22391907e+02 1.23829536e+02 1.44117783e+02 1.66920944e+02 1.75689774e+02 1.63638290e+02 1.51365707e+02 1.48812057e+02 1.53004837e+02 1.57511154e+02 1.50358337e+02 1.53593842e+02 1.50809174e+02 1.43535233e+02 1.39913712e+02 1.38825333e+02 1.52659988e+02 1.52166107e+02 1.38640457e+02 1.19421898e+02 1.20185875e+02 1.50239670e+02 1.71635010e+02 1.65348389e+02 1.38903595e+02 1.20838005e+02 1.19887207e+02 1.40382446e+02 1.62111786e+02 1.72548859e+02 1.55896301e+02 1.44475662e+02 1.32496140e+02 1.32795761e+02 1.37824875e+02 1.35505646e+02 1.35984116e+02 1.17590164e+02 1.10397629e+02 1.09965813e+02 1.20694443e+02 1.47139633e+02 1.54087601e+02 1.39865555e+02 1.12053703e+02 1.04661461e+02 1.19591850e+02 1.42264175e+02 1.44010696e+02 1.26022148e+02 1.01520882e+02 9.63505478e+01 1.20353973e+02 1.43697571e+02 1.51795929e+02 1.33439133e+02 1.16674759e+02 1.19544556e+02 1.33462097e+02 1.49846420e+02 1.53096527e+02 1.54670532e+02 1.42025681e+02 1.21438622e+02 1.13558983e+02 1.32918213e+02 1.67793030e+02 1.82446014e+02 1.59846268e+02 1.30037888e+02 1.11676743e+02 1.24737427e+02 1.48136642e+02 1.60273834e+02 1.53657791e+02 1.33654495e+02 1.33987320e+02 1.47060867e+02 1.64795853e+02 1.67970886e+02 1.45970459e+02 1.29819489e+02 1.30812424e+02 1.48117569e+02 1.70805923e+02 1.66683182e+02 1.67426849e+02 1.53845871e+02 1.39089035e+02 1.28271439e+02 1.25228256e+02 1.51358490e+02 1.65479401e+02 1.60023300e+02 1.38062714e+02 1.15358681e+02 1.29860947e+02 1.48969925e+02 1.67123138e+02 1.40333054e+02 9.34525223e+01 6.84584732e+01 8.57350388e+01 1.24187263e+02 1.37586334e+02 9.77319794e+01 4.46903725e+01 5.68048429e+00 -1.41662827e+02 -2.68966644e+02 -1.04057935e+03 -9.88183777e+02 -1.77957690e+03 -5.02545947e+03 -126094704. -52204196. -29627628. -33506270. -176723664. 260606832. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 615633472. 49117268. -1.01545195e+04 -3.44664917e+03 -9.98306702e+02 -4.19947853e+01 -1.58850723e+02 -2.07787109e+02 -7.68060608e+01 1.61939430e+01 2.88907051e+01 6.94761047e+01 1.13240829e+02 1.38063492e+02 1.33671341e+02 8.92290726e+01 5.51318016e+01 6.80658569e+01 1.24396294e+02 1.73057343e+02 1.63400711e+02 1.30416214e+02 1.05245575e+02 9.47729797e+01 8.60748215e+01 6.80225754e+01 9.84130707e+01 1.07585495e+02 7.88786774e+01 5.43570404e+01 9.00498505e+01 1.68991638e+02 1.97414154e+02 1.37764816e+02 6.41921997e+01 2.80731239e+01 5.16974945e+01 1.20371468e+02 1.72408463e+02 1.99033707e+02 1.53038467e+02 1.20340347e+02 1.12432732e+02 1.45459869e+02 1.69181824e+02 1.50603653e+02 1.53813751e+02 1.25652565e+02 9.58942490e+01 6.80502167e+01 9.16428375e+01 1.70314850e+02 1.79461899e+02 1.23350983e+02 4.23787231e+01 2.28590908e+01 8.32260818e+01 1.40674408e+02 1.47854004e+02 9.88255768e+01 7.37961044e+01 1.12450218e+02 1.82095428e+02 2.11178848e+02 1.86801178e+02 1.14044533e+02 5.66837692e+01 5.50325089e+01 1.06323753e+02 1.66543335e+02 2.09313095e+02 2.31481125e+02 2.16391144e+02 1.81112244e+02 1.33258743e+02 1.11304916e+02 1.28446457e+02 1.17384666e+02 6.66307449e+01 1.13614454e+01 1.43041677e+01 7.68489304e+01 1.18742599e+02 1.13713631e+02 8.87773132e+01 5.33625298e+01 2.43462372e+01 4.16537895e+01 1.01980423e+02 1.40142868e+02 1.05254356e+02 6.15144577e+01 7.33148499e+01 1.06323524e+02 1.11942764e+02 8.62712173e+01 1.00440353e+02 9.91622162e+01 7.75652847e+01 5.25548935e+01 6.25509453e+01 1.34084015e+02 1.42291962e+02 8.42917862e+01 -1.50721340e+01 -5.38169632e+01 2.87704825e+00 7.14402695e+01 1.05973373e+02 8.98323822e+01 7.02463150e+01 7.05775146e+01 8.36101761e+01 1.15537750e+02 1.31568863e+02 9.87018661e+01 3.33600807e+01 7.96655083e+00 2.87995300e+01 5.09946175e+01 5.13149223e+01 8.01529465e+01 8.00203552e+01 2.46032333e+01 -4.49906273e+01 -4.78726501e+01 5.26086998e+01 9.16555557e+01 4.44493523e+01 -3.73262291e+01 -4.88652344e+01 2.63070354e+01 8.80295792e+01 1.06190552e+02 8.63894348e+01 3.31086922e+01 -1.04233561e+01 -1.13831110e+01 4.87294655e+01 9.37526855e+01 6.00076180e+01 -2.95284247e+00 -3.25123062e+01 -8.04906940e+00 2.52621174e+01 4.92615471e+01 8.63961411e+01 1.02501907e+02 8.50293045e+01 5.58652916e+01 4.85679893e+01 9.37694397e+01 1.06152260e+02 6.23181839e+01 -2.65422726e+01 -8.57929916e+01 -5.77132568e+01 2.05052605e+01 8.72994461e+01 8.27460938e+01 4.75604553e+01 3.67181053e+01 4.65382156e+01 4.59712029e+01 6.83717270e+01 6.60343857e+01 6.26360359e+01 3.04151630e+01 -2.54704628e+01 -4.49784241e+01 -5.48814774e+01 1.46595573e+01 3.81059952e+01 7.22790480e-01 -3.83684082e+01 -2.05567398e+01 6.23690414e+01 9.30916290e+01 6.70131454e+01 2.76066971e+01 -1.43754172e+00 -6.49059153e+00 1.03983517e+01 2.57878056e+01 3.74919815e+01 -8.75852585e+00 5.85933256e+00 3.17942867e+01 8.16798248e+01 1.20259506e+02 1.51251068e+02 1.84135529e+02 1.36138031e+02 5.73226471e+01 3.41323280e+00 3.36104178e+00 5.14594345e+01 5.44928970e+01 -2.40316898e-01 -7.00831146e+01 -9.45739899e+01 -1.44837046e+01 7.96340485e+01 1.23193031e+02 1.00327507e+02 6.58721848e+01 5.75262833e+01 5.71695976e+01 6.79520264e+01 8.80879364e+01 7.13319855e+01 2.74762764e+01 -5.08748531e-01 2.49981747e+01 3.10011444e+01 3.65690384e+01 6.49796066e+01 9.07691269e+01 7.41803055e+01 3.68966599e+01 2.57483578e+01 2.79142227e+01 -1.42495155e+00 -3.88437996e+01 -7.06214066e+01 -8.00194016e+01 -3.98767548e+01 -7.76632833e+00 5.21940117e+01 6.75172272e+01 2.67223511e+01 -2.84267044e+01 -5.05907860e+01 -1.56638489e+01 7.54137516e+00 -1.10705256e+00 -2.88936782e+00 -1.91184938e+00 -5.73830366e+00 -5.74831200e+00 -4.00930738e+00 -2.99279547e+00 -4.42452478e+00 -1.51128969e+01 -2.24479446e+01 -4.06813507e+01 -4.31868629e+01 -4.00470886e+01 -2.43822613e+01 -2.17968349e+01 -3.07949619e+01 -3.05657635e+01 -2.87656422e+01 -4.05721235e+00 1.05661707e+01 1.20613575e+01 4.00648499e+00 -1.42365780e+01 -1.06981049e+01 -1.28812752e+01 -1.48801394e+01 -2.28054447e+01 -2.00592060e+01 -1.75930901e+01 -1.98262997e+01 -2.91868877e+01 -3.09917107e+01 -3.01320229e+01 -3.21296501e+01 -3.52816010e+01 -4.53759422e+01 -5.48534775e+01 -5.73123436e+01 -4.28301315e+01 -3.70987091e+01 -3.64404259e+01 -4.39991570e+01 -4.53171577e+01 -5.42997932e+01 -5.34481850e+01 -4.96026726e+01 -3.35802193e+01 -3.39444504e+01 -4.14198532e+01 -5.12124748e+01 -4.30051994e+01 -4.44259491e+01 -4.50085526e+01 -4.98120232e+01 -3.89802895e+01 -3.69901009e+01 -4.32607117e+01 -4.73427696e+01 -4.41535416e+01 -4.39167442e+01 -5.05531273e+01 -4.45173645e+01 -2.70475521e+01 -2.31306248e+01 -3.09897766e+01 -3.98995895e+01 -4.19710274e+01 -3.55438347e+01 -3.44959908e+01 -3.22266350e+01 -3.92176857e+01 -4.28294296e+01 -4.01206741e+01 -3.61300392e+01 -4.68896790e+01 -5.58874931e+01 -6.37984200e+01 -5.77314720e+01 -6.28337860e+01 -7.66741791e+01 -7.06646881e+01 -5.98368835e+01 -4.15269623e+01 -4.56456108e+01 -4.57978897e+01 -4.28206482e+01 -5.16826363e+01 -4.86212387e+01 -4.93820763e+01 -4.43380547e+01 -3.92884102e+01 -3.37370338e+01 -2.74978867e+01 -3.70380020e+01 -4.77491722e+01 -5.34012947e+01 -5.79540901e+01 -5.80887146e+01 -5.15126457e+01 -4.59893761e+01 -4.59335747e+01 -4.01094131e+01 -3.78925934e+01 -4.29360695e+01 -5.56259422e+01 -6.13635597e+01 -5.74959526e+01 -5.05426559e+01 -4.53121567e+01 -4.18477249e+01 -4.71808510e+01 -5.53502617e+01 -5.67385483e+01 -5.44188042e+01 -4.87571640e+01 -4.84163780e+01 -5.31096458e+01 -6.43474426e+01 -6.74870148e+01 -7.68171616e+01 -7.26313858e+01 -7.99199448e+01 -7.35801086e+01 -7.47773056e+01 -6.69786072e+01 -6.98378830e+01 -7.69063568e+01 -6.83882675e+01 -5.74971657e+01 -6.59055099e+01 -8.94079208e+01 -9.64458008e+01 -8.78405457e+01 -7.59282913e+01 -7.97470551e+01 -9.85984344e+01 -1.21191994e+02 -1.18686317e+02 -9.56536407e+01 -7.37506485e+01 -8.81128769e+01 -1.06832382e+02 -1.09716843e+02 -9.37772141e+01 -7.43679810e+01 -8.34010391e+01 -9.88728409e+01 -1.07872482e+02 -1.03869118e+02 -9.75652008e+01 -1.03744164e+02 -1.20076462e+02 -1.30674225e+02 -1.15969902e+02 -9.23516312e+01 -8.31048050e+01 -9.50187531e+01 -9.75963516e+01 -9.30808563e+01 -8.66870270e+01 -8.82927017e+01 -9.99236679e+01 -1.16166168e+02 -1.13733147e+02 -1.02979134e+02 -8.35497437e+01 -8.40260849e+01 -8.37168427e+01 -8.52550735e+01 -6.79796524e+01 -4.30417747e+01 -3.70381584e+01 -5.89093933e+01 -8.37153473e+01 -9.42463150e+01 -9.83237228e+01 -1.13222900e+02 -1.14138542e+02 -8.57966537e+01 -5.54822044e+01 -5.19268303e+01 -7.37468948e+01 -9.88178024e+01 -9.55139465e+01 -9.23005219e+01 -7.72551117e+01 -7.08367996e+01 -7.88823929e+01 -9.55398102e+01 -1.15803833e+02 -1.17267029e+02 -1.19743835e+02 -9.64890823e+01 -7.02589188e+01 -6.81919708e+01 -8.38731003e+01 -1.07189392e+02 -1.20268875e+02 -1.34384033e+02 -1.31723053e+02 -1.12185234e+02 -1.03793892e+02 -9.84670029e+01 -1.01334984e+02 -1.02815720e+02 -1.03361473e+02 -9.80426025e+01 -8.99856415e+01 -9.15522995e+01 -1.13019691e+02 -1.78081635e+02 -2.30189041e+02 -2.40276276e+02 -1.94740341e+02 -1.70720978e+02 -1.08857031e+03 -4.32718115e+03 -9.67403906e+03 -102494104. 27880224. -38967472. -164276416. -183627600. -520968256. -30965944. 48248820. -56369688. 52246980. -171502464. 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. 0. 0. 0. 0. 0. 0. 0. 155501632. -126679384. -2.57015742e+04 -1.09068018e+04 -2.50779785e+03 -1.55792078e+03 -1.31048193e+03 -2.97244116e+03 -1.74970117e+03 -5.11489990e+02 -3.38555908e+02 -2.71754761e+02 -1.95242920e+02 -1.82252502e+02 -1.84664719e+02 -2.01271591e+02 -1.95412277e+02 -1.24657692e+02 -5.64231987e+01 -5.92690277e+01 -1.28655426e+02 -2.33677811e+02 -2.47332855e+02 -3.19184357e+02 -3.51648590e+02 -3.50392212e+02 -2.89538910e+02 -2.70023773e+02 -3.19975616e+02 -3.29972076e+02 -3.22886658e+02 -3.06028076e+02 -2.64194061e+02 -1.84916931e+02 -1.51906906e+02 -1.40464127e+02 -1.38722366e+02 -1.34171265e+02 -1.26757637e+02 -1.20049377e+02 -1.21112656e+02 -1.26627975e+02 -1.23521454e+02 -1.20525345e+02 -1.17735008e+02 -1.16221329e+02 -1.15071304e+02 -1.18989998e+02 -1.32209305e+02 -1.42329742e+02 -1.44936218e+02 -1.38617126e+02 -1.32731583e+02 -1.28931259e+02 -1.27774666e+02 -1.31457748e+02 -1.36606949e+02 -1.36589859e+02 -1.32398346e+02 -1.28631882e+02 -1.27863022e+02 -1.24861084e+02 -1.30586395e+02 -1.39140732e+02 -1.45226440e+02 -1.48219040e+02 -1.49047043e+02 -1.51507889e+02 -1.48781631e+02 -1.44532410e+02 -1.42999649e+02 -1.41120544e+02 -1.33870621e+02 -1.30324875e+02 -1.29597794e+02 -1.33875809e+02 -1.35510117e+02 -1.34860031e+02 -1.42423782e+02 -1.51413925e+02 -1.52478348e+02 -1.48980789e+02 -1.42161209e+02 -1.54393829e+02 -1.65122665e+02 -1.68958405e+02 -1.62183258e+02 -1.56179230e+02 -1.56395645e+02 -1.55457367e+02 -1.52739090e+02 -1.53053741e+02 -1.60742004e+02 -1.67407120e+02 -1.64756256e+02 -1.53962250e+02 -1.46253799e+02 -1.43793549e+02 -1.46046539e+02 -1.47167450e+02 -1.50057343e+02 -1.44220764e+02 -1.39345535e+02 -1.41101135e+02 -1.48075287e+02 -1.50832260e+02 -1.46835312e+02 -1.43916550e+02 -1.50996918e+02 -1.56151627e+02 -1.56557877e+02 -1.50339340e+02 -1.44271225e+02 -1.41476715e+02 -1.40425430e+02 -1.41039322e+02 -1.43130905e+02 -1.44691864e+02 -1.45197556e+02 -1.43838333e+02 -1.44371811e+02 -1.46529587e+02 -1.47230362e+02 -1.47335220e+02 -1.46743134e+02 -1.48203506e+02 -1.48284714e+02 -1.49164001e+02 -1.53978027e+02 -1.59375656e+02 -1.58271851e+02 -1.53722763e+02 -1.49862076e+02 -1.53607391e+02 -1.57863480e+02 -1.58450089e+02 -1.56196793e+02 -1.53052338e+02 -1.51619675e+02 -1.50468933e+02 -1.49117935e+02 -1.49789688e+02 -1.50572861e+02 -1.51003311e+02 -1.49909576e+02 -1.48410507e+02 -1.48268311e+02 -1.49448624e+02 -1.50762421e+02 -1.50777878e+02 -1.50837204e+02 -1.50735611e+02 -1.52002029e+02 -1.54457443e+02 -1.56916901e+02 -1.56256836e+02 -1.54145554e+02 -1.52078384e+02 -1.53779800e+02 -1.55248108e+02 -1.54822189e+02 -1.53064102e+02 -1.51655502e+02 -1.51856888e+02 -1.51745255e+02 -1.51721375e+02 -1.51417160e+02 -1.51350189e+02 -1.51191254e+02 -1.51047623e+02 -1.51011017e+02 -1.51258438e+02 -1.51388290e+02 -1.51219177e+02 -1.51013214e+02 -1.50899185e+02 -1.50901443e+02 -1.50960449e+02 -1.50861969e+02 -1.50540085e+02 -1.50353775e+02 -1.50465683e+02 -1.50659668e+02 -1.50625565e+02 -1.50808685e+02 -1.50169846e+02 -1.48943451e+02 -1.48473785e+02 -1.49171997e+02 -1.50447525e+02 -1.50348770e+02 -1.50164856e+02 -1.50073700e+02 -1.50329178e+02 -1.49852570e+02 -1.49776794e+02 -1.47908203e+02 -1.46211578e+02 -1.45726578e+02 -1.47556747e+02 -1.49355072e+02 -1.49244034e+02 -1.49302872e+02 -1.47011459e+02 -1.44808762e+02 -1.44267059e+02 -1.47663162e+02 -1.50540436e+02 -1.49822784e+02 -1.48634384e+02 -1.48093292e+02 -1.48774261e+02 -1.49915146e+02 -1.50231155e+02 -1.50375229e+02 -1.49781265e+02 -1.49633011e+02 -1.50026825e+02 -1.49757278e+02 -1.51769608e+02 -1.52436737e+02 -1.53679169e+02 -1.53175613e+02 -1.52156265e+02 -1.52401230e+02 -1.52430176e+02 -1.53077057e+02 -1.52472061e+02 -1.51609528e+02 -1.51913239e+02 -1.50583389e+02 -1.50875610e+02 -1.51400162e+02 -1.53352585e+02 -1.53715317e+02 -1.51643906e+02 -1.50764587e+02 -1.49519394e+02 -1.51712936e+02 -1.50373367e+02 -1.51211288e+02 -1.48133026e+02 -1.46852493e+02 -1.45936340e+02 -1.50699814e+02 -1.56149948e+02 -1.52726776e+02 -1.43380844e+02 -1.34869003e+02 -1.35559204e+02 -1.39171783e+02 -1.41809494e+02 -1.42637115e+02 -1.40145035e+02 -1.37230118e+02 -1.36087189e+02 -1.38450592e+02 -1.42172577e+02 -1.45267715e+02 -1.47960114e+02 -1.48817337e+02 -1.47324936e+02 -1.43872742e+02 -1.41683807e+02 -1.39640701e+02 -1.39727020e+02 -1.38649017e+02 -1.43486969e+02 -1.44920776e+02 -1.46970108e+02 -1.42090622e+02 -1.34948135e+02 -1.28253555e+02 -1.30001083e+02 -1.34366287e+02 -1.39189651e+02 -1.39110229e+02 -1.39576614e+02 -1.33764267e+02 -1.26360153e+02 -1.23626846e+02 -1.25564682e+02 -1.33362930e+02 -1.37932816e+02 -1.43709671e+02 -1.39944077e+02 -1.35883453e+02 -1.34718613e+02 -1.39011047e+02 -1.40816498e+02 -1.41067947e+02 -1.36615570e+02 -1.34173080e+02 -1.34030853e+02 -1.32628006e+02 -1.32969864e+02 -1.20581322e+02 -1.11027954e+02 -1.12450684e+02 -1.25209991e+02 -1.36953690e+02 -1.32477768e+02 -1.28044647e+02 -1.28397873e+02 -1.29703461e+02 -1.21529991e+02 -1.10579361e+02 -1.10065140e+02 -1.20299110e+02 -1.31707687e+02 -1.27654053e+02 -1.27057823e+02 -1.29887558e+02 -1.36787796e+02 -1.36578842e+02 -1.32539658e+02 -1.25919952e+02 -1.27340958e+02 -1.34364868e+02 -1.36865005e+02 -1.35457245e+02 -1.33429825e+02 -1.37856003e+02 -1.30855942e+02 -1.21010399e+02 -1.17939217e+02 -1.11208961e+02 -9.97443695e+01 -8.71598892e+01 -8.40105438e+01 -8.87348938e+01 -8.65313187e+01 -1.00608025e+02 -1.06142616e+02 -1.20994911e+02 -1.29100250e+02 -1.43723541e+02 -1.42599884e+02 -1.36548981e+02 -1.32686676e+02 -1.33451462e+02 -1.34235291e+02 -1.33858047e+02 -1.35397812e+02 -1.39608612e+02 -1.27273384e+02 -1.09466385e+02 -9.70633240e+01 -9.66762772e+01 -1.08272934e+02 -1.12986839e+02 -1.17426086e+02 -1.26321053e+02 -1.14871811e+02 -1.10413399e+02 -1.02067825e+02 -1.01917709e+02 -9.89571457e+01 -9.06553421e+01 -1.03698715e+02 -1.14818642e+02 -1.19115570e+02 -1.05597168e+02 -9.92386017e+01 -1.06005875e+02 -1.19297577e+02 -1.08074326e+02 -9.67565918e+01 -9.11858215e+01 -9.98497467e+01 -1.06906883e+02 -8.95792160e+01 -7.40558319e+01 -7.98239059e+01 -1.05879700e+02 -1.17096420e+02 -1.00051804e+02 -8.57110062e+01 -1.05075508e+02 -1.29495361e+02 -1.14996315e+02 -8.81352768e+01 -7.50225372e+01 -8.30009079e+01 -9.11380615e+01 -8.67379456e+01 -7.56617050e+01 -6.38234138e+01 -7.17709198e+01 -9.45889587e+01 -1.14325096e+02 -1.12765007e+02 -1.07760963e+02 -1.01795975e+02 -1.04351707e+02 -1.03377968e+02 -9.69316177e+01 -8.17358704e+01 -8.41627197e+01 -1.01912743e+02 -1.05631683e+02 -9.83144989e+01 -7.82659607e+01 -7.69146347e+01 -8.49215546e+01 -8.88021851e+01 -9.67067642e+01 -9.72491150e+01 -1.06625427e+02 -1.17528458e+02 -1.21823318e+02 -1.17185066e+02 -8.27292023e+01 -5.92841911e+01 -7.79673386e+01 -1.20852692e+02 -1.23748383e+02 -8.49972076e+01 -7.02740631e+01 -9.21611938e+01 -1.05481186e+02 -9.13671875e+01 -8.16383362e+01 -8.82111893e+01 -1.06828094e+02 -9.58550720e+01 -8.16435013e+01 -7.13756790e+01 -8.27976990e+01 -9.83770752e+01 -9.87559814e+01 -9.66680450e+01 -7.87681351e+01 -6.72837143e+01 -6.65175781e+01 -8.46618347e+01 -8.37003021e+01 -4.36447220e+01 -1.63861637e+01 -2.39706402e+01 -5.96507111e+01 -6.07320557e+01 -4.47424202e+01 -6.25139236e+01 -1.02529984e+02 -1.20763008e+02 -9.69264374e+01 -7.51049271e+01 -7.57215881e+01 -8.30932617e+01 -7.67941895e+01 -7.91222382e+01 -7.54005508e+01 -7.63171844e+01 -8.10116348e+01 -8.97423630e+01 -9.76647644e+01 -8.94150543e+01 -8.13602066e+01 -6.65340424e+01 -6.43625183e+01 -6.08350868e+01 -4.91167526e+01 -4.10138168e+01 -4.89611816e+01 -6.69594803e+01 -6.70812149e+01 -4.66585274e+01 -4.30982895e+01 -5.25904922e+01 -4.12124023e+01 3.66276932e+00 3.66063805e+01 2.02249565e+01 -2.51959724e+01 -3.79868584e+01 -2.22371788e+01 -2.07631130e+01 -4.20664673e+01 -5.99764709e+01 -6.22879562e+01 -6.77215424e+01 -6.40394516e+01 -5.53942833e+01 -5.63122139e+01 -7.35034714e+01 -8.07605743e+01 -4.80266342e+01 -2.66334248e+01 -3.89086838e+01 -6.36841240e+01 -3.96310120e+01 -1.79941692e+01 -3.68500137e+01 -8.75594711e+01 -1.18650055e+02 -1.10737602e+02 -1.04008148e+02 -9.62089691e+01 -1.01367508e+02 -9.43180237e+01 -9.63945694e+01 -7.99546280e+01 -7.48821487e+01 -7.41096115e+01 -9.12741165e+01 -7.86329727e+01 -3.01271152e+01 3.21282744e+00 1.63383484e+01 4.06070089e+00 -1.62264519e+01 -4.06920967e+01 -6.10070801e+01 -5.65442238e+01 -5.68704491e+01 -5.74504509e+01 -5.67868996e+01 -5.42212219e+01 -6.05496750e+01 -5.70372047e+01 -4.95485191e+01 -4.73247833e+01 -4.63213120e+01 -5.14520988e+01 -2.12995033e+01 7.12358093e+00 1.08319740e+01 -1.56830025e+01 -3.78650017e+01 -3.52300758e+01 -3.30676079e+01 -3.42082024e+01 -3.30983047e+01 -2.67682037e+01 -2.15615768e+01 -1.02917528e+01 6.02209902e+00 -5.78664398e+00 -2.66352444e+01 -3.84129944e+01 9.44075012e+00 4.18964119e+01 3.02492390e+01 -1.30526543e+01 -1.66770363e+01 8.07094193e+00 6.30004215e+00 -1.19486446e+01 -3.27910614e+01 -5.85995674e+00 1.22157402e+01 2.90556793e+01 3.28973618e+01 3.94342995e+00 -1.66328011e+01 -1.62998505e+01 4.19918900e+01 7.08858566e+01 4.46626968e+01 -5.30872631e+00 2.25137830e+00 3.55358009e+01 3.94822235e+01 1.58992462e+01 -1.24716787e+01 8.15087318e+00 3.04784126e+01 4.15539246e+01 2.47136784e+01 9.03835595e-01 -5.90990353e+00 1.98249779e+01 4.50816422e+01 5.39388008e+01 2.97091408e+01 -2.55595374e+00 1.08470364e+01 3.31616745e+01 4.43643341e+01 2.87361488e+01 2.52638721e+01 4.72674484e+01 3.92918930e+01 1.33413572e+01 -1.93153191e+01 -2.26649628e+01 -2.13883152e+01 -2.41385674e+00 2.41418705e+01 3.10683575e+01 2.56791592e+01 9.59262657e+00 6.50247955e+01 2.11782028e+02 2.84199432e+02 4.52165619e+02 2.04086719e+03 7.84252002e+03 1.45237881e+04 -3.12742875e+06 4.31392250e+06 -1.35223193e+04 -6.35457520e+03 -1.16841272e+03 -1.35547375e+03 4.50291992e+03 1.13168516e+04 -2.45156850e+06 19237962. -13841511. 4.60260550e+06 -3.53934157e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.97151386e+10 2395078. 3.07521055e+04 1.12800479e+04 8.32711487e+02 -4.55796387e+03 -2.03760754e+03 4.11819366e+02 1.77560577e+02 -3.68672577e+02 -5.16457947e+02 -1.53106232e+02 -1.17184639e+00 1.37484421e+02 1.42299332e+02 5.09233818e+01 1.25099020e+01 4.33229713e+01 1.18330584e+01 -4.59522896e+01 -1.07037590e+02 -3.37022247e+01 1.07091415e+02 1.84483505e+02 1.43407974e+02 4.69428406e+01 -1.41733103e+01 -7.89335430e-01 2.14338131e+01 -7.17522383e+00 -4.16404152e+01 -1.06297760e+01 6.85307770e+01 1.09840721e+02 8.48115540e+01 1.87209263e+01 -2.32344937e+00 5.29755173e+01 1.37519424e+02 1.72712982e+02 1.32485260e+02 1.38779114e+02 1.83205795e+02 1.49943344e+02 5.90430412e+01 -1.43750172e+01 7.47361069e+01 2.21202728e+02 2.70717987e+02 1.92497696e+02 1.11710182e+02 6.48957596e+01 5.57327995e+01 6.35832634e+01 7.15682297e+01 5.61944504e+01 7.66071320e+01 1.83423950e+02 2.70607483e+02 2.41677368e+02 1.37990509e+02 7.47872543e+01 1.18269798e+02 1.90579178e+02 2.19827774e+02 1.58222183e+02 1.35174454e+02 1.58708069e+02 1.38653976e+02 7.42214584e+01 4.03259563e+00 2.41418209e+01 1.47170578e+02 1.82532227e+02 1.38189636e+02 4.41762505e+01 5.85838509e+01 1.33002274e+02 1.21667564e+02 7.80382004e+01 4.22939415e+01 8.62528305e+01 1.83435333e+02 2.27762146e+02 1.94276184e+02 9.66515503e+01 4.27764206e+01 6.82704544e+01 1.15312592e+02 1.00409668e+02 4.99618645e+01 5.60208702e+01 1.22398170e+02 1.50924332e+02 8.30028076e+01 6.60068095e-01 2.51337910e+00 1.01010880e+02 1.83876541e+02 1.84976212e+02 1.26309349e+02 1.12369576e+02 1.27139427e+02 7.83988037e+01 -9.78406715e+00 -5.37243919e+01 3.37740402e+01 1.63160721e+02 2.32652557e+02 1.90465775e+02 1.20657494e+02 4.20746841e+01 -4.18528986e+00 1.14993467e+01 3.07823582e+01 3.69054375e+01 5.28822365e+01 1.30714996e+02 1.99739197e+02 1.56707687e+02 3.84406471e+01 -1.25408382e+01 4.03268280e+01 1.59955292e+02 2.08991806e+02 1.64279663e+02 1.14820290e+02 1.03718864e+02 1.17981728e+02 7.36950531e+01 -1.69118500e+01 -1.40668554e+01 7.36406326e+01 1.67937500e+02 1.59673187e+02 1.10571381e+02 6.58790283e+01 6.25640297e+01 7.51793976e+01 1.14734070e+02 1.36330444e+02 8.95024796e+01 6.67156906e+01 1.12085106e+02 1.55342316e+02 1.70225967e+02 1.43678635e+02 1.42832138e+02 1.72417206e+02 1.74816544e+02 1.51984955e+02 1.17992142e+02 9.60927124e+01 1.31774261e+02 1.49515656e+02 1.43950455e+02 1.14926903e+02 1.51220520e+02 2.56043121e+02 3.04005646e+02 2.24254303e+02 1.32217575e+02 1.18607018e+02 1.71860291e+02 2.02592239e+02 2.04410187e+02 2.08266068e+02 2.45565872e+02 2.87245178e+02 3.01479156e+02 2.75374603e+02 2.07499847e+02 1.65922806e+02 2.08143631e+02 2.37340942e+02 2.24409225e+02 1.72649139e+02 2.08449661e+02 2.85463715e+02 2.87096161e+02 2.49424591e+02 2.14318115e+02 2.64480408e+02 3.49541687e+02 3.98002411e+02 3.43928741e+02 2.51719971e+02 1.98437424e+02 2.07758255e+02 1.99065094e+02 1.73492020e+02 1.90786392e+02 2.54269745e+02 3.25589447e+02 3.07843201e+02 2.53243729e+02 1.61053421e+02 1.27809097e+02 1.47783249e+02 2.13757004e+02 2.72189209e+02 2.72516724e+02 2.93499268e+02 3.14667603e+02 3.08451691e+02 2.37947769e+02 1.68569977e+02 1.98871841e+02 3.02462799e+02 3.59520508e+02 3.02163910e+02 1.96568130e+02 1.58895477e+02 2.04924454e+02 2.58703491e+02 2.37778488e+02 1.99193069e+02 2.10509537e+02 2.65600922e+02 2.79651367e+02 2.31905563e+02 1.56277802e+02 1.41696396e+02 1.80189529e+02 2.24823166e+02 2.23436127e+02 2.05003906e+02 2.07243164e+02 2.38017441e+02 2.24815109e+02 1.86918533e+02 1.75790207e+02 1.76651566e+02 2.26304108e+02 2.35881119e+02 2.31792084e+02 2.25897079e+02 2.27317993e+02 2.61315369e+02 2.36180420e+02 1.93461411e+02 1.74263504e+02 1.98741135e+02 2.87929962e+02 3.30800995e+02 3.24789490e+02 2.27211243e+02 1.78964981e+02 1.72987411e+02 2.12502640e+02 2.38560684e+02 2.15120270e+02 2.26236450e+02 2.50807312e+02 2.67305786e+02 2.38277390e+02 2.13603714e+02 2.55696548e+02 3.09259399e+02 3.00402802e+02 2.75950317e+02 2.61557251e+02 2.79496643e+02 3.13260376e+02 2.76052856e+02 2.51146072e+02 2.26506836e+02 2.46903183e+02 2.88764801e+02 3.05254761e+02 3.17400452e+02 2.81054443e+02 2.61661011e+02 2.53353592e+02 2.87238068e+02 2.90463959e+02 2.86139832e+02 2.92559540e+02 3.19744293e+02 3.30845520e+02 2.87152985e+02 2.60634064e+02 2.59812317e+02 2.96047699e+02 2.85254120e+02 2.73543304e+02 2.56336456e+02 2.48771011e+02 2.56039886e+02 2.53133163e+02 2.90543518e+02 3.06628174e+02 3.16827972e+02 3.11966064e+02 3.00010529e+02 2.86889557e+02 2.49233887e+02 2.34248505e+02 2.49873047e+02 3.04105499e+02 3.21529541e+02 3.10753937e+02 2.90864746e+02 2.88592560e+02 2.79276947e+02 2.38685120e+02 2.18492722e+02 2.34759003e+02 2.85743652e+02 3.03436920e+02 2.83517609e+02 2.59590424e+02 2.57751740e+02 2.82611206e+02 2.82679047e+02 2.86600983e+02 2.59118591e+02 2.51072800e+02 2.49991165e+02 2.76423126e+02 2.84196198e+02 2.63947510e+02 2.43729080e+02 2.59904602e+02 2.93306488e+02 2.86601013e+02 2.66247681e+02 2.61628540e+02 2.80089233e+02 2.82078247e+02 2.57446747e+02 2.46000259e+02 2.56387085e+02 2.87355804e+02 2.85177307e+02 2.76721191e+02 2.65661530e+02 2.75351990e+02 2.88877960e+02 2.84790131e+02 2.88665649e+02 2.71996552e+02 2.70717499e+02 2.65573669e+02 2.78501587e+02 2.81828064e+02 2.74762543e+02 2.65293732e+02 2.74841553e+02 2.95243622e+02 2.98521973e+02 2.97588226e+02 3.07996094e+02 3.31983032e+02 3.25813507e+02 3.05973389e+02 2.99093719e+02 3.10453918e+02 3.28069763e+02 3.08821136e+02 3.00429565e+02 2.87868896e+02 2.80691467e+02 2.79258240e+02 2.89032532e+02 3.16995880e+02 3.21640594e+02 3.03748993e+02 2.84426208e+02 2.95649078e+02 3.18687378e+02 3.32994415e+02 3.16672699e+02 3.05592529e+02 3.07435730e+02 3.14443298e+02 3.23318481e+02 3.34785645e+02 3.53379364e+02 3.48539459e+02 3.31211243e+02 3.23655945e+02 3.30408264e+02 3.39556335e+02 3.22281219e+02 3.12205688e+02 3.06971466e+02 3.08190948e+02 3.11090698e+02 3.18615356e+02 3.40951508e+02 3.44843140e+02 3.28007141e+02 3.00954620e+02 2.95613922e+02 3.17512299e+02 3.35302185e+02 3.35534088e+02 3.22651459e+02 3.15674866e+02 3.19931061e+02 3.30139282e+02 3.35873810e+02 3.29319885e+02 3.13682373e+02 3.09033264e+02 3.15073151e+02 3.24412231e+02 3.34082214e+02 3.32491882e+02 3.27133148e+02 3.15993042e+02 3.05123199e+02 3.01682953e+02 3.08381348e+02 3.22123169e+02 3.29644897e+02 3.22839081e+02 3.13660553e+02 3.13896973e+02 3.22513000e+02 3.29994385e+02 3.26231262e+02 3.18132538e+02 3.12062897e+02 3.11882446e+02 3.15735901e+02 3.18824036e+02 3.20279633e+02 3.16932770e+02 3.15346039e+02 3.14290344e+02 3.15626251e+02 3.16357544e+02 3.14869507e+02 3.13601349e+02 3.12803955e+02 3.13121826e+02 3.13613647e+02 3.14030548e+02 3.14054199e+02 3.13565552e+02 3.13467316e+02 3.14882294e+02 3.16378662e+02 3.15725433e+02 3.12745850e+02 3.10253204e+02 3.10438416e+02 3.12050690e+02 3.12413239e+02 3.10178375e+02 3.08605286e+02 3.07420715e+02 3.10555206e+02 3.13297974e+02 3.16552826e+02 3.17389954e+02 3.15475067e+02 3.12523041e+02 3.07709747e+02 3.08051147e+02 3.10618439e+02 3.16745819e+02 3.16863342e+02 3.11370544e+02 3.04243835e+02 3.06546204e+02 3.13563751e+02 3.17206299e+02 3.10793640e+02 3.00691528e+02 3.00225311e+02 3.07590332e+02 3.19528442e+02 3.18916931e+02 3.09295624e+02 2.99952057e+02 2.92630127e+02 3.03453827e+02 3.07933533e+02 3.13790649e+02 3.14345490e+02 3.16937653e+02 3.19359375e+02 3.12137299e+02 3.14042175e+02 3.21075897e+02 3.20536621e+02 3.10357697e+02 2.92081146e+02 2.84675720e+02 2.94809357e+02 3.20107300e+02 3.40391602e+02 3.38757965e+02 3.12013397e+02 2.83966278e+02 2.74655670e+02 2.93341461e+02 3.17129181e+02 3.22913300e+02 3.07113831e+02 2.86352386e+02 2.91922150e+02 3.07296478e+02 3.21631134e+02 3.22962769e+02 3.16355011e+02 3.03976685e+02 2.87040375e+02 2.88376526e+02 3.04232880e+02 3.28229095e+02 3.34202759e+02 3.15223572e+02 2.88907684e+02 2.87777557e+02 3.11073944e+02 3.27039093e+02 3.21890045e+02 3.05339783e+02 2.97266113e+02 2.90436157e+02 2.97805817e+02 3.05368439e+02 3.02205750e+02 2.97614380e+02 2.86835022e+02 2.98593170e+02 3.12063995e+02 3.26491272e+02 3.36767609e+02 3.20391724e+02 3.09509796e+02 2.82756744e+02 2.72932312e+02 2.84898346e+02 3.10216217e+02 3.15600342e+02 2.90625671e+02 2.61143799e+02 2.66957642e+02 2.84323029e+02 3.15809113e+02 3.24322815e+02 3.08073059e+02 2.89224487e+02 2.78306030e+02 3.06275818e+02 3.27521576e+02 3.49639252e+02 3.46673126e+02 3.17101105e+02 3.20983185e+02 3.31402344e+02 3.63239471e+02 3.63229431e+02 3.51306854e+02 3.28021790e+02 2.83860260e+02 2.65620483e+02 2.75956665e+02 3.14372467e+02 3.27242096e+02 3.01631744e+02 2.62312012e+02 2.67408295e+02 3.04678955e+02 3.39382935e+02 3.23066040e+02 2.81661560e+02 2.40834351e+02 2.37945755e+02 2.72860870e+02 3.15025421e+02 3.25015533e+02 3.25193542e+02 3.13916656e+02 2.98715607e+02 2.70582092e+02 2.65985016e+02 2.80925171e+02 2.90547028e+02 2.72151672e+02 2.25976135e+02 2.05980820e+02 2.41288940e+02 2.96224121e+02 3.21739075e+02 2.88106934e+02 2.34922760e+02 2.22305893e+02 2.51237869e+02 3.03625488e+02 3.10903870e+02 2.81853760e+02 2.62755005e+02 2.52161301e+02 2.81943298e+02 2.94841339e+02 2.86443207e+02 2.76382965e+02 2.43176971e+02 2.52821609e+02 2.54401947e+02 3.03813080e+02 3.55573425e+02 3.81178741e+02 3.73692322e+02 3.12913879e+02 2.62275391e+02 2.43868591e+02 3.15109253e+02 4.73255951e+02 4.47115936e+02 2.24484467e+02 2.41858545e+03 6.32164014e+03 -273986432. -843729088. -68009928. -263046736. 797366976. -40158668. -265194240. -68327544. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 615633472. 49117268. -1.01545195e+04 -3.84925146e+03 3.53379395e+03 2.85891797e+03 1.03630640e+03 8.93999512e+02 5.40466431e+02 3.98834564e+02 2.75342712e+02 2.38374710e+02 2.76915710e+02 2.98570923e+02 2.58205292e+02 1.62341202e+02 1.58696503e+02 2.02808167e+02 2.69435760e+02 2.57574890e+02 1.88951797e+02 1.20123184e+02 1.10282967e+02 1.64745285e+02 2.57918915e+02 2.70400421e+02 2.03140137e+02 1.22751396e+02 1.21330383e+02 1.84640625e+02 1.88515472e+02 1.45624496e+02 1.30172958e+02 1.71230667e+02 2.18274765e+02 2.15275513e+02 2.20216461e+02 2.45725403e+02 2.46900116e+02 1.93585800e+02 9.91311111e+01 9.11059418e+01 1.56840988e+02 2.18418472e+02 2.18591263e+02 1.49187820e+02 6.64762039e+01 7.57191772e+01 1.70138321e+02 2.97180054e+02 2.91313354e+02 1.83873962e+02 1.12882149e+02 1.00821640e+02 1.63307053e+02 1.89567429e+02 1.97862152e+02 2.04159988e+02 1.88620941e+02 1.52201569e+02 9.00591202e+01 1.05970055e+02 1.76434479e+02 1.88888138e+02 1.40334503e+02 5.07899132e+01 5.27828178e+01 1.02896492e+02 1.70136566e+02 2.08168274e+02 1.31888916e+02 3.63739281e+01 -4.33926315e+01 -7.84113526e-01 1.01461792e+02 1.38180054e+02 7.99846802e+01 2.82432041e+01 2.85008545e+01 1.26238457e+02 1.42786728e+02 1.28147903e+02 7.10115433e+01 8.43443375e+01 7.79096069e+01 5.51461487e+01 8.41239395e+01 1.48983795e+02 1.75937668e+02 1.00774467e+02 -1.64292583e+01 -2.96830025e+01 1.35152817e+01 9.91543503e+01 1.54257401e+02 1.53027039e+02 8.50662842e+01 3.19688339e+01 3.80704269e+01 1.43521927e+02 1.78386017e+02 1.09563751e+02 1.90042400e+01 2.85941010e+01 1.28387619e+02 1.86219025e+02 1.73551712e+02 1.60249710e+02 1.37455246e+02 9.75474854e+01 1.69692688e+01 2.30423431e+01 8.75884857e+01 1.38927933e+02 1.30190811e+02 6.13622093e+01 5.23632851e+01 9.75969925e+01 1.33121429e+02 1.68480026e+02 1.56376907e+02 9.16341324e+01 3.09117451e+01 7.84725094e+00 1.12638199e+02 1.57482895e+02 1.16600876e+02 8.26537170e+01 7.46449432e+01 1.23077301e+02 1.08721886e+02 1.00020126e+02 1.29917557e+02 1.41935638e+02 1.20000999e+02 2.23291912e+01 2.17294197e+01 9.53916092e+01 1.49079590e+02 1.44402634e+02 7.13434067e+01 7.89094391e+01 1.31289581e+02 1.57733185e+02 1.89693405e+02 1.41464737e+02 7.59741440e+01 4.71449661e+00 1.11872978e+01 8.21567841e+01 9.46727448e+01 6.99471283e+01 6.58665771e+01 9.32878342e+01 1.44845123e+02 1.77514587e+02 1.94613312e+02 1.95797119e+02 1.46856796e+02 1.00930878e+02 7.54504967e+00 -1.77045593e+01 -1.07724524e+01 4.53225555e+01 4.31596222e+01 -1.31714878e+01 -7.88331299e+01 -3.71568871e+01 5.93835983e+01 1.39638336e+02 1.44963440e+02 4.26473122e+01 -1.98355331e+01 -1.15665636e+01 5.37464485e+01 7.43532639e+01 2.76077423e+01 3.14422531e+01 2.06264610e+01 1.50378199e+01 1.41351347e+01 7.40611954e+01 1.47967697e+02 1.58005234e+02 1.25191513e+02 6.43905334e+01 1.99249706e+01 8.20845318e+00 2.30321712e+01 2.07917233e+01 -3.72086945e+01 -1.00384445e+02 -7.94017792e+01 1.83647022e+01 1.09550407e+02 1.27089539e+02 4.87160263e+01 2.28079453e+01 1.35286379e+01 9.14550247e+01 7.64858932e+01 2.56558895e+01 -4.66968384e+01 -9.76224976e+01 -1.08383904e+02 -1.56992630e+02 -1.14365349e+02 -3.25295868e+01 3.26190834e+01 2.55493755e+01 -5.11511383e+01 -5.65768738e+01 -2.50606298e+00 6.65481949e+01 1.32941650e+02 8.61001663e+01 -3.31687126e+01 -1.39286102e+02 -1.00184372e+02 1.57634096e+01 3.49846878e+01 -2.22611237e+01 -5.05429802e+01 -4.79013443e+01 1.02402508e+00 3.33135872e+01 6.94940796e+01 6.40495300e+01 4.29147606e+01 -1.48314152e+01 -9.66802826e+01 -1.22078712e+02 -9.66385803e+01 -4.98257217e+01 -4.40025673e+01 -4.72445641e+01 -1.33688812e+01 3.54290657e+01 4.95407333e+01 3.05187588e+01 -2.51063023e+01 -4.49050140e+01 -5.59773216e+01 -3.79339981e+01 -4.87170362e+00 1.46589146e+01 6.47142029e+00 -2.48731556e+01 -5.07936783e+01 -3.78246002e+01 -2.42311554e+01 -3.02701721e+01 -5.02981491e+01 -6.29797134e+01 -4.53382301e+01 -3.41367912e+01 -2.50704041e+01 -2.31143913e+01 -3.06087513e+01 -1.77268658e+01 -2.77274380e+01 -3.15015087e+01 -5.09430542e+01 -4.25925407e+01 -2.98714466e+01 -3.11148357e+01 -3.91482925e+01 -4.37358627e+01 -3.04933167e+01 -3.08968334e+01 -2.42432346e+01 -4.45158195e+00 -1.64564686e+01 -3.28012466e+01 -5.32727356e+01 -3.13447762e+01 -2.98819942e+01 -3.16111279e+01 -3.02128639e+01 -2.82856617e+01 -2.89170513e+01 -3.54685898e+01 -3.36155434e+01 -3.94915047e+01 -4.81590080e+01 -5.68757591e+01 -4.85641479e+01 -5.23042755e+01 -3.15631523e+01 -4.60750542e+01 -4.13110924e+01 -5.50433998e+01 -3.36993828e+01 -3.79202881e+01 -4.09974251e+01 -7.06885452e+01 -9.06889191e+01 -1.07955269e+02 -9.70666962e+01 -8.12462921e+01 -6.83515854e+01 -6.86285400e+01 -7.08136215e+01 -8.67274780e+01 -9.35860977e+01 -8.11425400e+01 -7.92928314e+01 -8.65742111e+01 -8.89805222e+01 -7.05618744e+01 -5.99859390e+01 -7.15084152e+01 -8.33811722e+01 -8.32241287e+01 -9.25458450e+01 -1.06278503e+02 -1.17092384e+02 -1.19402565e+02 -1.10137001e+02 -9.55092239e+01 -8.74214249e+01 -6.18971939e+01 -5.41594849e+01 -4.26473656e+01 -6.96744385e+01 -8.85389404e+01 -1.06918068e+02 -1.22254349e+02 -1.24604904e+02 -9.54777832e+01 -5.80649681e+01 -6.35232353e+01 -9.45310135e+01 -1.24296753e+02 -1.22776764e+02 -1.18119080e+02 -1.31213806e+02 -1.37635178e+02 -1.40037521e+02 -1.26820206e+02 -1.34833710e+02 -1.36110001e+02 -1.28028214e+02 -1.18030197e+02 -1.29903107e+02 -1.61533752e+02 -1.95334549e+02 -2.00393967e+02 -1.79661240e+02 -1.44794998e+02 -1.47280899e+02 -1.61514755e+02 -1.60585281e+02 -1.50950089e+02 -1.36479462e+02 -1.70107666e+02 -1.89931732e+02 -2.04443039e+02 -1.71374786e+02 -1.44753006e+02 -1.22507484e+02 -1.47505997e+02 -1.91096771e+02 -2.33905090e+02 -2.04059464e+02 -1.50371521e+02 -1.28882584e+02 -1.46364502e+02 -1.67271545e+02 -1.72388931e+02 -1.92127945e+02 -2.11362564e+02 -1.98893036e+02 -1.68181274e+02 -1.45607376e+02 -1.41088516e+02 -1.56548859e+02 -1.78677567e+02 -2.06978058e+02 -2.01816116e+02 -1.79061432e+02 -1.57442688e+02 -1.52395782e+02 -1.53623718e+02 -1.51400391e+02 -1.41485153e+02 -1.31419952e+02 -1.31576202e+02 -1.49858597e+02 -1.67818787e+02 -1.62719131e+02 -1.52300278e+02 -1.54519958e+02 -1.67958649e+02 -1.68643250e+02 -1.54924133e+02 -1.76186813e+02 -1.94101746e+02 -1.91982513e+02 -1.52488358e+02 -1.39659531e+02 -1.63455750e+02 -1.81813293e+02 -1.91155121e+02 -2.02265778e+02 -2.18372269e+02 -2.18017685e+02 -2.22595230e+02 -2.22670029e+02 -2.17508301e+02 -1.94506622e+02 -1.89149445e+02 -1.99824173e+02 -2.02699341e+02 -1.90026352e+02 -1.87095642e+02 -1.90791809e+02 -1.91620773e+02 -2.14366180e+02 -2.33676910e+02 -2.36860321e+02 -2.07919861e+02 -1.80170624e+02 -1.87152710e+02 -1.88133865e+02 -1.93556686e+02 -1.93494171e+02 -2.03885788e+02 -1.95405670e+02 -1.75830444e+02 -1.59391205e+02 -1.60575836e+02 -1.73151718e+02 -1.91651169e+02 -1.95111649e+02 -1.89892639e+02 -1.85450623e+02 -1.96730865e+02 -1.99221771e+02 -1.70345596e+02 -1.36799271e+02 -1.36549057e+02 -1.78388062e+02 -2.16502060e+02 -2.18398560e+02 -1.79239410e+02 -9.12901764e+01 2.36047077e+01 1.65932251e+02 2.01597275e+02 1.21628937e+02 3.08367944e+03 8.28708691e+03 -92078840. -47853516. -262688832. -42032992. -545635776. 541758464. 90642192. -60858756. 37681580. 95644312. 199722080. -854541824. 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. 0. 0. 0. 0. 0. 0. 155501632. -126679384. -2.57015742e+04 -1.09068018e+04 -2.50779785e+03 2.42084229e+03 1.79721265e+03 2.64538361e+02 -6.74367752e+01 -1.90366165e+02 -2.16137787e+02 -1.95888092e+02 -1.97392807e+02 -2.17941101e+02 -2.46517532e+02 -2.48077408e+02 -2.52563171e+02 -2.53046921e+02 -2.53565857e+02 -2.39817032e+02 -2.22018707e+02 -2.39805695e+02 -2.67759766e+02 -2.75452332e+02 -2.55252548e+02 -2.42989197e+02 -2.54104492e+02 -2.57570068e+02 -2.54657257e+02 -2.46998886e+02 -2.40667892e+02 -2.39197510e+02 -2.43426743e+02 -2.58740814e+02 -2.64396606e+02 -2.68592346e+02 -2.61920074e+02 -2.79238892e+02 -3.01364990e+02 -3.06311554e+02 -2.94379364e+02 -2.79019714e+02 -2.85388428e+02 -2.92758423e+02 -2.95659912e+02 -3.00751648e+02 -3.02761414e+02 -3.06463287e+02 -3.08802673e+02 -3.09474487e+02 -3.04407532e+02 -3.01728394e+02 -3.00631622e+02 -3.06601074e+02 -3.04562103e+02 -3.00564423e+02 -3.01680908e+02 -3.05178223e+02 -3.11213470e+02 -3.10045654e+02 -3.03395050e+02 -2.90475037e+02 -2.76034241e+02 -2.69403351e+02 -2.76359467e+02 -2.87299652e+02 -2.93955261e+02 -2.84116791e+02 -2.74475769e+02 -2.79000854e+02 -2.93988770e+02 -3.09389618e+02 -3.11131958e+02 -3.10747253e+02 -3.17281250e+02 -3.28361603e+02 -3.19701904e+02 -3.01260162e+02 -2.87965088e+02 -2.93799835e+02 -3.02111115e+02 -3.00989502e+02 -3.02120605e+02 -3.02299744e+02 -3.04023224e+02 -3.04020294e+02 -3.04057159e+02 -2.98983154e+02 -2.97716583e+02 -2.96086487e+02 -3.01497437e+02 -3.00235382e+02 -2.89264618e+02 -2.76351562e+02 -2.81076630e+02 -2.92740387e+02 -3.04034546e+02 -2.99363770e+02 -2.94721527e+02 -2.88933868e+02 -2.85887085e+02 -2.92680969e+02 -3.03899231e+02 -3.07331909e+02 -3.03680634e+02 -2.92533142e+02 -2.93410736e+02 -2.96196655e+02 -3.03095276e+02 -3.07441559e+02 -3.04563873e+02 -3.06614044e+02 -3.06148987e+02 -3.09731781e+02 -3.06901428e+02 -3.06287384e+02 -3.07127777e+02 -3.03695496e+02 -2.98880920e+02 -3.00198090e+02 -3.05589233e+02 -3.11600830e+02 -3.12198425e+02 -3.12888123e+02 -3.13251221e+02 -3.13725677e+02 -3.16237488e+02 -3.15873840e+02 -3.08335907e+02 -2.99428314e+02 -2.99232574e+02 -3.04837616e+02 -3.11826538e+02 -3.15646820e+02 -3.18193542e+02 -3.17004395e+02 -3.13905670e+02 -3.12851868e+02 -3.15416046e+02 -3.15057800e+02 -3.14572998e+02 -3.13503998e+02 -3.12960785e+02 -3.12499512e+02 -3.12761963e+02 -3.13022461e+02 -3.13256866e+02 -3.12782990e+02 -3.11940704e+02 -3.11877106e+02 -3.12056549e+02 -3.11666290e+02 -3.11378754e+02 -3.11137482e+02 -3.12332947e+02 -3.13018311e+02 -3.13805878e+02 -3.13943634e+02 -3.14227325e+02 -3.15013550e+02 -3.15133270e+02 -3.14272064e+02 -3.11030151e+02 -3.09753571e+02 -3.10006470e+02 -3.11258575e+02 -3.12275269e+02 -3.12579956e+02 -3.13116180e+02 -3.13450500e+02 -3.13434235e+02 -3.13433594e+02 -3.13561646e+02 -3.13702698e+02 -3.13867218e+02 -3.13975067e+02 -3.14004364e+02 -3.13765411e+02 -3.13339783e+02 -3.13035645e+02 -3.13195496e+02 -3.13664703e+02 -3.14437256e+02 -3.14496521e+02 -3.14314728e+02 -3.14220551e+02 -3.14149536e+02 -3.13910553e+02 -3.13738434e+02 -3.13648834e+02 -3.13163910e+02 -3.13409302e+02 -3.13545441e+02 -3.13765259e+02 -3.13378357e+02 -3.13099640e+02 -3.14224243e+02 -3.14895966e+02 -3.15455292e+02 -3.14913635e+02 -3.13478210e+02 -3.10103973e+02 -3.05286865e+02 -3.03155060e+02 -3.02685455e+02 -3.04083618e+02 -3.02323456e+02 -3.05454681e+02 -3.09385620e+02 -3.14420898e+02 -3.14680756e+02 -3.14448547e+02 -3.13249268e+02 -3.12550507e+02 -3.13391724e+02 -3.15437103e+02 -3.15137848e+02 -3.14151367e+02 -3.11646881e+02 -3.11474792e+02 -3.10816925e+02 -3.16871002e+02 -3.24402008e+02 -3.22159698e+02 -3.15331543e+02 -3.07741211e+02 -3.05087067e+02 -3.02447327e+02 -2.93880646e+02 -2.89010376e+02 -2.90627045e+02 -2.95819550e+02 -3.04816162e+02 -3.03371857e+02 -3.00374023e+02 -2.96317657e+02 -2.95094818e+02 -2.98475769e+02 -2.98467651e+02 -2.98539673e+02 -2.97478119e+02 -3.00860443e+02 -3.03952698e+02 -3.02988983e+02 -2.94252319e+02 -2.82710083e+02 -2.73322449e+02 -2.69350464e+02 -2.89670868e+02 -3.09380219e+02 -3.20526764e+02 -3.11062653e+02 -2.99811584e+02 -2.99093048e+02 -2.96327393e+02 -2.97152405e+02 -2.96368286e+02 -2.99737091e+02 -3.00627258e+02 -3.02944458e+02 -3.00702484e+02 -3.00096802e+02 -3.07822205e+02 -3.21074371e+02 -3.24779633e+02 -3.16841431e+02 -3.06914459e+02 -2.99060852e+02 -2.90817200e+02 -2.89362335e+02 -2.96363525e+02 -2.97389191e+02 -2.88261292e+02 -2.88118195e+02 -2.95146088e+02 -3.03746185e+02 -3.05170898e+02 -3.01653442e+02 -2.99638092e+02 -2.96632233e+02 -2.97546173e+02 -2.94494659e+02 -2.94758728e+02 -2.95328461e+02 -3.01702576e+02 -3.02633484e+02 -3.00907532e+02 -2.85857147e+02 -2.68238281e+02 -2.71559784e+02 -2.84008331e+02 -2.98097473e+02 -2.91782776e+02 -2.90207855e+02 -2.85993958e+02 -2.80944794e+02 -2.76183502e+02 -2.74377106e+02 -2.64641571e+02 -2.59361450e+02 -2.60392334e+02 -2.78263885e+02 -2.92794617e+02 -2.94258484e+02 -2.89266602e+02 -2.98805725e+02 -3.12009094e+02 -3.15899628e+02 -3.11685364e+02 -2.97226990e+02 -2.99249115e+02 -2.95873688e+02 -2.93440674e+02 -2.85498199e+02 -2.81589355e+02 -2.83853821e+02 -2.93775238e+02 -2.91234924e+02 -2.88228119e+02 -2.84171692e+02 -2.86731812e+02 -2.83570862e+02 -2.78994049e+02 -2.63583374e+02 -2.47744766e+02 -2.48817581e+02 -2.55296951e+02 -2.65157715e+02 -2.63907898e+02 -2.73303711e+02 -2.81769562e+02 -2.75821991e+02 -2.44096176e+02 -2.23107224e+02 -2.22010910e+02 -2.49463516e+02 -2.64467285e+02 -2.60600555e+02 -2.52976501e+02 -2.52313919e+02 -2.60153229e+02 -2.48676529e+02 -2.25314499e+02 -2.16289169e+02 -2.32527603e+02 -2.58314697e+02 -2.55097198e+02 -2.53486984e+02 -2.51870575e+02 -2.54607315e+02 -2.52243301e+02 -2.42995300e+02 -2.35755341e+02 -2.29816818e+02 -2.41377121e+02 -2.47653778e+02 -2.46953308e+02 -2.18031235e+02 -1.83766373e+02 -1.78882477e+02 -2.03140442e+02 -2.32365005e+02 -2.37072479e+02 -2.46646011e+02 -2.49381485e+02 -2.41187836e+02 -2.03490814e+02 -1.77377914e+02 -1.49960342e+02 -1.47508255e+02 -1.71483612e+02 -1.98243042e+02 -2.29857986e+02 -2.05423126e+02 -1.86805771e+02 -2.11877441e+02 -2.64538055e+02 -2.88389313e+02 -2.59805084e+02 -2.30817368e+02 -2.35348145e+02 -2.41487335e+02 -2.44577972e+02 -2.45421982e+02 -2.47750000e+02 -2.49401886e+02 -2.52092865e+02 -2.52766815e+02 -2.53796234e+02 -2.51002197e+02 -2.55195694e+02 -2.49701172e+02 -2.46467514e+02 -2.22937546e+02 -2.02520691e+02 -2.04971512e+02 -2.29303818e+02 -2.60451996e+02 -2.31051926e+02 -1.92717300e+02 -2.13948166e+02 -2.75052582e+02 -2.77043549e+02 -2.05590759e+02 -1.61120270e+02 -1.86647537e+02 -2.20803177e+02 -2.04147751e+02 -1.67680313e+02 -1.57462067e+02 -1.73003296e+02 -2.02812698e+02 -2.02260269e+02 -1.99451752e+02 -2.00706024e+02 -1.99431839e+02 -2.24309296e+02 -2.45128387e+02 -2.18376373e+02 -1.63420944e+02 -1.34267441e+02 -1.48107864e+02 -1.74466858e+02 -1.46266464e+02 -1.21447243e+02 -1.13891518e+02 -1.37115814e+02 -1.71950180e+02 -1.67010330e+02 -1.63257355e+02 -1.54688599e+02 -1.70891830e+02 -1.62005844e+02 -1.36143936e+02 -1.23538094e+02 -1.24195572e+02 -1.60800842e+02 -1.78652649e+02 -1.92818039e+02 -1.90975769e+02 -1.84996002e+02 -2.31373657e+02 -2.82995697e+02 -2.67211792e+02 -1.97524673e+02 -1.41453766e+02 -1.57941696e+02 -1.85859116e+02 -1.63971878e+02 -1.24863136e+02 -1.21968292e+02 -1.47319534e+02 -1.77072205e+02 -1.86354233e+02 -1.87451996e+02 -1.88482376e+02 -1.75382324e+02 -1.70130753e+02 -1.63490997e+02 -1.46954407e+02 -1.37487579e+02 -1.44693771e+02 -1.63625656e+02 -1.77986511e+02 -1.80836014e+02 -1.78101685e+02 -2.02881866e+02 -2.32538773e+02 -1.96559570e+02 -1.26489944e+02 -9.01512451e+01 -1.31388107e+02 -1.71461395e+02 -1.91599930e+02 -1.99691422e+02 -2.04661926e+02 -1.94015152e+02 -1.81235046e+02 -1.87924606e+02 -1.84970581e+02 -1.89066071e+02 -1.82468430e+02 -1.90143295e+02 -1.91811676e+02 -1.98171951e+02 -1.79214554e+02 -1.64798721e+02 -1.72391953e+02 -1.92765991e+02 -2.01044510e+02 -1.76113220e+02 -1.51392578e+02 -1.36435730e+02 -1.13165932e+02 -7.84542542e+01 -7.43352356e+01 -9.73775253e+01 -9.89438553e+01 -2.78640137e+01 1.69244576e+01 -1.24398003e+01 -6.30478439e+01 -5.29353371e+01 -9.70722675e+00 -9.87262428e-01 -4.10615005e+01 -7.54380417e+01 -8.44134750e+01 -8.84945755e+01 -7.68705902e+01 -7.33923950e+01 -7.38388519e+01 -9.07891541e+01 -5.98832664e+01 -2.67873917e+01 -5.91718912e+00 -4.16282806e+01 -7.45683670e+01 -6.59564743e+01 -3.05098972e+01 -5.85693321e+01 -1.20250603e+02 -1.51085007e+02 -1.29120773e+02 -9.36633911e+01 -1.05858330e+02 -1.02915535e+02 -1.03858833e+02 -1.06095757e+02 -1.12055313e+02 -1.07446709e+02 -8.81566467e+01 -9.17725525e+01 -1.01806419e+02 -1.17104240e+02 -1.11292526e+02 -9.70187607e+01 -9.87938766e+01 -6.75408173e+01 -3.49928055e+01 -3.31945457e+01 -6.84310074e+01 -1.21266487e+02 -1.30823776e+02 -1.34205002e+02 -1.60275772e+02 -1.96970947e+02 -1.94270859e+02 -1.59947968e+02 -1.14640434e+02 -1.04030685e+02 -1.02639549e+02 -5.28764229e+01 -9.37106460e-02 1.41294479e+01 -2.72413635e+01 -5.72594337e+01 -5.77045097e+01 -6.50774536e+01 -8.36274261e+01 -7.95681305e+01 -9.96410294e+01 -1.34039474e+02 -1.15366425e+02 -5.71644516e+01 -1.52056866e+01 -3.07444687e+01 -2.12519417e+01 5.31844139e+01 9.68766251e+01 7.51997757e+01 -2.66825914e+00 -1.78660526e+01 7.42317963e+00 1.66220570e+01 -2.00618496e+01 -7.04703445e+01 -6.30239220e+01 -3.17390690e+01 -2.09887218e+01 -4.02435036e+01 -7.69881973e+01 -9.82588959e+01 -1.09800751e+02 -1.07456444e+02 -8.75063782e+01 -9.21393433e+01 -9.81319580e+01 -7.05833511e+01 -2.85166969e+01 -9.57037163e+00 -3.60315781e+01 -6.15903282e+01 -4.22774277e+01 -1.16574005e+02 -3.95502289e+02 -4.86237335e+02 -8.44188660e+02 -5.57575781e+03 -1.49876807e+04 -5786565. -4.53292050e+06 1.34953896e+04 6.34027637e+03 1.16379968e+03 1.34281897e+03 -4.49511426e+03 -1.19925869e+04 -2.82100025e+06 -29960634. -5.69750950e+06 5.74074778e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.60025088e+10 7.60025088e+10 3.80012544e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.97151386e+10 2395078. 2957467. -10597720. -1.29338936e+04 -2.88130054e+03 -5.60705078e+02 -3.11993579e+03 -2.63802734e+02 -3.31959045e+02 8.00898457e+00 -2.27432327e+01 -5.32476807e+01 -1.44302759e+01 9.91922379e+00 -2.58418007e+01 -7.28104401e+01 -4.36119156e+01 4.09537697e+01 7.99564133e+01 2.61473789e+01 -8.34530258e+01 -8.61532364e+01 2.23083782e+00 1.15604706e+02 1.45657593e+02 1.00496849e+02 1.11618492e+02 1.56767609e+02 1.52681503e+02 1.08766922e+02 7.20570908e+01 1.29331375e+02 2.34170563e+02 2.56930176e+02 1.73659927e+02 8.27371140e+01 3.42912216e+01 3.19846153e+01 4.84468460e+00 -3.76806030e+01 -5.48007393e+01 5.13839674e+00 1.57410660e+02 2.54001816e+02 2.18055176e+02 1.10195930e+02 2.78882866e+01 2.99603767e+01 6.99884109e+01 1.13357254e+02 9.96803207e+01 1.18693031e+02 1.47428665e+02 1.19793282e+02 2.16651497e+01 -8.35671768e+01 -6.04739685e+01 9.68601532e+01 1.58813004e+02 1.12683060e+02 1.44713068e+01 3.11124363e+01 1.23719215e+02 1.30485168e+02 5.37496681e+01 -3.69248505e+01 -1.17769470e+01 1.17195084e+02 2.10130829e+02 1.81953979e+02 1.10023392e+02 7.85050583e+01 9.64689941e+01 9.43920441e+01 4.45771408e+01 -4.03406906e+00 2.47950401e+01 6.24515533e+01 5.10019875e+01 4.39937210e+00 -1.36076679e+01 1.37684908e+01 6.25187187e+01 1.14643822e+02 1.34583328e+02 1.04305862e+02 8.08339386e+01 8.63756714e+01 3.98613091e+01 -4.07211418e+01 -7.77880707e+01 4.07506847e+00 1.36776886e+02 2.07930267e+02 1.71454590e+02 7.00384521e+01 -4.03598557e+01 -7.36500015e+01 -4.63707619e+01 -1.99993439e+01 -3.72299805e+01 -4.91855812e+00 8.69931641e+01 1.60948395e+02 1.39562164e+02 6.43088684e+01 3.91232834e+01 6.52093735e+01 1.25306175e+02 1.41930939e+02 1.01858330e+02 7.49572372e+01 7.68186188e+01 8.97685471e+01 4.88819580e+01 -3.29626770e+01 -4.63961067e+01 2.41585884e+01 1.10898170e+02 1.13529305e+02 5.73040390e+01 6.58909798e+00 2.82512689e+00 5.55308685e+01 1.15806755e+02 1.42927185e+02 1.12733025e+02 1.20114609e+02 1.62828568e+02 1.70262665e+02 1.12648201e+02 5.31969414e+01 5.63641396e+01 1.13687325e+02 1.42234604e+02 1.12671349e+02 8.46240845e+01 6.70818100e+01 9.58456268e+01 8.18175888e+01 4.12453880e+01 2.27071609e+01 8.78774414e+01 2.19995438e+02 2.82217407e+02 2.35573624e+02 1.53481323e+02 1.32807144e+02 1.53361099e+02 1.85092636e+02 1.71456848e+02 1.75404755e+02 2.09392136e+02 2.68148468e+02 2.82894104e+02 2.21678589e+02 1.08337708e+02 5.08460922e+01 1.18716156e+02 1.85527298e+02 1.91264374e+02 1.57100998e+02 1.90971298e+02 2.73118378e+02 2.63269897e+02 1.88215225e+02 1.13679817e+02 1.64839691e+02 2.77400085e+02 3.45245331e+02 3.04782806e+02 2.25139359e+02 1.79068680e+02 1.80381409e+02 1.64490173e+02 1.49711227e+02 1.68434952e+02 2.35304214e+02 3.10327240e+02 2.66626465e+02 1.97045914e+02 1.30634567e+02 1.46117645e+02 1.84697937e+02 2.20257050e+02 2.38742630e+02 2.45831696e+02 2.69703918e+02 3.07189728e+02 2.81232300e+02 2.11266373e+02 1.44692245e+02 1.68146439e+02 2.51036209e+02 2.97062103e+02 2.76626709e+02 2.07234543e+02 1.81414505e+02 1.87002472e+02 1.80632065e+02 1.16916183e+02 9.23435440e+01 1.40401932e+02 2.26206924e+02 2.45874191e+02 2.16012985e+02 1.51921555e+02 1.24229355e+02 1.34157379e+02 1.66197189e+02 1.95181564e+02 1.93921097e+02 2.17548569e+02 2.46705322e+02 2.25879639e+02 1.79427979e+02 1.61080688e+02 1.68472855e+02 2.13682709e+02 2.19844193e+02 2.07756668e+02 1.92002701e+02 1.90403091e+02 2.18492630e+02 1.97770279e+02 1.64373154e+02 1.43069595e+02 1.42497162e+02 1.99545258e+02 2.33082870e+02 2.03057388e+02 1.41479477e+02 1.32327530e+02 1.86484512e+02 2.38244293e+02 2.35473785e+02 1.99988464e+02 1.99546265e+02 2.25849960e+02 2.35738800e+02 2.00116745e+02 1.82973801e+02 2.11982117e+02 2.34004211e+02 1.99167511e+02 1.82082230e+02 2.01682037e+02 2.23572327e+02 2.52118317e+02 2.31455933e+02 2.56062195e+02 2.61098724e+02 2.62475403e+02 2.62424805e+02 2.81204834e+02 2.94912659e+02 2.51135834e+02 2.26789291e+02 2.16764359e+02 2.54194168e+02 2.40758453e+02 2.41378128e+02 2.62636505e+02 2.96311615e+02 3.02995117e+02 2.46232773e+02 2.09208832e+02 2.05117950e+02 2.53922302e+02 2.72786224e+02 2.68247894e+02 2.51759232e+02 2.44102478e+02 2.76525482e+02 2.63296997e+02 2.42946350e+02 1.92253754e+02 1.73916595e+02 1.85503311e+02 2.22922318e+02 2.53943924e+02 2.34299530e+02 2.06843246e+02 1.93661484e+02 2.12518372e+02 2.00796051e+02 2.02730865e+02 2.33269165e+02 2.64889038e+02 2.65892853e+02 2.10121948e+02 1.97930237e+02 2.22915894e+02 2.62825043e+02 2.50442657e+02 2.26695007e+02 2.19860840e+02 2.27670898e+02 2.48738602e+02 2.43087372e+02 2.56548248e+02 2.36604675e+02 2.30055023e+02 2.28751572e+02 2.46999939e+02 2.54692368e+02 2.38685333e+02 2.20482056e+02 2.20190491e+02 2.13850952e+02 1.80512253e+02 1.64754807e+02 1.69656525e+02 1.88864517e+02 1.89450928e+02 1.76162338e+02 1.66506531e+02 1.82246094e+02 2.10764938e+02 2.26512100e+02 2.26281723e+02 2.36185684e+02 2.46691681e+02 2.69699860e+02 2.73640991e+02 2.79666107e+02 2.59365570e+02 2.46784897e+02 2.42627884e+02 2.50857269e+02 2.45711227e+02 2.35216980e+02 2.23965057e+02 2.27406677e+02 2.29735184e+02 2.13851151e+02 1.99304810e+02 2.08870972e+02 2.34004532e+02 2.42553635e+02 2.42185944e+02 2.59075989e+02 2.74260101e+02 2.84135071e+02 2.63452820e+02 2.63508667e+02 2.58951050e+02 2.48383865e+02 2.47150909e+02 2.61921265e+02 2.93642059e+02 2.99144989e+02 2.73718964e+02 2.49394440e+02 2.52876312e+02 2.70564117e+02 2.85703888e+02 2.75480347e+02 2.63390594e+02 2.49316513e+02 2.51392365e+02 2.64723389e+02 2.76139160e+02 2.92879730e+02 2.94113983e+02 2.94904083e+02 2.96793762e+02 2.98607788e+02 2.96705444e+02 2.77611176e+02 2.74917419e+02 2.75470703e+02 2.76110168e+02 2.79149231e+02 2.89027557e+02 3.15915131e+02 3.23031281e+02 3.04939545e+02 2.70029480e+02 2.53310959e+02 2.73537354e+02 2.99795990e+02 2.99539795e+02 2.72194305e+02 2.44671692e+02 2.50745590e+02 2.76418823e+02 2.92687714e+02 2.92548584e+02 2.75820526e+02 2.77688293e+02 2.86715637e+02 2.95652252e+02 2.96440552e+02 2.84935303e+02 2.84670868e+02 2.90858307e+02 2.95894958e+02 2.95093903e+02 2.88165863e+02 2.91775940e+02 2.92276917e+02 2.81299072e+02 2.68716217e+02 2.69110321e+02 2.89679413e+02 3.03318176e+02 2.99385895e+02 2.83985474e+02 2.74767426e+02 2.77623108e+02 2.87213684e+02 2.92360474e+02 2.93081360e+02 2.85033936e+02 2.84609955e+02 2.85046143e+02 2.87987823e+02 2.89943176e+02 2.86066925e+02 2.83360626e+02 2.78762604e+02 2.79751862e+02 2.82271881e+02 2.86177795e+02 2.91051331e+02 2.91989197e+02 2.88478241e+02 2.82183868e+02 2.79636841e+02 2.82304138e+02 2.87053925e+02 2.88305145e+02 2.85159546e+02 2.82785217e+02 2.83339020e+02 2.85370087e+02 2.85922241e+02 2.85682159e+02 2.85517456e+02 2.85638336e+02 2.85423859e+02 2.84713654e+02 2.83827271e+02 2.83386719e+02 2.82262726e+02 2.81857819e+02 2.82995911e+02 2.85621796e+02 2.86964386e+02 2.84232574e+02 2.81145508e+02 2.81872437e+02 2.86582428e+02 2.91960114e+02 2.90510101e+02 2.83939606e+02 2.81311707e+02 2.83963531e+02 2.91083557e+02 2.90185333e+02 2.83498505e+02 2.78330536e+02 2.73386200e+02 2.78650848e+02 2.76993774e+02 2.80417847e+02 2.79821503e+02 2.78159485e+02 2.75752075e+02 2.70555664e+02 2.75892273e+02 2.81469238e+02 2.89889343e+02 2.85858856e+02 2.74437775e+02 2.63055908e+02 2.70016327e+02 2.83905640e+02 2.94492249e+02 2.95257568e+02 2.86086151e+02 2.81058563e+02 2.77641663e+02 2.82314148e+02 2.78703186e+02 2.72280090e+02 2.63002960e+02 2.54596756e+02 2.56892487e+02 2.72437592e+02 2.85202728e+02 2.85786102e+02 2.77799683e+02 2.70115814e+02 2.58413513e+02 2.53426270e+02 2.69844543e+02 2.96929962e+02 3.06450073e+02 2.88543213e+02 2.63311249e+02 2.62678223e+02 2.87848206e+02 3.14312592e+02 3.09935089e+02 2.77517151e+02 2.44597458e+02 2.32437363e+02 2.51638596e+02 2.69993042e+02 2.68556885e+02 2.59612701e+02 2.50768326e+02 2.67617279e+02 2.65021637e+02 2.69557373e+02 2.76746796e+02 2.82784882e+02 2.79342621e+02 2.57709351e+02 2.60491180e+02 2.86752197e+02 3.16462982e+02 3.11552612e+02 2.67021332e+02 2.33931549e+02 2.45534714e+02 2.82488251e+02 3.07821045e+02 3.05640472e+02 2.70536926e+02 2.37672775e+02 2.22212738e+02 2.51149673e+02 2.66901367e+02 2.82541290e+02 2.80861969e+02 2.77831451e+02 2.83351318e+02 2.82110199e+02 3.03883759e+02 3.15064148e+02 3.15399689e+02 2.98757416e+02 2.62524811e+02 2.47449203e+02 2.69427490e+02 3.02948639e+02 3.14848175e+02 2.89378479e+02 2.55040726e+02 2.56633331e+02 2.83582550e+02 3.17408478e+02 3.22461243e+02 2.81689636e+02 2.46570923e+02 2.35855026e+02 2.69308380e+02 2.97422882e+02 2.88706543e+02 2.65597565e+02 2.34098297e+02 2.28586578e+02 2.32068985e+02 2.52276443e+02 2.82567169e+02 2.84824158e+02 2.52780563e+02 1.99875748e+02 1.83530914e+02 2.20843750e+02 2.62575317e+02 2.87354462e+02 2.65884521e+02 2.28769806e+02 2.09296310e+02 2.18335205e+02 2.49670609e+02 2.47180191e+02 2.25511444e+02 2.02177704e+02 1.99897736e+02 2.37362503e+02 2.62668701e+02 2.56731934e+02 2.28718018e+02 1.84717148e+02 1.85440414e+02 1.86159195e+02 2.07893326e+02 2.30022964e+02 2.43159119e+02 2.50373718e+02 2.15963364e+02 1.91044098e+02 2.00128998e+02 2.30063019e+02 2.62272491e+02 2.39519272e+02 2.00317520e+02 1.75216919e+02 2.12315552e+02 2.85462433e+02 3.26751251e+02 2.87088928e+02 2.26703400e+02 1.99877365e+02 2.70236053e+02 3.70072601e+02 4.39355621e+02 6.81389038e+02 8.51772522e+02 2.55379761e+03 3.56217065e+03 9.97904907e+02 9.31182922e+02 8.04269653e+02 6.00746338e+02 3.67025665e+02 8.74381409e+02 -3.92753735e+03 -1.25673594e+04 -265194240. -68327544. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 615633472. 49117268. -281170432. 72323480. 3.02630352e+04 1.09305322e+04 3.68754663e+03 8.72170227e+02 4.26080139e+02 3.66936554e+02 3.29763092e+02 2.66050903e+02 1.64201294e+02 1.26841728e+02 1.45445953e+02 2.19064011e+02 2.60577850e+02 2.49356079e+02 1.88054794e+02 1.12320175e+02 1.10044350e+02 1.34105942e+02 1.60042145e+02 1.60046814e+02 1.55977264e+02 1.81051453e+02 1.46645630e+02 1.53495300e+02 2.13655655e+02 2.58125977e+02 2.17643188e+02 1.00286827e+02 4.31003380e+01 1.14978378e+02 2.07667572e+02 2.63119049e+02 2.31008926e+02 1.18421104e+02 2.86051788e+01 -1.75811462e+01 7.43480148e+01 1.34376938e+02 1.40528900e+02 7.32123642e+01 3.61994629e+01 6.74405136e+01 7.22254333e+01 1.14250610e+02 1.58111679e+02 1.78679504e+02 1.37792404e+02 1.11689739e+01 4.57181215e+00 9.98477707e+01 2.27419373e+02 2.55006866e+02 1.56645889e+02 5.48956833e+01 5.57856598e+01 1.31268723e+02 1.63192871e+02 9.76155319e+01 -1.71833935e+01 -5.95154610e+01 -1.77279644e+01 1.08698143e+02 1.95137741e+02 1.91159531e+02 1.10982033e+02 7.67553186e+00 -6.31629791e+01 -1.00200401e+02 -6.66492386e+01 -5.81325054e+00 6.61784439e+01 9.65250626e+01 7.50841751e+01 7.84402313e+01 1.53160461e+02 2.25436417e+02 2.28966370e+02 1.34778793e+02 6.64955750e+01 7.21183624e+01 1.14846680e+02 1.77208908e+02 2.20022491e+02 1.79529510e+02 7.31360092e+01 1.18016548e+01 7.71080551e+01 1.54438553e+02 1.38849792e+02 8.71536865e+01 7.52369614e+01 1.05578438e+02 7.93703918e+01 8.70928040e+01 1.26089127e+02 1.57803421e+02 1.30942490e+02 1.65943336e+01 1.39197311e+01 1.12976387e+02 2.50231323e+02 2.97253082e+02 2.02604462e+02 1.02096680e+02 4.68475342e+01 7.47323685e+01 1.08920868e+02 1.16879845e+02 8.46955338e+01 2.81245384e+01 -3.77286673e+00 5.58234520e+01 1.60061935e+02 1.96284897e+02 1.60593292e+02 1.20766220e+02 1.12637161e+02 5.97168655e+01 5.96294403e+01 1.45391754e+02 2.51394180e+02 2.51326141e+02 1.17356346e+02 5.90066147e+01 1.33492798e+02 2.38130432e+02 2.46548981e+02 1.33021072e+02 2.75749607e+01 -2.72063041e+00 3.28354301e+01 1.20173714e+02 1.91578598e+02 1.74816895e+02 8.38457108e+01 1.11906490e+01 6.57389755e+01 1.64223923e+02 1.99824783e+02 1.64281281e+02 1.07322853e+02 7.34462738e+01 1.13409796e+01 -1.07639093e+01 1.66511612e+01 6.70152740e+01 7.08053207e+01 -4.88152313e+00 -3.77678032e+01 2.95196533e+01 1.71804337e+02 2.59640228e+02 2.23514908e+02 8.22932205e+01 -2.21776085e+01 -7.02288723e+00 6.37619362e+01 9.20626678e+01 6.24364319e+01 5.81509628e+01 1.37881136e+01 3.01273537e+01 4.25253334e+01 8.63792496e+01 1.52647125e+02 1.72786484e+02 1.90702499e+02 9.15148849e+01 5.42973480e+01 1.12348656e+02 1.63220200e+02 1.36852722e+02 -5.67086840e+00 -5.20006866e+01 -1.72672749e+01 5.61691132e+01 9.83919525e+01 1.02978371e+02 6.33701553e+01 4.31491699e+01 3.35991135e+01 1.06258720e+02 8.27122345e+01 3.59317055e+01 -4.38334618e+01 -1.16923645e+02 -1.70307007e+02 -2.12163788e+02 -1.38167877e+02 -1.75151482e+01 5.72042923e+01 5.40078201e+01 -1.21259537e+01 -2.40989304e+01 5.80342331e+01 1.53129105e+02 1.99288376e+02 8.79066162e+01 -7.02995987e+01 -1.46821747e+02 -1.19399765e+02 -5.42191010e+01 -2.45380898e+01 -2.86709042e+01 -4.93163795e+01 -9.49225235e+01 -6.32296028e+01 -1.48295593e+00 3.32795334e+01 -1.71835499e+01 -4.08198509e+01 -5.79568329e+01 -8.81043091e+01 -1.01970123e+02 -6.42084351e+01 -2.96850643e+01 -3.69127693e+01 -3.98736992e+01 -1.00123234e-01 5.86454544e+01 9.19155655e+01 1.02802147e+02 5.10750618e+01 7.99185896e+00 -7.27223434e+01 -9.81397018e+01 -4.13490715e+01 3.74715271e+01 5.93810120e+01 2.74261260e+00 -3.79293022e+01 -2.51178532e+01 -2.19312878e+01 -2.34464130e+01 -1.77344666e+01 -1.73921604e+01 -2.10327740e+01 -2.11353741e+01 -2.11502800e+01 2.18800354e+00 4.16801500e+00 3.59005699e+01 2.79740105e+01 2.70695591e+01 -1.09448786e+01 -8.03187943e+00 -9.14814568e+00 -1.53219194e+01 -1.85042706e+01 -4.39693642e+01 -5.46409225e+01 -7.19226532e+01 -6.36261063e+01 -4.22629166e+01 -4.53313828e+01 -4.03795013e+01 -3.14617500e+01 -1.86521740e+01 -3.05526791e+01 -4.37624626e+01 -5.01758423e+01 -2.89735279e+01 -3.00798569e+01 -2.86253967e+01 -3.30019493e+01 -1.94822025e+01 -1.06128807e+01 -2.68065548e+00 5.01872206e+00 -1.24576979e+01 -1.82055893e+01 -3.27382507e+01 -1.86712265e+01 -1.59210348e+01 -8.88890076e+00 -1.65018826e+01 -2.67701702e+01 -5.17925682e+01 -6.08342400e+01 -4.53560371e+01 -2.75259056e+01 -3.40293274e+01 -4.88103256e+01 -5.48210945e+01 -4.67276840e+01 -5.95800819e+01 -5.97734604e+01 -5.19902840e+01 -4.28228264e+01 -4.95961304e+01 -5.60817680e+01 -4.49415703e+01 -5.82739220e+01 -8.17651596e+01 -9.47955017e+01 -7.84020157e+01 -6.88665619e+01 -7.34621353e+01 -8.72100220e+01 -8.40489426e+01 -8.63558578e+01 -8.00427780e+01 -7.97782745e+01 -8.47750702e+01 -9.93556671e+01 -9.41831284e+01 -9.18779449e+01 -7.70131607e+01 -8.16236343e+01 -6.26529121e+01 -3.41697807e+01 -4.42909546e+01 -6.43367157e+01 -1.07666260e+02 -9.85462570e+01 -9.57738800e+01 -9.86372604e+01 -9.91601257e+01 -1.15764122e+02 -1.15315750e+02 -1.12958939e+02 -1.13363663e+02 -1.21640907e+02 -1.29491180e+02 -1.12497513e+02 -1.09513596e+02 -1.09317192e+02 -1.12431335e+02 -1.01124207e+02 -1.10867363e+02 -1.17012161e+02 -1.23577713e+02 -1.39620239e+02 -1.44138245e+02 -1.37334732e+02 -1.10510574e+02 -1.03086060e+02 -1.13776588e+02 -1.30136017e+02 -1.39017761e+02 -1.36590195e+02 -1.13467819e+02 -8.71525879e+01 -9.49426804e+01 -1.17483002e+02 -1.50005157e+02 -1.49450150e+02 -1.42119995e+02 -1.26060265e+02 -1.14425423e+02 -1.08048996e+02 -1.02293243e+02 -9.65427399e+01 -1.03150162e+02 -1.09550430e+02 -1.30625336e+02 -1.28347855e+02 -1.17472191e+02 -1.14947548e+02 -1.24367508e+02 -1.24846527e+02 -1.15853073e+02 -1.10914635e+02 -1.16259575e+02 -1.21089134e+02 -1.22177773e+02 -9.88794937e+01 -6.97486572e+01 -7.36225739e+01 -1.10828331e+02 -1.49634338e+02 -1.29935379e+02 -1.01193008e+02 -9.41464157e+01 -1.11299393e+02 -1.41767822e+02 -1.28419907e+02 -1.15250130e+02 -1.03678940e+02 -1.11162964e+02 -1.23855324e+02 -1.14594139e+02 -9.08106079e+01 -7.15722733e+01 -9.53884583e+01 -1.39618973e+02 -1.56110626e+02 -1.40686752e+02 -1.32573441e+02 -1.35437149e+02 -1.46423157e+02 -1.52596588e+02 -1.35470306e+02 -1.17417877e+02 -1.20406708e+02 -1.44246170e+02 -1.71623596e+02 -1.67918045e+02 -1.62689850e+02 -1.55691498e+02 -1.79845871e+02 -2.18446701e+02 -2.31062317e+02 -1.99787430e+02 -1.67581421e+02 -1.56897995e+02 -1.62401245e+02 -1.39686371e+02 -1.38955978e+02 -1.83473068e+02 -2.34883072e+02 -2.44390289e+02 -2.06992752e+02 -1.70461044e+02 -1.71107300e+02 -1.71128036e+02 -1.96628311e+02 -2.14270645e+02 -2.06575790e+02 -1.77192841e+02 -1.47574448e+02 -1.53673172e+02 -1.52414307e+02 -1.88147614e+02 -2.33690735e+02 -2.37455444e+02 -2.14994629e+02 -1.73748688e+02 -1.50039185e+02 -1.33171783e+02 -1.34598740e+02 -1.68658951e+02 -1.81936859e+02 -1.93844635e+02 -1.93779419e+02 -1.93792419e+02 -2.03385834e+02 -2.18289093e+02 -2.26088791e+02 -2.19311920e+02 -1.84770828e+02 -7.68045807e+01 -1.12457485e+01 -1.87736626e+01 -1.27023293e+02 -1.74456238e+02 1.50590894e+03 2.66599829e+03 -7.76443054e+02 -8.38617554e+02 -8.63366455e+02 -8.57659912e+02 -8.80284668e+02 -1.10517017e+03 -8.65689941e+02 -1.30070483e+03 -1.68941882e+03 -1.06066855e+04 -2.60787363e+04 199722080. -854541824. 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. 0. 0. 0. 0. 0. 0. 155501632. -126679384. 52295800. 45721904. 927507328. 1.60011963e+04 7.28576953e+03 2.06495215e+03 9.07070847e+01 -1.47696350e+02 -2.07092026e+02 -2.01118591e+02 -2.04067368e+02 -2.03359009e+02 -2.06118805e+02 -2.01950668e+02 -1.98649475e+02 -1.98654785e+02 -2.00652435e+02 -2.20440964e+02 -2.26813766e+02 -2.23671387e+02 -2.06788498e+02 -2.10045181e+02 -2.24475098e+02 -2.45546906e+02 -2.54313004e+02 -2.52667282e+02 -2.55097321e+02 -2.57014618e+02 -2.67978668e+02 -2.73276062e+02 -2.78377167e+02 -2.76494171e+02 -2.78826385e+02 -2.77793182e+02 -2.76551483e+02 -2.76553619e+02 -2.79169006e+02 -2.82117737e+02 -2.76854950e+02 -2.72986023e+02 -2.74138367e+02 -2.78341766e+02 -2.82329163e+02 -2.84584381e+02 -2.84242767e+02 -2.77299194e+02 -2.60328918e+02 -2.47581955e+02 -2.46008179e+02 -2.53867920e+02 -2.64953949e+02 -2.71879272e+02 -2.77023682e+02 -2.70660431e+02 -2.62230530e+02 -2.61215240e+02 -2.69152893e+02 -2.76512238e+02 -2.80071930e+02 -2.84757141e+02 -2.79139038e+02 -2.68024170e+02 -2.61302551e+02 -2.55180756e+02 -2.53101288e+02 -2.53440796e+02 -2.59138000e+02 -2.65404602e+02 -2.63195282e+02 -2.65764038e+02 -2.80340057e+02 -2.86057373e+02 -2.84036987e+02 -2.74544220e+02 -2.71104950e+02 -2.73711823e+02 -2.63698425e+02 -2.49662842e+02 -2.51444550e+02 -2.59356964e+02 -2.70287506e+02 -2.51449982e+02 -2.35635162e+02 -2.33657043e+02 -2.47876816e+02 -2.55831207e+02 -2.55593750e+02 -2.53565216e+02 -2.59133667e+02 -2.59180206e+02 -2.50134964e+02 -2.40976379e+02 -2.44738297e+02 -2.60991455e+02 -2.73423309e+02 -2.78700684e+02 -2.75983032e+02 -2.72434967e+02 -2.69234222e+02 -2.79162689e+02 -2.87223602e+02 -2.82931061e+02 -2.71669464e+02 -2.70083221e+02 -2.77455658e+02 -2.83408081e+02 -2.72160339e+02 -2.64216217e+02 -2.64191711e+02 -2.75523132e+02 -2.84806549e+02 -2.88108002e+02 -2.87731079e+02 -2.87612274e+02 -2.85536438e+02 -2.83726257e+02 -2.82366058e+02 -2.83688507e+02 -2.83508789e+02 -2.81441559e+02 -2.80231049e+02 -2.80377563e+02 -2.82505310e+02 -2.82071747e+02 -2.82605072e+02 -2.81672089e+02 -2.75387482e+02 -2.68385559e+02 -2.69900604e+02 -2.76273010e+02 -2.82740173e+02 -2.76963867e+02 -2.70517365e+02 -2.71067535e+02 -2.75604187e+02 -2.80746552e+02 -2.80850555e+02 -2.81545197e+02 -2.83458710e+02 -2.82017792e+02 -2.81102234e+02 -2.81206177e+02 -2.84207367e+02 -2.86985077e+02 -2.86855560e+02 -2.85051819e+02 -2.82604645e+02 -2.83216003e+02 -2.83373627e+02 -2.83963165e+02 -2.82614136e+02 -2.79417419e+02 -2.76168304e+02 -2.76347015e+02 -2.79090424e+02 -2.82273254e+02 -2.80409851e+02 -2.78517578e+02 -2.79257935e+02 -2.82241730e+02 -2.84699890e+02 -2.84722809e+02 -2.84550964e+02 -2.84486786e+02 -2.84582886e+02 -2.84606384e+02 -2.84766663e+02 -2.84992615e+02 -2.85201965e+02 -2.84775299e+02 -2.84564240e+02 -2.84832001e+02 -2.85279449e+02 -2.85510010e+02 -2.85504364e+02 -2.85478058e+02 -2.85685059e+02 -2.86133209e+02 -2.86320099e+02 -2.86052582e+02 -2.85703339e+02 -2.85827545e+02 -2.85441254e+02 -2.86283600e+02 -2.87951111e+02 -2.88782745e+02 -2.87610474e+02 -2.85911621e+02 -2.85947601e+02 -2.86091492e+02 -2.85876892e+02 -2.85620819e+02 -2.86406708e+02 -2.86715179e+02 -2.89642700e+02 -2.92562622e+02 -2.92794464e+02 -2.89205261e+02 -2.85673981e+02 -2.86881226e+02 -2.87234131e+02 -2.90979431e+02 -2.93817017e+02 -2.94155823e+02 -2.88719330e+02 -2.83301453e+02 -2.83369019e+02 -2.84454285e+02 -2.85784515e+02 -2.85110687e+02 -2.83610474e+02 -2.82262909e+02 -2.81737518e+02 -2.81734009e+02 -2.81580994e+02 -2.80312958e+02 -2.80591797e+02 -2.77846252e+02 -2.76224762e+02 -2.74061462e+02 -2.74219208e+02 -2.75660004e+02 -2.74508545e+02 -2.74108948e+02 -2.74252777e+02 -2.75891724e+02 -2.77057007e+02 -2.75130981e+02 -2.75995483e+02 -2.75718994e+02 -2.74694061e+02 -2.70654022e+02 -2.68739410e+02 -2.70600037e+02 -2.72565582e+02 -2.74732727e+02 -2.72633026e+02 -2.75786652e+02 -2.74143707e+02 -2.78539734e+02 -2.79184906e+02 -2.80599487e+02 -2.74234039e+02 -2.66138672e+02 -2.70392761e+02 -2.82307556e+02 -2.91787323e+02 -2.88619324e+02 -2.83368774e+02 -2.81090088e+02 -2.81850372e+02 -2.82944458e+02 -2.85497986e+02 -2.84994629e+02 -2.82734924e+02 -2.79314636e+02 -2.76148438e+02 -2.70937531e+02 -2.68836945e+02 -2.70547272e+02 -2.76461609e+02 -2.79092163e+02 -2.79943695e+02 -2.77525391e+02 -2.76061096e+02 -2.70940552e+02 -2.69099274e+02 -2.66817627e+02 -2.72791260e+02 -2.83767761e+02 -2.94922180e+02 -2.91391602e+02 -2.83885132e+02 -2.72233490e+02 -2.70611389e+02 -2.68176605e+02 -2.77379486e+02 -2.86031616e+02 -2.92136017e+02 -2.91642273e+02 -2.82501617e+02 -2.73295319e+02 -2.58886505e+02 -2.63180115e+02 -2.68490723e+02 -2.72693573e+02 -2.68306915e+02 -2.63928680e+02 -2.59790955e+02 -2.62162231e+02 -2.66486786e+02 -2.69094910e+02 -2.73124695e+02 -2.73352325e+02 -2.89973663e+02 -3.02019135e+02 -2.95141174e+02 -2.75915100e+02 -2.57842285e+02 -2.65872955e+02 -2.73595703e+02 -2.70707275e+02 -2.68204712e+02 -2.75801483e+02 -2.90888733e+02 -2.90290497e+02 -2.74989380e+02 -2.57496979e+02 -2.65490082e+02 -2.67180176e+02 -2.63852814e+02 -2.49819107e+02 -2.47548706e+02 -2.49757935e+02 -2.57834839e+02 -2.52074738e+02 -2.42231461e+02 -2.41655350e+02 -2.43828751e+02 -2.48178131e+02 -2.40616760e+02 -2.53626511e+02 -2.68441864e+02 -2.70330353e+02 -2.77263977e+02 -2.92955963e+02 -3.12038635e+02 -3.13390320e+02 -2.99594604e+02 -3.01197083e+02 -2.85400482e+02 -2.81638214e+02 -2.61617798e+02 -2.44150238e+02 -2.17359589e+02 -2.12459778e+02 -2.18008392e+02 -2.24970810e+02 -2.26185120e+02 -2.29799377e+02 -2.31744827e+02 -2.30021011e+02 -2.19318802e+02 -2.36979462e+02 -2.62269592e+02 -2.75208252e+02 -2.70052124e+02 -2.49651764e+02 -2.48430145e+02 -2.43289322e+02 -2.30643921e+02 -2.42911789e+02 -2.42145706e+02 -2.50472488e+02 -2.46940765e+02 -2.59562805e+02 -2.81238708e+02 -2.65890198e+02 -2.42120483e+02 -2.31363251e+02 -2.56436401e+02 -2.66630280e+02 -2.54181351e+02 -2.24015411e+02 -2.40988251e+02 -2.61102936e+02 -2.69822632e+02 -2.54209702e+02 -2.38293930e+02 -2.63189423e+02 -2.82884094e+02 -2.80060425e+02 -2.44669983e+02 -2.17270981e+02 -2.29792343e+02 -2.47104996e+02 -2.23061523e+02 -1.89312286e+02 -2.08092407e+02 -2.48617661e+02 -2.70472076e+02 -2.58146179e+02 -2.48947281e+02 -2.47974457e+02 -2.66508636e+02 -2.84595428e+02 -2.78160278e+02 -2.38208435e+02 -2.03923584e+02 -2.06313538e+02 -2.14390411e+02 -2.19958084e+02 -2.11703384e+02 -2.13594238e+02 -2.18336975e+02 -2.27188080e+02 -2.25234787e+02 -2.08675064e+02 -2.04685226e+02 -2.09022400e+02 -2.34495728e+02 -2.45874847e+02 -2.36587555e+02 -2.29899155e+02 -2.11080429e+02 -2.13405365e+02 -2.11835693e+02 -1.99311981e+02 -1.89749893e+02 -1.83945267e+02 -2.31281616e+02 -2.61937714e+02 -2.27462265e+02 -1.61473129e+02 -1.55607162e+02 -2.12098511e+02 -2.33339157e+02 -2.03707443e+02 -1.85910843e+02 -2.12336349e+02 -2.20461227e+02 -2.14366608e+02 -1.83956299e+02 -2.04317978e+02 -2.13171524e+02 -2.21074692e+02 -1.99392334e+02 -1.71055099e+02 -1.72744690e+02 -1.76050766e+02 -2.07879730e+02 -2.27324432e+02 -2.31056610e+02 -2.03848312e+02 -2.03445801e+02 -2.58099548e+02 -2.94241821e+02 -2.74055084e+02 -2.18687729e+02 -2.15338440e+02 -2.36330475e+02 -2.07552765e+02 -1.50248856e+02 -1.27461716e+02 -1.59205200e+02 -1.85958939e+02 -1.86637405e+02 -1.77176086e+02 -1.92706558e+02 -1.90124954e+02 -1.89897308e+02 -1.78672012e+02 -1.68956924e+02 -1.53476059e+02 -1.43306870e+02 -1.54402649e+02 -1.62662964e+02 -1.84004776e+02 -1.86293716e+02 -1.91396942e+02 -2.04231995e+02 -2.07198074e+02 -1.90777557e+02 -1.61642853e+02 -1.72600525e+02 -2.09392029e+02 -2.20872055e+02 -2.09007233e+02 -2.20143250e+02 -2.75842804e+02 -3.13597595e+02 -2.80225922e+02 -2.08098984e+02 -1.89782669e+02 -2.03670898e+02 -2.07532761e+02 -1.75523529e+02 -1.54622620e+02 -1.49736343e+02 -1.43688629e+02 -1.34866348e+02 -1.46386597e+02 -1.43572235e+02 -1.31361740e+02 -1.26807068e+02 -1.74500809e+02 -1.99014954e+02 -1.69477310e+02 -1.36811951e+02 -1.73674194e+02 -1.97554214e+02 -1.67890427e+02 -9.80197067e+01 -6.08890305e+01 -6.16167412e+01 -6.24047394e+01 -7.63203888e+01 -8.13984146e+01 -9.34721222e+01 -8.21204376e+01 -9.98667145e+01 -1.04239738e+02 -1.09360512e+02 -7.83946381e+01 -1.03688538e+02 -1.70072632e+02 -2.21302048e+02 -2.30541397e+02 -2.10976120e+02 -1.86024780e+02 -1.55180679e+02 -1.26213318e+02 -1.26576988e+02 -1.15419685e+02 -1.08822533e+02 -1.05360046e+02 -1.17289703e+02 -1.13749229e+02 -1.15060646e+02 -1.17841949e+02 -1.10723854e+02 -1.10315308e+02 -9.51665649e+01 -1.41257126e+02 -1.82283051e+02 -1.91419388e+02 -1.47820419e+02 -1.16263969e+02 -1.21929993e+02 -1.23383652e+02 -1.18748749e+02 -1.14491493e+02 -1.17125023e+02 -1.18012367e+02 -1.42724762e+02 -1.76229156e+02 -1.58902634e+02 -1.16008156e+02 -1.03091560e+02 -1.77836487e+02 -2.23020599e+02 -1.90153748e+02 -1.16589012e+02 -1.12899239e+02 -1.41557739e+02 -1.40191360e+02 -1.15060791e+02 -8.55554504e+01 -1.20029541e+02 -1.43662994e+02 -1.72960373e+02 -1.87230911e+02 -1.43781204e+02 -1.11884811e+02 -1.11690895e+02 -1.95704117e+02 -2.31417236e+02 -1.84406372e+02 -1.03230049e+02 -1.14711456e+02 -1.62519730e+02 -1.77718430e+02 -1.38410294e+02 -9.70298843e+01 -1.20144371e+02 -1.50710022e+02 -1.68931076e+02 -1.45071671e+02 -1.16461952e+02 -9.55634995e+01 -1.29665085e+02 -1.66526016e+02 -1.80658859e+02 -1.40116959e+02 -8.51661530e+01 -1.09666206e+02 -1.43614944e+02 -1.45755707e+02 -1.07164604e+02 -1.07952568e+02 -1.49717819e+02 -1.45000763e+02 -1.00137177e+02 -4.43583641e+01 -3.94790001e+01 -3.52662621e+01 -7.03664932e+01 -1.10251312e+02 -1.26470268e+02 -1.09317085e+02 -8.36580505e+01 -1.85245758e+02 -4.13161316e+02 -4.34863525e+02 -7.13725159e+02 -3.36862036e+03 -5.09734668e+03 4.49235115e+01 2.85204601e+01 -1.35099411e+01 -3.14363575e+01 -4.73037491e+01 -7.01793518e+01 1.51878067e+02 3.51634979e+02 5.78339478e+02 9.80398254e+02 -1.03761328e+03 -1.19404492e+04 -1.68798688e+05 2.50198897e+10 0. 0. 0. 0. 0. 0. 0. 1.97394739e+10 -12251109. 6.69585438e+05 2.78315039e+04 4.10479297e+04 8367779. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2048812928. 5.29756250e+06 2.13574258e+04 9.49296875e+03 2.37792310e+03 -3.82037506e+02 -1.32116302e+02 4.51557281e+02 5.45840149e+02 1.93312286e+02 3.90063133e+01 -8.67842865e+01 -8.52225037e+01 6.15389347e+00 3.54708939e+01 -7.52273798e-01 3.13108215e+01 9.75306931e+01 1.65369476e+02 9.76381912e+01 -4.90620270e+01 -1.21426918e+02 -7.17846985e+01 3.50299072e+01 8.58589783e+01 7.31106796e+01 5.33391724e+01 8.20985489e+01 1.25083725e+02 9.22020569e+01 1.18424511e+01 -3.24056320e+01 -4.73335646e-02 7.42510681e+01 1.00707108e+02 5.06345520e+01 -3.73908005e+01 -8.16115494e+01 -4.18865547e+01 -4.27282410e+01 -8.88444672e+01 -6.59925613e+01 3.36259651e+01 1.20160667e+02 4.58198318e+01 -1.08330421e+02 -1.61644516e+02 -7.67607803e+01 1.81062107e+01 6.61590576e+01 6.80562134e+01 5.14953575e+01 4.35211449e+01 6.91767349e+01 5.89151306e+01 -4.97687492e+01 -1.45068817e+02 -1.07045959e+02 3.03017735e+00 6.85509720e+01 2.86818256e+01 -3.82737961e+01 -7.12553940e+01 -7.16371679e+00 7.06137848e+00 -1.30778303e+01 1.35621538e+01 9.67269287e+01 1.74218765e+02 1.55830170e+02 2.36293850e+01 -1.76623535e+01 2.76839466e+01 1.25555046e+02 1.17016388e+02 4.27251930e+01 5.93073921e+01 1.03218910e+02 1.39098312e+02 9.11362839e+01 -1.25261765e+01 -6.09021950e+01 -2.51690636e+01 8.78945389e+01 1.55709473e+02 1.31774612e+02 7.86647797e+01 8.61370163e+01 1.38530350e+02 1.37250916e+02 6.82358475e+01 3.85554428e+01 1.06405045e+02 1.99192123e+02 2.06392319e+02 1.13561691e+02 2.84628506e+01 3.09881992e+01 9.42302475e+01 1.13406776e+02 9.21726074e+01 1.37192520e+02 2.17564957e+02 2.58714935e+02 1.78733521e+02 5.22745857e+01 -1.31106119e+01 3.23601418e+01 1.11201561e+02 1.88860306e+02 2.35167694e+02 2.28576248e+02 2.14243866e+02 2.16468155e+02 2.00533508e+02 1.26097595e+02 5.35676651e+01 9.84217300e+01 2.24168396e+02 2.75836975e+02 2.20767853e+02 9.54720459e+01 4.30705528e+01 9.86619720e+01 1.50147354e+02 1.68553375e+02 1.55223709e+02 2.05614212e+02 2.87399048e+02 2.80540863e+02 1.88083740e+02 1.00191772e+02 1.10068329e+02 1.70203888e+02 2.12801636e+02 2.17478210e+02 2.05091095e+02 1.67900299e+02 1.53740356e+02 1.99321793e+02 2.26363281e+02 1.83936539e+02 1.39191177e+02 1.27949638e+02 1.53680634e+02 1.52087799e+02 1.20565193e+02 1.19272911e+02 1.49065643e+02 1.91814117e+02 2.16719894e+02 1.83717422e+02 1.66939346e+02 1.77279922e+02 2.01227951e+02 1.64967209e+02 5.65234604e+01 2.86342645e+00 8.34943161e+01 1.87944153e+02 2.07263382e+02 1.55642426e+02 1.22437340e+02 1.27141464e+02 1.24494301e+02 8.64752426e+01 3.85826950e+01 2.54424400e+01 5.90038109e+01 1.28717682e+02 1.71632446e+02 1.29205231e+02 1.02192551e+02 1.19692894e+02 1.69446564e+02 1.44180710e+02 6.07967262e+01 6.75679932e+01 1.05098396e+02 1.35602966e+02 9.06425781e+01 5.31047535e+00 -3.29643021e+01 1.51473303e+01 1.08594872e+02 1.57867508e+02 1.49305405e+02 1.63035355e+02 1.91343185e+02 1.77567200e+02 1.19463135e+02 4.41598167e+01 6.63548813e+01 1.19202644e+02 2.13881149e+02 2.47446869e+02 2.26610138e+02 1.60538559e+02 1.03868355e+02 1.00989319e+02 9.02049866e+01 6.85449677e+01 9.10894089e+01 1.60435440e+02 2.23195770e+02 1.94918106e+02 9.39187698e+01 4.40092430e+01 9.76290436e+01 2.04263901e+02 2.40910507e+02 1.94658401e+02 1.42972214e+02 1.64230545e+02 2.09826004e+02 2.01502457e+02 1.46913040e+02 1.29903732e+02 1.83288574e+02 2.64049622e+02 2.73248901e+02 2.36931229e+02 1.90342560e+02 1.97684692e+02 2.13825302e+02 2.16899231e+02 1.91335403e+02 2.07524780e+02 2.44871872e+02 2.54222656e+02 2.57353394e+02 2.03097549e+02 1.93438156e+02 2.01513702e+02 2.12939362e+02 2.06745819e+02 1.69266022e+02 2.01016159e+02 2.41537613e+02 2.68035980e+02 2.46745514e+02 1.61810272e+02 1.10158569e+02 1.18434830e+02 2.05109497e+02 2.58580139e+02 2.65573608e+02 2.39490387e+02 2.14669617e+02 2.39345871e+02 2.32048019e+02 2.11433044e+02 1.95923386e+02 2.23714554e+02 2.45915207e+02 2.02439697e+02 1.48261551e+02 1.57212357e+02 1.84854843e+02 1.99905472e+02 1.87677811e+02 1.53849442e+02 1.90030594e+02 2.13347763e+02 2.42505814e+02 2.27911362e+02 1.87963104e+02 1.67742722e+02 1.54756973e+02 1.92486084e+02 2.11939407e+02 2.18397919e+02 1.89676910e+02 1.87256897e+02 1.94292969e+02 1.88270050e+02 1.63743790e+02 1.52528824e+02 1.92286957e+02 2.21805222e+02 2.22255463e+02 1.90686279e+02 1.99571320e+02 2.13976242e+02 2.31183319e+02 2.42067856e+02 2.34009094e+02 2.41536469e+02 2.07240891e+02 2.00302475e+02 1.87625305e+02 1.89478088e+02 2.00906204e+02 2.12948868e+02 2.49153549e+02 2.60723938e+02 2.52670319e+02 2.01277313e+02 1.89468552e+02 1.99023819e+02 2.18549179e+02 2.15819351e+02 2.24667465e+02 2.70634674e+02 2.91525238e+02 2.76188293e+02 2.21577560e+02 2.06361435e+02 2.24961349e+02 2.51525681e+02 2.58968018e+02 2.31371231e+02 2.32662476e+02 2.29437408e+02 2.63684387e+02 2.70013184e+02 2.74887268e+02 2.47072083e+02 2.43652100e+02 2.60573944e+02 2.76331604e+02 2.57190887e+02 2.26427643e+02 2.40144333e+02 2.64141754e+02 2.66801971e+02 2.53160904e+02 2.49048004e+02 2.78125977e+02 2.87198181e+02 2.76354675e+02 2.44906891e+02 2.47315903e+02 2.57982117e+02 2.71016174e+02 2.61969330e+02 2.49647430e+02 2.50354828e+02 2.48110977e+02 2.64982758e+02 2.70908020e+02 2.74359985e+02 2.60072754e+02 2.57894806e+02 2.64635345e+02 2.79385590e+02 2.68255157e+02 2.49150558e+02 2.43767960e+02 2.47345581e+02 2.39655731e+02 2.19124496e+02 2.23143570e+02 2.44621796e+02 2.50251373e+02 2.38125290e+02 2.20858398e+02 2.39204285e+02 2.50166931e+02 2.61382690e+02 2.72692169e+02 2.75141449e+02 2.65088501e+02 2.36129929e+02 2.31086700e+02 2.50592514e+02 2.71491577e+02 2.60564240e+02 2.37861099e+02 2.24668457e+02 2.39587631e+02 2.50709091e+02 2.47846420e+02 2.42836594e+02 2.34770264e+02 2.25159363e+02 2.09776321e+02 2.14191956e+02 2.29755402e+02 2.36476456e+02 2.30986313e+02 2.23285355e+02 2.39609451e+02 2.48385788e+02 2.55092484e+02 2.52842819e+02 2.52247910e+02 2.44178040e+02 2.26213272e+02 2.20796600e+02 2.37020340e+02 2.61226990e+02 2.68648224e+02 2.47252686e+02 2.29961929e+02 2.29080841e+02 2.43948914e+02 2.52714066e+02 2.48681671e+02 2.36937775e+02 2.31400024e+02 2.37756653e+02 2.55071564e+02 2.59447540e+02 2.52474579e+02 2.42521637e+02 2.33847672e+02 2.36181351e+02 2.40957199e+02 2.52361938e+02 2.63479370e+02 2.67498322e+02 2.61096985e+02 2.47523880e+02 2.40660141e+02 2.46913834e+02 2.56525085e+02 2.56293884e+02 2.48140930e+02 2.41354752e+02 2.44745926e+02 2.52801392e+02 2.58998962e+02 2.59456421e+02 2.55514786e+02 2.52626373e+02 2.50907013e+02 2.54162491e+02 2.56009827e+02 2.57414124e+02 2.55998520e+02 2.55467117e+02 2.56832520e+02 2.58116272e+02 2.59157471e+02 2.58918945e+02 2.58260834e+02 2.57822449e+02 2.57956146e+02 2.58564056e+02 2.58518097e+02 2.57086639e+02 2.55749893e+02 2.56440582e+02 2.59381256e+02 2.62035583e+02 2.61325653e+02 2.59754700e+02 2.59791412e+02 2.62005768e+02 2.63139099e+02 2.63672180e+02 2.60405731e+02 2.57796112e+02 2.54209915e+02 2.53409378e+02 2.55552460e+02 2.58793762e+02 2.63895813e+02 2.63816803e+02 2.60470245e+02 2.54594025e+02 2.53965622e+02 2.59312500e+02 2.65994843e+02 2.63729797e+02 2.56770813e+02 2.52815308e+02 2.58824524e+02 2.69389618e+02 2.69151367e+02 2.61176819e+02 2.47190567e+02 2.47395966e+02 2.57629639e+02 2.67735504e+02 2.73636902e+02 2.62127167e+02 2.56422394e+02 2.51747345e+02 2.51261292e+02 2.50245361e+02 2.48441055e+02 2.54419357e+02 2.51324005e+02 2.44027374e+02 2.45660675e+02 2.54771835e+02 2.71353027e+02 2.77649109e+02 2.68037933e+02 2.42562729e+02 2.20830307e+02 2.22650726e+02 2.49371368e+02 2.75642914e+02 2.83603943e+02 2.63049164e+02 2.39525925e+02 2.33440262e+02 2.49464706e+02 2.68299957e+02 2.64795258e+02 2.51710175e+02 2.36471588e+02 2.32706100e+02 2.37485626e+02 2.50907715e+02 2.67088318e+02 2.65693054e+02 2.49362625e+02 2.23230423e+02 2.16805298e+02 2.37355392e+02 2.59840668e+02 2.57936035e+02 2.35129944e+02 2.22065430e+02 2.30816879e+02 2.43566422e+02 2.49548737e+02 2.54218353e+02 2.46394379e+02 2.38387909e+02 2.40899796e+02 2.45420898e+02 2.55183807e+02 2.43556702e+02 2.30249695e+02 2.13406708e+02 2.02898209e+02 2.18253250e+02 2.32719757e+02 2.57737000e+02 2.66360748e+02 2.52716278e+02 2.27367905e+02 2.21544586e+02 2.46733841e+02 2.76240845e+02 2.70639282e+02 2.50959717e+02 2.20174835e+02 2.10181381e+02 2.25500656e+02 2.41885941e+02 2.52469772e+02 2.23263992e+02 2.00551712e+02 1.75888275e+02 1.80269409e+02 2.11079468e+02 2.08653381e+02 1.96724365e+02 1.61662094e+02 1.56304047e+02 1.68958862e+02 1.95171524e+02 2.39829666e+02 2.60054779e+02 2.49032593e+02 2.10276215e+02 1.89895111e+02 2.19177994e+02 2.56116486e+02 2.57630432e+02 2.11828537e+02 1.81157425e+02 1.90081482e+02 2.33289536e+02 2.66896423e+02 2.68677429e+02 2.33038025e+02 1.89586594e+02 1.77334381e+02 1.78459961e+02 1.91848694e+02 2.08021454e+02 2.35265594e+02 2.38683273e+02 2.25541199e+02 2.12755524e+02 2.30785202e+02 2.70922241e+02 2.94952881e+02 2.57210907e+02 2.04656265e+02 1.76305710e+02 2.07337677e+02 2.56309265e+02 2.65159363e+02 2.39100403e+02 1.87698776e+02 1.81215576e+02 2.10066727e+02 2.26011078e+02 2.31043579e+02 1.95986786e+02 1.87056244e+02 1.91656693e+02 2.06585281e+02 2.34490982e+02 2.25127869e+02 2.23558746e+02 1.78034042e+02 1.39907776e+02 1.45495590e+02 1.73290451e+02 2.20018387e+02 2.51505783e+02 2.56343475e+02 2.20075470e+02 1.35579910e+02 1.19253822e+02 1.29792038e+02 1.04815826e+02 -1.50502823e+02 -1.80607654e+03 -2.80929395e+03 3.67025665e+02 8.74381409e+02 -3.92753735e+03 -1.25673594e+04 -265194240. -68327544. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.07519795e+09 -3.53418047e+04 -5.22131250e+03 -1.03346997e+03 -6.01721924e+02 -1.37734695e+02 8.21874714e+00 1.04831032e+02 1.38359619e+02 9.78477173e+01 8.26847458e+01 1.24915359e+02 2.19833038e+02 2.23675507e+02 1.72554855e+02 1.05680099e+02 1.24778587e+02 2.03026291e+02 2.64753021e+02 2.70295746e+02 2.06200089e+02 1.09043175e+02 8.50982895e+01 1.49721176e+02 2.33390686e+02 2.32303574e+02 1.69332336e+02 1.65991150e+02 2.14687607e+02 2.34128143e+02 1.92371933e+02 1.47129608e+02 1.43026184e+02 1.31321075e+02 9.77573853e+01 9.78722076e+01 1.52230789e+02 2.45640320e+02 2.53803482e+02 1.84756287e+02 1.21847656e+02 1.23355217e+02 1.94097549e+02 2.69793640e+02 2.58154388e+02 1.60122208e+02 4.14989243e+01 5.02899208e+01 1.57314178e+02 2.16242798e+02 2.21291107e+02 1.63543854e+02 1.45379593e+02 1.38697006e+02 1.26852432e+02 1.42596329e+02 1.61964340e+02 2.13650391e+02 1.97180832e+02 1.34794159e+02 1.24515610e+02 1.58152710e+02 2.36558655e+02 2.40668106e+02 1.98512482e+02 1.28036118e+02 9.22338333e+01 1.67954422e+02 2.65891083e+02 3.35123108e+02 2.90505890e+02 1.85539169e+02 1.47980972e+02 2.10419174e+02 2.62525421e+02 2.50448837e+02 1.51050690e+02 1.28705719e+02 1.54763535e+02 2.05598465e+02 1.94290848e+02 1.99387817e+02 2.17276505e+02 1.83315155e+02 1.10180565e+02 8.43830338e+01 1.59127335e+02 2.65027924e+02 2.85219635e+02 2.38891174e+02 1.67752945e+02 1.06641029e+02 1.04815598e+02 1.51333313e+02 2.08956680e+02 1.91936966e+02 9.22770767e+01 5.18594398e+01 1.36771484e+02 2.25829941e+02 2.12445633e+02 1.07001999e+02 4.84889450e+01 5.69768181e+01 7.13390579e+01 8.67093582e+01 1.27937279e+02 2.11843979e+02 2.11066696e+02 1.35478790e+02 7.30616226e+01 7.88601074e+01 1.49778137e+02 1.60848709e+02 1.16122116e+02 7.42818756e+01 3.62644920e+01 4.62284546e+01 1.14670097e+02 1.79790222e+02 1.95557953e+02 8.65318680e+01 3.52076569e+01 8.40165100e+01 1.17020096e+02 1.19342514e+02 6.32857246e+01 7.46602402e+01 8.27013474e+01 4.95961876e+01 3.23819885e+01 5.45872879e+01 1.46881271e+02 1.52264389e+02 7.94723129e+01 2.73845367e+01 2.87291965e+01 1.03199150e+02 8.40123672e+01 3.36503220e+01 -9.72980022e+00 -3.69451904e+01 3.33668661e+00 8.06617126e+01 1.49414322e+02 1.49626495e+02 7.40238724e+01 5.80577621e+01 7.75878143e+01 7.70124664e+01 5.11491699e+01 -1.22826853e+01 -4.19011192e+01 -6.13608551e+01 -5.09748535e+01 -3.71194506e+00 4.62569008e+01 1.27923218e+02 1.43382690e+02 1.28007309e+02 6.79282379e+01 6.91156235e+01 1.28307449e+02 1.96070480e+02 1.61486374e+02 5.27019119e+01 -3.37856941e+01 -4.09748344e+01 6.29518471e+01 1.20502495e+02 1.17385185e+02 5.59903908e+01 3.49431725e+01 6.19912224e+01 4.57801018e+01 6.42989960e+01 7.80276337e+01 7.66389999e+01 7.11689758e+00 -6.90931931e+01 -6.81524506e+01 -3.69317360e+01 1.75751247e+01 6.50475540e+01 8.15100861e+01 6.56171799e+01 4.78868408e+01 1.01217415e+02 1.62040161e+02 1.37013855e+02 3.93735161e+01 -5.66377525e+01 -7.37055664e+01 6.09499598e+00 3.02651539e+01 4.01514511e+01 -3.45304413e+01 -1.91593609e+01 3.36216431e+01 1.02801682e+02 1.41257278e+02 1.39638733e+02 1.89261581e+02 1.57284424e+02 7.88122330e+01 6.78104687e+00 1.04554090e+01 8.71098709e+01 9.29216537e+01 3.29123688e+01 -4.50893326e+01 -1.10342545e+02 -6.63559418e+01 4.87120819e+01 1.46483627e+02 1.06118980e+02 -4.12970400e+00 -2.54566441e+01 3.16129379e+01 5.48311195e+01 4.79477654e+01 -7.06255770e+00 -4.26482010e+01 -7.06152802e+01 -5.55744743e+01 -3.92485504e+01 1.19415741e+01 7.98976059e+01 1.07676796e+02 8.15434723e+01 3.00137978e+01 2.20005207e+01 2.09481258e+01 -1.22616262e+01 -6.09236031e+01 -7.77691269e+01 -5.96072998e+01 -1.01838913e+01 9.79937077e+00 1.74787464e+01 -1.89179051e+00 -3.79022293e+01 -5.66506996e+01 -4.91164894e+01 -1.14150381e+01 -1.65147197e+00 -7.04278755e+00 -3.40253220e+01 -2.29257221e+01 -1.34710512e+01 -1.39652157e+00 -1.48648148e+01 -3.04844704e+01 -3.18931503e+01 -3.76597519e+01 -3.41035118e+01 -5.26050720e+01 -4.52217522e+01 -4.20151634e+01 -2.98660316e+01 -4.26450615e+01 -5.72414246e+01 -4.80419426e+01 -4.11247063e+01 -4.01689224e+01 -6.16056976e+01 -5.68896065e+01 -5.75461006e+01 -7.14705124e+01 -5.62526817e+01 -4.18008728e+01 -2.77885532e+01 -6.65102844e+01 -7.72971420e+01 -7.06864777e+01 -6.57138901e+01 -7.49123001e+01 -8.00327835e+01 -7.47713394e+01 -7.56158676e+01 -6.31798630e+01 -6.32398834e+01 -5.79579010e+01 -7.72746964e+01 -6.40185089e+01 -8.48260651e+01 -7.64983597e+01 -8.39088516e+01 -7.01540756e+01 -8.80292587e+01 -9.31687546e+01 -9.83937836e+01 -7.10055771e+01 -5.56026154e+01 -4.09204636e+01 -6.82198715e+01 -7.94323730e+01 -9.28221130e+01 -8.27325439e+01 -8.34382706e+01 -7.44178543e+01 -6.56707916e+01 -7.69569931e+01 -7.54931030e+01 -7.38814316e+01 -7.66216278e+01 -9.68485031e+01 -1.07169106e+02 -9.80398788e+01 -8.71773148e+01 -9.33976593e+01 -8.44485321e+01 -7.38473892e+01 -5.64524536e+01 -6.40341721e+01 -7.53316269e+01 -9.42451553e+01 -1.00746124e+02 -1.27432159e+02 -1.38402908e+02 -1.54684692e+02 -1.30630142e+02 -1.15960052e+02 -9.29301758e+01 -8.11094055e+01 -7.74799805e+01 -1.17520157e+02 -1.58244766e+02 -1.54367828e+02 -1.16739899e+02 -8.50591965e+01 -8.33598557e+01 -9.56366730e+01 -8.40078735e+01 -8.00184555e+01 -7.78090668e+01 -9.22766571e+01 -9.15400467e+01 -8.57355118e+01 -9.97849121e+01 -1.09740776e+02 -1.05978264e+02 -7.81582870e+01 -5.24619598e+01 -4.74379044e+01 -6.71702118e+01 -9.83409729e+01 -1.00661316e+02 -8.78643875e+01 -8.74456863e+01 -9.97143326e+01 -1.09058281e+02 -8.71941833e+01 -6.62645874e+01 -6.22460327e+01 -8.91066437e+01 -1.16128677e+02 -1.33039261e+02 -1.13978600e+02 -6.67037964e+01 -2.98136997e+01 -6.07486801e+01 -1.24804451e+02 -1.48779755e+02 -1.28808762e+02 -1.06907112e+02 -1.01818756e+02 -8.60539093e+01 -7.28864670e+01 -8.96699829e+01 -1.15899628e+02 -1.34359528e+02 -1.32716766e+02 -1.26774338e+02 -1.03980347e+02 -7.78623199e+01 -8.01867142e+01 -1.10156586e+02 -1.37966064e+02 -1.44233337e+02 -1.42381042e+02 -1.51227188e+02 -1.67302856e+02 -1.80075912e+02 -1.74978775e+02 -1.57006226e+02 -1.42065414e+02 -1.50711609e+02 -1.63444275e+02 -1.66231934e+02 -1.51239304e+02 -1.53183746e+02 -1.61271957e+02 -1.46382797e+02 -1.28521729e+02 -1.35623734e+02 -1.80685623e+02 -2.00144775e+02 -1.76396011e+02 -1.57025391e+02 -1.42882278e+02 -1.29918365e+02 -1.14056992e+02 -1.17602287e+02 -1.16363205e+02 -1.17528519e+02 -1.24239052e+02 -1.52536835e+02 -1.62107117e+02 -1.54356903e+02 -1.51072403e+02 -1.55335724e+02 -1.58585800e+02 -1.60719818e+02 -1.66264450e+02 -1.46245361e+02 -1.22949585e+02 -1.18665070e+02 -1.48708664e+02 -1.79629242e+02 -1.77112762e+02 -1.81067810e+02 -1.71916565e+02 -1.67573013e+02 -1.56328812e+02 -1.71956390e+02 -1.97546921e+02 -2.20833328e+02 -2.23063507e+02 -2.06246735e+02 -1.83639221e+02 -1.79982178e+02 -1.87344025e+02 -1.93773865e+02 -1.86802872e+02 -1.85112579e+02 -2.20750275e+02 -2.51913193e+02 -2.53835052e+02 -2.14614243e+02 -1.82393845e+02 -1.84075974e+02 -2.07838898e+02 -2.54463226e+02 -3.25611755e+02 -3.54942932e+02 -4.57458740e+02 -3.86446106e+02 -5.01994873e+02 -2.41968481e+03 -1.05239966e+03 -1.62428015e+03 -4.17964160e+03 -8.80284668e+02 -1.10517017e+03 -8.65689941e+02 -1.30070483e+03 -1.68941882e+03 -1.06066855e+04 -2.60787363e+04 199722080. -854541824. 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. 0. 0. 0. 0. 0. 0. 0. 0. -443228992. -139696864. 74457600. -1.15396162e+04 -4.41895020e+03 -9.23593445e+02 -4.60492432e+02 -3.04627197e+02 -2.71075958e+02 -2.80875183e+02 -2.83506470e+02 -2.61846008e+02 -2.37907669e+02 -2.37408325e+02 -2.35229065e+02 -2.34955246e+02 -2.38930099e+02 -2.50661209e+02 -2.66026306e+02 -2.46541275e+02 -2.18904190e+02 -2.12488388e+02 -2.34537674e+02 -2.49847778e+02 -2.41231995e+02 -2.32696472e+02 -2.36079865e+02 -2.43708527e+02 -2.56599976e+02 -2.61746918e+02 -2.61324799e+02 -2.48912445e+02 -2.43697540e+02 -2.40808044e+02 -2.46784042e+02 -2.30561325e+02 -2.08144653e+02 -2.02412399e+02 -2.15087555e+02 -2.31206879e+02 -2.29206985e+02 -2.19861435e+02 -2.17692368e+02 -2.12997360e+02 -2.11139206e+02 -2.06954269e+02 -2.02441650e+02 -2.02408905e+02 -2.09812393e+02 -2.17239471e+02 -2.20452164e+02 -2.12732086e+02 -2.14617889e+02 -2.18774658e+02 -2.20403809e+02 -2.16209564e+02 -2.11827423e+02 -2.12827576e+02 -2.21687500e+02 -2.40347382e+02 -2.58670441e+02 -2.65263794e+02 -2.54347824e+02 -2.41688187e+02 -2.34784393e+02 -2.46253860e+02 -2.57796295e+02 -2.53937881e+02 -2.40240250e+02 -2.27057129e+02 -2.26966232e+02 -2.28031891e+02 -2.20478485e+02 -2.07738098e+02 -2.19028992e+02 -2.38505753e+02 -2.54571762e+02 -2.46954391e+02 -2.37264023e+02 -2.37049316e+02 -2.36439087e+02 -2.36572098e+02 -2.34637680e+02 -2.35836197e+02 -2.38644165e+02 -2.45232056e+02 -2.49118286e+02 -2.50362564e+02 -2.47914169e+02 -2.48405350e+02 -2.59769012e+02 -2.73402374e+02 -2.68912140e+02 -2.58050171e+02 -2.45980179e+02 -2.50595078e+02 -2.55773407e+02 -2.61933716e+02 -2.65422180e+02 -2.58450470e+02 -2.47433701e+02 -2.45092178e+02 -2.50625763e+02 -2.62535248e+02 -2.62897339e+02 -2.59329651e+02 -2.52674988e+02 -2.48307236e+02 -2.52105606e+02 -2.51301086e+02 -2.52186905e+02 -2.48811615e+02 -2.52013351e+02 -2.52718735e+02 -2.52236984e+02 -2.56655243e+02 -2.63112640e+02 -2.61953247e+02 -2.55570099e+02 -2.49078400e+02 -2.48530945e+02 -2.47987915e+02 -2.48354065e+02 -2.48659454e+02 -2.47315155e+02 -2.47163605e+02 -2.54724594e+02 -2.63933472e+02 -2.65128113e+02 -2.59834076e+02 -2.53399918e+02 -2.50368744e+02 -2.48544937e+02 -2.49772476e+02 -2.52042068e+02 -2.53674896e+02 -2.51627319e+02 -2.52341919e+02 -2.52447983e+02 -2.53521622e+02 -2.54619034e+02 -2.55911240e+02 -2.55955719e+02 -2.55896210e+02 -2.55263412e+02 -2.55900070e+02 -2.56825836e+02 -2.56891052e+02 -2.57564331e+02 -2.58084106e+02 -2.58793121e+02 -2.59146027e+02 -2.57967896e+02 -2.57718292e+02 -2.57217163e+02 -2.57061340e+02 -2.56817535e+02 -2.55850113e+02 -2.55893677e+02 -2.56598511e+02 -2.59728485e+02 -2.61299255e+02 -2.61351471e+02 -2.60174713e+02 -2.59150513e+02 -2.58736298e+02 -2.58363586e+02 -2.58149261e+02 -2.58288727e+02 -2.58261261e+02 -2.58147064e+02 -2.58088287e+02 -2.58024109e+02 -2.57945984e+02 -2.57880432e+02 -2.58152100e+02 -2.58653564e+02 -2.58971466e+02 -2.58707764e+02 -2.58077026e+02 -2.57274078e+02 -2.57244324e+02 -2.57401093e+02 -2.57488403e+02 -2.57381561e+02 -2.57504120e+02 -2.57565002e+02 -2.57780334e+02 -2.58305267e+02 -2.57869507e+02 -2.57504028e+02 -2.57258636e+02 -2.57468994e+02 -2.57622437e+02 -2.56422516e+02 -2.55751953e+02 -2.55466827e+02 -2.55596512e+02 -2.56566193e+02 -2.59272339e+02 -2.63652802e+02 -2.65858734e+02 -2.66496277e+02 -2.65324524e+02 -2.67063171e+02 -2.63164307e+02 -2.57946472e+02 -2.52964386e+02 -2.53219421e+02 -2.54408295e+02 -2.54416336e+02 -2.53938553e+02 -2.53235214e+02 -2.51196411e+02 -2.51295654e+02 -2.50922226e+02 -2.52696167e+02 -2.53162918e+02 -2.53733841e+02 -2.47345871e+02 -2.39194031e+02 -2.41195526e+02 -2.48012329e+02 -2.55784409e+02 -2.58892090e+02 -2.60914490e+02 -2.68960052e+02 -2.73238434e+02 -2.71485840e+02 -2.65416199e+02 -2.54748413e+02 -2.56667786e+02 -2.58619537e+02 -2.63061066e+02 -2.62396088e+02 -2.59973267e+02 -2.60376190e+02 -2.59941498e+02 -2.60836365e+02 -2.57091034e+02 -2.54047607e+02 -2.53927414e+02 -2.62266205e+02 -2.72178040e+02 -2.81686005e+02 -2.84210175e+02 -2.65695160e+02 -2.43931122e+02 -2.32879257e+02 -2.40369980e+02 -2.52860168e+02 -2.53609161e+02 -2.56710236e+02 -2.55067215e+02 -2.53762512e+02 -2.50869583e+02 -2.48201904e+02 -2.45392151e+02 -2.45724167e+02 -2.45691437e+02 -2.38297424e+02 -2.24445557e+02 -2.21792969e+02 -2.28236511e+02 -2.37977463e+02 -2.44425858e+02 -2.51019669e+02 -2.52868881e+02 -2.45567612e+02 -2.45141556e+02 -2.51995453e+02 -2.51529358e+02 -2.44698151e+02 -2.36075378e+02 -2.33864578e+02 -2.36839737e+02 -2.37693893e+02 -2.38939865e+02 -2.38262039e+02 -2.40596451e+02 -2.39428192e+02 -2.38252808e+02 -2.31181778e+02 -2.30331680e+02 -2.29987045e+02 -2.45023621e+02 -2.60288269e+02 -2.57386475e+02 -2.43270157e+02 -2.30299423e+02 -2.36910019e+02 -2.37494659e+02 -2.37114746e+02 -2.37802444e+02 -2.42085617e+02 -2.44413437e+02 -2.52730194e+02 -2.58169983e+02 -2.56250916e+02 -2.39401169e+02 -2.24605118e+02 -2.22240921e+02 -2.27306152e+02 -2.18005676e+02 -2.05360764e+02 -1.96775177e+02 -2.03203690e+02 -2.16945938e+02 -2.14886490e+02 -2.14838959e+02 -2.15314346e+02 -2.22554169e+02 -2.25220016e+02 -2.19577820e+02 -2.14072189e+02 -2.13402069e+02 -2.15893066e+02 -2.13881058e+02 -2.11727051e+02 -2.16821777e+02 -2.21099503e+02 -2.36324020e+02 -2.48887405e+02 -2.46740753e+02 -2.37271790e+02 -2.27514343e+02 -2.28655807e+02 -2.20691956e+02 -2.11188049e+02 -2.14061966e+02 -2.39202469e+02 -2.59259949e+02 -2.60728424e+02 -2.37663879e+02 -2.20461609e+02 -2.22213303e+02 -2.29602509e+02 -2.29948563e+02 -2.21597763e+02 -2.33048080e+02 -2.53580841e+02 -2.62809113e+02 -2.46805908e+02 -2.20072083e+02 -2.21806076e+02 -2.20565582e+02 -2.22289520e+02 -2.17422623e+02 -2.16016891e+02 -2.22762802e+02 -2.27832581e+02 -2.33720917e+02 -2.23679657e+02 -2.17311203e+02 -2.16236969e+02 -2.45625076e+02 -2.80667908e+02 -2.84669830e+02 -2.54804199e+02 -2.22366623e+02 -2.18277863e+02 -2.05614227e+02 -2.05220612e+02 -2.08463791e+02 -2.46641312e+02 -2.68810333e+02 -2.99853668e+02 -2.97933502e+02 -2.77083893e+02 -2.46729156e+02 -2.14569946e+02 -2.34864517e+02 -2.53994125e+02 -2.29073700e+02 -1.73817474e+02 -1.49856522e+02 -1.75376190e+02 -2.01516998e+02 -1.96992508e+02 -1.92715927e+02 -1.88169937e+02 -1.87495895e+02 -1.79444397e+02 -1.76637299e+02 -1.74222015e+02 -1.71642654e+02 -1.67091339e+02 -1.60562836e+02 -1.57916550e+02 -1.66322922e+02 -1.72111359e+02 -1.95072372e+02 -2.11968338e+02 -2.09287140e+02 -1.82361282e+02 -1.50509888e+02 -1.78847092e+02 -2.16351120e+02 -1.91353760e+02 -1.28934998e+02 -1.22631889e+02 -1.94192322e+02 -2.36739410e+02 -2.14973740e+02 -1.74153732e+02 -1.89754486e+02 -2.23865356e+02 -2.33689835e+02 -2.20454559e+02 -1.87771881e+02 -1.88633957e+02 -1.89790146e+02 -1.86385086e+02 -1.84505997e+02 -1.58089264e+02 -1.32012009e+02 -1.55021713e+02 -2.08167557e+02 -2.37297195e+02 -2.19811600e+02 -1.95672592e+02 -2.23027252e+02 -2.48125153e+02 -2.53882858e+02 -2.25788589e+02 -1.87722656e+02 -1.93023331e+02 -1.99787567e+02 -2.10547867e+02 -1.89492905e+02 -1.99017044e+02 -2.27705994e+02 -2.40407486e+02 -2.34011093e+02 -1.87818558e+02 -1.67280045e+02 -1.54877838e+02 -1.63068161e+02 -1.68334702e+02 -1.22870857e+02 -6.44708099e+01 -7.67331772e+01 -1.45679153e+02 -1.97817566e+02 -1.79796753e+02 -1.43216614e+02 -1.64802216e+02 -2.02810471e+02 -2.06728760e+02 -1.79860031e+02 -1.48447495e+02 -1.35428696e+02 -1.34625214e+02 -1.35263092e+02 -1.45684769e+02 -1.47489075e+02 -1.55948990e+02 -1.68060623e+02 -1.78477280e+02 -1.67522598e+02 -1.47562592e+02 -1.31532455e+02 -1.32147888e+02 -1.35401901e+02 -1.04973190e+02 -6.76218109e+01 -9.91421204e+01 -1.67382492e+02 -2.04269791e+02 -1.63060776e+02 -1.19951080e+02 -9.29732666e+01 -8.00875320e+01 -7.87183151e+01 -9.13031082e+01 -1.04836166e+02 -9.73547211e+01 -9.70079651e+01 -8.84115982e+01 -9.07959213e+01 -7.78193207e+01 -7.66886520e+01 -7.12868042e+01 -9.93191071e+01 -1.14488060e+02 -1.03797600e+02 -7.50957642e+01 -6.12353363e+01 -8.47454224e+01 -1.07004272e+02 -1.21909462e+02 -1.45677551e+02 -1.85112732e+02 -1.85100449e+02 -1.53358704e+02 -1.42076706e+02 -2.09088715e+02 -2.55007477e+02 -2.25171921e+02 -1.72958618e+02 -1.87280899e+02 -2.30775040e+02 -2.37066345e+02 -1.92017105e+02 -1.57348083e+02 -1.48421738e+02 -1.43710220e+02 -1.54133698e+02 -1.53720657e+02 -1.52990677e+02 -1.29369751e+02 -1.50764038e+02 -1.84943024e+02 -2.04969833e+02 -1.75981873e+02 -1.39623718e+02 -1.45569916e+02 -1.72946747e+02 -1.47026764e+02 -8.66657028e+01 -5.84377518e+01 -7.07919159e+01 -1.04271980e+02 -9.08386459e+01 -9.53757935e+01 -9.30650940e+01 -9.27797623e+01 -8.13410187e+01 -8.49106674e+01 -9.33656845e+01 -8.90766220e+01 -7.96218185e+01 -6.44801636e+01 -7.16566315e+01 -7.96819305e+01 -7.39805069e+01 -1.03144470e+02 -1.33861877e+02 -1.34804764e+02 -9.44347916e+01 -4.33873100e+01 -2.96175556e+01 -2.56047592e+01 2.42316675e+00 3.88851089e+01 3.49156837e+01 -3.51707029e+00 -4.55918159e+01 -5.10016747e+01 -4.76612244e+01 -9.81804581e+01 -1.43855179e+02 -1.51256653e+02 -1.07028511e+02 -7.62411652e+01 -7.82423935e+01 -7.35212173e+01 -5.23445358e+01 -5.32638206e+01 -2.64215050e+01 1.18812618e+01 -1.13804264e+01 -7.22797089e+01 -1.16497063e+02 -8.91948242e+01 -9.03560791e+01 -1.54446167e+02 -2.02922470e+02 -1.83851532e+02 -1.07134628e+02 -7.81539307e+01 -9.83507538e+01 -1.16667862e+02 -8.15061111e+01 -2.77580528e+01 -2.76900482e+01 -6.16631012e+01 -6.70356293e+01 -5.17554703e+01 -1.38768063e+01 2.11821961e+00 1.69483051e+01 1.83521290e+01 5.42482424e+00 1.00687962e+01 1.99820156e+01 -4.27774334e+00 -3.91139297e+01 -6.10531845e+01 -3.55547409e+01 -1.21090040e+01 -3.52840576e+01 -7.72484665e+01 -7.56762466e+01 -3.52985115e+01 8.63038101e+01 2.64727997e+02 3.94207031e+02 5.38292786e+02 5.33348267e+02 6.18891716e+01 -2.14087204e+02 -4.76140259e+02 -6.65112152e+01 1.96817780e+02 1.65700180e+02 -1.82974792e+02 1.39104688e+03 -2.05818146e+02 -1.68798688e+05 2.50198897e+10 0. 0. 0. 0. -3.88826496e+09 -3.88826496e+09 -17269332. 2.82984243e+09 7.00192109e+04 6.69585438e+05 2.78315039e+04 4.10479297e+04 8367779. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.37251052e+10 -4.24189250e+06 9.54083008e+03 1.61088757e+03 2.78105981e+03 3.04544373e+02 2.18969070e+02 3.20224146e+03 3.45573914e+02 3.77085510e+02 3.60407829e+01 7.08155594e+01 8.95059662e+01 5.21659660e+01 2.64481735e+01 6.83696594e+01 1.15516731e+02 8.59555664e+01 -1.71183312e+00 -4.05100517e+01 2.35891705e+01 1.38786774e+02 1.40585068e+02 5.72315712e+01 -6.15553627e+01 -8.63970795e+01 -3.46653786e+01 -4.35279541e+01 -9.05693283e+01 -8.92135162e+01 -3.43474197e+01 1.22812643e+01 -4.20521088e+01 -1.54583664e+02 -1.75728394e+02 -9.17710724e+01 4.51661921e+00 5.81193848e+01 5.36612091e+01 8.47187881e+01 1.27798447e+02 1.53985016e+02 9.08034515e+01 -6.78293076e+01 -1.60045319e+02 -1.12999901e+02 -9.79868829e-01 8.29310684e+01 8.02442627e+01 4.73180122e+01 5.58261871e-01 9.72618103e+00 -1.34972706e+01 -3.97020531e+01 -8.20818710e+00 1.00326683e+02 2.08492996e+02 1.92063461e+02 3.15081558e+01 -4.23558617e+01 -4.27678251e+00 9.57627792e+01 8.29713440e+01 6.61482096e+00 9.04393005e+00 7.94183731e+01 1.60212875e+02 1.30473785e+02 2.07878399e+01 -7.20517960e+01 -3.76895447e+01 2.91356812e+01 6.66154251e+01 4.40745506e+01 5.20622215e+01 1.06241646e+02 1.59895401e+02 1.35665466e+02 1.06318573e+02 1.23280289e+02 1.68248886e+02 1.85911423e+02 1.59182556e+02 1.15922638e+02 6.04371796e+01 4.28730431e+01 6.29429855e+01 8.91014938e+01 8.53073502e+01 1.43206497e+02 2.30098938e+02 2.60491455e+02 1.80065933e+02 4.54949608e+01 -2.32028275e+01 1.31158743e+01 1.19517120e+02 2.17878082e+02 2.59944855e+02 2.40284637e+02 2.22716705e+02 2.37779053e+02 2.03971985e+02 1.11535583e+02 3.74943504e+01 6.18975410e+01 1.38667175e+02 1.61331528e+02 1.31750763e+02 6.87328568e+01 5.90053215e+01 1.04419807e+02 1.37498550e+02 1.33509125e+02 1.26484344e+02 1.70154861e+02 2.51917648e+02 2.65431061e+02 1.90794785e+02 1.07532776e+02 1.05936958e+02 1.75589111e+02 2.25399124e+02 2.29980286e+02 1.79613434e+02 1.21312134e+02 9.17529907e+01 1.22320145e+02 1.21998940e+02 8.65363541e+01 7.82877502e+01 1.35631424e+02 2.00339584e+02 1.97411087e+02 1.42364380e+02 1.08609993e+02 1.41149612e+02 1.67775909e+02 1.83046951e+02 1.57383850e+02 1.81427383e+02 2.21393585e+02 2.36233276e+02 1.71494553e+02 4.55767937e+01 -1.37030563e+01 3.82691650e+01 1.27737656e+02 1.49046280e+02 1.23110405e+02 8.79726181e+01 9.49678268e+01 9.68477631e+01 6.64290390e+01 1.50866938e+01 -1.15498514e+01 4.38608322e+01 1.54709335e+02 2.16530426e+02 1.56575302e+02 9.83540726e+01 1.00116028e+02 1.40318848e+02 1.04634216e+02 2.24720097e+01 3.06938572e+01 1.11040077e+02 1.79755844e+02 1.31349487e+02 2.07484093e+01 -3.59876366e+01 5.44108200e+00 8.78896637e+01 1.29761307e+02 1.31335251e+02 1.45964737e+02 1.67661240e+02 1.46560287e+02 8.38828354e+01 6.51411343e+00 4.77092400e+01 1.24454651e+02 1.82472336e+02 1.75283295e+02 1.28035965e+02 1.02594315e+02 8.26338577e+01 8.15115509e+01 6.06792908e+01 2.14797974e+01 4.85864944e+01 1.20745155e+02 1.77048203e+02 1.69982361e+02 9.01854858e+01 4.32842026e+01 5.59092865e+01 1.30195328e+02 1.64421265e+02 1.57752686e+02 1.63904663e+02 2.27191055e+02 2.52901566e+02 1.98088409e+02 1.15584297e+02 1.00635582e+02 1.36122406e+02 1.97708664e+02 2.29849472e+02 2.23348343e+02 1.90868607e+02 1.57033524e+02 1.61242264e+02 1.40832352e+02 1.16221161e+02 1.41830704e+02 1.90592453e+02 2.09961395e+02 2.02335403e+02 1.56481918e+02 1.46916229e+02 1.59769012e+02 1.77454803e+02 1.82998886e+02 1.57603027e+02 1.80942413e+02 2.19028915e+02 2.37839371e+02 2.43541382e+02 1.79348801e+02 1.40237869e+02 1.63916809e+02 2.25112213e+02 2.44480774e+02 1.98930237e+02 1.61732162e+02 1.62288223e+02 1.94248199e+02 1.92722137e+02 1.66689804e+02 1.58130524e+02 1.99532211e+02 2.13655914e+02 1.89861099e+02 1.64745270e+02 2.03255356e+02 2.15220840e+02 1.95768875e+02 1.72501724e+02 1.59960068e+02 1.82065109e+02 1.64631104e+02 1.51842377e+02 1.46710434e+02 1.37075531e+02 1.26903488e+02 1.18248169e+02 1.64377914e+02 1.83253693e+02 1.93445953e+02 1.61378815e+02 1.73824142e+02 1.76506836e+02 1.57435211e+02 1.27276230e+02 1.20194740e+02 1.76037750e+02 2.11315353e+02 2.11137970e+02 1.66537979e+02 1.47416824e+02 1.55384644e+02 1.76853027e+02 1.89441772e+02 1.62853943e+02 1.74931595e+02 1.96190338e+02 2.39499817e+02 2.54452072e+02 2.44494583e+02 2.10490173e+02 1.79845184e+02 2.01379837e+02 2.33315735e+02 2.50686447e+02 2.34348892e+02 2.47326050e+02 2.41406204e+02 2.17284348e+02 1.82046371e+02 1.86893280e+02 2.41265976e+02 2.55354507e+02 2.30511154e+02 1.88429443e+02 2.01457306e+02 2.23831955e+02 2.28393036e+02 2.19426788e+02 1.99714432e+02 2.05976440e+02 1.96503342e+02 2.26256714e+02 2.33508362e+02 2.36653351e+02 2.12236084e+02 2.07512161e+02 2.23008911e+02 2.43336334e+02 2.38915787e+02 2.43866272e+02 2.73409180e+02 2.92121368e+02 2.91187378e+02 2.77019043e+02 2.78961365e+02 2.92166748e+02 3.01763550e+02 2.89138519e+02 2.57561340e+02 2.39404205e+02 2.34999146e+02 2.37472031e+02 2.30795609e+02 2.10993881e+02 1.98815521e+02 1.88209991e+02 2.10416870e+02 2.23630447e+02 2.35849899e+02 2.31437668e+02 2.37207718e+02 2.45969971e+02 2.56957611e+02 2.53115906e+02 2.51420013e+02 2.66162231e+02 2.81389191e+02 2.72066406e+02 2.48337860e+02 2.42801544e+02 2.39669342e+02 2.22309677e+02 2.06797058e+02 2.00071350e+02 2.22787018e+02 2.24196686e+02 2.28363434e+02 2.40101761e+02 2.41324173e+02 2.27182449e+02 1.94942368e+02 1.90326523e+02 2.17816666e+02 2.43344635e+02 2.42347763e+02 2.23045975e+02 2.07996140e+02 2.16496643e+02 2.29881088e+02 2.44807938e+02 2.43287247e+02 2.30414230e+02 2.19597382e+02 2.03544144e+02 2.04475830e+02 2.04519669e+02 2.01993118e+02 2.02384979e+02 2.00586990e+02 2.21051392e+02 2.23276367e+02 2.26477982e+02 2.26891754e+02 2.22563263e+02 2.11820862e+02 1.84272186e+02 1.80519348e+02 1.98929169e+02 2.33589966e+02 2.51227478e+02 2.31338531e+02 2.07515656e+02 2.06415695e+02 2.34684662e+02 2.61326569e+02 2.54251892e+02 2.27093689e+02 2.11216782e+02 2.14007843e+02 2.29407867e+02 2.28596283e+02 2.18903824e+02 2.12305511e+02 2.11509521e+02 2.21975967e+02 2.22469757e+02 2.16099503e+02 2.11744125e+02 2.13367004e+02 2.21663818e+02 2.18924835e+02 2.17666733e+02 2.28753494e+02 2.41329071e+02 2.41325348e+02 2.20629501e+02 2.07685059e+02 2.11156830e+02 2.26999481e+02 2.35792526e+02 2.33470795e+02 2.23578827e+02 2.19903534e+02 2.19827179e+02 2.27111572e+02 2.27229218e+02 2.26726425e+02 2.25114258e+02 2.22728516e+02 2.26648712e+02 2.29042084e+02 2.34825500e+02 2.34037231e+02 2.31328171e+02 2.27330460e+02 2.22377014e+02 2.21523132e+02 2.24912003e+02 2.31186111e+02 2.33961899e+02 2.31172729e+02 2.26550125e+02 2.25549545e+02 2.28644089e+02 2.31439133e+02 2.30868790e+02 2.28618683e+02 2.28188034e+02 2.28448196e+02 2.28628845e+02 2.28538391e+02 2.28742157e+02 2.29574661e+02 2.30425720e+02 2.30854172e+02 2.31851013e+02 2.32380447e+02 2.30981155e+02 2.27717728e+02 2.26226929e+02 2.28806808e+02 2.32193649e+02 2.31329376e+02 2.25987808e+02 2.21051025e+02 2.22923599e+02 2.29727310e+02 2.32144623e+02 2.28959366e+02 2.22317184e+02 2.22890656e+02 2.29262909e+02 2.33530930e+02 2.38413040e+02 2.33113739e+02 2.35150421e+02 2.31439804e+02 2.31805328e+02 2.32445923e+02 2.35606598e+02 2.41377197e+02 2.37769257e+02 2.30827438e+02 2.21868271e+02 2.24625519e+02 2.34926025e+02 2.45540527e+02 2.38964828e+02 2.24475021e+02 2.14222137e+02 2.14836182e+02 2.24778381e+02 2.27888870e+02 2.29691208e+02 2.25078522e+02 2.29856003e+02 2.37198364e+02 2.46152740e+02 2.54274231e+02 2.51327484e+02 2.33911026e+02 2.20296234e+02 2.17454193e+02 2.25330048e+02 2.33224731e+02 2.45405869e+02 2.51165680e+02 2.34179413e+02 2.05757004e+02 1.95397446e+02 2.14009216e+02 2.39635864e+02 2.40525894e+02 2.15746552e+02 1.87858170e+02 1.91523636e+02 2.23511871e+02 2.55695755e+02 2.66647827e+02 2.46198441e+02 2.27529739e+02 2.29610107e+02 2.40460022e+02 2.48848663e+02 2.32182587e+02 2.31868729e+02 2.27028656e+02 2.16722992e+02 2.10584747e+02 2.11974533e+02 2.34386047e+02 2.30698273e+02 2.05759781e+02 1.75497772e+02 1.81917816e+02 2.25717560e+02 2.59583282e+02 2.45538483e+02 2.07015976e+02 1.77473541e+02 1.78687378e+02 2.13446777e+02 2.45619278e+02 2.61137512e+02 2.31909714e+02 2.16149460e+02 2.01650085e+02 2.03036377e+02 2.07092392e+02 2.00830521e+02 2.01427826e+02 1.79564972e+02 1.65386581e+02 1.63459274e+02 1.78394119e+02 2.14902939e+02 2.31250809e+02 2.08383194e+02 1.74121735e+02 1.61471237e+02 1.85360275e+02 2.19138107e+02 2.14663040e+02 1.90268417e+02 1.52239929e+02 1.47694412e+02 1.83768387e+02 2.20055984e+02 2.35870621e+02 2.06250137e+02 1.76464752e+02 1.78760468e+02 1.99585968e+02 2.32898239e+02 2.37166550e+02 2.32108398e+02 2.10447388e+02 1.79934753e+02 1.81625427e+02 2.11671631e+02 2.60384399e+02 2.75504364e+02 2.40715485e+02 1.98043900e+02 1.68184662e+02 1.88299576e+02 2.27052460e+02 2.46923691e+02 2.34372833e+02 2.03880814e+02 2.05458069e+02 2.27324142e+02 2.50139008e+02 2.48581009e+02 2.13429504e+02 1.85840454e+02 1.94197662e+02 2.16192291e+02 2.58779358e+02 2.54325821e+02 2.55910934e+02 2.36666611e+02 2.13362305e+02 1.98886032e+02 1.88178024e+02 2.20679123e+02 2.44890656e+02 2.30791992e+02 1.96367065e+02 1.64340836e+02 1.88380524e+02 2.28634644e+02 2.53943054e+02 2.14165024e+02 1.38775909e+02 1.03082787e+02 1.44253937e+02 2.21825485e+02 2.65611725e+02 2.37430359e+02 1.81749603e+02 1.38710510e+02 9.73696365e+01 5.51480064e+01 5.83873901e+01 7.62711945e+01 -1.38024060e+03 -2.90722925e+03 -7.72152734e+03 -1.68600625e+04 -382237856. -93150256. 159774448. 1627912. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.06372465e+10 -589859840. 59025448. 249763968. 142146384. -2.01766875e+04 -8.78452734e+03 -4.23833789e+03 -2.53446802e+03 -4.46829773e+02 -7.34166489e+01 -2.70117111e+01 9.41280174e+00 8.61959686e+01 1.93401154e+02 2.28485413e+02 2.00411667e+02 1.19425331e+02 7.76823578e+01 8.75672913e+01 1.51271561e+02 2.27219727e+02 2.27434402e+02 2.05804916e+02 1.81844147e+02 1.81382141e+02 1.74530533e+02 1.45028290e+02 1.81845749e+02 1.88590744e+02 1.25050545e+02 7.06089935e+01 1.09532738e+02 2.26992279e+02 2.90845490e+02 2.15258316e+02 1.20433884e+02 6.37197723e+01 9.22914200e+01 2.02297043e+02 2.87295776e+02 3.32340454e+02 2.40396927e+02 1.74230408e+02 1.62134109e+02 2.23319504e+02 2.64093414e+02 2.31567245e+02 2.24516708e+02 1.89510162e+02 1.48436096e+02 1.25050278e+02 1.59372223e+02 2.76559692e+02 2.86212189e+02 1.83195831e+02 5.68418922e+01 2.85149879e+01 1.29277161e+02 2.29235382e+02 2.29994080e+02 1.50023300e+02 1.17447136e+02 1.78787231e+02 2.95451843e+02 3.26908752e+02 2.88612946e+02 1.64894669e+02 7.32936096e+01 6.63227539e+01 1.45533798e+02 2.44822388e+02 3.14401245e+02 3.42393066e+02 3.18278839e+02 2.63010284e+02 1.94915527e+02 1.63373901e+02 1.78528702e+02 1.73713104e+02 9.76326675e+01 2.49240723e+01 2.44067802e+01 1.16443428e+02 1.80745514e+02 1.73470291e+02 1.36305267e+02 6.81274109e+01 2.10386181e+01 5.14926872e+01 1.53431824e+02 2.04373016e+02 1.44729065e+02 6.81559601e+01 8.52687836e+01 1.29891174e+02 1.47878448e+02 1.17537407e+02 1.41550751e+02 1.34659332e+02 9.05926132e+01 5.46567688e+01 8.54448547e+01 1.93010605e+02 2.01213654e+02 9.32014389e+01 -4.38864059e+01 -8.19513550e+01 1.18816853e+01 1.02165565e+02 1.46053925e+02 1.23218857e+02 9.47194443e+01 8.19315414e+01 1.16042999e+02 1.72247253e+02 2.02849670e+02 1.32925552e+02 2.69371910e+01 -8.13398743e+00 3.50508881e+01 7.43772964e+01 7.79702454e+01 1.19472061e+02 1.17207230e+02 3.32518616e+01 -7.70175171e+01 -6.41478043e+01 6.03652458e+01 1.15102715e+02 2.90958328e+01 -7.35014114e+01 -8.09610825e+01 2.41848660e+01 1.30119568e+02 1.61392776e+02 1.22462669e+02 3.59621811e+01 -3.48313293e+01 -1.95769253e+01 6.79492722e+01 1.35849152e+02 8.51251526e+01 -9.15378475e+00 -5.04463577e+01 -2.06607304e+01 3.30254974e+01 6.57686539e+01 1.24070198e+02 1.42050201e+02 1.13053238e+02 6.28929253e+01 5.87678070e+01 1.34254089e+02 1.64473740e+02 1.00618965e+02 -4.68200111e+01 -1.36545166e+02 -9.76294022e+01 4.34566269e+01 1.42361816e+02 1.25650879e+02 4.77311096e+01 1.64282036e+01 4.10471153e+01 4.89497681e+01 9.42111511e+01 6.97626190e+01 5.66124115e+01 1.27953281e+01 -5.40104103e+01 -7.85281067e+01 -1.01036644e+02 -5.54475129e-01 4.20991211e+01 -1.50294323e+01 -6.95192490e+01 -4.67781944e+01 8.79577637e+01 1.32447449e+02 1.00339767e+02 3.34999428e+01 -1.22277594e+01 -2.21896381e+01 1.45689545e+01 3.81042442e+01 4.66548004e+01 -2.20448246e+01 -4.01980019e+00 3.28753357e+01 9.94770737e+01 1.74800003e+02 2.26117249e+02 2.66655151e+02 1.91840805e+02 6.85826645e+01 -1.45216703e+00 5.84152102e-01 6.93937912e+01 7.85654526e+01 -7.53263855e+00 -1.08669510e+02 -1.43164291e+02 -2.73430347e+01 1.29083496e+02 1.96365906e+02 1.60523315e+02 8.70310593e+01 5.53641090e+01 6.42721863e+01 8.78936920e+01 1.32534698e+02 9.31219711e+01 3.13303394e+01 -1.63540668e+01 3.43605995e+01 5.66155930e+01 7.59765472e+01 1.04699608e+02 1.15308533e+02 7.55198441e+01 3.23267365e+01 4.27228165e+01 4.37135925e+01 9.71142673e+00 -5.51354332e+01 -8.70279770e+01 -1.03169785e+02 -5.78611794e+01 -2.30531902e+01 6.32567940e+01 9.29950790e+01 4.13357239e+01 -4.70004768e+01 -7.16302719e+01 -1.97473736e+01 2.35419579e+01 7.94618511e+00 -2.29189086e+00 -1.04262276e+01 -1.78463840e+01 -1.68273811e+01 -1.18391714e+01 -1.10247765e+01 -1.18232422e+01 -3.47246170e+01 -4.13606834e+01 -7.48994598e+01 -6.22387428e+01 -5.43145065e+01 -3.12084789e+01 -3.98609238e+01 -4.04429436e+01 -1.82512226e+01 -1.56317406e+01 1.40437710e+00 1.05158415e+01 2.31939831e+01 9.46066856e+00 -2.01411991e+01 -2.15601406e+01 -2.38775463e+01 -3.42112007e+01 -5.25342560e+01 -4.72361908e+01 -4.08601036e+01 -3.92606468e+01 -4.96023674e+01 -4.40952187e+01 -4.01900635e+01 -4.64985313e+01 -6.60059357e+01 -7.01380844e+01 -8.52031174e+01 -8.75321121e+01 -7.75702515e+01 -6.83169785e+01 -5.64763145e+01 -7.05643082e+01 -7.33450623e+01 -8.08000488e+01 -7.30896301e+01 -6.94195404e+01 -4.92188416e+01 -5.20697174e+01 -5.55636940e+01 -7.96488800e+01 -6.95263901e+01 -7.09825516e+01 -6.72073669e+01 -7.02370453e+01 -5.05616798e+01 -4.76482162e+01 -6.28845901e+01 -7.83654556e+01 -6.96674194e+01 -6.73846970e+01 -8.12660904e+01 -7.18295059e+01 -4.70043259e+01 -3.39026718e+01 -4.35348129e+01 -4.77878113e+01 -5.24736099e+01 -4.66083565e+01 -5.97890472e+01 -5.23587685e+01 -5.76229019e+01 -5.18759995e+01 -4.62949905e+01 -4.03055077e+01 -5.06685867e+01 -6.17447395e+01 -7.35377121e+01 -6.09444504e+01 -8.07756805e+01 -1.16078506e+02 -1.27561157e+02 -1.03581688e+02 -6.05663948e+01 -5.91919250e+01 -6.49966354e+01 -6.85336456e+01 -6.70922165e+01 -5.57501335e+01 -5.23277168e+01 -5.76403275e+01 -5.81772194e+01 -5.32634811e+01 -4.44253578e+01 -6.56355972e+01 -7.60220795e+01 -7.83223724e+01 -7.38926697e+01 -8.23099594e+01 -8.27380981e+01 -8.12778244e+01 -7.71282654e+01 -6.03261414e+01 -5.24885368e+01 -5.93329048e+01 -8.24687805e+01 -9.82680664e+01 -9.32548676e+01 -7.95816269e+01 -6.75724869e+01 -7.07012253e+01 -1.00475624e+02 -1.28947327e+02 -1.25468819e+02 -1.03538757e+02 -7.10643921e+01 -7.19720764e+01 -7.55375824e+01 -9.33106232e+01 -1.08085022e+02 -1.23005768e+02 -1.37700302e+02 -1.41389343e+02 -1.40604538e+02 -1.34327118e+02 -1.13997574e+02 -1.06260712e+02 -1.09550812e+02 -1.16659500e+02 -1.10134056e+02 -1.15045494e+02 -1.26879990e+02 -1.31055130e+02 -1.26989281e+02 -1.15731308e+02 -1.20822334e+02 -1.44787445e+02 -1.78601471e+02 -1.74299835e+02 -1.35334076e+02 -1.04687325e+02 -1.22593956e+02 -1.59202866e+02 -1.64065933e+02 -1.54095673e+02 -1.24735664e+02 -1.35052307e+02 -1.48766708e+02 -1.61076416e+02 -1.60072830e+02 -1.52687897e+02 -1.63857880e+02 -1.89227234e+02 -2.13554474e+02 -1.89013901e+02 -1.42415222e+02 -1.25897789e+02 -1.44755249e+02 -1.52746201e+02 -1.44585663e+02 -1.33468231e+02 -1.28595520e+02 -1.43150833e+02 -1.65784164e+02 -1.75037888e+02 -1.50913895e+02 -1.18311012e+02 -1.19708626e+02 -1.31805328e+02 -1.41635666e+02 -1.19282196e+02 -8.04837494e+01 -6.82665710e+01 -1.04578690e+02 -1.38750381e+02 -1.51045471e+02 -1.45084869e+02 -1.66161850e+02 -1.73925018e+02 -1.37518616e+02 -8.83114319e+01 -7.87940750e+01 -1.14102013e+02 -1.52021408e+02 -1.53861359e+02 -1.54304779e+02 -1.32719223e+02 -1.15820206e+02 -1.25671349e+02 -1.49248123e+02 -1.80135147e+02 -1.75023605e+02 -1.79143356e+02 -1.43628403e+02 -9.63749008e+01 -9.48934860e+01 -1.21067719e+02 -1.51517532e+02 -1.60632187e+02 -1.77658203e+02 -1.92101898e+02 -1.75118835e+02 -1.56691895e+02 -1.46751495e+02 -1.48257217e+02 -1.53971817e+02 -1.47240128e+02 -1.39825409e+02 -1.34072983e+02 -1.35392853e+02 -1.32591797e+02 -2.07184494e+02 -1.20177010e+02 -3.67939880e+02 -4.78040405e+02 -6.97223633e+02 -2.51575439e+03 -4.09828223e+03 -1.01045557e+04 -3.62242163e+03 -8.17192139e+03 -2.59109492e+04 -84643824. -169784160. 76916320. -100493344. 179656800. 60456676. -701517568. 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. 0. 0. -1133359616. -1133359616. -1133359616. 0. 0. 466143744. 180400144. 93516384. -1.93080703e+04 -9.08322461e+03 -1.81823669e+03 -1.31062341e+03 -3.37692554e+03 -2.14565161e+03 -4.98082336e+02 -2.78414032e+02 -2.24804428e+02 -2.33188339e+02 -2.34575226e+02 -2.32169861e+02 -2.25427032e+02 -2.30666946e+02 -2.36454514e+02 -2.38976135e+02 -2.35570267e+02 -2.18432358e+02 -2.10641357e+02 -2.14458359e+02 -2.31616821e+02 -2.31738968e+02 -2.18937943e+02 -1.97859192e+02 -1.93286392e+02 -1.90366760e+02 -1.86276764e+02 -1.81992584e+02 -1.78552444e+02 -1.77396072e+02 -1.75129669e+02 -1.74214966e+02 -1.73598953e+02 -1.75456955e+02 -1.81028091e+02 -1.79515930e+02 -1.80151123e+02 -1.76314499e+02 -1.85447922e+02 -1.87693359e+02 -1.85453156e+02 -1.78802612e+02 -1.76570251e+02 -1.76559418e+02 -1.79143234e+02 -1.85607056e+02 -2.03791595e+02 -2.18625443e+02 -2.22083466e+02 -2.14198364e+02 -2.03778107e+02 -1.98425980e+02 -1.92976532e+02 -1.97870377e+02 -2.06927414e+02 -2.07647568e+02 -2.01583466e+02 -1.94728653e+02 -1.95535965e+02 -1.90544342e+02 -1.97051575e+02 -2.07507706e+02 -2.14668701e+02 -2.20783936e+02 -2.22684860e+02 -2.23983917e+02 -2.18434311e+02 -2.14120911e+02 -2.16077087e+02 -2.15935883e+02 -2.04307129e+02 -2.00006546e+02 -2.01780670e+02 -2.10735779e+02 -2.12696442e+02 -2.09802246e+02 -2.20209457e+02 -2.35732773e+02 -2.34810455e+02 -2.28963379e+02 -2.20015030e+02 -2.39087769e+02 -2.53498077e+02 -2.55136841e+02 -2.42071075e+02 -2.34154205e+02 -2.35090698e+02 -2.36719193e+02 -2.31035767e+02 -2.31552322e+02 -2.41799637e+02 -2.53491119e+02 -2.49275253e+02 -2.34956589e+02 -2.22729523e+02 -2.18930466e+02 -2.21484344e+02 -2.24226151e+02 -2.28224472e+02 -2.19121841e+02 -2.11284271e+02 -2.15732590e+02 -2.26365952e+02 -2.28186646e+02 -2.20256104e+02 -2.15279678e+02 -2.26681839e+02 -2.34851761e+02 -2.34510361e+02 -2.24373154e+02 -2.15260361e+02 -2.13988724e+02 -2.14675537e+02 -2.16610260e+02 -2.18294220e+02 -2.20879990e+02 -2.21164093e+02 -2.21309067e+02 -2.22647659e+02 -2.24697876e+02 -2.26309525e+02 -2.25467834e+02 -2.24230865e+02 -2.23788849e+02 -2.24181824e+02 -2.24680984e+02 -2.30761520e+02 -2.37205505e+02 -2.37070938e+02 -2.31848648e+02 -2.26520157e+02 -2.32807358e+02 -2.38851761e+02 -2.38796463e+02 -2.33864182e+02 -2.29837326e+02 -2.29864792e+02 -2.28624115e+02 -2.26143112e+02 -2.26942535e+02 -2.28303772e+02 -2.28675964e+02 -2.26932632e+02 -2.24502792e+02 -2.24640198e+02 -2.26153488e+02 -2.28717529e+02 -2.28852173e+02 -2.29396988e+02 -2.29049088e+02 -2.30219498e+02 -2.33537766e+02 -2.36986496e+02 -2.36817200e+02 -2.33979248e+02 -2.30591110e+02 -2.32431763e+02 -2.34266159e+02 -2.34003433e+02 -2.31219299e+02 -2.29145264e+02 -2.29245590e+02 -2.29398254e+02 -2.29429718e+02 -2.29287949e+02 -2.29382004e+02 -2.29240601e+02 -2.29067490e+02 -2.28878723e+02 -2.29297836e+02 -2.29501480e+02 -2.29265778e+02 -2.28832550e+02 -2.28632919e+02 -2.28632812e+02 -2.28647949e+02 -2.28455460e+02 -2.28021362e+02 -2.27767502e+02 -2.27883255e+02 -2.28239029e+02 -2.28243225e+02 -2.28668457e+02 -2.27744476e+02 -2.25847183e+02 -2.25095657e+02 -2.26243515e+02 -2.27848648e+02 -2.27482452e+02 -2.26962387e+02 -2.27298431e+02 -2.27445648e+02 -2.26493408e+02 -2.26111313e+02 -2.23054367e+02 -2.20123489e+02 -2.19695007e+02 -2.22790573e+02 -2.25950333e+02 -2.24299088e+02 -2.23987610e+02 -2.20748825e+02 -2.17957489e+02 -2.18239532e+02 -2.23335953e+02 -2.28172409e+02 -2.27385696e+02 -2.26157074e+02 -2.24836182e+02 -2.25994858e+02 -2.26969559e+02 -2.28303070e+02 -2.28688263e+02 -2.27487137e+02 -2.26793350e+02 -2.27013397e+02 -2.26633041e+02 -2.29559570e+02 -2.31334793e+02 -2.33969208e+02 -2.34027084e+02 -2.31793686e+02 -2.31440933e+02 -2.31504593e+02 -2.31634247e+02 -2.29932999e+02 -2.28882675e+02 -2.30488419e+02 -2.28657898e+02 -2.27786026e+02 -2.27771988e+02 -2.31618240e+02 -2.32575653e+02 -2.30639908e+02 -2.28386353e+02 -2.26811111e+02 -2.27619186e+02 -2.25155823e+02 -2.25370010e+02 -2.21111526e+02 -2.20401199e+02 -2.20069611e+02 -2.26377487e+02 -2.34428284e+02 -2.29819580e+02 -2.16840378e+02 -2.06674789e+02 -2.09363312e+02 -2.15305527e+02 -2.17761749e+02 -2.14514664e+02 -2.12228210e+02 -2.09240463e+02 -2.10410080e+02 -2.11886276e+02 -2.13897507e+02 -2.17896820e+02 -2.21912415e+02 -2.23899643e+02 -2.20259232e+02 -2.15266937e+02 -2.10707855e+02 -2.10909439e+02 -2.13574844e+02 -2.16215378e+02 -2.19093979e+02 -2.19554337e+02 -2.19744339e+02 -2.14307877e+02 -2.02352737e+02 -1.91645813e+02 -1.90218002e+02 -1.97571625e+02 -2.07997131e+02 -2.12316422e+02 -2.12017685e+02 -2.04262207e+02 -1.93632111e+02 -1.87682373e+02 -1.84156006e+02 -1.92866180e+02 -2.00825485e+02 -2.14089676e+02 -2.10951141e+02 -2.08429901e+02 -2.07853256e+02 -2.12659134e+02 -2.14496414e+02 -2.17237183e+02 -2.13561035e+02 -2.08976700e+02 -2.01796936e+02 -1.97217300e+02 -1.96028030e+02 -1.81724564e+02 -1.69472900e+02 -1.74288879e+02 -1.92869278e+02 -2.08332092e+02 -1.99308853e+02 -1.90166504e+02 -193. -1.96913971e+02 -1.87357071e+02 -1.68595032e+02 -1.67540161e+02 -1.83368347e+02 -2.02590988e+02 -1.95222672e+02 -1.90441406e+02 -1.93172180e+02 -2.03370590e+02 -2.05269943e+02 -2.01493378e+02 -1.98143799e+02 -2.04831390e+02 -2.16596085e+02 -2.16411911e+02 -2.13099167e+02 -2.05992615e+02 -2.08644180e+02 -1.95383850e+02 -1.80000931e+02 -1.72040359e+02 -1.64771225e+02 -1.50649368e+02 -1.33926514e+02 -1.29564270e+02 -1.41275757e+02 -1.43266846e+02 -1.55020798e+02 -1.55615479e+02 -1.73342514e+02 -1.98695679e+02 -2.28700043e+02 -2.34164459e+02 -2.23466858e+02 -2.14176331e+02 -2.09885559e+02 -2.07318710e+02 -2.01699402e+02 -2.03334213e+02 -2.08242310e+02 -1.93223480e+02 -1.66122803e+02 -1.55837494e+02 -1.60297180e+02 -1.78586090e+02 -1.82326218e+02 -1.84998138e+02 -1.95926178e+02 -1.79769257e+02 -1.74059067e+02 -1.65581863e+02 -1.67053116e+02 -1.54939056e+02 -1.31295258e+02 -1.43150894e+02 -1.66416397e+02 -1.76978943e+02 -1.49715363e+02 -1.41746445e+02 -1.52782547e+02 -1.80826157e+02 -1.59244858e+02 -1.37671906e+02 -1.28927780e+02 -1.42685501e+02 -1.59852448e+02 -1.33967789e+02 -1.11063828e+02 -1.14618835e+02 -1.44500183e+02 -1.70152115e+02 -1.48914886e+02 -1.34804123e+02 -1.57893341e+02 -1.94251495e+02 -1.77355301e+02 -1.36198837e+02 -1.13897995e+02 -1.20596977e+02 -1.32882507e+02 -1.34300873e+02 -1.13629349e+02 -9.07527084e+01 -9.48878555e+01 -1.37075729e+02 -1.66781006e+02 -1.65954895e+02 -1.56135910e+02 -1.54732910e+02 -1.58200027e+02 -1.61186234e+02 -1.60037872e+02 -1.48102646e+02 -1.44838699e+02 -1.57817917e+02 -1.59442047e+02 -1.54202820e+02 -1.27200531e+02 -1.12905724e+02 -1.20506454e+02 -1.28367477e+02 -1.45452011e+02 -1.43509979e+02 -1.46223877e+02 -1.55407181e+02 -1.65027634e+02 -1.61979843e+02 -1.15680069e+02 -7.86716766e+01 -1.15348976e+02 -1.81655670e+02 -1.86497894e+02 -1.26063118e+02 -1.05251740e+02 -1.37662399e+02 -1.59573944e+02 -1.36327637e+02 -1.18053345e+02 -1.20274796e+02 -1.43514877e+02 -1.29198212e+02 -1.19967194e+02 -1.12577606e+02 -1.30724808e+02 -1.53706223e+02 -1.47157410e+02 -1.44735733e+02 -1.14423607e+02 -9.41745682e+01 -8.68814011e+01 -1.17979691e+02 -1.17482483e+02 -6.44934464e+01 -2.58529263e+01 -4.86962166e+01 -9.79736023e+01 -9.71192245e+01 -7.15087433e+01 -9.66108704e+01 -1.55145340e+02 -1.81829178e+02 -1.49675125e+02 -1.19881897e+02 -1.17943245e+02 -1.20784363e+02 -1.02929764e+02 -1.00145424e+02 -1.01414055e+02 -1.12623840e+02 -1.23587021e+02 -1.37871460e+02 -1.44722092e+02 -1.38000473e+02 -1.22096260e+02 -9.92507172e+01 -8.93293991e+01 -8.63849487e+01 -7.42919006e+01 -7.07889938e+01 -8.44006958e+01 -1.08079445e+02 -1.01071846e+02 -6.40747604e+01 -5.51532745e+01 -6.39856529e+01 -4.81249771e+01 6.88500834e+00 3.97421112e+01 8.90965748e+00 -5.53801193e+01 -6.78577881e+01 -5.31705208e+01 -4.86595802e+01 -7.92290649e+01 -1.02507408e+02 -1.10179733e+02 -1.11846199e+02 -1.17654724e+02 -1.02461388e+02 -1.06044357e+02 -1.14755356e+02 -1.15916016e+02 -6.35524406e+01 -3.30872688e+01 -6.58832626e+01 -9.55173340e+01 -5.59910393e+01 -2.01758423e+01 -5.56438560e+01 -1.29613800e+02 -1.75493637e+02 -1.68721069e+02 -1.59894897e+02 -1.38241898e+02 -1.36427979e+02 -1.30754379e+02 -1.41178024e+02 -1.18566528e+02 -1.10067566e+02 -1.02663170e+02 -1.33294403e+02 -1.03743919e+02 -3.76386452e+01 1.33752937e+01 2.23557911e+01 7.83926773e+00 -1.46939383e+01 -4.09408607e+01 -7.40657806e+01 -7.22140884e+01 -8.03624115e+01 -7.78149338e+01 -8.11994019e+01 -6.88690338e+01 -7.54690323e+01 -7.40068130e+01 -7.01912155e+01 -7.53312378e+01 -7.35541992e+01 -8.28928223e+01 -3.18328667e+01 1.10161600e+01 1.76400833e+01 -2.45018482e+01 -5.59628525e+01 -4.66024170e+01 -4.19540825e+01 -4.13205414e+01 -4.65883484e+01 -4.45153770e+01 -4.51489296e+01 -1.92171249e+01 1.56581287e+01 3.02383661e+00 -3.78127327e+01 -4.39967842e+01 2.83288422e+01 7.62090149e+01 4.08703346e+01 -2.75898590e+01 -3.04687538e+01 6.15630913e+00 5.04284811e+00 -1.76387520e+01 -4.92768135e+01 -1.19593744e+01 1.89970894e+01 4.54586143e+01 6.25085487e+01 1.82646675e+01 -8.11652756e+00 -1.19363203e+01 6.62561340e+01 9.68729401e+01 4.03989258e+01 -2.91561203e+01 -1.39671535e+01 4.94913177e+01 6.17609596e+01 3.00048599e+01 -8.87591934e+00 2.10129204e+01 5.64579124e+01 7.44780273e+01 5.01100540e+01 1.92101421e+01 2.33337092e+00 4.08713989e+01 8.23964615e+01 9.56488342e+01 6.02707863e+01 1.32466996e+00 2.65316639e+01 5.78919449e+01 6.29466133e+01 2.62202606e+01 2.81370945e+01 7.44591904e+01 6.59056854e+01 2.14622726e+01 -2.93050175e+01 -3.52119980e+01 -3.95472183e+01 -4.37833786e+00 3.83629608e+01 6.41146927e+01 4.18057861e+01 7.37052441e+00 -7.01336622e+00 -5.34921765e-01 2.75678005e+01 6.74022446e+01 2.11523483e+02 3.34201874e+02 2.18791718e+02 3.36946564e+02 5.82100830e+02 6.54139343e+02 7.27754578e+02 3.94476685e+02 3.02642609e+02 2.80897974e+03 4.15544629e+03 -1.44161536e+03 6.09277930e+03 1.87852402e+04 16086440. 2.50198897e+10 0. 0. 0. 0. -3.88826496e+09 -3.88826496e+09 -17269332. 2.82984243e+09 7.00192109e+04 6.69585438e+05 1.04387962e+06 2.31803575e+06 -3.29552650e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.37251052e+10 -4.24189250e+06 9.54083008e+03 1.61088757e+03 -2.88534302e+03 2.73519745e+02 1.18816357e+03 -4.23493164e+03 -3.25687891e+03 -7.38516541e+02 -6.96857849e+02 -1.88169846e+02 -1.35752344e+01 1.08661331e+02 1.13466080e+02 3.16553078e+01 1.17180462e+01 5.17071228e+01 2.57614765e+01 -5.26258392e+01 -1.18557007e+02 -4.63404694e+01 1.01046684e+02 1.70225266e+02 1.23306374e+02 2.12008266e+01 -2.52251434e+01 -3.85802579e+00 2.31663418e+01 -4.17670250e+00 -5.32311401e+01 -2.18342609e+01 5.01847992e+01 9.32353210e+01 6.72860107e+01 -3.82701445e+00 -2.31758404e+01 3.33189201e+01 1.30068634e+02 1.69242645e+02 1.29158234e+02 1.21937988e+02 1.64070328e+02 1.38635803e+02 4.20872192e+01 -3.63988686e+01 3.50111580e+01 2.09210068e+02 2.49718552e+02 1.68677505e+02 7.24070511e+01 2.72983494e+01 3.66997070e+01 5.68615379e+01 6.93763809e+01 4.49059677e+01 5.22559586e+01 1.63357254e+02 2.42204758e+02 2.17337967e+02 1.17070656e+02 5.63800049e+01 8.86707077e+01 1.44566208e+02 1.76584320e+02 1.26589653e+02 1.21015564e+02 1.44472061e+02 1.14625061e+02 3.93475494e+01 -4.43323975e+01 -3.29833794e+01 8.59837646e+01 1.35794189e+02 1.03783180e+02 2.14155197e+01 3.75379944e+01 1.13291840e+02 9.32810898e+01 4.41025581e+01 1.12642574e+01 5.52315102e+01 1.60381058e+02 1.99904922e+02 1.73162521e+02 6.36213303e+01 -1.23270869e+00 1.89316711e+01 6.87097778e+01 7.29608536e+01 2.10245399e+01 2.17883568e+01 8.42726212e+01 1.16671539e+02 6.09117851e+01 -3.47080879e+01 -4.14198952e+01 4.76830902e+01 1.37449554e+02 1.39289200e+02 7.77240829e+01 6.05505257e+01 8.02092590e+01 4.43956909e+01 -3.14647160e+01 -7.52952805e+01 -1.38797677e+00 1.15120499e+02 1.83976440e+02 1.48796494e+02 8.15710449e+01 -5.43361330e+00 -4.85370140e+01 -3.59465981e+01 -9.46242142e+00 -1.82821789e+01 -5.44452572e+00 7.00904846e+01 1.45597687e+02 1.07740829e+02 -1.39676199e+01 -5.93788414e+01 -3.28182530e+00 1.14958107e+02 1.65782700e+02 1.09410324e+02 5.89779091e+01 4.38135452e+01 6.27106323e+01 2.06883698e+01 -6.44055252e+01 -5.96696434e+01 3.30056725e+01 1.11813049e+02 1.09338310e+02 4.77550240e+01 9.75688744e+00 1.15209162e+00 2.60812225e+01 6.86688995e+01 9.04662628e+01 3.80969772e+01 1.78554382e+01 6.30041122e+01 1.00258034e+02 1.05141563e+02 7.77127991e+01 7.89063034e+01 1.19963112e+02 1.16764648e+02 8.13304672e+01 3.64870148e+01 2.00981579e+01 6.96964874e+01 9.18163300e+01 7.66464157e+01 4.30081558e+01 7.37306671e+01 1.92943314e+02 2.44040176e+02 1.82136490e+02 7.98020782e+01 6.10710449e+01 1.11019707e+02 1.40772415e+02 1.33772049e+02 1.37873734e+02 1.76398621e+02 2.27003784e+02 2.37900803e+02 2.14613312e+02 1.44856583e+02 9.57001266e+01 1.31891541e+02 1.62176010e+02 1.52921814e+02 1.10371117e+02 1.36509552e+02 2.23652451e+02 2.12434494e+02 1.76082413e+02 1.43231522e+02 1.88717834e+02 2.83505280e+02 3.23703491e+02 2.75581238e+02 1.82958939e+02 1.26664185e+02 1.40723389e+02 1.25116501e+02 1.06382294e+02 1.19657997e+02 1.79921097e+02 2.51701263e+02 2.43439667e+02 1.90543411e+02 9.17893524e+01 4.68366356e+01 7.46050339e+01 1.45618240e+02 1.98680969e+02 2.01788971e+02 2.14545715e+02 2.41968582e+02 2.21154312e+02 1.67987656e+02 1.02014328e+02 1.38995972e+02 2.25058304e+02 2.60992828e+02 2.13182785e+02 1.11457886e+02 8.68712921e+01 1.25951912e+02 1.87569321e+02 1.64302567e+02 1.19268379e+02 1.23674309e+02 1.79992233e+02 1.99856094e+02 1.44940567e+02 6.61701660e+01 6.04874077e+01 9.96314697e+01 1.40978409e+02 1.37814560e+02 1.20183823e+02 1.22869118e+02 1.45331848e+02 1.26194649e+02 9.80838470e+01 8.96564865e+01 1.00405083e+02 1.46303116e+02 1.59463928e+02 1.52545197e+02 1.49428253e+02 1.47511444e+02 1.77443741e+02 1.44932968e+02 1.11688431e+02 8.65305710e+01 1.07204605e+02 1.86934311e+02 2.41859680e+02 2.31851379e+02 1.43884338e+02 9.24746704e+01 9.21955643e+01 1.30275146e+02 1.53169861e+02 1.27218575e+02 1.23223984e+02 1.43494492e+02 1.64612564e+02 1.43913742e+02 1.26421196e+02 1.69155624e+02 2.24351746e+02 2.12064240e+02 1.82773926e+02 1.64897583e+02 1.79768524e+02 2.11213760e+02 1.75000122e+02 1.50510773e+02 1.22192429e+02 1.42539139e+02 1.88872559e+02 2.14001572e+02 2.31105759e+02 1.94406967e+02 1.73513916e+02 1.67514481e+02 1.95365952e+02 2.00160629e+02 1.95306427e+02 2.05214630e+02 2.26752960e+02 2.36913605e+02 1.94339417e+02 1.68607605e+02 1.70618301e+02 2.03085541e+02 1.94751328e+02 1.77411255e+02 1.60127502e+02 1.50045868e+02 1.58847321e+02 1.54866989e+02 1.89879547e+02 2.02410126e+02 2.16586441e+02 2.11656525e+02 2.00842255e+02 1.89579880e+02 1.54364014e+02 1.41153122e+02 1.47463989e+02 1.96902695e+02 2.06572281e+02 1.98539856e+02 1.82850510e+02 1.93500412e+02 1.81095901e+02 1.38291763e+02 1.16089775e+02 1.34946716e+02 1.90766632e+02 2.04926453e+02 1.86690079e+02 1.55756790e+02 1.49044479e+02 1.77923447e+02 1.81350616e+02 1.85293610e+02 1.53320129e+02 1.43638885e+02 1.38881546e+02 1.67323303e+02 1.76777542e+02 1.62741837e+02 1.42853302e+02 1.56843597e+02 1.87033051e+02 1.75413773e+02 1.58448074e+02 1.58782532e+02 1.76477692e+02 1.76921158e+02 1.49086914e+02 1.36867172e+02 1.46610992e+02 1.81767776e+02 1.80882248e+02 1.71058945e+02 1.54136017e+02 1.63274399e+02 1.79003586e+02 1.76514633e+02 1.81194061e+02 1.64590225e+02 1.60743774e+02 1.57742050e+02 1.70347534e+02 1.73755264e+02 1.64858704e+02 1.53406876e+02 1.61859924e+02 1.83580460e+02 1.90075500e+02 1.91816437e+02 1.98295090e+02 2.16505157e+02 2.09629593e+02 1.90566330e+02 1.88645920e+02 2.01297775e+02 2.16888397e+02 1.98802704e+02 1.89645981e+02 1.80864182e+02 1.69749481e+02 1.66790359e+02 1.77218628e+02 2.05459824e+02 2.11396927e+02 1.93651581e+02 1.73698166e+02 1.83701340e+02 2.05203262e+02 2.19076599e+02 2.05235718e+02 1.94280685e+02 1.97178940e+02 2.02324997e+02 2.11694473e+02 2.22742828e+02 2.37975372e+02 2.31978745e+02 2.16009094e+02 2.11571823e+02 2.17199203e+02 2.26183914e+02 2.08381348e+02 2.01200638e+02 1.95502258e+02 1.98342682e+02 1.98967239e+02 2.06767365e+02 2.26473389e+02 2.32151016e+02 2.16831085e+02 1.91632355e+02 1.83225174e+02 2.03304138e+02 2.21678192e+02 2.22508514e+02 2.09449158e+02 2.00788635e+02 2.05012924e+02 2.15911407e+02 2.21101776e+02 2.15660767e+02 1.99268234e+02 1.96264069e+02 2.03427658e+02 2.13160385e+02 2.22970688e+02 2.21425903e+02 2.16744049e+02 2.04559372e+02 1.92847687e+02 1.88221634e+02 1.95148605e+02 2.09427521e+02 2.16095230e+02 2.09073227e+02 1.99646286e+02 2.00124939e+02 2.08708221e+02 2.15673096e+02 2.12060379e+02 2.03851807e+02 1.98008804e+02 1.97722809e+02 2.01836060e+02 2.04898056e+02 2.06955048e+02 2.03598038e+02 2.01901642e+02 2.00391205e+02 2.01711868e+02 2.02334518e+02 2.01130936e+02 1.99701675e+02 1.98747482e+02 1.99007233e+02 1.99742722e+02 2.00180573e+02 2.00133057e+02 1.99593033e+02 1.99580856e+02 2.01027527e+02 2.02440933e+02 2.01551987e+02 1.98497604e+02 1.96221878e+02 1.96881943e+02 1.98642990e+02 1.98375412e+02 1.96063416e+02 1.94679688e+02 1.94014175e+02 1.97398376e+02 1.99457138e+02 2.02723587e+02 2.02964844e+02 2.00114990e+02 1.96859299e+02 1.92473175e+02 1.93855225e+02 1.97149231e+02 2.02555984e+02 2.02388458e+02 1.97470047e+02 1.90078033e+02 1.92914215e+02 1.98843674e+02 2.02993744e+02 1.96850967e+02 1.86278091e+02 1.85755371e+02 1.93636459e+02 2.08127365e+02 2.07844986e+02 1.96415283e+02 1.86266388e+02 1.80635651e+02 1.92735428e+02 1.97065826e+02 2.01618378e+02 2.01129501e+02 2.01696167e+02 2.01933197e+02 1.95767944e+02 1.99921127e+02 2.05492950e+02 2.03206787e+02 1.93335022e+02 1.75521545e+02 1.70164047e+02 1.81140244e+02 2.07577515e+02 2.28845444e+02 2.25529373e+02 2.00081039e+02 1.73732376e+02 1.64103714e+02 1.84267151e+02 2.06640762e+02 2.11210083e+02 1.94124451e+02 1.74037186e+02 1.79584061e+02 1.94269394e+02 2.11641830e+02 2.14716904e+02 2.09275711e+02 1.93334579e+02 1.75380051e+02 1.76340042e+02 1.95348190e+02 2.22253143e+02 2.29021301e+02 2.05212021e+02 1.79732224e+02 1.81273407e+02 2.04590805e+02 2.18236435e+02 2.10519882e+02 1.97163910e+02 1.91028580e+02 1.85382706e+02 1.91824554e+02 2.00144897e+02 1.92048782e+02 1.89972748e+02 1.78178085e+02 1.92043106e+02 2.01904358e+02 2.20781250e+02 2.29824585e+02 2.17350006e+02 1.99462448e+02 1.73258987e+02 1.61825226e+02 1.76622559e+02 2.04426086e+02 2.09209213e+02 1.81137299e+02 1.46825012e+02 1.49965714e+02 1.71335754e+02 2.06648148e+02 2.14082321e+02 2.00018845e+02 1.82394608e+02 1.76897720e+02 2.06380005e+02 2.30515610e+02 2.51852341e+02 2.43644470e+02 2.09627884e+02 2.09621796e+02 2.21981842e+02 2.54888031e+02 2.60356384e+02 2.50085373e+02 2.25325607e+02 1.79805878e+02 1.58188446e+02 1.67727692e+02 2.03558060e+02 2.24886963e+02 1.95935760e+02 1.57704285e+02 1.57276306e+02 2.00074005e+02 2.33930893e+02 2.21061356e+02 1.79471603e+02 1.44992783e+02 1.39461182e+02 1.76868439e+02 2.20532349e+02 2.31222290e+02 2.24388351e+02 2.07976196e+02 1.93417297e+02 1.68611954e+02 1.64958786e+02 1.76178421e+02 1.88081772e+02 1.69985428e+02 1.30271835e+02 1.03730766e+02 1.36406952e+02 1.90147583e+02 2.18889404e+02 1.93321121e+02 1.38031006e+02 1.29104752e+02 1.53406021e+02 2.03654037e+02 2.07449356e+02 1.76316177e+02 1.61105621e+02 1.58201538e+02 1.92748398e+02 2.01489075e+02 1.94107162e+02 1.79016556e+02 1.49734390e+02 1.56580856e+02 1.60921860e+02 2.05067368e+02 2.39790695e+02 2.30734451e+02 2.01822998e+02 1.53778671e+02 1.18190590e+02 1.16601891e+02 1.55511032e+02 2.41503128e+02 2.60951691e+02 2.42132370e+02 2.94320892e+02 6.08699524e+02 4.51857861e+03 9.98805273e+03 68677808. -338659552. 201786704. -245724176. 362859104. -2.41568486e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 1.06372465e+10 -589859840. 59025448. 249763968. 142146384. -2.01766875e+04 -8.78452734e+03 -4.12454346e+02 3.62422412e+03 2.53368359e+03 4.88218933e+02 2.53980347e+02 1.80925552e+02 1.70274643e+02 2.14122986e+02 2.13674942e+02 1.81017029e+02 7.96544647e+01 8.19546890e+01 1.26518089e+02 1.96945587e+02 1.78208099e+02 9.84224930e+01 3.87466202e+01 3.26557770e+01 9.46642685e+01 1.88214462e+02 2.06000412e+02 1.42835785e+02 5.98550377e+01 5.91531143e+01 1.16052452e+02 1.19986237e+02 7.42091064e+01 5.71096077e+01 9.09911118e+01 1.36498199e+02 1.38324127e+02 1.53162964e+02 1.78313614e+02 1.78882004e+02 1.27521706e+02 2.93391972e+01 1.79038239e+01 8.00624695e+01 1.35640991e+02 1.35859543e+02 6.92752762e+01 5.07370853e+00 1.41601458e+01 1.10787422e+02 2.20609283e+02 2.10510559e+02 1.00759987e+02 4.27130661e+01 3.07627792e+01 9.55960922e+01 1.15175819e+02 1.22035477e+02 1.31158234e+02 1.14585831e+02 9.12341995e+01 3.42572441e+01 5.68814926e+01 1.12498238e+02 1.23175293e+02 8.12691803e+01 1.34105444e+00 1.58313513e+00 4.06432037e+01 1.02061752e+02 1.30019272e+02 6.33655777e+01 -2.79741592e+01 -1.00829483e+02 -5.74995956e+01 4.35858688e+01 7.88738022e+01 1.22543335e+01 -3.46547470e+01 -2.57108746e+01 7.18601303e+01 9.03085785e+01 6.25569153e+01 1.50823126e+01 2.17884903e+01 1.72424393e+01 -8.57728481e+00 3.09856262e+01 9.91946564e+01 1.34041245e+02 5.28282013e+01 -5.24723244e+01 -7.99921570e+01 -4.06659126e+01 1.64064960e+01 8.06436462e+01 8.90732803e+01 4.25937347e+01 -1.13673887e+01 4.30122423e+00 9.93867722e+01 1.44012360e+02 5.35201683e+01 -1.48186092e+01 -2.02054367e+01 9.42673416e+01 1.38707520e+02 1.25000305e+02 1.07284592e+02 9.07033539e+01 5.49382401e+01 -2.80751495e+01 -2.76759377e+01 4.38223801e+01 1.04134827e+02 9.64733429e+01 2.63354015e+01 9.99214268e+00 5.72572212e+01 9.40942917e+01 1.39848022e+02 1.19853989e+02 4.53722496e+01 -3.41348381e+01 -5.66376610e+01 5.38603325e+01 1.09285774e+02 6.43693619e+01 3.00809517e+01 2.44612808e+01 8.10467911e+01 7.34289398e+01 6.23206787e+01 8.88490829e+01 1.08958687e+02 9.29254532e+01 4.26072550e+00 -8.47285366e+00 6.06389427e+01 1.06250389e+02 1.05901817e+02 3.33414345e+01 4.76068268e+01 9.96145630e+01 1.43357574e+02 1.74323517e+02 1.25238136e+02 3.98826180e+01 -2.95687485e+01 -2.37081490e+01 4.85234642e+01 6.33596954e+01 4.08394852e+01 4.47234421e+01 6.77557144e+01 1.19005646e+02 1.47857956e+02 1.64023788e+02 1.70291016e+02 1.32730286e+02 6.79920120e+01 -1.44382229e+01 -3.50560951e+01 -6.25448608e+00 3.70313988e+01 2.82582932e+01 -3.16717243e+01 -9.79741135e+01 -5.43891525e+01 4.78663673e+01 1.36288712e+02 1.30254715e+02 2.61435566e+01 -3.19774570e+01 -3.98352814e+01 2.45387154e+01 3.55588684e+01 2.19578915e+01 2.81432686e+01 1.13807745e+01 -1.01858587e+01 -1.14357576e+01 5.08136635e+01 1.22932220e+02 1.23333748e+02 9.37046661e+01 3.36865921e+01 -1.47717075e+01 -2.91318035e+01 -1.14748325e+01 7.88283873e+00 -5.16873703e+01 -1.19718925e+02 -9.54207611e+01 6.57994080e+00 1.06596352e+02 1.14767914e+02 3.99105568e+01 1.72920399e+01 4.88860607e+00 7.66530151e+01 6.14712105e+01 1.41487713e+01 -6.28151474e+01 -1.08621376e+02 -1.16744652e+02 -1.63471558e+02 -1.34191483e+02 -4.74378319e+01 2.87275505e+01 2.39637356e+01 -6.45749130e+01 -7.96769791e+01 -1.67315388e+01 6.23872528e+01 1.35830582e+02 8.91161804e+01 -2.64902287e+01 -1.33103027e+02 -1.02407860e+02 6.35825729e+00 2.94983482e+01 -2.14969406e+01 -4.21123657e+01 -4.49353714e+01 2.79395938e+00 3.60645905e+01 5.35461540e+01 4.18789330e+01 2.34599667e+01 -1.33976183e+01 -8.31220016e+01 -1.17418900e+02 -8.56458817e+01 -4.24202309e+01 -3.30871658e+01 -3.97796745e+01 -8.62883377e+00 3.35361710e+01 5.21521759e+01 3.43917503e+01 -1.11106634e+01 -3.35892944e+01 -4.58428917e+01 -2.85494823e+01 6.54501629e+00 2.10445900e+01 7.96106482e+00 -3.27837105e+01 -4.60557709e+01 -3.03715496e+01 -2.19402719e+00 1.01129651e+00 -1.66097355e+01 -3.72036972e+01 -3.42691612e+01 -2.07334595e+01 -1.18334398e+01 -4.24308872e+00 -6.25247812e+00 9.69208527e+00 -6.58753932e-01 -7.93987703e+00 -2.95957813e+01 -1.62766132e+01 -6.52803278e+00 -8.92891026e+00 -1.97777042e+01 -1.83266048e+01 -3.30384922e+00 -1.84736538e+00 -1.73047757e+00 7.31679487e+00 -4.32954311e+00 -2.98238430e+01 -3.87008095e+01 -1.48050003e+01 -3.81720066e+00 -1.47389412e+01 -2.07304649e+01 -1.07624054e+01 -3.71277547e+00 -8.33362293e+00 -1.21470718e+01 -1.89526691e+01 -2.46147060e+01 -2.88181705e+01 -1.88721409e+01 -2.03376122e+01 4.98819858e-01 -3.73660326e+00 -6.97425175e+00 -2.92463207e+01 -1.87595406e+01 -1.72809544e+01 -1.65277882e+01 -4.84817810e+01 -6.71811752e+01 -7.48854675e+01 -5.18294144e+01 -3.21396675e+01 -2.24506950e+01 -2.67880764e+01 -3.64945068e+01 -5.11242447e+01 -6.38456573e+01 -4.87517624e+01 -4.70837822e+01 -4.17510529e+01 -4.39691734e+01 -3.13900604e+01 -3.16733780e+01 -4.05323486e+01 -4.78183136e+01 -4.22270279e+01 -5.33119431e+01 -7.60162201e+01 -9.89347839e+01 -8.87510300e+01 -7.93696747e+01 -5.85033875e+01 -5.53741570e+01 -1.74242001e+01 -8.22178364e+00 2.66222644e+00 -2.42665005e+01 -3.89216919e+01 -6.44785614e+01 -7.81283646e+01 -7.66835022e+01 -3.35632858e+01 3.10015535e+00 -9.10989666e+00 -4.91703873e+01 -8.74610443e+01 -9.39690247e+01 -8.80243988e+01 -9.31000671e+01 -9.83074036e+01 -1.02954918e+02 -9.36335220e+01 -8.63993988e+01 -9.35845642e+01 -8.08061218e+01 -7.64618683e+01 -8.82750244e+01 -1.07198868e+02 -1.27323509e+02 -1.25148064e+02 -1.17403519e+02 -9.71036072e+01 -1.01978500e+02 -1.12242958e+02 -1.07119453e+02 -9.20386276e+01 -8.29315414e+01 -1.08127098e+02 -1.34785309e+02 -1.45718887e+02 -1.14450432e+02 -8.62642822e+01 -6.92679825e+01 -9.18288422e+01 -1.43765869e+02 -1.84075439e+02 -1.55403458e+02 -8.79886627e+01 -6.09961243e+01 -8.12280807e+01 -1.10980568e+02 -1.20049255e+02 -1.41167419e+02 -1.49941040e+02 -1.39192413e+02 -1.13126205e+02 -9.62943726e+01 -9.89834290e+01 -1.06917610e+02 -1.33111176e+02 -1.58718918e+02 -1.55977615e+02 -1.29217133e+02 -9.83719635e+01 -9.04313965e+01 -9.08720398e+01 -8.87585144e+01 -7.75621185e+01 -6.74287949e+01 -7.16032104e+01 -9.31459427e+01 -1.05719551e+02 -9.88807602e+01 -8.70338440e+01 -8.60167084e+01 -1.00439354e+02 -1.04884079e+02 -9.62927628e+01 -1.17281822e+02 -1.30198318e+02 -1.28723785e+02 -8.23563385e+01 -6.50824432e+01 -8.39748383e+01 -1.09539749e+02 -1.20866714e+02 -1.36338638e+02 -1.50421188e+02 -1.53499908e+02 -1.67087662e+02 -1.65195801e+02 -1.53768890e+02 -1.19632278e+02 -1.11508774e+02 -1.24645653e+02 -1.30675781e+02 -1.26740456e+02 -1.20323700e+02 -1.19287331e+02 -1.22279411e+02 -1.46131363e+02 -1.70804581e+02 -1.74222824e+02 -1.51079819e+02 -1.25284302e+02 -1.19687393e+02 -1.14609764e+02 -1.20908394e+02 -1.27408424e+02 -1.36563217e+02 -1.24670166e+02 -1.02209999e+02 -8.03084030e+01 -7.70261002e+01 -9.21065598e+01 -1.19171608e+02 -1.24763176e+02 -1.18487473e+02 -1.16334381e+02 -1.19610207e+02 -1.24185242e+02 -8.98206940e+01 -6.65049820e+01 -6.25672874e+01 -9.97511215e+01 -1.33369980e+02 -1.35423691e+02 -1.13389351e+02 -7.28124771e+01 1.14845409e+01 5.27081108e+01 1.30589767e+02 9.67775650e+01 2.31406204e+02 4.26168750e+03 1.20663306e+03 3.11888330e+03 1.13723281e+04 -119527008. -117451168. 479742816. -86874448. -191214496. 72932464. 726899072. 581115200. 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. 0. -1133359616. -1133359616. -1133359616. 0. 0. 466143744. 180400144. 93516384. -1.93080703e+04 -9.08322461e+03 -1.81823669e+03 -1.31062341e+03 2.45321338e+03 1.59874072e+03 1.30131790e+02 -8.51618347e+01 -1.23230286e+02 -1.07192841e+02 -1.10294708e+02 -1.27189209e+02 -1.49301193e+02 -1.47280365e+02 -1.47936096e+02 -1.51147278e+02 -1.50433975e+02 -1.38562500e+02 -1.24277893e+02 -1.41318420e+02 -1.73269745e+02 -1.83609665e+02 -1.62234146e+02 -1.46088516e+02 -1.56060242e+02 -1.65118317e+02 -1.58766907e+02 -1.51869949e+02 -1.41676254e+02 -1.39989685e+02 -1.44859467e+02 -1.56259323e+02 -1.62369766e+02 -1.62011032e+02 -1.55259598e+02 -1.73166000e+02 -1.94409286e+02 -2.02937363e+02 -1.90988281e+02 -1.77886948e+02 -1.78900894e+02 -1.85782486e+02 -1.88348190e+02 -1.96834412e+02 -2.02289993e+02 -2.06522614e+02 -2.11236969e+02 -2.11298172e+02 -2.03934692e+02 -1.94971313e+02 -1.91950577e+02 -1.99439880e+02 -2.01470901e+02 -1.99262619e+02 -1.97716583e+02 -1.99329575e+02 -2.03983749e+02 -2.07079697e+02 -2.02134537e+02 -1.83679443e+02 -1.65065506e+02 -1.55969788e+02 -1.69324249e+02 -1.83475601e+02 -1.91018494e+02 -1.80060165e+02 -1.68814255e+02 -1.73900757e+02 -1.86656967e+02 -1.99969925e+02 -1.99899582e+02 -2.00164154e+02 -2.07521301e+02 -2.23293869e+02 -2.12657562e+02 -1.94798386e+02 -1.76553345e+02 -1.83370026e+02 -1.93727798e+02 -1.93659256e+02 -1.94865784e+02 -1.95764648e+02 -2.00043472e+02 -1.99306091e+02 -1.96485367e+02 -1.91026627e+02 -1.88591019e+02 -1.89462357e+02 -1.91952332e+02 -1.90986847e+02 -1.80461334e+02 -1.67668869e+02 -1.73948166e+02 -1.82850403e+02 -1.94196396e+02 -1.88576996e+02 -1.84104904e+02 -1.79731003e+02 -1.77654739e+02 -1.85251984e+02 -1.95081512e+02 -1.98199615e+02 -1.93116745e+02 -1.82324829e+02 -1.82458496e+02 -1.84657349e+02 -1.91707840e+02 -1.96220367e+02 -1.94495682e+02 -1.95119446e+02 -1.93894791e+02 -1.96087906e+02 -1.94647430e+02 -1.95393875e+02 -1.97285049e+02 -1.92578339e+02 -1.85831223e+02 -1.87339310e+02 -1.94000015e+02 -2.01164581e+02 -2.01411118e+02 -2.01965088e+02 -2.01704880e+02 -2.01791580e+02 -2.02926498e+02 -2.03395203e+02 -1.96290024e+02 -1.87795898e+02 -1.86931183e+02 -1.92506058e+02 -1.99881241e+02 -2.02481369e+02 -2.04377960e+02 -2.02911118e+02 -2.01216034e+02 -1.99966492e+02 -2.02122833e+02 -2.01239914e+02 -2.01585022e+02 -2.01096771e+02 -2.00895889e+02 -1.99884750e+02 -1.99094315e+02 -1.98729523e+02 -1.99440796e+02 -1.99376785e+02 -1.98849640e+02 -1.98802216e+02 -1.98557129e+02 -1.98888351e+02 -1.98310181e+02 -1.97704788e+02 -1.98381134e+02 -1.98803970e+02 -1.99489822e+02 -1.99525406e+02 -2.00358536e+02 -2.01306213e+02 -2.01466202e+02 -2.00785339e+02 -1.97998444e+02 -1.96499298e+02 -1.96519958e+02 -1.97706390e+02 -1.98947601e+02 -1.99245575e+02 -1.99695190e+02 -1.99951752e+02 -1.99748871e+02 -1.99748505e+02 -1.99818253e+02 -1.99928848e+02 -1.99979706e+02 -2.00051437e+02 -2.00104324e+02 -1.99830856e+02 -1.99337097e+02 -1.99009537e+02 -1.99242676e+02 -1.99774658e+02 -2.00583618e+02 -2.00513794e+02 -2.00293228e+02 -1.99920502e+02 -2.00153885e+02 -2.00054413e+02 -2.00157471e+02 -1.99821457e+02 -1.99102539e+02 -1.99470154e+02 -1.99898193e+02 -1.99997742e+02 -1.99673569e+02 -1.98903168e+02 -2.00052704e+02 -2.00455170e+02 -2.01298767e+02 -2.01453751e+02 -2.00516327e+02 -1.96859955e+02 -1.92459747e+02 -1.89894196e+02 -1.89224808e+02 -1.89602325e+02 -1.88376007e+02 -1.91571014e+02 -1.97295944e+02 -2.02472717e+02 -2.03377823e+02 -2.01711166e+02 -2.00576401e+02 -2.00264664e+02 -2.00356628e+02 -2.01987793e+02 -2.01712494e+02 -2.01569977e+02 -2.00480209e+02 -2.00029770e+02 -1.99687988e+02 -2.05727280e+02 -2.13003693e+02 -2.11586914e+02 -2.04954758e+02 -1.97497879e+02 -1.93900055e+02 -1.90619461e+02 -1.82353439e+02 -1.77436371e+02 -1.78674042e+02 -1.84763855e+02 -1.94978760e+02 -1.91764664e+02 -1.89625504e+02 -1.84406647e+02 -1.85419937e+02 -1.87220535e+02 -1.86366989e+02 -1.85270676e+02 -1.85127747e+02 -1.89245560e+02 -1.92091125e+02 -1.91326813e+02 -1.82569366e+02 -1.72570786e+02 -1.62603210e+02 -1.59502274e+02 -1.76635300e+02 -1.97009827e+02 -2.07052719e+02 -2.01898514e+02 -1.89440475e+02 -1.88978897e+02 -1.84471268e+02 -1.85418182e+02 -1.86656479e+02 -1.88932236e+02 -1.90936966e+02 -1.89884125e+02 -1.88071869e+02 -1.87581177e+02 -1.98013702e+02 -2.12424911e+02 -2.14467682e+02 -2.08099777e+02 -1.97231155e+02 -1.90122543e+02 -1.81095566e+02 -1.77861526e+02 -1.84479935e+02 -1.85447388e+02 -1.80277603e+02 -1.81283188e+02 -1.90277344e+02 -1.96519348e+02 -1.96886276e+02 -1.94194519e+02 -1.92605927e+02 -1.89238342e+02 -1.88882706e+02 -1.85425339e+02 -1.86036423e+02 -1.86625198e+02 -1.94291092e+02 -1.98548309e+02 -1.98336670e+02 -1.84717529e+02 -1.65851440e+02 -1.63556030e+02 -1.76519363e+02 -1.92300278e+02 -1.86709229e+02 -1.82521255e+02 -1.79394623e+02 -1.81705078e+02 -1.80705460e+02 -1.77963074e+02 -1.69415375e+02 -1.60699677e+02 -1.61261490e+02 -1.74628616e+02 -1.87817535e+02 -1.88508270e+02 -1.80918121e+02 -1.89384445e+02 -2.03455887e+02 -2.12260803e+02 -2.04888107e+02 -1.91270325e+02 -1.92074478e+02 -1.91039993e+02 -1.90524506e+02 -1.84467209e+02 -1.84418793e+02 -1.89093887e+02 -1.95330856e+02 -1.92482300e+02 -1.88164047e+02 -1.87788330e+02 -1.89690720e+02 -1.83615555e+02 -1.77019669e+02 -1.62598694e+02 -1.52213913e+02 -1.54342560e+02 -1.62876373e+02 -1.72750946e+02 -1.72728195e+02 -1.77696548e+02 -1.84707047e+02 -1.81151489e+02 -1.56696564e+02 -1.33858505e+02 -1.26883469e+02 -1.45807159e+02 -1.65332077e+02 -1.68723465e+02 -1.62036240e+02 -1.58363815e+02 -1.62521957e+02 -1.49042374e+02 -1.22501762e+02 -1.14306305e+02 -1.30078934e+02 -1.62049088e+02 -1.59844879e+02 -1.60123795e+02 -1.54215103e+02 -1.58072617e+02 -1.58997345e+02 -1.52967590e+02 -1.41822281e+02 -1.35225601e+02 -1.39754898e+02 -1.49303360e+02 -1.46042282e+02 -1.21021477e+02 -8.56837463e+01 -8.52198410e+01 -1.11675018e+02 -1.41116516e+02 -1.43941788e+02 -1.51460602e+02 -1.47452072e+02 -1.43346603e+02 -1.10295280e+02 -9.05499268e+01 -6.58929977e+01 -6.57059479e+01 -8.78773499e+01 -1.14406761e+02 -1.44523666e+02 -1.22454964e+02 -1.00241608e+02 -1.23060257e+02 -1.74487167e+02 -2.01459854e+02 -1.77800858e+02 -1.46076065e+02 -1.50164658e+02 -1.48085434e+02 -1.53795807e+02 -1.54771744e+02 -1.62890015e+02 -1.66417419e+02 -1.67798477e+02 -1.71265350e+02 -1.75074661e+02 -1.77890259e+02 -1.75193329e+02 -1.70172012e+02 -1.66806229e+02 -1.47451294e+02 -1.21547203e+02 -1.23427361e+02 -1.46473541e+02 -1.77102798e+02 -1.50046417e+02 -1.14976097e+02 -1.41179901e+02 -1.99218353e+02 -1.99577423e+02 -1.27386475e+02 -8.49150772e+01 -1.08561920e+02 -1.43177567e+02 -1.27369293e+02 -8.95606461e+01 -8.12234955e+01 -9.44782486e+01 -1.25337837e+02 -1.22497612e+02 -1.18849640e+02 -1.20324463e+02 -1.20313354e+02 -1.46040512e+02 -1.72986633e+02 -1.47280960e+02 -9.54821701e+01 -6.05750694e+01 -8.31038666e+01 -1.03352928e+02 -7.81892700e+01 -5.05156784e+01 -4.38971214e+01 -6.89750061e+01 -1.02014748e+02 -9.60969696e+01 -8.99927597e+01 -8.02563782e+01 -9.70132370e+01 -8.24265594e+01 -4.94605980e+01 -3.58214989e+01 -4.36232529e+01 -9.03071823e+01 -1.14928429e+02 -1.27372726e+02 -1.18202744e+02 -1.05752136e+02 -1.47409149e+02 -2.04862701e+02 -1.92873917e+02 -1.30222626e+02 -7.07233582e+01 -8.40104599e+01 -1.16330727e+02 -9.65302200e+01 -5.79254913e+01 -5.22878914e+01 -7.72300873e+01 -1.14577507e+02 -1.19616859e+02 -1.19729637e+02 -1.19672630e+02 -1.17077240e+02 -1.14929352e+02 -1.00992516e+02 -7.88486176e+01 -6.73787308e+01 -8.15617752e+01 -1.05161186e+02 -1.13857643e+02 -1.14216286e+02 -1.08182373e+02 -1.43964432e+02 -1.79563004e+02 -1.44861191e+02 -7.42572784e+01 -2.96967449e+01 -7.17807617e+01 -1.13950005e+02 -1.41312469e+02 -1.46047852e+02 -1.46033463e+02 -1.34378265e+02 -1.26423203e+02 -1.32609573e+02 -1.26318321e+02 -1.28198502e+02 -1.25105812e+02 -1.39831314e+02 -1.44679276e+02 -1.44225525e+02 -1.14305687e+02 -1.01180168e+02 -1.13385704e+02 -1.35866837e+02 -1.47049271e+02 -1.25335625e+02 -1.07986969e+02 -9.40127792e+01 -6.39559288e+01 -3.00342674e+01 -2.30493317e+01 -5.17394066e+01 -5.39062653e+01 9.90879822e+00 5.70245209e+01 3.25216560e+01 -1.39017601e+01 -3.36925912e+00 3.96979294e+01 4.28679695e+01 1.42364395e+00 -2.72190018e+01 -3.05180416e+01 -2.60928783e+01 -2.55044422e+01 -2.30713997e+01 -2.40309677e+01 -4.66463356e+01 -3.18587627e+01 1.33603287e+00 2.80639648e+01 5.55610561e+00 -3.31194725e+01 -3.02374649e+01 -2.69301367e+00 -3.37452736e+01 -8.81125412e+01 -1.12236313e+02 -9.70919342e+01 -6.24672089e+01 -7.55692902e+01 -6.79614410e+01 -7.02496643e+01 -6.58230972e+01 -7.08688278e+01 -7.03830261e+01 -6.33076363e+01 -6.81019440e+01 -7.33815384e+01 -8.40446548e+01 -7.41746521e+01 -6.20286674e+01 -6.30375786e+01 -3.27460823e+01 -2.10379577e+00 -6.83945715e-01 -4.26630859e+01 -9.19239197e+01 -1.03279724e+02 -9.99079666e+01 -1.26361061e+02 -1.60176544e+02 -1.53173904e+02 -1.16012962e+02 -7.86811295e+01 -7.90403214e+01 -8.04998627e+01 -3.07299404e+01 2.50848503e+01 3.51599770e+01 -3.02090788e+00 -3.47853394e+01 -3.32309608e+01 -3.94540558e+01 -5.43739891e+01 -5.25555840e+01 -7.34619141e+01 -1.12784561e+02 -8.70536880e+01 -2.54816780e+01 1.76159897e+01 -5.05760670e+00 -5.06933737e+00 6.02108879e+01 1.06129501e+02 9.18706055e+01 1.56155205e+01 -7.76524878e+00 1.98003807e+01 3.41185760e+01 2.11973667e+00 -5.79303703e+01 -4.99915962e+01 -1.62867336e+01 -1.12194166e+01 -2.87913170e+01 -5.95256195e+01 -6.84359970e+01 -7.77942200e+01 -8.88297119e+01 -7.32384415e+01 -7.75476913e+01 -8.22803879e+01 -5.49241867e+01 -2.19111671e+01 9.54504371e-01 -1.84470692e+01 -3.37383423e+01 -5.71434784e+00 3.49384460e+01 3.26123924e+01 -5.03631020e+00 -1.18971046e+02 -2.90203491e+02 -3.92629272e+02 -5.76533752e+02 -6.30318604e+02 -9.80886154e+01 2.41788116e+02 6.27467712e+02 3.66799164e+02 4.64436432e+02 2.20267120e+02 2.19779160e+02 -4.25161133e+03 -1.49063164e+04 -4.65134450e+06 4.73921290e+10 0. 0. 0. 0. -3.88826496e+09 -3.88826496e+09 -17269332. -1.44161423e+10 -6.19512832e+09 -1.64064050e+06 -1.64064050e+06 3.13963192e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.37251052e+10 -4.24189250e+06 -6.49064750e+06 23994826. -3.59720450e+06 -1.84273672e+04 -8.81400781e+03 6.12560974e+02 -1.32325122e+03 -3.43172925e+03 -3.88652527e+02 -5.80236855e+01 -5.33480034e+01 -2.75759754e+01 -6.46129990e+00 -4.19490585e+01 -7.25198898e+01 -4.18528976e+01 4.44189987e+01 8.31719742e+01 1.79349632e+01 -9.91798859e+01 -9.60603485e+01 8.61253798e-01 1.19113441e+02 1.35459656e+02 8.73432693e+01 9.82366791e+01 1.51715729e+02 1.52342941e+02 9.38516312e+01 4.54228439e+01 9.53573914e+01 2.11743973e+02 2.31340439e+02 1.58184921e+02 6.80041962e+01 1.81399155e+01 1.47560377e+01 -1.89194775e+01 -5.94122467e+01 -7.43677368e+01 -1.18091879e+01 1.46505417e+02 2.27852173e+02 1.89294617e+02 7.95698471e+01 8.45738575e-02 3.63884544e+00 3.57245979e+01 8.26524887e+01 7.59196930e+01 1.05409950e+02 1.35417130e+02 1.03242737e+02 -1.25456219e+01 -1.27969078e+02 -1.14516273e+02 5.42102165e+01 1.35687469e+02 1.04958138e+02 1.43315744e+01 2.45997639e+01 9.27808228e+01 8.71626968e+01 1.84532948e+01 -5.19526405e+01 -2.55674953e+01 9.01132736e+01 1.74185989e+02 1.46497391e+02 7.72313385e+01 4.86686325e+01 7.58924561e+01 7.56218338e+01 2.95928726e+01 -2.45209465e+01 -9.00381947e+00 2.01464958e+01 1.42972031e+01 -3.02077160e+01 -4.58993530e+01 -2.01395149e+01 3.42928276e+01 8.79381485e+01 9.18424683e+01 6.96099777e+01 4.44067345e+01 5.82143784e+01 2.62017798e+00 -8.49617386e+01 -1.21565903e+02 -3.80259781e+01 1.10131378e+02 1.77732697e+02 1.35323822e+02 2.33305397e+01 -7.83808517e+01 -1.11624725e+02 -8.56205978e+01 -6.76455612e+01 -7.48129349e+01 -3.98499908e+01 6.12354202e+01 1.29303848e+02 1.06912071e+02 2.50622597e+01 1.89417136e+00 3.76049652e+01 9.59035568e+01 1.06650826e+02 6.03873215e+01 2.91619587e+01 3.26956787e+01 4.34519348e+01 8.16694832e+00 -7.03796234e+01 -8.44407806e+01 -1.22829065e+01 6.70889435e+01 6.70173035e+01 4.29187536e+00 -4.76487274e+01 -5.11488953e+01 1.98070824e+00 6.37216568e+01 9.11780548e+01 5.58310394e+01 5.41525574e+01 9.28805084e+01 1.05182014e+02 5.27085075e+01 -1.31425352e+01 -9.15359211e+00 4.91196671e+01 8.38554535e+01 5.47619438e+01 2.86039658e+01 1.65952930e+01 4.61487617e+01 2.39638863e+01 -2.20863819e+01 -3.63756866e+01 3.39992104e+01 1.62152573e+02 2.18984985e+02 1.66934357e+02 8.27647781e+01 5.57478905e+01 7.70148087e+01 1.05942017e+02 1.05721245e+02 1.13859512e+02 1.53762558e+02 2.08266373e+02 2.25009415e+02 1.70986267e+02 5.49755669e+01 -2.93078566e+00 5.57741661e+01 1.25924759e+02 1.26915413e+02 8.99360886e+01 1.19796341e+02 2.00111191e+02 1.94700516e+02 1.20072632e+02 4.94008484e+01 1.05072227e+02 2.26329239e+02 2.88843079e+02 2.41918289e+02 1.45482941e+02 9.91041870e+01 9.89034042e+01 9.18485260e+01 7.94593353e+01 1.03598305e+02 1.68926315e+02 2.41164841e+02 1.99484894e+02 1.29645721e+02 7.05740204e+01 7.83058853e+01 1.15489517e+02 1.38949570e+02 1.62684372e+02 1.65353729e+02 1.95071198e+02 2.21510895e+02 2.02822266e+02 1.26926453e+02 6.96039886e+01 7.67958298e+01 1.49562744e+02 2.06952988e+02 1.95085327e+02 1.36894440e+02 1.03475029e+02 1.04578926e+02 9.42982254e+01 2.98036880e+01 1.02526674e+01 8.00366821e+01 1.53041916e+02 1.72537308e+02 1.26918289e+02 7.70877686e+01 5.23126907e+01 5.89181442e+01 8.82948532e+01 1.17924896e+02 1.16431015e+02 1.35910538e+02 1.66280579e+02 1.39548050e+02 9.37259979e+01 6.52337570e+01 7.23014374e+01 1.18970016e+02 1.34657272e+02 1.25649216e+02 1.14918861e+02 1.12745789e+02 1.45273544e+02 1.19498253e+02 7.51669693e+01 4.96962585e+01 4.26910782e+01 1.09984726e+02 1.48487762e+02 1.35927444e+02 7.71163101e+01 6.36966438e+01 9.90912933e+01 1.38912796e+02 1.32878983e+02 1.08441704e+02 1.13465019e+02 1.48104218e+02 1.56043869e+02 1.02501350e+02 8.18903427e+01 1.07147163e+02 1.49558685e+02 1.16693413e+02 1.03653435e+02 1.13646194e+02 1.34387222e+02 1.41701004e+02 1.26964767e+02 1.47145584e+02 1.65169830e+02 1.69393478e+02 1.84744690e+02 1.96632019e+02 2.04896393e+02 1.52374863e+02 1.31527786e+02 1.30075516e+02 1.70106277e+02 1.60595459e+02 1.55346634e+02 1.68393478e+02 1.97108337e+02 2.07669373e+02 1.59672150e+02 1.32666229e+02 1.30936462e+02 1.76396652e+02 1.84951279e+02 1.80792709e+02 1.59478806e+02 1.51769348e+02 1.75572433e+02 1.62810699e+02 1.45049271e+02 1.06578911e+02 9.14053726e+01 1.02051956e+02 1.33054611e+02 1.61578705e+02 1.42679581e+02 1.10880356e+02 9.63437805e+01 1.06178207e+02 9.30782089e+01 1.00492050e+02 1.28030548e+02 1.67127945e+02 1.64498672e+02 1.10140419e+02 9.70750885e+01 1.18953842e+02 1.64004196e+02 1.48085938e+02 1.26561714e+02 1.20872963e+02 1.33845947e+02 1.54907867e+02 1.55350754e+02 1.58715973e+02 1.31523682e+02 1.21265144e+02 1.24125877e+02 1.47753891e+02 1.57755661e+02 1.39796616e+02 1.22781410e+02 1.23114174e+02 1.23096680e+02 9.20912781e+01 7.13209839e+01 7.45001831e+01 8.83523941e+01 8.75393372e+01 6.87391815e+01 6.31326065e+01 7.81466217e+01 1.16284767e+02 1.31335983e+02 1.36253204e+02 1.25899490e+02 1.30848923e+02 1.52746490e+02 1.69023193e+02 1.81474594e+02 1.62156021e+02 1.50046021e+02 1.35279221e+02 1.37639969e+02 1.31850449e+02 1.24371193e+02 1.14179321e+02 1.19200310e+02 1.22248322e+02 1.07564468e+02 9.32430725e+01 1.01782379e+02 1.25164192e+02 1.30766724e+02 1.35034973e+02 1.54430969e+02 1.71266342e+02 1.76796463e+02 1.54297668e+02 1.52911133e+02 1.51429916e+02 1.37919708e+02 1.37649506e+02 1.50643478e+02 1.82148895e+02 1.89635757e+02 1.64945175e+02 1.42054993e+02 1.42164764e+02 1.59740524e+02 1.76544434e+02 1.69866226e+02 1.56631989e+02 1.41652313e+02 1.39386520e+02 1.54822754e+02 1.65230759e+02 1.82023026e+02 1.79821930e+02 1.79524414e+02 1.86102386e+02 1.86856842e+02 1.90529358e+02 1.69231476e+02 1.66550888e+02 1.63614807e+02 1.61820297e+02 1.66694794e+02 1.79774384e+02 2.08452438e+02 2.13190399e+02 1.92093430e+02 1.57361740e+02 1.39916229e+02 1.59378830e+02 1.86240997e+02 1.88151169e+02 1.60998825e+02 1.32668213e+02 1.39320587e+02 1.66269714e+02 1.81152512e+02 1.79107803e+02 1.63829926e+02 1.66135559e+02 1.75512741e+02 1.81823456e+02 1.83602020e+02 1.73286270e+02 1.74027893e+02 1.79816025e+02 1.85180298e+02 1.83685333e+02 1.76422821e+02 1.78346542e+02 1.79640671e+02 1.68113708e+02 1.57438385e+02 1.57860199e+02 1.79037613e+02 1.90900055e+02 1.86532349e+02 1.71267166e+02 1.63615036e+02 1.65379761e+02 1.73602859e+02 1.76665344e+02 1.78425354e+02 1.72173523e+02 1.72196243e+02 1.73257446e+02 1.74619751e+02 1.77114273e+02 1.72567551e+02 1.70750671e+02 1.65466492e+02 1.65963943e+02 1.67829712e+02 1.71980728e+02 1.77704315e+02 1.78719101e+02 1.75348389e+02 1.69006165e+02 1.66646576e+02 1.69076889e+02 1.73827927e+02 1.74906693e+02 1.71928909e+02 1.69289185e+02 1.69904007e+02 1.71961029e+02 1.72509445e+02 1.72277313e+02 1.72098785e+02 1.72160492e+02 1.71881226e+02 1.71118729e+02 1.70276840e+02 1.69887726e+02 1.68963928e+02 1.68470901e+02 1.69932587e+02 1.72901901e+02 1.74463303e+02 1.71873825e+02 1.68638519e+02 1.69441574e+02 1.74778229e+02 1.79698990e+02 1.77496628e+02 1.70587067e+02 1.68031754e+02 1.71316589e+02 1.77358444e+02 1.76185257e+02 1.70012009e+02 1.65108490e+02 1.60595184e+02 1.65956543e+02 1.64407318e+02 1.67787216e+02 1.67027115e+02 1.66531631e+02 1.63057220e+02 1.56077499e+02 1.60136124e+02 1.68086670e+02 1.77589844e+02 1.74345901e+02 1.62577576e+02 1.51719818e+02 1.58244415e+02 1.72945251e+02 1.84192551e+02 1.81164978e+02 1.70293976e+02 1.66397430e+02 1.64405563e+02 1.67379929e+02 1.63585861e+02 1.58866730e+02 1.50772324e+02 1.40495728e+02 1.43902267e+02 1.60119370e+02 1.73561798e+02 1.75273590e+02 1.68423889e+02 1.60295410e+02 1.46915970e+02 1.39530182e+02 1.56422089e+02 1.83461258e+02 1.94942215e+02 1.76771698e+02 1.50740799e+02 1.50575470e+02 1.75397003e+02 2.04685669e+02 1.99812332e+02 1.67457031e+02 1.33102127e+02 1.22824860e+02 1.43891983e+02 1.62498444e+02 1.60993774e+02 1.49631073e+02 1.42661194e+02 1.54865158e+02 1.56358688e+02 1.57143661e+02 1.70218948e+02 1.74942627e+02 1.74064774e+02 1.54511856e+02 1.56702667e+02 1.81772873e+02 2.08277252e+02 2.01107254e+02 1.58374329e+02 1.21389687e+02 1.33460892e+02 1.74181091e+02 2.03749954e+02 2.03910339e+02 1.68546875e+02 1.36113571e+02 1.21756332e+02 1.48785095e+02 1.65333450e+02 1.79771973e+02 1.76397491e+02 1.70109970e+02 1.73984818e+02 1.72517685e+02 1.94284164e+02 2.06706284e+02 2.09890488e+02 1.92831970e+02 1.53614624e+02 1.40439514e+02 1.64473358e+02 2.01746002e+02 2.11841660e+02 1.89305527e+02 1.52528580e+02 1.55301865e+02 1.77460159e+02 2.17911880e+02 2.23203217e+02 1.87448425e+02 1.46706726e+02 1.28582153e+02 1.58465561e+02 1.89929214e+02 1.89292801e+02 1.66006134e+02 1.31796234e+02 1.27392082e+02 1.32157684e+02 1.47910919e+02 1.77764771e+02 1.82418854e+02 1.59194717e+02 1.06684296e+02 8.12951660e+01 1.13431679e+02 1.56610138e+02 1.85980286e+02 1.66572418e+02 1.29043579e+02 1.12549980e+02 1.24335457e+02 1.53363831e+02 1.49826508e+02 1.26843956e+02 9.71830063e+01 9.58078842e+01 1.28407959e+02 1.59687424e+02 1.51035355e+02 1.29218033e+02 8.51730118e+01 8.95548096e+01 8.96868057e+01 1.11010460e+02 1.30914444e+02 1.44201843e+02 1.52344604e+02 1.19161186e+02 9.60720596e+01 1.10893906e+02 1.46863129e+02 1.79003006e+02 1.56379410e+02 1.17728996e+02 9.48861389e+01 1.29533936e+02 2.04841980e+02 2.32147995e+02 1.94480667e+02 1.10332085e+02 6.16695213e+01 8.91585083e+01 1.42605179e+02 1.85576874e+02 2.16927475e+02 2.52307022e+02 2.60077301e+02 2.50930008e+02 1.73936975e+03 2.80472266e+03 3.94219116e+02 2.25297073e+02 1.79565338e+02 6.75605652e+02 -3.68945703e+03 -1.14620293e+04 362859104. -2.41568486e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 1.06372465e+10 -589859840. 59025448. 249763968. 142146384. -210576608. -475286016. 1.26736729e+04 5.08961719e+03 9.15561829e+02 3.79609467e+02 2.91738495e+02 2.53144104e+02 1.83333878e+02 8.49715195e+01 4.96587296e+01 7.47643890e+01 1.49041321e+02 1.96530197e+02 1.81022064e+02 1.19403236e+02 3.21451035e+01 2.99876938e+01 5.29701538e+01 7.32159576e+01 7.92802811e+01 8.44353638e+01 1.20976135e+02 7.57839203e+01 6.92870102e+01 1.26265991e+02 1.78177231e+02 1.38795990e+02 1.69199963e+01 -4.49149742e+01 3.00803833e+01 1.27142082e+02 1.84435837e+02 1.51393005e+02 4.18968506e+01 -4.63320885e+01 -8.46984406e+01 3.89702916e+00 6.72647324e+01 7.26317062e+01 7.80201864e+00 -3.58468666e+01 6.85973704e-01 1.14993620e+01 4.51916885e+01 8.45436401e+01 1.04106728e+02 7.31770782e+01 -4.43001366e+01 -5.56790390e+01 4.36658821e+01 1.60519257e+02 1.88389069e+02 9.02505798e+01 -4.53509140e+00 2.05693102e+00 7.33654175e+01 1.05936119e+02 3.53594971e+01 -7.68906326e+01 -1.16982910e+02 -7.77652893e+01 5.12085991e+01 1.40667938e+02 1.43950378e+02 6.44898987e+01 -3.99667778e+01 -1.11353737e+02 -1.43171753e+02 -1.04599960e+02 -4.74758224e+01 6.67197466e+00 3.14827213e+01 1.31652508e+01 3.04082127e+01 1.04352119e+02 1.72303345e+02 1.71011978e+02 7.20300827e+01 4.22006178e+00 1.29342775e+01 5.09015465e+01 1.23850418e+02 1.61513489e+02 1.25710052e+02 1.36162472e+01 -4.33740082e+01 2.09823341e+01 1.03495445e+02 9.26512146e+01 4.08992615e+01 2.24544926e+01 5.25488358e+01 3.98542328e+01 4.04026337e+01 7.76041946e+01 1.00953514e+02 7.24888611e+01 -3.51473656e+01 -4.86816483e+01 6.21834679e+01 1.92336700e+02 2.39722305e+02 1.43104080e+02 5.29861946e+01 1.16802330e+01 3.17482643e+01 5.91854935e+01 7.46905594e+01 4.62232132e+01 -1.54895353e+01 -4.79072876e+01 1.52334957e+01 1.25703812e+02 1.59076447e+02 1.20381783e+02 7.72751160e+01 6.50792542e+01 1.81879864e+01 2.05628624e+01 1.09557953e+02 2.14481018e+02 2.06096405e+02 6.72209702e+01 9.71189499e+00 9.06363678e+01 2.06525528e+02 2.21437302e+02 1.10471733e+02 9.16043663e+00 -2.12579479e+01 2.18239994e+01 1.00095436e+02 1.60948853e+02 1.38462036e+02 4.61040993e+01 -1.96361160e+01 3.35250664e+01 1.26154305e+02 1.49832809e+02 1.17407837e+02 7.35919724e+01 4.81488419e+01 -1.30696964e+01 -4.14730873e+01 -1.00458088e+01 3.95095100e+01 4.99222488e+01 -2.63532047e+01 -5.64783936e+01 -4.23794079e+00 1.43003052e+02 2.28760635e+02 1.90767792e+02 4.46188431e+01 -5.07213554e+01 -2.59874554e+01 4.37176361e+01 7.24193115e+01 3.49995079e+01 3.22246437e+01 -2.07011127e+01 5.22037506e+00 1.67062435e+01 6.89363861e+01 1.28944580e+02 1.56174408e+02 1.73910095e+02 7.27278137e+01 2.12374878e+01 7.45678635e+01 1.31515717e+02 1.11387695e+02 -2.19328632e+01 -7.44934845e+01 -3.59040642e+01 2.87893829e+01 7.55990677e+01 7.38427811e+01 3.47810440e+01 1.14522219e+01 8.35090351e+00 7.31904831e+01 5.87082634e+01 1.31213779e+01 -3.91949959e+01 -1.13216560e+02 -1.64111374e+02 -2.11090652e+02 -1.28498810e+02 -1.02867680e+01 4.87890625e+01 3.70614433e+01 -3.67145271e+01 -4.24732323e+01 4.35143700e+01 1.38246368e+02 1.74664825e+02 5.19488907e+01 -1.03040398e+02 -1.73650650e+02 -1.31362961e+02 -6.02145348e+01 -3.08529015e+01 -4.41375351e+01 -7.35630493e+01 -1.17696014e+02 -8.21725845e+01 -1.37701731e+01 3.02000446e+01 -1.66314335e+01 -4.10413399e+01 -6.10130081e+01 -9.83560791e+01 -1.07633301e+02 -6.92293549e+01 -2.76526394e+01 -4.08924828e+01 -4.20088158e+01 -4.47071981e+00 6.02113724e+01 8.65470810e+01 1.07285942e+02 6.32089996e+01 3.65323143e+01 -6.75625839e+01 -1.02510155e+02 -5.73254776e+01 4.24354668e+01 6.77085114e+01 1.39068527e+01 -3.98686142e+01 -2.65752087e+01 -1.47467203e+01 -4.20569515e+00 -2.21734428e+00 -7.63075066e+00 -1.06452961e+01 -9.82066917e+00 -9.67259407e+00 2.68903232e+00 8.00565529e+00 4.45858040e+01 3.74597664e+01 2.68097572e+01 -5.21771717e+00 4.44211197e+00 1.24521351e+01 -7.28453875e+00 -9.49639225e+00 -4.21347046e+01 -6.13083649e+01 -7.57602005e+01 -6.12760086e+01 -2.46018524e+01 -2.68619881e+01 -2.59333305e+01 -2.61733913e+01 -1.06741314e+01 -1.13402052e+01 -7.10759687e+00 -5.85133219e+00 -4.43645906e+00 -1.51388054e+01 -2.48873062e+01 -1.41470098e+01 5.91722918e+00 -5.35090876e+00 1.41166325e+01 1.26039219e+01 1.70890293e+01 -2.16703534e+00 -1.47133646e+01 -1.12983456e+01 -1.09982338e+01 -5.42040169e-01 -2.60843635e+00 -8.63823223e+00 -3.30803604e+01 -2.88836727e+01 -3.65446739e+01 -7.68288708e+00 -1.99110622e+01 -2.57377934e+00 -1.18518934e+01 -2.60526676e+01 -5.31261635e+01 -4.73055611e+01 -2.46163177e+01 -1.43458843e+01 -3.20595589e+01 -3.62764320e+01 -1.84392509e+01 -2.83800850e+01 -5.24391708e+01 -7.75511551e+01 -7.23695450e+01 -6.57856827e+01 -5.11037560e+01 -5.84899864e+01 -4.99476509e+01 -5.29496155e+01 -4.88055611e+01 -5.18200035e+01 -6.27751503e+01 -7.04834747e+01 -6.01071053e+01 -4.80825195e+01 -3.58625107e+01 -5.80938759e+01 -3.74612503e+01 -1.04621820e+01 2.27215981e+00 -2.04835491e+01 -6.85047455e+01 -6.78888245e+01 -7.17213058e+01 -5.65210304e+01 -4.64633217e+01 -6.84376144e+01 -7.38897858e+01 -8.33188705e+01 -7.12475204e+01 -8.52968063e+01 -9.20536499e+01 -7.57469482e+01 -6.79519653e+01 -6.82390747e+01 -7.01382294e+01 -6.26798897e+01 -7.05108948e+01 -7.43759155e+01 -7.94964676e+01 -9.32427292e+01 -1.05940323e+02 -1.00508499e+02 -8.27320328e+01 -7.06925888e+01 -7.31036682e+01 -8.08116455e+01 -9.15906982e+01 -8.55613251e+01 -6.15072708e+01 -3.26356316e+01 -4.22970543e+01 -6.07878456e+01 -1.00155830e+02 -1.01133629e+02 -9.56138000e+01 -7.35106430e+01 -6.55812149e+01 -5.35816269e+01 -4.34798927e+01 -4.01690521e+01 -4.55493698e+01 -5.14281387e+01 -6.57268066e+01 -7.32603455e+01 -8.00941315e+01 -7.33865204e+01 -8.21244125e+01 -7.32688293e+01 -7.52400665e+01 -7.52282486e+01 -7.53206558e+01 -8.43997803e+01 -7.21284943e+01 -5.56434898e+01 -1.45887575e+01 -3.14908943e+01 -6.79804535e+01 -1.02103416e+02 -8.32883606e+01 -4.73059158e+01 -4.26673927e+01 -5.86889076e+01 -8.69677353e+01 -8.02630386e+01 -6.03139305e+01 -4.72637634e+01 -4.83554802e+01 -5.67222939e+01 -5.16127396e+01 -2.63076916e+01 -9.57606888e+00 -3.27252350e+01 -7.41838684e+01 -9.10061264e+01 -7.60412750e+01 -6.81434097e+01 -7.55334396e+01 -8.60028534e+01 -9.50874710e+01 -8.09210358e+01 -5.56948509e+01 -5.74883957e+01 -7.99675064e+01 -1.16261536e+02 -1.14403267e+02 -1.02476059e+02 -9.41940765e+01 -1.15771622e+02 -1.58869232e+02 -1.74324188e+02 -1.39376328e+02 -1.00552162e+02 -8.93497314e+01 -9.51012192e+01 -6.86819992e+01 -5.80756340e+01 -1.00399933e+02 -1.61809860e+02 -1.77499390e+02 -1.37813156e+02 -9.38968658e+01 -8.38105545e+01 -8.94146194e+01 -1.18069496e+02 -1.34823349e+02 -1.25616806e+02 -9.73827744e+01 -7.57755051e+01 -7.88555984e+01 -8.08938751e+01 -1.16908882e+02 -1.67941055e+02 -1.71856598e+02 -1.46973450e+02 -1.12635002e+02 -1.01281731e+02 -8.17555695e+01 -7.58076477e+01 -9.76729279e+01 -1.18325188e+02 -1.26526291e+02 -1.22670982e+02 -1.22137169e+02 -1.31080017e+02 -1.36862411e+02 -1.40919250e+02 -1.40612396e+02 -1.43951538e+02 -7.06430664e+01 -1.56008408e+02 8.58144608e+01 1.95158218e+02 4.01266815e+02 2.09155859e+03 3.14894141e+03 -4.17050476e+02 -5.00505127e+02 -6.30640320e+02 -8.88686707e+02 -7.97525024e+02 -4.73307556e+02 -7.19672363e+02 -1.24995740e+03 -1.01706836e+04 -2.52621699e+04 726899072. 581115200. 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. 0. -1133359616. -1133359616. -1133359616. 0. 0. 466143744. 180400144. 93516384. 107867184. -507650400. 200183296. 123007416. 8.78252148e+03 3.64914160e+03 3.52589844e+02 1.39380608e+01 -1.00465981e+02 -1.06597801e+02 -1.08327080e+02 -1.09358101e+02 -1.11608742e+02 -1.09577530e+02 -1.02290215e+02 -9.95897827e+01 -1.01514229e+02 -1.18694336e+02 -1.23602570e+02 -1.22032669e+02 -1.05520012e+02 -1.11612762e+02 -1.25469650e+02 -1.45358749e+02 -1.47572037e+02 -1.50876495e+02 -1.59377106e+02 -1.67771439e+02 -1.69834366e+02 -1.74883316e+02 -1.81385498e+02 -1.82067307e+02 -1.80479843e+02 -1.74135422e+02 -1.70801086e+02 -1.76380630e+02 -1.82788528e+02 -1.89150833e+02 -1.77433273e+02 -1.70856857e+02 -1.73224640e+02 -1.80720108e+02 -1.82806000e+02 -1.83948975e+02 -1.82223404e+02 -1.78522461e+02 -1.62365616e+02 -1.49446381e+02 -1.43664719e+02 -1.50416763e+02 -1.57162064e+02 -1.62279648e+02 -1.66945572e+02 -1.65227066e+02 -1.58704041e+02 -1.59628143e+02 -1.64304077e+02 -1.72567368e+02 -1.74019699e+02 -1.80924423e+02 -1.74046875e+02 -1.62756943e+02 -1.55284149e+02 -1.48930115e+02 -1.49559113e+02 -1.46097305e+02 -1.52826859e+02 -1.56924133e+02 -1.56681580e+02 -1.59234177e+02 -1.69883667e+02 -1.76744095e+02 -1.74723816e+02 -1.68532715e+02 -1.64612106e+02 -1.67348694e+02 -1.57434418e+02 -1.43048843e+02 -1.43640457e+02 -1.49469604e+02 -1.57846817e+02 -1.41602585e+02 -1.26858772e+02 -1.27200668e+02 -1.39387085e+02 -1.47929169e+02 -1.47486786e+02 -1.45415756e+02 -1.51442566e+02 -1.49525558e+02 -1.41101044e+02 -1.29457443e+02 -1.32422424e+02 -1.47554657e+02 -1.60698853e+02 -1.67591125e+02 -1.64895401e+02 -1.64333527e+02 -1.60061691e+02 -1.68237839e+02 -1.74568771e+02 -1.69277023e+02 -1.59557449e+02 -1.57828064e+02 -1.67308945e+02 -1.73602371e+02 -1.62212311e+02 -1.54819351e+02 -1.56870178e+02 -1.67672668e+02 -1.75769501e+02 -1.77327072e+02 -1.77313248e+02 -1.75331100e+02 -1.73423599e+02 -1.71285126e+02 -1.72040359e+02 -1.72346497e+02 -1.71266083e+02 -1.69161896e+02 -1.67923294e+02 -1.68020523e+02 -1.69267548e+02 -1.68985565e+02 -1.69420181e+02 -1.68879501e+02 -1.63115097e+02 -1.57485001e+02 -1.57369797e+02 -1.63789124e+02 -1.69486710e+02 -1.63919098e+02 -1.58093307e+02 -1.58165405e+02 -1.63184814e+02 -1.67242142e+02 -1.67561188e+02 -1.69248718e+02 -1.72300400e+02 -1.71557709e+02 -1.70043808e+02 -1.69110840e+02 -1.70451492e+02 -1.72836624e+02 -1.73186646e+02 -1.72365662e+02 -1.70613953e+02 -1.70165054e+02 -1.69652496e+02 -1.70220657e+02 -1.69193542e+02 -1.65893906e+02 -1.62364120e+02 -1.62910995e+02 -1.65870117e+02 -1.69013840e+02 -1.67464447e+02 -1.65723129e+02 -1.66491974e+02 -1.69188751e+02 -1.71448013e+02 -1.71261124e+02 -1.71115555e+02 -1.71054855e+02 -1.71178665e+02 -1.71125778e+02 -1.71113312e+02 -1.71334015e+02 -1.71529724e+02 -1.71323517e+02 -1.71163330e+02 -1.71457947e+02 -1.71844925e+02 -1.72078232e+02 -1.72087524e+02 -1.72076736e+02 -1.72271896e+02 -1.72777802e+02 -1.72998688e+02 -1.72869965e+02 -1.72432938e+02 -1.72430832e+02 -1.71949081e+02 -1.72809509e+02 -1.74685883e+02 -1.75313904e+02 -1.74169342e+02 -1.72513779e+02 -1.72996017e+02 -1.73463699e+02 -1.73094986e+02 -1.72977234e+02 -1.73909027e+02 -1.74181229e+02 -1.76844772e+02 -1.79244629e+02 -1.79582962e+02 -1.76850388e+02 -1.73819473e+02 -1.75069489e+02 -1.75099182e+02 -1.78366394e+02 -1.80865143e+02 -1.80182907e+02 -1.74816055e+02 -1.70142899e+02 -1.70822098e+02 -1.71719955e+02 -1.72608780e+02 -1.71104813e+02 -1.69981918e+02 -1.68876114e+02 -1.68577942e+02 -1.69675583e+02 -1.70195908e+02 -1.69878952e+02 -1.70034561e+02 -1.66490341e+02 -1.64768051e+02 -1.62258591e+02 -1.61951599e+02 -1.63728577e+02 -1.63612411e+02 -1.63895844e+02 -1.63493042e+02 -1.63392960e+02 -1.63840866e+02 -1.62089981e+02 -1.64466125e+02 -1.65552155e+02 -1.65214752e+02 -1.61384171e+02 -1.61427094e+02 -1.63031525e+02 -1.64853714e+02 -1.64528671e+02 -1.63230301e+02 -1.65039017e+02 -1.64760178e+02 -1.69302521e+02 -1.69829178e+02 -1.69300003e+02 -1.61449677e+02 -1.52475937e+02 -1.58875168e+02 -1.74341522e+02 -1.85275787e+02 -1.80898300e+02 -1.71872742e+02 -1.71025345e+02 -1.72307831e+02 -1.73776230e+02 -1.73718552e+02 -1.73640442e+02 -1.72787827e+02 -1.70757736e+02 -1.64716095e+02 -1.60298065e+02 -1.56774384e+02 -1.60956940e+02 -1.64829758e+02 -1.70182648e+02 -1.70995621e+02 -1.67007034e+02 -1.63660263e+02 -1.59483063e+02 -1.60393417e+02 -1.58888336e+02 -1.63167206e+02 -1.75058090e+02 -1.86590881e+02 -1.87533279e+02 -1.77192154e+02 -1.68826843e+02 -1.63647476e+02 -1.64622971e+02 -1.68604996e+02 -1.78080872e+02 -1.83432251e+02 -1.87591156e+02 -1.79026596e+02 -1.70495117e+02 -1.57747345e+02 -1.61000870e+02 -1.63425400e+02 -1.66098969e+02 -1.60805267e+02 -1.57415863e+02 -1.52426086e+02 -1.57501938e+02 -1.63143936e+02 -1.67781738e+02 -1.69676041e+02 -1.67327118e+02 -1.81513351e+02 -1.93681763e+02 -1.91096939e+02 -1.70348602e+02 -1.54713043e+02 -1.61545593e+02 -1.71841705e+02 -1.68419495e+02 -1.65109543e+02 -1.74876617e+02 -1.90407547e+02 -1.90391403e+02 -1.71417816e+02 -1.52642868e+02 -1.59681442e+02 -1.65865021e+02 -1.62380219e+02 -1.56665710e+02 -1.52694427e+02 -1.55683136e+02 -1.58102692e+02 -1.50689102e+02 -1.36017761e+02 -1.31601562e+02 -1.34319275e+02 -1.44221146e+02 -1.42722504e+02 -1.56939224e+02 -1.74011475e+02 -1.78651154e+02 -1.83257172e+02 -1.91669891e+02 -2.09566605e+02 -2.12101593e+02 -2.05214645e+02 -2.01089890e+02 -1.90338791e+02 -1.87557632e+02 -1.68431885e+02 -1.40680252e+02 -1.09977966e+02 -1.04575943e+02 -1.13377754e+02 -1.21439804e+02 -1.27118019e+02 -1.28461884e+02 -1.33965240e+02 -1.30466156e+02 -1.26369072e+02 -1.40188477e+02 -1.68814011e+02 -1.77239258e+02 -1.70263260e+02 -1.53272980e+02 -1.50112137e+02 -1.46524399e+02 -1.31568634e+02 -1.45364777e+02 -1.47503159e+02 -1.55823059e+02 -1.58818405e+02 -1.71503204e+02 -1.96080231e+02 -1.77164062e+02 -1.52098694e+02 -1.41852661e+02 -1.68435883e+02 -1.72610168e+02 -1.62006699e+02 -1.36220963e+02 -1.59505096e+02 -1.79953033e+02 -1.84569229e+02 -1.67324692e+02 -1.49714584e+02 -1.74858887e+02 -2.00422943e+02 -1.94911224e+02 -1.62420624e+02 -1.34947144e+02 -1.54465546e+02 -1.69539673e+02 -1.47603821e+02 -1.12372986e+02 -1.25819397e+02 -1.63854614e+02 -1.83150925e+02 -1.76945557e+02 -1.63722336e+02 -1.66309265e+02 -1.84323288e+02 -2.08308609e+02 -2.01718842e+02 -1.59580017e+02 -1.27841064e+02 -1.24671127e+02 -1.35018570e+02 -1.41544617e+02 -1.37493271e+02 -1.31360611e+02 -1.28449600e+02 -1.44296066e+02 -1.48566620e+02 -1.30945969e+02 -1.22865128e+02 -1.26916260e+02 -1.58305222e+02 -1.70163025e+02 -1.61478851e+02 -1.51814072e+02 -1.33327759e+02 -1.34602783e+02 -1.26443710e+02 -1.14026077e+02 -1.01891792e+02 -1.06946007e+02 -1.57845703e+02 -1.92662033e+02 -1.55416824e+02 -8.81336441e+01 -8.58782272e+01 -1.40322464e+02 -1.63340698e+02 -1.28394684e+02 -1.06482567e+02 -1.24508263e+02 -1.43235550e+02 -1.39288895e+02 -1.15439751e+02 -1.23032234e+02 -1.30931396e+02 -1.39505371e+02 -1.24711647e+02 -1.00562317e+02 -1.00386627e+02 -1.02800758e+02 -1.31892197e+02 -1.53691406e+02 -1.53926239e+02 -1.24284279e+02 -1.22475388e+02 -1.76177383e+02 -2.14991028e+02 -1.93328140e+02 -1.39191452e+02 -1.35560242e+02 -1.59566132e+02 -1.37898544e+02 -8.56796570e+01 -6.57522736e+01 -1.04436615e+02 -1.29325592e+02 -1.22973900e+02 -1.07969849e+02 -1.31451721e+02 -1.37015213e+02 -1.40147110e+02 -1.23947487e+02 -1.09831871e+02 -9.06060257e+01 -8.38413925e+01 -8.64517365e+01 -1.00264381e+02 -1.24645752e+02 -1.38973694e+02 -1.43289124e+02 -1.51641052e+02 -1.56231995e+02 -1.42368271e+02 -1.21802521e+02 -1.17050903e+02 -1.44075760e+02 -1.48704041e+02 -1.43266418e+02 -1.58125519e+02 -2.10337341e+02 -2.46345673e+02 -2.15697357e+02 -1.51700272e+02 -1.32669327e+02 -1.50742630e+02 -1.55075302e+02 -1.23568550e+02 -9.65298080e+01 -8.23376999e+01 -8.03829575e+01 -7.99862289e+01 -1.05311768e+02 -1.01084808e+02 -8.06798859e+01 -7.36272888e+01 -1.28247528e+02 -1.63917877e+02 -1.31497391e+02 -9.66973877e+01 -1.28809937e+02 -1.58992874e+02 -1.23469788e+02 -4.72125473e+01 2.19408059e+00 -7.80767775e+00 -1.15864573e+01 -3.20799866e+01 -3.07522240e+01 -3.70316582e+01 -3.19317436e+01 -5.25165062e+01 -6.65230484e+01 -6.32443848e+01 -3.22486687e+01 -5.36413956e+01 -1.22442787e+02 -1.68390884e+02 -1.73315048e+02 -1.63201370e+02 -1.33884491e+02 -1.08589828e+02 -7.41758728e+01 -8.16566925e+01 -7.35387115e+01 -6.83617477e+01 -6.08891830e+01 -7.21119843e+01 -6.61515732e+01 -7.66219559e+01 -7.80551758e+01 -6.98082809e+01 -6.65102310e+01 -6.17731667e+01 -1.07865448e+02 -1.47957565e+02 -1.52521530e+02 -1.13220100e+02 -7.95136871e+01 -8.21253586e+01 -8.54345779e+01 -8.49256973e+01 -7.70321808e+01 -7.14280548e+01 -7.26707993e+01 -1.01577293e+02 -1.39300751e+02 -1.25400970e+02 -8.46079788e+01 -7.17882004e+01 -1.38231354e+02 -1.83220123e+02 -1.54285965e+02 -8.76893082e+01 -8.60787048e+01 -1.25973946e+02 -1.20022842e+02 -8.77539825e+01 -5.06692467e+01 -9.15495758e+01 -1.25549454e+02 -1.56175049e+02 -1.71179535e+02 -1.20201248e+02 -8.42005768e+01 -8.04062195e+01 -1.60543884e+02 -1.89138382e+02 -1.29685959e+02 -5.87432480e+01 -6.70752945e+01 -1.34174728e+02 -1.43643158e+02 -1.15072060e+02 -7.00030136e+01 -9.92008667e+01 -1.38561646e+02 -1.52145660e+02 -1.27247818e+02 -8.91045227e+01 -8.06835632e+01 -1.14187111e+02 -1.54180130e+02 -1.57864685e+02 -1.25453201e+02 -6.44012680e+01 -8.34261551e+01 -1.12626999e+02 -1.17366982e+02 -8.66113663e+01 -8.28967361e+01 -1.24368698e+02 -1.15468498e+02 -7.32622375e+01 -2.81264019e+01 -1.93499966e+01 -1.04226160e+01 -3.74618378e+01 -8.00274963e+01 -1.01493553e+02 -8.27628708e+01 -4.46861687e+01 -3.18405933e+01 -3.43175163e+01 -6.20385094e+01 -1.01273689e+02 -2.41602234e+02 -3.64005066e+02 -2.62935730e+02 -3.72504364e+02 -5.60409607e+02 -6.04747314e+02 -5.38358276e+02 -7.88404846e+01 8.69964142e+01 -2.35603003e+03 -4.09146191e+03 -1.80620825e+03 -2.62980200e+03 -5.22028516e+03 -2.32289375e+04 -652330752. 0. 0. 0. 0. 0. 0. 2.26273956e+10 2.26273956e+10 2.44004434e+04 5.29405391e+04 5.29405391e+04 3.13963192e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 157636080. 6.89158154e+03 6.25953418e+03 3.63216089e+03 9.34642944e+02 7.39877808e+02 2.00187485e+02 5.17107353e+01 -7.56138611e+01 -9.44043732e+01 -2.19370861e+01 5.49788904e+00 -2.91991787e+01 2.30710268e+00 8.04430389e+01 1.37710938e+02 7.25568848e+01 -6.65614243e+01 -1.26928741e+02 -8.14658585e+01 1.59237766e+01 5.94685669e+01 4.22218552e+01 1.75843983e+01 5.60533524e+01 1.01237000e+02 7.27426987e+01 -1.20325117e+01 -5.37494278e+01 -2.00833721e+01 5.16823654e+01 7.77368164e+01 1.87771626e+01 -6.06851807e+01 -9.56806488e+01 -4.90167694e+01 -4.94525642e+01 -9.99977036e+01 -6.68677902e+01 3.27505646e+01 1.02478424e+02 2.28900890e+01 -1.33420670e+02 -1.69387497e+02 -8.79601669e+01 -9.39701748e+00 3.52635040e+01 2.97678299e+01 2.75421829e+01 1.66185322e+01 3.26328430e+01 1.68160706e+01 -9.08486862e+01 -1.60157166e+02 -1.29432541e+02 -2.34642868e+01 3.36439285e+01 5.59746933e+00 -5.95211639e+01 -8.99050751e+01 -3.93141098e+01 -2.08157177e+01 -4.05946426e+01 -1.02410421e+01 5.27699013e+01 1.25137230e+02 1.17064056e+02 1.04349527e+01 -3.02846947e+01 6.00306913e-02 7.95816116e+01 5.08946609e+01 -2.13368988e+01 -1.54290748e+00 6.64586563e+01 9.42949295e+01 5.34499207e+01 -4.42626266e+01 -7.22318954e+01 -4.80513916e+01 4.59571877e+01 9.78928909e+01 8.38688736e+01 4.84421501e+01 5.72618484e+01 1.01311127e+02 9.19237823e+01 2.70504169e+01 -3.79263830e+00 5.78696251e+01 1.52986908e+02 1.68925110e+02 8.34273682e+01 -1.53538072e+00 -1.00724573e+01 5.75847626e+01 7.51969147e+01 5.68585777e+01 9.18522186e+01 1.73115097e+02 2.18825714e+02 1.46649612e+02 3.18545418e+01 -3.52917824e+01 -7.60086966e+00 5.58545303e+01 1.38869049e+02 1.86872925e+02 1.73556305e+02 1.45951889e+02 1.55335663e+02 1.47649536e+02 7.59197235e+01 4.08730841e+00 4.18723488e+01 1.54603027e+02 2.00368332e+02 1.57196075e+02 4.87489319e+01 1.77014005e+00 4.65504990e+01 9.60393753e+01 1.00645721e+02 9.51074295e+01 1.32856476e+02 2.19847702e+02 2.08077927e+02 1.25501060e+02 4.25089455e+01 4.58416328e+01 1.04481293e+02 1.50004761e+02 1.55078796e+02 1.33448395e+02 9.17038803e+01 8.00225220e+01 1.30148834e+02 1.51371811e+02 1.15946571e+02 7.68125916e+01 7.50564423e+01 1.01967964e+02 1.02265633e+02 6.17458000e+01 6.17592697e+01 9.70056686e+01 1.38655136e+02 1.50092819e+02 9.93017654e+01 8.44963150e+01 1.00222763e+02 1.39746902e+02 1.10852623e+02 2.62222838e+00 -5.29146156e+01 1.35234690e+01 1.15794815e+02 1.37366745e+02 9.03512039e+01 5.72209816e+01 6.16391716e+01 5.90046883e+01 2.45629826e+01 -2.83091660e+01 -3.89906235e+01 -1.62797279e+01 5.70534439e+01 1.09013168e+02 8.00130081e+01 5.93699722e+01 6.57298889e+01 1.12576050e+02 7.58882675e+01 -7.20224476e+00 3.36172342e+00 4.66199074e+01 8.15450287e+01 2.76085110e+01 -6.83080597e+01 -1.10659943e+02 -6.15134621e+01 2.63704300e+01 8.86341553e+01 7.69972382e+01 9.73995438e+01 1.08331902e+02 1.01888084e+02 4.34140739e+01 -2.71268253e+01 -2.66910286e+01 3.14568367e+01 1.37467377e+02 1.81431870e+02 1.53951660e+02 8.33215637e+01 3.20955467e+01 3.82284088e+01 1.74687386e+01 -9.29872799e+00 5.09395599e+00 6.60873871e+01 1.33537781e+02 9.92301178e+01 1.94939137e+01 -2.86221199e+01 2.61038361e+01 1.22880424e+02 1.53404984e+02 1.09114853e+02 5.48092766e+01 8.08940277e+01 1.28993484e+02 1.17525581e+02 6.29735146e+01 3.87571526e+01 9.14731979e+01 1.66977158e+02 1.85488632e+02 1.45194412e+02 1.03451096e+02 1.06926819e+02 1.28472061e+02 1.30954407e+02 1.12262291e+02 1.32784821e+02 1.63487122e+02 1.59839996e+02 1.47252899e+02 1.07342926e+02 9.26135559e+01 1.10569633e+02 1.11220306e+02 1.19434830e+02 9.07435837e+01 1.21351807e+02 1.51684021e+02 1.66172821e+02 1.50098267e+02 7.25203934e+01 3.37853317e+01 4.14020157e+01 1.31902481e+02 1.72745224e+02 1.76152557e+02 1.34608566e+02 1.20803917e+02 1.43539185e+02 1.45587555e+02 1.19850624e+02 1.02776901e+02 1.30996475e+02 1.50016754e+02 1.08001320e+02 4.96747780e+01 6.24699326e+01 9.43286057e+01 1.16234627e+02 1.00347527e+02 7.02192383e+01 1.10802383e+02 1.35980972e+02 1.62554993e+02 1.40374802e+02 9.85776215e+01 7.62033920e+01 5.75902100e+01 9.43889313e+01 1.18489189e+02 1.30851898e+02 9.99488068e+01 8.74890518e+01 9.28013916e+01 8.21698074e+01 6.45171051e+01 5.09788513e+01 9.97184219e+01 1.25888657e+02 1.23564156e+02 8.88753586e+01 9.67041855e+01 1.15130539e+02 1.35148712e+02 1.50375443e+02 1.41229416e+02 1.46368103e+02 1.08567253e+02 9.30541077e+01 7.43588104e+01 7.73599777e+01 9.20842743e+01 1.10832550e+02 1.46493423e+02 1.62828064e+02 1.53877914e+02 1.04421684e+02 9.56106949e+01 1.04445969e+02 1.19737633e+02 1.10200890e+02 1.21955910e+02 1.64807678e+02 1.87970474e+02 1.68233078e+02 1.18249100e+02 1.07508385e+02 1.27388298e+02 1.57004944e+02 1.62971436e+02 1.38770309e+02 1.35994507e+02 1.29381104e+02 1.57082993e+02 1.67511948e+02 1.74548279e+02 1.46418304e+02 1.35875748e+02 1.53319336e+02 1.76231476e+02 1.60537323e+02 1.33466980e+02 1.41284103e+02 1.54851898e+02 1.53757904e+02 1.32491257e+02 1.36879166e+02 1.63436050e+02 1.78142960e+02 1.69032227e+02 1.34208862e+02 1.39620956e+02 1.48525650e+02 1.65562286e+02 1.55736969e+02 1.39577713e+02 1.45280869e+02 1.44787598e+02 1.64346756e+02 1.68471924e+02 1.68078323e+02 1.54711105e+02 1.49441360e+02 1.58967453e+02 1.68463287e+02 1.61063171e+02 1.40481018e+02 1.36131607e+02 1.33047897e+02 1.24643883e+02 1.08997726e+02 1.16751999e+02 1.38928040e+02 1.41420258e+02 1.30656006e+02 1.14671234e+02 1.34211197e+02 1.41027740e+02 1.48111084e+02 1.57566895e+02 1.62594147e+02 1.53761261e+02 1.26027824e+02 1.20075691e+02 1.37640518e+02 1.56174744e+02 1.47368317e+02 1.24485001e+02 1.12727982e+02 1.25493713e+02 1.39626038e+02 1.37177948e+02 1.31752762e+02 1.20902206e+02 1.11234695e+02 9.80814590e+01 1.05121269e+02 1.18779793e+02 1.22380821e+02 1.15773186e+02 1.08596802e+02 1.27249130e+02 1.34816437e+02 1.40867813e+02 1.37129730e+02 1.36808884e+02 1.30242233e+02 1.10864471e+02 1.06097908e+02 1.20650291e+02 1.47371567e+02 1.54670532e+02 1.35203415e+02 1.16993362e+02 1.15642868e+02 1.29246323e+02 1.37899338e+02 1.33208755e+02 1.23481262e+02 1.19459389e+02 1.26604332e+02 1.41613708e+02 1.44348099e+02 1.36882339e+02 1.27489174e+02 1.18181343e+02 1.20047478e+02 1.24830429e+02 1.37109756e+02 1.49186295e+02 1.53031250e+02 1.46369614e+02 1.32805756e+02 1.26472878e+02 1.32942932e+02 1.41355118e+02 1.41335495e+02 1.33284637e+02 1.27037056e+02 1.30298462e+02 1.38627304e+02 1.44682098e+02 1.44934555e+02 1.40571823e+02 1.38058624e+02 1.36650177e+02 1.39837479e+02 1.41119629e+02 1.42094772e+02 1.41027481e+02 1.40521637e+02 1.42016037e+02 1.43324936e+02 1.44477325e+02 1.44201309e+02 1.43374542e+02 1.42942780e+02 1.43065292e+02 1.43608749e+02 1.43520813e+02 1.42018875e+02 1.40686737e+02 1.41325150e+02 1.44364609e+02 1.46663742e+02 1.46271286e+02 1.44383255e+02 1.44507492e+02 1.46536560e+02 1.48075378e+02 1.48753464e+02 1.45464523e+02 1.43338211e+02 1.40397400e+02 1.40282867e+02 1.42592087e+02 1.45219101e+02 1.48897064e+02 1.47526917e+02 1.43834274e+02 1.38813400e+02 1.38634415e+02 1.43736771e+02 1.50196533e+02 1.47496643e+02 1.41397156e+02 1.37540344e+02 1.43639969e+02 1.53609650e+02 1.54906479e+02 1.48173691e+02 1.35825089e+02 1.34817810e+02 1.44512268e+02 1.53551605e+02 1.59122147e+02 1.47586426e+02 1.44282272e+02 1.37922562e+02 1.38223434e+02 1.37193314e+02 1.35497269e+02 1.40621643e+02 1.36208252e+02 1.32634766e+02 1.35130463e+02 1.44320023e+02 1.61473907e+02 1.66620041e+02 1.56989883e+02 1.29956924e+02 1.08895004e+02 1.12512062e+02 1.37623871e+02 1.63880066e+02 1.70470795e+02 1.52087143e+02 1.30319458e+02 1.24774498e+02 1.40846207e+02 1.61527893e+02 1.55358246e+02 1.40620148e+02 1.21760773e+02 1.17977745e+02 1.24833786e+02 1.40597656e+02 1.58709381e+02 1.57180359e+02 1.37168015e+02 1.10286812e+02 1.06659363e+02 1.28707794e+02 1.57808762e+02 1.52891373e+02 1.27606728e+02 1.10405182e+02 1.17526993e+02 1.34741638e+02 1.40040909e+02 1.45217865e+02 1.37341965e+02 1.30466553e+02 1.39954208e+02 1.41246445e+02 1.49978333e+02 1.34688293e+02 1.24691612e+02 1.05235672e+02 9.40233231e+01 1.04928581e+02 1.23031906e+02 1.49189880e+02 1.61542053e+02 1.46457779e+02 1.19558815e+02 1.13373863e+02 1.42122086e+02 1.73078690e+02 1.70704559e+02 1.47554337e+02 1.13350533e+02 1.04998314e+02 1.19252609e+02 1.36640137e+02 1.39287918e+02 1.12130692e+02 8.87262268e+01 6.82618637e+01 7.49535370e+01 1.08326836e+02 1.04318649e+02 9.22763596e+01 5.89042664e+01 5.56943588e+01 6.50981674e+01 8.58635864e+01 1.31866898e+02 1.50052704e+02 1.43753448e+02 1.04846298e+02 8.62017746e+01 1.14049232e+02 1.52745438e+02 1.52837173e+02 1.09026329e+02 7.39086838e+01 8.50876312e+01 1.26953781e+02 1.60368088e+02 1.65311615e+02 1.30248016e+02 8.61416168e+01 7.27468796e+01 7.84402390e+01 9.56064148e+01 1.08834641e+02 1.35087799e+02 1.38002930e+02 1.25804779e+02 1.11019630e+02 1.26337555e+02 1.66317062e+02 1.92775421e+02 1.62947754e+02 1.06195763e+02 7.43409348e+01 1.03445511e+02 1.60713638e+02 1.73679794e+02 1.43873032e+02 9.03711777e+01 8.40598145e+01 1.17075081e+02 1.34398422e+02 1.36577560e+02 1.02515739e+02 9.18613358e+01 9.83853912e+01 1.12809067e+02 1.43988419e+02 1.37555161e+02 1.34360458e+02 8.24883499e+01 4.68394775e+01 5.23562698e+01 8.01549606e+01 1.28669312e+02 1.49524048e+02 1.49063889e+02 9.16841431e+01 -3.79773664e+00 -4.51490326e+01 -2.98581600e+01 9.15785599e+01 1.25665207e+02 1.79947159e+02 2.03030441e+02 -1.15853687e+03 -1.84409937e+03 -3.68945703e+03 -1.14620293e+04 362859104. -2.41568486e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 238809552. 180030000. 205186256. -205166352. -2.87536582e+04 -1.00697207e+04 -2.77751367e+03 -2.18407883e+02 1.22181454e+01 7.86886368e+01 8.62977371e+01 4.19480705e+01 3.27194214e+01 5.76427383e+01 1.48958801e+02 1.47182693e+02 9.91612091e+01 2.69396381e+01 3.80432816e+01 1.08904854e+02 1.73745316e+02 1.92459229e+02 1.35207108e+02 4.25837669e+01 2.29567833e+01 8.66911240e+01 1.60884811e+02 1.59551331e+02 1.02510300e+02 1.00652534e+02 1.43098099e+02 1.53087479e+02 1.13252419e+02 6.73653107e+01 6.43299408e+01 5.06279297e+01 3.02518959e+01 3.10707588e+01 8.34282150e+01 1.74756073e+02 1.83155228e+02 1.23027489e+02 5.96123428e+01 5.75241280e+01 1.20207298e+02 1.87008194e+02 1.78840729e+02 8.35838699e+01 -2.60081749e+01 -1.70014095e+01 9.48052673e+01 1.50230530e+02 1.57354980e+02 9.18564301e+01 6.67325211e+01 5.02278137e+01 4.27578850e+01 6.41706848e+01 1.01520737e+02 1.68139374e+02 1.45479874e+02 8.17198486e+01 5.92770081e+01 1.03821793e+02 1.81324890e+02 1.81095627e+02 1.38630600e+02 6.96632233e+01 4.04815826e+01 1.10431808e+02 2.01497375e+02 2.73227753e+02 2.32383667e+02 1.30542633e+02 9.58106384e+01 1.52102554e+02 1.93569901e+02 1.80365585e+02 9.03166504e+01 7.40570831e+01 9.77998199e+01 1.39378448e+02 1.33182632e+02 1.33272400e+02 1.63702393e+02 1.25831474e+02 6.03208313e+01 2.47589378e+01 1.00142075e+02 2.04518951e+02 2.24791260e+02 1.93624939e+02 1.16494225e+02 5.11622200e+01 4.41185188e+01 1.07282585e+02 1.67598740e+02 1.51954163e+02 4.92251854e+01 -1.86624956e+00 8.38772736e+01 1.54538757e+02 1.58482193e+02 4.75743446e+01 -3.01756859e+00 5.12960577e+00 2.27771988e+01 4.55550919e+01 7.47400436e+01 1.54753479e+02 1.46493042e+02 8.47656937e+01 2.55361576e+01 3.80535393e+01 1.06224289e+02 1.19249130e+02 6.96925507e+01 2.92559814e+01 -1.52383099e+01 3.06150246e+00 7.77099838e+01 1.50412582e+02 1.72024567e+02 6.00897636e+01 1.18693190e+01 4.75882988e+01 8.55859833e+01 8.59268265e+01 3.61889229e+01 4.47512436e+01 5.01102829e+01 2.07793217e+01 2.00692248e+00 2.02802162e+01 1.08965477e+02 1.09452904e+02 4.23608894e+01 -7.09108543e+00 2.77740455e+00 7.01721115e+01 5.52708969e+01 5.00811115e-02 -3.64869804e+01 -7.23913956e+01 -2.36128349e+01 5.65686150e+01 1.23968552e+02 1.16344398e+02 4.32524490e+01 2.81162796e+01 4.41433372e+01 4.11057129e+01 1.72141132e+01 -2.18703442e+01 -5.87252846e+01 -8.32059784e+01 -1.00341835e+02 -6.31927948e+01 3.11014414e+00 9.05068588e+01 1.18688499e+02 8.41158752e+01 3.48062515e+01 4.32701149e+01 1.06349800e+02 1.63595078e+02 1.21801071e+02 1.66456871e+01 -6.23053856e+01 -5.45023155e+01 4.92970314e+01 1.02298035e+02 9.96133194e+01 2.67210464e+01 1.66690331e+01 3.32630539e+01 3.96339111e+01 4.90744133e+01 6.51535339e+01 6.93157425e+01 3.52986908e+00 -7.44274979e+01 -7.84796143e+01 -4.46864548e+01 1.23253117e+01 5.66359787e+01 6.27012672e+01 5.03621674e+01 3.84852715e+01 1.04336258e+02 1.62910843e+02 1.34984558e+02 2.71022091e+01 -6.82379227e+01 -7.46242294e+01 4.88853598e+00 2.87689266e+01 3.16941071e+01 -5.03742485e+01 -4.16597900e+01 6.80957174e+00 9.02175598e+01 1.36199524e+02 1.43256134e+02 1.92272858e+02 1.51601212e+02 5.38983383e+01 -2.14402828e+01 -1.48497019e+01 7.48799210e+01 8.40733032e+01 2.62188168e+01 -5.44959450e+01 -1.26872467e+02 -8.50530014e+01 2.87863464e+01 1.40566925e+02 1.15992859e+02 4.43001747e+00 -2.52820568e+01 1.48889437e+01 4.16023636e+01 4.70982666e+01 6.59689474e+00 -2.86812019e+01 -5.27693481e+01 -4.11095467e+01 -2.62329922e+01 1.29099007e+01 7.83897095e+01 1.15847328e+02 8.66042633e+01 4.02510452e+01 2.38159695e+01 2.76312237e+01 -4.82632208e+00 -5.25466690e+01 -6.67678680e+01 -5.65945549e+01 -7.97230291e+00 8.60239315e+00 2.63152905e+01 1.24531107e+01 -2.41876488e+01 -3.62390976e+01 -2.95110760e+01 6.81126070e+00 1.41557217e+01 -3.63843155e+00 -1.99931965e+01 -2.28535576e+01 8.16007996e+00 1.95766716e+01 1.81167450e+01 -6.82223225e+00 -2.28149185e+01 -3.50588837e+01 -3.59631920e+01 -4.45285606e+01 -3.41516304e+01 -2.69302273e+01 -9.50769711e+00 -2.36450424e+01 -2.94816494e+01 -3.71675072e+01 -3.39351692e+01 -4.49633636e+01 -6.01781998e+01 -5.59118042e+01 -6.54982147e+01 -6.94950943e+01 -6.35072517e+01 -3.10506516e+01 -2.23879337e+01 -4.72339439e+01 -6.21809044e+01 -5.23674088e+01 -4.53955460e+01 -5.42093620e+01 -6.58275223e+01 -6.43341446e+01 -6.48088684e+01 -5.14993324e+01 -4.45512276e+01 -3.91808167e+01 -5.42168732e+01 -5.49779129e+01 -7.33774033e+01 -7.60037079e+01 -6.56990662e+01 -4.82122040e+01 -5.46947479e+01 -6.70423279e+01 -7.02671051e+01 -4.08448830e+01 -1.75678825e+01 -6.52843475e+00 -2.90872078e+01 -4.71897774e+01 -6.06503830e+01 -5.49183884e+01 -4.48045273e+01 -3.56366882e+01 -3.22275276e+01 -5.33616753e+01 -5.48122063e+01 -5.73614655e+01 -5.34053879e+01 -6.79854126e+01 -6.84462891e+01 -6.21610069e+01 -6.21176376e+01 -5.76786575e+01 -4.88158875e+01 -3.19396095e+01 -1.66770630e+01 -2.80214272e+01 -2.98191090e+01 -5.19921112e+01 -6.02907944e+01 -1.01134758e+02 -1.28352524e+02 -1.24153084e+02 -9.27326584e+01 -6.49282913e+01 -5.44890518e+01 -3.58348885e+01 -3.71063309e+01 -7.31878967e+01 -1.14122864e+02 -1.04910675e+02 -6.72597198e+01 -3.51647034e+01 -3.17297096e+01 -3.95571327e+01 -3.52581863e+01 -3.55110741e+01 -2.82164879e+01 -4.11962700e+01 -4.48566933e+01 -4.52910233e+01 -5.77278633e+01 -6.66505966e+01 -5.42983208e+01 -3.85337143e+01 -1.09989376e+01 -2.12491589e+01 -2.20694351e+01 -5.84298096e+01 -5.26327515e+01 -4.65354385e+01 -4.46355972e+01 -5.94372253e+01 -6.45292587e+01 -3.60032349e+01 -5.65945005e+00 -3.51067877e+00 -4.06798706e+01 -7.09688950e+01 -8.29120178e+01 -6.60230331e+01 -1.77178669e+01 1.38743954e+01 -7.82273245e+00 -7.72914886e+01 -1.04045677e+02 -8.42638092e+01 -6.64132614e+01 -4.79290619e+01 -2.97710876e+01 -1.91033351e+00 -2.01671009e+01 -4.52403450e+01 -7.73644867e+01 -7.31674194e+01 -7.02944031e+01 -4.50635262e+01 -3.64604874e+01 -4.42568092e+01 -7.12836304e+01 -8.88775101e+01 -9.52630005e+01 -9.10106125e+01 -9.21422272e+01 -9.92503204e+01 -1.08315163e+02 -1.09106964e+02 -9.25962524e+01 -7.52422409e+01 -8.53441391e+01 -9.46544342e+01 -9.95322266e+01 -8.96147690e+01 -8.74131241e+01 -1.01782127e+02 -7.60751190e+01 -5.46043205e+01 -5.47370148e+01 -9.14973450e+01 -1.15422852e+02 -9.77360611e+01 -8.79063644e+01 -7.93650665e+01 -6.72011337e+01 -5.20484238e+01 -5.15798950e+01 -4.23720245e+01 -4.27140160e+01 -5.01268120e+01 -8.14183426e+01 -9.04195862e+01 -8.15328598e+01 -7.92310791e+01 -8.31052094e+01 -8.84430695e+01 -8.55915604e+01 -8.52819824e+01 -5.88157310e+01 -3.72791901e+01 -3.65273781e+01 -6.28803825e+01 -8.66769028e+01 -9.33401260e+01 -9.93634033e+01 -1.00158875e+02 -9.83285446e+01 -9.37912979e+01 -9.85270386e+01 -1.13713852e+02 -1.36925812e+02 -1.44552719e+02 -1.34970612e+02 -1.08577538e+02 -1.06021172e+02 -1.13954193e+02 -1.18217850e+02 -1.13325760e+02 -1.06590248e+02 -1.38849747e+02 -1.73429398e+02 -1.79327667e+02 -1.42399582e+02 -1.03773018e+02 -9.89266205e+01 -1.23287704e+02 -1.60940552e+02 -2.76704742e+02 -4.51772034e+02 -6.77577271e+02 -2.60120898e+03 -3.75594922e+03 -4.17050476e+02 -5.00505127e+02 -6.30640320e+02 -8.88686707e+02 -7.97525024e+02 -4.73307556e+02 -7.19672363e+02 -1.24995740e+03 -1.01706836e+04 -2.52621699e+04 726899072. 581115200. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1342290816. -200843328. -525966304. -9.63161133e+03 -3.56590454e+03 -4.33552917e+02 -1.97430420e+02 -1.53939133e+02 -1.70416199e+02 -1.66839066e+02 -1.48718826e+02 -1.28391525e+02 -1.34461945e+02 -1.39623962e+02 -1.39501495e+02 -1.39895142e+02 -1.51979340e+02 -1.65539139e+02 -1.50414185e+02 -1.20469147e+02 -1.13203697e+02 -1.34022705e+02 -1.52298340e+02 -1.40058960e+02 -1.38201996e+02 -1.42585571e+02 -1.52433762e+02 -1.56087326e+02 -1.57517212e+02 -1.52803329e+02 -1.42334396e+02 -1.38214874e+02 -1.39479614e+02 -1.45260605e+02 -1.29023788e+02 -1.10275314e+02 -1.07218140e+02 -1.19001991e+02 -1.29770523e+02 -1.25855064e+02 -1.18634705e+02 -1.17762291e+02 -1.11138481e+02 -1.06195641e+02 -1.03854568e+02 -1.01450851e+02 -1.02600639e+02 -1.06986343e+02 -1.12492050e+02 -1.17590294e+02 -1.14605659e+02 -1.14099464e+02 -1.15519104e+02 -1.15391312e+02 -1.15902679e+02 -1.11032967e+02 -1.08178505e+02 -1.13059860e+02 -1.28567429e+02 -1.47300079e+02 -1.56964081e+02 -1.48772568e+02 -1.36963043e+02 -1.29106232e+02 -1.40835403e+02 -1.50787155e+02 -1.46035156e+02 -1.30948685e+02 -1.18190834e+02 -1.18240433e+02 -1.18916931e+02 -1.12248909e+02 -9.74747543e+01 -1.07367126e+02 -1.26262459e+02 -1.43522675e+02 -1.41162766e+02 -1.31980347e+02 -1.32887894e+02 -1.29526901e+02 -1.31714691e+02 -1.29804428e+02 -1.33663589e+02 -1.34161514e+02 -1.37907684e+02 -1.39483887e+02 -1.38458023e+02 -1.35793365e+02 -1.36687729e+02 -1.47297241e+02 -1.60483719e+02 -1.53398300e+02 -1.45055664e+02 -1.34690033e+02 -1.41222733e+02 -1.44848389e+02 -1.50607819e+02 -1.55625351e+02 -1.48329758e+02 -1.37019485e+02 -1.32517197e+02 -1.38070709e+02 -1.49646683e+02 -1.49888153e+02 -1.48939255e+02 -1.42851944e+02 -1.39380737e+02 -1.39688644e+02 -1.38903320e+02 -1.39512787e+02 -1.38066208e+02 -1.40395752e+02 -1.39877243e+02 -1.38614410e+02 -1.43691956e+02 -1.49665894e+02 -1.49335159e+02 -1.43309372e+02 -1.37953369e+02 -1.37876938e+02 -1.35599670e+02 -1.36009155e+02 -1.34831543e+02 -1.35325470e+02 -1.35061111e+02 -1.42622314e+02 -1.49418121e+02 -1.50013580e+02 -1.44495865e+02 -1.39297928e+02 -1.36141632e+02 -1.34146439e+02 -1.34510895e+02 -1.37290756e+02 -1.39120438e+02 -1.37450226e+02 -1.40111954e+02 -1.41029739e+02 -1.41255783e+02 -1.40010849e+02 -1.40188156e+02 -1.41524750e+02 -1.41899612e+02 -1.41664734e+02 -1.41788971e+02 -1.42703201e+02 -1.42582184e+02 -1.42746582e+02 -1.42846130e+02 -1.43566086e+02 -1.44074036e+02 -1.43416397e+02 -1.42766724e+02 -1.42342529e+02 -1.42206024e+02 -1.41763382e+02 -1.41282242e+02 -1.41244156e+02 -1.41879883e+02 -1.44607086e+02 -1.46155624e+02 -1.46102768e+02 -1.45042343e+02 -1.43898132e+02 -1.43767319e+02 -1.43121536e+02 -1.42863678e+02 -1.42994614e+02 -1.43155930e+02 -1.43186996e+02 -1.43150375e+02 -1.43069458e+02 -1.43003998e+02 -1.43013077e+02 -1.43333115e+02 -1.43806961e+02 -1.44098465e+02 -1.43809235e+02 -1.43287201e+02 -1.42454605e+02 -1.42663589e+02 -1.42803360e+02 -1.43097763e+02 -1.42796967e+02 -1.43068649e+02 -1.43092392e+02 -1.43338730e+02 -1.43595123e+02 -1.43080292e+02 -1.42726501e+02 -1.42811142e+02 -1.43351242e+02 -1.43828110e+02 -1.42132599e+02 -1.41162674e+02 -1.40246185e+02 -1.40336716e+02 -1.41393646e+02 -1.44773087e+02 -1.49084747e+02 -1.51363022e+02 -1.51888367e+02 -1.51482712e+02 -1.52796509e+02 -1.49558182e+02 -1.44297974e+02 -1.37999924e+02 -1.36496948e+02 -1.37425247e+02 -1.39549286e+02 -1.39876663e+02 -1.39403122e+02 -1.37247864e+02 -1.37250031e+02 -1.37607544e+02 -1.39146225e+02 -1.38969376e+02 -1.38462723e+02 -1.32731857e+02 -1.26418816e+02 -1.27911842e+02 -1.32817017e+02 -1.39071655e+02 -1.42132080e+02 -1.45761948e+02 -1.53711548e+02 -1.59138519e+02 -1.56597336e+02 -1.51394913e+02 -1.41304871e+02 -1.44764145e+02 -1.47223923e+02 -1.52074280e+02 -1.51707779e+02 -1.49294998e+02 -1.49237717e+02 -1.49819290e+02 -1.49343521e+02 -1.45671280e+02 -1.42226196e+02 -1.42431168e+02 -1.50228256e+02 -1.59891022e+02 -1.69507538e+02 -1.72891739e+02 -1.55923660e+02 -1.36148071e+02 -1.25372070e+02 -1.31082733e+02 -1.42318802e+02 -1.41519760e+02 -1.45013901e+02 -1.43173431e+02 -1.42638779e+02 -1.39207611e+02 -1.37909241e+02 -1.38786240e+02 -1.42065018e+02 -1.41521378e+02 -1.30318039e+02 -1.15508621e+02 -1.12540924e+02 -1.18703339e+02 -1.27547653e+02 -1.34173599e+02 -1.42927872e+02 -1.44320663e+02 -1.38367508e+02 -1.36754333e+02 -1.42857010e+02 -1.44246750e+02 -1.36356400e+02 -1.29572403e+02 -1.26108269e+02 -1.27840813e+02 -1.29723312e+02 -1.33327393e+02 -1.31536316e+02 -1.33801575e+02 -1.32882050e+02 -1.32392914e+02 -1.24292198e+02 -1.19007500e+02 -1.20107216e+02 -1.32449066e+02 -1.52859756e+02 -1.54261734e+02 -1.40914993e+02 -1.23651939e+02 -1.27996941e+02 -1.31560913e+02 -1.31911530e+02 -1.29023102e+02 -1.28873840e+02 -1.33490067e+02 -1.43469971e+02 -1.52694580e+02 -1.50430222e+02 -1.34815399e+02 -1.21058037e+02 -1.19954056e+02 -1.26973961e+02 -1.17924919e+02 -1.00707703e+02 -9.40724106e+01 -9.93055878e+01 -1.14878525e+02 -1.12530678e+02 -1.14493919e+02 -1.13393684e+02 -1.20725716e+02 -1.19632385e+02 -1.18230545e+02 -1.08763649e+02 -1.13101395e+02 -1.12571404e+02 -1.14090103e+02 -1.10585838e+02 -1.16576019e+02 -1.22196541e+02 -1.35197266e+02 -1.46741104e+02 -1.44495865e+02 -1.35080261e+02 -1.24064377e+02 -1.25160393e+02 -1.19067345e+02 -1.11591988e+02 -1.12538246e+02 -1.38201706e+02 -1.59787460e+02 -1.63491776e+02 -1.43915085e+02 -1.26642418e+02 -1.27139740e+02 -1.29810562e+02 -1.30600967e+02 -1.26501068e+02 -1.39493240e+02 -1.66503067e+02 -1.70940933e+02 -1.53118851e+02 -1.22114616e+02 -1.24164291e+02 -1.24029289e+02 -1.26317436e+02 -1.22195717e+02 -1.25668320e+02 -1.31902145e+02 -1.41748901e+02 -1.44451569e+02 -1.36513290e+02 -1.27302124e+02 -1.30831284e+02 -1.54909866e+02 -1.88839432e+02 -1.90875412e+02 -1.64190979e+02 -1.33005493e+02 -1.27243614e+02 -1.21751938e+02 -1.21622002e+02 -1.25782448e+02 -1.57357956e+02 -1.76335800e+02 -2.05536179e+02 -2.08693863e+02 -1.82118881e+02 -1.53906204e+02 -1.20762466e+02 -1.43126160e+02 -1.64031937e+02 -1.38837692e+02 -8.68082809e+01 -5.62254601e+01 -7.97910156e+01 -1.14472710e+02 -1.11100929e+02 -1.11032784e+02 -1.04564468e+02 -1.03471558e+02 -9.27665482e+01 -8.53369598e+01 -8.10114899e+01 -7.88174210e+01 -8.08135147e+01 -8.42554779e+01 -8.60070572e+01 -8.29863510e+01 -8.53412094e+01 -1.00008430e+02 -1.29784302e+02 -1.22196449e+02 -1.01711754e+02 -6.95195923e+01 -9.80439606e+01 -1.29347992e+02 -1.00953461e+02 -4.31000900e+01 -4.47327919e+01 -1.13997284e+02 -1.56363312e+02 -1.28993408e+02 -9.62777939e+01 -1.13615929e+02 -1.50045929e+02 -1.55486832e+02 -1.41392014e+02 -1.09853981e+02 -1.12808426e+02 -1.14758331e+02 -1.09147858e+02 -1.07472542e+02 -8.16451721e+01 -6.05383606e+01 -9.05610275e+01 -1.43796310e+02 -1.74133591e+02 -1.46746262e+02 -1.25072655e+02 -1.49086731e+02 -1.71655060e+02 -1.77688339e+02 -1.50823959e+02 -1.18536797e+02 -1.21902039e+02 -1.25703545e+02 -1.32249557e+02 -1.16713554e+02 -1.32147812e+02 -1.59384613e+02 -1.67437943e+02 -1.59267807e+02 -1.21820717e+02 -9.74554749e+01 -8.74709015e+01 -8.75171280e+01 -1.04639870e+02 -5.52858887e+01 -4.77974749e+00 -9.48329353e+00 -7.14624786e+01 -1.22757996e+02 -1.09638062e+02 -8.50226974e+01 -1.06025650e+02 -1.43641800e+02 -1.44217667e+02 -1.18082169e+02 -8.42619781e+01 -7.61803894e+01 -7.53273621e+01 -7.36783295e+01 -7.58669739e+01 -7.67912903e+01 -8.81621017e+01 -1.13241600e+02 -1.22631035e+02 -1.11685387e+02 -8.62452850e+01 -7.32087631e+01 -6.44744720e+01 -6.81759949e+01 -3.28612480e+01 2.61228538e+00 -2.72607155e+01 -1.03582031e+02 -1.46315857e+02 -1.06420746e+02 -5.95270042e+01 -3.65265923e+01 -2.82046185e+01 -2.56736259e+01 -3.28986473e+01 -4.12257538e+01 -3.59783363e+01 -4.23619576e+01 -4.02767792e+01 -4.46600914e+01 -2.98402481e+01 -2.63265324e+01 -2.23988914e+01 -4.45270576e+01 -4.83479042e+01 -3.53512726e+01 -1.47991533e+01 -7.74688196e+00 -3.05277157e+01 -5.08440247e+01 -6.41774292e+01 -9.63170013e+01 -1.25462883e+02 -1.34718979e+02 -1.04673393e+02 -1.03554230e+02 -1.65388336e+02 -2.06632477e+02 -1.78496811e+02 -1.28844513e+02 -1.35406235e+02 -1.79774277e+02 -1.81602371e+02 -1.40839050e+02 -1.07339508e+02 -1.03515869e+02 -1.07974823e+02 -1.09773041e+02 -1.14158257e+02 -1.10272789e+02 -9.11113129e+01 -1.07034210e+02 -1.39933197e+02 -1.64128876e+02 -1.34872101e+02 -9.47355728e+01 -9.52579651e+01 -1.21852737e+02 -8.91990891e+01 -3.68847885e+01 -5.30018044e+00 -2.77608013e+01 -5.75289154e+01 -4.28120537e+01 -4.56890373e+01 -4.68499832e+01 -5.41498375e+01 -4.67582970e+01 -4.52833862e+01 -5.27363510e+01 -4.60529823e+01 -3.82656250e+01 -1.93568230e+01 -2.79512806e+01 -4.27143936e+01 -5.03154716e+01 -7.59288254e+01 -1.02915627e+02 -9.67414093e+01 -5.62740784e+01 -8.38111782e+00 5.37941504e+00 -1.99682742e-01 2.57760429e+01 5.68408813e+01 6.02866173e+01 3.44213943e+01 -3.88545878e-02 2.86502004e-01 -2.50459105e-01 -5.57739716e+01 -1.09851654e+02 -1.20650070e+02 -8.03644485e+01 -5.31120224e+01 -5.79831543e+01 -4.64232140e+01 -2.28488407e+01 -2.46338806e+01 3.08886504e+00 4.07227173e+01 2.51352119e+01 -3.62652931e+01 -7.91224060e+01 -6.10575371e+01 -6.73597031e+01 -1.36104034e+02 -1.77445099e+02 -1.55325439e+02 -7.61604385e+01 -5.38602448e+01 -8.07814636e+01 -8.60007172e+01 -5.68462524e+01 -1.51677918e+00 -1.15883560e+01 -4.06312599e+01 -4.30871162e+01 -2.39940186e+01 1.03831625e+01 2.60313091e+01 3.37056885e+01 4.14218483e+01 2.40893230e+01 2.99450054e+01 3.39578400e+01 2.57626963e+00 -2.83070183e+01 -4.50854530e+01 -1.41474724e+01 1.08483534e+01 -9.01068020e+00 -3.94771309e+01 -2.35455723e+01 1.72376450e+02 3.28999969e+02 3.86801605e+02 2.82317188e+03 4.55244678e+03 2.18530334e+02 6.24774902e+02 7.27376892e+02 -3.20098267e+03 -1.45053638e+03 3.29319116e+03 3.85698828e+03 -1.80620825e+03 -2.62980200e+03 -5.22028516e+03 -2.32289375e+04 -652330752. 0. 0. 0. 0. 0. 0. 2.26273956e+10 2.26273956e+10 2.44004434e+04 5.29405391e+04 5.29405391e+04 3.13963192e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -855827968. -8622476. 6835689. 1.97393965e+04 8.13630615e+03 -8.81611450e+02 8.63096985e+02 3.10262622e+03 3.69037018e+02 7.28763351e+01 7.18290558e+01 4.49999161e+01 2.92763481e+01 6.53043823e+01 1.05900772e+02 7.67033463e+01 -9.03530216e+00 -4.97146759e+01 1.37813206e+01 1.23876480e+02 1.16288055e+02 2.29962425e+01 -9.00945206e+01 -1.05883774e+02 -5.42587357e+01 -6.24374771e+01 -1.03309921e+02 -1.09137169e+02 -5.99316101e+01 -1.77437382e+01 -5.92276878e+01 -1.63078751e+02 -1.81847519e+02 -1.12780533e+02 -2.65086327e+01 2.29290791e+01 3.52316208e+01 7.18866043e+01 1.16285172e+02 1.29199951e+02 6.88424530e+01 -9.07870865e+01 -1.73310913e+02 -1.29870346e+02 -1.98524647e+01 5.52070923e+01 4.93319054e+01 2.05268459e+01 -2.67416935e+01 -8.57312775e+00 -2.82054520e+01 -5.55666275e+01 -2.92110062e+01 7.14235077e+01 1.83176224e+02 1.64581528e+02 1.42516098e+01 -6.19023018e+01 -2.44336262e+01 5.92957497e+01 4.54148979e+01 -1.93980083e+01 -1.85320301e+01 5.64001274e+01 1.32082947e+02 1.16799530e+02 -2.34380078e+00 -8.39881058e+01 -5.95003777e+01 1.55483017e+01 3.71344223e+01 8.11025620e+00 7.63497210e+00 5.49057884e+01 1.21728554e+02 1.02846069e+02 6.70124283e+01 6.89259262e+01 1.11898384e+02 1.30498123e+02 1.02764709e+02 5.14211311e+01 1.06564033e+00 -1.00985250e+01 2.38960476e+01 5.58180733e+01 5.28228493e+01 9.75257950e+01 1.71898422e+02 1.96469437e+02 1.20235641e+02 -1.75388470e+01 -7.81409378e+01 -3.29556465e+01 7.78800888e+01 1.83052536e+02 2.20309265e+02 1.98481598e+02 1.71634750e+02 1.78920410e+02 1.49265503e+02 5.91558952e+01 -1.28119392e+01 1.59216881e+01 8.28097839e+01 1.14749489e+02 8.95549393e+01 3.23373718e+01 1.90562210e+01 5.30253372e+01 9.29257736e+01 8.56893845e+01 7.81292877e+01 1.14674759e+02 1.98975037e+02 2.11561981e+02 1.49642334e+02 6.55526657e+01 6.52252884e+01 1.24028503e+02 1.70142044e+02 1.70907211e+02 1.18383789e+02 6.17750244e+01 4.13048134e+01 7.19307480e+01 7.10236359e+01 2.62451782e+01 2.08167858e+01 7.49164124e+01 1.27944946e+02 1.29595490e+02 7.54099808e+01 4.82715683e+01 7.62707138e+01 1.07408226e+02 1.23723358e+02 1.02050064e+02 1.17270218e+02 1.68411514e+02 1.82238876e+02 1.13234955e+02 -1.04273052e+01 -7.74418411e+01 -2.47017879e+01 6.12766647e+01 9.86769943e+01 8.09972382e+01 5.28124428e+01 5.00931740e+01 4.41112633e+01 2.94386506e+00 -4.71944084e+01 -5.42923851e+01 1.58849144e+01 1.30463455e+02 1.74549744e+02 1.06766693e+02 3.29481964e+01 3.51635551e+01 6.93961411e+01 4.08812981e+01 -4.01065598e+01 -3.53054543e+01 4.92037239e+01 1.26796921e+02 7.24946060e+01 -5.99451828e+01 -1.34401352e+02 -7.84364319e+01 2.39866600e+01 7.98930130e+01 7.75610733e+01 8.48044205e+01 1.01327843e+02 8.13653183e+01 1.89951859e+01 -6.41330948e+01 -2.62997932e+01 4.09911728e+01 1.11597404e+02 9.53658600e+01 6.55388641e+01 3.06918316e+01 1.86860943e+01 1.91482353e+01 -3.26495409e+00 -4.11828308e+01 -2.21580257e+01 5.56706886e+01 1.29283066e+02 1.14672935e+02 3.54179764e+01 -2.95423775e+01 -1.61446686e+01 3.89475098e+01 7.66218872e+01 8.31951141e+01 9.77826233e+01 1.54957001e+02 1.81916611e+02 1.23273926e+02 4.44321213e+01 1.20650177e+01 5.67083817e+01 1.11450172e+02 1.37524414e+02 1.23907791e+02 1.02941940e+02 8.04427185e+01 8.79839783e+01 6.74497681e+01 3.77151413e+01 6.66914825e+01 1.12636200e+02 1.38198471e+02 1.25462227e+02 8.52082977e+01 7.81173172e+01 9.44597244e+01 1.01644173e+02 9.49547882e+01 5.77765121e+01 8.49107971e+01 1.24844902e+02 1.55339523e+02 1.59385651e+02 1.00943298e+02 6.36051712e+01 7.44842911e+01 1.36449127e+02 1.49786041e+02 1.16239052e+02 6.98303299e+01 7.96199646e+01 1.08169250e+02 1.04865807e+02 6.85236588e+01 5.97086220e+01 1.12099167e+02 1.42015778e+02 1.14462585e+02 8.18709488e+01 1.05832306e+02 1.25564758e+02 1.11217270e+02 9.53162994e+01 8.24696426e+01 9.66877136e+01 7.04915543e+01 5.70277252e+01 5.73177071e+01 4.64294930e+01 3.13215923e+01 2.71529598e+01 8.28132553e+01 1.04046494e+02 1.05078087e+02 6.22962990e+01 7.39792099e+01 7.96373138e+01 6.96760101e+01 3.89223061e+01 2.72036972e+01 7.50944672e+01 1.08805763e+02 1.10848534e+02 6.44038544e+01 6.10566330e+01 7.31483765e+01 9.77215729e+01 9.58287506e+01 6.04780045e+01 7.02054062e+01 9.39801025e+01 1.39979172e+02 1.56453278e+02 1.44220901e+02 1.12697823e+02 8.63129959e+01 1.05619385e+02 1.35765198e+02 1.48419586e+02 1.33811874e+02 1.49036392e+02 1.50512436e+02 1.23179886e+02 8.40336380e+01 8.03476410e+01 1.35093414e+02 1.50146393e+02 1.28295853e+02 8.42231827e+01 1.02437904e+02 1.25005348e+02 1.31121841e+02 1.15607185e+02 9.59321899e+01 9.98707504e+01 9.25491333e+01 1.17374565e+02 1.29531387e+02 1.32128601e+02 1.08529755e+02 9.56612854e+01 1.17331131e+02 1.35587021e+02 1.41630096e+02 1.39600662e+02 1.74173813e+02 1.92046799e+02 1.88663879e+02 1.73471313e+02 1.72904465e+02 1.92323563e+02 1.99375916e+02 1.82299210e+02 1.44295715e+02 1.29759277e+02 1.27291878e+02 1.37050903e+02 1.28893738e+02 1.06645782e+02 8.94189987e+01 8.23078232e+01 1.07813026e+02 1.19831360e+02 1.29754776e+02 1.21493286e+02 1.26334259e+02 1.34604431e+02 1.46472809e+02 1.43192352e+02 1.43585281e+02 1.59059036e+02 1.72911667e+02 1.63614777e+02 1.43433609e+02 1.42070709e+02 1.37650894e+02 1.15954201e+02 9.57838364e+01 8.85409241e+01 1.10825935e+02 1.14971741e+02 1.18418869e+02 1.32188416e+02 1.32155533e+02 1.19402908e+02 8.95603333e+01 8.30870056e+01 1.07979828e+02 1.29005692e+02 1.28082138e+02 1.10670486e+02 9.72782288e+01 1.06731918e+02 1.23907433e+02 1.37434219e+02 1.37910126e+02 1.21892517e+02 1.12636253e+02 9.83607483e+01 1.00245621e+02 1.00641830e+02 9.27435760e+01 8.87751389e+01 8.65493011e+01 1.10183296e+02 1.13758163e+02 1.15446114e+02 1.13865005e+02 1.10171982e+02 9.68016205e+01 6.97288437e+01 6.64701080e+01 8.89799118e+01 1.24210579e+02 1.38955048e+02 1.18176743e+02 9.12292404e+01 9.11954803e+01 1.18327103e+02 1.47266556e+02 1.39250320e+02 1.14755684e+02 1.00955292e+02 1.02567596e+02 1.17674034e+02 1.14701134e+02 1.06808754e+02 9.99241791e+01 9.83508987e+01 1.10316109e+02 1.09847969e+02 1.05523026e+02 9.83727417e+01 9.94418030e+01 1.05807388e+02 1.04106911e+02 1.02343231e+02 1.13114838e+02 1.25972176e+02 1.24888573e+02 1.05919701e+02 9.40325623e+01 9.95379562e+01 1.14025436e+02 1.21599480e+02 1.19010773e+02 1.09989128e+02 1.06002319e+02 1.05059921e+02 1.12622284e+02 1.13783783e+02 1.12963844e+02 1.09865692e+02 1.07945900e+02 1.12643585e+02 1.15599838e+02 1.20455223e+02 1.19878349e+02 1.18348610e+02 1.14496727e+02 1.09495110e+02 1.07989746e+02 1.11526443e+02 1.17606018e+02 1.19964836e+02 1.17286156e+02 1.12508316e+02 1.11596626e+02 1.14460854e+02 1.17360970e+02 1.16704933e+02 1.14612534e+02 1.14056816e+02 1.14276054e+02 1.14417099e+02 1.14315697e+02 1.14573082e+02 1.15325661e+02 1.16344910e+02 1.16638023e+02 1.17722801e+02 1.18279953e+02 1.16932915e+02 1.13874374e+02 1.12171600e+02 1.14778564e+02 1.17822052e+02 1.17144470e+02 1.12293571e+02 1.07519653e+02 1.09337059e+02 1.15777672e+02 1.17599403e+02 1.14686752e+02 1.08050369e+02 1.09768555e+02 1.15871750e+02 1.21156433e+02 1.25416458e+02 1.20090889e+02 1.20405746e+02 1.17466263e+02 1.17917686e+02 1.20011734e+02 1.22336205e+02 1.28060638e+02 1.22894485e+02 1.15107262e+02 1.06127693e+02 1.09865135e+02 1.21593239e+02 1.31738098e+02 1.25033707e+02 1.10781998e+02 1.00010796e+02 1.02857315e+02 1.12447739e+02 1.17574150e+02 1.19126465e+02 1.15224594e+02 1.17323952e+02 1.21920906e+02 1.30208374e+02 1.40542053e+02 1.37522720e+02 1.20676689e+02 1.07557762e+02 1.06008850e+02 1.15170135e+02 1.22299301e+02 1.33888092e+02 1.40483582e+02 1.21810921e+02 9.50598755e+01 8.24106598e+01 1.02588829e+02 1.28070709e+02 1.30032761e+02 1.06045235e+02 7.51018600e+01 7.84501572e+01 1.08845551e+02 1.43398422e+02 1.55683334e+02 1.36635590e+02 1.18791443e+02 1.17457970e+02 1.26923965e+02 1.34212769e+02 1.22348793e+02 1.22866623e+02 1.19264648e+02 1.08119728e+02 1.04356499e+02 1.03736061e+02 1.22597305e+02 1.16871521e+02 9.33852463e+01 6.46726074e+01 6.97294159e+01 1.14871422e+02 1.48764801e+02 1.41252899e+02 1.00120110e+02 7.21181564e+01 6.94597321e+01 1.02977554e+02 1.34693787e+02 1.48923080e+02 1.23642075e+02 1.07233498e+02 9.25658951e+01 9.36708298e+01 9.88503876e+01 9.52403412e+01 9.36639557e+01 6.93487091e+01 5.59864731e+01 5.66081696e+01 7.55244370e+01 1.12994370e+02 1.25773544e+02 1.04170052e+02 6.59176178e+01 5.45303650e+01 7.70894470e+01 1.13903572e+02 1.11738396e+02 8.68747864e+01 4.67401085e+01 4.17328300e+01 7.68096542e+01 1.16771935e+02 1.35607224e+02 1.04074020e+02 7.19838867e+01 6.93557663e+01 9.53959656e+01 1.23244507e+02 1.25782036e+02 1.23818314e+02 1.11198341e+02 7.91095657e+01 7.06710129e+01 9.48339005e+01 1.52080948e+02 1.73783310e+02 1.41470276e+02 9.53116913e+01 6.19588737e+01 8.44991302e+01 1.22374908e+02 1.44596588e+02 1.30789810e+02 9.74414291e+01 1.00201683e+02 1.26874825e+02 1.57007935e+02 1.57610565e+02 1.17549408e+02 8.88304291e+01 9.64308167e+01 1.28057968e+02 1.65186005e+02 1.59631210e+02 1.53818375e+02 1.38424225e+02 1.16395935e+02 1.01111801e+02 9.06198959e+01 1.26198700e+02 1.49776337e+02 1.39968582e+02 1.03134567e+02 6.89320908e+01 9.39117279e+01 1.31378769e+02 1.55133759e+02 1.16555626e+02 3.84027786e+01 -2.58159947e+00 3.64386902e+01 1.28542755e+02 1.83103333e+02 1.56664017e+02 1.00979881e+02 7.58370056e+01 7.38546448e+01 6.42839661e+01 3.02612743e+01 7.98870697e+01 -2.11959248e+01 -1.00003799e+02 -1.65536304e+03 -2.22267383e+03 -3.89407642e+03 -1.02722529e+04 -155285872. -3.63683302e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.74436659e+09 -366176064. -6.34325439e+03 -1.21440259e+03 1.00040802e+03 -9.69398071e+02 -5.28750488e+03 -2.85249927e+03 -5.52344421e+02 -1.58050934e+02 -8.05359879e+01 -4.29439812e+01 1.79975510e+01 1.10114639e+02 1.41724136e+02 1.22186340e+02 5.48185005e+01 1.21470366e+01 1.97491589e+01 7.65024643e+01 1.57297546e+02 1.57105835e+02 1.33425690e+02 1.06378403e+02 1.04682152e+02 1.04132767e+02 7.31054230e+01 1.03837746e+02 1.04368446e+02 4.71558952e+01 3.64070034e+00 4.33397598e+01 1.57463120e+02 2.20390289e+02 1.47037048e+02 5.24106560e+01 -9.66890049e+00 2.09881573e+01 1.26412804e+02 2.13323425e+02 2.51270630e+02 1.68271133e+02 1.08363098e+02 1.01870338e+02 1.62899948e+02 2.04728317e+02 1.68774338e+02 1.63604736e+02 1.22494102e+02 8.02854767e+01 5.59893532e+01 8.80499725e+01 2.02433167e+02 2.12607544e+02 1.18710930e+02 7.63853639e-02 -2.70081310e+01 7.38566513e+01 1.67413544e+02 1.60547745e+02 8.45754395e+01 4.96919975e+01 1.17992104e+02 2.29255508e+02 2.62175934e+02 2.20049637e+02 9.69833832e+01 1.19555035e+01 8.50647259e+00 8.13748856e+01 1.86320801e+02 2.54688950e+02 2.89720795e+02 2.53735657e+02 1.92037277e+02 1.31344574e+02 1.01747177e+02 1.23783012e+02 1.08128380e+02 3.32812500e+01 -3.89423294e+01 -2.96050758e+01 6.87782974e+01 1.39829712e+02 1.19490410e+02 7.48952637e+01 7.60542393e+00 -2.92053413e+01 6.99016380e+00 1.06070892e+02 1.60849350e+02 1.00817154e+02 2.39051781e+01 3.32315445e+01 8.37888489e+01 9.86972656e+01 6.96961899e+01 8.79060364e+01 8.53661575e+01 4.42486649e+01 1.85374260e+01 4.83300476e+01 1.60835175e+02 1.69766769e+02 6.63095169e+01 -7.29654617e+01 -1.24310478e+02 -2.99134178e+01 6.88479156e+01 1.09120361e+02 8.47166748e+01 4.56595917e+01 3.80211525e+01 6.04557953e+01 1.18377098e+02 1.51790268e+02 9.47760925e+01 -1.01034403e+01 -4.51338005e+01 -7.49200678e+00 3.12415581e+01 4.20783424e+01 8.52776184e+01 8.66554718e+01 -4.36481524e+00 -1.10594421e+02 -1.06739265e+02 3.10598965e+01 9.13332291e+01 1.22506094e+01 -1.01863876e+02 -1.20421173e+02 -1.71509781e+01 8.32041702e+01 1.04713295e+02 6.56937866e+01 -2.15934582e+01 -8.47159195e+01 -5.97686043e+01 4.11824265e+01 1.13582832e+02 5.75727463e+01 -4.10081863e+01 -7.30347366e+01 -4.02013512e+01 3.65667373e-01 3.00920601e+01 9.48099670e+01 1.28045670e+02 9.82522736e+01 4.19289894e+01 3.64318886e+01 1.03212067e+02 1.33912872e+02 6.09984665e+01 -7.05624084e+01 -1.59951691e+02 -1.10378426e+02 2.23144016e+01 1.13370819e+02 9.01289291e+01 1.73094006e+01 -1.23829327e+01 2.78704319e+01 3.45457878e+01 8.53446503e+01 5.62570763e+01 4.59838371e+01 -1.29952550e+00 -6.38579407e+01 -9.18597946e+01 -1.06151634e+02 -1.95508804e+01 2.37248878e+01 -2.73369579e+01 -8.67709808e+01 -5.98524628e+01 5.98032417e+01 1.17355019e+02 7.31717224e+01 1.68989754e+01 -2.68240967e+01 -2.67612514e+01 7.85548687e+00 2.73357906e+01 3.77342033e+01 -3.30276985e+01 -2.33716164e+01 1.49015036e+01 8.16543732e+01 1.54116302e+02 1.97950134e+02 2.39748810e+02 1.67862595e+02 5.25501900e+01 -1.36786356e+01 -1.56812525e+01 5.30910912e+01 5.56286430e+01 -1.69037113e+01 -1.09002396e+02 -1.50287857e+02 -3.41960487e+01 1.13164551e+02 1.88894928e+02 1.48103729e+02 7.87430496e+01 4.66258011e+01 5.57535477e+01 8.67517853e+01 1.26281876e+02 9.68131332e+01 2.54127598e+01 -1.14733381e+01 3.12364006e+01 5.04203682e+01 6.76806412e+01 9.64274521e+01 1.05556587e+02 6.78316574e+01 2.85812054e+01 2.97281246e+01 4.19621811e+01 4.87275267e+00 -4.96077118e+01 -9.45923920e+01 -1.16846558e+02 -6.53200684e+01 -2.63738384e+01 6.37686005e+01 9.71100159e+01 4.67011414e+01 -3.73216095e+01 -7.01956100e+01 -1.02023020e+01 3.80680008e+01 2.78061218e+01 1.00853014e+01 3.81266427e+00 -1.70895755e+00 -8.03125381e+00 -9.99438858e+00 -9.70954418e+00 -5.24599218e+00 -2.00159016e+01 -3.19088421e+01 -6.66081772e+01 -6.27344437e+01 -4.97502823e+01 -1.37796946e+01 -1.73060627e+01 -3.22836266e+01 -3.40548325e+01 -2.70537949e+01 1.47055826e+01 4.32098846e+01 4.93019981e+01 3.12659950e+01 -7.11773062e+00 -6.89314127e+00 -7.97405958e+00 -4.86904621e+00 -2.17929440e+01 -2.03138065e+01 -1.86407509e+01 -1.72761631e+01 -3.81986809e+01 -3.44013290e+01 -3.56056938e+01 -3.82186165e+01 -5.49455910e+01 -5.40872688e+01 -5.72400017e+01 -5.96026077e+01 -4.75297127e+01 -3.79198074e+01 -2.36331615e+01 -3.45235519e+01 -3.52040825e+01 -5.08662491e+01 -5.19640656e+01 -4.74768486e+01 -1.95877094e+01 -2.39286919e+01 -2.04500732e+01 -3.76105614e+01 -2.36851368e+01 -4.50215874e+01 -4.17496567e+01 -4.02012634e+01 -1.79341774e+01 -2.55806026e+01 -3.29698753e+01 -3.67846413e+01 -2.68599472e+01 -2.65701122e+01 -4.59503860e+01 -4.06266365e+01 -2.26858425e+01 -4.29331183e-01 -1.79608679e+00 1.86642611e+00 -3.36528254e+00 -1.08120041e+01 -1.86712627e+01 -1.09293652e+01 -1.63344345e+01 -2.17639828e+01 -2.32927189e+01 -3.63136578e+00 -1.67153015e+01 -2.75910358e+01 -4.34184189e+01 -3.05925999e+01 -5.77390976e+01 -8.52760544e+01 -8.88042908e+01 -6.61929703e+01 -3.41838875e+01 -3.22183533e+01 -3.86428452e+01 -4.51966057e+01 -6.03090973e+01 -3.89949608e+01 -3.46327095e+01 -2.95859051e+01 -3.10340996e+01 -1.04295225e+01 -6.08791399e+00 -3.07414188e+01 -3.96769333e+01 -3.37419128e+01 -3.09136143e+01 -4.09997978e+01 -3.46062622e+01 -2.41313572e+01 -1.88147430e+01 -1.76364231e+01 -8.36260891e+00 -1.74870415e+01 -2.63862534e+01 -3.75715370e+01 -3.56010132e+01 -3.27944603e+01 -2.13249912e+01 -2.90173454e+01 -4.91525650e+01 -8.53443069e+01 -7.06153564e+01 -4.99734039e+01 -2.19183006e+01 -2.31608524e+01 -3.92573853e+01 -4.91324120e+01 -5.88792038e+01 -6.74069901e+01 -7.90266724e+01 -9.02693481e+01 -7.06938629e+01 -6.91833954e+01 -5.63125801e+01 -6.63159256e+01 -5.86321945e+01 -5.30995407e+01 -4.50359688e+01 -5.82328339e+01 -6.62416077e+01 -6.94527206e+01 -6.17674332e+01 -5.52121048e+01 -6.54819717e+01 -8.63740616e+01 -1.24640350e+02 -1.13879349e+02 -8.08872833e+01 -3.36099205e+01 -5.44695320e+01 -8.40982895e+01 -1.06378181e+02 -8.67933350e+01 -6.15543747e+01 -6.41268845e+01 -8.70197906e+01 -1.07128098e+02 -1.08631363e+02 -9.58036118e+01 -1.02476997e+02 -1.24699059e+02 -1.38803345e+02 -1.13682426e+02 -7.40488968e+01 -6.27747154e+01 -8.06006393e+01 -8.94180145e+01 -8.87022629e+01 -7.03919449e+01 -6.38854942e+01 -7.85871735e+01 -1.05396782e+02 -1.00134727e+02 -8.11770782e+01 -4.75680962e+01 -5.31376495e+01 -5.62554169e+01 -6.69650879e+01 -4.61361351e+01 -1.04101648e+01 5.79408312e+00 -2.84445210e+01 -6.66261139e+01 -8.20089417e+01 -8.12958221e+01 -1.01450638e+02 -1.10096771e+02 -6.12820740e+01 -7.66626000e-02 6.86712027e+00 -3.86160889e+01 -8.18112259e+01 -8.53827591e+01 -7.67858353e+01 -5.17220230e+01 -3.50778961e+01 -4.68641510e+01 -7.74336090e+01 -9.86934433e+01 -9.92365875e+01 -1.05293533e+02 -7.52277451e+01 -2.91291008e+01 -2.03389626e+01 -5.01235962e+01 -8.52630463e+01 -1.01731346e+02 -1.11595764e+02 -1.13261917e+02 -8.75516052e+01 -7.75095596e+01 -7.15663605e+01 -7.13703232e+01 -6.48857880e+01 -5.78178368e+01 -5.40945244e+01 -5.69964638e+01 -5.92053947e+01 -6.00237694e+01 -5.09375877e+01 -4.72139969e+01 -6.33425522e+01 -8.21657639e+01 -1.79700165e+02 -2.41680664e+02 -1.70348160e+02 -1.10953903e+02 1.29140869e+02 -3.06715723e+03 -8.11410742e+03 278654560. 136519120. 136705408. -278194656. 464661568. -950955392. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -875751680. 229478736. -2.56669766e+04 -1.01079121e+04 -2.06051636e+03 -3.78615820e+03 -2.29509766e+03 -5.54885254e+02 -2.51302582e+02 -1.40268738e+02 -1.28597244e+02 -1.25573242e+02 -1.24599480e+02 -1.31437042e+02 -1.36106033e+02 -1.42018219e+02 -1.41020081e+02 -1.37996597e+02 -1.21112709e+02 -1.16693413e+02 -1.21090218e+02 -1.38743561e+02 -1.35461197e+02 -1.21401215e+02 -1.00884781e+02 -9.84893723e+01 -9.60543747e+01 -9.26893234e+01 -8.39566269e+01 -7.94029541e+01 -7.67972183e+01 -7.23047714e+01 -7.43196030e+01 -7.29341125e+01 -7.91922607e+01 -8.02635117e+01 -7.37985764e+01 -6.92515793e+01 -6.73170776e+01 -8.03525314e+01 -8.67970428e+01 -8.68115387e+01 -8.01465607e+01 -7.72270050e+01 -7.15404510e+01 -7.02941132e+01 -7.40265045e+01 -9.46747665e+01 -1.10701408e+02 -1.18997383e+02 -1.11564407e+02 -1.05230087e+02 -9.95323410e+01 -9.31634979e+01 -9.36644058e+01 -9.86253967e+01 -1.02552727e+02 -1.01258194e+02 -9.49773560e+01 -9.26365891e+01 -8.48723907e+01 -9.28014526e+01 -1.00040329e+02 -1.06974815e+02 -1.13812164e+02 -1.17639290e+02 -1.21553337e+02 -1.14882286e+02 -1.10048729e+02 -1.11164223e+02 -1.07511490e+02 -9.76707687e+01 -9.16961136e+01 -9.62991562e+01 -1.03250473e+02 -1.04636467e+02 -1.02030182e+02 -1.10659828e+02 -1.25142220e+02 -1.23491989e+02 -1.18354164e+02 -1.11663826e+02 -1.29047745e+02 -1.44077011e+02 -1.43024002e+02 -1.34057144e+02 -1.26864471e+02 -1.28631271e+02 -1.29469711e+02 -1.23332397e+02 -1.26035187e+02 -1.32368454e+02 -1.44215302e+02 -1.40572342e+02 -1.28359451e+02 -1.15061981e+02 -1.08761009e+02 -1.09116669e+02 -1.10315613e+02 -1.13634293e+02 -1.08403786e+02 -1.02797997e+02 -1.08737984e+02 -1.18457581e+02 -1.21050514e+02 -1.11412598e+02 -1.05316116e+02 -1.16760933e+02 -1.24779495e+02 -1.22202744e+02 -1.10395515e+02 -1.03425865e+02 -1.02966545e+02 -1.03088264e+02 -1.03724327e+02 -1.05564316e+02 -1.09306877e+02 -1.09276253e+02 -1.07850380e+02 -1.07566246e+02 -1.10275986e+02 -1.12162827e+02 -1.12415657e+02 -1.11706749e+02 -1.12584183e+02 -1.13015900e+02 -1.13416191e+02 -1.19886215e+02 -1.26075775e+02 -1.25144417e+02 -1.18756721e+02 -1.13022453e+02 -1.19127205e+02 -1.25122185e+02 -1.25579338e+02 -1.20707329e+02 -1.16037132e+02 -1.15314560e+02 -1.14365677e+02 -1.11963837e+02 -1.13205215e+02 -1.14090546e+02 -1.15181305e+02 -1.13281235e+02 -1.11502991e+02 -1.11652428e+02 -1.13291100e+02 -1.14979866e+02 -1.14856506e+02 -1.14685814e+02 -1.14490410e+02 -1.15678993e+02 -1.19234596e+02 -1.22681007e+02 -1.22392990e+02 -1.19536346e+02 -1.16867203e+02 -1.18726555e+02 -1.20699966e+02 -1.19852081e+02 -1.16826378e+02 -1.14282021e+02 -1.14290001e+02 -1.14786781e+02 -1.15052116e+02 -1.15135506e+02 -1.15009041e+02 -1.15027046e+02 -1.14809303e+02 -1.14763283e+02 -1.15067009e+02 -1.15362022e+02 -1.15037399e+02 -1.14647797e+02 -1.14406197e+02 -1.14422142e+02 -1.14453613e+02 -1.14228699e+02 -1.13704910e+02 -1.13503708e+02 -1.13690422e+02 -1.14018257e+02 -1.13930855e+02 -1.14386810e+02 -1.13575478e+02 -1.11828995e+02 -1.11088646e+02 -1.12143486e+02 -1.13557335e+02 -1.13129234e+02 -1.12776039e+02 -1.13171684e+02 -1.13539162e+02 -1.12750938e+02 -1.12360565e+02 -1.09632126e+02 -1.07027588e+02 -1.06570374e+02 -1.09193176e+02 -1.11934547e+02 -1.10931694e+02 -1.10411079e+02 -1.07143837e+02 -1.04411484e+02 -1.04617256e+02 -1.09569809e+02 -1.14046989e+02 -1.13277809e+02 -1.12523956e+02 -1.11432510e+02 -1.12840790e+02 -1.13893951e+02 -1.15010071e+02 -1.14658829e+02 -1.14229378e+02 -1.14149231e+02 -1.15091347e+02 -1.14836517e+02 -1.17496117e+02 -1.19965187e+02 -1.21347366e+02 -1.21582016e+02 -1.18995277e+02 -1.19393394e+02 -1.19436348e+02 -1.19160271e+02 -1.18705650e+02 -1.17724823e+02 -1.19688858e+02 -1.16932137e+02 -1.15175354e+02 -1.15050995e+02 -1.19603760e+02 -1.19993752e+02 -1.18637039e+02 -1.16368393e+02 -1.16675339e+02 -1.17984901e+02 -1.15206017e+02 -1.16302101e+02 -1.10740356e+02 -1.09264381e+02 -1.06982788e+02 -1.15181465e+02 -1.24876236e+02 -1.19534920e+02 -1.03519348e+02 -9.12976303e+01 -9.50271606e+01 -1.02831139e+02 -1.05069153e+02 -1.04523270e+02 -1.05274612e+02 -1.04554588e+02 -1.03919830e+02 -1.02930008e+02 -1.04557037e+02 -1.09129173e+02 -1.13686333e+02 -1.15706642e+02 -1.12024734e+02 -1.07704071e+02 -1.03043724e+02 -1.02068893e+02 -1.04289032e+02 -1.05975395e+02 -1.09687241e+02 -1.10580360e+02 -1.14615021e+02 -1.09273415e+02 -9.62231140e+01 -8.24737167e+01 -8.50362396e+01 -9.43778000e+01 -1.06147141e+02 -1.07809708e+02 -1.08137375e+02 -1.01315758e+02 -9.21802368e+01 -8.65348282e+01 -8.24624329e+01 -9.19834213e+01 -1.01527588e+02 -1.13491135e+02 -1.07457199e+02 -1.01845825e+02 -9.76272278e+01 -1.03553841e+02 -1.05834084e+02 -1.10561035e+02 -1.04351227e+02 -9.75547562e+01 -9.31837158e+01 -9.08422165e+01 -9.22712021e+01 -7.60107117e+01 -6.42509613e+01 -6.73115768e+01 -8.72251892e+01 -1.02346581e+02 -9.85335159e+01 -8.99890823e+01 -9.24527740e+01 -9.19059753e+01 -8.17880630e+01 -6.51850357e+01 -6.67665558e+01 -8.62893600e+01 -1.05276718e+02 -9.55344772e+01 -8.37732849e+01 -8.68579788e+01 -9.85489807e+01 -1.03785782e+02 -9.75801239e+01 -9.02406693e+01 -9.73986969e+01 -1.11928299e+02 -1.14989517e+02 -1.12043983e+02 -1.03036812e+02 -1.09496819e+02 -9.50897064e+01 -7.66036911e+01 -7.17857590e+01 -6.52799911e+01 -5.52900848e+01 -3.71447906e+01 -3.71497154e+01 -4.40592613e+01 -4.20344963e+01 -5.23060570e+01 -5.54097786e+01 -7.43315811e+01 -9.43806915e+01 -1.21606117e+02 -1.27679550e+02 -1.21755394e+02 -1.14890816e+02 -1.10316628e+02 -1.06830650e+02 -1.05009819e+02 -1.10353737e+02 -1.15272575e+02 -9.71768646e+01 -6.80250168e+01 -5.80980263e+01 -6.08668633e+01 -7.52645416e+01 -8.08933487e+01 -8.46517563e+01 -1.00163902e+02 -9.13855438e+01 -9.04649429e+01 -7.81533585e+01 -6.63821564e+01 -5.35069656e+01 -3.23869820e+01 -5.29067459e+01 -7.64874344e+01 -8.65102158e+01 -5.98213577e+01 -5.44486465e+01 -6.46488037e+01 -9.00746002e+01 -6.88369598e+01 -4.63177986e+01 -3.74325981e+01 -5.60685806e+01 -7.70061569e+01 -5.32793083e+01 -2.77881203e+01 -3.31587257e+01 -6.84701614e+01 -9.54544678e+01 -7.56657486e+01 -5.77907448e+01 -7.92970505e+01 -1.10078667e+02 -9.40210876e+01 -5.13209648e+01 -3.24821091e+01 -4.26835442e+01 -5.57373657e+01 -4.51252060e+01 -2.60255184e+01 -7.94434834e+00 -2.05234909e+01 -5.72054863e+01 -8.76336441e+01 -8.71763611e+01 -7.79471054e+01 -7.18042068e+01 -7.51972351e+01 -7.83594589e+01 -7.24301605e+01 -5.50234451e+01 -5.50936203e+01 -7.34148865e+01 -7.92575073e+01 -7.11084518e+01 -4.18895607e+01 -2.78965378e+01 -3.74940033e+01 -4.89653893e+01 -7.10468445e+01 -6.41836395e+01 -6.80768356e+01 -7.55187531e+01 -9.23983536e+01 -9.22121201e+01 -4.53358841e+01 -1.16971502e+01 -4.68964005e+01 -1.12774940e+02 -1.13938255e+02 -5.81607437e+01 -3.59016190e+01 -6.56096725e+01 -8.08125992e+01 -5.87023468e+01 -4.65630112e+01 -5.09696770e+01 -7.80329819e+01 -6.36027641e+01 -5.71286545e+01 -4.51295891e+01 -5.88165092e+01 -8.71497955e+01 -8.55425034e+01 -8.63222122e+01 -5.15390282e+01 -2.75176678e+01 -2.47062244e+01 -5.45129051e+01 -5.69295807e+01 9.73888934e-01 4.01956062e+01 2.10586853e+01 -3.44320297e+01 -3.85965042e+01 -1.51925268e+01 -3.72190094e+01 -8.48871078e+01 -1.03160835e+02 -6.02519073e+01 -3.51369934e+01 -4.11317520e+01 -5.90233994e+01 -3.81134453e+01 -2.60286865e+01 -2.20682220e+01 -3.49772797e+01 -5.13144569e+01 -6.77259445e+01 -7.80804214e+01 -6.79984512e+01 -5.45846939e+01 -3.54893227e+01 -2.94994850e+01 -2.48295975e+01 -3.16880608e+00 3.59362936e+00 -1.36338062e+01 -3.48964691e+01 -3.44998932e+01 -7.20014668e+00 -4.83893919e+00 -8.82436752e+00 7.95483828e+00 6.39603004e+01 1.01160004e+02 7.55935287e+01 8.68977737e+00 -1.26033850e+01 5.55339718e+00 1.38189306e+01 -1.39135942e+01 -3.59413528e+01 -4.93823280e+01 -5.91789055e+01 -5.53101921e+01 -3.41917191e+01 -3.45744629e+01 -5.44036064e+01 -5.77861137e+01 -2.90506363e+00 2.53903809e+01 9.29585993e-01 -3.61195679e+01 -8.19376850e+00 1.14852209e+01 -1.96304169e+01 -8.48739319e+01 -1.30388992e+02 -1.21313011e+02 -1.17493340e+02 -9.88161392e+01 -8.53281784e+01 -7.53030853e+01 -7.25061264e+01 -6.37619400e+01 -5.24001083e+01 -5.66480179e+01 -8.37159042e+01 -6.08204193e+01 5.41383266e+00 5.00522385e+01 5.62273865e+01 4.74042625e+01 1.84042130e+01 -5.03190088e+00 -3.45084343e+01 -2.39187393e+01 -3.33657379e+01 -4.73207054e+01 -5.28594513e+01 -3.90522842e+01 -2.93950253e+01 -2.03801785e+01 -2.23553619e+01 -3.11364746e+01 -3.68523788e+01 -4.07933083e+01 1.50243926e+00 4.78979149e+01 5.66017151e+01 2.54638710e+01 -1.03095970e+01 -7.47239494e+00 -1.05292873e+01 -7.39168119e+00 -1.90107517e+01 -2.04713154e+01 -1.55605841e+01 2.09196720e+01 5.78548088e+01 3.72961693e+01 -3.35562277e+00 -1.22029514e+01 5.85170593e+01 1.01516907e+02 7.46305847e+01 5.83166742e+00 1.10509520e+01 3.96373940e+01 4.00894470e+01 6.85977697e+00 -2.07779675e+01 1.95671005e+01 4.85518341e+01 7.78210068e+01 9.33158646e+01 4.96862411e+01 1.29246082e+01 9.06751251e+00 9.31839676e+01 1.29582550e+02 7.69385147e+01 6.45534182e+00 1.72464027e+01 7.55831604e+01 8.01302490e+01 4.91302681e+01 1.52162523e+01 4.10949020e+01 7.50926361e+01 8.19801254e+01 6.35398788e+01 3.29159775e+01 2.60024948e+01 5.90419426e+01 9.59676361e+01 9.87385101e+01 6.70747070e+01 1.08144474e+01 3.52805328e+01 6.40596237e+01 6.70407333e+01 3.42287598e+01 3.31891022e+01 8.16644363e+01 7.80933990e+01 3.52718086e+01 -1.46313505e+01 -1.92111511e+01 -2.18134308e+01 8.27511311e+00 4.97419815e+01 7.13953018e+01 5.37191772e+01 1.24085712e+01 -9.14430332e+00 -1.26492929e+01 1.67930813e+01 4.49319115e+01 4.42155876e+01 2.43836578e+02 5.09911041e+02 4.85195068e+02 2.03178131e+02 -1.41682373e+02 1.74226868e+02 1.99874695e+02 4.10787079e+02 4.85387598e+03 1.14639746e+04 21604182. 9025177. 6713434. -16907282. -4.11726561e+10 0. 0. 0. 0. 0. 0. 2.26273956e+10 2.26273956e+10 10582239. -3.54597233e+10 -3.54597233e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -855827968. -8622476. 6835689. 3.98411094e+04 1.70962891e+04 2.33563916e+03 -5.22220020e+03 -3.96949048e+03 -1.23438757e+03 -6.94770264e+02 -2.47669861e+02 6.86582108e+01 8.65398483e+01 2.10933228e+01 -1.79034698e+00 4.18557167e+01 1.20840302e+01 -5.96044807e+01 -1.19319000e+02 -4.98894997e+01 9.40282211e+01 1.53819122e+02 1.02750832e+02 2.33307886e+00 -4.23064537e+01 -2.37578468e+01 -4.54543889e-01 -2.80627003e+01 -6.22373352e+01 -2.34403038e+01 5.82158546e+01 9.75959091e+01 6.33673210e+01 -1.06847725e+01 -3.58584175e+01 1.50331717e+01 8.88688354e+01 1.23984245e+02 8.37811432e+01 9.22353210e+01 1.35279297e+02 9.66440811e+01 -1.30762506e+00 -6.59353180e+01 2.93067570e+01 1.85678177e+02 2.22433182e+02 1.39226151e+02 6.13711243e+01 1.15553741e+01 6.49533510e+00 1.14985485e+01 2.10751820e+01 1.77917271e+01 3.82009392e+01 1.48537445e+02 2.20792603e+02 1.88200043e+02 8.07910004e+01 5.95818901e+00 4.19883614e+01 1.08014839e+02 1.54159241e+02 9.62657776e+01 7.64757156e+01 9.49288025e+01 6.86636581e+01 2.65605092e+00 -7.87366867e+01 -5.79710693e+01 5.80746803e+01 9.75461273e+01 6.05544815e+01 -2.95857105e+01 -1.42676878e+00 6.63527298e+01 5.62358246e+01 -3.90184951e+00 -3.12898674e+01 1.40430832e+01 1.12423317e+02 1.55378510e+02 1.25733543e+02 3.40728798e+01 -2.62209625e+01 -7.64685583e+00 3.25862961e+01 2.09535923e+01 -2.57899437e+01 -1.64150772e+01 4.77061272e+01 8.05867767e+01 1.68202190e+01 -7.18600998e+01 -8.57349091e+01 8.74284649e+00 8.75678864e+01 9.11685638e+01 2.37764492e+01 6.87607813e+00 2.52517471e+01 -1.00770330e+01 -9.17487564e+01 -1.35130188e+02 -6.87422638e+01 5.68086472e+01 1.22756126e+02 9.81529922e+01 2.74665356e+01 -4.90522156e+01 -1.01014938e+02 -8.51050644e+01 -6.77687988e+01 -6.73805237e+01 -5.20519485e+01 2.35516930e+01 8.92718201e+01 4.56158943e+01 -7.42533188e+01 -1.23118454e+02 -7.57227859e+01 4.10846329e+01 9.84075089e+01 6.64909210e+01 2.18236504e+01 1.03612776e+01 9.49227142e+00 -3.36698112e+01 -1.23170578e+02 -1.18784935e+02 -3.13881588e+01 6.51376495e+01 6.48886185e+01 2.39038682e+00 -4.77352905e+01 -4.73115158e+01 -2.13639450e+01 1.86699524e+01 3.79114799e+01 -1.32767305e+01 -3.91114044e+01 -4.23830271e+00 4.20262985e+01 4.91572189e+01 2.16468372e+01 1.97549591e+01 5.61782608e+01 5.65150261e+01 2.52973080e+01 -1.38845415e+01 -2.78272991e+01 1.61801987e+01 3.37204933e+01 2.03510151e+01 -2.11264248e+01 1.05830870e+01 1.19514725e+02 1.76012985e+02 1.03367134e+02 2.27997637e+00 -1.55460339e+01 4.12703629e+01 7.91351700e+01 7.44930801e+01 7.35164642e+01 1.14079178e+02 1.67744827e+02 1.81620148e+02 1.55923065e+02 7.91074448e+01 2.93043003e+01 5.86380730e+01 7.92198029e+01 6.77394714e+01 2.39341354e+01 5.91311264e+01 1.47401398e+02 1.37998871e+02 1.01662781e+02 6.06481972e+01 1.12498383e+02 2.11974777e+02 2.55495270e+02 2.07984344e+02 1.04635513e+02 4.87485847e+01 6.65836487e+01 5.41231689e+01 3.52437515e+01 4.44529839e+01 1.15229248e+02 1.95357010e+02 1.89078979e+02 1.23099678e+02 1.03333654e+01 -2.67592564e+01 1.39965076e+01 8.51044540e+01 1.28222076e+02 1.17814186e+02 1.36463852e+02 1.58183304e+02 1.50368011e+02 7.69464951e+01 8.91977882e+00 3.89351234e+01 1.38558136e+02 1.90297409e+02 1.32066040e+02 3.28414421e+01 6.77440822e-01 4.65073738e+01 1.00035126e+02 7.65270844e+01 3.12812119e+01 4.54758301e+01 9.72616272e+01 1.16682709e+02 7.26391144e+01 6.25361323e-01 -1.10578804e+01 1.91066055e+01 6.40810547e+01 6.42749481e+01 4.52862129e+01 3.76872330e+01 5.38431931e+01 3.38759232e+01 1.34990358e+00 -2.87917793e-01 1.20869780e+01 4.97943344e+01 6.67771301e+01 4.95023193e+01 5.35523643e+01 5.29374542e+01 8.34397812e+01 5.66961823e+01 1.98245316e+01 4.81237268e+00 2.37505703e+01 1.03343307e+02 1.48376205e+02 1.45210373e+02 5.27561989e+01 9.79472446e+00 -1.57126927e+00 3.65851173e+01 5.22934265e+01 3.35413704e+01 4.05063858e+01 6.51774597e+01 8.21118927e+01 5.32983704e+01 3.14724445e+01 7.86175156e+01 1.35970490e+02 1.28483337e+02 9.47254028e+01 7.34372482e+01 9.37946930e+01 1.28217148e+02 9.23915253e+01 6.49052429e+01 3.22936745e+01 5.04246979e+01 8.85432968e+01 1.11709358e+02 1.21659073e+02 8.15995102e+01 6.20960579e+01 6.04157562e+01 9.86531830e+01 1.09068779e+02 1.08868980e+02 1.15979126e+02 1.34141708e+02 1.45212540e+02 9.65004196e+01 6.72427292e+01 6.69703293e+01 1.13128517e+02 1.15121170e+02 9.47854233e+01 6.70455856e+01 4.59340286e+01 5.63875237e+01 5.88626900e+01 9.25558090e+01 1.09287827e+02 1.23797165e+02 1.20894753e+02 1.11110069e+02 9.24352341e+01 6.08878822e+01 4.32748528e+01 5.27036743e+01 9.93685760e+01 1.07620796e+02 9.82051849e+01 8.64381943e+01 9.29902573e+01 8.19128952e+01 3.48390045e+01 1.69036160e+01 3.97080421e+01 9.47642288e+01 1.06984451e+02 8.77165222e+01 5.75594139e+01 4.72678337e+01 6.55296783e+01 6.80919724e+01 7.98212891e+01 5.52706375e+01 4.55226326e+01 4.12437248e+01 6.30947342e+01 7.29345779e+01 5.61462021e+01 3.66561623e+01 5.47751961e+01 8.04849014e+01 7.29814224e+01 5.64373474e+01 5.93496933e+01 7.69065704e+01 7.51681290e+01 4.60210876e+01 3.70605164e+01 4.53869438e+01 7.50487518e+01 7.27881851e+01 6.50693130e+01 5.51051178e+01 6.19836502e+01 7.69504318e+01 7.16366882e+01 6.82939301e+01 4.65362740e+01 4.03235741e+01 4.39272232e+01 5.92287102e+01 6.85451279e+01 6.15014305e+01 5.11387253e+01 5.62750969e+01 7.65165710e+01 8.20216446e+01 8.26142273e+01 9.29940109e+01 1.10596535e+02 1.04218483e+02 7.99741364e+01 7.62955017e+01 8.99122543e+01 1.06492355e+02 8.70306931e+01 7.79355469e+01 7.14003296e+01 6.29201622e+01 5.99421387e+01 6.96892471e+01 9.89541321e+01 1.05114388e+02 8.39879532e+01 6.53043747e+01 7.37979736e+01 9.87567902e+01 1.10167068e+02 9.60748901e+01 8.29633560e+01 8.59470367e+01 9.36353149e+01 1.03952057e+02 1.12808601e+02 1.26559052e+02 1.20620171e+02 1.05213112e+02 1.00342781e+02 1.07273483e+02 1.17450333e+02 1.00368019e+02 9.10713730e+01 8.27356110e+01 8.71298599e+01 8.73899078e+01 9.69833755e+01 1.14621704e+02 1.19189034e+02 1.03887779e+02 7.74332962e+01 7.07516708e+01 9.15720520e+01 1.11670082e+02 1.12580254e+02 9.79207993e+01 8.85184937e+01 9.34708405e+01 1.03826721e+02 1.08856308e+02 1.01974319e+02 8.60292435e+01 8.29770279e+01 9.00944138e+01 9.97432098e+01 1.09794952e+02 1.08144226e+02 1.03137001e+02 9.08181992e+01 7.91350708e+01 7.56014404e+01 8.24645462e+01 9.60713348e+01 1.02057701e+02 9.54687271e+01 8.71975098e+01 8.75225449e+01 9.61743927e+01 1.02698547e+02 9.86287689e+01 8.93397522e+01 8.35921021e+01 8.35378494e+01 8.80181885e+01 9.03072891e+01 9.24697647e+01 8.91442566e+01 8.78870697e+01 8.69226379e+01 8.80571518e+01 8.87110291e+01 8.70315781e+01 8.58495789e+01 8.47507401e+01 8.49789124e+01 8.57004547e+01 8.61366577e+01 8.61034851e+01 8.55983429e+01 8.56057510e+01 8.70881958e+01 8.84550552e+01 8.77141724e+01 8.46688919e+01 8.22400513e+01 8.24773560e+01 8.41774368e+01 8.38946915e+01 8.21459122e+01 8.05958862e+01 7.98871841e+01 8.31679382e+01 8.58732300e+01 8.92003098e+01 8.91821289e+01 8.74846268e+01 8.43124008e+01 8.01574783e+01 8.03158569e+01 8.48626556e+01 8.97932663e+01 9.03546906e+01 8.44810257e+01 7.75149536e+01 8.01341476e+01 8.68424530e+01 9.03776093e+01 8.37315063e+01 7.26640167e+01 7.24420471e+01 7.94459076e+01 9.17523651e+01 9.27596817e+01 8.43646317e+01 7.52903748e+01 6.76914673e+01 7.72869415e+01 8.18057251e+01 8.81901169e+01 8.93680115e+01 9.04830627e+01 9.29582901e+01 8.60517731e+01 8.86849060e+01 9.32782211e+01 9.17314224e+01 8.21867371e+01 6.53068085e+01 5.70454941e+01 6.71477356e+01 9.16264877e+01 1.15685776e+02 1.13075554e+02 8.77795792e+01 6.02735519e+01 5.17085533e+01 7.07957458e+01 9.36256180e+01 9.98642044e+01 8.59021072e+01 6.55267029e+01 7.01878967e+01 8.43616638e+01 1.00892464e+02 1.03981758e+02 9.60538940e+01 7.99820099e+01 6.28787155e+01 6.61397324e+01 8.46191635e+01 1.09864220e+02 1.12931473e+02 9.32526093e+01 6.51034088e+01 7.03030090e+01 9.43972931e+01 1.11966957e+02 1.03054588e+02 8.62435379e+01 7.89948654e+01 7.27802353e+01 8.41186447e+01 9.11281128e+01 8.27951508e+01 7.71076431e+01 6.73517685e+01 8.23258362e+01 9.42564163e+01 1.12191284e+02 1.25020058e+02 1.12293007e+02 9.72944870e+01 7.23373871e+01 6.23295479e+01 7.74360733e+01 1.00775940e+02 1.04889610e+02 7.46344070e+01 4.47314796e+01 4.62774353e+01 6.78606262e+01 9.88382187e+01 1.09261154e+02 9.80321503e+01 8.14759903e+01 7.37525024e+01 9.72807312e+01 1.19301552e+02 1.41512894e+02 1.35110138e+02 1.04030937e+02 1.03303780e+02 1.17983368e+02 1.49537338e+02 1.55795975e+02 1.42373474e+02 1.22506248e+02 7.87565994e+01 6.17794151e+01 7.03558655e+01 1.06438866e+02 1.23419823e+02 9.07959900e+01 5.78699265e+01 5.47691231e+01 1.03140648e+02 1.30219620e+02 1.20644737e+02 7.76663132e+01 4.31133575e+01 3.93811302e+01 7.40578461e+01 1.15973808e+02 1.28156937e+02 1.24583603e+02 1.11631226e+02 9.58782883e+01 6.68059464e+01 6.55579300e+01 7.73129959e+01 9.01892014e+01 6.95651169e+01 2.98679619e+01 3.06034994e+00 4.06387215e+01 9.14619522e+01 1.20333031e+02 8.71264801e+01 3.29320831e+01 2.30831776e+01 5.33988647e+01 1.08212326e+02 1.18026909e+02 8.23945389e+01 6.45418625e+01 5.86431923e+01 9.48171234e+01 1.01011971e+02 9.64861832e+01 8.11570740e+01 5.04930382e+01 5.30935440e+01 5.53867722e+01 1.03390053e+02 1.39084488e+02 1.33975906e+02 1.11332664e+02 5.73595963e+01 3.34245605e+01 3.42886429e+01 8.78377838e+01 1.77647964e+02 2.14160278e+02 2.02436630e+02 8.72386932e+01 5.06423454e+01 -4.62948990e+00 -2.88022881e+01 2.65661157e+03 7.05225928e+03 516205440. 557197568. 1252064128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.74436659e+09 -366176064. -6.34325439e+03 -1.21440259e+03 1.00040802e+03 -9.69398071e+02 -1.95148975e+03 -5.13851685e+02 3.35446069e+03 2.22597144e+03 3.38654999e+02 2.82058990e+02 2.08933441e+02 1.61044266e+02 1.28373672e+02 1.00263931e+02 1.67655144e+01 1.18815155e+01 5.94120789e+01 1.24056648e+02 1.15283218e+02 4.28595581e+01 -2.38532467e+01 -4.24560013e+01 1.93425884e+01 1.07913780e+02 1.27125572e+02 5.11924706e+01 -2.05723495e+01 -2.03541203e+01 4.67965202e+01 4.35131187e+01 -5.81421041e+00 -1.79457321e+01 2.25441551e+01 8.18064957e+01 8.27595215e+01 9.75020676e+01 1.17374123e+02 1.15571465e+02 5.94345970e+01 -4.35090637e+01 -5.10072670e+01 1.58512640e+01 8.50522537e+01 8.18034210e+01 1.34349222e+01 -5.90432816e+01 -4.56707764e+01 4.92617874e+01 1.61688293e+02 1.47920166e+02 4.12659950e+01 -1.94142323e+01 -3.16338577e+01 3.08835602e+01 5.50356293e+01 7.48399658e+01 8.21763458e+01 5.86347237e+01 1.90215378e+01 -4.51525154e+01 -1.95755806e+01 4.01341400e+01 6.50533447e+01 1.84329662e+01 -6.33013802e+01 -6.13794785e+01 -2.14146366e+01 5.41378860e+01 7.94260864e+01 1.26488667e+01 -8.50769730e+01 -1.57413834e+02 -1.14351166e+02 -1.16860332e+01 2.29126396e+01 -3.67070503e+01 -7.95671005e+01 -7.09147491e+01 2.25336094e+01 4.27647247e+01 1.49189129e+01 -2.87797756e+01 -3.00135307e+01 -2.45810375e+01 -5.52596359e+01 -2.25204277e+01 3.69566803e+01 7.02319641e+01 6.16015673e+00 -1.00992950e+02 -1.19968590e+02 -8.53631287e+01 -9.91183472e+00 5.23630447e+01 5.58563499e+01 -9.20810282e-01 -5.82678223e+01 -4.46799736e+01 5.67923279e+01 9.89941406e+01 2.40634289e+01 -5.62337341e+01 -6.02284660e+01 4.69140930e+01 9.37989807e+01 8.97510376e+01 7.36467743e+01 5.35030861e+01 8.99988079e+00 -7.36838226e+01 -6.56221466e+01 4.89452648e+00 5.80644951e+01 4.98983612e+01 -2.52551975e+01 -3.76994171e+01 6.95263195e+00 4.91703186e+01 9.38942795e+01 7.60537491e+01 -2.44778156e+00 -7.44774704e+01 -9.16572342e+01 2.53280201e+01 7.07055817e+01 2.82870140e+01 -9.88166142e+00 -1.87147446e+01 3.34113922e+01 2.63360081e+01 2.55919762e+01 5.61393242e+01 7.28561707e+01 5.68164673e+01 -4.29001579e+01 -4.39628677e+01 2.33409557e+01 7.90776672e+01 7.11304092e+01 5.12742186e+00 1.33069725e+01 6.70690994e+01 1.02730263e+02 1.43446655e+02 9.65342407e+01 1.80481262e+01 -5.60992966e+01 -5.08161049e+01 2.30469780e+01 4.15775261e+01 1.04371510e+01 1.18344393e+01 2.17353287e+01 9.11819153e+01 1.18588753e+02 1.48728867e+02 1.43050018e+02 1.05080589e+02 4.76208954e+01 -4.80078087e+01 -7.30855179e+01 -4.76290131e+01 1.55841227e+01 1.87375317e+01 -5.13697243e+01 -1.18541573e+02 -8.72478867e+01 3.03543167e+01 1.07125343e+02 1.03795410e+02 -4.50485325e+00 -5.24862747e+01 -5.30840874e+01 1.26720629e+01 1.81588573e+01 -8.87629414e+00 -8.45662498e+00 -1.61728764e+01 -2.61343346e+01 -2.86824360e+01 3.30818367e+01 1.06222359e+02 1.06865288e+02 7.75836792e+01 2.00162983e+01 -2.54774227e+01 -3.96017647e+01 -1.53780413e+01 -9.91372585e+00 -7.72387924e+01 -1.37901489e+02 -9.63498306e+01 1.32436266e+01 9.59296265e+01 9.45710602e+01 1.68887386e+01 -9.87711811e+00 -1.40429010e+01 6.55910263e+01 5.27303886e+01 1.10980046e+00 -6.69627304e+01 -1.05411713e+02 -1.16156143e+02 -1.72881607e+02 -1.40096191e+02 -5.46570473e+01 1.60966949e+01 1.21619864e+01 -6.65070190e+01 -6.24739876e+01 -9.26268864e+00 7.30101547e+01 1.41911423e+02 1.01991112e+02 -2.05717983e+01 -1.38538651e+02 -1.09036026e+02 4.29098701e+00 3.19229965e+01 -7.33816719e+00 -3.13510227e+01 -3.55914268e+01 -3.99428666e-01 2.53458214e+01 5.86554489e+01 4.97751579e+01 2.72173424e+01 -2.81301823e+01 -9.87215424e+01 -1.21205040e+02 -8.80257950e+01 -4.27134972e+01 -2.72168961e+01 -2.95089664e+01 3.10774326e-01 4.48877258e+01 5.41149025e+01 3.98022537e+01 -1.75361366e+01 -2.94811974e+01 -4.63197746e+01 -3.32943802e+01 1.00041819e+00 1.83101482e+01 1.45646391e+01 -1.90588589e+01 -3.21874084e+01 -1.55362921e+01 1.60497773e+00 3.24347705e-01 -2.77648525e+01 -3.74126816e+01 -3.55196228e+01 -1.87126217e+01 -1.91493587e+01 -9.87315369e+00 -1.12167072e+01 3.66684318e+00 -1.12967765e+00 -8.11234891e-01 -1.44670858e+01 -3.80656624e+00 -5.20544112e-01 8.06707382e+00 -3.84235196e-02 4.81678867e+00 1.81502209e+01 1.35275364e+01 1.44099474e+01 2.72552834e+01 2.03460655e+01 6.96020508e+00 -1.72174110e+01 1.63468800e+01 1.67619686e+01 9.85413742e+00 -3.84911990e+00 4.63317919e+00 1.38963079e+01 1.36587467e+01 2.14952469e+01 1.24640789e+01 5.77366829e+00 -5.50225067e+00 2.03989291e+00 -1.96249831e+00 2.90740085e+00 2.74509597e+00 3.38288975e+00 4.90838432e+00 1.23806200e+01 1.42468586e+01 1.36858730e+01 -1.08157921e+01 -3.71967087e+01 -5.36591339e+01 -3.86857910e+01 -1.70232239e+01 5.43967342e+00 -3.65826416e+00 -1.63711815e+01 -2.91257687e+01 -2.04641247e+01 -2.12824416e+00 -3.08422589e+00 -1.56525097e+01 -1.59320145e+01 -7.37837017e-01 4.12682295e+00 -4.76783323e+00 -1.22180710e+01 -1.15720301e+01 -1.91411171e+01 -2.50830460e+01 -4.06669693e+01 -4.53994904e+01 -4.56203079e+01 -2.36836262e+01 2.83001089e+00 3.39006996e+01 6.22487106e+01 4.55864944e+01 1.23264837e+01 -1.85692596e+01 -2.05343628e+01 -3.10928707e+01 -4.67070312e+01 -1.44048491e+01 2.28727722e+01 2.10159111e+01 -1.60470066e+01 -4.19076538e+01 -3.87500229e+01 -3.35426140e+01 -4.84107132e+01 -5.05214119e+01 -5.32630959e+01 -3.81005325e+01 -4.40225372e+01 -4.46035843e+01 -3.35643463e+01 -2.01468964e+01 -2.70824318e+01 -5.82530632e+01 -9.40768585e+01 -9.49826965e+01 -7.93884888e+01 -4.51319847e+01 -4.85999832e+01 -5.84316788e+01 -5.45360184e+01 -5.23333359e+01 -4.30591736e+01 -7.64263687e+01 -1.04743759e+02 -1.03950539e+02 -6.94347687e+01 -3.82596436e+01 -2.92923603e+01 -4.50303230e+01 -8.13916702e+01 -1.14904770e+02 -9.22554169e+01 -3.70723686e+01 -1.69856415e+01 -3.48232727e+01 -5.63303299e+01 -6.35630302e+01 -9.07615967e+01 -1.12504471e+02 -1.01809395e+02 -8.01798325e+01 -4.51934662e+01 -4.23001366e+01 -3.80537910e+01 -6.63935776e+01 -8.02592697e+01 -7.92604904e+01 -5.22210999e+01 -3.64820251e+01 -2.74261494e+01 -3.46099205e+01 -3.17974319e+01 -2.56594334e+01 -1.68214378e+01 -2.40333233e+01 -3.57880974e+01 -5.05213013e+01 -3.82592812e+01 -3.09739571e+01 -3.53940582e+01 -4.93568077e+01 -4.23892860e+01 -2.87247334e+01 -5.42176590e+01 -8.05858688e+01 -7.09768372e+01 -3.29031029e+01 -1.27304659e+01 -3.64734383e+01 -4.15756187e+01 -5.35197563e+01 -6.04537086e+01 -8.01301804e+01 -7.56098633e+01 -8.26997375e+01 -8.08365860e+01 -8.38537064e+01 -6.18055115e+01 -5.26703644e+01 -6.10027428e+01 -5.99342995e+01 -5.78928909e+01 -5.08331146e+01 -5.11026115e+01 -4.68326492e+01 -7.53893738e+01 -9.99156265e+01 -1.10665649e+02 -7.88059845e+01 -5.62562332e+01 -4.61276169e+01 -4.32340431e+01 -4.20163536e+01 -4.62254829e+01 -5.34473305e+01 -4.84375420e+01 -2.96607990e+01 -8.85450554e+00 -6.53090096e+00 -1.82929993e+01 -4.08625298e+01 -4.20966911e+01 -3.60355148e+01 -3.33280525e+01 -4.18473358e+01 -4.80025749e+01 -1.55733652e+01 1.64667072e+01 2.04474373e+01 -1.68344383e+01 -5.17244453e+01 -5.26955719e+01 -3.34483795e+01 2.91344047e+00 1.09549774e+02 2.88302338e+02 5.29342896e+02 2.50059497e+03 3.32434131e+03 -1.59889511e+02 -6.06660339e+02 5.75978906e+03 1.47661787e+04 895762240. 3.07605274e+09 3.65783475e+09 481550656. 829045312. 5.95769344e+09 253882064. -3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -875751680. 229478736. -2.56669766e+04 -1.01079121e+04 -2.06051636e+03 -1.09017627e+03 2.45521094e+03 1.72096704e+03 3.03496002e+02 1.75784027e+02 2.80584297e+01 -5.33661222e+00 -3.63723030e+01 -6.22638588e+01 -5.95482597e+01 -5.54045181e+01 -5.19914398e+01 -5.04388962e+01 -3.90182419e+01 -2.45130939e+01 -4.28183136e+01 -7.23982697e+01 -7.78185043e+01 -5.90766525e+01 -3.99368820e+01 -5.08017921e+01 -5.37390671e+01 -5.66794891e+01 -5.04601898e+01 -4.37336311e+01 -4.06979637e+01 -4.53532372e+01 -5.94598808e+01 -6.11839943e+01 -6.53615036e+01 -6.28651123e+01 -8.10579605e+01 -9.85888748e+01 -9.92821655e+01 -8.81488647e+01 -7.68027573e+01 -8.19513474e+01 -8.91628494e+01 -9.16221924e+01 -9.56769562e+01 -9.97323761e+01 -1.01177818e+02 -1.06043465e+02 -1.05153793e+02 -1.01863426e+02 -9.69990540e+01 -9.31815796e+01 -9.58308105e+01 -9.47966919e+01 -9.52419739e+01 -9.63008347e+01 -9.76500473e+01 -1.00968575e+02 -1.03738846e+02 -9.75127335e+01 -8.26218643e+01 -6.24017944e+01 -5.35043755e+01 -5.88863869e+01 -6.99261322e+01 -7.95538330e+01 -7.20489426e+01 -6.39510880e+01 -6.69931793e+01 -8.29122314e+01 -9.62361298e+01 -9.75652695e+01 -9.53094330e+01 -1.02224434e+02 -1.15064560e+02 -1.05361816e+02 -8.74865723e+01 -7.17321014e+01 -7.41946182e+01 -8.31716080e+01 -8.29823761e+01 -8.85959702e+01 -8.68134155e+01 -8.84140778e+01 -8.40271072e+01 -8.36206741e+01 -7.73624420e+01 -7.55536346e+01 -7.50978699e+01 -7.95197220e+01 -7.99048615e+01 -6.94304962e+01 -5.81732178e+01 -6.37814178e+01 -7.32739487e+01 -8.38825302e+01 -7.93453064e+01 -7.48946991e+01 -6.77722244e+01 -6.37468987e+01 -7.31786575e+01 -8.59280624e+01 -8.89002228e+01 -8.36298218e+01 -7.23926468e+01 -7.31941986e+01 -7.47114410e+01 -8.04236832e+01 -8.40143738e+01 -8.15518723e+01 -8.29294815e+01 -8.23680115e+01 -8.57907867e+01 -8.33505402e+01 -8.33577347e+01 -8.33955307e+01 -7.90698395e+01 -7.32726746e+01 -7.36308975e+01 -7.93247070e+01 -8.70873795e+01 -8.85639191e+01 -9.12598190e+01 -8.97906494e+01 -9.10186691e+01 -9.10549393e+01 -9.18016968e+01 -8.46613770e+01 -7.75694885e+01 -7.63707809e+01 -8.10525131e+01 -8.57368546e+01 -9.01891632e+01 -9.28179703e+01 -9.38422623e+01 -9.01013412e+01 -8.81110077e+01 -8.93695297e+01 -8.73652420e+01 -8.58177643e+01 -8.56330948e+01 -8.70147858e+01 -8.73479919e+01 -8.66624374e+01 -8.61715927e+01 -8.66873169e+01 -8.61132965e+01 -8.53107910e+01 -8.51208420e+01 -8.47231674e+01 -8.43186569e+01 -8.43841858e+01 -8.45509338e+01 -8.56829910e+01 -8.65180435e+01 -8.68150024e+01 -8.66710052e+01 -8.64890976e+01 -8.69625702e+01 -8.74972153e+01 -8.69326859e+01 -8.42502289e+01 -8.26299667e+01 -8.26812134e+01 -8.36446381e+01 -8.46999588e+01 -8.50637665e+01 -8.57022705e+01 -8.59781723e+01 -8.58214035e+01 -8.58340683e+01 -8.59161606e+01 -8.59753418e+01 -8.60028915e+01 -8.60806808e+01 -8.61002121e+01 -8.58320312e+01 -8.53908081e+01 -8.50963440e+01 -8.53812637e+01 -8.59022903e+01 -8.67475281e+01 -8.65522156e+01 -8.63794022e+01 -8.60422287e+01 -8.60861282e+01 -8.58102341e+01 -8.60352707e+01 -8.58927841e+01 -8.56324539e+01 -8.56899948e+01 -8.59205246e+01 -8.58980789e+01 -8.54640884e+01 -8.54627686e+01 -8.71201019e+01 -8.79616394e+01 -8.80245590e+01 -8.76209641e+01 -8.68159790e+01 -8.40077133e+01 -7.94713821e+01 -7.71437302e+01 -7.66931686e+01 -7.76311798e+01 -7.60041199e+01 -7.92072144e+01 -8.40393829e+01 -8.94580917e+01 -8.98476105e+01 -8.89136887e+01 -8.74517899e+01 -8.72985153e+01 -8.77282104e+01 -8.99666977e+01 -8.94120712e+01 -8.86266174e+01 -8.65800781e+01 -8.68482590e+01 -8.79572906e+01 -9.31572495e+01 -9.94072113e+01 -9.69660873e+01 -9.23568039e+01 -8.60170517e+01 -8.22031784e+01 -7.81444321e+01 -7.11409073e+01 -6.61706619e+01 -6.84921494e+01 -7.23932953e+01 -8.29390564e+01 -8.00349655e+01 -7.75032501e+01 -7.38730850e+01 -7.43289642e+01 -7.73414841e+01 -7.55797577e+01 -7.45597000e+01 -7.43595581e+01 -7.75413589e+01 -8.10716705e+01 -8.09420166e+01 -7.37843628e+01 -6.35510368e+01 -5.35599709e+01 -4.83827934e+01 -6.59029007e+01 -8.44553070e+01 -9.61028366e+01 -9.01424255e+01 -7.91955338e+01 -8.01120300e+01 -7.61260071e+01 -7.95720520e+01 -7.92709885e+01 -8.27911606e+01 -8.29243622e+01 -8.41599884e+01 -8.11534195e+01 -8.10994492e+01 -9.13142090e+01 -1.05491493e+02 -1.07452614e+02 -9.84193039e+01 -8.95607224e+01 -8.44107513e+01 -7.79751968e+01 -7.57760391e+01 -7.96307449e+01 -8.00024338e+01 -7.26748962e+01 -7.01751785e+01 -7.64712143e+01 -8.52907791e+01 -8.95525665e+01 -8.89007416e+01 -8.70251312e+01 -8.50780258e+01 -8.53754959e+01 -8.18460007e+01 -8.27233887e+01 -8.54012527e+01 -9.18233719e+01 -9.44487000e+01 -9.13359604e+01 -7.64040451e+01 -5.61632729e+01 -5.85022011e+01 -7.26148605e+01 -8.89071274e+01 -8.13287735e+01 -7.85190125e+01 -7.93785706e+01 -8.12151718e+01 -7.77524261e+01 -7.32403412e+01 -6.03375549e+01 -5.22412949e+01 -5.34222870e+01 -7.31884155e+01 -9.00593338e+01 -9.02528000e+01 -8.51550980e+01 -9.27237625e+01 -1.09718147e+02 -1.11489693e+02 -1.05913742e+02 -9.11474609e+01 -9.43737335e+01 -9.29512100e+01 -9.14940338e+01 -8.58862610e+01 -8.39636841e+01 -8.49437485e+01 -8.99508209e+01 -8.75988159e+01 -8.57332153e+01 -8.66253662e+01 -8.77513199e+01 -8.51217575e+01 -8.08380203e+01 -6.56506424e+01 -5.01881866e+01 -5.11361084e+01 -6.13782120e+01 -7.16069641e+01 -6.73115616e+01 -7.18372498e+01 -8.36981430e+01 -8.46818695e+01 -6.05885010e+01 -3.75026855e+01 -3.56441536e+01 -5.56390686e+01 -6.88225861e+01 -6.66169357e+01 -6.57730331e+01 -6.55206985e+01 -6.79559631e+01 -5.10582886e+01 -2.71537342e+01 -2.28490601e+01 -3.88935738e+01 -6.60102463e+01 -6.16041756e+01 -6.24796219e+01 -6.21098137e+01 -6.72271271e+01 -6.48469849e+01 -5.79112892e+01 -4.81457405e+01 -4.46448631e+01 -5.38742180e+01 -5.89321976e+01 -5.90459099e+01 -3.28562584e+01 -1.76896274e+00 2.49091005e+00 -2.33603725e+01 -5.35192223e+01 -5.99728737e+01 -6.47985153e+01 -6.44971924e+01 -5.88269882e+01 -2.60847282e+01 -2.26052976e+00 2.66408329e+01 3.26618004e+01 3.67508006e+00 -2.32609558e+01 -5.70451660e+01 -3.26111450e+01 -1.50421762e+01 -3.60833473e+01 -8.71688614e+01 -1.15173386e+02 -9.37622910e+01 -6.17545738e+01 -6.31446991e+01 -6.44205475e+01 -6.99362564e+01 -7.06483231e+01 -7.72769928e+01 -8.10085754e+01 -8.60776215e+01 -8.99215546e+01 -8.56874390e+01 -8.26661911e+01 -8.04052277e+01 -8.15539474e+01 -7.88843765e+01 -6.59029083e+01 -3.88473701e+01 -4.34068832e+01 -6.23568001e+01 -9.45204239e+01 -6.49261932e+01 -3.10077553e+01 -5.57591019e+01 -1.17784546e+02 -1.19172562e+02 -5.04768562e+01 -2.58392882e+00 -2.58758774e+01 -5.80326042e+01 -3.99872513e+01 -5.04031849e+00 -1.03534389e+00 -1.64152107e+01 -4.42349548e+01 -4.16266403e+01 -3.69645691e+01 -4.70708160e+01 -4.70403786e+01 -7.36406860e+01 -9.11002579e+01 -5.59348907e+01 -2.83055544e+00 2.99666061e+01 3.05188346e+00 -2.25588169e+01 2.63484693e+00 2.03009701e+01 3.07469120e+01 2.36779284e+00 -2.83675404e+01 -2.98876534e+01 -2.37126369e+01 -1.35880327e+01 -2.42134266e+01 -8.16188717e+00 1.92363834e+01 2.54205761e+01 1.63138924e+01 -1.87411175e+01 -3.86475410e+01 -4.93574867e+01 -4.92183914e+01 -3.93226204e+01 -9.09515076e+01 -1.42497604e+02 -1.32717117e+02 -6.45170288e+01 -1.29587011e+01 -2.81414070e+01 -5.26682320e+01 -3.00895023e+01 1.34699841e+01 1.44335938e+01 -1.20663528e+01 -4.75664177e+01 -5.48552704e+01 -5.56521797e+01 -5.48390121e+01 -4.57572327e+01 -4.43842430e+01 -3.62474442e+01 -1.85832386e+01 -9.78547573e+00 -1.64216309e+01 -3.88012352e+01 -4.98575668e+01 -6.25693855e+01 -5.76625862e+01 -8.78754196e+01 -1.15034966e+02 -8.83189926e+01 -1.20172176e+01 2.85372372e+01 -8.09950733e+00 -5.82141609e+01 -8.07471466e+01 -9.35485458e+01 -9.71219864e+01 -9.18230743e+01 -7.81807404e+01 -8.22951050e+01 -7.19111862e+01 -7.56720047e+01 -7.15646744e+01 -8.18851776e+01 -8.52615662e+01 -8.87786865e+01 -6.74122772e+01 -5.78616295e+01 -6.37629623e+01 -8.57003937e+01 -9.04664230e+01 -6.93314590e+01 -4.41493721e+01 -3.60628586e+01 -6.60315943e+00 2.54972057e+01 3.38006706e+01 7.95682907e+00 -1.44454026e+00 6.85626526e+01 1.10492149e+02 7.80999680e+01 2.24244938e+01 3.59482384e+01 8.36967468e+01 8.96413574e+01 4.64676819e+01 1.13102713e+01 8.82131100e+00 8.10723495e+00 2.16264076e+01 2.75629463e+01 2.52113762e+01 7.17384911e+00 2.34578724e+01 6.57690353e+01 8.68230515e+01 6.16132774e+01 1.83413086e+01 2.19039879e+01 5.12465096e+01 1.60144329e+01 -4.27346344e+01 -7.52617493e+01 -4.99253120e+01 -2.60271587e+01 -4.18867722e+01 -4.18493576e+01 -3.32142105e+01 -2.51452618e+01 -2.93697987e+01 -2.56807613e+01 -1.34469910e+01 -2.15236530e+01 -2.98669910e+01 -4.87873650e+01 -4.06155663e+01 -3.08092632e+01 -2.91355534e+01 3.90052676e+00 2.75766983e+01 2.93074551e+01 -1.56584759e+01 -5.61732178e+01 -6.58600464e+01 -6.17264366e+01 -8.70104218e+01 -1.22680359e+02 -1.26264648e+02 -1.03251678e+02 -6.74096603e+01 -6.12177544e+01 -5.41987114e+01 1.41852164e+00 5.54101715e+01 6.54001999e+01 2.75148296e+01 -4.68880749e+00 -1.32547259e+00 -1.18719244e+01 -2.80513706e+01 -1.82921562e+01 -4.02646637e+01 -7.62631226e+01 -6.46133347e+01 -1.15160675e+01 3.19035225e+01 1.29180832e+01 1.87272148e+01 8.93022308e+01 1.32427765e+02 1.18668510e+02 3.61198578e+01 1.45592632e+01 4.17538757e+01 4.76454086e+01 1.69803848e+01 -3.81490555e+01 -2.85386162e+01 5.51722813e+00 1.53000603e+01 -2.46564722e+00 -4.26920929e+01 -6.39708443e+01 -7.44679642e+01 -7.50198517e+01 -6.26130600e+01 -5.88589401e+01 -6.52847214e+01 -2.74087257e+01 3.52443767e+00 2.51995258e+01 -9.41496181e+00 -3.67949409e+01 -3.05441723e+01 3.64840579e+00 -1.09861422e+01 -1.88172150e+02 -3.43840942e+02 -4.31035126e+02 -3.17384619e+03 -4.75090869e+03 -6.07446960e+02 -4.41996155e+01 -4.82090424e+02 3.59446924e+03 7.83416199e+02 -5.89000586e+03 -3.42433984e+04 4.74124616e+10 -3.51075983e+10 1583832192. 1583832192. 2.60913623e+10 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. -855827968. -8622476. 6835689. 4.89724250e+06 9355888. 12616733. -9.36792480e+03 -3.33173193e+03 2.94482605e+02 -2.31771317e+02 -3.81276794e+02 -8.66647461e+02 -7.48400574e+02 -5.32390320e+02 -2.10408340e+02 -1.47909790e+02 -2.44299713e+02 -2.85679291e+02 -5.19346558e+02 -6.80408203e+02 -4.30912292e+02 -1.10307022e+02 2.27274227e+01 6.74318390e+01 4.36673660e+01 6.65603638e+01 1.24447662e+02 1.25036629e+02 7.85081558e+01 4.12980843e+01 9.28499756e+01 1.96557465e+02 2.16375946e+02 1.36674500e+02 4.37943687e+01 -8.28018856e+00 -8.63674736e+00 -3.57397118e+01 -7.86371689e+01 -9.88147354e+01 -3.48748245e+01 1.28071365e+02 2.07081558e+02 1.68320908e+02 5.92956848e+01 -1.43951387e+01 -5.57043600e+00 2.01994820e+01 6.94179306e+01 4.11932068e+01 5.57187767e+01 7.56452560e+01 5.85444489e+01 -3.17098885e+01 -1.36040054e+02 -1.23855690e+02 2.87605190e+01 1.02168060e+02 7.16736298e+01 -1.28560028e+01 -4.46320504e-01 6.85386734e+01 6.92320251e+01 -3.25469136e+00 -8.50009308e+01 -6.80287552e+01 5.41008987e+01 1.35703903e+02 1.11706764e+02 3.69539948e+01 2.09434910e+01 4.53054733e+01 3.57870331e+01 -1.93575706e+01 -8.19630661e+01 -5.07833252e+01 -1.18573294e+01 -2.29351101e+01 -6.27779846e+01 -7.74582443e+01 -5.02339287e+01 -7.27470875e+00 3.87053032e+01 6.14423027e+01 3.33004684e+01 -8.35602939e-01 -5.72875071e+00 -4.46256485e+01 -1.11444717e+02 -1.35554092e+02 -6.08492622e+01 7.30993042e+01 1.33415543e+02 9.57991486e+01 -1.09289131e+01 -1.24080719e+02 -1.64158829e+02 -1.34241287e+02 -1.03985191e+02 -1.20452431e+02 -8.84679565e+01 3.07049537e+00 7.83880844e+01 4.79563789e+01 -1.88187656e+01 -4.71932564e+01 -2.08190575e+01 4.56893120e+01 5.94615631e+01 2.80255013e+01 -1.61171818e+01 -6.81897020e+00 3.28828812e+00 -3.79398384e+01 -1.25361580e+02 -1.45628967e+02 -7.75553894e+01 4.64842367e+00 6.32953930e+00 -5.45098343e+01 -1.04117065e+02 -1.00877480e+02 -4.40754623e+01 1.09998026e+01 3.01767426e+01 1.77252603e+00 2.71385264e+00 4.72768860e+01 6.06550446e+01 1.16999378e+01 -4.82043266e+01 -5.04557419e+01 9.45333290e+00 4.41294899e+01 5.67001390e+00 -2.57162971e+01 -4.24094658e+01 -1.17619305e+01 -2.26435471e+01 -7.58980942e+01 -9.13639069e+01 -3.03833065e+01 9.69636002e+01 1.61123825e+02 1.07789856e+02 2.81385593e+01 -4.07806921e+00 1.87141685e+01 4.48773956e+01 4.01099091e+01 4.27228279e+01 7.93071594e+01 1.28177872e+02 1.40611176e+02 6.48646774e+01 -4.50379410e+01 -9.16020203e+01 -1.12304306e+01 5.93911667e+01 5.31206207e+01 2.16162720e+01 5.52236366e+01 1.37821579e+02 1.27493896e+02 4.19860764e+01 -3.30492554e+01 2.33215809e+01 1.50806870e+02 2.21876892e+02 1.69803085e+02 8.10099258e+01 2.99513416e+01 3.47228470e+01 1.88700600e+01 1.03903043e+00 2.10685520e+01 8.51136551e+01 1.63898529e+02 1.24788666e+02 6.21641998e+01 -1.26441555e+01 3.51429963e+00 3.66755867e+01 8.23411484e+01 9.69634781e+01 1.01991722e+02 1.14997093e+02 1.55206299e+02 1.29135391e+02 6.14412270e+01 -1.71984005e+01 1.30128508e+01 9.08231049e+01 1.46015808e+02 1.19731392e+02 6.52163010e+01 3.18967915e+01 3.71819687e+01 1.94297791e+01 -3.88764648e+01 -7.18796616e+01 -1.53493376e+01 8.27640533e+01 1.07032005e+02 6.97926788e+01 -7.53030539e+00 -2.28431683e+01 -1.31398067e+01 1.42213440e+01 3.03791904e+01 3.44977188e+01 5.72800903e+01 8.65905762e+01 5.70635910e+01 1.23302841e+01 -1.09232807e+01 -5.20248747e+00 2.68842735e+01 3.78668137e+01 3.11627026e+01 3.03736019e+01 3.24765854e+01 6.10839195e+01 3.25914078e+01 -7.48457479e+00 -3.37476730e+01 -3.17277107e+01 3.25929909e+01 6.67097321e+01 4.89359474e+01 -1.47799282e+01 -2.45237961e+01 1.76690712e+01 6.15965767e+01 5.37478828e+01 1.73633289e+01 2.27776070e+01 5.46773872e+01 7.04326324e+01 2.84806080e+01 -2.48189509e-01 1.93882484e+01 3.98856583e+01 1.88363285e+01 7.25219393e+00 3.10243912e+01 5.23944054e+01 6.84537354e+01 4.27108192e+01 6.29341736e+01 7.27152023e+01 8.18618851e+01 9.43714676e+01 1.11498726e+02 1.17474060e+02 5.92146759e+01 3.60138512e+01 3.37735100e+01 7.61331024e+01 6.47730103e+01 5.79104767e+01 7.00655060e+01 9.84955444e+01 1.07570923e+02 5.80966568e+01 2.18261242e+01 1.71498814e+01 6.42022705e+01 7.15265732e+01 6.21412735e+01 4.33244591e+01 4.83032227e+01 8.80421295e+01 7.74652023e+01 5.34946556e+01 5.02794409e+00 -9.77121353e+00 6.39413881e+00 4.22411499e+01 6.76624146e+01 4.51340599e+01 1.40141850e+01 4.57962275e+00 2.33544750e+01 1.37839770e+00 -2.00209832e+00 2.18361282e+01 6.58195572e+01 6.72894745e+01 1.71285324e+01 -2.37592554e+00 2.02430267e+01 6.05180931e+01 5.16210060e+01 3.19696102e+01 2.69821548e+01 3.70729446e+01 5.68628693e+01 5.66879044e+01 6.52378998e+01 3.96114044e+01 2.38207550e+01 1.88207512e+01 4.18389168e+01 5.22060280e+01 3.76725349e+01 1.91677437e+01 1.72991695e+01 1.26395950e+01 -2.08005867e+01 -4.06767197e+01 -3.89143982e+01 -2.38113289e+01 -1.99827728e+01 -3.68230858e+01 -4.04680328e+01 -2.53454475e+01 1.19700909e+01 2.80270519e+01 3.13568497e+01 2.34437733e+01 3.23971825e+01 5.55521469e+01 7.35418777e+01 7.58206406e+01 4.87296333e+01 3.69699287e+01 3.36775856e+01 4.22906151e+01 3.52654343e+01 2.41279793e+01 1.42520847e+01 1.99277363e+01 1.83814468e+01 3.46168542e+00 -9.34665394e+00 -1.10376430e+00 1.98553371e+01 2.25016537e+01 2.46051769e+01 4.64270287e+01 6.68121109e+01 7.86482925e+01 5.62952576e+01 5.28718224e+01 4.48793488e+01 3.21731186e+01 3.02151222e+01 4.45754280e+01 7.16123352e+01 7.95865707e+01 5.35141029e+01 3.51449203e+01 3.66223793e+01 5.48210793e+01 6.69834366e+01 5.38399963e+01 3.69121399e+01 2.34557114e+01 2.70803871e+01 4.36945572e+01 5.53821983e+01 7.11203995e+01 7.06507797e+01 6.84665985e+01 7.26595306e+01 7.56716309e+01 7.86335983e+01 5.51615372e+01 5.23417358e+01 5.13653183e+01 5.48552895e+01 5.78549538e+01 6.89993057e+01 9.64477081e+01 1.00966064e+02 8.07447052e+01 4.59945908e+01 3.06672459e+01 5.04865494e+01 7.64545441e+01 7.87232590e+01 5.07528648e+01 2.28702335e+01 2.95230579e+01 5.54344673e+01 7.06251678e+01 6.89325485e+01 5.36267586e+01 5.58700523e+01 6.36014366e+01 7.10611191e+01 7.18111191e+01 5.91306648e+01 5.78042221e+01 6.31410255e+01 6.99081345e+01 6.92333069e+01 6.20614815e+01 6.44805908e+01 6.57412415e+01 5.61361008e+01 4.33665924e+01 4.46060562e+01 6.42727966e+01 7.66975021e+01 7.17485886e+01 5.65204926e+01 5.00031395e+01 5.25206718e+01 6.12023697e+01 6.49846802e+01 6.61461945e+01 5.90659561e+01 5.83951225e+01 5.88867531e+01 6.18000793e+01 6.32029037e+01 5.92959213e+01 5.58150330e+01 5.13782768e+01 5.17742729e+01 5.40615959e+01 5.79369469e+01 6.26210136e+01 6.40193634e+01 6.02099457e+01 5.42771530e+01 5.16765251e+01 5.44187012e+01 5.94775162e+01 6.04508018e+01 5.74342613e+01 5.44812851e+01 5.49920311e+01 5.70025177e+01 5.76273079e+01 5.74189873e+01 5.72371292e+01 5.73463745e+01 5.71691475e+01 5.64476128e+01 5.53440971e+01 5.48765411e+01 5.37589912e+01 5.35865326e+01 5.48752289e+01 5.78128052e+01 5.91252480e+01 5.62185822e+01 5.30695992e+01 5.37060776e+01 5.89002342e+01 6.37415581e+01 6.25105553e+01 5.62436333e+01 5.43264961e+01 5.68779640e+01 6.26906967e+01 6.12550850e+01 5.59039726e+01 5.04025002e+01 4.56923447e+01 5.00319061e+01 5.02672424e+01 5.32541161e+01 5.25628548e+01 5.04062386e+01 4.80264091e+01 4.22999954e+01 4.73929214e+01 5.51433601e+01 6.34352531e+01 5.93046722e+01 4.59179153e+01 3.68871574e+01 4.42762718e+01 5.96946411e+01 6.88763351e+01 6.77949066e+01 5.66369476e+01 5.29222603e+01 5.08635292e+01 5.67449989e+01 5.30085106e+01 4.55057640e+01 3.55368767e+01 2.54474335e+01 2.92645988e+01 4.56114502e+01 5.93874168e+01 6.13610458e+01 5.42250290e+01 4.66155434e+01 3.45602684e+01 2.84667568e+01 4.58083305e+01 7.15823517e+01 8.38181152e+01 6.53632355e+01 3.96661835e+01 3.68811607e+01 6.27173996e+01 9.26296310e+01 8.97744980e+01 5.71459351e+01 2.25188217e+01 8.36218643e+00 2.87699375e+01 4.81611900e+01 5.03221626e+01 4.02885361e+01 3.09964199e+01 4.40427475e+01 4.33912163e+01 5.01487770e+01 5.76647148e+01 6.21565437e+01 6.08459015e+01 4.16128540e+01 4.54319000e+01 6.70480652e+01 9.61363373e+01 9.16241684e+01 4.77552872e+01 1.49616385e+01 2.44455528e+01 6.32145157e+01 9.09003983e+01 9.26580887e+01 6.05990524e+01 2.73713837e+01 1.25486870e+01 3.75462799e+01 5.38636208e+01 6.86384125e+01 7.10574493e+01 6.59479675e+01 6.81960449e+01 6.81563721e+01 9.33333435e+01 1.06992584e+02 1.04102730e+02 8.61154556e+01 4.91134796e+01 3.67950134e+01 5.51113129e+01 9.16202774e+01 1.02451111e+02 8.08880463e+01 4.60963326e+01 4.65687218e+01 7.15537262e+01 1.05685547e+02 1.11813454e+02 7.77295609e+01 3.83168755e+01 2.08709984e+01 5.48798409e+01 8.86934433e+01 8.87808914e+01 5.80415726e+01 3.29051590e+01 2.93353577e+01 3.40272179e+01 4.42732048e+01 7.11449051e+01 7.78812180e+01 5.28598671e+01 7.00922191e-01 -1.79070454e+01 1.55105057e+01 5.77251968e+01 9.15731735e+01 6.97809448e+01 3.24985809e+01 7.76231337e+00 1.62927856e+01 4.70705185e+01 4.82114677e+01 2.66404839e+01 -8.81366611e-01 -8.04318523e+00 3.33517265e+01 6.05342293e+01 5.09875069e+01 2.15495319e+01 -1.39785509e+01 -6.55787945e+00 -3.74269414e+00 9.35168648e+00 3.27593193e+01 4.70605354e+01 5.47699738e+01 1.50268993e+01 -9.08433056e+00 7.13290930e+00 4.39156837e+01 7.47612991e+01 4.67386818e+01 8.90215111e+00 -1.46950464e+01 2.75276222e+01 1.03677650e+02 1.45620605e+02 1.00009857e+02 4.26586056e+00 -5.31085968e+01 -2.19103451e+01 3.39326515e+01 5.73203011e+01 6.40748825e+01 7.18149719e+01 1.05302147e+02 3.64376717e+01 1.23118103e+02 2.05285522e+02 1.77956079e+03 2.71184302e+03 -4.44546997e+02 3.01194458e+02 -4.31568896e+03 -1.51168643e+04 1252064128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.74436659e+09 -366176064. 229783328. -625852608. 718892352. -249392048. -931135680. -444683168. 2.03038867e+04 9.28786719e+03 2.68042358e+03 5.30097839e+02 3.94183258e+02 -1.42795935e+03 8.85760498e+01 1.50039636e+03 -1.16056816e+02 7.16766739e+01 2.81951813e+02 2.87280701e+02 2.07059021e+02 2.21468414e+02 1.69422440e+02 1.02522202e+02 4.59960442e+01 3.98763695e+01 6.07738914e+01 2.30741100e+01 1.41817150e+01 7.26657562e+01 1.14898705e+02 6.73712158e+01 -5.12457657e+01 -1.16440033e+02 -4.00074615e+01 5.42590904e+01 1.19255997e+02 8.42163925e+01 -2.39677505e+01 -1.15655289e+02 -1.58691818e+02 -7.29136658e+01 -5.50084734e+00 5.65702248e+00 -5.47834320e+01 -1.01094460e+02 -6.55110855e+01 -6.04189262e+01 -1.14955893e+01 2.87659454e+01 5.11862335e+01 1.08222389e+01 -1.08081223e+02 -1.16616127e+02 -2.29175377e+01 9.54389954e+01 1.22927055e+02 2.45260696e+01 -6.66723328e+01 -5.93250809e+01 1.54513807e+01 4.52048149e+01 -3.25755463e+01 -1.33989822e+02 -1.65916840e+02 -1.14388885e+02 3.63965213e-01 8.14654999e+01 7.98368301e+01 7.78287935e+00 -9.15763931e+01 -1.61168488e+02 -1.97127548e+02 -1.65496063e+02 -9.84518814e+01 -3.90210762e+01 -9.71325970e+00 -3.90707817e+01 -2.10945702e+01 5.30409393e+01 1.24305237e+02 1.14919106e+02 2.24306297e+01 -5.21974754e+01 -2.83781662e+01 1.35133400e+01 7.95942612e+01 1.11149460e+02 7.50043716e+01 -1.55354557e+01 -7.17018967e+01 -1.97035542e+01 4.84605713e+01 2.99433460e+01 -9.26394653e+00 -2.63270874e+01 7.69742584e+00 -1.57089977e+01 -1.06206818e+01 3.07742844e+01 5.73219833e+01 2.46630917e+01 -9.19937210e+01 -1.04527855e+02 3.50042844e+00 1.34243378e+02 1.97648483e+02 1.10065819e+02 8.59101772e+00 -4.30482635e+01 -2.27804680e+01 1.95927982e+01 2.52660980e+01 1.64461720e+00 -5.93578529e+01 -9.39211807e+01 -3.36502724e+01 7.66678696e+01 1.05249123e+02 5.95972672e+01 1.73514900e+01 1.46491785e+01 -1.99278488e+01 -1.63014011e+01 7.04638214e+01 1.68780289e+02 1.59899170e+02 2.40443592e+01 -4.07331581e+01 4.09910774e+01 1.52147980e+02 1.73661942e+02 6.89838028e+01 -4.16053429e+01 -6.65555038e+01 -3.47183838e+01 5.87427292e+01 1.23235847e+02 1.00935921e+02 7.92033863e+00 -6.70301743e+01 -7.88600874e+00 9.23548355e+01 1.30503952e+02 1.03463097e+02 5.50672646e+01 1.67906265e+01 -5.01639442e+01 -7.40762329e+01 -4.28318138e+01 5.71275234e+00 9.56965542e+00 -5.58670425e+01 -8.62110443e+01 -1.19795961e+01 1.11416817e+02 2.01043076e+02 1.54252808e+02 2.82610302e+01 -6.61713333e+01 -6.03776894e+01 1.74796333e+01 4.29303360e+01 1.86112652e+01 4.59974146e+00 -4.04602318e+01 -2.24745655e+01 -1.93955078e+01 2.40987949e+01 9.08092880e+01 1.35209930e+02 1.53126434e+02 6.87116013e+01 2.15919762e+01 6.73175964e+01 1.24847725e+02 1.01980309e+02 -1.82771969e+01 -8.16870346e+01 -4.27312012e+01 1.56569090e+01 5.88820457e+01 5.17793465e+01 2.70698566e+01 7.02361405e-01 -1.51738787e+01 4.89000893e+01 3.99710197e+01 8.37746811e+00 -6.80558929e+01 -1.42042694e+02 -1.86969391e+02 -2.25574661e+02 -1.47667435e+02 -3.83156166e+01 2.71493855e+01 3.69919624e+01 -3.57945099e+01 -3.55556717e+01 2.56993542e+01 1.20159599e+02 1.65299484e+02 5.56219406e+01 -9.08496857e+01 -1.66796173e+02 -1.29392654e+02 -6.28122826e+01 -3.18928452e+01 -4.12649460e+01 -7.39416199e+01 -1.16665680e+02 -8.60749283e+01 -1.98084908e+01 2.06592140e+01 -1.88402634e+01 -3.62097931e+01 -6.00156288e+01 -8.89067535e+01 -1.00136032e+02 -6.08219528e+01 -2.90616226e+01 -2.87456036e+01 -3.94332542e+01 -3.37522817e+00 4.96626854e+01 9.91983032e+01 1.15809692e+02 5.43882713e+01 3.46194077e+00 -7.68014221e+01 -9.58445740e+01 -4.10880737e+01 3.59924431e+01 6.54619293e+01 3.79332137e+00 -3.48760338e+01 -2.63849373e+01 -1.00941420e+01 -1.38497915e+01 -3.32139087e+00 -2.09257174e+00 -3.00053978e+00 -1.44908123e+01 -1.24436922e+01 6.43717146e+00 2.46768265e+01 4.86367378e+01 4.26028938e+01 2.72097702e+01 1.24100578e+00 4.67287970e+00 1.81808128e+01 1.62023544e+01 3.48200202e+00 -3.19972000e+01 -5.87215805e+01 -5.72536316e+01 -4.82188454e+01 -1.09482861e+01 -1.44538155e+01 -8.42564487e+00 -8.26775932e+00 1.17561598e+01 9.60803318e+00 3.57200813e+00 -3.60768342e+00 1.69939079e+01 1.57298222e+01 1.28008709e+01 7.51986885e+00 2.06643639e+01 3.54362679e+01 3.29496498e+01 3.61255875e+01 1.92915936e+01 1.43602238e+01 7.17715263e-01 2.76625061e+00 3.92680860e+00 2.07900200e+01 1.93589249e+01 1.66458130e+01 -1.03375902e+01 -6.57337093e+00 3.14481401e+00 8.26377201e+00 -6.43487263e+00 -1.27405891e+01 -3.30545688e+00 1.25317039e+01 -3.52628517e+00 -4.61328936e+00 -3.21932137e-01 8.25806904e+00 -7.56706953e+00 -1.56408653e+01 3.45048213e+00 5.37211657e+00 -2.11987762e+01 -4.29762917e+01 -4.10977440e+01 -4.48199501e+01 -5.22501755e+01 -4.12047119e+01 -4.50508919e+01 -5.19236679e+01 -5.59675865e+01 -3.39157524e+01 -2.34633770e+01 -3.25962982e+01 -2.32815552e+01 -9.11315727e+00 -2.56523347e+00 -1.16110573e+01 8.97368240e+00 3.99598999e+01 3.70542450e+01 1.43382654e+01 -1.08978891e+01 -2.16600780e+01 -1.36561251e+01 -1.46355038e+01 1.11995578e+00 -1.26951313e+01 -2.32552567e+01 -3.39075584e+01 -4.26951447e+01 -6.23628693e+01 -6.05941658e+01 -3.65723343e+01 -2.04835529e+01 -2.57124863e+01 -3.08867970e+01 -2.65247612e+01 -2.73215981e+01 -4.12067299e+01 -4.35044289e+01 -5.18620224e+01 -5.19587784e+01 -3.94171829e+01 -2.44914246e+01 -9.95265865e+00 -1.93299809e+01 -2.80975533e+01 -4.33055573e+01 -4.79139786e+01 -2.31800976e+01 -4.92515516e+00 -1.21015558e+01 -3.71036453e+01 -4.34510651e+01 -4.29536247e+01 -2.36912079e+01 -2.40564175e+01 -2.30359192e+01 -2.47811966e+01 -1.45989037e+01 1.89994526e+01 8.42032850e-01 9.68973696e-01 -2.17057610e+01 -5.49470997e+00 -9.79176521e+00 -2.00064144e+01 -4.02467308e+01 -2.88681774e+01 -5.64582062e+00 2.02048135e+00 -1.91458759e+01 -3.22251282e+01 -2.66009464e+01 2.52187014e+00 3.78600922e+01 3.48320541e+01 3.46246624e+00 -4.56280479e+01 -2.47871075e+01 8.99269009e+00 3.09312267e+01 7.12171650e+00 -2.54051037e+01 -2.69214916e+01 -2.84164047e+00 1.36672754e+01 1.76054134e+01 5.75230503e+00 1.62417431e+01 3.60330276e+01 4.40136337e+01 1.78733044e+01 -2.12259598e+01 -3.01024914e+01 -1.21392870e+01 -5.49346972e+00 -2.00576630e+01 -3.60113678e+01 -3.53209343e+01 -4.96808958e+00 1.73536034e+01 1.57042656e+01 -8.35974979e+00 -4.12425690e+01 -4.49604187e+01 -4.17228394e+01 -3.77385635e+01 -5.46305771e+01 -8.88024063e+01 -9.50482788e+01 -7.13407822e+01 -4.05500221e+01 -2.21933708e+01 -1.51659679e+01 6.15531921e-01 4.03130531e-01 -5.07999382e+01 -1.02674431e+02 -1.02851395e+02 -6.46647415e+01 -2.50259666e+01 -2.95823307e+01 -3.11827450e+01 -5.41769485e+01 -7.86469727e+01 -7.45427856e+01 -4.26121941e+01 -1.15804167e+01 -6.60090494e+00 9.25557673e-01 -3.40483360e+01 -7.34605103e+01 -8.50778732e+01 -5.50868797e+01 -2.38837070e+01 -6.42470789e+00 4.66533756e+00 1.04265623e+01 -1.67562389e+01 -3.00205307e+01 -4.48426208e+01 -4.75755920e+01 -4.92752724e+01 -5.34681969e+01 -5.38636513e+01 -5.36892128e+01 -5.21015434e+01 -5.80403824e+01 -6.93504181e+01 -7.36501007e+01 -5.67035675e+01 -3.48693047e+01 5.86509743e+01 9.45813980e+01 2.40386791e+01 -4.93514824e+01 -2.82277069e+02 1.30735156e+03 2.32696216e+03 7.85812531e+01 -4.98739014e+02 -8.77386621e+03 -2.08308535e+04 829045312. 5.95769344e+09 253882064. -3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -875751680. 229478736. 595909952. 984809472. 380755104. -102812792. 1.57804512e+04 7.27544922e+03 1.00884534e+03 5.40870911e+02 1.49597435e+01 -1.10351639e+02 -1.70282013e+02 -2.01386337e+02 -2.01514877e+02 -1.88385468e+02 2.73608057e+03 1.87522791e+03 3.85026001e+02 1.24674644e+02 6.58411407e+01 4.13255386e+01 2.84665470e+01 7.65443802e+00 -3.00693913e+01 -4.18571930e+01 -5.61268959e+01 -5.64393654e+01 -6.49428406e+01 -6.51867981e+01 -6.71634445e+01 -7.08460693e+01 -7.47169800e+01 -7.92742920e+01 -7.42116165e+01 -7.31579285e+01 -7.72716827e+01 -7.93339233e+01 -8.15208130e+01 -7.28280258e+01 -6.80040131e+01 -6.57099533e+01 -7.09114075e+01 -7.48252029e+01 -8.09438858e+01 -8.21251907e+01 -7.62069626e+01 -5.47909622e+01 -3.81046257e+01 -3.53315392e+01 -4.56939278e+01 -5.34644661e+01 -5.75822792e+01 -6.39039917e+01 -6.28358841e+01 -5.84826660e+01 -5.58149147e+01 -5.81391830e+01 -6.31972466e+01 -6.47781296e+01 -7.49649429e+01 -6.70904999e+01 -5.92745667e+01 -5.02672386e+01 -4.40059662e+01 -4.00957870e+01 -3.76100693e+01 -4.59131470e+01 -5.15790443e+01 -5.01264305e+01 -5.41012230e+01 -6.50244064e+01 -6.90144348e+01 -6.53533554e+01 -5.69504700e+01 -5.72818832e+01 -5.82146950e+01 -5.02869873e+01 -3.62854004e+01 -3.73756714e+01 -4.26789551e+01 -5.04173317e+01 -3.31106987e+01 -1.87177658e+01 -1.90027046e+01 -2.95457401e+01 -3.68735085e+01 -3.38332939e+01 -3.23843536e+01 -3.71440735e+01 -3.62271423e+01 -3.08094997e+01 -2.18867893e+01 -2.65841236e+01 -3.99379463e+01 -5.32682114e+01 -5.73615646e+01 -5.75139961e+01 -5.43956871e+01 -5.03248367e+01 -5.48753281e+01 -6.22257042e+01 -5.76347961e+01 -4.83601151e+01 -4.51510582e+01 -5.46944046e+01 -6.11213379e+01 -4.95662613e+01 -4.11937752e+01 -4.24904785e+01 -5.53155441e+01 -6.51745071e+01 -6.57106552e+01 -6.55206146e+01 -6.39411392e+01 -6.34586525e+01 -5.97392807e+01 -5.90114326e+01 -6.05115242e+01 -6.08053436e+01 -5.79074821e+01 -5.53064156e+01 -5.55673141e+01 -5.62873955e+01 -5.66767273e+01 -5.60329094e+01 -5.65140648e+01 -4.99730148e+01 -4.32325363e+01 -4.40529099e+01 -5.03115997e+01 -5.73413620e+01 -5.08649788e+01 -4.53733177e+01 -4.49059982e+01 -5.01056709e+01 -5.40721512e+01 -5.49541359e+01 -5.59200668e+01 -5.82214203e+01 -5.68910484e+01 -5.63485260e+01 -5.56487999e+01 -5.79510345e+01 -5.95887070e+01 -5.90665855e+01 -5.67492447e+01 -5.53681259e+01 -5.60111465e+01 -5.66950493e+01 -5.62468987e+01 -5.47164345e+01 -5.10733757e+01 -4.76663704e+01 -4.83343849e+01 -5.13230057e+01 -5.46271210e+01 -5.23792419e+01 -5.03234825e+01 -5.11416512e+01 -5.46267891e+01 -5.72088470e+01 -5.69047737e+01 -5.62674217e+01 -5.60792694e+01 -5.63496628e+01 -5.64882240e+01 -5.65754738e+01 -5.68962212e+01 -5.69821854e+01 -5.65687408e+01 -5.62602463e+01 -5.65687065e+01 -5.70042152e+01 -5.72364426e+01 -5.72332382e+01 -5.72105141e+01 -5.74463997e+01 -5.79133263e+01 -5.80614815e+01 -5.77969093e+01 -5.75568886e+01 -5.76403770e+01 -5.71905022e+01 -5.79849701e+01 -5.97019997e+01 -6.04618721e+01 -5.94555244e+01 -5.80591049e+01 -5.83157997e+01 -5.85943642e+01 -5.80323296e+01 -5.75658379e+01 -5.80101662e+01 -5.82992363e+01 -6.13741379e+01 -6.42698746e+01 -6.46867065e+01 -6.14056206e+01 -5.87238350e+01 -6.00319901e+01 -6.09018250e+01 -6.39090843e+01 -6.70073318e+01 -6.67707748e+01 -6.17415047e+01 -5.68583221e+01 -5.77843094e+01 -5.84107780e+01 -5.92330780e+01 -5.75868530e+01 -5.61353340e+01 -5.51952820e+01 -5.51374435e+01 -5.58543358e+01 -5.55760612e+01 -5.51804962e+01 -5.55534668e+01 -5.19936867e+01 -4.82630806e+01 -4.62352676e+01 -4.66175575e+01 -4.99574394e+01 -5.02092400e+01 -5.06060677e+01 -5.01226158e+01 -5.07452240e+01 -5.18303947e+01 -5.00616150e+01 -5.15803146e+01 -5.30344887e+01 -5.28435173e+01 -4.89739380e+01 -4.77071991e+01 -4.89343834e+01 -5.08352013e+01 -5.06471863e+01 -5.02020798e+01 -5.26444435e+01 -5.20157280e+01 -5.61351089e+01 -5.81607437e+01 -5.96845093e+01 -5.19897041e+01 -4.23524246e+01 -4.71447983e+01 -6.24782333e+01 -7.19786224e+01 -6.96203232e+01 -6.28687057e+01 -5.97790298e+01 -6.00087967e+01 -5.98720589e+01 -6.31284447e+01 -6.31184425e+01 -6.27746201e+01 -6.06891136e+01 -5.75172234e+01 -5.36382332e+01 -5.15270081e+01 -5.43594704e+01 -5.83443756e+01 -6.16505089e+01 -6.12297211e+01 -5.97084465e+01 -5.88638420e+01 -5.49037056e+01 -5.33486977e+01 -5.05906372e+01 -5.59383926e+01 -6.77792816e+01 -8.02952042e+01 -7.86546097e+01 -7.07306595e+01 -5.73395538e+01 -5.53842163e+01 -5.25422745e+01 -6.27815094e+01 -7.18997879e+01 -7.74491577e+01 -7.98486404e+01 -7.00572052e+01 -6.18937759e+01 -4.93016510e+01 -5.31963387e+01 -5.68149338e+01 -5.87821045e+01 -5.51251907e+01 -5.36208305e+01 -4.97026672e+01 -5.38468781e+01 -6.01869392e+01 -6.43049088e+01 -6.71661453e+01 -6.54862595e+01 -8.11698914e+01 -9.07964020e+01 -8.70934753e+01 -6.81113663e+01 -5.44644012e+01 -6.04758110e+01 -6.58944702e+01 -6.38507347e+01 -6.21113434e+01 -7.32712784e+01 -8.92070389e+01 -8.86508408e+01 -6.91482239e+01 -4.85394173e+01 -5.60447578e+01 -6.43341064e+01 -6.34063034e+01 -5.12646561e+01 -4.83321609e+01 -5.18601913e+01 -6.08775139e+01 -5.51430206e+01 -4.27889481e+01 -3.85476303e+01 -4.14018707e+01 -4.66192284e+01 -3.85716705e+01 -5.08871117e+01 -6.92151642e+01 -7.45215073e+01 -8.12206497e+01 -9.32012253e+01 -1.10402687e+02 -1.08886650e+02 -9.98533936e+01 -1.03033913e+02 -9.38214645e+01 -8.99454193e+01 -7.00282364e+01 -4.94182549e+01 -2.19858456e+01 -1.66080647e+01 -2.35091896e+01 -2.99034882e+01 -3.46757698e+01 -3.76071053e+01 -3.76981430e+01 -3.27066803e+01 -2.68417587e+01 -4.44394836e+01 -7.29159927e+01 -8.38345261e+01 -7.89548492e+01 -5.96087189e+01 -5.13640060e+01 -5.02881203e+01 -3.83257751e+01 -4.90532455e+01 -4.83636703e+01 -6.08627663e+01 -6.87338257e+01 -8.21328583e+01 -1.02102806e+02 -8.46367264e+01 -6.34264870e+01 -5.23752708e+01 -7.71844559e+01 -8.40845642e+01 -7.54249268e+01 -4.84982338e+01 -6.70286636e+01 -8.82013474e+01 -9.96593552e+01 -8.21387558e+01 -6.26586761e+01 -8.44516373e+01 -1.06818779e+02 -9.97752151e+01 -6.21936569e+01 -4.00923119e+01 -6.26853256e+01 -7.92938080e+01 -5.27711563e+01 -1.99102440e+01 -3.90874786e+01 -8.62945938e+01 -1.04707909e+02 -9.22416458e+01 -7.38177795e+01 -7.88455124e+01 -9.96214752e+01 -1.19554558e+02 -1.07459564e+02 -7.06073914e+01 -3.68350258e+01 -3.97758064e+01 -4.68167610e+01 -5.18209763e+01 -4.72064934e+01 -4.71498299e+01 -5.49601364e+01 -7.28523636e+01 -7.52060928e+01 -5.62689438e+01 -4.92558937e+01 -5.23568039e+01 -8.31327362e+01 -9.44635162e+01 -7.92604141e+01 -6.58241272e+01 -4.50233078e+01 -5.01851273e+01 -4.49054527e+01 -3.93917656e+01 -2.79520073e+01 -3.10368214e+01 -7.36620636e+01 -1.08633507e+02 -7.04355927e+01 -5.47870970e+00 -6.11166060e-01 -6.00520477e+01 -8.15764771e+01 -4.60914268e+01 -2.62915192e+01 -5.15705223e+01 -6.40822220e+01 -5.84587364e+01 -3.09195614e+01 -4.46037025e+01 -5.71918602e+01 -6.50373001e+01 -5.18659935e+01 -2.44184647e+01 -2.65352135e+01 -2.63977089e+01 -5.63113174e+01 -7.89147186e+01 -8.38037567e+01 -5.01125259e+01 -5.05438652e+01 -1.09085762e+02 -1.50654053e+02 -1.33459534e+02 -7.32925568e+01 -7.05009155e+01 -8.82321091e+01 -6.94446869e+01 -1.40887127e+01 2.78614116e+00 -3.36123085e+01 -6.85108109e+01 -6.06651535e+01 -4.94765587e+01 -6.09114761e+01 -6.81979980e+01 -6.49091492e+01 -5.72442589e+01 -3.66474342e+01 -2.25282650e+01 -1.05696697e+01 -2.95563354e+01 -4.28595276e+01 -5.82726402e+01 -5.97186279e+01 -6.79325714e+01 -8.97825699e+01 -9.03254623e+01 -6.93356171e+01 -4.30349007e+01 -5.21359329e+01 -8.47711258e+01 -8.82089005e+01 -8.68249054e+01 -9.72460785e+01 -1.56102921e+02 -1.86415359e+02 -1.60726273e+02 -9.15579529e+01 -7.15397034e+01 -8.29770279e+01 -9.21356430e+01 -6.55852127e+01 -5.20801697e+01 -3.52567596e+01 -2.21420403e+01 -2.07170639e+01 -3.58450165e+01 -3.72331276e+01 -1.49971905e+01 -1.55146656e+01 -6.63883057e+01 -8.98625870e+01 -6.74922333e+01 -3.54004211e+01 -7.47686462e+01 -9.50340042e+01 -6.06241875e+01 7.74256039e+00 4.95570221e+01 4.72427559e+01 4.52291946e+01 2.82478008e+01 6.63287830e+00 -5.54280710e+00 1.31754959e+00 -5.34942865e+00 -1.71944199e+01 -1.91563892e+01 7.92837238e+00 -1.07176752e+01 -7.41170425e+01 -1.15094276e+02 -1.20235458e+02 -1.09986572e+02 -8.76229935e+01 -6.07600098e+01 -2.97471333e+01 -2.88962879e+01 -2.29606495e+01 -1.67963543e+01 -1.73797970e+01 -2.95922318e+01 -3.33545036e+01 -4.05131607e+01 -3.46673584e+01 -2.16876564e+01 -1.41881456e+01 -1.22731180e+01 -6.05470886e+01 -1.08836662e+02 -1.16115616e+02 -8.01944122e+01 -4.24673996e+01 -4.67418137e+01 -4.51751022e+01 -4.84484482e+01 -3.51647415e+01 -3.98414421e+01 -4.21673508e+01 -8.03523026e+01 -1.09042595e+02 -9.13670273e+01 -4.88081055e+01 -3.69228439e+01 -1.03897736e+02 -1.44590897e+02 -1.18500572e+02 -5.12371635e+01 -5.27211380e+01 -7.61298599e+01 -8.10392685e+01 -5.26001740e+01 -2.70800648e+01 -6.31705399e+01 -8.59418793e+01 -1.14590706e+02 -1.26711189e+02 -8.52759247e+01 -5.34660683e+01 -5.18861465e+01 -1.32753342e+02 -1.72295456e+02 -1.17623062e+02 -4.51833153e+01 -5.44202614e+01 -1.10743584e+02 -1.24268250e+02 -9.41040726e+01 -5.82092247e+01 -7.93338776e+01 -1.02133553e+02 -1.15519051e+02 -9.42652130e+01 -6.63449402e+01 -5.00225449e+01 -8.82426300e+01 -1.30901154e+02 -1.38281906e+02 -1.03086815e+02 -4.19163055e+01 -6.67655258e+01 -9.68429108e+01 -1.01251244e+02 -6.55603180e+01 -6.03659325e+01 -1.08266579e+02 -1.07393333e+02 -6.75585938e+01 -1.29024048e+01 2.71413946e+00 3.74683523e+00 -3.06506500e+01 -8.30988464e+01 -9.93912659e+01 -7.88562775e+01 -3.29223328e+01 -1.48806753e+01 -1.26626902e+01 -3.35564308e+01 -5.23433075e+01 -4.03611412e+01 -2.21607208e+02 -3.59278717e+02 -2.86311127e+02 4.73044205e+01 2.19424103e+02 -4.81239891e+01 -1.25920845e+02 -2.45253525e+02 -1.35615186e+03 -2.56578101e+03 -5.13050293e+03 3.77181978e+09 1.39022500e+05 1583832192. 2.60913623e+10 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. 0. 0. 0. 1.72460215e+04 6.52683105e+03 1.17781970e+03 6.67517273e+02 2.22836426e+02 -7.37948303e+01 -8.79293137e+01 -1.06612329e+01 1.20292625e+01 -3.26986923e+01 5.83143806e+00 8.29117126e+01 1.39918243e+02 7.04519958e+01 -7.95663681e+01 -1.49859894e+02 -9.48110580e+01 -1.46157110e+00 4.55856552e+01 2.97715511e+01 8.37552166e+00 3.42513161e+01 7.62916412e+01 4.21918602e+01 -2.77812290e+01 -6.99270096e+01 -4.04904404e+01 2.35641632e+01 4.25102615e+01 -3.40323853e+00 -7.75314713e+01 -1.13638695e+02 -7.61244431e+01 -8.37480011e+01 -1.32578979e+02 -8.90615540e+01 2.00839500e+01 9.55596924e+01 9.79972649e+00 -1.50914154e+02 -1.97312271e+02 -1.18602905e+02 -3.19589710e+01 1.78384323e+01 2.56694641e+01 4.38008595e+00 -2.09922862e+00 -1.92220461e+00 -1.40074997e+01 -1.31320831e+02 -2.08762695e+02 -1.65961548e+02 -5.40794449e+01 2.05110340e+01 -2.39615746e+01 -9.11868057e+01 -1.34933441e+02 -7.05222092e+01 -5.19073715e+01 -7.44347763e+01 -5.08419342e+01 2.03262024e+01 1.00745346e+02 8.71984482e+01 -2.29645157e+01 -6.28192520e+01 -3.18858643e+01 5.35021935e+01 3.79545937e+01 -2.09992847e+01 -1.59141245e+01 3.07798271e+01 6.40692673e+01 2.30831928e+01 -7.78382111e+01 -1.30019745e+02 -1.02377663e+02 4.52575505e-01 6.53129807e+01 5.06096420e+01 5.11187315e+00 1.21925182e+01 6.28851166e+01 5.80440102e+01 -6.89024639e+00 -4.35655403e+01 2.14127731e+01 1.07829796e+02 1.14309822e+02 2.17572536e+01 -5.66533127e+01 -5.12907944e+01 1.08256102e+01 2.12403412e+01 -2.33517647e+00 4.19145088e+01 1.31756104e+02 1.73250290e+02 1.07532654e+02 -1.33057127e+01 -8.35290985e+01 -5.13553200e+01 2.23738003e+01 1.04877884e+02 1.58715729e+02 1.41880157e+02 1.21132889e+02 1.13554382e+02 9.97970352e+01 2.38607655e+01 -4.48005867e+01 -2.92720318e+00 1.10272888e+02 1.62804977e+02 1.16752800e+02 5.51882172e+00 -5.79045753e+01 -2.00777473e+01 2.71251316e+01 4.65845337e+01 4.17336693e+01 8.69259491e+01 1.72316833e+02 1.76666855e+02 9.09149170e+01 -6.77872300e-01 -2.69697332e+00 5.84213753e+01 9.97118149e+01 1.08090981e+02 8.17594147e+01 4.76157188e+01 1.96613827e+01 7.21702118e+01 9.58404312e+01 5.82877808e+01 1.42125168e+01 5.52765417e+00 2.99051590e+01 3.13707657e+01 -4.10552531e-01 8.52091694e+00 3.52432556e+01 7.04012680e+01 8.42881470e+01 4.49491844e+01 2.24311543e+01 3.80531578e+01 7.79401245e+01 5.03215485e+01 -6.06068649e+01 -1.15085312e+02 -3.57122116e+01 6.42254639e+01 6.83663788e+01 1.10167580e+01 -2.29305096e+01 -7.25330687e+00 -7.22709322e+00 -4.50693588e+01 -9.44588318e+01 -1.02769989e+02 -7.21236191e+01 -7.35902882e+00 3.62627487e+01 3.98143649e+00 -2.11416817e+01 -1.09199200e+01 2.81428432e+01 6.25412512e+00 -8.27399216e+01 -6.92307663e+01 -3.23568687e+01 1.67665977e+01 -3.20525894e+01 -1.34314636e+02 -1.84664703e+02 -1.39276688e+02 -3.03506908e+01 1.85165138e+01 1.02140856e+01 1.79118843e+01 4.37419815e+01 2.60511208e+01 -4.59498863e+01 -1.24966827e+02 -1.22744377e+02 -5.21561089e+01 5.65217819e+01 9.58424301e+01 6.09291458e+01 -7.10873842e+00 -4.11041756e+01 -3.57321739e+01 -5.93684540e+01 -8.57622528e+01 -7.48076935e+01 5.98747683e+00 6.21524506e+01 3.59402618e+01 -6.84890060e+01 -1.08672760e+02 -5.37722321e+01 4.56807365e+01 7.52882080e+01 2.93395596e+01 -2.32194595e+01 2.58788514e+00 4.36102448e+01 3.61331177e+01 -1.39094276e+01 -2.41333790e+01 2.56613388e+01 9.28207321e+01 1.02584412e+02 6.66421509e+01 1.96490364e+01 1.90444202e+01 4.17432175e+01 5.12918320e+01 2.87855453e+01 4.19951057e+01 7.05048981e+01 7.76708755e+01 7.25481720e+01 3.75141106e+01 2.49090271e+01 3.62826385e+01 3.64506226e+01 3.26003151e+01 2.16761899e+00 2.65042496e+01 6.51008606e+01 8.48272400e+01 7.11132660e+01 -9.86924076e+00 -5.71623802e+01 -5.03810539e+01 4.18248444e+01 8.80111084e+01 9.23919830e+01 5.17799187e+01 3.41682739e+01 5.58099403e+01 5.36532860e+01 2.93340912e+01 9.77325249e+00 3.46194916e+01 5.59276695e+01 1.48161659e+01 -4.14577980e+01 -3.52025070e+01 -1.16706324e+00 2.00143681e+01 5.82803965e-01 -4.07971115e+01 -5.44184780e+00 2.46917286e+01 5.80674858e+01 4.38759651e+01 1.93934035e+00 -2.01433125e+01 -3.14516773e+01 1.24361153e+01 2.62957306e+01 2.91064816e+01 -9.39937019e+00 -9.28080082e+00 -8.43410301e+00 -1.16280994e+01 -3.25115929e+01 -4.40465660e+01 2.36969173e-01 3.03744221e+01 3.27818527e+01 -1.02707787e+01 -1.15473433e+01 8.75361252e+00 3.45053368e+01 5.24362564e+01 4.29882126e+01 4.40491371e+01 9.83591938e+00 -8.35041332e+00 -2.23547821e+01 -1.65705261e+01 -4.83345127e+00 1.19659557e+01 4.59788895e+01 6.55953598e+01 5.24623184e+01 4.79188061e+00 -5.02420378e+00 6.09767914e+00 1.17198505e+01 7.41559744e+00 2.13061008e+01 7.27351608e+01 8.68619080e+01 6.16460876e+01 7.61351681e+00 -4.31735420e+00 1.39700842e+01 4.34130249e+01 5.39409752e+01 3.48073654e+01 3.23880997e+01 2.22555523e+01 4.84209671e+01 6.14220467e+01 6.36569672e+01 4.16141319e+01 2.72559223e+01 4.37079430e+01 6.46537170e+01 5.22044640e+01 2.67355099e+01 3.34825249e+01 5.17473488e+01 5.33309364e+01 4.03271294e+01 4.12161064e+01 6.80869446e+01 7.52878113e+01 5.98057823e+01 3.24432945e+01 3.05504646e+01 4.21138191e+01 5.07347221e+01 4.62474136e+01 3.30377045e+01 3.57943077e+01 3.63915901e+01 5.49852486e+01 6.39088516e+01 6.37860870e+01 5.18530769e+01 4.52638245e+01 5.47222900e+01 6.55459290e+01 5.68895340e+01 3.36657829e+01 2.66060963e+01 2.71365395e+01 2.13939247e+01 3.50121379e+00 9.64058208e+00 2.96451168e+01 3.30929947e+01 1.88522491e+01 2.48367950e-01 1.93758163e+01 3.06585979e+01 3.89692116e+01 4.77204933e+01 4.91266594e+01 4.00799942e+01 1.24066610e+01 7.81060410e+00 2.84614830e+01 4.61192970e+01 3.70243530e+01 1.38426542e+01 2.05898809e+00 1.69252625e+01 2.86015701e+01 2.58048973e+01 1.76604252e+01 7.16125727e+00 -1.78694785e+00 -1.48303194e+01 -9.09184170e+00 6.28868437e+00 1.12409496e+01 5.25720930e+00 -2.46668935e+00 1.37442799e+01 2.27813854e+01 2.98821983e+01 2.73647766e+01 2.58375530e+01 1.62624874e+01 -3.10076857e+00 -7.78196669e+00 8.63228703e+00 3.66075172e+01 4.32641525e+01 2.18557777e+01 2.68544316e+00 1.78840339e+00 1.61222839e+01 2.41782494e+01 2.00512524e+01 1.02373600e+01 5.23243809e+00 1.17049313e+01 2.61817150e+01 3.02290611e+01 2.36482754e+01 1.46692896e+01 5.27192879e+00 5.86775351e+00 1.02389727e+01 2.24236870e+01 3.38249435e+01 3.77014923e+01 3.10208836e+01 1.82179947e+01 1.21405783e+01 1.86057606e+01 2.77360725e+01 2.70884285e+01 1.85266380e+01 1.22542639e+01 1.64975166e+01 2.55775223e+01 3.12765789e+01 3.12451496e+01 2.68551483e+01 2.41195850e+01 2.21219234e+01 2.52683449e+01 2.67351933e+01 2.80839767e+01 2.67983227e+01 2.62491684e+01 2.77224445e+01 2.88441849e+01 3.00194893e+01 2.97979393e+01 2.90613060e+01 2.85645180e+01 2.86467361e+01 2.91999741e+01 2.92114162e+01 2.77590179e+01 2.64865513e+01 2.72165966e+01 3.02721119e+01 3.26849174e+01 3.21535187e+01 3.03817635e+01 3.05564308e+01 3.26248093e+01 3.44369926e+01 3.50829697e+01 3.14594555e+01 2.79770565e+01 2.44815063e+01 2.44930305e+01 2.70781536e+01 3.01952248e+01 3.41939087e+01 3.38414955e+01 2.95638580e+01 2.46342278e+01 2.46786804e+01 3.03418102e+01 3.75665131e+01 3.43137550e+01 2.73024025e+01 2.36203232e+01 3.03108406e+01 4.23800468e+01 4.20310745e+01 3.42466011e+01 2.13344326e+01 2.07611351e+01 3.11390514e+01 4.00410995e+01 4.72394447e+01 3.66322594e+01 3.21204262e+01 2.56508732e+01 2.36057224e+01 2.20702400e+01 2.09393597e+01 2.84769440e+01 2.51496544e+01 1.79909649e+01 1.86435127e+01 2.84152908e+01 4.54080048e+01 5.35924072e+01 4.41519890e+01 1.97675972e+01 -2.87920332e+00 -5.16674876e-01 2.58800945e+01 5.28390884e+01 6.16796074e+01 4.23246536e+01 1.68331566e+01 1.12898836e+01 2.71651402e+01 4.71450844e+01 4.00651512e+01 2.48014965e+01 1.13632078e+01 8.78294849e+00 1.54757490e+01 2.86600895e+01 4.50421562e+01 4.33270454e+01 2.69440002e+01 4.24385160e-01 -4.38536787e+00 1.55532637e+01 4.37325325e+01 4.15856590e+01 1.91559620e+01 2.45907140e+00 1.10398493e+01 2.43512478e+01 3.14741669e+01 3.51098366e+01 2.42762737e+01 1.69817276e+01 2.61650467e+01 3.46804848e+01 4.47490005e+01 2.89265671e+01 1.52831125e+01 -3.29491758e+00 -1.57177753e+01 -1.95178199e+00 1.23657026e+01 3.80324135e+01 4.81361809e+01 3.31720390e+01 8.64819431e+00 4.40336800e+00 3.29358482e+01 6.15717201e+01 5.88826790e+01 4.19192429e+01 1.06929388e+01 1.41295207e+00 1.02252884e+01 2.72060432e+01 3.80712051e+01 1.40312901e+01 -8.51214314e+00 -3.63236580e+01 -2.97133808e+01 6.89960718e-01 3.07561970e+00 -1.08757257e+01 -4.17210274e+01 -5.09672585e+01 -3.90459099e+01 -1.61523590e+01 2.69384251e+01 4.36547241e+01 3.23925591e+01 -3.85875487e+00 -1.98368664e+01 8.55517673e+00 4.33051529e+01 4.28309631e+01 1.58867979e+00 -3.03815651e+01 -2.02545948e+01 2.25574570e+01 5.95347366e+01 6.22649689e+01 2.88454647e+01 -1.37721148e+01 -2.56572742e+01 -2.19430828e+01 -8.54363728e+00 6.76860762e+00 2.96348228e+01 3.22460060e+01 1.97791557e+01 1.08386030e+01 3.04224663e+01 7.49147415e+01 9.82964478e+01 6.12428703e+01 4.89441729e+00 -2.31893692e+01 1.33141203e+01 6.53938522e+01 7.60912094e+01 4.36913910e+01 -1.15286436e+01 -2.11256332e+01 1.25331373e+01 3.11925850e+01 4.04184914e+01 7.24111223e+00 -2.02311143e-01 3.14320230e+00 1.42041664e+01 4.39061317e+01 3.39277420e+01 2.52269535e+01 -2.04170818e+01 -5.88332634e+01 -4.28806190e+01 -2.02709770e+01 3.28196449e+01 4.32630234e+01 3.53875961e+01 -2.39596062e+01 -8.58169861e+01 -9.31389008e+01 -4.39226456e+01 -1.36971498e+00 -1.49893219e+02 -1.53436584e+02 -4.90495644e+01 -1.35070203e+03 -1.90111267e+03 -4.31568896e+03 -1.51168643e+04 1252064128. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98855859e+03 -3.81954419e+03 -3.59041595e+02 -2.52202255e+02 -1.55202621e+02 -1.33030655e+02 -6.09685669e+01 -3.26861191e+01 6.15505371e+01 6.10941734e+01 1.97751312e+01 -4.59125900e+01 -3.32215424e+01 4.44072342e+01 1.11305611e+02 1.23646767e+02 5.17029266e+01 -3.71878204e+01 -5.59837837e+01 2.11583042e+01 9.14925995e+01 9.42255096e+01 3.16343670e+01 3.63177071e+01 7.85378265e+01 8.68490677e+01 4.98024940e+01 -2.48112059e+00 -5.56118727e+00 -2.07350464e+01 -4.67185898e+01 -4.17194557e+01 5.84258270e+00 1.03174553e+02 1.04982788e+02 4.67622337e+01 -1.49586296e+01 -8.99771500e+00 5.87107162e+01 1.33461502e+02 1.21989296e+02 2.17218857e+01 -1.00239662e+02 -8.79272003e+01 2.75115547e+01 9.20403824e+01 9.47753372e+01 2.93341064e+01 7.99947786e+00 -3.62016869e+00 -1.53669262e+01 2.90421939e+00 3.21266975e+01 1.08829987e+02 8.00920105e+01 1.56908503e+01 -1.44303226e+01 3.58133774e+01 1.19532463e+02 1.20680367e+02 8.03346176e+01 8.05333614e+00 -2.08315830e+01 4.87939301e+01 1.47155350e+02 2.19024155e+02 1.76651001e+02 7.25984802e+01 3.72033997e+01 9.62567215e+01 1.40260391e+02 1.29052841e+02 3.67465897e+01 1.74951382e+01 4.42398338e+01 8.92336273e+01 8.50826187e+01 8.00880890e+01 1.05441101e+02 7.22966003e+01 1.33651819e+01 -1.66971970e+01 5.19787369e+01 1.56338837e+02 1.73344009e+02 1.35984421e+02 5.49261894e+01 -3.59573990e-01 -9.26344776e+00 5.46988640e+01 1.06233955e+02 9.81854553e+01 -4.94553947e+00 -4.49118614e+01 3.04387608e+01 1.02994232e+02 9.94305344e+01 -3.15322876e+00 -4.38871765e+01 -3.21706161e+01 -1.97732964e+01 -4.38426447e+00 3.26496239e+01 1.19854759e+02 1.13866219e+02 4.46446228e+01 -1.02908878e+01 -8.99221992e+00 5.79495926e+01 6.49298859e+01 2.43074093e+01 -8.99279118e+00 -5.26481628e+01 -3.72609673e+01 2.85420170e+01 1.03457855e+02 1.21334114e+02 2.01017265e+01 -3.01447868e+01 1.29127674e+01 4.09346428e+01 5.01865730e+01 -1.65246630e+00 6.12332106e+00 9.99234867e+00 -2.20734940e+01 -3.13837719e+01 -1.84169407e+01 8.09001617e+01 8.14189453e+01 1.62664509e+01 -4.65497437e+01 -3.86789665e+01 2.15039539e+01 2.44263554e+01 -2.81890965e+01 -6.24397430e+01 -1.12955254e+02 -6.81326675e+01 6.81891775e+00 7.86766968e+01 6.62337952e+01 -8.47215748e+00 -1.92315006e+01 1.40977526e+01 1.76572151e+01 -4.09291792e+00 -6.83763657e+01 -9.88876953e+01 -1.27396423e+02 -1.30996429e+02 -8.24789505e+01 -2.33801003e+01 6.61530075e+01 9.15371323e+01 7.47391205e+01 1.99403095e+01 1.78133812e+01 8.19363403e+01 1.42439392e+02 1.06152405e+02 -7.67807102e+00 -8.97916946e+01 -8.44213409e+01 2.43671398e+01 8.32002640e+01 7.52775421e+01 7.97710037e+00 -5.82575655e+00 2.74548149e+01 2.28537712e+01 3.14413013e+01 4.06375351e+01 4.62573586e+01 -1.01683455e+01 -8.73612137e+01 -8.28691330e+01 -5.10408936e+01 7.00134230e+00 4.17689400e+01 5.73069649e+01 2.52139969e+01 2.22843342e+01 8.17467422e+01 1.49432266e+02 1.08043175e+02 9.63793373e+00 -7.81216812e+01 -7.97679749e+01 -5.57192183e+00 2.09413548e+01 3.25561943e+01 -3.96876907e+01 -3.20912819e+01 2.18142128e+01 9.01596603e+01 1.29300064e+02 1.27892334e+02 1.76808105e+02 1.46883194e+02 6.41606369e+01 -1.02937565e+01 -1.36950846e+01 5.76015091e+01 6.68723450e+01 1.83282890e+01 -6.56057968e+01 -1.39871124e+02 -9.62191467e+01 2.84989510e+01 1.37309982e+02 9.77851639e+01 -1.37239513e+01 -3.05947247e+01 2.63668022e+01 4.97125244e+01 5.00375443e+01 2.93670440e+00 -2.51380692e+01 -5.66576538e+01 -5.00584793e+01 -2.75683193e+01 2.12494907e+01 9.58025513e+01 1.18410469e+02 9.01938248e+01 4.05508614e+01 2.30548248e+01 2.64806080e+01 -6.17514610e+00 -4.40544205e+01 -5.66281929e+01 -4.02871895e+01 1.22476463e+01 1.84946117e+01 3.01116505e+01 1.77915192e+01 -1.09502640e+01 -2.12613735e+01 -1.69613819e+01 2.68736019e+01 3.81058273e+01 1.55070858e+01 -1.62246723e+01 -1.53008451e+01 6.57869148e+00 2.41523018e+01 1.29707651e+01 -3.41151857e+00 -5.18500042e+00 -8.88159370e+00 -5.87438405e-01 -1.85642052e+01 -1.15640860e+01 -1.48226328e+01 6.09668875e+00 -1.09735136e+01 -2.42486076e+01 -3.09224072e+01 -2.29173031e+01 -1.43999224e+01 -3.13389969e+01 -4.27413788e+01 -3.87935028e+01 -4.55203400e+01 -4.10558624e+01 -3.39332352e+01 -1.22008276e+01 -2.20530052e+01 -2.44804897e+01 -2.88441982e+01 -2.18555317e+01 -3.06444893e+01 -3.69763412e+01 -3.41917191e+01 -3.63737068e+01 -3.22391167e+01 -2.09069672e+01 -1.72049103e+01 -2.39805470e+01 -2.96396465e+01 -3.78442383e+01 -3.23534851e+01 -4.91022377e+01 -3.83208809e+01 -4.71223679e+01 -3.53566360e+01 -3.69363708e+01 -1.45365877e+01 1.68940086e+01 2.77781315e+01 1.34464808e+01 -8.29477406e+00 -2.32120953e+01 -9.20576096e+00 -1.26447468e+01 1.13015699e+00 -9.09757996e+00 -2.38804722e+01 -3.00246601e+01 -1.70127239e+01 -4.76301479e+00 -1.45151520e+01 -1.93958015e+01 -9.40195942e+00 -9.94335842e+00 -2.92381096e+01 -2.04589424e+01 -4.34436560e+00 1.80116024e+01 1.19388552e+01 1.27940245e+01 -1.38630733e+01 -3.98861389e+01 -7.68825607e+01 -8.44601135e+01 -6.92372818e+01 -4.14414635e+01 -2.48070164e+01 -1.78192692e+01 -1.71409168e+01 -6.79822397e+00 -3.49671783e+01 -6.56402969e+01 -6.05955505e+01 -2.88461342e+01 -9.42799926e-01 -5.90686417e+00 -1.31187830e+01 -2.69463587e+00 3.45970583e+00 2.62443423e+00 -2.36282158e+00 2.53176427e+00 5.47785473e+00 -1.35778265e+01 -2.45366135e+01 -1.14614811e+01 2.34521999e+01 5.77425003e+01 5.81840057e+01 3.98297844e+01 4.39747572e+00 1.13286257e+01 1.78089161e+01 1.92598286e+01 1.37962503e+01 3.13684011e+00 2.69868221e+01 4.12379036e+01 4.67609940e+01 7.48628712e+00 -2.18792706e+01 -3.53129272e+01 -5.46596050e+00 3.20652733e+01 6.80584335e+01 3.93069344e+01 -1.45144539e+01 -3.30106583e+01 -2.21233120e+01 8.05364990e+00 1.01110191e+01 4.40233841e+01 5.65211449e+01 4.69379158e+01 1.81016006e+01 -6.83134270e+00 -2.00385056e+01 -1.30438948e+01 6.06837177e+00 3.30470695e+01 3.29737778e+01 7.63516998e+00 -1.13566608e+01 -2.58973866e+01 -2.28287048e+01 -2.83168468e+01 -3.66640549e+01 -3.96967773e+01 -3.02084827e+01 -2.10092220e+01 -1.26895056e+01 -2.21889305e+01 -2.70869579e+01 -2.67084885e+01 -1.17617416e+01 -1.97512684e+01 -3.26377296e+01 -1.65989819e+01 3.34802485e+00 -3.74146724e+00 -4.37827148e+01 -5.93913231e+01 -3.52208214e+01 -1.86291752e+01 -1.32271614e+01 -8.52545738e+00 1.16340971e+01 1.38163424e+01 2.45243263e+01 1.61167412e+01 1.25148659e+01 -1.13239899e+01 -1.39175406e+01 -1.59122527e+00 -5.52471590e+00 -1.27190552e+01 -2.47462482e+01 -2.74562130e+01 -3.19763317e+01 2.14068675e+00 3.28947754e+01 4.51039734e+01 6.70439863e+00 -1.29823771e+01 -2.44328499e+01 -2.49437199e+01 -3.12734394e+01 -3.24505806e+01 -2.17316132e+01 -3.34410210e+01 -5.27830048e+01 -7.57261810e+01 -7.29292526e+01 -5.84850998e+01 -3.27654381e+01 -3.31476822e+01 -3.77341347e+01 -4.63200455e+01 -4.33138199e+01 -3.51176682e+01 -6.44664307e+01 -9.43247223e+01 -9.35996552e+01 -5.70545883e+01 -1.31550674e+01 -1.01551666e+01 -3.67690353e+01 -7.95358658e+01 -1.80671936e+02 -4.54600311e+02 -6.19631775e+02 -6.51332336e+02 -8.05892944e+02 -2.87709692e+03 -4.14713623e+03 -5.46478943e+02 -2.66634338e+02 7.85812531e+01 -4.98739014e+02 -8.77386621e+03 -2.08308535e+04 829045312. 5.95769344e+09 253882064. -3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.23476855e+03 -3.83377271e+03 -6.12698608e+02 -4.12772766e+02 -1.88964539e+02 -1.36008896e+02 -9.22733994e+01 -4.64535866e+01 -4.93045959e+01 -4.95302505e+01 -4.34809990e+01 -4.62795753e+01 -6.03344269e+01 -7.77909470e+01 -5.87565269e+01 -3.11655121e+01 -2.67104015e+01 -4.74779739e+01 -6.58357086e+01 -5.27669678e+01 -4.62841339e+01 -4.47425232e+01 -4.91555481e+01 -5.83381844e+01 -5.73520355e+01 -5.43336449e+01 -4.36876602e+01 -4.38488770e+01 -3.96275749e+01 -3.90156822e+01 -2.02110538e+01 -3.44473720e+00 -2.80428886e+00 -1.51925974e+01 -2.61717377e+01 -2.28825970e+01 -1.30575247e+01 -9.58068752e+00 -3.06747532e+00 -9.98523355e-01 -2.27727127e+00 2.14252687e+00 2.24723625e+00 -1.00521755e+00 -6.52708960e+00 -1.11130953e+01 -8.55661774e+00 -1.10461922e+01 -1.24191895e+01 -1.08293953e+01 -1.01217823e+01 -4.40664911e+00 -1.63069701e+00 -6.17243433e+00 -2.39465828e+01 -4.50768280e+01 -5.30493546e+01 -4.57376862e+01 -3.42793236e+01 -2.65136318e+01 -3.38906822e+01 -4.34266434e+01 -4.03360023e+01 -2.66501713e+01 -1.16088390e+01 -1.16852493e+01 -1.31455297e+01 -8.09906006e+00 6.44064903e+00 -3.83464170e+00 -2.13041458e+01 -3.90031281e+01 -3.54531708e+01 -2.60481720e+01 -2.55032845e+01 -2.14134064e+01 -1.90900173e+01 -1.60928192e+01 -1.95347633e+01 -2.46991100e+01 -3.29599991e+01 -3.45303688e+01 -3.44933472e+01 -2.86482124e+01 -2.94705086e+01 -3.90938148e+01 -5.11329079e+01 -4.76873703e+01 -3.77958488e+01 -2.85546741e+01 -3.15513687e+01 -3.71091614e+01 -4.34242210e+01 -4.63218880e+01 -3.80730515e+01 -2.49498901e+01 -2.37859077e+01 -2.68599033e+01 -3.83210373e+01 -3.49351578e+01 -3.40936852e+01 -2.77395649e+01 -2.50975666e+01 -2.75560036e+01 -2.76758881e+01 -2.87462330e+01 -2.62937069e+01 -2.86925793e+01 -2.87253704e+01 -2.86969395e+01 -3.25656052e+01 -3.94681587e+01 -3.94396057e+01 -3.30560303e+01 -2.42666187e+01 -2.22747459e+01 -2.10087509e+01 -2.31135292e+01 -2.20742188e+01 -2.06567135e+01 -1.96096401e+01 -2.72464733e+01 -3.73515816e+01 -3.94952698e+01 -3.50294724e+01 -2.77192516e+01 -2.43166351e+01 -2.18535995e+01 -2.17503452e+01 -2.49173870e+01 -2.63556843e+01 -2.50330620e+01 -2.62303791e+01 -2.66125946e+01 -2.74452896e+01 -2.66483498e+01 -2.73689270e+01 -2.76390209e+01 -2.88093605e+01 -2.85564938e+01 -2.89445534e+01 -2.86554852e+01 -2.91321220e+01 -2.93690968e+01 -2.97576122e+01 -2.95603142e+01 -2.94773159e+01 -2.83020782e+01 -2.79020863e+01 -2.74369812e+01 -2.79833145e+01 -2.76573277e+01 -2.74321976e+01 -2.69116440e+01 -2.78788948e+01 -3.07488937e+01 -3.21896095e+01 -3.21584091e+01 -3.10667572e+01 -3.00588989e+01 -2.96492233e+01 -2.91002331e+01 -2.88198948e+01 -2.90809288e+01 -2.89891186e+01 -2.89575653e+01 -2.87395096e+01 -2.87273026e+01 -2.86408653e+01 -2.86200275e+01 -2.89068947e+01 -2.93754005e+01 -2.96149101e+01 -2.93062744e+01 -2.87617931e+01 -2.78755836e+01 -2.80073128e+01 -2.81816807e+01 -2.87085209e+01 -2.86138611e+01 -2.87728729e+01 -2.83035412e+01 -2.85752392e+01 -2.87120419e+01 -2.86480312e+01 -2.81332150e+01 -2.81607456e+01 -2.84405937e+01 -2.86113243e+01 -2.75402317e+01 -2.69812870e+01 -2.66667023e+01 -2.67282562e+01 -2.71776676e+01 -3.04860287e+01 -3.45401382e+01 -3.73603859e+01 -3.74589157e+01 -3.71875763e+01 -3.80500755e+01 -3.48174515e+01 -2.98454819e+01 -2.47279320e+01 -2.35545444e+01 -2.46706867e+01 -2.63713303e+01 -2.68484478e+01 -2.55803833e+01 -2.30041485e+01 -2.42102184e+01 -2.53588486e+01 -2.72291985e+01 -2.67237911e+01 -2.57809353e+01 -2.04216347e+01 -1.34424810e+01 -1.59172983e+01 -2.10354137e+01 -2.84168835e+01 -3.11283836e+01 -3.44024963e+01 -4.11620216e+01 -4.64991226e+01 -4.52633362e+01 -3.99485855e+01 -3.08359051e+01 -3.40135384e+01 -3.67134323e+01 -3.81976547e+01 -3.62690659e+01 -3.36493874e+01 -3.63514214e+01 -3.75633774e+01 -3.78986893e+01 -3.49078407e+01 -3.08446617e+01 -3.12454472e+01 -3.74635086e+01 -4.83462029e+01 -5.72872124e+01 -6.24539032e+01 -4.44182968e+01 -2.57923698e+01 -1.40162659e+01 -2.03915310e+01 -3.04543953e+01 -2.94091396e+01 -3.41056442e+01 -3.05445976e+01 -2.97917728e+01 -2.58631496e+01 -2.51979198e+01 -2.57929554e+01 -2.65786705e+01 -2.73637962e+01 -1.66465855e+01 -3.40281725e+00 5.28050840e-01 -8.63617325e+00 -1.78777409e+01 -2.63103046e+01 -3.41276093e+01 -3.71656075e+01 -3.08019543e+01 -2.85401573e+01 -3.37545738e+01 -3.45748634e+01 -2.72714710e+01 -1.90213966e+01 -1.75926170e+01 -1.76036034e+01 -1.82201385e+01 -2.10900917e+01 -2.27722454e+01 -2.69942341e+01 -2.34302025e+01 -2.03199024e+01 -1.43526545e+01 -1.34401388e+01 -1.61029987e+01 -3.10803204e+01 -5.01316605e+01 -4.72488480e+01 -3.26947594e+01 -1.59368439e+01 -2.37684746e+01 -2.72158451e+01 -3.00980282e+01 -2.98753300e+01 -3.41385269e+01 -3.50129128e+01 -4.63802185e+01 -5.30176353e+01 -5.17754593e+01 -3.34620361e+01 -1.65919838e+01 -1.69618988e+01 -2.02937412e+01 -1.22251501e+01 5.33187246e+00 8.92411804e+00 3.57975698e+00 -1.10477972e+01 -8.12567043e+00 -7.82319450e+00 -9.89733028e+00 -1.29869604e+01 -1.70633698e+01 -1.39028883e+01 -1.04682245e+01 -1.23541498e+01 -1.54938259e+01 -1.36979532e+01 -9.75535393e+00 -1.01916695e+01 -1.49923897e+01 -3.14939079e+01 -4.83686256e+01 -4.61201820e+01 -3.54588203e+01 -2.43922901e+01 -2.85456791e+01 -2.36795540e+01 -1.24032345e+01 -1.30035229e+01 -3.71047440e+01 -6.00655899e+01 -6.29958344e+01 -4.18542480e+01 -2.64762955e+01 -2.76552277e+01 -3.11488552e+01 -3.07450848e+01 -2.85482597e+01 -4.32447472e+01 -6.77731781e+01 -6.94842148e+01 -5.22807770e+01 -2.08319626e+01 -2.48713989e+01 -2.62472172e+01 -3.24374924e+01 -2.67729263e+01 -2.68503017e+01 -3.27172813e+01 -4.14429550e+01 -4.56450500e+01 -3.91118164e+01 -3.55108147e+01 -3.48214417e+01 -5.87529678e+01 -9.00017395e+01 -9.58664169e+01 -7.16691208e+01 -3.94663010e+01 -3.10872421e+01 -2.50011387e+01 -2.82958469e+01 -3.74279289e+01 -6.80560303e+01 -8.95594406e+01 -1.13414490e+02 -1.16257011e+02 -8.85339966e+01 -6.57532272e+01 -3.20846367e+01 -5.48376541e+01 -7.19036560e+01 -5.10951805e+01 -1.08860326e+00 2.58081722e+01 5.01832914e+00 -2.46008663e+01 -2.10336189e+01 -2.05597229e+01 -1.52757473e+01 -1.33705807e+01 -8.48812962e+00 -7.47426891e+00 -5.20742083e+00 -6.72032759e-02 -2.45404029e+00 -3.29902148e+00 -4.08438110e+00 -1.23759592e+00 -3.80647612e+00 -2.00035095e+01 -4.42128983e+01 -4.22944183e+01 -1.90450401e+01 1.19691210e+01 -1.25241070e+01 -4.91262321e+01 -2.68169708e+01 3.18327808e+01 3.84955978e+01 -2.96012764e+01 -7.78997879e+01 -5.83539391e+01 -2.39909554e+01 -4.19349060e+01 -7.45455246e+01 -8.00701675e+01 -6.33442268e+01 -3.67304916e+01 -3.70905876e+01 -4.14056320e+01 -3.09881840e+01 -3.01906300e+01 -2.90175486e+00 1.63443775e+01 -1.75500660e+01 -7.04276810e+01 -1.01506058e+02 -7.80751877e+01 -5.49571037e+01 -7.60883942e+01 -9.34962463e+01 -1.00944016e+02 -8.22169952e+01 -4.98577881e+01 -4.82788467e+01 -4.92403374e+01 -6.06901054e+01 -4.97251320e+01 -6.37711067e+01 -8.73314362e+01 -9.74301224e+01 -9.00335464e+01 -5.28757210e+01 -3.05374413e+01 -1.42201328e+01 -1.60480194e+01 -2.54523277e+01 2.17282906e+01 7.45764465e+01 6.61534653e+01 -2.23001194e+00 -5.39441261e+01 -4.16915550e+01 -1.51756363e+01 -4.06450119e+01 -8.03653030e+01 -8.29188156e+01 -5.80224304e+01 -1.83721161e+01 -1.10418835e+01 -1.24107475e+01 -1.59979143e+01 -2.28114090e+01 -1.85886002e+01 -2.81314621e+01 -4.35556946e+01 -5.37166862e+01 -4.17494545e+01 -2.40028992e+01 -1.47112026e+01 -7.59865379e+00 -9.60715103e+00 2.38811474e+01 5.26315193e+01 2.59711647e+01 -5.03310928e+01 -8.73866806e+01 -5.15678177e+01 -3.12350988e+00 2.56020298e+01 3.93596573e+01 3.91721191e+01 3.01465912e+01 1.58598433e+01 2.06639900e+01 8.44731045e+00 1.43263607e+01 1.72764988e+01 2.79783325e+01 3.86340599e+01 4.07128296e+01 2.13084545e+01 -2.98489809e-01 3.84067273e+00 2.82812099e+01 4.13580360e+01 1.79275532e+01 -3.65919948e+00 -1.70618782e+01 -3.60620728e+01 -7.63605194e+01 -7.80378647e+01 -6.00140762e+01 -4.81870537e+01 -1.14922798e+02 -1.60207367e+02 -1.29743790e+02 -7.40793762e+01 -8.07121658e+01 -1.27972130e+02 -1.41160370e+02 -1.00026833e+02 -6.12243385e+01 -5.39131851e+01 -5.40646782e+01 -6.68583374e+01 -7.24113083e+01 -7.17487640e+01 -5.41279564e+01 -6.88225861e+01 -1.09612961e+02 -1.26543060e+02 -1.03764137e+02 -5.74833031e+01 -6.39516678e+01 -9.31416473e+01 -6.08267670e+01 -4.62869167e+00 3.30920486e+01 9.36844921e+00 -1.43283558e+01 -3.51195312e+00 -2.84931469e+00 -5.95336533e+00 -8.15755558e+00 -1.83316588e+00 -6.63242292e+00 -1.41135941e+01 -6.69553661e+00 2.99657893e+00 1.22903795e+01 8.01241779e+00 -4.63165426e+00 -7.61423886e-01 -3.84400139e+01 -6.46474152e+01 -6.40965271e+01 -1.92144775e+01 2.43595104e+01 3.30689468e+01 2.91573296e+01 5.64675522e+01 9.48220062e+01 9.91906738e+01 7.47806015e+01 3.81904068e+01 3.00014668e+01 2.13820229e+01 -3.05698338e+01 -8.26849670e+01 -9.77857361e+01 -6.42566605e+01 -2.81318951e+01 -2.46750698e+01 -1.26836395e+01 -4.38595533e+00 -1.61994858e+01 5.03411531e+00 4.84359283e+01 3.71259613e+01 -1.52818899e+01 -5.74498901e+01 -3.13021030e+01 -3.40224266e+01 -1.06628014e+02 -1.56954803e+02 -1.40392624e+02 -6.05416451e+01 -3.73224602e+01 -6.43457947e+01 -7.54733429e+01 -4.90789452e+01 7.57913685e+00 -4.36387599e-01 -3.12976665e+01 -4.89134331e+01 -3.11085854e+01 9.13961983e+00 3.33480148e+01 4.88429565e+01 4.97369156e+01 3.31782761e+01 3.38966484e+01 4.40500221e+01 1.21456947e+01 -2.33327446e+01 -4.51784897e+01 -1.47156410e+01 1.60725422e+01 8.64035988e+00 -2.47168369e+01 1.69585919e+00 1.67263199e+02 2.89870941e+02 4.87984375e+02 4.68632599e+02 3.16217651e+03 5.05980615e+03 -4.56781738e+03 -2.52883276e+03 2.64771094e+03 1.06806628e+03 3.01941162e+03 3.11157012e+04 -5.13050293e+03 3.77181978e+09 1.39022500e+05 1583832192. 2.60913623e+10 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. -5.72994478e+10 5.50336289e+04 1.51437617e+04 1.63462268e+03 1.01430029e+03 3.55508838e+03 1.98860083e+03 -2.87865295e+02 2.16272369e+02 3.48247711e+02 8.60936646e+02 7.70141968e+02 5.44504578e+02 2.12840637e+02 1.48561768e+02 2.51886826e+02 2.93618225e+02 5.25230591e+02 6.63090820e+02 4.22833527e+02 1.06030182e+02 -2.95019760e+01 -7.39602890e+01 -4.91843948e+01 -6.64561920e+01 -1.37942581e+02 -1.33263992e+02 -8.29400330e+01 -2.88375702e+01 -8.13648987e+01 -1.97414566e+02 -2.17675278e+02 -1.29417023e+02 -3.06278439e+01 1.35224581e+01 2.71692824e+00 3.06866112e+01 7.56901627e+01 9.94819489e+01 3.58888168e+01 -1.29467499e+02 -2.16423691e+02 -1.71062531e+02 -5.52673683e+01 1.68818264e+01 1.38567228e+01 -1.65413647e+01 -6.49083939e+01 -3.63009911e+01 -5.64706001e+01 -7.04951096e+01 -5.90552216e+01 3.51564102e+01 1.41500229e+02 1.29434753e+02 -1.76721630e+01 -9.93834229e+01 -6.61022186e+01 2.49302044e+01 1.70117474e+01 -5.65635071e+01 -6.12434082e+01 1.45320864e+01 9.63139420e+01 7.31783600e+01 -5.48404541e+01 -1.37713074e+02 -1.03135841e+02 -3.11275883e+01 -1.37283440e+01 -3.97905312e+01 -3.44252510e+01 2.27434654e+01 7.63748856e+01 5.03855400e+01 1.51759710e+01 2.83203831e+01 7.71707458e+01 9.21344833e+01 7.07272873e+01 2.14641781e+01 -2.77854195e+01 -4.62825737e+01 -1.33509245e+01 1.45724907e+01 1.61226501e+01 6.19221878e+01 1.44849426e+02 1.72418930e+02 9.15539703e+01 -4.61676750e+01 -1.13732475e+02 -6.95990524e+01 3.63627930e+01 1.43272263e+02 1.78727448e+02 1.50456680e+02 1.18440117e+02 1.27803986e+02 9.89961700e+01 2.44187951e+00 -6.73486557e+01 -3.68539085e+01 3.84289398e+01 6.63579178e+01 3.57078323e+01 -2.47020721e+01 -4.00425072e+01 2.88992119e+00 3.93827820e+01 2.66374378e+01 1.64350700e+01 6.51011353e+01 1.54849075e+02 1.66446930e+02 9.53865891e+01 1.81741199e+01 1.91214275e+01 7.10577316e+01 1.22372536e+02 1.22563751e+02 8.01607513e+01 1.74445553e+01 -4.59199953e+00 2.20094852e+01 2.56899204e+01 -1.63159161e+01 -2.85275288e+01 2.09282513e+01 8.50316010e+01 8.37590103e+01 2.42388039e+01 -1.43092566e+01 3.06113205e+01 5.87101593e+01 7.00791321e+01 3.36550064e+01 5.43785400e+01 1.10130714e+02 1.22735893e+02 5.73950882e+01 -6.96108704e+01 -1.30504303e+02 -7.81687088e+01 -4.78701973e+00 2.54067345e+01 2.00330183e-01 -2.42350426e+01 -1.70504360e+01 -1.91464558e+01 -5.31948929e+01 -1.00754997e+02 -1.20799583e+02 -5.98746834e+01 4.89457550e+01 1.04864281e+02 4.56959114e+01 -2.43767910e+01 -2.28258495e+01 1.36030474e+01 -1.72629890e+01 -9.90202332e+01 -8.79552536e+01 -1.14889288e+01 6.20358505e+01 4.48244667e+00 -1.16812073e+02 -1.81198654e+02 -1.36228378e+02 -5.22737198e+01 -8.65168190e+00 -1.27950096e+01 9.33541870e+00 2.45496006e+01 4.64743376e+00 -6.18323288e+01 -1.35304489e+02 -9.26350861e+01 -2.14781799e+01 5.07099075e+01 3.90747414e+01 1.63109398e+00 -4.69359436e+01 -7.22699432e+01 -7.56412430e+01 -8.66328354e+01 -1.21931030e+02 -9.33730011e+01 -2.24284172e+01 4.95443878e+01 2.30485744e+01 -4.99963150e+01 -1.05141571e+02 -7.53310852e+01 -1.99953823e+01 7.83455324e+00 -1.75995815e+00 2.14090309e+01 8.23439484e+01 1.07667465e+02 4.81992455e+01 -4.85724907e+01 -6.47199554e+01 -3.62982254e+01 4.27883415e+01 5.25883636e+01 5.15965424e+01 2.20024185e+01 2.41723537e+00 1.46938846e-01 -2.46943073e+01 -5.26582451e+01 -2.93475437e+01 1.85500164e+01 4.76678352e+01 4.29831123e+01 5.77118063e+00 -1.19712868e+01 -5.60341740e+00 6.72366381e-01 6.01923752e+00 -1.35896215e+01 1.71401272e+01 5.71404877e+01 7.56424484e+01 7.66993713e+01 1.25978451e+01 -2.24437256e+01 -2.35250497e+00 5.82955894e+01 6.84747238e+01 2.74360237e+01 -1.26961565e+01 -2.22425246e+00 2.47196579e+01 2.15353603e+01 -1.27912474e+01 -2.36638966e+01 1.68015156e+01 4.43590431e+01 2.61242256e+01 2.38860488e+00 2.68089695e+01 3.57264977e+01 1.46566114e+01 -7.33741426e+00 -2.49191055e+01 -3.63640404e+00 -2.28164272e+01 -2.79969158e+01 -2.61429195e+01 -4.08470306e+01 -6.02089691e+01 -7.51546936e+01 -2.15390701e+01 1.32903230e+00 5.29266739e+00 -3.34202118e+01 -1.97472935e+01 -1.25987701e+01 -2.73149567e+01 -5.64569588e+01 -6.88037491e+01 -1.50449295e+01 1.91636791e+01 3.06177540e+01 -1.27720270e+01 -2.46284485e+01 -2.36963177e+01 -8.29984093e+00 -5.40431595e+00 -3.79069824e+01 -2.53858566e+01 -8.04485321e+00 3.69291916e+01 5.15071678e+01 4.06044083e+01 4.56285238e+00 -2.31036549e+01 -1.24285720e-01 3.08695278e+01 4.41774940e+01 2.66407413e+01 4.45389252e+01 4.60981369e+01 2.09362259e+01 -1.79339981e+01 -1.64134579e+01 3.01561012e+01 4.80418129e+01 2.43142624e+01 -1.60404739e+01 -5.65053940e+00 1.76295433e+01 2.79163685e+01 1.87661304e+01 -2.64199090e+00 -8.73721027e+00 -1.58055897e+01 9.74373913e+00 3.03821316e+01 3.36557426e+01 9.09509182e+00 -4.40719366e+00 8.17683983e+00 2.79066753e+01 3.26562424e+01 4.19876938e+01 7.23805084e+01 8.84167709e+01 8.38289108e+01 7.56969452e+01 7.65143051e+01 9.25594864e+01 9.27792053e+01 7.74345322e+01 4.05133133e+01 2.60057087e+01 2.04736843e+01 2.69399719e+01 2.18442459e+01 4.18549681e+00 -9.74545002e+00 -1.66015301e+01 7.98791075e+00 2.00012131e+01 2.54583588e+01 1.69385223e+01 2.53227997e+01 3.32065544e+01 4.28087692e+01 3.68161430e+01 3.85081596e+01 5.42812996e+01 6.37256699e+01 5.40578346e+01 3.25390739e+01 2.99589252e+01 3.13850307e+01 9.16833687e+00 -7.62731600e+00 -1.97709503e+01 2.62008691e+00 5.66342974e+00 1.37683363e+01 2.72102222e+01 2.90542393e+01 1.43911304e+01 -1.44736691e+01 -2.14730759e+01 2.60404444e+00 2.19003868e+01 1.92551346e+01 7.93121576e-01 -1.35660553e+01 -2.51069570e+00 1.24754810e+01 2.90633202e+01 2.56922779e+01 1.08615675e+01 -2.67496109e+00 -1.88787670e+01 -1.92242985e+01 -1.89220676e+01 -2.21142941e+01 -2.24521236e+01 -2.21176949e+01 -7.35506654e-01 1.10226715e+00 2.43986964e+00 9.64942276e-01 -1.78875268e+00 -1.14795914e+01 -4.01906853e+01 -4.42405548e+01 -2.65864944e+01 8.96145535e+00 2.65600700e+01 6.58824158e+00 -1.74339466e+01 -2.05535164e+01 7.25260448e+00 3.37431297e+01 2.65161610e+01 1.74356031e+00 -1.32839956e+01 -1.12960091e+01 3.39934039e+00 2.26006079e+00 -7.14614296e+00 -1.52821989e+01 -1.61359482e+01 -2.54233813e+00 -1.25122321e+00 -7.12766552e+00 -1.34555178e+01 -1.36334124e+01 -6.09318924e+00 -8.42350006e+00 -8.18115139e+00 2.18964410e+00 1.49055481e+01 1.31421938e+01 -7.05297089e+00 -2.01775093e+01 -1.51739483e+01 -2.34810412e-01 7.33468485e+00 5.15714073e+00 -2.76838279e+00 -6.12354088e+00 -7.87761450e+00 -1.65581477e+00 -1.81186914e+00 -2.40573454e+00 -4.87143278e+00 -5.79687262e+00 -1.85948002e+00 1.38383746e+00 6.15090513e+00 6.10306072e+00 3.37203526e+00 -6.73282802e-01 -5.79963398e+00 -6.97509623e+00 -3.29753280e+00 3.25202346e+00 6.07386017e+00 3.12827611e+00 -1.98113692e+00 -3.03112364e+00 8.57274607e-03 2.99201465e+00 2.40561843e+00 3.39814097e-01 -3.82521033e-01 -1.93289861e-01 -2.13131565e-03 -8.10442790e-02 1.32928938e-01 8.23659480e-01 1.87303674e+00 2.25302577e+00 3.40734434e+00 3.65422988e+00 2.48093629e+00 -4.84859973e-01 -1.77953231e+00 9.16428566e-01 4.16468573e+00 3.40811944e+00 -2.07121158e+00 -7.16350937e+00 -5.75364971e+00 3.68189633e-01 2.93000603e+00 5.22286117e-01 -5.29291821e+00 -4.66883373e+00 9.56806600e-01 6.84898281e+00 1.13435249e+01 6.64457989e+00 7.27764177e+00 4.28587866e+00 5.08960915e+00 6.21655798e+00 8.35478687e+00 1.42253571e+01 9.12864685e+00 1.73059809e+00 -7.93841982e+00 -2.66311383e+00 1.05541306e+01 2.11587658e+01 1.25618687e+01 -3.49676037e+00 -1.44254274e+01 -1.35531397e+01 -1.21106517e+00 3.65211368e+00 7.11517811e+00 8.85725677e-01 4.06627512e+00 1.09583712e+01 1.95945892e+01 2.93937721e+01 2.59251575e+01 1.12986670e+01 -3.04003000e+00 -5.53995800e+00 -8.66882354e-02 7.66769791e+00 1.97383461e+01 2.72510300e+01 1.28290682e+01 -1.36291208e+01 -2.66331844e+01 -8.53146648e+00 1.63177509e+01 1.67534790e+01 -1.17203245e+01 -4.21680603e+01 -3.54672318e+01 -1.02257156e+00 3.26730843e+01 4.44112930e+01 2.40097218e+01 6.43504715e+00 5.14739323e+00 1.43322449e+01 2.20250130e+01 9.11700153e+00 1.17689514e+01 7.71399784e+00 -2.61228609e+00 -9.28976154e+00 -8.77791786e+00 1.02542744e+01 8.87129498e+00 -1.41617956e+01 -4.16119843e+01 -3.78881264e+01 5.39958048e+00 4.00674324e+01 2.98615284e+01 -9.82565308e+00 -3.90180244e+01 -3.85926018e+01 -3.63459897e+00 2.95210915e+01 4.39559059e+01 1.81305275e+01 -8.38215351e-02 -1.69305420e+01 -1.86969872e+01 -1.29991312e+01 -1.43648920e+01 -1.26701422e+01 -3.71301804e+01 -5.10621948e+01 -4.99582329e+01 -3.11760540e+01 6.18805885e+00 1.63187733e+01 -4.05758095e+00 -4.16951714e+01 -5.10521393e+01 -2.98198013e+01 4.35868645e+00 3.08557773e+00 -2.10258236e+01 -5.74024124e+01 -6.26044884e+01 -2.46580906e+01 1.59393282e+01 3.18845673e+01 -2.54477549e+00 -3.60070953e+01 -3.45966263e+01 -8.58469009e+00 2.07913551e+01 2.37549686e+01 2.10699978e+01 6.85890293e+00 -1.86798229e+01 -2.42162971e+01 -6.30172312e-01 4.75468674e+01 6.94779282e+01 3.88236732e+01 -1.14576888e+00 -3.09186993e+01 -1.23024826e+01 1.81284561e+01 3.86065483e+01 3.25243607e+01 7.89813137e+00 3.35125685e+00 2.05247707e+01 4.56005363e+01 5.26198311e+01 1.77768612e+01 -1.24766521e+01 -6.45504236e+00 1.84386311e+01 5.92676010e+01 5.47558556e+01 5.33994293e+01 3.72912521e+01 1.40373449e+01 1.47177947e+00 -3.21159148e+00 3.45290337e+01 6.00796356e+01 4.14991798e+01 7.86917543e+00 -2.18326435e+01 5.53666258e+00 4.32035217e+01 6.10922775e+01 2.22466812e+01 -6.01519890e+01 -9.18540115e+01 -5.14144707e+01 4.45860710e+01 9.07499695e+01 5.55210342e+01 -1.36312351e+01 -4.20399551e+01 -7.12135773e+01 -1.30894730e+02 -7.77431641e+01 1.35091782e+02 1.45229660e+02 -1.12947762e+02 -1.94889172e+03 -2.51649829e+03 -4.26926318e+03 -1.00683184e+04 -1.13229046e+10 2.03060879e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -914026496. -423721024. -2.42461992e+04 -8.56551270e+03 -7.65737183e+02 -1.05972061e+02 -4.78749573e+02 -1.83614365e+02 -5.92792091e+01 -3.79746753e+03 -2.48620337e+03 -4.81401855e+02 -3.43190216e+02 1.52889160e+03 -1.51519947e+01 -1.40126636e+03 1.50766937e+02 -3.82153625e+01 -2.51107559e+02 -2.54993118e+02 -1.70555649e+02 -1.80084641e+02 -1.31495224e+02 -6.58641052e+01 -1.28486452e+01 -7.57472515e+00 -3.03670177e+01 1.22134724e+01 2.97773113e+01 -3.01886158e+01 -8.11158295e+01 -3.61602631e+01 8.67799606e+01 1.56104553e+02 7.63752060e+01 -2.19500504e+01 -8.11751556e+01 -4.60826149e+01 6.09207726e+01 1.48585983e+02 1.81503464e+02 9.79811096e+01 3.29730072e+01 2.62659702e+01 8.97229004e+01 1.28127121e+02 9.14812927e+01 7.79124451e+01 4.11615562e+01 2.14571095e+00 -1.77872810e+01 2.31494102e+01 1.37864471e+02 1.51027084e+02 5.26981430e+01 -6.69962082e+01 -9.81090088e+01 1.98893398e-01 9.51117783e+01 9.14306259e+01 1.89912319e+01 -1.44709082e+01 6.43337555e+01 1.71151367e+02 1.99711258e+02 1.46603882e+02 2.92608967e+01 -5.19219780e+01 -4.69134789e+01 2.75113010e+01 1.25118828e+02 1.89256882e+02 2.20881226e+02 1.97786301e+02 1.32598938e+02 7.14122162e+01 4.07100525e+01 7.00959396e+01 5.63226738e+01 -1.73595695e+01 -9.15533142e+01 -8.82624207e+01 2.76756620e+00 7.83022156e+01 5.85789566e+01 1.47951899e+01 -5.49935570e+01 -9.05596390e+01 -5.13064499e+01 4.64694786e+01 1.03320824e+02 4.72181473e+01 -2.37978668e+01 -1.08602924e+01 1.84561253e+01 3.64905815e+01 6.52284384e+00 3.72575874e+01 3.17422104e+01 -5.21931553e+00 -3.24301453e+01 -1.05022001e+00 1.08528503e+02 1.25836800e+02 1.81271744e+01 -1.19472267e+02 -1.79614059e+02 -8.55999908e+01 1.56488285e+01 6.04286003e+01 3.55346756e+01 -1.57143521e+00 -1.11757827e+00 2.91277466e+01 9.14212570e+01 1.22606400e+02 5.93466644e+01 -5.52187576e+01 -8.80358124e+01 -4.19531898e+01 2.39438033e+00 6.51071644e+00 4.47706299e+01 3.71157722e+01 -4.68041801e+01 -1.54389359e+02 -1.43347855e+02 -7.67769480e+00 5.92002640e+01 -2.26231117e+01 -1.38541656e+02 -1.59762100e+02 -4.81134033e+01 6.28623886e+01 8.96797104e+01 5.08428001e+01 -4.00993843e+01 -1.11595192e+02 -9.19999924e+01 4.83353615e+00 8.01182175e+01 2.11006126e+01 -8.09306335e+01 -1.18143089e+02 -8.75263138e+01 -3.76033745e+01 -4.81078100e+00 5.92532730e+01 8.65772629e+01 5.54466553e+01 4.47075367e+00 -8.74716568e+00 6.55251007e+01 9.98273163e+01 3.91358337e+01 -1.03347527e+02 -1.98605896e+02 -1.59112961e+02 -2.50963707e+01 7.85343323e+01 6.87267685e+01 -8.81656766e-01 -2.90184708e+01 -2.69764066e+00 1.09384527e+01 5.53218269e+01 3.51454315e+01 2.40404243e+01 -2.66163216e+01 -9.01433258e+01 -1.28437820e+02 -1.43033340e+02 -5.58847389e+01 -1.24099360e+01 -6.65119171e+01 -1.26452316e+02 -9.36478195e+01 3.13980675e+01 9.88473053e+01 4.92907867e+01 -5.01804304e+00 -4.98527031e+01 -4.15532150e+01 -8.02084732e+00 1.35800142e+01 2.29003353e+01 -4.80522804e+01 -3.88178368e+01 6.63215351e+00 7.77178650e+01 1.55762863e+02 1.97073853e+02 2.39349442e+02 1.62691101e+02 4.00371437e+01 -2.41342754e+01 -2.63736210e+01 4.66479950e+01 4.69027634e+01 -1.61707191e+01 -1.04549286e+02 -1.51196838e+02 -4.39729385e+01 9.12808151e+01 1.71073532e+02 1.33305679e+02 6.84425049e+01 4.42011948e+01 5.08456993e+01 7.32036362e+01 1.08542183e+02 7.37444229e+01 1.20798626e+01 -3.60289497e+01 8.16837025e+00 3.00519791e+01 5.01723671e+01 8.06228561e+01 9.81480179e+01 6.30584679e+01 2.36357136e+01 2.71516533e+01 3.05174675e+01 -9.06958580e+00 -7.13600769e+01 -1.11718842e+02 -1.17186058e+02 -5.04270821e+01 -7.35452652e+00 7.00916214e+01 7.56939240e+01 2.76591377e+01 -5.38339958e+01 -7.08961868e+01 -1.46990919e+01 2.28292274e+01 1.45716057e+01 7.04327917e+00 8.38721275e+00 -3.78709555e+00 -8.09879017e+00 -7.70603371e+00 3.12314415e+00 4.60814762e+00 -7.10834980e+00 -1.83041840e+01 -3.99020538e+01 -3.72108688e+01 -3.23546410e+01 -8.07412815e+00 -2.36198082e+01 -3.49303474e+01 -3.13590164e+01 -6.59160328e+00 3.17054119e+01 5.16965218e+01 4.26609192e+01 2.77937622e+01 -4.69165277e+00 8.59826946e+00 5.38821888e+00 6.40935421e+00 -1.46966591e+01 -1.75637321e+01 -1.31534567e+01 2.05551219e+00 -1.31275425e+01 -1.53169937e+01 -2.19557781e+01 -1.19535666e+01 -2.48476906e+01 -2.65364380e+01 -4.07884598e+01 -5.03727264e+01 -4.93547592e+01 -3.13794689e+01 -9.54046249e+00 -9.12117672e+00 -1.88501530e+01 -3.98220329e+01 -3.46801567e+01 -2.84578362e+01 -1.99232602e+00 1.00922232e+01 -8.95421410e+00 -2.39019413e+01 -2.16571083e+01 5.16840172e+00 6.63461018e+00 -3.99745345e+00 4.50980949e+00 5.93599224e+00 -8.78390789e+00 -2.38183689e+01 -1.02636604e+01 4.56347287e-01 -1.77887421e+01 -1.52780371e+01 6.67804050e+00 3.67333221e+01 2.70719242e+01 2.20785351e+01 2.20717258e+01 2.17403431e+01 2.71267014e+01 2.45592270e+01 2.78088856e+01 9.23965359e+00 7.02828121e+00 1.67441578e+01 1.34384289e+01 4.34698963e+00 -9.85356331e+00 -2.36483741e+00 -2.85795536e+01 -5.72208290e+01 -4.84962540e+01 -2.39291515e+01 8.04517460e+00 6.73611546e+00 5.58692312e+00 2.01202226e+00 -9.06771660e+00 5.96288157e+00 1.34014959e+01 2.12525616e+01 1.72033024e+01 3.29593010e+01 3.33067780e+01 1.44864111e+01 5.25943089e+00 2.76667571e+00 6.35255241e+00 -1.95097208e+00 4.31374502e+00 1.80002308e+01 1.92707500e+01 3.26660042e+01 3.19942837e+01 2.31437092e+01 2.92539167e+00 -1.54169817e+01 -9.98253822e+00 -2.40316010e+00 1.64574490e+01 2.38434887e+01 2.33652544e+00 -1.06500778e+01 -6.20776606e+00 1.51978207e+01 2.15706177e+01 1.15469017e+01 -5.41258216e-01 -1.07271290e+01 -1.27194273e+00 -3.51860595e+00 -9.12244034e+00 -3.68229027e+01 -3.08844299e+01 -2.38738823e+01 -2.25064063e+00 -5.54180861e+00 -6.70843554e+00 -8.75168610e+00 7.29180861e+00 -3.21757603e+00 -1.51738520e+01 -2.73339863e+01 -1.51363182e+01 -4.62361783e-01 -3.99664354e+00 -2.99647808e+01 -6.76520004e+01 -5.92094536e+01 -2.96245346e+01 9.76475716e+00 -1.61744308e+01 -4.39059639e+01 -5.44369202e+01 -3.24411736e+01 -5.39232302e+00 -1.14068899e+01 -3.35935898e+01 -4.68345337e+01 -4.66532860e+01 -3.68690414e+01 -4.46191483e+01 -6.13080978e+01 -6.71585312e+01 -4.64142838e+01 -1.55203514e+01 -5.10344744e+00 -2.04088020e+01 -2.90786896e+01 -1.79155903e+01 -2.99661851e+00 -8.51615191e-01 -3.54529495e+01 -6.22733421e+01 -6.17343483e+01 -3.16095963e+01 2.34104171e-02 6.29391015e-01 -9.75947762e+00 -5.97218657e+00 1.85605793e+01 5.79969482e+01 5.44077873e+01 2.45723228e+01 -5.75448847e+00 -1.15294209e+01 -1.36485682e+01 -3.61975784e+01 -4.63167496e+01 9.38578904e-01 5.38725166e+01 6.15268440e+01 1.96495018e+01 -1.82438908e+01 -1.26437359e+01 -6.46934700e+00 1.85980072e+01 3.63502922e+01 2.90121784e+01 2.00901294e+00 -2.92333813e+01 -2.82754402e+01 -3.67310410e+01 -4.38706160e-01 4.19606171e+01 5.17419243e+01 2.65053921e+01 -1.27379303e+01 -4.00541344e+01 -5.90096245e+01 -6.33229980e+01 -3.22522659e+01 -1.56102791e+01 -9.89716232e-01 2.04076603e-01 -4.76110764e-02 9.40755653e+00 1.17587719e+01 1.04764452e+01 9.26726246e+00 1.32657373e+00 -3.97754021e+01 -1.48105316e+02 -2.55180847e+02 -2.45441055e+02 -2.36387451e+02 -1.99542374e+02 -3.70441956e+02 -1.81709183e+02 -1.98053932e+01 5.21529968e+02 -2.30579834e+03 -5.16046082e+02 -3.38795361e+03 -4.38676406e+04 -3.41135488e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.94549770e+10 -8.94549770e+10 993453312. -2.62259121e+04 -7.58207861e+03 -8.43289551e+02 -6.01180359e+02 -1.24290596e+02 -6.72395325e+01 -4.55873833e+01 -4.31550789e+01 2.15570068e+01 9.25956573e+01 1.32547241e+02 9.83896713e+01 5.51155510e+01 6.67156754e+01 6.20307884e+01 -2.79882715e+03 -1.93659424e+03 -4.39669647e+02 -1.80518265e+02 -1.18119827e+02 -9.30019379e+01 -7.90624008e+01 -5.88001366e+01 -2.09264107e+01 -1.27560625e+01 -5.85960925e-01 -7.29495287e-01 9.83876133e+00 1.15975895e+01 1.95492439e+01 2.27134304e+01 2.45490780e+01 2.59365082e+01 2.15039597e+01 2.27302685e+01 2.51005440e+01 3.12651329e+01 3.78715477e+01 3.12726574e+01 2.10609989e+01 1.66288414e+01 1.81045513e+01 2.34333439e+01 2.67146759e+01 3.08067989e+01 2.63360882e+01 7.85191298e+00 -1.12138262e+01 -1.32446728e+01 -4.75160074e+00 3.05240130e+00 5.03862667e+00 1.21158571e+01 1.22876472e+01 7.70191765e+00 5.28543043e+00 8.33219433e+00 1.24348402e+01 1.46846008e+01 2.47513123e+01 1.57833834e+01 6.66859245e+00 -2.83579707e+00 -6.91611338e+00 -1.16567688e+01 -1.50067625e+01 -8.17704201e+00 -2.55953622e+00 -1.86919928e+00 2.75970221e+00 1.56078997e+01 1.97765007e+01 1.58051939e+01 5.36146116e+00 1.60405433e+00 1.33609235e+00 -9.11890984e+00 -2.20354958e+01 -2.06665649e+01 -1.35741510e+01 -5.53002834e+00 -2.28725128e+01 -3.64660454e+01 -3.56537590e+01 -2.33744106e+01 -1.46761894e+01 -1.74343987e+01 -1.91038647e+01 -1.59291162e+01 -1.69376907e+01 -2.39158306e+01 -3.20534668e+01 -2.83287239e+01 -1.34362078e+01 -7.85399556e-01 4.80570126e+00 1.78697622e+00 -1.28552806e+00 -5.76579905e+00 1.41141212e+00 9.76297855e+00 5.30094624e+00 -5.19782543e+00 -8.84960747e+00 -3.77733678e-01 5.85004711e+00 -6.35000372e+00 -1.45678587e+01 -1.40015316e+01 -1.16616797e+00 9.88150692e+00 1.17923937e+01 9.82609272e+00 6.52386284e+00 4.88211584e+00 2.71237111e+00 1.53364885e+00 3.07448649e+00 2.79803085e+00 2.08621129e-01 -2.47298551e+00 -9.68973875e-01 9.04963017e-01 1.69677055e+00 1.03925860e+00 7.29083598e-01 -6.56776476e+00 -1.36421967e+01 -1.25292072e+01 -5.39549351e+00 1.02575076e+00 -5.57095051e+00 -1.15282488e+01 -1.19097252e+01 -6.88542271e+00 -2.46312189e+00 -2.10805154e+00 -1.45854282e+00 5.32963812e-01 -8.02410364e-01 -1.25066614e+00 -1.69138932e+00 6.27952814e-01 2.45802116e+00 1.62501061e+00 1.56990796e-01 -1.01144552e+00 -7.14374006e-01 -5.19383907e-01 -9.06584501e-01 -2.32682610e+00 -5.50520325e+00 -8.91196537e+00 -8.31752682e+00 -5.66397524e+00 -2.11013293e+00 -4.18934822e+00 -6.33986521e+00 -6.06992435e+00 -2.55431342e+00 -3.24022658e-02 -3.93518180e-01 -1.02952778e+00 -1.34055114e+00 -9.25918937e-01 -8.08418095e-01 -6.59831107e-01 -2.94139773e-01 -2.08181188e-01 -5.80679536e-01 -9.95993674e-01 -7.21249342e-01 -2.83998132e-01 -1.65107902e-02 -1.86920370e-04 -8.94319918e-03 2.09051147e-01 6.78186953e-01 8.53105962e-01 6.18343353e-01 3.71796250e-01 4.84289914e-01 1.02955624e-01 7.73759723e-01 2.41158509e+00 3.32406116e+00 2.50068855e+00 8.11975539e-01 6.44481778e-01 9.11870539e-01 7.84944832e-01 7.19896376e-01 1.42926621e+00 1.71992087e+00 5.07636595e+00 7.97215557e+00 7.99625301e+00 4.62168646e+00 1.64701998e+00 3.28077960e+00 3.39268446e+00 6.68406010e+00 9.88978767e+00 9.68773842e+00 4.44454241e+00 -8.77236247e-01 7.16868043e-01 2.12360620e+00 3.10984826e+00 1.51541865e+00 -3.76764119e-01 -1.17103732e+00 -1.53768265e+00 -6.99534893e-01 -2.22043589e-01 -9.04674590e-01 -5.93635261e-01 -4.90437841e+00 -7.44306135e+00 -9.59271431e+00 -8.66245079e+00 -6.13283253e+00 -5.43054008e+00 -5.27652836e+00 -5.87441444e+00 -5.94141340e+00 -4.73655653e+00 -6.52366257e+00 -5.50563431e+00 -4.43389654e+00 -4.49012518e+00 -8.34743595e+00 -9.49709034e+00 -7.29595089e+00 -4.45633173e+00 -4.41588879e+00 -5.57844925e+00 -2.96952462e+00 -2.88726282e+00 1.02289200e+00 1.32144606e+00 1.30239391e+00 -4.74170208e+00 -1.20973368e+01 -6.41727686e+00 7.42087936e+00 1.65200348e+01 1.34361906e+01 6.13087130e+00 3.93726158e+00 5.36873579e+00 6.56648111e+00 1.01660099e+01 1.08564911e+01 9.12732506e+00 6.82628822e+00 3.15246105e+00 1.36642335e-02 -2.48796701e+00 7.43094981e-02 4.27462244e+00 6.52037287e+00 5.79080582e+00 4.68790817e+00 5.55877066e+00 2.19583797e+00 2.10469246e+00 -1.59078225e-01 4.29353476e+00 1.49082022e+01 2.69801712e+01 2.78081608e+01 2.00119419e+01 8.21526432e+00 4.51480818e+00 2.26394296e+00 1.07899313e+01 1.89097157e+01 2.35763130e+01 2.49538422e+01 1.60126152e+01 8.13281631e+00 -3.67654157e+00 1.42546415e-01 4.58501577e+00 5.50253010e+00 2.81833839e+00 -1.55639517e+00 -3.74580932e+00 2.91019827e-01 9.85897350e+00 1.46402063e+01 1.56378183e+01 1.31414289e+01 2.62866592e+01 3.90196228e+01 3.30693283e+01 1.59565201e+01 1.73210371e+00 1.17674637e+01 1.72807484e+01 1.54973383e+01 1.21812735e+01 2.32532005e+01 3.83908691e+01 3.64094772e+01 1.58904285e+01 -5.18880463e+00 -7.06265926e-01 8.59805012e+00 9.72902966e+00 6.52464867e-01 -2.71980405e+00 -5.43380141e-01 8.54438305e+00 2.71852756e+00 -6.91213608e+00 -1.02810469e+01 -7.66594362e+00 -4.28034639e+00 -1.04479189e+01 5.51081276e+00 2.40720024e+01 2.62948246e+01 3.11462326e+01 4.21014900e+01 6.13302689e+01 6.27929649e+01 5.22562866e+01 5.45424957e+01 4.12557411e+01 3.93690529e+01 2.03860149e+01 1.40809774e+00 -2.24612255e+01 -2.80619373e+01 -2.02323780e+01 -1.59174862e+01 -1.03300877e+01 -1.05366154e+01 -9.37120438e+00 -1.28560057e+01 -1.59676542e+01 2.56388640e+00 3.10793667e+01 4.15893135e+01 3.23607407e+01 1.24251127e+01 5.94157696e+00 2.93238163e+00 -7.17004156e+00 4.51883984e+00 6.04241943e+00 1.46928701e+01 1.79397831e+01 3.31976357e+01 5.45554886e+01 4.02990532e+01 1.76554470e+01 1.00895529e+01 3.65263672e+01 4.38572845e+01 3.14152260e+01 3.30355501e+00 2.33733749e+01 4.43101807e+01 5.69758263e+01 3.92388306e+01 2.10730839e+01 4.40040817e+01 6.26967697e+01 5.48241692e+01 1.79954967e+01 -4.47862196e+00 1.80338459e+01 3.07876778e+01 7.64346075e+00 -2.43112812e+01 -4.02006954e-01 4.56291733e+01 6.28928413e+01 4.83142166e+01 2.87030792e+01 3.31443596e+01 5.67857170e+01 8.23110123e+01 7.40447998e+01 3.36660614e+01 -2.09683704e+00 -4.04066849e+00 3.89953804e+00 1.01616850e+01 9.52285004e+00 1.13904390e+01 1.53515081e+01 3.19469261e+01 3.47365341e+01 1.52281666e+01 4.52128935e+00 -2.39501095e+00 2.72728767e+01 3.99225845e+01 3.44615974e+01 2.26819439e+01 4.61368370e+00 8.28443527e+00 3.14877439e+00 -8.10219669e+00 -1.72601738e+01 -1.29476957e+01 3.79349785e+01 7.63170090e+01 3.57174873e+01 -3.45390549e+01 -4.22324524e+01 2.01231785e+01 4.40762100e+01 1.10169687e+01 -5.22152901e+00 1.88959675e+01 3.22514229e+01 2.39062672e+01 5.63477933e-01 1.39652481e+01 2.53539429e+01 3.41002007e+01 2.24388237e+01 3.08400798e+00 2.72184825e+00 2.92970157e+00 2.51470890e+01 4.48584442e+01 4.82574692e+01 1.93391018e+01 1.76385956e+01 8.15813751e+01 1.20263046e+02 1.06208366e+02 4.31784058e+01 3.86044426e+01 5.67564240e+01 3.59832344e+01 -1.68381729e+01 -3.22318153e+01 1.59412432e+00 3.28609009e+01 2.37405338e+01 1.04654474e+01 2.83969727e+01 3.76752510e+01 3.88298912e+01 2.74604511e+01 2.49428892e+00 -1.34963007e+01 -2.15855541e+01 -6.13966131e+00 6.43303490e+00 2.51999397e+01 3.31294708e+01 4.70218163e+01 6.14059258e+01 6.10533638e+01 3.83271179e+01 8.69212914e+00 1.51565886e+01 4.81713409e+01 5.73547096e+01 5.20019760e+01 6.65580978e+01 1.21644554e+02 1.55645081e+02 1.31535675e+02 6.77490158e+01 4.84685898e+01 5.95630836e+01 6.33495483e+01 3.90051346e+01 2.09217205e+01 9.40498829e+00 -3.02188706e+00 -1.98405826e+00 1.52825260e+01 1.95372353e+01 -1.03913345e+01 -1.45910139e+01 3.22102013e+01 6.17150879e+01 3.85499458e+01 1.22592878e+01 5.65947647e+01 8.69875488e+01 4.76832962e+01 -2.19681263e+01 -6.84571991e+01 -6.52078476e+01 -6.14813004e+01 -4.51670227e+01 -3.86065178e+01 -2.98124256e+01 -3.70836601e+01 -1.75468884e+01 3.18187445e-01 -2.64295936e+00 -3.57010002e+01 -2.09837780e+01 5.65058632e+01 1.00762596e+02 1.09742050e+02 8.95982971e+01 6.87872772e+01 3.62013855e+01 5.63003492e+00 -6.95499241e-01 -6.90577507e+00 -8.08123302e+00 -2.40552592e+00 9.76097393e+00 6.40121508e+00 1.49063139e+01 1.58849726e+01 4.72782755e+00 -3.69070679e-01 -1.09915407e-02 4.78672104e+01 9.18281097e+01 9.36910324e+01 5.51464310e+01 2.03089790e+01 2.32999477e+01 2.51594772e+01 2.68633118e+01 1.50121794e+01 2.05355568e+01 2.34865341e+01 5.93662186e+01 8.95009766e+01 7.84211197e+01 3.78467598e+01 2.45070877e+01 9.10501785e+01 1.36066299e+02 1.10794472e+02 3.92419167e+01 3.40858192e+01 6.23712769e+01 6.03519783e+01 2.89722748e+01 -1.22859430e+00 3.74013748e+01 6.79159393e+01 9.99736938e+01 1.13251289e+02 8.01596146e+01 3.94307213e+01 3.79029655e+01 1.15749786e+02 1.57554901e+02 1.02750458e+02 2.52356491e+01 3.33327675e+01 9.27123642e+01 1.12320908e+02 8.42040863e+01 4.73354683e+01 6.37672729e+01 8.66922913e+01 1.00347221e+02 7.85408554e+01 5.41126747e+01 3.84188004e+01 7.68808823e+01 1.19851891e+02 1.22799835e+02 9.01297302e+01 2.66315479e+01 5.64096146e+01 8.75861664e+01 1.00981873e+02 6.82095718e+01 5.87239799e+01 9.40149689e+01 8.99380341e+01 5.30079346e+01 9.07789898e+00 -6.64027309e+00 -1.26271229e+01 1.91961193e+01 6.95109558e+01 8.99781189e+01 6.64900436e+01 2.79269714e+01 1.23706341e+01 1.19319248e+01 6.58159943e+01 2.88869385e+02 4.83430237e+02 6.07103394e+02 4.78332794e+02 4.82174658e+03 1.40941934e+04 -1.71781797e+04 -5.30711865e+03 7.82370801e+03 2.41867529e+03 1.88411597e+03 1.10586961e+05 204508384. 1.02358991e+11 1.02358991e+11 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. -5.72994478e+10 5.50336289e+04 1.51437617e+04 1.63462268e+03 1.01430029e+03 -4.99594629e+03 -3.73757104e+03 -9.35938354e+02 -5.25404968e+02 -4.33104782e+01 1.00713791e+02 1.05753494e+02 2.55888634e+01 -1.01225376e+00 3.07182236e+01 -8.92947865e+00 -9.78207550e+01 -1.53112579e+02 -7.21985931e+01 8.14245682e+01 1.45899551e+02 9.98477097e+01 8.80132961e+00 -3.57306480e+01 -1.42164736e+01 5.81973600e+00 -2.28259048e+01 -7.14005280e+01 -4.19559402e+01 2.58274956e+01 5.61496544e+01 2.81076813e+01 -3.72107887e+01 -5.39102287e+01 -8.61221313e+00 6.95581436e+01 1.10017456e+02 7.01209259e+01 7.69352341e+01 1.22866074e+02 9.19280090e+01 -1.61311626e+01 -9.64799347e+01 -2.21169186e+01 1.46218048e+02 1.90777512e+02 1.21138725e+02 3.03290386e+01 -1.01366634e+01 -1.48920317e+01 6.28017473e+00 6.33313227e+00 -1.25609887e+00 1.32011585e+01 1.28036728e+02 1.93597031e+02 1.58713318e+02 4.59208298e+01 -2.10854168e+01 2.54244690e+01 1.00712990e+02 1.35734131e+02 6.72474594e+01 4.86912079e+01 7.36590347e+01 5.28739204e+01 -2.23926296e+01 -9.90361557e+01 -9.09760284e+01 2.03400440e+01 5.86032715e+01 3.22130432e+01 -5.19636307e+01 -3.19445267e+01 2.90528316e+01 1.52311459e+01 -3.99045258e+01 -7.30228500e+01 -2.65851326e+01 7.29600754e+01 1.19536171e+02 9.03297501e+01 -8.09649372e+00 -6.96672821e+01 -5.55345306e+01 -1.57525826e+01 -2.93493385e+01 -7.19485321e+01 -5.77596931e+01 1.31841002e+01 4.33722572e+01 -2.23909302e+01 -1.12467613e+02 -1.21103691e+02 -2.66728630e+01 5.23023834e+01 5.35229568e+01 -1.26603842e+01 -2.05539246e+01 7.70432234e-01 -4.04009819e+01 -1.31154007e+02 -1.79221542e+02 -1.00783928e+02 2.13548737e+01 8.71331711e+01 5.30926132e+01 -1.99227066e+01 -1.00211159e+02 -1.51181381e+02 -1.37618698e+02 -1.20351082e+02 -1.19665070e+02 -1.00751297e+02 -2.54397583e+01 4.24293098e+01 6.72316408e+00 -9.65662537e+01 -1.50991226e+02 -1.10147141e+02 -4.19248915e+00 5.09049149e+01 9.73489285e+00 -3.93250237e+01 -5.20026512e+01 -4.46336975e+01 -8.95453339e+01 -1.75095764e+02 -1.73753189e+02 -8.61837921e+01 4.84198618e+00 5.03720093e+00 -5.28205681e+01 -1.00790375e+02 -1.10198502e+02 -8.17263184e+01 -4.27340202e+01 -2.34367466e+01 -7.73667603e+01 -1.02379463e+02 -6.36875305e+01 -2.10435600e+01 -9.79380608e+00 -2.79552269e+01 -2.85655556e+01 4.18828249e+00 -3.66447210e+00 -2.91113396e+01 -6.84201279e+01 -7.70567322e+01 -3.59926834e+01 -1.23693218e+01 -3.01107178e+01 -6.75351028e+01 -4.10909920e+01 6.70444946e+01 1.12539108e+02 3.70555801e+01 -6.77824631e+01 -7.44772797e+01 -1.99046917e+01 1.82749538e+01 7.01266289e+00 6.37180328e+00 3.88814583e+01 8.29111938e+01 9.94411697e+01 7.39697266e+01 9.54488277e+00 -3.77652664e+01 3.28400373e+00 3.04471283e+01 1.94427204e+01 -2.67539692e+01 -5.50793648e+00 7.67666931e+01 6.99070358e+01 3.43811493e+01 -1.25144787e+01 3.57427330e+01 1.34436005e+02 1.81934738e+02 1.37538849e+02 3.30875893e+01 -1.83625031e+01 -1.68962936e+01 -2.22126122e+01 -4.38613548e+01 -2.81981659e+01 3.30190468e+01 9.89990768e+01 8.69336853e+01 3.01641273e+01 -7.19283447e+01 -1.02943680e+02 -7.97291031e+01 -9.63248539e+00 3.19302483e+01 3.60232010e+01 5.88186760e+01 8.73538513e+01 6.58925705e+01 -6.75424576e+00 -6.06738129e+01 -2.25223827e+01 6.74180984e+01 1.08067825e+02 5.52095299e+01 -3.60150604e+01 -7.41905060e+01 -2.77064304e+01 1.91219826e+01 -4.67374039e+00 -5.07582932e+01 -3.92947922e+01 1.17505045e+01 2.66468887e+01 -2.44537544e+01 -9.68760605e+01 -1.05073090e+02 -6.73273773e+01 -2.47060738e+01 -2.72359104e+01 -4.64708786e+01 -4.28947792e+01 -1.89716339e+01 -3.37710953e+01 -6.92494278e+01 -7.78632584e+01 -7.34804764e+01 -3.18870716e+01 -2.31862431e+01 -3.46104202e+01 -3.71529312e+01 -3.79467506e+01 -4.63674736e+00 -3.33160553e+01 -6.31911888e+01 -8.44571152e+01 -6.63221817e+01 7.68731403e+00 4.78009186e+01 4.06422195e+01 -4.63298607e+01 -8.74956818e+01 -9.11403275e+01 -5.67036705e+01 -3.80131836e+01 -6.24584198e+01 -5.96870575e+01 -3.17711601e+01 -1.28317118e+01 -4.18351555e+01 -6.31524506e+01 -2.12338467e+01 4.08491058e+01 2.77969570e+01 -5.90462446e+00 -2.59520626e+01 -7.90092087e+00 3.40016785e+01 -4.13783932e+00 -2.89874535e+01 -5.85600700e+01 -3.92609253e+01 5.72779703e+00 2.41499252e+01 3.93958397e+01 -1.73397863e+00 -1.74744720e+01 -2.63086891e+01 4.37694120e+00 4.71670055e+00 2.95170808e+00 4.44019175e+00 2.47224045e+01 3.80262375e+01 -3.04698229e+00 -2.91364822e+01 -3.45207214e+01 1.55398405e+00 -5.61268759e+00 -1.92994442e+01 -3.68414345e+01 -4.65732803e+01 -3.82577286e+01 -4.30534248e+01 -8.63139820e+00 5.21846056e+00 1.51864185e+01 7.11011600e+00 -3.16185117e+00 -1.77637482e+01 -5.53837585e+01 -7.04223633e+01 -5.62120667e+01 -3.53391361e+00 5.72414923e+00 -5.41730165e+00 -1.59398413e+01 -1.17797365e+01 -2.56486130e+01 -7.29311676e+01 -9.12114563e+01 -7.18805389e+01 -1.87392941e+01 -7.05990887e+00 -2.43407249e+01 -5.24244423e+01 -5.88412933e+01 -3.44625168e+01 -3.21670303e+01 -2.48696785e+01 -5.10876579e+01 -6.39671173e+01 -6.23535423e+01 -3.75587654e+01 -2.42799587e+01 -4.52787209e+01 -6.87695923e+01 -5.70705452e+01 -2.70313950e+01 -3.32263870e+01 -5.22725029e+01 -5.68556519e+01 -4.11970673e+01 -4.20537872e+01 -6.58204422e+01 -7.68227158e+01 -6.16028824e+01 -3.35841141e+01 -3.20002365e+01 -4.26125984e+01 -5.44507904e+01 -4.84757729e+01 -3.88932419e+01 -3.97049789e+01 -3.64902344e+01 -5.10506554e+01 -5.81188240e+01 -6.09741135e+01 -4.85372734e+01 -4.43209915e+01 -5.47893982e+01 -6.53547821e+01 -5.29156876e+01 -2.92246113e+01 -2.31701622e+01 -2.58708038e+01 -2.09513130e+01 -3.50879836e+00 -8.78264427e+00 -2.74225006e+01 -3.01827888e+01 -1.87410355e+01 -7.69467413e-01 -2.03192730e+01 -3.12509193e+01 -4.15254097e+01 -5.13620224e+01 -5.45531425e+01 -4.50551529e+01 -1.73843460e+01 -1.06027117e+01 -3.02669697e+01 -4.60141792e+01 -3.63080177e+01 -1.30612822e+01 -7.30667710e-01 -1.52371311e+01 -2.63628082e+01 -2.45406570e+01 -1.75892029e+01 -8.08008480e+00 1.03210056e+00 1.70531960e+01 1.04170628e+01 -4.62066555e+00 -1.04785862e+01 -3.59990954e+00 4.66028166e+00 -1.29636202e+01 -2.23384476e+01 -2.93492737e+01 -2.68204861e+01 -2.32867603e+01 -1.44613466e+01 5.31672430e+00 7.38642216e+00 -1.02165194e+01 -3.81055641e+01 -4.42663460e+01 -2.16147461e+01 -3.76875925e+00 -3.95682836e+00 -1.78093624e+01 -2.48793430e+01 -2.13310394e+01 -1.07981281e+01 -5.32812548e+00 -1.11359310e+01 -2.68250370e+01 -3.19109268e+01 -2.52884617e+01 -1.59543324e+01 -4.32976866e+00 -5.42458773e+00 -1.01458063e+01 -2.26548328e+01 -3.37639732e+01 -3.79933052e+01 -3.15638752e+01 -1.87416286e+01 -1.24516296e+01 -1.89730148e+01 -2.78546028e+01 -2.73399601e+01 -1.89585209e+01 -1.17407961e+01 -1.58323574e+01 -2.47056007e+01 -3.07801228e+01 -3.09723244e+01 -2.64557877e+01 -2.36272774e+01 -2.17358017e+01 -2.51486759e+01 -2.69957905e+01 -2.83577328e+01 -2.70425243e+01 -2.63064499e+01 -2.76977119e+01 -2.88127346e+01 -2.99834805e+01 -2.96778393e+01 -2.90406361e+01 -2.85552044e+01 -2.86440964e+01 -2.91740189e+01 -2.91673908e+01 -2.77796154e+01 -2.64325924e+01 -2.70793018e+01 -3.00909920e+01 -3.24599342e+01 -3.19779758e+01 -3.01473122e+01 -3.02646027e+01 -3.24268494e+01 -3.40853233e+01 -3.48984451e+01 -3.13052864e+01 -2.81598778e+01 -2.52044411e+01 -2.51379662e+01 -2.71344261e+01 -2.99532871e+01 -3.41765862e+01 -3.42529335e+01 -2.99406738e+01 -2.48786907e+01 -2.44408054e+01 -3.04082069e+01 -3.77462769e+01 -3.48938675e+01 -2.81614151e+01 -2.39635544e+01 -2.98785629e+01 -4.11869965e+01 -4.08983688e+01 -3.42255325e+01 -2.12925415e+01 -2.16957836e+01 -3.15855255e+01 -4.02177505e+01 -4.71166115e+01 -3.52612953e+01 -3.05095596e+01 -2.47058125e+01 -2.37558651e+01 -2.29839077e+01 -2.18183022e+01 -2.84615345e+01 -2.43820095e+01 -1.73737507e+01 -1.71333504e+01 -2.67785397e+01 -4.29659615e+01 -5.28436127e+01 -4.27705841e+01 -1.83060970e+01 3.48747301e+00 -2.67205480e-02 -2.73029118e+01 -5.32795143e+01 -6.22436371e+01 -4.14046707e+01 -1.77822247e+01 -1.34113407e+01 -2.93334255e+01 -4.85591698e+01 -4.13187485e+01 -2.75191154e+01 -1.63960285e+01 -1.44011345e+01 -1.82182560e+01 -2.87687569e+01 -4.45685539e+01 -4.21045609e+01 -2.48650436e+01 2.93568671e-01 4.25261164e+00 -1.58373995e+01 -4.25873833e+01 -3.97128563e+01 -1.79792652e+01 -3.26471400e+00 -1.51612730e+01 -2.86016254e+01 -3.52933769e+01 -3.81564331e+01 -2.69882355e+01 -1.89047642e+01 -2.67233410e+01 -3.45107117e+01 -4.63918839e+01 -2.99079857e+01 -1.70391102e+01 2.07078648e+00 1.31623049e+01 -7.54568219e-01 -1.67587585e+01 -4.54392662e+01 -5.36853676e+01 -3.78770485e+01 -1.11836205e+01 -8.23124409e+00 -3.47045708e+01 -6.24423485e+01 -5.67910118e+01 -3.82162094e+01 -7.79158258e+00 5.04408002e-01 -1.17322893e+01 -2.85926304e+01 -4.11462173e+01 -1.57323875e+01 6.10591507e+00 3.33363495e+01 2.81340141e+01 -6.48814261e-01 9.36692357e-01 9.76879787e+00 3.92246323e+01 4.28163223e+01 3.62563171e+01 1.47016487e+01 -3.00741768e+01 -4.55945549e+01 -3.43454437e+01 3.18624973e+00 1.98447132e+01 -7.79173994e+00 -4.54895325e+01 -4.87103157e+01 -7.54239035e+00 2.62134266e+01 1.55879011e+01 -2.52533569e+01 -5.92116203e+01 -6.28017616e+01 -2.59933281e+01 1.81777344e+01 2.96219215e+01 2.22696381e+01 6.35575151e+00 -8.34756088e+00 -2.87598057e+01 -3.13438015e+01 -1.85508766e+01 -9.34732628e+00 -2.50109730e+01 -6.70327530e+01 -8.96187744e+01 -5.71227989e+01 -4.08074379e+00 2.15904884e+01 -1.18092146e+01 -6.49489899e+01 -7.53173447e+01 -4.59679298e+01 8.29335594e+00 1.37690258e+01 -1.50895195e+01 -3.36010246e+01 -4.06156044e+01 -8.45092583e+00 2.52334690e+00 -2.25103402e+00 -1.51493502e+01 -4.60013123e+01 -3.41447601e+01 -2.57700214e+01 1.99235592e+01 5.14938316e+01 3.72304039e+01 1.62232647e+01 -3.15537415e+01 -3.80442848e+01 -2.32301311e+01 3.60291862e+01 9.20693817e+01 7.89372330e+01 1.64038353e+01 -1.95285149e+01 1.58341675e+02 1.77770935e+02 4.58368149e+01 2.45091748e+03 5.41397656e+03 -881920960. -560643584. 1533132160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -914026496. -423721024. -2.42461992e+04 -8.56551270e+03 -7.65737183e+02 -1.05972061e+02 -4.78749573e+02 -1.83614365e+02 3.19781885e+03 2.13238452e+03 2.67701660e+02 2.38669708e+02 1.11806160e+02 7.67535706e+01 6.01640358e+01 3.05373821e+01 -6.06046600e+01 -6.29905663e+01 -2.36481400e+01 4.50825043e+01 3.26921730e+01 -4.19748840e+01 -1.10194138e+02 -1.21670341e+02 -5.71359634e+01 3.55018044e+01 5.76166954e+01 -1.49005814e+01 -8.82669067e+01 -9.81762772e+01 -3.13146915e+01 -2.92680168e+01 -6.38166809e+01 -7.71004868e+01 -4.43184929e+01 1.43199098e+00 9.29539979e-01 1.11387873e+01 3.72031784e+01 3.76925659e+01 -4.01536512e+00 -9.95508804e+01 -9.90708923e+01 -4.31992722e+01 1.54366627e+01 8.93755341e+00 -5.50600319e+01 -1.29006195e+02 -1.21379974e+02 -2.15587673e+01 9.70702591e+01 8.50589981e+01 -3.08047161e+01 -8.87005386e+01 -9.10769272e+01 -1.99533920e+01 -2.36418653e+00 5.31637192e+00 1.73128757e+01 1.77113235e+00 -2.70026035e+01 -1.07519341e+02 -8.02318878e+01 -1.55604601e+01 1.76476154e+01 -3.47588196e+01 -1.22235123e+02 -1.24391594e+02 -7.97124405e+01 -1.34800301e+01 2.00117264e+01 -4.74996338e+01 -1.40288254e+02 -2.15611160e+02 -1.82242401e+02 -7.46392822e+01 -3.54947510e+01 -8.97601242e+01 -1.40440750e+02 -1.36160645e+02 -3.96588554e+01 -1.54251766e+01 -3.89832458e+01 -8.40786591e+01 -8.13113708e+01 -8.11691666e+01 -1.03831421e+02 -6.69229584e+01 -4.30812836e+00 2.25827618e+01 -4.85841560e+01 -1.56457977e+02 -1.72881454e+02 -1.34090057e+02 -5.10238457e+01 -3.47758937e+00 9.69180298e+00 -5.95438232e+01 -1.04872307e+02 -1.04794579e+02 3.84899092e+00 4.44797897e+01 -2.94619694e+01 -1.08051682e+02 -1.06321220e+02 -1.39273679e+00 4.25572166e+01 2.94129219e+01 2.04250546e+01 7.07285929e+00 -2.72163143e+01 -1.13335037e+02 -1.12679604e+02 -4.33800430e+01 1.41180592e+01 1.74132595e+01 -5.04511452e+01 -5.92414436e+01 -1.91672211e+01 1.46221437e+01 5.58971901e+01 3.87915459e+01 -2.84865856e+01 -1.02651054e+02 -1.24436081e+02 -2.12078362e+01 3.23073959e+01 -1.02189531e+01 -4.12797852e+01 -4.87618713e+01 7.90990210e+00 1.95822692e+00 -9.81587982e+00 1.96785469e+01 2.59763813e+01 9.10113239e+00 -8.80517426e+01 -7.80042801e+01 -5.79661131e+00 4.59151230e+01 3.27669487e+01 -3.07089500e+01 -2.85147877e+01 2.21919289e+01 5.42478104e+01 9.77436295e+01 5.50797768e+01 -1.46342096e+01 -7.90875397e+01 -7.13156509e+01 7.34795570e+00 1.46325417e+01 -4.20712948e+00 -1.31390629e+01 1.29112988e+01 6.08280487e+01 9.08812561e+01 1.13353577e+02 1.19212471e+02 8.01146698e+01 2.34221210e+01 -6.38613625e+01 -9.61737518e+01 -7.34123230e+01 -1.99180660e+01 -1.49557981e+01 -8.28133698e+01 -1.46682861e+02 -1.08428978e+02 6.66692615e-01 8.14234161e+01 6.82003403e+01 -3.74843674e+01 -1.00123680e+02 -8.66274872e+01 -1.10342379e+01 8.02387714e+00 -3.17781754e+01 -3.11182079e+01 -4.03361320e+01 -4.27119865e+01 -4.35558014e+01 1.60662861e+01 1.01010033e+02 9.35762177e+01 6.64249802e+01 1.84065008e+00 -3.12933025e+01 -4.98413887e+01 -2.83957024e+01 -1.94751797e+01 -6.74359665e+01 -1.33091660e+02 -1.05924515e+02 -1.40338860e+01 8.27579117e+01 9.06135406e+01 1.40929222e+01 -1.08042717e+01 -2.13163662e+01 5.37961922e+01 3.95914879e+01 -1.49057922e+01 -8.44074554e+01 -1.26235527e+02 -1.29806396e+02 -1.74704376e+02 -1.39367279e+02 -5.64067574e+01 1.88924294e+01 1.97821445e+01 -5.31000671e+01 -6.57798843e+01 -1.09639645e+01 6.40730133e+01 1.41637878e+02 9.43697433e+01 -1.56515341e+01 -1.32681320e+02 -9.98021774e+01 6.74016619e+00 2.98834209e+01 -2.12805042e+01 -4.93059311e+01 -4.65317001e+01 -4.26215857e-01 4.19367790e+01 6.01805763e+01 5.68505630e+01 2.06121540e+01 -1.29587374e+01 -9.12854919e+01 -1.10882774e+02 -8.54017715e+01 -3.92940331e+01 -2.24713078e+01 -1.94221802e+01 1.48062115e+01 5.87781906e+01 7.05909348e+01 5.39891701e+01 2.06236315e+00 -8.18009567e+00 -1.96586361e+01 -1.22108736e+01 1.40720091e+01 1.67208118e+01 1.38182249e+01 -3.28266296e+01 -3.57491798e+01 -2.31990471e+01 1.08310251e+01 4.83230257e+00 -1.09271460e+01 -2.49465065e+01 -1.04253588e+01 8.21452618e+00 8.00244999e+00 1.64019337e+01 9.49062634e+00 2.18664646e+01 8.60543060e+00 4.61846733e+00 -1.33985929e+01 6.58540821e+00 2.31158047e+01 3.41770515e+01 2.68766918e+01 2.16366138e+01 3.28959198e+01 3.45754929e+01 3.12333927e+01 3.48678894e+01 3.09584885e+01 2.41178970e+01 1.29312687e+01 2.52170486e+01 2.82282543e+01 2.65177917e+01 2.34146271e+01 2.87670269e+01 3.52406425e+01 3.11759071e+01 3.65047379e+01 2.62280540e+01 1.56965599e+01 1.09876928e+01 2.84220104e+01 3.11852779e+01 4.05237808e+01 2.86837120e+01 4.36271782e+01 3.41246414e+01 4.54111633e+01 4.25244141e+01 4.33487129e+01 1.42115631e+01 -2.50747166e+01 -4.71948128e+01 -2.67320786e+01 -2.22958660e+00 1.43501215e+01 3.38355589e+00 9.82961464e+00 -6.61229658e+00 -4.82660580e+00 9.33556366e+00 2.44684315e+01 1.86552830e+01 8.12711525e+00 1.64359035e+01 1.98481655e+01 1.08953838e+01 6.36026812e+00 2.46565933e+01 1.91546192e+01 5.63565493e+00 -1.61823406e+01 -1.15236425e+01 -1.08686972e+01 1.59770098e+01 4.27249641e+01 8.57102356e+01 9.52747955e+01 7.73518295e+01 4.21482620e+01 1.84210339e+01 1.09138556e+01 1.18345432e+01 4.00312376e+00 2.68710041e+01 5.80191231e+01 5.78373070e+01 2.68895264e+01 -6.24323893e+00 -6.73584080e+00 5.91859341e+00 -3.59749460e+00 -3.57476139e+00 -5.19540310e+00 -3.65324736e+00 -6.69107533e+00 -1.35386400e+01 4.24890661e+00 1.23293409e+01 -4.53485340e-01 -1.48645172e+01 -4.40009232e+01 -4.45228615e+01 -3.98959732e+01 -1.19622822e+01 -1.96833515e+01 -2.15672474e+01 -1.86314335e+01 -5.75206804e+00 4.04728079e+00 -1.59089098e+01 -3.30035515e+01 -4.53800125e+01 -1.18496246e+01 1.68591976e+01 3.01896038e+01 -2.77106190e+00 -3.79860573e+01 -6.89912949e+01 -3.66647682e+01 1.25982199e+01 3.14635563e+01 2.22897835e+01 -1.48726726e+00 -2.02792764e+00 -3.92806892e+01 -5.51593895e+01 -4.21301117e+01 -1.34356298e+01 1.17999086e+01 2.04452400e+01 1.78670273e+01 -1.54742193e+00 -3.02992153e+01 -3.42485313e+01 -8.53042603e+00 9.54589176e+00 1.83862686e+01 1.66679287e+01 2.54161110e+01 3.91498871e+01 4.14748039e+01 3.92433624e+01 3.06473274e+01 1.85724010e+01 2.21372967e+01 2.24843845e+01 2.31808987e+01 8.35019207e+00 1.90602226e+01 3.37324829e+01 1.70440216e+01 -1.82335210e+00 4.80016470e+00 5.00426331e+01 6.65231628e+01 4.29161949e+01 2.06417046e+01 2.06965008e+01 1.62288685e+01 -1.23299599e+01 -3.00587273e+01 -4.02166328e+01 -2.53067722e+01 -9.88051319e+00 1.06932297e+01 1.28143673e+01 -6.30561531e-01 4.75366974e+00 1.11087265e+01 2.13442993e+01 1.79969025e+01 2.58887501e+01 -7.28841019e+00 -3.39133110e+01 -4.38777275e+01 -1.33132744e+01 8.97339153e+00 1.66546612e+01 1.96003838e+01 1.97219925e+01 2.42014656e+01 1.15126171e+01 3.06989784e+01 4.55397644e+01 7.29062805e+01 6.78788147e+01 5.20008163e+01 3.08437271e+01 3.41652946e+01 4.21127853e+01 4.86070442e+01 4.35051117e+01 3.61557198e+01 6.45750580e+01 9.67716217e+01 9.85897675e+01 6.19408035e+01 1.49745140e+01 1.02435570e+01 3.87766304e+01 8.65607605e+01 1.94412628e+02 4.57351440e+02 6.28721558e+02 6.65815063e+02 8.33081116e+02 2.68299854e+03 3.72373218e+03 -4.82158630e+02 5.63206006e+03 8.38958191e+02 5.65309033e+03 2.03313184e+04 375353952. 857250240. 309577056. 569123392. 3.30910413e+09 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. 0. 0. 0. 0. 0. 0. -8.94549770e+10 -8.94549770e+10 993453312. -2.62259121e+04 -7.58207861e+03 -8.43289551e+02 2.76617358e+03 1.94521912e+03 5.40832947e+02 4.74805084e+02 3.64085114e+02 1.49002930e+02 8.01347580e+01 7.73152466e+01 5.58295135e+01 3.31501274e+01 3.59468613e+01 3.72369080e+01 3.75151520e+01 3.70561790e+01 5.40021935e+01 6.88919983e+01 5.40446892e+01 2.57481308e+01 2.19067917e+01 3.88446159e+01 5.19868584e+01 4.07466240e+01 3.91656647e+01 4.47060928e+01 5.02358170e+01 5.48296089e+01 5.52848625e+01 5.42457199e+01 4.69651947e+01 4.54889145e+01 4.00134621e+01 4.08358688e+01 2.15844688e+01 6.23220062e+00 3.10358930e+00 1.50849438e+01 2.47493687e+01 2.15737057e+01 1.25341167e+01 1.10160084e+01 3.00847459e+00 2.63690531e-01 -2.63703990e+00 -5.23574591e+00 -6.98986578e+00 -1.26614416e+00 5.41545343e+00 1.11105423e+01 9.12200165e+00 1.04064360e+01 1.31926470e+01 1.04849730e+01 8.88036346e+00 2.62572074e+00 7.84994543e-01 7.93671989e+00 2.60878334e+01 4.57463188e+01 5.30713310e+01 4.25729103e+01 3.14817600e+01 2.36256046e+01 3.46507950e+01 4.43059578e+01 3.88826866e+01 2.40238132e+01 1.06985798e+01 1.15599470e+01 1.33376884e+01 5.59323883e+00 -8.68043232e+00 7.90966511e-01 1.95549889e+01 3.79825516e+01 3.49919853e+01 2.68557720e+01 2.71132755e+01 2.33568039e+01 2.12766075e+01 1.69560413e+01 1.95522385e+01 2.31053715e+01 3.07648697e+01 3.30382614e+01 3.29751854e+01 2.63490200e+01 2.71282349e+01 3.68940468e+01 5.15985832e+01 4.75634727e+01 3.81656418e+01 2.73324432e+01 3.03503532e+01 3.60714951e+01 4.28185081e+01 4.55688629e+01 3.72083130e+01 2.47126255e+01 2.29791737e+01 2.67257557e+01 3.83049736e+01 3.57923050e+01 3.50937157e+01 2.85230713e+01 2.66770172e+01 2.77162685e+01 2.88274403e+01 2.86239738e+01 2.77749081e+01 2.84579258e+01 2.83959465e+01 2.68801765e+01 3.18667793e+01 3.93703575e+01 4.04236641e+01 3.34723015e+01 2.58626976e+01 2.38242798e+01 2.27070141e+01 2.31430950e+01 2.18342381e+01 2.10243034e+01 2.02365265e+01 2.81882706e+01 3.76280251e+01 3.93227654e+01 3.47492752e+01 2.76339321e+01 2.45293770e+01 2.24487972e+01 2.34441071e+01 2.61011028e+01 2.72346783e+01 2.56779861e+01 2.70114594e+01 2.71623249e+01 2.75991974e+01 2.69389019e+01 2.77028751e+01 2.80775547e+01 2.92365322e+01 2.87509689e+01 2.89373188e+01 2.86185093e+01 2.87758446e+01 2.87569790e+01 2.92505550e+01 2.97681236e+01 2.98036518e+01 2.83096867e+01 2.78874779e+01 2.75716820e+01 2.80238781e+01 2.75957890e+01 2.73026943e+01 2.73280640e+01 2.81645641e+01 3.11302700e+01 3.23619652e+01 3.23014030e+01 3.12259731e+01 3.02834053e+01 2.99319839e+01 2.91830978e+01 2.88666286e+01 2.90357361e+01 2.90234165e+01 2.89588375e+01 2.87642803e+01 2.87035675e+01 2.86233921e+01 2.86204967e+01 2.89140949e+01 2.93831062e+01 2.96156616e+01 2.93195419e+01 2.88235226e+01 2.79617462e+01 2.81058311e+01 2.81549835e+01 2.86579361e+01 2.84848804e+01 2.87411213e+01 2.84028778e+01 2.86627846e+01 2.87284012e+01 2.83623276e+01 2.78806171e+01 2.83308964e+01 2.89685040e+01 2.93150482e+01 2.81978912e+01 2.73689880e+01 2.68982582e+01 2.68032341e+01 2.77027798e+01 3.13407593e+01 3.47879677e+01 3.74874153e+01 3.73288689e+01 3.72466812e+01 3.79163132e+01 3.48350677e+01 2.98196735e+01 2.46068649e+01 2.31301231e+01 2.41683655e+01 2.60066662e+01 2.66809902e+01 2.58543701e+01 2.29327221e+01 2.34976826e+01 2.37329121e+01 2.56187801e+01 2.60759697e+01 2.58469315e+01 2.03179798e+01 1.35202484e+01 1.55454388e+01 2.12551212e+01 2.78878803e+01 3.13403759e+01 3.48187523e+01 4.21680183e+01 4.67200699e+01 4.43883781e+01 3.85243721e+01 2.97738323e+01 3.38940392e+01 3.70952911e+01 3.97044678e+01 3.77507591e+01 3.63048897e+01 3.76930161e+01 3.91466446e+01 3.87334366e+01 3.62759628e+01 3.25260468e+01 3.27911377e+01 3.98357506e+01 4.87148323e+01 5.82708702e+01 6.13745651e+01 4.25885048e+01 2.32717896e+01 1.29829931e+01 2.08371525e+01 3.10861359e+01 2.94516735e+01 3.33983040e+01 3.06885777e+01 2.98227463e+01 2.73017025e+01 2.59445839e+01 2.66542206e+01 2.69145451e+01 2.79462109e+01 1.78176498e+01 4.75294638e+00 6.07464612e-02 7.51692677e+00 1.74584751e+01 2.57601700e+01 3.53891411e+01 3.68876839e+01 2.97242641e+01 2.63980198e+01 3.24430161e+01 3.34317474e+01 2.67096329e+01 2.01715679e+01 1.94481277e+01 2.05961571e+01 2.11361294e+01 2.35985413e+01 2.34102936e+01 2.56263943e+01 2.29031296e+01 2.22048702e+01 1.62323093e+01 1.54182596e+01 1.72864571e+01 3.26659813e+01 4.96934929e+01 4.62550201e+01 3.18980198e+01 1.76110802e+01 2.47896919e+01 2.88385086e+01 3.17822609e+01 3.13500156e+01 3.47395630e+01 3.64475822e+01 4.74238091e+01 5.30102921e+01 5.22914581e+01 3.41262550e+01 1.91832771e+01 1.66145649e+01 2.23559170e+01 1.30038958e+01 -1.97268224e+00 -8.46865368e+00 -3.34622836e+00 1.19064398e+01 1.26804619e+01 1.38416882e+01 1.37314434e+01 1.47526178e+01 1.72485542e+01 1.30116529e+01 7.56052542e+00 9.02864361e+00 1.14792681e+01 1.17448950e+01 8.10600853e+00 1.19899130e+01 1.67557240e+01 3.28526077e+01 4.83916130e+01 4.58798714e+01 3.68573380e+01 2.64459534e+01 2.99689026e+01 2.55785084e+01 1.48351498e+01 1.83529282e+01 4.06766968e+01 6.17678108e+01 6.03013039e+01 3.82376862e+01 2.34519329e+01 2.78174839e+01 3.46782417e+01 3.62958221e+01 3.15135651e+01 4.65084000e+01 6.87826385e+01 7.45989838e+01 5.55732079e+01 2.45419979e+01 2.61050320e+01 2.77226543e+01 3.33090210e+01 2.75744896e+01 2.55900860e+01 3.26644249e+01 3.97207832e+01 4.48782768e+01 3.79594955e+01 3.26671371e+01 3.77342796e+01 6.32396469e+01 9.78705750e+01 9.90346603e+01 7.33849869e+01 4.37719269e+01 3.65541306e+01 3.04338970e+01 3.13999348e+01 3.89800339e+01 6.84682159e+01 9.02826614e+01 1.13618599e+02 1.17290031e+02 9.59815063e+01 7.43923187e+01 4.08594856e+01 5.75905952e+01 7.43993607e+01 5.62739944e+01 7.63317156e+00 -2.02852592e+01 3.58738244e-01 3.15383358e+01 2.97309284e+01 2.71989346e+01 1.96222801e+01 1.65418110e+01 6.93085337e+00 4.67949820e+00 3.67972183e+00 6.32832813e+00 9.52947330e+00 8.09518528e+00 4.17347044e-01 -4.51859665e+00 7.62779176e-01 2.46173649e+01 4.90654297e+01 4.21755180e+01 1.89091644e+01 -9.42072105e+00 1.86344719e+01 5.31677055e+01 2.51506901e+01 -3.44452095e+01 -4.16416550e+01 3.38211937e+01 7.70446396e+01 5.82121315e+01 2.13695984e+01 3.99155350e+01 7.46825638e+01 7.98043671e+01 6.29947395e+01 3.39568558e+01 3.70257072e+01 4.02177773e+01 3.06461601e+01 2.76793098e+01 2.64767861e+00 -1.88177948e+01 1.32453747e+01 6.53266144e+01 9.58113174e+01 7.53617401e+01 5.42189865e+01 7.68142548e+01 9.79894714e+01 1.01056480e+02 8.08264999e+01 4.49211845e+01 4.60239182e+01 5.23545837e+01 6.41562958e+01 4.75218620e+01 5.95795631e+01 8.24724045e+01 9.67656021e+01 9.30811996e+01 5.64666595e+01 3.43678055e+01 1.32685928e+01 1.20130529e+01 1.80945168e+01 -2.42757244e+01 -7.16355667e+01 -5.97472878e+01 6.02361774e+00 5.50468178e+01 4.57023468e+01 1.85406666e+01 4.72426910e+01 8.02694702e+01 8.28881226e+01 5.55419426e+01 2.36657848e+01 1.62494164e+01 1.99883118e+01 1.55457077e+01 2.38005219e+01 1.73973389e+01 2.97488842e+01 4.25351448e+01 5.33684196e+01 4.17855453e+01 2.45959053e+01 1.59952536e+01 1.11701908e+01 1.39791098e+01 -2.33482132e+01 -5.62471657e+01 -2.99303341e+01 4.78689613e+01 8.78155060e+01 5.13091202e+01 1.53959394e+00 -2.50979462e+01 -3.54019661e+01 -3.45391808e+01 -2.36911716e+01 -1.48894482e+01 -1.94114094e+01 -7.16843319e+00 -1.27607498e+01 -1.50796671e+01 -2.88725300e+01 -3.75713806e+01 -4.01240959e+01 -2.43769493e+01 -4.00652313e+00 -7.97535372e+00 -2.83361683e+01 -4.24707413e+01 -1.98614082e+01 -1.94904292e+00 1.89785786e+01 3.77769165e+01 7.58337250e+01 7.73014221e+01 5.77261009e+01 5.33259087e+01 1.19733833e+02 1.63910294e+02 1.38323380e+02 8.53520355e+01 9.22780914e+01 1.34588898e+02 1.44410858e+02 1.07268158e+02 7.38023376e+01 5.96212387e+01 5.73555908e+01 6.22718697e+01 7.04384689e+01 6.71335602e+01 4.90068092e+01 6.87197647e+01 1.06863800e+02 1.23063934e+02 9.60881805e+01 5.11334457e+01 5.32277298e+01 7.96815262e+01 5.35388374e+01 8.08053970e+00 -2.26892853e+01 -2.52613807e+00 1.96218224e+01 7.03585482e+00 5.56155539e+00 8.08941746e+00 1.28116369e+01 7.39955187e+00 9.04474163e+00 1.09217100e+01 2.78051615e+00 -7.80994606e+00 -1.80799503e+01 -1.53720055e+01 3.53394002e-01 1.09256721e+00 3.68178825e+01 6.81854782e+01 6.74749146e+01 2.69332943e+01 -2.58798504e+01 -3.63608971e+01 -3.26927414e+01 -5.81929207e+01 -9.24104080e+01 -9.67298889e+01 -7.02840347e+01 -2.96215057e+01 -1.85286636e+01 -1.47206278e+01 3.50563469e+01 8.18639221e+01 9.65027695e+01 5.85835876e+01 2.80204601e+01 2.98337364e+01 2.23498192e+01 9.89739513e+00 1.31063747e+01 -1.18108854e+01 -5.26337967e+01 -3.22687645e+01 2.41655502e+01 6.04519539e+01 3.29751282e+01 3.49673042e+01 1.11205627e+02 1.59988907e+02 1.40659348e+02 6.56345139e+01 4.00325165e+01 6.71708221e+01 6.49462357e+01 3.67605972e+01 -1.50258045e+01 -3.41302705e+00 2.91646442e+01 4.13955803e+01 2.92091084e+01 -2.89562964e+00 -2.00906353e+01 -3.37654190e+01 -3.71044807e+01 -1.77460957e+01 -2.36046314e+01 -3.45864601e+01 -1.08133612e+01 2.70847321e+01 4.41387100e+01 6.80703306e+00 -2.30356388e+01 -8.91817665e+00 3.59907341e+01 8.66223621e+00 -1.70456436e+02 -3.01992737e+02 -4.74660553e+02 -4.48880524e+02 -4.99268213e+03 -1.39724590e+04 1.32154268e+04 5.17507471e+03 -6.69870801e+03 -9.00275757e+02 -1.28611877e+03 -2.22937246e+04 8.62917427e+09 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. 0. 0. -5.72994478e+10 230083248. -140996784. -43314828. -1.59190781e+04 -6.46976855e+03 -8.96385071e+02 -2.98797668e+02 -9.08916931e+01 -4.95646362e+01 -1.82326088e+01 5.87351656e+00 -4.46514015e+01 -9.02500610e+01 -5.86512184e+01 2.93384247e+01 7.55058975e+01 1.84925480e+01 -7.88853683e+01 -6.22378683e+00 1.19009628e+02 2.50121628e+02 2.70097839e+02 2.24503448e+02 1.07464409e+02 5.47769203e+01 1.18547554e+01 6.72100372e+01 4.74816475e+01 7.77863693e+01 1.62279572e+02 1.82068130e+02 1.03459091e+02 1.58114872e+01 -1.94689121e+01 -1.52650938e+01 -5.02504044e+01 -9.79122467e+01 -1.13291039e+02 -4.78983765e+01 1.10547150e+02 1.89954330e+02 1.46516190e+02 3.71126175e+01 -3.52917938e+01 -3.13290176e+01 -1.78427470e+00 4.45217438e+01 2.32517376e+01 4.28463669e+01 6.56632690e+01 4.95426102e+01 -4.08090782e+01 -1.63098663e+02 -1.48052689e+02 -2.28003359e+00 8.30411911e+01 4.43654327e+01 -4.48510551e+01 -3.61384354e+01 3.62177849e+01 3.65320969e+01 -3.23618126e+01 -1.07222435e+02 -8.14552383e+01 3.89405556e+01 1.11757072e+02 7.94554825e+01 5.89992762e+00 -5.93527985e+00 2.08106899e+01 1.66302071e+01 -4.24598770e+01 -1.03564903e+02 -7.94825516e+01 -4.09183960e+01 -5.24933052e+01 -1.01181976e+02 -1.21723785e+02 -1.02086884e+02 -4.27643166e+01 9.71121502e+00 2.80717392e+01 -1.17259588e+01 -4.15817375e+01 -3.48371391e+01 -7.85803452e+01 -1.55538162e+02 -1.93580795e+02 -1.12235207e+02 1.70046291e+01 8.09435730e+01 3.60691490e+01 -6.57751465e+01 -1.72672012e+02 -2.08036179e+02 -1.70776733e+02 -1.45941238e+02 -1.53125351e+02 -1.37296127e+02 -3.67474976e+01 3.72048912e+01 1.75628681e+01 -6.55586853e+01 -1.12469910e+02 -8.12669067e+01 -2.31431904e+01 -3.87546480e-01 -4.19985886e+01 -7.08538971e+01 -6.09761810e+01 -5.18821335e+01 -1.00697777e+02 -1.92518494e+02 -2.04909637e+02 -1.29207565e+02 -4.10296745e+01 -4.17554932e+01 -9.02753754e+01 -1.44693375e+02 -1.45682526e+02 -1.00886292e+02 -3.99593887e+01 -1.56972380e+01 -4.21434250e+01 -4.57521095e+01 -3.79291058e+00 -1.19034147e+00 -5.00988655e+01 -1.16889198e+02 -1.09762871e+02 -4.84973831e+01 -1.59130716e+01 -5.46765404e+01 -8.66038055e+01 -1.01005867e+02 -7.36997452e+01 -9.56886826e+01 -1.42772415e+02 -1.56253632e+02 -9.11449966e+01 3.60577202e+01 9.67807312e+01 4.96338081e+01 -2.39065056e+01 -5.00103760e+01 -2.34717236e+01 8.90317345e+00 5.77140808e+00 8.11405563e+00 2.77940922e+01 7.63524780e+01 9.29435120e+01 4.67514038e+01 -6.72332230e+01 -1.30117783e+02 -7.98529968e+01 -1.13782501e+01 -1.14630423e+01 -4.47825737e+01 -1.58049974e+01 6.79212875e+01 5.84804382e+01 -1.14740458e+01 -8.69297333e+01 -2.69647827e+01 9.39897537e+01 1.58299393e+02 1.09039177e+02 1.84106884e+01 -2.26618805e+01 -2.70802250e+01 -4.50712967e+01 -6.78635483e+01 -4.90262184e+01 2.33709240e+01 1.02140366e+02 6.70740280e+01 -8.48173904e+00 -8.08794937e+01 -7.15114059e+01 -3.06113873e+01 5.93636894e+00 2.86996708e+01 2.48739986e+01 4.08463974e+01 7.30105438e+01 5.67096901e+01 -2.31792545e+01 -9.35953522e+01 -7.04417038e+01 1.79027157e+01 7.64636154e+01 4.60145035e+01 -1.28570309e+01 -5.41464310e+01 -4.52043610e+01 -6.21485901e+01 -1.11285065e+02 -1.35107407e+02 -8.11137085e+01 4.65001917e+00 2.67043972e+01 -2.17310929e+00 -7.48197403e+01 -9.84899902e+01 -8.88487167e+01 -5.61484718e+01 -3.04481068e+01 -3.61415367e+01 -1.19841366e+01 1.17218180e+01 -1.20118284e+01 -6.30589027e+01 -8.93681259e+01 -7.96735840e+01 -3.84905777e+01 -2.59459877e+01 -3.93158340e+01 -4.42519722e+01 -4.73589325e+01 -2.42898083e+01 -5.35667648e+01 -9.03073273e+01 -1.10124756e+02 -1.14481705e+02 -5.57421570e+01 -2.08587952e+01 -3.90832977e+01 -9.94402237e+01 -1.14020561e+02 -7.35157623e+01 -3.12588634e+01 -3.56166801e+01 -6.05784454e+01 -6.17210655e+01 -2.57091465e+01 -2.48676376e+01 -6.26031418e+01 -9.67545929e+01 -7.12738571e+01 -4.93856659e+01 -7.15613098e+01 -8.43254166e+01 -6.58926544e+01 -4.79250298e+01 -3.30186157e+01 -4.60309029e+01 -2.13152580e+01 -1.39078255e+01 -2.04399834e+01 -1.36034288e+01 5.63382196e+00 2.19582615e+01 -2.56338921e+01 -4.90901604e+01 -5.77880287e+01 -1.93201294e+01 -2.91782627e+01 -3.27143440e+01 -2.06116104e+01 6.95501423e+00 2.12974167e+01 -3.23259697e+01 -6.34726677e+01 -7.39611511e+01 -2.69767303e+01 -1.90994720e+01 -2.86012287e+01 -4.69705963e+01 -5.18573723e+01 -1.48939209e+01 -2.83577538e+01 -4.45171204e+01 -9.08912201e+01 -1.06882095e+02 -9.72275391e+01 -6.14993286e+01 -3.26209373e+01 -5.28200150e+01 -8.31357727e+01 -9.73523712e+01 -7.72523880e+01 -9.43493423e+01 -9.35089874e+01 -7.15463333e+01 -2.92245960e+01 -2.83785076e+01 -7.80611572e+01 -9.80068741e+01 -7.55384827e+01 -3.28339310e+01 -4.72684097e+01 -7.27804031e+01 -8.43652496e+01 -7.44228134e+01 -5.15358696e+01 -5.01148300e+01 -4.09063797e+01 -6.70215988e+01 -8.41667328e+01 -8.78459473e+01 -6.28243103e+01 -5.00124397e+01 -6.53333435e+01 -8.48495560e+01 -8.77045670e+01 -9.53042831e+01 -1.28022339e+02 -1.42290955e+02 -1.36018311e+02 -1.26321426e+02 -1.28368866e+02 -1.44865494e+02 -1.45332809e+02 -1.31060165e+02 -9.35470200e+01 -8.11904678e+01 -7.43867645e+01 -8.06098938e+01 -7.32612610e+01 -5.27374382e+01 -4.18736839e+01 -3.64018784e+01 -6.10356522e+01 -7.23462830e+01 -7.61190491e+01 -6.74841766e+01 -7.36587296e+01 -8.17705078e+01 -9.38534927e+01 -9.01448212e+01 -9.17717972e+01 -1.09218048e+02 -1.19351891e+02 -1.12639252e+02 -8.82075272e+01 -8.30692291e+01 -8.20087814e+01 -6.33954773e+01 -4.96317482e+01 -4.07964478e+01 -6.45893860e+01 -6.60972519e+01 -6.97975006e+01 -8.11783600e+01 -8.16285629e+01 -6.82797775e+01 -3.86091728e+01 -3.30068626e+01 -5.67303810e+01 -7.73322525e+01 -7.47739105e+01 -5.48121300e+01 -3.92525330e+01 -4.84272537e+01 -6.59031296e+01 -8.18961868e+01 -8.01511307e+01 -6.67900925e+01 -5.48895950e+01 -3.94038811e+01 -3.74001236e+01 -3.70695076e+01 -3.32461624e+01 -3.37153625e+01 -3.30482101e+01 -5.40681190e+01 -5.51346283e+01 -5.60514603e+01 -5.56482773e+01 -5.41953049e+01 -4.48503799e+01 -1.67101860e+01 -1.19714804e+01 -3.08938484e+01 -6.67528534e+01 -8.26218185e+01 -6.40463867e+01 -3.92444992e+01 -3.74685707e+01 -6.42405319e+01 -8.97342377e+01 -8.38901749e+01 -5.92235069e+01 -4.44309540e+01 -4.65406532e+01 -6.24864082e+01 -6.27190018e+01 -5.27228241e+01 -4.43398857e+01 -4.06389236e+01 -5.43645287e+01 -5.47817001e+01 -4.95168610e+01 -4.32970314e+01 -4.34172516e+01 -5.09953003e+01 -4.67913742e+01 -4.65372543e+01 -5.78510170e+01 -7.15299225e+01 -6.98061142e+01 -4.94250336e+01 -3.64109306e+01 -4.24487534e+01 -5.70631027e+01 -6.48694687e+01 -6.21235733e+01 -5.38452530e+01 -5.03232613e+01 -4.88275604e+01 -5.59980125e+01 -5.66210938e+01 -5.58006325e+01 -5.25446854e+01 -5.04107666e+01 -5.49202271e+01 -5.83580284e+01 -6.28166618e+01 -6.26777725e+01 -6.04455986e+01 -5.67366524e+01 -5.12161713e+01 -4.97468834e+01 -5.35815620e+01 -6.01285248e+01 -6.31408195e+01 -6.03255386e+01 -5.52801399e+01 -5.42711563e+01 -5.72444725e+01 -6.00189514e+01 -5.94964142e+01 -5.74791222e+01 -5.68424301e+01 -5.70602684e+01 -5.72310410e+01 -5.71144600e+01 -5.73182411e+01 -5.79841881e+01 -5.90803795e+01 -5.94662895e+01 -6.07270622e+01 -6.09912186e+01 -5.97792664e+01 -5.67397079e+01 -5.53499298e+01 -5.80644798e+01 -6.12852478e+01 -6.05456009e+01 -5.53396416e+01 -5.05460129e+01 -5.18781548e+01 -5.83777657e+01 -6.07413406e+01 -5.78995743e+01 -5.14006081e+01 -5.20738297e+01 -5.75246353e+01 -6.36133881e+01 -6.81398239e+01 -6.37199249e+01 -6.31818886e+01 -6.06950760e+01 -6.21298561e+01 -6.35246544e+01 -6.55673599e+01 -7.06128540e+01 -6.60104904e+01 -5.82481956e+01 -4.91206932e+01 -5.32718582e+01 -6.59660873e+01 -7.58339767e+01 -6.80511551e+01 -5.34176903e+01 -4.34498024e+01 -4.38627472e+01 -5.50920372e+01 -6.02951164e+01 -6.31214752e+01 -5.68198624e+01 -6.00410500e+01 -6.60959549e+01 -7.40650482e+01 -8.28091965e+01 -7.89426270e+01 -6.49816895e+01 -5.08401146e+01 -4.99014702e+01 -5.58703194e+01 -6.35538673e+01 -7.59801559e+01 -8.31173096e+01 -6.77782211e+01 -4.19710426e+01 -2.86883869e+01 -4.70462036e+01 -6.94464417e+01 -6.97759171e+01 -4.29906197e+01 -1.63037739e+01 -2.11608486e+01 -5.34278107e+01 -8.81999359e+01 -1.01921997e+02 -8.06456451e+01 -6.26608849e+01 -6.11795769e+01 -7.15421295e+01 -7.95273361e+01 -6.86255951e+01 -7.12302399e+01 -6.55579224e+01 -5.37512779e+01 -4.70828629e+01 -4.55783806e+01 -6.61888962e+01 -6.43357925e+01 -4.17247047e+01 -1.35462704e+01 -1.52802439e+01 -6.10489883e+01 -9.46047668e+01 -8.62035370e+01 -4.54905853e+01 -1.71497192e+01 -1.54017811e+01 -4.91374588e+01 -8.23720856e+01 -9.63253937e+01 -7.18694000e+01 -5.17297287e+01 -3.60287247e+01 -3.65226822e+01 -4.28733864e+01 -4.20420074e+01 -3.96390266e+01 -1.59360819e+01 -5.20963609e-01 -6.70393944e-01 -2.04167500e+01 -5.74473991e+01 -7.05977707e+01 -4.84704170e+01 -1.18792467e+01 -1.81806505e+00 -2.21612682e+01 -5.94854622e+01 -5.95003128e+01 -3.24609184e+01 5.80504704e+00 1.43809156e+01 -2.61342907e+01 -6.69049454e+01 -8.36803131e+01 -5.39895134e+01 -2.27181110e+01 -2.30227623e+01 -4.08545303e+01 -6.53080368e+01 -7.11295013e+01 -7.39282455e+01 -5.96645546e+01 -3.13241692e+01 -2.19194813e+01 -4.94872208e+01 -1.01051048e+02 -1.19313576e+02 -8.83256683e+01 -4.85859680e+01 -2.06555538e+01 -3.68114281e+01 -6.87347870e+01 -9.20797958e+01 -8.38891373e+01 -5.46338272e+01 -4.91240997e+01 -6.94400177e+01 -9.61192398e+01 -1.01443275e+02 -6.20783463e+01 -3.31771431e+01 -3.69285469e+01 -6.94063110e+01 -1.09086563e+02 -1.11254295e+02 -1.05878777e+02 -8.91161270e+01 -6.48418198e+01 -5.23865356e+01 -4.57421722e+01 -8.34134064e+01 -1.08635902e+02 -9.77722626e+01 -6.68086777e+01 -3.57714005e+01 -6.06116524e+01 -9.39560776e+01 -1.12337936e+02 -7.06363754e+01 1.25116692e+01 4.74779472e+01 5.14647007e+00 -9.64530334e+01 -1.44269775e+02 -1.03527832e+02 -3.12275200e+01 -1.59481468e+01 4.16837692e-01 4.58180122e+01 8.30794334e+00 -1.76758194e+02 -1.86412888e+02 3.98583679e+01 1.78901953e+03 2.78590039e+03 -4.55772736e+02 -9.41168457e+02 -6.62357666e+03 -6.13413516e+04 1533132160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -914026496. -423721024. 530500992. -1351590528. -1.23915878e+10 246353968. 636666944. 1.10055088e+04 4.54575342e+03 4.15053131e+02 9.33286819e+01 1.82015427e+02 8.65165024e+01 -3.88666306e+01 -9.75642090e+01 -9.06704025e+01 -1.42327309e+01 3.01547031e+01 1.55865526e+01 -6.91494675e+01 -1.42713211e+02 -1.34299973e+02 -8.12066193e+01 -6.44792557e+01 -6.16296082e+01 -5.50660744e+01 -1.88959808e+01 -4.63173485e+01 -6.29027519e+01 -4.40513849e+00 3.80445633e+01 5.19065046e+00 -1.07921349e+02 -1.67358124e+02 -9.02252884e+01 -1.66311324e+00 5.66947327e+01 1.92629986e+01 -8.69459229e+01 -1.71927216e+02 -2.12812332e+02 -1.30567429e+02 -7.05713043e+01 -6.42389526e+01 -1.27521255e+02 -1.64302811e+02 -1.25463524e+02 -1.12840446e+02 -7.60230713e+01 -4.00914688e+01 -2.38825760e+01 -6.19766312e+01 -1.75068130e+02 -1.80325104e+02 -7.93592911e+01 3.87506981e+01 7.42117462e+01 -2.88281364e+01 -1.25848740e+02 -1.27189796e+02 -5.77238312e+01 -2.36244717e+01 -9.04552231e+01 -1.95491531e+02 -2.32937973e+02 -1.89836533e+02 -6.56114883e+01 1.83015308e+01 1.52958097e+01 -5.80639305e+01 -1.60990646e+02 -2.29177444e+02 -2.63022705e+02 -2.28706177e+02 -1.61316620e+02 -9.99404297e+01 -7.06614609e+01 -1.01705757e+02 -9.16745224e+01 -1.55774479e+01 5.77316360e+01 5.93115578e+01 -3.10270329e+01 -9.92334442e+01 -8.34725723e+01 -4.23371887e+01 2.27266045e+01 6.24135780e+01 2.34970627e+01 -7.26254425e+01 -1.36083267e+02 -7.89216919e+01 -3.00837040e+00 -9.04400063e+00 -4.23627930e+01 -6.66823349e+01 -4.24878540e+01 -7.03508301e+01 -5.75025024e+01 -1.94550915e+01 1.22910805e+01 -1.91127815e+01 -1.30568237e+02 -1.41638412e+02 -3.67860909e+01 1.02347885e+02 1.47560379e+02 6.12964172e+01 -4.51432266e+01 -7.97565308e+01 -6.19441566e+01 -2.25228786e+01 -2.39129925e+01 -5.04886322e+01 -1.06748238e+02 -1.39706680e+02 -7.96433716e+01 3.12372265e+01 5.82381363e+01 1.47689209e+01 -2.86503010e+01 -2.75932827e+01 -6.40558853e+01 -6.28269310e+01 2.45728951e+01 1.27770996e+02 1.25145416e+02 -1.11157351e+01 -7.28612823e+01 7.89086914e+00 1.22826363e+02 1.39329254e+02 3.24917870e+01 -7.87541275e+01 -1.08447235e+02 -7.22607727e+01 1.90126629e+01 9.48763428e+01 6.57382050e+01 -2.81623878e+01 -1.04783722e+02 -3.84684067e+01 6.60365219e+01 9.92702179e+01 6.53400192e+01 1.72860031e+01 -1.57422819e+01 -7.72992249e+01 -1.01021431e+02 -6.72392044e+01 -1.33610392e+01 -8.45336437e+00 -7.43635483e+01 -1.14807159e+02 -4.89254875e+01 8.32276306e+01 1.85432755e+02 1.45253174e+02 9.45168209e+00 -9.45269775e+01 -8.60855789e+01 -1.37149563e+01 2.37239552e+01 2.07065892e+00 -1.33691015e+01 -6.32134323e+01 -4.84553490e+01 -2.98088837e+01 1.48186827e+01 7.25918961e+01 1.11156029e+02 1.21159332e+02 4.26501007e+01 -2.62780118e+00 5.19881821e+01 1.10440567e+02 7.25980759e+01 -4.28259125e+01 -1.11173820e+02 -6.28351135e+01 -1.26203794e+01 4.03331337e+01 4.22939720e+01 7.05691576e+00 -1.31747026e+01 -2.13174686e+01 5.44225998e+01 3.77752457e+01 -8.93730354e+00 -8.24326477e+01 -1.57499481e+02 -2.02658936e+02 -2.39528488e+02 -1.56679321e+02 -3.94390717e+01 1.91761513e+01 1.76923885e+01 -5.32680359e+01 -4.93916855e+01 1.52517910e+01 1.01235085e+02 1.55184006e+02 4.50338364e+01 -9.30863190e+01 -1.78196518e+02 -1.35578796e+02 -6.65397110e+01 -4.03145447e+01 -4.70583801e+01 -7.07861862e+01 -1.07689140e+02 -7.23689728e+01 -1.02900362e+01 4.01883163e+01 -5.31003094e+00 -2.59016724e+01 -4.94525795e+01 -7.92755585e+01 -9.76865845e+01 -6.49602890e+01 -3.00088749e+01 -2.51144447e+01 -3.00918274e+01 1.44311247e+01 7.16548691e+01 1.15985008e+02 1.30876114e+02 6.23900452e+01 1.87530060e+01 -7.21837616e+01 -7.55344849e+01 -2.60614700e+01 5.52620659e+01 7.41817780e+01 1.73536167e+01 -1.38443136e+01 -1.17028475e+01 -3.61702561e+00 -1.00866261e+01 5.83523571e-01 5.89573956e+00 8.50361633e+00 8.53581619e+00 2.92473578e+00 5.93385744e+00 1.64924698e+01 4.13115005e+01 4.46224632e+01 2.95986710e+01 1.47723017e+01 2.74554577e+01 4.53989334e+01 3.40208588e+01 9.10937500e+00 -3.09047775e+01 -4.76960907e+01 -3.50129967e+01 -1.84688206e+01 9.58905506e+00 -1.47373068e+00 -1.70708513e+00 6.00928724e-01 1.67900829e+01 1.47044325e+01 1.38824463e+01 9.89562130e+00 2.77253437e+01 3.02030277e+01 3.32015953e+01 1.97462387e+01 3.35470009e+01 4.12768402e+01 6.32815628e+01 6.31440468e+01 4.75995827e+01 3.25503159e+01 1.97478561e+01 2.77293015e+01 3.62209435e+01 5.58938255e+01 4.84096718e+01 4.91250420e+01 1.58827801e+01 4.34266615e+00 1.71863213e+01 3.16750565e+01 3.04461098e+01 1.42074232e+01 1.63685513e+01 2.59466438e+01 1.35206337e+01 1.60096569e+01 2.74385967e+01 3.50470581e+01 2.22698441e+01 1.30121670e+01 2.40045910e+01 1.32291603e+01 -1.39482117e+01 -2.18495216e+01 -3.91363955e+00 4.10809755e+00 -1.16184511e+01 -1.41487942e+01 -1.50622215e+01 -7.45718718e+00 -2.28901505e+00 1.27776165e+01 1.65030632e+01 3.69446135e+00 8.28666210e+00 1.38505802e+01 1.46048260e+01 1.24504805e+01 3.72557640e+01 7.14952011e+01 6.37998428e+01 4.16490402e+01 2.15689278e+01 2.05241566e+01 2.04869518e+01 1.48116102e+01 1.88983669e+01 5.98966074e+00 -2.36136746e+00 -1.23866189e+00 -5.82161331e+00 -1.25019417e+01 -1.93696747e+01 2.19927826e+01 2.37947903e+01 2.68344307e+01 1.48164473e+01 2.50590954e+01 2.18874855e+01 9.75800610e+00 6.63693476e+00 9.29894298e-02 -9.58357430e+00 -1.68800187e+00 8.51273918e+00 3.25332260e+01 2.07141037e+01 1.66483955e+01 -3.83761215e+00 -3.25824594e+00 1.91268692e+01 3.49496078e+01 3.83145027e+01 8.95917511e+00 5.11486435e+00 1.57440224e+01 2.72927437e+01 3.84546967e+01 3.65744781e+01 4.55159492e+01 4.85568275e+01 6.37698555e+01 6.32336502e+01 4.73420944e+01 2.27330894e+01 1.47833805e+01 2.23308735e+01 3.31794815e+01 3.37896042e+01 4.17550316e+01 4.74081154e+01 5.65726280e+01 5.19221802e+01 3.48714981e+01 3.89931679e+01 7.45190964e+01 1.16674019e+02 1.02856636e+02 6.34514351e+01 1.74238129e+01 4.30522614e+01 6.46463776e+01 8.10021286e+01 6.19836044e+01 3.77268677e+01 5.05325050e+01 6.68784561e+01 7.93168564e+01 7.07764587e+01 6.43686752e+01 7.92600174e+01 9.69932785e+01 1.00569283e+02 7.76343307e+01 4.66008682e+01 4.04462433e+01 5.38628197e+01 6.10458069e+01 6.08374519e+01 3.73335686e+01 4.47282562e+01 6.44270325e+01 9.91005020e+01 8.37865677e+01 5.78905334e+01 2.90484333e+01 4.11994820e+01 4.64355698e+01 4.04721947e+01 1.17162724e+01 -2.54988213e+01 -2.10406551e+01 7.20418978e+00 4.42159309e+01 4.95146179e+01 5.56929359e+01 7.44519958e+01 8.62907257e+01 4.19497185e+01 -1.16499891e+01 -2.18262539e+01 1.86375370e+01 5.30769272e+01 4.39580345e+01 3.32402458e+01 1.69323978e+01 6.10187531e+00 1.85246067e+01 3.60181732e+01 6.31246948e+01 6.11654167e+01 7.32823029e+01 3.93369370e+01 -7.92572927e+00 -2.22558346e+01 1.09963155e+00 4.42262306e+01 7.24240799e+01 9.20028915e+01 9.34392776e+01 6.67452393e+01 5.09285164e+01 4.05217590e+01 3.65256462e+01 3.69507141e+01 2.96468678e+01 2.62821407e+01 2.78184662e+01 2.90427418e+01 4.41235008e+01 8.63042374e+01 1.92819168e+02 2.92104095e+02 2.75631195e+02 2.81637177e+02 2.60556976e+02 4.08300537e+02 2.16225937e+02 1.47164658e+02 -1.84251251e+02 1.41490918e+03 2.33700989e+02 9.46768799e+02 3.28826147e+03 -2.45517944e+03 -1.37887129e+04 -3.13007383e+04 569123392. 3.30910413e+09 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. 0. 0. 0. 0. 0. 0. -8.94549770e+10 -8.94549770e+10 993453312. 1566925568. 1248277632. 524154048. 1.80504980e+04 6.89924219e+03 2.02456006e+03 4.01787262e+02 3.33315765e+02 1.38010452e+02 9.19312973e+01 7.59334106e+01 7.47323074e+01 7.49962082e+01 7.55176086e+01 7.70091095e+01 4.57441521e+01 -2.67646198e+01 -7.41965027e+01 -4.88823853e+01 -2.22229805e+01 2.08933887e+01 1.17082214e+02 1.70309692e+02 1.60826843e+02 1.39168304e+02 1.61901993e+02 2.10705536e+02 1.45890488e+02 1.70214401e+02 1.56169128e+02 1.32917801e+02 7.25429840e+01 5.25222092e+01 4.25717010e+01 3.42034454e+01 2.56421432e+01 1.76442852e+01 1.45770168e+01 2.03896122e+01 3.11853428e+01 3.37214508e+01 3.44430428e+01 2.96171646e+01 2.58791580e+01 2.01997929e+01 2.48702793e+01 4.27370186e+01 6.48722382e+01 7.01465683e+01 6.32843475e+01 5.23484764e+01 4.92707481e+01 4.07888908e+01 4.18054962e+01 4.51650658e+01 4.77240181e+01 4.28677025e+01 3.84598770e+01 3.84425430e+01 3.22094383e+01 4.15325279e+01 4.84053612e+01 5.54079514e+01 5.48217316e+01 5.87461281e+01 6.10794296e+01 5.78653679e+01 5.29792595e+01 5.35827713e+01 5.15055504e+01 3.99371872e+01 3.60637398e+01 3.82110329e+01 4.86254921e+01 5.19855843e+01 5.26022110e+01 6.14841309e+01 7.49977417e+01 7.07168274e+01 6.54301300e+01 5.79236450e+01 7.89450378e+01 9.24369431e+01 9.05493164e+01 7.84109802e+01 6.96613846e+01 7.24234390e+01 7.32604218e+01 6.97552338e+01 7.15040665e+01 7.82338562e+01 8.76673279e+01 8.42931061e+01 6.93791122e+01 5.62161407e+01 5.15127487e+01 5.50332603e+01 5.73819084e+01 6.03823891e+01 5.20978317e+01 4.42724876e+01 4.92516327e+01 6.08119659e+01 6.42079315e+01 5.57429543e+01 4.93053284e+01 6.14819717e+01 7.08763351e+01 6.92714462e+01 5.65356445e+01 4.59918365e+01 4.57099724e+01 4.74454460e+01 4.96078186e+01 5.02305641e+01 5.36355247e+01 5.53832779e+01 5.46406021e+01 5.41583939e+01 5.57906876e+01 5.76244087e+01 5.56044540e+01 5.34925461e+01 5.35449409e+01 5.52694778e+01 5.66171494e+01 6.33560867e+01 6.93842392e+01 6.81408691e+01 6.14689484e+01 5.66432343e+01 6.34981499e+01 7.03607178e+01 7.01595535e+01 6.48426895e+01 5.96730270e+01 5.88230247e+01 5.84421387e+01 5.60954094e+01 5.73832054e+01 5.79092293e+01 5.84821777e+01 5.68213120e+01 5.47360077e+01 5.53523560e+01 5.62968483e+01 5.78542976e+01 5.73425217e+01 5.72495003e+01 5.75714226e+01 5.94008904e+01 6.25587349e+01 6.55667496e+01 6.48523788e+01 6.24447708e+01 5.91481476e+01 6.09139633e+01 6.28768921e+01 6.24637642e+01 5.95014534e+01 5.70285988e+01 5.72753448e+01 5.78118744e+01 5.82281532e+01 5.79912949e+01 5.78819351e+01 5.76345329e+01 5.73496132e+01 5.73395157e+01 5.77232475e+01 5.81599045e+01 5.79056816e+01 5.75243530e+01 5.72527428e+01 5.72336578e+01 5.72414780e+01 5.70153732e+01 5.65009689e+01 5.63081322e+01 5.64998360e+01 5.68280334e+01 5.67149696e+01 5.70571098e+01 5.63073044e+01 5.45926132e+01 5.37441826e+01 5.45893021e+01 5.62926064e+01 5.64898605e+01 5.60985756e+01 5.63242874e+01 5.62777557e+01 5.58456306e+01 5.56053925e+01 5.25490913e+01 4.92654266e+01 4.89639778e+01 5.19122124e+01 5.51241035e+01 5.37762947e+01 5.37273026e+01 5.05430756e+01 4.74323120e+01 4.77314491e+01 5.28983040e+01 5.78147087e+01 5.59243011e+01 5.44406700e+01 5.36316719e+01 5.56646729e+01 5.69928246e+01 5.79169617e+01 5.76858177e+01 5.71727486e+01 5.63312454e+01 5.70251198e+01 5.72980652e+01 6.07773132e+01 6.28097420e+01 6.43869934e+01 6.37443085e+01 6.25864868e+01 6.24573326e+01 6.28976517e+01 6.28494453e+01 6.17600136e+01 6.03014412e+01 6.23451958e+01 6.11146011e+01 6.05128479e+01 6.04976540e+01 6.43062210e+01 6.51391296e+01 6.13382301e+01 5.91778831e+01 5.93216438e+01 6.16465683e+01 5.89854126e+01 5.85421715e+01 5.50618401e+01 5.51846085e+01 5.51811829e+01 6.09157028e+01 6.76507568e+01 6.21163597e+01 4.85200272e+01 4.01542549e+01 4.36013985e+01 5.01656075e+01 5.22023964e+01 5.00995369e+01 4.81339531e+01 4.44262161e+01 4.33229256e+01 4.47934875e+01 4.75641823e+01 5.21076660e+01 5.53276215e+01 5.55171585e+01 5.36514053e+01 5.02568359e+01 4.89844780e+01 4.88074226e+01 4.95738869e+01 4.90259514e+01 5.11434364e+01 5.19881821e+01 5.56677094e+01 5.14540977e+01 3.86807175e+01 2.51667652e+01 2.61186962e+01 3.66271667e+01 4.80836983e+01 5.14043503e+01 5.21329498e+01 4.67229118e+01 3.72879791e+01 3.15325298e+01 2.78927574e+01 3.81000633e+01 4.77009087e+01 5.86466179e+01 5.28772202e+01 4.79129295e+01 4.70844154e+01 5.09626160e+01 5.40295601e+01 5.70381699e+01 5.30450897e+01 4.62561531e+01 4.01386604e+01 3.92314796e+01 3.94368858e+01 2.54379044e+01 1.16624041e+01 1.69596272e+01 3.65087090e+01 5.19772949e+01 4.24052696e+01 3.36835060e+01 3.57728500e+01 3.96669044e+01 3.00754089e+01 1.36336613e+01 1.44076147e+01 3.42182808e+01 5.43890419e+01 4.81896629e+01 3.92354240e+01 3.99312820e+01 5.10957718e+01 5.27987213e+01 4.95641327e+01 4.08912582e+01 4.70664368e+01 5.83013382e+01 5.97637291e+01 5.68885918e+01 5.27318802e+01 5.92650566e+01 4.35288887e+01 2.39612789e+01 2.21414680e+01 1.73497028e+01 5.48621225e+00 -1.38754826e+01 -1.60461750e+01 -4.01097059e+00 -7.82563972e+00 5.43395472e+00 7.58384323e+00 2.58454266e+01 4.43597870e+01 6.98978729e+01 7.90926132e+01 7.10337296e+01 6.52283859e+01 5.84699478e+01 5.87683640e+01 5.60821571e+01 5.91484833e+01 6.45947876e+01 4.73454437e+01 1.75879726e+01 3.66643739e+00 1.06355524e+01 3.13270741e+01 3.60204163e+01 4.15563011e+01 5.22355499e+01 4.02424088e+01 3.53807831e+01 2.55114174e+01 2.24160175e+01 1.10410690e+01 -8.45247746e+00 1.02996922e+01 3.03873386e+01 3.83155518e+01 1.09737682e+01 4.14125395e+00 1.55428705e+01 4.26816559e+01 1.97095318e+01 -2.57737207e+00 -1.27724915e+01 7.46226645e+00 2.86694946e+01 6.85953140e+00 -1.61612587e+01 -1.01923418e+01 2.49793797e+01 5.07827034e+01 2.76837578e+01 1.20114841e+01 3.04390240e+01 6.59534149e+01 4.28726501e+01 1.90577579e+00 -1.81284122e+01 5.32373041e-03 1.27190189e+01 7.37936926e+00 -1.65214825e+01 -3.69637032e+01 -2.70049458e+01 1.62087078e+01 4.83065834e+01 4.62025642e+01 3.53319397e+01 3.45186768e+01 3.70421066e+01 3.29980507e+01 2.34461803e+01 7.18126774e+00 7.69427156e+00 2.73978939e+01 4.17764587e+01 4.75458488e+01 2.20589771e+01 3.27782536e+00 6.53200150e+00 1.74472198e+01 3.70564804e+01 2.84196701e+01 2.76458149e+01 3.59140511e+01 5.63803062e+01 5.58553047e+01 6.17596579e+00 -3.45865746e+01 1.17956734e+00 6.79825821e+01 7.20684128e+01 1.57717810e+01 -5.45880890e+00 2.86333599e+01 4.06116447e+01 1.75897636e+01 5.18882656e+00 1.48909826e+01 3.78744774e+01 2.17562542e+01 7.46174669e+00 -4.49383497e+00 1.01231880e+01 3.33008766e+01 3.22441216e+01 3.12005806e+01 5.57777834e+00 -1.24647074e+01 -1.30558100e+01 1.19205513e+01 1.26922579e+01 -4.97354851e+01 -8.11417770e+01 -6.52035370e+01 -8.82742977e+00 -4.97123671e+00 -2.29223785e+01 2.76691198e-01 5.23305168e+01 6.53823624e+01 2.88805943e+01 9.81736422e-01 1.09418459e+01 2.66033096e+01 8.11220932e+00 -1.56830251e+00 -7.73664427e+00 2.51923347e+00 2.50036621e+01 4.29989052e+01 5.08942909e+01 3.80251656e+01 2.29558926e+01 2.92678332e+00 -5.94971466e+00 -1.19879160e+01 -2.89287357e+01 -2.98209457e+01 -1.13043177e+00 2.96852169e+01 2.21513367e+01 -1.36350479e+01 -2.39736385e+01 -1.68055115e+01 -3.74353638e+01 -9.25717621e+01 -1.27981750e+02 -1.06420479e+02 -3.81710014e+01 -1.93411121e+01 -3.09228783e+01 -3.81238060e+01 -1.18351727e+01 1.76132107e+01 2.37110710e+01 3.45725708e+01 2.33839722e+01 1.07376595e+01 9.86917591e+00 3.51751823e+01 3.86375542e+01 -1.57557526e+01 -4.37650223e+01 -1.87185822e+01 1.53363113e+01 -1.95736065e+01 -4.58013954e+01 -1.09002132e+01 5.62199669e+01 1.01030609e+02 8.66125565e+01 8.00001907e+01 6.23213043e+01 6.41303406e+01 5.79378624e+01 6.10971832e+01 4.05382881e+01 1.85999813e+01 2.23234730e+01 5.88788261e+01 4.27171936e+01 -3.42427177e+01 -8.43271255e+01 -9.61153946e+01 -7.42508316e+01 -4.73588676e+01 -7.43623400e+00 2.02849674e+01 1.99545879e+01 2.53198109e+01 2.71793079e+01 2.24924908e+01 1.01923094e+01 1.31157417e+01 1.12359514e+01 8.57535744e+00 1.26670771e+01 1.28563862e+01 1.14016619e+01 -2.94159679e+01 -7.21900406e+01 -7.07443161e+01 -3.41473732e+01 -4.50645256e+00 -7.72697735e+00 -4.64526033e+00 -6.65970945e+00 -2.72405863e+00 -8.95497513e+00 -1.01486387e+01 -3.86402435e+01 -7.23724747e+01 -5.85096703e+01 -1.47770281e+01 -4.32702065e+00 -7.68794403e+01 -1.28894394e+02 -9.86103745e+01 -2.60457630e+01 -2.10401402e+01 -5.10350304e+01 -5.10392380e+01 -1.72613869e+01 1.52580738e+01 -1.86220112e+01 -5.11233139e+01 -8.66380844e+01 -9.81605530e+01 -5.92335167e+01 -1.78265305e+01 -2.14901390e+01 -1.01541153e+02 -1.38327850e+02 -8.68992767e+01 -1.38468552e+01 -2.87217503e+01 -8.39092636e+01 -9.81223450e+01 -6.56853867e+01 -3.12772503e+01 -5.55573883e+01 -8.23519669e+01 -9.50256729e+01 -6.93364182e+01 -3.83541183e+01 -2.14287758e+01 -6.20528259e+01 -1.08050575e+02 -1.12951683e+02 -8.02095184e+01 -2.03324871e+01 -4.99027252e+01 -8.02584229e+01 -9.50801849e+01 -6.28200035e+01 -5.86851349e+01 -9.63774185e+01 -8.81984177e+01 -4.64439812e+01 9.68103504e+00 1.61314850e+01 2.40142479e+01 -1.53879499e+01 -5.92801323e+01 -8.03693161e+01 -5.57179298e+01 -2.00573292e+01 3.39447570e+00 -3.82021451e+00 -6.64692383e+01 -2.93143158e+02 -4.95245697e+02 -6.33640198e+02 -5.38176880e+02 -2.96952881e+03 -4.52245947e+03 5.38963672e+03 1.70928931e+03 -3.24928345e+03 -1.77186133e+03 -2.43098413e+03 -1.43347305e+04 -3.87784766e+04 25046594. -8.42500710e+09 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. 0. -1.06434068e+10 -31487976. -31614706. 3.41439961e+04 1.39529121e+04 4.63979102e+03 9.91061951e+02 5.28219116e+02 4.95315132e+01 -8.39189224e+01 -9.10445862e+01 -2.25636024e+01 2.76125717e+00 -3.03889370e+01 7.00950098e+00 8.91233139e+01 1.48559418e+02 7.07961884e+01 -9.22786942e+01 -1.60337234e+02 -1.05218666e+02 -1.21789789e+01 3.32471619e+01 4.38650036e+00 -7.64467859e+00 1.13233004e+01 5.29362526e+01 1.96042881e+01 -5.23957100e+01 -8.17230911e+01 -5.03969994e+01 2.10718479e+01 3.93224487e+01 -1.36454411e+01 -9.80137711e+01 -1.31297760e+02 -8.33707199e+01 -8.42687454e+01 -1.37207458e+02 -1.12579063e+02 -7.23909473e+00 6.30643425e+01 -1.33545513e+01 -1.82290649e+02 -2.26659088e+02 -1.48267242e+02 -5.34253006e+01 -1.69405537e+01 -1.87106533e+01 -3.39057198e+01 -3.44844437e+01 -2.38197689e+01 -3.65873489e+01 -1.46204758e+02 -2.16840439e+02 -1.79382507e+02 -7.37277222e+01 -1.42967644e+01 -5.82650909e+01 -1.24763588e+02 -1.53541199e+02 -8.80500793e+01 -7.02580109e+01 -9.99954071e+01 -7.82603455e+01 -7.75974941e+00 6.05009804e+01 5.20472069e+01 -6.23467140e+01 -9.62220764e+01 -6.53669205e+01 1.77498074e+01 -6.09334230e-01 -6.74181061e+01 -4.64862022e+01 7.34775972e+00 3.92631187e+01 -9.76821613e+00 -1.08507034e+02 -1.57630478e+02 -1.21757599e+02 -2.06280994e+01 3.89145737e+01 1.79113960e+01 -2.21421299e+01 -9.96437931e+00 3.59216385e+01 2.01848068e+01 -4.34604950e+01 -7.36045456e+01 -7.49807978e+00 8.09211044e+01 8.69108047e+01 -1.06501169e+01 -9.05495148e+01 -1.00821899e+02 -3.16026192e+01 -2.50540619e+01 -3.73590240e+01 5.19271469e+00 9.11532211e+01 1.28353897e+02 5.19448814e+01 -7.28001022e+01 -1.34844116e+02 -1.02538849e+02 -2.91324139e+01 4.35061951e+01 9.31298294e+01 8.46504440e+01 7.11728210e+01 7.49664459e+01 5.11155357e+01 -2.50154324e+01 -9.79713287e+01 -5.55718002e+01 5.07109871e+01 1.03602722e+02 6.01502838e+01 -5.43940163e+01 -1.09076073e+02 -6.59985962e+01 -1.15306664e+01 -3.10606456e+00 -4.30152082e+00 3.91424484e+01 1.28825684e+02 1.20525871e+02 3.78364220e+01 -5.38612938e+01 -5.39699516e+01 8.31365490e+00 5.14961281e+01 5.77211418e+01 2.49790497e+01 -1.74377270e+01 -3.74030952e+01 1.67163429e+01 4.19354858e+01 6.03158522e+00 -4.22844658e+01 -5.41276245e+01 -2.76345501e+01 -2.36938610e+01 -5.07101555e+01 -4.94286613e+01 -2.24670944e+01 1.26841297e+01 1.54327612e+01 -2.55560150e+01 -4.09051781e+01 -1.22854071e+01 1.84870415e+01 -1.90961018e+01 -1.36110474e+02 -1.91478821e+02 -1.15058479e+02 -1.49191637e+01 3.27422428e+00 -4.58199196e+01 -7.99730606e+01 -7.24821091e+01 -7.20261993e+01 -1.06117767e+02 -1.60199112e+02 -1.83967300e+02 -1.57324814e+02 -8.35841446e+01 -3.38760567e+01 -7.11242447e+01 -1.00558601e+02 -8.73268661e+01 -4.01982117e+01 -6.66385040e+01 -1.48718781e+02 -1.49721420e+02 -1.18206787e+02 -8.11069565e+01 -1.17026917e+02 -2.09818726e+02 -2.55517822e+02 -2.06757248e+02 -9.85018463e+01 -5.33286781e+01 -6.40290070e+01 -6.19163551e+01 -2.91595535e+01 -4.53023987e+01 -1.06905121e+02 -1.78469452e+02 -1.61702362e+02 -1.02873589e+02 -2.95816636e+00 2.79139366e+01 7.01389647e+00 -6.39811592e+01 -1.08205292e+02 -1.10679276e+02 -1.28407104e+02 -1.55767517e+02 -1.37504349e+02 -7.75018463e+01 -1.86141148e+01 -5.91208534e+01 -1.45094910e+02 -1.96877716e+02 -1.36420242e+02 -3.94907379e+01 -1.79188180e+00 -4.51579018e+01 -9.94205322e+01 -7.42297211e+01 -3.10665855e+01 -3.96038742e+01 -1.00583397e+02 -1.23944542e+02 -7.37759628e+01 1.99580133e+00 1.52103434e+01 -1.92427750e+01 -5.60734673e+01 -5.11646690e+01 -3.62105408e+01 -4.50570068e+01 -7.16138611e+01 -5.05551376e+01 -1.42263889e+01 -7.46399117e+00 -1.79843388e+01 -5.63278160e+01 -6.82293930e+01 -5.40140953e+01 -5.72127113e+01 -5.13385963e+01 -8.54708710e+01 -5.31067810e+01 -2.71820259e+01 -7.11473799e+00 -2.82472992e+01 -1.04707085e+02 -1.42930191e+02 -1.33903915e+02 -4.72495308e+01 -4.62528849e+00 2.87965631e+00 -3.04910984e+01 -5.14508629e+01 -3.08207436e+01 -3.21330223e+01 -5.94069519e+01 -7.62537231e+01 -5.21453934e+01 -3.08351879e+01 -7.60117645e+01 -1.33397110e+02 -1.24195503e+02 -8.88772812e+01 -7.10332642e+01 -8.80458069e+01 -1.28692871e+02 -9.02021103e+01 -6.74162445e+01 -3.86920624e+01 -5.69673538e+01 -1.00149269e+02 -1.21215591e+02 -1.37954056e+02 -1.01532227e+02 -8.46299438e+01 -7.41479263e+01 -1.02283997e+02 -1.04725441e+02 -1.03941956e+02 -1.08614754e+02 -1.27282204e+02 -1.39865692e+02 -9.71434097e+01 -6.99485168e+01 -6.69271622e+01 -1.03233200e+02 -9.77586975e+01 -8.33203964e+01 -6.70210266e+01 -5.32960320e+01 -6.25123901e+01 -5.94428253e+01 -9.50363998e+01 -1.08797157e+02 -1.16352264e+02 -1.11805656e+02 -9.80146179e+01 -8.75520172e+01 -5.04204636e+01 -3.51831207e+01 -4.39335403e+01 -9.98374786e+01 -1.10572067e+02 -9.80656967e+01 -8.30922623e+01 -8.50435104e+01 -7.36358337e+01 -2.55283470e+01 -8.92343044e+00 -2.81086464e+01 -8.24968338e+01 -9.49684448e+01 -7.72221756e+01 -4.96855659e+01 -4.55479927e+01 -7.25771484e+01 -7.51567307e+01 -8.03501892e+01 -5.39345779e+01 -4.22462387e+01 -4.23178825e+01 -6.39785805e+01 -7.45427475e+01 -5.42455101e+01 -3.49442749e+01 -4.81427155e+01 -7.89892426e+01 -7.04865112e+01 -5.51967201e+01 -5.38601265e+01 -6.93388519e+01 -6.76951447e+01 -4.06366196e+01 -3.07913399e+01 -4.09897652e+01 -7.14930267e+01 -7.18095703e+01 -6.58973541e+01 -5.32335892e+01 -6.07488747e+01 -7.09888458e+01 -6.79377213e+01 -6.97710876e+01 -5.39715958e+01 -4.82470703e+01 -4.81373329e+01 -6.33417206e+01 -6.62298660e+01 -5.86180153e+01 -4.68169098e+01 -5.66650238e+01 -7.70730667e+01 -8.19442291e+01 -8.38676300e+01 -9.10809784e+01 -1.09220985e+02 -1.03427162e+02 -8.59844284e+01 -8.23532486e+01 -9.28254395e+01 -1.06830124e+02 -8.76745987e+01 -7.95402527e+01 -6.99312439e+01 -5.96131248e+01 -5.45940247e+01 -6.57018585e+01 -9.37270126e+01 -1.01236267e+02 -8.02286758e+01 -6.31074982e+01 -7.43057251e+01 -9.73179932e+01 -1.11248535e+02 -9.50638428e+01 -8.36755524e+01 -8.61426010e+01 -9.39508896e+01 -1.03062263e+02 -1.11868958e+02 -1.25956528e+02 -1.21466537e+02 -1.06684952e+02 -1.02610657e+02 -1.08445930e+02 -1.16144440e+02 -9.73887634e+01 -8.87819443e+01 -8.35419693e+01 -8.61604538e+01 -8.95625076e+01 -9.76039734e+01 -1.17843559e+02 -1.21125481e+02 -1.03773438e+02 -7.62866364e+01 -7.09899521e+01 -9.26702652e+01 -1.10052979e+02 -1.09448250e+02 -9.50761795e+01 -8.86909256e+01 -9.28231812e+01 -1.03683861e+02 -1.08675751e+02 -1.02049332e+02 -8.64866486e+01 -8.22041550e+01 -8.91098862e+01 -9.85793991e+01 -1.08607521e+02 -1.07511490e+02 -1.03425774e+02 -9.10149460e+01 -8.00027542e+01 -7.59755936e+01 -8.29761658e+01 -9.59452896e+01 -1.02479378e+02 -9.55496597e+01 -8.68460388e+01 -8.70889740e+01 -9.54422913e+01 -1.02015656e+02 -9.85147629e+01 -9.01931839e+01 -8.40770721e+01 -8.36268311e+01 -8.78616333e+01 -9.06891327e+01 -9.25244980e+01 -8.89697952e+01 -8.75116806e+01 -8.62888412e+01 -8.77382126e+01 -8.83952789e+01 -8.69669647e+01 -8.59714966e+01 -8.48907700e+01 -8.51397781e+01 -8.57012100e+01 -8.61420898e+01 -8.60996857e+01 -8.55903015e+01 -8.55899887e+01 -8.69774246e+01 -8.84392395e+01 -8.77906876e+01 -8.48482132e+01 -8.24299927e+01 -8.31819382e+01 -8.49938126e+01 -8.48389740e+01 -8.24220581e+01 -8.09371185e+01 -8.03724518e+01 -8.34250488e+01 -8.61228638e+01 -8.93507156e+01 -8.97852402e+01 -8.79841614e+01 -8.49576263e+01 -8.04815063e+01 -8.03275986e+01 -8.44212570e+01 -8.93878403e+01 -8.95811691e+01 -8.34794540e+01 -7.61310043e+01 -7.85991516e+01 -8.56910477e+01 -9.03323135e+01 -8.43547058e+01 -7.35692825e+01 -7.39883423e+01 -8.12057266e+01 -9.34868317e+01 -9.34582291e+01 -8.37782593e+01 -7.50549927e+01 -6.83927383e+01 -7.96541748e+01 -8.46696854e+01 -9.00496445e+01 -8.97494888e+01 -8.90492325e+01 -8.99678116e+01 -8.36001053e+01 -8.90012054e+01 -9.64513474e+01 -9.72154617e+01 -8.58074341e+01 -6.76069031e+01 -5.80409584e+01 -6.78389282e+01 -9.37019272e+01 -1.15652412e+02 -1.13403572e+02 -8.67935562e+01 -6.08756599e+01 -5.12675285e+01 -7.05602036e+01 -9.09311218e+01 -9.77725067e+01 -8.24369507e+01 -6.34647179e+01 -6.88420029e+01 -8.18877258e+01 -9.67056427e+01 -9.89235306e+01 -9.36246033e+01 -8.02693481e+01 -6.50539703e+01 -6.72117310e+01 -8.55674515e+01 -1.10546951e+02 -1.14015564e+02 -9.32112808e+01 -6.71538620e+01 -7.16781387e+01 -9.53410187e+01 -1.09891762e+02 -9.91158447e+01 -8.36889114e+01 -7.81706543e+01 -7.24755630e+01 -8.16413040e+01 -8.96004257e+01 -8.32254791e+01 -7.97521667e+01 -6.71419983e+01 -8.23335190e+01 -9.22798843e+01 -1.11298225e+02 -1.22813675e+02 -1.08765572e+02 -9.24143524e+01 -6.48743515e+01 -5.64085388e+01 -7.16027985e+01 -9.89384613e+01 -1.02158882e+02 -7.41304016e+01 -4.36590195e+01 -4.95148621e+01 -6.96812897e+01 -1.01599503e+02 -1.08762985e+02 -9.63110352e+01 -8.00269928e+01 -6.93311310e+01 -9.41136627e+01 -1.16075134e+02 -1.42070526e+02 -1.37408112e+02 -1.04996216e+02 -1.05929146e+02 -1.16586838e+02 -1.48580429e+02 -1.51791626e+02 -1.42024063e+02 -1.17848747e+02 -7.52106400e+01 -5.99171524e+01 -7.08666611e+01 -1.09225029e+02 -1.25588463e+02 -9.21877975e+01 -5.56133080e+01 -5.15773201e+01 -9.89331818e+01 -1.30040207e+02 -1.21155594e+02 -7.70548553e+01 -4.23149338e+01 -3.71353378e+01 -7.49375610e+01 -1.18925476e+02 -1.30420074e+02 -1.25836731e+02 -1.08174576e+02 -9.25678635e+01 -6.66275406e+01 -6.44126434e+01 -7.87089462e+01 -9.22009506e+01 -7.57481384e+01 -3.92882538e+01 -1.34223442e+01 -4.46687164e+01 -9.59366608e+01 -1.19950134e+02 -8.87233276e+01 -3.38481903e+01 -2.53596535e+01 -5.38389778e+01 -1.06347397e+02 -1.13318199e+02 -8.18242645e+01 -6.46579437e+01 -5.91144295e+01 -9.27423172e+01 -1.01440971e+02 -9.68903656e+01 -8.00824738e+01 -5.08620987e+01 -6.35795555e+01 -7.09456406e+01 -1.17801643e+02 -1.53990280e+02 -1.43074799e+02 -1.20319542e+02 -7.20796585e+01 -8.88019028e+01 -1.49219925e+02 -2.10091888e+02 -2.35615875e+02 -2.41048843e+02 -5.84798401e+02 -2.34765210e+03 -1.10423938e+03 -1.34442676e+03 -3.70847290e+03 -4.55772736e+02 -9.41168457e+02 -6.62357666e+03 -6.13413516e+04 1533132160. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 372310976. 244396064. -379121888. 997909696. -2.39366406e+04 -9.08108203e+03 -2.49267847e+03 -3.16111481e+02 -3.04153900e+02 -1.79770248e+02 -1.45808411e+02 -1.33262497e+02 -1.07545898e+02 -1.91032925e+01 -1.24928799e+01 -4.50616531e+01 -1.15727066e+02 -1.05394508e+02 -3.51265717e+01 3.02998829e+01 4.17779503e+01 -2.38539810e+01 -1.18763214e+02 -1.38252502e+02 -6.68706436e+01 1.41461315e+01 1.65315208e+01 -4.73260803e+01 -5.36792755e+01 -7.59240294e+00 6.25422764e+00 -2.56859798e+01 -7.43311539e+01 -7.04752045e+01 -8.49788437e+01 -1.12229446e+02 -1.13181709e+02 -6.13631287e+01 3.86999741e+01 4.32001114e+01 -1.85684433e+01 -8.17011108e+01 -7.76647949e+01 -1.08113022e+01 5.80161018e+01 5.27569275e+01 -4.25522003e+01 -1.54217392e+02 -1.45593018e+02 -3.41094894e+01 1.97491150e+01 2.20353603e+01 -4.15044212e+01 -6.38981972e+01 -7.98848419e+01 -8.93754120e+01 -6.68627014e+01 -3.51065331e+01 3.70705338e+01 9.06460476e+00 -5.10079536e+01 -7.48931046e+01 -2.71778851e+01 5.60870476e+01 5.60877495e+01 1.63929501e+01 -5.03877945e+01 -8.19153748e+01 -1.25674734e+01 8.06084213e+01 1.52016464e+02 1.19529892e+02 1.67226257e+01 -2.15245228e+01 4.19404068e+01 9.91807785e+01 9.43509750e+01 -1.06807070e+01 -4.65221481e+01 -2.36004734e+01 2.28007126e+01 2.17467041e+01 2.15307961e+01 4.94020309e+01 1.03807955e+01 -4.98408928e+01 -7.94351273e+01 -5.07844400e+00 9.96564026e+01 1.26203568e+02 9.82156982e+01 9.07979012e+00 -3.87007713e+01 -5.77699471e+01 1.34468527e+01 4.85095482e+01 4.81557884e+01 -5.66845512e+01 -9.47974243e+01 -2.21119404e+01 5.52818069e+01 5.59072685e+01 -4.04428673e+01 -8.65319443e+01 -8.13949509e+01 -6.64157867e+01 -4.83253975e+01 -9.76134872e+00 6.93684464e+01 7.01516418e+01 -1.77254677e+00 -5.69027290e+01 -5.53289337e+01 1.58304482e+01 3.22010040e+01 -1.09770012e+01 -5.40438271e+01 -1.03069405e+02 -8.42417068e+01 -5.76812792e+00 7.14818726e+01 8.58170395e+01 -2.33257732e+01 -7.84684067e+01 -3.47296638e+01 3.41533232e+00 1.41161079e+01 -3.48860130e+01 -3.33680344e+01 -2.62926521e+01 -5.58888550e+01 -6.24206009e+01 -4.71260872e+01 4.64723320e+01 3.06991291e+01 -3.58458595e+01 -9.15004272e+01 -7.14792557e+01 -1.03027515e+01 -1.55482836e+01 -6.98186951e+01 -9.52888412e+01 -1.31630295e+02 -8.22809906e+01 -1.65173512e+01 4.65055809e+01 3.87262039e+01 -3.41327896e+01 -4.86332741e+01 -2.22189465e+01 -1.31907511e+01 -2.49279747e+01 -8.32514114e+01 -1.18571968e+02 -1.46690872e+02 -1.48515472e+02 -1.07794350e+02 -5.65324974e+01 3.26420174e+01 6.63889389e+01 4.84265518e+01 -9.17814541e+00 -1.66505032e+01 5.23515854e+01 1.17148285e+02 8.88630219e+01 -1.87660294e+01 -9.59731598e+01 -8.71633911e+01 1.77573395e+01 7.08916702e+01 5.89757652e+01 -1.01035404e+01 -2.54537659e+01 1.29172783e+01 5.80569649e+00 2.29655190e+01 2.52554131e+01 2.41017838e+01 -3.79777298e+01 -1.23419601e+02 -1.15250557e+02 -9.61408768e+01 -3.03061924e+01 8.53533459e+00 3.50404320e+01 2.18702641e+01 1.75643349e+01 6.59999847e+01 1.26054642e+02 9.07410507e+01 6.41346741e+00 -9.09342346e+01 -9.78547134e+01 -2.99817963e+01 -5.10579062e+00 1.38754797e+00 -5.69065170e+01 -4.61600609e+01 1.34356852e+01 7.44049377e+01 1.18953110e+02 1.22846024e+02 1.77036819e+02 1.38604568e+02 5.08825874e+01 -2.34751320e+01 -1.50522299e+01 6.29204559e+01 6.94208984e+01 6.64226437e+00 -6.45929031e+01 -1.38476639e+02 -9.10333862e+01 1.17645578e+01 1.26304337e+02 9.53283997e+01 -4.15490961e+00 -3.38295517e+01 6.77511549e+00 2.49390545e+01 3.23302193e+01 -5.56981802e-01 -4.23283539e+01 -6.24882545e+01 -6.69534683e+01 -2.32821693e+01 1.07821150e+01 9.14764404e+01 1.13395485e+02 9.01695328e+01 4.32282333e+01 2.66171494e+01 2.21061592e+01 -1.21222858e+01 -6.31135178e+01 -6.85805740e+01 -4.60779076e+01 1.39138403e+01 2.83876801e+01 3.75374413e+01 2.45161743e+01 2.89370251e+00 -1.24897108e+01 -6.37380552e+00 2.50881386e+01 4.08711243e+01 3.39725800e+01 5.16628504e+00 8.73570824e+00 1.83777027e+01 3.81368294e+01 3.04462337e+01 2.26942844e+01 2.04420700e+01 9.37699032e+00 7.25302029e+00 -6.20385122e+00 2.04412794e+00 1.01113844e+01 2.04336681e+01 5.73343706e+00 -6.61025000e+00 -1.95103111e+01 -1.00539243e+00 2.81090045e+00 5.51426840e+00 6.60176849e+00 7.41566610e+00 6.32836640e-01 9.31199455e+00 6.08026457e+00 2.46332455e+00 -2.88368664e+01 -2.72522812e+01 -1.43881159e+01 -5.92702675e+00 -5.85346270e+00 -6.43635130e+00 -5.69721746e+00 -1.74698162e+01 -1.62340736e+01 -8.97399902e+00 1.53861630e+00 -5.97945929e+00 -4.94056988e+00 -2.45841360e+00 1.04280624e+01 9.98412991e+00 3.43553305e+00 -1.24780426e+01 -1.48940754e+01 -1.08480005e+01 1.24907923e+01 4.68038521e+01 6.67049484e+01 6.21087112e+01 2.81024990e+01 9.40807724e+00 4.21807718e+00 1.61263084e+01 4.00844955e+01 3.53097267e+01 2.37434864e+01 5.56902981e+00 1.33223085e+01 1.32129459e+01 9.94575500e-01 2.06798458e+00 1.28303404e+01 2.72596474e+01 1.29106789e+01 1.75903091e+01 2.89476929e+01 4.94950485e+01 5.16865196e+01 3.62197380e+01 1.58391285e+01 -2.22244835e+00 -3.45777855e+01 -5.22850494e+01 -4.69948616e+01 -1.31909342e+01 2.07604656e+01 3.08835506e+01 3.85040970e+01 4.09674149e+01 1.53315496e+01 -2.22645741e+01 -2.42386436e+01 6.49646473e+00 4.23546982e+01 4.48343315e+01 3.69638214e+01 4.90191002e+01 4.88622284e+01 4.66093063e+01 4.08830070e+01 4.64757195e+01 5.16336136e+01 4.24467278e+01 3.65865784e+01 4.88292999e+01 6.40394440e+01 8.66978226e+01 1.00649834e+02 8.57069626e+01 7.11105347e+01 7.18740692e+01 8.02859268e+01 6.01887817e+01 4.44655571e+01 3.96521568e+01 6.77336044e+01 8.85807495e+01 1.03762939e+02 7.78094864e+01 5.30929985e+01 3.03847084e+01 5.07718658e+01 8.37536774e+01 1.22187386e+02 8.74789658e+01 4.94313354e+01 2.32877483e+01 4.40627785e+01 5.69436951e+01 6.50787964e+01 9.14798203e+01 1.02655197e+02 9.26175766e+01 7.02110977e+01 4.18765602e+01 3.66543465e+01 3.60229759e+01 6.51874084e+01 9.29057541e+01 9.93874283e+01 7.09188232e+01 5.16236076e+01 4.21114731e+01 4.56994591e+01 3.58030205e+01 1.97868690e+01 1.55591221e+01 1.79344330e+01 3.08599224e+01 4.18072357e+01 3.95540390e+01 3.87313995e+01 4.58893509e+01 5.85265121e+01 4.61712914e+01 3.23738403e+01 5.17579918e+01 7.21903305e+01 6.38557320e+01 2.03682709e+01 1.85523546e+00 2.21174107e+01 3.74788742e+01 4.06894150e+01 4.65020981e+01 8.01390305e+01 8.81183701e+01 1.00001495e+02 9.11625290e+01 8.51542664e+01 6.77725983e+01 5.27945251e+01 6.38282394e+01 5.93797684e+01 5.77734222e+01 5.34357872e+01 5.91881752e+01 5.13840981e+01 8.00566254e+01 9.89077072e+01 1.12419685e+02 8.94222488e+01 6.63668442e+01 5.80226555e+01 5.06122017e+01 5.59728851e+01 5.49186020e+01 6.77819748e+01 4.59228516e+01 2.86578217e+01 1.45774737e-01 3.36767673e+00 2.36410732e+01 4.57753181e+01 4.63125191e+01 3.70811615e+01 3.53975792e+01 4.46846657e+01 5.05948105e+01 2.03130188e+01 -1.11224699e+01 -1.50728960e+01 2.55463657e+01 6.39348907e+01 6.69498901e+01 4.80273743e+01 8.88349950e-01 -1.25170883e+02 -5.09393501e+01 -2.39916977e+02 -8.19508972e+01 -1.84655408e+03 -2.87520923e+03 1.86553085e+02 1.43498322e+02 1.28857775e+01 1.88022919e+02 -4.70253716e+01 -4.03748444e+02 -2.45517944e+03 -1.37887129e+04 -3.13007383e+04 569123392. 3.30910413e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 389030656. -914048064. 908183104. -8.97945117e+03 -3.42545679e+03 -5.46184998e+02 -4.07128082e+02 -3.08194336e+02 -6.40424500e+01 1.29527874e+01 1.79905643e+01 4.30516129e+01 6.53282700e+01 6.55813599e+01 6.35335159e+01 5.92068100e+01 5.81923065e+01 4.17537041e+01 3.19434910e+01 4.67156487e+01 7.59235764e+01 8.16934891e+01 6.26685791e+01 5.23519516e+01 6.32722855e+01 6.53214798e+01 5.88570404e+01 5.27568970e+01 4.91534615e+01 4.10785599e+01 4.14617310e+01 5.39239502e+01 6.01946983e+01 6.52545471e+01 5.82056274e+01 7.76115265e+01 9.47807770e+01 1.01501846e+02 9.13933563e+01 7.90697021e+01 8.34837570e+01 8.89195404e+01 9.22868881e+01 9.94436035e+01 1.03350777e+02 1.08369843e+02 1.10446297e+02 1.13233582e+02 1.06118256e+02 9.80120468e+01 9.34718933e+01 9.88183746e+01 9.87410202e+01 9.34556351e+01 9.35140076e+01 9.44602966e+01 1.00411736e+02 1.01923615e+02 9.68927689e+01 8.07745972e+01 6.39125786e+01 5.43169479e+01 6.43353958e+01 7.37147827e+01 8.34290924e+01 7.12504044e+01 6.49581757e+01 6.94846954e+01 8.51701813e+01 9.80255966e+01 9.84320145e+01 9.71570969e+01 1.04181122e+02 1.17849152e+02 1.07170174e+02 8.44257126e+01 6.81525345e+01 7.17353287e+01 8.37893906e+01 8.22115555e+01 8.67111130e+01 8.61975937e+01 8.99690475e+01 8.79597244e+01 8.68063660e+01 7.97135315e+01 7.85950394e+01 7.83784485e+01 8.56468811e+01 8.49098740e+01 7.46574707e+01 5.96990204e+01 6.26183090e+01 7.31659393e+01 8.43262177e+01 8.11518173e+01 7.47794647e+01 6.86629639e+01 6.50993576e+01 7.44049988e+01 8.59978790e+01 8.83400803e+01 8.28304749e+01 7.10666351e+01 7.36548233e+01 7.59980164e+01 8.12349091e+01 8.28057709e+01 7.98267517e+01 8.05451355e+01 8.02570343e+01 8.35124969e+01 8.38751221e+01 8.50081100e+01 8.51502609e+01 7.91029129e+01 7.16075745e+01 7.18757172e+01 7.91081467e+01 8.67583694e+01 8.81410599e+01 8.93282471e+01 8.97129822e+01 9.10218048e+01 9.14481354e+01 9.17984238e+01 8.41932602e+01 7.61815414e+01 7.45237503e+01 8.01951218e+01 8.66670609e+01 8.92450256e+01 8.98312149e+01 8.95041046e+01 8.76013641e+01 8.71929779e+01 8.86969986e+01 8.68994293e+01 8.64563828e+01 8.59995041e+01 8.67134857e+01 8.62098083e+01 8.61171646e+01 8.58661041e+01 8.68154373e+01 8.63900375e+01 8.59198532e+01 8.58064804e+01 8.60235062e+01 8.57458496e+01 8.46031723e+01 8.44227905e+01 8.58644104e+01 8.65758286e+01 8.68249893e+01 8.63119278e+01 8.68597412e+01 8.72702560e+01 8.74781113e+01 8.64970703e+01 8.35500641e+01 8.21991730e+01 8.24488831e+01 8.35056305e+01 8.43199387e+01 8.47344437e+01 8.55620728e+01 8.59081116e+01 8.57308044e+01 8.56875305e+01 8.58223495e+01 8.59772797e+01 8.59870529e+01 8.60761490e+01 8.60999374e+01 8.58310852e+01 8.53869476e+01 8.51185684e+01 8.53379822e+01 8.58325424e+01 8.66204453e+01 8.65125504e+01 8.63281403e+01 8.59538269e+01 8.59519272e+01 8.56531677e+01 8.60355530e+01 8.58759689e+01 8.56434479e+01 8.57006226e+01 8.61711807e+01 8.60589066e+01 8.56076736e+01 8.51284409e+01 8.64638901e+01 8.71464844e+01 8.78314285e+01 8.78703232e+01 8.67401276e+01 8.33593140e+01 7.94013519e+01 7.71383514e+01 7.73204117e+01 7.76074982e+01 7.64621429e+01 7.90905838e+01 8.33535919e+01 8.82590561e+01 8.95082474e+01 8.91120987e+01 8.78649979e+01 8.70339890e+01 8.70439606e+01 8.98192520e+01 9.01480789e+01 9.03402634e+01 8.92203293e+01 8.83447571e+01 8.84405060e+01 9.33463669e+01 1.00207466e+02 9.81632004e+01 9.18225021e+01 8.57196960e+01 8.19130478e+01 7.80896072e+01 6.98210144e+01 6.52461395e+01 6.82499390e+01 7.33978729e+01 8.28467026e+01 7.87215881e+01 7.57909241e+01 7.19417572e+01 7.36539841e+01 7.51453934e+01 7.46977539e+01 7.33343658e+01 7.47599716e+01 7.72812347e+01 8.05915604e+01 7.98515396e+01 7.17305756e+01 6.17079391e+01 5.27906609e+01 4.96662750e+01 6.84840393e+01 8.81889725e+01 9.83679733e+01 9.03178329e+01 7.78122253e+01 7.96209717e+01 7.78066177e+01 8.05884705e+01 7.96402588e+01 7.99353867e+01 8.12534180e+01 8.21299133e+01 8.10644989e+01 8.02965622e+01 9.01176376e+01 1.03689880e+02 1.07229202e+02 1.02042374e+02 9.17038193e+01 8.56744385e+01 7.44860535e+01 7.34601746e+01 7.80785065e+01 8.11157303e+01 7.36672516e+01 7.41344452e+01 8.10169525e+01 8.93025360e+01 8.95781631e+01 8.68529434e+01 8.55932770e+01 8.41521912e+01 8.47833481e+01 8.25374222e+01 8.30078354e+01 8.32548828e+01 8.80425186e+01 8.92874298e+01 8.83650284e+01 7.38576736e+01 5.74236450e+01 5.93467522e+01 7.32486877e+01 8.68406219e+01 8.15329590e+01 7.76716309e+01 7.51803589e+01 7.29808655e+01 6.93991928e+01 6.68540344e+01 5.48308907e+01 5.05614128e+01 5.19336357e+01 7.10882874e+01 8.43520279e+01 8.67920990e+01 8.10331955e+01 9.00871964e+01 1.03302574e+02 1.10197624e+02 1.06261864e+02 8.96512985e+01 8.91084900e+01 8.68558121e+01 8.87321472e+01 8.75806885e+01 8.42408295e+01 8.71473541e+01 9.04216080e+01 8.95666351e+01 9.11291885e+01 9.18421097e+01 9.25771713e+01 8.34900589e+01 7.95923386e+01 6.51847000e+01 5.06255951e+01 4.99841919e+01 5.93139000e+01 7.08432770e+01 6.84828568e+01 7.14431763e+01 8.22576218e+01 7.84144745e+01 5.74060249e+01 3.64001122e+01 3.70518341e+01 5.98411446e+01 7.53931046e+01 7.34037323e+01 6.55816650e+01 6.02889786e+01 6.15317116e+01 4.44453392e+01 2.34632835e+01 2.07068233e+01 4.10673141e+01 7.17753830e+01 6.83851929e+01 6.49389877e+01 5.86581268e+01 6.46145935e+01 6.89156952e+01 6.12433548e+01 5.32914238e+01 4.69525566e+01 5.48676682e+01 5.88636932e+01 5.47862473e+01 3.06416950e+01 -3.27165246e+00 -6.08459663e+00 1.70084324e+01 4.87025261e+01 5.66694221e+01 6.25967751e+01 6.07183914e+01 5.41957436e+01 2.13882122e+01 -1.75022984e+00 -2.91371784e+01 -2.95735493e+01 -5.68010855e+00 1.82728767e+01 4.74413338e+01 3.04087772e+01 1.03186817e+01 2.83495655e+01 7.67287445e+01 1.04734108e+02 9.03658905e+01 5.47975578e+01 5.69248619e+01 5.81882515e+01 6.95408401e+01 7.11571808e+01 8.27982254e+01 7.90738983e+01 8.27175827e+01 8.08983078e+01 8.48492508e+01 8.41663513e+01 8.60477676e+01 8.50765305e+01 7.98866501e+01 6.02424316e+01 3.37221451e+01 3.74669609e+01 5.55053978e+01 8.72687454e+01 5.86355858e+01 2.40624886e+01 5.34543648e+01 1.14289162e+02 1.20124969e+02 4.34441185e+01 2.72429109e+00 2.91112671e+01 6.52447662e+01 4.49599190e+01 8.02173615e+00 2.56598639e+00 2.41932964e+01 5.36784935e+01 5.17173729e+01 4.23902893e+01 4.74505577e+01 4.53800049e+01 6.83562241e+01 9.20158234e+01 6.59817734e+01 1.36090574e+01 -1.59790802e+01 6.76338243e+00 3.14337158e+01 3.17204905e+00 -2.37065563e+01 -3.36572495e+01 -4.68473625e+00 3.11508675e+01 3.04338894e+01 1.91704407e+01 1.14708548e+01 2.93973217e+01 1.80798950e+01 -1.01248207e+01 -2.54829311e+01 -2.20411739e+01 1.48248663e+01 3.09553146e+01 5.09165344e+01 5.55070992e+01 5.57743759e+01 9.78233566e+01 1.44920975e+02 1.30522705e+02 6.20765419e+01 9.32989788e+00 2.13089371e+01 5.26282005e+01 2.78600216e+01 -8.84985447e+00 -1.36005278e+01 1.32039642e+01 4.73879471e+01 5.21875191e+01 5.05559235e+01 5.51089821e+01 4.85445633e+01 4.55052071e+01 3.49339066e+01 2.25835686e+01 1.89035263e+01 2.90318241e+01 4.74258995e+01 5.48899117e+01 6.07258072e+01 5.04509048e+01 8.19609909e+01 1.13771118e+02 8.73355026e+01 1.02786474e+01 -3.32492943e+01 5.88075924e+00 5.65671272e+01 8.41502686e+01 9.08008041e+01 9.02799072e+01 8.10819397e+01 7.59746170e+01 7.92024918e+01 6.84650269e+01 7.52275085e+01 7.30335922e+01 8.17361984e+01 8.14090424e+01 8.39612808e+01 7.19287415e+01 5.54792786e+01 6.22102013e+01 8.02831573e+01 8.78881912e+01 6.70467453e+01 4.76827316e+01 3.61291046e+01 1.27883835e+01 -2.05935135e+01 -2.51318226e+01 -5.49744368e+00 -5.53422880e+00 -7.86264725e+01 -1.21692337e+02 -9.42312546e+01 -4.03577271e+01 -5.40234566e+01 -1.01707855e+02 -1.11568748e+02 -6.94567108e+01 -3.15536251e+01 -1.90659103e+01 -2.18422222e+01 -2.43634834e+01 -2.72332096e+01 -1.73715534e+01 -1.91004276e+00 -2.03135014e+01 -6.31006393e+01 -8.00483246e+01 -5.27162285e+01 -8.78883362e+00 -1.33515244e+01 -4.01707573e+01 -1.12666082e+01 3.71175117e+01 6.14315300e+01 4.11110764e+01 1.58715057e+01 2.88000240e+01 2.58894444e+01 2.51687679e+01 2.54921570e+01 3.20672340e+01 3.10518646e+01 2.19600296e+01 3.37956123e+01 4.21528282e+01 5.47739449e+01 4.74133034e+01 3.45497322e+01 3.63736916e+01 2.99958396e+00 -3.30148544e+01 -3.68652420e+01 -1.36750150e+00 5.80511017e+01 7.42674103e+01 7.44341583e+01 9.31538239e+01 1.27606178e+02 1.35250153e+02 1.05924744e+02 6.19762764e+01 5.57228584e+01 5.25509605e+01 3.50067067e+00 -5.32645416e+01 -6.89475708e+01 -2.70215168e+01 4.51240349e+00 -4.51572371e+00 -1.45854855e+00 1.52411661e+01 1.71486378e+01 3.23997955e+01 6.77141876e+01 5.30637398e+01 4.85565042e+00 -3.49761543e+01 -1.39106855e+01 -2.25222206e+01 -9.45060883e+01 -1.40699097e+02 -1.16549179e+02 -3.96019630e+01 -2.26243706e+01 -4.93093300e+01 -5.19906082e+01 -1.23920479e+01 4.04718094e+01 2.92740517e+01 -6.38598633e+00 -1.44681292e+01 -2.30086207e+00 2.72180195e+01 4.17766838e+01 5.42047386e+01 5.91742668e+01 4.03967781e+01 4.84314537e+01 5.66903534e+01 3.33252602e+01 -6.61336851e+00 -1.78692570e+01 1.31646729e+01 3.48021469e+01 1.21745052e+01 -1.93051262e+01 -1.64174976e+01 -5.34625530e+00 4.53758583e+01 1.13716118e+02 2.64608643e+02 3.94561005e+02 5.04489532e+02 7.00908752e+02 5.69626099e+02 1.00899971e+02 -4.97854401e+02 -1.13342456e+03 -2.68537183e+03 -9.37060352e+03 25046594. -8.42500710e+09 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. -1101049216. -22439274. 4.14685898e+04 1.67291855e+04 2.34686670e+03 5.51308789e+03 3.64827075e+03 7.35839417e+02 2.63583588e+02 6.90797119e+01 4.11492577e+01 9.09780025e+00 -1.33699255e+01 3.28410225e+01 6.92685547e+01 4.38442001e+01 -4.25098419e+01 -8.70895309e+01 -4.44668350e+01 5.32612648e+01 -1.71298141e+01 -1.30161102e+02 -2.67532715e+02 -2.76197876e+02 -2.29595688e+02 -1.19824669e+02 -7.72829819e+01 -3.90505066e+01 -9.36254501e+01 -7.41948929e+01 -1.02661682e+02 -1.87305527e+02 -2.06829590e+02 -1.31304504e+02 -4.97913475e+01 -1.58273706e+01 -1.54918566e+01 2.22740078e+01 7.29334183e+01 8.34142761e+01 1.70655975e+01 -1.45102066e+02 -2.31813782e+02 -1.86257202e+02 -7.12917175e+01 -7.95021713e-01 -2.79099441e+00 -3.57695580e+01 -8.07969666e+01 -5.91070328e+01 -8.19487686e+01 -1.02393158e+02 -8.68101578e+01 5.74873161e+00 1.15744888e+02 9.57600174e+01 -4.72843399e+01 -1.26148148e+02 -8.34619064e+01 3.67627883e+00 -1.27987814e+01 -8.84174423e+01 -9.14864655e+01 -2.18608437e+01 5.92525482e+01 3.61074829e+01 -7.89840317e+01 -1.55562485e+02 -1.17546677e+02 -3.92358208e+01 -3.28166885e+01 -5.93238640e+01 -6.06756973e+01 5.36938810e+00 6.35268288e+01 4.11066093e+01 -1.31738496e+00 5.54279625e-01 4.47692642e+01 7.01460571e+01 5.35662041e+01 -5.59237957e+00 -6.49027786e+01 -8.50639572e+01 -4.52563705e+01 -1.50417833e+01 -2.95538635e+01 1.27569704e+01 9.37190628e+01 1.32068466e+02 5.64291916e+01 -7.40587540e+01 -1.38887024e+02 -1.03051239e+02 -3.30505610e+00 9.20562897e+01 1.29277573e+02 1.01950386e+02 7.90065613e+01 9.07800293e+01 6.87046432e+01 -2.69895687e+01 -1.02444763e+02 -8.37207947e+01 -9.18878317e-01 4.17646942e+01 2.07633152e+01 -4.30268097e+01 -6.90129700e+01 -3.43096313e+01 -4.54548359e+00 -9.33361626e+00 -2.09932480e+01 2.23327827e+01 1.05305817e+02 1.20174690e+02 5.54665451e+01 -3.08873672e+01 -2.96069927e+01 1.71685791e+01 6.75338898e+01 6.84602737e+01 2.10427666e+01 -4.08549843e+01 -7.16178970e+01 -3.78984756e+01 -3.92067604e+01 -7.85922318e+01 -8.32608109e+01 -3.02398605e+01 3.06894398e+01 2.46552181e+01 -3.19377975e+01 -6.23543243e+01 -2.96865330e+01 -1.16396397e-01 1.39251242e+01 -9.89917850e+00 1.29984560e+01 5.97203522e+01 6.96384583e+01 -2.75194645e+00 -1.30247604e+02 -1.90541534e+02 -1.36820496e+02 -6.42905884e+01 -4.38439789e+01 -6.97049866e+01 -9.92967758e+01 -9.18806000e+01 -9.40684357e+01 -1.13546227e+02 -1.66314728e+02 -1.84862274e+02 -1.34181931e+02 -1.77974434e+01 3.94669952e+01 -1.54070749e+01 -9.03324814e+01 -9.10357208e+01 -5.84760246e+01 -8.37115860e+01 -1.67223297e+02 -1.57693207e+02 -8.93758087e+01 -1.37216406e+01 -7.11845627e+01 -1.86269943e+02 -2.55963028e+02 -2.11167709e+02 -1.24795135e+02 -7.68722916e+01 -7.05266190e+01 -5.24574242e+01 -2.71662407e+01 -4.89061317e+01 -1.20150963e+02 -2.08362778e+02 -1.74708038e+02 -1.04613480e+02 -3.86197090e+01 -4.78814125e+01 -7.67821350e+01 -1.08560402e+02 -1.29759445e+02 -1.28103149e+02 -1.45584625e+02 -1.78732910e+02 -1.63371841e+02 -9.01028137e+01 -1.95435696e+01 -4.95113335e+01 -1.36301743e+02 -1.99236801e+02 -1.65152908e+02 -1.06453354e+02 -6.37626190e+01 -6.93775711e+01 -5.08551712e+01 -1.89531557e-02 2.23938122e+01 -3.24114532e+01 -1.18824989e+02 -1.34805771e+02 -1.00272980e+02 -3.37997093e+01 -1.37592716e+01 -1.71165009e+01 -5.37244720e+01 -8.69069748e+01 -8.87783585e+01 -1.08864540e+02 -1.27746635e+02 -9.91666183e+01 -4.75162811e+01 -2.99590778e+01 -4.63822441e+01 -8.67892914e+01 -9.88156891e+01 -8.36100159e+01 -8.08303146e+01 -7.95746689e+01 -1.03619713e+02 -7.50197754e+01 -3.29219055e+01 -1.05845690e+01 -1.45456791e+00 -6.65021591e+01 -1.03624992e+02 -8.87675323e+01 -2.86521358e+01 -1.67599812e+01 -6.15823174e+01 -1.03632553e+02 -1.02363785e+02 -7.40047073e+01 -7.58556366e+01 -1.10546265e+02 -1.14725327e+02 -7.87323380e+01 -4.85098152e+01 -7.40397339e+01 -8.78878250e+01 -6.43665695e+01 -5.49963913e+01 -7.83098373e+01 -9.71259995e+01 -1.11360886e+02 -9.66688614e+01 -1.22887817e+02 -1.29970459e+02 -1.26870209e+02 -1.30427734e+02 -1.47951019e+02 -1.60136658e+02 -1.06050797e+02 -8.57116241e+01 -7.67109756e+01 -1.19238510e+02 -1.08123451e+02 -1.04941734e+02 -1.20637459e+02 -1.53144638e+02 -1.65931168e+02 -1.09275818e+02 -8.10990448e+01 -8.05785980e+01 -1.29309052e+02 -1.37744537e+02 -1.17012856e+02 -9.62530670e+01 -8.60546188e+01 -1.24380135e+02 -1.14053871e+02 -9.83596725e+01 -5.57868462e+01 -3.97430267e+01 -4.87308273e+01 -8.48842850e+01 -1.14341133e+02 -9.40545731e+01 -6.34367332e+01 -5.01469688e+01 -7.04287338e+01 -5.19053917e+01 -5.21979446e+01 -7.28104935e+01 -1.14082031e+02 -1.13096458e+02 -6.63858490e+01 -5.01553497e+01 -6.96695099e+01 -1.14785934e+02 -9.99952774e+01 -8.06924515e+01 -6.54739227e+01 -7.82752609e+01 -9.89961014e+01 -1.00420296e+02 -1.11172050e+02 -8.41955643e+01 -7.14777908e+01 -6.44110947e+01 -8.91460571e+01 -1.01350044e+02 -8.76631393e+01 -7.18443527e+01 -6.76788025e+01 -6.10525360e+01 -2.99377766e+01 -1.30433569e+01 -2.07537689e+01 -2.98874493e+01 -3.02058125e+01 -1.20867329e+01 -8.21991062e+00 -2.28051014e+01 -5.91426964e+01 -7.23100662e+01 -7.63043213e+01 -7.18931580e+01 -8.40575562e+01 -1.08010269e+02 -1.19941566e+02 -1.21244965e+02 -9.76062393e+01 -8.71556473e+01 -8.52995758e+01 -9.35577240e+01 -8.79938278e+01 -7.78561172e+01 -6.57847519e+01 -6.60549774e+01 -6.82035751e+01 -5.21590652e+01 -3.96303215e+01 -4.78844452e+01 -7.05061798e+01 -7.91373978e+01 -7.87590485e+01 -9.90441132e+01 -1.13443634e+02 -1.20790283e+02 -9.79980316e+01 -9.59692459e+01 -9.45274506e+01 -8.42400589e+01 -8.45998459e+01 -9.73163376e+01 -1.24315239e+02 -1.30087479e+02 -1.08850021e+02 -8.87596664e+01 -9.00025864e+01 -1.08143982e+02 -1.23352577e+02 -1.15181084e+02 -9.89431992e+01 -8.39401550e+01 -8.46194153e+01 -9.88014526e+01 -1.10839500e+02 -1.25458229e+02 -1.26515556e+02 -1.26245270e+02 -1.31583160e+02 -1.30125717e+02 -1.31142899e+02 -1.11283379e+02 -1.10736900e+02 -1.10709068e+02 -1.11153015e+02 -1.13287125e+02 -1.22173935e+02 -1.48912857e+02 -1.53326096e+02 -1.35665451e+02 -1.00405830e+02 -8.36939926e+01 -1.04138428e+02 -1.30225586e+02 -1.31590881e+02 -1.03381142e+02 -7.59249954e+01 -8.43618622e+01 -1.08485405e+02 -1.25417625e+02 -1.22634117e+02 -1.05826469e+02 -1.05057564e+02 -1.14498093e+02 -1.24027725e+02 -1.26131660e+02 -1.13271431e+02 -1.13585701e+02 -1.19686653e+02 -1.25468292e+02 -1.24734535e+02 -1.17758804e+02 -1.21680832e+02 -1.21544777e+02 -1.10475525e+02 -9.82448273e+01 -1.00934258e+02 -1.21133972e+02 -1.33002060e+02 -1.27595078e+02 -1.13460266e+02 -1.06448212e+02 -1.09568497e+02 -1.18571655e+02 -1.21463303e+02 -1.22305046e+02 -1.14799019e+02 -1.14197166e+02 -1.15583725e+02 -1.18618698e+02 -1.21166618e+02 -1.16394539e+02 -1.13395416e+02 -1.08790047e+02 -1.09033112e+02 -1.11123901e+02 -1.14600487e+02 -1.19874168e+02 -1.21223755e+02 -1.17774490e+02 -1.11258423e+02 -1.08558868e+02 -1.11556427e+02 -1.16577614e+02 -1.17530998e+02 -1.14239372e+02 -1.11651688e+02 -1.12212921e+02 -1.14235405e+02 -1.14735115e+02 -1.14558784e+02 -1.14429031e+02 -1.14587852e+02 -1.14383530e+02 -1.13692886e+02 -1.12653358e+02 -1.12343361e+02 -1.11233513e+02 -1.10833626e+02 -1.12063362e+02 -1.15046181e+02 -1.16279541e+02 -1.13422653e+02 -1.10037071e+02 -1.10757057e+02 -1.16204887e+02 -1.21334770e+02 -1.19621193e+02 -1.12755791e+02 -1.10773674e+02 -1.13606796e+02 -1.20202469e+02 -1.18765160e+02 -1.13574768e+02 -1.07291275e+02 -1.03218033e+02 -1.07810677e+02 -1.07690681e+02 -1.10471489e+02 -1.08621315e+02 -1.07646614e+02 -1.05427933e+02 -9.99604416e+01 -1.04080223e+02 -1.11286926e+02 -1.20676842e+02 -1.16684845e+02 -1.03665810e+02 -9.35849991e+01 -1.00961327e+02 -1.15802269e+02 -1.25866730e+02 -1.25164703e+02 -1.14475166e+02 -1.09760994e+02 -1.07217979e+02 -1.13307106e+02 -1.09223335e+02 -1.03277794e+02 -9.49154129e+01 -8.65666046e+01 -8.93632584e+01 -1.04010330e+02 -1.17793777e+02 -1.19042305e+02 -1.11162956e+02 -1.02922401e+02 -9.10756454e+01 -8.45711212e+01 -1.00161461e+02 -1.27070038e+02 -1.40125626e+02 -1.21479187e+02 -9.95642319e+01 -9.66920395e+01 -1.21685059e+02 -1.49073944e+02 -1.46619476e+02 -1.13714500e+02 -7.78316269e+01 -6.41795883e+01 -8.63977814e+01 -1.04646919e+02 -1.05187874e+02 -9.45572815e+01 -8.71694412e+01 -9.97681656e+01 -1.00710930e+02 -1.04654137e+02 -1.15760895e+02 -1.18326485e+02 -1.18270187e+02 -9.79646149e+01 -1.00468384e+02 -1.22285278e+02 -1.50568863e+02 -1.46800491e+02 -1.02375671e+02 -6.84293900e+01 -7.86088333e+01 -1.17678673e+02 -1.46003799e+02 -1.47008636e+02 -1.14888802e+02 -8.21279907e+01 -6.62029419e+01 -9.18057098e+01 -1.11560112e+02 -1.28740860e+02 -1.25335930e+02 -1.16961075e+02 -1.18804001e+02 -1.20129181e+02 -1.45103317e+02 -1.59544846e+02 -1.59919708e+02 -1.40767166e+02 -1.02007210e+02 -8.64717636e+01 -1.08178558e+02 -1.47123093e+02 -1.59751999e+02 -1.35466690e+02 -9.60239410e+01 -9.58513489e+01 -1.23841454e+02 -1.63894760e+02 -1.72269470e+02 -1.31565140e+02 -9.14171982e+01 -7.29621353e+01 -1.05867805e+02 -1.37596664e+02 -1.39286362e+02 -1.18910255e+02 -9.13931961e+01 -8.50262909e+01 -8.07696075e+01 -9.77608795e+01 -1.32603271e+02 -1.42243591e+02 -1.11305328e+02 -5.73511162e+01 -3.90309906e+01 -6.87830505e+01 -1.12302986e+02 -1.41100006e+02 -1.21787766e+02 -8.00515594e+01 -5.70492325e+01 -6.85912552e+01 -9.85280609e+01 -9.93330688e+01 -7.88311615e+01 -5.51416435e+01 -5.43211594e+01 -9.08712158e+01 -1.16901550e+02 -1.04645592e+02 -7.48706894e+01 -3.50132370e+01 -3.83585014e+01 -3.78552513e+01 -5.52522354e+01 -7.88449707e+01 -9.39372101e+01 -9.83341675e+01 -6.29137726e+01 -3.99136696e+01 -5.26516342e+01 -8.55772858e+01 -1.17420090e+02 -9.46119919e+01 -6.07894135e+01 -3.96477470e+01 -8.43088150e+01 -1.58804596e+02 -1.94173538e+02 -1.52011200e+02 -6.34409065e+01 -4.29308968e+01 -1.23781952e+02 -2.15709991e+02 -1.23274055e+02 -1.50884369e+02 -1.24769821e+02 -1.22425430e+02 2.87493286e+02 -1.22395068e+03 -2.37746118e+03 -7.06446191e+03 -2.36734648e+04 -5.90321971e+09 271363584. 6.41086925e+09 544389376. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 888686720. 981909888. -1.75417285e+04 -6.57703418e+03 -6.05154785e+02 -1.39233301e+03 -4.02011206e+03 -2.52497119e+03 -4.51570068e+02 -2.04850327e+02 -2.78377716e+02 -1.95557220e+02 -8.28491364e+01 -2.76884651e+01 -3.18019695e+01 -1.02461136e+02 -1.45067368e+02 -1.30382401e+02 -4.23781929e+01 2.97385998e+01 1.73286972e+01 -3.37085266e+01 -4.40853348e+01 -4.36913109e+01 -4.78529663e+01 -9.22147598e+01 -5.78385963e+01 -4.83420715e+01 -1.03389748e+02 -1.53648743e+02 -1.17036232e+02 -1.98778927e+00 5.82789459e+01 -1.47104807e+01 -1.07153313e+02 -1.64668625e+02 -1.30419800e+02 -2.15601120e+01 6.57586212e+01 1.12266777e+02 3.18038502e+01 -2.88061256e+01 -4.13180962e+01 1.87651577e+01 5.78202400e+01 2.23214283e+01 1.35038109e+01 -2.39840965e+01 -5.89929771e+01 -7.35655899e+01 -3.52143631e+01 7.22071381e+01 8.05825806e+01 -1.06760559e+01 -1.22190552e+02 -1.55428284e+02 -6.35706978e+01 3.01261311e+01 2.99770279e+01 -4.01356544e+01 -7.22992554e+01 1.59608376e+00 1.18532784e+02 1.46187439e+02 9.93569717e+01 -2.68623180e+01 -1.11890961e+02 -1.13273979e+02 -3.21448631e+01 7.20479965e+01 1.37162399e+02 1.67363098e+02 1.40859283e+02 8.17777100e+01 1.48614492e+01 -1.60803699e+01 8.24856091e+00 1.10132611e+00 -7.22641525e+01 -1.42449326e+02 -1.37164948e+02 -4.98963699e+01 1.71427746e+01 -2.63042307e+00 -3.87543602e+01 -1.02728668e+02 -1.40544952e+02 -1.04404411e+02 -3.68398952e+00 6.24217796e+01 3.19424987e+00 -6.75867004e+01 -6.52233810e+01 -1.46712923e+01 -3.09377503e+00 -2.57806206e+01 -8.96588230e+00 -1.56253614e+01 -5.66787148e+01 -8.57309799e+01 -5.22113152e+01 5.66986160e+01 6.95121994e+01 -3.42667923e+01 -1.72998886e+02 -2.14767853e+02 -1.25674515e+02 -1.81626148e+01 1.67958736e+01 2.24572039e+00 -3.98753777e+01 -4.08813438e+01 -1.94978600e+01 4.02181625e+01 7.19492416e+01 1.48439245e+01 -9.29683380e+01 -1.21883766e+02 -8.08723755e+01 -3.48387260e+01 -3.09345894e+01 1.11212616e+01 1.10411615e+01 -8.40689850e+01 -1.87719162e+02 -1.84553162e+02 -4.32617035e+01 1.72030373e+01 -6.25728569e+01 -1.78840851e+02 -1.98658401e+02 -8.52219849e+01 3.05690174e+01 6.10137253e+01 1.41800995e+01 -7.51983795e+01 -1.46309189e+02 -1.18072342e+02 -1.94318161e+01 5.06102104e+01 -1.44990015e+01 -1.21513931e+02 -1.54918365e+02 -1.13640152e+02 -5.88660965e+01 -2.31795101e+01 3.48995209e+01 4.86524353e+01 1.54674749e+01 -3.15778160e+01 -2.91539249e+01 3.38832703e+01 7.02216949e+01 5.03665447e+00 -1.24375854e+02 -2.24640701e+02 -1.78357819e+02 -4.41923752e+01 5.27448769e+01 4.24451523e+01 -3.02993946e+01 -5.49073563e+01 -4.01730118e+01 -2.19367409e+01 1.28216801e+01 5.94222689e+00 -1.25278749e+01 -4.81589470e+01 -1.08510712e+02 -1.45280350e+02 -1.52896912e+02 -7.61664352e+01 -2.75485592e+01 -8.63121262e+01 -1.44189667e+02 -1.15117752e+02 9.96682549e+00 8.20452957e+01 4.56767960e+01 -2.02919102e+01 -7.36744690e+01 -8.25034103e+01 -4.91934662e+01 -2.94929581e+01 -2.61444607e+01 -8.60108719e+01 -7.09199829e+01 -1.13958292e+01 5.91063499e+01 1.32687622e+02 1.71517700e+02 2.06921173e+02 1.29341415e+02 1.97388802e+01 -4.21523476e+01 -2.68602982e+01 3.74020386e+01 4.55546379e+01 -3.06554165e+01 -1.28886627e+02 -1.73023636e+02 -6.83864899e+01 8.51745987e+01 1.54414185e+02 1.20044891e+02 4.93902321e+01 2.80126438e+01 3.77730713e+01 5.88400612e+01 9.46853714e+01 6.31795921e+01 8.52574825e+00 -3.51006927e+01 1.04651623e+01 2.26647091e+01 4.65254631e+01 6.58336029e+01 9.30334167e+01 6.39430771e+01 3.77528992e+01 4.52066231e+01 4.62039566e+01 4.47504520e+00 -6.12885971e+01 -1.06602036e+02 -1.28535431e+02 -6.69479980e+01 -2.13793869e+01 6.97796021e+01 8.36743011e+01 3.37919731e+01 -4.63547783e+01 -7.22974167e+01 -1.25783281e+01 2.15055180e+01 1.75593739e+01 7.92331505e+00 1.98954830e+01 1.60520782e+01 2.13333092e+01 1.58295860e+01 9.69958973e+00 7.25239325e+00 7.24398661e+00 -1.74832571e+00 -2.85243073e+01 -3.33370552e+01 -1.46768093e+01 5.57870007e+00 -2.63030624e+00 -2.33541985e+01 -8.28277206e+00 2.21067977e+00 4.03164902e+01 5.34047813e+01 5.69859505e+01 4.57235413e+01 1.38310499e+01 1.58436975e+01 1.79978466e+01 1.85042496e+01 5.68883228e+00 2.75538325e+00 2.39572120e+00 -1.39029527e+00 -6.56079102e+00 -5.76933479e+00 8.04119110e+00 1.26739883e+00 -3.20581532e+00 -2.29036274e+01 -2.80538521e+01 -3.56005478e+01 -1.52796564e+01 -9.72272873e+00 -3.07098222e+00 -8.26923561e+00 -7.65309095e+00 -1.42438231e+01 -1.38414583e+01 -1.39753036e+01 9.82263374e+00 1.31504154e+01 1.57507098e+00 -5.07725191e+00 -1.05374229e+00 5.41052628e+00 -9.86061156e-01 -5.10599971e-01 2.29298573e+01 2.20937634e+01 1.16405449e+01 2.11890054e+00 1.69016476e+01 2.70384007e+01 1.39153862e+01 2.87162132e+01 4.96795921e+01 6.63264008e+01 4.54956131e+01 4.46471024e+01 4.59796638e+01 5.59773407e+01 6.78671188e+01 7.12502518e+01 6.26474609e+01 3.66512108e+01 3.24619331e+01 3.34720306e+01 3.16668301e+01 1.69612331e+01 2.39259033e+01 2.89625454e+01 1.36595030e+01 -2.09237804e+01 -1.76164551e+01 5.85307121e+00 4.02116623e+01 4.45412979e+01 4.45704231e+01 4.36850243e+01 4.15681458e+01 5.32998581e+01 6.14428711e+01 6.06448174e+01 6.90473022e+01 7.37972031e+01 8.03599014e+01 4.23015671e+01 3.68023720e+01 3.88733253e+01 4.80492287e+01 4.47626228e+01 4.71584015e+01 5.59153633e+01 5.72323647e+01 6.46486740e+01 7.82783737e+01 7.42553864e+01 6.33778191e+01 4.60780373e+01 5.35972748e+01 6.01373482e+01 7.33883438e+01 7.31522446e+01 4.64584579e+01 3.47143860e+01 2.78577271e+01 6.31413841e+01 7.31059952e+01 8.16776886e+01 5.85808182e+01 4.08532600e+01 2.59546337e+01 2.80145130e+01 1.93509369e+01 1.51706114e+01 1.30482845e+01 3.20870781e+01 5.30300140e+01 5.86115952e+01 4.75749016e+01 4.22842941e+01 3.88421326e+01 4.04874763e+01 3.16207275e+01 3.45957909e+01 4.00783958e+01 5.84716682e+01 5.39773293e+01 1.04707527e+01 -3.25993500e+01 -2.51258430e+01 2.46871014e+01 6.80218811e+01 4.77150383e+01 1.88077927e+01 5.98663044e+00 2.36889057e+01 4.95440254e+01 3.60227051e+01 2.06518764e+01 1.63243866e+01 2.33960838e+01 2.60198803e+01 1.09419985e+01 -2.68166256e+00 -4.77740192e+00 2.35055828e+01 5.42357483e+01 5.96974640e+01 3.69981995e+01 3.12119293e+01 3.75399551e+01 5.33987122e+01 4.56882439e+01 2.56368370e+01 3.87497997e+00 1.59809980e+01 5.07305603e+01 7.86875610e+01 7.59268799e+01 6.96074753e+01 7.47416458e+01 1.02450089e+02 1.35840500e+02 1.38728851e+02 1.07672913e+02 7.08479385e+01 5.62800255e+01 4.78190460e+01 2.76805859e+01 2.34830704e+01 6.73255920e+01 1.19995071e+02 1.31865326e+02 9.11708221e+01 5.25781021e+01 5.49540443e+01 6.57543335e+01 8.28518372e+01 9.95176315e+01 9.13634186e+01 7.49718323e+01 4.35593719e+01 4.17248917e+01 3.61143150e+01 7.13396378e+01 1.19755531e+02 1.29882477e+02 1.09138916e+02 6.76154251e+01 4.79297791e+01 2.07276096e+01 2.30696087e+01 4.63513985e+01 7.03174286e+01 8.53583069e+01 8.84742584e+01 8.28113022e+01 8.95454330e+01 9.21025238e+01 9.71362762e+01 9.23532333e+01 8.97425613e+01 7.93551102e+01 -5.26047039e+00 -7.99024429e+01 -1.77632950e+02 -1.14462708e+02 -2.98372631e+01 8.33094330e+01 2.36987972e+01 -6.67640076e+01 4.45229950e+01 -2.16536148e+02 -4.33758301e+03 -1.03038721e+04 -468581088. -166904384. -278647392. 34589056. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1153186048. 374735552. -1.91875703e+04 -7.17846191e+03 -5.49217407e+02 -1.04884766e+02 -2.57562183e+03 -1.71737524e+03 -2.51602890e+02 -1.56704224e+02 1.60976830e+01 5.64893341e+01 6.64836121e+01 6.84655228e+01 6.73558044e+01 6.82617569e+01 6.55307922e+01 1.01446671e+02 1.76237839e+02 2.28616623e+02 2.02971817e+02 1.76853165e+02 1.37709747e+02 3.99217224e+01 -1.24436874e+01 -7.68625832e+00 1.33022585e+01 -8.61943531e+00 -5.44288750e+01 1.05006886e+01 -2.20124359e+01 -5.93175364e+00 1.61505451e+01 8.30534973e+01 1.02050301e+02 1.14158401e+02 1.20709785e+02 1.28214523e+02 1.32205261e+02 1.34608704e+02 1.26239555e+02 1.19289108e+02 1.19110313e+02 1.23018425e+02 1.28634415e+02 1.31633835e+02 1.34422531e+02 1.25621902e+02 1.08625473e+02 9.24173355e+01 8.88168945e+01 9.69906387e+01 1.04935387e+02 1.09778709e+02 1.16203590e+02 1.11443077e+02 1.07398552e+02 1.08006157e+02 1.16578964e+02 1.23607079e+02 1.20609726e+02 1.27075470e+02 1.16885284e+02 1.10192139e+02 1.03378746e+02 1.02936089e+02 1.00683945e+02 9.79790192e+01 1.01220001e+02 1.05806168e+02 1.04747398e+02 1.05555428e+02 1.17308266e+02 1.21695892e+02 1.21460838e+02 1.11364044e+02 1.09623085e+02 1.11313385e+02 1.04804825e+02 9.08259811e+01 9.24487000e+01 9.83856964e+01 1.05156830e+02 8.71479874e+01 7.29635849e+01 7.33774643e+01 8.41019974e+01 9.20139694e+01 9.14566879e+01 9.04833603e+01 9.45643463e+01 9.21900711e+01 8.57021408e+01 7.59019318e+01 8.02537537e+01 9.55030136e+01 1.08764442e+02 1.13430260e+02 1.11441895e+02 1.09242165e+02 1.05855103e+02 1.12231262e+02 1.18904373e+02 1.14526810e+02 1.05264954e+02 1.03940804e+02 1.12381950e+02 1.17582886e+02 1.04692017e+02 9.58196564e+01 9.76673889e+01 1.10410309e+02 1.20116310e+02 1.20778870e+02 1.19704338e+02 1.17851196e+02 1.17121811e+02 1.14303261e+02 1.14189835e+02 1.15369827e+02 1.15373459e+02 1.13900452e+02 1.13025635e+02 1.14192940e+02 1.15910538e+02 1.14102058e+02 1.13759827e+02 1.12892990e+02 1.06835976e+02 1.00098381e+02 1.00618790e+02 1.06869949e+02 1.12138435e+02 1.05338013e+02 9.86382904e+01 9.87497177e+01 1.04904572e+02 1.10634216e+02 1.11741608e+02 1.12541580e+02 1.14683495e+02 1.14189095e+02 1.13401001e+02 1.12890198e+02 1.13993919e+02 1.15744171e+02 1.15192474e+02 1.13994537e+02 1.12680855e+02 1.13551163e+02 1.14023277e+02 1.13704323e+02 1.11784401e+02 1.08480766e+02 1.05477783e+02 1.06500862e+02 1.09110214e+02 1.12356857e+02 1.10286263e+02 1.08317108e+02 1.09013710e+02 1.11901665e+02 1.14517799e+02 1.14320221e+02 1.14128235e+02 1.13771553e+02 1.13957863e+02 1.13919319e+02 1.14061073e+02 1.14192429e+02 1.14218040e+02 1.13816628e+02 1.13506256e+02 1.13715324e+02 1.14107079e+02 1.14383904e+02 1.14421791e+02 1.14421913e+02 1.14671379e+02 1.15165604e+02 1.15354179e+02 1.15148445e+02 1.14769890e+02 1.14712883e+02 1.14265663e+02 1.15098160e+02 1.16840775e+02 1.17546829e+02 1.16763161e+02 1.15519394e+02 1.15449890e+02 1.15590332e+02 1.15062805e+02 1.15180023e+02 1.15600731e+02 1.15734238e+02 1.18520302e+02 1.21518196e+02 1.21864014e+02 1.18856674e+02 1.16125877e+02 1.16886024e+02 1.17033119e+02 1.19673340e+02 1.23007103e+02 1.22623764e+02 1.17554810e+02 1.12531647e+02 1.14127907e+02 1.15163963e+02 1.15881660e+02 1.13792984e+02 1.12668442e+02 1.11904449e+02 1.12627563e+02 1.13649879e+02 1.13566391e+02 1.12770622e+02 1.11928131e+02 1.09390938e+02 1.06835930e+02 1.05005180e+02 1.04887718e+02 1.06735466e+02 1.06710938e+02 1.06872391e+02 1.05968826e+02 1.07708824e+02 1.08854118e+02 1.07456841e+02 1.07919037e+02 1.08629150e+02 1.08276520e+02 1.05552116e+02 1.04997223e+02 1.07601036e+02 1.07641182e+02 1.06257858e+02 1.04739792e+02 1.08649445e+02 1.09511086e+02 1.12930565e+02 1.12240753e+02 1.12885704e+02 1.05782303e+02 9.87732315e+01 1.03621155e+02 1.18421944e+02 1.26557007e+02 1.22433784e+02 1.13213493e+02 1.13335365e+02 1.15575668e+02 1.19367439e+02 1.21223236e+02 1.20919983e+02 1.18930183e+02 1.15836403e+02 1.11705620e+02 1.08177124e+02 1.08133049e+02 1.10808357e+02 1.13179970e+02 1.13342453e+02 1.13659203e+02 1.13694199e+02 1.13848557e+02 1.09948738e+02 1.08735970e+02 1.05124687e+02 1.10639832e+02 1.22829704e+02 1.36699417e+02 1.35263596e+02 1.23670265e+02 1.11884598e+02 1.09230835e+02 1.09045982e+02 1.14656654e+02 1.25531288e+02 1.33333939e+02 1.35554611e+02 1.23170319e+02 1.13198128e+02 1.02098763e+02 1.08154640e+02 1.10608246e+02 1.12340553e+02 1.09830215e+02 1.09681648e+02 1.05957367e+02 1.08706772e+02 1.12196846e+02 1.15380051e+02 1.16965172e+02 1.16103706e+02 1.31850388e+02 1.40877914e+02 1.37677307e+02 1.16956223e+02 1.02491089e+02 1.10138916e+02 1.18411377e+02 1.17063126e+02 1.13404327e+02 1.22004669e+02 1.37017807e+02 1.36810989e+02 1.21201584e+02 1.04003151e+02 1.10704811e+02 1.15311592e+02 1.13364609e+02 9.90567551e+01 9.86957245e+01 1.01559227e+02 1.10698578e+02 1.05746010e+02 9.35293121e+01 9.33735580e+01 9.58378448e+01 1.00324265e+02 9.24990692e+01 1.01788521e+02 1.17567230e+02 1.20556786e+02 1.29819855e+02 1.43951675e+02 1.62912140e+02 1.64311295e+02 1.52750656e+02 1.54995651e+02 1.42080582e+02 1.37385254e+02 1.17011620e+02 9.14859238e+01 6.08804932e+01 5.55336723e+01 6.72371063e+01 8.00283279e+01 8.30511932e+01 8.62225494e+01 8.92625504e+01 8.78546295e+01 7.70280457e+01 9.31176224e+01 1.23483322e+02 1.37582825e+02 1.34043121e+02 1.11309769e+02 1.04530647e+02 9.73638153e+01 8.43025055e+01 1.01938240e+02 1.02922562e+02 1.15983238e+02 1.17261749e+02 1.29137329e+02 1.49598389e+02 1.31420212e+02 1.10860504e+02 9.72715149e+01 1.19873795e+02 1.26879326e+02 1.15691719e+02 9.22905273e+01 1.12963600e+02 1.36601105e+02 1.44261887e+02 1.25007683e+02 1.04468742e+02 1.29861725e+02 1.52594620e+02 1.48636246e+02 1.11667572e+02 8.66361771e+01 1.09173683e+02 1.25146988e+02 1.01321693e+02 6.44865494e+01 8.59966507e+01 1.26082916e+02 1.47876892e+02 1.32124451e+02 1.22516579e+02 1.21638908e+02 1.42261673e+02 1.58758438e+02 1.51673477e+02 1.08857491e+02 7.94814606e+01 8.18766022e+01 8.91265259e+01 9.09631805e+01 8.17310486e+01 8.45670624e+01 9.07013702e+01 1.11706329e+02 1.12152809e+02 9.62724686e+01 8.54492569e+01 8.50405197e+01 1.09214607e+02 1.25279099e+02 1.21015480e+02 1.09236435e+02 8.37315216e+01 8.96820145e+01 9.15214157e+01 8.71561203e+01 6.86966934e+01 6.68607025e+01 1.10937233e+02 1.48153046e+02 1.13737358e+02 4.77949753e+01 4.26675606e+01 1.00132149e+02 1.23788681e+02 9.25150146e+01 7.51933823e+01 9.95559540e+01 1.09426949e+02 9.99214554e+01 7.71791992e+01 9.18008575e+01 1.05851501e+02 1.12532516e+02 9.69138107e+01 7.31662369e+01 7.11327133e+01 6.93505936e+01 9.79220123e+01 1.18672981e+02 1.21783279e+02 9.62119141e+01 9.46805420e+01 1.52757050e+02 1.81832092e+02 1.63629135e+02 1.13100746e+02 1.11092171e+02 1.28713959e+02 1.06579407e+02 5.45213242e+01 3.49925003e+01 6.74477310e+01 9.34614334e+01 9.04513931e+01 7.61528625e+01 9.13817291e+01 9.22471390e+01 9.32255402e+01 8.36188278e+01 7.14015579e+01 5.38725052e+01 4.87966042e+01 5.83290825e+01 7.27880478e+01 9.44886627e+01 1.01843330e+02 1.03485176e+02 1.16560112e+02 1.19758141e+02 9.60098495e+01 6.60512085e+01 7.46811905e+01 1.09522362e+02 1.16235260e+02 1.08701370e+02 1.29797958e+02 1.85151566e+02 2.13726593e+02 1.86651108e+02 1.17794243e+02 9.94803696e+01 1.13014374e+02 1.21083031e+02 8.84091568e+01 6.34605827e+01 5.50730553e+01 4.75558510e+01 5.31274872e+01 6.53497009e+01 6.68741684e+01 4.76738968e+01 4.73115501e+01 1.00901489e+02 1.28304459e+02 9.87977753e+01 6.39999123e+01 9.82715073e+01 1.25702156e+02 9.50404205e+01 1.76783161e+01 -2.57553997e+01 -1.74464760e+01 -4.49391222e+00 8.87092209e+00 6.49235773e+00 1.12738161e+01 4.27124739e+00 2.44552364e+01 4.27899513e+01 4.95010452e+01 1.23802652e+01 2.78680439e+01 9.07841644e+01 1.40936508e+02 1.52621155e+02 1.39934143e+02 1.12342613e+02 7.57665939e+01 4.30983505e+01 5.35525093e+01 5.30021439e+01 5.22739487e+01 4.50155182e+01 5.13024254e+01 4.86840057e+01 5.20400391e+01 5.38382568e+01 4.72076836e+01 4.61600227e+01 4.12176094e+01 8.23745499e+01 1.24120728e+02 1.30502335e+02 9.61863022e+01 6.40939636e+01 6.78669357e+01 6.27420807e+01 6.63989792e+01 6.39528160e+01 6.42292709e+01 6.34913177e+01 8.66597214e+01 1.26627487e+02 1.08981300e+02 6.26210747e+01 4.75563431e+01 1.23332336e+02 1.73682861e+02 1.40576248e+02 6.88900833e+01 6.91340103e+01 1.08512512e+02 1.06498940e+02 7.91389771e+01 4.47228203e+01 7.95347366e+01 1.05013496e+02 1.30224197e+02 1.34284317e+02 9.00707932e+01 5.83130989e+01 6.68991394e+01 1.44076889e+02 1.80976379e+02 1.25538414e+02 5.37954712e+01 6.56883545e+01 1.22875717e+02 1.32941635e+02 1.01171585e+02 6.72413025e+01 9.41332932e+01 1.20989029e+02 1.36770111e+02 1.20163727e+02 8.49580841e+01 5.96371040e+01 9.11364212e+01 1.36408035e+02 1.50661057e+02 1.21342125e+02 6.26035118e+01 8.65631638e+01 1.08651634e+02 1.16209366e+02 8.04552002e+01 7.81826172e+01 1.21899933e+02 1.14762779e+02 7.60379562e+01 1.35348434e+01 4.32123375e+00 -4.01488580e-02 4.35059013e+01 9.15194855e+01 1.10277641e+02 9.10083771e+01 5.31944237e+01 3.12427292e+01 3.59878731e+01 5.98464127e+01 1.05819778e+02 1.16285049e+02 2.29840225e+02 2.72266296e+02 5.16150085e+02 2.47385956e+02 2.89264209e+03 -2.14130264e+02 -1.66074072e+03 3.14277173e+03 3.87220947e+03 4.06610522e+03 1.29894014e+04 25046594. -8.42500710e+09 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. -1101049216. -22439274. 4.14685898e+04 1.67291855e+04 2.34686670e+03 -3.62198901e+03 -1.93899158e+03 -8.67557907e+01 6.25456238e+00 -5.71653557e+01 9.76858444e+01 2.45580734e+02 3.50779266e+01 1.55488342e+03 2.78223291e+03 1.56362595e+02 -4.64798779e+03 -2.98160303e+03 -8.30647827e+02 -5.72818298e+02 -3.39329926e+02 -3.75329170e+01 3.19712505e+01 4.30337524e+01 1.32319870e+01 2.03633232e+01 2.86197281e+01 -3.78588796e+00 -3.29555969e+01 -2.25058002e+01 5.22423897e+01 1.09516281e+02 1.21016388e+02 6.73276672e+01 -1.13336439e+01 -4.52222023e+01 -3.66169128e+01 -3.88975143e+01 -4.45583458e+01 -4.26342125e+01 8.00564384e+00 5.98518562e+01 5.18428230e+01 5.26911068e+00 -2.58712730e+01 -2.10566878e+00 -5.51374376e-01 -6.63918018e+00 1.72704887e+01 1.67758350e+01 2.25348186e+01 2.40530729e+00 -2.99444637e+01 -6.84016800e+01 -9.09380264e+01 -2.91773243e+01 5.40705757e+01 8.38343964e+01 4.09061852e+01 -4.11676712e+01 -4.48424149e+01 -6.49980307e+00 2.11757469e+01 4.81551695e+00 -2.47720108e+01 -8.65808392e+00 2.25409298e+01 3.70639420e+01 -4.70290422e+00 -6.34315033e+01 -4.89912376e+01 -3.19488792e+01 -1.47540894e+01 -1.51760902e+01 -1.95767612e+01 -2.38458395e+00 -1.84269791e+01 -5.05438538e+01 -8.79088669e+01 -9.13969345e+01 -5.40861511e+01 -2.91754580e+00 4.22423019e+01 4.68078613e+01 1.09201694e+00 -2.00632915e+01 -2.33201656e+01 -5.38222847e+01 -1.07114357e+02 -1.08806091e+02 -4.23353653e+01 3.31204758e+01 4.04369698e+01 -1.53217573e+01 -8.68364105e+01 -1.00210304e+02 -9.58850632e+01 -9.23833389e+01 -8.92773590e+01 -7.78772964e+01 -4.73875732e+01 -2.14901161e+01 -2.71904430e+01 -5.81723633e+01 -7.15434036e+01 -3.91388779e+01 5.56542206e+00 2.33151035e+01 1.80387745e+01 -2.45708466e+01 -5.87103195e+01 -4.67020378e+01 -4.63236389e+01 -6.72425385e+01 -9.42709122e+01 -7.44552536e+01 -2.37568855e+01 -1.37678938e+01 -5.94732780e+01 -1.09992516e+02 -1.22264404e+02 -7.99198608e+01 -3.83334122e+01 -4.49696392e-01 1.26461201e+01 -1.15249052e+01 -2.91763458e+01 -3.26816406e+01 -6.43853912e+01 -9.97515030e+01 -1.14795578e+02 -8.67625275e+01 -4.55397491e+01 -2.31649952e+01 -2.60412540e+01 -5.17111855e+01 -6.71611557e+01 -7.05941391e+01 -7.68770370e+01 -1.01582718e+02 -1.01251770e+02 -6.16368866e+01 4.56504393e+00 3.79518547e+01 1.67579994e+01 -1.60203266e+01 -2.94766369e+01 -4.36863708e+01 -4.76016960e+01 -3.60303612e+01 -2.34945621e+01 -1.45511603e+00 1.15795832e+01 2.27340055e+00 -3.40496941e+01 -6.07994499e+01 -4.20314980e+01 -7.40441656e+00 -1.12393408e+01 -4.47201729e+01 -6.63111877e+01 -3.61287003e+01 4.99260139e+00 -7.60880089e+00 -2.65246983e+01 -4.14965935e+01 7.32187414e+00 5.55289230e+01 7.64334412e+01 1.90232620e+01 -5.71095047e+01 -8.02137451e+01 -7.81943665e+01 -7.65752487e+01 -7.76080551e+01 -5.01847839e+01 -7.79704189e+00 2.06789436e+01 -1.47241879e+01 -5.78080406e+01 -7.77271881e+01 -4.56218147e+01 -1.95754604e+01 -8.94827557e+00 -1.41988201e+01 -6.62692881e+00 6.04813242e+00 1.85938263e+01 -6.51810741e+00 -2.18834114e+01 -3.10452290e+01 -7.81135035e+00 1.95052280e+01 2.51511974e+01 -2.51998863e+01 -8.50257034e+01 -9.78478775e+01 -7.86813202e+01 -7.52896194e+01 -8.09444885e+01 -7.50326767e+01 -3.65294418e+01 -1.87974472e+01 -4.88249779e+01 -9.38347549e+01 -1.10597054e+02 -7.92359009e+01 -5.65660858e+01 -4.80472336e+01 -4.84755363e+01 -4.66401062e+01 -3.83111649e+01 -2.13453045e+01 -4.41477890e+01 -7.49235458e+01 -8.95675278e+01 -6.45259094e+01 -2.21742878e+01 -1.54367132e+01 -4.47396469e+01 -7.34758072e+01 -7.66274643e+01 -6.33649712e+01 -7.08545380e+01 -7.77739487e+01 -8.14694138e+01 -8.42901764e+01 -7.18959808e+01 -7.02418976e+01 -7.11315842e+01 -9.11785355e+01 -9.28562393e+01 -8.40385208e+01 -7.33927231e+01 -4.49790344e+01 -3.68661270e+01 -2.16253033e+01 -3.39663887e+01 -4.87072105e+01 -7.23102951e+01 -8.86719131e+01 -5.65256500e+01 -2.92103634e+01 -3.12720299e+01 -6.31246834e+01 -7.84658508e+01 -6.44493256e+01 -4.81353149e+01 -6.24907646e+01 -7.07378769e+01 -6.27824821e+01 -3.65225487e+01 -2.61797543e+01 -3.58660278e+01 -3.20256004e+01 -4.47262650e+01 -5.08900299e+01 -7.22183685e+01 -5.57190094e+01 -4.75996666e+01 -3.68229561e+01 -2.33308430e+01 -1.83506718e+01 -2.28524990e+01 -5.95187454e+01 -8.37258835e+01 -6.92246094e+01 -2.43816624e+01 -6.64657640e+00 -2.68946953e+01 -3.76312523e+01 -3.36216011e+01 -2.11696014e+01 -4.34237633e+01 -5.61380577e+01 -6.58752441e+01 -6.25102043e+01 -6.51480103e+01 -6.09573860e+01 -4.58200836e+01 -4.66431656e+01 -6.20508003e+01 -7.83712082e+01 -7.07272873e+01 -7.72323227e+01 -9.37438660e+01 -9.18840179e+01 -6.75449295e+01 -4.58171234e+01 -5.40392189e+01 -6.26407547e+01 -5.52510071e+01 -3.90586205e+01 -4.68414574e+01 -6.00136833e+01 -6.09276009e+01 -4.86054153e+01 -3.91568069e+01 -4.70215111e+01 -4.70019226e+01 -5.38398628e+01 -5.47160721e+01 -6.88973541e+01 -7.78273010e+01 -7.29226913e+01 -6.24729919e+01 -6.05858421e+01 -6.93088074e+01 -7.85467834e+01 -8.75336304e+01 -9.53640289e+01 -9.06682968e+01 -8.20700302e+01 -7.59349213e+01 -8.66773300e+01 -9.68593369e+01 -8.46001892e+01 -5.88298836e+01 -5.46051025e+01 -6.65686951e+01 -7.52313995e+01 -5.92145920e+01 -4.38722534e+01 -4.83075981e+01 -5.77549973e+01 -7.28271866e+01 -7.73306427e+01 -8.52786789e+01 -8.73520813e+01 -8.27569733e+01 -7.96241150e+01 -7.79921341e+01 -7.99893112e+01 -7.63515396e+01 -8.15419312e+01 -8.99939651e+01 -8.46911621e+01 -6.67511597e+01 -5.66647263e+01 -5.84066124e+01 -6.01303291e+01 -5.11546974e+01 -4.32988129e+01 -5.45960999e+01 -5.88569908e+01 -6.24578667e+01 -5.70849075e+01 -6.00250626e+01 -6.42217865e+01 -5.77476158e+01 -5.95941353e+01 -6.32675056e+01 -7.74295044e+01 -7.98110886e+01 -7.38102493e+01 -6.43297424e+01 -5.97079735e+01 -6.37714615e+01 -6.78725204e+01 -7.24636917e+01 -8.27033844e+01 -8.12744980e+01 -6.27258682e+01 -4.27371407e+01 -3.57267418e+01 -4.70723877e+01 -5.23459244e+01 -5.03931847e+01 -5.14460487e+01 -4.75282707e+01 -5.42856369e+01 -5.60358963e+01 -5.98604279e+01 -5.81647186e+01 -4.33702545e+01 -3.99518929e+01 -4.39854584e+01 -6.32550735e+01 -7.65077438e+01 -6.73882675e+01 -5.58440170e+01 -5.13897285e+01 -6.56103592e+01 -7.86087341e+01 -7.40561295e+01 -7.08447876e+01 -6.37972374e+01 -6.11455498e+01 -5.95737076e+01 -5.58739243e+01 -5.91082916e+01 -6.11827087e+01 -6.41039200e+01 -6.62815094e+01 -5.93481789e+01 -5.48531380e+01 -5.08811760e+01 -5.45134468e+01 -6.32085114e+01 -6.30068855e+01 -6.34464645e+01 -6.59456024e+01 -7.29258652e+01 -7.16075974e+01 -5.93338623e+01 -5.27363014e+01 -5.34523621e+01 -6.06894264e+01 -6.43788681e+01 -6.41595154e+01 -6.47299194e+01 -6.38441734e+01 -6.17936287e+01 -6.14934769e+01 -5.95726662e+01 -6.09647522e+01 -6.02619629e+01 -6.07393990e+01 -6.22828712e+01 -6.36418152e+01 -6.72001648e+01 -6.72653046e+01 -6.62010269e+01 -6.47386322e+01 -6.19896011e+01 -6.14545059e+01 -6.20006218e+01 -6.55881653e+01 -6.76111755e+01 -6.71542511e+01 -6.50288696e+01 -6.39010849e+01 -6.49056091e+01 -6.62626266e+01 -6.62984085e+01 -6.58277054e+01 -6.55141449e+01 -6.54207840e+01 -6.54530258e+01 -6.55654373e+01 -6.55366821e+01 -6.54107971e+01 -6.52817459e+01 -6.54587936e+01 -6.68446503e+01 -6.78907242e+01 -6.78112030e+01 -6.59397888e+01 -6.41357498e+01 -6.51021957e+01 -6.72824936e+01 -6.83094254e+01 -6.59952393e+01 -6.29208107e+01 -6.29308205e+01 -6.48152542e+01 -6.69391861e+01 -6.61702423e+01 -6.44053421e+01 -6.53396683e+01 -6.75833588e+01 -6.88120575e+01 -6.95696182e+01 -6.81239700e+01 -6.95789413e+01 -6.85439072e+01 -6.84946136e+01 -6.75965805e+01 -6.62460938e+01 -6.97921524e+01 -6.66329346e+01 -6.39491806e+01 -5.79664536e+01 -6.03303070e+01 -6.85482025e+01 -7.49521255e+01 -7.55539169e+01 -6.60898438e+01 -5.83509140e+01 -5.70407143e+01 -6.14664650e+01 -6.88390274e+01 -7.01494827e+01 -6.49912491e+01 -6.14267349e+01 -5.89607315e+01 -6.33087006e+01 -7.20554199e+01 -7.90442123e+01 -7.83235245e+01 -6.47035294e+01 -5.62123833e+01 -5.39739838e+01 -5.76854134e+01 -6.94872589e+01 -7.76671600e+01 -7.73481064e+01 -6.29925613e+01 -5.16099129e+01 -5.72574730e+01 -7.04009247e+01 -7.86162033e+01 -6.77475357e+01 -5.09912987e+01 -4.93986740e+01 -5.90840492e+01 -7.32893448e+01 -8.14932327e+01 -7.88424988e+01 -7.56630402e+01 -6.74243927e+01 -6.18145866e+01 -6.18786545e+01 -6.34907455e+01 -7.36033859e+01 -7.12326508e+01 -6.53066940e+01 -6.16542435e+01 -5.30923424e+01 -6.30300865e+01 -6.27372093e+01 -6.01631432e+01 -4.76223793e+01 -4.58497086e+01 -7.21434860e+01 -8.56578140e+01 -8.46381302e+01 -5.90048027e+01 -4.25848007e+01 -4.15445747e+01 -5.26713905e+01 -6.87320786e+01 -7.90417328e+01 -7.73520050e+01 -7.23047485e+01 -6.25397301e+01 -5.89291763e+01 -6.56014023e+01 -6.42927780e+01 -6.60391998e+01 -4.68093681e+01 -4.18754082e+01 -4.21346359e+01 -4.91180038e+01 -6.74601898e+01 -6.90057907e+01 -6.02005501e+01 -3.41300087e+01 -2.52031574e+01 -3.27653885e+01 -5.15171700e+01 -6.43847427e+01 -5.33703194e+01 -3.05663261e+01 -2.22872829e+01 -3.20317688e+01 -5.07258263e+01 -6.01143761e+01 -5.80379028e+01 -5.56379204e+01 -5.58018570e+01 -6.16814880e+01 -6.59908371e+01 -7.38938599e+01 -8.51497192e+01 -7.18995667e+01 -4.79273338e+01 -3.34586449e+01 -4.67497253e+01 -7.51902237e+01 -9.04996948e+01 -8.39194870e+01 -5.66627884e+01 -3.31633873e+01 -4.71719971e+01 -6.13893127e+01 -7.49761887e+01 -6.45129166e+01 -5.97778702e+01 -6.83057861e+01 -7.64291611e+01 -8.38462448e+01 -8.54327469e+01 -7.81712418e+01 -7.91857529e+01 -7.19636993e+01 -7.19583054e+01 -7.44028397e+01 -6.97052689e+01 -7.85509033e+01 -7.30021896e+01 -6.79714508e+01 -5.62408066e+01 -4.66210938e+01 -6.85172806e+01 -7.13644867e+01 -7.16271210e+01 -5.00452690e+01 -3.96013794e+01 -5.79975204e+01 -6.91663589e+01 -9.40109329e+01 -7.71002350e+01 -4.56787186e+01 -1.72365608e+01 -1.59022484e+01 -5.92067909e+01 -6.73455353e+01 -4.52359695e+01 -1.11338504e-01 9.17937374e+00 1.74928246e+01 2.35831490e+01 4.19100609e+01 1.41624786e+02 1.95870410e+03 1.10258655e+03 2.13292310e+03 6.74792822e+03 -125253952. 185504224. -139222448. 967352960. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 888686720. 981909888. -1.75417285e+04 -6.57703418e+03 -6.05154785e+02 -1.39233301e+03 -7.29704956e+02 1.84465344e+03 4.05449493e+02 -2.52783798e+02 -2.61522766e+02 -1.95381149e+02 -5.38930664e+02 -3.60985291e+02 -1.08202858e+02 8.11611099e+01 1.92987061e+02 1.63544418e+02 2.00001160e+02 1.44241058e+02 1.06313171e+02 1.90300007e+01 8.81903362e+00 -1.11463947e+01 -1.22672141e+00 -5.01148272e+00 -5.12246094e+01 -6.93178406e+01 -4.50298615e+01 -7.92007017e+00 -3.00837784e+01 -8.28856888e+01 -9.70344086e+01 -6.86202164e+01 -3.44236336e+01 -2.71981163e+01 -3.72052650e+01 -5.51965027e+01 -7.82789688e+01 -9.39541931e+01 -8.39266434e+01 -6.32849388e+01 -3.94759178e+01 -6.31000862e+01 -8.24304276e+01 -1.00105255e+02 -1.22953697e+02 -9.61950989e+01 -5.37856941e+01 4.63988781e-02 -7.72993279e+00 -6.96704178e+01 -7.90768051e+01 -5.45916595e+01 1.11182988e+00 7.39457893e+00 -3.36723862e+01 -5.76478691e+01 -6.69248352e+01 -4.06191978e+01 -3.97229767e+01 -5.60393372e+01 -7.78510666e+01 -1.07133179e+02 -1.21623894e+02 -1.02271294e+02 -6.44640198e+01 -3.80982208e+01 -5.46593323e+01 -8.02254028e+01 -1.16135887e+02 -1.51215668e+02 -1.58777176e+02 -1.48561188e+02 -1.06934166e+02 -8.12742920e+01 -1.01003479e+02 -7.99594193e+01 -4.28511620e+01 2.64683800e+01 1.57874918e+01 -3.42391739e+01 -6.17786026e+01 -6.64230118e+01 -6.37819862e+01 -5.78271484e+01 -3.94167824e+01 -2.58626881e+01 -4.65310516e+01 -7.23397293e+01 -6.04638901e+01 -5.63663330e+01 -6.53852005e+01 -9.56355667e+01 -8.31843109e+01 -5.26590614e+01 -7.50371246e+01 -7.33749924e+01 -6.62095718e+01 -2.35700455e+01 -1.89765110e+01 -7.46000290e+01 -8.01019516e+01 -4.63190956e+01 2.54560165e+01 4.24200020e+01 -7.84918118e+00 -4.25999489e+01 -7.13526993e+01 -7.38594055e+01 -8.01415558e+01 -8.81306839e+01 -6.89783325e+01 -7.21277924e+01 -7.88000488e+01 -7.87570953e+01 -5.29300766e+01 -2.02812634e+01 -3.11594753e+01 -3.43868790e+01 -2.55262146e+01 -5.66260414e+01 -5.74878120e+01 -3.22020645e+01 3.81522064e+01 4.21257858e+01 -3.85993462e+01 -6.58562012e+01 -3.37138863e+01 3.20710907e+01 3.85951843e+01 -1.63466892e+01 -3.98214111e+01 -5.25408745e+01 -4.73919067e+01 -2.78846607e+01 5.08304644e+00 2.42363853e+01 -1.16795588e+01 -5.36263885e+01 -4.10357475e+01 -6.32522821e+00 2.98815689e+01 5.90640962e-01 -1.97641621e+01 -3.33506775e+01 -5.08745689e+01 -5.38826141e+01 -6.12292099e+01 -4.68825340e+01 -4.40769157e+01 -7.35948868e+01 -8.10159836e+01 -5.78148270e+01 1.18057785e+01 6.57113037e+01 4.66849480e+01 1.04536114e+01 -3.89030571e+01 -4.34085846e+01 -4.77098694e+01 -6.66849976e+01 -8.23012619e+01 -6.81605530e+01 -5.68343506e+01 -5.38419342e+01 -7.09043198e+01 -4.60980835e+01 1.79808736e+00 4.39777412e+01 4.97286377e+01 -1.42232113e+01 -3.29125481e+01 -9.99386311e+00 3.64987450e+01 2.12747307e+01 -2.68340073e+01 -3.55862198e+01 -4.18906326e+01 -3.79752312e+01 -3.13394737e+01 -1.34988194e+01 2.25102091e+00 -2.01909370e+01 -4.15824394e+01 -2.74352798e+01 -2.87111626e+01 -3.89233932e+01 -7.96762772e+01 -1.18212585e+02 -1.33544739e+02 -1.48921371e+02 -8.67361755e+01 -3.79069824e+01 -2.64322233e+00 -2.50668049e+00 -4.73514595e+01 -4.06398926e+01 -1.55417099e+01 4.66527138e+01 5.65966339e+01 -1.01402121e+01 -6.37272644e+01 -9.68900909e+01 -7.02328186e+01 -7.15501328e+01 -7.55705261e+01 -7.34235992e+01 -6.56142731e+01 -7.51462936e+01 -7.54167175e+01 -5.59943962e+01 -1.46609716e+01 -2.12590351e+01 3.71220922e+00 -2.30875826e+00 -4.31319313e+01 -8.77035675e+01 -8.07307892e+01 -3.42964058e+01 -1.17896366e+01 -1.83857956e+01 1.53885889e+01 3.93435287e+01 6.83400269e+01 8.10699158e+01 4.30292397e+01 9.11840343e+00 -5.24115562e+01 -5.80041847e+01 -1.57215357e+01 2.79145699e+01 3.53449669e+01 3.42869306e+00 -1.51099491e+01 9.79104042e-01 2.40011141e-01 3.72589588e+00 6.51881027e+00 5.06860685e+00 4.55115604e+00 2.01356626e+00 5.71592808e-01 -8.31075609e-01 6.17400217e+00 2.63752518e+01 3.57602386e+01 2.23153152e+01 5.97067118e+00 5.41074848e+00 1.70363731e+01 1.31634312e+01 7.28190756e+00 -2.46208210e+01 -3.99171066e+01 -4.03746681e+01 -1.74530697e+01 8.10647392e+00 3.98078966e+00 2.92555022e+00 -8.11628327e-02 1.74499214e+00 -4.83527136e+00 -4.83765841e+00 -4.53893232e+00 7.35899162e+00 2.63285613e+00 1.08415871e+01 1.48618374e+01 2.08439465e+01 2.57152157e+01 2.80664673e+01 2.78620014e+01 1.83627949e+01 2.79175797e+01 3.41143532e+01 3.86379433e+01 2.38389626e+01 2.77288055e+01 3.16448860e+01 2.75948429e+01 1.57663345e+01 1.31627579e+01 3.24448318e+01 4.23686600e+01 3.78106537e+01 3.75519447e+01 4.90236092e+01 4.77348175e+01 3.37126045e+01 1.57573557e+01 1.75186749e+01 1.84123745e+01 1.77414913e+01 2.09633656e+01 2.27878418e+01 1.19260769e+01 -6.19955635e+00 -6.82276773e+00 6.84827900e+00 1.87044945e+01 1.24539833e+01 1.83201408e+01 1.26264706e+01 1.70837841e+01 1.15151615e+01 1.64910450e+01 1.24185629e+01 1.32313395e+01 2.94402199e+01 4.50614052e+01 4.16299820e+01 3.10556698e+01 2.81555653e+01 2.57415371e+01 1.49830036e+01 8.89198685e+00 1.95016251e+01 2.81653652e+01 2.35284100e+01 8.76208401e+00 1.96730461e+01 3.67676620e+01 4.15106659e+01 2.48291302e+01 4.12551260e+00 9.47832093e-02 5.27119815e-01 7.99122667e+00 3.28291931e+01 5.52776108e+01 6.31418037e+01 4.85237198e+01 3.26389771e+01 2.79904099e+01 2.54582729e+01 2.08917046e+01 1.89032269e+01 2.28583546e+01 2.69505272e+01 2.64290638e+01 2.87668171e+01 2.83199482e+01 1.94596806e+01 5.43457747e+00 -4.95130444e+00 -8.07832527e+00 -1.24822350e+01 -1.82957077e+00 7.44757318e+00 1.34416924e+01 8.61930275e+00 2.47994061e+01 3.30687065e+01 4.19610901e+01 2.69996910e+01 3.03349609e+01 2.20680981e+01 3.04080563e+01 2.22961807e+01 3.18410931e+01 2.70590496e+01 1.29962606e+01 -1.28360367e+01 1.97910233e+01 6.01514397e+01 7.55295334e+01 4.63566704e+01 1.95690308e+01 2.49867001e+01 3.14908581e+01 4.04577675e+01 3.54399414e+01 3.05951729e+01 2.64877720e+01 4.10973282e+01 4.94969177e+01 4.70327301e+01 2.42612572e+01 6.36489344e+00 2.09533710e+01 3.68689957e+01 5.35300636e+01 5.03165245e+01 5.26471405e+01 5.85601006e+01 7.39551239e+01 8.48457184e+01 7.21774139e+01 5.05590591e+01 4.00597916e+01 4.54427261e+01 4.28692017e+01 3.99896774e+01 3.47282143e+01 4.08675842e+01 3.88955269e+01 4.95951195e+01 4.52888412e+01 5.65543365e+01 4.70499687e+01 4.98512726e+01 4.51637383e+01 3.67285042e+01 1.89154282e+01 -1.42550402e+01 -2.48387432e+01 -1.29115601e+01 1.00101318e+01 2.31120129e+01 2.93044796e+01 3.43787384e+01 2.95941601e+01 2.15707016e+01 1.75661392e+01 1.98414078e+01 3.00288486e+01 3.74919167e+01 2.67013321e+01 8.98540974e+00 2.34735942e+00 9.44202137e+00 2.36522121e+01 2.84716568e+01 3.85770912e+01 4.63624535e+01 5.75942421e+01 5.14868851e+01 4.43139763e+01 4.04609451e+01 4.96997108e+01 5.32047844e+01 5.17246475e+01 5.59004669e+01 5.84225616e+01 5.22567863e+01 4.78564987e+01 4.26561584e+01 4.94424477e+01 5.46688156e+01 5.71917038e+01 5.20541267e+01 4.01753731e+01 3.42249222e+01 3.38135719e+01 3.87825546e+01 6.42227249e+01 1.44478592e+02 1.21165703e+02 2.29416397e+02 1.42254944e+02 1.09733960e+03 1.58870959e+03 3.08006134e+02 2.18010086e+02 5.78293030e+02 4.83591357e+03 1.15579453e+04 177180416. 45672612. 77218000. 593099968. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1153186048. 374735552. -1.91875703e+04 -7.17846191e+03 -5.49217407e+02 -1.04884766e+02 2.15180756e+02 2.89480377e+02 3.61253418e+02 3.94289246e+02 4.51289978e+02 4.98751190e+02 5.14952515e+02 4.71387604e+02 4.28284119e+02 4.31613403e+02 4.28861633e+02 4.46881317e+02 2.58912646e+03 1.48641089e+03 2.99929749e+02 1.24724983e+02 1.00089844e+02 8.60798416e+01 8.50577011e+01 7.63937683e+01 6.21607399e+01 5.17073326e+01 4.58931122e+01 4.59683418e+01 4.94176292e+01 5.44132080e+01 5.36395721e+01 4.84724960e+01 4.45315552e+01 4.45003624e+01 4.96491699e+01 5.07675743e+01 5.27310524e+01 5.06357613e+01 5.36552658e+01 5.71420174e+01 5.74024353e+01 5.42015533e+01 4.81887856e+01 4.31035347e+01 3.94908180e+01 4.36427078e+01 4.25558815e+01 4.13555260e+01 4.14025726e+01 4.76661224e+01 5.32552872e+01 5.16819763e+01 4.91060982e+01 5.17713242e+01 5.47147827e+01 5.79360161e+01 5.53356323e+01 5.34871330e+01 5.47288513e+01 5.60852356e+01 6.55158844e+01 7.38273010e+01 7.65748672e+01 7.73696518e+01 7.53761215e+01 8.14623718e+01 8.27836533e+01 7.68468933e+01 6.95874939e+01 5.94226227e+01 5.67253571e+01 5.44611588e+01 5.03656197e+01 4.42409210e+01 4.05398483e+01 4.24107780e+01 5.01074448e+01 5.79920654e+01 6.04922791e+01 6.16810532e+01 5.92098198e+01 6.76070786e+01 7.47217331e+01 8.28708267e+01 8.64249496e+01 8.30608597e+01 7.70939560e+01 6.85704193e+01 6.78774643e+01 6.90390625e+01 7.74589462e+01 8.31340561e+01 8.10531464e+01 7.13843079e+01 6.49921799e+01 6.56529007e+01 6.87572174e+01 7.08730545e+01 7.32696381e+01 6.64198990e+01 5.84553108e+01 5.58993492e+01 6.01485405e+01 6.56521912e+01 6.38140488e+01 6.40627747e+01 6.93885727e+01 7.37168655e+01 7.81916275e+01 7.62619476e+01 7.06802216e+01 6.28237648e+01 5.60798836e+01 5.59110374e+01 5.88243294e+01 6.17728233e+01 6.31631584e+01 6.06129532e+01 5.97831001e+01 6.07179680e+01 6.18794289e+01 6.28886414e+01 6.29786491e+01 6.49079361e+01 6.48881760e+01 6.51154709e+01 6.95425186e+01 7.48500748e+01 7.52192688e+01 7.04601822e+01 6.61709747e+01 6.91917648e+01 7.25517120e+01 7.49978485e+01 7.47816162e+01 7.23882141e+01 6.87361145e+01 6.55212402e+01 6.41552200e+01 6.45659637e+01 6.43400345e+01 6.42003937e+01 6.33992996e+01 6.25738411e+01 6.31410675e+01 6.46645279e+01 6.52303085e+01 6.45698624e+01 6.44884109e+01 6.49786758e+01 6.64246368e+01 6.84617233e+01 7.04994278e+01 7.01299362e+01 6.79925156e+01 6.58879700e+01 6.71559372e+01 6.87422028e+01 6.96258316e+01 6.94675980e+01 6.92252731e+01 6.91054001e+01 6.77858276e+01 6.70334091e+01 6.60417557e+01 6.58821793e+01 6.55679321e+01 6.54174118e+01 6.55870972e+01 6.56215591e+01 6.56736069e+01 6.55794907e+01 6.55746231e+01 6.54722137e+01 6.54527206e+01 6.56542664e+01 6.57939224e+01 6.55908813e+01 6.52727814e+01 6.51194992e+01 6.50683289e+01 6.52354507e+01 6.56730423e+01 6.51936874e+01 6.40303802e+01 6.37423210e+01 6.44154434e+01 6.54407120e+01 6.50954437e+01 6.48020935e+01 6.46068039e+01 6.48358307e+01 6.47695618e+01 6.48652115e+01 6.36501427e+01 6.29114075e+01 6.27907906e+01 6.34122543e+01 6.39427528e+01 6.49569550e+01 6.69839630e+01 6.67191467e+01 6.49993668e+01 6.29955139e+01 6.46389999e+01 6.57868347e+01 6.52688980e+01 6.43973160e+01 6.38012733e+01 6.42808151e+01 6.46754684e+01 6.49254837e+01 6.46893692e+01 6.35771027e+01 6.36360435e+01 6.40915527e+01 6.40173492e+01 6.49700546e+01 6.53012161e+01 6.66198654e+01 6.61786270e+01 6.57181015e+01 6.56771851e+01 6.56103592e+01 6.79177704e+01 6.98335724e+01 7.00917664e+01 6.87485428e+01 6.62668304e+01 6.70057068e+01 6.66095810e+01 6.84460678e+01 6.92307510e+01 6.98215256e+01 6.85022125e+01 6.74670486e+01 6.82132416e+01 6.83205948e+01 6.67117462e+01 6.38614655e+01 6.12206306e+01 6.15778236e+01 6.72446823e+01 7.36325531e+01 7.49352646e+01 6.87881470e+01 5.59606323e+01 4.77513466e+01 4.82579155e+01 5.57685013e+01 6.24095192e+01 5.45450287e+01 4.84876823e+01 4.83351326e+01 5.69422722e+01 6.37045403e+01 6.38603897e+01 6.41581116e+01 6.33259583e+01 6.17668457e+01 6.26389694e+01 6.39393234e+01 6.50702209e+01 6.10172195e+01 5.70804634e+01 6.05147362e+01 6.53557358e+01 6.82468796e+01 6.17244148e+01 5.54754829e+01 5.13814888e+01 5.16419830e+01 5.18307228e+01 5.50348663e+01 5.56194725e+01 5.67828941e+01 4.99401207e+01 4.53550529e+01 4.74916687e+01 5.53762779e+01 6.38221512e+01 6.23222694e+01 6.19146881e+01 5.70301666e+01 5.60196533e+01 6.27444687e+01 7.18258743e+01 7.21769867e+01 6.64728317e+01 5.80936012e+01 6.17202415e+01 6.23767738e+01 6.15804138e+01 5.87678032e+01 4.67122955e+01 3.68635254e+01 3.77862625e+01 4.64510689e+01 5.87458801e+01 5.74015503e+01 5.70232620e+01 5.66781425e+01 5.69237556e+01 4.82749367e+01 3.67852058e+01 3.34127350e+01 3.84103279e+01 5.31939087e+01 5.23710175e+01 5.31973076e+01 5.07828255e+01 5.57040291e+01 5.48154221e+01 5.22139626e+01 4.83057785e+01 5.20820389e+01 5.63495903e+01 5.71681213e+01 5.44097862e+01 5.57944145e+01 6.00596085e+01 5.98530388e+01 5.88078461e+01 5.52551689e+01 4.77069855e+01 3.21948738e+01 2.14257584e+01 1.70429611e+01 1.91216202e+01 1.98591309e+01 3.54841118e+01 4.31414566e+01 5.14088249e+01 5.17473183e+01 5.67922249e+01 4.95433426e+01 3.74313583e+01 3.88767395e+01 4.48328171e+01 6.30670815e+01 7.31133957e+01 7.45029297e+01 6.90719757e+01 5.25764236e+01 4.80020714e+01 4.13930397e+01 3.18341656e+01 2.52104359e+01 3.13867798e+01 4.63383636e+01 6.52294769e+01 5.78818855e+01 4.97139587e+01 4.01257782e+01 3.94476242e+01 4.14112396e+01 4.42136230e+01 5.54293213e+01 6.21211548e+01 6.17717552e+01 5.94749298e+01 5.86103020e+01 6.14205856e+01 6.42260742e+01 6.16928368e+01 5.67111740e+01 4.91293373e+01 4.34793091e+01 4.25145683e+01 2.57807121e+01 9.23375893e+00 1.78011932e+01 4.82670784e+01 5.75434990e+01 3.38815269e+01 1.77115784e+01 2.81623344e+01 4.74248810e+01 3.10541210e+01 1.54236031e+01 1.07361803e+01 2.40692959e+01 3.54834251e+01 3.64273491e+01 3.11186943e+01 2.28855553e+01 2.00884533e+01 3.08395023e+01 4.71989784e+01 4.91962318e+01 4.76916695e+01 3.93540230e+01 4.06318932e+01 3.52321396e+01 2.79670277e+01 1.25577927e+01 3.04725761e+01 6.25088081e+01 6.02559280e+01 3.19839134e+01 7.70287991e+00 2.52706509e+01 3.86423416e+01 3.19128418e+01 2.53505592e+01 3.65509377e+01 5.55289307e+01 6.85582428e+01 6.44784775e+01 6.03171806e+01 3.94330750e+01 1.62485466e+01 2.36583176e+01 5.13166351e+01 5.66257210e+01 2.27547913e+01 1.46386137e+01 3.49985313e+01 5.85001144e+01 5.57641258e+01 5.04356689e+01 6.26740265e+01 8.18714600e+01 6.89503021e+01 4.21117096e+01 2.07629986e+01 3.31789970e+01 4.32018967e+01 4.19846001e+01 3.75877380e+01 3.11631126e+01 2.66459103e+01 2.96226692e+01 4.27844467e+01 4.45870705e+01 2.23483257e+01 -1.22674954e+00 -8.06179225e-01 1.41756697e+01 6.03714466e+00 -2.12697029e+01 -8.01495838e+00 3.18881493e+01 6.80721436e+01 6.56562881e+01 4.77501259e+01 5.19463882e+01 5.89664192e+01 4.96490898e+01 3.41089745e+01 2.00917130e+01 2.65630207e+01 3.88025284e+01 4.59251709e+01 5.38319588e+01 5.41345520e+01 4.91604004e+01 4.59701157e+01 4.53377647e+01 4.60268211e+01 2.70903740e+01 1.03942385e+01 1.82720413e+01 4.28892746e+01 4.89024467e+01 2.98506298e+01 3.54688835e+01 5.47743950e+01 4.88258171e+01 1.40032709e+00 -4.87816200e+01 -5.27511673e+01 -2.62347755e+01 -1.96127682e+01 -2.83390961e+01 -2.16511078e+01 1.99748170e+00 1.68713970e+01 1.12024879e+01 1.27649126e+01 1.32253561e+01 1.15056634e+00 8.81590664e-01 2.19158955e+01 4.66998749e+01 3.21114540e+01 2.96044159e+00 5.05111074e+00 2.59112206e+01 1.92676105e+01 -1.01997299e+01 8.93314457e+00 7.02680817e+01 1.08108383e+02 9.12042618e+01 6.07383995e+01 6.90948410e+01 9.01762390e+01 9.20378189e+01 7.60912933e+01 6.33163033e+01 7.34373627e+01 7.88010254e+01 7.58610229e+01 5.47794800e+01 1.67773495e+01 -1.64338303e+01 -3.75425949e+01 -3.98887825e+01 -2.28471190e-01 4.12394600e+01 5.98887100e+01 4.40202599e+01 2.98246746e+01 3.60856705e+01 3.39584351e+01 4.81260986e+01 7.09772186e+01 6.59216690e+01 4.53257561e+01 2.37362003e+01 2.37926350e+01 1.90524502e+01 -1.44230013e+01 -3.83741722e+01 -3.17007542e+01 -4.66895247e+00 1.42947645e+01 1.19611416e+01 1.74247189e+01 1.57341909e+01 4.90876007e+00 -4.45798159e+00 -1.93760943e+00 5.09520912e+00 8.54451370e+00 1.40156326e+01 2.26822853e+01 2.02544518e+01 -1.25303955e+01 -5.51601677e+01 -5.00634460e+01 -2.26024380e+01 -1.21454248e+01 -3.79977684e+01 -3.96392326e+01 -1.92679787e+01 2.53494477e+00 -2.24951706e+01 -4.95851135e+01 -4.84230270e+01 -2.19936943e+01 2.10117149e+01 2.90292645e+01 2.69701672e+01 -6.55700636e+00 -3.59640198e+01 -3.06538982e+01 8.83186460e-01 1.43840432e+00 -3.22776337e+01 -4.51249924e+01 -2.78277054e+01 8.16239643e+00 -8.92369938e+00 -3.19695969e+01 -3.38741226e+01 -1.26358771e+00 2.93465824e+01 1.71420631e+01 -1.54369507e+01 -2.93457870e+01 -3.10254688e+01 -1.82360821e+01 -1.37529058e+01 -2.41038723e+01 -2.83702946e+01 -5.05313683e+01 -5.49560814e+01 -5.15236893e+01 -3.37023201e+01 -1.30506220e+01 -8.95942593e+00 2.97714376e+00 -3.73777062e-01 -7.94509947e-01 -6.71158743e+00 -1.10164919e+01 -1.31932173e+01 -1.01756382e+01 -5.12718022e-01 2.42741566e+01 3.41196060e+01 8.47553253e-01 -4.01681252e+01 -5.63676796e+01 -7.99318848e+01 -1.48022812e+02 -2.64781433e+02 -2.81401367e+02 -7.76567932e+02 -3.74135406e+02 -1.37690186e+02 -5.12692383e+02 5.70276337e+01 -1.48233337e+03 -4.31090820e+03 -7.69042850e+06 6.81935411e+09 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. -18890046. -2.78302417e+03 -5.65158752e+02 -4.35592804e+02 -1.85760437e+02 5.40331841e+01 9.18388748e+01 2.21943169e+01 3.61165161e+01 4.96953239e+01 2.64753933e+01 1.17102461e+01 1.61708546e+01 -9.51639099e+01 -1.34022079e+02 -4.75708847e+01 1.47646561e+02 2.05017426e+02 1.13462181e+02 5.65123253e+01 -8.29691887e+00 -3.56314507e+01 -2.28150215e+01 -1.78270569e+01 -1.04873142e+01 -4.84984159e+00 1.97070370e+01 4.89609070e+01 5.07047844e+01 2.03807583e+01 -1.01660490e+01 -6.21350241e+00 -2.99037242e+00 -3.58854938e+00 1.60477028e+01 1.67867699e+01 1.39723978e+01 -2.95037031e+00 -1.99032841e+01 -3.57167854e+01 -4.31467857e+01 -8.78202343e+00 3.78948708e+01 5.37417603e+01 2.61505108e+01 -2.34343700e+01 -2.84011059e+01 -1.08606672e+01 -1.03056679e+01 -1.69449310e+01 -2.98277855e+00 2.26086674e+01 3.66313477e+01 1.43145428e+01 -2.03412399e+01 -5.37498245e+01 -4.94144020e+01 -3.79669228e+01 -2.75495167e+01 -8.01783371e+00 4.90974140e+00 1.55385771e+01 -2.40814090e+00 -2.48615437e+01 -4.62159538e+01 -4.66764259e+01 -1.38501425e+01 1.62766361e+01 2.92084389e+01 3.58415375e+01 1.92448215e+01 1.83757191e+01 3.35595012e+00 -2.75970936e+01 -5.17511024e+01 -5.53200417e+01 -2.61790943e+01 6.42745137e-01 8.84368801e+00 -2.62433553e+00 -2.69470081e+01 -3.54097748e+01 -4.15984268e+01 -3.86678352e+01 -2.92580643e+01 -2.55314045e+01 -1.73820992e+01 -1.23615217e+01 -1.35494070e+01 -2.72730770e+01 -4.47334976e+01 -3.73148727e+01 -1.24348955e+01 1.35431919e+01 1.41557741e+01 -2.04448814e+01 -4.07036591e+01 -2.66146488e+01 -1.73912220e+01 -3.25759544e+01 -4.48321953e+01 -2.35183811e+01 1.38411713e+01 2.55983524e+01 -1.12225747e+00 -3.65683975e+01 -5.62432251e+01 -4.42176819e+01 -3.34689102e+01 -1.86036968e+01 -4.84203911e+00 -6.75297642e+00 -6.42037058e+00 -1.18841972e+01 -3.42153282e+01 -5.87194099e+01 -6.49295959e+01 -3.62592545e+01 -9.02729452e-01 1.22837477e+01 -2.06880474e+00 -2.85377445e+01 -3.91592979e+01 -3.92027321e+01 -3.99635963e+01 -3.63525620e+01 -2.40971661e+01 -2.39627218e+00 2.39460335e+01 2.64556713e+01 8.70576859e+00 -1.25922680e+01 -1.79905796e+01 -2.44071007e+01 -3.69117012e+01 -3.33327293e+01 -2.72258930e+01 -1.24245176e+01 -1.49493494e+01 -2.02655621e+01 -2.45299625e+01 -2.30250950e+01 -1.08861675e+01 -8.51525688e+00 -1.86389809e+01 -3.21031990e+01 -3.58908119e+01 -1.41895952e+01 3.65501595e+00 -6.74519300e+00 -1.44317713e+01 -1.85896873e+01 -4.56199884e+00 7.54976702e+00 6.90397215e+00 -2.58122482e+01 -5.88328476e+01 -5.29169884e+01 -1.49060850e+01 9.27288723e+00 8.68210793e+00 -2.89795899e+00 2.23897743e+00 1.19264118e-01 -2.14512196e+01 -4.68999557e+01 -5.23557320e+01 -2.99675102e+01 -1.12087059e+01 9.90461445e+00 2.29843216e+01 1.45980749e+01 1.05423546e+01 1.45850372e+00 -8.93409348e+00 -1.52686224e+01 -1.84385738e+01 1.63740468e+00 1.04485760e+01 1.07248383e+01 -6.47431278e+00 -2.92892742e+01 -3.39353943e+01 -2.54531918e+01 -2.10682507e+01 -1.74925804e+01 -1.95432262e+01 -3.87697601e+00 7.35733151e-01 -2.22736015e+01 -5.21194420e+01 -6.21151009e+01 -4.14510765e+01 -1.71284237e+01 5.36180878e+00 1.76888866e+01 8.23328209e+00 -2.28294873e+00 -1.37834864e+01 -3.67875290e+01 -5.81106644e+01 -6.13993607e+01 -3.13357773e+01 2.43245554e+00 1.94005718e+01 4.72528219e+00 -2.84066849e+01 -4.44082756e+01 -3.76320572e+01 -2.37833672e+01 -2.24713326e+01 -2.49946804e+01 -2.75330772e+01 -2.29766502e+01 -2.07606735e+01 -2.03066921e+01 -3.17943573e+01 -4.12492943e+01 -4.02620926e+01 -2.69293900e+01 -7.00973558e+00 -2.79590797e+00 -2.84698510e+00 -1.55070391e+01 -3.16105042e+01 -3.57558174e+01 -3.76047363e+01 -1.47860661e+01 -3.77532744e+00 -6.23877573e+00 -2.06343994e+01 -2.14876328e+01 -9.43076515e+00 7.33612478e-01 -2.20282803e+01 -4.34518127e+01 -5.25565338e+01 -2.97599182e+01 -1.20264292e+01 -1.19677114e+01 -9.22257996e+00 -2.48831367e+01 -3.74579811e+01 -5.18335304e+01 -3.23075600e+01 -1.18783255e+01 -1.27413321e+01 -1.85896301e+01 -1.45548458e+01 2.38844109e+00 4.38816220e-01 -1.97277431e+01 -2.61522217e+01 -1.06837759e+01 -6.95338535e+00 -2.11150875e+01 -2.74425087e+01 -2.04559631e+01 -1.43885498e+01 -2.77063408e+01 -3.56559563e+01 -3.64346046e+01 -2.20528736e+01 -1.28116646e+01 -1.50480776e+01 -1.54097538e+01 -2.56430016e+01 -3.45950050e+01 -3.79639320e+01 -3.34794235e+01 -3.42070770e+01 -4.33547516e+01 -3.59128952e+01 -2.61929379e+01 -2.35752029e+01 -3.71949387e+01 -4.64735451e+01 -4.26642494e+01 -2.87589741e+01 -2.49051323e+01 -3.25008354e+01 -3.47977219e+01 -3.03851261e+01 -2.75895481e+01 -3.04453964e+01 -2.11307983e+01 -1.23689985e+01 -1.18959293e+01 -2.87025986e+01 -4.53813477e+01 -4.75621414e+01 -4.25425949e+01 -3.58470383e+01 -3.57917137e+01 -3.47299461e+01 -3.93169479e+01 -4.59453011e+01 -4.58483543e+01 -4.16426086e+01 -3.55368843e+01 -4.15826035e+01 -4.66105270e+01 -3.88539238e+01 -2.19864044e+01 -2.04601059e+01 -3.32445412e+01 -4.36341934e+01 -3.85025368e+01 -3.83321114e+01 -4.30611649e+01 -4.43622093e+01 -4.41592293e+01 -4.59963379e+01 -5.20617752e+01 -5.33977509e+01 -4.94525948e+01 -5.17974548e+01 -5.34265137e+01 -5.03068275e+01 -4.13121910e+01 -3.73867455e+01 -4.25139465e+01 -4.06356010e+01 -2.90130634e+01 -2.14023418e+01 -2.16312485e+01 -2.42695866e+01 -2.12302246e+01 -1.83405380e+01 -2.54980831e+01 -3.31984062e+01 -3.80273590e+01 -3.59731407e+01 -3.70533409e+01 -4.20870857e+01 -4.21355171e+01 -4.21618042e+01 -4.55817528e+01 -4.92777100e+01 -4.77540512e+01 -3.71220284e+01 -3.63086853e+01 -3.74210167e+01 -3.95213318e+01 -3.70708771e+01 -3.71667442e+01 -4.64397469e+01 -4.55803757e+01 -3.61902008e+01 -2.55656643e+01 -2.18191509e+01 -2.89203110e+01 -2.90465431e+01 -2.62689705e+01 -2.31845856e+01 -2.41121120e+01 -3.31552162e+01 -3.75170670e+01 -4.09345589e+01 -3.60621414e+01 -2.19117813e+01 -1.87625790e+01 -2.49417686e+01 -3.97503738e+01 -4.48494987e+01 -3.53469429e+01 -3.11572933e+01 -3.20734329e+01 -4.01418457e+01 -4.40939941e+01 -3.91146698e+01 -3.77044830e+01 -3.36654625e+01 -2.98674908e+01 -2.87964935e+01 -2.97216682e+01 -3.59537773e+01 -3.73343658e+01 -3.60652618e+01 -3.28704224e+01 -3.00903759e+01 -3.30076408e+01 -3.59321556e+01 -3.97005730e+01 -3.71541176e+01 -2.99527340e+01 -2.67794361e+01 -3.09030476e+01 -3.85424271e+01 -4.12339668e+01 -3.48690567e+01 -2.86616993e+01 -2.61571445e+01 -3.07744179e+01 -3.63198013e+01 -3.66696053e+01 -3.69114532e+01 -3.41438675e+01 -3.13100033e+01 -2.97416115e+01 -2.93298645e+01 -3.27378120e+01 -3.34802055e+01 -3.42346497e+01 -3.33471870e+01 -3.24609795e+01 -3.40219612e+01 -3.57018776e+01 -3.66822128e+01 -3.52208824e+01 -3.06473484e+01 -2.97583828e+01 -3.11975899e+01 -3.51623344e+01 -3.70752983e+01 -3.56426353e+01 -3.44138641e+01 -3.31238251e+01 -3.43645935e+01 -3.53304062e+01 -3.48794479e+01 -3.41674156e+01 -3.36144753e+01 -3.30184326e+01 -3.30451927e+01 -3.30855713e+01 -3.42426338e+01 -3.45325050e+01 -3.40525284e+01 -3.30081215e+01 -3.22118607e+01 -3.28144569e+01 -3.35049210e+01 -3.38889160e+01 -3.35819130e+01 -3.29953651e+01 -3.29664001e+01 -3.30992775e+01 -3.31481743e+01 -3.30121651e+01 -3.31304169e+01 -3.35958862e+01 -3.42099495e+01 -3.41163673e+01 -3.34658356e+01 -3.29352722e+01 -3.24712906e+01 -3.25465088e+01 -3.31963959e+01 -3.36627083e+01 -3.35879707e+01 -3.23064651e+01 -3.16344261e+01 -3.12886410e+01 -3.17727165e+01 -3.33889542e+01 -3.30226440e+01 -3.24356651e+01 -3.04460907e+01 -3.03113480e+01 -3.18870239e+01 -3.38786087e+01 -3.54282150e+01 -3.39651871e+01 -3.31691055e+01 -3.24132843e+01 -3.27537537e+01 -3.37492752e+01 -3.56124687e+01 -3.59454956e+01 -3.60493240e+01 -3.46858978e+01 -3.48083496e+01 -3.50490837e+01 -3.44808960e+01 -3.44954872e+01 -3.06518555e+01 -3.14356022e+01 -3.17905922e+01 -3.33544464e+01 -3.48364677e+01 -3.24695511e+01 -3.22754631e+01 -3.27099609e+01 -3.67642479e+01 -4.23662643e+01 -4.27832489e+01 -4.08816338e+01 -3.41729851e+01 -2.78371944e+01 -3.05413532e+01 -3.56400375e+01 -4.21877823e+01 -4.31136894e+01 -3.91452560e+01 -3.48710098e+01 -2.75609455e+01 -2.57526989e+01 -2.84205666e+01 -3.26502647e+01 -3.51178398e+01 -3.13354092e+01 -2.66848259e+01 -2.43710232e+01 -2.46356888e+01 -3.40373192e+01 -3.96291580e+01 -4.06758080e+01 -3.26111832e+01 -2.65732479e+01 -3.19394264e+01 -4.04672432e+01 -4.37411728e+01 -3.69460220e+01 -2.86874771e+01 -2.88644218e+01 -2.73449154e+01 -2.96113167e+01 -3.37987747e+01 -3.65398827e+01 -3.44002151e+01 -2.64412632e+01 -2.22462330e+01 -2.58795719e+01 -2.79868279e+01 -3.35689659e+01 -2.97082024e+01 -2.92785511e+01 -2.85631180e+01 -2.83517513e+01 -3.66239128e+01 -3.87608795e+01 -3.82547913e+01 -2.68970985e+01 -2.22141476e+01 -2.14175644e+01 -2.46646729e+01 -2.45339222e+01 -2.51047611e+01 -2.47965794e+01 -2.60018787e+01 -2.18717155e+01 -2.12586250e+01 -2.44498615e+01 -2.85985203e+01 -3.31001472e+01 -2.88454838e+01 -3.00098705e+01 -3.13238831e+01 -3.69243660e+01 -4.05275154e+01 -2.94896679e+01 -2.54918175e+01 -2.27275810e+01 -2.62372169e+01 -3.80842705e+01 -4.41091385e+01 -4.52571030e+01 -3.02572250e+01 -1.62356968e+01 -1.56896105e+01 -2.24022312e+01 -3.33952179e+01 -3.03065643e+01 -2.15409870e+01 -2.19522610e+01 -2.43924809e+01 -2.99487114e+01 -3.32004509e+01 -3.52305298e+01 -3.47311363e+01 -2.65644588e+01 -2.64121685e+01 -2.75441875e+01 -2.58375568e+01 -3.51682892e+01 -3.81431274e+01 -4.19256134e+01 -3.33732948e+01 -2.67856121e+01 -2.88145809e+01 -3.11728230e+01 -2.80361443e+01 -1.75736141e+01 -3.68899345e+00 -1.74697113e+01 -2.98067055e+01 -4.58098259e+01 -4.67108498e+01 -3.97944221e+01 -3.89240837e+01 -2.97424545e+01 -3.17723370e+01 -3.55185890e+01 -3.77690506e+01 -4.64151649e+01 -3.87507133e+01 -3.67729797e+01 -2.92688885e+01 -2.51363068e+01 -3.45977592e+01 -2.62024803e+01 -1.75991344e+01 -5.08045006e+00 -8.50793648e+00 -2.77583866e+01 -3.64530334e+01 -3.71084213e+01 -9.26942825e+00 2.44756527e+01 -2.77979398e+00 2.42950416e+00 -3.98044777e+01 -6.52128754e+01 -2.07011780e+02 7.08321457e+01 1.19370506e+02 -3.28015967e+03 -6.76067285e+03 -125253952. 185504224. -139222448. 967352960. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 888686720. 981909888. 5.54291943e+03 2.14342554e+03 3.08234070e+02 1.57952515e+02 4.09287643e+01 -7.10944977e+01 -2.96683102e+01 1.03744698e+01 1.61063061e+01 -1.26421630e+00 -9.28594875e+00 -2.53943672e+01 -2.88971539e+01 -1.40817871e+01 -1.19285192e+01 -1.70720196e+01 -3.44989700e+01 -4.95572739e+01 -4.25266342e+01 -2.45511703e+01 -2.13159161e+01 -2.27624893e+01 -3.57417374e+01 -2.66871796e+01 -1.77998734e+01 -1.08420019e+01 -3.84355307e+00 -1.14941263e+01 -1.39510307e+01 -3.10239296e+01 -4.78721504e+01 -3.33712997e+01 -1.32051907e+01 8.14173031e+00 7.11411655e-01 -3.89790878e+01 -6.23500862e+01 -6.95073090e+01 -3.50603485e+01 -2.14701672e+01 -3.16121864e+01 -4.41768188e+01 -4.98891258e+01 -2.08749218e+01 1.02038264e+00 5.85801840e+00 -1.20044699e+01 -4.36179504e+01 -5.83770256e+01 -6.11868095e+01 -5.62021980e+01 -2.97709675e+01 -1.71679688e+01 -6.61115885e+00 -1.83053322e+01 -4.33437042e+01 -3.48473930e+01 -2.13664665e+01 -9.87806606e+00 -3.46684990e+01 -7.17012329e+01 -6.21970062e+01 -2.72511444e+01 1.68547020e+01 2.86281414e+01 1.16201553e+01 -1.30986433e+01 -4.48276939e+01 -5.44589653e+01 -4.41047516e+01 -2.09851017e+01 1.93902624e+00 5.15870619e+00 1.99584758e+00 1.83788979e+00 -1.58441849e+01 -1.21400356e+01 -2.52544327e+01 -1.62970924e+01 -1.86804085e+01 -3.23216667e+01 -1.54004993e+01 -4.07390371e-02 2.64015560e+01 2.74715023e+01 -4.02916610e-01 -2.75483608e+01 -3.79857979e+01 -1.52274847e+01 1.21907406e+01 1.63130455e+01 1.51744232e+01 4.24430180e+00 -4.69072580e+00 1.93123865e+00 1.44182134e+00 1.59490929e+01 -6.79987550e-01 -1.63002014e+01 -2.50138664e+01 -2.67531452e+01 -4.25641012e+00 6.34484673e+00 1.71547527e+01 1.41113100e+01 -1.09610701e+01 -6.13535738e+00 2.42517161e+00 2.54427128e+01 2.91815643e+01 5.05051804e+00 -1.75591736e+01 -2.48564091e+01 2.58288860e+00 3.49069290e+01 2.78393269e+01 2.02798233e+01 3.17688489e+00 -6.88895988e+00 -1.01544199e+01 -8.21154308e+00 1.79133873e+01 2.07870007e+01 1.59700375e+01 9.82187653e+00 7.06893802e-01 1.00678864e+01 1.27952995e+01 1.71451035e+01 8.74601173e+00 -2.24284134e+01 -2.45228329e+01 -7.56266308e+00 1.82527828e+01 2.89579792e+01 3.25576663e+00 -1.30538712e+01 -1.75016193e+01 4.32487011e+00 2.67265720e+01 2.04792976e+01 2.23686733e+01 9.99873543e+00 -3.98598671e+00 -1.51873283e+01 -1.53720846e+01 9.96341324e+00 2.26953201e+01 2.08427887e+01 8.97998047e+00 -5.32619047e+00 5.71022177e+00 1.60592785e+01 3.05217056e+01 2.20458183e+01 -9.81557465e+00 -2.61124420e+01 -1.14332418e+01 2.11615257e+01 4.33992462e+01 3.61995125e+01 2.56621952e+01 7.98052597e+00 1.56889057e+01 3.14567604e+01 2.83865433e+01 1.96240463e+01 2.79763675e+00 1.37737024e+00 1.40414152e+01 1.60152302e+01 2.90467091e+01 2.53129654e+01 1.64330750e+01 -5.01014709e+00 -3.31991043e+01 -8.68879986e+00 1.67043171e+01 3.60385361e+01 2.64567280e+01 -1.78872085e+00 9.12586117e+00 1.97789631e+01 3.93313522e+01 3.52019768e+01 1.85451450e+01 1.42670832e+01 4.57003927e+00 -6.49939954e-01 -4.53030872e+00 -1.54768543e+01 2.21837330e+00 7.81275749e+00 6.03379726e+00 1.15806551e+01 2.37879014e+00 2.15430145e+01 1.74265728e+01 3.20445786e+01 2.50201130e+01 -8.86495399e+00 -1.79517689e+01 -1.71462994e+01 1.99747391e+01 3.62332649e+01 2.76327953e+01 1.16541033e+01 -1.92989922e+00 1.46764383e+01 2.97233238e+01 2.00594788e+01 4.57803696e-01 -2.52694511e+01 -2.93670254e+01 -3.45107698e+00 2.40787354e+01 3.43018074e+01 8.33103561e+00 -1.46088133e+01 -7.59039831e+00 -7.91048336e+00 6.47398353e-01 -1.86388946e+00 -6.41314507e+00 -4.59449291e+00 -4.92298126e+00 2.09299469e+00 -1.98557222e+00 -4.60129118e+00 6.48003757e-01 6.99028158e+00 8.00617313e+00 1.56566584e+00 -4.37341738e+00 -1.59173727e+00 -4.08792162e+00 -2.20691729e+00 -5.15191936e+00 1.39154136e+00 3.22922301e+00 7.24628019e+00 7.33392239e+00 5.66124058e+00 2.16227078e+00 -9.92367983e-01 1.45720136e+00 4.61768675e+00 1.05686474e+01 8.52536774e+00 8.49163055e+00 2.88759923e+00 9.08740330e+00 1.27123785e+01 1.35012274e+01 4.49276924e+00 -1.65076390e-01 1.56110895e+00 8.32732856e-01 3.97426581e+00 9.26478672e+00 1.86584606e+01 1.37942858e+01 1.23675747e+01 6.71893883e+00 1.11191435e+01 3.19108868e+00 3.59847069e+00 5.04525948e+00 1.39455194e+01 1.19861794e+01 1.38373699e+01 7.22360373e+00 4.93085194e+00 3.14402199e+00 9.15682316e+00 1.85493507e+01 1.47088394e+01 1.11086283e+01 7.03381252e+00 9.41164970e+00 1.10224943e+01 9.58456135e+00 8.01750660e+00 7.25502443e+00 -1.47339475e+00 -7.40662432e+00 -1.09858818e+01 -4.56489420e+00 -1.15358584e-01 5.43657875e+00 4.27540350e+00 6.10880280e+00 6.34186411e+00 2.15037556e+01 2.46523552e+01 2.85060120e+01 1.09418697e+01 6.69066095e+00 -3.44049883e+00 3.01240945e+00 -1.38051820e+00 1.01938748e+00 1.78152645e+00 8.06793499e+00 9.93859291e+00 1.17246027e+01 5.25948381e+00 -4.58570290e+00 -8.87827206e+00 -2.38845801e+00 2.53971624e+00 1.72209988e+01 3.36873093e+01 4.20629196e+01 3.06666470e+01 8.69559860e+00 2.83983731e+00 2.84402013e+00 1.19520063e+01 6.51358891e+00 -6.98930883e+00 -1.04211168e+01 -1.89027172e-02 1.39914255e+01 1.26114979e+01 1.27417583e+01 1.75591316e+01 2.69509578e+00 -1.52031231e+01 -1.84442997e+01 -5.90964317e+00 3.21213889e+00 1.33317113e+00 4.40636492e+00 5.92490578e+00 4.82771397e+00 9.13166714e+00 1.29892673e+01 1.68631668e+01 5.60549355e+00 2.49374604e+00 4.08717728e+00 1.59965277e+01 3.62504082e+01 4.95008240e+01 4.73001060e+01 2.67078400e+01 1.16472826e+01 1.29671288e+01 2.38312397e+01 2.22516651e+01 1.80674858e+01 1.14563417e+01 2.60883789e+01 3.24878464e+01 3.83588448e+01 2.77131500e+01 2.33457870e+01 1.97951965e+01 2.17893333e+01 3.18226776e+01 4.33429985e+01 2.58608551e+01 9.04837549e-01 -6.02640629e+00 1.00099049e+01 2.11782074e+01 1.92508926e+01 3.20982552e+01 4.50998650e+01 4.54300194e+01 3.04930134e+01 1.55941658e+01 1.45872145e+01 1.88338413e+01 3.11093960e+01 4.32942772e+01 4.75088120e+01 4.00705986e+01 3.27520180e+01 2.65917206e+01 2.68459892e+01 2.35527515e+01 2.38347225e+01 1.80785809e+01 1.43328304e+01 1.13585138e+01 1.65339108e+01 1.70918503e+01 2.01400242e+01 1.96052761e+01 2.45814838e+01 2.29149208e+01 2.24855614e+01 3.12693901e+01 4.01754608e+01 3.60434570e+01 1.10475445e+01 -3.65550447e+00 2.33194160e+00 1.17958279e+01 2.00963135e+01 1.58651943e+01 2.60850639e+01 3.16960144e+01 3.88987961e+01 3.46309967e+01 2.77047482e+01 2.72811298e+01 3.91685181e+01 4.94879570e+01 3.28614159e+01 7.54313469e+00 5.36804676e-01 1.68196125e+01 2.89767361e+01 3.66813393e+01 4.39580460e+01 3.85472336e+01 2.24890022e+01 1.54345417e+01 2.37666912e+01 3.39757347e+01 3.09674778e+01 2.80548267e+01 1.53589001e+01 -2.26741004e+00 -3.89530897e+00 3.31025004e+00 2.02277870e+01 2.87053928e+01 3.52813797e+01 3.06645069e+01 2.22664375e+01 1.80059128e+01 1.60423374e+01 1.36228628e+01 1.12966242e+01 7.91797638e+00 8.21333218e+00 1.22527933e+01 1.89164753e+01 2.04356232e+01 2.31280861e+01 5.15115662e+01 7.22225037e+01 1.09711372e+02 7.83744125e+01 4.41529236e+01 -9.78644466e+00 -1.08890667e+01 -5.57824230e+00 -1.35865993e+01 4.29348259e+01 5.92594482e+02 7.72261658e+01 -8.27843945e+03 45672612. 77218000. 593099968. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1153186048. 6.28572070e+03 1.30400806e+03 1.14375816e+02 1.61247467e+02 7.06306381e+01 6.18631248e+01 5.46031570e+01 4.49700470e+01 3.93374825e+01 2.34453564e+01 1.20196514e+01 9.43473434e+00 2.03248158e+01 2.86696720e+01 2.61280193e+01 2.69992313e+01 2.47502060e+01 -4.52656441e+01 -5.10920372e+01 2.86107326e+00 2.18710957e+01 3.20121269e+01 3.32003098e+01 2.70704327e+01 2.13167496e+01 2.60171299e+01 2.89888515e+01 2.94850388e+01 2.58318443e+01 2.47896557e+01 2.17922668e+01 2.08833523e+01 2.27323418e+01 2.57961025e+01 2.73448944e+01 2.58453903e+01 2.26067028e+01 2.09586754e+01 2.10585804e+01 2.32889462e+01 2.40932693e+01 2.14677448e+01 2.22419605e+01 2.36701164e+01 2.57117653e+01 2.75615292e+01 2.84214802e+01 3.82248154e+01 4.56279259e+01 4.70183640e+01 3.94795265e+01 3.28920784e+01 3.11070061e+01 3.12227516e+01 3.11860828e+01 3.31462097e+01 3.19939442e+01 2.99808788e+01 2.73977757e+01 2.57153225e+01 2.25190105e+01 1.91314087e+01 1.63388119e+01 1.87490902e+01 2.13913918e+01 2.47696018e+01 2.20322247e+01 1.81322250e+01 1.99737282e+01 2.43515205e+01 3.11968708e+01 2.86163826e+01 2.82650299e+01 3.30934296e+01 4.25261002e+01 4.82955856e+01 4.71647415e+01 4.46300163e+01 4.41654968e+01 4.00150604e+01 3.66462440e+01 3.45909233e+01 3.60175095e+01 3.73720398e+01 3.18193150e+01 2.70877914e+01 2.61128101e+01 3.04644699e+01 3.50795135e+01 3.43649025e+01 3.40957642e+01 3.14800262e+01 3.11551094e+01 3.17662258e+01 3.21912422e+01 3.12216778e+01 2.82026691e+01 2.67422409e+01 2.59251518e+01 2.58069382e+01 2.89257755e+01 3.25006905e+01 3.64768143e+01 3.73471794e+01 3.32880554e+01 3.10039177e+01 2.84652367e+01 3.08620796e+01 3.18037262e+01 2.88201294e+01 2.53054256e+01 2.54577560e+01 2.88224049e+01 3.39197502e+01 3.46537704e+01 3.46437263e+01 3.37386131e+01 3.34905624e+01 3.38140488e+01 3.43665810e+01 3.46556549e+01 3.40571938e+01 3.34158134e+01 3.22080460e+01 3.27757225e+01 3.22601624e+01 3.18013477e+01 3.10162563e+01 3.07918148e+01 3.08412571e+01 3.07539043e+01 3.11153488e+01 3.26365395e+01 3.41644974e+01 3.23535385e+01 2.92766495e+01 2.85110340e+01 3.08234444e+01 3.30774956e+01 3.29593048e+01 3.30464668e+01 3.33592224e+01 3.35259361e+01 3.33839264e+01 3.31622238e+01 3.31672554e+01 3.31126022e+01 3.35229340e+01 3.36952286e+01 3.35182724e+01 3.31280022e+01 3.28955688e+01 3.29883575e+01 3.30324707e+01 3.31768570e+01 3.35900307e+01 3.37178116e+01 3.35742645e+01 3.33290863e+01 3.25534439e+01 3.16097126e+01 3.06370163e+01 3.07734947e+01 3.16450806e+01 3.22726593e+01 3.29107513e+01 3.30005379e+01 3.32096863e+01 3.32092171e+01 3.30750618e+01 3.32128563e+01 3.33588295e+01 3.33350334e+01 3.31961441e+01 3.31356850e+01 3.31506577e+01 3.30257454e+01 3.28058472e+01 3.27124672e+01 3.28369217e+01 3.30377846e+01 3.32050972e+01 3.31056175e+01 3.29926262e+01 3.30079269e+01 3.30753746e+01 3.29983788e+01 3.27757759e+01 3.26312485e+01 3.27634239e+01 3.29452934e+01 3.30858498e+01 3.29612122e+01 3.28485718e+01 3.29733429e+01 3.22595634e+01 3.13687553e+01 3.10915718e+01 3.20582314e+01 3.28093758e+01 3.14517727e+01 3.00622368e+01 2.90158806e+01 2.87912502e+01 3.02373352e+01 3.13676548e+01 3.31185226e+01 3.30845795e+01 3.31396675e+01 3.31177444e+01 3.31484680e+01 3.35969582e+01 3.36243248e+01 3.39008179e+01 3.40709305e+01 3.36228294e+01 3.35943527e+01 3.33962669e+01 3.41788254e+01 3.49440918e+01 3.48713150e+01 3.53517380e+01 3.45810394e+01 3.45785370e+01 3.40361404e+01 3.20990601e+01 3.00069332e+01 2.96687393e+01 3.14183350e+01 3.26784286e+01 3.14667587e+01 3.19919777e+01 3.21111870e+01 3.14381008e+01 3.08335247e+01 3.11463642e+01 3.24528732e+01 3.19379559e+01 3.07342472e+01 3.11417065e+01 3.10297413e+01 3.25782471e+01 3.22646866e+01 3.17375584e+01 3.03743744e+01 2.68556042e+01 2.42648106e+01 2.96713753e+01 3.75389137e+01 4.09502487e+01 3.54737625e+01 3.06671848e+01 3.40153122e+01 3.71493721e+01 3.65079041e+01 3.14756927e+01 2.83651371e+01 2.96635551e+01 3.09678154e+01 3.17173977e+01 3.10428734e+01 2.87946892e+01 2.74412632e+01 2.74662857e+01 3.01636333e+01 3.20019531e+01 3.03067570e+01 2.72916489e+01 2.70740108e+01 2.89693527e+01 2.99979553e+01 2.70814819e+01 2.70456161e+01 2.90300846e+01 3.11308937e+01 3.32745285e+01 3.34968414e+01 3.49124489e+01 3.26740685e+01 2.72289124e+01 2.07047176e+01 1.95832138e+01 2.40070362e+01 3.04525623e+01 3.17066536e+01 3.14361916e+01 2.58586540e+01 1.96647797e+01 1.99400558e+01 2.47837486e+01 2.85716400e+01 2.47728920e+01 2.53181438e+01 2.43591461e+01 2.81959305e+01 2.68157310e+01 2.94262638e+01 2.90723782e+01 3.04142036e+01 2.89376488e+01 2.61702747e+01 2.47462463e+01 2.52523327e+01 2.63236370e+01 2.79542522e+01 3.03095455e+01 3.20649796e+01 3.43635521e+01 3.27902374e+01 3.06138020e+01 2.83798332e+01 3.00911427e+01 3.28248749e+01 3.38200455e+01 3.43457947e+01 3.27622948e+01 3.32686462e+01 3.39609528e+01 3.46242638e+01 3.30789719e+01 3.01368732e+01 3.01707458e+01 2.76417484e+01 2.10478039e+01 2.03488750e+01 2.22358341e+01 2.80437832e+01 2.89029655e+01 3.09827023e+01 3.17546597e+01 2.84618187e+01 2.07847576e+01 1.69405537e+01 1.90007172e+01 3.08298225e+01 4.12076759e+01 4.88505173e+01 5.35956154e+01 4.79896469e+01 4.20340309e+01 2.54943981e+01 1.74244118e+01 1.72126083e+01 2.52112522e+01 2.60015125e+01 1.46107969e+01 1.58851757e+01 2.72904167e+01 4.20296745e+01 3.98010178e+01 3.04679050e+01 2.19340878e+01 2.05205040e+01 2.95239105e+01 3.04575539e+01 2.86986847e+01 1.63351250e+01 5.22421694e+00 4.34089804e+00 1.21702728e+01 1.76832085e+01 8.92531395e+00 5.98219776e+00 1.07813730e+01 1.94151363e+01 1.41678190e+01 5.95905876e+00 3.77307796e+00 1.06650381e+01 2.02311020e+01 2.17976379e+01 2.60247288e+01 1.79018974e+01 1.27470770e+01 1.56386023e+01 2.37743912e+01 2.93669624e+01 3.30072784e+01 3.91603546e+01 4.09050522e+01 3.27794037e+01 2.58916721e+01 2.02761765e+01 1.39843569e+01 1.28137302e+01 6.68174028e+00 5.16806412e+00 6.76132584e+00 1.99952450e+01 2.56866493e+01 2.40742111e+01 2.14793663e+01 2.43355904e+01 2.81902847e+01 3.26466293e+01 3.59619141e+01 3.93840370e+01 2.63332214e+01 1.17854881e+01 1.51084604e+01 3.50424805e+01 3.78181419e+01 1.77682190e+01 8.21854210e+00 1.78248730e+01 3.34476662e+01 2.31581650e+01 8.15906715e+00 1.36372411e+00 1.00647087e+01 1.32930937e+01 6.65729046e+00 7.66035938e+00 2.15079422e+01 3.25736809e+01 3.15786819e+01 2.65030823e+01 1.89175587e+01 1.78330288e+01 1.07043343e+01 1.88482225e+00 -4.40688819e-01 -6.63245487e+00 -8.03356171e+00 -5.85794592e+00 7.43923664e+00 1.95316639e+01 1.89311905e+01 2.13639011e+01 2.23122959e+01 2.52089825e+01 1.54133272e+01 7.84311056e+00 2.68758941e+00 3.22809768e+00 2.09909010e+00 -5.74169970e+00 -7.98853934e-02 1.13077669e+01 2.43925228e+01 3.03363476e+01 3.72654991e+01 3.86760406e+01 3.50185051e+01 1.76600361e+01 1.76691127e+00 1.56528795e+00 1.64331114e+00 1.24230754e+00 -9.03014600e-01 1.12450399e+01 2.18540096e+01 2.49372559e+01 1.86303806e+01 2.01139526e+01 1.09980059e+01 6.41000605e+00 3.14878345e+00 -3.07005000e+00 -6.92422485e+00 -8.55484581e+00 1.84690142e+00 1.13293505e+01 1.46135178e+01 1.17191448e+01 6.55247068e+00 3.65871620e+00 -7.01971483e+00 -1.98937626e+01 -2.52742348e+01 -1.79153843e+01 1.37062454e+00 1.74773006e+01 3.09406567e+01 3.20723114e+01 3.01907978e+01 2.32205906e+01 2.56544094e+01 2.67810287e+01 3.13061733e+01 3.18764992e+01 3.26909828e+01 3.49394913e+01 3.34520187e+01 2.70957451e+01 1.25007591e+01 1.70726311e+00 4.63045216e+00 1.53617058e+01 1.23175993e+01 9.40495431e-01 4.79974699e+00 3.43651390e+00 -1.58837128e+00 -5.40233755e+00 7.45305395e+00 2.01073666e+01 7.34523201e+00 -9.17079926e+00 -1.08440809e+01 2.78112388e+00 1.96338785e+00 -1.30540781e+01 -1.92038937e+01 -2.13770413e+00 4.22412777e+00 -5.18845975e-01 4.10480738e+00 1.00162954e+01 1.77889347e+01 -4.10488462e+00 -1.80838966e+01 -1.89653797e+01 -7.34504414e+00 6.70174503e+00 7.69717741e+00 7.53478909e+00 -6.50727749e+00 -2.79834576e+01 -2.44607048e+01 -1.01755695e+01 1.08454237e+01 1.19274359e+01 1.60108414e+01 1.81603889e+01 1.69363670e+01 1.21772642e+01 7.96345043e+00 8.95982838e+00 4.79537630e+00 4.68485689e+00 2.55319285e+00 9.77378941e+00 1.41786633e+01 1.19141884e+01 -3.65480733e+00 -2.24007416e+01 -1.94503670e+01 -4.73287010e+00 1.29474533e+00 -9.54486847e+00 -4.32814169e+00 8.09888554e+00 2.27919006e+01 1.91634312e+01 1.85373821e+01 1.61278934e+01 1.43379688e+01 1.52290268e+01 1.85606136e+01 2.23630962e+01 6.62599754e+00 -1.80417900e+01 -3.01604061e+01 -1.73114128e+01 -1.51858435e+01 -2.59878101e+01 -2.62808857e+01 -8.70253849e+00 2.54452300e+00 3.17441463e+00 3.38087296e+00 3.89607763e+00 -3.50357085e-01 -1.08825960e+01 -7.31040668e+00 -2.37480447e-01 -7.42009544e+00 -2.84379597e+01 -3.83692169e+01 -1.91514702e+01 -8.49143887e+00 -1.93649540e+01 -2.27315159e+01 -1.80670242e+01 3.05656910e+00 -2.13611293e+00 -1.01406622e+01 6.34900475e+00 2.78087616e+01 2.66158695e+01 -5.46064377e+00 -2.09120369e+01 -7.18721437e+00 8.15055275e+00 1.25102854e+01 1.51140699e+01 -1.66750264e+00 -2.01569309e+01 -3.20611839e+01 -2.02689915e+01 -8.62518501e+00 -1.87399731e+01 -3.71576233e+01 -2.67890987e+01 -9.67425632e+00 -1.84581995e+00 -6.31231804e+01 -9.41390991e+01 -1.86823441e+02 -9.62816849e+01 -9.12954468e+02 4.44621086e+01 6.48769226e+02 -1.17668518e+03 -1.48813391e+03 4.60575391e+03 1.02681279e+04 -7.69042850e+06 6.81935411e+09 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. -6.86737715e+09 -1.88435586e+04 -4.14930859e+03 -6.08133728e+02 -3.60543457e+02 1.07170850e+03 7.33421387e+02 6.22430534e+01 -1.02482712e+00 -1.47140608e+01 -7.62071838e+01 -1.28299133e+02 -3.35501099e+01 -5.54912720e+02 -8.05727966e+02 8.09428596e+00 1.28434839e+03 9.52475098e+02 2.70512970e+02 1.69655670e+02 1.11267807e+02 2.75158310e+01 2.14447289e+01 2.13283386e+01 1.28287191e+01 9.02995682e+00 4.49375582e+00 3.40422802e-02 -3.42730689e+00 -3.73092842e+00 -4.76856142e-01 4.41382170e+00 2.18951988e+00 -1.14715803e+00 -7.21218348e+00 -3.86654305e+00 -2.55399346e+00 -8.31151605e-01 -4.67425919e+00 -2.42763615e+00 -2.90449691e+00 1.95943034e+00 1.15607178e+00 8.56369972e-01 -1.70352113e+00 -2.98938084e+00 -3.65110087e+00 -5.60909605e+00 -4.11957073e+00 -4.44081020e+00 -5.48065758e+00 -6.70872355e+00 -5.52333069e+00 -5.62039375e+00 -4.78681564e+00 -4.39038754e+00 -1.92477369e+00 -2.82623100e+00 -4.76917982e+00 -8.34470749e+00 -8.18294811e+00 -7.10528612e+00 -6.88527489e+00 -8.47470188e+00 -8.35928154e+00 -8.01232624e+00 -5.15305328e+00 -5.79319000e+00 -4.92805958e+00 -6.99175978e+00 -7.09045935e+00 -5.79674625e+00 -2.60489655e+00 4.51889336e-02 -1.47459579e+00 -2.06809425e+00 -4.42728424e+00 -7.74245501e+00 -1.20649776e+01 -1.15473337e+01 -7.98741055e+00 -6.71390295e+00 -5.57427311e+00 -6.41614962e+00 -6.60821295e+00 -6.23969269e+00 -7.17768908e+00 -8.84821892e+00 -1.14010162e+01 -1.00625343e+01 -6.98068428e+00 -4.93558788e+00 -5.17693901e+00 -8.75360489e+00 -1.24902744e+01 -1.57348375e+01 -1.41609602e+01 -1.33416615e+01 -1.18033381e+01 -1.05669279e+01 -9.81051159e+00 -8.30351830e+00 -8.14694405e+00 -7.19355392e+00 -8.84874725e+00 -1.10499973e+01 -1.24228640e+01 -9.63555622e+00 -8.28966618e+00 -9.31121731e+00 -1.21658936e+01 -1.43697186e+01 -1.46713800e+01 -1.65262070e+01 -1.58510847e+01 -1.31551723e+01 -1.00005484e+01 -9.17851734e+00 -1.09418383e+01 -1.34396849e+01 -1.35770397e+01 -1.45604277e+01 -1.16031256e+01 -9.46519947e+00 -8.47608471e+00 -9.88562775e+00 -1.12537537e+01 -1.00658264e+01 -1.20124245e+01 -1.47237272e+01 -1.55590096e+01 -1.31347399e+01 -9.78318024e+00 -9.45332909e+00 -9.57536507e+00 -1.09234657e+01 -1.09744663e+01 -1.05306950e+01 -1.11063805e+01 -1.25190620e+01 -1.54660473e+01 -1.34183302e+01 -9.28780651e+00 -6.30713081e+00 -7.01689768e+00 -1.11428232e+01 -1.35082617e+01 -1.55714159e+01 -1.43561068e+01 -1.23677282e+01 -1.09764986e+01 -1.04380503e+01 -1.05624313e+01 -1.19605961e+01 -1.20850878e+01 -1.20054646e+01 -1.30010405e+01 -1.37056246e+01 -1.51976614e+01 -1.39859276e+01 -1.49509983e+01 -1.53811502e+01 -1.40028925e+01 -1.16479521e+01 -9.79424858e+00 -9.09323215e+00 -9.99605274e+00 -1.05419559e+01 -1.08868523e+01 -1.29808044e+01 -1.57778330e+01 -1.85264645e+01 -1.69747581e+01 -1.55575495e+01 -1.44271946e+01 -1.63905983e+01 -1.27524452e+01 -1.21144133e+01 -1.25200119e+01 -1.80294857e+01 -1.94352360e+01 -1.63091946e+01 -1.26843624e+01 -9.71783257e+00 -9.30211926e+00 -1.13138447e+01 -1.31850281e+01 -1.37419443e+01 -1.52620459e+01 -1.52963581e+01 -1.64860420e+01 -1.44844437e+01 -1.04085121e+01 -9.31747913e+00 -1.16305494e+01 -1.67061939e+01 -1.74840965e+01 -1.64282665e+01 -1.60452156e+01 -1.50526276e+01 -1.32873735e+01 -1.14363728e+01 -1.39512424e+01 -1.68169727e+01 -1.88448067e+01 -1.67923088e+01 -1.50965500e+01 -1.50040426e+01 -1.88156700e+01 -1.85226669e+01 -1.78284931e+01 -1.45810308e+01 -1.57785788e+01 -1.63437195e+01 -1.62507095e+01 -1.74665756e+01 -1.49510355e+01 -1.62195072e+01 -1.44516754e+01 -1.91936169e+01 -1.86423187e+01 -1.81443748e+01 -1.67410870e+01 -1.74465733e+01 -1.78101139e+01 -1.88638992e+01 -1.55255690e+01 -1.84024296e+01 -1.68726521e+01 -2.09684181e+01 -1.92479534e+01 -1.78009739e+01 -1.81459389e+01 -1.85619297e+01 -1.77198029e+01 -1.72982426e+01 -1.59987431e+01 -1.79675026e+01 -1.94049816e+01 -2.15915470e+01 -2.17841091e+01 -1.76404362e+01 -1.65655403e+01 -1.64976730e+01 -1.97776203e+01 -1.87381248e+01 -1.85575485e+01 -1.73476219e+01 -1.91222763e+01 -1.99617519e+01 -2.04941692e+01 -1.93274727e+01 -1.77719784e+01 -1.82902927e+01 -1.90697937e+01 -1.97846184e+01 -2.03349552e+01 -1.96605415e+01 -2.01399441e+01 -1.86158314e+01 -1.84765892e+01 -1.75476093e+01 -1.81527538e+01 -1.80396557e+01 -1.84088421e+01 -1.74082565e+01 -1.84859390e+01 -1.87394047e+01 -2.04384136e+01 -2.00237350e+01 -1.97348976e+01 -1.93502502e+01 -1.92320099e+01 -1.88140945e+01 -1.93840351e+01 -1.86453724e+01 -1.98621578e+01 -1.99964237e+01 -2.19776115e+01 -2.16012611e+01 -2.11745605e+01 -2.09875965e+01 -2.15412445e+01 -2.10827618e+01 -2.17325249e+01 -2.19512081e+01 -2.30164967e+01 -2.16267776e+01 -2.15542450e+01 -2.15834694e+01 -2.16633835e+01 -2.09128628e+01 -2.04408360e+01 -2.16256313e+01 -2.22073116e+01 -2.15761986e+01 -2.08447914e+01 -2.05853405e+01 -2.10105076e+01 -2.14424973e+01 -2.25988026e+01 -2.25599117e+01 -2.27596722e+01 -2.20638657e+01 -2.20822010e+01 -2.32930298e+01 -2.29329433e+01 -2.28084221e+01 -2.04646301e+01 -2.03465252e+01 -2.21822929e+01 -2.16225452e+01 -2.16151943e+01 -2.11413364e+01 -2.28117790e+01 -2.34957199e+01 -2.23314972e+01 -2.20284119e+01 -2.23065434e+01 -2.34673328e+01 -2.33646183e+01 -2.26148491e+01 -2.16256485e+01 -2.27347336e+01 -2.33866386e+01 -2.34399014e+01 -2.28688850e+01 -2.27373066e+01 -2.22071533e+01 -2.14867344e+01 -2.16575317e+01 -2.23110752e+01 -2.26313705e+01 -2.25589409e+01 -2.24325542e+01 -2.26990891e+01 -2.22643471e+01 -2.23363552e+01 -2.19354496e+01 -2.20774937e+01 -2.31806526e+01 -2.37469234e+01 -2.42304573e+01 -2.33312283e+01 -2.33755836e+01 -2.28328934e+01 -2.32489319e+01 -2.36708946e+01 -2.31327324e+01 -2.25323391e+01 -2.25653706e+01 -2.31745987e+01 -2.38178177e+01 -2.40187683e+01 -2.38500481e+01 -2.38123493e+01 -2.32309589e+01 -2.34097347e+01 -2.32102089e+01 -2.34835453e+01 -2.37698231e+01 -2.33139629e+01 -2.23259945e+01 -2.19752274e+01 -2.18650608e+01 -2.26385193e+01 -2.32463741e+01 -2.34167042e+01 -2.34809666e+01 -2.28130646e+01 -2.31295395e+01 -2.28076839e+01 -2.30662613e+01 -2.29495926e+01 -2.25179653e+01 -2.24214134e+01 -2.25584583e+01 -2.30419407e+01 -2.33673534e+01 -2.34423599e+01 -2.33990040e+01 -2.34252205e+01 -2.39443035e+01 -2.41100597e+01 -2.46968651e+01 -2.37313862e+01 -2.32889385e+01 -2.21157284e+01 -2.23240051e+01 -2.29040527e+01 -2.32392044e+01 -2.35519238e+01 -2.32018318e+01 -2.37722721e+01 -2.37873688e+01 -2.36481705e+01 -2.32305107e+01 -2.32257957e+01 -2.38535194e+01 -2.39930649e+01 -2.41140022e+01 -2.39077377e+01 -2.42056522e+01 -2.38341541e+01 -2.38130054e+01 -2.36260185e+01 -2.39159679e+01 -2.38080730e+01 -2.36473083e+01 -2.36224117e+01 -2.36776924e+01 -2.37469349e+01 -2.36268120e+01 -2.35301285e+01 -2.33924255e+01 -2.33108997e+01 -2.33620682e+01 -2.34187679e+01 -2.35300064e+01 -2.35452290e+01 -2.37361202e+01 -2.40644894e+01 -2.41248379e+01 -2.40668812e+01 -2.37856007e+01 -2.38388062e+01 -2.38873158e+01 -2.39686966e+01 -2.40052052e+01 -2.39197865e+01 -2.39282417e+01 -2.38512573e+01 -2.39605770e+01 -2.39280491e+01 -2.39460316e+01 -2.39416313e+01 -2.39514675e+01 -2.39385700e+01 -2.39266300e+01 -2.39330769e+01 -2.39367676e+01 -2.39278316e+01 -2.39072933e+01 -2.39322014e+01 -2.40056858e+01 -2.40693684e+01 -2.39769058e+01 -2.38432732e+01 -2.37494488e+01 -2.38455296e+01 -2.39932404e+01 -2.40424461e+01 -2.38739300e+01 -2.38042431e+01 -2.39678631e+01 -2.42204628e+01 -2.40971031e+01 -2.40002537e+01 -2.39420757e+01 -2.41351013e+01 -2.38341045e+01 -2.39776745e+01 -2.37583771e+01 -2.37120781e+01 -2.36808701e+01 -2.36086273e+01 -2.37919979e+01 -2.35561066e+01 -2.38331623e+01 -2.40502949e+01 -2.41263847e+01 -2.37133064e+01 -2.35515480e+01 -2.32997189e+01 -2.40236149e+01 -2.41870461e+01 -2.43763409e+01 -2.36415501e+01 -2.33961105e+01 -2.33367271e+01 -2.35271912e+01 -2.34659061e+01 -2.34404278e+01 -2.35690155e+01 -2.34335747e+01 -2.31224613e+01 -2.32183762e+01 -2.31300640e+01 -2.33292503e+01 -2.35779839e+01 -2.36062126e+01 -2.32096272e+01 -2.20627365e+01 -2.26889877e+01 -2.34719410e+01 -2.42817650e+01 -2.41166763e+01 -2.35199928e+01 -2.32097187e+01 -2.31047287e+01 -2.35316792e+01 -2.37079525e+01 -2.36423149e+01 -2.33080826e+01 -2.38478565e+01 -2.34950848e+01 -2.42572708e+01 -2.37652950e+01 -2.36494884e+01 -2.36489391e+01 -2.31389313e+01 -2.34180698e+01 -2.29329052e+01 -2.36637516e+01 -2.39236565e+01 -2.32961502e+01 -2.24995384e+01 -2.18028584e+01 -2.23737392e+01 -2.29316139e+01 -2.32343330e+01 -2.29971581e+01 -2.25154915e+01 -2.19548454e+01 -2.23108311e+01 -2.27388515e+01 -2.32898121e+01 -2.29206619e+01 -2.24522400e+01 -2.23113327e+01 -2.24900513e+01 -2.31465511e+01 -2.45525150e+01 -2.43851223e+01 -2.42177315e+01 -2.27143383e+01 -2.20718269e+01 -2.14902382e+01 -2.16418781e+01 -2.20226822e+01 -2.19977970e+01 -2.27149162e+01 -2.29023705e+01 -2.28545761e+01 -2.29351425e+01 -2.27473640e+01 -2.25962543e+01 -2.16093807e+01 -2.10700474e+01 -2.08784618e+01 -2.11304646e+01 -2.12973061e+01 -2.10487099e+01 -2.09357471e+01 -2.01059799e+01 -2.03821201e+01 -2.04377804e+01 -2.19558487e+01 -2.24948330e+01 -2.28021507e+01 -2.21270809e+01 -2.14872398e+01 -2.06972027e+01 -2.24181194e+01 -2.13214378e+01 -2.09910450e+01 -1.78210487e+01 -1.92565727e+01 -2.01633282e+01 -2.26805477e+01 -2.31383953e+01 -2.27824211e+01 -2.18082085e+01 -2.07674732e+01 -2.00986118e+01 -2.03810291e+01 -2.05440750e+01 -2.06321602e+01 -1.96853828e+01 -1.98373089e+01 -2.07915077e+01 -2.17566872e+01 -2.26243210e+01 -2.11636925e+01 -2.21952400e+01 -2.07029877e+01 -2.05812283e+01 -2.07372265e+01 -2.11312199e+01 -2.25920544e+01 -2.04033718e+01 -2.04949856e+01 -1.96443462e+01 -1.98506012e+01 -2.04796829e+01 -2.17223759e+01 -2.22515354e+01 -2.16428452e+01 -2.03220272e+01 -2.04482403e+01 -1.99046574e+01 -2.08334198e+01 -1.92207489e+01 -1.73590984e+01 -1.62128048e+01 -1.48964901e+01 -1.64610996e+01 -1.71569004e+01 -1.95633450e+01 -2.04715557e+01 -1.97031574e+01 -1.59168530e+01 -1.41833591e+01 -1.15074177e+01 -1.10650492e+01 1.85387969e+00 9.62174034e+00 4.45003624e+01 2.15972595e+01 -8.74906235e+01 -2.78782623e+02 -1.28486743e+03 9.98227625e+05 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -466714336. -49914308. 6.91996240e+03 3.26204224e+03 5.08377716e+02 -5.31287903e+02 -1.70254517e+02 7.10043335e+01 7.25418472e+01 4.62726440e+01 1.72888870e+02 9.37595291e+01 -5.35256577e+00 -7.27273407e+01 -1.04666336e+02 -9.08087387e+01 -1.12466034e+02 -1.02804214e+02 -8.79323502e+01 -5.39700966e+01 -4.69585304e+01 -3.72356300e+01 -3.37818375e+01 -2.74831429e+01 -2.18179264e+01 -1.82795181e+01 -1.78820534e+01 -1.53327293e+01 -1.60516396e+01 -1.64902534e+01 -1.85947437e+01 -1.83630543e+01 -1.67137566e+01 -1.53507338e+01 -1.42631435e+01 -1.25345011e+01 -1.18110752e+01 -1.29279079e+01 -1.53152723e+01 -1.57610197e+01 -1.39396257e+01 -1.39151735e+01 -1.29239111e+01 -1.26665487e+01 -1.23417616e+01 -1.49788885e+01 -1.38022213e+01 -1.20170269e+01 -1.09550552e+01 -1.45953674e+01 -1.49940987e+01 -1.56098089e+01 -1.42289047e+01 -1.44301586e+01 -1.31724625e+01 -1.19626513e+01 -1.27777195e+01 -1.28665380e+01 -1.35811243e+01 -1.34905567e+01 -1.32292719e+01 -1.42176085e+01 -1.57902880e+01 -1.52176514e+01 -1.23863106e+01 -9.21777534e+00 -1.07329369e+01 -1.27952681e+01 -1.33270102e+01 -1.41349945e+01 -1.50235491e+01 -1.77010994e+01 -1.70651779e+01 -1.59610262e+01 -1.47926159e+01 -1.49689007e+01 -1.41653080e+01 -1.18122215e+01 -1.17539282e+01 -1.38402500e+01 -1.40398970e+01 -1.20218544e+01 -1.09244070e+01 -1.14072914e+01 -1.13809385e+01 -8.17956734e+00 -7.98654652e+00 -7.57158327e+00 -1.03750763e+01 -1.12879505e+01 -1.33834858e+01 -1.34636765e+01 -1.50575438e+01 -1.32647324e+01 -1.49361696e+01 -1.22477665e+01 -1.35768080e+01 -1.21377106e+01 -1.30664244e+01 -1.37856569e+01 -1.19810381e+01 -1.05542574e+01 -6.43344164e+00 -5.43448019e+00 -7.28467751e+00 -9.81089115e+00 -1.33166428e+01 -1.33461866e+01 -1.28761911e+01 -1.15497770e+01 -9.81257915e+00 -9.65920353e+00 -1.13589640e+01 -1.04008379e+01 -1.11142817e+01 -9.50972080e+00 -1.18390865e+01 -1.24358816e+01 -1.07393017e+01 -8.63542080e+00 -8.66772366e+00 -7.54625654e+00 -6.74220943e+00 -3.04566860e+00 -4.49627447e+00 -6.50038147e+00 -5.42034054e+00 -5.19341087e+00 -6.59502554e+00 -9.57056904e+00 -9.62548733e+00 -8.66114902e+00 -9.24178600e+00 -8.88829803e+00 -6.09609747e+00 -3.12347817e+00 -3.43927097e+00 -4.92771196e+00 -6.97730112e+00 -6.42504549e+00 -6.88248301e+00 -7.81786680e+00 -1.01896257e+01 -9.68569660e+00 -1.28595924e+01 -1.15417099e+01 -1.25217409e+01 -9.93567371e+00 -1.00119486e+01 -1.12673225e+01 -9.32127476e+00 -8.42178059e+00 -5.19671297e+00 -5.76580667e+00 -5.05790520e+00 -9.30459309e+00 -8.01558971e+00 -8.80251694e+00 -5.76596737e+00 -7.20913124e+00 -6.25957394e+00 -9.56139469e+00 -8.56722832e+00 -8.62413979e+00 -7.15430546e+00 -8.39818001e+00 -5.29758263e+00 -2.66617990e+00 -2.31072330e+00 -5.77233505e+00 -9.33603573e+00 -9.20522404e+00 -8.87412453e+00 -6.83686829e+00 -7.36435080e+00 -4.82607460e+00 -5.87813187e+00 -3.97459292e+00 -3.61158276e+00 -1.42102146e+00 -2.95032191e+00 -6.27284527e+00 -6.13032675e+00 -4.33924198e+00 -5.37770176e+00 -7.69281244e+00 -8.79424763e+00 -5.27284813e+00 -4.69052219e+00 -8.41668606e+00 -7.61305285e+00 -6.29276419e+00 -1.76250565e+00 -3.07603335e+00 -4.91399574e+00 -5.40262365e+00 -5.38833046e+00 -1.58127582e+00 -2.89374757e+00 -4.61811972e+00 -6.79484510e+00 -4.23502827e+00 -3.38782763e+00 -4.12327242e+00 -6.29579830e+00 -3.32997251e+00 -4.03190279e+00 -2.30908060e+00 -3.71676517e+00 -2.14466977e+00 -6.82551086e-01 -1.25133169e+00 1.22983932e+00 -2.65889317e-01 -1.59393656e+00 -4.88775539e+00 -2.83269739e+00 4.29699332e-01 1.94123852e+00 4.91725355e-01 1.14269924e+00 2.64766240e+00 2.92256236e+00 4.23226213e+00 1.99400496e+00 2.94257545e+00 3.43504876e-01 9.99592170e-02 1.10308111e+00 1.27693164e+00 1.79461420e+00 -1.44087672e+00 -1.31455755e+00 2.15307355e+00 3.03337908e+00 3.34885740e+00 3.85482311e-01 1.11255741e+00 -6.41308546e-01 1.84360743e-01 2.00875258e+00 3.83272052e+00 3.15527439e+00 3.24849582e+00 1.69642818e+00 6.25087380e-01 6.90277815e-01 -1.19044375e+00 -7.85560966e-01 -4.03627586e+00 -1.24376655e+00 7.70757139e-01 3.85181928e+00 3.65093613e+00 4.07333565e+00 2.89159942e+00 3.41070390e+00 3.25285554e+00 3.64643884e+00 5.56354666e+00 6.73347425e+00 8.28894520e+00 7.51845217e+00 8.45200443e+00 8.04933262e+00 6.88421059e+00 5.73749542e+00 4.11334610e+00 2.87843609e+00 1.90846074e+00 2.39859223e+00 3.49224067e+00 4.22514915e+00 4.46582699e+00 4.54301453e+00 2.33343434e+00 3.21964765e+00 3.33581662e+00 5.56930113e+00 4.40278196e+00 4.46025610e+00 2.62981439e+00 3.87133026e+00 3.42703342e+00 8.47037029e+00 5.84788370e+00 6.66582108e+00 2.75687528e+00 4.39470196e+00 5.07681561e+00 5.73835659e+00 7.57703447e+00 6.69063854e+00 6.10366821e+00 2.81778741e+00 1.66414785e+00 3.33532953e+00 4.81833363e+00 3.78269529e+00 3.59168601e+00 3.11597753e+00 6.16305208e+00 4.02771330e+00 7.34521389e+00 6.17814255e+00 6.61291122e+00 5.01807117e+00 6.85504055e+00 7.46696949e+00 7.48384428e+00 5.71418333e+00 5.82806253e+00 6.20192814e+00 6.47458649e+00 6.48230791e+00 6.49070072e+00 7.30426645e+00 7.73904228e+00 6.79373360e+00 7.62769270e+00 8.99320889e+00 9.63958836e+00 8.71783447e+00 7.24849796e+00 7.95888853e+00 7.52489090e+00 9.50265503e+00 9.60258198e+00 1.17591267e+01 9.36822224e+00 1.00284367e+01 8.06471252e+00 8.83103657e+00 8.15244389e+00 8.39144897e+00 9.25480080e+00 1.04860592e+01 1.02972260e+01 1.03735838e+01 9.88131809e+00 1.07041855e+01 1.01423903e+01 8.83310223e+00 7.66409445e+00 7.19097614e+00 6.86125278e+00 7.63816833e+00 7.84422112e+00 7.72586441e+00 7.65262318e+00 9.37948418e+00 1.26248236e+01 1.49768457e+01 1.30485067e+01 1.36201878e+01 1.07798033e+01 1.16501007e+01 9.46241760e+00 8.64156151e+00 1.08664341e+01 9.71193218e+00 1.00358305e+01 9.86243057e+00 1.34335957e+01 1.42384186e+01 1.36420469e+01 1.23681126e+01 1.19664145e+01 1.26532526e+01 1.34566593e+01 1.47036753e+01 1.22847672e+01 1.34338093e+01 1.33620615e+01 1.61570358e+01 1.27313576e+01 1.16758575e+01 9.57796001e+00 1.01481686e+01 1.24419937e+01 1.29201441e+01 1.34515219e+01 1.22412519e+01 1.28776836e+01 1.43984432e+01 1.47429485e+01 1.31467810e+01 1.12168465e+01 1.22313290e+01 1.20436554e+01 1.37009583e+01 1.22654028e+01 1.35184822e+01 1.38848076e+01 1.53046370e+01 1.47418957e+01 1.32618551e+01 1.24106750e+01 1.57321033e+01 1.66505241e+01 1.51698904e+01 1.22464771e+01 1.08371611e+01 1.03840179e+01 1.06073618e+01 1.29415960e+01 1.44554300e+01 1.67238731e+01 1.60775261e+01 1.70586243e+01 1.66287842e+01 1.70249062e+01 1.71977787e+01 1.52952471e+01 1.30870514e+01 1.22107697e+01 1.32147980e+01 1.32360439e+01 1.36017313e+01 1.41068077e+01 1.54516058e+01 1.61669865e+01 1.59312525e+01 1.69963169e+01 1.66238079e+01 1.71239471e+01 1.66838341e+01 1.70137138e+01 1.76289082e+01 1.76346550e+01 1.69614086e+01 1.67343884e+01 1.63493500e+01 1.65025349e+01 1.58518057e+01 1.65397720e+01 1.61274567e+01 1.48739252e+01 1.53044119e+01 1.52787514e+01 1.64524250e+01 1.57803574e+01 1.68661366e+01 1.69266148e+01 1.77244701e+01 1.86026802e+01 1.90239887e+01 2.17113609e+01 2.05603828e+01 2.21793365e+01 1.73457928e+01 1.39881973e+01 1.39878044e+01 1.79754448e+01 2.33067551e+01 6.18554306e+01 9.53967438e+01 9.65203476e+01 1.25058228e+03 2.61711182e+03 222337152. -152192576. 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. 0. 0. 0. 0. 0. 0. 0. 0. -589007808. -148787952. 39189644. 53970552. 4.67588525e+03 2.09151611e+03 2.98112915e+02 1.17330185e+02 8.21103668e+01 8.95008469e+01 1.09841919e+02 1.15440033e+02 1.03513062e+02 9.26671295e+01 9.74155197e+01 9.79315567e+01 9.77155533e+01 -6.19581604e+02 -4.40560394e+02 -6.52079544e+01 -6.80401981e-01 6.16303301e+00 1.13817272e+01 1.34085197e+01 1.76445713e+01 2.07264824e+01 2.06941547e+01 2.11638660e+01 2.07688332e+01 2.18692188e+01 2.24131145e+01 2.24881840e+01 2.21048431e+01 2.07342834e+01 2.05146313e+01 2.01978989e+01 2.03777027e+01 1.91908951e+01 1.94630775e+01 1.93712502e+01 2.05350094e+01 2.03884201e+01 2.06331863e+01 2.11522064e+01 2.16106548e+01 2.18440418e+01 2.19020634e+01 2.22879696e+01 2.22264786e+01 2.24087944e+01 2.17717476e+01 2.16943226e+01 2.17270298e+01 2.08317242e+01 2.09572620e+01 2.03332691e+01 2.08472271e+01 2.10621948e+01 2.15333271e+01 2.17759190e+01 2.15612392e+01 2.21370201e+01 2.31270504e+01 2.31193275e+01 2.21488228e+01 2.13675594e+01 2.22741852e+01 2.26574402e+01 2.28548698e+01 2.28471909e+01 2.22110500e+01 2.22840328e+01 2.21678524e+01 2.22714901e+01 2.17288761e+01 2.07982826e+01 2.11331444e+01 2.12089348e+01 2.19862823e+01 2.19427128e+01 2.23049355e+01 2.18953037e+01 2.26456795e+01 2.28781414e+01 2.40650768e+01 2.34946461e+01 2.38875446e+01 2.31247597e+01 2.34736080e+01 2.25893841e+01 2.29194183e+01 2.32120342e+01 2.43390980e+01 2.38631802e+01 2.35911026e+01 2.30184860e+01 2.31416950e+01 2.30926647e+01 2.29220028e+01 2.33909607e+01 2.28022842e+01 2.25574303e+01 2.21908436e+01 2.24808464e+01 2.32926388e+01 2.32744617e+01 2.36912899e+01 2.36546631e+01 2.35078449e+01 2.36161461e+01 2.33731384e+01 2.32556248e+01 2.28001652e+01 2.25947514e+01 2.27970066e+01 2.29805393e+01 2.30226135e+01 2.27944450e+01 2.29806538e+01 2.31765308e+01 2.32250519e+01 2.31417885e+01 2.28611679e+01 2.30607910e+01 2.28432636e+01 2.33491211e+01 2.35791473e+01 2.38005695e+01 2.37164822e+01 2.35214462e+01 2.38282452e+01 2.40688782e+01 2.42056751e+01 2.42019825e+01 2.43377762e+01 2.44382496e+01 2.42004814e+01 2.40038891e+01 2.38076172e+01 2.37788296e+01 2.36752663e+01 2.37078171e+01 2.38260918e+01 2.37748203e+01 2.38209114e+01 2.36514206e+01 2.36855125e+01 2.36961842e+01 2.39020481e+01 2.38955822e+01 2.39353333e+01 2.40375061e+01 2.41154442e+01 2.41378841e+01 2.38853836e+01 2.38013706e+01 2.37727795e+01 2.39743423e+01 2.40597496e+01 2.40303421e+01 2.39215908e+01 2.39066048e+01 2.39185486e+01 2.39453812e+01 2.39062366e+01 2.38884716e+01 2.38649731e+01 2.38692760e+01 2.38777714e+01 2.39023838e+01 2.39246998e+01 2.39206257e+01 2.39365501e+01 2.39363194e+01 2.39351826e+01 2.39265633e+01 2.39324245e+01 2.39409275e+01 2.39235134e+01 2.39168129e+01 2.39133987e+01 2.39404087e+01 2.39626865e+01 2.40013084e+01 2.39682560e+01 2.39105473e+01 2.38622723e+01 2.38189545e+01 2.38579159e+01 2.38362656e+01 2.39280872e+01 2.39232140e+01 2.39599361e+01 2.38514500e+01 2.38454189e+01 2.39314632e+01 2.40524235e+01 2.40128078e+01 2.38712425e+01 2.37176495e+01 2.38679008e+01 2.39657669e+01 2.41112366e+01 2.39496059e+01 2.38221359e+01 2.38163128e+01 2.38014317e+01 2.37490864e+01 2.37032471e+01 2.37321377e+01 2.37040405e+01 2.38429642e+01 2.37569542e+01 2.38073578e+01 2.37547169e+01 2.37962914e+01 2.38197536e+01 2.38402157e+01 2.39287663e+01 2.38977127e+01 2.38799019e+01 2.37873535e+01 2.36988487e+01 2.37046089e+01 2.37816067e+01 2.40675068e+01 2.40890465e+01 2.40038242e+01 2.38942680e+01 2.36528988e+01 2.37920399e+01 2.38249207e+01 2.37154560e+01 2.39335728e+01 2.37718639e+01 2.39245243e+01 2.39194813e+01 2.37231941e+01 2.34119873e+01 2.32496452e+01 2.32735672e+01 2.32814465e+01 2.31541157e+01 2.31515350e+01 2.36923008e+01 2.31765327e+01 2.28121662e+01 2.18737316e+01 2.19905739e+01 2.23063927e+01 2.28103428e+01 2.27456226e+01 2.25465107e+01 2.22172585e+01 2.25572891e+01 2.28750763e+01 2.32435741e+01 2.33297386e+01 2.31105461e+01 2.27497826e+01 2.34597988e+01 2.36303120e+01 2.36963577e+01 2.27265682e+01 2.33091736e+01 2.28397732e+01 2.31447716e+01 2.33862019e+01 2.38088322e+01 2.32761822e+01 2.19127312e+01 2.24390278e+01 2.26700687e+01 2.27773571e+01 2.15653229e+01 2.11823101e+01 2.16419258e+01 2.22737293e+01 2.12331734e+01 2.04145813e+01 2.05133018e+01 2.17062740e+01 2.28926296e+01 2.29651909e+01 2.26187859e+01 2.21858139e+01 2.14928398e+01 2.19963856e+01 2.17383289e+01 2.18764458e+01 2.18203640e+01 2.10413532e+01 2.12451630e+01 2.15561848e+01 2.19301739e+01 2.11778202e+01 2.03433342e+01 2.04933701e+01 2.08167362e+01 2.09644928e+01 2.04571323e+01 2.09562874e+01 2.10905228e+01 2.10273190e+01 2.04131069e+01 2.00810661e+01 2.12027531e+01 2.17796993e+01 2.12995033e+01 2.03646145e+01 2.11022320e+01 2.16118126e+01 2.12086258e+01 2.01100521e+01 2.00524044e+01 1.99789715e+01 1.94738750e+01 1.87773857e+01 1.96744804e+01 2.11619415e+01 2.32785339e+01 2.22244606e+01 2.16959305e+01 2.07426224e+01 2.15152531e+01 2.01770687e+01 1.95892467e+01 1.85539875e+01 1.93944778e+01 1.86224251e+01 1.86938572e+01 1.91904907e+01 1.99480019e+01 2.16561661e+01 2.16241264e+01 2.13240738e+01 2.03322315e+01 2.00703545e+01 2.01528206e+01 2.07345715e+01 2.17321091e+01 2.11990013e+01 2.06549053e+01 1.92511826e+01 1.97350063e+01 1.97317410e+01 1.99004917e+01 1.89281082e+01 1.73041573e+01 1.72910137e+01 1.79002800e+01 1.96764507e+01 1.92338333e+01 1.86903954e+01 1.80883465e+01 1.68087025e+01 1.79288292e+01 1.88606853e+01 2.10571842e+01 2.09557762e+01 2.01794472e+01 1.95908394e+01 1.83751163e+01 1.90255909e+01 1.87990742e+01 1.81745815e+01 1.68726692e+01 1.82808781e+01 1.89312763e+01 1.91177044e+01 1.75672092e+01 1.68177567e+01 1.79607906e+01 1.82413521e+01 1.91668663e+01 1.79680386e+01 1.75568886e+01 1.78569946e+01 1.75631962e+01 1.77310581e+01 1.76965313e+01 1.69832668e+01 1.75052376e+01 1.82815285e+01 1.87479076e+01 1.82179279e+01 1.72681026e+01 1.77494926e+01 1.72976227e+01 1.67720814e+01 1.78254490e+01 1.81287327e+01 1.81292152e+01 1.72673225e+01 1.74519730e+01 1.85749893e+01 1.78273544e+01 1.75910149e+01 1.67555065e+01 1.53854952e+01 1.29175730e+01 1.28679428e+01 1.39372988e+01 1.59292097e+01 1.34664850e+01 1.15694370e+01 1.40181608e+01 1.76082535e+01 1.95026512e+01 1.66713505e+01 1.59000082e+01 1.60018787e+01 1.62367153e+01 1.57225447e+01 1.75374279e+01 1.74160271e+01 1.68495293e+01 1.67965088e+01 1.71796398e+01 1.71805820e+01 1.55216055e+01 1.48475952e+01 1.47475729e+01 1.57065544e+01 1.57478867e+01 1.59026432e+01 1.48858624e+01 1.49139957e+01 1.38833675e+01 1.38808165e+01 1.50237007e+01 1.60137024e+01 1.64554882e+01 1.53747463e+01 1.58484840e+01 1.56883202e+01 1.47079487e+01 1.38457432e+01 1.17259750e+01 1.14906511e+01 1.04704323e+01 1.04307919e+01 1.08266392e+01 1.24844599e+01 1.48581495e+01 1.59684076e+01 1.39934244e+01 1.37164593e+01 1.25005980e+01 1.41411772e+01 1.35372210e+01 1.35631113e+01 1.24142962e+01 1.09221077e+01 1.12562590e+01 1.32127581e+01 1.41270428e+01 1.42935619e+01 1.20417070e+01 1.27728167e+01 1.32263603e+01 1.32902937e+01 1.15828056e+01 9.66270733e+00 9.53374863e+00 1.12624025e+01 1.05378580e+01 1.07814245e+01 1.12719793e+01 1.22140198e+01 1.09345217e+01 8.84952354e+00 7.55158234e+00 7.45953846e+00 9.69928551e+00 1.04274492e+01 1.10797262e+01 8.47540665e+00 9.23976803e+00 9.73555279e+00 1.00765524e+01 9.60010910e+00 8.66061306e+00 8.35905647e+00 8.00407410e+00 1.04256239e+01 9.69478607e+00 8.41101360e+00 6.09443188e+00 8.34360695e+00 1.02403765e+01 1.05367403e+01 1.13808384e+01 1.25887318e+01 1.19078379e+01 1.05467148e+01 1.04848537e+01 1.21492062e+01 1.27879868e+01 1.10419865e+01 1.07260942e+01 1.07072210e+01 1.09899359e+01 1.13502626e+01 1.18370724e+01 1.13514585e+01 1.02862940e+01 8.59028053e+00 8.48474216e+00 9.03166771e+00 1.08338537e+01 1.24566078e+01 1.24913445e+01 1.04832277e+01 8.00715065e+00 6.78552246e+00 8.27658844e+00 8.52543545e+00 9.89218044e+00 8.52858829e+00 6.65502119e+00 4.58581972e+00 3.89191055e+00 6.45087624e+00 6.85049057e+00 6.20273304e+00 3.96224260e+00 5.09373474e+00 5.94337797e+00 6.53826046e+00 4.79251623e+00 5.70958662e+00 7.46727133e+00 9.10562420e+00 8.95903301e+00 8.28256798e+00 7.40566397e+00 7.89385128e+00 6.84603119e+00 6.18276691e+00 5.04874372e+00 4.23061895e+00 2.92173886e+00 3.29263854e+00 3.56390738e+00 3.21739650e+00 4.22718430e+00 5.00963926e+00 6.69139862e+00 4.70356369e+00 4.34687996e+00 5.62450838e+00 7.28355694e+00 7.65821743e+00 5.27022934e+00 5.34010124e+00 4.71620417e+00 5.49201393e+00 5.24630165e+00 5.45612288e+00 4.80575466e+00 2.97164321e+00 2.99667597e+00 3.60531807e+00 5.33654928e+00 3.25820088e+00 2.67393970e+00 1.31698120e+00 5.24286890e+00 5.70377827e+00 5.07046652e+00 3.20298386e+00 2.31721091e+00 3.13775444e+00 3.76348710e+00 4.73489571e+00 2.99726796e+00 9.90484655e-01 -1.49579093e-01 2.04320803e-01 2.24410081e+00 1.25083041e+00 3.21319747e+00 3.03641129e+00 4.21303082e+00 4.97238541e+00 2.83804584e+00 3.03207922e+00 1.65283656e+00 3.64156890e+00 2.64673877e+00 2.48619914e+00 3.58695579e+00 3.89628768e+00 2.90406084e+00 -9.83766198e-01 -3.75117207e+00 -4.16271067e+00 -2.33039141e+00 1.53763139e+00 2.54455113e+00 -1.15251887e+00 -5.51524353e+00 -1.64847984e+01 -3.36935043e+01 -6.09991913e+01 -1.24053627e+02 -1.29254852e+02 -1.63538098e+03 -9.66793945e+03 -1638379008. 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. 2.75057254e+09 9.10379590e+03 1.56643201e+03 3.54193634e+02 1.56131119e+02 4.90150223e+01 1.49881184e+00 -3.39687705e+00 -3.20769477e+00 8.68863165e-01 4.14139652e+00 4.49025393e+00 3.30277276e+00 1.33455908e+00 -1.58992517e+00 -7.42653310e-01 -1.47440457e+00 9.49045479e-01 3.01023185e-01 8.47012997e-01 -3.62867802e-01 -1.69109690e+00 -3.69897246e+00 -6.00239038e+00 -7.60358095e+00 -6.31420469e+00 -5.48581028e+00 -4.18385839e+00 -1.08723080e+00 8.34556282e-01 -1.83786285e+00 -6.34200716e+00 -9.58170795e+00 -8.16304398e+00 -4.53372288e+00 -4.04057771e-01 1.69256020e+00 3.08179945e-01 -8.11212420e-01 -2.32168841e+00 -3.65080142e+00 -4.95794058e+00 -5.91784954e+00 -4.06453228e+00 -2.90952921e+00 -1.48533297e+00 -3.01030326e+00 -3.30342340e+00 -3.72212029e+00 -4.93832922e+00 -3.98690081e+00 -5.41816282e+00 -3.48041630e+00 -1.86033082e+00 -4.02778208e-01 -8.67546916e-01 -4.61722994e+00 -6.28022575e+00 -7.59537458e+00 -5.34121418e+00 -1.90935349e+00 -1.72015083e+00 -3.55564427e+00 -4.87468386e+00 -3.56560946e+00 -4.01334906e+00 -6.26819801e+00 -7.56055260e+00 -7.05074501e+00 -4.03691292e+00 -2.59024453e+00 -4.23347187e+00 -5.44042063e+00 -5.47351646e+00 -5.12377787e+00 -5.49048901e+00 -5.71849394e+00 -3.95159364e+00 -2.70088553e+00 -1.70984697e+00 -1.37190640e+00 -2.85942650e+00 -5.74302244e+00 -8.37337875e+00 -7.72146845e+00 -4.91606045e+00 -3.47568274e+00 -4.81939220e+00 -3.76426530e+00 -1.96595573e+00 -8.40689063e-01 -2.95435452e+00 -5.46129417e+00 -5.15053988e+00 -2.34176254e+00 2.55488485e-01 5.71284890e-01 -1.02332306e+00 -1.65008903e+00 -3.25096798e+00 -4.26916075e+00 -4.83678770e+00 -4.72424746e+00 -3.91180897e+00 -3.68713331e+00 -4.03145313e+00 -6.01662588e+00 -7.22480345e+00 -8.07087994e+00 -7.29999256e+00 -5.82073498e+00 -4.79249716e+00 -5.89637566e+00 -5.94878483e+00 -4.15563965e+00 -3.10741043e+00 -3.64679670e+00 -6.64866400e+00 -6.16337299e+00 -3.44483495e+00 -1.65849045e-01 -4.19532537e-01 -3.23577642e+00 -4.58438253e+00 -7.08595514e+00 -7.57776880e+00 -8.02023697e+00 -7.41115952e+00 -7.26372957e+00 -5.13862610e+00 -2.41726685e+00 -2.79406643e+00 -4.53313398e+00 -7.77398920e+00 -8.33784103e+00 -8.92062092e+00 -6.90228748e+00 -4.98563385e+00 -4.63375330e+00 -4.80838060e+00 -4.79860687e+00 -4.90398788e+00 -6.60744667e+00 -9.44888210e+00 -1.07127047e+01 -9.37400913e+00 -7.32594681e+00 -6.16085958e+00 -5.29455423e+00 -6.06381512e+00 -6.51249504e+00 -6.69307613e+00 -8.25039482e+00 -9.29400158e+00 -9.26059723e+00 -6.73073244e+00 -5.79488325e+00 -7.05732346e+00 -9.66357517e+00 -9.80739594e+00 -9.43351460e+00 -8.59359169e+00 -1.10008030e+01 -1.16640911e+01 -1.06043673e+01 -9.87299061e+00 -9.81380272e+00 -1.11427908e+01 -1.25812531e+01 -1.40348167e+01 -1.29580555e+01 -8.25165272e+00 -6.44296265e+00 -6.12089586e+00 -6.28553343e+00 -6.49563742e+00 -7.52107239e+00 -1.11132975e+01 -1.17289467e+01 -9.96115017e+00 -5.94522953e+00 -5.91186285e+00 -7.98653460e+00 -1.16917543e+01 -1.19519949e+01 -1.16662979e+01 -9.35253906e+00 -9.54229450e+00 -1.03155317e+01 -1.17274923e+01 -1.08369226e+01 -9.54164124e+00 -8.67380238e+00 -1.07425642e+01 -1.09474764e+01 -8.07370758e+00 -4.47837830e+00 -5.06879139e+00 -7.32490969e+00 -8.10708427e+00 -8.20771217e+00 -8.73097706e+00 -1.04308643e+01 -1.06899786e+01 -8.35462666e+00 -7.89899302e+00 -7.82174444e+00 -1.02886848e+01 -9.48828125e+00 -7.90041685e+00 -7.07328987e+00 -6.52977133e+00 -8.91645813e+00 -1.00327978e+01 -1.08761730e+01 -8.98736763e+00 -8.41439724e+00 -8.92620659e+00 -1.01055622e+01 -1.18330469e+01 -1.09285545e+01 -1.11175060e+01 -1.00686417e+01 -1.03763237e+01 -8.58695602e+00 -9.21535492e+00 -8.91758728e+00 -9.66605568e+00 -9.35318565e+00 -9.56990910e+00 -9.77807140e+00 -9.09105015e+00 -9.66143322e+00 -9.14515305e+00 -8.55377293e+00 -9.72234535e+00 -1.08672924e+01 -1.29326496e+01 -1.29342680e+01 -1.12648506e+01 -9.18817806e+00 -9.00196362e+00 -1.05276165e+01 -1.24035177e+01 -1.08407145e+01 -9.68876362e+00 -9.43660069e+00 -9.87251472e+00 -1.02768364e+01 -8.60956287e+00 -8.93313789e+00 -1.01188946e+01 -1.22878504e+01 -1.26313238e+01 -1.20433054e+01 -1.21204901e+01 -1.18008919e+01 -1.13868093e+01 -1.00112448e+01 -9.56250381e+00 -1.03584671e+01 -1.09129572e+01 -1.22212543e+01 -1.16782713e+01 -1.14051847e+01 -9.73510742e+00 -8.32618046e+00 -9.26861954e+00 -1.10762520e+01 -1.33360291e+01 -1.30683823e+01 -1.37271805e+01 -1.36492882e+01 -1.29571571e+01 -1.14404087e+01 -1.09008245e+01 -1.11854134e+01 -1.12990484e+01 -1.08245840e+01 -1.05952101e+01 -1.15840302e+01 -1.15809231e+01 -1.06130323e+01 -1.01908932e+01 -1.11837645e+01 -1.16139441e+01 -1.04993410e+01 -1.07092934e+01 -1.20464993e+01 -1.28321438e+01 -1.21856089e+01 -1.09262848e+01 -1.11539764e+01 -1.20380535e+01 -1.25085430e+01 -1.21538601e+01 -1.27417278e+01 -1.32000437e+01 -1.33547764e+01 -1.15973558e+01 -1.13036242e+01 -1.09973955e+01 -1.18187790e+01 -1.12920685e+01 -1.12755442e+01 -1.16218071e+01 -1.20098572e+01 -1.14334106e+01 -1.08848753e+01 -1.06473866e+01 -1.12424994e+01 -1.03431606e+01 -1.10360184e+01 -1.10278988e+01 -1.18649654e+01 -1.08750286e+01 -1.05687714e+01 -1.11151657e+01 -1.29545708e+01 -1.30983801e+01 -1.20658951e+01 -1.09093838e+01 -1.20267220e+01 -1.28290319e+01 -1.29152679e+01 -1.24847565e+01 -1.24266796e+01 -1.30292797e+01 -1.21596279e+01 -1.20060234e+01 -1.17613468e+01 -1.24695129e+01 -1.23985233e+01 -1.20630512e+01 -1.22249460e+01 -1.18854265e+01 -1.14476738e+01 -1.19834204e+01 -1.28892164e+01 -1.37371273e+01 -1.31531820e+01 -1.21931610e+01 -1.25149851e+01 -1.26394768e+01 -1.36501570e+01 -1.35690918e+01 -1.37806797e+01 -1.39082251e+01 -1.36167774e+01 -1.35188322e+01 -1.32183723e+01 -1.28824692e+01 -1.28925610e+01 -1.24480438e+01 -1.23415461e+01 -1.27052507e+01 -1.28922033e+01 -1.33660078e+01 -1.27322569e+01 -1.27386532e+01 -1.26213646e+01 -1.17586069e+01 -1.18100471e+01 -1.26105042e+01 -1.42117872e+01 -1.45137358e+01 -1.40483866e+01 -1.36185637e+01 -1.34876442e+01 -1.34298763e+01 -1.37348766e+01 -1.39378128e+01 -1.43835020e+01 -1.41163416e+01 -1.44359703e+01 -1.48463316e+01 -1.49215021e+01 -1.43179340e+01 -1.33077660e+01 -1.28378258e+01 -1.37057858e+01 -1.41839733e+01 -1.42336235e+01 -1.35094032e+01 -1.31855793e+01 -1.33744736e+01 -1.31428175e+01 -1.35852280e+01 -1.35432339e+01 -1.42461843e+01 -1.41044073e+01 -1.42921267e+01 -1.36986752e+01 -1.34396782e+01 -1.33647861e+01 -1.38485641e+01 -1.42872829e+01 -1.46687765e+01 -1.43749485e+01 -1.37140179e+01 -1.34801626e+01 -1.33488808e+01 -1.36438522e+01 -1.32533627e+01 -1.33107700e+01 -1.35758419e+01 -1.40398111e+01 -1.40843363e+01 -1.38846483e+01 -1.37893114e+01 -1.37593708e+01 -1.37121525e+01 -1.36944714e+01 -1.38973989e+01 -1.39505405e+01 -1.41080179e+01 -1.40184412e+01 -1.40803080e+01 -1.40367823e+01 -1.38867865e+01 -1.38409491e+01 -1.36422052e+01 -1.37958546e+01 -1.37709169e+01 -1.39111795e+01 -1.40360689e+01 -1.40453424e+01 -1.39117002e+01 -1.37188807e+01 -1.37176504e+01 -1.37190886e+01 -1.38144598e+01 -1.38328152e+01 -1.38238087e+01 -1.37613344e+01 -1.37523613e+01 -1.37648172e+01 -1.37771349e+01 -1.37885485e+01 -1.37844496e+01 -1.37838259e+01 -1.37985411e+01 -1.37966366e+01 -1.37830677e+01 -1.37608881e+01 -1.37424173e+01 -1.36860361e+01 -1.37361698e+01 -1.37560053e+01 -1.38101015e+01 -1.37180109e+01 -1.36347647e+01 -1.36771536e+01 -1.38132448e+01 -1.38715258e+01 -1.38704815e+01 -1.37288647e+01 -1.37514210e+01 -1.36264811e+01 -1.36505651e+01 -1.35124445e+01 -1.35412655e+01 -1.35817604e+01 -1.35832462e+01 -1.36529179e+01 -1.35051327e+01 -1.36185045e+01 -1.37290745e+01 -1.37808638e+01 -1.37314768e+01 -1.33306742e+01 -1.35248976e+01 -1.37673035e+01 -1.39802017e+01 -1.38476038e+01 -1.33393278e+01 -1.32548695e+01 -1.30578480e+01 -1.35051956e+01 -1.38327169e+01 -1.40399456e+01 -1.38100271e+01 -1.34282131e+01 -1.34058867e+01 -1.38231869e+01 -1.38911543e+01 -1.38692350e+01 -1.33242130e+01 -1.33302870e+01 -1.29652691e+01 -1.29438057e+01 -1.33427725e+01 -1.39978085e+01 -1.42386312e+01 -1.38385315e+01 -1.34678144e+01 -1.31288624e+01 -1.31524601e+01 -1.37240562e+01 -1.46088610e+01 -1.42276201e+01 -1.36769743e+01 -1.26078701e+01 -1.29605331e+01 -1.32636337e+01 -1.37788773e+01 -1.38229933e+01 -1.32145548e+01 -1.30118198e+01 -1.29105244e+01 -1.29192200e+01 -1.29051361e+01 -1.31143675e+01 -1.33008986e+01 -1.31211615e+01 -1.29256029e+01 -1.31946516e+01 -1.33374157e+01 -1.32779875e+01 -1.39338541e+01 -1.36432409e+01 -1.37513847e+01 -1.31287508e+01 -1.36698332e+01 -1.40398932e+01 -1.34142609e+01 -1.25919466e+01 -1.20657768e+01 -1.29280539e+01 -1.38259544e+01 -1.40197678e+01 -1.32773247e+01 -1.23949537e+01 -1.15293360e+01 -1.15684843e+01 -1.17698307e+01 -1.30783558e+01 -1.32826614e+01 -1.29921904e+01 -1.24489565e+01 -1.25056524e+01 -1.34453793e+01 -1.35165796e+01 -1.34363012e+01 -1.30984859e+01 -1.24033909e+01 -1.21808138e+01 -1.31515293e+01 -1.48071508e+01 -1.54193630e+01 -1.43862600e+01 -1.30785112e+01 -1.24956408e+01 -1.29619951e+01 -1.36377192e+01 -1.37091255e+01 -1.34605055e+01 -1.24172764e+01 -1.22201653e+01 -1.19634418e+01 -1.23663893e+01 -1.30004225e+01 -1.29789076e+01 -1.22626944e+01 -1.09947786e+01 -1.05428782e+01 -1.20219002e+01 -1.32771969e+01 -1.42744112e+01 -1.37297668e+01 -1.19255705e+01 -1.07815056e+01 -1.06091938e+01 -1.25269966e+01 -1.38236666e+01 -1.42221460e+01 -1.32880621e+01 -1.25602570e+01 -1.21709337e+01 -1.24977484e+01 -1.19293909e+01 -1.14998350e+01 -1.08100882e+01 -1.10739775e+01 -1.05409164e+01 -1.09160814e+01 -1.10615473e+01 -1.22667294e+01 -1.16303864e+01 -1.13474598e+01 -1.03242903e+01 -1.08088322e+01 -1.10420227e+01 -1.16093502e+01 -1.15547533e+01 -1.10214872e+01 -1.09182825e+01 -1.08660440e+01 -1.14179535e+01 -1.20101595e+01 -1.16820946e+01 -1.11808367e+01 -1.01186495e+01 -1.02561178e+01 -1.08622284e+01 -1.14380817e+01 -1.10351467e+01 -9.56071472e+00 -9.95600510e+00 -1.07134829e+01 -1.16703138e+01 -9.02381611e+00 -3.80177593e+00 2.07488871e+00 8.00098991e+00 1.53010511e+01 2.97354183e+01 7.57691498e+01 3.23103333e+02 3.85932343e+02 -1.15392632e+02 -1.19968225e+03 -5.31114404e+03 153894144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -77444984. -367311776. -2.57832446e+03 -9.90230591e+02 -1.61073166e+02 -1.29564270e+02 -4.87485733e+01 -2.62190018e+01 -1.37280989e+01 -1.24724112e+01 -1.28791819e+01 -1.22702398e+01 -1.12191830e+01 -7.95900249e+00 -5.60059404e+00 -5.21286631e+00 -5.46661615e+00 -8.83930779e+00 -9.66686726e+00 -9.11511517e+00 -7.14427853e+00 -6.40426111e+00 -6.25864077e+00 -7.51396561e+00 -8.51098728e+00 -8.08598232e+00 -6.65073586e+00 -6.08561802e+00 -7.10057402e+00 -8.55038738e+00 -7.66382980e+00 -7.39055157e+00 -7.06792545e+00 -7.72127199e+00 -7.71668148e+00 -7.69211340e+00 -7.21056414e+00 -6.66332197e+00 -7.36812210e+00 -7.66314363e+00 -8.31646347e+00 -7.61437464e+00 -6.49759674e+00 -4.71985435e+00 -4.20286512e+00 -4.09318304e+00 -3.25628662e+00 -3.93296909e+00 -6.36283493e+00 -1.12234116e+01 -1.13114548e+01 -9.43025303e+00 -8.48782253e+00 -9.39930248e+00 -1.11106062e+01 -1.05219746e+01 -7.95935583e+00 -6.67456341e+00 -5.88949871e+00 -7.41141701e+00 -7.79542351e+00 -8.15314007e+00 -8.04841232e+00 -5.88427353e+00 -3.89191294e+00 -3.87784958e+00 -5.57171583e+00 -6.82384539e+00 -5.64553452e+00 -3.71553564e+00 -3.98175836e+00 -3.59349680e+00 -4.32577991e+00 -2.57032847e+00 -3.92782259e+00 -4.30988073e+00 -3.01806211e+00 -2.47043085e+00 -3.01559448e+00 -5.70295048e+00 -5.53760386e+00 -4.72342062e+00 -5.29157019e+00 -5.74568319e+00 -5.06393766e+00 -3.38296461e+00 -3.81673932e+00 -5.26889896e+00 -7.09677458e+00 -6.00778580e+00 -6.43533707e+00 -4.59700441e+00 -4.46903419e+00 -2.74937868e+00 -3.43490505e+00 -3.73277807e+00 -1.91343546e+00 -1.27008283e+00 -2.51802444e+00 -3.84220076e+00 -5.67216825e+00 -2.87074399e+00 -4.42122698e+00 -4.86302996e+00 -7.02218580e+00 -6.60385656e+00 -4.33778429e+00 -4.78878069e+00 -2.55929565e+00 -2.37370324e+00 -1.03498542e+00 -1.62522876e+00 -4.60695839e+00 -4.20318747e+00 -4.02621555e+00 -2.61454940e+00 -3.19698358e+00 -4.12193775e+00 -3.35105062e+00 -2.76503444e+00 -4.14761782e+00 -2.65671444e+00 -3.49508739e+00 -4.18987656e+00 -6.28560877e+00 -6.51415825e+00 -2.26802635e+00 -2.06062388e+00 -2.64749885e+00 -5.45817327e+00 -4.49153376e+00 -1.17470479e+00 -1.46654356e+00 -1.94303906e+00 -3.87042856e+00 -3.82191396e+00 -3.75818706e+00 -5.00974941e+00 -4.14793634e+00 -4.22870922e+00 -3.25766563e+00 -4.18865395e+00 -5.47262478e+00 -5.34592628e+00 -4.89095783e+00 -2.93018293e+00 -1.14993906e+00 -1.28957725e+00 -2.56685495e+00 -3.90497065e+00 -3.51307559e+00 -1.67768049e+00 -8.66673410e-01 -1.52230036e+00 -3.05927682e+00 -6.09825468e+00 -5.35135984e+00 -5.17692518e+00 -2.54495215e+00 -1.95632613e+00 -1.40120745e+00 -7.41408527e-01 -1.24794590e+00 -2.23688555e+00 -2.28578830e+00 -5.72952807e-01 1.17828023e+00 9.04599965e-01 -1.88226259e+00 -4.19804621e+00 -4.02285147e+00 -1.94179201e+00 -1.37927067e+00 -3.06269598e+00 -4.76601315e+00 -3.44253278e+00 -1.81257594e+00 -2.03866267e+00 -2.86159515e+00 -2.58388901e+00 -1.90841484e+00 -1.62155771e+00 -1.37515628e+00 -4.52158421e-01 1.70905650e+00 3.49149108e-01 6.63612664e-01 1.57337236e+00 4.02911472e+00 4.78222132e+00 3.46888089e+00 4.42743015e+00 2.89110708e+00 5.17468750e-01 -1.66858399e+00 -2.73907495e+00 8.82835090e-02 -8.41649175e-01 -2.23405457e+00 -6.34591103e+00 -6.63055563e+00 -3.26313996e+00 -6.75835550e-01 1.26292765e+00 6.99102581e-01 1.33705103e+00 2.00546670e+00 2.31880426e+00 2.74940085e+00 2.02402854e+00 2.03735924e+00 1.54509783e+00 9.69908416e-01 1.08951294e+00 -2.25404525e+00 -1.39274430e+00 5.57050467e-01 4.03398800e+00 3.24582934e+00 1.75733650e+00 1.23939729e+00 2.22159433e+00 1.72395438e-01 -1.89346898e+00 -4.35507679e+00 -5.58518648e+00 -2.43526626e+00 -1.29890889e-01 3.12608385e+00 1.90754879e+00 -4.47763741e-01 -2.59546638e+00 -2.28712630e+00 -2.95984715e-01 1.08230603e+00 1.13831937e+00 4.38998461e-01 2.26634175e-01 -1.42620325e+00 -1.06368613e+00 -1.14638388e+00 1.57266945e-01 3.98201168e-01 7.52301157e-01 1.26943254e+00 1.38859272e+00 1.55040753e+00 1.42581856e+00 4.28257436e-02 9.12902653e-02 -2.19191462e-01 7.65248001e-01 -1.29328206e-01 8.56495619e-01 1.89342833e+00 2.07561326e+00 1.32969046e+00 3.11139643e-01 1.68574059e+00 1.93678010e+00 2.32536483e+00 1.86317885e+00 3.71330810e+00 2.98698068e+00 3.08616233e+00 1.30992246e+00 3.73211741e+00 3.50306439e+00 3.37803364e+00 1.73578048e+00 1.76786387e+00 1.25987291e+00 1.03981185e+00 1.21224797e+00 8.51647854e-01 8.60688448e-01 8.78365219e-01 2.42782259e+00 2.23113632e+00 2.40715170e+00 1.58476138e+00 1.56888032e+00 2.13393879e+00 -2.88342535e-01 7.75138915e-01 1.05922483e-01 2.27769423e+00 2.40067410e+00 2.66730237e+00 3.29104638e+00 3.02119207e+00 1.95641708e+00 2.31588054e+00 1.76426005e+00 1.67746508e+00 5.26755512e-01 2.43515658e+00 3.62785029e+00 5.16648626e+00 4.31849909e+00 5.11852074e+00 5.79477024e+00 4.64494991e+00 4.36796618e+00 2.33351970e+00 1.62136483e+00 1.30877292e+00 3.91866398e+00 4.78873682e+00 4.69402981e+00 2.73598242e+00 3.87056065e+00 5.45192432e+00 4.81425333e+00 4.51912022e+00 4.61847878e+00 5.93030930e+00 5.93726110e+00 4.53544331e+00 4.15107203e+00 4.73636246e+00 5.57744455e+00 5.67702389e+00 5.82802582e+00 6.46924782e+00 6.00787306e+00 5.76758242e+00 4.14746618e+00 4.16603518e+00 1.98075485e+00 5.84612489e-01 1.65465605e+00 3.49726176e+00 4.89334869e+00 5.27253532e+00 5.23348284e+00 4.87118435e+00 3.47066474e+00 2.23609447e+00 3.11217427e+00 4.05254841e+00 7.04595709e+00 7.10914087e+00 7.79412079e+00 8.12505150e+00 6.66203785e+00 7.33091640e+00 5.85481834e+00 7.29856014e+00 5.63731527e+00 5.92491341e+00 6.02406836e+00 5.65493822e+00 5.19534159e+00 4.73135138e+00 6.09422588e+00 4.81527424e+00 6.52503061e+00 5.16326141e+00 6.82221889e+00 5.92416716e+00 6.87586021e+00 7.26185369e+00 9.84515285e+00 7.79919338e+00 6.64234495e+00 4.01862335e+00 5.50327396e+00 7.06086159e+00 6.56200790e+00 6.57875872e+00 5.36506796e+00 6.15145302e+00 6.65413094e+00 8.33881569e+00 6.44470692e+00 5.97265005e+00 4.12110281e+00 6.23891830e+00 7.11175680e+00 7.20165491e+00 6.02432442e+00 5.88900614e+00 6.44538403e+00 7.34520197e+00 6.72519445e+00 5.08943605e+00 4.96431255e+00 5.07400513e+00 6.93989754e+00 6.93940401e+00 7.49168444e+00 7.73503113e+00 8.00516701e+00 8.16523933e+00 6.69463539e+00 6.97344542e+00 6.61581802e+00 8.11271286e+00 7.45929575e+00 8.80423164e+00 8.90160942e+00 9.91635132e+00 1.00310211e+01 1.09754372e+01 1.15556364e+01 1.11764374e+01 1.11509209e+01 1.03946733e+01 1.00295277e+01 8.75431728e+00 8.93387413e+00 9.47800922e+00 1.05853109e+01 1.11364126e+01 1.06113272e+01 8.84623528e+00 7.97525978e+00 8.77497578e+00 1.12056513e+01 1.16862240e+01 1.02988997e+01 8.56492043e+00 7.95098591e+00 8.94458485e+00 8.87377548e+00 8.10437775e+00 8.13263321e+00 8.86033821e+00 1.02399883e+01 1.02961264e+01 9.93002892e+00 8.90564728e+00 7.88912058e+00 7.54387093e+00 8.16907310e+00 7.86875629e+00 8.43218517e+00 7.55435801e+00 8.44708443e+00 8.31973171e+00 9.36817169e+00 9.85122299e+00 1.06151428e+01 1.16198502e+01 1.11200590e+01 9.70191383e+00 7.44250107e+00 5.45794439e+00 9.63981056e+00 1.64923306e+01 2.65772877e+01 3.45532265e+01 4.23695450e+01 4.00585403e+01 4.83919106e+01 9.01679993e+01 3.89438263e+02 4.88958282e+02 -1.04028824e+02 -4.88586044e+01 -9.13721375e+02 -3.89800903e+03 -152192576. 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. 0. 0. 0. 0. 0. 0. 0. 186387872. -1.09556042e+03 -4.07465637e+02 2.89119072e+01 -2.47893753e+01 -3.98855782e+01 -3.76375275e+01 -1.58534765e+00 8.15391827e+00 1.04399853e+01 1.08935909e+01 9.99221611e+00 9.61750221e+00 9.46550083e+00 9.40536880e+00 9.32410145e+00 9.96098804e+00 1.09955902e+01 1.12047758e+01 1.10414562e+01 1.00959435e+01 1.01132078e+01 1.06430416e+01 1.10942707e+01 1.12042112e+01 1.09589672e+01 1.13427191e+01 1.12146406e+01 1.17352076e+01 1.21413240e+01 1.27404909e+01 1.27878561e+01 1.25653963e+01 1.20808697e+01 1.18667316e+01 1.22014742e+01 1.23539457e+01 1.32433739e+01 1.34029207e+01 1.34235420e+01 1.26728563e+01 1.21117649e+01 1.26799345e+01 1.29796724e+01 1.31791096e+01 1.32514200e+01 1.31806211e+01 1.27151737e+01 1.29443960e+01 1.29690504e+01 1.35820551e+01 1.32227840e+01 1.34147673e+01 1.33957644e+01 1.35462246e+01 1.34248066e+01 1.32914448e+01 1.31149178e+01 1.29878941e+01 1.31490955e+01 1.28952866e+01 1.25136108e+01 1.18517284e+01 1.16298647e+01 1.16214066e+01 1.20483761e+01 1.25793457e+01 1.23853645e+01 1.20118246e+01 1.23501778e+01 1.30562801e+01 1.36402903e+01 1.36770878e+01 1.34267731e+01 1.34768276e+01 1.35982685e+01 1.38125706e+01 1.38388615e+01 1.36280527e+01 1.35061359e+01 1.34480886e+01 1.31956568e+01 1.31083870e+01 1.24966297e+01 1.23755283e+01 1.21351891e+01 1.23320961e+01 1.24972696e+01 1.28746414e+01 1.29108458e+01 1.30798311e+01 1.27364960e+01 1.27666178e+01 1.24509535e+01 1.24916840e+01 1.26846609e+01 1.28256369e+01 1.30571928e+01 1.32375546e+01 1.33466969e+01 1.33183346e+01 1.34319620e+01 1.35838499e+01 1.36720304e+01 1.35344124e+01 1.34766102e+01 1.34346285e+01 1.32923899e+01 1.31074381e+01 1.30465212e+01 1.28182993e+01 1.28552694e+01 1.31762266e+01 1.37964439e+01 1.39575281e+01 1.38800755e+01 1.35341892e+01 1.33415718e+01 1.31168356e+01 1.33979702e+01 1.37208700e+01 1.38915520e+01 1.38906441e+01 1.35460386e+01 1.34193916e+01 1.33920670e+01 1.36143970e+01 1.38076057e+01 1.35989676e+01 1.33018227e+01 1.30974360e+01 1.33644600e+01 1.36529264e+01 1.37809696e+01 1.36505079e+01 1.33730621e+01 1.32406006e+01 1.31696291e+01 1.34895678e+01 1.36514378e+01 1.36496553e+01 1.36824293e+01 1.36494837e+01 1.37962046e+01 1.37606421e+01 1.37945843e+01 1.37723064e+01 1.37082272e+01 1.36876211e+01 1.37291832e+01 1.37509861e+01 1.37648134e+01 1.37421417e+01 1.36252327e+01 1.35268288e+01 1.34717531e+01 1.35720310e+01 1.36289387e+01 1.36218042e+01 1.36093674e+01 1.36162186e+01 1.36158113e+01 1.35733461e+01 1.35678835e+01 1.36161652e+01 1.37035980e+01 1.37504435e+01 1.37763281e+01 1.37777290e+01 1.37957973e+01 1.37811956e+01 1.37805109e+01 1.37752209e+01 1.37831192e+01 1.37776413e+01 1.37823610e+01 1.37844095e+01 1.37726526e+01 1.37638521e+01 1.37736654e+01 1.37901134e+01 1.37939100e+01 1.37978516e+01 1.37809954e+01 1.37439680e+01 1.37369251e+01 1.38170815e+01 1.38401766e+01 1.38309460e+01 1.37517405e+01 1.37728338e+01 1.37804022e+01 1.38260784e+01 1.37893314e+01 1.38176193e+01 1.37587328e+01 1.38330708e+01 1.37629051e+01 1.38293915e+01 1.38594217e+01 1.39107695e+01 1.37833176e+01 1.36181765e+01 1.36835299e+01 1.37692795e+01 1.38145027e+01 1.36617765e+01 1.36334438e+01 1.36759081e+01 1.36685648e+01 1.35903301e+01 1.35675125e+01 1.35156202e+01 1.35755405e+01 1.35655518e+01 1.36039419e+01 1.37005997e+01 1.36405878e+01 1.36820469e+01 1.36244926e+01 1.36482325e+01 1.36086912e+01 1.35353136e+01 1.34398813e+01 1.34942122e+01 1.34572926e+01 1.35552530e+01 1.35348597e+01 1.34614258e+01 1.34884186e+01 1.35164747e+01 1.36025524e+01 1.35442305e+01 1.34245224e+01 1.32676764e+01 1.31031046e+01 1.31027088e+01 1.32325115e+01 1.30901318e+01 1.29132414e+01 1.29260645e+01 1.34112911e+01 1.36747675e+01 1.35790977e+01 1.31264906e+01 1.30073023e+01 1.30145807e+01 1.32199306e+01 1.37246399e+01 1.43110685e+01 1.43439054e+01 1.39156227e+01 1.33700886e+01 1.39596167e+01 1.43308764e+01 1.40698795e+01 1.33224277e+01 1.28441572e+01 1.29401064e+01 1.29947443e+01 1.31543856e+01 1.33458805e+01 1.33793087e+01 1.30280085e+01 1.29808607e+01 1.27382545e+01 1.31747742e+01 1.30860720e+01 1.30405645e+01 1.30633221e+01 1.33912382e+01 1.30768785e+01 1.28041868e+01 1.28398809e+01 1.37844801e+01 1.38676052e+01 1.36126184e+01 1.31989803e+01 1.35722094e+01 1.37917042e+01 1.41068296e+01 1.38379583e+01 1.35860882e+01 1.34601536e+01 1.26835308e+01 1.26655655e+01 1.24390602e+01 1.25880585e+01 1.24353180e+01 1.23183527e+01 1.29995947e+01 1.33079977e+01 1.34322948e+01 1.24847326e+01 1.23934269e+01 1.16590719e+01 1.31879139e+01 1.40907993e+01 1.43522644e+01 1.35454121e+01 1.24033327e+01 1.26190796e+01 1.22969952e+01 1.24871836e+01 1.27733593e+01 1.31625538e+01 1.30794964e+01 1.31899910e+01 1.34602461e+01 1.31983328e+01 1.30776958e+01 1.24393587e+01 1.24990482e+01 1.23475943e+01 1.27625351e+01 1.30523272e+01 1.33951778e+01 1.29304466e+01 1.20953836e+01 1.16221838e+01 1.13711023e+01 1.13716488e+01 1.10627537e+01 1.14006433e+01 1.18521776e+01 1.22499952e+01 1.29203415e+01 1.26879892e+01 1.29636641e+01 1.23067865e+01 1.35190296e+01 1.38166981e+01 1.42722378e+01 1.32376890e+01 1.23669949e+01 1.18101254e+01 1.21924276e+01 1.23888454e+01 1.28664503e+01 1.21038847e+01 1.22668571e+01 1.21834784e+01 1.15255299e+01 1.12052345e+01 1.05727921e+01 1.18106089e+01 1.23499823e+01 1.21244555e+01 1.25894594e+01 1.31952896e+01 1.37165842e+01 1.29100866e+01 1.16396713e+01 1.26887293e+01 1.24407873e+01 1.32839603e+01 1.21281443e+01 1.22144213e+01 1.05823326e+01 9.43280220e+00 8.93775082e+00 9.05961609e+00 9.22010422e+00 9.27882004e+00 9.70945072e+00 9.78035069e+00 9.47571850e+00 9.63521004e+00 9.87900829e+00 1.03442945e+01 1.10514107e+01 1.17210093e+01 1.25943213e+01 1.16000328e+01 1.05995493e+01 1.00463238e+01 1.19856853e+01 1.28016768e+01 1.22308664e+01 1.08283596e+01 1.00269012e+01 1.12407074e+01 1.07289591e+01 1.12027521e+01 1.07658005e+01 1.14577570e+01 1.16475239e+01 1.14977779e+01 1.05104885e+01 9.65602493e+00 9.05793953e+00 9.74328232e+00 9.85699749e+00 9.68573952e+00 1.00482407e+01 1.01597099e+01 1.11442823e+01 1.05408154e+01 1.04279394e+01 8.72327232e+00 8.96512127e+00 1.05474205e+01 1.15815821e+01 1.03887949e+01 9.01990891e+00 9.88707829e+00 1.02649660e+01 9.74195480e+00 9.39403629e+00 8.32873249e+00 8.30384541e+00 7.56476736e+00 8.98997211e+00 9.43107224e+00 9.54258537e+00 9.07583046e+00 9.14559269e+00 9.78302097e+00 9.46042156e+00 8.40992928e+00 6.77014780e+00 7.01896334e+00 6.70721579e+00 7.43161011e+00 6.77550936e+00 8.35502338e+00 9.13522339e+00 1.02957640e+01 9.72585201e+00 8.40649509e+00 8.21559525e+00 7.61201620e+00 8.83455372e+00 7.93843746e+00 8.20809555e+00 8.03937912e+00 9.40152645e+00 1.03067789e+01 1.08385439e+01 1.01476908e+01 9.46104145e+00 9.92727947e+00 1.13994827e+01 1.08999109e+01 8.76828098e+00 7.41659641e+00 6.93255758e+00 8.25412750e+00 6.35899162e+00 6.40897083e+00 6.45328522e+00 7.43390751e+00 8.49560738e+00 7.74101973e+00 7.57790375e+00 5.76592875e+00 5.30571413e+00 5.50744343e+00 5.94255543e+00 6.25378990e+00 5.89068794e+00 6.20944786e+00 6.84353447e+00 7.49303007e+00 6.93284512e+00 5.86532545e+00 5.04626036e+00 5.92019701e+00 5.13961363e+00 5.27700472e+00 5.67491627e+00 8.90568542e+00 1.14277859e+01 1.20054464e+01 1.03110914e+01 9.44259930e+00 9.62775326e+00 9.27085209e+00 7.97826147e+00 5.71792316e+00 7.82122469e+00 8.77613163e+00 9.62334538e+00 8.11827564e+00 8.12163448e+00 8.18278408e+00 6.09576130e+00 5.24833536e+00 5.86647320e+00 7.82998466e+00 7.05177498e+00 7.35666943e+00 8.58582020e+00 8.76752758e+00 5.21255350e+00 2.47826052e+00 1.70411170e+00 3.99318218e+00 3.87819195e+00 3.66088414e+00 3.69412231e+00 4.38208580e+00 5.61990929e+00 4.94717216e+00 4.38389730e+00 3.75252843e+00 3.46282601e+00 5.03511000e+00 6.47408819e+00 7.80701399e+00 7.53796196e+00 5.76332760e+00 4.24648666e+00 3.34104013e+00 4.10958958e+00 3.65480280e+00 3.77758265e+00 4.31927490e+00 3.60701013e+00 1.89723301e+00 1.57283092e+00 4.03161240e+00 4.43204308e+00 4.46982861e+00 4.94538403e+00 7.63839817e+00 8.26614761e+00 6.84538651e+00 5.19051600e+00 3.81054306e+00 4.36962461e+00 4.07357025e+00 4.77414656e+00 6.00126219e+00 6.45101213e+00 6.50529099e+00 4.93612432e+00 4.86560059e+00 5.00602102e+00 5.19011354e+00 6.52894688e+00 7.26787710e+00 8.27049255e+00 6.95103359e+00 5.79322147e+00 5.82097721e+00 7.53065395e+00 6.36584187e+00 4.51737404e+00 2.08971620e+00 3.27331233e+00 4.69085979e+00 4.51924086e+00 4.76223993e+00 3.73782492e+00 2.75283623e+00 1.90312457e+00 2.50108647e+00 5.12464857e+00 6.75633860e+00 5.34546757e+00 5.02558994e+00 5.14765453e+00 4.63987875e+00 4.04923725e+00 2.83866787e+00 4.66888475e+00 5.19134903e+00 3.77637243e+00 1.52645731e+00 1.17589928e-01 2.01176286e+00 3.63575554e+00 3.80688334e+00 3.25030589e+00 3.11512661e+00 3.63318729e+00 3.19336486e+00 3.26590157e+00 4.21906805e+00 5.89579678e+00 5.47957373e+00 4.18029642e+00 2.46297240e+00 3.78623652e+00 3.60007858e+00 4.08776951e+00 2.67075610e+00 2.41546464e+00 2.65649223e+00 3.06025553e+00 9.74893868e-01 -4.76014882e-01 -3.89597964e+00 -2.79021811e+00 -1.41852272e+00 2.49152136e+00 1.79199517e+00 4.14213568e-01 -9.16099668e-01 -2.23338199e+00 -2.09031534e+00 -2.22061682e+00 -2.87523985e+00 -7.10333157e+00 -4.46260834e+01 -1.14003059e+02 -5.10893219e+02 -6.08851685e+02 2.47417627e+03 1.64311953e+04 -1638379008. 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. 2.75057254e+09 -6.25107520e+03 2.29594406e+02 3.92353943e+02 9.91939163e+01 5.53960762e+01 1.29673672e+01 1.84001207e+00 1.39472103e+00 -6.66706711e-02 -4.12799120e-02 -7.53637850e-01 -6.47033215e-01 -9.43506122e-01 2.79523939e-01 7.22882211e-01 -2.90064663e-01 -2.02865505e+00 -3.82159472e+00 -4.06781244e+00 -3.41497874e+00 -1.51238394e+00 -3.45806152e-01 6.76226616e-01 -1.39336109e-01 -8.84987354e-01 -8.84445310e-01 -5.85370362e-01 -1.88748527e+00 -2.48642945e+00 -1.78767920e+00 -7.66435638e-02 4.68951881e-01 7.68140256e-01 7.39777863e-01 -9.75473505e-03 -1.72669268e+00 -2.45489717e+00 -3.07664180e+00 -1.61823702e+00 -2.17786074e+00 -8.56720805e-01 -5.51900506e-01 1.43043935e-01 -1.29734075e+00 -2.12925029e+00 -1.84726679e+00 -1.34025693e+00 -8.87690365e-01 -1.09180188e+00 -9.25451875e-01 -1.95461464e+00 -2.26492214e+00 -3.67134356e+00 -3.55810595e+00 -4.32534075e+00 -2.78615928e+00 -1.08290780e+00 4.81229156e-01 2.84637511e-01 -1.16723979e+00 -1.88636363e+00 -2.16357803e+00 -1.93008757e+00 -1.98011649e+00 -2.63884521e+00 -2.62789702e+00 -2.52004313e+00 -1.42442155e+00 -2.49427629e+00 -3.09198999e+00 -3.36443162e+00 -3.55294943e+00 -3.47215772e+00 -3.44010282e+00 -3.17996573e+00 -3.57612848e+00 -3.40303969e+00 -3.62960982e+00 -3.48005414e+00 -4.49233532e+00 -4.00535107e+00 -3.06995869e+00 -2.89571524e+00 -2.97957397e+00 -4.30125237e+00 -4.39823771e+00 -4.06089640e+00 -3.27749014e+00 -3.55387068e+00 -3.74739361e+00 -2.90049076e+00 -1.57586265e+00 -1.88486898e+00 -3.44636250e+00 -4.24020720e+00 -3.12938118e+00 -2.65563345e+00 -3.40093064e+00 -4.28167391e+00 -4.26142025e+00 -3.45440531e+00 -3.47882581e+00 -4.32170153e+00 -5.57837439e+00 -5.39861393e+00 -4.49353266e+00 -2.76560807e+00 -1.85108614e+00 -1.33270073e+00 -2.79507947e+00 -4.28415489e+00 -4.49285746e+00 -3.48826790e+00 -2.98527622e+00 -2.68437505e+00 -3.09186649e+00 -2.01068830e+00 -2.14045048e+00 -3.84194303e+00 -5.08846855e+00 -5.82185888e+00 -4.22983885e+00 -3.74913406e+00 -2.97936988e+00 -2.36872673e+00 -3.44686389e+00 -4.22541046e+00 -5.54493284e+00 -5.77767611e+00 -5.81673193e+00 -5.33793736e+00 -5.21540689e+00 -5.41567326e+00 -4.68581390e+00 -4.08150005e+00 -3.21824837e+00 -3.73098421e+00 -4.74327421e+00 -6.30572510e+00 -6.80970573e+00 -6.07113314e+00 -4.46671295e+00 -3.75055814e+00 -3.58670592e+00 -4.23390818e+00 -3.60613322e+00 -3.63334966e+00 -3.57252455e+00 -4.98725557e+00 -5.59271288e+00 -6.49585295e+00 -5.63240814e+00 -4.76943111e+00 -4.05050468e+00 -4.79798889e+00 -5.10255051e+00 -4.38267946e+00 -2.89133644e+00 -3.29549623e+00 -5.00061417e+00 -5.55361986e+00 -4.56413698e+00 -3.41049004e+00 -4.55263758e+00 -4.80781269e+00 -4.84224176e+00 -3.59128094e+00 -3.18209791e+00 -4.09855509e+00 -5.39058161e+00 -6.73646212e+00 -6.16465330e+00 -6.52982569e+00 -6.73326731e+00 -5.76513624e+00 -5.79848766e+00 -4.76195621e+00 -5.48343277e+00 -5.37765455e+00 -6.12122583e+00 -6.93397760e+00 -6.31459093e+00 -5.92836380e+00 -6.02172136e+00 -5.66669893e+00 -6.31120872e+00 -4.94493008e+00 -5.88638687e+00 -5.79799604e+00 -5.92410898e+00 -4.72676516e+00 -4.56631565e+00 -6.09247303e+00 -6.27981520e+00 -7.33239222e+00 -6.70709085e+00 -7.43266106e+00 -6.31703424e+00 -6.53150415e+00 -6.29697132e+00 -6.19473171e+00 -6.10744095e+00 -5.44443798e+00 -6.08456707e+00 -5.23516846e+00 -6.02880621e+00 -5.61271858e+00 -6.61487389e+00 -5.89111757e+00 -6.40887308e+00 -6.13906670e+00 -6.44457912e+00 -5.21502733e+00 -5.79847956e+00 -6.75711441e+00 -7.17029715e+00 -7.13078928e+00 -5.15592813e+00 -5.01158381e+00 -4.44498682e+00 -5.96887398e+00 -7.19463015e+00 -7.23723173e+00 -6.51704407e+00 -5.81302738e+00 -5.92482281e+00 -7.19668388e+00 -7.20666075e+00 -7.50668335e+00 -6.13657856e+00 -6.36088991e+00 -6.17920780e+00 -6.50989962e+00 -6.18354177e+00 -6.27901983e+00 -5.48686028e+00 -5.42393351e+00 -5.50489378e+00 -6.42929029e+00 -6.08299017e+00 -6.31512213e+00 -6.85395050e+00 -6.35600662e+00 -6.04896688e+00 -5.72330713e+00 -7.22055817e+00 -7.06537104e+00 -7.06195164e+00 -6.66594601e+00 -7.26773739e+00 -7.24843025e+00 -6.90258884e+00 -6.54414225e+00 -5.93821430e+00 -5.85108328e+00 -6.08384132e+00 -6.11748743e+00 -5.92619801e+00 -6.14762497e+00 -6.23637342e+00 -6.83505297e+00 -5.89063597e+00 -6.55582714e+00 -6.90224695e+00 -7.36349487e+00 -7.55204391e+00 -6.53421640e+00 -5.90524530e+00 -5.72169876e+00 -6.34738302e+00 -5.94988108e+00 -5.78730726e+00 -5.15795040e+00 -6.24713421e+00 -6.54411793e+00 -7.00070953e+00 -6.81348991e+00 -6.80033207e+00 -6.51641130e+00 -6.89067888e+00 -7.35627604e+00 -8.28065968e+00 -7.79002714e+00 -7.35782814e+00 -7.37543201e+00 -7.80355978e+00 -7.56322193e+00 -7.09543276e+00 -6.41684675e+00 -6.60185575e+00 -6.73860216e+00 -7.18420172e+00 -6.83764124e+00 -7.04274178e+00 -7.37635088e+00 -7.20031595e+00 -7.21109724e+00 -6.73554277e+00 -7.17294884e+00 -6.42504215e+00 -6.09804916e+00 -6.14426947e+00 -6.82188988e+00 -7.66159534e+00 -7.45303488e+00 -7.10737562e+00 -7.17134142e+00 -7.57211781e+00 -7.78611279e+00 -7.99357653e+00 -7.76874018e+00 -7.80567265e+00 -7.38058138e+00 -7.39542580e+00 -7.66351509e+00 -8.06174564e+00 -7.93709040e+00 -7.19893789e+00 -6.91766787e+00 -7.03228855e+00 -7.53455067e+00 -7.57654095e+00 -7.20427704e+00 -7.29126930e+00 -7.45657015e+00 -8.15523720e+00 -8.75248337e+00 -8.87283039e+00 -8.77525234e+00 -8.09455109e+00 -8.02022839e+00 -8.03482437e+00 -8.17903042e+00 -7.90317535e+00 -7.91781235e+00 -8.43354511e+00 -8.43068695e+00 -8.21129322e+00 -7.94311333e+00 -8.28587818e+00 -8.23169231e+00 -7.61723089e+00 -7.07369661e+00 -7.58310556e+00 -8.00590801e+00 -8.73329735e+00 -8.30880833e+00 -8.36659241e+00 -8.22691345e+00 -8.45790291e+00 -8.07527161e+00 -8.08032799e+00 -8.38871574e+00 -8.72398853e+00 -8.36496067e+00 -7.96921873e+00 -7.78576565e+00 -8.16201115e+00 -8.43604851e+00 -8.68776608e+00 -8.98333073e+00 -8.78466511e+00 -8.41142464e+00 -7.99483871e+00 -8.06102943e+00 -7.96817636e+00 -8.01752663e+00 -7.88721180e+00 -8.26042366e+00 -8.23555756e+00 -8.34042740e+00 -8.28358364e+00 -8.18342400e+00 -8.21829128e+00 -8.05461025e+00 -7.97322321e+00 -7.88940287e+00 -8.18279171e+00 -8.37208271e+00 -8.18611431e+00 -7.95677280e+00 -7.99996996e+00 -8.38370037e+00 -8.36482430e+00 -8.48972607e+00 -8.28501606e+00 -8.48104477e+00 -8.35531712e+00 -8.37531090e+00 -8.04896641e+00 -8.09409904e+00 -8.36246204e+00 -8.83863354e+00 -8.49052525e+00 -8.03792763e+00 -7.81291056e+00 -7.99651670e+00 -8.34787178e+00 -8.47893810e+00 -8.59992123e+00 -8.49423122e+00 -8.58182812e+00 -8.55189228e+00 -8.73980713e+00 -8.32677078e+00 -8.26639843e+00 -8.07427979e+00 -8.35370350e+00 -8.45625591e+00 -8.51840305e+00 -8.53466320e+00 -8.46679401e+00 -8.42463684e+00 -8.38323212e+00 -8.36486721e+00 -8.46738529e+00 -8.45977211e+00 -8.50499630e+00 -8.46697998e+00 -8.45090866e+00 -8.54816914e+00 -8.55444622e+00 -8.57328510e+00 -8.51691628e+00 -8.47631168e+00 -8.43968868e+00 -8.43036366e+00 -8.51738453e+00 -8.56767845e+00 -8.57459641e+00 -8.51769257e+00 -8.51655293e+00 -8.52110863e+00 -8.55104160e+00 -8.54205227e+00 -8.53912354e+00 -8.52828407e+00 -8.52991104e+00 -8.53403664e+00 -8.53775215e+00 -8.53036213e+00 -8.52599049e+00 -8.50767899e+00 -8.50977325e+00 -8.54113102e+00 -8.54676437e+00 -8.56561184e+00 -8.53795147e+00 -8.51618004e+00 -8.51762486e+00 -8.54203224e+00 -8.57637024e+00 -8.57468033e+00 -8.52646542e+00 -8.55751801e+00 -8.51484966e+00 -8.50939178e+00 -8.46413898e+00 -8.48977280e+00 -8.59478951e+00 -8.60314655e+00 -8.51883602e+00 -8.57163811e+00 -8.55576324e+00 -8.70152855e+00 -8.54784489e+00 -8.56371498e+00 -8.49987984e+00 -8.49998856e+00 -8.58763504e+00 -8.45923996e+00 -8.39377117e+00 -8.14874840e+00 -8.21480656e+00 -8.35918236e+00 -8.45897675e+00 -8.56259537e+00 -8.39142132e+00 -8.31637669e+00 -8.25163651e+00 -8.44852829e+00 -8.49363518e+00 -8.46753502e+00 -8.17530537e+00 -8.24616814e+00 -8.07436943e+00 -8.35214901e+00 -8.38049126e+00 -8.76141644e+00 -8.57794285e+00 -8.47822285e+00 -8.39794636e+00 -8.49816132e+00 -8.43987179e+00 -8.47032738e+00 -8.55972099e+00 -8.66835499e+00 -8.38935852e+00 -8.18991852e+00 -8.39278507e+00 -8.42311478e+00 -8.52812672e+00 -8.21750450e+00 -8.16872311e+00 -7.88821030e+00 -7.95034647e+00 -7.99936533e+00 -8.35904980e+00 -8.43054771e+00 -8.48084068e+00 -8.49579144e+00 -8.18382740e+00 -8.25674629e+00 -8.07955456e+00 -8.48082066e+00 -8.42881012e+00 -8.28724861e+00 -8.10758400e+00 -8.04361343e+00 -8.17771626e+00 -8.26697063e+00 -8.37321377e+00 -8.18909645e+00 -8.31724548e+00 -8.45186043e+00 -8.73615837e+00 -8.38177776e+00 -8.21020794e+00 -7.83761263e+00 -7.94587326e+00 -7.60162067e+00 -8.09843254e+00 -8.17566872e+00 -8.53205776e+00 -8.39225292e+00 -8.34469223e+00 -8.10317326e+00 -8.49553490e+00 -8.34755993e+00 -8.33055878e+00 -7.74942112e+00 -7.36131001e+00 -7.29507303e+00 -7.66710854e+00 -8.33374786e+00 -8.77421093e+00 -8.15468407e+00 -7.32498121e+00 -6.77606726e+00 -7.07119560e+00 -7.73855591e+00 -8.51268101e+00 -8.13956165e+00 -7.61408567e+00 -7.40887642e+00 -7.42293692e+00 -7.93284130e+00 -7.70793962e+00 -7.90128422e+00 -7.89696884e+00 -7.83658218e+00 -7.67144203e+00 -7.41912317e+00 -7.52250767e+00 -8.48383141e+00 -9.13549709e+00 -8.79980183e+00 -8.09108829e+00 -7.52552271e+00 -7.95621681e+00 -8.14699841e+00 -8.25726700e+00 -7.03423834e+00 -6.76621389e+00 -7.30187607e+00 -8.23945045e+00 -7.91289282e+00 -7.12664080e+00 -7.04010677e+00 -7.46059608e+00 -7.85809374e+00 -8.21444988e+00 -8.24251556e+00 -7.63571358e+00 -7.65596628e+00 -7.57283115e+00 -8.00502491e+00 -7.87769938e+00 -7.67838478e+00 -7.90211487e+00 -7.93060637e+00 -7.55269623e+00 -7.23674536e+00 -7.05668354e+00 -8.10534000e+00 -7.85069847e+00 -7.48416758e+00 -6.84876633e+00 -7.42831182e+00 -7.99599743e+00 -8.10512161e+00 -8.24645710e+00 -8.04189873e+00 -7.70388031e+00 -6.93391895e+00 -6.61615515e+00 -7.57601023e+00 -7.44329977e+00 -6.70145702e+00 -5.85148668e+00 -5.92944765e+00 -6.14857292e+00 -5.53958941e+00 -5.94149303e+00 -6.53786469e+00 -6.21295691e+00 -4.72536612e+00 -1.93173707e+00 -2.75404263e+00 5.38519001e+00 4.19462013e+01 4.19347198e+02 9.95509644e+02 130009296. -133904840. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -77444984. -367311776. 878504896. 2.26729395e+03 -1.51179459e+02 -2.76879150e+02 -7.72380676e+01 -3.87421455e+01 -1.90842991e+01 -1.26877689e+01 -9.06159019e+00 -9.31713867e+00 -8.86458206e+00 -7.19921780e+00 -6.17544365e+00 -5.04050303e+00 -6.32977009e+00 -5.51157188e+00 -6.03708172e+00 -6.53497267e+00 -6.51864719e+00 -7.32037735e+00 -6.83818054e+00 -6.81585455e+00 -4.74340010e+00 -3.77503467e+00 -5.80824327e+00 -6.67563057e+00 -5.88008213e+00 -4.16823864e+00 -4.90732861e+00 -7.26165915e+00 -7.30848265e+00 -6.43666220e+00 -5.11945677e+00 -5.03200245e+00 -5.10604239e+00 -5.46726751e+00 -5.77668142e+00 -6.04503202e+00 -5.60776091e+00 -5.62691307e+00 -5.54899073e+00 -5.79436827e+00 -5.91985178e+00 -6.46411705e+00 -7.20074701e+00 -6.44119358e+00 -5.91981840e+00 -5.08330965e+00 -5.45906925e+00 -6.57332516e+00 -6.17770243e+00 -5.21529007e+00 -3.89366436e+00 -4.34384394e+00 -5.24125576e+00 -4.79730511e+00 -4.75230217e+00 -3.66900992e+00 -3.72999859e+00 -3.50005889e+00 -4.05181980e+00 -5.16399860e+00 -6.17642260e+00 -6.38390112e+00 -5.73438835e+00 -5.24085522e+00 -4.97698975e+00 -4.85066605e+00 -5.23817205e+00 -6.49083185e+00 -6.83952332e+00 -6.14258623e+00 -4.95047665e+00 -4.43120384e+00 -4.89367151e+00 -3.74424791e+00 -3.18791270e+00 -2.34962058e+00 -2.94122744e+00 -4.07556009e+00 -3.67859221e+00 -4.59655476e+00 -3.54634237e+00 -3.67646646e+00 -2.70778275e+00 -3.08513308e+00 -4.10654640e+00 -4.51885128e+00 -4.54019737e+00 -4.08350706e+00 -4.30756378e+00 -4.14489412e+00 -3.74000907e+00 -2.81679487e+00 -3.57282782e+00 -3.94244337e+00 -4.05342388e+00 -3.44658208e+00 -2.80795288e+00 -4.48555994e+00 -5.33946371e+00 -5.28648567e+00 -4.34356928e+00 -3.88903284e+00 -5.03610086e+00 -5.08198452e+00 -4.86275482e+00 -4.62000847e+00 -4.53532410e+00 -4.42421961e+00 -4.20540047e+00 -5.13899803e+00 -5.21258211e+00 -5.01968527e+00 -4.51915264e+00 -4.83607435e+00 -4.80390120e+00 -3.97162557e+00 -3.33847380e+00 -3.94870234e+00 -3.35005975e+00 -3.37537599e+00 -1.91620398e+00 -2.55585170e+00 -3.89927888e+00 -4.49900532e+00 -3.95611453e+00 -2.52923322e+00 -2.09383249e+00 -3.33537316e+00 -3.97932220e+00 -4.49136829e+00 -4.13289452e+00 -3.58432531e+00 -3.75045896e+00 -3.59542799e+00 -4.00848389e+00 -4.06575584e+00 -3.14036965e+00 -2.65351582e+00 -2.23244715e+00 -3.30545282e+00 -3.57638097e+00 -3.36913919e+00 -2.83933902e+00 -2.87043500e+00 -2.56500077e+00 -3.44393730e+00 -3.20998502e+00 -3.93638587e+00 -3.20738053e+00 -3.43183589e+00 -2.36250234e+00 -1.48024821e+00 -1.33499444e+00 -6.89817131e-01 -1.81489670e+00 -1.77081585e+00 -3.22484517e+00 -2.86802101e+00 -2.18422842e+00 -1.68623650e+00 -2.83939528e+00 -3.80340576e+00 -3.09569669e+00 -2.32253885e+00 -6.44841433e-01 -5.40993392e-01 1.88221848e+00 -6.40843391e-01 -5.75437188e-01 -1.18495619e+00 -2.33443424e-01 4.85644042e-01 -8.32305908e-01 -6.49224699e-01 -2.05020261e+00 -2.56687045e+00 -2.27603483e+00 -1.68495786e+00 -2.94797421e-01 -8.03233206e-01 -1.51671052e+00 -1.48439562e+00 -1.49129435e-01 -2.05334514e-01 -8.66475701e-01 -3.50428128e+00 -4.26517773e+00 -3.66127896e+00 -1.30451190e+00 -7.87899196e-02 4.80556697e-01 -5.07639587e-01 -1.98501229e+00 -2.36596131e+00 -7.69357264e-01 6.53208673e-01 8.57773602e-01 -1.71128854e-01 -9.32884455e-01 -2.18114734e+00 -2.03341460e+00 -2.02530813e+00 -1.78252232e+00 -1.81618738e+00 -1.31189644e+00 -1.60141516e+00 -2.26258945e+00 -2.88456702e+00 -2.02777624e+00 -8.97444785e-01 2.10720137e-01 -2.91680992e-02 -1.97560024e+00 -3.44183183e+00 -3.11951804e+00 -2.11625242e+00 -1.84436917e+00 -1.93107331e+00 -6.96724117e-01 4.21699643e-01 2.04483247e+00 2.40922451e+00 1.94128919e+00 4.83075321e-01 -4.43436086e-01 -5.34523785e-01 7.66499117e-02 5.99035323e-01 1.20644629e+00 1.43497360e+00 1.09983921e+00 1.08041227e+00 7.56538689e-01 9.33095753e-01 7.45166004e-01 1.66327834e+00 1.61582839e+00 1.50218165e+00 2.20060065e-01 -6.59360066e-02 1.87258697e+00 1.91830719e+00 2.68412876e+00 1.21190166e+00 1.37355971e+00 1.21147668e+00 1.69882250e+00 2.19545674e+00 1.93843651e+00 1.01071429e+00 -2.38189518e-01 -6.84134185e-01 -4.87680405e-01 4.44415882e-02 6.57568216e-01 6.94945395e-01 7.95514107e-01 -1.44294128e-01 -6.33054912e-01 -2.58637667e-01 1.61424935e+00 1.30132246e+00 4.97609109e-01 -6.16725206e-01 2.44872761e+00 2.52069998e+00 3.03195238e+00 1.41744936e+00 1.64071417e+00 2.23042560e+00 1.18477893e+00 1.34612501e+00 1.21961260e+00 2.53269458e+00 2.57493877e+00 1.92819417e+00 8.14672351e-01 7.10021555e-01 2.44190621e+00 2.65456438e+00 2.35012269e+00 1.28715515e+00 2.39404082e+00 3.19182062e+00 2.85787344e+00 1.75148952e+00 1.18673432e+00 1.44436777e+00 1.89514101e+00 1.67509234e+00 1.80603349e+00 2.04782772e+00 2.94702744e+00 2.65718865e+00 3.11342144e+00 2.75266862e+00 2.83043671e+00 4.42795658e+00 3.20102406e+00 3.41663265e+00 1.87440920e+00 2.54471064e+00 2.30030632e+00 1.19086909e+00 1.72888911e+00 2.39525628e+00 2.74128079e+00 2.50970721e+00 2.92971539e+00 2.47545600e+00 1.78429985e+00 2.03934145e+00 2.24963927e+00 3.32923508e+00 2.47034502e+00 3.14434290e+00 3.37532973e+00 3.23863411e+00 3.43514562e+00 2.50399518e+00 3.35569763e+00 3.02871418e+00 3.36867356e+00 2.65453839e+00 2.29939342e+00 3.34170914e+00 3.50405550e+00 3.85440755e+00 3.33546877e+00 3.60811973e+00 3.56869912e+00 3.85119724e+00 3.12603474e+00 2.79190922e+00 2.02096558e+00 2.39716101e+00 1.99847555e+00 4.22089863e+00 3.54243279e+00 3.82995653e+00 2.40544534e+00 2.16094661e+00 8.24083507e-01 2.58104181e+00 2.97904515e+00 4.54159832e+00 2.81721997e+00 3.10986543e+00 2.14401031e+00 3.24358511e+00 2.82767725e+00 4.88155603e+00 3.84273052e+00 4.93618250e+00 4.39689636e+00 4.35293531e+00 3.77706933e+00 4.38348007e+00 3.63947415e+00 4.20920038e+00 3.99258733e+00 5.73768091e+00 5.26207304e+00 3.75395823e+00 3.99986959e+00 3.24375987e+00 4.86628294e+00 3.82171655e+00 4.51936102e+00 3.61260438e+00 3.65509892e+00 4.43551302e+00 5.74798822e+00 5.95267820e+00 4.64601755e+00 4.47092485e+00 5.11731911e+00 5.26598930e+00 4.50337267e+00 4.09181070e+00 4.63551712e+00 5.21735239e+00 5.55012846e+00 5.74439001e+00 5.48363829e+00 4.65360928e+00 4.34667683e+00 4.05525827e+00 4.83969975e+00 4.85678720e+00 5.64005518e+00 4.81595659e+00 5.44926691e+00 4.51429033e+00 6.62276316e+00 5.45704412e+00 5.93842697e+00 4.18213844e+00 5.77702856e+00 5.69193697e+00 5.67441750e+00 3.25090384e+00 2.06921768e+00 2.67562485e+00 4.00113153e+00 5.34216452e+00 5.64899063e+00 5.40869999e+00 5.28049660e+00 4.99952984e+00 5.33296251e+00 5.68104076e+00 5.78184175e+00 6.31243420e+00 5.26537704e+00 4.91121483e+00 4.52013683e+00 5.60859871e+00 5.66443729e+00 5.32175064e+00 4.61057997e+00 4.36061001e+00 4.54059219e+00 4.80625391e+00 5.67892838e+00 5.65574121e+00 5.47540951e+00 4.74918413e+00 4.75012016e+00 5.15116644e+00 6.01319313e+00 6.42870426e+00 5.99970388e+00 5.82098103e+00 5.58684444e+00 6.35688543e+00 6.08896112e+00 5.90191460e+00 5.53142357e+00 5.25296402e+00 5.79701853e+00 6.04320812e+00 6.85420036e+00 7.14231634e+00 6.90745306e+00 5.74420118e+00 5.27436590e+00 4.81864786e+00 6.14016771e+00 6.65579796e+00 6.34270382e+00 5.98871517e+00 7.50708628e+00 7.58951902e+00 1.03069372e+01 2.28306446e+01 2.24735947e+01 5.19342041e+01 4.46850647e+02 3.53963623e+03 68307016. 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. 0. 0. 0. 0. 0. 0. 186387872. 36761196. 1.11109082e+03 7.80300537e+02 9.85371323e+01 -2.48511551e+02 -1.78236374e+02 -2.12954330e+01 2.00043845e+00 6.03901243e+00 7.98186636e+00 8.06787395e+00 7.30520153e+00 7.25245476e+00 7.59531260e+00 7.68490791e+00 7.70361805e+00 8.29364300e+00 8.71714973e+00 8.44476700e+00 8.00701523e+00 7.60996485e+00 7.75022840e+00 7.47472525e+00 7.49289513e+00 7.24900627e+00 7.09725761e+00 7.19931984e+00 7.49755144e+00 7.55852175e+00 7.10714579e+00 6.82110453e+00 7.01201868e+00 7.23404789e+00 7.25973225e+00 7.24164391e+00 7.48328352e+00 7.61439562e+00 7.74153566e+00 7.50433922e+00 8.03433704e+00 8.07704163e+00 8.24586868e+00 7.92851496e+00 7.51891518e+00 7.45732212e+00 7.33340216e+00 7.34733105e+00 7.04963350e+00 7.00475550e+00 6.99624634e+00 7.19200277e+00 7.58084011e+00 7.68884754e+00 7.83772326e+00 7.82676315e+00 7.78185892e+00 7.82190418e+00 7.49636793e+00 7.90521431e+00 7.63735151e+00 7.75197315e+00 8.01976109e+00 8.50142384e+00 8.59548187e+00 8.25148487e+00 8.15081215e+00 8.35470104e+00 8.54445362e+00 8.64251518e+00 8.18353558e+00 8.03217316e+00 7.65818501e+00 7.71355438e+00 7.42361355e+00 7.31628466e+00 7.46163225e+00 7.49763012e+00 7.85854721e+00 7.90907049e+00 8.13469028e+00 8.27830887e+00 8.24252224e+00 8.19674206e+00 8.23654842e+00 8.33942795e+00 8.57016373e+00 8.28163052e+00 8.23321438e+00 8.14087963e+00 8.36350346e+00 8.32771587e+00 8.37029266e+00 8.44129467e+00 8.53553391e+00 8.46289539e+00 8.34067154e+00 8.15009785e+00 8.25201607e+00 8.44878864e+00 8.71089363e+00 8.66735840e+00 8.45447159e+00 8.40786743e+00 8.38642216e+00 8.46624851e+00 8.27195740e+00 8.30708027e+00 8.42455387e+00 8.75707436e+00 8.85896778e+00 8.64671516e+00 8.45392704e+00 8.38916302e+00 8.42429733e+00 8.52823257e+00 8.41390038e+00 8.42444038e+00 8.26306629e+00 8.13416004e+00 8.07728672e+00 8.11925411e+00 8.43926525e+00 8.56836796e+00 8.64120007e+00 8.52832603e+00 8.45674706e+00 8.50518513e+00 8.68640614e+00 8.86392307e+00 8.80461884e+00 8.65085411e+00 8.45350552e+00 8.48775673e+00 8.47296810e+00 8.62675667e+00 8.60668182e+00 8.60202122e+00 8.45972538e+00 8.45383263e+00 8.49285698e+00 8.54856396e+00 8.51499176e+00 8.47690201e+00 8.49617672e+00 8.50043106e+00 8.55630589e+00 8.50559616e+00 8.53829002e+00 8.48866940e+00 8.51517200e+00 8.45460796e+00 8.41673183e+00 8.48530006e+00 8.59895802e+00 8.61040211e+00 8.55927944e+00 8.51531792e+00 8.57152843e+00 8.60654068e+00 8.62339687e+00 8.63746643e+00 8.63739109e+00 8.62762260e+00 8.56971169e+00 8.53535271e+00 8.52477741e+00 8.54706383e+00 8.54281235e+00 8.53549480e+00 8.53905106e+00 8.53660774e+00 8.54067993e+00 8.53415108e+00 8.53581810e+00 8.53472042e+00 8.53393459e+00 8.53578091e+00 8.53624725e+00 8.53612614e+00 8.53117752e+00 8.52974224e+00 8.52469158e+00 8.51108551e+00 8.52187729e+00 8.50995159e+00 8.51015186e+00 8.50618172e+00 8.56576157e+00 8.55495453e+00 8.56356621e+00 8.51146698e+00 8.56014824e+00 8.50935841e+00 8.49391937e+00 8.46212196e+00 8.47641182e+00 8.46051216e+00 8.44007015e+00 8.46761799e+00 8.53756618e+00 8.56480789e+00 8.58915424e+00 8.50780201e+00 8.48554707e+00 8.48704433e+00 8.55697823e+00 8.54620647e+00 8.46685791e+00 8.37095833e+00 8.44727898e+00 8.47071838e+00 8.48691368e+00 8.41683674e+00 8.40105438e+00 8.41511059e+00 8.43593311e+00 8.42929173e+00 8.39039040e+00 8.32310200e+00 8.30612659e+00 8.35645676e+00 8.43880653e+00 8.50880051e+00 8.47850418e+00 8.39239788e+00 8.35240746e+00 8.37984657e+00 8.49074364e+00 8.48515892e+00 8.45437241e+00 8.40840244e+00 8.32060814e+00 8.50007534e+00 8.51024914e+00 8.61354065e+00 8.51030540e+00 8.46148586e+00 8.57107067e+00 8.57328415e+00 8.49991417e+00 8.39963627e+00 8.35032177e+00 8.42279148e+00 8.57062912e+00 8.63720894e+00 8.80779839e+00 8.76407242e+00 8.52309799e+00 8.11878109e+00 8.15989304e+00 8.29737473e+00 8.55383873e+00 8.20827675e+00 8.03374958e+00 7.99991083e+00 8.35911560e+00 8.54094124e+00 8.75535393e+00 8.72103977e+00 8.70146561e+00 8.21250057e+00 8.00242424e+00 7.97233438e+00 8.23662949e+00 7.79739666e+00 8.14101124e+00 8.20680237e+00 8.71368313e+00 8.45069981e+00 8.52670479e+00 8.43014240e+00 8.37608433e+00 8.33004761e+00 8.28774929e+00 8.45951939e+00 8.28862095e+00 8.13472939e+00 7.69444513e+00 7.70874357e+00 7.89016151e+00 8.23745060e+00 8.52589226e+00 8.38544846e+00 8.11089706e+00 7.90985775e+00 8.08643055e+00 8.31875420e+00 8.50134182e+00 8.40907288e+00 8.16551399e+00 7.95510435e+00 8.19643307e+00 8.15748978e+00 8.12611961e+00 8.09156322e+00 8.19139957e+00 7.93568230e+00 7.52293444e+00 7.61879253e+00 7.87511635e+00 8.21945858e+00 7.66647100e+00 7.58542204e+00 7.29039717e+00 7.66940022e+00 7.35004377e+00 7.24302721e+00 6.91193104e+00 7.02875137e+00 7.03054380e+00 7.03382444e+00 7.21634769e+00 7.25207615e+00 7.49161577e+00 7.23850203e+00 7.50312519e+00 7.54933119e+00 8.11122990e+00 7.61025620e+00 7.86579466e+00 7.22323322e+00 7.68472147e+00 7.55339956e+00 7.68614197e+00 7.47816324e+00 6.98027563e+00 6.58636999e+00 6.30130482e+00 6.08831453e+00 6.54218626e+00 6.62900400e+00 7.46733189e+00 7.57854319e+00 7.83762836e+00 7.48832512e+00 7.71990538e+00 7.31682062e+00 6.73630476e+00 6.43883228e+00 6.79964447e+00 7.46356726e+00 8.11953831e+00 8.09716511e+00 8.12942791e+00 7.51379538e+00 7.37945032e+00 7.26704264e+00 6.80460644e+00 6.68010712e+00 6.75159454e+00 7.20441866e+00 7.46022415e+00 6.68786430e+00 5.78949976e+00 5.77922487e+00 6.22711229e+00 6.69577312e+00 6.62390709e+00 7.01597929e+00 6.63899517e+00 6.80104876e+00 6.46093941e+00 6.75261593e+00 6.28552961e+00 6.49724340e+00 6.48284864e+00 6.90101147e+00 7.44002295e+00 7.95261574e+00 7.80402374e+00 6.85880709e+00 5.89281273e+00 6.15832138e+00 7.14756966e+00 7.74976730e+00 7.42342281e+00 6.68746805e+00 6.68772173e+00 6.64777279e+00 5.96175718e+00 5.57111835e+00 5.52714348e+00 5.98580980e+00 6.41446590e+00 5.98483086e+00 5.99137402e+00 5.47183752e+00 6.02397156e+00 6.22918510e+00 6.33104181e+00 5.88458347e+00 5.62030554e+00 5.59165096e+00 6.12478209e+00 6.39149237e+00 6.19195509e+00 5.51947975e+00 5.67903519e+00 6.46954584e+00 6.59758139e+00 6.25619125e+00 5.70678949e+00 6.36719942e+00 6.21189928e+00 6.70314550e+00 6.87476110e+00 7.06961870e+00 6.25864601e+00 5.98357391e+00 5.94208956e+00 7.00812483e+00 5.93265533e+00 5.59479952e+00 5.34217501e+00 6.13805723e+00 6.34514475e+00 5.49637508e+00 5.43541908e+00 5.39602709e+00 6.01531267e+00 6.35223436e+00 6.48607159e+00 7.18072510e+00 6.78626347e+00 6.81186104e+00 5.41884327e+00 5.48818970e+00 5.22343493e+00 5.75278664e+00 5.72644281e+00 5.17148304e+00 5.03146887e+00 4.61707497e+00 5.40058661e+00 5.66708136e+00 6.04210043e+00 5.26063061e+00 4.66564035e+00 4.22228575e+00 4.48087883e+00 4.28651094e+00 4.07928991e+00 4.48082066e+00 5.13214302e+00 6.40765238e+00 6.17563868e+00 6.40243435e+00 5.47072649e+00 5.47881222e+00 4.80533504e+00 4.98627949e+00 4.94604206e+00 5.14843845e+00 5.24466991e+00 5.37637901e+00 5.59179783e+00 5.63020706e+00 4.84378052e+00 5.34972477e+00 5.00839758e+00 5.26012278e+00 4.00587893e+00 4.60022593e+00 5.24093962e+00 6.27187872e+00 4.81095505e+00 4.35435486e+00 3.63540673e+00 4.73985004e+00 4.63860559e+00 4.80025578e+00 4.04282904e+00 4.34454632e+00 4.04994535e+00 3.52046061e+00 3.08483005e+00 2.80840898e+00 4.54977274e+00 5.38778543e+00 5.50214434e+00 3.98707032e+00 2.40962148e+00 2.16642404e+00 2.72006059e+00 4.43042278e+00 4.39364672e+00 4.24346590e+00 3.53070164e+00 4.27501202e+00 4.05009365e+00 2.62313199e+00 7.36737013e-01 5.24888039e-01 1.30116868e+00 3.60198307e+00 4.08973694e+00 4.06936026e+00 3.50880861e+00 3.31484723e+00 3.83032990e+00 3.03323531e+00 2.37871861e+00 2.40804529e+00 2.66764808e+00 3.73258162e+00 4.00482416e+00 3.91356921e+00 2.92720795e+00 2.13426900e+00 1.83064103e+00 2.49207187e+00 2.19513750e+00 2.88864231e+00 2.41947937e+00 2.86350727e+00 2.78670835e+00 3.06479597e+00 3.69078612e+00 4.25579453e+00 3.95796967e+00 3.22817302e+00 3.12166405e+00 3.56313515e+00 3.67588282e+00 2.80924726e+00 2.17912889e+00 2.09693003e+00 2.25967765e+00 2.89733338e+00 2.81363344e+00 2.51149559e+00 2.37067342e+00 2.48382282e+00 2.21074462e+00 1.74482751e+00 1.37610769e+00 2.01907301e+00 2.49116468e+00 3.41661596e+00 3.31256676e+00 2.85324383e+00 1.53972626e+00 1.80208671e+00 2.03244996e+00 1.59213293e+00 1.07040215e+00 1.80971313e+00 2.55062914e+00 2.47828412e+00 1.39280856e+00 1.21130955e+00 1.70351422e+00 2.23660064e+00 3.57347012e+00 3.85970020e+00 3.52118015e+00 3.19141769e+00 2.09499788e+00 2.20822620e+00 1.70807993e+00 1.24204481e+00 4.97278363e-01 3.10761034e-02 9.72345293e-01 1.77417529e+00 1.29711616e+00 6.18928969e-01 1.10642564e+00 2.16713572e+00 3.13108587e+00 1.88058519e+00 1.37660384e+00 7.46684909e-01 1.23918009e+00 1.35034895e+00 1.16642320e+00 1.05631006e+00 1.11042714e+00 6.91035807e-01 2.24686280e-01 -8.72745037e-01 -2.58658469e-01 1.07248873e-01 7.29461908e-01 8.48008513e-01 6.41456187e-01 1.27347004e+00 6.40314758e-01 8.27198476e-02 -4.92521703e-01 6.86360240e-01 8.42789471e-01 1.39410150e+00 1.18390477e+00 1.00501204e+00 -4.83876765e-01 -1.60800219e+00 -1.15193570e+00 -5.83839238e-01 -1.17245865e+00 -9.74456429e-01 8.06671858e-01 2.18834019e+00 2.38732314e+00 -4.53537405e-01 -1.90018272e+00 -2.49558878e+00 2.98708415e+00 1.07168264e+01 1.32301056e+02 22310668. 0. 0. 0. 0. 0. 0. 0. 0. -1482731520. -3.15743656e+05 -3.15743656e+05 -3.32142592e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.67776768e+09 3.24284825e+06 1.58901904e+03 5.32333435e+02 6.52723312e+01 1.24403706e+01 2.15389180e+00 -1.25448272e-01 1.53786147e+00 1.53366852e+00 1.00045073e+00 1.15675175e+00 1.47740281e+00 8.69968891e-01 -1.05666257e-01 -2.86927134e-01 -1.44407079e-01 -7.59894431e-01 -1.37658191e+00 -1.48579121e+00 5.43775484e-02 1.12237597e+00 1.33270657e+00 2.33921021e-01 -4.37122047e-01 -6.83361650e-01 -1.41835606e+00 -1.66417325e+00 -2.08150744e+00 -2.13041425e+00 -1.43413901e+00 -1.02356243e+00 -5.23802757e-01 -1.19952250e+00 -2.06398296e+00 -2.16868830e+00 -1.94626081e+00 -8.18457901e-01 -1.02735090e+00 -1.05769026e+00 -6.38250232e-01 -2.30186731e-01 2.36075848e-01 -1.18050814e+00 -2.17398143e+00 -2.42035437e+00 -1.47757554e+00 -1.38853860e+00 -2.08628726e+00 -1.87416148e+00 -1.06571019e+00 -1.33075249e+00 -1.92333710e+00 -1.88096189e+00 -1.93121016e+00 -1.94963813e+00 -1.75312912e+00 -8.91375542e-01 -1.63277698e+00 -3.56467438e+00 -4.31827879e+00 -3.19177055e+00 -1.70302665e+00 -1.29396248e+00 -1.45333111e+00 -1.64449608e+00 -2.05735826e+00 -1.89511883e+00 -1.50633132e+00 -1.34580219e+00 -1.81301510e+00 -2.16871190e+00 -1.56264818e+00 -1.66326368e+00 -1.76313269e+00 -2.17932963e+00 -2.28500772e+00 -1.92050660e+00 -2.44765353e+00 -1.93820214e+00 -1.12700629e+00 -5.43070771e-03 -4.25064802e-01 -1.34962523e+00 -2.22361779e+00 -2.89085197e+00 -3.17151570e+00 -2.16681361e+00 -1.47061896e+00 -1.10955405e+00 -8.67068946e-01 -6.58940494e-01 -1.26568031e+00 -2.90550900e+00 -4.35640955e+00 -4.96400261e+00 -3.77230334e+00 -2.48024321e+00 -1.87261581e+00 -1.76620293e+00 -1.32150555e+00 -6.71064854e-01 -1.33743370e+00 -2.09018970e+00 -3.31826186e+00 -2.33803916e+00 -1.83124387e+00 -1.14612293e+00 -1.98700523e+00 -2.59553480e+00 -2.86021280e+00 -3.19026017e+00 -2.20388246e+00 -1.83407068e+00 -1.97732055e+00 -2.05869055e+00 -2.16897798e+00 -1.87401652e+00 -2.42590404e+00 -2.70189404e+00 -2.82410097e+00 -2.79481530e+00 -2.15049529e+00 -1.86073518e+00 -2.25071645e+00 -2.77534246e+00 -3.64318037e+00 -3.74750233e+00 -3.21836615e+00 -2.23530364e+00 -1.89161479e+00 -1.83226621e+00 -1.49662530e+00 -1.66896236e+00 -2.08733773e+00 -2.05512953e+00 -1.89214003e+00 -1.93099010e+00 -2.28991556e+00 -2.77066803e+00 -2.62275982e+00 -2.24906492e+00 -2.10150313e+00 -1.77613819e+00 -2.64129591e+00 -2.65224338e+00 -4.04734898e+00 -4.59511900e+00 -4.67697430e+00 -3.85484219e+00 -2.86765981e+00 -2.48355198e+00 -2.89843607e+00 -3.17421198e+00 -3.73821712e+00 -3.59746599e+00 -3.17718792e+00 -2.75693750e+00 -2.93880272e+00 -3.56054544e+00 -3.63632751e+00 -3.70806026e+00 -3.05698466e+00 -2.37259769e+00 -2.22825432e+00 -2.57766891e+00 -3.00163722e+00 -3.17765784e+00 -3.49438119e+00 -4.56557274e+00 -4.78381968e+00 -5.06531143e+00 -3.67522311e+00 -3.31094265e+00 -2.88517761e+00 -2.90216208e+00 -2.87943268e+00 -3.30202651e+00 -4.62805700e+00 -4.79592276e+00 -4.83780956e+00 -3.58905339e+00 -3.06691623e+00 -3.12267065e+00 -4.09511232e+00 -3.76497889e+00 -4.12809467e+00 -3.93945599e+00 -4.69781780e+00 -4.92159081e+00 -4.79400396e+00 -4.77648306e+00 -4.66494799e+00 -5.76045036e+00 -7.06147385e+00 -7.10603094e+00 -6.26287651e+00 -4.50366306e+00 -3.88141346e+00 -3.53658462e+00 -3.92437267e+00 -3.76420236e+00 -3.84630156e+00 -3.53130269e+00 -4.70503950e+00 -4.82720613e+00 -5.33678532e+00 -4.21949387e+00 -4.31728888e+00 -4.09264946e+00 -4.11800480e+00 -4.14582396e+00 -4.43862343e+00 -4.98394537e+00 -4.70333385e+00 -5.72694111e+00 -5.43428230e+00 -4.40542269e+00 -4.04572535e+00 -3.70581794e+00 -5.97682762e+00 -5.59306669e+00 -5.26616859e+00 -4.13065052e+00 -4.18852949e+00 -4.54783487e+00 -4.91676903e+00 -4.33937550e+00 -4.88589764e+00 -4.41335487e+00 -4.27512550e+00 -3.67124033e+00 -3.55253768e+00 -3.88138962e+00 -4.02599669e+00 -4.38035727e+00 -4.93689775e+00 -5.02457571e+00 -5.19813585e+00 -4.68955708e+00 -4.47612095e+00 -4.40056372e+00 -4.69151163e+00 -4.65986300e+00 -4.98635769e+00 -5.37754536e+00 -5.84602022e+00 -4.91133118e+00 -4.49636459e+00 -4.68226337e+00 -5.12230206e+00 -4.91555834e+00 -4.10929441e+00 -4.24944162e+00 -4.13644457e+00 -4.69734716e+00 -4.67506123e+00 -5.22130299e+00 -4.93525076e+00 -4.57321978e+00 -3.86625886e+00 -4.54617357e+00 -4.40406275e+00 -4.67800665e+00 -4.78660583e+00 -5.45905638e+00 -5.73224115e+00 -5.59348011e+00 -5.53420687e+00 -5.77977324e+00 -6.19450283e+00 -6.19090176e+00 -5.35564375e+00 -4.98604012e+00 -5.25946379e+00 -6.56583071e+00 -6.41581440e+00 -6.21396017e+00 -5.68133116e+00 -5.49897814e+00 -5.43415499e+00 -5.53009748e+00 -5.62893581e+00 -5.66522455e+00 -5.28909874e+00 -5.26176310e+00 -5.01961899e+00 -4.80555820e+00 -4.52718973e+00 -4.48216391e+00 -4.91244555e+00 -5.25679731e+00 -5.28721571e+00 -5.21812201e+00 -5.35850811e+00 -5.81591320e+00 -5.58352661e+00 -5.15516090e+00 -5.01234150e+00 -5.01298428e+00 -5.49264717e+00 -5.79308367e+00 -6.05566359e+00 -5.76179552e+00 -5.32724667e+00 -5.26561213e+00 -4.70738220e+00 -4.90881205e+00 -5.01649237e+00 -5.68777418e+00 -5.50996447e+00 -5.44933987e+00 -5.18495083e+00 -5.25900364e+00 -5.23611641e+00 -5.50172281e+00 -5.49837875e+00 -5.52010059e+00 -5.27421522e+00 -5.49740696e+00 -5.86385965e+00 -5.88278341e+00 -5.74771214e+00 -5.42838621e+00 -6.02589989e+00 -6.32135391e+00 -6.28571320e+00 -5.56951237e+00 -5.60084629e+00 -5.53814507e+00 -5.66843843e+00 -5.25908518e+00 -5.36524439e+00 -5.26255655e+00 -5.21789455e+00 -5.11458492e+00 -5.16999292e+00 -5.38922262e+00 -5.34436750e+00 -5.53582382e+00 -5.76418257e+00 -5.81427240e+00 -5.81305456e+00 -5.82489634e+00 -5.95528364e+00 -6.21963024e+00 -5.75349760e+00 -5.70340347e+00 -5.42842627e+00 -5.70947218e+00 -5.37892723e+00 -5.49898624e+00 -5.68814802e+00 -6.22445583e+00 -5.93038654e+00 -5.43880701e+00 -5.22699547e+00 -5.38757038e+00 -5.89481258e+00 -6.06009579e+00 -6.19864273e+00 -5.99296570e+00 -5.77756357e+00 -5.76440382e+00 -5.89287806e+00 -6.24475861e+00 -6.35329580e+00 -6.50842571e+00 -6.26329041e+00 -6.16293621e+00 -6.09528494e+00 -6.19526911e+00 -6.25409412e+00 -6.08531380e+00 -5.93068266e+00 -5.84309006e+00 -5.77725077e+00 -6.01829195e+00 -6.22973442e+00 -6.43937492e+00 -6.23418283e+00 -6.03569794e+00 -6.00452709e+00 -6.13869953e+00 -6.20751047e+00 -6.09144449e+00 -5.83103943e+00 -5.90364552e+00 -6.01881456e+00 -6.16000509e+00 -6.32157707e+00 -6.16249466e+00 -6.33186483e+00 -6.09746981e+00 -6.19181633e+00 -6.13803577e+00 -5.99238825e+00 -6.00808764e+00 -6.14372540e+00 -6.31363821e+00 -6.30947781e+00 -6.16791964e+00 -6.21680021e+00 -6.31592703e+00 -6.21236944e+00 -6.15594244e+00 -6.07956743e+00 -6.33747244e+00 -6.37458706e+00 -6.41354990e+00 -6.27667570e+00 -6.13147211e+00 -6.09464455e+00 -6.01199055e+00 -6.12152863e+00 -6.14589500e+00 -6.20933771e+00 -6.20979977e+00 -6.25899076e+00 -6.23410130e+00 -6.25099993e+00 -6.28718996e+00 -6.30447292e+00 -6.20759916e+00 -6.13229513e+00 -6.18152189e+00 -6.21384954e+00 -6.20576525e+00 -6.20114994e+00 -6.25284910e+00 -6.26291561e+00 -6.21543407e+00 -6.22009802e+00 -6.23840141e+00 -6.25807524e+00 -6.23703814e+00 -6.20604801e+00 -6.20244169e+00 -6.21164370e+00 -6.21711969e+00 -6.21566391e+00 -6.21301699e+00 -6.20612383e+00 -6.20083475e+00 -6.20423555e+00 -6.21518946e+00 -6.20958662e+00 -6.17175865e+00 -6.17000294e+00 -6.15894794e+00 -6.19017696e+00 -6.23132467e+00 -6.22371626e+00 -6.19173717e+00 -6.13846493e+00 -6.16572523e+00 -6.20643425e+00 -6.19240570e+00 -6.22267818e+00 -6.20792532e+00 -6.23108053e+00 -6.22726440e+00 -6.21685505e+00 -6.19468307e+00 -6.21113300e+00 -6.21263266e+00 -6.25073338e+00 -6.18573952e+00 -6.14415741e+00 -6.07801914e+00 -6.10679150e+00 -6.17452431e+00 -6.12835073e+00 -6.18334150e+00 -6.18962622e+00 -6.35009480e+00 -6.27132797e+00 -6.18457937e+00 -5.99737644e+00 -6.06203747e+00 -6.12605810e+00 -6.20408010e+00 -6.11464167e+00 -6.20791054e+00 -6.20016241e+00 -6.24762821e+00 -6.15474463e+00 -6.19464254e+00 -6.16240597e+00 -6.34463263e+00 -6.15553188e+00 -6.14162159e+00 -6.02961874e+00 -6.21510744e+00 -6.26284933e+00 -6.30527067e+00 -6.35756493e+00 -6.20578718e+00 -5.95322609e+00 -5.85284138e+00 -5.92355251e+00 -5.96849346e+00 -5.92032576e+00 -5.68822384e+00 -5.80500078e+00 -5.94565582e+00 -6.27804041e+00 -6.15236330e+00 -6.16428852e+00 -5.98057318e+00 -5.86695862e+00 -5.79677725e+00 -5.85136795e+00 -6.09488487e+00 -6.10952234e+00 -6.10157061e+00 -6.09179449e+00 -5.87696838e+00 -5.61145782e+00 -5.78966951e+00 -6.04100323e+00 -6.29956055e+00 -5.97273302e+00 -5.73964787e+00 -5.81562996e+00 -6.14848375e+00 -6.24624872e+00 -6.04083157e+00 -5.79325771e+00 -5.85757399e+00 -6.07479286e+00 -6.10259390e+00 -6.17485905e+00 -6.23745155e+00 -6.19077396e+00 -5.96527290e+00 -5.95755482e+00 -6.03087282e+00 -6.23232317e+00 -6.30783319e+00 -6.14872122e+00 -6.18652105e+00 -5.82656813e+00 -6.15647793e+00 -6.11417723e+00 -6.35402679e+00 -6.28785324e+00 -5.95539761e+00 -5.96535158e+00 -6.01091719e+00 -6.17838430e+00 -6.16859293e+00 -5.94313431e+00 -6.04810619e+00 -5.82072973e+00 -5.92265129e+00 -6.16991282e+00 -6.32694960e+00 -6.22875309e+00 -5.92844772e+00 -5.60885811e+00 -5.44021225e+00 -5.27411652e+00 -5.07946920e+00 -5.18566370e+00 -5.49773264e+00 -5.75018930e+00 -5.51807070e+00 -5.25690651e+00 -5.38497400e+00 -5.46243954e+00 -5.33237219e+00 -5.21718550e+00 -5.19388962e+00 -5.39020681e+00 -5.71649075e+00 -5.46571636e+00 -4.89963245e+00 -4.50457525e+00 -4.78272915e+00 -5.12432575e+00 -4.64420700e+00 -4.60821962e+00 -4.63084316e+00 -5.00996971e+00 -4.78516912e+00 -4.93389702e+00 -4.87486172e+00 -5.16348410e+00 -5.02458382e+00 -5.29735041e+00 -5.36593390e+00 -5.38557482e+00 -5.34258080e+00 -5.39988470e+00 -5.58352661e+00 -5.98899937e+00 -5.42745781e+00 -5.15688753e+00 -4.59491730e+00 -4.97572136e+00 -5.20177937e+00 -5.02666855e+00 -4.63831139e+00 -3.94361925e+00 -4.29323483e+00 -4.56011915e+00 -5.11540890e+00 -4.93191528e+00 -5.04276991e+00 -4.67548656e+00 -5.06582737e+00 -4.36228466e+00 -4.77868080e+00 -4.38259602e+00 -5.24950790e+00 -4.95531416e+00 -3.56842375e+00 -2.25561380e+00 5.01724243e-01 7.06090257e-02 8.96974182e+00 2.21998825e+01 1.41167160e+02 1.89902939e+02 -6.24494324e+02 -2.65695361e+03 -133904840. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -92942288. -2.82418042e+03 -5.11950134e+02 -8.53073883e+01 -4.35279198e+01 -2.61827641e+01 -1.18030081e+01 -7.26940155e+00 -5.13783836e+00 -4.81285000e+00 -4.73482895e+00 -4.41126156e+00 -4.11031675e+00 -4.41848278e+00 -4.51331711e+00 -4.49545622e+00 -4.50082636e+00 -4.81617355e+00 -4.37210894e+00 -4.13253260e+00 -3.53720641e+00 -3.88877892e+00 -3.29724813e+00 -3.67645478e+00 -3.58079576e+00 -3.83870387e+00 -4.39145756e+00 -3.89349055e+00 -3.96599603e+00 -3.89958644e+00 -4.98179960e+00 -5.30720663e+00 -4.14663744e+00 -3.38023376e+00 -3.28308964e+00 -3.66998649e+00 -3.49397087e+00 -3.62575912e+00 -3.78393579e+00 -3.83922195e+00 -3.52902150e+00 -3.65013194e+00 -3.52476788e+00 -4.00480366e+00 -3.71720576e+00 -3.05639720e+00 -2.58130622e+00 -1.82161498e+00 -2.81849742e+00 -2.60261321e+00 -3.41374612e+00 -3.35618687e+00 -2.95611954e+00 -2.94892597e+00 -3.03588891e+00 -3.69560122e+00 -3.38195300e+00 -3.10288763e+00 -2.97212267e+00 -2.86960173e+00 -2.43415189e+00 -2.04231882e+00 -1.74340010e+00 -2.17251992e+00 -2.01584578e+00 -2.02641606e+00 -2.39136195e+00 -2.94229031e+00 -3.40409207e+00 -3.13254786e+00 -2.85604835e+00 -2.08754253e+00 -1.05143023e+00 -6.88210011e-01 -1.02281678e+00 -2.30349803e+00 -2.89542580e+00 -2.70907950e+00 -2.98772979e+00 -3.50425935e+00 -4.07174492e+00 -3.17710614e+00 -1.95370781e+00 -2.10132527e+00 -2.38898349e+00 -2.99114442e+00 -3.09399796e+00 -2.92406726e+00 -2.98119235e+00 -2.47513747e+00 -2.99061251e+00 -3.11791706e+00 -3.47064662e+00 -2.34824705e+00 -1.18921649e+00 -1.44204295e+00 -2.01709843e+00 -2.14643884e+00 -2.10231614e+00 -2.40294719e+00 -3.12823057e+00 -2.94975996e+00 -2.16002250e+00 -1.96471500e+00 -2.22252226e+00 -2.91426587e+00 -3.21358728e+00 -2.75409389e+00 -2.90170431e+00 -2.82414579e+00 -2.82112980e+00 -2.26654387e+00 -1.73336923e+00 -1.15375865e+00 -1.62822175e+00 -2.12004900e+00 -2.37821674e+00 -2.53113317e+00 -3.05249786e+00 -3.50561547e+00 -3.32354188e+00 -2.97147369e+00 -2.48814988e+00 -2.62076712e+00 -2.96135616e+00 -3.92498493e+00 -4.13442469e+00 -3.24453235e+00 -2.25199509e+00 -2.45334578e+00 -2.80659175e+00 -3.09521890e+00 -2.52138686e+00 -2.20603514e+00 -1.83579814e+00 -9.23191845e-01 -1.10709488e+00 -1.61727941e+00 -2.44841385e+00 -2.23399711e+00 -1.30259538e+00 -1.35350490e+00 -1.57254314e+00 -2.39145112e+00 -1.85584998e+00 -1.33469093e+00 -8.57505083e-01 -5.63419342e-01 -4.27379787e-01 -2.68107593e-01 -4.14644986e-01 -1.05092859e+00 -9.17074323e-01 -1.03009939e+00 -7.35328972e-01 -1.38561261e+00 -2.13417125e+00 -2.30976868e+00 -2.81248903e+00 -1.47735178e+00 -1.39034986e+00 -3.52389514e-01 -2.63531446e-01 6.54882789e-02 -2.12708205e-01 -5.77970982e-01 -7.92166412e-01 -5.45694709e-01 -1.25245059e+00 -1.17516184e+00 -1.90805876e+00 -2.22718120e+00 -1.26351690e+00 -5.20979404e-01 -1.06612213e-01 -7.06970394e-01 -1.09430325e+00 -9.24651623e-01 -1.02983963e+00 -8.51647198e-01 -7.44894147e-01 -1.28668511e+00 -1.67359424e+00 -2.31940484e+00 -1.37041247e+00 -1.17267704e+00 -3.27822179e-01 -4.63154465e-01 -9.84251201e-01 -1.88279963e+00 -6.93310440e-01 1.04223788e+00 1.02517474e+00 -3.80508810e-01 -1.61246669e+00 -1.60450935e+00 -9.40015316e-01 2.02162638e-02 3.93003762e-01 -5.90315819e-01 -1.41212952e+00 -8.54957521e-01 -2.03147098e-01 -2.63189655e-02 -2.40733370e-01 -6.16491497e-01 1.66611537e-01 6.08151734e-01 4.65157151e-01 -7.50897080e-02 1.96639448e-01 5.64828873e-01 4.33376171e-02 -4.41309094e-01 -2.24699587e-01 -1.94091816e-02 -3.77479047e-01 2.77929991e-01 5.52479863e-01 2.13656023e-01 -5.91862321e-01 -9.89174128e-01 -1.55854475e+00 -1.19290972e+00 -4.52461421e-01 1.60556480e-01 2.35018879e-01 -4.82422024e-01 3.23665529e-01 8.27646315e-01 2.19202065e+00 1.80405188e+00 7.45775580e-01 3.18709731e-01 2.74845809e-01 8.05082560e-01 6.32579446e-01 1.81890833e+00 2.25131392e+00 2.83607316e+00 2.30380201e+00 2.00547433e+00 9.07589674e-01 6.07786000e-01 4.90552962e-01 -4.25809592e-01 4.37712371e-02 -2.66201615e-01 1.11982942e+00 1.20568621e+00 1.31488800e+00 8.94649565e-01 1.01404715e+00 1.44789791e+00 1.63200963e+00 1.68831408e+00 1.58466136e+00 1.44143665e+00 8.09300840e-01 4.65970278e-01 5.25154293e-01 4.46934283e-01 4.30088162e-01 1.40252277e-01 6.53484821e-01 4.92456138e-01 1.22605026e+00 9.02875960e-02 3.75718206e-01 1.06615447e-01 1.22954178e+00 7.73510098e-01 3.05821508e-01 2.74573676e-02 9.28311169e-01 1.44145083e+00 1.12847698e+00 9.06940460e-01 8.90417218e-01 1.08479536e+00 8.27078223e-01 9.58545506e-01 1.24458051e+00 2.72993118e-01 6.56673968e-01 1.50581315e-01 1.49419212e+00 1.12863457e+00 5.40336132e-01 3.13952602e-02 -1.55875146e-01 5.06744504e-01 9.74260926e-01 1.49154270e+00 1.65117145e+00 1.79883313e+00 2.22148252e+00 2.46669102e+00 3.15113616e+00 1.85235679e+00 2.11497831e+00 1.83076346e+00 1.24675655e+00 1.69485724e+00 1.02463579e+00 1.92782664e+00 1.58439744e+00 1.71970475e+00 1.06779933e+00 8.78687918e-01 5.40414155e-01 1.68790472e+00 1.62178349e+00 2.37302732e+00 2.33942938e+00 2.88477159e+00 3.00388408e+00 3.17416692e+00 2.23641133e+00 1.88895524e+00 2.02264977e+00 2.08510590e+00 6.06583118e-01 -1.33154299e-02 5.04853368e-01 1.61038029e+00 1.75638306e+00 1.48983145e+00 1.92868137e+00 2.43692946e+00 2.70241642e+00 2.69237638e+00 2.00276875e+00 2.17187905e+00 2.35038757e+00 2.38418770e+00 2.07508063e+00 2.48313093e+00 2.95227885e+00 3.62012291e+00 2.88644290e+00 2.57203817e+00 2.12282395e+00 2.68575001e+00 2.88874316e+00 2.89417553e+00 2.72404981e+00 2.44803166e+00 2.60699153e+00 2.95635223e+00 3.51014757e+00 3.79026198e+00 3.67928863e+00 3.51554894e+00 2.71002936e+00 2.17034292e+00 1.83371651e+00 2.44497681e+00 1.65699887e+00 2.23375535e+00 2.22968006e+00 2.83647704e+00 3.04990458e+00 3.30915594e+00 3.08096790e+00 2.65878582e+00 1.56106794e+00 2.09194922e+00 1.78858030e+00 2.12567234e+00 2.77294874e+00 2.82846498e+00 3.79020023e+00 3.50262904e+00 3.98566675e+00 2.83731151e+00 2.54957485e+00 1.58070076e+00 2.37860608e+00 2.69129968e+00 3.42437315e+00 3.32200861e+00 3.24590111e+00 2.58382893e+00 2.79780984e+00 2.65822434e+00 3.37328911e+00 2.97451878e+00 2.71227956e+00 2.56865287e+00 2.47005057e+00 2.94449997e+00 3.17489290e+00 3.60777283e+00 3.17405677e+00 2.98082352e+00 3.51034713e+00 3.39785194e+00 2.80651832e+00 2.03600860e+00 2.86906433e+00 3.11821771e+00 3.38205671e+00 3.06086993e+00 3.53237200e+00 4.23741722e+00 4.65273237e+00 4.86286449e+00 3.52607226e+00 3.15920568e+00 3.24717784e+00 3.91306233e+00 3.73629975e+00 3.44200230e+00 3.37744522e+00 3.99438477e+00 3.79301858e+00 4.32520342e+00 4.04593182e+00 4.65196705e+00 4.44496584e+00 4.43747902e+00 4.35370922e+00 4.12177086e+00 4.05608988e+00 3.71758747e+00 3.40432644e+00 3.34873438e+00 3.33660436e+00 3.54706645e+00 3.43838716e+00 3.37619138e+00 3.52644515e+00 3.76470423e+00 3.94862342e+00 4.00331783e+00 4.15470552e+00 4.55400944e+00 4.63001204e+00 4.63453102e+00 4.26076746e+00 4.14277506e+00 4.05053949e+00 4.40212440e+00 4.45404625e+00 4.16535091e+00 3.97121072e+00 4.18349695e+00 3.69293904e+00 2.80156994e+00 2.26068568e+00 3.00700235e+00 3.98241568e+00 5.13165903e+00 5.18133974e+00 5.32653332e+00 5.07234287e+00 6.75841999e+00 7.66030073e+00 1.88280945e+01 2.61398487e+01 2.04808006e+01 1.36465500e+02 6.37814331e+01 -3.80820068e+03 68307016. 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. 0. 0. 0. 0. 0. 0. 4.00486531e+05 1.67677216e+02 2.60538273e+01 -2.26473694e+01 1.41447401e+00 3.37273002e+00 4.53683805e+00 5.33837509e+00 4.69911814e+00 4.63656950e+00 4.59787703e+00 4.86639595e+00 5.12659597e+00 5.15398073e+00 5.28275537e+00 5.29728556e+00 4.99504614e+00 4.85407162e+00 4.83118248e+00 5.23883867e+00 5.47004986e+00 5.75132847e+00 5.56261730e+00 5.11932182e+00 5.03787374e+00 5.20236635e+00 5.66885996e+00 5.71564245e+00 5.61479521e+00 5.44975853e+00 5.21250153e+00 5.13753319e+00 5.12394190e+00 5.39460230e+00 5.46634436e+00 5.42271376e+00 5.50842571e+00 5.54362535e+00 5.57284689e+00 5.55899286e+00 5.54619217e+00 5.58353996e+00 5.39965057e+00 5.38646221e+00 5.49443436e+00 5.62367916e+00 5.68957329e+00 5.72954369e+00 5.73133469e+00 6.01232100e+00 5.95725965e+00 6.04999876e+00 5.57797098e+00 5.66063261e+00 5.62807655e+00 5.81056595e+00 5.87865114e+00 5.81480169e+00 5.78750992e+00 5.75916290e+00 5.82464600e+00 5.96988487e+00 5.80181217e+00 5.54420233e+00 5.44495296e+00 5.39549685e+00 5.44407129e+00 5.39719534e+00 5.46243238e+00 5.65510750e+00 5.68292284e+00 5.73614025e+00 5.75455809e+00 5.74006081e+00 5.83453417e+00 6.04589748e+00 6.07522631e+00 6.02405739e+00 5.83430576e+00 5.81760645e+00 5.92607403e+00 5.95010614e+00 6.11567545e+00 6.08300638e+00 5.99026346e+00 5.85279179e+00 5.71269226e+00 5.71650267e+00 5.78435993e+00 5.94144964e+00 5.89786530e+00 5.92908335e+00 5.72242308e+00 5.66666698e+00 5.71601391e+00 5.85634756e+00 6.00107241e+00 5.89944220e+00 5.91141129e+00 5.81983185e+00 5.78482914e+00 5.80993176e+00 6.02519417e+00 6.11990404e+00 6.18277025e+00 6.08828735e+00 6.01892614e+00 5.96114492e+00 5.89862394e+00 5.91395473e+00 5.88629818e+00 5.94584322e+00 6.01197481e+00 6.06379414e+00 6.08133507e+00 6.07341814e+00 6.15662622e+00 6.22065544e+00 6.25265646e+00 6.10610962e+00 6.01746988e+00 6.02266264e+00 6.08271790e+00 6.20856380e+00 6.18942499e+00 6.15998316e+00 6.10982513e+00 6.04944706e+00 6.04552937e+00 6.00542307e+00 6.08205128e+00 6.14947128e+00 6.20258427e+00 6.10731936e+00 5.98281050e+00 5.95376015e+00 5.97591448e+00 6.07345724e+00 6.07979155e+00 6.16216660e+00 6.21412611e+00 6.21485138e+00 6.21840382e+00 6.23916531e+00 6.25293684e+00 6.26538944e+00 6.23202801e+00 6.21704817e+00 6.20184231e+00 6.18986368e+00 6.23427868e+00 6.23756075e+00 6.23410892e+00 6.16058588e+00 6.13207340e+00 6.17615271e+00 6.19776630e+00 6.23488522e+00 6.18302250e+00 6.16770744e+00 6.12946558e+00 6.11958075e+00 6.13619280e+00 6.15396595e+00 6.19143724e+00 6.21298504e+00 6.22644949e+00 6.22394371e+00 6.21355772e+00 6.20698214e+00 6.20356798e+00 6.20800591e+00 6.21384430e+00 6.21156883e+00 6.20983601e+00 6.21083641e+00 6.21314764e+00 6.21038771e+00 6.20647144e+00 6.21077204e+00 6.21522951e+00 6.21925640e+00 6.21014929e+00 6.22126245e+00 6.22092915e+00 6.23674774e+00 6.23765993e+00 6.22651052e+00 6.21294451e+00 6.19719982e+00 6.22118282e+00 6.21385574e+00 6.22504044e+00 6.20050049e+00 6.18544340e+00 6.17194557e+00 6.15842056e+00 6.18144655e+00 6.15482521e+00 6.14248896e+00 6.14191723e+00 6.14611340e+00 6.12685728e+00 6.09802341e+00 6.08946514e+00 6.13689041e+00 6.14873600e+00 6.20594406e+00 6.19842148e+00 6.19649649e+00 6.20441818e+00 6.19150305e+00 6.18593836e+00 6.14409447e+00 6.18935251e+00 6.22428942e+00 6.22256231e+00 6.18731689e+00 6.16205549e+00 6.11559296e+00 6.09498739e+00 6.02772188e+00 6.02736616e+00 6.09394741e+00 6.14350462e+00 6.20264053e+00 6.15099812e+00 6.07818508e+00 6.04069090e+00 6.04173040e+00 6.03982210e+00 5.98897123e+00 5.99270391e+00 5.99906158e+00 6.02355385e+00 6.03011370e+00 6.01996565e+00 6.00104618e+00 5.98184204e+00 6.03897619e+00 6.06513739e+00 6.07562494e+00 6.08150816e+00 6.11546373e+00 5.96116829e+00 5.77308369e+00 5.70194387e+00 5.78898716e+00 6.04658985e+00 6.06646585e+00 6.04386950e+00 5.87285376e+00 5.80767536e+00 6.00133276e+00 6.21395063e+00 6.28581667e+00 6.21337080e+00 6.01677418e+00 6.08455420e+00 6.00985909e+00 6.01385355e+00 5.94646311e+00 5.92984819e+00 6.00021505e+00 5.97912884e+00 6.07894707e+00 6.09124470e+00 6.12355661e+00 6.18442535e+00 6.18232393e+00 6.15752792e+00 6.21464777e+00 6.08774900e+00 6.06728983e+00 5.81751156e+00 5.91977644e+00 5.94640493e+00 5.86327600e+00 6.20697832e+00 6.25612974e+00 6.44424057e+00 6.04320049e+00 5.86488008e+00 5.63930178e+00 5.91856337e+00 5.97583103e+00 6.00664949e+00 5.63536930e+00 5.46536875e+00 5.56417322e+00 5.52988243e+00 5.64466286e+00 5.38362169e+00 5.33497000e+00 5.30368614e+00 5.68216515e+00 5.85926628e+00 5.96748400e+00 5.88725233e+00 5.82007790e+00 5.57535267e+00 5.51057243e+00 5.54993010e+00 5.63512325e+00 5.40143061e+00 5.49143982e+00 5.89520264e+00 5.98834181e+00 5.98462772e+00 5.59831524e+00 5.73189545e+00 5.60331678e+00 5.62592459e+00 5.45437908e+00 5.49384356e+00 5.33482265e+00 5.38048983e+00 5.47639322e+00 5.76707172e+00 5.75295782e+00 5.71378946e+00 5.44205332e+00 5.39321661e+00 5.38905144e+00 5.47506571e+00 5.53540039e+00 5.60263491e+00 5.69953299e+00 5.98896837e+00 6.04405975e+00 5.92240191e+00 5.72148848e+00 5.20921850e+00 5.28525686e+00 5.11472416e+00 5.42068481e+00 5.05134869e+00 5.22165108e+00 5.39313841e+00 5.55552912e+00 5.16946602e+00 4.52515411e+00 4.48551178e+00 4.61019278e+00 5.08247137e+00 5.05748606e+00 4.86568260e+00 4.95737696e+00 5.23035669e+00 5.48181534e+00 4.91769743e+00 4.56598616e+00 4.33894444e+00 4.38116217e+00 4.55425024e+00 4.44222641e+00 4.97973680e+00 4.85572863e+00 5.03454590e+00 4.68285227e+00 4.76577806e+00 4.85366726e+00 4.80627012e+00 4.78015280e+00 4.74045849e+00 4.70387506e+00 5.04689407e+00 5.21765518e+00 5.36402512e+00 4.96279335e+00 4.63703299e+00 4.97558689e+00 5.37459326e+00 5.48993826e+00 4.99043465e+00 5.00373459e+00 5.13746738e+00 5.14032173e+00 5.13083839e+00 4.77458477e+00 5.14011335e+00 4.67151260e+00 4.98619318e+00 4.88093424e+00 4.69771051e+00 4.55246782e+00 4.66912603e+00 4.97303867e+00 5.08108282e+00 4.70397711e+00 4.85740089e+00 4.78414583e+00 4.96216917e+00 4.85263586e+00 4.70489502e+00 4.85881805e+00 4.74535751e+00 5.05038929e+00 4.47041225e+00 4.21064854e+00 4.33780146e+00 4.88572121e+00 5.02576923e+00 4.64531279e+00 4.53563738e+00 4.63572359e+00 4.78486061e+00 4.58592463e+00 4.00056791e+00 3.81411624e+00 3.47832513e+00 3.80843496e+00 3.78141236e+00 4.29908466e+00 4.29795218e+00 3.95741391e+00 3.97931767e+00 4.49624825e+00 4.58083248e+00 4.51731205e+00 4.32952929e+00 4.23789358e+00 4.18009901e+00 3.76601553e+00 3.84638047e+00 3.62884402e+00 4.04837036e+00 4.00443125e+00 3.74034452e+00 3.70487309e+00 3.83911371e+00 4.13750982e+00 3.65108562e+00 3.82045078e+00 3.62117815e+00 3.62288451e+00 2.99176455e+00 3.28810334e+00 3.61625361e+00 3.80223846e+00 3.64308405e+00 3.41560483e+00 4.11612368e+00 3.98087907e+00 3.90556359e+00 3.41187596e+00 3.50275445e+00 3.11412168e+00 2.87693930e+00 2.63699150e+00 3.15233421e+00 3.57021904e+00 3.37914991e+00 3.22596931e+00 2.96270299e+00 3.37858105e+00 3.62532759e+00 3.63261247e+00 3.98009038e+00 3.96781969e+00 4.00250006e+00 3.31410885e+00 3.00051618e+00 3.26895714e+00 3.26512241e+00 2.97782707e+00 2.89859653e+00 3.27617931e+00 3.51799035e+00 3.01560163e+00 3.10591865e+00 3.09271049e+00 3.37407756e+00 3.36743116e+00 3.21266079e+00 3.69041800e+00 3.62146330e+00 3.83402061e+00 3.40905952e+00 3.53370976e+00 2.92338347e+00 2.36490154e+00 2.12899470e+00 3.07284570e+00 3.01877308e+00 2.51630974e+00 2.01850557e+00 2.43592429e+00 3.10427189e+00 2.29699683e+00 2.36359525e+00 1.91774189e+00 2.44933844e+00 1.60047531e+00 1.19434011e+00 8.70307684e-01 1.76504695e+00 2.49798965e+00 2.24224353e+00 1.29828000e+00 2.30024576e-01 3.87057781e-01 6.34987533e-01 5.54842412e-01 8.26736867e-01 8.25995624e-01 1.84763765e+00 2.50087786e+00 3.02669740e+00 3.31775570e+00 3.54478693e+00 3.19625974e+00 2.29401040e+00 1.66178465e+00 1.77957904e+00 2.49380851e+00 2.21963525e+00 1.90780795e+00 1.37978578e+00 1.09244382e+00 9.97500777e-01 8.98334801e-01 1.46119916e+00 2.19086480e+00 2.30267596e+00 2.02980876e+00 1.75142944e+00 1.52381694e+00 1.89399421e+00 1.90686083e+00 1.82535231e+00 1.33511531e+00 1.17940319e+00 1.30554271e+00 1.47693908e+00 1.73758256e+00 1.66197419e+00 1.60970879e+00 7.72987604e-01 4.61255312e-01 2.31675148e-01 1.70496142e+00 2.60317850e+00 3.17467260e+00 2.07285023e+00 1.93079400e+00 1.77825129e+00 2.88425207e+00 2.93898034e+00 2.58736467e+00 2.05299878e+00 1.70279670e+00 1.92988658e+00 1.91793668e+00 1.36982894e+00 1.29118061e+00 1.20257533e+00 1.68189573e+00 2.18015957e+00 1.41850078e+00 1.31935871e+00 1.27508736e+00 1.72420454e+00 1.83614635e+00 1.54065311e+00 1.28842139e+00 1.12177956e+00 1.44106138e+00 1.64034009e+00 1.87740231e+00 1.58234406e+00 1.43476987e+00 1.20031822e+00 6.44170940e-01 1.00109303e+00 1.37044001e+00 2.14706874e+00 2.55252576e+00 2.40825915e+00 2.04235625e+00 1.18618071e+00 8.75845194e-01 5.46337545e-01 9.24955606e-01 1.01077306e+00 1.29934716e+00 7.14992106e-01 3.72743577e-01 6.42953753e-01 1.19443285e+00 7.84719765e-01 6.82023406e-01 4.42810327e-01 6.52827740e-01 -3.31278145e-01 9.12576467e-02 1.17233440e-01 8.25424612e-01 -5.18623888e-01 -8.82829607e-01 -1.95303559e+00 -1.38222122e+00 -6.82692170e-01 9.19699550e-01 1.02631497e+00 7.97712147e-01 1.19783700e+00 1.49816217e+01 1.05747366e+01 7.11579971e+01 3.26375656e+01 -1267417728. 0. 0. 0. 0. 693049472. -1.19657625e+06 2.43456525e+06 4.04202750e+05 4.00055273e+03 1.19903330e+04 1.99676035e+04 -3.32142592e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.67776768e+09 3.24284825e+06 2.30516025e+06 1.90124365e+03 7.60904663e+02 7.60815201e+01 5.12376175e+01 9.78202629e+00 -1.04957366e+00 -9.81751442e+00 -1.22167959e+01 1.97805119e+00 1.68637848e+01 1.68880482e+01 1.13038235e+01 7.12443113e+00 1.03061008e+00 -1.81577885e+00 -5.42223072e+00 6.68655336e-01 9.63175774e+00 1.81033363e+01 1.73051853e+01 2.56562161e+00 -1.12466240e+01 -1.99537754e+01 -2.12220554e+01 -1.37961473e+01 -1.38073940e+01 -1.27276812e+01 -1.31447375e+00 6.20813131e+00 2.33334947e+00 -1.47102709e+01 -2.76111984e+01 -2.74265976e+01 -1.77184753e+01 -8.81456554e-01 4.87207794e+00 3.59892702e+00 2.94081163e+00 2.33372641e+00 7.10061133e-01 -9.91860008e+00 -1.91260490e+01 -1.57133427e+01 -5.60956573e+00 -1.38617918e-01 -6.85377359e+00 -7.68468618e+00 -5.37422895e+00 -9.96842289e+00 -1.04933529e+01 -9.30927181e+00 -3.83529329e+00 2.82506371e+00 7.05643606e+00 9.52806950e+00 -4.41372252e+00 -2.21259975e+01 -2.76627312e+01 -1.78734722e+01 -4.43523377e-01 1.97417343e+00 -3.71118331e+00 -9.01296139e+00 -7.45115995e+00 -4.47733021e+00 -7.18636894e+00 -1.11025782e+01 -1.23009319e+01 -4.58516932e+00 5.91258955e+00 2.78737020e+00 -4.34475511e-01 -5.34758997e+00 -7.74181604e+00 -8.12598896e+00 -1.10953693e+01 -5.93630409e+00 2.60848188e+00 1.12685633e+01 1.17042933e+01 1.74952459e+00 -8.85450554e+00 -1.79255066e+01 -1.85947685e+01 -8.74720955e+00 -4.17934608e+00 -3.42982197e+00 1.51940584e+00 1.04648542e+01 1.02117262e+01 -4.88270140e+00 -2.01350117e+01 -2.00965900e+01 -5.83814240e+00 7.80831671e+00 8.53165054e+00 5.47105503e+00 7.13515186e+00 7.70500660e+00 3.53137445e+00 -3.68745613e+00 -8.20881748e+00 -2.89243174e+00 3.34681630e+00 4.98447371e+00 -3.27272320e+00 -1.27364197e+01 -1.71698933e+01 -1.70165768e+01 -6.68266344e+00 1.47397768e+00 3.17419112e-01 -1.65665102e+00 1.17786169e+00 3.88063097e+00 -1.28944290e+00 -1.16291466e+01 -1.15856476e+01 -3.78115356e-01 1.10810976e+01 1.32651892e+01 3.30475235e+00 -5.12232733e+00 -1.40954895e+01 -1.75547695e+01 -1.21423035e+01 -6.97721720e+00 -3.76103973e+00 2.99671865e+00 1.04370279e+01 1.07237644e+01 3.74575758e+00 -3.91770124e+00 -8.43980408e+00 -9.62879562e+00 -6.83762598e+00 -3.64484286e+00 -1.12471318e+00 2.16953182e+00 5.87389374e+00 6.24261284e+00 -3.04234886e+00 -1.42994518e+01 -2.18994083e+01 -1.91228657e+01 -1.47694464e+01 -1.12890024e+01 -6.03438997e+00 -3.00467610e+00 -5.51595402e+00 -7.33294535e+00 -1.34022894e+01 -1.59204655e+01 -1.42727871e+01 -7.11870241e+00 -4.38488865e+00 -9.47346878e+00 -1.62435722e+01 -1.31905355e+01 -5.15714741e+00 2.99862266e-01 -6.07394934e+00 -1.41372385e+01 -1.29374790e+01 -1.19082756e+01 -1.21404963e+01 -2.19781532e+01 -2.79941368e+01 -2.90441360e+01 -1.61186295e+01 -1.84703231e+00 2.29302096e+00 1.44646156e+00 6.78512692e-01 -1.90931892e+00 -7.16360569e+00 -1.74153671e+01 -1.96210823e+01 -1.14388561e+01 -9.17147398e-01 1.35973644e+00 -8.56633282e+00 -1.47002316e+01 -1.67970390e+01 -1.65460052e+01 -1.56177139e+01 -1.85000305e+01 -1.76782589e+01 -1.51030893e+01 -1.34461250e+01 -1.59227152e+01 -2.18936348e+01 -2.51681919e+01 -2.36779404e+01 -1.03557673e+01 6.48739517e-01 2.95677137e+00 -3.33483791e+00 -4.51263523e+00 -5.72988510e+00 -8.11846733e+00 -1.68567924e+01 -1.76651726e+01 -9.47382736e+00 -1.37506497e+00 4.11452085e-01 -7.43657780e+00 -9.66081524e+00 -9.79251862e+00 -8.71465302e+00 -9.69229698e+00 -1.25140371e+01 -1.78002911e+01 -1.39797382e+01 -6.43268871e+00 -3.11471725e+00 -7.33003283e+00 -1.86656761e+01 -2.03858414e+01 -1.41821451e+01 -6.76764345e+00 -4.19523811e+00 -7.63163471e+00 -7.98154116e+00 -8.00194073e+00 -7.66283989e+00 -6.32012177e+00 -5.41270733e+00 -4.82915497e+00 -4.94917965e+00 -3.80047393e+00 -4.30105448e+00 -4.95188904e+00 -6.76697350e+00 -1.24323473e+01 -1.64308910e+01 -1.93476143e+01 -1.56308928e+01 -1.04718628e+01 -6.64428568e+00 -3.91573691e+00 -1.10325279e+01 -1.78610630e+01 -1.87170830e+01 -1.11411848e+01 -6.00808048e+00 -8.72671318e+00 -1.25254517e+01 -9.27394581e+00 -5.46779633e+00 -7.24134207e+00 -1.28708849e+01 -1.64356956e+01 -1.43847122e+01 -1.54859467e+01 -1.32375116e+01 -1.20310240e+01 -7.93378687e+00 -1.04698839e+01 -1.26982298e+01 -1.44611435e+01 -1.82345123e+01 -1.80952015e+01 -1.69213772e+01 -1.12161388e+01 -7.76793957e+00 -1.16219683e+01 -1.95562649e+01 -2.21156960e+01 -1.76696262e+01 -1.64898396e+01 -1.81935177e+01 -2.19477005e+01 -1.67952099e+01 -1.39632578e+01 -1.26919870e+01 -1.32066965e+01 -1.24646597e+01 -1.20854530e+01 -1.42031870e+01 -1.41315098e+01 -1.01958752e+01 -8.20868778e+00 -9.69072723e+00 -8.91655731e+00 -5.15857553e+00 -4.71829748e+00 -1.01189928e+01 -1.52517548e+01 -1.45811577e+01 -1.29847574e+01 -1.37033100e+01 -1.74206333e+01 -1.54375381e+01 -1.25209913e+01 -1.29190569e+01 -1.56286592e+01 -1.83566151e+01 -1.63862247e+01 -1.69337063e+01 -1.55833035e+01 -1.54367285e+01 -1.21479540e+01 -8.83631229e+00 -1.01248846e+01 -1.23147669e+01 -1.40506001e+01 -1.16510792e+01 -1.10929737e+01 -9.51806831e+00 -7.80011463e+00 -8.64763165e+00 -1.08520823e+01 -1.27136831e+01 -1.03133221e+01 -7.74027109e+00 -1.05964260e+01 -1.64525337e+01 -1.71445312e+01 -1.41677065e+01 -1.13759851e+01 -1.51722155e+01 -1.83156948e+01 -1.65106812e+01 -1.32826452e+01 -1.07093506e+01 -1.01374893e+01 -8.74236012e+00 -8.07008839e+00 -1.00102196e+01 -1.10833912e+01 -1.10420685e+01 -1.01299534e+01 -1.10816116e+01 -1.10401363e+01 -9.07916737e+00 -1.04108639e+01 -1.40957756e+01 -1.64898624e+01 -1.54378767e+01 -1.39570360e+01 -1.59444008e+01 -1.77653904e+01 -1.60833168e+01 -1.47193985e+01 -1.35571547e+01 -1.55351048e+01 -1.44884300e+01 -1.40428820e+01 -1.41203165e+01 -1.47733545e+01 -1.39083118e+01 -1.08014421e+01 -9.46477985e+00 -1.09052620e+01 -1.35696907e+01 -1.56212912e+01 -1.48931103e+01 -1.39726963e+01 -1.23199558e+01 -9.45825672e+00 -1.01421623e+01 -1.43668509e+01 -1.92240543e+01 -2.06341667e+01 -1.82658882e+01 -1.67233047e+01 -1.68656864e+01 -1.68105736e+01 -1.79317417e+01 -1.65535507e+01 -1.63486557e+01 -1.55384178e+01 -1.56066732e+01 -1.83745575e+01 -1.92955341e+01 -1.91709614e+01 -1.54964218e+01 -1.30507812e+01 -1.44864216e+01 -1.66802750e+01 -1.73873672e+01 -1.47754993e+01 -1.27900391e+01 -1.29275265e+01 -1.36113253e+01 -1.46815929e+01 -1.60158539e+01 -1.65797501e+01 -1.75640469e+01 -1.64937286e+01 -1.52840242e+01 -1.42063093e+01 -1.41154509e+01 -1.61377716e+01 -1.74862251e+01 -1.83664455e+01 -1.71612320e+01 -1.50852346e+01 -1.48392992e+01 -1.49316368e+01 -1.47549038e+01 -1.36108294e+01 -1.36918211e+01 -1.61345997e+01 -1.72890854e+01 -1.73672333e+01 -1.60454769e+01 -1.53572941e+01 -1.52052975e+01 -1.47522116e+01 -1.50189400e+01 -1.55655804e+01 -1.60082779e+01 -1.65090675e+01 -1.62676010e+01 -1.62120876e+01 -1.60492573e+01 -1.58909931e+01 -1.58584576e+01 -1.50161924e+01 -1.47921019e+01 -1.49087915e+01 -1.52591639e+01 -1.58435335e+01 -1.59299049e+01 -1.58942900e+01 -1.52618704e+01 -1.48352709e+01 -1.48661833e+01 -1.52304773e+01 -1.54870529e+01 -1.53057308e+01 -1.50682945e+01 -1.50420189e+01 -1.51049833e+01 -1.51659861e+01 -1.51876764e+01 -1.51788492e+01 -1.51432838e+01 -1.51569433e+01 -1.52102814e+01 -1.52952204e+01 -1.52300005e+01 -1.48928776e+01 -1.46854525e+01 -1.46890507e+01 -1.50440550e+01 -1.54338789e+01 -1.52454767e+01 -1.47943268e+01 -1.44897871e+01 -1.49190331e+01 -1.54312830e+01 -1.53327026e+01 -1.51032753e+01 -1.48698988e+01 -1.50009880e+01 -1.50996780e+01 -1.47096472e+01 -1.45927172e+01 -1.46389341e+01 -1.46602478e+01 -1.48845119e+01 -1.43389921e+01 -1.45799999e+01 -1.44542780e+01 -1.47952852e+01 -1.50382051e+01 -1.42098904e+01 -1.48877983e+01 -1.53925619e+01 -1.68119488e+01 -1.63557987e+01 -1.45418720e+01 -1.32215509e+01 -1.28745899e+01 -1.48302383e+01 -1.62086506e+01 -1.65172195e+01 -1.57953234e+01 -1.45969181e+01 -1.44910097e+01 -1.53931713e+01 -1.60266590e+01 -1.68131123e+01 -1.59519997e+01 -1.45039768e+01 -1.26727228e+01 -1.25030813e+01 -1.47664032e+01 -1.66758842e+01 -1.77605896e+01 -1.71489277e+01 -1.46485071e+01 -1.23700113e+01 -1.18741913e+01 -1.44537792e+01 -1.68139610e+01 -1.58411360e+01 -1.34987688e+01 -1.19495039e+01 -1.37539473e+01 -1.64803009e+01 -1.66537971e+01 -1.60608826e+01 -1.36051083e+01 -1.22719278e+01 -1.20279760e+01 -1.21807785e+01 -1.38985233e+01 -1.54004021e+01 -1.57083635e+01 -1.50287800e+01 -1.23592730e+01 -1.24979486e+01 -1.37641001e+01 -1.51709194e+01 -1.69345913e+01 -1.50299559e+01 -1.43070269e+01 -1.41433344e+01 -1.65826073e+01 -1.74338226e+01 -1.33405619e+01 -1.05605545e+01 -1.08037663e+01 -1.47389355e+01 -1.78266544e+01 -1.79319000e+01 -1.70776863e+01 -1.38014994e+01 -1.10890732e+01 -1.04932213e+01 -1.13476353e+01 -1.40127020e+01 -1.51113720e+01 -1.36877165e+01 -1.38703976e+01 -1.31898251e+01 -1.71487713e+01 -1.76694298e+01 -1.79045067e+01 -1.66091576e+01 -1.27037563e+01 -1.21423950e+01 -1.41794415e+01 -1.96815796e+01 -2.20833187e+01 -2.02211170e+01 -1.66056557e+01 -1.29325352e+01 -1.49052982e+01 -1.88936749e+01 -2.08408585e+01 -1.99054165e+01 -1.63834057e+01 -1.43292217e+01 -1.30979424e+01 -1.24448204e+01 -1.27000189e+01 -1.27892752e+01 -1.32399101e+01 -1.13413944e+01 -8.29802322e+00 -9.87497139e+00 -1.50390320e+01 -1.77348080e+01 -1.60472775e+01 -9.99691296e+00 -7.32167006e+00 -8.12865067e+00 -1.44867525e+01 -1.80453415e+01 -1.50530891e+01 -1.15733271e+01 -1.06938648e+01 -1.34707289e+01 -1.35135803e+01 -1.13211069e+01 -9.30492115e+00 -7.78732681e+00 -6.72980309e+00 -8.19350719e+00 -7.17520189e+00 -9.79756451e+00 -1.04225368e+01 -1.07835693e+01 -1.15679770e+01 -9.07211590e+00 -1.08800621e+01 -1.13081589e+01 -1.40191278e+01 -1.58688841e+01 -1.10188770e+01 -1.04975567e+01 -9.43799114e+00 -1.34349165e+01 -1.49284410e+01 -1.12984877e+01 -9.62414169e+00 -4.03372478e+00 -6.78593302e+00 -1.12696686e+01 -1.68235226e+01 -1.79990768e+01 -1.11606827e+01 -9.60550404e+00 -1.13324900e+01 -1.16567392e+01 -1.03641205e+01 -9.21753025e+00 -1.56078682e+01 -1.71093903e+01 -9.58164024e+00 -6.37731600e+00 -6.27559423e+00 -1.02726212e+01 -9.48406887e+00 -1.36079812e+00 -1.57865572e+01 -4.30552979e+01 -3.40200897e+02 -1.34761426e+03 -66952420. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -92942288. 74114848. -8866299. -19721688. -1.64556213e+03 -5.96046204e+02 -6.73279648e+01 -3.30105629e+01 -1.07333975e+01 -3.09873033e+00 -9.28190422e+00 -1.11173668e+01 -9.98922253e+00 -9.81311798e+00 -7.37854147e+00 -4.34484625e+00 -5.08266926e+00 -7.42101908e+00 -1.12273970e+01 -8.65042305e+00 -4.00959158e+00 -2.62965250e+00 -4.65624362e-01 -2.14893126e+00 -3.45000744e+00 -9.01066589e+00 -1.23569622e+01 -4.11592817e+00 -1.79152727e+00 -5.98826981e+00 -1.63955574e+01 -1.26637535e+01 -2.27386308e+00 9.67079163e-01 -3.08279562e+00 -8.72849369e+00 -8.85718536e+00 -8.06103420e+00 -7.99495935e+00 -6.61590958e+00 -3.85097361e+00 -3.58785343e+00 -4.88758659e+00 -8.87155247e+00 -4.90903425e+00 -1.76914275e+00 2.91308260e+00 9.35075951e+00 5.08239937e+00 -3.48335242e+00 -1.67217846e+01 -1.68231297e+01 -4.50904322e+00 -2.71892715e+00 -5.65479708e+00 -1.57324095e+01 -1.44419012e+01 -7.24084902e+00 -5.10271502e+00 -3.19629669e+00 -6.85624647e+00 -6.39056301e+00 -5.43019152e+00 -4.25859213e+00 3.00861597e+00 9.08308029e+00 7.91060114e+00 5.55928290e-01 -5.89256191e+00 -3.79723287e+00 -3.21856380e-01 5.01441193e+00 1.27897415e+01 1.58197651e+01 1.58679457e+01 7.35106277e+00 2.17179108e+00 5.55322790e+00 2.62682773e-02 -6.54181576e+00 -1.88230286e+01 -1.46624508e+01 -3.80877542e+00 -2.12464666e+00 -9.84187484e-01 -2.43609357e+00 -8.58303308e-01 -4.00280666e+00 -8.55722904e+00 -6.03461933e+00 -3.19776630e+00 -2.99914122e+00 -2.19456387e+00 1.78491354e+00 8.16520023e+00 5.34282351e+00 -7.60431409e-01 3.87877202e+00 4.00004578e+00 2.84870243e+00 -5.70852375e+00 -7.81262636e+00 3.53821015e+00 4.13441658e+00 -5.59108794e-01 -1.32380371e+01 -1.60328445e+01 -5.61192083e+00 -2.35015512e+00 3.52177835e+00 3.78281713e+00 7.34800768e+00 8.28076553e+00 3.67876554e+00 3.77137756e+00 4.07208967e+00 5.29947567e+00 2.86746597e+00 -2.52480316e+00 -1.01300907e+00 -1.17279041e+00 -3.89174342e+00 8.97055626e-01 -3.64110351e-01 -3.42512798e+00 -1.57955647e+01 -1.75820980e+01 -1.98212767e+00 3.63449240e+00 -1.90606523e+00 -1.37683315e+01 -1.43572187e+01 -2.43707585e+00 2.05767512e-01 2.27133679e+00 2.51894093e+00 3.45544845e-01 -4.26221514e+00 -1.11412325e+01 -5.46124268e+00 1.46400070e+00 1.16330099e+00 -3.62645578e+00 -1.02462711e+01 -4.37590742e+00 -4.07336146e-01 9.42066371e-01 4.99517012e+00 5.63803196e+00 7.76245165e+00 5.85511732e+00 4.42545891e+00 9.79552269e+00 8.47009659e+00 5.96985769e+00 -6.34658098e+00 -1.45330572e+01 -1.33467255e+01 -9.46574879e+00 -4.39534187e-01 2.22727227e+00 6.60628176e+00 1.08042917e+01 1.10216064e+01 8.81329346e+00 6.85887480e+00 8.36773396e+00 1.08132353e+01 5.99147224e+00 -4.64068699e+00 -1.38235826e+01 -1.80561123e+01 -2.51469040e+00 3.20696878e+00 1.47045696e+00 -6.92114544e+00 -7.50995111e+00 1.08245456e+00 -6.33903146e-01 2.95245910e+00 3.41661119e+00 2.72261500e+00 -1.46148801e+00 -6.52540874e+00 7.04288304e-01 5.81967211e+00 4.96992493e+00 3.95222211e+00 5.35947800e+00 1.09157391e+01 1.86755199e+01 2.29058304e+01 2.55837669e+01 1.14799557e+01 1.59291303e+00 -5.09456682e+00 -2.86609030e+00 8.79400826e+00 8.18604088e+00 1.96381533e+00 -1.26177683e+01 -1.18616819e+01 -3.61247696e-02 8.43305397e+00 1.23939457e+01 8.27900410e+00 1.25401602e+01 1.56733789e+01 1.39992094e+01 1.13427868e+01 1.14029036e+01 1.35405369e+01 1.10956345e+01 3.74710321e+00 3.03237534e+00 -4.35192156e+00 -3.26136184e+00 8.05758667e+00 1.99662971e+01 1.77500935e+01 6.40065384e+00 8.21959376e-01 2.43346667e+00 -2.86651683e+00 -7.30903769e+00 -1.33710756e+01 -1.67056046e+01 -1.06210823e+01 -3.05914593e+00 9.46526527e+00 1.20014353e+01 3.85804272e+00 -4.83834314e+00 -6.57677698e+00 -1.99196607e-01 3.57326198e+00 1.06484719e-01 2.17220759e+00 2.20593238e+00 3.10345340e+00 9.22016263e-01 1.64586437e+00 9.29068744e-01 2.13583040e+00 1.81338727e+00 -2.39295983e+00 -4.45794725e+00 -6.23913717e+00 -1.93638459e-01 1.51207829e+00 2.78200555e+00 3.85936350e-02 1.83683538e+00 1.57911396e+00 6.51296377e+00 9.40138340e+00 1.00281181e+01 6.23122931e+00 1.20698822e+00 1.34304011e+00 1.58667350e+00 2.30545211e+00 2.48399901e+00 4.98110580e+00 3.92723966e+00 2.00923491e+00 3.65292817e-01 1.73916769e+00 2.27974892e+00 -2.17456698e+00 -1.03710043e+00 -1.31525350e+00 -8.62437785e-01 -2.06626630e+00 -8.84961724e-01 6.42362177e-01 -3.80924404e-01 -2.39731416e-01 2.14905167e+00 1.03925979e+00 1.72755048e-01 3.34785908e-01 3.17588949e+00 1.19822800e+00 -1.18833828e+00 -2.59716511e+00 6.77282929e-01 -2.16492414e+00 -4.83739710e+00 -5.70126390e+00 -7.37838268e-01 2.06092763e+00 1.98354256e+00 1.79982364e+00 2.49588585e+00 2.86085153e+00 4.63876009e+00 7.40552807e+00 1.24093161e+01 7.57997751e+00 5.88994408e+00 3.45431828e+00 2.94343066e+00 3.13785481e+00 1.96556759e+00 4.89120722e+00 3.74463439e+00 3.91195798e+00 5.71725655e+00 5.05361032e+00 8.14564347e-01 -1.49364650e+00 1.96442157e-01 3.84651470e+00 5.49918079e+00 8.07809830e+00 9.44725418e+00 1.02527905e+01 5.78475380e+00 4.16390991e+00 3.70211267e+00 6.03304529e+00 2.78532696e+00 -1.00642765e+00 2.85665661e-01 4.05191898e+00 7.74701595e+00 6.87847757e+00 7.88773489e+00 8.13605595e+00 2.41939926e+00 -2.55155635e+00 -3.74397087e+00 4.46293652e-01 3.71556854e+00 4.28625870e+00 4.23263216e+00 6.43205976e+00 6.84676218e+00 8.21977329e+00 6.81759214e+00 7.55113888e+00 4.46592474e+00 5.46194315e+00 7.09756088e+00 1.17360153e+01 1.38322706e+01 1.69067459e+01 1.44473410e+01 1.30878210e+01 9.46553040e+00 1.17685032e+01 1.22885427e+01 1.04942322e+01 5.96719980e+00 3.08408546e+00 4.61604548e+00 5.88971806e+00 6.50380898e+00 5.17717791e+00 7.22897482e+00 7.69379187e+00 7.81021500e+00 1.18466520e+01 1.56890392e+01 9.68736172e+00 -1.77135253e+00 -4.05026627e+00 2.27384877e+00 7.54393148e+00 8.45110512e+00 6.90014696e+00 8.57100868e+00 7.95649147e+00 1.02833281e+01 8.44068050e+00 4.79645777e+00 -4.52760644e-02 2.40893245e+00 9.30728054e+00 1.42302237e+01 1.09735432e+01 6.69390106e+00 3.81961989e+00 5.39600134e+00 5.07526207e+00 4.73600721e+00 5.01499400e-02 -2.06309676e+00 -3.58953834e-01 5.37745857e+00 7.28123426e+00 7.47259665e+00 6.69076967e+00 7.57517433e+00 7.01831198e+00 7.68732214e+00 7.15644836e+00 6.97220087e+00 4.89749241e+00 4.33020735e+00 3.90482569e+00 6.20064688e+00 6.38117599e+00 1.01369085e+01 1.42707214e+01 2.27050152e+01 2.52569199e+01 2.01640377e+01 1.42233086e+01 9.97008228e+00 9.90917587e+00 1.00878754e+01 1.17489548e+01 1.23172932e+01 1.20919590e+01 1.11048517e+01 1.12549353e+01 9.92471600e+00 1.33091345e+01 1.72807102e+01 1.82747173e+01 1.44022560e+01 1.06564312e+01 1.04579563e+01 1.07428503e+01 9.06212616e+00 7.45997524e+00 7.15994549e+00 7.32331133e+00 7.89492846e+00 7.46381807e+00 8.93368530e+00 9.57242966e+00 8.44867039e+00 6.63623476e+00 7.16722202e+00 8.88758278e+00 9.97563171e+00 8.87658501e+00 7.46944761e+00 7.09837532e+00 8.26593781e+00 1.07045927e+01 1.26058683e+01 1.21508121e+01 1.07292929e+01 8.79599571e+00 5.28507519e+00 2.54965472e+00 4.13121796e+00 8.49005508e+00 1.26948004e+01 1.47457504e+01 1.62200947e+01 1.81994171e+01 1.72964516e+01 1.52308016e+01 1.45362959e+01 9.01046562e+00 -3.66923547e+00 -1.70894039e+00 -6.91141701e+00 -2.55207047e+02 -1.89865051e+03 34153508. 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. 0. 0. 0. 0. 0. 0. -94158472. -201580864. -1.24439307e+03 -4.23945343e+02 -2.55678158e+01 -1.22803030e+01 -8.77172410e-01 7.68980551e+00 9.34512520e+00 1.09217577e+01 8.25754833e+00 5.44439793e+00 5.72055340e+00 7.30868292e+00 8.57434654e+00 7.88786936e+00 7.69494247e+00 7.57594585e+00 7.49735069e+00 8.50506687e+00 9.12586880e+00 1.07036610e+01 1.17642784e+01 1.16215219e+01 1.10809212e+01 1.07436609e+01 1.27703362e+01 1.40873766e+01 1.43825140e+01 1.41745300e+01 1.36957436e+01 1.34690866e+01 1.32214680e+01 1.39918661e+01 1.50757837e+01 1.54077339e+01 1.50646048e+01 1.49200735e+01 1.49076920e+01 1.52679510e+01 1.40671978e+01 1.32609577e+01 1.27543936e+01 1.36808414e+01 1.50748644e+01 1.58864470e+01 1.66621723e+01 1.60055237e+01 1.69811172e+01 1.79263554e+01 1.82360764e+01 1.70942020e+01 1.53133802e+01 1.53409958e+01 1.58861380e+01 1.57404222e+01 1.59020691e+01 1.52701702e+01 1.55868587e+01 1.51063118e+01 1.48043251e+01 1.45026245e+01 1.21314707e+01 9.80126381e+00 9.37516594e+00 1.02418594e+01 1.13389301e+01 9.79343605e+00 8.97249317e+00 1.01984816e+01 1.20795259e+01 1.45230083e+01 1.52566385e+01 1.53529072e+01 1.66236820e+01 1.84780674e+01 1.97188549e+01 1.95137386e+01 1.75851974e+01 1.60605488e+01 1.52037458e+01 1.46780100e+01 1.52530947e+01 1.37729406e+01 1.26456900e+01 1.05968304e+01 1.00092802e+01 1.07004919e+01 1.21655903e+01 1.35836916e+01 1.36349449e+01 1.33043976e+01 1.17004156e+01 1.03736286e+01 1.08318233e+01 1.25670595e+01 1.39693165e+01 1.38288584e+01 1.34308348e+01 1.29170980e+01 1.21511765e+01 1.35748186e+01 1.54981642e+01 1.63733597e+01 1.59008961e+01 1.44893923e+01 1.46140966e+01 1.40916395e+01 1.33121386e+01 1.26435843e+01 1.17513895e+01 1.22552166e+01 1.35198336e+01 1.50609713e+01 1.62096958e+01 1.59715919e+01 1.58039227e+01 1.54985199e+01 1.55678816e+01 1.58298206e+01 1.58873014e+01 1.58167219e+01 1.54586458e+01 1.53020287e+01 1.49933138e+01 1.49511461e+01 1.48924980e+01 1.47118006e+01 1.37499590e+01 1.27666645e+01 1.28565035e+01 1.37324867e+01 1.46253939e+01 1.42493763e+01 1.37929258e+01 1.30169811e+01 1.27652588e+01 1.31887884e+01 1.41467457e+01 1.49843721e+01 1.51703205e+01 1.51327019e+01 1.51649313e+01 1.53310719e+01 1.54318409e+01 1.55361662e+01 1.53977499e+01 1.51867485e+01 1.50975819e+01 1.51805573e+01 1.52243233e+01 1.51851730e+01 1.50148802e+01 1.45356350e+01 1.40798998e+01 1.42461185e+01 1.47163525e+01 1.51418896e+01 1.47511396e+01 1.44575796e+01 1.42460670e+01 1.42606611e+01 1.42684498e+01 1.43316355e+01 1.46581755e+01 1.48927507e+01 1.51108685e+01 1.51205330e+01 1.51641245e+01 1.51807461e+01 1.51335793e+01 1.51377230e+01 1.51469078e+01 1.51579733e+01 1.51511307e+01 1.51667032e+01 1.51795168e+01 1.51384497e+01 1.50958614e+01 1.51297150e+01 1.51961288e+01 1.52368011e+01 1.52330484e+01 1.52250013e+01 1.51265459e+01 1.52312021e+01 1.54378405e+01 1.54959440e+01 1.53151217e+01 1.51186829e+01 1.51948929e+01 1.52654114e+01 1.52700062e+01 1.52162924e+01 1.52568464e+01 1.52534685e+01 1.53344383e+01 1.53503265e+01 1.53419123e+01 1.53073568e+01 1.52660208e+01 1.49349737e+01 1.44511271e+01 1.44583120e+01 1.47486525e+01 1.51861868e+01 1.48969154e+01 1.49434958e+01 1.51516762e+01 1.53642149e+01 1.53177557e+01 1.51575470e+01 1.50435581e+01 1.50627756e+01 1.51922464e+01 1.54016457e+01 1.53146238e+01 1.51421604e+01 1.51077061e+01 1.49883652e+01 1.49755220e+01 1.46194000e+01 1.45854244e+01 1.46060266e+01 1.47441578e+01 1.48261471e+01 1.42758045e+01 1.37699690e+01 1.35896606e+01 1.39600086e+01 1.44608307e+01 1.42498426e+01 1.43213072e+01 1.38893156e+01 1.36279650e+01 1.34552927e+01 1.36368160e+01 1.39203548e+01 1.35607843e+01 1.36274776e+01 1.39333630e+01 1.46556168e+01 1.51756201e+01 1.51231403e+01 1.37590570e+01 1.23342180e+01 1.18534307e+01 1.28577890e+01 1.57684126e+01 1.78884010e+01 1.78249454e+01 1.58664875e+01 1.43257742e+01 1.63532066e+01 1.79457645e+01 1.77511215e+01 1.54996004e+01 1.37057123e+01 1.36094742e+01 1.36509275e+01 1.40191965e+01 1.44674110e+01 1.43612776e+01 1.39979925e+01 1.38149796e+01 1.46880093e+01 1.52687435e+01 1.45164547e+01 1.34049902e+01 1.31422329e+01 1.42471056e+01 1.54450874e+01 1.53950882e+01 1.52764196e+01 1.53144913e+01 1.52866373e+01 1.56367817e+01 1.52670851e+01 1.71880093e+01 1.79906292e+01 1.77512074e+01 1.52742157e+01 1.31668749e+01 1.30349569e+01 1.38022738e+01 1.48775749e+01 1.47518072e+01 1.31073542e+01 1.09654198e+01 1.12020693e+01 1.25353861e+01 1.41872549e+01 1.31824646e+01 1.27427578e+01 1.26109867e+01 1.34723997e+01 1.58234329e+01 1.82231693e+01 1.84443836e+01 1.64448662e+01 1.36222124e+01 1.33448400e+01 1.37271719e+01 1.40575581e+01 1.41659069e+01 1.55955782e+01 1.81032696e+01 1.85138493e+01 1.80869179e+01 1.55126257e+01 1.58996372e+01 1.49930782e+01 1.50850563e+01 1.42811489e+01 1.47554693e+01 1.53463755e+01 1.58992586e+01 1.54396448e+01 1.41279936e+01 1.39378195e+01 1.32764463e+01 1.27997608e+01 1.19034090e+01 1.24024019e+01 1.26455450e+01 1.31714439e+01 1.54900866e+01 1.82625675e+01 2.09805431e+01 2.14522705e+01 2.11026211e+01 2.02482185e+01 1.61545467e+01 1.43033514e+01 1.18754177e+01 1.28785257e+01 1.21393824e+01 1.44924107e+01 1.75347691e+01 1.74352322e+01 1.53649969e+01 1.01886053e+01 7.57820320e+00 7.44179249e+00 9.21014118e+00 1.19693336e+01 1.20462637e+01 1.33799076e+01 1.66365948e+01 1.94037495e+01 1.77463818e+01 1.36005640e+01 9.02419281e+00 1.13368120e+01 1.43822346e+01 1.61429672e+01 1.60922089e+01 1.38003330e+01 1.22252989e+01 8.89651871e+00 8.82749271e+00 9.30673122e+00 9.56276703e+00 9.48536491e+00 9.79094696e+00 9.57946682e+00 1.05272236e+01 1.10305424e+01 1.09013243e+01 1.04469166e+01 1.07431431e+01 1.53143930e+01 1.99015045e+01 1.73665390e+01 1.06851482e+01 8.67280388e+00 1.37851152e+01 1.74429035e+01 1.54986200e+01 1.28043337e+01 1.56614285e+01 1.77149277e+01 1.83922825e+01 1.55762911e+01 1.23241014e+01 1.26915560e+01 1.33236876e+01 1.54502735e+01 1.44830952e+01 1.28982687e+01 1.12667809e+01 1.14339085e+01 1.18027697e+01 1.27815390e+01 1.25447311e+01 1.37287588e+01 1.50623341e+01 1.80261402e+01 1.40373907e+01 7.55510950e+00 8.49925613e+00 1.58595724e+01 1.99766006e+01 1.45793886e+01 1.07790375e+01 1.27527094e+01 1.50848637e+01 1.17062521e+01 7.14152527e+00 3.82663250e+00 4.98597240e+00 4.82593107e+00 8.78524876e+00 1.31379566e+01 1.34970894e+01 8.44496059e+00 7.92927313e+00 1.38253613e+01 1.44443016e+01 1.09478903e+01 5.89508247e+00 5.90441513e+00 5.92953396e+00 2.96037722e+00 7.84928203e-01 3.02869391e+00 9.05890942e+00 1.29022427e+01 1.09521532e+01 8.95275402e+00 9.03875732e+00 9.95860481e+00 9.86863995e+00 1.02915373e+01 9.00883102e+00 6.49703121e+00 5.59662294e+00 1.02811556e+01 1.52563639e+01 1.69336529e+01 1.46415548e+01 1.61847572e+01 2.18796654e+01 1.94514160e+01 1.20539274e+01 2.97947621e+00 2.18880129e+00 4.51746941e+00 3.93197846e+00 2.87500501e+00 4.86814976e+00 8.49136925e+00 1.08680305e+01 9.93418026e+00 8.03520012e+00 6.64814949e+00 4.05789089e+00 3.49881577e+00 5.61455727e+00 5.91336632e+00 5.44829321e+00 3.91299367e+00 8.39595795e+00 1.16018257e+01 1.03820868e+01 4.96198654e+00 4.63261986e+00 8.30703926e+00 7.67500353e+00 2.50522351e+00 3.08278394e+00 1.08396873e+01 2.08383865e+01 2.24665012e+01 1.90705147e+01 1.84001141e+01 1.96061668e+01 1.85686398e+01 1.35622950e+01 9.98948288e+00 1.02180262e+01 1.09341021e+01 1.28780127e+01 1.59357109e+01 1.54410658e+01 9.94672489e+00 3.87202263e+00 5.62892771e+00 1.13409805e+01 1.10950966e+01 7.47739267e+00 8.28940773e+00 1.50696592e+01 1.10770893e+01 -5.21743894e-01 -9.08073807e+00 -5.18246126e+00 1.39420295e+00 -7.32944906e-01 -5.78190279e+00 -7.79719400e+00 -3.61793518e+00 -2.53874421e-01 -2.70123792e+00 -4.07405806e+00 -4.82950401e+00 -6.98291481e-01 5.61529827e+00 1.34534168e+01 1.80553017e+01 1.89470005e+01 9.66388130e+00 1.58749056e+00 -3.43503308e+00 1.22856998e+00 4.77747393e+00 4.79911089e+00 3.76535892e+00 -4.44253236e-01 -7.27662134e+00 -5.89229727e+00 -2.37117440e-01 5.37059498e+00 6.17664814e+00 6.28786182e+00 1.21905165e+01 1.58916101e+01 1.48156004e+01 1.01628227e+01 6.09665632e+00 6.06084108e+00 5.47945356e+00 5.17956352e+00 6.82441902e+00 8.35658360e+00 8.85195351e+00 7.05574751e+00 5.10560894e+00 2.65668416e+00 1.25522852e+00 2.17203736e+00 9.20667839e+00 1.78051472e+01 1.80049038e+01 1.25034952e+01 1.15033674e+01 1.57875347e+01 1.57735920e+01 1.12109823e+01 6.52902222e+00 1.13789787e+01 1.50844765e+01 1.32558537e+01 7.78650951e+00 -1.13050163e+00 -1.39948714e+00 -9.42025065e-01 4.36629868e+00 1.08177671e+01 1.01003151e+01 5.94623280e+00 6.84503889e+00 1.35366411e+01 1.52757721e+01 1.01356134e+01 2.50433087e+00 6.69338846e+00 1.21568012e+01 1.13985529e+01 3.04867268e+00 -4.00030947e+00 7.43670702e-01 6.77147627e+00 7.86635351e+00 7.53822088e+00 6.27338505e+00 7.86679220e+00 9.81623936e+00 1.01298647e+01 1.45087519e+01 1.59514332e+01 1.53006687e+01 9.98953819e+00 5.49192905e+00 5.61261177e+00 4.77196550e+00 4.40600777e+00 3.48196340e+00 3.88643122e+00 5.35922718e+00 3.83355141e+00 2.77121735e+00 9.83222902e-01 -4.95002604e+00 -9.83227634e+00 -3.55727315e+00 7.96161366e+00 1.28161774e+01 3.78099728e+00 -2.70457673e+00 -4.15747833e+00 -2.99080157e+00 -2.02048922e+00 -5.18656731e-01 2.92615104e+00 4.25952816e+00 6.16342497e+00 3.40619392e+01 8.54001083e+01 6.52724304e+02 3.70589697e+03 -633708864. 0. 0. 0. 0. 693049472. -1.19657625e+06 2.43456525e+06 4.04202750e+05 4.00009937e+03 8.30788281e+03 9.98359766e+03 -1660712960. 0. 0.
================================================ FILE: config/m2dgr/ring32_M_8.xml ================================================ 32 1800
f
0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -237791040. -405504288. 5.47562675e+01 2.56278496e+01 1.68884449e+01 1.68601818e+01 1.68607483e+01 1.68593712e+01 1.68630924e+01 1.68587513e+01 1.68632317e+01 1.68638878e+01 1.68617649e+01 1.68601646e+01 1.68589096e+01 1.68587627e+01 1.68589687e+01 1.68588676e+01 1.68604546e+01 1.68641186e+01 1.68637981e+01 1.68588676e+01 1.68605385e+01 1.68647118e+01 1.68652916e+01 1.68608532e+01 1.68602333e+01 1.68600597e+01 1.68589001e+01 1.68595047e+01 1.68589287e+01 1.68615952e+01 1.68683414e+01 1.68688049e+01 1.68624344e+01 1.68587685e+01 1.68597298e+01 1.68594208e+01 1.68592892e+01 1.68592491e+01 1.68588009e+01 1.68595390e+01 1.68626308e+01 1.68605423e+01 1.68587494e+01 1.68590126e+01 1.68588524e+01 1.68590851e+01 1.68588657e+01 1.68595104e+01 1.68594704e+01 1.68593369e+01 1.68588848e+01 1.68593159e+01 1.68607235e+01 1.68613644e+01 1.68587742e+01 1.68640385e+01 1.68670502e+01 1.68614521e+01 1.68592224e+01 1.68596954e+01 1.68588123e+01 1.68600731e+01 1.68595657e+01 1.68589096e+01 1.68593159e+01 1.68602009e+01 1.68600407e+01 1.68588428e+01 1.68610229e+01 1.68598652e+01 1.68591423e+01 1.68588028e+01 1.68588734e+01 1.68589287e+01 1.68596649e+01 1.68589058e+01 1.68595734e+01 1.68623734e+01 1.68624229e+01 1.68591595e+01 1.68593922e+01 1.68626766e+01 1.68631248e+01 1.68593082e+01 1.68588257e+01 1.68588333e+01 1.68593826e+01 1.68629360e+01 1.68629074e+01 1.68587303e+01 1.68624516e+01 1.68628407e+01 1.68588104e+01 1.68617821e+01 1.68624992e+01 1.68614502e+01 1.68616810e+01 1.68617344e+01 1.68604012e+01 1.68589725e+01 1.68589973e+01 1.68589096e+01 1.68600044e+01 1.68608494e+01 1.68592167e+01 1.68591290e+01 1.68608074e+01 1.68612595e+01 1.68589039e+01 1.68596401e+01 1.68593521e+01 1.68592930e+01 1.68603077e+01 1.68616562e+01 1.68595181e+01 1.68590279e+01 1.68590908e+01 1.68599892e+01 1.68650951e+01 1.68665352e+01 1.68611507e+01 1.68588543e+01 1.68596344e+01 1.68610764e+01 1.68639717e+01 1.69270058e+01 2.58306332e+01 5.28632469e+01 26792542. -31353328. -44430808. 66744296. 5.67820435e+01 2.77277470e+01 1.70839005e+01 1.68649273e+01 1.70069733e+01 2.61909771e+01 5.13025627e+01 -222507312. 997721792. -29581050. -488975904. -22973196. 30235850. -91189864. 61268848. 28594182. -35304000. 5.39695587e+01 2.69129295e+01 1.70339375e+01 1.68832054e+01 1.68593216e+01 1.68588257e+01 1.68592091e+01 1.68594303e+01 1.68590755e+01 1.68593731e+01 1.68608418e+01 1.68588333e+01 1.68595104e+01 1.68593349e+01 1.68590946e+01 1.68589745e+01 1.68622742e+01 1.68668404e+01 1.68687878e+01 1.68604145e+01 1.68601894e+01 1.68619156e+01 1.68613644e+01 1.68610210e+01 1.68605766e+01 1.68590755e+01 1.68597736e+01 1.68610325e+01 1.68589096e+01 1.68599472e+01 1.68609524e+01 1.68587112e+01 1.68593826e+01 1.68599491e+01 1.68602200e+01 1.68596878e+01 1.68606796e+01 1.68607502e+01 1.68594666e+01 1.68591995e+01 1.68594360e+01 1.68623066e+01 1.68647156e+01 1.68639774e+01 1.68588886e+01 1.68617306e+01 1.68631325e+01 1.68605423e+01 1.68598652e+01 1.68595028e+01 1.68588333e+01 1.68600197e+01 1.68602543e+01 1.68589611e+01 1.68625908e+01 1.68644047e+01 1.68598309e+01 1.68587360e+01 1.68588581e+01 1.68588181e+01 1.68588161e+01 1.68588696e+01 1.68597775e+01 1.68589439e+01 1.68592510e+01 1.68604622e+01 1.68588943e+01 1.68600006e+01 1.68609638e+01 1.68589039e+01 1.68597641e+01 1.68605042e+01 1.68594875e+01 1.68594799e+01 1.68592358e+01 1.68594418e+01 1.68596344e+01 1.68598919e+01 1.68598442e+01 1.68601322e+01 1.68620338e+01 1.68620205e+01 1.68616085e+01 1.68604641e+01 1.68588734e+01 1.68592377e+01 1.68612156e+01 1.68597221e+01 1.68588409e+01 1.68601799e+01 1.68623562e+01 1.68589935e+01 1.68595543e+01 1.68600998e+01 1.68590050e+01 1.68601933e+01 1.68592358e+01 1.68587360e+01 1.68592339e+01 1.68600349e+01 1.68594761e+01 1.68589764e+01 1.68598785e+01 1.68589668e+01 1.68589325e+01 1.68587303e+01 1.68586864e+01 1.68592415e+01 1.68588161e+01 1.68589268e+01 1.68594398e+01 1.68607750e+01 1.68607235e+01 1.68597584e+01 1.68590603e+01 1.68604984e+01 1.68591385e+01 1.68610401e+01 1.68638210e+01 1.68605938e+01 1.68594589e+01 1.68606415e+01 1.68618832e+01 1.68593025e+01 1.68587055e+01 1.68588867e+01 1.68586845e+01 1.68588791e+01 1.68589096e+01 1.68590240e+01 1.68589516e+01 1.68588581e+01 1.68601036e+01 1.68593540e+01 1.68601742e+01 1.68624229e+01 1.68624706e+01 1.68592815e+01 1.68589859e+01 1.68589497e+01 1.68587589e+01 1.68588409e+01 1.68596306e+01 1.68591309e+01 1.68588715e+01 1.68588333e+01 1.68594551e+01 1.68608799e+01 1.68596649e+01 1.68591747e+01 1.68588486e+01 1.68588982e+01 1.68591213e+01 1.68602505e+01 1.68596821e+01 1.68588142e+01 1.68587704e+01 1.68590984e+01 1.68592720e+01 1.68602028e+01 1.68617592e+01 1.68613415e+01 1.68600006e+01 1.68590412e+01 1.68598995e+01 1.68615780e+01 1.68597775e+01 1.68591442e+01 1.68596172e+01 1.68588715e+01 1.68594990e+01 1.68588142e+01 1.68600922e+01 1.68592358e+01 1.68588047e+01 1.68599186e+01 1.68604565e+01 1.68625526e+01 1.68629436e+01 1.68610191e+01 1.68597965e+01 1.68596573e+01 1.68601208e+01 1.68594036e+01 1.68598843e+01 1.68614922e+01 1.68603840e+01 1.68588448e+01 1.68595829e+01 1.68591366e+01 1.68587112e+01 1.68593178e+01 1.68600349e+01 1.68591747e+01 1.68588181e+01 1.68588657e+01 1.68595467e+01 1.68592434e+01 1.68589191e+01 1.68589039e+01 1.68588219e+01 1.68587875e+01 1.68607979e+01 1.68619728e+01 1.68603630e+01 1.68588600e+01 1.68590164e+01 1.68590031e+01 1.68588448e+01 1.68597794e+01 1.68642921e+01 1.68634968e+01 1.68589249e+01 1.68635254e+01 1.68684540e+01 1.68620358e+01 1.68600712e+01 1.68600941e+01 1.68604336e+01 1.68625851e+01 1.68601933e+01 1.68598804e+01 1.68590565e+01 1.68590984e+01 1.68639126e+01 1.68664169e+01 1.68655148e+01 1.68589630e+01 1.68606586e+01 1.68590717e+01 1.68594894e+01 1.68607674e+01 1.68587933e+01 1.68609810e+01 1.68604774e+01 1.68599129e+01 1.68589096e+01 1.68590698e+01 1.68601379e+01 1.68618355e+01 1.68598995e+01 1.68590202e+01 1.68588963e+01 1.68588142e+01 1.68599720e+01 1.68628254e+01 1.68663502e+01 1.68624229e+01 1.68589039e+01 1.68588715e+01 1.68588486e+01 1.68588428e+01 1.68611851e+01 1.68607330e+01 1.68597622e+01 1.68648853e+01 1.68654594e+01 1.68603516e+01 1.68590393e+01 1.68590527e+01 1.68588772e+01 1.68589230e+01 1.68590412e+01 1.68601151e+01 1.68626728e+01 1.68612823e+01 1.68617535e+01 1.68616924e+01 1.68610325e+01 1.68607292e+01 1.68588848e+01 1.68592606e+01 1.68591099e+01 1.68587418e+01 1.68616486e+01 1.68631744e+01 1.68634281e+01 1.68587551e+01 1.68605461e+01 1.68606949e+01 1.68588085e+01 1.68607979e+01 1.68591042e+01 1.68594685e+01 1.68608723e+01 1.68600979e+01 1.68591976e+01 1.68586407e+01 1.68589478e+01 1.68599434e+01 1.68589916e+01 1.68591900e+01 1.68598518e+01 1.68589287e+01 1.68616962e+01 1.68654366e+01 1.68636723e+01 1.68589993e+01 1.68597755e+01 1.68589993e+01 1.68600998e+01 1.68623695e+01 1.68593006e+01 1.68593159e+01 1.68593102e+01 1.68588104e+01 1.68593884e+01 1.68589287e+01 1.68587685e+01 1.68593369e+01 1.68596325e+01 1.68594933e+01 1.68593960e+01 1.68589401e+01 1.68603764e+01 1.68597126e+01 1.68595867e+01 1.68590240e+01 1.68587055e+01 1.68596325e+01 1.68588486e+01 1.68588772e+01 1.68616467e+01 1.68601742e+01 1.68594017e+01 1.68628139e+01 1.68639336e+01 1.68588505e+01 1.68599815e+01 1.68609753e+01 1.68592911e+01 1.68590546e+01 1.68591709e+01 1.68587761e+01 1.68593388e+01 1.68609810e+01 1.68594284e+01 1.68589439e+01 1.68618145e+01 1.68621655e+01 1.68587666e+01 1.68604546e+01 1.68624039e+01 1.68604431e+01 1.68589153e+01 1.68614426e+01 1.68619404e+01 1.68588352e+01 1.68607578e+01 1.68595009e+01 1.68590431e+01 1.68614979e+01 1.68593006e+01 1.68596249e+01 1.68601513e+01 1.68592606e+01 1.68594513e+01 1.68609753e+01 1.68611736e+01 1.68606815e+01 1.68591156e+01 1.68589554e+01 1.68589344e+01 1.68586540e+01 1.68600121e+01 1.68596859e+01 1.68589802e+01 1.68588066e+01 1.68597813e+01 1.68587399e+01 1.68587952e+01 1.68587799e+01 1.68598022e+01 1.68604012e+01 1.68595448e+01 1.68627949e+01 1.68627396e+01 1.68587799e+01 1.68606853e+01 1.68610306e+01 1.68595142e+01 1.68591862e+01 1.68607655e+01 1.68606529e+01 1.68600922e+01 1.68589363e+01 1.68588123e+01 1.68588467e+01 1.68587189e+01 1.68588848e+01 1.68596992e+01 1.68597164e+01 1.68596878e+01 1.68590717e+01 1.68591537e+01 1.68592072e+01 1.68587589e+01 1.68618889e+01 1.68645954e+01 1.68623524e+01 1.68594055e+01 1.68588104e+01 1.68588200e+01 1.68611717e+01 1.68634682e+01 1.68617992e+01 1.68592224e+01 1.68586788e+01 1.68586712e+01 1.68588352e+01 1.68589840e+01 1.68590240e+01 1.68589058e+01 1.68595066e+01 1.68613567e+01 1.68595734e+01 1.68591995e+01 1.68608570e+01 1.68593235e+01 1.68597870e+01 1.68615570e+01 1.68604908e+01 1.68588047e+01 1.68602123e+01 1.68591843e+01 1.68588619e+01 1.68590355e+01 1.68587055e+01 1.68587112e+01 1.68589592e+01 1.68594894e+01 1.68605747e+01 1.68611202e+01 1.68603764e+01 1.68611450e+01 1.68596153e+01 1.68592682e+01 1.68593311e+01 1.68588638e+01 1.68597870e+01 1.68589630e+01 1.68590679e+01 1.68587875e+01 1.68588505e+01 1.68594360e+01 1.68593445e+01 1.68595428e+01 1.68588181e+01 1.68591423e+01 1.68589077e+01 1.68590298e+01 1.68625774e+01 1.68606300e+01 1.68588009e+01 1.68599968e+01 1.68606472e+01 1.68589344e+01 1.68589592e+01 1.68586864e+01 1.68588886e+01 1.68592510e+01 1.68597183e+01 1.68592911e+01 1.68599186e+01 1.68589649e+01 1.68598499e+01 1.68597202e+01 1.68611145e+01 1.68612976e+01 1.69022636e+01 1.69406528e+01 2.42388802e+01 5.02298470e+01 43535268. 634051904. 22391922. 16369420. -1479806848. 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. 0. 0. 0. 0. 0. 0. 0. 555684032. 6.83735275e+01 2.68503418e+01 1.70764408e+01 1.68966885e+01 1.68617744e+01 1.68605385e+01 1.68620644e+01 1.68632183e+01 1.68593025e+01 1.68587914e+01 1.68589706e+01 1.68589325e+01 1.68592014e+01 1.68596916e+01 1.68595123e+01 1.68589478e+01 1.68589554e+01 1.68589211e+01 1.68593922e+01 1.68598633e+01 1.68604889e+01 1.68601036e+01 1.68595905e+01 1.68587780e+01 1.68588238e+01 1.68595448e+01 1.68606472e+01 1.68591671e+01 1.68597279e+01 1.68588943e+01 1.68601093e+01 1.68609829e+01 1.68594418e+01 1.68585625e+01 1.68585396e+01 1.68589516e+01 1.68589153e+01 1.68590622e+01 1.68593845e+01 1.68595524e+01 1.68592167e+01 1.68588600e+01 1.68589668e+01 1.68595028e+01 1.68618717e+01 1.68666954e+01 1.68641281e+01 1.68590202e+01 1.68623943e+01 1.68624744e+01 1.68588696e+01 1.68593636e+01 1.68589249e+01 1.68600540e+01 1.68598042e+01 1.68589344e+01 1.68590832e+01 1.68594112e+01 1.68587170e+01 1.68589649e+01 1.68593807e+01 1.68595695e+01 1.68613892e+01 1.68642883e+01 1.68638668e+01 1.68605385e+01 1.68591022e+01 1.68594360e+01 1.68600674e+01 1.68623123e+01 1.68669338e+01 1.68696423e+01 1.68699417e+01 1.68643169e+01 1.68615170e+01 1.68632946e+01 1.68607216e+01 1.68588200e+01 1.68618908e+01 1.68609104e+01 1.68589668e+01 1.68591595e+01 1.68598595e+01 1.68597603e+01 1.68599186e+01 1.68591576e+01 1.68589096e+01 1.68589783e+01 1.68594170e+01 1.68591747e+01 1.68593140e+01 1.68602085e+01 1.68631248e+01 1.68618126e+01 1.68593464e+01 1.68608646e+01 1.68606300e+01 1.68604984e+01 1.68587990e+01 1.68587322e+01 1.68605461e+01 1.68606758e+01 1.68592129e+01 1.68603191e+01 1.68610363e+01 1.68589306e+01 1.68590088e+01 1.68604279e+01 1.68605824e+01 1.68620071e+01 1.68623943e+01 1.68603020e+01 1.68602409e+01 1.68604164e+01 1.68609180e+01 1.68600769e+01 1.68589745e+01 1.68590355e+01 1.68589077e+01 1.68586750e+01 1.68597469e+01 1.68597107e+01 1.68590565e+01 1.68602715e+01 1.68605232e+01 1.68592587e+01 1.68605385e+01 1.68589096e+01 1.68601055e+01 1.68604069e+01 1.68589897e+01 1.68595085e+01 1.68602085e+01 1.68599243e+01 1.68590775e+01 1.68588696e+01 1.68596821e+01 1.68588600e+01 1.68592396e+01 1.68593655e+01 1.68589115e+01 1.68593655e+01 1.68588028e+01 1.68588314e+01 1.68589497e+01 1.68600578e+01 1.68604660e+01 1.68619328e+01 1.68609829e+01 1.68603611e+01 1.68619900e+01 1.68613472e+01 1.68599567e+01 1.68589287e+01 1.68607006e+01 1.68600140e+01 1.68590202e+01 1.68591499e+01 1.68593311e+01 1.68604355e+01 1.68622341e+01 1.68625965e+01 1.68613377e+01 1.68607559e+01 1.68611145e+01 1.68626423e+01 1.68602428e+01 1.68588047e+01 1.68605442e+01 1.68613911e+01 1.68588848e+01 1.68595600e+01 1.68589840e+01 1.68591557e+01 1.68589611e+01 1.68592701e+01 1.68590965e+01 1.68593712e+01 1.68594093e+01 1.68594799e+01 1.68589897e+01 1.68588867e+01 1.68590221e+01 1.68598785e+01 1.68594799e+01 1.68596382e+01 1.68601284e+01 1.68620262e+01 1.68658218e+01 1.68690147e+01 1.68719997e+01 1.68624630e+01 1.68591671e+01 1.68588810e+01 1.68587685e+01 1.68601646e+01 1.68598862e+01 1.68590355e+01 1.68606930e+01 1.68604355e+01 1.68589554e+01 1.68602715e+01 1.68619232e+01 1.68604527e+01 1.68618279e+01 1.68637314e+01 1.68630962e+01 1.68619385e+01 1.68616085e+01 1.68619499e+01 1.68607731e+01 1.68591919e+01 1.68591385e+01 1.68587990e+01 1.68587914e+01 1.68600540e+01 1.68661118e+01 1.68653851e+01 1.68595085e+01 1.68587284e+01 1.68588486e+01 1.68587685e+01 1.68596096e+01 1.68618755e+01 1.68628960e+01 1.68603764e+01 1.68589973e+01 1.68599644e+01 1.68607769e+01 1.68588676e+01 1.68592110e+01 1.68598957e+01 1.68587494e+01 1.68591118e+01 1.68587608e+01 1.68588943e+01 1.68586636e+01 1.68586388e+01 1.68586140e+01 1.68589115e+01 1.68589153e+01 1.68588848e+01 1.68586082e+01 1.68585987e+01 1.68589859e+01 1.68594303e+01 1.68591232e+01 1.68589096e+01 1.68586750e+01 1.68588734e+01 1.68587589e+01 1.68589058e+01 1.68591137e+01 1.68599663e+01 1.68598461e+01 1.68592033e+01 1.68588963e+01 1.68588409e+01 1.68588009e+01 1.68586445e+01 1.68587456e+01 1.68589058e+01 1.68588905e+01 1.68588238e+01 1.68587608e+01 1.68587627e+01 1.68588886e+01 1.68588257e+01 1.68590164e+01 1.68587894e+01 1.68590298e+01 1.68588543e+01 1.68589020e+01 1.68587189e+01 1.68590069e+01 1.68589211e+01 1.68587990e+01 1.68586082e+01 1.68587265e+01 1.68587780e+01 1.68588905e+01 1.68588390e+01 1.68589115e+01 1.68588753e+01 1.68588772e+01 1.68589840e+01 1.68594532e+01 1.68594227e+01 1.68591728e+01 1.68587170e+01 1.68589497e+01 1.68588371e+01 1.68588696e+01 1.68588867e+01 1.68586617e+01 1.68588619e+01 1.68593750e+01 1.68592548e+01 1.68590813e+01 1.68588009e+01 1.68587551e+01 1.68586979e+01 1.68585911e+01 1.68587952e+01 1.68588390e+01 1.68589153e+01 1.68588428e+01 1.68586750e+01 1.68587914e+01 1.68593922e+01 1.68593521e+01 1.68589840e+01 1.68587112e+01 1.68586864e+01 1.68588867e+01 1.68590927e+01 1.68589649e+01 1.68588619e+01 1.68586636e+01 1.68588581e+01 1.68587303e+01 1.68592739e+01 1.68592281e+01 1.68589230e+01 1.68587933e+01 1.68590374e+01 1.68589478e+01 1.68590870e+01 1.68586636e+01 1.68591156e+01 1.68595600e+01 1.68593349e+01 1.68587608e+01 1.68590031e+01 1.68588066e+01 1.68588161e+01 1.68587780e+01 1.68586597e+01 1.68587112e+01 1.68587341e+01 1.68588543e+01 1.68587971e+01 1.68585892e+01 1.68589306e+01 1.68599300e+01 1.68605995e+01 1.68603668e+01 1.68593121e+01 1.68588543e+01 1.68591461e+01 1.68595657e+01 1.68590336e+01 1.68589420e+01 1.68589363e+01 1.68587093e+01 1.68588142e+01 1.68593712e+01 1.68590107e+01 1.68589954e+01 1.68587437e+01 1.68588390e+01 1.68596153e+01 1.68611679e+01 1.68590813e+01 1.68600655e+01 1.68610268e+01 1.68593636e+01 1.68588619e+01 1.68589287e+01 1.68586464e+01 1.68588085e+01 1.68587112e+01 1.68590164e+01 1.68587227e+01 1.68590508e+01 1.68596687e+01 1.68591442e+01 1.68590012e+01 1.68602276e+01 1.68591766e+01 1.68587360e+01 1.68589706e+01 1.68589954e+01 1.68587589e+01 1.68589611e+01 1.68597946e+01 1.68607635e+01 1.68598099e+01 1.68588333e+01 1.68586922e+01 1.68589401e+01 1.68590393e+01 1.68589039e+01 1.68588905e+01 1.68586559e+01 1.68587246e+01 1.68588066e+01 1.68591728e+01 1.68593178e+01 1.68591061e+01 1.68587227e+01 1.68589420e+01 1.68588886e+01 1.68597927e+01 1.68621101e+01 1.68635540e+01 1.68612976e+01 1.68595657e+01 1.68589516e+01 1.68590717e+01 1.68588219e+01 1.68592587e+01 1.68591137e+01 1.68589706e+01 1.68587360e+01 1.68588276e+01 1.68588829e+01 1.68590946e+01 1.68599300e+01 1.68604584e+01 1.68593426e+01 1.68588657e+01 1.68587551e+01 1.68587990e+01 1.68586655e+01 1.68589630e+01 1.68589821e+01 1.68590374e+01 1.68587017e+01 1.68586063e+01 1.68585987e+01 1.68587608e+01 1.68589535e+01 1.68591232e+01 1.68591557e+01 1.68588638e+01 1.68589878e+01 1.68588829e+01 1.68591328e+01 1.68590031e+01 1.68590412e+01 1.68586922e+01 1.68590431e+01 1.68587551e+01 1.68590088e+01 1.68588161e+01 1.68591576e+01 1.68593311e+01 1.68587666e+01 1.68587341e+01 1.68590069e+01 1.68591557e+01 1.68594971e+01 1.68595181e+01 1.68595161e+01 1.68593712e+01 1.68600788e+01 1.68776550e+01 1.69369717e+01 1.68781624e+01 2.21669941e+01 4.45876808e+01 -171510176. 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. 0. 0. 0. 0. 0. 0. -2.56068478e+01 2.57584915e+01 1.69173336e+01 1.68755741e+01 1.68605671e+01 1.68609409e+01 1.68610401e+01 1.68589287e+01 1.68587914e+01 1.68590775e+01 1.68589325e+01 1.68591423e+01 1.68611145e+01 1.68617001e+01 1.68607101e+01 1.68596897e+01 1.68601952e+01 1.68603611e+01 1.68603439e+01 1.68599758e+01 1.68596020e+01 1.68596325e+01 1.68591442e+01 1.68588982e+01 1.68588428e+01 1.68590088e+01 1.68589077e+01 1.68588085e+01 1.68588066e+01 1.68590088e+01 1.68588905e+01 1.68587742e+01 1.68587589e+01 1.68587341e+01 1.68588543e+01 1.68589802e+01 1.68590775e+01 1.68588848e+01 1.68587513e+01 1.68589802e+01 1.68591385e+01 1.68589859e+01 1.68587227e+01 1.68587570e+01 1.68587971e+01 1.68588810e+01 1.68591003e+01 1.68594799e+01 1.68592205e+01 1.68594284e+01 1.68598003e+01 1.68598995e+01 1.68595581e+01 1.68588848e+01 1.68590336e+01 1.68590183e+01 1.68588886e+01 1.68590088e+01 1.68589649e+01 1.68592091e+01 1.68590355e+01 1.68588524e+01 1.68588848e+01 1.68589363e+01 1.68601284e+01 1.68606873e+01 1.68601551e+01 1.68595181e+01 1.68609352e+01 1.68619289e+01 1.68605709e+01 1.68593578e+01 1.68587856e+01 1.68588219e+01 1.68588772e+01 1.68593521e+01 1.68609104e+01 1.68627186e+01 1.68627243e+01 1.68603401e+01 1.68593330e+01 1.68587608e+01 1.68589897e+01 1.68588696e+01 1.68589554e+01 1.68596859e+01 1.68617649e+01 1.68625507e+01 1.68613796e+01 1.68598404e+01 1.68589268e+01 1.68588276e+01 1.68589230e+01 1.68600960e+01 1.68617306e+01 1.68608837e+01 1.68593235e+01 1.68586864e+01 1.68590088e+01 1.68592567e+01 1.68594723e+01 1.68598194e+01 1.68587303e+01 1.68591347e+01 1.68596439e+01 1.68593216e+01 1.68587170e+01 1.68589516e+01 1.68588390e+01 1.68591976e+01 1.68596115e+01 1.68608551e+01 1.68607502e+01 1.68593445e+01 1.68588581e+01 1.68598652e+01 1.68596191e+01 1.68591805e+01 1.68589725e+01 1.68589554e+01 1.68592453e+01 1.68591995e+01 1.68590126e+01 1.68589382e+01 1.68587151e+01 1.68589478e+01 1.68588409e+01 1.68589249e+01 1.68587570e+01 1.68594227e+01 1.68614979e+01 1.68615742e+01 1.68600082e+01 1.68589191e+01 1.68593502e+01 1.68604355e+01 1.68627491e+01 1.68635063e+01 1.68616047e+01 1.68595028e+01 1.68589516e+01 1.68588505e+01 1.68586922e+01 1.68588543e+01 1.68588867e+01 1.68591232e+01 1.68590889e+01 1.68588924e+01 1.68588467e+01 1.68587246e+01 1.68589497e+01 1.68586903e+01 1.68588123e+01 1.68589535e+01 1.68599052e+01 1.68619328e+01 1.68613968e+01 1.68596077e+01 1.68587742e+01 1.68593082e+01 1.68610401e+01 1.68628731e+01 1.68631344e+01 1.68636169e+01 1.68641739e+01 1.68618011e+01 1.68603516e+01 1.68590736e+01 1.68589478e+01 1.68587246e+01 1.68589420e+01 1.68589058e+01 1.68589020e+01 1.68589478e+01 1.68588734e+01 1.68591537e+01 1.68588924e+01 1.68592777e+01 1.68616066e+01 1.68613434e+01 1.68594456e+01 1.68587170e+01 1.68589191e+01 1.68588829e+01 1.68588734e+01 1.68589687e+01 1.68586597e+01 1.68594818e+01 1.68600292e+01 1.68591862e+01 1.68589401e+01 1.68588200e+01 1.68587341e+01 1.68589344e+01 1.68587589e+01 1.68590145e+01 1.68588524e+01 1.68588829e+01 1.68589039e+01 1.68588428e+01 1.68591061e+01 1.68589020e+01 1.68588791e+01 1.68595924e+01 1.68595161e+01 1.68591709e+01 1.68587875e+01 1.68588657e+01 1.68588600e+01 1.68589630e+01 1.68590088e+01 1.68588734e+01 1.68586693e+01 1.68587875e+01 1.68588200e+01 1.68589497e+01 1.68588352e+01 1.68586979e+01 1.68588028e+01 1.68587246e+01 1.68589211e+01 1.68587856e+01 1.68589363e+01 1.68588219e+01 1.68586407e+01 1.68587837e+01 1.68587952e+01 1.68592300e+01 1.68597202e+01 1.68596020e+01 1.68593369e+01 1.68589134e+01 1.68591175e+01 1.68587856e+01 1.68591766e+01 1.68593426e+01 1.68595028e+01 1.68590794e+01 1.68589706e+01 1.68592243e+01 1.68594074e+01 1.68591614e+01 1.68586807e+01 1.68587246e+01 1.68587971e+01 1.68590717e+01 1.68602009e+01 1.68606415e+01 1.68596325e+01 1.68591442e+01 1.68616581e+01 1.68614368e+01 1.68593082e+01 1.68587971e+01 1.68595314e+01 1.68608646e+01 1.68603859e+01 1.68589592e+01 1.68588238e+01 1.68588161e+01 1.68588066e+01 1.68587704e+01 1.68586273e+01 1.68588047e+01 1.68587780e+01 1.68590031e+01 1.68587894e+01 1.68588543e+01 1.68587418e+01 1.68588886e+01 1.68593082e+01 1.68588886e+01 1.68590431e+01 1.68589535e+01 1.68588123e+01 1.68589897e+01 1.68589058e+01 1.68591881e+01 1.68590412e+01 1.68596516e+01 1.68601913e+01 1.68597660e+01 1.68587818e+01 1.68589306e+01 1.68590450e+01 1.68589764e+01 1.68587875e+01 1.68587246e+01 1.68587933e+01 1.68597851e+01 1.68598690e+01 1.68590088e+01 1.68586388e+01 1.68588161e+01 1.68587189e+01 1.68589630e+01 1.68587856e+01 1.68593712e+01 1.68607235e+01 1.68605633e+01 1.68594952e+01 1.68587685e+01 1.68588982e+01 1.68586197e+01 1.68587589e+01 1.68587933e+01 1.68590717e+01 1.68602467e+01 1.68607826e+01 1.68600559e+01 1.68590603e+01 1.68589211e+01 1.68586903e+01 1.68588371e+01 1.68587456e+01 1.68589249e+01 1.68588657e+01 1.68590698e+01 1.68590279e+01 1.68587818e+01 1.68589821e+01 1.68586979e+01 1.68588161e+01 1.68588600e+01 1.68589706e+01 1.68592949e+01 1.68589973e+01 1.68589134e+01 1.68602715e+01 1.68620892e+01 1.68627510e+01 1.68622761e+01 1.68616219e+01 1.68590755e+01 1.68586922e+01 1.68589668e+01 1.68589077e+01 1.68587990e+01 1.68588772e+01 1.68598614e+01 1.68598080e+01 1.68591919e+01 1.68591270e+01 1.68600655e+01 1.68603840e+01 1.68596134e+01 1.68586884e+01 1.68588448e+01 1.68589878e+01 1.68601875e+01 1.68613586e+01 1.68600044e+01 1.68587303e+01 1.68591061e+01 1.68588276e+01 1.68592625e+01 1.68597374e+01 1.68595982e+01 1.68588238e+01 1.68588963e+01 1.68593750e+01 1.68593979e+01 1.68589592e+01 1.68590393e+01 1.68589306e+01 1.68592148e+01 1.68589954e+01 1.68588963e+01 1.68588791e+01 1.68587303e+01 1.68589611e+01 1.68588142e+01 1.68594856e+01 1.68615036e+01 1.68598232e+01 1.68588924e+01 1.68589268e+01 1.68594170e+01 1.68610649e+01 1.68599930e+01 1.68590202e+01 1.68595047e+01 1.68604145e+01 1.68607655e+01 1.68595734e+01 1.68589382e+01 1.68588181e+01 1.68587742e+01 1.68593292e+01 1.68591843e+01 1.68591862e+01 1.68587093e+01 1.68587379e+01 1.68588085e+01 1.68588810e+01 1.68591061e+01 1.68591213e+01 1.68596268e+01 1.68608418e+01 1.68592281e+01 1.68592663e+01 1.68590336e+01 1.68594112e+01 1.68610706e+01 1.68593159e+01 1.68587990e+01 1.68590469e+01 1.68592319e+01 1.68587265e+01 1.68591042e+01 1.68602886e+01 1.68597450e+01 1.68594532e+01 1.68587933e+01 1.68591385e+01 1.68592510e+01 1.68588562e+01 1.68588257e+01 1.68592949e+01 1.68594170e+01 1.68588734e+01 1.68590813e+01 1.68592491e+01 1.68591442e+01 1.68598289e+01 1.68611317e+01 1.68597260e+01 1.68587265e+01 1.68593369e+01 1.68589478e+01 1.68589001e+01 1.68588390e+01 1.68587093e+01 1.68587189e+01 1.68586864e+01 1.68589268e+01 1.68590527e+01 1.68589211e+01 1.68587494e+01 1.68594646e+01 1.68600597e+01 1.68593884e+01 1.68601570e+01 1.68627186e+01 1.68612709e+01 1.68589478e+01 1.68595905e+01 1.68599758e+01 1.68591499e+01 1.68592682e+01 1.68595638e+01 1.68592281e+01 1.68587589e+01 1.68589268e+01 1.68589096e+01 1.68589573e+01 1.68588371e+01 1.68590889e+01 1.68593216e+01 1.68590775e+01 1.68592052e+01 1.68590641e+01 1.68592072e+01 1.68586617e+01 1.68589859e+01 1.68588848e+01 1.68589554e+01 1.68590946e+01 1.68587608e+01 1.68588238e+01 1.68597450e+01 1.68593197e+01 1.68591499e+01 1.68632374e+01 1.68644142e+01 1.68622265e+01 1.68612118e+01 1.68621063e+01 1.68611946e+01 1.68598862e+01 1.68591328e+01 1.68593311e+01 1.68591328e+01 1.68594723e+01 1.68605824e+01 1.68605385e+01 1.68590813e+01 1.68587303e+01 1.68587875e+01 1.68596592e+01 1.68599758e+01 1.68587570e+01 1.68588448e+01 1.68597984e+01 1.68589973e+01 1.68601818e+01 1.68637581e+01 1.68613701e+01 1.68590832e+01 1.68596973e+01 1.68617535e+01 1.68622189e+01 1.68605556e+01 1.68597698e+01 1.68608017e+01 1.68613987e+01 1.68608227e+01 1.68592968e+01 1.68587646e+01 1.68599777e+01 1.68617020e+01 1.68615856e+01 1.68588924e+01 1.68595524e+01 1.68606358e+01 1.68594265e+01 1.68588772e+01 1.68588829e+01 1.68589115e+01 1.68593063e+01 1.68615513e+01 1.68607082e+01 1.68590965e+01 1.68588009e+01 1.68588467e+01 1.68588409e+01 1.68598309e+01 1.68615913e+01 1.68612347e+01 1.68592796e+01 1.68589725e+01 1.68588696e+01 1.68588753e+01 1.68587322e+01 1.68587132e+01 1.68590736e+01 1.68590374e+01 1.68588333e+01 1.68588066e+01 1.68586712e+01 1.68589649e+01 1.68586922e+01 1.68593941e+01 1.68616199e+01 1.68616467e+01 1.68601170e+01 1.68596191e+01 1.68613987e+01 1.68610306e+01 1.68596821e+01 1.68587914e+01 1.68597927e+01 1.68616219e+01 1.68609829e+01 1.68592854e+01 1.68590565e+01 1.68590126e+01 1.68588753e+01 1.68587933e+01 1.68597946e+01 1.68599586e+01 1.68588657e+01 1.68589592e+01 1.68602810e+01 1.68607635e+01 1.68594646e+01 1.68587532e+01 1.68590603e+01 1.68602257e+01 1.68600941e+01 1.68587971e+01 1.68595676e+01 1.68588524e+01 1.68589497e+01 1.68593178e+01 1.68594055e+01 1.68590431e+01 1.68588333e+01 1.68590755e+01 1.68593426e+01 1.68610325e+01 1.68625050e+01 1.68616600e+01 1.68599834e+01 1.68588219e+01 1.68591213e+01 1.68589153e+01 1.68589592e+01 1.68589306e+01 1.68587132e+01 1.68589878e+01 1.68587818e+01 1.68588467e+01 1.68588352e+01 1.68593559e+01 1.68607826e+01 1.68591328e+01 1.68593826e+01 1.68607368e+01 1.68589020e+01 1.68590260e+01 1.68589401e+01 1.68589725e+01 1.68587685e+01 1.68586903e+01 1.68587589e+01 1.68587971e+01 1.68588619e+01 1.68592319e+01 1.68613148e+01 1.68777351e+01 1.69537792e+01 1.69101505e+01 1.68784904e+01 2.26208210e+01 4.53105583e+01 16906696. 18379446. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -475582080. -811008576. 7.44593964e+01 1.87126503e+01 1.24618616e+01 1.03078909e+01 1.02743368e+01 1.02513638e+01 1.02478781e+01 1.02470541e+01 1.02470636e+01 1.02470846e+01 1.02470617e+01 1.02470551e+01 1.02470207e+01 1.02470312e+01 1.02470369e+01 1.02470102e+01 1.02470369e+01 1.02471266e+01 1.02471533e+01 1.02470284e+01 1.02470798e+01 1.02471657e+01 1.02471724e+01 1.02470665e+01 1.02470598e+01 1.02470503e+01 1.02470274e+01 1.02470436e+01 1.02470293e+01 1.02470894e+01 1.02472191e+01 1.02472229e+01 1.02470903e+01 1.02469988e+01 1.02470446e+01 1.02470379e+01 1.02470264e+01 1.02470312e+01 1.02470074e+01 1.02470713e+01 1.02471542e+01 1.02470741e+01 1.02469997e+01 1.02470026e+01 1.02470360e+01 1.02470341e+01 1.02470455e+01 1.02470226e+01 1.02470236e+01 1.02470245e+01 1.02470360e+01 1.02470131e+01 1.02470379e+01 1.02470589e+01 1.02470398e+01 1.02471876e+01 1.02472258e+01 1.02470894e+01 1.02469959e+01 1.02470503e+01 1.02470388e+01 1.02471809e+01 1.02471371e+01 1.02470589e+01 1.02470493e+01 1.02470961e+01 1.02470589e+01 1.02470179e+01 1.02470598e+01 1.02470608e+01 1.02470207e+01 1.02470264e+01 1.02470026e+01 1.02470121e+01 1.02470341e+01 1.02470226e+01 1.02470341e+01 1.02470551e+01 1.02470770e+01 1.02470207e+01 1.02470655e+01 1.02471685e+01 1.02471838e+01 1.02470589e+01 1.02470465e+01 1.02470293e+01 1.02470226e+01 1.02470541e+01 1.02470942e+01 1.02470350e+01 1.02471323e+01 1.02471275e+01 1.02470102e+01 1.02470779e+01 1.02471046e+01 1.02470942e+01 1.02470922e+01 1.02470999e+01 1.02470608e+01 1.02470522e+01 1.02470551e+01 1.02470303e+01 1.02470551e+01 1.02471495e+01 1.02471981e+01 1.02470961e+01 1.02470465e+01 1.02471228e+01 1.02470446e+01 1.02470322e+01 1.02470350e+01 1.02470341e+01 1.02470360e+01 1.02470703e+01 1.02470379e+01 1.02470379e+01 1.02470226e+01 1.02470751e+01 1.02471256e+01 1.02471895e+01 1.02470741e+01 1.02470417e+01 1.02470598e+01 1.02471075e+01 1.02486048e+01 1.02832518e+01 1.49868050e+01 2.68336296e+01 1.10553665e+02 1.10556625e+02 1.10525261e+02 1.10506340e+02 2.84386845e+01 1.58853292e+01 1.03625164e+01 1.02532730e+01 1.03409863e+01 1.52078247e+01 2.64633713e+01 1.10535767e+02 1.10510376e+02 1.10515442e+02 1.10541000e+02 1.10528130e+02 1.10511971e+02 1.10509216e+02 1.10505646e+02 1.10506409e+02 1.10504646e+02 2.72324409e+01 1.55841837e+01 1.03606739e+01 1.02648239e+01 1.02474556e+01 1.02471895e+01 1.02472324e+01 1.02470827e+01 1.02470360e+01 1.02470303e+01 1.02470350e+01 1.02470245e+01 1.02470331e+01 1.02470417e+01 1.02470398e+01 1.02470503e+01 1.02471371e+01 1.02472076e+01 1.02472057e+01 1.02470407e+01 1.02470646e+01 1.02471008e+01 1.02470903e+01 1.02470875e+01 1.02470808e+01 1.02470474e+01 1.02470493e+01 1.02470331e+01 1.02470083e+01 1.02470207e+01 1.02470808e+01 1.02470207e+01 1.02470341e+01 1.02470655e+01 1.02470427e+01 1.02470369e+01 1.02470284e+01 1.02470484e+01 1.02470245e+01 1.02470188e+01 1.02470636e+01 1.02472658e+01 1.02474499e+01 1.02472992e+01 1.02470102e+01 1.02470741e+01 1.02471161e+01 1.02470732e+01 1.02470713e+01 1.02470713e+01 1.02470388e+01 1.02470846e+01 1.02470722e+01 1.02470179e+01 1.02470951e+01 1.02471676e+01 1.02470598e+01 1.02470198e+01 1.02470417e+01 1.02470140e+01 1.02470322e+01 1.02470121e+01 1.02470274e+01 1.02470255e+01 1.02470284e+01 1.02471142e+01 1.02470407e+01 1.02470589e+01 1.02471066e+01 1.02470264e+01 1.02470322e+01 1.02470846e+01 1.02470531e+01 1.02470436e+01 1.02470360e+01 1.02470312e+01 1.02470303e+01 1.02470741e+01 1.02470589e+01 1.02470608e+01 1.02471085e+01 1.02471476e+01 1.02471962e+01 1.02470846e+01 1.02470226e+01 1.02470579e+01 1.02471008e+01 1.02470694e+01 1.02470236e+01 1.02470627e+01 1.02471762e+01 1.02470350e+01 1.02470388e+01 1.02470951e+01 1.02470274e+01 1.02471075e+01 1.02470903e+01 1.02470274e+01 1.02471056e+01 1.02471056e+01 1.02470598e+01 1.02470255e+01 1.02470160e+01 1.02470417e+01 1.02470322e+01 1.02470217e+01 1.02469978e+01 1.02470436e+01 1.02470350e+01 1.02470293e+01 1.02470150e+01 1.02470446e+01 1.02470608e+01 1.02470617e+01 1.02470369e+01 1.02470417e+01 1.02470627e+01 1.02470913e+01 1.02471313e+01 1.02470703e+01 1.02470236e+01 1.02470894e+01 1.02470961e+01 1.02470484e+01 1.02470055e+01 1.02470284e+01 1.02470160e+01 1.02470560e+01 1.02470598e+01 1.02470417e+01 1.02470427e+01 1.02470169e+01 1.02470741e+01 1.02470379e+01 1.02470541e+01 1.02470646e+01 1.02470932e+01 1.02470493e+01 1.02470169e+01 1.02470388e+01 1.02470245e+01 1.02470388e+01 1.02470379e+01 1.02470398e+01 1.02470322e+01 1.02470255e+01 1.02470207e+01 1.02470150e+01 1.02470551e+01 1.02470112e+01 1.02470341e+01 1.02470188e+01 1.02470665e+01 1.02470875e+01 1.02470589e+01 1.02470245e+01 1.02470102e+01 1.02470236e+01 1.02470179e+01 1.02470484e+01 1.02470818e+01 1.02471027e+01 1.02470770e+01 1.02470493e+01 1.02470570e+01 1.02470713e+01 1.02470665e+01 1.02470350e+01 1.02470636e+01 1.02470312e+01 1.02470474e+01 1.02470236e+01 1.02470779e+01 1.02470894e+01 1.02470217e+01 1.02470169e+01 1.02470160e+01 1.02470665e+01 1.02470684e+01 1.02470512e+01 1.02470264e+01 1.02470455e+01 1.02470703e+01 1.02470417e+01 1.02470512e+01 1.02470617e+01 1.02470903e+01 1.02470407e+01 1.02470818e+01 1.02470665e+01 1.02470407e+01 1.02470703e+01 1.02470608e+01 1.02470465e+01 1.02470331e+01 1.02470369e+01 1.02470465e+01 1.02470226e+01 1.02470360e+01 1.02470264e+01 1.02470331e+01 1.02470140e+01 1.02470264e+01 1.02470636e+01 1.02470474e+01 1.02470322e+01 1.02470570e+01 1.02470388e+01 1.02470312e+01 1.02470837e+01 1.02471943e+01 1.02472019e+01 1.02470474e+01 1.02471294e+01 1.02472935e+01 1.02471390e+01 1.02470942e+01 1.02470522e+01 1.02470551e+01 1.02471209e+01 1.02470570e+01 1.02470589e+01 1.02470112e+01 1.02470312e+01 1.02471418e+01 1.02471952e+01 1.02471209e+01 1.02470264e+01 1.02471151e+01 1.02470684e+01 1.02470188e+01 1.02470446e+01 1.02470198e+01 1.02471132e+01 1.02471218e+01 1.02470694e+01 1.02470484e+01 1.02469988e+01 1.02470522e+01 1.02470932e+01 1.02470512e+01 1.02470398e+01 1.02470169e+01 1.02470255e+01 1.02470274e+01 1.02470970e+01 1.02471933e+01 1.02471228e+01 1.02470360e+01 1.02470303e+01 1.02470350e+01 1.02470322e+01 1.02471228e+01 1.02471189e+01 1.02470379e+01 1.02471075e+01 1.02471304e+01 1.02470350e+01 1.02470264e+01 1.02470455e+01 1.02470236e+01 1.02470503e+01 1.02470055e+01 1.02470284e+01 1.02470732e+01 1.02470722e+01 1.02470922e+01 1.02470560e+01 1.02470531e+01 1.02470303e+01 1.02470303e+01 1.02470675e+01 1.02470427e+01 1.02470436e+01 1.02470655e+01 1.02471123e+01 1.02471008e+01 1.02470140e+01 1.02470570e+01 1.02470827e+01 1.02470398e+01 1.02470579e+01 1.02470121e+01 1.02470388e+01 1.02471342e+01 1.02470980e+01 1.02470589e+01 1.02470140e+01 1.02470360e+01 1.02470675e+01 1.02470474e+01 1.02470427e+01 1.02470369e+01 1.02470312e+01 1.02471075e+01 1.02472038e+01 1.02471304e+01 1.02470360e+01 1.02470751e+01 1.02470541e+01 1.02470560e+01 1.02471466e+01 1.02470388e+01 1.02470465e+01 1.02470694e+01 1.02470236e+01 1.02470274e+01 1.02469921e+01 1.02470207e+01 1.02470446e+01 1.02470284e+01 1.02470474e+01 1.02470026e+01 1.02470293e+01 1.02470427e+01 1.02470322e+01 1.02470407e+01 1.02470055e+01 1.02470293e+01 1.02470284e+01 1.02470274e+01 1.02470255e+01 1.02471027e+01 1.02470608e+01 1.02470617e+01 1.02471237e+01 1.02471409e+01 1.02470303e+01 1.02470465e+01 1.02471056e+01 1.02470503e+01 1.02470427e+01 1.02469950e+01 1.02470045e+01 1.02470236e+01 1.02470579e+01 1.02470465e+01 1.02470322e+01 1.02470875e+01 1.02470751e+01 1.02470112e+01 1.02470837e+01 1.02471027e+01 1.02470770e+01 1.02470379e+01 1.02471018e+01 1.02470932e+01 1.02470312e+01 1.02470942e+01 1.02470627e+01 1.02470179e+01 1.02470694e+01 1.02470188e+01 1.02470579e+01 1.02470913e+01 1.02470608e+01 1.02470789e+01 1.02470789e+01 1.02470770e+01 1.02470760e+01 1.02470474e+01 1.02470369e+01 1.02469959e+01 1.02470074e+01 1.02470608e+01 1.02470503e+01 1.02470245e+01 1.02470036e+01 1.02470760e+01 1.02470160e+01 1.02470245e+01 1.02470293e+01 1.02470541e+01 1.02470942e+01 1.02470570e+01 1.02471046e+01 1.02470808e+01 1.02470083e+01 1.02470303e+01 1.02470932e+01 1.02470579e+01 1.02470922e+01 1.02470999e+01 1.02470551e+01 1.02470560e+01 1.02470255e+01 1.02470245e+01 1.02469978e+01 1.02470121e+01 1.02470226e+01 1.02470531e+01 1.02470541e+01 1.02470398e+01 1.02470179e+01 1.02470312e+01 1.02470455e+01 1.02470131e+01 1.02470579e+01 1.02471285e+01 1.02471161e+01 1.02470512e+01 1.02470198e+01 1.02470150e+01 1.02470837e+01 1.02471676e+01 1.02471132e+01 1.02470617e+01 1.02469931e+01 1.02470102e+01 1.02470226e+01 1.02470493e+01 1.02470503e+01 1.02470427e+01 1.02470474e+01 1.02470798e+01 1.02470312e+01 1.02470531e+01 1.02471685e+01 1.02471199e+01 1.02470551e+01 1.02470417e+01 1.02470617e+01 1.02470255e+01 1.02470760e+01 1.02470579e+01 1.02470417e+01 1.02470226e+01 1.02470093e+01 1.02470121e+01 1.02470455e+01 1.02470665e+01 1.02471008e+01 1.02471027e+01 1.02470732e+01 1.02471066e+01 1.02470636e+01 1.02470427e+01 1.02470474e+01 1.02470427e+01 1.02470675e+01 1.02470236e+01 1.02470379e+01 1.02470074e+01 1.02470169e+01 1.02471066e+01 1.02470856e+01 1.02470818e+01 1.02469988e+01 1.02470360e+01 1.02470474e+01 1.02470512e+01 1.02470989e+01 1.02470722e+01 1.02469997e+01 1.02470598e+01 1.02470827e+01 1.02470522e+01 1.02470226e+01 1.02470179e+01 1.02470341e+01 1.02470560e+01 1.02470970e+01 1.02470274e+01 1.02470293e+01 1.02470493e+01 1.02470398e+01 1.02470751e+01 1.02475481e+01 1.02473888e+01 1.02589054e+01 1.02782965e+01 1.05796013e+01 1.66152954e+01 3.49396019e+01 634051904. 22391922. 16369420. -1479806848. 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. 0. 0. 0. 0. 0. 0. 0. 1111368064. 1.01986542e+02 3.54055634e+01 1.54324293e+01 1.24179163e+01 1.02681065e+01 1.02510471e+01 1.02476826e+01 1.02485399e+01 1.02470121e+01 1.02470150e+01 1.02470493e+01 1.02470503e+01 1.02470350e+01 1.02470236e+01 1.02470169e+01 1.02470293e+01 1.02470551e+01 1.02470598e+01 1.02470369e+01 1.02470179e+01 1.02470417e+01 1.02470407e+01 1.02470484e+01 1.02470217e+01 1.02470350e+01 1.02470274e+01 1.02470589e+01 1.02470045e+01 1.02470455e+01 1.02470427e+01 1.02470884e+01 1.02470837e+01 1.02470169e+01 1.02469902e+01 1.02469826e+01 1.02470522e+01 1.02470512e+01 1.02470560e+01 1.02470198e+01 1.02470303e+01 1.02470388e+01 1.02470484e+01 1.02470484e+01 1.02470245e+01 1.02470827e+01 1.02472124e+01 1.02471485e+01 1.02470169e+01 1.02472448e+01 1.02472820e+01 1.02470341e+01 1.02470465e+01 1.02470255e+01 1.02470274e+01 1.02470522e+01 1.02470646e+01 1.02470484e+01 1.02470179e+01 1.02469931e+01 1.02470140e+01 1.02470531e+01 1.02470751e+01 1.02470856e+01 1.02471247e+01 1.02471075e+01 1.02470560e+01 1.02470703e+01 1.02470675e+01 1.02470579e+01 1.02470751e+01 1.02471809e+01 1.02472839e+01 1.02472887e+01 1.02471495e+01 1.02470627e+01 1.02471142e+01 1.02470579e+01 1.02469940e+01 1.02470741e+01 1.02470989e+01 1.02470694e+01 1.02470446e+01 1.02470655e+01 1.02470188e+01 1.02470322e+01 1.02470188e+01 1.02470493e+01 1.02470446e+01 1.02470579e+01 1.02470436e+01 1.02470560e+01 1.02471094e+01 1.02472219e+01 1.02471466e+01 1.02470388e+01 1.02470598e+01 1.02470579e+01 1.02470551e+01 1.02470074e+01 1.02470226e+01 1.02470551e+01 1.02470589e+01 1.02470264e+01 1.02470512e+01 1.02470856e+01 1.02470608e+01 1.02470474e+01 1.02470808e+01 1.02470436e+01 1.02470827e+01 1.02470865e+01 1.02470798e+01 1.02470646e+01 1.02470331e+01 1.02470436e+01 1.02470570e+01 1.02470636e+01 1.02470360e+01 1.02469988e+01 1.02470217e+01 1.02471333e+01 1.02471218e+01 1.02470446e+01 1.02470636e+01 1.02470732e+01 1.02470541e+01 1.02470484e+01 1.02469931e+01 1.02470217e+01 1.02470675e+01 1.02470551e+01 1.02471037e+01 1.02471752e+01 1.02471352e+01 1.02470436e+01 1.02470312e+01 1.02470570e+01 1.02470455e+01 1.02470360e+01 1.02470331e+01 1.02470245e+01 1.02470474e+01 1.02470503e+01 1.02470245e+01 1.02470303e+01 1.02470675e+01 1.02470884e+01 1.02471285e+01 1.02470598e+01 1.02470560e+01 1.02471056e+01 1.02471142e+01 1.02470379e+01 1.02470217e+01 1.02470589e+01 1.02470760e+01 1.02470407e+01 1.02470598e+01 1.02470160e+01 1.02470646e+01 1.02471409e+01 1.02471609e+01 1.02470846e+01 1.02470636e+01 1.02470665e+01 1.02471266e+01 1.02470446e+01 1.02470274e+01 1.02470503e+01 1.02471037e+01 1.02470388e+01 1.02470379e+01 1.02470121e+01 1.02470188e+01 1.02470350e+01 1.02470522e+01 1.02470560e+01 1.02470465e+01 1.02470217e+01 1.02470140e+01 1.02470255e+01 1.02470493e+01 1.02470484e+01 1.02470407e+01 1.02470255e+01 1.02470322e+01 1.02470722e+01 1.02470999e+01 1.02472229e+01 1.02473106e+01 1.02473011e+01 1.02470560e+01 1.02470150e+01 1.02470150e+01 1.02470179e+01 1.02470570e+01 1.02470484e+01 1.02470188e+01 1.02470675e+01 1.02470598e+01 1.02470646e+01 1.02470951e+01 1.02470970e+01 1.02470446e+01 1.02470808e+01 1.02471561e+01 1.02471352e+01 1.02470827e+01 1.02470579e+01 1.02470694e+01 1.02471008e+01 1.02470741e+01 1.02470675e+01 1.02469902e+01 1.02470160e+01 1.02470331e+01 1.02471981e+01 1.02471762e+01 1.02470522e+01 1.02470341e+01 1.02470303e+01 1.02470112e+01 1.02470140e+01 1.02470875e+01 1.02471342e+01 1.02470818e+01 1.02470407e+01 1.02470760e+01 1.02470522e+01 1.02470112e+01 1.02470093e+01 1.02470694e+01 1.02470074e+01 1.02470360e+01 1.02470036e+01 1.02470484e+01 1.02469912e+01 1.02469950e+01 1.02469902e+01 1.02470598e+01 1.02470589e+01 1.02470512e+01 1.02470045e+01 1.02469940e+01 1.02469893e+01 1.02470484e+01 1.02470570e+01 1.02470474e+01 1.02470007e+01 1.02470245e+01 1.02470255e+01 1.02470446e+01 1.02470264e+01 1.02470551e+01 1.02470331e+01 1.02470388e+01 1.02470303e+01 1.02470446e+01 1.02470322e+01 1.02469816e+01 1.02470026e+01 1.02470198e+01 1.02470312e+01 1.02470350e+01 1.02470217e+01 1.02470121e+01 1.02470341e+01 1.02469950e+01 1.02470398e+01 1.02469997e+01 1.02470398e+01 1.02470016e+01 1.02470121e+01 1.02469959e+01 1.02470598e+01 1.02470531e+01 1.02470369e+01 1.02469978e+01 1.02470007e+01 1.02469978e+01 1.02470465e+01 1.02470512e+01 1.02470407e+01 1.02469997e+01 1.02470064e+01 1.02469921e+01 1.02470484e+01 1.02470102e+01 1.02470455e+01 1.02469873e+01 1.02470455e+01 1.02470169e+01 1.02470293e+01 1.02470245e+01 1.02469769e+01 1.02470388e+01 1.02470837e+01 1.02470922e+01 1.02470570e+01 1.02470188e+01 1.02470150e+01 1.02470026e+01 1.02469759e+01 1.02470131e+01 1.02470284e+01 1.02470570e+01 1.02470293e+01 1.02470055e+01 1.02469883e+01 1.02470493e+01 1.02470350e+01 1.02470474e+01 1.02470102e+01 1.02470007e+01 1.02470007e+01 1.02470474e+01 1.02470407e+01 1.02470455e+01 1.02470179e+01 1.02470255e+01 1.02470179e+01 1.02470551e+01 1.02470055e+01 1.02470264e+01 1.02469883e+01 1.02470570e+01 1.02470293e+01 1.02470522e+01 1.02469978e+01 1.02470121e+01 1.02469864e+01 1.02470350e+01 1.02469950e+01 1.02470579e+01 1.02470198e+01 1.02470102e+01 1.02470131e+01 1.02469721e+01 1.02470074e+01 1.02470150e+01 1.02470503e+01 1.02470264e+01 1.02470007e+01 1.02470102e+01 1.02470694e+01 1.02470989e+01 1.02470942e+01 1.02470312e+01 1.02470226e+01 1.02470245e+01 1.02470798e+01 1.02470541e+01 1.02470503e+01 1.02470274e+01 1.02470160e+01 1.02470427e+01 1.02471237e+01 1.02470589e+01 1.02470608e+01 1.02470026e+01 1.02470226e+01 1.02470341e+01 1.02471218e+01 1.02470198e+01 1.02470417e+01 1.02470570e+01 1.02470474e+01 1.02470150e+01 1.02470531e+01 1.02469969e+01 1.02470274e+01 1.02470055e+01 1.02470484e+01 1.02470074e+01 1.02470436e+01 1.02470694e+01 1.02470837e+01 1.02470503e+01 1.02470484e+01 1.02470102e+01 1.02470188e+01 1.02470388e+01 1.02470446e+01 1.02469864e+01 1.02469997e+01 1.02470217e+01 1.02470856e+01 1.02470436e+01 1.02470179e+01 1.02470026e+01 1.02470341e+01 1.02470560e+01 1.02470484e+01 1.02470407e+01 1.02469997e+01 1.02470102e+01 1.02470188e+01 1.02470646e+01 1.02470379e+01 1.02470436e+01 1.02469997e+01 1.02470446e+01 1.02470169e+01 1.02470598e+01 1.02470713e+01 1.02470551e+01 1.02470436e+01 1.02470350e+01 1.02470150e+01 1.02470484e+01 1.02470045e+01 1.02470522e+01 1.02470322e+01 1.02470312e+01 1.02470160e+01 1.02470312e+01 1.02470446e+01 1.02470484e+01 1.02470093e+01 1.02470350e+01 1.02470160e+01 1.02470636e+01 1.02470407e+01 1.02470369e+01 1.02470036e+01 1.02470331e+01 1.02470245e+01 1.02470598e+01 1.02470284e+01 1.02470398e+01 1.02470398e+01 1.02470331e+01 1.02470436e+01 1.02470274e+01 1.02470322e+01 1.02470007e+01 1.02470388e+01 1.02470188e+01 1.02470541e+01 1.02470121e+01 1.02470312e+01 1.02469902e+01 1.02470512e+01 1.02469950e+01 1.02470446e+01 1.02470198e+01 1.02470369e+01 1.02470284e+01 1.02469988e+01 1.02470379e+01 1.02470369e+01 1.02470579e+01 1.02470655e+01 1.02470083e+01 1.02470160e+01 1.02473402e+01 1.02475090e+01 1.02482929e+01 1.02472067e+01 1.02509499e+01 1.03350525e+01 1.55993166e+01 1.35801306e+01 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. 0. 0. 0. 0. 0. 0. -9.16319733e+01 3.37829208e+01 1.59612732e+01 1.27789087e+01 1.03653278e+01 1.02754316e+01 1.02527018e+01 1.02473230e+01 1.02481146e+01 1.02470617e+01 1.02470398e+01 1.02470465e+01 1.02470827e+01 1.02470942e+01 1.02470646e+01 1.02470446e+01 1.02470512e+01 1.02470646e+01 1.02470503e+01 1.02470531e+01 1.02470407e+01 1.02470427e+01 1.02470322e+01 1.02470541e+01 1.02470589e+01 1.02470636e+01 1.02470093e+01 1.02470236e+01 1.02470331e+01 1.02470522e+01 1.02470474e+01 1.02470436e+01 1.02470388e+01 1.02470217e+01 1.02470360e+01 1.02470379e+01 1.02470360e+01 1.02470236e+01 1.02470055e+01 1.02470179e+01 1.02470293e+01 1.02470484e+01 1.02470245e+01 1.02470255e+01 1.02470264e+01 1.02470303e+01 1.02470293e+01 1.02470436e+01 1.02470407e+01 1.02470198e+01 1.02470560e+01 1.02470331e+01 1.02470579e+01 1.02470245e+01 1.02470493e+01 1.02470417e+01 1.02470007e+01 1.02470207e+01 1.02470264e+01 1.02470665e+01 1.02470360e+01 1.02470303e+01 1.02470512e+01 1.02469940e+01 1.02470331e+01 1.02470350e+01 1.02470541e+01 1.02470169e+01 1.02470465e+01 1.02470932e+01 1.02470942e+01 1.02470579e+01 1.02470360e+01 1.02470350e+01 1.02470303e+01 1.02470379e+01 1.02470770e+01 1.02471333e+01 1.02471542e+01 1.02470627e+01 1.02470417e+01 1.02469997e+01 1.02470531e+01 1.02470312e+01 1.02470341e+01 1.02470522e+01 1.02470865e+01 1.02471590e+01 1.02470751e+01 1.02470837e+01 1.02470341e+01 1.02470245e+01 1.02470102e+01 1.02470474e+01 1.02470722e+01 1.02470541e+01 1.02470284e+01 1.02470026e+01 1.02470531e+01 1.02470560e+01 1.02470732e+01 1.02470665e+01 1.02470303e+01 1.02470427e+01 1.02470493e+01 1.02470541e+01 1.02470131e+01 1.02470503e+01 1.02470312e+01 1.02470360e+01 1.02470417e+01 1.02470522e+01 1.02470551e+01 1.02470398e+01 1.02470484e+01 1.02470789e+01 1.02470531e+01 1.02470016e+01 1.02470188e+01 1.02470245e+01 1.02470627e+01 1.02470465e+01 1.02470160e+01 1.02470303e+01 1.02469854e+01 1.02470274e+01 1.02470226e+01 1.02470531e+01 1.02470303e+01 1.02470140e+01 1.02470751e+01 1.02470913e+01 1.02470665e+01 1.02470303e+01 1.02470074e+01 1.02470512e+01 1.02470922e+01 1.02471180e+01 1.02470865e+01 1.02470675e+01 1.02470570e+01 1.02470407e+01 1.02470064e+01 1.02470102e+01 1.02470274e+01 1.02470770e+01 1.02470455e+01 1.02470121e+01 1.02470112e+01 1.02469997e+01 1.02470427e+01 1.02469931e+01 1.02470160e+01 1.02470360e+01 1.02470655e+01 1.02471304e+01 1.02470846e+01 1.02470675e+01 1.02470379e+01 1.02470264e+01 1.02470741e+01 1.02471104e+01 1.02471523e+01 1.02471514e+01 1.02471876e+01 1.02471266e+01 1.02470827e+01 1.02470274e+01 1.02470226e+01 1.02470074e+01 1.02470560e+01 1.02470274e+01 1.02470236e+01 1.02470331e+01 1.02470255e+01 1.02470636e+01 1.02470427e+01 1.02470379e+01 1.02470913e+01 1.02470636e+01 1.02470360e+01 1.02470016e+01 1.02470226e+01 1.02470312e+01 1.02470551e+01 1.02470388e+01 1.02469978e+01 1.02470121e+01 1.02470608e+01 1.02470560e+01 1.02470551e+01 1.02470427e+01 1.02470131e+01 1.02470417e+01 1.02469988e+01 1.02470474e+01 1.02470255e+01 1.02470226e+01 1.02470360e+01 1.02470026e+01 1.02470512e+01 1.02470284e+01 1.02470388e+01 1.02470484e+01 1.02470293e+01 1.02470503e+01 1.02470121e+01 1.02470293e+01 1.02470303e+01 1.02470665e+01 1.02470579e+01 1.02470322e+01 1.02469912e+01 1.02470150e+01 1.02470303e+01 1.02470570e+01 1.02470388e+01 1.02470102e+01 1.02470160e+01 1.02470093e+01 1.02470531e+01 1.02470417e+01 1.02470531e+01 1.02470427e+01 1.02470007e+01 1.02470198e+01 1.02470255e+01 1.02470484e+01 1.02470484e+01 1.02470112e+01 1.02470341e+01 1.02470255e+01 1.02470675e+01 1.02470207e+01 1.02470398e+01 1.02470474e+01 1.02470589e+01 1.02470255e+01 1.02470293e+01 1.02470360e+01 1.02470655e+01 1.02470407e+01 1.02469921e+01 1.02470016e+01 1.02470179e+01 1.02470627e+01 1.02470827e+01 1.02470512e+01 1.02470407e+01 1.02470045e+01 1.02470751e+01 1.02470388e+01 1.02470360e+01 1.02470322e+01 1.02470694e+01 1.02470989e+01 1.02470436e+01 1.02470503e+01 1.02470484e+01 1.02470398e+01 1.02470360e+01 1.02470388e+01 1.02470036e+01 1.02470255e+01 1.02470064e+01 1.02470636e+01 1.02470360e+01 1.02470245e+01 1.02470121e+01 1.02470112e+01 1.02470608e+01 1.02470455e+01 1.02470465e+01 1.02470226e+01 1.02470121e+01 1.02470484e+01 1.02470484e+01 1.02470865e+01 1.02470627e+01 1.02470856e+01 1.02470827e+01 1.02470455e+01 1.02470217e+01 1.02470264e+01 1.02470570e+01 1.02470560e+01 1.02470407e+01 1.02470093e+01 1.02470093e+01 1.02470255e+01 1.02470665e+01 1.02470379e+01 1.02470140e+01 1.02470264e+01 1.02470064e+01 1.02470379e+01 1.02470217e+01 1.02470379e+01 1.02470837e+01 1.02470655e+01 1.02470779e+01 1.02470284e+01 1.02470465e+01 1.02470064e+01 1.02470255e+01 1.02470322e+01 1.02470284e+01 1.02470284e+01 1.02470541e+01 1.02470694e+01 1.02470570e+01 1.02470379e+01 1.02470093e+01 1.02470369e+01 1.02470198e+01 1.02470484e+01 1.02470284e+01 1.02470121e+01 1.02470360e+01 1.02470083e+01 1.02470570e+01 1.02470131e+01 1.02470293e+01 1.02470293e+01 1.02470522e+01 1.02471113e+01 1.02470846e+01 1.02470255e+01 1.02470398e+01 1.02470484e+01 1.02470884e+01 1.02470522e+01 1.02470751e+01 1.02469950e+01 1.02470150e+01 1.02470388e+01 1.02470493e+01 1.02470264e+01 1.02470007e+01 1.02470112e+01 1.02470560e+01 1.02470446e+01 1.02470598e+01 1.02471008e+01 1.02471123e+01 1.02470837e+01 1.02470131e+01 1.02470341e+01 1.02470875e+01 1.02471638e+01 1.02471142e+01 1.02470045e+01 1.02469931e+01 1.02470140e+01 1.02470341e+01 1.02470894e+01 1.02470846e+01 1.02470570e+01 1.02470083e+01 1.02470551e+01 1.02470617e+01 1.02470694e+01 1.02470074e+01 1.02470255e+01 1.02469854e+01 1.02470427e+01 1.02470217e+01 1.02470198e+01 1.02470150e+01 1.02469931e+01 1.02470455e+01 1.02470360e+01 1.02470446e+01 1.02470894e+01 1.02470493e+01 1.02470474e+01 1.02470112e+01 1.02470655e+01 1.02471609e+01 1.02470837e+01 1.02470512e+01 1.02470055e+01 1.02470140e+01 1.02470407e+01 1.02470465e+01 1.02470598e+01 1.02470331e+01 1.02470083e+01 1.02470303e+01 1.02470064e+01 1.02470474e+01 1.02469873e+01 1.02470007e+01 1.02470055e+01 1.02470217e+01 1.02470474e+01 1.02470245e+01 1.02470541e+01 1.02470722e+01 1.02470417e+01 1.02470646e+01 1.02470236e+01 1.02470531e+01 1.02470531e+01 1.02470398e+01 1.02470293e+01 1.02470646e+01 1.02470579e+01 1.02470112e+01 1.02470150e+01 1.02471504e+01 1.02470961e+01 1.02470551e+01 1.02470074e+01 1.02470541e+01 1.02470646e+01 1.02470484e+01 1.02470064e+01 1.02470245e+01 1.02470112e+01 1.02470360e+01 1.02470007e+01 1.02470284e+01 1.02470322e+01 1.02470531e+01 1.02470951e+01 1.02470341e+01 1.02470198e+01 1.02470722e+01 1.02470427e+01 1.02470465e+01 1.02470388e+01 1.02470026e+01 1.02469864e+01 1.02469912e+01 1.02470579e+01 1.02470617e+01 1.02470236e+01 1.02470169e+01 1.02470007e+01 1.02470455e+01 1.02470350e+01 1.02470589e+01 1.02470951e+01 1.02470379e+01 1.02470360e+01 1.02470770e+01 1.02470503e+01 1.02470360e+01 1.02470446e+01 1.02470598e+01 1.02470570e+01 1.02470531e+01 1.02470484e+01 1.02470388e+01 1.02470675e+01 1.02470551e+01 1.02470312e+01 1.02470417e+01 1.02469826e+01 1.02470474e+01 1.02470274e+01 1.02470617e+01 1.02470016e+01 1.02470074e+01 1.02470207e+01 1.02470608e+01 1.02470417e+01 1.02470198e+01 1.02470369e+01 1.02470770e+01 1.02470293e+01 1.02470245e+01 1.02470894e+01 1.02471275e+01 1.02470913e+01 1.02470617e+01 1.02471390e+01 1.02470913e+01 1.02470627e+01 1.02470331e+01 1.02470322e+01 1.02470198e+01 1.02470312e+01 1.02470999e+01 1.02471285e+01 1.02470312e+01 1.02470064e+01 1.02470169e+01 1.02470961e+01 1.02471123e+01 1.02470112e+01 1.02470045e+01 1.02470369e+01 1.02470369e+01 1.02471075e+01 1.02471924e+01 1.02470760e+01 1.02469959e+01 1.02470207e+01 1.02471104e+01 1.02471323e+01 1.02470522e+01 1.02470484e+01 1.02470989e+01 1.02471409e+01 1.02471018e+01 1.02470112e+01 1.02469940e+01 1.02470255e+01 1.02471008e+01 1.02470903e+01 1.02470417e+01 1.02470703e+01 1.02470646e+01 1.02470570e+01 1.02470293e+01 1.02470293e+01 1.02470350e+01 1.02470407e+01 1.02471256e+01 1.02470884e+01 1.02470264e+01 1.02470226e+01 1.02470293e+01 1.02470169e+01 1.02470150e+01 1.02470589e+01 1.02470942e+01 1.02470255e+01 1.02470474e+01 1.02470350e+01 1.02470503e+01 1.02470398e+01 1.02469978e+01 1.02470217e+01 1.02470284e+01 1.02470245e+01 1.02470160e+01 1.02470055e+01 1.02470427e+01 1.02470064e+01 1.02470531e+01 1.02471018e+01 1.02471132e+01 1.02470827e+01 1.02470350e+01 1.02471027e+01 1.02470741e+01 1.02470627e+01 1.02470398e+01 1.02470350e+01 1.02470684e+01 1.02470531e+01 1.02470598e+01 1.02470579e+01 1.02470150e+01 1.02470121e+01 1.02470160e+01 1.02470770e+01 1.02470894e+01 1.02470207e+01 1.02470188e+01 1.02470484e+01 1.02470436e+01 1.02470274e+01 1.02470112e+01 1.02470198e+01 1.02470198e+01 1.02470560e+01 1.02470341e+01 1.02470531e+01 1.02470236e+01 1.02470093e+01 1.02470388e+01 1.02470732e+01 1.02470570e+01 1.02469931e+01 1.02470007e+01 1.02470245e+01 1.02470617e+01 1.02471085e+01 1.02470665e+01 1.02470713e+01 1.02470102e+01 1.02470350e+01 1.02470398e+01 1.02470284e+01 1.02470407e+01 1.02470045e+01 1.02470436e+01 1.02470245e+01 1.02470217e+01 1.02470150e+01 1.02470207e+01 1.02470636e+01 1.02470341e+01 1.02470160e+01 1.02470837e+01 1.02470160e+01 1.02470512e+01 1.02470236e+01 1.02470465e+01 1.02470236e+01 1.02470007e+01 1.02470226e+01 1.02470179e+01 1.02470732e+01 1.02471695e+01 1.02485590e+01 1.02545967e+01 1.02633028e+01 1.03137636e+01 1.03029385e+01 1.49675484e+01 2.89928017e+01 16906696. 18379446. 0. 0. 0. 0. 0. -550760512. -229551168. 56548068. -163830784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -475582080. -811008576. 1.47004822e+02 6.79621887e+01 4.51879463e+01 4.43828201e+01 4.43369370e+01 4.43152466e+01 4.43136711e+01 4.43137894e+01 4.43142700e+01 4.43144951e+01 4.43141556e+01 4.43139954e+01 4.43138123e+01 4.43139343e+01 4.43138390e+01 4.43136559e+01 4.43137703e+01 4.43141632e+01 4.43145332e+01 4.43141441e+01 4.43141594e+01 4.43142548e+01 4.43141975e+01 4.43140182e+01 4.43141632e+01 4.43138771e+01 4.43136673e+01 4.43138771e+01 4.43141441e+01 4.43141365e+01 4.43144264e+01 4.43147278e+01 4.43139610e+01 4.43138161e+01 4.43138771e+01 4.43139420e+01 4.43140068e+01 4.43140869e+01 4.43142509e+01 4.43139648e+01 4.43138123e+01 4.43137054e+01 4.43137741e+01 4.43142052e+01 4.43140984e+01 4.43136673e+01 4.43138123e+01 4.43138084e+01 4.43138123e+01 4.43137970e+01 4.43135757e+01 4.43139076e+01 4.43139343e+01 4.43143463e+01 4.43139992e+01 4.43141747e+01 4.43142433e+01 4.43136826e+01 4.43139191e+01 4.43138504e+01 4.43138618e+01 4.43138924e+01 4.43138733e+01 4.43140755e+01 4.43140335e+01 4.43137169e+01 4.43137970e+01 4.43136024e+01 4.43143044e+01 4.43140450e+01 4.43138885e+01 4.43137665e+01 4.43138123e+01 4.43141289e+01 4.43139229e+01 4.43136444e+01 4.43136482e+01 4.43139076e+01 4.43142204e+01 4.43140945e+01 4.43140030e+01 4.43140030e+01 4.43139267e+01 4.43138771e+01 4.43139305e+01 4.43137856e+01 4.43137321e+01 4.43141518e+01 4.43144951e+01 4.43140907e+01 4.43140907e+01 4.43141899e+01 4.43138657e+01 4.43139992e+01 4.43143311e+01 4.43139153e+01 4.43138885e+01 4.43140068e+01 4.43142281e+01 4.43140297e+01 4.43136292e+01 4.43137321e+01 4.43138618e+01 4.43141327e+01 4.43140297e+01 4.43140907e+01 4.43141518e+01 4.43140297e+01 4.43137016e+01 4.43138542e+01 4.43139000e+01 4.43138847e+01 4.43139191e+01 4.43140526e+01 4.43140678e+01 4.43139763e+01 4.43137474e+01 4.43138199e+01 4.43143272e+01 4.43145943e+01 4.43142471e+01 4.43139572e+01 4.43139915e+01 4.43139915e+01 4.43140182e+01 4.43138618e+01 4.43136864e+01 4.43138123e+01 4.43142624e+01 4.43144455e+01 4.43142319e+01 4.43139191e+01 4.43139153e+01 4.43138237e+01 4.43140984e+01 4.43142433e+01 4.43139725e+01 4.43138771e+01 4.43136520e+01 4.43142624e+01 4.43138237e+01 4.43141441e+01 4.43141022e+01 4.43140373e+01 4.43139572e+01 4.43139801e+01 4.43136940e+01 4.43137932e+01 4.43137169e+01 4.43141174e+01 4.43140068e+01 4.43140335e+01 4.43136673e+01 4.43138123e+01 4.43139610e+01 4.43141823e+01 4.43137703e+01 4.43135719e+01 4.43138466e+01 4.43144417e+01 4.43142166e+01 4.43136520e+01 4.43137817e+01 4.43136711e+01 4.43140144e+01 4.43139992e+01 4.43142433e+01 4.43144722e+01 4.43136368e+01 4.43139229e+01 4.43139763e+01 4.43140259e+01 4.43140221e+01 4.43139343e+01 4.43141785e+01 4.43139000e+01 4.43138008e+01 4.43137741e+01 4.43139381e+01 4.43142548e+01 4.43141289e+01 4.43137779e+01 4.43133698e+01 4.43138885e+01 4.43139000e+01 4.43142281e+01 4.43134956e+01 4.43137360e+01 4.43138351e+01 4.43142242e+01 4.43143349e+01 4.43145943e+01 4.43142128e+01 4.43138046e+01 4.43141022e+01 4.43144989e+01 4.43139610e+01 4.43139763e+01 4.43138466e+01 4.43140945e+01 4.43138924e+01 4.43136673e+01 4.43137360e+01 4.43139381e+01 4.43143845e+01 4.43142929e+01 4.43141060e+01 4.43138313e+01 4.43139229e+01 4.43138809e+01 4.43141708e+01 4.43142662e+01 4.43140068e+01 4.43140335e+01 4.43139114e+01 4.43141365e+01 4.43141441e+01 4.43139954e+01 4.43139915e+01 4.43138924e+01 4.43140678e+01 4.43138733e+01 4.43139420e+01 4.43139076e+01 4.43140144e+01 4.43142090e+01 4.43136139e+01 4.43138695e+01 4.43138618e+01 4.43139572e+01 4.43142471e+01 4.43135185e+01 4.43139381e+01 4.43137360e+01 4.43141861e+01 4.43140945e+01 4.43136635e+01 4.43138123e+01 4.43136177e+01 4.43142090e+01 4.43138275e+01 4.43142242e+01 4.43137550e+01 4.43137207e+01 4.43137932e+01 4.43138924e+01 4.43139458e+01 4.43134346e+01 4.43139534e+01 4.43138428e+01 4.43142471e+01 4.43139229e+01 4.43140068e+01 4.43140068e+01 4.43142815e+01 4.43139610e+01 4.43136101e+01 4.43138542e+01 4.43138771e+01 4.43141785e+01 4.43140068e+01 4.43137512e+01 4.43138580e+01 4.43134918e+01 4.43141060e+01 4.43138008e+01 4.43139648e+01 4.43135834e+01 4.43136559e+01 4.43138580e+01 4.43137589e+01 4.43138084e+01 4.43133926e+01 4.43140030e+01 4.43138428e+01 4.43142281e+01 4.43137703e+01 4.43140373e+01 4.43136253e+01 4.43137207e+01 4.43136520e+01 4.43136559e+01 4.43140106e+01 4.43135948e+01 4.43139038e+01 4.43141022e+01 4.43140335e+01 4.43140640e+01 4.43139458e+01 4.43138733e+01 4.43139877e+01 4.43139839e+01 4.43136940e+01 4.43138618e+01 4.43138618e+01 4.43141327e+01 4.43143120e+01 4.43139343e+01 4.43139420e+01 4.43138809e+01 4.43141098e+01 4.43135796e+01 4.43138428e+01 4.43138084e+01 4.43141327e+01 4.43139114e+01 4.43137054e+01 4.43138313e+01 4.43137360e+01 4.43142204e+01 4.43139725e+01 4.43138161e+01 4.43138351e+01 4.43136101e+01 4.43141708e+01 4.43140411e+01 4.43142242e+01 4.43137207e+01 4.43137016e+01 4.43138428e+01 4.43140793e+01 4.43137169e+01 4.43136215e+01 4.43138428e+01 4.43139877e+01 4.43142395e+01 4.43140488e+01 4.43145714e+01 4.43140907e+01 4.43141861e+01 4.43139381e+01 4.43136864e+01 4.43138618e+01 4.43136902e+01 4.43143578e+01 4.43139648e+01 4.43139381e+01 4.43140068e+01 4.43137741e+01 4.43142509e+01 4.43138657e+01 4.43140831e+01 4.43137665e+01 4.43139229e+01 4.43137436e+01 4.43139420e+01 4.43134460e+01 4.43136139e+01 4.43134880e+01 4.43138771e+01 4.43138771e+01 4.43138199e+01 4.43138199e+01 4.43137436e+01 4.43140030e+01 4.43139877e+01 4.43135033e+01 4.43137245e+01 4.43134537e+01 4.43143272e+01 4.43142128e+01 4.43140488e+01 4.43143997e+01 4.43144226e+01 4.43136749e+01 4.43135643e+01 4.43137131e+01 4.43140678e+01 4.43141212e+01 4.43135414e+01 4.43137741e+01 4.43135719e+01 4.43140373e+01 4.43141365e+01 4.43143616e+01 4.43142090e+01 4.43135681e+01 4.43137512e+01 4.43137894e+01 4.43141899e+01 4.43141785e+01 4.43136520e+01 4.43139648e+01 4.43134804e+01 4.43138771e+01 4.43137894e+01 4.43142509e+01 4.43141289e+01 4.43141289e+01 4.43136253e+01 4.43134575e+01 4.43136253e+01 4.43139725e+01 4.43143921e+01 4.43145828e+01 4.43144913e+01 4.43137550e+01 4.43136749e+01 4.43137321e+01 4.43138390e+01 4.43137550e+01 4.43133698e+01 4.43139076e+01 4.43138390e+01 4.43142776e+01 4.43142700e+01 4.43138580e+01 4.43139381e+01 4.43136406e+01 4.43136559e+01 4.43138123e+01 4.43141899e+01 4.43142242e+01 4.43141556e+01 4.43138657e+01 4.43141708e+01 4.43140564e+01 4.43141975e+01 4.43139229e+01 4.43135910e+01 4.43139076e+01 4.43135643e+01 4.43141022e+01 4.43140297e+01 4.43143539e+01 4.43142662e+01 4.43136826e+01 4.43138771e+01 4.43136177e+01 4.43139839e+01 4.43140678e+01 4.43138733e+01 4.43137970e+01 4.43135529e+01 4.43139687e+01 4.43140259e+01 4.43142776e+01 4.43141556e+01 4.43140144e+01 4.43136826e+01 4.43136368e+01 4.43138390e+01 4.43141441e+01 4.43143120e+01 4.43144569e+01 4.43145103e+01 4.43138123e+01 4.43137779e+01 4.43136597e+01 4.43140717e+01 4.43140602e+01 4.43136292e+01 4.43138733e+01 4.43134193e+01 4.43140869e+01 4.43138885e+01 4.43143196e+01 4.43139801e+01 4.43139458e+01 4.43136711e+01 4.43137627e+01 4.43138428e+01 4.43141899e+01 4.43140869e+01 4.43137589e+01 4.43138466e+01 4.43135529e+01 4.43140335e+01 4.43139153e+01 4.43138504e+01 4.43140144e+01 4.43139038e+01 4.43141327e+01 4.43136635e+01 4.43141708e+01 4.43141136e+01 4.43136253e+01 4.43140221e+01 4.43138962e+01 4.43140373e+01 4.43137283e+01 4.43137169e+01 4.43138046e+01 4.43134575e+01 4.43139305e+01 4.43138466e+01 4.43140182e+01 4.43142815e+01 4.43143692e+01 4.43137550e+01 4.43138428e+01 4.43138504e+01 4.43141060e+01 4.43140793e+01 4.43143387e+01 4.43141708e+01 4.43136711e+01 4.43139725e+01 4.43138504e+01 4.43141518e+01 4.43142471e+01 4.43137894e+01 4.43139114e+01 4.43135872e+01 4.43138809e+01 4.43137970e+01 4.43142548e+01 4.43140945e+01 4.43138351e+01 4.43135071e+01 4.43136902e+01 4.43138885e+01 4.43142319e+01 4.43140717e+01 4.43137169e+01 4.43137093e+01 4.43135109e+01 4.43140831e+01 4.43139610e+01 4.43139496e+01 4.43138809e+01 4.43135414e+01 4.43141136e+01 4.43138428e+01 4.43138466e+01 4.43140297e+01 4.43134804e+01 4.43140602e+01 4.43135147e+01 4.43137512e+01 4.43138046e+01 4.43142891e+01 4.43142319e+01 4.43139153e+01 4.43135147e+01 4.43137321e+01 4.43138771e+01 4.43139954e+01 4.43138733e+01 4.43136292e+01 4.43139038e+01 4.43136826e+01 4.43140297e+01 4.43136978e+01 4.43138161e+01 4.43137627e+01 4.43138580e+01 4.43144035e+01 4.43138695e+01 4.43140373e+01 4.43139114e+01 4.43138504e+01 4.43139191e+01 4.43137741e+01 4.43138504e+01 4.43138275e+01 4.43138847e+01 4.43140831e+01 4.43138962e+01 4.43136864e+01 4.43137131e+01 4.43139153e+01 4.43141975e+01 4.43142776e+01 4.43139305e+01 4.43138580e+01 4.43137054e+01 4.43140106e+01 4.43139381e+01 4.43142929e+01 4.43141174e+01 4.43137093e+01 4.43137550e+01 4.43134422e+01 4.43137627e+01 4.43139267e+01 4.43139954e+01 4.43140297e+01 4.43139305e+01 4.43136749e+01 4.43140106e+01 4.43140984e+01 4.43142319e+01 4.43141556e+01 4.43137436e+01 4.43138695e+01 4.43135567e+01 4.43140068e+01 4.43139153e+01 4.43140373e+01 4.43140259e+01 4.43136330e+01 4.43139229e+01 4.43137665e+01 4.43137589e+01 4.43138237e+01 4.43136215e+01 4.43139801e+01 4.43135185e+01 4.43138847e+01 4.43140297e+01 4.43140144e+01 4.43138008e+01 4.43135338e+01 4.43137970e+01 4.43137550e+01 4.43139038e+01 4.43140068e+01 4.43138237e+01 4.43146172e+01 4.43143959e+01 4.43136101e+01 4.43135948e+01 4.43137283e+01 4.43146057e+01 4.43336906e+01 4.43239517e+01 4.43309059e+01 5.40213623e+01 7.18576126e+01 1.55635284e+02 3.38393707e+02 246460512. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1111368064. 1.71005997e+02 6.62896194e+01 4.53358383e+01 4.47624474e+01 4.43370323e+01 4.43152695e+01 4.43145447e+01 4.43139839e+01 4.43141251e+01 4.43141403e+01 4.43138237e+01 4.43138199e+01 4.43140564e+01 4.43142014e+01 4.43143005e+01 4.43137054e+01 4.43137589e+01 4.43138046e+01 4.43142433e+01 4.43145981e+01 4.43145599e+01 4.43141518e+01 4.43137245e+01 4.43137894e+01 4.43142319e+01 4.43142014e+01 4.43139381e+01 4.43137970e+01 4.43139191e+01 4.43141861e+01 4.43138466e+01 4.43139763e+01 4.43140488e+01 4.43143005e+01 4.43143120e+01 4.43136520e+01 4.43136177e+01 4.43137665e+01 4.43141861e+01 4.43141899e+01 4.43137054e+01 4.43137856e+01 4.43137741e+01 4.43141212e+01 4.43140984e+01 4.43142014e+01 4.43140526e+01 4.43136444e+01 4.43141594e+01 4.43146439e+01 4.43137321e+01 4.43138657e+01 4.43138161e+01 4.43138123e+01 4.43138924e+01 4.43135529e+01 4.43139381e+01 4.43140335e+01 4.43141518e+01 4.43138618e+01 4.43139343e+01 4.43138466e+01 4.43144913e+01 4.43146782e+01 4.43144951e+01 4.43138390e+01 4.43135872e+01 4.43138275e+01 4.43139954e+01 4.43144531e+01 4.43146248e+01 4.43145332e+01 4.43146782e+01 4.43139763e+01 4.43143005e+01 4.43142853e+01 4.43142662e+01 4.43138885e+01 4.43138657e+01 4.43145981e+01 4.43138504e+01 4.43138847e+01 4.43139191e+01 4.43142815e+01 4.43142700e+01 4.43136253e+01 4.43136024e+01 4.43137169e+01 4.43141212e+01 4.43140907e+01 4.43140335e+01 4.43136520e+01 4.43138962e+01 4.43136444e+01 4.43139648e+01 4.43139763e+01 4.43139687e+01 4.43139305e+01 4.43135338e+01 4.43139648e+01 4.43139191e+01 4.43138504e+01 4.43137436e+01 4.43136368e+01 4.43142128e+01 4.43135567e+01 4.43138733e+01 4.43139763e+01 4.43141861e+01 4.43142128e+01 4.43138008e+01 4.43138390e+01 4.43139191e+01 4.43142090e+01 4.43141441e+01 4.43137321e+01 4.43135757e+01 4.43137131e+01 4.43137932e+01 4.43140144e+01 4.43139915e+01 4.43139305e+01 4.43139305e+01 4.43136520e+01 4.43141632e+01 4.43138199e+01 4.43139572e+01 4.43139114e+01 4.43139458e+01 4.43141479e+01 4.43136902e+01 4.43137436e+01 4.43140411e+01 4.43140907e+01 4.43141212e+01 4.43135872e+01 4.43137054e+01 4.43138542e+01 4.43140602e+01 4.43140297e+01 4.43136177e+01 4.43137016e+01 4.43138237e+01 4.43138428e+01 4.43140335e+01 4.43138275e+01 4.43137856e+01 4.43138733e+01 4.43137360e+01 4.43140755e+01 4.43139114e+01 4.43136978e+01 4.43138618e+01 4.43135147e+01 4.43141594e+01 4.43136902e+01 4.43138275e+01 4.43138428e+01 4.43139915e+01 4.43141365e+01 4.43140373e+01 4.43139572e+01 4.43139839e+01 4.43138733e+01 4.43141212e+01 4.43141022e+01 4.43137856e+01 4.43138504e+01 4.43137856e+01 4.43142433e+01 4.43139229e+01 4.43138962e+01 4.43139000e+01 4.43139038e+01 4.43139992e+01 4.43136711e+01 4.43136787e+01 4.43139038e+01 4.43142128e+01 4.43143158e+01 4.43137283e+01 4.43138275e+01 4.43138962e+01 4.43142204e+01 4.43140755e+01 4.43139954e+01 4.43138313e+01 4.43141518e+01 4.43143425e+01 4.43148308e+01 4.43149147e+01 4.43138618e+01 4.43138008e+01 4.43135376e+01 4.43139229e+01 4.43139153e+01 4.43136330e+01 4.43138390e+01 4.43136063e+01 4.43141556e+01 4.43136253e+01 4.43140907e+01 4.43140678e+01 4.43142929e+01 4.43142662e+01 4.43139458e+01 4.43140106e+01 4.43140640e+01 4.43141823e+01 4.43142662e+01 4.43136826e+01 4.43135910e+01 4.43136177e+01 4.43139076e+01 4.43141403e+01 4.43141937e+01 4.43141632e+01 4.43140030e+01 4.43135948e+01 4.43140373e+01 4.43141327e+01 4.43140373e+01 4.43142509e+01 4.43140488e+01 4.43142891e+01 4.43136826e+01 4.43138046e+01 4.43138771e+01 4.43142891e+01 4.43139191e+01 4.43140030e+01 4.43136101e+01 4.43138847e+01 4.43135338e+01 4.43137932e+01 4.43137703e+01 4.43140945e+01 4.43139877e+01 4.43140030e+01 4.43135681e+01 4.43136368e+01 4.43136406e+01 4.43140907e+01 4.43140755e+01 4.43141212e+01 4.43138046e+01 4.43137245e+01 4.43138123e+01 4.43140144e+01 4.43137703e+01 4.43138847e+01 4.43136787e+01 4.43141785e+01 4.43139763e+01 4.43140144e+01 4.43134384e+01 4.43137512e+01 4.43136978e+01 4.43138161e+01 4.43139610e+01 4.43138390e+01 4.43137894e+01 4.43138847e+01 4.43137779e+01 4.43138847e+01 4.43138771e+01 4.43134995e+01 4.43139458e+01 4.43136559e+01 4.43139000e+01 4.43135910e+01 4.43140144e+01 4.43138962e+01 4.43141479e+01 4.43136559e+01 4.43138123e+01 4.43137817e+01 4.43141098e+01 4.43140755e+01 4.43140068e+01 4.43137245e+01 4.43135948e+01 4.43137436e+01 4.43140869e+01 4.43138008e+01 4.43138695e+01 4.43135262e+01 4.43140564e+01 4.43136101e+01 4.43138962e+01 4.43134613e+01 4.43137283e+01 4.43136940e+01 4.43138351e+01 4.43139076e+01 4.43137436e+01 4.43136711e+01 4.43138351e+01 4.43134384e+01 4.43137016e+01 4.43137360e+01 4.43138237e+01 4.43140030e+01 4.43138771e+01 4.43136864e+01 4.43136444e+01 4.43137016e+01 4.43140488e+01 4.43140221e+01 4.43137321e+01 4.43137436e+01 4.43136253e+01 4.43140030e+01 4.43140984e+01 4.43140793e+01 4.43137283e+01 4.43136749e+01 4.43137093e+01 4.43140678e+01 4.43139534e+01 4.43138962e+01 4.43136444e+01 4.43140030e+01 4.43138733e+01 4.43140335e+01 4.43135719e+01 4.43138466e+01 4.43139076e+01 4.43141670e+01 4.43140564e+01 4.43140259e+01 4.43138161e+01 4.43139534e+01 4.43134422e+01 4.43137932e+01 4.43137932e+01 4.43138390e+01 4.43140297e+01 4.43139114e+01 4.43138504e+01 4.43137054e+01 4.43137817e+01 4.43142128e+01 4.43141823e+01 4.43139877e+01 4.43136940e+01 4.43137360e+01 4.43139420e+01 4.43141556e+01 4.43141708e+01 4.43136406e+01 4.43136673e+01 4.43135452e+01 4.43141289e+01 4.43139877e+01 4.43141098e+01 4.43135490e+01 4.43136787e+01 4.43135109e+01 4.43140526e+01 4.43138008e+01 4.43140221e+01 4.43137741e+01 4.43137703e+01 4.43137131e+01 4.43140793e+01 4.43138199e+01 4.43137970e+01 4.43137016e+01 4.43141136e+01 4.43138275e+01 4.43140411e+01 4.43134499e+01 4.43140030e+01 4.43134804e+01 4.43139191e+01 4.43137398e+01 4.43141899e+01 4.43145447e+01 4.43141518e+01 4.43137321e+01 4.43136253e+01 4.43135109e+01 4.43139801e+01 4.43140297e+01 4.43138123e+01 4.43137970e+01 4.43138885e+01 4.43141060e+01 4.43140907e+01 4.43139420e+01 4.43135986e+01 4.43135376e+01 4.43134766e+01 4.43140411e+01 4.43139496e+01 4.43140602e+01 4.43135719e+01 4.43137627e+01 4.43134651e+01 4.43139954e+01 4.43135376e+01 4.43140678e+01 4.43140907e+01 4.43148804e+01 4.43147850e+01 4.43142128e+01 4.43136139e+01 4.43136139e+01 4.43132286e+01 4.43138390e+01 4.43133774e+01 4.43137589e+01 4.43137245e+01 4.43141098e+01 4.43138657e+01 4.43135948e+01 4.43138618e+01 4.43141937e+01 4.43140144e+01 4.43136520e+01 4.43136482e+01 4.43138847e+01 4.43139191e+01 4.43140411e+01 4.43137283e+01 4.43137932e+01 4.43136406e+01 4.43139381e+01 4.43141670e+01 4.43140793e+01 4.43137207e+01 4.43137093e+01 4.43138657e+01 4.43137512e+01 4.43139267e+01 4.43132935e+01 4.43137321e+01 4.43134766e+01 4.43141403e+01 4.43138084e+01 4.43138885e+01 4.43133049e+01 4.43137817e+01 4.43133659e+01 4.43137550e+01 4.43135948e+01 4.43140030e+01 4.43140640e+01 4.43144226e+01 4.43148727e+01 4.43148575e+01 4.43149490e+01 4.43166237e+01 4.43172798e+01 4.43409119e+01 4.43341713e+01 4.43191566e+01 4.43294449e+01 5.37938118e+01 8.43647766e+01 3.44270905e+02 379335360. 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. 0. 0. 0. 0. 0. 0. 803204160. 1.78890533e+02 6.86387253e+01 4.52848320e+01 4.44518738e+01 4.43521080e+01 4.43220024e+01 4.43162804e+01 4.43142738e+01 4.43139725e+01 4.43138504e+01 4.43136520e+01 4.43139000e+01 4.43140717e+01 4.43141403e+01 4.43140488e+01 4.43140755e+01 4.43140640e+01 4.43140297e+01 4.43140678e+01 4.43139915e+01 4.43140411e+01 4.43141403e+01 4.43138885e+01 4.43138275e+01 4.43136444e+01 4.43141022e+01 4.43137970e+01 4.43137779e+01 4.43135414e+01 4.43138809e+01 4.43140526e+01 4.43140869e+01 4.43140030e+01 4.43139763e+01 4.43138771e+01 4.43139153e+01 4.43139076e+01 4.43141289e+01 4.43138313e+01 4.43139725e+01 4.43136597e+01 4.43138733e+01 4.43138123e+01 4.43138771e+01 4.43140144e+01 4.43140831e+01 4.43140221e+01 4.43139114e+01 4.43140335e+01 4.43136978e+01 4.43140793e+01 4.43134956e+01 4.43138161e+01 4.43136101e+01 4.43139191e+01 4.43140640e+01 4.43137589e+01 4.43138084e+01 4.43137093e+01 4.43139458e+01 4.43139992e+01 4.43138733e+01 4.43139038e+01 4.43138313e+01 4.43139610e+01 4.43140144e+01 4.43142395e+01 4.43141365e+01 4.43141136e+01 4.43138695e+01 4.43139915e+01 4.43139191e+01 4.43139038e+01 4.43139496e+01 4.43143044e+01 4.43139954e+01 4.43140717e+01 4.43135948e+01 4.43139343e+01 4.43135834e+01 4.43139267e+01 4.43134956e+01 4.43138542e+01 4.43137741e+01 4.43139496e+01 4.43139381e+01 4.43139954e+01 4.43140450e+01 4.43140450e+01 4.43138504e+01 4.43140297e+01 4.43140259e+01 4.43138237e+01 4.43138733e+01 4.43137779e+01 4.43139915e+01 4.43139954e+01 4.43136063e+01 4.43136177e+01 4.43136368e+01 4.43140831e+01 4.43141518e+01 4.43137703e+01 4.43139839e+01 4.43135071e+01 4.43139229e+01 4.43134880e+01 4.43137589e+01 4.43136520e+01 4.43139496e+01 4.43139725e+01 4.43142090e+01 4.43139153e+01 4.43138390e+01 4.43136711e+01 4.43138657e+01 4.43140755e+01 4.43137283e+01 4.43137932e+01 4.43135719e+01 4.43139687e+01 4.43141289e+01 4.43137169e+01 4.43139267e+01 4.43134346e+01 4.43136902e+01 4.43134842e+01 4.43138199e+01 4.43140030e+01 4.43140564e+01 4.43140068e+01 4.43139648e+01 4.43139038e+01 4.43140755e+01 4.43140678e+01 4.43142281e+01 4.43141823e+01 4.43138809e+01 4.43136559e+01 4.43135414e+01 4.43139229e+01 4.43141251e+01 4.43137589e+01 4.43136749e+01 4.43134918e+01 4.43137970e+01 4.43139420e+01 4.43136482e+01 4.43139534e+01 4.43133812e+01 4.43139229e+01 4.43136444e+01 4.43136177e+01 4.43136177e+01 4.43137016e+01 4.43140450e+01 4.43138351e+01 4.43140259e+01 4.43138733e+01 4.43140335e+01 4.43140793e+01 4.43140335e+01 4.43140259e+01 4.43143311e+01 4.43138962e+01 4.43138351e+01 4.43136253e+01 4.43137627e+01 4.43139076e+01 4.43133965e+01 4.43136711e+01 4.43136635e+01 4.43136711e+01 4.43137054e+01 4.43135033e+01 4.43138771e+01 4.43140755e+01 4.43138733e+01 4.43139687e+01 4.43133621e+01 4.43138809e+01 4.43137016e+01 4.43138542e+01 4.43136444e+01 4.43136330e+01 4.43139229e+01 4.43141594e+01 4.43138924e+01 4.43137398e+01 4.43135796e+01 4.43138199e+01 4.43139534e+01 4.43136826e+01 4.43138504e+01 4.43134041e+01 4.43137093e+01 4.43138199e+01 4.43138771e+01 4.43140068e+01 4.43135567e+01 4.43137283e+01 4.43138199e+01 4.43138351e+01 4.43140259e+01 4.43133774e+01 4.43138123e+01 4.43136292e+01 4.43136864e+01 4.43135529e+01 4.43136139e+01 4.43139191e+01 4.43141174e+01 4.43138084e+01 4.43138695e+01 4.43137207e+01 4.43138924e+01 4.43140717e+01 4.43137207e+01 4.43138313e+01 4.43134575e+01 4.43137207e+01 4.43137131e+01 4.43138733e+01 4.43140564e+01 4.43136826e+01 4.43138733e+01 4.43137589e+01 4.43140640e+01 4.43142204e+01 4.43136330e+01 4.43137627e+01 4.43135834e+01 4.43140945e+01 4.43138123e+01 4.43138542e+01 4.43137321e+01 4.43140335e+01 4.43137817e+01 4.43137016e+01 4.43137321e+01 4.43140297e+01 4.43140907e+01 4.43138237e+01 4.43138390e+01 4.43137856e+01 4.43140297e+01 4.43142624e+01 4.43136749e+01 4.43137817e+01 4.43137856e+01 4.43143654e+01 4.43140984e+01 4.43137589e+01 4.43136253e+01 4.43137016e+01 4.43140564e+01 4.43138199e+01 4.43139381e+01 4.43138847e+01 4.43139648e+01 4.43139343e+01 4.43139992e+01 4.43137512e+01 4.43139229e+01 4.43136024e+01 4.43138161e+01 4.43138199e+01 4.43140411e+01 4.43140678e+01 4.43135338e+01 4.43136444e+01 4.43136406e+01 4.43139076e+01 4.43140831e+01 4.43137131e+01 4.43139114e+01 4.43134842e+01 4.43138161e+01 4.43136826e+01 4.43140106e+01 4.43141556e+01 4.43141365e+01 4.43138390e+01 4.43135719e+01 4.43135262e+01 4.43138161e+01 4.43139763e+01 4.43139801e+01 4.43138771e+01 4.43137512e+01 4.43137550e+01 4.43141708e+01 4.43138542e+01 4.43139458e+01 4.43134689e+01 4.43138542e+01 4.43136406e+01 4.43139267e+01 4.43140831e+01 4.43137741e+01 4.43138351e+01 4.43136978e+01 4.43141136e+01 4.43138580e+01 4.43138313e+01 4.43136597e+01 4.43141670e+01 4.43137932e+01 4.43138046e+01 4.43136101e+01 4.43139534e+01 4.43141441e+01 4.43137970e+01 4.43138466e+01 4.43136215e+01 4.43139496e+01 4.43140526e+01 4.43137283e+01 4.43138695e+01 4.43133774e+01 4.43138924e+01 4.43137627e+01 4.43136368e+01 4.43137093e+01 4.43134727e+01 4.43138199e+01 4.43135834e+01 4.43140221e+01 4.43141098e+01 4.43140068e+01 4.43140221e+01 4.43139915e+01 4.43139954e+01 4.43142242e+01 4.43139191e+01 4.43136597e+01 4.43137093e+01 4.43137817e+01 4.43139725e+01 4.43133659e+01 4.43137550e+01 4.43137894e+01 4.43138733e+01 4.43138733e+01 4.43136559e+01 4.43140373e+01 4.43136482e+01 4.43136749e+01 4.43134651e+01 4.43139763e+01 4.43141479e+01 4.43140755e+01 4.43137207e+01 4.43136368e+01 4.43135643e+01 4.43139114e+01 4.43139610e+01 4.43139610e+01 4.43135910e+01 4.43136101e+01 4.43136597e+01 4.43141098e+01 4.43138237e+01 4.43139954e+01 4.43134804e+01 4.43138199e+01 4.43138580e+01 4.43138161e+01 4.43139076e+01 4.43134041e+01 4.43136368e+01 4.43135376e+01 4.43139496e+01 4.43140793e+01 4.43137016e+01 4.43137436e+01 4.43137779e+01 4.43137245e+01 4.43139000e+01 4.43136253e+01 4.43139763e+01 4.43142776e+01 4.43139458e+01 4.43137512e+01 4.43135262e+01 4.43138847e+01 4.43140106e+01 4.43138351e+01 4.43139839e+01 4.43136406e+01 4.43139572e+01 4.43138428e+01 4.43136787e+01 4.43137054e+01 4.43133469e+01 4.43137474e+01 4.43136253e+01 4.43139038e+01 4.43140106e+01 4.43136368e+01 4.43137360e+01 4.43135338e+01 4.43142014e+01 4.43136101e+01 4.43136635e+01 4.43135300e+01 4.43140526e+01 4.43140755e+01 4.43141937e+01 4.43137169e+01 4.43137016e+01 4.43137398e+01 4.43137360e+01 4.43136673e+01 4.43136482e+01 4.43139496e+01 4.43138657e+01 4.43138924e+01 4.43140640e+01 4.43137741e+01 4.43139229e+01 4.43137245e+01 4.43137703e+01 4.43137894e+01 4.43135948e+01 4.43139153e+01 4.43138046e+01 4.43137817e+01 4.43136711e+01 4.43135185e+01 4.43137093e+01 4.43138771e+01 4.43138580e+01 4.43139496e+01 4.43136787e+01 4.43136444e+01 4.43137894e+01 4.43137283e+01 4.43139381e+01 4.43135986e+01 4.43138161e+01 4.43136711e+01 4.43141060e+01 4.43142700e+01 4.43138962e+01 4.43139572e+01 4.43137436e+01 4.43136635e+01 4.43136597e+01 4.43134842e+01 4.43137703e+01 4.43138313e+01 4.43137436e+01 4.43138123e+01 4.43135872e+01 4.43139191e+01 4.43139954e+01 4.43138084e+01 4.43138847e+01 4.43135071e+01 4.43138275e+01 4.43136711e+01 4.43139114e+01 4.43140259e+01 4.43138046e+01 4.43136940e+01 4.43135223e+01 4.43138123e+01 4.43141022e+01 4.43139839e+01 4.43140831e+01 4.43135643e+01 4.43139915e+01 4.43139992e+01 4.43139992e+01 4.43138962e+01 4.43137932e+01 4.43139648e+01 4.43139458e+01 4.43139381e+01 4.43139687e+01 4.43140717e+01 4.43138237e+01 4.43138580e+01 4.43137283e+01 4.43141861e+01 4.43140717e+01 4.43137474e+01 4.43136215e+01 4.43136826e+01 4.43140373e+01 4.43137932e+01 4.43138885e+01 4.43139267e+01 4.43139343e+01 4.43140526e+01 4.43138161e+01 4.43140945e+01 4.43141251e+01 4.43138008e+01 4.43137245e+01 4.43138657e+01 4.43140526e+01 4.43138504e+01 4.43137817e+01 4.43137703e+01 4.43140984e+01 4.43138237e+01 4.43139725e+01 4.43137016e+01 4.43139839e+01 4.43137856e+01 4.43139038e+01 4.43141479e+01 4.43136215e+01 4.43138199e+01 4.43138084e+01 4.43137970e+01 4.43139114e+01 4.43136978e+01 4.43139954e+01 4.43138885e+01 4.43137932e+01 4.43138313e+01 4.43137321e+01 4.43139114e+01 4.43142090e+01 4.43138008e+01 4.43140450e+01 4.43135529e+01 4.43137627e+01 4.43137360e+01 4.43139801e+01 4.43141136e+01 4.43138084e+01 4.43137665e+01 4.43138275e+01 4.43138123e+01 4.43139114e+01 4.43134537e+01 4.43139572e+01 4.43134918e+01 4.43139191e+01 4.43138161e+01 4.43138351e+01 4.43139000e+01 4.43139114e+01 4.43141136e+01 4.43139381e+01 4.43139267e+01 4.43139763e+01 4.43142815e+01 4.43141747e+01 4.43139153e+01 4.43136749e+01 4.43138313e+01 4.43140869e+01 4.43137131e+01 4.43135948e+01 4.43135109e+01 4.43140297e+01 4.43137016e+01 4.43139343e+01 4.43139725e+01 4.43139114e+01 4.43137512e+01 4.43136368e+01 4.43141670e+01 4.43141327e+01 4.43137894e+01 4.43137665e+01 4.43138313e+01 4.43141670e+01 4.43138580e+01 4.43136292e+01 4.43136826e+01 4.43140793e+01 4.43140755e+01 4.43138885e+01 4.43137894e+01 4.43137970e+01 4.43141899e+01 4.43138847e+01 4.43139305e+01 4.43136101e+01 4.43137245e+01 4.43137703e+01 4.43138351e+01 4.43140259e+01 4.43136292e+01 4.43137894e+01 4.43137321e+01 4.43137703e+01 4.43139458e+01 4.43139458e+01 4.43138466e+01 4.43137779e+01 4.43137932e+01 4.43149757e+01 4.43140640e+01 4.43141823e+01 4.43137741e+01 4.43143692e+01 4.43147583e+01 4.43149071e+01 4.43175735e+01 4.43198013e+01 4.43250656e+01 4.44770813e+01 5.62447968e+01 7.38887405e+01 1.10643242e+02 1.10846176e+02 1.74606247e+02 2.38706895e+04 0. 0. 0. 0. 0. 272663296. 272663296. -78026824. -229551168. 56548068. -163830784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 675282432. 3.81542419e+02 1.90913589e+02 1.27791168e+02 1.27750786e+02 1.27777184e+02 1.27771461e+02 1.27748154e+02 1.27740425e+02 1.27741501e+02 1.27742332e+02 1.27742943e+02 1.27742882e+02 1.27743408e+02 1.27743179e+02 1.27743858e+02 1.27743721e+02 1.27744034e+02 1.27743248e+02 1.27742554e+02 1.27743065e+02 1.27743713e+02 1.27744179e+02 1.27743195e+02 1.27743317e+02 1.27742981e+02 1.27743217e+02 1.27743080e+02 1.27743622e+02 1.27743454e+02 1.27744789e+02 1.27745010e+02 1.27744423e+02 1.27743805e+02 1.27743515e+02 1.27742615e+02 1.27743347e+02 1.27742950e+02 1.27743042e+02 1.27742699e+02 1.27742775e+02 1.27744087e+02 1.27744179e+02 1.27743881e+02 1.27742294e+02 1.27742905e+02 1.27742874e+02 1.27743797e+02 1.27743996e+02 1.27743752e+02 1.27743652e+02 1.27744003e+02 1.27744736e+02 1.27744102e+02 1.27743011e+02 1.27743111e+02 1.27744629e+02 1.27743942e+02 1.27744247e+02 1.27743454e+02 1.27743347e+02 1.27743408e+02 1.27743950e+02 1.27743370e+02 1.27743629e+02 1.27743095e+02 1.27743858e+02 1.27744026e+02 1.27744225e+02 1.27742958e+02 1.27742973e+02 1.27742630e+02 1.27744102e+02 1.27743637e+02 1.27743507e+02 1.27743637e+02 1.27743965e+02 1.27744347e+02 1.27743851e+02 1.27743294e+02 1.27742180e+02 1.27742775e+02 1.27743149e+02 1.27743256e+02 1.27743668e+02 1.27744186e+02 1.27743744e+02 1.27744232e+02 1.27743011e+02 1.27742470e+02 1.27742897e+02 1.27743561e+02 1.27743637e+02 1.27743492e+02 1.27743507e+02 1.27743469e+02 1.27743095e+02 1.27743065e+02 1.27743523e+02 1.27742851e+02 1.27742805e+02 1.27743340e+02 1.27743515e+02 1.27743790e+02 1.27743599e+02 1.27743546e+02 1.27744141e+02 1.27743393e+02 1.27743156e+02 1.27743393e+02 1.27744041e+02 1.27743362e+02 1.27744164e+02 1.27744072e+02 1.27743423e+02 1.27743149e+02 1.27743782e+02 1.27743225e+02 1.27744514e+02 1.27744026e+02 1.27743713e+02 1.27743332e+02 1.27742989e+02 1.27743385e+02 1.27742836e+02 1.27743286e+02 1.27742966e+02 1.27743752e+02 1.27744179e+02 1.27744095e+02 1.27743118e+02 1.27743111e+02 1.27743607e+02 1.27743668e+02 1.27743622e+02 1.27743500e+02 1.27743454e+02 1.27743484e+02 1.27743248e+02 1.27743019e+02 1.27742752e+02 1.27743065e+02 1.27744743e+02 1.27744133e+02 1.27743515e+02 1.27743340e+02 1.27742714e+02 1.27742722e+02 1.27743309e+02 1.27743927e+02 1.27744110e+02 1.27743813e+02 1.27743477e+02 1.27743958e+02 1.27743431e+02 1.27742767e+02 1.27743172e+02 1.27743622e+02 1.27743622e+02 1.27744423e+02 1.27742432e+02 1.27743149e+02 1.27742706e+02 1.27743370e+02 1.27742752e+02 1.27743225e+02 1.27743713e+02 1.27745026e+02 1.27743088e+02 1.27742722e+02 1.27743553e+02 1.27743332e+02 1.27742813e+02 1.27742455e+02 1.27742836e+02 1.27742264e+02 1.27743469e+02 1.27743233e+02 1.27743805e+02 1.27743050e+02 1.27742493e+02 1.27742775e+02 1.27742638e+02 1.27743408e+02 1.27742371e+02 1.27743004e+02 1.27743271e+02 1.27743240e+02 1.27743073e+02 1.27742561e+02 1.27742592e+02 1.27742485e+02 1.27743469e+02 1.27743576e+02 1.27743797e+02 1.27743477e+02 1.27743294e+02 1.27742683e+02 1.27742722e+02 1.27742340e+02 1.27742607e+02 1.27743713e+02 1.27743431e+02 1.27743843e+02 1.27743919e+02 1.27742447e+02 1.27742287e+02 1.27742760e+02 1.27743210e+02 1.27742958e+02 1.27743263e+02 1.27743179e+02 1.27743103e+02 1.27743202e+02 1.27742729e+02 1.27742485e+02 1.27742241e+02 1.27742912e+02 1.27743073e+02 1.27743134e+02 1.27743050e+02 1.27743187e+02 1.27743126e+02 1.27742905e+02 1.27742798e+02 1.27742828e+02 1.27742340e+02 1.27743019e+02 1.27742844e+02 1.27743095e+02 1.27742783e+02 1.27742668e+02 1.27743034e+02 1.27743584e+02 1.27743095e+02 1.27743011e+02 1.27743149e+02 1.27743332e+02 1.27743362e+02 1.27742844e+02 1.27742149e+02 1.27743057e+02 1.27742828e+02 1.27742958e+02 1.27743340e+02 1.27742645e+02 1.27743538e+02 1.27742706e+02 1.27742470e+02 1.27742737e+02 1.27742554e+02 1.27742737e+02 1.27742889e+02 1.27743706e+02 1.27743797e+02 1.27743965e+02 1.27744148e+02 1.27742889e+02 1.27742867e+02 1.27744095e+02 1.27743950e+02 1.27743484e+02 1.27743385e+02 1.27742325e+02 1.27742790e+02 1.27742264e+02 1.27742561e+02 1.27744270e+02 1.27743385e+02 1.27743462e+02 1.27742943e+02 1.27743462e+02 1.27742455e+02 1.27742676e+02 1.27742714e+02 1.27742882e+02 1.27742805e+02 1.27741859e+02 1.27742104e+02 1.27742401e+02 1.27743164e+02 1.27742737e+02 1.27743286e+02 1.27743279e+02 1.27743370e+02 1.27742950e+02 1.27742325e+02 1.27743576e+02 1.27743256e+02 1.27743683e+02 1.27742744e+02 1.27743919e+02 1.27742691e+02 1.27742287e+02 1.27742737e+02 1.27743454e+02 1.27743629e+02 1.27742210e+02 1.27742271e+02 1.27742805e+02 1.27742706e+02 1.27742577e+02 1.27742767e+02 1.27743263e+02 1.27743057e+02 1.27743393e+02 1.27743515e+02 1.27744438e+02 1.27743744e+02 1.27743141e+02 1.27742043e+02 1.27741409e+02 1.27742317e+02 1.27742775e+02 1.27743179e+02 1.27742729e+02 1.27743011e+02 1.27742958e+02 1.27742523e+02 1.27742744e+02 1.27743011e+02 1.27743187e+02 1.27742508e+02 1.27743225e+02 1.27744057e+02 1.27743874e+02 1.27743538e+02 1.27743423e+02 1.27742973e+02 1.27743286e+02 1.27743233e+02 1.27742401e+02 1.27742371e+02 1.27742813e+02 1.27743393e+02 1.27743172e+02 1.27742813e+02 1.27742828e+02 1.27742561e+02 1.27742683e+02 1.27742165e+02 1.27742516e+02 1.27742760e+02 1.27742889e+02 1.27742645e+02 1.27742821e+02 1.27743484e+02 1.27743202e+02 1.27742958e+02 1.27742767e+02 1.27742493e+02 1.27743301e+02 1.27743469e+02 1.27743698e+02 1.27742805e+02 1.27742775e+02 1.27742722e+02 1.27742722e+02 1.27743408e+02 1.27743210e+02 1.27742859e+02 1.27743111e+02 1.27743393e+02 1.27743294e+02 1.27743027e+02 1.27742851e+02 1.27743507e+02 1.27743324e+02 1.27743744e+02 1.27743515e+02 1.27743271e+02 1.27743767e+02 1.27743332e+02 1.27744026e+02 1.27745621e+02 1.27745422e+02 1.27744148e+02 1.27742912e+02 1.27742905e+02 1.27743622e+02 1.27743813e+02 1.27743782e+02 1.27742920e+02 1.27742523e+02 1.27743385e+02 1.27742592e+02 1.27743195e+02 1.27743668e+02 1.27743202e+02 1.27743225e+02 1.27742966e+02 1.27743126e+02 1.27742531e+02 1.27743248e+02 1.27743721e+02 1.27743866e+02 1.27743881e+02 1.27743607e+02 1.27743088e+02 1.27742844e+02 1.27742859e+02 1.27743156e+02 1.27742279e+02 1.27742714e+02 1.27743767e+02 1.27744316e+02 1.27744110e+02 1.27742821e+02 1.27742599e+02 1.27743095e+02 1.27743332e+02 1.27743782e+02 1.27743355e+02 1.27743362e+02 1.27742775e+02 1.27742912e+02 1.27744080e+02 1.27744232e+02 1.27744431e+02 1.27741966e+02 1.27742256e+02 1.27743317e+02 1.27742836e+02 1.27743935e+02 1.27743393e+02 1.27743256e+02 1.27742752e+02 1.27742485e+02 1.27742783e+02 1.27742691e+02 1.27743279e+02 1.27743439e+02 1.27742668e+02 1.27742554e+02 1.27743279e+02 1.27742973e+02 1.27743782e+02 1.27742470e+02 1.27743004e+02 1.27743111e+02 1.27743042e+02 1.27743172e+02 1.27742416e+02 1.27743324e+02 1.27743195e+02 1.27743721e+02 1.27743156e+02 1.27742767e+02 1.27742439e+02 1.27742958e+02 1.27743431e+02 1.27743553e+02 1.27743179e+02 1.27743202e+02 1.27743286e+02 1.27743027e+02 1.27743355e+02 1.27742630e+02 1.27742653e+02 1.27743744e+02 1.27742996e+02 1.27744545e+02 1.27743011e+02 1.27743263e+02 1.27742508e+02 1.27742928e+02 1.27743141e+02 1.27742607e+02 1.27743004e+02 1.27742783e+02 1.27742653e+02 1.27742729e+02 1.27742249e+02 1.27742218e+02 1.27743492e+02 1.27743431e+02 1.27742821e+02 1.27742645e+02 1.27742607e+02 1.27743317e+02 1.27743469e+02 1.27743835e+02 1.27742661e+02 1.27743179e+02 1.27743484e+02 1.27743294e+02 1.27743103e+02 1.27743332e+02 1.27742752e+02 1.27742477e+02 1.27742775e+02 1.27743355e+02 1.27743187e+02 1.27742760e+02 1.27743423e+02 1.27743782e+02 1.27743248e+02 1.27742973e+02 1.27742798e+02 1.27743340e+02 1.27743027e+02 1.27743172e+02 1.27741837e+02 1.27742180e+02 1.27742668e+02 1.27742706e+02 1.27743431e+02 1.27743431e+02 1.27743462e+02 1.27743439e+02 1.27743416e+02 1.27743317e+02 1.27743340e+02 1.27742950e+02 1.27743805e+02 1.27743309e+02 1.27744469e+02 1.27743340e+02 1.27743904e+02 1.27743591e+02 1.27743362e+02 1.27743683e+02 1.27743004e+02 1.27743263e+02 1.27743813e+02 1.27744843e+02 1.27743881e+02 1.27744110e+02 1.27743271e+02 1.27742935e+02 1.27742859e+02 1.27743492e+02 1.27743355e+02 1.27743988e+02 1.27743874e+02 1.27743645e+02 1.27744431e+02 1.27743484e+02 1.27743919e+02 1.27743324e+02 1.27743248e+02 1.27743675e+02 1.27743385e+02 1.27743225e+02 1.27743294e+02 1.27742691e+02 1.27743202e+02 1.27743057e+02 1.27742989e+02 1.27743164e+02 1.27743858e+02 1.27743546e+02 1.27743881e+02 1.27743340e+02 1.27742958e+02 1.27742706e+02 1.27743286e+02 1.27743530e+02 1.27743912e+02 1.27742798e+02 1.27742599e+02 1.27742729e+02 1.27742249e+02 1.27743103e+02 1.27743073e+02 1.27742569e+02 1.27743034e+02 1.27743233e+02 1.27744186e+02 1.27744423e+02 1.27743706e+02 1.27743561e+02 1.27742943e+02 1.27742851e+02 1.27742981e+02 1.27743629e+02 1.27743492e+02 1.27743347e+02 1.27742996e+02 1.27742584e+02 1.27743210e+02 1.27743805e+02 1.27743805e+02 1.27743721e+02 1.27743408e+02 1.27743492e+02 1.27743401e+02 1.27742973e+02 1.27743500e+02 1.27743698e+02 1.27743294e+02 1.27743736e+02 1.27743141e+02 1.27743866e+02 1.27744087e+02 1.27743706e+02 1.27744095e+02 1.27742714e+02 1.27742882e+02 1.27743027e+02 1.27744225e+02 1.27744125e+02 1.27743813e+02 1.27743233e+02 1.27742966e+02 1.27742363e+02 1.27742889e+02 1.27742645e+02 1.27742577e+02 1.27741234e+02 1.27740623e+02 1.27739799e+02 1.27739769e+02 1.27739731e+02 1.27739700e+02 1.27742508e+02 1.27754921e+02 1.27784271e+02 1.28397964e+02 1.28892441e+02 1.76506973e+02 3.73516937e+02 246460512. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1610688256. -192897584. 1.14675378e+03 5.38902344e+02 3.50253784e+02 2.19873734e+02 1.63010452e+02 1.27975830e+02 1.27813293e+02 1.27746864e+02 1.27740433e+02 1.27740326e+02 1.27741463e+02 1.27742928e+02 1.27743042e+02 1.27743019e+02 1.27742027e+02 1.27742256e+02 1.27742638e+02 1.27742920e+02 1.27742447e+02 1.27743050e+02 1.27741867e+02 1.27742523e+02 1.27742256e+02 1.27742889e+02 1.27742920e+02 1.27743187e+02 1.27743431e+02 1.27742279e+02 1.27742348e+02 1.27742149e+02 1.27742699e+02 1.27743126e+02 1.27743729e+02 1.27742203e+02 1.27742210e+02 1.27742020e+02 1.27742905e+02 1.27742935e+02 1.27742805e+02 1.27742416e+02 1.27742378e+02 1.27743568e+02 1.27743324e+02 1.27743439e+02 1.27743233e+02 1.27742668e+02 1.27744186e+02 1.27743172e+02 1.27742661e+02 1.27742538e+02 1.27742844e+02 1.27743645e+02 1.27742134e+02 1.27742195e+02 1.27742279e+02 1.27742767e+02 1.27742737e+02 1.27743042e+02 1.27742348e+02 1.27742188e+02 1.27742577e+02 1.27743851e+02 1.27744164e+02 1.27743698e+02 1.27742210e+02 1.27742401e+02 1.27743111e+02 1.27743553e+02 1.27743332e+02 1.27743034e+02 1.27742577e+02 1.27743301e+02 1.27743225e+02 1.27743408e+02 1.27743889e+02 1.27743919e+02 1.27743935e+02 1.27742905e+02 1.27741943e+02 1.27742348e+02 1.27742661e+02 1.27743279e+02 1.27743141e+02 1.27742897e+02 1.27742210e+02 1.27742119e+02 1.27743057e+02 1.27742905e+02 1.27743080e+02 1.27742462e+02 1.27743164e+02 1.27743462e+02 1.27742867e+02 1.27742943e+02 1.27742691e+02 1.27742195e+02 1.27742897e+02 1.27742714e+02 1.27743179e+02 1.27742859e+02 1.27742699e+02 1.27743217e+02 1.27742668e+02 1.27742134e+02 1.27742157e+02 1.27742188e+02 1.27743607e+02 1.27743454e+02 1.27743523e+02 1.27742836e+02 1.27742836e+02 1.27743652e+02 1.27743813e+02 1.27743423e+02 1.27742569e+02 1.27742393e+02 1.27743454e+02 1.27743690e+02 1.27743690e+02 1.27743500e+02 1.27743759e+02 1.27743469e+02 1.27742821e+02 1.27742691e+02 1.27743759e+02 1.27743668e+02 1.27744682e+02 1.27742950e+02 1.27742645e+02 1.27742622e+02 1.27742737e+02 1.27743217e+02 1.27743057e+02 1.27743355e+02 1.27743111e+02 1.27742439e+02 1.27744133e+02 1.27743614e+02 1.27744049e+02 1.27743073e+02 1.27742950e+02 1.27742989e+02 1.27742577e+02 1.27742615e+02 1.27742996e+02 1.27743721e+02 1.27744850e+02 1.27743683e+02 1.27743553e+02 1.27742691e+02 1.27743752e+02 1.27743820e+02 1.27743454e+02 1.27742882e+02 1.27742744e+02 1.27743179e+02 1.27743820e+02 1.27743408e+02 1.27743683e+02 1.27743362e+02 1.27743896e+02 1.27743439e+02 1.27743591e+02 1.27743881e+02 1.27743980e+02 1.27743393e+02 1.27744057e+02 1.27743248e+02 1.27743134e+02 1.27744041e+02 1.27743828e+02 1.27743889e+02 1.27743011e+02 1.27743202e+02 1.27742844e+02 1.27743195e+02 1.27744148e+02 1.27743233e+02 1.27743126e+02 1.27742386e+02 1.27742516e+02 1.27743248e+02 1.27743637e+02 1.27743156e+02 1.27743118e+02 1.27743332e+02 1.27743599e+02 1.27743622e+02 1.27744682e+02 1.27744583e+02 1.27743843e+02 1.27744263e+02 1.27743523e+02 1.27744080e+02 1.27744209e+02 1.27744141e+02 1.27744339e+02 1.27742935e+02 1.27742523e+02 1.27742470e+02 1.27743820e+02 1.27743851e+02 1.27744041e+02 1.27743462e+02 1.27743546e+02 1.27743675e+02 1.27744095e+02 1.27743927e+02 1.27743477e+02 1.27742737e+02 1.27742966e+02 1.27743629e+02 1.27743607e+02 1.27744255e+02 1.27744034e+02 1.27743698e+02 1.27743118e+02 1.27742851e+02 1.27743622e+02 1.27744156e+02 1.27743935e+02 1.27744530e+02 1.27743195e+02 1.27743279e+02 1.27743195e+02 1.27743217e+02 1.27744537e+02 1.27744194e+02 1.27743744e+02 1.27742897e+02 1.27743904e+02 1.27744263e+02 1.27744400e+02 1.27743614e+02 1.27744286e+02 1.27744171e+02 1.27743675e+02 1.27743088e+02 1.27742981e+02 1.27742584e+02 1.27744141e+02 1.27743919e+02 1.27744118e+02 1.27743149e+02 1.27742935e+02 1.27743019e+02 1.27744133e+02 1.27743744e+02 1.27743797e+02 1.27743271e+02 1.27743172e+02 1.27743279e+02 1.27744087e+02 1.27744034e+02 1.27743919e+02 1.27743546e+02 1.27743301e+02 1.27744225e+02 1.27743858e+02 1.27744362e+02 1.27743408e+02 1.27743164e+02 1.27743492e+02 1.27744179e+02 1.27743271e+02 1.27744568e+02 1.27743629e+02 1.27744255e+02 1.27743622e+02 1.27743881e+02 1.27743805e+02 1.27743835e+02 1.27743202e+02 1.27742905e+02 1.27742638e+02 1.27743950e+02 1.27743248e+02 1.27743454e+02 1.27742996e+02 1.27742638e+02 1.27742737e+02 1.27743111e+02 1.27743126e+02 1.27744492e+02 1.27743584e+02 1.27743973e+02 1.27743446e+02 1.27744415e+02 1.27743843e+02 1.27743828e+02 1.27743546e+02 1.27743500e+02 1.27744263e+02 1.27743752e+02 1.27743599e+02 1.27743858e+02 1.27743828e+02 1.27743774e+02 1.27744278e+02 1.27743889e+02 1.27745232e+02 1.27744186e+02 1.27743607e+02 1.27743408e+02 1.27744171e+02 1.27744514e+02 1.27744133e+02 1.27743050e+02 1.27743263e+02 1.27743179e+02 1.27744019e+02 1.27744041e+02 1.27743874e+02 1.27743164e+02 1.27743042e+02 1.27743134e+02 1.27743515e+02 1.27743423e+02 1.27744102e+02 1.27743210e+02 1.27744408e+02 1.27744102e+02 1.27744469e+02 1.27743942e+02 1.27743530e+02 1.27743294e+02 1.27744476e+02 1.27743599e+02 1.27744484e+02 1.27743622e+02 1.27744316e+02 1.27743393e+02 1.27743889e+02 1.27743774e+02 1.27743988e+02 1.27744568e+02 1.27743828e+02 1.27743904e+02 1.27743149e+02 1.27743240e+02 1.27743904e+02 1.27743423e+02 1.27743576e+02 1.27743622e+02 1.27743385e+02 1.27743835e+02 1.27743599e+02 1.27744110e+02 1.27742805e+02 1.27742798e+02 1.27743347e+02 1.27744110e+02 1.27744316e+02 1.27744492e+02 1.27743202e+02 1.27743080e+02 1.27742737e+02 1.27743973e+02 1.27743530e+02 1.27743774e+02 1.27742554e+02 1.27743805e+02 1.27743729e+02 1.27744804e+02 1.27743881e+02 1.27743599e+02 1.27742828e+02 1.27744019e+02 1.27743790e+02 1.27743683e+02 1.27743240e+02 1.27744125e+02 1.27743629e+02 1.27743576e+02 1.27742500e+02 1.27743118e+02 1.27743591e+02 1.27744095e+02 1.27743965e+02 1.27743248e+02 1.27742996e+02 1.27744659e+02 1.27744019e+02 1.27744385e+02 1.27742828e+02 1.27743980e+02 1.27743629e+02 1.27743889e+02 1.27743538e+02 1.27743675e+02 1.27743507e+02 1.27743431e+02 1.27743690e+02 1.27743683e+02 1.27743675e+02 1.27743065e+02 1.27743881e+02 1.27744194e+02 1.27744560e+02 1.27743736e+02 1.27743759e+02 1.27743484e+02 1.27743523e+02 1.27744324e+02 1.27744415e+02 1.27743706e+02 1.27744331e+02 1.27743744e+02 1.27744057e+02 1.27743385e+02 1.27743439e+02 1.27743271e+02 1.27743347e+02 1.27743172e+02 1.27743385e+02 1.27743301e+02 1.27744713e+02 1.27744255e+02 1.27743568e+02 1.27742905e+02 1.27743599e+02 1.27743538e+02 1.27743935e+02 1.27744102e+02 1.27743744e+02 1.27743187e+02 1.27743065e+02 1.27743073e+02 1.27743706e+02 1.27743088e+02 1.27743042e+02 1.27743340e+02 1.27743294e+02 1.27744225e+02 1.27743652e+02 1.27743584e+02 1.27742912e+02 1.27744232e+02 1.27743942e+02 1.27744576e+02 1.27743362e+02 1.27744614e+02 1.27743942e+02 1.27744286e+02 1.27743591e+02 1.27744148e+02 1.27744308e+02 1.27744431e+02 1.27743912e+02 1.27740524e+02 1.27739204e+02 1.27740356e+02 1.27740219e+02 1.27742218e+02 1.27748070e+02 1.27782784e+02 1.27788513e+02 1.28316223e+02 1.28863205e+02 1.94667404e+02 3.87996002e+02 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. 0. 0. 0. 0. 0. 0. 0. -662361344. 1.41654175e+03 5.49502441e+02 3.51903748e+02 3.49072540e+02 3.48685638e+02 2.24671616e+02 1.64805923e+02 1.28427460e+02 1.27878090e+02 1.27756386e+02 1.27746841e+02 1.27742805e+02 1.27742722e+02 1.27742851e+02 1.27742989e+02 1.27743141e+02 1.27743118e+02 1.27743469e+02 1.27743362e+02 1.27743187e+02 1.27742950e+02 1.27742836e+02 1.27743103e+02 1.27742783e+02 1.27743484e+02 1.27742882e+02 1.27742744e+02 1.27742355e+02 1.27742401e+02 1.27742538e+02 1.27742821e+02 1.27742462e+02 1.27743202e+02 1.27743477e+02 1.27742989e+02 1.27742653e+02 1.27743530e+02 1.27743134e+02 1.27743767e+02 1.27742775e+02 1.27743141e+02 1.27742912e+02 1.27742577e+02 1.27743286e+02 1.27743370e+02 1.27743439e+02 1.27743080e+02 1.27743095e+02 1.27743645e+02 1.27744644e+02 1.27743828e+02 1.27743591e+02 1.27742760e+02 1.27742706e+02 1.27744377e+02 1.27744072e+02 1.27743698e+02 1.27742867e+02 1.27743317e+02 1.27743202e+02 1.27742661e+02 1.27744240e+02 1.27744164e+02 1.27744110e+02 1.27743370e+02 1.27743294e+02 1.27743721e+02 1.27742928e+02 1.27742844e+02 1.27743317e+02 1.27742981e+02 1.27743118e+02 1.27742905e+02 1.27743172e+02 1.27743256e+02 1.27743996e+02 1.27744225e+02 1.27744286e+02 1.27743492e+02 1.27743889e+02 1.27742897e+02 1.27743507e+02 1.27743637e+02 1.27743759e+02 1.27743820e+02 1.27743134e+02 1.27742813e+02 1.27742737e+02 1.27742653e+02 1.27743240e+02 1.27743309e+02 1.27743507e+02 1.27743187e+02 1.27743790e+02 1.27743507e+02 1.27743614e+02 1.27742935e+02 1.27742821e+02 1.27742470e+02 1.27743103e+02 1.27743202e+02 1.27743309e+02 1.27742973e+02 1.27742821e+02 1.27742737e+02 1.27742905e+02 1.27743073e+02 1.27743439e+02 1.27743210e+02 1.27744370e+02 1.27743507e+02 1.27743706e+02 1.27742317e+02 1.27742462e+02 1.27743462e+02 1.27744522e+02 1.27743843e+02 1.27743553e+02 1.27742760e+02 1.27743668e+02 1.27743477e+02 1.27742897e+02 1.27744034e+02 1.27743607e+02 1.27743736e+02 1.27743073e+02 1.27743034e+02 1.27743935e+02 1.27743858e+02 1.27743492e+02 1.27742538e+02 1.27743561e+02 1.27744026e+02 1.27744041e+02 1.27744583e+02 1.27744370e+02 1.27744049e+02 1.27743164e+02 1.27742996e+02 1.27743263e+02 1.27743469e+02 1.27743553e+02 1.27743553e+02 1.27742134e+02 1.27742714e+02 1.27743225e+02 1.27743324e+02 1.27743950e+02 1.27742950e+02 1.27743874e+02 1.27742920e+02 1.27743057e+02 1.27743324e+02 1.27743370e+02 1.27743782e+02 1.27743149e+02 1.27743401e+02 1.27743729e+02 1.27742760e+02 1.27743767e+02 1.27743454e+02 1.27743835e+02 1.27743721e+02 1.27743073e+02 1.27743019e+02 1.27742958e+02 1.27743019e+02 1.27743355e+02 1.27742966e+02 1.27743225e+02 1.27743385e+02 1.27743385e+02 1.27743416e+02 1.27742554e+02 1.27742752e+02 1.27742668e+02 1.27743698e+02 1.27744354e+02 1.27743576e+02 1.27743965e+02 1.27743050e+02 1.27743149e+02 1.27742950e+02 1.27742668e+02 1.27743835e+02 1.27743454e+02 1.27743652e+02 1.27742470e+02 1.27742378e+02 1.27742752e+02 1.27743599e+02 1.27743263e+02 1.27743874e+02 1.27743340e+02 1.27743210e+02 1.27743080e+02 1.27742775e+02 1.27744041e+02 1.27743439e+02 1.27743683e+02 1.27742653e+02 1.27743004e+02 1.27743607e+02 1.27743172e+02 1.27743477e+02 1.27743271e+02 1.27743095e+02 1.27742622e+02 1.27742149e+02 1.27743118e+02 1.27744232e+02 1.27743530e+02 1.27743324e+02 1.27742844e+02 1.27742981e+02 1.27743629e+02 1.27743904e+02 1.27743622e+02 1.27743095e+02 1.27742882e+02 1.27742920e+02 1.27742714e+02 1.27744217e+02 1.27743584e+02 1.27743568e+02 1.27742851e+02 1.27743103e+02 1.27743889e+02 1.27743362e+02 1.27742897e+02 1.27742653e+02 1.27743317e+02 1.27743263e+02 1.27743362e+02 1.27743034e+02 1.27742943e+02 1.27743248e+02 1.27743912e+02 1.27742950e+02 1.27743172e+02 1.27743843e+02 1.27743767e+02 1.27744026e+02 1.27742882e+02 1.27742775e+02 1.27743080e+02 1.27743248e+02 1.27743591e+02 1.27743179e+02 1.27744125e+02 1.27743507e+02 1.27743217e+02 1.27743195e+02 1.27743172e+02 1.27743874e+02 1.27743347e+02 1.27743599e+02 1.27743294e+02 1.27743149e+02 1.27742630e+02 1.27743767e+02 1.27743782e+02 1.27743942e+02 1.27742943e+02 1.27743454e+02 1.27743660e+02 1.27743614e+02 1.27743668e+02 1.27742813e+02 1.27742653e+02 1.27742928e+02 1.27743271e+02 1.27744003e+02 1.27743576e+02 1.27743835e+02 1.27742935e+02 1.27743042e+02 1.27743408e+02 1.27744003e+02 1.27743912e+02 1.27743309e+02 1.27743752e+02 1.27742798e+02 1.27743103e+02 1.27743073e+02 1.27744049e+02 1.27743904e+02 1.27743874e+02 1.27742661e+02 1.27743156e+02 1.27743393e+02 1.27742935e+02 1.27743698e+02 1.27743660e+02 1.27743225e+02 1.27743706e+02 1.27744102e+02 1.27744286e+02 1.27743088e+02 1.27743713e+02 1.27742706e+02 1.27742950e+02 1.27742905e+02 1.27743362e+02 1.27743690e+02 1.27743980e+02 1.27743782e+02 1.27743095e+02 1.27743149e+02 1.27743111e+02 1.27743248e+02 1.27743294e+02 1.27743484e+02 1.27742844e+02 1.27743492e+02 1.27743515e+02 1.27743355e+02 1.27743423e+02 1.27743248e+02 1.27743484e+02 1.27743210e+02 1.27743103e+02 1.27743729e+02 1.27743263e+02 1.27743576e+02 1.27744110e+02 1.27744316e+02 1.27745125e+02 1.27744492e+02 1.27745041e+02 1.27744118e+02 1.27744293e+02 1.27743752e+02 1.27743744e+02 1.27743416e+02 1.27743881e+02 1.27743599e+02 1.27743797e+02 1.27743034e+02 1.27742828e+02 1.27743279e+02 1.27743530e+02 1.27743248e+02 1.27743233e+02 1.27743858e+02 1.27743767e+02 1.27743774e+02 1.27744415e+02 1.27744041e+02 1.27745079e+02 1.27744102e+02 1.27744286e+02 1.27743233e+02 1.27742920e+02 1.27743507e+02 1.27743149e+02 1.27743172e+02 1.27743233e+02 1.27743370e+02 1.27743034e+02 1.27743507e+02 1.27743073e+02 1.27744232e+02 1.27744247e+02 1.27744049e+02 1.27743858e+02 1.27744064e+02 1.27744492e+02 1.27743355e+02 1.27743584e+02 1.27743889e+02 1.27744011e+02 1.27744019e+02 1.27743294e+02 1.27743690e+02 1.27743439e+02 1.27743393e+02 1.27743706e+02 1.27742912e+02 1.27744148e+02 1.27744324e+02 1.27743980e+02 1.27743179e+02 1.27742958e+02 1.27743011e+02 1.27744186e+02 1.27743820e+02 1.27744186e+02 1.27743233e+02 1.27744835e+02 1.27744087e+02 1.27744568e+02 1.27743713e+02 1.27743866e+02 1.27743729e+02 1.27743652e+02 1.27744225e+02 1.27743370e+02 1.27743347e+02 1.27743652e+02 1.27743584e+02 1.27744484e+02 1.27743896e+02 1.27743538e+02 1.27743202e+02 1.27744255e+02 1.27744537e+02 1.27744881e+02 1.27743729e+02 1.27743614e+02 1.27743484e+02 1.27743973e+02 1.27743591e+02 1.27743500e+02 1.27742760e+02 1.27744461e+02 1.27744476e+02 1.27744804e+02 1.27743462e+02 1.27744423e+02 1.27743538e+02 1.27743790e+02 1.27743073e+02 1.27742996e+02 1.27743385e+02 1.27743324e+02 1.27743378e+02 1.27743248e+02 1.27742874e+02 1.27743271e+02 1.27744118e+02 1.27744453e+02 1.27744400e+02 1.27743401e+02 1.27742981e+02 1.27743759e+02 1.27744141e+02 1.27744286e+02 1.27743729e+02 1.27743408e+02 1.27743584e+02 1.27744049e+02 1.27744446e+02 1.27743568e+02 1.27743584e+02 1.27744263e+02 1.27743980e+02 1.27743431e+02 1.27743698e+02 1.27743301e+02 1.27743927e+02 1.27743652e+02 1.27743027e+02 1.27743225e+02 1.27743492e+02 1.27744156e+02 1.27744278e+02 1.27745178e+02 1.27744064e+02 1.27744476e+02 1.27743507e+02 1.27744286e+02 1.27743919e+02 1.27743988e+02 1.27743378e+02 1.27743080e+02 1.27743492e+02 1.27743515e+02 1.27743240e+02 1.27743927e+02 1.27744598e+02 1.27744980e+02 1.27744827e+02 1.27744110e+02 1.27744110e+02 1.27743011e+02 1.27743507e+02 1.27743446e+02 1.27743614e+02 1.27743607e+02 1.27744576e+02 1.27744331e+02 1.27744072e+02 1.27743629e+02 1.27743980e+02 1.27744041e+02 1.27743408e+02 1.27743118e+02 1.27742989e+02 1.27744286e+02 1.27744438e+02 1.27744408e+02 1.27742989e+02 1.27743347e+02 1.27743896e+02 1.27744339e+02 1.27744415e+02 1.27744690e+02 1.27743469e+02 1.27743828e+02 1.27744507e+02 1.27744301e+02 1.27743942e+02 1.27742958e+02 1.27743347e+02 1.27744949e+02 1.27744949e+02 1.27744560e+02 1.27743340e+02 1.27743904e+02 1.27743340e+02 1.27743248e+02 1.27743675e+02 1.27743599e+02 1.27743637e+02 1.27743797e+02 1.27744186e+02 1.27743752e+02 1.27743744e+02 1.27743736e+02 1.27743507e+02 1.27744301e+02 1.27743713e+02 1.27743988e+02 1.27744156e+02 1.27744240e+02 1.27743370e+02 1.27743340e+02 1.27743919e+02 1.27743668e+02 1.27743134e+02 1.27743118e+02 1.27744484e+02 1.27744133e+02 1.27744530e+02 1.27743950e+02 1.27743492e+02 1.27744057e+02 1.27743172e+02 1.27743721e+02 1.27743912e+02 1.27743729e+02 1.27743347e+02 1.27743118e+02 1.27743889e+02 1.27743439e+02 1.27743767e+02 1.27742691e+02 1.27742340e+02 1.27743324e+02 1.27743729e+02 1.27743996e+02 1.27742691e+02 1.27743111e+02 1.27743683e+02 1.27743546e+02 1.27743568e+02 1.27742729e+02 1.27742973e+02 1.27743187e+02 1.27743431e+02 1.27743347e+02 1.27743896e+02 1.27743668e+02 1.27743698e+02 1.27743980e+02 1.27744171e+02 1.27743767e+02 1.27742744e+02 1.27742607e+02 1.27742691e+02 1.27743134e+02 1.27743340e+02 1.27742737e+02 1.27742821e+02 1.27744301e+02 1.27744095e+02 1.27743889e+02 1.27744080e+02 1.27744011e+02 1.27743698e+02 1.27742874e+02 1.27743301e+02 1.27743317e+02 1.27742889e+02 1.27743477e+02 1.27742805e+02 1.27743446e+02 1.27743782e+02 1.27743828e+02 1.27743393e+02 1.27743622e+02 1.27743362e+02 1.27743622e+02 1.27743027e+02 1.27743240e+02 1.27743172e+02 1.27743134e+02 1.27742416e+02 1.27742729e+02 1.27741119e+02 1.27740875e+02 1.27740326e+02 1.27741081e+02 1.27743019e+02 1.27740700e+02 1.27740982e+02 1.27746414e+02 1.28425415e+02 1.29952316e+02 1.94400650e+02 4.01709839e+02 -96675672. -167928112. 0. 0. 0. 0. 0. 272663296. -338852480. 6.74981567e+02 4.23685693e+03 56548068. -163830784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.65576525e+09 1.38253345e+03 4.04185425e+02 2.93974915e+02 2.93372284e+02 2.93190582e+02 2.93194946e+02 2.93177063e+02 2.93176910e+02 2.93179626e+02 2.93181244e+02 2.93181946e+02 2.93181152e+02 2.93178864e+02 2.93180786e+02 2.93180908e+02 2.93180054e+02 2.93179871e+02 2.93181335e+02 2.93180847e+02 2.93180084e+02 2.93180115e+02 2.93183228e+02 2.93182892e+02 2.93178894e+02 2.93180573e+02 2.93179535e+02 2.93179138e+02 2.93181396e+02 2.93181519e+02 2.93182312e+02 2.93180298e+02 2.93180695e+02 2.93180023e+02 2.93181915e+02 2.93181213e+02 2.93181366e+02 2.93181213e+02 2.93181183e+02 2.93181366e+02 2.93180634e+02 2.93180115e+02 2.93178040e+02 2.93180145e+02 2.93182526e+02 2.93181305e+02 2.93177704e+02 2.93180420e+02 2.93182861e+02 2.93179535e+02 2.93180786e+02 2.93180481e+02 2.93180725e+02 2.93180756e+02 2.93182159e+02 2.93182343e+02 2.93180573e+02 2.93181976e+02 2.93180023e+02 2.93179901e+02 2.93179474e+02 2.93178741e+02 2.93180725e+02 2.93179810e+02 2.93182190e+02 2.93180115e+02 2.93179840e+02 2.93179077e+02 2.93179962e+02 2.93181915e+02 2.93181213e+02 2.93179871e+02 2.93181183e+02 2.93179901e+02 2.93181976e+02 2.93177032e+02 2.93178314e+02 2.93176758e+02 2.93180450e+02 2.93182159e+02 2.93180725e+02 2.93180298e+02 2.93181396e+02 2.93179047e+02 2.93180206e+02 2.93180267e+02 2.93178375e+02 2.93177887e+02 2.93182007e+02 2.93179932e+02 2.93181641e+02 2.93180756e+02 2.93180542e+02 2.93178284e+02 2.93180817e+02 2.93181396e+02 2.93179199e+02 2.93179962e+02 2.93181244e+02 2.93180389e+02 2.93179443e+02 2.93176758e+02 2.93177673e+02 2.93181183e+02 2.93182129e+02 2.93179901e+02 2.93180115e+02 2.93180389e+02 2.93181030e+02 2.93179474e+02 2.93178986e+02 2.93178223e+02 2.93179810e+02 2.93181366e+02 2.93180298e+02 2.93179993e+02 2.93180054e+02 2.93179138e+02 2.93177612e+02 2.93178619e+02 2.93181641e+02 2.93182343e+02 2.93182281e+02 2.93179565e+02 2.93177948e+02 2.93179260e+02 2.93177307e+02 2.93177460e+02 2.93176880e+02 2.93180298e+02 2.93180420e+02 2.93180023e+02 2.93180450e+02 2.93179962e+02 2.93178619e+02 2.93179443e+02 2.93180420e+02 2.93180145e+02 2.93180115e+02 2.93179718e+02 2.93182526e+02 2.93179871e+02 2.93181427e+02 2.93182007e+02 2.93180969e+02 2.93179962e+02 2.93179657e+02 2.93178955e+02 2.93180206e+02 2.93179840e+02 2.93182709e+02 2.93179199e+02 2.93178711e+02 2.93176910e+02 2.93178040e+02 2.93180481e+02 2.93180786e+02 2.93179840e+02 2.93178986e+02 2.93179840e+02 2.93181122e+02 2.93180237e+02 2.93179626e+02 2.93179932e+02 2.93179596e+02 2.93180542e+02 2.93179291e+02 2.93178986e+02 2.93179779e+02 2.93178192e+02 2.93179474e+02 2.93180176e+02 2.93179443e+02 2.93179779e+02 2.93180634e+02 2.93180573e+02 2.93178253e+02 2.93178101e+02 2.93177002e+02 2.93180420e+02 2.93181488e+02 2.93180908e+02 2.93178802e+02 2.93177094e+02 2.93178314e+02 2.93178986e+02 2.93176666e+02 2.93178040e+02 2.93179199e+02 2.93179718e+02 2.93179077e+02 2.93179047e+02 2.93178955e+02 2.93178497e+02 2.93177673e+02 2.93180176e+02 2.93181580e+02 2.93179565e+02 2.93180023e+02 2.93179626e+02 2.93179199e+02 2.93177460e+02 2.93177277e+02 2.93177795e+02 2.93180084e+02 2.93179352e+02 2.93178223e+02 2.93177612e+02 2.93177704e+02 2.93179718e+02 2.93179047e+02 2.93180359e+02 2.93178375e+02 2.93177094e+02 2.93180939e+02 2.93179413e+02 2.93179871e+02 2.93179352e+02 2.93177582e+02 2.93178406e+02 2.93180450e+02 2.93179718e+02 2.93178680e+02 2.93178986e+02 2.93179657e+02 2.93178711e+02 2.93178894e+02 2.93177460e+02 2.93177979e+02 2.93179688e+02 2.93179047e+02 2.93178894e+02 2.93178192e+02 2.93179810e+02 2.93179718e+02 2.93178314e+02 2.93177155e+02 2.93177094e+02 2.93177612e+02 2.93177917e+02 2.93179932e+02 2.93179291e+02 2.93180603e+02 2.93178680e+02 2.93177216e+02 2.93177948e+02 2.93179047e+02 2.93180176e+02 2.93178833e+02 2.93179413e+02 2.93176880e+02 2.93177429e+02 2.93177887e+02 2.93177338e+02 2.93179047e+02 2.93179413e+02 2.93179504e+02 2.93179169e+02 2.93178253e+02 2.93178406e+02 2.93179291e+02 2.93179840e+02 2.93178406e+02 2.93179077e+02 2.93178680e+02 2.93180969e+02 2.93178070e+02 2.93180023e+02 2.93179871e+02 2.93178406e+02 2.93181030e+02 2.93180237e+02 2.93180908e+02 2.93178070e+02 2.93181000e+02 2.93178101e+02 2.93177185e+02 2.93176575e+02 2.93177307e+02 2.93178497e+02 2.93178833e+02 2.93180084e+02 2.93179047e+02 2.93181458e+02 2.93178925e+02 2.93178955e+02 2.93178101e+02 2.93176819e+02 2.93178375e+02 2.93176147e+02 2.93176392e+02 2.93177551e+02 2.93177551e+02 2.93178467e+02 2.93179718e+02 2.93179443e+02 2.93180237e+02 2.93177856e+02 2.93176178e+02 2.93178070e+02 2.93179443e+02 2.93178650e+02 2.93177887e+02 2.93179169e+02 2.93178223e+02 2.93178436e+02 2.93177368e+02 2.93177704e+02 2.93177155e+02 2.93178711e+02 2.93179199e+02 2.93178009e+02 2.93180511e+02 2.93180145e+02 2.93177979e+02 2.93180634e+02 2.93178711e+02 2.93177887e+02 2.93178406e+02 2.93176575e+02 2.93177979e+02 2.93179047e+02 2.93179199e+02 2.93176147e+02 2.93180511e+02 2.93179718e+02 2.93179291e+02 2.93176178e+02 2.93177979e+02 2.93178772e+02 2.93180267e+02 2.93178131e+02 2.93176910e+02 2.93176178e+02 2.93177826e+02 2.93181458e+02 2.93178650e+02 2.93178528e+02 2.93178741e+02 2.93176697e+02 2.93179840e+02 2.93177704e+02 2.93176849e+02 2.93176849e+02 2.93177246e+02 2.93177582e+02 2.93178711e+02 2.93180084e+02 2.93178162e+02 2.93179108e+02 2.93178101e+02 2.93176727e+02 2.93176910e+02 2.93178741e+02 2.93180054e+02 2.93178589e+02 2.93178497e+02 2.93177917e+02 2.93179565e+02 2.93180573e+02 2.93179474e+02 2.93180145e+02 2.93178741e+02 2.93180389e+02 2.93179901e+02 2.93176758e+02 2.93179199e+02 2.93178772e+02 2.93178375e+02 2.93177979e+02 2.93177338e+02 2.93179626e+02 2.93178101e+02 2.93181274e+02 2.93181305e+02 2.93180511e+02 2.93179688e+02 2.93177948e+02 2.93179352e+02 2.93179565e+02 2.93181152e+02 2.93177277e+02 2.93179810e+02 2.93179047e+02 2.93176758e+02 2.93178650e+02 2.93177246e+02 2.93179413e+02 2.93177429e+02 2.93177185e+02 2.93179016e+02 2.93178680e+02 2.93177216e+02 2.93177521e+02 2.93178802e+02 2.93179382e+02 2.93178589e+02 2.93178558e+02 2.93180084e+02 2.93179840e+02 2.93181366e+02 2.93179047e+02 2.93179535e+02 2.93181274e+02 2.93180176e+02 2.93180786e+02 2.93179169e+02 2.93179230e+02 2.93179626e+02 2.93179382e+02 2.93178040e+02 2.93177979e+02 2.93179230e+02 2.93181274e+02 2.93178345e+02 2.93177338e+02 2.93178345e+02 2.93181061e+02 2.93179443e+02 2.93179596e+02 2.93176880e+02 2.93177979e+02 2.93179626e+02 2.93179901e+02 2.93178375e+02 2.93181824e+02 2.93181061e+02 2.93178986e+02 2.93180359e+02 2.93176208e+02 2.93180115e+02 2.93180817e+02 2.93180481e+02 2.93180695e+02 2.93179138e+02 2.93179535e+02 2.93180511e+02 2.93178894e+02 2.93176361e+02 2.93177521e+02 2.93176697e+02 2.93176086e+02 2.93178650e+02 2.93177124e+02 2.93179108e+02 2.93180023e+02 2.93179504e+02 2.93179260e+02 2.93179169e+02 2.93178070e+02 2.93177094e+02 2.93178864e+02 2.93179260e+02 2.93179871e+02 2.93178589e+02 2.93181610e+02 2.93178650e+02 2.93179779e+02 2.93177582e+02 2.93178833e+02 2.93178101e+02 2.93179810e+02 2.93179169e+02 2.93179382e+02 2.93179382e+02 2.93179047e+02 2.93177338e+02 2.93180023e+02 2.93179840e+02 2.93181152e+02 2.93180695e+02 2.93180939e+02 2.93179840e+02 2.93179169e+02 2.93179230e+02 2.93180054e+02 2.93179199e+02 2.93177612e+02 2.93179749e+02 2.93177948e+02 2.93178772e+02 2.93177887e+02 2.93178711e+02 2.93180145e+02 2.93178680e+02 2.93180603e+02 2.93179596e+02 2.93180908e+02 2.93181702e+02 2.93179718e+02 2.93176849e+02 2.93177216e+02 2.93177795e+02 2.93180511e+02 2.93179871e+02 2.93179474e+02 2.93180267e+02 2.93179596e+02 2.93180450e+02 2.93180450e+02 2.93181458e+02 2.93177734e+02 2.93178467e+02 2.93176361e+02 2.93177460e+02 2.93180115e+02 2.93177704e+02 2.93178253e+02 2.93179810e+02 2.93178619e+02 2.93176392e+02 2.93176270e+02 2.93182037e+02 2.93179474e+02 2.93179749e+02 2.93179291e+02 2.93180328e+02 2.93180115e+02 2.93178375e+02 2.93180084e+02 2.93179352e+02 2.93180267e+02 2.93180023e+02 2.93180511e+02 2.93180847e+02 2.93183258e+02 2.93183105e+02 2.93180298e+02 2.93184509e+02 2.93179291e+02 2.93181824e+02 2.93178650e+02 2.93181885e+02 2.93180695e+02 2.93177490e+02 2.93179169e+02 2.93180023e+02 2.93180756e+02 2.93182861e+02 2.93179993e+02 2.93178070e+02 2.93180511e+02 2.93178497e+02 2.93180695e+02 2.93180542e+02 2.93180023e+02 2.93181580e+02 2.93179840e+02 2.93181152e+02 2.93179474e+02 2.93180145e+02 2.93178986e+02 2.93179260e+02 2.93179626e+02 2.93181091e+02 2.93181915e+02 2.93179352e+02 2.93179199e+02 2.93180450e+02 2.93178345e+02 2.93179535e+02 2.93178650e+02 2.93179901e+02 2.93181335e+02 2.93179474e+02 2.93176147e+02 2.93179901e+02 2.93178131e+02 2.93180084e+02 2.93178741e+02 2.93181488e+02 2.93180634e+02 2.93178864e+02 2.93178802e+02 2.93179474e+02 2.93178467e+02 2.93179993e+02 2.93178131e+02 2.93180206e+02 2.93178497e+02 2.93179474e+02 2.93180908e+02 2.93180420e+02 2.93182831e+02 2.93179596e+02 2.93177338e+02 2.93179840e+02 2.93179352e+02 2.93180237e+02 2.93181396e+02 2.93179169e+02 2.93179810e+02 2.93178314e+02 2.93180237e+02 2.93179749e+02 2.93179230e+02 2.93179871e+02 2.93178589e+02 2.93180359e+02 2.93178741e+02 2.93181702e+02 2.93181702e+02 2.93181061e+02 2.93180878e+02 2.93178802e+02 2.93180237e+02 2.93177673e+02 2.93178833e+02 2.93177765e+02 2.93177734e+02 2.93185669e+02 2.93187012e+02 2.93197174e+02 2.93198853e+02 2.93205261e+02 2.93215942e+02 2.93218140e+02 2.93269257e+02 2.93226929e+02 4.38784668e+02 8.80839600e+02 191309488. -224700528. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.92016327e+02 4.46179718e+02 2.96668976e+02 2.96266205e+02 2.96239410e+02 2.95123901e+02 2.94236298e+02 2.93210663e+02 2.93187805e+02 2.93181091e+02 2.93175873e+02 2.93175568e+02 2.93176392e+02 2.93179047e+02 2.93179443e+02 2.93179138e+02 2.93177124e+02 2.93178101e+02 2.93177826e+02 2.93179688e+02 2.93178314e+02 2.93178040e+02 2.93178345e+02 2.93177399e+02 2.93179810e+02 2.93178162e+02 2.93178925e+02 2.93179871e+02 2.93178314e+02 2.93180359e+02 2.93178040e+02 2.93178101e+02 2.93179718e+02 2.93181000e+02 2.93180267e+02 2.93177826e+02 2.93177917e+02 2.93179718e+02 2.93180237e+02 2.93179321e+02 2.93178955e+02 2.93177063e+02 2.93180511e+02 2.93181519e+02 2.93182129e+02 2.93181152e+02 2.93178528e+02 2.93178314e+02 2.93179840e+02 2.93181305e+02 2.93180634e+02 2.93179260e+02 2.93181335e+02 2.93181091e+02 2.93180145e+02 2.93178650e+02 2.93178833e+02 2.93179626e+02 2.93179047e+02 2.93179382e+02 2.93178253e+02 2.93179932e+02 2.93181976e+02 2.93183411e+02 2.93180725e+02 2.93177460e+02 2.93176697e+02 2.93177429e+02 2.93178192e+02 2.93181030e+02 2.93181366e+02 2.93180847e+02 2.93182983e+02 2.93180603e+02 2.93180664e+02 2.93179535e+02 2.93179382e+02 2.93177338e+02 2.93181580e+02 2.93180634e+02 2.93177246e+02 2.93178009e+02 2.93180969e+02 2.93181488e+02 2.93179260e+02 2.93178345e+02 2.93176483e+02 2.93180206e+02 2.93179138e+02 2.93179321e+02 2.93176788e+02 2.93177460e+02 2.93180908e+02 2.93180420e+02 2.93181091e+02 2.93180511e+02 2.93179321e+02 2.93178497e+02 2.93179596e+02 2.93182678e+02 2.93181152e+02 2.93181030e+02 2.93180298e+02 2.93178375e+02 2.93181061e+02 2.93177887e+02 2.93180267e+02 2.93180756e+02 2.93178680e+02 2.93181213e+02 2.93177979e+02 2.93178436e+02 2.93180328e+02 2.93180969e+02 2.93179779e+02 2.93178711e+02 2.93176880e+02 2.93179504e+02 2.93179840e+02 2.93179993e+02 2.93180481e+02 2.93181671e+02 2.93179596e+02 2.93180908e+02 2.93182587e+02 2.93180084e+02 2.93180359e+02 2.93181488e+02 2.93178497e+02 2.93181366e+02 2.93177399e+02 2.93177917e+02 2.93181213e+02 2.93181854e+02 2.93181671e+02 2.93177856e+02 2.93177643e+02 2.93180573e+02 2.93181366e+02 2.93182922e+02 2.93179199e+02 2.93176392e+02 2.93181274e+02 2.93180511e+02 2.93183441e+02 2.93179657e+02 2.93181793e+02 2.93183594e+02 2.93182648e+02 2.93181915e+02 2.93180786e+02 2.93180145e+02 2.93180298e+02 2.93181396e+02 2.93181213e+02 2.93178314e+02 2.93180573e+02 2.93180389e+02 2.93182526e+02 2.93180206e+02 2.93180634e+02 2.93178436e+02 2.93179932e+02 2.93179047e+02 2.93181305e+02 2.93180603e+02 2.93178375e+02 2.93181763e+02 2.93180481e+02 2.93183167e+02 2.93182434e+02 2.93182251e+02 2.93181274e+02 2.93181580e+02 2.93180237e+02 2.93177185e+02 2.93179169e+02 2.93181519e+02 2.93180878e+02 2.93182495e+02 2.93177582e+02 2.93179993e+02 2.93181122e+02 2.93182922e+02 2.93181549e+02 2.93181396e+02 2.93179688e+02 2.93181549e+02 2.93181213e+02 2.93181702e+02 2.93183411e+02 2.93181885e+02 2.93181213e+02 2.93181122e+02 2.93183258e+02 2.93181488e+02 2.93181824e+02 2.93180389e+02 2.93178528e+02 2.93179626e+02 2.93177856e+02 2.93181488e+02 2.93182800e+02 2.93183319e+02 2.93182434e+02 2.93179779e+02 2.93179016e+02 2.93182312e+02 2.93179535e+02 2.93182404e+02 2.93181122e+02 2.93178833e+02 2.93179230e+02 2.93178833e+02 2.93182281e+02 2.93181610e+02 2.93181824e+02 2.93181793e+02 2.93181091e+02 2.93178436e+02 2.93182800e+02 2.93179321e+02 2.93183685e+02 2.93181763e+02 2.93184296e+02 2.93180450e+02 2.93180115e+02 2.93178925e+02 2.93179932e+02 2.93181458e+02 2.93180908e+02 2.93179443e+02 2.93181549e+02 2.93179016e+02 2.93181763e+02 2.93178162e+02 2.93184052e+02 2.93181915e+02 2.93182312e+02 2.93179413e+02 2.93177246e+02 2.93177979e+02 2.93180634e+02 2.93181305e+02 2.93181763e+02 2.93181152e+02 2.93179077e+02 2.93179138e+02 2.93182251e+02 2.93181824e+02 2.93181030e+02 2.93180450e+02 2.93182739e+02 2.93183441e+02 2.93180664e+02 2.93180237e+02 2.93180084e+02 2.93180603e+02 2.93181549e+02 2.93184143e+02 2.93181549e+02 2.93181610e+02 2.93181702e+02 2.93180542e+02 2.93181183e+02 2.93180725e+02 2.93178375e+02 2.93183075e+02 2.93178986e+02 2.93181061e+02 2.93177002e+02 2.93179962e+02 2.93181030e+02 2.93182587e+02 2.93179565e+02 2.93179810e+02 2.93178680e+02 2.93181641e+02 2.93179932e+02 2.93181549e+02 2.93179932e+02 2.93179749e+02 2.93180908e+02 2.93181641e+02 2.93180084e+02 2.93184082e+02 2.93180573e+02 2.93181488e+02 2.93179810e+02 2.93184021e+02 2.93179657e+02 2.93180878e+02 2.93180756e+02 2.93180298e+02 2.93180908e+02 2.93178131e+02 2.93180359e+02 2.93181183e+02 2.93180939e+02 2.93180420e+02 2.93181091e+02 2.93181305e+02 2.93182007e+02 2.93180878e+02 2.93180573e+02 2.93180878e+02 2.93180573e+02 2.93181793e+02 2.93182526e+02 2.93179077e+02 2.93177826e+02 2.93180023e+02 2.93181427e+02 2.93183807e+02 2.93180725e+02 2.93180023e+02 2.93177368e+02 2.93179443e+02 2.93182434e+02 2.93180634e+02 2.93179779e+02 2.93179260e+02 2.93182892e+02 2.93181091e+02 2.93181122e+02 2.93178925e+02 2.93179291e+02 2.93179504e+02 2.93180817e+02 2.93181335e+02 2.93183289e+02 2.93180634e+02 2.93184021e+02 2.93180725e+02 2.93181580e+02 2.93180298e+02 2.93181915e+02 2.93181885e+02 2.93179108e+02 2.93180298e+02 2.93178619e+02 2.93179565e+02 2.93181244e+02 2.93183533e+02 2.93180023e+02 2.93179199e+02 2.93178650e+02 2.93182495e+02 2.93183502e+02 2.93182068e+02 2.93180084e+02 2.93180084e+02 2.93178772e+02 2.93184235e+02 2.93180969e+02 2.93182800e+02 2.93181305e+02 2.93180328e+02 2.93179688e+02 2.93181671e+02 2.93180267e+02 2.93181305e+02 2.93176697e+02 2.93178619e+02 2.93179352e+02 2.93183685e+02 2.93181335e+02 2.93182220e+02 2.93178986e+02 2.93182037e+02 2.93179932e+02 2.93181183e+02 2.93179749e+02 2.93183441e+02 2.93179443e+02 2.93181519e+02 2.93180176e+02 2.93181122e+02 2.93183105e+02 2.93182495e+02 2.93181091e+02 2.93179565e+02 2.93177979e+02 2.93180969e+02 2.93181702e+02 2.93181366e+02 2.93178833e+02 2.93180878e+02 2.93181458e+02 2.93182190e+02 2.93180878e+02 2.93179413e+02 2.93179688e+02 2.93179535e+02 2.93184082e+02 2.93181549e+02 2.93181854e+02 2.93179291e+02 2.93180359e+02 2.93180756e+02 2.93182617e+02 2.93179626e+02 2.93180817e+02 2.93181366e+02 2.93183289e+02 2.93182159e+02 2.93181030e+02 2.93179657e+02 2.93181000e+02 2.93178589e+02 2.93182587e+02 2.93179413e+02 2.93181488e+02 2.93181274e+02 2.93183289e+02 2.93179749e+02 2.93180115e+02 2.93180298e+02 2.93180237e+02 2.93179779e+02 2.93179199e+02 2.93178802e+02 2.93179016e+02 2.93181641e+02 2.93182037e+02 2.93180756e+02 2.93180786e+02 2.93178833e+02 2.93179565e+02 2.93182129e+02 2.93181854e+02 2.93180542e+02 2.93179169e+02 2.93180603e+02 2.93180084e+02 2.93182831e+02 2.93181244e+02 2.93181335e+02 2.93179413e+02 2.93181976e+02 2.93181519e+02 2.93185242e+02 2.93181091e+02 2.93183594e+02 2.93180267e+02 2.93181274e+02 2.93178986e+02 2.93183533e+02 2.93182770e+02 2.93185974e+02 2.93200592e+02 2.93210419e+02 2.93217468e+02 2.93213806e+02 2.93214386e+02 2.93260345e+02 2.93291992e+02 2.93259186e+02 2.93225708e+02 3.90248199e+02 6.73051880e+02 6.81025439e+03 408063840. 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. 0. 0. 0. 0. 0. 0. 0. -662361344. 1.05954431e+03 4.37522583e+02 2.96682678e+02 2.96244293e+02 2.96234589e+02 2.95350342e+02 2.94410126e+02 2.93225555e+02 2.93185516e+02 2.93178802e+02 2.93179993e+02 2.93181061e+02 2.93181488e+02 2.93180634e+02 2.93181030e+02 2.93180359e+02 2.93179718e+02 2.93179871e+02 2.93179932e+02 2.93179749e+02 2.93182343e+02 2.93179840e+02 2.93181305e+02 2.93179474e+02 2.93181671e+02 2.93179657e+02 2.93180847e+02 2.93178101e+02 2.93180023e+02 2.93178894e+02 2.93181213e+02 2.93181519e+02 2.93179810e+02 2.93182190e+02 2.93180908e+02 2.93179077e+02 2.93180939e+02 2.93181335e+02 2.93182526e+02 2.93178406e+02 2.93181000e+02 2.93179657e+02 2.93181244e+02 2.93180573e+02 2.93181671e+02 2.93179535e+02 2.93180145e+02 2.93182556e+02 2.93182556e+02 2.93182831e+02 2.93178558e+02 2.93180786e+02 2.93179749e+02 2.93181427e+02 2.93183502e+02 2.93181702e+02 2.93182800e+02 2.93180511e+02 2.93182098e+02 2.93180634e+02 2.93180908e+02 2.93179718e+02 2.93180664e+02 2.93180664e+02 2.93179169e+02 2.93183044e+02 2.93182037e+02 2.93181427e+02 2.93178406e+02 2.93179962e+02 2.93179443e+02 2.93180969e+02 2.93179626e+02 2.93181610e+02 2.93181213e+02 2.93183472e+02 2.93182251e+02 2.93184540e+02 2.93179718e+02 2.93182129e+02 2.93178467e+02 2.93180603e+02 2.93180359e+02 2.93180817e+02 2.93181824e+02 2.93179840e+02 2.93181000e+02 2.93179138e+02 2.93180756e+02 2.93180054e+02 2.93182068e+02 2.93179474e+02 2.93180267e+02 2.93179840e+02 2.93182709e+02 2.93183655e+02 2.93177917e+02 2.93180145e+02 2.93179749e+02 2.93179352e+02 2.93180420e+02 2.93180634e+02 2.93182465e+02 2.93179382e+02 2.93181458e+02 2.93178741e+02 2.93179291e+02 2.93181030e+02 2.93179352e+02 2.93181030e+02 2.93181213e+02 2.93180298e+02 2.93179688e+02 2.93179504e+02 2.93180756e+02 2.93182281e+02 2.93180603e+02 2.93180298e+02 2.93178619e+02 2.93179901e+02 2.93181061e+02 2.93180450e+02 2.93181335e+02 2.93179382e+02 2.93179474e+02 2.93177734e+02 2.93179657e+02 2.93179504e+02 2.93179901e+02 2.93178986e+02 2.93180359e+02 2.93180511e+02 2.93180573e+02 2.93179779e+02 2.93179596e+02 2.93181915e+02 2.93182190e+02 2.93178314e+02 2.93179321e+02 2.93178192e+02 2.93183044e+02 2.93183228e+02 2.93181732e+02 2.93178284e+02 2.93176941e+02 2.93179565e+02 2.93179138e+02 2.93181335e+02 2.93180298e+02 2.93181366e+02 2.93178680e+02 2.93180725e+02 2.93179382e+02 2.93179016e+02 2.93180298e+02 2.93180115e+02 2.93179108e+02 2.93180481e+02 2.93181519e+02 2.93181305e+02 2.93181152e+02 2.93179443e+02 2.93180511e+02 2.93180786e+02 2.93179260e+02 2.93180908e+02 2.93180054e+02 2.93180939e+02 2.93179962e+02 2.93179871e+02 2.93179779e+02 2.93182800e+02 2.93180237e+02 2.93178802e+02 2.93178284e+02 2.93179718e+02 2.93178284e+02 2.93181335e+02 2.93179993e+02 2.93180054e+02 2.93179810e+02 2.93179535e+02 2.93176880e+02 2.93178345e+02 2.93181946e+02 2.93182251e+02 2.93178528e+02 2.93178528e+02 2.93177765e+02 2.93178314e+02 2.93182007e+02 2.93179352e+02 2.93179657e+02 2.93177032e+02 2.93180359e+02 2.93179688e+02 2.93178406e+02 2.93180389e+02 2.93177521e+02 2.93179199e+02 2.93181519e+02 2.93181213e+02 2.93182465e+02 2.93180298e+02 2.93181854e+02 2.93178680e+02 2.93180817e+02 2.93178101e+02 2.93178314e+02 2.93179657e+02 2.93181793e+02 2.93181915e+02 2.93179016e+02 2.93179047e+02 2.93180634e+02 2.93182556e+02 2.93180634e+02 2.93180511e+02 2.93179443e+02 2.93180176e+02 2.93179321e+02 2.93180023e+02 2.93180328e+02 2.93180573e+02 2.93181976e+02 2.93179199e+02 2.93179504e+02 2.93182129e+02 2.93178528e+02 2.93180298e+02 2.93177795e+02 2.93179718e+02 2.93179932e+02 2.93181122e+02 2.93178680e+02 2.93180298e+02 2.93181671e+02 2.93178558e+02 2.93178986e+02 2.93179138e+02 2.93180145e+02 2.93179871e+02 2.93181274e+02 2.93180267e+02 2.93178894e+02 2.93180481e+02 2.93178650e+02 2.93179565e+02 2.93178101e+02 2.93180206e+02 2.93181854e+02 2.93180450e+02 2.93179443e+02 2.93178467e+02 2.93181763e+02 2.93178223e+02 2.93178314e+02 2.93181244e+02 2.93181244e+02 2.93181580e+02 2.93182220e+02 2.93179840e+02 2.93180969e+02 2.93179688e+02 2.93180359e+02 2.93182007e+02 2.93180267e+02 2.93181976e+02 2.93178741e+02 2.93177460e+02 2.93179565e+02 2.93181000e+02 2.93180420e+02 2.93180115e+02 2.93180115e+02 2.93178986e+02 2.93181854e+02 2.93178650e+02 2.93181091e+02 2.93180145e+02 2.93182770e+02 2.93178894e+02 2.93179474e+02 2.93178955e+02 2.93178345e+02 2.93182190e+02 2.93181641e+02 2.93180389e+02 2.93179108e+02 2.93180450e+02 2.93180573e+02 2.93179535e+02 2.93179810e+02 2.93180542e+02 2.93180115e+02 2.93178741e+02 2.93179749e+02 2.93180969e+02 2.93178223e+02 2.93181000e+02 2.93180237e+02 2.93181702e+02 2.93180084e+02 2.93179382e+02 2.93178833e+02 2.93183228e+02 2.93180389e+02 2.93181213e+02 2.93178711e+02 2.93179749e+02 2.93181793e+02 2.93180908e+02 2.93179840e+02 2.93178894e+02 2.93179749e+02 2.93181030e+02 2.93180878e+02 2.93181824e+02 2.93179047e+02 2.93182068e+02 2.93182098e+02 2.93181732e+02 2.93182098e+02 2.93179718e+02 2.93181580e+02 2.93178955e+02 2.93181091e+02 2.93180023e+02 2.93180420e+02 2.93181061e+02 2.93179077e+02 2.93181244e+02 2.93181488e+02 2.93179779e+02 2.93177887e+02 2.93180969e+02 2.93181793e+02 2.93184082e+02 2.93179901e+02 2.93182098e+02 2.93181641e+02 2.93181335e+02 2.93182068e+02 2.93178802e+02 2.93181152e+02 2.93180481e+02 2.93181061e+02 2.93179352e+02 2.93181152e+02 2.93182983e+02 2.93183960e+02 2.93183075e+02 2.93182007e+02 2.93179535e+02 2.93182129e+02 2.93183228e+02 2.93182617e+02 2.93180267e+02 2.93177948e+02 2.93180054e+02 2.93184601e+02 2.93182648e+02 2.93183228e+02 2.93179077e+02 2.93180725e+02 2.93181091e+02 2.93180145e+02 2.93182343e+02 2.93179504e+02 2.93181732e+02 2.93179474e+02 2.93181458e+02 2.93182281e+02 2.93180817e+02 2.93181885e+02 2.93181976e+02 2.93182678e+02 2.93183105e+02 2.93178558e+02 2.93181122e+02 2.93182343e+02 2.93180878e+02 2.93181274e+02 2.93179230e+02 2.93180756e+02 2.93181976e+02 2.93181366e+02 2.93181213e+02 2.93180328e+02 2.93182220e+02 2.93180298e+02 2.93180237e+02 2.93179840e+02 2.93179688e+02 2.93179504e+02 2.93177673e+02 2.93180328e+02 2.93182037e+02 2.93181580e+02 2.93181305e+02 2.93180450e+02 2.93184448e+02 2.93182709e+02 2.93181549e+02 2.93180298e+02 2.93182251e+02 2.93181488e+02 2.93182800e+02 2.93180634e+02 2.93180725e+02 2.93180420e+02 2.93181580e+02 2.93180786e+02 2.93180054e+02 2.93179871e+02 2.93180573e+02 2.93180206e+02 2.93183136e+02 2.93181396e+02 2.93181427e+02 2.93181061e+02 2.93180328e+02 2.93180908e+02 2.93180145e+02 2.93181641e+02 2.93180664e+02 2.93181274e+02 2.93180298e+02 2.93179413e+02 2.93178894e+02 2.93181519e+02 2.93183716e+02 2.93182983e+02 2.93179321e+02 2.93180237e+02 2.93180481e+02 2.93181549e+02 2.93184021e+02 2.93181152e+02 2.93181793e+02 2.93180450e+02 2.93181641e+02 2.93183380e+02 2.93180695e+02 2.93184631e+02 2.93181030e+02 2.93181488e+02 2.93179260e+02 2.93181183e+02 2.93181793e+02 2.93181458e+02 2.93182068e+02 2.93181976e+02 2.93178558e+02 2.93179443e+02 2.93181335e+02 2.93181519e+02 2.93183838e+02 2.93180023e+02 2.93181061e+02 2.93180298e+02 2.93182251e+02 2.93181702e+02 2.93180939e+02 2.93180450e+02 2.93180237e+02 2.93180603e+02 2.93181519e+02 2.93181702e+02 2.93182892e+02 2.93179535e+02 2.93180420e+02 2.93182556e+02 2.93181183e+02 2.93181458e+02 2.93180695e+02 2.93180817e+02 2.93182343e+02 2.93182373e+02 2.93181427e+02 2.93183594e+02 2.93181641e+02 2.93180206e+02 2.93178955e+02 2.93181732e+02 2.93182678e+02 2.93179901e+02 2.93179596e+02 2.93179230e+02 2.93181732e+02 2.93181488e+02 2.93181793e+02 2.93182343e+02 2.93182465e+02 2.93183105e+02 2.93183197e+02 2.93181213e+02 2.93183044e+02 2.93179932e+02 2.93180084e+02 2.93181793e+02 2.93182220e+02 2.93181366e+02 2.93179199e+02 2.93179810e+02 2.93183075e+02 2.93182098e+02 2.93182709e+02 2.93180450e+02 2.93182434e+02 2.93179382e+02 2.93179047e+02 2.93184204e+02 2.93180542e+02 2.93180847e+02 2.93179565e+02 2.93179840e+02 2.93180786e+02 2.93179993e+02 2.93180145e+02 2.93180664e+02 2.93181641e+02 2.93181366e+02 2.93180725e+02 2.93181641e+02 2.93182129e+02 2.93178345e+02 2.93181152e+02 2.93177734e+02 2.93178711e+02 2.93178497e+02 2.93179901e+02 2.93181641e+02 2.93180084e+02 2.93181000e+02 2.93180878e+02 2.93179626e+02 2.93182037e+02 2.93178619e+02 2.93183350e+02 2.93179840e+02 2.93183258e+02 2.93183044e+02 2.93179626e+02 2.93180786e+02 2.93180389e+02 2.93180237e+02 2.93179291e+02 2.93179535e+02 2.93180634e+02 2.93181854e+02 2.93181610e+02 2.93181610e+02 2.93179840e+02 2.93179077e+02 2.93181274e+02 2.93179840e+02 2.93179565e+02 2.93177734e+02 2.93181946e+02 2.93181091e+02 2.93179504e+02 2.93181671e+02 2.93179535e+02 2.93180145e+02 2.93177307e+02 2.93180817e+02 2.93181458e+02 2.93179718e+02 2.93180023e+02 2.93181396e+02 2.93180908e+02 2.93178894e+02 2.93179871e+02 2.93177582e+02 2.93180603e+02 2.93181396e+02 2.93179657e+02 2.93178589e+02 2.93178223e+02 2.93180328e+02 2.93180115e+02 2.93182068e+02 2.93177887e+02 2.93180389e+02 2.93179901e+02 2.93179321e+02 2.93179688e+02 2.93179565e+02 2.93179779e+02 2.93179382e+02 2.93180145e+02 2.93180634e+02 2.93180786e+02 2.93180145e+02 2.93179932e+02 2.93182800e+02 2.93186859e+02 2.93179718e+02 2.93183105e+02 2.93185364e+02 2.93186310e+02 2.93189423e+02 2.93203766e+02 2.93214539e+02 2.93236084e+02 2.93495758e+02 2.94208008e+02 4.21734894e+02 7.75598267e+02 2.64754932e+03 -4112165. 0. 0. 0. 0. 0. 1983649664. -2.95593293e+09 8.13317139e+02 7.59830261e+02 8.95897583e+02 1438243840. 0. 0. 2.83988480e+09 2.83988480e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.65576525e+09 -6.76188467e+09 6.05676270e+03 1.16502356e+03 7.15033813e+02 5.81679626e+02 5.81720886e+02 5.82613892e+02 5.82329346e+02 5.81649963e+02 5.81794983e+02 5.82007568e+02 5.81886108e+02 5.81627014e+02 5.81601990e+02 5.81606140e+02 5.81602844e+02 5.81601440e+02 5.81595642e+02 5.81661194e+02 5.81704834e+02 5.81642273e+02 5.81615906e+02 5.81771606e+02 5.81741943e+02 5.81686890e+02 5.81644714e+02 5.81604736e+02 5.81607483e+02 5.81598877e+02 5.81632324e+02 5.81696167e+02 5.81768982e+02 5.81736023e+02 5.81601074e+02 5.81639282e+02 5.81726196e+02 5.81780640e+02 5.81708130e+02 5.81692627e+02 5.81660828e+02 5.81598877e+02 5.81635193e+02 5.81636780e+02 5.81610229e+02 5.81754211e+02 5.81832092e+02 5.81707153e+02 5.81593018e+02 5.81609985e+02 5.81607239e+02 5.81597839e+02 5.81616028e+02 5.81633972e+02 5.81686707e+02 5.81693359e+02 5.81638916e+02 5.81592285e+02 5.81598267e+02 5.81602417e+02 5.81676392e+02 5.81698486e+02 5.81660278e+02 5.81604004e+02 5.81615112e+02 5.81609558e+02 5.81593811e+02 5.81646057e+02 5.81659668e+02 5.81602905e+02 5.81698059e+02 5.81710327e+02 5.81611694e+02 5.81627075e+02 5.81633545e+02 5.81602600e+02 5.81603210e+02 5.81599426e+02 5.81626160e+02 5.81711487e+02 5.81765381e+02 5.81674377e+02 5.81608215e+02 5.81736267e+02 5.81692566e+02 5.81628418e+02 5.81602417e+02 5.81611755e+02 5.81624207e+02 5.81643860e+02 5.81601807e+02 5.81630188e+02 5.81721741e+02 5.81686829e+02 5.81597900e+02 5.81686401e+02 5.81841003e+02 5.81863525e+02 5.81692688e+02 5.81636414e+02 5.81605042e+02 5.81628479e+02 5.81696350e+02 5.81674072e+02 5.81605530e+02 5.81639038e+02 5.81625183e+02 5.81598511e+02 5.81664612e+02 5.81670044e+02 5.81645874e+02 5.81643921e+02 5.81616272e+02 5.81602356e+02 5.81598450e+02 5.81615784e+02 5.81612305e+02 5.81597839e+02 5.81613159e+02 5.81597351e+02 5.81630554e+02 5.81679260e+02 5.81644714e+02 5.81613525e+02 5.81730713e+02 5.81650696e+02 5.81622437e+02 5.81640747e+02 5.81700562e+02 5.81608154e+02 5.81640442e+02 5.81688660e+02 5.81602600e+02 5.81651733e+02 5.81728149e+02 5.81654785e+02 5.81607117e+02 5.81611023e+02 5.81614441e+02 5.81602173e+02 5.81605713e+02 5.81604370e+02 5.81637024e+02 5.81699463e+02 5.81711975e+02 5.81640137e+02 5.81605652e+02 5.81606995e+02 5.81603882e+02 5.81630554e+02 5.81675720e+02 5.81661743e+02 5.81655396e+02 5.81670349e+02 5.81636353e+02 5.81609619e+02 5.81666199e+02 5.81679138e+02 5.81609558e+02 5.81595337e+02 5.81593689e+02 5.81606445e+02 5.81613037e+02 5.81608704e+02 5.81602051e+02 5.81628967e+02 5.81611938e+02 5.81610413e+02 5.81638062e+02 5.81619446e+02 5.81615723e+02 5.81707336e+02 5.81767212e+02 5.81734192e+02 5.81630920e+02 5.81622620e+02 5.81630920e+02 5.81611145e+02 5.81620667e+02 5.81663452e+02 5.81843384e+02 5.81967590e+02 5.81932983e+02 5.81713867e+02 5.81608521e+02 5.81642944e+02 5.81660767e+02 5.81664246e+02 5.81674011e+02 5.81632812e+02 5.81616760e+02 5.81618286e+02 5.81609863e+02 5.81646179e+02 5.81654053e+02 5.81605530e+02 5.81630737e+02 5.81664368e+02 5.81738342e+02 5.81739441e+02 5.81718018e+02 5.81641418e+02 5.81614746e+02 5.81612183e+02 5.81628723e+02 5.81730347e+02 5.81817749e+02 5.81857727e+02 5.81681702e+02 5.81603027e+02 5.81649292e+02 5.81628235e+02 5.81606934e+02 5.81606567e+02 5.81597717e+02 5.81641235e+02 5.81664490e+02 5.81606995e+02 5.81651917e+02 5.81705933e+02 5.81623657e+02 5.81613586e+02 5.81619934e+02 5.81621155e+02 5.81602234e+02 5.81611938e+02 5.81630310e+02 5.81612305e+02 5.81613342e+02 5.81611572e+02 5.81623535e+02 5.81679504e+02 5.81673401e+02 5.81631653e+02 5.81603149e+02 5.81635010e+02 5.81632812e+02 5.81634216e+02 5.81621521e+02 5.81614441e+02 5.81621338e+02 5.81671875e+02 5.81665100e+02 5.81630432e+02 5.81602356e+02 5.81615662e+02 5.81651978e+02 5.81642822e+02 5.81600403e+02 5.81609741e+02 5.81612427e+02 5.81629761e+02 5.81636414e+02 5.81645752e+02 5.81678833e+02 5.81605774e+02 5.81680603e+02 5.81761230e+02 5.81629883e+02 5.81600586e+02 5.81614624e+02 5.81596680e+02 5.81633484e+02 5.81645752e+02 5.81613098e+02 5.81637085e+02 5.81659485e+02 5.81614563e+02 5.81602722e+02 5.81610107e+02 5.81610840e+02 5.81662048e+02 5.81625183e+02 5.81601990e+02 5.81617126e+02 5.81645142e+02 5.81697144e+02 5.81744263e+02 5.81642822e+02 5.81618164e+02 5.81622009e+02 5.81660950e+02 5.81706482e+02 5.81633240e+02 5.81615723e+02 5.81662842e+02 5.81672241e+02 5.81611755e+02 5.81600952e+02 5.81620300e+02 5.81671570e+02 5.81643494e+02 5.81604736e+02 5.81601257e+02 5.81620056e+02 5.81654419e+02 5.81720581e+02 5.81628235e+02 5.81617126e+02 5.81609924e+02 5.81599731e+02 5.81606567e+02 5.81601746e+02 5.81622253e+02 5.81673767e+02 5.81668213e+02 5.81608887e+02 5.81667175e+02 5.81632568e+02 5.81606628e+02 5.81626587e+02 5.81681641e+02 5.81656799e+02 5.81619263e+02 5.81603821e+02 5.81603455e+02 5.81612793e+02 5.81644287e+02 5.81630249e+02 5.81621460e+02 5.81626221e+02 5.81662109e+02 5.81645264e+02 5.81632996e+02 5.81630249e+02 5.81601685e+02 5.81632629e+02 5.81657349e+02 5.81614014e+02 5.81605469e+02 5.81612976e+02 5.81624451e+02 5.81642395e+02 5.81614075e+02 5.81611389e+02 5.81642090e+02 5.81643250e+02 5.81625671e+02 5.81650818e+02 5.81719727e+02 5.81712158e+02 5.81798096e+02 5.81750549e+02 5.81642395e+02 5.81640442e+02 5.81690796e+02 5.81740112e+02 5.81626282e+02 5.81612549e+02 5.81608582e+02 5.81626953e+02 5.81713928e+02 5.81820557e+02 5.81718872e+02 5.81635254e+02 5.81634460e+02 5.81626221e+02 5.81611450e+02 5.81609375e+02 5.81607605e+02 5.81638733e+02 5.81617554e+02 5.81632202e+02 5.81670593e+02 5.81730347e+02 5.81709106e+02 5.81767456e+02 5.81699158e+02 5.81608459e+02 5.81607483e+02 5.81608093e+02 5.81664734e+02 5.81614624e+02 5.81608276e+02 5.81626526e+02 5.81609741e+02 5.81624146e+02 5.81801392e+02 5.81856018e+02 5.81675293e+02 5.81627930e+02 5.81625488e+02 5.81646606e+02 5.81707642e+02 5.81637634e+02 5.81639160e+02 5.81617920e+02 5.81628235e+02 5.81715454e+02 5.81685547e+02 5.81628784e+02 5.81651489e+02 5.81652344e+02 5.81649841e+02 5.81689697e+02 5.81628662e+02 5.81658447e+02 5.81658875e+02 5.81634338e+02 5.81753784e+02 5.81851807e+02 5.81740356e+02 5.81677734e+02 5.81648926e+02 5.81616760e+02 5.81615540e+02 5.81616028e+02 5.81711792e+02 5.81720215e+02 5.81603455e+02 5.81633850e+02 5.81703674e+02 5.81652771e+02 5.81619141e+02 5.81650208e+02 5.81611755e+02 5.81682373e+02 5.81667358e+02 5.81625793e+02 5.81851135e+02 5.81995728e+02 5.81706421e+02 5.81605286e+02 5.81633118e+02 5.81637207e+02 5.81615234e+02 5.81606079e+02 5.81643188e+02 5.81729919e+02 5.81687805e+02 5.81645447e+02 5.81598328e+02 5.81603027e+02 5.81610718e+02 5.81609741e+02 5.81621643e+02 5.81617737e+02 5.81613831e+02 5.81683289e+02 5.81675049e+02 5.81645020e+02 5.81643127e+02 5.81698486e+02 5.81660156e+02 5.81624512e+02 5.81610779e+02 5.81601135e+02 5.81618774e+02 5.81712769e+02 5.81714050e+02 5.81636169e+02 5.81608704e+02 5.81612793e+02 5.81630371e+02 5.81620911e+02 5.81634216e+02 5.81644348e+02 5.81609619e+02 5.81644287e+02 5.81620728e+02 5.81617798e+02 5.81679749e+02 5.81661865e+02 5.81612427e+02 5.81616699e+02 5.81615662e+02 5.81632202e+02 5.81642029e+02 5.81616211e+02 5.81634338e+02 5.81683350e+02 5.81634949e+02 5.81623901e+02 5.81618774e+02 5.81613586e+02 5.81621216e+02 5.81598877e+02 5.81608398e+02 5.81645203e+02 5.81632080e+02 5.81609924e+02 5.81627686e+02 5.81656311e+02 5.81610535e+02 5.81615784e+02 5.81613892e+02 5.81616272e+02 5.81618164e+02 5.81607544e+02 5.81619812e+02 5.81671143e+02 5.81614441e+02 5.81630371e+02 5.81651367e+02 5.81626831e+02 5.81613708e+02 5.81616211e+02 5.81630066e+02 5.81615784e+02 5.81605225e+02 5.81606018e+02 5.81608582e+02 5.81627075e+02 5.81650757e+02 5.81618652e+02 5.81644897e+02 5.81704407e+02 5.81663086e+02 5.81598389e+02 5.81608948e+02 5.81611023e+02 5.81663452e+02 5.81671021e+02 5.81617798e+02 5.81612732e+02 5.81605774e+02 5.81627869e+02 5.81644470e+02 5.81609375e+02 5.81607544e+02 5.81609680e+02 5.81602173e+02 5.81621582e+02 5.81634338e+02 5.81630066e+02 5.81692993e+02 5.81639893e+02 5.81596008e+02 5.81609131e+02 5.81608276e+02 5.81660522e+02 5.81704163e+02 5.81727844e+02 5.81612915e+02 5.81598755e+02 5.81601990e+02 5.81621033e+02 5.81663696e+02 5.81608521e+02 5.81632690e+02 5.81752380e+02 5.81664978e+02 5.81596436e+02 5.81609558e+02 5.81645935e+02 5.81620605e+02 5.81605652e+02 5.81634949e+02 5.81616577e+02 5.81623230e+02 5.81699768e+02 5.81659790e+02 5.81618713e+02 5.81596497e+02 5.81621277e+02 5.81652893e+02 5.81697815e+02 5.81669617e+02 5.81596436e+02 5.81612732e+02 5.81606323e+02 5.81648804e+02 5.81709412e+02 5.81665466e+02 5.81635620e+02 5.81612000e+02 5.81606750e+02 5.81616272e+02 5.81630615e+02 5.81640503e+02 5.81605652e+02 5.81594543e+02 5.81590393e+02 5.81597778e+02 5.81639893e+02 5.81712097e+02 5.81705078e+02 5.81620911e+02 5.81599182e+02 5.81603210e+02 5.81629944e+02 5.81696777e+02 5.81658813e+02 5.81598450e+02 5.81617310e+02 5.81607178e+02 5.81661682e+02 5.81734863e+02 5.81621521e+02 5.81609436e+02 5.81628540e+02 5.81597717e+02 5.81622192e+02 5.81625793e+02 5.81614258e+02 5.81603455e+02 5.81598083e+02 5.81597107e+02 5.81605957e+02 5.81623535e+02 5.81626648e+02 5.81645874e+02 5.81626343e+02 5.81598694e+02 5.81607056e+02 5.81619080e+02 5.81729736e+02 5.81671326e+02 5.81612244e+02 5.81662354e+02 5.81653198e+02 5.81683716e+02 5.81716003e+02 5.81678162e+02 5.81685608e+02 5.81724426e+02 5.81707092e+02 5.81699951e+02 5.81717407e+02 5.82739014e+02 5.84246460e+02 8.23992004e+02 1.64304102e+03 821182272. -1482585856. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -407196224. 669654016. -3.80612480e+09 708823552. -7.60187585e+11 1.73902319e+03 8.70910278e+02 5.81690247e+02 5.81675842e+02 5.81695435e+02 5.81735535e+02 5.81730957e+02 5.81731079e+02 5.81696960e+02 5.81631531e+02 5.81645752e+02 5.81622803e+02 5.81671509e+02 5.81729065e+02 5.81613647e+02 5.81623840e+02 5.81653137e+02 5.81614990e+02 5.81655640e+02 5.81677063e+02 5.81663818e+02 5.81622559e+02 5.81628235e+02 5.81636414e+02 5.81622009e+02 5.81621338e+02 5.81620300e+02 5.81601624e+02 5.81601624e+02 5.81599426e+02 5.81631653e+02 5.81679871e+02 5.81722412e+02 5.81649963e+02 5.81616150e+02 5.81655273e+02 5.81628662e+02 5.81634827e+02 5.81675171e+02 5.81640259e+02 5.81626221e+02 5.81605469e+02 5.81610657e+02 5.81615051e+02 5.81626709e+02 5.81620239e+02 5.81624268e+02 5.81632874e+02 5.81642334e+02 5.81635254e+02 5.81620422e+02 5.81648804e+02 5.81638062e+02 5.81605591e+02 5.81659180e+02 5.81621521e+02 5.81619690e+02 5.81712097e+02 5.81711304e+02 5.81601929e+02 5.81612244e+02 5.81628357e+02 5.81617554e+02 5.81692383e+02 5.81649170e+02 5.81621277e+02 5.81607300e+02 5.81611389e+02 5.81658752e+02 5.81654053e+02 5.81617981e+02 5.81658142e+02 5.81718079e+02 5.81726318e+02 5.81652954e+02 5.81625183e+02 5.81625977e+02 5.81606873e+02 5.81601379e+02 5.81606506e+02 5.81615234e+02 5.81620667e+02 5.81650574e+02 5.81614868e+02 5.81694763e+02 5.81737061e+02 5.81655212e+02 5.81633911e+02 5.81686523e+02 5.81644531e+02 5.81630737e+02 5.81616638e+02 5.81609558e+02 5.81607300e+02 5.81634399e+02 5.81640198e+02 5.81619568e+02 5.81630005e+02 5.81632812e+02 5.81624634e+02 5.81632080e+02 5.81647400e+02 5.81664856e+02 5.81644226e+02 5.81607666e+02 5.81609009e+02 5.81619385e+02 5.81684692e+02 5.81692932e+02 5.81616638e+02 5.81604492e+02 5.81612549e+02 5.81639587e+02 5.81697083e+02 5.81642395e+02 5.81619324e+02 5.81622559e+02 5.81641846e+02 5.81639282e+02 5.81611816e+02 5.81619019e+02 5.81624390e+02 5.81593750e+02 5.81618347e+02 5.81637573e+02 5.81609985e+02 5.81645264e+02 5.81669006e+02 5.81652039e+02 5.81609802e+02 5.81646118e+02 5.81634277e+02 5.81620483e+02 5.81667725e+02 5.81604004e+02 5.81596985e+02 5.81605774e+02 5.81640442e+02 5.81747192e+02 5.81686401e+02 5.81643372e+02 5.81611084e+02 5.81605957e+02 5.81649414e+02 5.81676514e+02 5.81688232e+02 5.81673096e+02 5.81633118e+02 5.81605103e+02 5.81593079e+02 5.81643188e+02 5.81705139e+02 5.81732727e+02 5.81661011e+02 5.81602783e+02 5.81598206e+02 5.81620361e+02 5.81638916e+02 5.81649536e+02 5.81601440e+02 5.81613464e+02 5.81609863e+02 5.81596191e+02 5.81598022e+02 5.81610168e+02 5.81610596e+02 5.81610474e+02 5.81616272e+02 5.81622925e+02 5.81616150e+02 5.81617615e+02 5.81619385e+02 5.81609741e+02 5.81599243e+02 5.81596985e+02 5.81605103e+02 5.81660522e+02 5.81727173e+02 5.81745178e+02 5.81641479e+02 5.81604309e+02 5.81618896e+02 5.81661255e+02 5.81780640e+02 5.81709229e+02 5.81662048e+02 5.81590576e+02 5.81605713e+02 5.81629333e+02 5.81656372e+02 5.81639038e+02 5.81618103e+02 5.81591675e+02 5.81599304e+02 5.81611145e+02 5.81609253e+02 5.81612427e+02 5.81587463e+02 5.81604736e+02 5.81627075e+02 5.81596802e+02 5.81641357e+02 5.81722351e+02 5.81711182e+02 5.81610779e+02 5.81592773e+02 5.81600891e+02 5.81638977e+02 5.81663086e+02 5.81613586e+02 5.81603821e+02 5.81609985e+02 5.81612427e+02 5.81631653e+02 5.81614258e+02 5.81598572e+02 5.81610168e+02 5.81671387e+02 5.81689819e+02 5.81664917e+02 5.81595520e+02 5.81606384e+02 5.81660156e+02 5.81629150e+02 5.81628479e+02 5.81791992e+02 5.81767822e+02 5.81609497e+02 5.81602173e+02 5.81595764e+02 5.81597229e+02 5.81598999e+02 5.81609985e+02 5.81598145e+02 5.81594360e+02 5.81599121e+02 5.81602295e+02 5.81577332e+02 5.81572937e+02 5.81581665e+02 5.81611694e+02 5.81626343e+02 5.81610046e+02 5.81578491e+02 5.81592468e+02 5.81592224e+02 5.81602234e+02 5.81589233e+02 5.81612915e+02 5.81616699e+02 5.81607788e+02 5.81592651e+02 5.81593323e+02 5.81600220e+02 5.81593018e+02 5.81599365e+02 5.81597778e+02 5.81599487e+02 5.81604614e+02 5.81605774e+02 5.81601562e+02 5.81597229e+02 5.81586182e+02 5.81604675e+02 5.81585876e+02 5.81610291e+02 5.81588074e+02 5.81601440e+02 5.81585876e+02 5.81598511e+02 5.81598572e+02 5.81604675e+02 5.81585022e+02 5.81588806e+02 5.81589172e+02 5.81607483e+02 5.81601929e+02 5.81600525e+02 5.81593872e+02 5.81601685e+02 5.81599060e+02 5.81615112e+02 5.81595886e+02 5.81602051e+02 5.81586121e+02 5.81603577e+02 5.81592468e+02 5.81594482e+02 5.81591431e+02 5.81589050e+02 5.81598633e+02 5.81598633e+02 5.81597900e+02 5.81596375e+02 5.81594666e+02 5.81590637e+02 5.81594421e+02 5.81586975e+02 5.81592163e+02 5.81593262e+02 5.81600708e+02 5.81600220e+02 5.81584595e+02 5.81583130e+02 5.81603271e+02 5.81606323e+02 5.81604309e+02 5.81594543e+02 5.81594360e+02 5.81594055e+02 5.81598450e+02 5.81601135e+02 5.81601624e+02 5.81587646e+02 5.81600037e+02 5.81603394e+02 5.81611328e+02 5.81591370e+02 5.81607666e+02 5.81597839e+02 5.81607422e+02 5.81596497e+02 5.81601990e+02 5.81585876e+02 5.81593384e+02 5.81587646e+02 5.81604431e+02 5.81591064e+02 5.81605774e+02 5.81597839e+02 5.81597656e+02 5.81598389e+02 5.81586304e+02 5.81594299e+02 5.81593079e+02 5.81604065e+02 5.81595276e+02 5.81588623e+02 5.81592834e+02 5.81603088e+02 5.81601746e+02 5.81602600e+02 5.81589172e+02 5.81586426e+02 5.81588501e+02 5.81602783e+02 5.81598450e+02 5.81604614e+02 5.81614624e+02 5.81635925e+02 5.81636108e+02 5.81623413e+02 5.81602661e+02 5.81598267e+02 5.81588379e+02 5.81596802e+02 5.81601990e+02 5.81609680e+02 5.81610352e+02 5.81642944e+02 5.81618225e+02 5.81605530e+02 5.81596069e+02 5.81606628e+02 5.81607056e+02 5.81621521e+02 5.81597473e+02 5.81601135e+02 5.81592407e+02 5.81604858e+02 5.81620056e+02 5.81636902e+02 5.81604553e+02 5.81580627e+02 5.81584778e+02 5.81592896e+02 5.81598877e+02 5.81602600e+02 5.81583313e+02 5.81587341e+02 5.81594971e+02 5.81630798e+02 5.81614441e+02 5.81595642e+02 5.81588501e+02 5.81593262e+02 5.81599182e+02 5.81604492e+02 5.81600830e+02 5.81584534e+02 5.81585571e+02 5.81591980e+02 5.81607483e+02 5.81591431e+02 5.81596802e+02 5.81587646e+02 5.81601135e+02 5.81595337e+02 5.81605042e+02 5.81631165e+02 5.81666077e+02 5.81625000e+02 5.81597351e+02 5.81592407e+02 5.81597412e+02 5.81591736e+02 5.81603210e+02 5.81602417e+02 5.81602112e+02 5.81596924e+02 5.81601746e+02 5.81596802e+02 5.81598511e+02 5.81586609e+02 5.81598755e+02 5.81597351e+02 5.81604980e+02 5.81598389e+02 5.81595154e+02 5.81582520e+02 5.81592346e+02 5.81595398e+02 5.81602600e+02 5.81593811e+02 5.81614868e+02 5.81618958e+02 5.81610046e+02 5.81601440e+02 5.81596130e+02 5.81594116e+02 5.81585754e+02 5.81601257e+02 5.81591919e+02 5.81602173e+02 5.81624939e+02 5.81643921e+02 5.81604736e+02 5.81602966e+02 5.81583252e+02 5.81605103e+02 5.81606201e+02 5.81607910e+02 5.81600708e+02 5.81584290e+02 5.81616211e+02 5.81642151e+02 5.81681274e+02 5.81690674e+02 5.81695984e+02 5.81719849e+02 5.81728333e+02 5.81700623e+02 5.81670410e+02 5.81723206e+02 5.81700317e+02 5.82738647e+02 8.37089539e+02 2.24573657e+03 -2.75051981e+09 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. 0. 0. 0. 0. 0. 0. 0. -3.42252800e+09 -1155212160. -284272224. -899558528. 9.72683496e+03 1.34259790e+03 8.01906494e+02 5.82859375e+02 5.81964661e+02 5.81683105e+02 5.81701721e+02 5.81653503e+02 5.81635559e+02 5.81617737e+02 5.81620544e+02 5.81616211e+02 5.81604370e+02 5.81600586e+02 5.81593811e+02 5.81603882e+02 5.81596069e+02 5.81603760e+02 5.81603638e+02 5.81598083e+02 5.81593140e+02 5.81601990e+02 5.81611206e+02 5.81633606e+02 5.81656799e+02 5.81661560e+02 5.81649841e+02 5.81628418e+02 5.81619446e+02 5.81619690e+02 5.81622620e+02 5.81616211e+02 5.81592285e+02 5.81591797e+02 5.81599792e+02 5.81599060e+02 5.81593750e+02 5.81591492e+02 5.81594482e+02 5.81592957e+02 5.81591553e+02 5.81587830e+02 5.81592773e+02 5.81588318e+02 5.81595825e+02 5.81592468e+02 5.81603516e+02 5.81595093e+02 5.81607788e+02 5.81594116e+02 5.81587463e+02 5.81598633e+02 5.81600586e+02 5.81610657e+02 5.81605652e+02 5.81594055e+02 5.81596130e+02 5.81583374e+02 5.81598389e+02 5.81610779e+02 5.81625366e+02 5.81615723e+02 5.81621399e+02 5.81632996e+02 5.81622681e+02 5.81624634e+02 5.81604004e+02 5.81604858e+02 5.81601379e+02 5.81595642e+02 5.81598267e+02 5.81605408e+02 5.81660583e+02 5.81658997e+02 5.81621582e+02 5.81587769e+02 5.81606384e+02 5.81600952e+02 5.81611450e+02 5.81639099e+02 5.81699402e+02 5.81743347e+02 5.81678955e+02 5.81632080e+02 5.81597595e+02 5.81602234e+02 5.81603210e+02 5.81602234e+02 5.81604553e+02 5.81601074e+02 5.81594177e+02 5.81590393e+02 5.81608826e+02 5.81608398e+02 5.81606140e+02 5.81593628e+02 5.81593689e+02 5.81599365e+02 5.81597351e+02 5.81604675e+02 5.81606018e+02 5.81623169e+02 5.81601990e+02 5.81603882e+02 5.81631531e+02 5.81655090e+02 5.81657410e+02 5.81615784e+02 5.81605957e+02 5.81636414e+02 5.81625000e+02 5.81600159e+02 5.81607178e+02 5.81629517e+02 5.81655640e+02 5.81627991e+02 5.81589722e+02 5.81598999e+02 5.81594727e+02 5.81609497e+02 5.81610901e+02 5.81619324e+02 5.81612122e+02 5.81599060e+02 5.81610291e+02 5.81606689e+02 5.81610352e+02 5.81602417e+02 5.81623535e+02 5.81684937e+02 5.81767212e+02 5.81772217e+02 5.81700256e+02 5.81643250e+02 5.81609985e+02 5.81600159e+02 5.81592651e+02 5.81595337e+02 5.81599304e+02 5.81611755e+02 5.81601562e+02 5.81590637e+02 5.81596375e+02 5.81592834e+02 5.81608521e+02 5.81590149e+02 5.81599182e+02 5.81598877e+02 5.81619385e+02 5.81691833e+02 5.81675842e+02 5.81625427e+02 5.81592896e+02 5.81623169e+02 5.81691528e+02 5.81786255e+02 5.81759583e+02 5.81651550e+02 5.81614807e+02 5.81598022e+02 5.81607544e+02 5.81597168e+02 5.81600403e+02 5.81593567e+02 5.81605286e+02 5.81596558e+02 5.81598206e+02 5.81598328e+02 5.81601624e+02 5.81611145e+02 5.81597473e+02 5.81593506e+02 5.81595032e+02 5.81588318e+02 5.81617432e+02 5.81623413e+02 5.81604858e+02 5.81597839e+02 5.81602234e+02 5.81606750e+02 5.81590149e+02 5.81602478e+02 5.81629456e+02 5.81612244e+02 5.81600159e+02 5.81601074e+02 5.81592468e+02 5.81596924e+02 5.81595032e+02 5.81605957e+02 5.81599365e+02 5.81593323e+02 5.81593689e+02 5.81592651e+02 5.81603821e+02 5.81593933e+02 5.81603638e+02 5.81600342e+02 5.81617493e+02 5.81649231e+02 5.81679810e+02 5.81653687e+02 5.81627380e+02 5.81608093e+02 5.81608337e+02 5.81596069e+02 5.81591553e+02 5.81599426e+02 5.81595642e+02 5.81603821e+02 5.81591492e+02 5.81591797e+02 5.81605408e+02 5.81593018e+02 5.81604614e+02 5.81601562e+02 5.81624023e+02 5.81668762e+02 5.81635681e+02 5.81612122e+02 5.81592285e+02 5.81605713e+02 5.81600830e+02 5.81594666e+02 5.81622986e+02 5.81628235e+02 5.81608521e+02 5.81593994e+02 5.81604797e+02 5.81601562e+02 5.81606201e+02 5.81588623e+02 5.81596069e+02 5.81597107e+02 5.81603271e+02 5.81594299e+02 5.81584778e+02 5.81595337e+02 5.81597412e+02 5.81604919e+02 5.81599670e+02 5.81610107e+02 5.81661743e+02 5.81679932e+02 5.81662109e+02 5.81610535e+02 5.81601990e+02 5.81604431e+02 5.81630737e+02 5.81699463e+02 5.81660767e+02 5.81611084e+02 5.81596863e+02 5.81595154e+02 5.81599548e+02 5.81591064e+02 5.81582458e+02 5.81595764e+02 5.81645874e+02 5.81671448e+02 5.81629944e+02 5.81600098e+02 5.81597473e+02 5.81596497e+02 5.81609741e+02 5.81602844e+02 5.81609436e+02 5.81624512e+02 5.81620178e+02 5.81609802e+02 5.81588440e+02 5.81606995e+02 5.81600525e+02 5.81610046e+02 5.81628784e+02 5.81611328e+02 5.81592041e+02 5.81604187e+02 5.81609192e+02 5.81616760e+02 5.81604248e+02 5.81587708e+02 5.81595947e+02 5.81600891e+02 5.81608398e+02 5.81598145e+02 5.81593384e+02 5.81598389e+02 5.81594238e+02 5.81604614e+02 5.81599060e+02 5.81631287e+02 5.81681702e+02 5.81716003e+02 5.81695984e+02 5.81616333e+02 5.81600891e+02 5.81596741e+02 5.81602783e+02 5.81598083e+02 5.81594055e+02 5.81587952e+02 5.81591980e+02 5.81602051e+02 5.81604980e+02 5.81593201e+02 5.81587891e+02 5.81593628e+02 5.81598999e+02 5.81600159e+02 5.81592285e+02 5.81587708e+02 5.81594604e+02 5.81590820e+02 5.81604187e+02 5.81589172e+02 5.81598083e+02 5.81599426e+02 5.81596130e+02 5.81606079e+02 5.81599915e+02 5.81609802e+02 5.81636963e+02 5.81693420e+02 5.81700012e+02 5.81659180e+02 5.81667786e+02 5.81646545e+02 5.81662048e+02 5.81630676e+02 5.81606567e+02 5.81592712e+02 5.81596130e+02 5.81638977e+02 5.81645630e+02 5.81616089e+02 5.81602112e+02 5.81596375e+02 5.81595581e+02 5.81597290e+02 5.81587585e+02 5.81590942e+02 5.81596191e+02 5.81633423e+02 5.81680786e+02 5.81651428e+02 5.81612061e+02 5.81591919e+02 5.81611206e+02 5.81624878e+02 5.81627136e+02 5.81641357e+02 5.81672119e+02 5.81747253e+02 5.81680237e+02 5.81619873e+02 5.81584412e+02 5.81592285e+02 5.81593872e+02 5.81610535e+02 5.81591675e+02 5.81622009e+02 5.81652039e+02 5.81731995e+02 5.81768799e+02 5.81696838e+02 5.81700256e+02 5.81701477e+02 5.81701660e+02 5.81644165e+02 5.81590881e+02 5.81587646e+02 5.81599609e+02 5.81605347e+02 5.81605225e+02 5.81615967e+02 5.81631897e+02 5.81641907e+02 5.81610901e+02 5.81602539e+02 5.81593628e+02 5.81585449e+02 5.81592529e+02 5.81583740e+02 5.81602539e+02 5.81590698e+02 5.81597961e+02 5.81598389e+02 5.81591248e+02 5.81615295e+02 5.81621216e+02 5.81606262e+02 5.81598206e+02 5.81595337e+02 5.81591309e+02 5.81586243e+02 5.81595154e+02 5.81592529e+02 5.81638245e+02 5.81645569e+02 5.81622681e+02 5.81588501e+02 5.81598206e+02 5.81595642e+02 5.81604187e+02 5.81590271e+02 5.81598877e+02 5.81589172e+02 5.81620361e+02 5.81626892e+02 5.81594116e+02 5.81590210e+02 5.81595032e+02 5.81602966e+02 5.81641052e+02 5.81607056e+02 5.81589539e+02 5.81593384e+02 5.81600281e+02 5.81600891e+02 5.81606079e+02 5.81623901e+02 5.81639587e+02 5.81617188e+02 5.81616333e+02 5.81615417e+02 5.81593567e+02 5.81620911e+02 5.81667664e+02 5.81688782e+02 5.81631958e+02 5.81591309e+02 5.81596741e+02 5.81623230e+02 5.81659973e+02 5.81629028e+02 5.81597168e+02 5.81593079e+02 5.81593323e+02 5.81600891e+02 5.81583069e+02 5.81591614e+02 5.81598328e+02 5.81599121e+02 5.81601746e+02 5.81603699e+02 5.81606934e+02 5.81601501e+02 5.81595337e+02 5.81592834e+02 5.81591187e+02 5.81590698e+02 5.81601685e+02 5.81584229e+02 5.81595886e+02 5.81587463e+02 5.81595764e+02 5.81582214e+02 5.81586182e+02 5.81595520e+02 5.81599426e+02 5.81625305e+02 5.81633606e+02 5.81619446e+02 5.81603333e+02 5.81591003e+02 5.81632996e+02 5.81701111e+02 5.81681580e+02 5.81622131e+02 5.81600037e+02 5.81637512e+02 5.81626831e+02 5.81600647e+02 5.81588440e+02 5.81590088e+02 5.81581787e+02 5.81588440e+02 5.81589844e+02 5.81597534e+02 5.81585632e+02 5.81591797e+02 5.81593018e+02 5.81593384e+02 5.81597168e+02 5.81589478e+02 5.81586426e+02 5.81622192e+02 5.81622559e+02 5.81590088e+02 5.81616394e+02 5.81601013e+02 5.81583435e+02 5.81606323e+02 5.81613037e+02 5.81597168e+02 5.81580872e+02 5.81598206e+02 5.81614441e+02 5.81614136e+02 5.81592041e+02 5.81581848e+02 5.81618835e+02 5.81709351e+02 5.81804199e+02 5.81813049e+02 5.81644348e+02 5.81594604e+02 5.81591858e+02 5.81622314e+02 5.81702637e+02 5.81644531e+02 5.81600769e+02 5.81588989e+02 5.81602295e+02 5.81597900e+02 5.81609253e+02 5.81606384e+02 5.81606079e+02 5.81601440e+02 5.81619995e+02 5.81664551e+02 5.81672607e+02 5.81611633e+02 5.81600403e+02 5.81592407e+02 5.81600342e+02 5.81589844e+02 5.81579529e+02 5.81595032e+02 5.81599609e+02 5.81594666e+02 5.81594604e+02 5.81594910e+02 5.81626953e+02 5.81620972e+02 5.81629944e+02 5.81645386e+02 5.81634399e+02 5.81612549e+02 5.81591064e+02 5.81600403e+02 5.81594971e+02 5.81602295e+02 5.81591797e+02 5.81602966e+02 5.81654785e+02 5.81725708e+02 5.81726807e+02 5.81638062e+02 5.81595947e+02 5.81593567e+02 5.81595154e+02 5.81635864e+02 5.81624756e+02 5.81596252e+02 5.81588745e+02 5.81601868e+02 5.81617676e+02 5.81636047e+02 5.81619995e+02 5.81630615e+02 5.81715210e+02 5.81858643e+02 5.81799866e+02 5.81645752e+02 5.81598755e+02 5.81632996e+02 5.81687195e+02 5.81710571e+02 5.81639282e+02 5.81592468e+02 5.81611694e+02 5.81651062e+02 5.81731201e+02 5.81758728e+02 5.81663757e+02 5.81613037e+02 5.81597534e+02 5.81619080e+02 5.81606750e+02 5.81610352e+02 5.81605896e+02 5.81596375e+02 5.81616455e+02 5.81609070e+02 5.81594116e+02 5.81604919e+02 5.81623474e+02 5.81613831e+02 5.81594727e+02 5.81633728e+02 5.81638367e+02 5.81599060e+02 5.81616760e+02 5.81616272e+02 5.81638916e+02 5.81652832e+02 5.81676331e+02 5.81689026e+02 5.81705383e+02 5.81705444e+02 5.81740601e+02 5.81787354e+02 5.81730652e+02 5.81702637e+02 8.72557251e+02 1.76590027e+03 0. 0. 0. 0. 0. 1983649664. -2.95593293e+09 562742656. 1.76629333e+03 1.47862329e+03 1.54467493e+03 -310378336. -1227188992. 2.83988480e+09 2.83988480e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.65576525e+09 -6.76188467e+09 762447744. 8.96737500e+03 2.05290088e+03 1.24288086e+03 9.86065613e+02 9.87322937e+02 9.86105896e+02 9.86384705e+02 9.86269531e+02 9.86035950e+02 9.85929993e+02 9.85905334e+02 9.85901367e+02 9.85909058e+02 9.85911865e+02 9.86011169e+02 9.86197815e+02 9.86155334e+02 9.85892029e+02 9.85974121e+02 9.86156921e+02 9.86273193e+02 9.86067383e+02 9.86022827e+02 9.85949341e+02 9.85882385e+02 9.85904358e+02 9.85866699e+02 9.85981384e+02 9.86388611e+02 9.86340698e+02 9.86026428e+02 9.85926758e+02 9.85996887e+02 9.85942444e+02 9.85916504e+02 9.85909973e+02 9.85896240e+02 9.85942444e+02 9.86060608e+02 9.85981384e+02 9.85910767e+02 9.85917480e+02 9.85909119e+02 9.85940369e+02 9.85906616e+02 9.85938721e+02 9.85924866e+02 9.85936890e+02 9.85913940e+02 9.85928772e+02 9.85985901e+02 9.86005554e+02 9.85895447e+02 9.86177917e+02 9.86347900e+02 9.86056091e+02 9.85921631e+02 9.85926331e+02 9.85901428e+02 9.85936096e+02 9.85921265e+02 9.85908752e+02 9.85927307e+02 9.85951782e+02 9.85935486e+02 9.85911438e+02 9.86018494e+02 9.85945435e+02 9.85920654e+02 9.85900940e+02 9.85902405e+02 9.85906311e+02 9.85966553e+02 9.85926208e+02 9.85960388e+02 9.86138672e+02 9.86063232e+02 9.85895508e+02 9.85946228e+02 9.86065674e+02 9.86084900e+02 9.85924561e+02 9.85911194e+02 9.85901550e+02 9.85943665e+02 9.86126404e+02 9.86126221e+02 9.85898743e+02 9.86046936e+02 9.86029663e+02 9.85915955e+02 9.86080811e+02 9.86099182e+02 9.86033325e+02 9.86031982e+02 9.86044800e+02 9.85957153e+02 9.85907654e+02 9.85912659e+02 9.85911316e+02 9.85995300e+02 9.85991638e+02 9.85904480e+02 9.85950073e+02 9.85992737e+02 9.85969666e+02 9.85917236e+02 9.85967712e+02 9.85945740e+02 9.85947754e+02 9.86009338e+02 9.86050354e+02 9.85938843e+02 9.85923218e+02 9.85933289e+02 9.85960022e+02 9.86223511e+02 9.86293030e+02 9.85995117e+02 9.85903503e+02 9.85935730e+02 9.85991882e+02 9.85928223e+02 9.85905334e+02 9.85919373e+02 9.86015015e+02 9.86223450e+02 9.86218384e+02 9.86018921e+02 9.85907776e+02 9.85908875e+02 9.85910461e+02 9.85926697e+02 9.85952759e+02 9.85964355e+02 9.85971558e+02 9.86054932e+02 9.86078979e+02 9.85938660e+02 9.85926270e+02 9.86041321e+02 9.85991699e+02 9.85923462e+02 9.85921631e+02 9.85922241e+02 9.85918152e+02 9.85903931e+02 9.85898315e+02 9.85953125e+02 9.85967590e+02 9.85955566e+02 9.85911865e+02 9.85912109e+02 9.85904114e+02 9.85977173e+02 9.85943848e+02 9.85931641e+02 9.85994507e+02 9.85901917e+02 9.85935852e+02 9.85925293e+02 9.85912598e+02 9.85924500e+02 9.86102966e+02 9.86340759e+02 9.86373352e+02 9.85974426e+02 9.85974854e+02 9.86010071e+02 9.85975769e+02 9.85959900e+02 9.85962524e+02 9.85907104e+02 9.85954041e+02 9.86036133e+02 9.85931335e+02 9.85960205e+02 9.85991821e+02 9.85893677e+02 9.85967712e+02 9.85973022e+02 9.85954895e+02 9.85928284e+02 9.85965698e+02 9.85987793e+02 9.85932861e+02 9.85921997e+02 9.85929932e+02 9.86094849e+02 9.86212097e+02 9.86185364e+02 9.85931641e+02 9.86028870e+02 9.86088074e+02 9.85969055e+02 9.85936035e+02 9.85929443e+02 9.85903320e+02 9.85978271e+02 9.85991943e+02 9.85931885e+02 9.86109314e+02 9.86183838e+02 9.85938232e+02 9.85902283e+02 9.85905579e+02 9.85901001e+02 9.85897339e+02 9.85905151e+02 9.85965271e+02 9.85924316e+02 9.85967163e+02 9.86031128e+02 9.85908020e+02 9.85950928e+02 9.85968567e+02 9.85915833e+02 9.85961914e+02 9.85975830e+02 9.85927307e+02 9.85938660e+02 9.85938293e+02 9.85954468e+02 9.85932068e+02 9.85931946e+02 9.85950378e+02 9.85996460e+02 9.86085327e+02 9.86058167e+02 9.86027771e+02 9.85972046e+02 9.85903076e+02 9.85925293e+02 9.86021240e+02 9.85951355e+02 9.85915649e+02 9.85984070e+02 9.86095093e+02 9.85915344e+02 9.85947021e+02 9.85982605e+02 9.85921631e+02 9.85988159e+02 9.85930603e+02 9.85910828e+02 9.85922180e+02 9.85995850e+02 9.85950439e+02 9.85920654e+02 9.85979370e+02 9.85915039e+02 9.85916260e+02 9.85906555e+02 9.85921143e+02 9.85933960e+02 9.85904602e+02 9.85911987e+02 9.85931824e+02 9.86006653e+02 9.85986633e+02 9.85940125e+02 9.85917114e+02 9.85994812e+02 9.85919861e+02 9.86004395e+02 9.86133423e+02 9.85989868e+02 9.85939148e+02 9.85958313e+02 9.86026306e+02 9.85923279e+02 9.85898071e+02 9.85906494e+02 9.85908203e+02 9.85910156e+02 9.85907715e+02 9.85907227e+02 9.85922363e+02 9.85928284e+02 9.85965454e+02 9.85945374e+02 9.85978455e+02 9.86128296e+02 9.86120117e+02 9.85936646e+02 9.85924500e+02 9.85920776e+02 9.85910156e+02 9.85915833e+02 9.85971863e+02 9.85937805e+02 9.85903259e+02 9.85899597e+02 9.85920288e+02 9.86009216e+02 9.85969543e+02 9.85942993e+02 9.85910950e+02 9.85916077e+02 9.85925232e+02 9.85971863e+02 9.85950317e+02 9.85913147e+02 9.85913147e+02 9.85914307e+02 9.85929382e+02 9.85974121e+02 9.86086853e+02 9.86035583e+02 9.85970947e+02 9.85915222e+02 9.85959717e+02 9.86034729e+02 9.85955139e+02 9.85922180e+02 9.85939636e+02 9.85925842e+02 9.85964844e+02 9.85905884e+02 9.85946289e+02 9.85919617e+02 9.85907715e+02 9.85973389e+02 9.85983826e+02 9.86081970e+02 9.86106812e+02 9.86027100e+02 9.85978516e+02 9.85967224e+02 9.85979065e+02 9.85947083e+02 9.85964600e+02 9.86023376e+02 9.85977661e+02 9.85912903e+02 9.85948181e+02 9.85930115e+02 9.85919312e+02 9.85922241e+02 9.85972534e+02 9.85925964e+02 9.85912659e+02 9.85908386e+02 9.85938843e+02 9.85945068e+02 9.85905884e+02 9.85910217e+02 9.85914490e+02 9.85922119e+02 9.86026794e+02 9.86085754e+02 9.86026306e+02 9.85912842e+02 9.85934082e+02 9.85916992e+02 9.85896240e+02 9.85961182e+02 9.86166809e+02 9.86113708e+02 9.85897583e+02 9.86114563e+02 9.86304504e+02 9.86046936e+02 9.85927795e+02 9.85965027e+02 9.85980347e+02 9.86115723e+02 9.85969666e+02 9.85957886e+02 9.85922974e+02 9.85903870e+02 9.86103943e+02 9.86212402e+02 9.86240540e+02 9.85917664e+02 9.85966736e+02 9.85905579e+02 9.85954956e+02 9.86031616e+02 9.85923645e+02 9.85972412e+02 9.85954163e+02 9.85958984e+02 9.85902039e+02 9.85924927e+02 9.85983215e+02 9.86062134e+02 9.85965942e+02 9.85927246e+02 9.85914185e+02 9.85921082e+02 9.85973206e+02 9.86058594e+02 9.86235840e+02 9.86064026e+02 9.85911011e+02 9.85909058e+02 9.85903870e+02 9.85904297e+02 9.85995789e+02 9.85974670e+02 9.85952332e+02 9.86251953e+02 9.86295471e+02 9.86004761e+02 9.85924988e+02 9.85905823e+02 9.85923584e+02 9.85913391e+02 9.85919739e+02 9.85976746e+02 9.86115601e+02 9.86019409e+02 9.85998840e+02 9.85989258e+02 9.85985046e+02 9.86005615e+02 9.85923340e+02 9.85926880e+02 9.85904480e+02 9.85912476e+02 9.86039734e+02 9.86136292e+02 9.86153503e+02 9.85925964e+02 9.85988159e+02 9.85978210e+02 9.85904236e+02 9.86011536e+02 9.85933289e+02 9.85953918e+02 9.86018494e+02 9.85971497e+02 9.85922058e+02 9.85917969e+02 9.85931946e+02 9.85985840e+02 9.85920654e+02 9.85917786e+02 9.85967285e+02 9.85911743e+02 9.86037231e+02 9.86253174e+02 9.86154114e+02 9.85937683e+02 9.85946716e+02 9.85911682e+02 9.85968872e+02 9.86057495e+02 9.85932129e+02 9.85930847e+02 9.85912048e+02 9.85894226e+02 9.85932678e+02 9.85932129e+02 9.85934998e+02 9.85941711e+02 9.85950134e+02 9.85928101e+02 9.85937500e+02 9.85934570e+02 9.86015259e+02 9.85952698e+02 9.85923462e+02 9.85910767e+02 9.85889160e+02 9.85949890e+02 9.85909485e+02 9.85903564e+02 9.86017822e+02 9.85966309e+02 9.85905090e+02 9.86083252e+02 9.86190796e+02 9.85921082e+02 9.85967773e+02 9.86016296e+02 9.85919678e+02 9.85909241e+02 9.85924744e+02 9.85914978e+02 9.85952087e+02 9.86011902e+02 9.85940552e+02 9.85915710e+02 9.86117981e+02 9.86129944e+02 9.85924988e+02 9.86014221e+02 9.86124939e+02 9.86010925e+02 9.85900757e+02 9.86033630e+02 9.86074768e+02 9.85911560e+02 9.85985229e+02 9.85940552e+02 9.85915100e+02 9.86028687e+02 9.85915955e+02 9.85972351e+02 9.85995422e+02 9.85934998e+02 9.85915894e+02 9.86004578e+02 9.86025024e+02 9.85993042e+02 9.85922913e+02 9.85925476e+02 9.85919067e+02 9.85894714e+02 9.85951782e+02 9.85951538e+02 9.85904419e+02 9.85918762e+02 9.85953552e+02 9.85901672e+02 9.85907837e+02 9.85910400e+02 9.85926636e+02 9.85948425e+02 9.85922852e+02 9.86043701e+02 9.86061096e+02 9.85908508e+02 9.85981323e+02 9.86005615e+02 9.85926331e+02 9.85910522e+02 9.85997070e+02 9.85991150e+02 9.85968262e+02 9.85919495e+02 9.85918762e+02 9.85913452e+02 9.85903320e+02 9.85916260e+02 9.85932678e+02 9.85934937e+02 9.85953308e+02 9.85931274e+02 9.85934326e+02 9.85941833e+02 9.85905701e+02 9.86040100e+02 9.86143494e+02 9.86064453e+02 9.85932312e+02 9.85902222e+02 9.85928772e+02 9.86017700e+02 9.86130188e+02 9.86053284e+02 9.85937561e+02 9.85906555e+02 9.85893799e+02 9.85920105e+02 9.85915100e+02 9.85922852e+02 9.85911133e+02 9.85910522e+02 9.86029846e+02 9.85939758e+02 9.85934998e+02 9.86026428e+02 9.85916870e+02 9.85942383e+02 9.86058899e+02 9.86001648e+02 9.85907898e+02 9.85966492e+02 9.85922546e+02 9.85908569e+02 9.85925171e+02 9.85913025e+02 9.85902161e+02 9.85910889e+02 9.85927673e+02 9.85952209e+02 9.85983276e+02 9.85987610e+02 9.86023315e+02 9.85936829e+02 9.85903625e+02 9.85915222e+02 9.85899963e+02 9.85945007e+02 9.85912964e+02 9.85907471e+02 9.85916321e+02 9.85927979e+02 9.85903320e+02 9.85921936e+02 9.85935242e+02 9.85908875e+02 9.85926147e+02 9.85906067e+02 9.85891968e+02 9.86031006e+02 9.85951599e+02 9.85901917e+02 9.85946838e+02 9.85996643e+02 9.85907837e+02 9.85925720e+02 9.85937317e+02 9.85935303e+02 9.85919800e+02 9.85884888e+02 9.85903259e+02 9.85908142e+02 9.85778259e+02 9.85735046e+02 9.85829163e+02 9.86889038e+02 9.86180176e+02 1.30626794e+03 2.01975269e+03 6.80591748e+03 1.32579092e+04 821182272. -1482585856. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -407196224. 669654016. 2.66070947e+03 1.37253259e+03 9.90049438e+02 9.94036255e+02 9.94480591e+02 9.87370789e+02 9.86114746e+02 9.85992676e+02 9.85905884e+02 9.85915771e+02 9.85886658e+02 9.85900452e+02 9.85912903e+02 9.85908936e+02 9.85900757e+02 9.85931030e+02 9.85969971e+02 9.85927429e+02 9.85919250e+02 9.85886047e+02 9.85875061e+02 9.85912659e+02 9.85921143e+02 9.85901733e+02 9.85950989e+02 9.85904846e+02 9.85930237e+02 9.85883362e+02 9.86036255e+02 9.86080383e+02 9.85936523e+02 9.85891296e+02 9.85899902e+02 9.85901917e+02 9.85893738e+02 9.85897888e+02 9.85928528e+02 9.85954773e+02 9.85941650e+02 9.85909302e+02 9.85913818e+02 9.85947571e+02 9.86045776e+02 9.86278137e+02 9.86113159e+02 9.85926208e+02 9.86032288e+02 9.85990601e+02 9.85907776e+02 9.85927185e+02 9.85904236e+02 9.85971008e+02 9.85951721e+02 9.85908997e+02 9.85928345e+02 9.85977112e+02 9.85914368e+02 9.85914246e+02 9.85909851e+02 9.85909668e+02 9.86004028e+02 9.86127197e+02 9.86145081e+02 9.85997131e+02 9.85924438e+02 9.85936890e+02 9.85956604e+02 9.86063416e+02 9.86314514e+02 9.86478455e+02 9.86462830e+02 9.86142822e+02 9.86022949e+02 9.86119019e+02 9.86019287e+02 9.85924500e+02 9.86003235e+02 9.85937256e+02 9.85916382e+02 9.85952698e+02 9.85948853e+02 9.85976868e+02 9.85991089e+02 9.85942383e+02 9.85920715e+02 9.85911438e+02 9.85919922e+02 9.85934509e+02 9.85950500e+02 9.85979675e+02 9.86082642e+02 9.86013794e+02 9.85926880e+02 9.86026245e+02 9.86050598e+02 9.86025330e+02 9.85909912e+02 9.85904663e+02 9.85996155e+02 9.86018616e+02 9.85941772e+02 9.85952393e+02 9.86001038e+02 9.85912720e+02 9.85919006e+02 9.85969421e+02 9.85991211e+02 9.86047180e+02 9.86087097e+02 9.85959595e+02 9.85962036e+02 9.85976196e+02 9.86024231e+02 9.85985901e+02 9.85921143e+02 9.85918701e+02 9.85925110e+02 9.85921448e+02 9.85956787e+02 9.85954712e+02 9.85927856e+02 9.85957153e+02 9.85969238e+02 9.85939087e+02 9.86004883e+02 9.85934326e+02 9.85969177e+02 9.85971985e+02 9.85901245e+02 9.85923035e+02 9.85932678e+02 9.85926758e+02 9.85916260e+02 9.85921570e+02 9.85949158e+02 9.85900085e+02 9.85921692e+02 9.85931824e+02 9.85917236e+02 9.85935364e+02 9.85904846e+02 9.85903687e+02 9.85905823e+02 9.85961487e+02 9.85994446e+02 9.86033752e+02 9.85998718e+02 9.85977905e+02 9.86071167e+02 9.86022888e+02 9.85945007e+02 9.85931213e+02 9.86010925e+02 9.85964417e+02 9.85921021e+02 9.85923767e+02 9.85935730e+02 9.85965698e+02 9.86048096e+02 9.86044067e+02 9.85988647e+02 9.85968506e+02 9.86022522e+02 9.86113464e+02 9.85997620e+02 9.85899170e+02 9.85978455e+02 9.86001404e+02 9.85901917e+02 9.85937988e+02 9.85909485e+02 9.85934875e+02 9.85908813e+02 9.85935059e+02 9.85919067e+02 9.85914856e+02 9.85937927e+02 9.85929443e+02 9.85909363e+02 9.85907471e+02 9.85903931e+02 9.85955017e+02 9.85947083e+02 9.85958008e+02 9.85967590e+02 9.86037170e+02 9.86190613e+02 9.86345825e+02 9.86538025e+02 9.86133850e+02 9.85944336e+02 9.85909241e+02 9.85889709e+02 9.85958862e+02 9.85947021e+02 9.85904663e+02 9.86025391e+02 9.85982422e+02 9.85911133e+02 9.85976135e+02 9.86058167e+02 9.85987000e+02 9.86070740e+02 9.86173401e+02 9.86104553e+02 9.86046021e+02 9.86027771e+02 9.86075928e+02 9.86008972e+02 9.85922424e+02 9.85921448e+02 9.85922546e+02 9.85918091e+02 9.85966370e+02 9.86266724e+02 9.86223328e+02 9.85955505e+02 9.85907410e+02 9.85907104e+02 9.85898376e+02 9.85925781e+02 9.86026123e+02 9.86066101e+02 9.85956299e+02 9.85903381e+02 9.85953674e+02 9.86012695e+02 9.85935364e+02 9.85913574e+02 9.85927734e+02 9.85897278e+02 9.85916992e+02 9.85905518e+02 9.85894775e+02 9.85897156e+02 9.85885559e+02 9.85904419e+02 9.85913391e+02 9.85909607e+02 9.85914246e+02 9.85902405e+02 9.85904785e+02 9.85915405e+02 9.85922546e+02 9.85897034e+02 9.85895203e+02 9.85885620e+02 9.85900269e+02 9.85902588e+02 9.85913635e+02 9.85903809e+02 9.85947754e+02 9.85945190e+02 9.85913208e+02 9.85906555e+02 9.85910034e+02 9.85895691e+02 9.85903931e+02 9.85895691e+02 9.85912659e+02 9.85905334e+02 9.85896973e+02 9.85903564e+02 9.85904114e+02 9.85916077e+02 9.85911316e+02 9.85910950e+02 9.85897156e+02 9.85911987e+02 9.85922974e+02 9.85915588e+02 9.85898560e+02 9.85909058e+02 9.85913696e+02 9.85906372e+02 9.85907837e+02 9.85910522e+02 9.85905762e+02 9.85912537e+02 9.85912231e+02 9.85923096e+02 9.85924805e+02 9.85912476e+02 9.85921997e+02 9.85937134e+02 9.85930115e+02 9.85906616e+02 9.85898560e+02 9.85905701e+02 9.85901550e+02 9.85904663e+02 9.85906433e+02 9.85907837e+02 9.85904175e+02 9.85916809e+02 9.85913818e+02 9.85902466e+02 9.85896790e+02 9.85904541e+02 9.85908813e+02 9.85905273e+02 9.85908813e+02 9.85909424e+02 9.85903870e+02 9.85901550e+02 9.85891418e+02 9.85910889e+02 9.85934814e+02 9.85933289e+02 9.85917175e+02 9.85910767e+02 9.85893921e+02 9.85903381e+02 9.85923584e+02 9.85906921e+02 9.85905884e+02 9.85897766e+02 9.85905212e+02 9.85913818e+02 9.85937195e+02 9.85925781e+02 9.85907959e+02 9.85912048e+02 9.85921814e+02 9.85916138e+02 9.85925293e+02 9.85921997e+02 9.85987366e+02 9.85994629e+02 9.85933350e+02 9.85896545e+02 9.85907715e+02 9.85908142e+02 9.85907715e+02 9.85915588e+02 9.85901611e+02 9.85908081e+02 9.85906006e+02 9.85909424e+02 9.85904114e+02 9.85894836e+02 9.85914429e+02 9.85954102e+02 9.86012451e+02 9.85991943e+02 9.85933716e+02 9.85902832e+02 9.85902832e+02 9.85918030e+02 9.85913391e+02 9.85907654e+02 9.85909180e+02 9.85898010e+02 9.85898193e+02 9.85918396e+02 9.85904907e+02 9.85911621e+02 9.85897156e+02 9.85907776e+02 9.85934570e+02 9.86037842e+02 9.85940063e+02 9.85937439e+02 9.85981140e+02 9.85905396e+02 9.85908142e+02 9.85902649e+02 9.85904541e+02 9.85911682e+02 9.85900085e+02 9.85908630e+02 9.85891357e+02 9.85909607e+02 9.85913635e+02 9.85902527e+02 9.85915283e+02 9.85943176e+02 9.85915588e+02 9.85910217e+02 9.85910339e+02 9.85906982e+02 9.85907715e+02 9.85917725e+02 9.85952271e+02 9.86004883e+02 9.85964478e+02 9.85908386e+02 9.85898315e+02 9.85916077e+02 9.85912720e+02 9.85900879e+02 9.85905029e+02 9.85895935e+02 9.85898315e+02 9.85890320e+02 9.85924255e+02 9.85947937e+02 9.85934204e+02 9.85910156e+02 9.85907166e+02 9.85896729e+02 9.85917358e+02 9.85992554e+02 9.86089050e+02 9.86032959e+02 9.85937561e+02 9.85909119e+02 9.85906433e+02 9.85898682e+02 9.85917542e+02 9.85927185e+02 9.85913940e+02 9.85893188e+02 9.85901794e+02 9.85902100e+02 9.85904053e+02 9.85960327e+02 9.85979675e+02 9.85936646e+02 9.85912659e+02 9.85911072e+02 9.85902283e+02 9.85895569e+02 9.85914856e+02 9.85905029e+02 9.85910645e+02 9.85898682e+02 9.85898254e+02 9.85899353e+02 9.85906860e+02 9.85915833e+02 9.85913208e+02 9.85917786e+02 9.85895447e+02 9.85907898e+02 9.85908630e+02 9.85912720e+02 9.85923584e+02 9.85916809e+02 9.85894714e+02 9.85900513e+02 9.85889648e+02 9.85907715e+02 9.85903748e+02 9.85945618e+02 9.85954041e+02 9.85895996e+02 9.85854187e+02 9.85867493e+02 9.85834778e+02 9.85839844e+02 9.85817200e+02 9.85764771e+02 9.85788940e+02 9.86001526e+02 9.86489502e+02 9.87795227e+02 9.89234070e+02 1.33959778e+03 2.23583105e+03 1.73271172e+04 -2.75051981e+09 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. 0. 0. 0. 0. 0. 0. 0. -3.42252800e+09 -1155212160. -284272224. -899558528. 9.72683496e+03 4.87212012e+03 1.96642407e+03 1.34523218e+03 9.97696716e+02 9.90318542e+02 9.88304199e+02 9.86633057e+02 9.86310486e+02 9.86266968e+02 9.86460938e+02 9.86352112e+02 9.85884705e+02 9.86378540e+02 9.86324951e+02 9.85918518e+02 9.87009888e+02 9.86989319e+02 9.89067810e+02 9.90940369e+02 9.91215271e+02 9.88676025e+02 9.88070984e+02 9.89612183e+02 9.90219666e+02 9.90323059e+02 9.89744873e+02 9.88360107e+02 9.86361633e+02 9.85975891e+02 9.85890442e+02 9.85903687e+02 9.85892090e+02 9.85889526e+02 9.85895264e+02 9.85901611e+02 9.85904236e+02 9.85902527e+02 9.85900757e+02 9.85909546e+02 9.85929077e+02 9.85949829e+02 9.85936279e+02 9.85937378e+02 9.85952209e+02 9.85939087e+02 9.85936890e+02 9.85906921e+02 9.85923645e+02 9.85913513e+02 9.85911682e+02 9.85908203e+02 9.85904968e+02 9.85920532e+02 9.85913696e+02 9.85896729e+02 9.85901917e+02 9.85940308e+02 9.85978821e+02 9.85985596e+02 9.85962952e+02 9.85939453e+02 9.85991028e+02 9.86037170e+02 9.85976013e+02 9.85908813e+02 9.85899292e+02 9.85901611e+02 9.85911499e+02 9.85933289e+02 9.86016907e+02 9.86069458e+02 9.86070679e+02 9.85976013e+02 9.85934631e+02 9.85910461e+02 9.85907715e+02 9.85909424e+02 9.85905151e+02 9.85932800e+02 9.86032227e+02 9.86071228e+02 9.86007507e+02 9.85939087e+02 9.85910767e+02 9.85909119e+02 9.85901733e+02 9.85958496e+02 9.86046204e+02 9.86008606e+02 9.85915100e+02 9.85901978e+02 9.85906677e+02 9.85933350e+02 9.85938293e+02 9.85957764e+02 9.85900146e+02 9.85915649e+02 9.85937866e+02 9.85929932e+02 9.85893250e+02 9.85911865e+02 9.85904480e+02 9.85919067e+02 9.85946045e+02 9.85996887e+02 9.85979797e+02 9.85933289e+02 9.85904053e+02 9.85953674e+02 9.85952209e+02 9.85931824e+02 9.85914856e+02 9.85909302e+02 9.85928528e+02 9.85926392e+02 9.85915100e+02 9.85917786e+02 9.85905762e+02 9.85903748e+02 9.85908997e+02 9.85901123e+02 9.85902954e+02 9.85947449e+02 9.86047363e+02 9.86049927e+02 9.85961548e+02 9.85911804e+02 9.85922791e+02 9.85969910e+02 9.86030212e+02 9.86071838e+02 9.86007629e+02 9.85929749e+02 9.85909790e+02 9.85910828e+02 9.85906860e+02 9.85896790e+02 9.85909424e+02 9.85902344e+02 9.85912415e+02 9.85908691e+02 9.85900085e+02 9.85899109e+02 9.85905945e+02 9.85899597e+02 9.85913208e+02 9.85919617e+02 9.85968506e+02 9.86055054e+02 9.86030029e+02 9.85933472e+02 9.85897705e+02 9.85929504e+02 9.85999451e+02 9.86076538e+02 9.86077881e+02 9.86123108e+02 9.86135559e+02 9.86040039e+02 9.85960205e+02 9.85908936e+02 9.85908813e+02 9.85897827e+02 9.85905457e+02 9.85904785e+02 9.85910339e+02 9.85903992e+02 9.85906860e+02 9.85920654e+02 9.85903687e+02 9.85927246e+02 9.86033264e+02 9.86023376e+02 9.85939209e+02 9.85893494e+02 9.85916626e+02 9.85917297e+02 9.85918579e+02 9.85917603e+02 9.85920593e+02 9.85962769e+02 9.85959412e+02 9.85910828e+02 9.85904419e+02 9.85907471e+02 9.85893127e+02 9.85905212e+02 9.85895874e+02 9.85901917e+02 9.85914001e+02 9.85909058e+02 9.85904602e+02 9.85906677e+02 9.85923157e+02 9.85914734e+02 9.85900696e+02 9.85949524e+02 9.85944092e+02 9.85907654e+02 9.85899048e+02 9.85901428e+02 9.85911011e+02 9.85914551e+02 9.85914612e+02 9.85915344e+02 9.85900635e+02 9.85909302e+02 9.85900696e+02 9.85911072e+02 9.85911682e+02 9.85908508e+02 9.85895508e+02 9.85895935e+02 9.85900513e+02 9.85910767e+02 9.85913147e+02 9.85908325e+02 9.85908325e+02 9.85907288e+02 9.85904724e+02 9.85917908e+02 9.85947632e+02 9.85944702e+02 9.85927795e+02 9.85911194e+02 9.85918091e+02 9.85901428e+02 9.85918823e+02 9.85925537e+02 9.85919067e+02 9.85909424e+02 9.85912231e+02 9.85915527e+02 9.85926331e+02 9.85925171e+02 9.85917236e+02 9.85908447e+02 9.85915466e+02 9.85917908e+02 9.85979431e+02 9.85996704e+02 9.85938232e+02 9.85941650e+02 9.86047546e+02 9.86029175e+02 9.85909424e+02 9.85899597e+02 9.85940063e+02 9.86000488e+02 9.85999207e+02 9.85919556e+02 9.85910217e+02 9.85907776e+02 9.85912170e+02 9.85910828e+02 9.85902588e+02 9.85909668e+02 9.85908813e+02 9.85912048e+02 9.85907043e+02 9.85911987e+02 9.85905212e+02 9.85924988e+02 9.85938660e+02 9.85908569e+02 9.85924500e+02 9.85922241e+02 9.85915039e+02 9.85916748e+02 9.85908203e+02 9.85916260e+02 9.85911316e+02 9.85949646e+02 9.85969543e+02 9.85956482e+02 9.85910156e+02 9.85914368e+02 9.85914734e+02 9.85902161e+02 9.85910522e+02 9.85901978e+02 9.85907227e+02 9.85955872e+02 9.85952698e+02 9.85913208e+02 9.85894958e+02 9.85900513e+02 9.85897156e+02 9.85918152e+02 9.85907959e+02 9.85929810e+02 9.86002502e+02 9.85981445e+02 9.85935181e+02 9.85906738e+02 9.85906921e+02 9.85894958e+02 9.85915833e+02 9.85910156e+02 9.85936951e+02 9.85987732e+02 9.86015076e+02 9.85965576e+02 9.85922546e+02 9.85923645e+02 9.85913147e+02 9.85909668e+02 9.85901367e+02 9.85909119e+02 9.85914062e+02 9.85918213e+02 9.85921753e+02 9.85908020e+02 9.85908020e+02 9.85897644e+02 9.85899292e+02 9.85909912e+02 9.85915649e+02 9.85915710e+02 9.85899109e+02 9.85916870e+02 9.85978516e+02 9.86040344e+02 9.86071350e+02 9.86070312e+02 9.86060669e+02 9.85932800e+02 9.85895325e+02 9.85910767e+02 9.85911682e+02 9.85903564e+02 9.85931580e+02 9.85962891e+02 9.85937744e+02 9.85907288e+02 9.85899536e+02 9.85933167e+02 9.85949463e+02 9.85922119e+02 9.85900269e+02 9.85899902e+02 9.85910217e+02 9.85960754e+02 9.86011963e+02 9.85944275e+02 9.85889160e+02 9.85921387e+02 9.85908386e+02 9.85921326e+02 9.85935364e+02 9.85919861e+02 9.85894104e+02 9.85899292e+02 9.85928223e+02 9.85926453e+02 9.85904175e+02 9.85925964e+02 9.85911072e+02 9.85921753e+02 9.85917358e+02 9.85904480e+02 9.85914124e+02 9.85911438e+02 9.85913574e+02 9.85909790e+02 9.85932861e+02 9.86008606e+02 9.85928406e+02 9.85901001e+02 9.85907959e+02 9.85934143e+02 9.86014099e+02 9.85931335e+02 9.85910583e+02 9.85926270e+02 9.85949463e+02 9.85963379e+02 9.85918518e+02 9.85908630e+02 9.85904907e+02 9.85920288e+02 9.85932312e+02 9.85913025e+02 9.85912231e+02 9.85898499e+02 9.85895569e+02 9.85895264e+02 9.85899719e+02 9.85909485e+02 9.85916077e+02 9.85941772e+02 9.85990417e+02 9.85915833e+02 9.85912781e+02 9.85908813e+02 9.85936523e+02 9.86014404e+02 9.85908936e+02 9.85895325e+02 9.85913940e+02 9.85918396e+02 9.85901978e+02 9.85929138e+02 9.86000916e+02 9.85958008e+02 9.85934509e+02 9.85908020e+02 9.85918335e+02 9.85915710e+02 9.85905640e+02 9.85911987e+02 9.85929077e+02 9.85928528e+02 9.85908264e+02 9.85926392e+02 9.85932312e+02 9.85917175e+02 9.85946838e+02 9.86008728e+02 9.85958679e+02 9.85908386e+02 9.85932678e+02 9.85909912e+02 9.85909363e+02 9.85898376e+02 9.85893005e+02 9.85894470e+02 9.85890259e+02 9.85902283e+02 9.85927185e+02 9.85914734e+02 9.85906677e+02 9.85954895e+02 9.85994202e+02 9.85940552e+02 9.85975464e+02 9.86075806e+02 9.86018555e+02 9.85895996e+02 9.85929321e+02 9.85952881e+02 9.85916748e+02 9.85924988e+02 9.85937805e+02 9.85921387e+02 9.85899231e+02 9.85899963e+02 9.85890320e+02 9.85900757e+02 9.85890930e+02 9.85916199e+02 9.85922546e+02 9.85909485e+02 9.85923462e+02 9.85915222e+02 9.85908997e+02 9.85911560e+02 9.85917603e+02 9.85917175e+02 9.85898987e+02 9.85906738e+02 9.85909973e+02 9.85890564e+02 9.85939148e+02 9.85934692e+02 9.85924622e+02 9.86124817e+02 9.86188049e+02 9.86068787e+02 9.86029297e+02 9.86073059e+02 9.86026550e+02 9.85958252e+02 9.85918274e+02 9.85935120e+02 9.85919006e+02 9.85955200e+02 9.85967163e+02 9.85963013e+02 9.85903503e+02 9.85900513e+02 9.85898376e+02 9.85929565e+02 9.85945374e+02 9.85901428e+02 9.85906555e+02 9.85957031e+02 9.85907166e+02 9.85950500e+02 9.86116699e+02 9.86016785e+02 9.85925598e+02 9.85953369e+02 9.86068726e+02 9.86092102e+02 9.86005188e+02 9.85946045e+02 9.85987793e+02 9.86013306e+02 9.85993042e+02 9.85931030e+02 9.85903625e+02 9.85948364e+02 9.86021545e+02 9.86007751e+02 9.85905640e+02 9.85926880e+02 9.85979187e+02 9.85940308e+02 9.85902893e+02 9.85908997e+02 9.85899780e+02 9.85933716e+02 9.86029297e+02 9.85990356e+02 9.85928772e+02 9.85900330e+02 9.85907837e+02 9.85902405e+02 9.85943604e+02 9.86019714e+02 9.85995056e+02 9.85927002e+02 9.85904175e+02 9.85891174e+02 9.85909790e+02 9.85901917e+02 9.85910767e+02 9.85916138e+02 9.85908447e+02 9.85903259e+02 9.85893555e+02 9.85900574e+02 9.85906677e+02 9.85887512e+02 9.85914856e+02 9.86002502e+02 9.86017578e+02 9.85960693e+02 9.85951782e+02 9.86047424e+02 9.86013245e+02 9.85950195e+02 9.85909607e+02 9.85973511e+02 9.86045349e+02 9.85994385e+02 9.85919373e+02 9.85907837e+02 9.85906494e+02 9.85900146e+02 9.85906982e+02 9.85947083e+02 9.85952820e+02 9.85906067e+02 9.85924011e+02 9.85991211e+02 9.85985657e+02 9.85929199e+02 9.85901062e+02 9.85923889e+02 9.85951294e+02 9.85942627e+02 9.85905884e+02 9.85962830e+02 9.85912354e+02 9.85909363e+02 9.85916870e+02 9.85915955e+02 9.85919983e+02 9.85924072e+02 9.85933838e+02 9.85930420e+02 9.86002075e+02 9.86056274e+02 9.86047668e+02 9.85961670e+02 9.85907898e+02 9.85914978e+02 9.85908813e+02 9.85911499e+02 9.85912109e+02 9.85902405e+02 9.85919006e+02 9.85902405e+02 9.85907532e+02 9.85903503e+02 9.85913086e+02 9.85995544e+02 9.85921631e+02 9.85939270e+02 9.85979858e+02 9.85908447e+02 9.85903870e+02 9.85913696e+02 9.85893860e+02 9.85866638e+02 9.85845886e+02 9.85818054e+02 9.85810486e+02 9.86524902e+02 9.89494141e+02 9.85801880e+02 9.89131470e+02 9.95260376e+02 1.49639294e+03 4.06931030e+03 0. 0. 0. 0. 0. 1983649664. -2.95593293e+09 562742656. 2.30831289e+04 2.50500176e+04 -403864032. -310378336. -1227188992. 2.83988480e+09 2.83988480e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1529998336. -1856067456. -1105195136. 3.27138867e+03 1.71339771e+03 1.22356543e+03 1.22561255e+03 1.22663184e+03 1.22621509e+03 1.22408716e+03 1.22366577e+03 1.22387964e+03 1.22393359e+03 1.22372168e+03 1.22370642e+03 1.22370850e+03 1.22370874e+03 1.22383740e+03 1.22403381e+03 1.22376819e+03 1.22382288e+03 1.22413013e+03 1.22393469e+03 1.22372510e+03 1.22375745e+03 1.22374170e+03 1.22371533e+03 1.22372986e+03 1.22379688e+03 1.22375928e+03 1.22373376e+03 1.22379724e+03 1.22375208e+03 1.22371582e+03 1.22372815e+03 1.22369934e+03 1.22381641e+03 1.22396167e+03 1.22383997e+03 1.22384778e+03 1.22403491e+03 1.22386035e+03 1.22372668e+03 1.22381567e+03 1.22370471e+03 1.22418213e+03 1.22452222e+03 1.22405505e+03 1.22376831e+03 1.22372241e+03 1.22371252e+03 1.22369922e+03 1.22370813e+03 1.22371960e+03 1.22371338e+03 1.22395227e+03 1.22449438e+03 1.22424182e+03 1.22379199e+03 1.22371118e+03 1.22375024e+03 1.22395813e+03 1.22409546e+03 1.22381970e+03 1.22377893e+03 1.22384985e+03 1.22379297e+03 1.22372595e+03 1.22388293e+03 1.22379285e+03 1.22374866e+03 1.22385999e+03 1.22377258e+03 1.22375439e+03 1.22370813e+03 1.22373877e+03 1.22371252e+03 1.22372498e+03 1.22377478e+03 1.22371216e+03 1.22389148e+03 1.22400562e+03 1.22387012e+03 1.22369666e+03 1.22376831e+03 1.22373035e+03 1.22369397e+03 1.22369958e+03 1.22377893e+03 1.22377539e+03 1.22371057e+03 1.22373999e+03 1.22373645e+03 1.22392249e+03 1.22394165e+03 1.22368628e+03 1.22377673e+03 1.22380298e+03 1.22371680e+03 1.22370703e+03 1.22370935e+03 1.22374036e+03 1.22404224e+03 1.22433252e+03 1.22387512e+03 1.22373181e+03 1.22391235e+03 1.22380164e+03 1.22372046e+03 1.22387036e+03 1.22409790e+03 1.22398096e+03 1.22388672e+03 1.22387219e+03 1.22385938e+03 1.22370044e+03 1.22379175e+03 1.22371875e+03 1.22390967e+03 1.22419116e+03 1.22392664e+03 1.22370679e+03 1.22378625e+03 1.22372852e+03 1.22373389e+03 1.22373193e+03 1.22371912e+03 1.22382812e+03 1.22435168e+03 1.22430798e+03 1.22383984e+03 1.22370972e+03 1.22370862e+03 1.22376465e+03 1.22387463e+03 1.22392065e+03 1.22385205e+03 1.22373535e+03 1.22372351e+03 1.22383777e+03 1.22390662e+03 1.22376855e+03 1.22370496e+03 1.22371594e+03 1.22371680e+03 1.22371936e+03 1.22370105e+03 1.22370435e+03 1.22372278e+03 1.22380676e+03 1.22385120e+03 1.22373303e+03 1.22369360e+03 1.22372681e+03 1.22379041e+03 1.22371497e+03 1.22387305e+03 1.22418091e+03 1.22379688e+03 1.22376147e+03 1.22378687e+03 1.22371167e+03 1.22372717e+03 1.22372168e+03 1.22372900e+03 1.22383203e+03 1.22407544e+03 1.22419629e+03 1.22399084e+03 1.22372070e+03 1.22371655e+03 1.22369922e+03 1.22376257e+03 1.22374438e+03 1.22372070e+03 1.22370105e+03 1.22399561e+03 1.22400037e+03 1.22380188e+03 1.22371179e+03 1.22382361e+03 1.22453613e+03 1.22498145e+03 1.22435315e+03 1.22373975e+03 1.22369629e+03 1.22368542e+03 1.22368579e+03 1.22372131e+03 1.22370215e+03 1.22376538e+03 1.22417773e+03 1.22407031e+03 1.22377551e+03 1.22376086e+03 1.22392847e+03 1.22382739e+03 1.22368457e+03 1.22379443e+03 1.22381592e+03 1.22388501e+03 1.22406604e+03 1.22395776e+03 1.22371631e+03 1.22378882e+03 1.22369592e+03 1.22390540e+03 1.22431384e+03 1.22391931e+03 1.22376257e+03 1.22382178e+03 1.22369861e+03 1.22375171e+03 1.22370093e+03 1.22372278e+03 1.22369385e+03 1.22375562e+03 1.22380005e+03 1.22372351e+03 1.22389282e+03 1.22397424e+03 1.22379065e+03 1.22369617e+03 1.22369507e+03 1.22373975e+03 1.22370703e+03 1.22370044e+03 1.22370654e+03 1.22379260e+03 1.22383569e+03 1.22378162e+03 1.22369531e+03 1.22369995e+03 1.22369775e+03 1.22371265e+03 1.22370557e+03 1.22371167e+03 1.22369800e+03 1.22379321e+03 1.22389368e+03 1.22377295e+03 1.22376404e+03 1.22406250e+03 1.22398206e+03 1.22373425e+03 1.22391736e+03 1.22396582e+03 1.22373804e+03 1.22370129e+03 1.22374402e+03 1.22372375e+03 1.22370667e+03 1.22370459e+03 1.22372107e+03 1.22374805e+03 1.22369434e+03 1.22392822e+03 1.22385742e+03 1.22372534e+03 1.22371326e+03 1.22372205e+03 1.22390186e+03 1.22372180e+03 1.22372253e+03 1.22376331e+03 1.22368506e+03 1.22376501e+03 1.22382068e+03 1.22388635e+03 1.22372192e+03 1.22372058e+03 1.22370093e+03 1.22375037e+03 1.22376367e+03 1.22376904e+03 1.22379883e+03 1.22390161e+03 1.22400269e+03 1.22372278e+03 1.22370215e+03 1.22368604e+03 1.22377039e+03 1.22373926e+03 1.22371838e+03 1.22373828e+03 1.22372656e+03 1.22374219e+03 1.22371838e+03 1.22373291e+03 1.22380591e+03 1.22383276e+03 1.22381213e+03 1.22373499e+03 1.22371985e+03 1.22375574e+03 1.22386658e+03 1.22377710e+03 1.22374109e+03 1.22380603e+03 1.22376172e+03 1.22372400e+03 1.22370557e+03 1.22372644e+03 1.22391138e+03 1.22412036e+03 1.22387292e+03 1.22370679e+03 1.22372595e+03 1.22368530e+03 1.22373254e+03 1.22375500e+03 1.22371460e+03 1.22368738e+03 1.22370996e+03 1.22375659e+03 1.22384338e+03 1.22382532e+03 1.22371533e+03 1.22368103e+03 1.22374451e+03 1.22393115e+03 1.22380212e+03 1.22367871e+03 1.22369507e+03 1.22379492e+03 1.22381274e+03 1.22369617e+03 1.22372253e+03 1.22384717e+03 1.22399451e+03 1.22383704e+03 1.22371472e+03 1.22369922e+03 1.22372827e+03 1.22379663e+03 1.22374390e+03 1.22371582e+03 1.22368652e+03 1.22369641e+03 1.22379883e+03 1.22383020e+03 1.22384558e+03 1.22373560e+03 1.22373096e+03 1.22378687e+03 1.22388000e+03 1.22377612e+03 1.22367542e+03 1.22369446e+03 1.22371118e+03 1.22370398e+03 1.22384106e+03 1.22380908e+03 1.22368591e+03 1.22371277e+03 1.22370081e+03 1.22383582e+03 1.22371033e+03 1.22369946e+03 1.22374866e+03 1.22381384e+03 1.22385217e+03 1.22375220e+03 1.22376636e+03 1.22377893e+03 1.22371179e+03 1.22379224e+03 1.22369678e+03 1.22377405e+03 1.22396924e+03 1.22375415e+03 1.22368091e+03 1.22369202e+03 1.22373242e+03 1.22382483e+03 1.22405273e+03 1.22453442e+03 1.22436523e+03 1.22394324e+03 1.22385120e+03 1.22397583e+03 1.22421216e+03 1.22380933e+03 1.22371289e+03 1.22370911e+03 1.22367944e+03 1.22371936e+03 1.22375354e+03 1.22435181e+03 1.22453894e+03 1.22398560e+03 1.22375598e+03 1.22384460e+03 1.22371411e+03 1.22418567e+03 1.22427222e+03 1.22383801e+03 1.22371069e+03 1.22375916e+03 1.22402087e+03 1.22425720e+03 1.22399585e+03 1.22371997e+03 1.22370605e+03 1.22371570e+03 1.22397070e+03 1.22444421e+03 1.22443909e+03 1.22418262e+03 1.22374890e+03 1.22378674e+03 1.22393909e+03 1.22372827e+03 1.22395959e+03 1.22446838e+03 1.22399341e+03 1.22372253e+03 1.22371277e+03 1.22402710e+03 1.22484985e+03 1.22448181e+03 1.22381897e+03 1.22371741e+03 1.22371692e+03 1.22373047e+03 1.22391284e+03 1.22413562e+03 1.22379724e+03 1.22373096e+03 1.22370703e+03 1.22376514e+03 1.22388489e+03 1.22372095e+03 1.22372644e+03 1.22382812e+03 1.22380933e+03 1.22374646e+03 1.22368359e+03 1.22394775e+03 1.22410034e+03 1.22379468e+03 1.22384033e+03 1.22418713e+03 1.22388574e+03 1.22372986e+03 1.22406799e+03 1.22392798e+03 1.22372791e+03 1.22370923e+03 1.22384949e+03 1.22396118e+03 1.22403662e+03 1.22374207e+03 1.22369116e+03 1.22372119e+03 1.22375659e+03 1.22370593e+03 1.22368152e+03 1.22381873e+03 1.22378186e+03 1.22369751e+03 1.22371899e+03 1.22371289e+03 1.22369080e+03 1.22386194e+03 1.22377783e+03 1.22368201e+03 1.22370935e+03 1.22369019e+03 1.22392529e+03 1.22390906e+03 1.22373145e+03 1.22376929e+03 1.22375146e+03 1.22371375e+03 1.22383337e+03 1.22407043e+03 1.22374475e+03 1.22370251e+03 1.22369275e+03 1.22370398e+03 1.22371301e+03 1.22370715e+03 1.22369336e+03 1.22369324e+03 1.22374426e+03 1.22374426e+03 1.22368005e+03 1.22395874e+03 1.22409082e+03 1.22382825e+03 1.22373120e+03 1.22419067e+03 1.22411560e+03 1.22370190e+03 1.22393188e+03 1.22419885e+03 1.22380237e+03 1.22373352e+03 1.22376770e+03 1.22370166e+03 1.22390125e+03 1.22378540e+03 1.22367639e+03 1.22379187e+03 1.22381592e+03 1.22375647e+03 1.22368433e+03 1.22381482e+03 1.22377026e+03 1.22369250e+03 1.22386108e+03 1.22394556e+03 1.22372412e+03 1.22373486e+03 1.22374084e+03 1.22372412e+03 1.22380603e+03 1.22376941e+03 1.22368982e+03 1.22368982e+03 1.22371741e+03 1.22370837e+03 1.22371436e+03 1.22370312e+03 1.22368677e+03 1.22374219e+03 1.22368787e+03 1.22372961e+03 1.22385693e+03 1.22398120e+03 1.22381824e+03 1.22374475e+03 1.22373584e+03 1.22376746e+03 1.22370959e+03 1.22373560e+03 1.22377258e+03 1.22368201e+03 1.22384973e+03 1.22384106e+03 1.22376086e+03 1.22375964e+03 1.22378821e+03 1.22371826e+03 1.22369128e+03 1.22373621e+03 1.22371643e+03 1.22389612e+03 1.22418640e+03 1.22412170e+03 1.22378918e+03 1.22379688e+03 1.22390405e+03 1.22429480e+03 1.22431897e+03 1.22416028e+03 1.22388892e+03 1.22370862e+03 1.22375989e+03 1.22371191e+03 1.22378662e+03 1.22387354e+03 1.22371899e+03 1.22370862e+03 1.22371729e+03 1.22373889e+03 1.22395203e+03 1.22386597e+03 1.22369519e+03 1.22382434e+03 1.22387048e+03 1.22372620e+03 1.22381860e+03 1.22386707e+03 1.22385779e+03 1.22380200e+03 1.22373730e+03 1.22371838e+03 1.22371484e+03 1.22370667e+03 1.22372693e+03 1.22369971e+03 1.22385400e+03 1.22405164e+03 1.22378625e+03 1.22373010e+03 1.22383179e+03 1.22371277e+03 1.22380957e+03 1.22391138e+03 1.22373987e+03 1.22379297e+03 1.22382703e+03 1.22371924e+03 1.22370544e+03 1.22373254e+03 1.22371887e+03 1.22375684e+03 1.22375024e+03 1.22371338e+03 1.22373999e+03 1.22369409e+03 1.22372351e+03 1.22387512e+03 1.22428735e+03 1.22461621e+03 1.22441418e+03 1.22389966e+03 1.22371692e+03 1.22369629e+03 1.22381665e+03 1.22566064e+03 1.22528101e+03 1.22363171e+03 1.55752148e+03 2.29829565e+03 4.89623730e+03 4.89696240e+03 4.89982471e+03 4.89677881e+03 6.80591748e+03 1.32579092e+04 821182272. -1482585856. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.22188800e+09 1.25184336e+04 6.57540723e+03 4.90257568e+03 2.46572949e+03 1.67691772e+03 1.22703796e+03 1.22402661e+03 1.22354077e+03 1.22361658e+03 1.22374756e+03 1.22375195e+03 1.22365979e+03 1.22376221e+03 1.22378357e+03 1.22369275e+03 1.22381970e+03 1.22377795e+03 1.22372485e+03 1.22388745e+03 1.22395898e+03 1.22374878e+03 1.22377161e+03 1.22382983e+03 1.22366467e+03 1.22385059e+03 1.22390698e+03 1.22372180e+03 1.22368958e+03 1.22375208e+03 1.22377832e+03 1.22372607e+03 1.22373071e+03 1.22372327e+03 1.22372461e+03 1.22377258e+03 1.22380627e+03 1.22370032e+03 1.22389954e+03 1.22396948e+03 1.22373010e+03 1.22373218e+03 1.22373083e+03 1.22373035e+03 1.22401721e+03 1.22400769e+03 1.22371680e+03 1.22406763e+03 1.22401965e+03 1.22369482e+03 1.22379443e+03 1.22385608e+03 1.22371350e+03 1.22371204e+03 1.22372192e+03 1.22371997e+03 1.22373499e+03 1.22371057e+03 1.22389050e+03 1.22378772e+03 1.22370190e+03 1.22373499e+03 1.22373767e+03 1.22403333e+03 1.22397754e+03 1.22379248e+03 1.22372046e+03 1.22371326e+03 1.22373694e+03 1.22403235e+03 1.22460132e+03 1.22428027e+03 1.22379114e+03 1.22370874e+03 1.22385535e+03 1.22411963e+03 1.22409485e+03 1.22372632e+03 1.22370044e+03 1.22369861e+03 1.22381189e+03 1.22381482e+03 1.22381128e+03 1.22394690e+03 1.22379663e+03 1.22367102e+03 1.22371094e+03 1.22369568e+03 1.22417065e+03 1.22433655e+03 1.22410181e+03 1.22376721e+03 1.22367480e+03 1.22368433e+03 1.22374414e+03 1.22389490e+03 1.22387415e+03 1.22369385e+03 1.22373621e+03 1.22369141e+03 1.22388293e+03 1.22391504e+03 1.22368640e+03 1.22377258e+03 1.22372766e+03 1.22370166e+03 1.22371655e+03 1.22368970e+03 1.22394714e+03 1.22392053e+03 1.22372412e+03 1.22375049e+03 1.22372119e+03 1.22374585e+03 1.22376672e+03 1.22369043e+03 1.22372791e+03 1.22377112e+03 1.22372986e+03 1.22369324e+03 1.22387329e+03 1.22395349e+03 1.22371570e+03 1.22375024e+03 1.22370203e+03 1.22370239e+03 1.22373901e+03 1.22370618e+03 1.22371069e+03 1.22370569e+03 1.22371716e+03 1.22374512e+03 1.22370703e+03 1.22382312e+03 1.22382715e+03 1.22369824e+03 1.22379114e+03 1.22374426e+03 1.22371582e+03 1.22372473e+03 1.22373254e+03 1.22383704e+03 1.22395886e+03 1.22379138e+03 1.22370142e+03 1.22379565e+03 1.22378394e+03 1.22371960e+03 1.22371765e+03 1.22372266e+03 1.22369153e+03 1.22371545e+03 1.22378198e+03 1.22392468e+03 1.22400964e+03 1.22406506e+03 1.22386133e+03 1.22373083e+03 1.22376379e+03 1.22388074e+03 1.22380078e+03 1.22372656e+03 1.22370496e+03 1.22385364e+03 1.22411670e+03 1.22395483e+03 1.22371826e+03 1.22384204e+03 1.22382983e+03 1.22370898e+03 1.22380383e+03 1.22380969e+03 1.22370178e+03 1.22368884e+03 1.22368994e+03 1.22368591e+03 1.22371338e+03 1.22374146e+03 1.22374707e+03 1.22372314e+03 1.22384338e+03 1.22392566e+03 1.22384265e+03 1.22372180e+03 1.22373975e+03 1.22370068e+03 1.22371484e+03 1.22369189e+03 1.22380884e+03 1.22405139e+03 1.22396057e+03 1.22373499e+03 1.22382764e+03 1.22386169e+03 1.22372180e+03 1.22371094e+03 1.22373657e+03 1.22377979e+03 1.22376038e+03 1.22370068e+03 1.22378064e+03 1.22397815e+03 1.22404358e+03 1.22428406e+03 1.22405298e+03 1.22376843e+03 1.22373352e+03 1.22371533e+03 1.22381494e+03 1.22381213e+03 1.22371716e+03 1.22378662e+03 1.22402979e+03 1.22384119e+03 1.22375195e+03 1.22407874e+03 1.22393591e+03 1.22371313e+03 1.22374207e+03 1.22372058e+03 1.22376306e+03 1.22378552e+03 1.22374365e+03 1.22375403e+03 1.22380090e+03 1.22377429e+03 1.22374304e+03 1.22371619e+03 1.22388879e+03 1.22396741e+03 1.22384656e+03 1.22376331e+03 1.22372266e+03 1.22374268e+03 1.22372327e+03 1.22378015e+03 1.22381921e+03 1.22377441e+03 1.22370837e+03 1.22373071e+03 1.22375256e+03 1.22375037e+03 1.22375159e+03 1.22375781e+03 1.22371887e+03 1.22371570e+03 1.22374646e+03 1.22376013e+03 1.22373938e+03 1.22373804e+03 1.22371484e+03 1.22374829e+03 1.22373987e+03 1.22374805e+03 1.22371216e+03 1.22373486e+03 1.22373120e+03 1.22373010e+03 1.22373083e+03 1.22372205e+03 1.22371667e+03 1.22372510e+03 1.22372766e+03 1.22372461e+03 1.22371204e+03 1.22369775e+03 1.22373682e+03 1.22371851e+03 1.22374951e+03 1.22374170e+03 1.22375354e+03 1.22371973e+03 1.22373914e+03 1.22373303e+03 1.22373621e+03 1.22372412e+03 1.22374146e+03 1.22373743e+03 1.22375024e+03 1.22373523e+03 1.22372693e+03 1.22371631e+03 1.22373169e+03 1.22372839e+03 1.22374036e+03 1.22372119e+03 1.22375403e+03 1.22372107e+03 1.22374548e+03 1.22371460e+03 1.22374207e+03 1.22375195e+03 1.22374622e+03 1.22372913e+03 1.22372375e+03 1.22374011e+03 1.22373083e+03 1.22370544e+03 1.22373071e+03 1.22372156e+03 1.22373486e+03 1.22372876e+03 1.22373047e+03 1.22373486e+03 1.22371057e+03 1.22371802e+03 1.22373438e+03 1.22375281e+03 1.22373181e+03 1.22371448e+03 1.22371838e+03 1.22372107e+03 1.22372058e+03 1.22372949e+03 1.22371240e+03 1.22371362e+03 1.22371448e+03 1.22373718e+03 1.22371594e+03 1.22374573e+03 1.22377295e+03 1.22381323e+03 1.22374377e+03 1.22373755e+03 1.22371179e+03 1.22371777e+03 1.22370959e+03 1.22374097e+03 1.22379309e+03 1.22378223e+03 1.22372803e+03 1.22373706e+03 1.22371460e+03 1.22371899e+03 1.22371875e+03 1.22371899e+03 1.22372754e+03 1.22371216e+03 1.22372058e+03 1.22371375e+03 1.22372375e+03 1.22373315e+03 1.22372668e+03 1.22372839e+03 1.22379761e+03 1.22380286e+03 1.22378223e+03 1.22374304e+03 1.22373950e+03 1.22371423e+03 1.22370850e+03 1.22372437e+03 1.22373010e+03 1.22375464e+03 1.22380225e+03 1.22380334e+03 1.22374988e+03 1.22371814e+03 1.22374329e+03 1.22371204e+03 1.22377832e+03 1.22393384e+03 1.22384338e+03 1.22371570e+03 1.22373950e+03 1.22372461e+03 1.22372437e+03 1.22371704e+03 1.22376160e+03 1.22378833e+03 1.22377710e+03 1.22372107e+03 1.22373804e+03 1.22371069e+03 1.22371655e+03 1.22372302e+03 1.22378577e+03 1.22378235e+03 1.22375891e+03 1.22372314e+03 1.22372168e+03 1.22371130e+03 1.22375488e+03 1.22375549e+03 1.22374890e+03 1.22373242e+03 1.22372351e+03 1.22372852e+03 1.22374561e+03 1.22372827e+03 1.22371509e+03 1.22370081e+03 1.22371521e+03 1.22376404e+03 1.22373682e+03 1.22374390e+03 1.22371179e+03 1.22373926e+03 1.22374280e+03 1.22374341e+03 1.22370911e+03 1.22371741e+03 1.22373340e+03 1.22376624e+03 1.22376550e+03 1.22375671e+03 1.22372925e+03 1.22372095e+03 1.22371558e+03 1.22373718e+03 1.22371875e+03 1.22372131e+03 1.22373096e+03 1.22373547e+03 1.22372388e+03 1.22370264e+03 1.22372485e+03 1.22378833e+03 1.22377808e+03 1.22372681e+03 1.22370825e+03 1.22373560e+03 1.22372778e+03 1.22374475e+03 1.22372900e+03 1.22372876e+03 1.22371436e+03 1.22376050e+03 1.22380408e+03 1.22382153e+03 1.22375146e+03 1.22371765e+03 1.22372375e+03 1.22374146e+03 1.22375964e+03 1.22371558e+03 1.22371680e+03 1.22378406e+03 1.22394470e+03 1.22391992e+03 1.22376245e+03 1.22370251e+03 1.22372644e+03 1.22375061e+03 1.22421228e+03 1.22581982e+03 1.22949634e+03 1.23057727e+03 1.22671387e+03 1.60621594e+03 2.37440967e+03 4.89607031e+03 4.89606982e+03 4.89598438e+03 4.89597217e+03 4.89597510e+03 4.89623535e+03 4.89666748e+03 4.90056934e+03 4.90911084e+03 7.17940527e+03 1.73271172e+04 -2.75051981e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -6.70493338e+09 1419968640. 879319296. 3.68619409e+03 1.82954126e+03 1.22655762e+03 1.22464734e+03 1.22358240e+03 1.22374402e+03 1.22382776e+03 1.22388000e+03 1.22380420e+03 1.22373303e+03 1.22374023e+03 1.22374634e+03 1.22374841e+03 1.22374438e+03 1.22378735e+03 1.22386267e+03 1.22379211e+03 1.22370349e+03 1.22372668e+03 1.22373022e+03 1.22380518e+03 1.22374524e+03 1.22374146e+03 1.22373486e+03 1.22380127e+03 1.22381738e+03 1.22382239e+03 1.22379785e+03 1.22374866e+03 1.22374500e+03 1.22375244e+03 1.22375732e+03 1.22372742e+03 1.22377197e+03 1.22380383e+03 1.22374597e+03 1.22372314e+03 1.22373755e+03 1.22373877e+03 1.22373499e+03 1.22374695e+03 1.22377625e+03 1.22379211e+03 1.22381091e+03 1.22379932e+03 1.22378564e+03 1.22374731e+03 1.22374365e+03 1.22374451e+03 1.22375110e+03 1.22375732e+03 1.22374634e+03 1.22376221e+03 1.22378784e+03 1.22379883e+03 1.22377344e+03 1.22373206e+03 1.22374890e+03 1.22376624e+03 1.22375793e+03 1.22371802e+03 1.22374536e+03 1.22375305e+03 1.22375342e+03 1.22373035e+03 1.22371167e+03 1.22376099e+03 1.22376221e+03 1.22377747e+03 1.22381189e+03 1.22391113e+03 1.22383179e+03 1.22371924e+03 1.22375403e+03 1.22370093e+03 1.22373767e+03 1.22371545e+03 1.22372180e+03 1.22370801e+03 1.22372522e+03 1.22372400e+03 1.22372705e+03 1.22373865e+03 1.22372485e+03 1.22372437e+03 1.22372827e+03 1.22372620e+03 1.22375159e+03 1.22383508e+03 1.22382178e+03 1.22376440e+03 1.22373999e+03 1.22369971e+03 1.22372778e+03 1.22377209e+03 1.22379724e+03 1.22375134e+03 1.22373450e+03 1.22375122e+03 1.22372693e+03 1.22377429e+03 1.22376050e+03 1.22375842e+03 1.22372192e+03 1.22371997e+03 1.22371252e+03 1.22372791e+03 1.22371790e+03 1.22371545e+03 1.22368909e+03 1.22371082e+03 1.22372705e+03 1.22372607e+03 1.22374524e+03 1.22372864e+03 1.22372522e+03 1.22374084e+03 1.22371362e+03 1.22373035e+03 1.22372156e+03 1.22373462e+03 1.22375244e+03 1.22375537e+03 1.22374780e+03 1.22380200e+03 1.22382642e+03 1.22373743e+03 1.22372253e+03 1.22374963e+03 1.22376636e+03 1.22377112e+03 1.22375647e+03 1.22373535e+03 1.22374194e+03 1.22371582e+03 1.22373608e+03 1.22373364e+03 1.22372974e+03 1.22371448e+03 1.22369373e+03 1.22371997e+03 1.22372424e+03 1.22371790e+03 1.22371777e+03 1.22370300e+03 1.22373413e+03 1.22372449e+03 1.22372437e+03 1.22370386e+03 1.22370935e+03 1.22372168e+03 1.22373010e+03 1.22372986e+03 1.22371252e+03 1.22374841e+03 1.22375293e+03 1.22373462e+03 1.22378735e+03 1.22387891e+03 1.22386902e+03 1.22378003e+03 1.22374646e+03 1.22374048e+03 1.22374121e+03 1.22371533e+03 1.22372729e+03 1.22372913e+03 1.22372644e+03 1.22373657e+03 1.22370764e+03 1.22373022e+03 1.22375745e+03 1.22384509e+03 1.22391711e+03 1.22386633e+03 1.22378613e+03 1.22374036e+03 1.22373108e+03 1.22372192e+03 1.22372083e+03 1.22372815e+03 1.22373303e+03 1.22371948e+03 1.22372070e+03 1.22370874e+03 1.22373157e+03 1.22373315e+03 1.22372046e+03 1.22373755e+03 1.22371204e+03 1.22372754e+03 1.22372827e+03 1.22372949e+03 1.22375647e+03 1.22371838e+03 1.22373157e+03 1.22374243e+03 1.22387427e+03 1.22393530e+03 1.22390967e+03 1.22384753e+03 1.22389893e+03 1.22380396e+03 1.22373254e+03 1.22370239e+03 1.22372949e+03 1.22373120e+03 1.22371655e+03 1.22372107e+03 1.22371558e+03 1.22374854e+03 1.22376367e+03 1.22372974e+03 1.22373303e+03 1.22369116e+03 1.22370728e+03 1.22374341e+03 1.22384338e+03 1.22382947e+03 1.22372595e+03 1.22372791e+03 1.22370972e+03 1.22375293e+03 1.22380591e+03 1.22387878e+03 1.22382910e+03 1.22377051e+03 1.22371667e+03 1.22371436e+03 1.22374377e+03 1.22376318e+03 1.22376709e+03 1.22374695e+03 1.22375989e+03 1.22374097e+03 1.22375598e+03 1.22375378e+03 1.22372192e+03 1.22373071e+03 1.22375073e+03 1.22386218e+03 1.22400037e+03 1.22406506e+03 1.22378540e+03 1.22372400e+03 1.22379736e+03 1.22373608e+03 1.22372192e+03 1.22371399e+03 1.22371985e+03 1.22373621e+03 1.22372888e+03 1.22373230e+03 1.22370483e+03 1.22372278e+03 1.22372815e+03 1.22372778e+03 1.22375049e+03 1.22382678e+03 1.22382727e+03 1.22376721e+03 1.22371729e+03 1.22371094e+03 1.22373486e+03 1.22370105e+03 1.22371277e+03 1.22370154e+03 1.22371411e+03 1.22373560e+03 1.22370789e+03 1.22375305e+03 1.22372302e+03 1.22372717e+03 1.22371216e+03 1.22370886e+03 1.22373462e+03 1.22373450e+03 1.22372449e+03 1.22371875e+03 1.22371497e+03 1.22374280e+03 1.22374036e+03 1.22371899e+03 1.22377271e+03 1.22373999e+03 1.22370654e+03 1.22373621e+03 1.22372083e+03 1.22372607e+03 1.22370142e+03 1.22371252e+03 1.22370520e+03 1.22372876e+03 1.22374463e+03 1.22377258e+03 1.22375232e+03 1.22371387e+03 1.22374658e+03 1.22372559e+03 1.22372070e+03 1.22374829e+03 1.22381750e+03 1.22384155e+03 1.22380066e+03 1.22373779e+03 1.22374390e+03 1.22374609e+03 1.22373572e+03 1.22371716e+03 1.22370764e+03 1.22372070e+03 1.22376636e+03 1.22373376e+03 1.22374500e+03 1.22370850e+03 1.22373535e+03 1.22372852e+03 1.22372205e+03 1.22371277e+03 1.22374609e+03 1.22374902e+03 1.22371814e+03 1.22372168e+03 1.22371069e+03 1.22372241e+03 1.22373535e+03 1.22372766e+03 1.22374353e+03 1.22384644e+03 1.22384863e+03 1.22373718e+03 1.22373267e+03 1.22373291e+03 1.22373474e+03 1.22370886e+03 1.22371887e+03 1.22374158e+03 1.22382654e+03 1.22385620e+03 1.22377734e+03 1.22373071e+03 1.22371667e+03 1.22371472e+03 1.22370325e+03 1.22371619e+03 1.22373816e+03 1.22375903e+03 1.22377478e+03 1.22376074e+03 1.22372986e+03 1.22373206e+03 1.22374512e+03 1.22380920e+03 1.22401099e+03 1.22400024e+03 1.22385413e+03 1.22377637e+03 1.22373926e+03 1.22372546e+03 1.22370276e+03 1.22372705e+03 1.22379846e+03 1.22394092e+03 1.22411279e+03 1.22416809e+03 1.22393787e+03 1.22380945e+03 1.22372107e+03 1.22376294e+03 1.22384961e+03 1.22376660e+03 1.22375073e+03 1.22381946e+03 1.22372119e+03 1.22370728e+03 1.22371997e+03 1.22373926e+03 1.22372363e+03 1.22372827e+03 1.22372314e+03 1.22373877e+03 1.22374927e+03 1.22374756e+03 1.22376233e+03 1.22374121e+03 1.22376392e+03 1.22375000e+03 1.22375171e+03 1.22372900e+03 1.22374219e+03 1.22375659e+03 1.22374023e+03 1.22378418e+03 1.22375305e+03 1.22377808e+03 1.22375146e+03 1.22382556e+03 1.22381824e+03 1.22373682e+03 1.22386926e+03 1.22377600e+03 1.22373938e+03 1.22373303e+03 1.22382751e+03 1.22384668e+03 1.22378711e+03 1.22373987e+03 1.22372974e+03 1.22373914e+03 1.22372388e+03 1.22373181e+03 1.22374463e+03 1.22376392e+03 1.22373254e+03 1.22380164e+03 1.22393274e+03 1.22384534e+03 1.22375208e+03 1.22381812e+03 1.22390942e+03 1.22395447e+03 1.22384766e+03 1.22374390e+03 1.22375745e+03 1.22375549e+03 1.22379944e+03 1.22377466e+03 1.22378821e+03 1.22388354e+03 1.22389917e+03 1.22388745e+03 1.22378210e+03 1.22372864e+03 1.22372766e+03 1.22370996e+03 1.22373157e+03 1.22375989e+03 1.22396338e+03 1.22390771e+03 1.22373010e+03 1.22380750e+03 1.22375879e+03 1.22374585e+03 1.22373694e+03 1.22382837e+03 1.22384802e+03 1.22378638e+03 1.22372717e+03 1.22373401e+03 1.22373364e+03 1.22374182e+03 1.22375122e+03 1.22373193e+03 1.22375732e+03 1.22374744e+03 1.22376721e+03 1.22373767e+03 1.22374854e+03 1.22374561e+03 1.22374011e+03 1.22372815e+03 1.22376807e+03 1.22385132e+03 1.22376733e+03 1.22373926e+03 1.22386035e+03 1.22374622e+03 1.22372473e+03 1.22374768e+03 1.22376501e+03 1.22377319e+03 1.22374536e+03 1.22375916e+03 1.22377368e+03 1.22376526e+03 1.22376575e+03 1.22376367e+03 1.22375171e+03 1.22375928e+03 1.22375696e+03 1.22376929e+03 1.22374976e+03 1.22374048e+03 1.22376660e+03 1.22378613e+03 1.22377112e+03 1.22373474e+03 1.22372754e+03 1.22372766e+03 1.22379944e+03 1.22381543e+03 1.22377588e+03 1.22375854e+03 1.22397998e+03 1.22418726e+03 1.22404382e+03 1.22386157e+03 1.22388916e+03 1.22406946e+03 1.22406396e+03 1.22388586e+03 1.22381653e+03 1.22378198e+03 1.22378992e+03 1.22376819e+03 1.22380334e+03 1.22378796e+03 1.22375464e+03 1.22380054e+03 1.22391199e+03 1.22401123e+03 1.22388940e+03 1.22375793e+03 1.22375732e+03 1.22382141e+03 1.22375366e+03 1.22371155e+03 1.22375110e+03 1.22370361e+03 1.22371021e+03 1.22372009e+03 1.22373132e+03 1.22369763e+03 1.22372961e+03 1.22370581e+03 1.22372083e+03 1.22371021e+03 1.22372412e+03 1.22374329e+03 1.22373755e+03 1.22372705e+03 1.22372375e+03 1.22371655e+03 1.22374353e+03 1.22376904e+03 1.22379736e+03 1.22371838e+03 1.22374243e+03 1.22374438e+03 1.22375720e+03 1.22381726e+03 1.22391443e+03 1.22395410e+03 1.22383386e+03 1.22374048e+03 1.22372778e+03 1.22373242e+03 1.22372913e+03 1.22385120e+03 1.22386292e+03 1.22377710e+03 1.22373669e+03 1.22371985e+03 1.22371680e+03 1.22372278e+03 1.22372852e+03 1.22373682e+03 1.22379224e+03 1.22375403e+03 1.22370166e+03 1.22376880e+03 1.22374011e+03 1.22374902e+03 1.22396729e+03 1.22415808e+03 1.22400732e+03 1.22377380e+03 1.22374341e+03 1.22379871e+03 1.22378687e+03 1.22373193e+03 1.22372351e+03 1.22371228e+03 1.22371448e+03 1.22370911e+03 1.22370764e+03 1.22373499e+03 1.22376245e+03 1.22379358e+03 1.22377039e+03 1.22374524e+03 1.22377197e+03 1.22375830e+03 1.22372180e+03 1.22371228e+03 1.22371875e+03 1.22373279e+03 1.22372754e+03 1.22372083e+03 1.22382666e+03 1.22606250e+03 1.22724756e+03 1.23138147e+03 1.64522913e+03 2.47385718e+03 4.89775586e+03 4.89739307e+03 2.41733594e+03 1.67879858e+03 1.23531641e+03 1.23540918e+03 1.57276270e+03 2.34947339e+03 4.89661865e+03 4.89657129e+03 4.90151758e+03 7.41303027e+03 2.75941150e+06 0. 0. 0. 0. 0. 0. 0. 0. -809208448. 623402496. -403864032. -310378336. -1227188992. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.34818294e+10 876152640. 5.85605039e+04 2.82431719e+04 1.96748770e+04 1.97285078e+04 4.74849805e+03 2.88135474e+03 2.09959839e+03 2.10218530e+03 2.09961621e+03 2.09975195e+03 2.09978418e+03 2.09953101e+03 2.09949927e+03 2.09951831e+03 2.09958594e+03 2.09953101e+03 2.09948120e+03 2.09950317e+03 2.09947632e+03 2.09993555e+03 2.09988037e+03 2.09951392e+03 2.09984692e+03 2.10021484e+03 2.09983740e+03 2.09987305e+03 2.09999048e+03 2.09983984e+03 2.09960205e+03 2.09954761e+03 2.09977661e+03 2.10109326e+03 2.10115454e+03 2.10008643e+03 2.09953394e+03 2.09964624e+03 2.09954639e+03 2.09955444e+03 2.09964160e+03 2.09973804e+03 2.09952124e+03 2.09987134e+03 2.10049902e+03 2.10003003e+03 2.09947803e+03 2.09947485e+03 2.09947949e+03 2.09945776e+03 2.09953320e+03 2.09949072e+03 2.09955566e+03 2.09962476e+03 2.09946533e+03 2.09954028e+03 2.10020435e+03 2.09984644e+03 2.09956836e+03 2.09990015e+03 2.09957959e+03 2.09948608e+03 2.09950854e+03 2.09952271e+03 2.09957373e+03 2.09945972e+03 2.09975415e+03 2.09962402e+03 2.09957520e+03 2.09999023e+03 2.09971021e+03 2.09943726e+03 2.09945752e+03 2.09947168e+03 2.09945239e+03 2.09948462e+03 2.09955347e+03 2.09946045e+03 2.09946265e+03 2.09950879e+03 2.09976660e+03 2.09982666e+03 2.09964185e+03 2.09945850e+03 2.09952368e+03 2.09954175e+03 2.09944189e+03 2.09946875e+03 2.09943213e+03 2.09954858e+03 2.10020093e+03 2.10062817e+03 2.09970605e+03 2.09954834e+03 2.09988916e+03 2.09955103e+03 2.09957495e+03 2.10034839e+03 2.10069189e+03 2.10035376e+03 2.10009375e+03 2.10008325e+03 2.09981616e+03 2.09946558e+03 2.09953418e+03 2.09944678e+03 2.09956982e+03 2.09969263e+03 2.09956372e+03 2.09947388e+03 2.09950391e+03 2.09945703e+03 2.09955859e+03 2.09953589e+03 2.09949194e+03 2.09967480e+03 2.10029346e+03 2.10030908e+03 2.09967944e+03 2.09947461e+03 2.09948120e+03 2.09974878e+03 2.10015991e+03 2.10008813e+03 2.09965674e+03 2.09948340e+03 2.09946582e+03 2.09944922e+03 2.09945850e+03 2.09944897e+03 2.09947778e+03 2.09947656e+03 2.09978662e+03 2.09974219e+03 2.09945679e+03 2.09946729e+03 2.09945630e+03 2.09960938e+03 2.09972241e+03 2.09955176e+03 2.09960327e+03 2.09992236e+03 2.10014062e+03 2.09961572e+03 2.09966211e+03 2.10017017e+03 2.09978296e+03 2.09946973e+03 2.09946021e+03 2.09946387e+03 2.09949634e+03 2.09946484e+03 2.09946240e+03 2.09960278e+03 2.09998511e+03 2.10007593e+03 2.09960229e+03 2.09955469e+03 2.09979150e+03 2.09951465e+03 2.09951416e+03 2.09945215e+03 2.09944434e+03 2.09952026e+03 2.09992139e+03 2.09980054e+03 2.09946777e+03 2.09951440e+03 2.09947998e+03 2.10047266e+03 2.10145288e+03 2.10042480e+03 2.09950073e+03 2.09944116e+03 2.09945728e+03 2.09946118e+03 2.09950269e+03 2.09946997e+03 2.09968018e+03 2.10044360e+03 2.09986304e+03 2.09945093e+03 2.09963428e+03 2.09950830e+03 2.09946191e+03 2.09953979e+03 2.09960303e+03 2.09960132e+03 2.09979492e+03 2.10004883e+03 2.09982153e+03 2.09945020e+03 2.09955176e+03 2.09946045e+03 2.09979883e+03 2.10038745e+03 2.09983472e+03 2.09944971e+03 2.09953735e+03 2.09948291e+03 2.09949414e+03 2.09974634e+03 2.09995605e+03 2.09955591e+03 2.09954590e+03 2.09954590e+03 2.09943188e+03 2.09969922e+03 2.09977051e+03 2.09967993e+03 2.09952222e+03 2.09947290e+03 2.09946704e+03 2.09948779e+03 2.09958789e+03 2.09946021e+03 2.09949341e+03 2.09963647e+03 2.09956934e+03 2.09946289e+03 2.09946240e+03 2.09946045e+03 2.09949121e+03 2.09948975e+03 2.09944727e+03 2.09945215e+03 2.09956982e+03 2.09973047e+03 2.09970459e+03 2.09947363e+03 2.09947534e+03 2.09945947e+03 2.09988281e+03 2.09994238e+03 2.09955811e+03 2.09945557e+03 2.09947217e+03 2.09947339e+03 2.09947266e+03 2.09947778e+03 2.09944385e+03 2.09948804e+03 2.09968701e+03 2.09949243e+03 2.09946338e+03 2.09945557e+03 2.09955957e+03 2.09951440e+03 2.09944897e+03 2.09947656e+03 2.09944214e+03 2.09947852e+03 2.09951440e+03 2.09954736e+03 2.09958276e+03 2.09971631e+03 2.09974878e+03 2.09946875e+03 2.09944556e+03 2.09951953e+03 2.09951831e+03 2.09948047e+03 2.09948633e+03 2.09955078e+03 2.09982520e+03 2.09990869e+03 2.09947729e+03 2.09950586e+03 2.09952759e+03 2.09951904e+03 2.09961694e+03 2.09952930e+03 2.09945166e+03 2.09948779e+03 2.09968555e+03 2.09949097e+03 2.09941675e+03 2.09964697e+03 2.09975659e+03 2.09968970e+03 2.09950439e+03 2.09947534e+03 2.09942651e+03 2.09956250e+03 2.09976221e+03 2.09960474e+03 2.09975781e+03 2.09984082e+03 2.09955591e+03 2.09950513e+03 2.09951538e+03 2.09954468e+03 2.09970825e+03 2.09953931e+03 2.09952075e+03 2.09946167e+03 2.09948633e+03 2.09952417e+03 2.09946680e+03 2.09941309e+03 2.09945215e+03 2.09944165e+03 2.09947168e+03 2.09954395e+03 2.09953271e+03 2.09948364e+03 2.09946460e+03 2.09952271e+03 2.09958643e+03 2.09962817e+03 2.09971094e+03 2.10028857e+03 2.10078857e+03 2.10065210e+03 2.10015186e+03 2.10011523e+03 2.10062793e+03 2.10097266e+03 2.10034253e+03 2.09964575e+03 2.09955859e+03 2.09963989e+03 2.09965430e+03 2.09952441e+03 2.09945776e+03 2.09951611e+03 2.09947681e+03 2.09946631e+03 2.09955469e+03 2.09957861e+03 2.09958716e+03 2.09961377e+03 2.09966821e+03 2.09983447e+03 2.09985034e+03 2.09974951e+03 2.10010156e+03 2.10062524e+03 2.10040674e+03 2.09975513e+03 2.09955347e+03 2.09954272e+03 2.09948999e+03 2.09948193e+03 2.09953613e+03 2.09948169e+03 2.09949658e+03 2.09949658e+03 2.09949902e+03 2.09949316e+03 2.09945386e+03 2.09957568e+03 2.09960156e+03 2.09946045e+03 2.09970288e+03 2.09971436e+03 2.09951392e+03 2.09948975e+03 2.09945557e+03 2.09949854e+03 2.09970386e+03 2.09973169e+03 2.09961963e+03 2.09948657e+03 2.09958398e+03 2.09968188e+03 2.09976709e+03 2.09974048e+03 2.09965991e+03 2.09964868e+03 2.09948511e+03 2.09949023e+03 2.09945190e+03 2.09945874e+03 2.09945532e+03 2.09958765e+03 2.10047681e+03 2.10085059e+03 2.10007764e+03 2.09949194e+03 2.09991626e+03 2.09948120e+03 2.09980542e+03 2.09981958e+03 2.09944507e+03 2.10044092e+03 2.10013696e+03 2.09950732e+03 2.09957007e+03 2.09960474e+03 2.09948022e+03 2.09947803e+03 2.09951416e+03 2.09971289e+03 2.09967749e+03 2.09941284e+03 2.09946582e+03 2.09964844e+03 2.09988892e+03 2.09979663e+03 2.09952686e+03 2.09958862e+03 2.09960107e+03 2.09943823e+03 2.09988721e+03 2.09984521e+03 2.09965137e+03 2.10059619e+03 2.10019238e+03 2.09946875e+03 2.09954980e+03 2.09950024e+03 2.09949780e+03 2.09961279e+03 2.09970215e+03 2.09949658e+03 2.09948413e+03 2.09950488e+03 2.09959985e+03 2.09968335e+03 2.09948584e+03 2.09945630e+03 2.09972095e+03 2.09965723e+03 2.09948242e+03 2.09949243e+03 2.10000098e+03 2.10028711e+03 2.09971533e+03 2.09956494e+03 2.10029883e+03 2.09977661e+03 2.09956787e+03 2.09991943e+03 2.09942749e+03 2.10018091e+03 2.10022729e+03 2.09945752e+03 2.09953369e+03 2.09954614e+03 2.09946802e+03 2.09946484e+03 2.09947485e+03 2.09957153e+03 2.09974146e+03 2.09978662e+03 2.10012085e+03 2.10019336e+03 2.09969312e+03 2.09945117e+03 2.09959741e+03 2.09947656e+03 2.09974414e+03 2.09966772e+03 2.09947070e+03 2.09994922e+03 2.09972827e+03 2.09948975e+03 2.09954883e+03 2.09942334e+03 2.09963110e+03 2.09957983e+03 2.09944873e+03 2.09970386e+03 2.09997729e+03 2.09966406e+03 2.09969116e+03 2.09952515e+03 2.09954272e+03 2.09951196e+03 2.09960864e+03 2.09985352e+03 2.09962549e+03 2.09945288e+03 2.09955444e+03 2.09950146e+03 2.09964136e+03 2.10016797e+03 2.09984741e+03 2.09945239e+03 2.09972266e+03 2.09975024e+03 2.09948633e+03 2.09951245e+03 2.09947192e+03 2.09944238e+03 2.09944434e+03 2.09951880e+03 2.09970435e+03 2.10018921e+03 2.10013818e+03 2.09967529e+03 2.09943677e+03 2.09953247e+03 2.09944604e+03 2.09952295e+03 2.09978149e+03 2.10005640e+03 2.09961499e+03 2.09956958e+03 2.09989868e+03 2.09951807e+03 2.09961230e+03 2.09967065e+03 2.09950073e+03 2.10032202e+03 2.10024683e+03 2.09951392e+03 2.10003955e+03 2.10055127e+03 2.09981689e+03 2.09951294e+03 2.09949243e+03 2.09953271e+03 2.09959204e+03 2.09949463e+03 2.09951782e+03 2.09946777e+03 2.09943140e+03 2.09945435e+03 2.09950684e+03 2.09953833e+03 2.09951074e+03 2.09948169e+03 2.09998901e+03 2.09996851e+03 2.09953784e+03 2.10009351e+03 2.09976758e+03 2.09942944e+03 2.09984082e+03 2.09988110e+03 2.09947803e+03 2.09971704e+03 2.10005347e+03 2.09954175e+03 2.09944580e+03 2.09951221e+03 2.09948633e+03 2.09945435e+03 2.09948901e+03 2.09948730e+03 2.09979004e+03 2.09998193e+03 2.10000635e+03 2.09967847e+03 2.09948120e+03 2.09955396e+03 2.09942188e+03 2.09984424e+03 2.10009277e+03 2.09966284e+03 2.09946265e+03 2.09944702e+03 2.09950537e+03 2.10010645e+03 2.10031592e+03 2.09962280e+03 2.09946973e+03 2.09953589e+03 2.09943018e+03 2.09960620e+03 2.09958081e+03 2.09943750e+03 2.09950879e+03 2.09955518e+03 2.09960815e+03 2.09945752e+03 2.09953223e+03 2.09962988e+03 2.09945874e+03 2.09986963e+03 2.10028711e+03 2.09966699e+03 2.09944458e+03 2.09961792e+03 2.09947412e+03 2.09952808e+03 2.09970972e+03 2.09960889e+03 2.09944702e+03 2.09946436e+03 2.09952808e+03 2.09978247e+03 2.09983643e+03 2.09950537e+03 2.09946094e+03 2.09947314e+03 2.09957837e+03 2.09991577e+03 2.09985132e+03 2.09985693e+03 2.09960205e+03 2.09945557e+03 2.09944971e+03 2.09949658e+03 2.09959131e+03 2.09982715e+03 2.09969507e+03 2.09946802e+03 2.09950391e+03 2.09946265e+03 2.09958643e+03 2.09986157e+03 2.09948584e+03 2.09969604e+03 2.10023535e+03 2.09981079e+03 2.09935034e+03 2.09934375e+03 2.09944922e+03 2.10074536e+03 2.10251001e+03 2.11365161e+03 2.13067505e+03 2.72012085e+03 3.40704053e+03 6.58614893e+03 1.22374209e+04 -1910834560. -792025344. -448833472. -508395968. -2.70145792e+09 -869269504. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.84767974e+09 1087012992. 4.46687656e+04 5.32755664e+03 2.87293115e+03 2.10242139e+03 2.10960278e+03 2.11176880e+03 2.10366162e+03 2.10062036e+03 2.10036401e+03 2.09978149e+03 2.09962939e+03 2.09974365e+03 2.09967383e+03 2.09949683e+03 2.09974854e+03 2.09960034e+03 2.09960352e+03 2.10029346e+03 2.10018970e+03 2.09977905e+03 2.09966235e+03 2.09963110e+03 2.09961865e+03 2.09968579e+03 2.09953101e+03 2.09953394e+03 2.09954053e+03 2.09972534e+03 2.09954492e+03 2.10020898e+03 2.10076392e+03 2.09974121e+03 2.09959692e+03 2.09997656e+03 2.09966333e+03 2.09958813e+03 2.10021313e+03 2.10083203e+03 2.09990649e+03 2.09955933e+03 2.09950342e+03 2.09980225e+03 2.10015674e+03 2.09985864e+03 2.09993335e+03 2.09962378e+03 2.09948071e+03 2.09946558e+03 2.09946265e+03 2.10021582e+03 2.10037280e+03 2.09959937e+03 2.09966675e+03 2.09986816e+03 2.09948169e+03 2.09982593e+03 2.09990112e+03 2.09947314e+03 2.09947192e+03 2.09958521e+03 2.10046851e+03 2.10122705e+03 2.10063159e+03 2.09956274e+03 2.09950073e+03 2.09952930e+03 2.09954736e+03 2.10024243e+03 2.10121411e+03 2.10184326e+03 2.10134302e+03 2.10049902e+03 2.09977344e+03 2.09958398e+03 2.09972534e+03 2.09959351e+03 2.09943628e+03 2.09979980e+03 2.09980859e+03 2.09945581e+03 2.09965454e+03 2.09960962e+03 2.09944922e+03 2.09947559e+03 2.09963989e+03 2.09953857e+03 2.09954175e+03 2.09992041e+03 2.09953589e+03 2.09943774e+03 2.09946191e+03 2.09960254e+03 2.09962231e+03 2.09949731e+03 2.09957715e+03 2.09953076e+03 2.09946558e+03 2.09944067e+03 2.09945703e+03 2.09992212e+03 2.09998804e+03 2.09949585e+03 2.09995801e+03 2.10062402e+03 2.09975391e+03 2.09944775e+03 2.09963843e+03 2.09952173e+03 2.09947729e+03 2.09945410e+03 2.09951196e+03 2.09974976e+03 2.09994189e+03 2.09959082e+03 2.09949927e+03 2.09965625e+03 2.09954443e+03 2.09943970e+03 2.09946216e+03 2.09952319e+03 2.09950586e+03 2.09951758e+03 2.10026343e+03 2.10026636e+03 2.09946509e+03 2.09955078e+03 2.09942896e+03 2.10008130e+03 2.10029004e+03 2.09950415e+03 2.09957764e+03 2.09971924e+03 2.09958350e+03 2.09944580e+03 2.09968286e+03 2.09969067e+03 2.09946436e+03 2.09966406e+03 2.09947119e+03 2.09960083e+03 2.09989600e+03 2.09968213e+03 2.09947656e+03 2.09945776e+03 2.09961621e+03 2.09978052e+03 2.09957861e+03 2.09945703e+03 2.09946143e+03 2.09970752e+03 2.09979980e+03 2.09946021e+03 2.09972803e+03 2.10060547e+03 2.10015576e+03 2.09949536e+03 2.09969458e+03 2.09961426e+03 2.09944678e+03 2.09942065e+03 2.09948608e+03 2.09948462e+03 2.09958301e+03 2.09955005e+03 2.09952441e+03 2.09945044e+03 2.09968774e+03 2.09986548e+03 2.09997412e+03 2.09947437e+03 2.09944824e+03 2.09950952e+03 2.09976074e+03 2.09959937e+03 2.09956372e+03 2.09981470e+03 2.09957178e+03 2.09943872e+03 2.09952490e+03 2.09948901e+03 2.09945459e+03 2.09945630e+03 2.09944434e+03 2.09951562e+03 2.09946558e+03 2.09945972e+03 2.09974976e+03 2.10020337e+03 2.10079663e+03 2.10147559e+03 2.10044263e+03 2.09954028e+03 2.09943335e+03 2.09948828e+03 2.09953003e+03 2.09957983e+03 2.09947632e+03 2.09993726e+03 2.10032544e+03 2.09951050e+03 2.09980518e+03 2.10036572e+03 2.10003394e+03 2.09965894e+03 2.09961694e+03 2.09958521e+03 2.09969165e+03 2.09992798e+03 2.09974951e+03 2.09942920e+03 2.09943481e+03 2.09946948e+03 2.09950708e+03 2.09950879e+03 2.09972949e+03 2.09998389e+03 2.09976685e+03 2.09952319e+03 2.09947363e+03 2.09952661e+03 2.09945776e+03 2.09956567e+03 2.09981128e+03 2.09992700e+03 2.09957617e+03 2.09949585e+03 2.09970483e+03 2.09981982e+03 2.09947363e+03 2.09948828e+03 2.09962744e+03 2.09944238e+03 2.09945874e+03 2.09941064e+03 2.09946924e+03 2.09943213e+03 2.09943530e+03 2.09942847e+03 2.09945117e+03 2.09945361e+03 2.09945361e+03 2.09943945e+03 2.09943433e+03 2.09952393e+03 2.09953979e+03 2.09951904e+03 2.09943921e+03 2.09946265e+03 2.09945728e+03 2.09946094e+03 2.09946948e+03 2.09947241e+03 2.09949805e+03 2.09947192e+03 2.09945215e+03 2.09945020e+03 2.09945020e+03 2.09945068e+03 2.09941699e+03 2.09943433e+03 2.09942212e+03 2.09943115e+03 2.09947314e+03 2.09942725e+03 2.09943506e+03 2.09944141e+03 2.09946460e+03 2.09947217e+03 2.09947607e+03 2.09954199e+03 2.09952271e+03 2.09949976e+03 2.09944165e+03 2.09945630e+03 2.09949609e+03 2.09948560e+03 2.09949707e+03 2.09949194e+03 2.09945215e+03 2.09944995e+03 2.09944287e+03 2.09943457e+03 2.09948267e+03 2.09943262e+03 2.09943335e+03 2.09943335e+03 2.09947998e+03 2.09944629e+03 2.09944263e+03 2.09944336e+03 2.09945312e+03 2.09946313e+03 2.09945068e+03 2.09943286e+03 2.09943311e+03 2.09944214e+03 2.09945386e+03 2.09944165e+03 2.09945215e+03 2.09942212e+03 2.09943213e+03 2.09940161e+03 2.09945850e+03 2.09944067e+03 2.09945557e+03 2.09944995e+03 2.09943896e+03 2.09943652e+03 2.09946533e+03 2.09945850e+03 2.09947119e+03 2.09947241e+03 2.09951343e+03 2.09950269e+03 2.09948438e+03 2.09943945e+03 2.09943164e+03 2.09944849e+03 2.09943384e+03 2.09942383e+03 2.09946875e+03 2.09945776e+03 2.09942920e+03 2.09946216e+03 2.09950317e+03 2.09950586e+03 2.09946826e+03 2.09943921e+03 2.09944922e+03 2.09941748e+03 2.09945044e+03 2.09943945e+03 2.09947729e+03 2.09946875e+03 2.09947681e+03 2.09947656e+03 2.09941382e+03 2.09944458e+03 2.09942065e+03 2.09944971e+03 2.09947290e+03 2.09948193e+03 2.09948535e+03 2.09949683e+03 2.09943262e+03 2.09947241e+03 2.09944360e+03 2.09944922e+03 2.09946387e+03 2.09947119e+03 2.09946240e+03 2.09945508e+03 2.09944775e+03 2.09946436e+03 2.09946875e+03 2.09944336e+03 2.09944653e+03 2.09944019e+03 2.09942456e+03 2.09943848e+03 2.09941284e+03 2.09945581e+03 2.09941626e+03 2.09946802e+03 2.09948071e+03 2.09946387e+03 2.09944727e+03 2.09948047e+03 2.09951440e+03 2.09968018e+03 2.09961377e+03 2.09951099e+03 2.09943628e+03 2.09948267e+03 2.09953076e+03 2.09956470e+03 2.09947925e+03 2.09944141e+03 2.09945142e+03 2.09947632e+03 2.09953760e+03 2.09953052e+03 2.09949146e+03 2.09949731e+03 2.09960059e+03 2.09970898e+03 2.09956738e+03 2.09945068e+03 2.09943896e+03 2.09949414e+03 2.09949927e+03 2.09945752e+03 2.09946631e+03 2.09944336e+03 2.09945923e+03 2.09954907e+03 2.09954443e+03 2.09949780e+03 2.09942993e+03 2.09944043e+03 2.09943774e+03 2.09945996e+03 2.09951782e+03 2.09971265e+03 2.09976196e+03 2.09955762e+03 2.09944287e+03 2.09943018e+03 2.09942603e+03 2.09946680e+03 2.09950317e+03 2.09945093e+03 2.09962646e+03 2.09966821e+03 2.09948535e+03 2.09947070e+03 2.09945947e+03 2.09944995e+03 2.09946826e+03 2.09950708e+03 2.09949292e+03 2.09944849e+03 2.09950293e+03 2.09949854e+03 2.09951465e+03 2.09945728e+03 2.09955469e+03 2.09956299e+03 2.09945752e+03 2.09945557e+03 2.09948022e+03 2.09959546e+03 2.09959863e+03 2.09946143e+03 2.09945386e+03 2.09945483e+03 2.09945190e+03 2.09947144e+03 2.09944653e+03 2.09946191e+03 2.09945605e+03 2.09945776e+03 2.09941406e+03 2.10007056e+03 2.10141016e+03 2.10181909e+03 2.10048389e+03 2.09991040e+03 2.56094727e+03 4.42257715e+03 1.34682412e+04 1757062144. -477961056. 662865216. 2.80360550e+09 3.10220134e+09 8.80731955e+09 520045920. -808828288. 942762688. -875321920. 1.40285102e+10 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. 0. 0. 0. 0. 0. 0. 0. -2.93439411e+09 2.41809920e+09 6.82860859e+04 3.14953203e+04 1.99077266e+04 1.96843125e+04 1.96616016e+04 5.51528564e+03 3.14910938e+03 2.13172241e+03 2.10978174e+03 2.10455884e+03 2.10062769e+03 2.10027881e+03 2.10034839e+03 2.10090112e+03 2.10066260e+03 2.09956714e+03 2.10080396e+03 2.10083594e+03 2.09945996e+03 2.10255640e+03 2.10337402e+03 2.10963525e+03 2.11383203e+03 2.11297754e+03 2.10677515e+03 2.10526807e+03 2.10979517e+03 2.11106885e+03 2.11077246e+03 2.10870239e+03 2.10475488e+03 2.10042285e+03 2.09968994e+03 2.09955933e+03 2.09953638e+03 2.09948340e+03 2.09950195e+03 2.09952271e+03 2.09949268e+03 2.09945898e+03 2.09949048e+03 2.09951514e+03 2.09955371e+03 2.09957300e+03 2.09957983e+03 2.09954492e+03 2.09945972e+03 2.09947681e+03 2.09945654e+03 2.09941357e+03 2.09942847e+03 2.09946118e+03 2.09948706e+03 2.09947021e+03 2.09943262e+03 2.09943408e+03 2.09946118e+03 2.09947119e+03 2.09952368e+03 2.09954858e+03 2.09945703e+03 2.09940845e+03 2.09945361e+03 2.09948120e+03 2.09948755e+03 2.09951953e+03 2.09947119e+03 2.09945801e+03 2.09943188e+03 2.09946606e+03 2.09945923e+03 2.09951318e+03 2.09952661e+03 2.09949341e+03 2.09948999e+03 2.09949902e+03 2.09942114e+03 2.09949365e+03 2.09951221e+03 2.09948364e+03 2.09946875e+03 2.09953491e+03 2.09978223e+03 2.09990894e+03 2.09971729e+03 2.09956030e+03 2.09957593e+03 2.09956128e+03 2.09951978e+03 2.09951196e+03 2.09966919e+03 2.09990479e+03 2.09980371e+03 2.09952393e+03 2.09944092e+03 2.09945410e+03 2.09945093e+03 2.09947485e+03 2.09946680e+03 2.09943970e+03 2.09949512e+03 2.09946021e+03 2.09943677e+03 2.09945581e+03 2.09945752e+03 2.09946753e+03 2.09948242e+03 2.09956641e+03 2.09957373e+03 2.09947925e+03 2.09944482e+03 2.09950732e+03 2.09950732e+03 2.09952539e+03 2.09946924e+03 2.09947876e+03 2.09945093e+03 2.09949170e+03 2.09948926e+03 2.09943506e+03 2.09943408e+03 2.09947217e+03 2.09948950e+03 2.09946484e+03 2.09946582e+03 2.09944946e+03 2.09950415e+03 2.09975244e+03 2.09969800e+03 2.09953979e+03 2.09946655e+03 2.09949756e+03 2.09971973e+03 2.09972681e+03 2.09963281e+03 2.09951172e+03 2.09947217e+03 2.09946631e+03 2.09945801e+03 2.09944482e+03 2.09944604e+03 2.09943384e+03 2.09946289e+03 2.09946802e+03 2.09950244e+03 2.09945532e+03 2.09947046e+03 2.09944727e+03 2.09943555e+03 2.09945557e+03 2.09947607e+03 2.09962622e+03 2.09993945e+03 2.09992383e+03 2.09963062e+03 2.09948218e+03 2.09960938e+03 2.09989307e+03 2.09986597e+03 2.09961255e+03 2.09947461e+03 2.09945190e+03 2.09946460e+03 2.09948169e+03 2.09948535e+03 2.09947827e+03 2.09946509e+03 2.09945166e+03 2.09945630e+03 2.09947046e+03 2.09954688e+03 2.09951147e+03 2.09946436e+03 2.09946509e+03 2.09945703e+03 2.09947314e+03 2.09946362e+03 2.09954077e+03 2.09957642e+03 2.09946143e+03 2.09942065e+03 2.09946240e+03 2.09945972e+03 2.09945923e+03 2.09962671e+03 2.09972412e+03 2.09957349e+03 2.09947778e+03 2.09944775e+03 2.09943091e+03 2.09944629e+03 2.09940869e+03 2.09945825e+03 2.09943506e+03 2.09952295e+03 2.09970752e+03 2.09974756e+03 2.09955762e+03 2.09948242e+03 2.09945166e+03 2.09944531e+03 2.09952612e+03 2.09967017e+03 2.09969067e+03 2.09948340e+03 2.09945605e+03 2.09947192e+03 2.09946997e+03 2.09945483e+03 2.09942358e+03 2.09944434e+03 2.09944238e+03 2.09944336e+03 2.09947607e+03 2.09944971e+03 2.09945923e+03 2.09942407e+03 2.09946802e+03 2.09946582e+03 2.09952002e+03 2.09948950e+03 2.09946191e+03 2.09948804e+03 2.09944312e+03 2.09948486e+03 2.09948242e+03 2.09946948e+03 2.09948193e+03 2.09942749e+03 2.09945239e+03 2.09945605e+03 2.09950879e+03 2.09949756e+03 2.09947314e+03 2.09942163e+03 2.09941699e+03 2.09945044e+03 2.09944482e+03 2.09948315e+03 2.09944629e+03 2.09943481e+03 2.09943579e+03 2.09946606e+03 2.09956836e+03 2.09948901e+03 2.09944922e+03 2.09956274e+03 2.09958862e+03 2.09946851e+03 2.09948511e+03 2.09944458e+03 2.09945850e+03 2.09951318e+03 2.09950757e+03 2.09948779e+03 2.09945996e+03 2.09945898e+03 2.09944971e+03 2.09944897e+03 2.09944141e+03 2.09944678e+03 2.09944531e+03 2.09946216e+03 2.09946704e+03 2.09944507e+03 2.09945752e+03 2.09944482e+03 2.09944849e+03 2.09944092e+03 2.09946851e+03 2.09957031e+03 2.09954785e+03 2.09950342e+03 2.09946191e+03 2.09945557e+03 2.09945459e+03 2.09947778e+03 2.09957300e+03 2.09962793e+03 2.09956372e+03 2.09946509e+03 2.09943896e+03 2.09943604e+03 2.09945996e+03 2.09942407e+03 2.09945166e+03 2.09944800e+03 2.09947974e+03 2.09944995e+03 2.09943091e+03 2.09943286e+03 2.09944482e+03 2.09944531e+03 2.09944312e+03 2.09957617e+03 2.09974487e+03 2.09971118e+03 2.09949902e+03 2.09944800e+03 2.09946899e+03 2.09949268e+03 2.09945776e+03 2.09946313e+03 2.09951221e+03 2.09967969e+03 2.09966699e+03 2.09954761e+03 2.09943286e+03 2.09947266e+03 2.09945312e+03 2.09944604e+03 2.09944312e+03 2.09946924e+03 2.09944092e+03 2.09946924e+03 2.09945508e+03 2.09946191e+03 2.09947095e+03 2.09943481e+03 2.09942847e+03 2.09944775e+03 2.09945117e+03 2.09949829e+03 2.09947925e+03 2.09952905e+03 2.09971484e+03 2.09994189e+03 2.10002295e+03 2.09986377e+03 2.09994141e+03 2.09965625e+03 2.09960083e+03 2.09947021e+03 2.09946606e+03 2.09951343e+03 2.09948022e+03 2.09943506e+03 2.09947046e+03 2.09947876e+03 2.09947852e+03 2.09946875e+03 2.09947778e+03 2.09952783e+03 2.09944727e+03 2.09948804e+03 2.09961450e+03 2.09960791e+03 2.09949194e+03 2.09945459e+03 2.09944189e+03 2.09945386e+03 2.09946631e+03 2.09948462e+03 2.09952148e+03 2.09952637e+03 2.09955103e+03 2.09967798e+03 2.09954736e+03 2.09947778e+03 2.09943970e+03 2.09947144e+03 2.09949292e+03 2.09948218e+03 2.09943555e+03 2.09944458e+03 2.09953149e+03 2.09956250e+03 2.09948608e+03 2.09948340e+03 2.09959375e+03 2.09978369e+03 2.09970605e+03 2.09948535e+03 2.09944067e+03 2.09947339e+03 2.09960620e+03 2.09947534e+03 2.09947900e+03 2.09942407e+03 2.09954150e+03 2.09968604e+03 2.09960254e+03 2.09952832e+03 2.09956152e+03 2.09963062e+03 2.09981567e+03 2.09968481e+03 2.09950098e+03 2.09941943e+03 2.09941992e+03 2.09943945e+03 2.09946265e+03 2.09945142e+03 2.09944727e+03 2.09946777e+03 2.09955688e+03 2.09954272e+03 2.09947656e+03 2.09945020e+03 2.09947412e+03 2.09956201e+03 2.09957129e+03 2.09949756e+03 2.09949658e+03 2.09943335e+03 2.09945190e+03 2.09942554e+03 2.09946655e+03 2.09949878e+03 2.09947656e+03 2.09948438e+03 2.09970093e+03 2.09953027e+03 2.09951489e+03 2.09948242e+03 2.09946753e+03 2.09954663e+03 2.09945093e+03 2.09941284e+03 2.09945654e+03 2.09948364e+03 2.09946558e+03 2.09945044e+03 2.09943481e+03 2.09947339e+03 2.09952490e+03 2.09948730e+03 2.09947314e+03 2.09946289e+03 2.09942700e+03 2.09944263e+03 2.09951831e+03 2.09955835e+03 2.09945728e+03 2.09946167e+03 2.09971533e+03 2.10010596e+03 2.09998633e+03 2.09956934e+03 2.09954297e+03 2.09969482e+03 2.09954590e+03 2.09949365e+03 2.09955933e+03 2.09944214e+03 2.09945410e+03 2.09947852e+03 2.09948022e+03 2.09947046e+03 2.09944556e+03 2.09944189e+03 2.09945679e+03 2.09947778e+03 2.09948096e+03 2.09945654e+03 2.09945239e+03 2.09941040e+03 2.09947803e+03 2.09945776e+03 2.09949951e+03 2.09953467e+03 2.09963232e+03 2.09955444e+03 2.09946753e+03 2.09947119e+03 2.09956152e+03 2.09958960e+03 2.09952856e+03 2.09958130e+03 2.10009375e+03 2.10069824e+03 2.10032959e+03 2.09970166e+03 2.09955518e+03 2.09974048e+03 2.09972754e+03 2.09956519e+03 2.09947437e+03 2.09948730e+03 2.09942554e+03 2.09945459e+03 2.09944385e+03 2.09947363e+03 2.09945190e+03 2.09943604e+03 2.09947778e+03 2.09961035e+03 2.09955493e+03 2.09943115e+03 2.09952637e+03 2.09968164e+03 2.09955664e+03 2.09950146e+03 2.09971338e+03 2.09961694e+03 2.09960010e+03 2.09952002e+03 2.09954834e+03 2.09954126e+03 2.09951880e+03 2.09946265e+03 2.09945654e+03 2.09948169e+03 2.09951929e+03 2.09945532e+03 2.09951709e+03 2.09978491e+03 2.09998169e+03 2.09979346e+03 2.09958154e+03 2.09947217e+03 2.09942529e+03 2.09941235e+03 2.09946338e+03 2.09943970e+03 2.09943823e+03 2.09944678e+03 2.09946582e+03 2.09946216e+03 2.09946582e+03 2.09943335e+03 2.09943799e+03 2.09942871e+03 2.09951294e+03 2.09971436e+03 2.09973657e+03 2.09956201e+03 2.09946655e+03 2.09946509e+03 2.09944775e+03 2.09946582e+03 2.09942944e+03 2.09947095e+03 2.09949609e+03 2.09953101e+03 2.09966016e+03 2.09958569e+03 2.09948999e+03 2.09945752e+03 2.09967578e+03 2.10002319e+03 2.09989185e+03 2.09952563e+03 2.09947461e+03 2.09961157e+03 2.09962280e+03 2.09953564e+03 2.09946973e+03 2.09953125e+03 2.09967041e+03 2.09981250e+03 2.09985132e+03 2.09958569e+03 2.09948120e+03 2.09947534e+03 2.09991333e+03 2.10030054e+03 2.09996265e+03 2.09953931e+03 2.09952930e+03 2.09979956e+03 2.09984180e+03 2.09965454e+03 2.09948779e+03 2.09957568e+03 2.09974976e+03 2.09987915e+03 2.09968188e+03 2.09951416e+03 2.09948511e+03 2.09963843e+03 2.09985938e+03 2.09995703e+03 2.09969019e+03 2.09949365e+03 2.09955396e+03 2.09972363e+03 2.09979761e+03 2.09966309e+03 2.09959180e+03 2.09982715e+03 2.09974658e+03 2.09954004e+03 2.09947266e+03 2.09946289e+03 2.09944653e+03 2.09947803e+03 2.09958862e+03 2.09965747e+03 2.09958325e+03 2.09954907e+03 2.09986719e+03 2.10288916e+03 2.10579980e+03 2.11508960e+03 2.67674707e+03 5.11710645e+03 1.50365957e+04 417856352. -604281152. 1.42073271e+04 7.55787988e+03 4.95751758e+03 4.96133984e+03 6.72291211e+03 1.31216865e+04 483664992. -4.05728486e+09 2.98740685e+09 -1062916800. 291795168. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.34818294e+10 876152640. 5.85605039e+04 2.82431719e+04 1.96748770e+04 9.76708008e+03 6.24702881e+03 4.90930664e+03 4.90176074e+03 4.91073926e+03 4.91923291e+03 4.90241992e+03 4.90015625e+03 4.90106787e+03 4.90122217e+03 4.90025049e+03 4.90024902e+03 4.90011865e+03 4.90016504e+03 4.90061768e+03 4.90153955e+03 4.90047363e+03 4.90050244e+03 4.90186279e+03 4.90086914e+03 4.90005127e+03 4.90041064e+03 4.90028223e+03 4.90021484e+03 4.90018457e+03 4.90063086e+03 4.90022266e+03 4.90006201e+03 4.90042773e+03 4.90024707e+03 4.90028613e+03 4.90047021e+03 4.90017383e+03 4.90073438e+03 4.90116406e+03 4.90052441e+03 4.90069873e+03 4.90122119e+03 4.90066895e+03 4.90006055e+03 4.90040820e+03 4.90010791e+03 4.90194775e+03 4.90315869e+03 4.90123975e+03 4.90028662e+03 4.90002344e+03 4.90010938e+03 4.90024609e+03 4.90015186e+03 4.90009375e+03 4.90006494e+03 4.90115283e+03 4.90308447e+03 4.90224268e+03 4.90037451e+03 4.90017920e+03 4.90033154e+03 4.90113623e+03 4.90165381e+03 4.90040479e+03 4.90036230e+03 4.90060498e+03 4.90031885e+03 4.90015039e+03 4.90061572e+03 4.90038770e+03 4.90037207e+03 4.90081104e+03 4.90028369e+03 4.90019238e+03 4.90030762e+03 4.90018945e+03 4.90008154e+03 4.90011035e+03 4.90024023e+03 4.90013379e+03 4.90064502e+03 4.90146826e+03 4.90083740e+03 4.90009131e+03 4.90038623e+03 4.90026367e+03 4.90011133e+03 4.90025293e+03 4.90034863e+03 4.90040771e+03 4.90015088e+03 4.90024268e+03 4.90020508e+03 4.90111768e+03 4.90124463e+03 4.90008105e+03 4.90040869e+03 4.90043457e+03 4.90008887e+03 4.90010742e+03 4.90013574e+03 4.90027197e+03 4.90149902e+03 4.90282715e+03 4.90085010e+03 4.90017773e+03 4.90102002e+03 4.90037451e+03 4.90006055e+03 4.90058057e+03 4.90164307e+03 4.90141260e+03 4.90096680e+03 4.90094385e+03 4.90070557e+03 4.90022852e+03 4.90051367e+03 4.90011035e+03 4.90089941e+03 4.90206836e+03 4.90096045e+03 4.90010889e+03 4.90043164e+03 4.90012842e+03 4.90020850e+03 4.90019971e+03 4.90008691e+03 4.90055518e+03 4.90266309e+03 4.90263379e+03 4.90062842e+03 4.90019482e+03 4.90002100e+03 4.90020898e+03 4.90072070e+03 4.90082422e+03 4.90069482e+03 4.90036377e+03 4.90010596e+03 4.90060889e+03 4.90095752e+03 4.90025830e+03 4.89998730e+03 4.90000342e+03 4.90008350e+03 4.90016064e+03 4.90012598e+03 4.90013330e+03 4.90010303e+03 4.90025000e+03 4.90057275e+03 4.90031494e+03 4.90024316e+03 4.90016211e+03 4.90038232e+03 4.90008252e+03 4.90081006e+03 4.90193945e+03 4.90035889e+03 4.90030420e+03 4.90044824e+03 4.90009473e+03 4.90012744e+03 4.90016504e+03 4.90013574e+03 4.90056494e+03 4.90131592e+03 4.90158740e+03 4.90097217e+03 4.90015479e+03 4.90016260e+03 4.90006494e+03 4.90033740e+03 4.90022363e+03 4.90006055e+03 4.90020654e+03 4.90120752e+03 4.90117090e+03 4.90046973e+03 4.90016113e+03 4.90070850e+03 4.90292529e+03 4.90509912e+03 4.90255029e+03 4.90044238e+03 4.90011719e+03 4.90013330e+03 4.90017188e+03 4.90020117e+03 4.90006543e+03 4.90035547e+03 4.90192139e+03 4.90155518e+03 4.90032568e+03 4.90041260e+03 4.90097607e+03 4.90060742e+03 4.90012207e+03 4.90058984e+03 4.90064111e+03 4.90103711e+03 4.90154150e+03 4.90146680e+03 4.90026904e+03 4.90039795e+03 4.90018018e+03 4.90116650e+03 4.90294873e+03 4.90114111e+03 4.90022461e+03 4.90061816e+03 4.90021924e+03 4.90023926e+03 4.90015137e+03 4.90020557e+03 4.90014160e+03 4.90026465e+03 4.90059375e+03 4.90001807e+03 4.90095215e+03 4.90125928e+03 4.90046533e+03 4.90005469e+03 4.90006934e+03 4.90014355e+03 4.90019043e+03 4.90004102e+03 4.90007422e+03 4.90052393e+03 4.90067285e+03 4.90073096e+03 4.90018555e+03 4.90014355e+03 4.90017236e+03 4.90008350e+03 4.90006201e+03 4.90022119e+03 4.90011377e+03 4.90039893e+03 4.90093262e+03 4.90047754e+03 4.90061377e+03 4.90148633e+03 4.90127881e+03 4.90019043e+03 4.90093604e+03 4.90115088e+03 4.90034961e+03 4.90021338e+03 4.90034570e+03 4.90021338e+03 4.89999951e+03 4.90019971e+03 4.90008545e+03 4.90038477e+03 4.90018408e+03 4.90082275e+03 4.90052100e+03 4.90022363e+03 4.90012305e+03 4.90022998e+03 4.90075244e+03 4.90011182e+03 4.90009473e+03 4.90042139e+03 4.90018164e+03 4.90027441e+03 4.90053271e+03 4.90086133e+03 4.90020850e+03 4.90007568e+03 4.90011523e+03 4.90022949e+03 4.90020898e+03 4.90009326e+03 4.90029541e+03 4.90092236e+03 4.90121924e+03 4.90030762e+03 4.90016797e+03 4.90016113e+03 4.90027100e+03 4.90008496e+03 4.90010010e+03 4.90013818e+03 4.90027100e+03 4.90014746e+03 4.90027783e+03 4.90019531e+03 4.90048633e+03 4.90080127e+03 4.90049268e+03 4.90040381e+03 4.90014014e+03 4.90025635e+03 4.90054199e+03 4.90034912e+03 4.90037354e+03 4.90087451e+03 4.90053760e+03 4.90003516e+03 4.90011182e+03 4.90002441e+03 4.90070020e+03 4.90139111e+03 4.90102881e+03 4.90013379e+03 4.90035156e+03 4.90007715e+03 4.90023047e+03 4.90045068e+03 4.90020166e+03 4.90026562e+03 4.90011914e+03 4.90045801e+03 4.90069092e+03 4.90079053e+03 4.90018750e+03 4.90018848e+03 4.90045557e+03 4.90100732e+03 4.90049316e+03 4.90021582e+03 4.90009229e+03 4.90036670e+03 4.90040283e+03 4.90017480e+03 4.90007959e+03 4.90074902e+03 4.90123242e+03 4.90087988e+03 4.90001514e+03 4.90016309e+03 4.90033545e+03 4.90049756e+03 4.90023389e+03 4.90012354e+03 4.90020947e+03 4.90004395e+03 4.90045557e+03 4.90047852e+03 4.90078809e+03 4.90042285e+03 4.90025000e+03 4.90046582e+03 4.90085303e+03 4.90056250e+03 4.90009033e+03 4.90007422e+03 4.90002197e+03 4.90013818e+03 4.90115381e+03 4.90075928e+03 4.90010742e+03 4.90007812e+03 4.90025732e+03 4.90074756e+03 4.90016650e+03 4.90011377e+03 4.90019775e+03 4.90060791e+03 4.90072266e+03 4.90023145e+03 4.90025098e+03 4.90053906e+03 4.89997070e+03 4.90046240e+03 4.90022119e+03 4.90037012e+03 4.90120068e+03 4.90026904e+03 4.90017529e+03 4.90005029e+03 4.90026025e+03 4.90045850e+03 4.90122705e+03 4.90350732e+03 4.90263721e+03 4.90110596e+03 4.90050391e+03 4.90117871e+03 4.90198633e+03 4.90048584e+03 4.90020752e+03 4.90005078e+03 4.90021582e+03 4.90016602e+03 4.90038721e+03 4.90250781e+03 4.90319043e+03 4.90111914e+03 4.90033936e+03 4.90081104e+03 4.90028516e+03 4.90209814e+03 4.90217041e+03 4.90064404e+03 4.90035303e+03 4.90045557e+03 4.90153857e+03 4.90251465e+03 4.90133398e+03 4.90018799e+03 4.90015479e+03 4.90026074e+03 4.90117773e+03 4.90294824e+03 4.90263477e+03 4.90155029e+03 4.90022559e+03 4.90060352e+03 4.90096777e+03 4.90028223e+03 4.90085010e+03 4.90301855e+03 4.90104004e+03 4.90005615e+03 4.90014160e+03 4.90125830e+03 4.90451904e+03 4.90298242e+03 4.90059814e+03 4.90019775e+03 4.90041406e+03 4.90027344e+03 4.90113574e+03 4.90171436e+03 4.90069336e+03 4.90037305e+03 4.90020410e+03 4.90035205e+03 4.90074609e+03 4.90020508e+03 4.90017773e+03 4.90073340e+03 4.90079395e+03 4.90036719e+03 4.90015771e+03 4.90107715e+03 4.90192383e+03 4.90049463e+03 4.90049805e+03 4.90201855e+03 4.90081982e+03 4.90036621e+03 4.90186133e+03 4.90121191e+03 4.90053027e+03 4.90023340e+03 4.90076123e+03 4.90139893e+03 4.90150781e+03 4.90044092e+03 4.90009180e+03 4.90029834e+03 4.90032812e+03 4.90019189e+03 4.90023779e+03 4.90071191e+03 4.90053418e+03 4.90020605e+03 4.90029883e+03 4.90037061e+03 4.90007666e+03 4.90085498e+03 4.90061963e+03 4.90010986e+03 4.90030811e+03 4.90003125e+03 4.90081299e+03 4.90100293e+03 4.90011670e+03 4.90039551e+03 4.90033008e+03 4.90003418e+03 4.90070264e+03 4.90157568e+03 4.90039258e+03 4.90017334e+03 4.90020850e+03 4.90008936e+03 4.90033691e+03 4.90051758e+03 4.90013574e+03 4.90012158e+03 4.90045850e+03 4.90044482e+03 4.90011963e+03 4.90097754e+03 4.90151416e+03 4.90053223e+03 4.90049609e+03 4.90226074e+03 4.90211084e+03 4.90009521e+03 4.90112842e+03 4.90206396e+03 4.90036670e+03 4.90011328e+03 4.90054980e+03 4.90016943e+03 4.90057861e+03 4.90046240e+03 4.90001904e+03 4.90040234e+03 4.90061914e+03 4.90036426e+03 4.90017334e+03 4.90041357e+03 4.90033154e+03 4.90015234e+03 4.90071631e+03 4.90111523e+03 4.90024463e+03 4.90017383e+03 4.90034668e+03 4.90019531e+03 4.90084082e+03 4.90061816e+03 4.90028906e+03 4.90007227e+03 4.90018604e+03 4.90008789e+03 4.90017480e+03 4.90014062e+03 4.90020898e+03 4.90022119e+03 4.90007373e+03 4.90025049e+03 4.90076562e+03 4.90126416e+03 4.90035596e+03 4.90026855e+03 4.90031641e+03 4.90040723e+03 4.90017920e+03 4.90038428e+03 4.90041064e+03 4.90025342e+03 4.90077930e+03 4.90063184e+03 4.90015186e+03 4.90027393e+03 4.90074609e+03 4.90020117e+03 4.90022754e+03 4.90024805e+03 4.90018115e+03 4.90075488e+03 4.90188281e+03 4.90172803e+03 4.90036914e+03 4.90052002e+03 4.90097607e+03 4.90277734e+03 4.90254980e+03 4.90197266e+03 4.90079883e+03 4.89998877e+03 4.90015479e+03 4.90009863e+03 4.90047852e+03 4.90088672e+03 4.90037402e+03 4.90034912e+03 4.90019922e+03 4.90031934e+03 4.90127148e+03 4.90079102e+03 4.90007324e+03 4.90056543e+03 4.90064307e+03 4.89997998e+03 4.90047461e+03 4.90085938e+03 4.90085352e+03 4.90048535e+03 4.90020898e+03 4.90017383e+03 4.90010352e+03 4.90014990e+03 4.90020654e+03 4.90021631e+03 4.90084668e+03 4.90161328e+03 4.90052539e+03 4.90030420e+03 4.90088330e+03 4.90019727e+03 4.90047070e+03 4.90075293e+03 4.90018213e+03 4.90029688e+03 4.90063867e+03 4.90011475e+03 4.90008643e+03 4.90009570e+03 4.90014160e+03 4.90031055e+03 4.90021729e+03 4.90013086e+03 4.90023242e+03 4.90015967e+03 4.90006689e+03 4.90037646e+03 4.90210254e+03 4.90339844e+03 4.90292822e+03 4.90058350e+03 4.89993701e+03 4.89999170e+03 4.90059229e+03 4.90927637e+03 4.90710498e+03 4.89981689e+03 6.55040039e+03 1.21838115e+04 -5.81436826e+09 -1.79567923e+10 -1446518016. -5.59686093e+09 1.69227049e+10 -858605440. -5.65300070e+09 7.13690982e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.84767974e+09 1087012992. 4.46687656e+04 2.64658574e+04 9.87780762e+03 6.73442236e+03 4.98616699e+03 4.95517188e+03 4.91287402e+03 4.90399658e+03 4.90003564e+03 4.89996289e+03 4.90057617e+03 4.90115332e+03 4.90038818e+03 4.90058252e+03 4.90051562e+03 4.90019531e+03 4.90050342e+03 4.90047168e+03 4.90017334e+03 4.90111768e+03 4.90134473e+03 4.90041846e+03 4.90061719e+03 4.90079443e+03 4.90018896e+03 4.90094824e+03 4.90095166e+03 4.90024072e+03 4.90010205e+03 4.90054834e+03 4.90074121e+03 4.90031006e+03 4.90024561e+03 4.90020850e+03 4.90030225e+03 4.90057178e+03 4.90045898e+03 4.90016211e+03 4.90107959e+03 4.90125000e+03 4.90021387e+03 4.90029541e+03 4.90027344e+03 4.90027539e+03 4.90161768e+03 4.90128711e+03 4.90004004e+03 4.90153564e+03 4.90157812e+03 4.90022607e+03 4.90060596e+03 4.90064258e+03 4.90009912e+03 4.90011475e+03 4.90027930e+03 4.90024072e+03 4.90013086e+03 4.90017236e+03 4.90078809e+03 4.90059326e+03 4.90015137e+03 4.90010889e+03 4.90015967e+03 4.90143311e+03 4.90135059e+03 4.90046826e+03 4.90010498e+03 4.90039893e+03 4.90026221e+03 4.90162891e+03 4.90420312e+03 4.90253662e+03 4.90038574e+03 4.90013477e+03 4.90071338e+03 4.90173145e+03 4.90164014e+03 4.90012793e+03 4.90022607e+03 4.90021484e+03 4.90071240e+03 4.90061914e+03 4.90063916e+03 4.90101514e+03 4.90058203e+03 4.90029102e+03 4.90022217e+03 4.90040430e+03 4.90238037e+03 4.90284180e+03 4.90178271e+03 4.90035254e+03 4.90024023e+03 4.90026318e+03 4.90049023e+03 4.90113672e+03 4.90102637e+03 4.90014502e+03 4.90033887e+03 4.90021387e+03 4.90135791e+03 4.90100830e+03 4.90025977e+03 4.90054834e+03 4.90040039e+03 4.90042139e+03 4.90023145e+03 4.90027832e+03 4.90120557e+03 4.90096143e+03 4.90036133e+03 4.90019971e+03 4.90021729e+03 4.90041943e+03 4.90053418e+03 4.90019873e+03 4.90027393e+03 4.90048438e+03 4.90037451e+03 4.90033154e+03 4.90068457e+03 4.90097900e+03 4.90026611e+03 4.90048242e+03 4.90017139e+03 4.90019580e+03 4.90012256e+03 4.90021484e+03 4.90015381e+03 4.90007178e+03 4.90030322e+03 4.90029053e+03 4.90021240e+03 4.90062256e+03 4.90053760e+03 4.90016650e+03 4.90033740e+03 4.90031299e+03 4.90016211e+03 4.90013525e+03 4.90029785e+03 4.90048438e+03 4.90099902e+03 4.90043018e+03 4.90009473e+03 4.90061816e+03 4.90045898e+03 4.89995068e+03 4.90017529e+03 4.90022510e+03 4.90026660e+03 4.90015820e+03 4.90059229e+03 4.90094238e+03 4.90132568e+03 4.90129102e+03 4.90051562e+03 4.90034570e+03 4.90059326e+03 4.90068213e+03 4.90059277e+03 4.90015820e+03 4.90027734e+03 4.90070801e+03 4.90157861e+03 4.90079004e+03 4.90008057e+03 4.90065186e+03 4.90079590e+03 4.90012061e+03 4.90054443e+03 4.90058447e+03 4.90030713e+03 4.90021338e+03 4.90032861e+03 4.90025391e+03 4.90025293e+03 4.90022559e+03 4.90009717e+03 4.90000195e+03 4.90077246e+03 4.90098779e+03 4.90045996e+03 4.90017188e+03 4.90010938e+03 4.90027490e+03 4.90013232e+03 4.90023633e+03 4.90048975e+03 4.90156348e+03 4.90094482e+03 4.90002197e+03 4.90032373e+03 4.90069531e+03 4.89999365e+03 4900. 4.90002197e+03 4.90054883e+03 4.90038574e+03 4.90014111e+03 4.90044727e+03 4.90114111e+03 4.90123291e+03 4.90235889e+03 4.90131982e+03 4.90021582e+03 4.89997070e+03 4.90013037e+03 4.90036963e+03 4.90033447e+03 4.90009717e+03 4.90022021e+03 4.90115381e+03 4.90051758e+03 4.90015625e+03 4.90160693e+03 4.90082959e+03 4.90011914e+03 4.90021826e+03 4.90011865e+03 4.90030225e+03 4.90026611e+03 4.90003027e+03 4.90005859e+03 4.90033496e+03 4.90035742e+03 4.90023340e+03 4.90021631e+03 4.90057275e+03 4.90106055e+03 4.90057227e+03 4.90005762e+03 4.90017188e+03 4.90009277e+03 4.90005518e+03 4.90007178e+03 4.90030225e+03 4.90017920e+03 4.90012109e+03 4.90010693e+03 4.90019971e+03 4.90012891e+03 4.90007715e+03 4.90012109e+03 4.90024756e+03 4.90010205e+03 4.90017139e+03 4.89993115e+03 4.90009277e+03 4.90016797e+03 4.90000342e+03 4.90001465e+03 4.90010303e+03 4.89989551e+03 4.90000244e+03 4.89996631e+03 4.90016943e+03 4.90010254e+03 4.90010303e+03 4.90000732e+03 4.90005566e+03 4.89998340e+03 4.90003125e+03 4.89995361e+03 4.90010205e+03 4.90005469e+03 4.90010352e+03 4.90012695e+03 4.89994580e+03 4.90034180e+03 4.90023926e+03 4.90011719e+03 4.90016162e+03 4.90019043e+03 4.90008398e+03 4.90015918e+03 4.90003662e+03 4.90014258e+03 4.89997803e+03 4.90006445e+03 4.89997314e+03 4.90000586e+03 4.90001172e+03 4.90018701e+03 4.90010596e+03 4.90006787e+03 4.90004150e+03 4900. 4.89999121e+03 4.90000195e+03 4.90016016e+03 4.90015088e+03 4.90016699e+03 4.90011963e+03 4.90013184e+03 4.90005566e+03 4.90006348e+03 4.90010107e+03 4.89999902e+03 4.90000244e+03 4.90011426e+03 4.89995068e+03 4.89994482e+03 4.90006787e+03 4.89993945e+03 4.90014404e+03 4.90000732e+03 4.90008008e+03 4.90011182e+03 4.90012549e+03 4.90004443e+03 4.90015967e+03 4.89996094e+03 4.90003809e+03 4.90019287e+03 4.90014209e+03 4.90006738e+03 4.89997168e+03 4.90012305e+03 4.90025342e+03 4.90032812e+03 4.90032617e+03 4.90019775e+03 4.90007031e+03 4.90010156e+03 4.90016406e+03 4.89998877e+03 4.90008252e+03 4.90034717e+03 4.90019336e+03 4.90021973e+03 4.89999268e+03 4.90014600e+03 4.90008594e+03 4.90019092e+03 4.90017285e+03 4.90014893e+03 4.90006592e+03 4.90006396e+03 4.90016943e+03 4.90018359e+03 4.90016211e+03 4.90012646e+03 4.90017725e+03 4.90047754e+03 4.90054834e+03 4.90010791e+03 4.89996680e+03 4.89994922e+03 4.90005713e+03 4.90012158e+03 4.90010449e+03 4.90006738e+03 4.90017334e+03 4.90032568e+03 4.90050244e+03 4.90018750e+03 4.90007959e+03 4.90000098e+03 4.90006104e+03 4.90019824e+03 4.90087451e+03 4.90042090e+03 4.90016113e+03 4.90003223e+03 4.90016357e+03 4.90018066e+03 4.90018262e+03 4.90007666e+03 4.90033594e+03 4.90016211e+03 4.90004346e+03 4.90001611e+03 4.90019043e+03 4.89997119e+03 4.90007031e+03 4.90020361e+03 4.90008887e+03 4.90002148e+03 4.90003076e+03 4.89999902e+03 4.90006152e+03 4.90001514e+03 4.90002881e+03 4.90021436e+03 4.90022168e+03 4.89999512e+03 4.89994629e+03 4.89998682e+03 4.90013330e+03 4.90008887e+03 4.90004785e+03 4.89999902e+03 4.90004199e+03 4.89996582e+03 4.90000684e+03 4.90006641e+03 4.90016992e+03 4.90025391e+03 4.90005078e+03 4.90007764e+03 4.90007129e+03 4.90014014e+03 4.90011670e+03 4.90017578e+03 4.90019092e+03 4.90021094e+03 4.90014453e+03 4900. 4.89991162e+03 4.90006738e+03 4.90013477e+03 4.90001562e+03 4.89994922e+03 4.90010352e+03 4.90010352e+03 4.90007617e+03 4.90016455e+03 4.90022510e+03 4.90003369e+03 4.90017432e+03 4.89998975e+03 4.90004346e+03 4.89995410e+03 4.89994482e+03 4.89999268e+03 4.90005518e+03 4.90009619e+03 4.90026807e+03 4.90027441e+03 4.90027441e+03 4.90007812e+03 4.90007715e+03 4.90017285e+03 4.90005078e+03 4.90006250e+03 4.90002441e+03 4.90021143e+03 4.90085254e+03 4.90086621e+03 4.90019189e+03 4.90002783e+03 4.89995654e+03 4.90021045e+03 4.90220459e+03 4.90803809e+03 4.92154785e+03 4.92596777e+03 4.91500830e+03 6.95922949e+03 1.34697764e+04 2.21951309e+09 1146871552. 6.29035571e+09 999020544. 1.28919306e+10 -1.27256760e+10 -2131678720. 1430662528. -883230656. -2.22702438e+09 -4.59006208e+09 5.38010163e+09 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. 0. 0. 0. 0. 0. 0. -2.93439411e+09 2.41809920e+09 6.82860859e+04 3.14953203e+04 1.99077266e+04 1.01304502e+04 6.85623486e+03 4.96069775e+03 4.90828613e+03 4.90084180e+03 4.90045166e+03 4.90125391e+03 4.90128223e+03 4.90072949e+03 4.90013184e+03 4.90021875e+03 4.90009912e+03 4.90005127e+03 4.90010010e+03 4.90026562e+03 4.90071582e+03 4.90039551e+03 4.90011621e+03 4.90008154e+03 4.90016699e+03 4.90028418e+03 4.90018604e+03 4.90015430e+03 4.90011426e+03 4.90017432e+03 4.90041748e+03 4.90044336e+03 4.90034131e+03 4.90005957e+03 4.89995361e+03 4.90004590e+03 4.90004639e+03 4.89995801e+03 4.90025977e+03 4.90022510e+03 4.90022119e+03 4.90010742e+03 4.90003955e+03 4.90001221e+03 4.90008203e+03 4.90023438e+03 4.90020361e+03 4.90018408e+03 4.90032227e+03 4.90028711e+03 4.90006543e+03 4.90017090e+03 4.90022900e+03 4.90036621e+03 4.90015234e+03 4.90023193e+03 4.90018945e+03 4.90021582e+03 4.90028174e+03 4.90034570e+03 4.90000635e+03 4.90005762e+03 4.90012695e+03 4.90027100e+03 4.90016602e+03 4.90008398e+03 4.90004590e+03 4.90002002e+03 4.90019678e+03 4.90022803e+03 4.90001465e+03 4.90015186e+03 4.90011035e+03 4.90025000e+03 4.90037598e+03 4.90079053e+03 4.90045215e+03 4.90005615e+03 4.90008740e+03 4.90010156e+03 4.90010889e+03 4.90004590e+03 4.90013037e+03 4.90013916e+03 4.90013623e+03 4.90010645e+03 4.89999365e+03 4.89994189e+03 4.90004004e+03 4.90001611e+03 4.90006201e+03 4.89989404e+03 4.89998779e+03 4.90050781e+03 4.90045508e+03 4.90015234e+03 4.90000830e+03 4.90014160e+03 4.90021191e+03 4.90037451e+03 4.90030273e+03 4.90005615e+03 4.89995166e+03 4.90001758e+03 4.89999854e+03 4.90013525e+03 4.90032861e+03 4.90009131e+03 4.90016113e+03 4.89996338e+03 4.90004834e+03 4.89993652e+03 4.89997949e+03 4.90011328e+03 4.90013281e+03 4.90000684e+03 4.89998877e+03 4.90011963e+03 4.90021777e+03 4.90013184e+03 4.90004834e+03 4.90001025e+03 4.90008496e+03 4.90005029e+03 4.90003369e+03 4.90000684e+03 4.90019482e+03 4.90011768e+03 4.90008350e+03 4.90040137e+03 4.90047314e+03 4.90010205e+03 4.90011670e+03 4.89996582e+03 4.90022217e+03 4.90001367e+03 4.89987354e+03 4.89996533e+03 4.90009473e+03 4.90014990e+03 4.89996240e+03 4.90003223e+03 4.89992578e+03 4.89985791e+03 4.90008594e+03 4.90004053e+03 4.89999658e+03 4.90011475e+03 4.90005518e+03 4.90002393e+03 4.89999072e+03 4.89995947e+03 4.90008301e+03 4.90016357e+03 4.90014160e+03 4.90004736e+03 4.90003320e+03 4.90004492e+03 4.90012500e+03 4.90022949e+03 4.90013379e+03 4.89998535e+03 4.90009082e+03 4.90055908e+03 4.90064355e+03 4.90026562e+03 4.90027246e+03 4.90032812e+03 4.90013281e+03 4.90020264e+03 4.90010303e+03 4.90008643e+03 4.90006299e+03 4.89998535e+03 4.90004150e+03 4.90013721e+03 4.90007178e+03 4.90033838e+03 4.90078467e+03 4.90064258e+03 4.90029297e+03 4.89997852e+03 4.90010303e+03 4.90008203e+03 4.89997754e+03 4.90004492e+03 4.89993799e+03 4.90006250e+03 4.89990430e+03 4.90014502e+03 4.90001855e+03 4.89988672e+03 4.90009033e+03 4.89997217e+03 4.90004590e+03 4.89998975e+03 4.90002441e+03 4.89999023e+03 4.90020654e+03 4.90014502e+03 4.90010352e+03 4.90011475e+03 4.90038477e+03 4.90060156e+03 4.90064893e+03 4.90049219e+03 4.90069971e+03 4.90028613e+03 4.90011719e+03 4.90016406e+03 4.89996045e+03 4.90002930e+03 4.89994141e+03 4.89987891e+03 4.90006592e+03 4.90015771e+03 4.89999658e+03 4.90002295e+03 4.89993848e+03 4.90016113e+03 4.90008594e+03 4.90014941e+03 4.90065723e+03 4.90051172e+03 4.90019580e+03 4.90002832e+03 4.90004980e+03 4.90020312e+03 4.90061572e+03 4.90095752e+03 4.90062354e+03 4.90034912e+03 4.90010449e+03 4.90016504e+03 4.90006201e+03 4.90034668e+03 4.90020996e+03 4.90019043e+03 4.90010693e+03 4.90024023e+03 4.90025000e+03 4.90015967e+03 4.90015088e+03 4.90011719e+03 4.90011426e+03 4.90060498e+03 4.90130811e+03 4.90158057e+03 4.90029932e+03 4.90006201e+03 4.90020996e+03 4.90011816e+03 4.89996484e+03 4.90008398e+03 4.90025049e+03 4.90015527e+03 4.90000195e+03 4.90006934e+03 4.89998047e+03 4.90003760e+03 4.90003320e+03 4.89999561e+03 4.89990088e+03 4.90036719e+03 4.90061426e+03 4.90035498e+03 4.90009033e+03 4.90013770e+03 4.90014502e+03 4.90017041e+03 4.90024316e+03 4.90004395e+03 4.90004150e+03 4.89995361e+03 4.90003027e+03 4.89993311e+03 4.90018799e+03 4.89996094e+03 4.90012793e+03 4.90007715e+03 4.89991553e+03 4.90000537e+03 4.90001367e+03 4.90016406e+03 4.90007959e+03 4.90006738e+03 4.89994336e+03 4.90016357e+03 4.90030957e+03 4.90031494e+03 4.90020801e+03 4.89997021e+03 4.89991113e+03 4.90004297e+03 4.90016992e+03 4.90004004e+03 4.90016504e+03 4.90003320e+03 4.90020898e+03 4.90042627e+03 4.90027246e+03 4.89999805e+03 4.89999512e+03 4.90018408e+03 4.90001025e+03 4.90010254e+03 4.90043896e+03 4.90038379e+03 4.90042139e+03 4.90022021e+03 4.90013672e+03 4.90005273e+03 4.90016016e+03 4.90002783e+03 4.90000293e+03 4.90003125e+03 4.90007666e+03 4.90010156e+03 4.90003809e+03 4.90005957e+03 4.90002441e+03 4.90006543e+03 4.90010986e+03 4.90013037e+03 4.90024316e+03 4.90027930e+03 4.90016260e+03 4.90006641e+03 4.90009668e+03 4.89997559e+03 4.90005127e+03 4.89997754e+03 4.90016016e+03 4.90059424e+03 4.90056641e+03 4.90013672e+03 4.90006445e+03 4.90005713e+03 4.90004736e+03 4.90013330e+03 4.89995215e+03 4.90005664e+03 4.90043604e+03 4.90055078e+03 4.90016113e+03 4.89996289e+03 4.90007764e+03 4.89994775e+03 4.90011475e+03 4.90004102e+03 4.89999658e+03 4.89996582e+03 4.90009863e+03 4.90021289e+03 4.90006982e+03 4.89997705e+03 4.89996924e+03 4.90023438e+03 4.90097168e+03 4.90114941e+03 4.90043994e+03 4.90008789e+03 4.90009717e+03 4.89989697e+03 4.90004980e+03 4.90007959e+03 4.90044824e+03 4.90102002e+03 4.90179150e+03 4.90185986e+03 4.90104883e+03 4.90038086e+03 4.90012402e+03 4.90030957e+03 4.90057715e+03 4.90021191e+03 4.90010205e+03 4.90048584e+03 4.90012256e+03 4.90007080e+03 4.90010107e+03 4900. 4.89996680e+03 4.90000928e+03 4.90004883e+03 4.90003613e+03 4.89996191e+03 4.90008203e+03 4.89996143e+03 4.90008740e+03 4.89997803e+03 4.90007812e+03 4.89992822e+03 4.89995410e+03 4.90012305e+03 4.90005029e+03 4.90005762e+03 4.90027295e+03 4.89995410e+03 4.90003809e+03 4.89986816e+03 4.90043506e+03 4.90052002e+03 4.90005713e+03 4.90051270e+03 4.90016455e+03 4.89998486e+03 4.90001562e+03 4.90031787e+03 4.90048438e+03 4.90018701e+03 4.90001318e+03 4.90006445e+03 4.90003174e+03 4.90007568e+03 4.90008154e+03 4.90005225e+03 4.90025342e+03 4.90009033e+03 4.90027832e+03 4.90070703e+03 4.90046289e+03 4.90016895e+03 4.90047119e+03 4.90093018e+03 4.90104053e+03 4.90055566e+03 4.90010986e+03 4.90015723e+03 4.90023730e+03 4.90015771e+03 4.90001855e+03 4.90012402e+03 4.90038037e+03 4.90079102e+03 4.90059912e+03 4.90013477e+03 4.90014160e+03 4.90009277e+03 4.90005176e+03 4.90002344e+03 4.90024121e+03 4.90105225e+03 4.90070801e+03 4.90000977e+03 4.90020068e+03 4.90005518e+03 4.89989941e+03 4.90005859e+03 4.90037500e+03 4.90033691e+03 4.90004639e+03 4.89998584e+03 4.89999463e+03 4.90009131e+03 4.90002393e+03 4.90004736e+03 4.89991113e+03 4.89997656e+03 4.90017334e+03 4.90012598e+03 4.90010986e+03 4.89999170e+03 4.89997656e+03 4.89998535e+03 4.90005762e+03 4.90009473e+03 4.90047119e+03 4.90001660e+03 4.90016553e+03 4.90050146e+03 4.90015527e+03 4.90003027e+03 4.90013281e+03 4.90024658e+03 4.90030469e+03 4.90014062e+03 4.90014600e+03 4.90009375e+03 4.90011475e+03 4.90013135e+03 4.90000391e+03 4.90008887e+03 4.90012891e+03 4.90020361e+03 4.90004053e+03 4.89999463e+03 4.90007910e+03 4.90023438e+03 4.90039844e+03 4.90004785e+03 4.90006543e+03 4.90008301e+03 4.90015771e+03 4.90042188e+03 4.90033398e+03 4.90007666e+03 4.90013623e+03 4.90111621e+03 4.90205078e+03 4.90138184e+03 4.90049072e+03 4.90059326e+03 4.90118359e+03 4.90149268e+03 4.90071143e+03 4.90021680e+03 4.90013281e+03 4.90005957e+03 4.90032666e+03 4.90028076e+03 4.90034375e+03 4.90007520e+03 4.90043896e+03 4.90079932e+03 4.90103809e+03 4.90054102e+03 4.90012256e+03 4.90021582e+03 4.90064551e+03 4.90030273e+03 4.89997998e+03 4.90025586e+03 4.90018457e+03 4.90004736e+03 4.89994385e+03 4.90000195e+03 4.90009082e+03 4.90006934e+03 4.90005469e+03 4.89998975e+03 4.90009961e+03 4.90006982e+03 4.89995020e+03 4.89987500e+03 4.90008984e+03 4.89998340e+03 4.90005811e+03 4.90011328e+03 4.90053125e+03 4.90033936e+03 4.90020508e+03 4.90013232e+03 4.90017139e+03 4.90025977e+03 4.90051074e+03 4.90114600e+03 4.90098291e+03 4.90043604e+03 4.90014258e+03 4.90011377e+03 4.90000635e+03 4.90008057e+03 4.90051416e+03 4.90082666e+03 4.90020605e+03 4.90000879e+03 4.89994922e+03 4.90011133e+03 4.90013379e+03 4.89995312e+03 4.90010254e+03 4.90041553e+03 4.90019824e+03 4.90004102e+03 4.90028467e+03 4.90016064e+03 4.90015723e+03 4.90105811e+03 4.90203320e+03 4.90143457e+03 4.90010352e+03 4.90020459e+03 4.90026562e+03 4.90047607e+03 4.90014941e+03 4.90010156e+03 4.90009863e+03 4.90004248e+03 4.90022705e+03 4.90012109e+03 4.90016553e+03 4.90026221e+03 4.90039893e+03 4.90041406e+03 4.90024268e+03 4.90030225e+03 4.90031934e+03 4.90017529e+03 4.90012256e+03 4.90004150e+03 4.90003174e+03 4.90011084e+03 4.90009424e+03 4.90049365e+03 4.90941309e+03 4.91473193e+03 4.93893799e+03 7.24130273e+03 1.51792061e+04 1095444736. 879351168. 1.42733789e+04 7.59409814e+03 4.97106836e+03 4.97403076e+03 6.71324365e+03 1.31909717e+04 758851264. 8.61799731e+09 1649484800. -4.59162726e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.29749197e+09 3.29749197e+09 1648745984. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.34818294e+10 876152640. 1080937728. -3.61158170e+09 1.36156855e+04 9.49105469e+03 6.07137500e+03 6.59645312e+03 4.90940234e+03 4.91033984e+03 4.90187256e+03 4.90210498e+03 4.90233057e+03 4.90212598e+03 4.90195654e+03 4.90216260e+03 4.90277344e+03 4.90240283e+03 4.90205127e+03 4.90225635e+03 4.90205615e+03 4.90296387e+03 4.90291357e+03 4.90203760e+03 4.90244189e+03 4.90298242e+03 4.90227490e+03 4.90233350e+03 4.90304590e+03 4.90296582e+03 4.90234619e+03 4.90204150e+03 4.90241699e+03 4.90465723e+03 4.90535205e+03 4.90316895e+03 4.90199707e+03 4.90199854e+03 4.90204639e+03 4.90221777e+03 4.90263721e+03 4.90287500e+03 4.90215088e+03 4.90281299e+03 4.90500586e+03 4.90413135e+03 4.90221387e+03 4.90203711e+03 4.90202246e+03 4.90199121e+03 4.90214258e+03 4.90205713e+03 4.90220605e+03 4.90251416e+03 4.90223828e+03 4.90217773e+03 4.90371436e+03 4.90323291e+03 4.90199365e+03 4.90271924e+03 4.90219727e+03 4.90218994e+03 4.90220508e+03 4.90216162e+03 4.90228662e+03 4.90216455e+03 4.90296973e+03 4.90266992e+03 4.90212158e+03 4.90343066e+03 4.90273828e+03 4.90201367e+03 4.90193750e+03 4.90198828e+03 4.90207080e+03 4.90217285e+03 4.90268848e+03 4.90228906e+03 4.90199219e+03 4.90209814e+03 4.90256885e+03 4.90287256e+03 4.90242920e+03 4.90204834e+03 4.90207422e+03 4.90216260e+03 4.90208008e+03 4.90203564e+03 4.90201416e+03 4.90223584e+03 4.90367090e+03 4.90459570e+03 4.90278223e+03 4.90216357e+03 4.90302734e+03 4.90241553e+03 4.90211035e+03 4.90365283e+03 4.90465088e+03 4.90392480e+03 4.90340137e+03 4.90378174e+03 4.90312646e+03 4.90205078e+03 4.90218457e+03 4.90208447e+03 4.90224316e+03 4.90242090e+03 4.90220264e+03 4.90202148e+03 4.90203613e+03 4.90195459e+03 4.90215820e+03 4.90207764e+03 4.90207373e+03 4.90244385e+03 4.90406689e+03 4.90444287e+03 4.90284668e+03 4.90195752e+03 4.90199463e+03 4.90244922e+03 4.90327490e+03 4.90342334e+03 4.90242676e+03 4.90197412e+03 4.90204932e+03 4.90202588e+03 4.90194238e+03 4.90202734e+03 4.90217383e+03 4.90206055e+03 4.90259961e+03 4.90258838e+03 4.90201172e+03 4.90202881e+03 4.90200732e+03 4.90219775e+03 4.90245898e+03 4.90217578e+03 4.90234082e+03 4.90298096e+03 4.90336035e+03 4.90222363e+03 4.90248633e+03 4.90381445e+03 4.90283398e+03 4.90204102e+03 4.90209814e+03 4.90199902e+03 4.90212451e+03 4.90211816e+03 4.90206787e+03 4.90232568e+03 4.90327930e+03 4.90362988e+03 4.90246729e+03 4.90223242e+03 4.90317773e+03 4.90208301e+03 4.90208887e+03 4.90211377e+03 4.90201074e+03 4.90207178e+03 4.90332715e+03 4.90307910e+03 4.90208594e+03 4.90228369e+03 4.90189062e+03 4.90330957e+03 4.90551074e+03 4.90412549e+03 4.90236084e+03 4.90199316e+03 4.90204541e+03 4.90201367e+03 4.90207568e+03 4.90199854e+03 4.90237402e+03 4.90414404e+03 4.90295312e+03 4.90206641e+03 4.90221924e+03 4.90206934e+03 4.90195605e+03 4.90215088e+03 4.90244922e+03 4.90253174e+03 4.90297070e+03 4.90389258e+03 4.90322705e+03 4.90214990e+03 4.90218066e+03 4.90203467e+03 4.90246094e+03 4.90344873e+03 4.90307520e+03 4.90204395e+03 4.90197607e+03 4.90196777e+03 4.90209180e+03 4.90278760e+03 4.90334229e+03 4.90238721e+03 4.90204590e+03 4.90232764e+03 4.90204492e+03 4.90230371e+03 4.90269531e+03 4.90265625e+03 4.90210645e+03 4.90202881e+03 4.90196826e+03 4.90202295e+03 4.90228174e+03 4.90210742e+03 4.90208691e+03 4.90226416e+03 4.90215576e+03 4.90203223e+03 4.90206006e+03 4.90194189e+03 4.90199316e+03 4.90195947e+03 4.90198584e+03 4.90207373e+03 4.90232617e+03 4.90268018e+03 4.90272070e+03 4.90204883e+03 4.90204688e+03 4.90207568e+03 4.90284131e+03 4.90313184e+03 4.90208545e+03 4.90206055e+03 4.90208008e+03 4.90202686e+03 4.90202686e+03 4.90206348e+03 4.90210205e+03 4.90210205e+03 4.90222119e+03 4.90198828e+03 4.90199951e+03 4.90216113e+03 4.90232568e+03 4.90210449e+03 4.90202588e+03 4.90217725e+03 4.90205713e+03 4.90215088e+03 4.90218115e+03 4.90226416e+03 4.90225635e+03 4.90257227e+03 4.90284473e+03 4.90213574e+03 4.90207275e+03 4.90200146e+03 4.90206836e+03 4.90202148e+03 4.90202002e+03 4.90212109e+03 4.90281592e+03 4.90311230e+03 4.90205518e+03 4.90215723e+03 4.90219678e+03 4.90212842e+03 4.90234033e+03 4.90218164e+03 4.90206787e+03 4.90197559e+03 4.90231592e+03 4.90220166e+03 4.90202930e+03 4.90262793e+03 4.90316846e+03 4.90280908e+03 4.90206396e+03 4.90207227e+03 4.90203809e+03 4.90235498e+03 4.90275977e+03 4.90231787e+03 4.90256250e+03 4.90248975e+03 4.90195215e+03 4.90202783e+03 4.90212256e+03 4.90242432e+03 4.90274707e+03 4.90213135e+03 4.90200537e+03 4.90206592e+03 4.90216699e+03 4.90230029e+03 4.90215771e+03 4.90203174e+03 4.90202930e+03 4.90199072e+03 4.90205762e+03 4.90213818e+03 4.90219336e+03 4.90194678e+03 4.90205371e+03 4.90211523e+03 4.90245654e+03 4.90247852e+03 4.90270703e+03 4.90428223e+03 4.90542285e+03 4.90512402e+03 4.90401514e+03 4.90397119e+03 4.90495020e+03 4.90579492e+03 4.90455371e+03 4.90305518e+03 4.90257471e+03 4.90253662e+03 4.90226074e+03 4.90207568e+03 4.90197754e+03 4.90206885e+03 4.90212744e+03 4.90195850e+03 4.90213281e+03 4.90222119e+03 4.90211230e+03 4.90224658e+03 4.90253027e+03 4.90292188e+03 4.90283154e+03 4.90269287e+03 4.90360693e+03 4.90476221e+03 4.90401172e+03 4.90268262e+03 4.90242969e+03 4.90239990e+03 4.90202002e+03 4.90201953e+03 4.90214355e+03 4.90206592e+03 4.90195752e+03 4.90212646e+03 4.90241064e+03 4.90247803e+03 4.90201611e+03 4.90231396e+03 4.90259668e+03 4.90199854e+03 4.90246729e+03 4.90237061e+03 4.90201562e+03 4.90217676e+03 4.90210156e+03 4.90211572e+03 4.90267773e+03 4.90246387e+03 4.90206396e+03 4.90186621e+03 4.90218896e+03 4.90241357e+03 4.90239844e+03 4.90250830e+03 4.90267383e+03 4.90244629e+03 4.90202490e+03 4.90193115e+03 4.90205127e+03 4.90195312e+03 4.90203613e+03 4.90216846e+03 4.90406787e+03 4.90492285e+03 4903. 4.90205127e+03 4.90319385e+03 4.90199512e+03 4.90282520e+03 4.90270264e+03 4.90210010e+03 4.90463086e+03 4.90375049e+03 4.90198438e+03 4.90237891e+03 4.90226904e+03 4.90208496e+03 4.90196436e+03 4.90202734e+03 4.90244238e+03 4.90253125e+03 4.90200586e+03 4.90200586e+03 4.90229736e+03 4.90255420e+03 4.90258691e+03 4.90209863e+03 4.90228516e+03 4.90241992e+03 4.90205469e+03 4.90310303e+03 4.90294727e+03 4.90216846e+03 4.90418164e+03 4.90356152e+03 4.90211719e+03 4.90262256e+03 4.90223926e+03 4.90204492e+03 4.90252246e+03 4.90271387e+03 4.90194482e+03 4.90198730e+03 4.90187500e+03 4.90201172e+03 4.90235254e+03 4.90198682e+03 4.90204297e+03 4.90266406e+03 4.90252441e+03 4.90235645e+03 4.90199121e+03 4.90294141e+03 4.90356152e+03 4.90248047e+03 4.90261523e+03 4.90414111e+03 4.90269092e+03 4.90230420e+03 4.90306738e+03 4.90218408e+03 4.90406494e+03 4.90402002e+03 4.90206885e+03 4.90236719e+03 4.90223486e+03 4.90213428e+03 4.90206787e+03 4.90208252e+03 4.90229590e+03 4.90304346e+03 4.90294336e+03 4.90364844e+03 4.90364697e+03 4.90258887e+03 4.90202344e+03 4.90214600e+03 4.90200928e+03 4.90281494e+03 4.90235938e+03 4.90216992e+03 4.90316113e+03 4.90272998e+03 4.90204492e+03 4.90225830e+03 4.90210303e+03 4.90251270e+03 4.90246338e+03 4.90206006e+03 4.90236768e+03 4.90334521e+03 4.90232812e+03 4.90254932e+03 4.90204980e+03 4.90218066e+03 4.90221582e+03 4.90233545e+03 4.90303662e+03 4.90234277e+03 4.90200537e+03 4.90217725e+03 4.90207715e+03 4.90224902e+03 4.90369189e+03 4.90276709e+03 4.90195068e+03 4.90247412e+03 4.90245068e+03 4.90198633e+03 4.90202246e+03 4.90211572e+03 4.90204834e+03 4.90200293e+03 4.90222217e+03 4.90280566e+03 4.90371289e+03 4.90336426e+03 4.90212939e+03 4.90212842e+03 4.90204053e+03 4.90201318e+03 4.90221094e+03 4.90284180e+03 4.90325098e+03 4.90230127e+03 4.90253369e+03 4.90321143e+03 4.90210547e+03 4.90243066e+03 4.90239941e+03 4.90219287e+03 4.90380518e+03 4.90331006e+03 4.90203027e+03 4.90344580e+03 4.90464453e+03 4.90279883e+03 4.90189404e+03 4.90205322e+03 4.90224854e+03 4.90269873e+03 4.90208643e+03 4.90210059e+03 4.90199072e+03 4.90197363e+03 4.90205078e+03 4.90197021e+03 4.90213721e+03 4.90214355e+03 4.90218457e+03 4.90367725e+03 4.90319238e+03 4.90188037e+03 4.90318994e+03 4.90266357e+03 4.90213916e+03 4.90302930e+03 4.90285352e+03 4.90199707e+03 4.90269189e+03 4.90367432e+03 4.90220654e+03 4.90195605e+03 4.90216016e+03 4.90204980e+03 4.90209766e+03 4.90218066e+03 4.90212891e+03 4.90280371e+03 4.90333594e+03 4.90334814e+03 4.90257373e+03 4.90204248e+03 4.90223779e+03 4.90204883e+03 4.90275342e+03 4.90334082e+03 4.90230078e+03 4.90199756e+03 4.90203564e+03 4.90224072e+03 4.90344678e+03 4.90365723e+03 4.90214502e+03 4.90209033e+03 4.90229297e+03 4.90211670e+03 4.90258838e+03 4.90237109e+03 4.90202881e+03 4.90229590e+03 4.90236182e+03 4.90234570e+03 4.90204102e+03 4.90222705e+03 4.90229883e+03 4.90196729e+03 4.90313037e+03 4.90390625e+03 4.90243750e+03 4.90201807e+03 4.90241846e+03 4.90204346e+03 4.90214893e+03 4.90264502e+03 4.90237500e+03 4.90196045e+03 4.90194922e+03 4.90225586e+03 4.90272119e+03 4.90281543e+03 4.90203418e+03 4.90207910e+03 4.90198779e+03 4.90207666e+03 4.90316064e+03 4.90306543e+03 4.90308691e+03 4.90244141e+03 4.90210498e+03 4.90202197e+03 4.90200830e+03 4.90215967e+03 4.90270020e+03 4.90252881e+03 4.90202490e+03 4.90214014e+03 4.90194629e+03 4.90237939e+03 4.90309766e+03 4.90226074e+03 4.90266846e+03 4.90399219e+03 4.90276074e+03 4.90233887e+03 4.90287598e+03 4.90297656e+03 4.90668018e+03 4.91188965e+03 4.94366064e+03 4.98269678e+03 6.92415820e+03 1.01584580e+04 1.96719004e+04 1.96713809e+04 1.96750430e+04 1.96852578e+04 1.97091660e+04 1.96769512e+04 2.66204336e+04 4.92400508e+04 -5.65300070e+09 7.13690982e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.84767974e+09 1087012992. -6.27202560e+09 1614841856. 7.12140078e+04 1.52293008e+04 7.09873975e+03 4.95324756e+03 4.90896387e+03 4.90604199e+03 4.90437012e+03 4.90256396e+03 4.90203760e+03 4.90252100e+03 4.90223779e+03 4.90213574e+03 4.90263037e+03 4.90243799e+03 4.90199609e+03 4.90272900e+03 4.90272949e+03 4.90236426e+03 4.90202246e+03 4.90209277e+03 4.90218506e+03 4.90200586e+03 4.90212012e+03 4.90213721e+03 4.90215967e+03 4.90273682e+03 4.90206348e+03 4.90270947e+03 4.90404883e+03 4.90252686e+03 4.90214600e+03 4.90295752e+03 4.90233789e+03 4.90237158e+03 4.90440234e+03 4.90612354e+03 4.90309473e+03 4.90207812e+03 4.90215967e+03 4.90306641e+03 4.90411328e+03 4.90319092e+03 4.90294873e+03 4.90228174e+03 4.90196436e+03 4.90200977e+03 4.90205322e+03 4.90439893e+03 4.90459473e+03 4.90244141e+03 4.90254150e+03 4.90295312e+03 4.90197070e+03 4.90313525e+03 4.90307861e+03 4.90208691e+03 4.90196436e+03 4.90235156e+03 4.90502832e+03 4.90656836e+03 4.90496680e+03 4.90220117e+03 4.90215137e+03 4.90213916e+03 4.90210693e+03 4.90406299e+03 4.90635938e+03 4.90795020e+03 4.90645264e+03 4.90421484e+03 4.90266064e+03 4.90227734e+03 4.90249951e+03 4.90246582e+03 4.90201562e+03 4.90278223e+03 4.90273340e+03 4.90198779e+03 4.90247510e+03 4.90243066e+03 4.90207031e+03 4.90226758e+03 4.90273682e+03 4.90222510e+03 4.90235645e+03 4.90338232e+03 4.90233545e+03 4.90217627e+03 4.90202393e+03 4.90218408e+03 4.90223730e+03 4.90200684e+03 4.90216602e+03 4.90220850e+03 4.90207080e+03 4.90214648e+03 4.90199805e+03 4.90291309e+03 4.90299121e+03 4.90206885e+03 4.90370166e+03 4.90488965e+03 4.90263965e+03 4.90200830e+03 4.90231592e+03 4.90217871e+03 4.90207568e+03 4.90202539e+03 4.90203662e+03 4.90257666e+03 4.90315918e+03 4.90227197e+03 4.90225928e+03 4.90270020e+03 4.90229395e+03 4.90201123e+03 4.90204541e+03 4.90211084e+03 4.90220752e+03 4.90221240e+03 4.90396436e+03 4.90395166e+03 4.90199023e+03 4.90212598e+03 4.90217236e+03 4.90370752e+03 4.90387939e+03 4.90206689e+03 4.90231836e+03 4.90263525e+03 4.90224561e+03 4.90213623e+03 4.90293994e+03 4.90268359e+03 4.90197314e+03 4.90242480e+03 4.90201025e+03 4.90256885e+03 4.90299023e+03 4.90261816e+03 4.90211377e+03 4.90192969e+03 4.90232568e+03 4.90261865e+03 4.90233398e+03 4.90204346e+03 4.90192090e+03 4.90247559e+03 4.90295068e+03 4.90220605e+03 4.90290039e+03 4.90476270e+03 4.90377393e+03 4.90198096e+03 4.90259521e+03 4.90233789e+03 4.90200586e+03 4.90200391e+03 4.90204688e+03 4.90193115e+03 4.90202002e+03 4.90203906e+03 4.90197607e+03 4.90204297e+03 4.90271289e+03 4.90294580e+03 4.90335010e+03 4.90202295e+03 4.90198828e+03 4.90233545e+03 4.90299561e+03 4.90258740e+03 4.90213086e+03 4.90269580e+03 4.90223096e+03 4.90198584e+03 4.90223926e+03 4.90220410e+03 4.90210156e+03 4.90195312e+03 4.90207031e+03 4.90224023e+03 4.90211035e+03 4.90195459e+03 4.90251562e+03 4.90374561e+03 4.90499463e+03 4.90646045e+03 4.90412988e+03 4.90214307e+03 4.90201367e+03 4.90205420e+03 4.90203369e+03 4.90211816e+03 4.90205127e+03 4.90318994e+03 4.90427832e+03 4.90218896e+03 4.90261621e+03 4.90422510e+03 4.90354346e+03 4.90239453e+03 4.90216504e+03 4.90218701e+03 4.90233447e+03 4.90285596e+03 4.90246924e+03 4.90197607e+03 4.90205908e+03 4.90202686e+03 4.90221436e+03 4.90231982e+03 4.90261035e+03 4.90283691e+03 4.90232617e+03 4.90217090e+03 4.90210986e+03 4.90205029e+03 4.90203076e+03 4.90225732e+03 4.90264648e+03 4.90281055e+03 4.90227100e+03 4.90200879e+03 4.90233105e+03 4.90262549e+03 4.90212109e+03 4.90213525e+03 4.90235010e+03 4.90199072e+03 4.90214355e+03 4.90204980e+03 4.90209912e+03 4.90204150e+03 4.90206738e+03 4.90205518e+03 4.90188379e+03 4.90202832e+03 4.90209619e+03 4.90194531e+03 4.90201611e+03 4.90225195e+03 4.90205908e+03 4.90219043e+03 4.90208887e+03 4.90202686e+03 4.90195850e+03 4.90204248e+03 4.90195850e+03 4.90201416e+03 4.90208838e+03 4.90209131e+03 4.90212109e+03 4.90189893e+03 4.90193457e+03 4902. 4.90202051e+03 4.90198828e+03 4.90196143e+03 4.90202100e+03 4.90184863e+03 4.90201074e+03 4.90187695e+03 4.90204980e+03 4.90200586e+03 4.90206250e+03 4.90201367e+03 4.90212695e+03 4.90212793e+03 4.90205420e+03 4.90198242e+03 4.90209814e+03 4.90215234e+03 4.90218994e+03 4.90222949e+03 4.90213037e+03 4.90189648e+03 4.90207812e+03 4.90198535e+03 4.90202490e+03 4.90202100e+03 4.90204492e+03 4.90192725e+03 4.90187207e+03 4.90205273e+03 4.90198193e+03 4.90192822e+03 4.90202637e+03 4.90205469e+03 4.90207129e+03 4.90201758e+03 4.90203516e+03 4.90194141e+03 4.90205957e+03 4.90212988e+03 4.90196777e+03 4.90206885e+03 4.90211621e+03 4.90199316e+03 4.90198877e+03 4.90201953e+03 4.90198438e+03 4.90206396e+03 4.90202002e+03 4.90201660e+03 4.90190820e+03 4.90193213e+03 4.90204541e+03 4.90199170e+03 4.90204248e+03 4.90220947e+03 4.90206982e+03 4.90200293e+03 4.90202734e+03 4.90200879e+03 4.90190674e+03 4.90197559e+03 4.90201758e+03 4.90203223e+03 4.90201758e+03 4.90207666e+03 4.90197852e+03 4.90210010e+03 4.90216016e+03 4.90206836e+03 4.90197217e+03 4.90198975e+03 4.90201416e+03 4.90201807e+03 4.90194971e+03 4.90198145e+03 4.90195508e+03 4.90203955e+03 4.90208057e+03 4.90196045e+03 4.90202051e+03 4.90196240e+03 4.90201660e+03 4.90200342e+03 4.90210107e+03 4.90199805e+03 4.90200244e+03 4.90214062e+03 4.90208203e+03 4.90198877e+03 4.90204346e+03 4.90206152e+03 4.90202490e+03 4.90200488e+03 4.90198096e+03 4.90202832e+03 4.90200342e+03 4.90204541e+03 4.90204395e+03 4.90202588e+03 4.90202441e+03 4.90193359e+03 4.90205713e+03 4.90204492e+03 4.90205762e+03 4.90202637e+03 4.90202979e+03 4.90199561e+03 4.90202490e+03 4.90198242e+03 4.90199951e+03 4.90219482e+03 4.90251416e+03 4.90240234e+03 4.90206006e+03 4.90192822e+03 4.90200391e+03 4.90217920e+03 4.90223486e+03 4.90208789e+03 4.90199219e+03 4.90204199e+03 4.90212305e+03 4.90217139e+03 4.90211377e+03 4.90202930e+03 4.90209717e+03 4.90237061e+03 4.90267383e+03 4.90233252e+03 4.90196387e+03 4.90194043e+03 4.90193799e+03 4.90201758e+03 4.90200928e+03 4.90205273e+03 4.90197510e+03 4.90209619e+03 4.90216699e+03 4.90220264e+03 4.90201660e+03 4.90199561e+03 4.90189014e+03 4.90196289e+03 4.90198975e+03 4.90194873e+03 4.90225098e+03 4.90238574e+03 4.90205469e+03 4.90199609e+03 4.90197266e+03 4.90201318e+03 4.90208740e+03 4.90216113e+03 4.90199463e+03 4.90231201e+03 4.90247900e+03 4.90208789e+03 4.90205176e+03 4.90201709e+03 4.90198584e+03 4.90199561e+03 4.90213623e+03 4.90214062e+03 4.90199268e+03 4.90216846e+03 4.90203369e+03 4.90206152e+03 4.90190918e+03 4.90224463e+03 4.90233105e+03 4.90208105e+03 4.90207617e+03 4.90221631e+03 4.90245312e+03 4.90242529e+03 4.90206836e+03 4.90199316e+03 4.90191455e+03 4.90193652e+03 4.90199463e+03 4.90191602e+03 4.90201123e+03 4.90214941e+03 4.90210596e+03 4.90204688e+03 4.90427197e+03 4.90726660e+03 4.90726367e+03 4.90325391e+03 4.90257910e+03 6.38842188e+03 9.58180176e+03 1.96706523e+04 1.96702207e+04 1.96712305e+04 1.96717012e+04 1.96743320e+04 1.96838574e+04 1.96765000e+04 1.97017148e+04 1.97548242e+04 3.00960840e+04 6.24148438e+04 -4.59006208e+09 5.38010163e+09 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. 0. 0. 0. 0. 0. 0. -2.93439411e+09 2.41809920e+09 -989288192. -863531776. -1.75289119e+10 6.84192969e+04 1.46154277e+04 6.90542822e+03 4.92515771e+03 4.90386768e+03 4.90217627e+03 4.90229541e+03 4.90219385e+03 4.90233398e+03 4.90227441e+03 4.90230811e+03 4.90246045e+03 4.90247705e+03 4.90252393e+03 4.90215332e+03 4.90207861e+03 4.90208057e+03 4.90240430e+03 4.90236670e+03 4.90209863e+03 4.90192285e+03 4.90199219e+03 4.90198340e+03 4.90201904e+03 4.90197070e+03 4.90204688e+03 4.90215527e+03 4.90226025e+03 4.90213965e+03 4.90224951e+03 4.90219043e+03 4.90214990e+03 4.90224609e+03 4.90223486e+03 4.90228613e+03 4.90216211e+03 4.90207520e+03 4.90211426e+03 4.90215430e+03 4.90224805e+03 4.90225439e+03 4.90230029e+03 4.90215137e+03 4.90197705e+03 4.90208350e+03 4.90209326e+03 4.90202881e+03 4.90201611e+03 4.90206445e+03 4.90210791e+03 4.90203125e+03 4.90196094e+03 4.90194189e+03 4.90198682e+03 4.90207764e+03 4.90213818e+03 4.90221338e+03 4.90213477e+03 4.90207666e+03 4.90194824e+03 4.90198145e+03 4.90204248e+03 4.90205664e+03 4.90203076e+03 4.90199121e+03 4.90197168e+03 4.90196924e+03 4.90206592e+03 4.90221289e+03 4.90211768e+03 4.90202539e+03 4.90198291e+03 4.90197949e+03 4.90196875e+03 4.90227344e+03 4.90226660e+03 4.90210840e+03 4.90193994e+03 4.90228369e+03 4.90295898e+03 4.90313232e+03 4.90243457e+03 4.90221973e+03 4.90226025e+03 4.90228076e+03 4.90217822e+03 4.90210840e+03 4.90249072e+03 4.90284424e+03 4.90266260e+03 4.90210449e+03 4.90196240e+03 4.90206641e+03 4.90195020e+03 4.90206689e+03 4.90205029e+03 4.90196973e+03 4.90209717e+03 4.90210107e+03 4.90197559e+03 4.90199805e+03 4.90190283e+03 4.90198730e+03 4.90208594e+03 4.90233643e+03 4.90217236e+03 4.90197217e+03 4.90207129e+03 4.90210400e+03 4.90221240e+03 4.90215771e+03 4.90200732e+03 4.90206592e+03 4.90198389e+03 4.90197217e+03 4.90196729e+03 4.90189795e+03 4.90199512e+03 4.90188623e+03 4.90195459e+03 4.90195264e+03 4.90202686e+03 4.90199414e+03 4.90213379e+03 4.90252197e+03 4.90246631e+03 4.90200928e+03 4.90194824e+03 4.90214160e+03 4.90249414e+03 4.90240186e+03 4.90217236e+03 4.90198438e+03 4.90212549e+03 4.90214209e+03 4.90193604e+03 4.90196777e+03 4.90190820e+03 4.90190332e+03 4.90198975e+03 4.90196436e+03 4.90205518e+03 4.90189014e+03 4.90191455e+03 4.90207959e+03 4.90200781e+03 4.90208496e+03 4.90199805e+03 4.90220166e+03 4.90286426e+03 4.90288428e+03 4.90250879e+03 4.90218359e+03 4.90238721e+03 4.90284521e+03 4.90269287e+03 4.90209033e+03 4.90188477e+03 4.90198486e+03 4.90199219e+03 4.90197510e+03 4.90209619e+03 4.90203076e+03 4.90203467e+03 4.90201318e+03 4.90195459e+03 4.90213916e+03 4.90230664e+03 4.90233691e+03 4.90203418e+03 4.90198535e+03 4.90199951e+03 4.90195605e+03 4.90202051e+03 4.90225049e+03 4.90217871e+03 4.90213965e+03 4.90202588e+03 4.90207568e+03 4.90190283e+03 4.90204248e+03 4.90252002e+03 4.90252686e+03 4.90225732e+03 4.90186572e+03 4.90199561e+03 4.90205078e+03 4.90203467e+03 4.90190479e+03 4.90194434e+03 4.90198291e+03 4.90242871e+03 4.90284180e+03 4.90277979e+03 4.90216406e+03 4.90192969e+03 4.90214795e+03 4.90196777e+03 4.90233203e+03 4.90259863e+03 4.90270654e+03 4.90218750e+03 4.90203564e+03 4.90206201e+03 4.90204590e+03 4.90192578e+03 4.90201904e+03 4.90189844e+03 4.90189062e+03 4.90195215e+03 4.90193555e+03 4.90182764e+03 4.90203076e+03 4.90189209e+03 4.90211084e+03 4.90218262e+03 4.90224219e+03 4.90215674e+03 4.90205762e+03 4.90210498e+03 4.90214062e+03 4.90222266e+03 4.90204883e+03 4.90204150e+03 4.90200635e+03 4.90210449e+03 4.90199609e+03 4.90196045e+03 4.90220508e+03 4.90214990e+03 4.90217773e+03 4.90208740e+03 4.90216455e+03 4.90198340e+03 4.90198926e+03 4.90206885e+03 4.90200488e+03 4.90208154e+03 4.90193311e+03 4.90204736e+03 4.90213623e+03 4.90211133e+03 4.90200195e+03 4.90231396e+03 4.90216602e+03 4.90201611e+03 4.90213232e+03 4.90207227e+03 4.90211230e+03 4.90219580e+03 4.90215625e+03 4.90212549e+03 4.90191113e+03 4.90201221e+03 4.90193750e+03 4.90202539e+03 4.90201953e+03 4.90199268e+03 4.90199756e+03 4.90207373e+03 4.90204736e+03 4.90196924e+03 4.90194531e+03 4.90198828e+03 4.90201953e+03 4.90200830e+03 4.90212061e+03 4.90240576e+03 4.90232373e+03 4.90213721e+03 4.90191260e+03 4.90187939e+03 4.90196143e+03 4.90204102e+03 4.90221729e+03 4.90235693e+03 4.90240674e+03 4.90212402e+03 4902. 4.90200146e+03 4.90200439e+03 4.90199121e+03 4.90203076e+03 4.90202734e+03 4.90197412e+03 4.90200488e+03 4.90196826e+03 4.90196973e+03 4.90202197e+03 4.90209229e+03 4.90203223e+03 4.90237207e+03 4.90272314e+03 4.90246289e+03 4.90209326e+03 4.90192529e+03 4.90199561e+03 4.90209473e+03 4.90207568e+03 4.90198389e+03 4.90218213e+03 4.90244922e+03 4.90241748e+03 4.90207959e+03 4.90198877e+03 4.90202051e+03 4.90200537e+03 4.90205908e+03 4.90201465e+03 4.90199316e+03 4.90201221e+03 4.90198340e+03 4.90196045e+03 4.90198584e+03 4.90204395e+03 4.90198730e+03 4.90197998e+03 4.90205469e+03 4.90198193e+03 4.90207666e+03 4.90211719e+03 4.90225000e+03 4.90262012e+03 4.90317969e+03 4.90329541e+03 4.90286621e+03 4.90290381e+03 4.90238623e+03 4.90236768e+03 4.90210645e+03 4.90197852e+03 4.90217578e+03 4.90226416e+03 4.90209473e+03 4.90199414e+03 4.90204053e+03 4.90204102e+03 4.90203174e+03 4.90199756e+03 4.90210107e+03 4.90200488e+03 4.90212109e+03 4.90233057e+03 4.90226074e+03 4.90196387e+03 4.90204346e+03 4.90196191e+03 4.90196875e+03 4.90201758e+03 4.90196680e+03 4.90198730e+03 4.90207373e+03 4.90213965e+03 4.90250000e+03 4.90219287e+03 4.90200098e+03 4.90194824e+03 4.90222461e+03 4.90232812e+03 4.90215381e+03 4.90203955e+03 4.90203174e+03 4.90219141e+03 4.90239990e+03 4.90213477e+03 4.90200342e+03 4.90223779e+03 4.90262793e+03 4.90258008e+03 4.90203711e+03 4.90194775e+03 4.90197607e+03 4.90215381e+03 4.90196240e+03 4.90209814e+03 4.90201611e+03 4.90220459e+03 4.90247363e+03 4.90226123e+03 4.90221680e+03 4.90216846e+03 4.90248486e+03 4.90294336e+03 4.90264453e+03 4.90205859e+03 4.90193457e+03 4.90204248e+03 4.90204834e+03 4.90194043e+03 4.90194873e+03 4.90191943e+03 4.90201514e+03 4.90206250e+03 4.90201709e+03 4.90195898e+03 4.90197900e+03 4.90200781e+03 4.90219336e+03 4.90229150e+03 4.90209375e+03 4.90203613e+03 4.90192529e+03 4.90200586e+03 4.90203955e+03 4.90202686e+03 4.90203516e+03 4.90199902e+03 4.90213965e+03 4.90264453e+03 4.90218750e+03 4.90209277e+03 4.90219092e+03 4.90205957e+03 4.90220459e+03 4.90199756e+03 4.90200244e+03 4.90206445e+03 4.90209961e+03 4.90206250e+03 4.90199023e+03 4.90202344e+03 4.90208740e+03 4.90217725e+03 4.90203955e+03 4.90202588e+03 4.90192627e+03 4.90197705e+03 4.90209912e+03 4.90230371e+03 4.90229150e+03 4.90202637e+03 4.90209277e+03 4.90285303e+03 4.90363232e+03 4.90308936e+03 4.90226367e+03 4.90221777e+03 4.90245654e+03 4.90213916e+03 4.90206934e+03 4.90221143e+03 4.90198828e+03 4.90206396e+03 4.90199414e+03 4.90198975e+03 4.90200684e+03 4.90197510e+03 4.90200928e+03 4.90202051e+03 4.90194678e+03 4.90191699e+03 4902. 4.90197900e+03 4.90195557e+03 4.90208350e+03 4.90204443e+03 4.90212158e+03 4.90223096e+03 4.90227295e+03 4.90210303e+03 4.90193652e+03 4.90203760e+03 4.90230127e+03 4.90247607e+03 4.90236426e+03 4.90248389e+03 4.90365283e+03 4.90471289e+03 4.90381885e+03 4.90244238e+03 4.90220801e+03 4.90227002e+03 4.90233545e+03 4.90207568e+03 4.90194189e+03 4.90191650e+03 4.90196631e+03 4.90195410e+03 4.90201465e+03 4.90199219e+03 4.90197705e+03 4.90207422e+03 4.90215137e+03 4.90237646e+03 4.90211865e+03 4.90201074e+03 4.90216162e+03 4.90238818e+03 4.90207520e+03 4.90204785e+03 4.90236621e+03 4.90237793e+03 4.90229785e+03 4.90212646e+03 4.90212207e+03 4.90210400e+03 4.90209180e+03 4.90198096e+03 4.90195312e+03 4.90203662e+03 4.90204932e+03 4.90195703e+03 4.90219873e+03 4.90288916e+03 4.90318018e+03 4.90280225e+03 4.90249219e+03 4.90215625e+03 4.90205225e+03 4.90204785e+03 4.90198975e+03 4.90198047e+03 4.90198242e+03 4.90202393e+03 4.90197705e+03 4.90198975e+03 4.90200977e+03 4.90203418e+03 4.90196094e+03 4.90193701e+03 4.90214160e+03 4.90255957e+03 4.90272314e+03 4.90219336e+03 4.90199414e+03 4.90206738e+03 4.90204492e+03 4.90204932e+03 4.90200830e+03 4.90208691e+03 4.90204346e+03 4.90218066e+03 4.90263623e+03 4.90237891e+03 4.90201221e+03 4.90201123e+03 4.90270752e+03 4.90359082e+03 4.90288623e+03 4.90209961e+03 4.90215137e+03 4.90227783e+03 4.90225537e+03 4.90216553e+03 4.90200928e+03 4.90212402e+03 4.90230908e+03 4.90282324e+03 4.90291162e+03 4.90229541e+03 4.90214648e+03 4.90220459e+03 4.90324951e+03 4.90393262e+03 4.90295459e+03 4.90215527e+03 4.90221973e+03 4.90279492e+03 4.90292920e+03 4.90250586e+03 4.90204834e+03 4.90227930e+03 4.90270947e+03 4.90290283e+03 4.90255713e+03 4.90215967e+03 4.90196924e+03 4.90235400e+03 4.90297070e+03 4.90312451e+03 4.90255908e+03 4.90211475e+03 4.90236377e+03 4.90269824e+03 4.90266699e+03 4.90224463e+03 4.90232666e+03 4.90282959e+03 4.90280859e+03 4.90213281e+03 4.90198438e+03 4.90193457e+03 4.90190576e+03 4.90206152e+03 4.90243506e+03 4.90255566e+03 4.90240137e+03 4.90209912e+03 4.90381055e+03 4.91267139e+03 4.91537695e+03 4.93656787e+03 6.63923486e+03 9.99938672e+03 1.96709785e+04 1.96705898e+04 1.96699355e+04 1.96695938e+04 1.96715176e+04 1.96710879e+04 1.96748574e+04 1.96812891e+04 1.96947520e+04 1.97232754e+04 1.97247559e+04 2.88736465e+04 1.21140453e+05 -1515792384. 0. 0. 0. 0. 0. 0. 0. -1701739392. 1.48386120e+10 -871242112. 5.65047891e+04 5.90364570e+04 3.02046152e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.30416384e+09 2.45269350e+09 5.51156797e+04 1.25684668e+04 6.35823242e+03 4.92961865e+03 4.92293994e+03 4.93373975e+03 4.93967236e+03 4.92269531e+03 4.92047510e+03 4.92131006e+03 4.92127295e+03 4.92057568e+03 4.92047998e+03 4.92052246e+03 4.92053516e+03 4.92093115e+03 4.92202686e+03 4.92094287e+03 4.92096094e+03 4.92226318e+03 4.92143066e+03 4.92055127e+03 4.92069531e+03 4.92065039e+03 4.92046826e+03 4.92067578e+03 4.92112354e+03 4.92078418e+03 4.92076367e+03 4.92090674e+03 4.92067578e+03 4.92059375e+03 4.92081543e+03 4.92053516e+03 4.92102979e+03 4.92175879e+03 4.92125977e+03 4.92119238e+03 4.92196143e+03 4.92156348e+03 4.92059033e+03 4.92093213e+03 4.92054932e+03 4.92247852e+03 4.92396143e+03 4.92186963e+03 4.92075732e+03 4.92056738e+03 4.92053564e+03 4.92047363e+03 4.92048828e+03 4.92049414e+03 4.92053955e+03 4.92142480e+03 4.92378809e+03 4.92289453e+03 4.92085156e+03 4.92055322e+03 4.92063135e+03 4.92134961e+03 4.92200684e+03 4.92106348e+03 4.92087158e+03 4.92109229e+03 4.92078516e+03 4.92065234e+03 4.92144824e+03 4.92108594e+03 4.92071729e+03 4.92122217e+03 4.92079395e+03 4.92082959e+03 4.92075195e+03 4.92069385e+03 4.92056104e+03 4.92065918e+03 4.92086572e+03 4.92059668e+03 4.92135645e+03 4.92224365e+03 4.92155469e+03 4.92053174e+03 4.92095264e+03 4.92069580e+03 4.92057227e+03 4.92052686e+03 4.92070703e+03 4.92070947e+03 4.92066064e+03 4.92082617e+03 4.92056689e+03 4.92152295e+03 4.92159961e+03 4.92061133e+03 4.92092676e+03 4.92091943e+03 4.92066602e+03 4.92062695e+03 4.92056396e+03 4.92069043e+03 4.92179248e+03 4.92282324e+03 4.92114648e+03 4.92085986e+03 4.92179590e+03 4.92108154e+03 4.92064551e+03 4.92125244e+03 4.92203271e+03 4.92187842e+03 4.92161279e+03 4.92160205e+03 4.92125977e+03 4.92052881e+03 4.92085303e+03 4.92054932e+03 4.92172217e+03 4.92301660e+03 4.92165723e+03 4.92068750e+03 4.92106445e+03 4.92064600e+03 4.92069189e+03 4.92085840e+03 4.92070898e+03 4.92130859e+03 4.92310986e+03 4.92287549e+03 4.92090430e+03 4.92061279e+03 4.92062256e+03 4.92087500e+03 4.92132861e+03 4.92137451e+03 4.92112842e+03 4.92068457e+03 4.92054980e+03 4.92102393e+03 4.92148584e+03 4.92088916e+03 4.92063086e+03 4.92065723e+03 4.92062793e+03 4.92065674e+03 4.92054102e+03 4.92061572e+03 4.92051025e+03 4.92092432e+03 4.92127051e+03 4.92077393e+03 4.92063672e+03 4.92067041e+03 4.92098291e+03 4.92059082e+03 4.92130811e+03 4.92261426e+03 4.92103125e+03 4.92077441e+03 4.92098535e+03 4.92059619e+03 4.92059619e+03 4.92064062e+03 4.92066895e+03 4.92106592e+03 4.92193457e+03 4.92223584e+03 4.92153809e+03 4.92064160e+03 4.92054590e+03 4.92059717e+03 4.92091602e+03 4.92066309e+03 4.92058154e+03 4.92048682e+03 4.92159033e+03 4.92146338e+03 4.92083252e+03 4.92063525e+03 4.92109570e+03 4.92349902e+03 4.92508398e+03 4.92321973e+03 4.92100293e+03 4.92050732e+03 4.92051074e+03 4.92052100e+03 4.92064600e+03 4.92061084e+03 4.92079248e+03 4.92249805e+03 4.92181104e+03 4.92087793e+03 4.92073438e+03 4.92130225e+03 4.92100635e+03 4.92051270e+03 4.92111719e+03 4.92125879e+03 4.92145508e+03 4.92202441e+03 4.92141797e+03 4.92048584e+03 4.92081885e+03 4.92058740e+03 4.92145068e+03 4.92302100e+03 4.92158154e+03 4.92066943e+03 4.92109912e+03 4.92051807e+03 4.92075391e+03 4.92057471e+03 4.92069873e+03 4.92055225e+03 4.92075000e+03 4.92103027e+03 4.92052490e+03 4.92140381e+03 4.92174561e+03 4.92094824e+03 4.92053125e+03 4.92055908e+03 4.92067822e+03 4.92061426e+03 4.92055273e+03 4.92060205e+03 4.92099561e+03 4.92110107e+03 4.92115869e+03 4.92059912e+03 4.92047607e+03 4.92048438e+03 4.92061035e+03 4.92058008e+03 4.92071240e+03 4.92056494e+03 4.92090137e+03 4.92141895e+03 4.92084717e+03 4.92064941e+03 4.92192871e+03 4.92172168e+03 4.92054248e+03 4.92113721e+03 4.92139844e+03 4.92075830e+03 4.92056836e+03 4.92078564e+03 4.92068604e+03 4.92056543e+03 4.92053125e+03 4.92069678e+03 4.92090430e+03 4.92051367e+03 4.92129492e+03 4.92110254e+03 4.92069824e+03 4.92062744e+03 4.92065430e+03 4.92130176e+03 4.92061475e+03 4.92052930e+03 4.92071924e+03 4.92045850e+03 4.92071582e+03 4.92101855e+03 4.92136621e+03 4.92060645e+03 4.92050195e+03 4.92050195e+03 4.92063525e+03 4.92081445e+03 4.92076123e+03 4.92088281e+03 4.92132666e+03 4.92163721e+03 4.92067432e+03 4.92055957e+03 4.92050195e+03 4.92079639e+03 4.92069092e+03 4.92058203e+03 4.92060596e+03 4.92065576e+03 4.92063916e+03 4.92063330e+03 4.92058398e+03 4.92065869e+03 4.92083057e+03 4.92090039e+03 4.92067432e+03 4.92060840e+03 4.92078320e+03 4.92102832e+03 4.92080664e+03 4.92080713e+03 4.92098145e+03 4.92074414e+03 4.92064111e+03 4.92058447e+03 4.92053320e+03 4.92101270e+03 4.92184912e+03 4.92125781e+03 4.92055859e+03 4.92066797e+03 4.92043945e+03 4.92066113e+03 4.92073438e+03 4.92054590e+03 4.92048682e+03 4.92057715e+03 4.92088818e+03 4.92102441e+03 4.92112402e+03 4.92051514e+03 4.92053516e+03 4.92073877e+03 4.92119238e+03 4.92064258e+03 4.92049219e+03 4.92051904e+03 4.92084766e+03 4.92106445e+03 4.92067383e+03 4.92065088e+03 4.92138428e+03 4.92189111e+03 4.92123779e+03 4.92059619e+03 4.92059619e+03 4.92078711e+03 4.92114795e+03 4.92070898e+03 4.92063135e+03 4.92048193e+03 4.92049902e+03 4.92081104e+03 4.92107178e+03 4.92122754e+03 4.92069580e+03 4.92065283e+03 4.92088428e+03 4.92150146e+03 4.92097705e+03 4.92049902e+03 4.92061670e+03 4.92062207e+03 4.92059326e+03 4.92104834e+03 4.92096143e+03 4.92055908e+03 4.92062646e+03 4.92064795e+03 4.92119287e+03 4.92061230e+03 4.92059912e+03 4.92070703e+03 4.92113965e+03 4.92133691e+03 4.92082715e+03 4.92078125e+03 4.92092285e+03 4.92057471e+03 4.92111719e+03 4.92066602e+03 4.92074072e+03 4.92137793e+03 4.92064990e+03 4.92044824e+03 4.92052490e+03 4.92068066e+03 4.92097412e+03 4.92169189e+03 4.92345703e+03 4.92302295e+03 4.92139453e+03 4.92095166e+03 4.92137939e+03 4.92227002e+03 4.92085254e+03 4.92054199e+03 4.92056396e+03 4.92049170e+03 4.92063184e+03 4.92079150e+03 4.92245215e+03 4.92342432e+03 4.92143164e+03 4.92069531e+03 4.92100049e+03 4.92071289e+03 4.92249219e+03 4.92273047e+03 4.92101074e+03 4.92047949e+03 4.92070410e+03 4.92191504e+03 4.92304297e+03 4.92209033e+03 4.92054883e+03 4.92062451e+03 4.92062256e+03 4.92152588e+03 4.92356348e+03 4.92317334e+03 4.92232275e+03 4.92072900e+03 4.92087598e+03 4.92153711e+03 4.92069629e+03 4.92138574e+03 4.92331445e+03 4.92179541e+03 4.92057422e+03 4.92054834e+03 4.92179492e+03 4.92488818e+03 4.92354688e+03 4.92099854e+03 4.92055957e+03 4.92057617e+03 4.92064502e+03 4.92148340e+03 4.92260059e+03 4.92122363e+03 4.92077393e+03 4.92055273e+03 4.92072705e+03 4.92121729e+03 4.92068799e+03 4.92055371e+03 4.92120410e+03 4.92121680e+03 4.92075391e+03 4.92053613e+03 4.92177734e+03 4.92244482e+03 4.92111182e+03 4.92097119e+03 4.92216748e+03 4.92099268e+03 4.92092236e+03 4.92259082e+03 4.92175781e+03 4.92083350e+03 4.92073340e+03 4.92135400e+03 4.92180127e+03 4.92181982e+03 4.92081201e+03 4.92059814e+03 4.92077637e+03 4.92078516e+03 4.92056836e+03 4.92050830e+03 4.92115918e+03 4.92109229e+03 4.92068018e+03 4.92050537e+03 4.92054004e+03 4.92054150e+03 4.92119678e+03 4.92080420e+03 4.92043848e+03 4.92056885e+03 4.92056787e+03 4.92162402e+03 4.92159131e+03 4.92073730e+03 4.92087451e+03 4.92084033e+03 4.92057910e+03 4.92121826e+03 4.92196875e+03 4.92069971e+03 4.92050781e+03 4.92051660e+03 4.92056543e+03 4.92061230e+03 4.92063818e+03 4.92048096e+03 4.92044434e+03 4.92076855e+03 4.92069434e+03 4.92053271e+03 4.92126709e+03 4.92183545e+03 4.92093848e+03 4.92073584e+03 4.92262939e+03 4.92241943e+03 4.92060645e+03 4.92150928e+03 4.92242725e+03 4.92074316e+03 4.92089258e+03 4.92111377e+03 4.92059619e+03 4.92093018e+03 4.92078613e+03 4.92052051e+03 4.92077295e+03 4.92084668e+03 4.92073730e+03 4.92052295e+03 4.92099951e+03 4.92087109e+03 4.92057373e+03 4.92122119e+03 4.92169336e+03 4.92072705e+03 4.92079395e+03 4.92062793e+03 4.92074756e+03 4.92112109e+03 4.92081738e+03 4.92052734e+03 4.92045361e+03 4.92061670e+03 4.92055518e+03 4.92066211e+03 4.92055859e+03 4.92047314e+03 4.92063330e+03 4.92050000e+03 4.92071729e+03 4.92131836e+03 4.92175586e+03 4.92103076e+03 4.92066309e+03 4.92070459e+03 4.92083984e+03 4.92051318e+03 4.92061768e+03 4.92081543e+03 4.92048486e+03 4.92132666e+03 4.92103906e+03 4.92067041e+03 4.92083057e+03 4.92101953e+03 4.92060400e+03 4.92043896e+03 4.92062012e+03 4.92065527e+03 4.92141748e+03 4.92254492e+03 4.92216992e+03 4.92091748e+03 4.92096436e+03 4.92138965e+03 4.92321533e+03 4.92351123e+03 4.92265039e+03 4.92128076e+03 4.92062646e+03 4.92083838e+03 4.92061963e+03 4.92084863e+03 4.92123877e+03 4.92055615e+03 4.92066748e+03 4.92073389e+03 4.92070654e+03 4.92153613e+03 4.92118164e+03 4.92054053e+03 4.92104199e+03 4.92111719e+03 4.92064453e+03 4.92112256e+03 4.92143359e+03 4.92128174e+03 4.92097754e+03 4.92062012e+03 4.92057080e+03 4.92062109e+03 4.92059033e+03 4.92061475e+03 4.92054346e+03 4.92123828e+03 4.92207422e+03 4.92079785e+03 4.92061426e+03 4.92116455e+03 4.92064111e+03 4.92085840e+03 4.92111084e+03 4.92066943e+03 4.92088184e+03 4.92100586e+03 4.92063623e+03 4.92052197e+03 4.92067578e+03 4.92074951e+03 4.92087500e+03 4.92083447e+03 4.92066699e+03 4.92074316e+03 4.92056152e+03 4.92067383e+03 4.92097852e+03 4.92194580e+03 4.92166455e+03 4.92082520e+03 4.92034912e+03 4.92042480e+03 4.92051904e+03 4.91989844e+03 4.92116016e+03 4.92169775e+03 4.92132324e+03 4.92246191e+03 4.94626904e+03 6.76206396e+03 1.02709707e+04 1.97091660e+04 1.96769512e+04 2.66204336e+04 4.92400508e+04 -5.65300070e+09 7.13690982e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.93912750e+10 2.30234121e+04 8.13792529e+03 5.06826514e+03 4.98760010e+03 4.93362500e+03 4.92473633e+03 4.92152344e+03 4.92084277e+03 4.92135645e+03 4.92159619e+03 4.92078906e+03 4.92074023e+03 4.92076123e+03 4.92039404e+03 4.92105566e+03 4.92074658e+03 4.92065137e+03 4.92162354e+03 4.92173877e+03 4.92067920e+03 4.92085938e+03 4.92134131e+03 4.92051416e+03 4.92099658e+03 4.92106885e+03 4.92050146e+03 4.92052734e+03 4.92079639e+03 4.92104785e+03 4.92060205e+03 4.92055811e+03 4.92059229e+03 4.92050098e+03 4.92087109e+03 4.92088672e+03 4.92054639e+03 4.92151660e+03 4.92156055e+03 4.92056787e+03 4.92065186e+03 4.92063867e+03 4.92077295e+03 4.92207324e+03 4.92186084e+03 4.92056445e+03 4.92185938e+03 4.92155908e+03 4.92050342e+03 4.92104248e+03 4.92124023e+03 4.92060693e+03 4.92050342e+03 4.92052051e+03 4.92047998e+03 4.92048389e+03 4.92058545e+03 4.92111963e+03 4.92085645e+03 4.92053760e+03 4.92059814e+03 4.92061133e+03 4.92161719e+03 4.92159863e+03 4.92085693e+03 4.92059375e+03 4.92066162e+03 4.92061426e+03 4.92232178e+03 4.92468701e+03 4.92315088e+03 4.92090039e+03 4.92061523e+03 4.92109570e+03 4.92222168e+03 4.92206641e+03 4.92061182e+03 4.92050098e+03 4.92053564e+03 4.92103369e+03 4.92097949e+03 4.92103369e+03 4.92143311e+03 4.92079004e+03 4.92044678e+03 4.92060791e+03 4.92062500e+03 4.92254590e+03 4.92310693e+03 4.92183838e+03 4.92072217e+03 4.92039697e+03 4.92043408e+03 4.92052197e+03 4.92127197e+03 4.92099658e+03 4.92047119e+03 4.92085938e+03 4.92050488e+03 4.92160840e+03 4.92147021e+03 4.92040869e+03 4.92077637e+03 4.92068848e+03 4.92054297e+03 4.92055225e+03 4.92045752e+03 4.92151611e+03 4.92145752e+03 4.92055127e+03 4.92058691e+03 4.92053467e+03 4.92075244e+03 4.92079248e+03 4.92045410e+03 4.92048926e+03 4.92074561e+03 4.92065869e+03 4.92042480e+03 4.92106494e+03 4.92141992e+03 4.92048730e+03 4.92070508e+03 4.92040674e+03 4.92055273e+03 4.92066016e+03 4.92064062e+03 4.92058936e+03 4.92051611e+03 4.92061133e+03 4.92076025e+03 4.92060156e+03 4.92089502e+03 4.92094629e+03 4.92052441e+03 4.92068652e+03 4.92071338e+03 4.92051074e+03 4.92052344e+03 4.92063721e+03 4.92116064e+03 4.92148877e+03 4.92091992e+03 4.92046777e+03 4.92094824e+03 4.92099512e+03 4.92045020e+03 4.92049951e+03 4.92047314e+03 4.92041455e+03 4.92053467e+03 4.92087402e+03 4.92140088e+03 4.92156494e+03 4.92134277e+03 4.92070605e+03 4.92044922e+03 4.92077637e+03 4.92105127e+03 4.92083398e+03 4.92059424e+03 4.92043555e+03 4.92090479e+03 4.92200635e+03 4.92142578e+03 4.92052686e+03 4.92094775e+03 4.92102930e+03 4.92043262e+03 4.92088867e+03 4.92085352e+03 4.92053760e+03 4.92039600e+03 4.92038574e+03 4.92046777e+03 4.92053809e+03 4.92077637e+03 4.92073730e+03 4.92070264e+03 4.92144336e+03 4.92142578e+03 4.92100146e+03 4.92063037e+03 4.92056836e+03 4.92058789e+03 4.92060059e+03 4.92055225e+03 4.92097461e+03 4.92178271e+03 4.92144434e+03 4.92061914e+03 4.92113525e+03 4.92125537e+03 4.92065332e+03 4.92057227e+03 4.92063330e+03 4.92081250e+03 4.92068750e+03 4.92062988e+03 4.92102246e+03 4.92171631e+03 4.92174072e+03 4.92277246e+03 4.92198047e+03 4.92094238e+03 4.92065918e+03 4.92063232e+03 4.92105859e+03 4.92110547e+03 4.92063281e+03 4.92087939e+03 4.92174170e+03 4.92111279e+03 4.92075830e+03 4.92195850e+03 4.92132715e+03 4.92051807e+03 4.92067090e+03 4.92058154e+03 4.92072266e+03 4.92078125e+03 4.92067236e+03 4.92076270e+03 4.92098193e+03 4.92082568e+03 4.92073096e+03 4.92056543e+03 4.92114795e+03 4.92151416e+03 4.92120605e+03 4.92086084e+03 4.92070801e+03 4.92066992e+03 4.92064795e+03 4.92089404e+03 4.92102441e+03 4.92081787e+03 4.92053125e+03 4.92058398e+03 4.92069434e+03 4.92070459e+03 4.92068262e+03 4.92069873e+03 4.92056934e+03 4.92054248e+03 4.92060889e+03 4.92076270e+03 4.92057178e+03 4.92058057e+03 4.92050098e+03 4.92076562e+03 4.92060791e+03 4.92065820e+03 4.92060938e+03 4.92062988e+03 4.92064502e+03 4.92064551e+03 4.92065381e+03 4.92059766e+03 4.92060254e+03 4.92062646e+03 4.92062500e+03 4.92062891e+03 4.92059229e+03 4.92055859e+03 4.92071826e+03 4.92060693e+03 4.92072998e+03 4.92064160e+03 4.92062451e+03 4.92061035e+03 4.92071484e+03 4.92059717e+03 4.92066699e+03 4.92063965e+03 4.92062354e+03 4.92066162e+03 4.92074072e+03 4.92060400e+03 4.92058447e+03 4.92062646e+03 4.92068994e+03 4.92062061e+03 4.92068994e+03 4.92059033e+03 4.92077539e+03 4.92059180e+03 4.92072705e+03 4.92054053e+03 4.92070020e+03 4.92073193e+03 4.92077344e+03 4.92069873e+03 4.92063916e+03 4.92069287e+03 4.92069189e+03 4.92056934e+03 4.92068555e+03 4.92069971e+03 4.92065869e+03 4.92068018e+03 4.92068262e+03 4.92062842e+03 4.92056982e+03 4.92061426e+03 4.92076562e+03 4.92073486e+03 4.92072168e+03 4.92062158e+03 4.92061377e+03 4.92072559e+03 4.92066309e+03 4.92069336e+03 4.92062744e+03 4.92059570e+03 4.92059473e+03 4.92064209e+03 4.92066260e+03 4.92072168e+03 4.92075000e+03 4.92098145e+03 4.92074902e+03 4.92075439e+03 4.92051611e+03 4.92062109e+03 4.92058496e+03 4.92066406e+03 4.92098145e+03 4.92095166e+03 4.92064014e+03 4.92069092e+03 4.92066504e+03 4.92057715e+03 4.92056055e+03 4.92060742e+03 4.92063574e+03 4.92058691e+03 4.92057178e+03 4.92055469e+03 4.92061084e+03 4.92060498e+03 4.92063867e+03 4.92058398e+03 4.92077051e+03 4.92080225e+03 4.92081299e+03 4.92069043e+03 4.92072412e+03 4.92065381e+03 4.92061914e+03 4.92061084e+03 4.92069336e+03 4.92066699e+03 4.92085498e+03 4.92084131e+03 4.92068799e+03 4.92062988e+03 4.92074512e+03 4.92064844e+03 4.92085400e+03 4.92133203e+03 4.92098486e+03 4.92059863e+03 4.92082617e+03 4.92062988e+03 4.92065088e+03 4.92062207e+03 4.92080029e+03 4.92094336e+03 4.92082520e+03 4.92060254e+03 4.92064990e+03 4.92057959e+03 4.92061865e+03 4.92065479e+03 4.92091504e+03 4.92097510e+03 4.92078955e+03 4.92063721e+03 4.92062891e+03 4.92067822e+03 4.92082568e+03 4.92078613e+03 4.92079932e+03 4.92069336e+03 4.92062061e+03 4.92074170e+03 4.92071338e+03 4.92070215e+03 4.92066602e+03 4.92059717e+03 4.92064551e+03 4.92075977e+03 4.92069971e+03 4.92073096e+03 4.92060156e+03 4.92073828e+03 4.92088037e+03 4.92077637e+03 4.92061230e+03 4.92064307e+03 4.92063037e+03 4.92086719e+03 4.92076221e+03 4.92079883e+03 4.92075732e+03 4.92075293e+03 4.92064844e+03 4.92070605e+03 4.92066504e+03 4.92066016e+03 4.92070459e+03 4.92072412e+03 4.92065137e+03 4.92061475e+03 4.92061133e+03 4.92083936e+03 4.92088623e+03 4.92070166e+03 4.92059863e+03 4.92070068e+03 4.92062939e+03 4.92067578e+03 4.92065283e+03 4.92065820e+03 4.92053906e+03 4.92075000e+03 4.92105811e+03 4.92103125e+03 4.92072705e+03 4.92063916e+03 4.92064648e+03 4.92071436e+03 4.92077002e+03 4.92057520e+03 4.92068945e+03 4.92087012e+03 4.92149219e+03 4.92151660e+03 4.92083203e+03 4.92057178e+03 4.92068066e+03 4.92061035e+03 4.92128418e+03 4.92329785e+03 4.92449512e+03 4.93068945e+03 4.92615723e+03 4.93476562e+03 6.54900586e+03 6.14553662e+03 8.77826367e+03 1.03443857e+04 1.96743320e+04 1.96838574e+04 1.96765000e+04 1.97017148e+04 1.97548242e+04 3.00960840e+04 6.24148438e+04 -4.59006208e+09 5.38010163e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. -831493696. 3.63582669e+09 -1933689984. 1.75733145e+04 7.95559717e+03 5.00538184e+03 4.93371631e+03 4.92253223e+03 4.92127930e+03 4.92157373e+03 4.92158252e+03 4.92107275e+03 4.92072900e+03 4.92070312e+03 4.92073633e+03 4.92075635e+03 4.92074121e+03 4.92085596e+03 4.92119141e+03 4.92075293e+03 4.92060742e+03 4.92064697e+03 4.92068750e+03 4.92086328e+03 4.92074609e+03 4.92062109e+03 4.92059766e+03 4.92073828e+03 4.92096289e+03 4.92100146e+03 4.92104004e+03 4.92082959e+03 4.92077344e+03 4.92075830e+03 4.92074561e+03 4.92071045e+03 4.92081641e+03 4.92087012e+03 4.92067676e+03 4.92064014e+03 4.92066309e+03 4.92070166e+03 4.92068018e+03 4.92076123e+03 4.92081543e+03 4.92088477e+03 4.92110352e+03 4.92106104e+03 4.92097412e+03 4.92070654e+03 4.92072705e+03 4.92078369e+03 4.92079199e+03 4.92081006e+03 4.92070898e+03 4.92079199e+03 4.92082520e+03 4.92086182e+03 4.92082324e+03 4.92064111e+03 4.92089600e+03 4.92091357e+03 4.92074463e+03 4.92052881e+03 4.92067139e+03 4.92070605e+03 4.92078320e+03 4.92069092e+03 4.92058887e+03 4.92082031e+03 4.92077539e+03 4.92074609e+03 4.92088428e+03 4.92134131e+03 4.92093945e+03 4.92058936e+03 4.92077393e+03 4.92054395e+03 4.92072754e+03 4.92056055e+03 4.92063428e+03 4.92064014e+03 4.92068359e+03 4.92066064e+03 4.92069971e+03 4.92062842e+03 4.92059814e+03 4.92064941e+03 4.92058691e+03 4.92070020e+03 4.92080859e+03 4.92124121e+03 4.92109912e+03 4.92076221e+03 4.92069336e+03 4.92059619e+03 4.92069141e+03 4.92079395e+03 4.92098438e+03 4.92074072e+03 4.92071387e+03 4.92069824e+03 4.92063232e+03 4.92085205e+03 4.92080908e+03 4.92075244e+03 4.92057080e+03 4.92071143e+03 4.92058057e+03 4.92068164e+03 4.92068311e+03 4.92063037e+03 4.92059033e+03 4.92055664e+03 4.92063477e+03 4.92065332e+03 4.92083105e+03 4.92074609e+03 4.92068359e+03 4.92068506e+03 4.92069287e+03 4.92066797e+03 4.92066455e+03 4.92070996e+03 4.92075146e+03 4.92080127e+03 4.92068750e+03 4.92093262e+03 4.92099951e+03 4.92068359e+03 4.92069385e+03 4.92075049e+03 4.92083789e+03 4.92084717e+03 4.92080469e+03 4.92071387e+03 4.92081836e+03 4.92062939e+03 4.92067383e+03 4.92071289e+03 4.92064697e+03 4.92069043e+03 4.92067334e+03 4.92066895e+03 4.92072607e+03 4.92065674e+03 4.92077246e+03 4.92063379e+03 4.92073730e+03 4.92066455e+03 4.92069824e+03 4.92064014e+03 4.92056201e+03 4.92070752e+03 4.92064795e+03 4.92063867e+03 4.92061084e+03 4.92066504e+03 4.92079346e+03 4.92070264e+03 4.92083691e+03 4.92120459e+03 4.92121387e+03 4.92095752e+03 4.92076611e+03 4.92067627e+03 4.92071045e+03 4.92061816e+03 4.92066309e+03 4.92064648e+03 4.92061719e+03 4.92069336e+03 4.92064893e+03 4.92075000e+03 4.92069922e+03 4.92104590e+03 4.92153467e+03 4.92139551e+03 4.92092773e+03 4.92069141e+03 4.92070752e+03 4.92069141e+03 4.92059326e+03 4.92062598e+03 4.92070068e+03 4.92068994e+03 4.92066650e+03 4.92069287e+03 4.92066699e+03 4.92076953e+03 4.92065576e+03 4.92073291e+03 4.92059326e+03 4.92063818e+03 4.92061084e+03 4.92061865e+03 4.92078125e+03 4.92062598e+03 4.92064697e+03 4.92067236e+03 4.92106934e+03 4.92134229e+03 4.92137549e+03 4.92122119e+03 4.92142334e+03 4.92097656e+03 4.92061523e+03 4.92061279e+03 4.92069385e+03 4.92071045e+03 4.92063965e+03 4.92073828e+03 4.92060059e+03 4.92079150e+03 4.92075098e+03 4.92074805e+03 4.92069531e+03 4.92055322e+03 4.92064893e+03 4.92072266e+03 4.92127100e+03 4.92111621e+03 4.92068018e+03 4.92056836e+03 4.92066064e+03 4.92075000e+03 4.92116553e+03 4.92146582e+03 4.92128369e+03 4.92090137e+03 4.92067969e+03 4.92065527e+03 4.92064795e+03 4.92077393e+03 4.92080664e+03 4.92077832e+03 4.92072266e+03 4.92073291e+03 4.92086328e+03 4.92076367e+03 4.92071875e+03 4.92069971e+03 4.92089551e+03 4.92120801e+03 4.92190332e+03 4.92205957e+03 4.92102344e+03 4.92069629e+03 4.92097363e+03 4.92077588e+03 4.92062598e+03 4.92065186e+03 4.92063965e+03 4.92068750e+03 4.92065234e+03 4.92067334e+03 4.92064258e+03 4.92067480e+03 4.92065576e+03 4.92075928e+03 4.92078223e+03 4.92109766e+03 4.92106543e+03 4.92080713e+03 4.92060840e+03 4.92057666e+03 4.92065869e+03 4.92060352e+03 4.92061133e+03 4.92063818e+03 4.92071924e+03 4.92072754e+03 4.92068750e+03 4.92068555e+03 4.92064209e+03 4.92071631e+03 4.92061426e+03 4.92066162e+03 4.92071582e+03 4.92074365e+03 4.92068994e+03 4.92060449e+03 4.92063623e+03 4.92070166e+03 4.92072998e+03 4.92071533e+03 4.92094336e+03 4.92071582e+03 4.92061377e+03 4.92075049e+03 4.92072070e+03 4.92070557e+03 4.92059570e+03 4.92061963e+03 4.92052344e+03 4.92068018e+03 4.92078174e+03 4.92083154e+03 4.92081592e+03 4.92061914e+03 4.92073828e+03 4.92064355e+03 4.92065674e+03 4.92073096e+03 4.92107275e+03 4.92111914e+03 4.92088916e+03 4.92066748e+03 4.92075977e+03 4.92072461e+03 4.92073047e+03 4.92062207e+03 4.92064893e+03 4.92065723e+03 4.92077832e+03 4.92067041e+03 4.92072412e+03 4.92069434e+03 4.92075830e+03 4.92071924e+03 4.92065918e+03 4.92062744e+03 4.92078369e+03 4.92075439e+03 4.92068701e+03 4.92064551e+03 4.92068359e+03 4.92065430e+03 4.92070361e+03 4.92069629e+03 4.92078027e+03 4.92111230e+03 4.92110156e+03 4.92073779e+03 4.92060742e+03 4.92067236e+03 4.92069580e+03 4.92061768e+03 4.92073291e+03 4.92072021e+03 4.92101221e+03 4.92123096e+03 4.92094531e+03 4.92071826e+03 4.92062549e+03 4.92068896e+03 4.92065186e+03 4.92065625e+03 4.92070459e+03 4.92074023e+03 4.92066309e+03 4.92074023e+03 4.92065430e+03 4.92064600e+03 4.92070166e+03 4.92097266e+03 4.92172852e+03 4.92180029e+03 4.92113379e+03 4.92073633e+03 4.92074854e+03 4.92075293e+03 4.92068115e+03 4.92060986e+03 4.92093652e+03 4.92148975e+03 4.92240186e+03 4.92240674e+03 4.92173682e+03 4.92104541e+03 4.92066016e+03 4.92090088e+03 4.92121777e+03 4.92084668e+03 4.92077295e+03 4.92096240e+03 4.92064844e+03 4.92060645e+03 4.92069189e+03 4.92072656e+03 4.92062939e+03 4.92067041e+03 4.92066309e+03 4.92077637e+03 4.92078467e+03 4.92073242e+03 4.92078418e+03 4.92084912e+03 4.92086182e+03 4.92076807e+03 4.92074854e+03 4.92069678e+03 4.92077100e+03 4.92077148e+03 4.92065186e+03 4.92089648e+03 4.92078076e+03 4.92089844e+03 4.92080225e+03 4.92108105e+03 4.92125342e+03 4.92068359e+03 4.92112451e+03 4.92085791e+03 4.92079395e+03 4.92068262e+03 4.92105127e+03 4.92105420e+03 4.92093359e+03 4.92071826e+03 4.92069092e+03 4.92072070e+03 4.92063623e+03 4.92064795e+03 4.92075879e+03 4.92084229e+03 4.92063574e+03 4.92072705e+03 4.92129004e+03 4.92102930e+03 4.92075391e+03 4.92096240e+03 4.92145215e+03 4.92166797e+03 4.92112891e+03 4.92071338e+03 4.92076123e+03 4.92079736e+03 4.92101465e+03 4.92080273e+03 4.92090479e+03 4.92123096e+03 4.92133350e+03 4.92121387e+03 4.92070801e+03 4.92060986e+03 4.92074072e+03 4.92065186e+03 4.92060791e+03 4.92069775e+03 4.92161523e+03 4.92144629e+03 4.92068848e+03 4.92093750e+03 4.92081006e+03 4.92070947e+03 4.92068262e+03 4.92095703e+03 4.92103271e+03 4.92084619e+03 4.92067822e+03 4.92070361e+03 4.92070166e+03 4.92065820e+03 4.92073340e+03 4.92072266e+03 4.92072412e+03 4.92070410e+03 4.92088330e+03 4.92074170e+03 4.92070264e+03 4.92072705e+03 4.92075391e+03 4.92067090e+03 4.92071729e+03 4.92117529e+03 4.92081152e+03 4.92071436e+03 4.92120508e+03 4.92065967e+03 4.92065186e+03 4.92079639e+03 4.92086230e+03 4.92086670e+03 4.92065527e+03 4.92071729e+03 4.92071875e+03 4.92079736e+03 4.92081689e+03 4.92092139e+03 4.92089014e+03 4.92090479e+03 4.92084961e+03 4.92073926e+03 4.92066309e+03 4.92070557e+03 4.92076270e+03 4.92087695e+03 4.92084766e+03 4.92068213e+03 4.92067725e+03 4.92068896e+03 4.92114648e+03 4.92111914e+03 4.92085693e+03 4.92072949e+03 4.92159277e+03 4.92238574e+03 4.92179932e+03 4.92103125e+03 4.92123926e+03 4.92197510e+03 4.92207861e+03 4.92126123e+03 4.92091748e+03 4.92086182e+03 4.92084619e+03 4.92079980e+03 4.92091650e+03 4.92087842e+03 4.92076270e+03 4.92087842e+03 4.92121777e+03 4.92161182e+03 4.92129297e+03 4.92086377e+03 4.92092773e+03 4.92116602e+03 4.92095508e+03 4.92064746e+03 4.92066309e+03 4.92056885e+03 4.92059668e+03 4.92061475e+03 4.92067822e+03 4.92056201e+03 4.92063672e+03 4.92058887e+03 4.92063818e+03 4.92063086e+03 4.92063672e+03 4.92077930e+03 4.92075781e+03 4.92061914e+03 4.92062402e+03 4.92064014e+03 4.92071680e+03 4.92081152e+03 4.92100098e+03 4.92064502e+03 4.92078613e+03 4.92078271e+03 4.92083301e+03 4.92105664e+03 4.92151123e+03 4.92151416e+03 4.92089307e+03 4.92068311e+03 4.92063477e+03 4.92065869e+03 4.92070312e+03 4.92111963e+03 4.92116602e+03 4.92081494e+03 4.92074512e+03 4.92064355e+03 4.92065674e+03 4.92062695e+03 4.92067432e+03 4.92079590e+03 4.92097705e+03 4.92074561e+03 4.92066992e+03 4.92085449e+03 4.92069336e+03 4.92069287e+03 4.92146045e+03 4.92232373e+03 4.92189502e+03 4.92092139e+03 4.92070850e+03 4.92082764e+03 4.92095117e+03 4.92064893e+03 4.92073047e+03 4.92060010e+03 4.92070557e+03 4.92060059e+03 4.92062549e+03 4.92074316e+03 4.92072803e+03 4.92088184e+03 4.92070020e+03 4.92073340e+03 4.92078760e+03 4.92088721e+03 4.92070605e+03 4.92057227e+03 4.92070654e+03 4.92069678e+03 4.92070801e+03 4.92065186e+03 4.92081689e+03 4.92080908e+03 4.92062207e+03 4.92126807e+03 4.92605176e+03 4.93256250e+03 4.94236621e+03 4.94195850e+03 4.92065381e+03 4.92313330e+03 4.93507568e+03 4.92034229e+03 4.92346240e+03 4.92296387e+03 4.92269189e+03 6.17373926e+03 1.04202344e+04 1.21140453e+05 -1515792384. 0. 0. 0. 0. -5.34919168e+09 -5.34919168e+09 1.48798433e+10 1781748480. 1.22399047e+05 -871242112. 5.65047891e+04 5.90364570e+04 3.02046152e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.50911519e+10 -2.59433395e+09 4.14223281e+04 2.45511289e+04 9.07632520e+03 8.59017090e+03 6.04364209e+03 6.61961621e+03 4.91718750e+03 4.91777197e+03 4.90904883e+03 4.90913086e+03 4.90933496e+03 4.90901709e+03 4.90889941e+03 4.90907520e+03 4.90955078e+03 4.90921240e+03 4.90898730e+03 4.90917920e+03 4.90886084e+03 4.90987500e+03 4.90988428e+03 4.90901660e+03 4.90948389e+03 4.90981689e+03 4.90915479e+03 4.90930566e+03 4.90991895e+03 4.90987256e+03 4.90917578e+03 4.90894775e+03 4.90934229e+03 4.91155371e+03 4.91222900e+03 4.91005811e+03 4.90895410e+03 4.90888525e+03 4.90892334e+03 4.90899707e+03 4.90944971e+03 4.90985840e+03 4.90904102e+03 4.90982227e+03 4.91195117e+03 4.91076025e+03 4.90903809e+03 4.90899902e+03 4.90894141e+03 4.90888672e+03 4.90900391e+03 4.90896338e+03 4.90911035e+03 4.90941699e+03 4.90905957e+03 4.90900928e+03 4.91077783e+03 4.91037451e+03 4.90893115e+03 4.90960791e+03 4.90915527e+03 4.90898779e+03 4.90887158e+03 4.90903418e+03 4.90907861e+03 4.90891748e+03 4.90970361e+03 4.90929492e+03 4.90905322e+03 4.91032031e+03 4.90965723e+03 4.90900293e+03 4.90882275e+03 4.90893506e+03 4.90887988e+03 4.90893555e+03 4.90950928e+03 4.90926514e+03 4.90896973e+03 4.90907178e+03 4.90961963e+03 4.90993457e+03 4.90947119e+03 4.90906445e+03 4.90892383e+03 4.90895068e+03 4.90886963e+03 4.90885840e+03 4.90890332e+03 4.90919434e+03 4.91073828e+03 4.91166064e+03 4.90975537e+03 4.90893799e+03 4.90974707e+03 4.90920605e+03 4.90901318e+03 4.91041357e+03 4.91147949e+03 4.91094092e+03 4.91044189e+03 4.91079883e+03 4.91004541e+03 4.90889648e+03 4.90901416e+03 4.90885889e+03 4.90901074e+03 4.90927588e+03 4.90899902e+03 4.90891455e+03 4.90901074e+03 4.90887451e+03 4.90907617e+03 4.90903027e+03 4.90896924e+03 4.90929541e+03 4.91092920e+03 4.91135742e+03 4.90961914e+03 4.90883594e+03 4.90879736e+03 4.90936719e+03 4.91023584e+03 4.91033936e+03 4.90942383e+03 4.90889502e+03 4.90891016e+03 4.90890918e+03 4.90891406e+03 4.90892529e+03 4.90896875e+03 4.90890723e+03 4.90965430e+03 4.90960205e+03 4.90895703e+03 4.90886572e+03 4.90897070e+03 4.90918213e+03 4.90937354e+03 4.90902686e+03 4.90925635e+03 4.90993701e+03 4.91029248e+03 4.90923584e+03 4.90940625e+03 4.91060254e+03 4.90949414e+03 4.90886621e+03 4.90899658e+03 4.90887744e+03 4.90898193e+03 4.90890723e+03 4.90896973e+03 4.90922119e+03 4.91011963e+03 4.91078711e+03 4.90950732e+03 4.90899609e+03 4.90977686e+03 4.90904346e+03 4.90894971e+03 4.90889893e+03 4.90884326e+03 4.90893164e+03 4.91005859e+03 4.90996436e+03 4.90887012e+03 4.90911523e+03 4.90891113e+03 4.91035156e+03 4.91212158e+03 4.91073193e+03 4.90911914e+03 4.90885156e+03 4.90888721e+03 4.90885742e+03 4.90896289e+03 4.90888281e+03 4.90927100e+03 4.91098926e+03 4.90984033e+03 4.90884619e+03 4.90909473e+03 4.90902930e+03 4.90888525e+03 4.90899707e+03 4.90937207e+03 4.90941602e+03 4.90982715e+03 4.91072852e+03 4.91007324e+03 4.90887988e+03 4.90900732e+03 4.90893213e+03 4.90935547e+03 4.91035059e+03 4.90998242e+03 4.90891846e+03 4.90885791e+03 4.90882373e+03 4.90886670e+03 4.90954883e+03 4.91015869e+03 4.90914062e+03 4.90905713e+03 4.90923096e+03 4.90890527e+03 4.90906689e+03 4.90959473e+03 4.90944287e+03 4.90903760e+03 4.90888184e+03 4.90891699e+03 4.90890381e+03 4.90914355e+03 4.90889697e+03 4.90900635e+03 4.90921582e+03 4.90913232e+03 4.90889160e+03 4.90888037e+03 4.90887305e+03 4.90893115e+03 4.90895020e+03 4.90889453e+03 4.90887549e+03 4.90929639e+03 4.90966406e+03 4.90977148e+03 4.90891846e+03 4.90904053e+03 4.90886963e+03 4.90937305e+03 4.90978662e+03 4.90898779e+03 4.90890430e+03 4.90891357e+03 4.90890771e+03 4.90897363e+03 4.90888916e+03 4.90884521e+03 4.90894873e+03 4.90909180e+03 4.90891846e+03 4.90893994e+03 4.90901660e+03 4.90908984e+03 4.90891846e+03 4.90889990e+03 4.90891309e+03 4.90888623e+03 4.90897656e+03 4.90903857e+03 4.90912207e+03 4.90925977e+03 4.90953418e+03 4.90972705e+03 4.90891797e+03 4.90886523e+03 4.90891650e+03 4.90905615e+03 4.90891943e+03 4.90892578e+03 4.90904395e+03 4.90968213e+03 4.90985742e+03 4.90893457e+03 4.90895557e+03 4.90897510e+03 4.90900391e+03 4.90926074e+03 4.90916455e+03 4.90885254e+03 4.90894678e+03 4.90906445e+03 4.90886230e+03 4.90879443e+03 4.90942920e+03 4.90987354e+03 4.90957764e+03 4.90890625e+03 4.90891113e+03 4.90887500e+03 4.90929541e+03 4.90971582e+03 4.90925195e+03 4.90958936e+03 4.90943115e+03 4.90899609e+03 4.90895068e+03 4.90885645e+03 4.90939062e+03 4.90981787e+03 4.90922461e+03 4.90889453e+03 4.90885400e+03 4.90907666e+03 4.90909473e+03 4.90896777e+03 4.90888184e+03 4.90886621e+03 4.90885254e+03 4.90904346e+03 4.90923633e+03 4.90930176e+03 4.90893994e+03 4.90887598e+03 4.90904150e+03 4.90941650e+03 4.90928418e+03 4.90933984e+03 4.91054639e+03 4.91176611e+03 4.91168555e+03 4.91077832e+03 4.91085156e+03 4.91177686e+03 4.91263721e+03 4.91164893e+03 4.90988574e+03 4.90926123e+03 4.90923340e+03 4.90924414e+03 4.90911523e+03 4.90888867e+03 4.90897607e+03 4.90902930e+03 4.90886475e+03 4.90891064e+03 4.90914355e+03 4.90907861e+03 4.90916113e+03 4.90942285e+03 4.90992969e+03 4.90978760e+03 4.90969678e+03 4.91044678e+03 4.91157031e+03 4.91088379e+03 4.90957080e+03 4.90937549e+03 4.90928320e+03 4.90894092e+03 4.90895215e+03 4.90906348e+03 4.90893555e+03 4.90892432e+03 4.90896680e+03 4.90920166e+03 4.90921875e+03 4.90899756e+03 4.90927051e+03 4.90947754e+03 4.90883838e+03 4.90940088e+03 4.90932861e+03 4.90892334e+03 4.90900732e+03 4.90885205e+03 4.90897461e+03 4.90943213e+03 4.90945361e+03 4.90900342e+03 4.90888037e+03 4.90923926e+03 4.90920312e+03 4.90920898e+03 4.90931299e+03 4.90930566e+03 4.90935254e+03 4.90885840e+03 4.90884766e+03 4.90891748e+03 4.90892578e+03 4.90891846e+03 4.90908496e+03 4.91121777e+03 4.91171436e+03 4.90980273e+03 4.90905420e+03 4.91014844e+03 4.90901855e+03 4.90936572e+03 4.90947607e+03 4.90898145e+03 4.91147949e+03 4.91070996e+03 4.90897021e+03 4.90924023e+03 4.90913525e+03 4.90891309e+03 4.90896289e+03 4.90898145e+03 4.90933887e+03 4.90944385e+03 4.90888818e+03 4.90894287e+03 4.90920410e+03 4.90964355e+03 4.90946143e+03 4.90898828e+03 4.90910352e+03 4.90920361e+03 4.90886426e+03 4.90974756e+03 4.90987207e+03 4.90908740e+03 4.91101367e+03 4.91036328e+03 4.90885938e+03 4.90927490e+03 4.90916504e+03 4.90899072e+03 4.90937061e+03 4.90939355e+03 4.90888477e+03 4.90889209e+03 4.90888379e+03 4.90900488e+03 4.90926855e+03 4.90890137e+03 4.90887451e+03 4.90963330e+03 4.90949854e+03 4.90901855e+03 4.90887646e+03 4.90999365e+03 4.91059521e+03 4.90939404e+03 4.90921777e+03 4.91059912e+03 4.90937256e+03 4.90923682e+03 4.90994678e+03 4.90876465e+03 4.91062158e+03 4.91066895e+03 4.90885645e+03 4.90919629e+03 4.90906934e+03 4.90894189e+03 4.90888721e+03 4.90885059e+03 4.90943359e+03 4.91001758e+03 4.91008887e+03 4.91055322e+03 4.91054492e+03 4.90940820e+03 4.90892139e+03 4.90913037e+03 4.90893066e+03 4.90947656e+03 4.90911182e+03 4.90902246e+03 4.91028662e+03 4.90959863e+03 4.90895947e+03 4.90918945e+03 4.90883838e+03 4.90933398e+03 4.90922852e+03 4.90885156e+03 4.90920801e+03 4.90996680e+03 4.90911523e+03 4.90934424e+03 4.90896045e+03 4.90902295e+03 4.90905713e+03 4.90937695e+03 4.91014209e+03 4.90947803e+03 4.90894385e+03 4.90897510e+03 4.90885107e+03 4.90914844e+03 4.91042041e+03 4.90951660e+03 4.90887891e+03 4.90940479e+03 4.90933545e+03 4.90882422e+03 4.90884424e+03 4.90888965e+03 4.90895410e+03 4.90896924e+03 4.90925146e+03 4.90995410e+03 4.91101611e+03 4.91050488e+03 4.90906201e+03 4.90889404e+03 4.90899268e+03 4.90885254e+03 4.90906006e+03 4.90975830e+03 4.91027197e+03 4.90904004e+03 4.90945996e+03 4.91019287e+03 4.90905469e+03 4.90930322e+03 4.90928516e+03 4.90897803e+03 4.91063672e+03 4.91028320e+03 4.90892529e+03 4.91038184e+03 4.91149365e+03 4.90958496e+03 4.90895264e+03 4.90902002e+03 4.90931738e+03 4.90970459e+03 4.90902344e+03 4.90901514e+03 4.90893359e+03 4.90892334e+03 4.90889404e+03 4.90900879e+03 4.90913379e+03 4.90904053e+03 4.90902734e+03 4.91055029e+03 4.91004297e+03 4.90902002e+03 4.91033838e+03 4.90943945e+03 4.90896484e+03 4.91011279e+03 4.90999023e+03 4.90893750e+03 4.90945020e+03 4.91031006e+03 4.90904297e+03 4.90885791e+03 4.90897461e+03 4.90891602e+03 4.90890479e+03 4.90897998e+03 4.90893604e+03 4.90959814e+03 4.91021436e+03 4.91028516e+03 4.90953955e+03 4.90884277e+03 4.90903027e+03 4.90880762e+03 4.90957959e+03 4.91018994e+03 4.90925537e+03 4.90895312e+03 4.90885986e+03 4.90902734e+03 4.91044336e+03 4.91071240e+03 4.90921240e+03 4.90893994e+03 4.90922119e+03 4.90882129e+03 4.90927295e+03 4.90922363e+03 4.90890820e+03 4.90913184e+03 4.90927881e+03 4.90914600e+03 4.90888818e+03 4.90907080e+03 4.90909717e+03 4.90891797e+03 4.91002344e+03 4.91073047e+03 4.90929492e+03 4.90881104e+03 4.90923730e+03 4.90889941e+03 4.90909619e+03 4.90955811e+03 4.90923584e+03 4.90887695e+03 4.90885840e+03 4.90913867e+03 4.90963574e+03 4.90962842e+03 4.90892871e+03 4.90893896e+03 4.90893994e+03 4.90901514e+03 4.90996631e+03 4.90979004e+03 4.90984619e+03 4.90926562e+03 4.90888525e+03 4.90887012e+03 4.90889551e+03 4.90903418e+03 4.90952734e+03 4.90919189e+03 4.90887939e+03 4.90911084e+03 4.90892236e+03 4.90921289e+03 4.90983887e+03 4.90895850e+03 4.90956348e+03 4.91080957e+03 4.90939355e+03 4.90903613e+03 4.91019434e+03 4.90922852e+03 4.90873242e+03 4.90928613e+03 4.91044629e+03 4.91256348e+03 4.91261328e+03 4.91158398e+03 6.46693555e+03 1.00604980e+04 3.10548613e+04 6.47092695e+04 -9.06319155e+09 -2.21036646e+09 3.82919091e+09 -3.33437850e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.99497679e+11 -2.04913459e+10 2054114944. 8.75027149e+09 4.96315699e+09 6.07120078e+04 2.96034668e+04 1.06889180e+04 6.84277686e+03 4.95423193e+03 4.91579736e+03 4.91369824e+03 4.91191016e+03 4.90966992e+03 4.90926465e+03 4.90973926e+03 4.90924072e+03 4.90903613e+03 4.90954785e+03 4.90940137e+03 4.90892969e+03 4.90972021e+03 4.90969629e+03 4.90930859e+03 4.90906982e+03 4.90900146e+03 4.90898730e+03 4.90890479e+03 4.90908203e+03 4.90908105e+03 4.90890576e+03 4.90952441e+03 4.90906836e+03 4.90979980e+03 4.91143994e+03 4.90947656e+03 4.90890918e+03 4.90956299e+03 4.90918457e+03 4.90932764e+03 4.91147949e+03 4.91335889e+03 4.91009619e+03 4.90906250e+03 4.90889014e+03 4.90975098e+03 4.91074756e+03 4.90987891e+03 4.90974268e+03 4.90919727e+03 4.90889697e+03 4.90889990e+03 4.90900830e+03 4.91126074e+03 4.91146729e+03 4.90917285e+03 4.90937988e+03 4.90989795e+03 4.90888818e+03 4.90997803e+03 4.90998779e+03 4.90893213e+03 4.90889600e+03 4.90922559e+03 4.91187354e+03 4.91319922e+03 4.91173584e+03 4.90907129e+03 4.90907129e+03 4.90917676e+03 4.90897705e+03 4.91051025e+03 4.91277490e+03 4.91401758e+03 4.91280518e+03 4.91094824e+03 4.90948584e+03 4.90916064e+03 4.90928223e+03 4.90922412e+03 4.90891553e+03 4.90958838e+03 4.90964111e+03 4.90893408e+03 4.90937891e+03 4.90930518e+03 4.90893555e+03 4.90897168e+03 4.90951318e+03 4.90911084e+03 4.90906006e+03 4.90980664e+03 4.90897949e+03 4.90897070e+03 4.90890332e+03 4.90897217e+03 4.90905029e+03 4.90884961e+03 4.90903857e+03 4.90892285e+03 4.90890137e+03 4.90905029e+03 4.90897900e+03 4.90973438e+03 4.90986377e+03 4.90882617e+03 4.91051855e+03 4.91148926e+03 4.90941992e+03 4.90888330e+03 4.90917725e+03 4.90899023e+03 4.90891357e+03 4.90889746e+03 4.90899561e+03 4.90955908e+03 4.91007227e+03 4.90909619e+03 4.90916309e+03 4.90957812e+03 4.90906885e+03 4.90887305e+03 4.90886182e+03 4.90902734e+03 4.90898828e+03 4.90900098e+03 4.91090576e+03 4.91055664e+03 4.90894092e+03 4.90900635e+03 4.90902441e+03 4.91073682e+03 4.91087500e+03 4.90914404e+03 4.90917090e+03 4.90954053e+03 4.90909375e+03 4.90895605e+03 4.90971582e+03 4.90949658e+03 4.90891455e+03 4.90928320e+03 4.90889893e+03 4.90934570e+03 4.90995654e+03 4.90950879e+03 4.90896338e+03 4.90887500e+03 4.90924414e+03 4.90935400e+03 4.90910303e+03 4.90883789e+03 4.90883691e+03 4.90934814e+03 4.90970557e+03 4.90897363e+03 4.90960693e+03 4.91176270e+03 4.91076611e+03 4.90890576e+03 4.90949414e+03 4.90930859e+03 4.90888672e+03 4.90895508e+03 4.90884521e+03 4.90887842e+03 4.90909082e+03 4.90890430e+03 4.90887793e+03 4.90893262e+03 4.90958398e+03 4.90994385e+03 4.91042188e+03 4.90900244e+03 4.90886719e+03 4.90907324e+03 4.90980859e+03 4.90945166e+03 4.90907617e+03 4.90953760e+03 4.90913477e+03 4.90883838e+03 4.90909082e+03 4.90905469e+03 4.90888379e+03 4.90882617e+03 4.90884375e+03 4.90908105e+03 4.90892627e+03 4.90886523e+03 4.90924854e+03 4.91044824e+03 4.91188525e+03 4.91309473e+03 4.91084033e+03 4.90900684e+03 4.90897803e+03 4.90893555e+03 4.90904736e+03 4.90917236e+03 4.90890576e+03 4.91005176e+03 4.91082275e+03 4.90905762e+03 4.90975488e+03 4.91124658e+03 4.91041113e+03 4.90926660e+03 4.90897266e+03 4.90906836e+03 4.90930420e+03 4.90995898e+03 4.90937793e+03 4.90882129e+03 4.90893066e+03 4.90889355e+03 4.90904932e+03 4.90921338e+03 4.90957959e+03 4.90970557e+03 4.90920850e+03 4.90891992e+03 4.90894873e+03 4.90898389e+03 4.90883154e+03 4.90917432e+03 4.90940234e+03 4.90964893e+03 4.90913818e+03 4.90891553e+03 4.90916699e+03 4.90960352e+03 4.90898584e+03 4.90903760e+03 4.90918994e+03 4.90891260e+03 4.90893799e+03 4.90884961e+03 4.90884131e+03 4.90889648e+03 4.90883643e+03 4.90888281e+03 4.90886426e+03 4.90881494e+03 4.90885303e+03 4.90884131e+03 4.90888135e+03 4.90913330e+03 4.90903320e+03 4.90893701e+03 4.90884082e+03 4.90893115e+03 4.90888428e+03 4.90884668e+03 4.90887793e+03 4.90892822e+03 4.90897949e+03 4.90904150e+03 4.90898926e+03 4.90890527e+03 4.90892139e+03 4.90888525e+03 4.90888916e+03 4.90895752e+03 4.90889258e+03 4.90889600e+03 4.90883057e+03 4.90888330e+03 4.90886475e+03 4.90883154e+03 4.90886768e+03 4.90894092e+03 4.90896582e+03 4.90901709e+03 4.90904688e+03 4.90902246e+03 4.90900439e+03 4.90887500e+03 4.90896387e+03 4.90894336e+03 4.90887256e+03 4.90892139e+03 4.90890283e+03 4.90886670e+03 4.90886670e+03 4.90880322e+03 4.90890234e+03 4.90888721e+03 4.90886768e+03 4.90884961e+03 4.90889746e+03 4.90889453e+03 4.90889746e+03 4.90886865e+03 4.90888965e+03 4.90892822e+03 4.90888135e+03 4.90891650e+03 4.90887109e+03 4.90887891e+03 4.90890234e+03 4.90889453e+03 4.90892871e+03 4.90885449e+03 4.90883301e+03 4.90882568e+03 4.90894873e+03 4.90889746e+03 4.90890479e+03 4.90893262e+03 4.90895020e+03 4.90885010e+03 4.90888965e+03 4.90882373e+03 4.90888428e+03 4.90884180e+03 4.90906641e+03 4.90912988e+03 4.90896143e+03 4.90886182e+03 4.90891602e+03 4.90886279e+03 4.90884619e+03 4.90890869e+03 4.90889502e+03 4.90892529e+03 4.90889795e+03 4.90887500e+03 4.90887891e+03 4.90897705e+03 4.90885156e+03 4.90893359e+03 4.90887549e+03 4.90889258e+03 4.90891846e+03 4.90892822e+03 4.90889844e+03 4.90890869e+03 4.90894531e+03 4.90898340e+03 4.90893799e+03 4.90889697e+03 4.90885498e+03 4.90886523e+03 4.90884619e+03 4.90896680e+03 4.90888818e+03 4.90887891e+03 4.90891748e+03 4.90890723e+03 4.90882910e+03 4.90894678e+03 4.90890527e+03 4.90893848e+03 4.90888379e+03 4.90890674e+03 4.90896289e+03 4.90898096e+03 4.90901367e+03 4.90900293e+03 4.90898242e+03 4.90890723e+03 4.90892041e+03 4.90890234e+03 4.90893262e+03 4.90884814e+03 4.90887744e+03 4.90890381e+03 4.90895605e+03 4.90892969e+03 4.90893164e+03 4.90887939e+03 4.90900439e+03 4.90931494e+03 4.90927783e+03 4.90890674e+03 4.90886377e+03 4.90883008e+03 4.90900049e+03 4.90907080e+03 4909. 4.90887842e+03 4.90892041e+03 4.90900146e+03 4.90906348e+03 4.90902148e+03 4.90900537e+03 4.90909375e+03 4.90930273e+03 4.90961963e+03 4.90929639e+03 4.90893115e+03 4.90891650e+03 4.90894922e+03 4.90896240e+03 4.90890869e+03 4.90883105e+03 4.90885742e+03 4.90889600e+03 4.90904736e+03 4.90908203e+03 4.90892139e+03 4.90890869e+03 4.90889551e+03 4.90885010e+03 4.90885547e+03 4.90887402e+03 4.90923340e+03 4.90936816e+03 4.90901221e+03 4.90887012e+03 4.90891260e+03 4.90889111e+03 4.90896191e+03 4.90906348e+03 4.90893457e+03 4.90926611e+03 4.90935742e+03 4.90897949e+03 4.90886621e+03 4.90891748e+03 4.90887939e+03 4.90890576e+03 4.90892334e+03 4.90891602e+03 4.90887793e+03 4.90901562e+03 4.90899219e+03 4.90902344e+03 4.90884863e+03 4.90919873e+03 4.90924707e+03 4.90894629e+03 4.90888818e+03 4.90885400e+03 4.90895264e+03 4.90908789e+03 4.90895557e+03 4.90887109e+03 4.90883057e+03 4.90885791e+03 4.90887305e+03 4.90887598e+03 4.90889453e+03 4.90894775e+03 4.90890039e+03 4.90897363e+03 4.90911230e+03 4.90900342e+03 4.91440674e+03 4.92233057e+03 4.95041895e+03 6.65699463e+03 1.00727998e+04 2.90737871e+04 2.52439980e+04 4.16308047e+04 6.77701953e+04 2.23069568e+09 4.48306278e+09 -2017037952. 2.63294899e+09 -4.66747904e+09 -1576615936. 1.99682396e+10 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. 0. 0. 9.98637875e+09 9.98637875e+09 9.98637875e+09 0. 0. 1.78115625e+10 -5.32207514e+09 -2.80256666e+09 6.08834688e+04 3.02518281e+04 1.97488066e+04 1.96333223e+04 1.01581572e+04 6.69501562e+03 4.93024805e+03 4.91074219e+03 4.90925684e+03 4.90940234e+03 4.90935938e+03 4.90935791e+03 4.90918896e+03 4.90925928e+03 4.90931738e+03 4.90941895e+03 4.90932666e+03 4.90899023e+03 4.90892529e+03 4.90894922e+03 4.90924023e+03 4.90924072e+03 4.90902344e+03 4.90891748e+03 4.90890820e+03 4.90887939e+03 4.90889062e+03 4.90897998e+03 4.90900293e+03 4.90904248e+03 4.90904639e+03 4.90907324e+03 4.90909961e+03 4.90916699e+03 4.90900391e+03 4.90905420e+03 4.90902490e+03 4.90915088e+03 4.90895898e+03 4.90894678e+03 4.90902539e+03 4.90909717e+03 4.90922070e+03 4.90918311e+03 4.90910645e+03 4.90904834e+03 4.90886035e+03 4.90893945e+03 4.90894775e+03 4.90887549e+03 4.90880127e+03 4.90891553e+03 4.90900098e+03 4.90893457e+03 4.90888525e+03 4.90887305e+03 4.90888428e+03 4.90898486e+03 4.90901270e+03 4.90911133e+03 4.90895898e+03 4.90883203e+03 4.90886182e+03 4.90889014e+03 4.90892578e+03 4.90892529e+03 4.90885986e+03 4.90888281e+03 4.90885498e+03 4.90887695e+03 4.90898193e+03 4.90903223e+03 4.90898291e+03 4.90888525e+03 4.90889014e+03 4.90890088e+03 4.90887695e+03 4.90910645e+03 4.90909717e+03 4.90902246e+03 4.90882324e+03 4.90920605e+03 4.90985986e+03 4.90989697e+03 4.90932471e+03 4.90911426e+03 4.90907422e+03 4.90922559e+03 4.90904785e+03 4.90905713e+03 4.90936816e+03 4.90991211e+03 4.90970703e+03 4.90920215e+03 4.90892285e+03 4.90890869e+03 4.90890283e+03 4.90889648e+03 4.90891016e+03 4.90890039e+03 4.90899512e+03 4.90889355e+03 4.90891650e+03 4.90894971e+03 4.90886621e+03 4.90888379e+03 4.90887500e+03 4.90907666e+03 4.90912451e+03 4.90894922e+03 4.90898926e+03 4.90893066e+03 4.90895752e+03 4.90893896e+03 4.90888184e+03 4.90896289e+03 4.90888721e+03 4.90895215e+03 4.90890723e+03 4.90885986e+03 4.90885938e+03 4.90891016e+03 4.90894531e+03 4.90891748e+03 4.90888281e+03 4.90889014e+03 4.90893848e+03 4.90926904e+03 4.90929688e+03 4.90905908e+03 4.90891895e+03 4.90896973e+03 4.90939209e+03 4.90945605e+03 4.90920361e+03 4.90897266e+03 4.90896338e+03 4.90886768e+03 4.90896094e+03 4.90893164e+03 4.90893262e+03 4.90894482e+03 4.90891211e+03 4.90897119e+03 4.90894287e+03 4.90889502e+03 4.90895264e+03 4.90893555e+03 4.90893604e+03 4.90887939e+03 4.90898389e+03 4.90922363e+03 4.90984619e+03 4.90992920e+03 4.90942871e+03 4.90897754e+03 4.90918115e+03 4.90963818e+03 4.90971533e+03 4.90908740e+03 4.90892676e+03 4.90892822e+03 4.90891602e+03 4.90890332e+03 4.90885791e+03 4.90891455e+03 4.90890967e+03 4.90889893e+03 4.90889111e+03 4.90890723e+03 4.90913965e+03 4.90917236e+03 4.90898389e+03 4.90893164e+03 4.90890479e+03 4.90884326e+03 4.90899805e+03 4.90912158e+03 4.90915723e+03 4.90899561e+03 4.90888184e+03 4.90887598e+03 4.90884424e+03 4.90893213e+03 4.90925195e+03 4.90948877e+03 4.90909668e+03 4.90882959e+03 4.90896777e+03 4.90892432e+03 4.90890137e+03 4.90893164e+03 4.90896387e+03 4.90896826e+03 4.90920654e+03 4.90975684e+03 4.90973926e+03 4.90913525e+03 4.90888135e+03 4.90895508e+03 4.90903027e+03 4.90926318e+03 4.90961377e+03 4.90952930e+03 4.90897168e+03 4.90880615e+03 4.90887061e+03 4.90889990e+03 4.90886133e+03 4.90887842e+03 4.90888574e+03 4.90886963e+03 4.90890674e+03 4.90889404e+03 4.90889160e+03 4.90895508e+03 4.90888232e+03 4.90896973e+03 4.90893750e+03 4.90906445e+03 4.90908398e+03 4.90899121e+03 4.90894727e+03 4.90896484e+03 4.90895996e+03 4.90887305e+03 4.90891748e+03 4.90898682e+03 4.90885938e+03 4.90886719e+03 4.90891943e+03 4.90904150e+03 4.90906445e+03 4.90889697e+03 4.90884863e+03 4.90883887e+03 4.90890283e+03 4.90884521e+03 4.90889258e+03 4.90885205e+03 4.90888184e+03 4.90885303e+03 4.90887305e+03 4.90909863e+03 4.90897266e+03 4.90890527e+03 4.90916748e+03 4.90900586e+03 4.90886572e+03 4.90890674e+03 4.90888574e+03 4.90888867e+03 4.90895361e+03 4.90895068e+03 4.90894482e+03 4.90888965e+03 4.90885986e+03 4.90886328e+03 4.90887207e+03 4.90889307e+03 4.90892627e+03 4.90896777e+03 4.90894824e+03 4.90890625e+03 4.90893408e+03 4.90890381e+03 4.90889941e+03 4.90888770e+03 4.90889014e+03 4.90894629e+03 4.90928125e+03 4.90930176e+03 4.90912207e+03 4.90896875e+03 4.90893262e+03 4.90890576e+03 4.90894092e+03 4.90908057e+03 4.90927148e+03 4.90933398e+03 4.90910205e+03 4.90894971e+03 4.90887451e+03 4.90891016e+03 4.90893848e+03 4.90885889e+03 4.90892334e+03 4.90884766e+03 4.90894824e+03 4.90893945e+03 4.90886963e+03 4.90892578e+03 4.90889648e+03 4.90893896e+03 4.90915186e+03 4.90953418e+03 4.90939453e+03 4.90901367e+03 4.90893066e+03 4.90886279e+03 4.90897412e+03 4.90894238e+03 4.90894580e+03 4.90897461e+03 4.90937988e+03 4.90940820e+03 4.90905615e+03 4.90887012e+03 4.90888818e+03 4.90895654e+03 4.90894238e+03 4.90890918e+03 4.90888184e+03 4.90886035e+03 4.90892773e+03 4.90893066e+03 4.90891064e+03 4.90890186e+03 4.90888867e+03 4.90888818e+03 4.90891406e+03 4.90885498e+03 4.90899316e+03 4.90907080e+03 4.90920654e+03 4.90955029e+03 4.91002393e+03 4.91009766e+03 4.90968652e+03 4.90962451e+03 4.90932471e+03 4.90934424e+03 4.90895801e+03 4.90890576e+03 4.90919287e+03 4.90930371e+03 4.90908740e+03 4.90902539e+03 4.90896289e+03 4.90892969e+03 4.90889941e+03 4.90892725e+03 4.90893457e+03 4.90887744e+03 4.90900195e+03 4.90918018e+03 4.90910303e+03 4.90892871e+03 4.90894287e+03 4.90889111e+03 4.90890869e+03 4.90888232e+03 4.90892236e+03 4.90900684e+03 4.90898584e+03 4.90906299e+03 4.90947803e+03 4.90918066e+03 4.90898340e+03 4.90887842e+03 4.90905078e+03 4.90919434e+03 4.90901611e+03 4.90888086e+03 4.90890625e+03 4.90926465e+03 4.90936035e+03 4.90915625e+03 4.90892285e+03 4.90923975e+03 4.90975928e+03 4.90960547e+03 4.90908008e+03 4.90889160e+03 4.90895557e+03 4.90914014e+03 4.90897168e+03 4.90893701e+03 4.90888867e+03 4.90913525e+03 4.90952490e+03 4.90928809e+03 4.90904736e+03 4.90907861e+03 4.90935986e+03 4.90994531e+03 4.90978271e+03 4.90907910e+03 4.90886768e+03 4.90884180e+03 4.90885693e+03 4.90891553e+03 4.90895703e+03 4.90889844e+03 4.90889697e+03 4.90893018e+03 4.90902588e+03 4.90890820e+03 4.90891748e+03 4.90890527e+03 4.90906885e+03 4.90923779e+03 4.90912109e+03 4.90904297e+03 4.90889307e+03 4.90889209e+03 4.90885840e+03 4.90888379e+03 4.90888379e+03 4.90889209e+03 4.90911523e+03 4.90967578e+03 4.90906250e+03 4.90902637e+03 4.90901514e+03 4.90897070e+03 4.90917480e+03 4.90886816e+03 4.90882031e+03 4.90887354e+03 4.90905615e+03 4.90901270e+03 4.90885400e+03 4.90892432e+03 4.90898682e+03 4.90898828e+03 4.90892139e+03 4.90891260e+03 4.90896289e+03 4.90885840e+03 4.90899072e+03 4.90917627e+03 4.90922900e+03 4.90895654e+03 4.90895605e+03 4.90958984e+03 4.91042480e+03 4.90984326e+03 4.90906738e+03 4.90903027e+03 4.90939160e+03 4.90904932e+03 4.90891064e+03 4.90908789e+03 4.90885449e+03 4.90892871e+03 4.90894678e+03 4.90896094e+03 4.90900830e+03 4.90899951e+03 4.90899902e+03 4.90887939e+03 4.90886328e+03 4.90894824e+03 4.90896631e+03 4.90889990e+03 4.90888818e+03 4.90898291e+03 4.90900781e+03 4.90904150e+03 4.90911963e+03 4.90922314e+03 4.90909131e+03 4.90891260e+03 4.90888818e+03 4.90918408e+03 4.90930859e+03 4.90914453e+03 4.90940234e+03 4.91042041e+03 4.91129688e+03 4.91037451e+03 4.90925098e+03 4.90904492e+03 4.90920605e+03 4.90929834e+03 4.90904541e+03 4.90892236e+03 4.90886182e+03 4.90890674e+03 4.90889551e+03 4.90887256e+03 4.90889111e+03 4.90888721e+03 4.90884424e+03 4.90896143e+03 4.90931348e+03 4.90898828e+03 4.90890186e+03 4.90909180e+03 4.90951025e+03 4.90907666e+03 4.90898193e+03 4.90942139e+03 4.90936328e+03 4.90922607e+03 4.90899805e+03 4.90895215e+03 4.90894678e+03 4.90906445e+03 4.90894043e+03 4.90888184e+03 4.90892725e+03 4.90902490e+03 4.90890625e+03 4.90920703e+03 4.90982471e+03 4.91000391e+03 4.90968994e+03 4.90934619e+03 4.90910742e+03 4.90889893e+03 4.90888232e+03 4.90888135e+03 4.90892334e+03 4.90888379e+03 4.90889258e+03 4.90889404e+03 4.90886963e+03 4.90892529e+03 4.90887598e+03 4.90887549e+03 4.90893457e+03 4.90908154e+03 4.90947412e+03 4.90956934e+03 4.90909961e+03 4.90888281e+03 4.90894141e+03 4.90894189e+03 4.90899023e+03 4.90892676e+03 4.90896875e+03 4.90889941e+03 4.90903613e+03 4.90949219e+03 4.90928076e+03 4.90897168e+03 4.90892578e+03 4.90956641e+03 4.91050537e+03 4.90979395e+03 4.90899805e+03 4.90892773e+03 4.90918848e+03 4.90922266e+03 4.90900098e+03 4.90884131e+03 4.90903760e+03 4.90943018e+03 4.90975244e+03 4.91001514e+03 4.90931982e+03 4.90910693e+03 4909. 4.91000732e+03 4.91059717e+03 4.90959131e+03 4.90893213e+03 4.90895654e+03 4.90962354e+03 4.90983154e+03 4.90940527e+03 4.90903809e+03 4.90921582e+03 4.90974658e+03 4.91002734e+03 4.90953955e+03 4.90925195e+03 4.90905811e+03 4.90942725e+03 4.91008105e+03 4.91025586e+03 4.90961230e+03 4.90900195e+03 4.90916992e+03 4.90957275e+03 4.90967627e+03 4.90917480e+03 4.90917578e+03 4.90973193e+03 4.90959717e+03 4.90910400e+03 4.90885059e+03 4.90885205e+03 4.90884766e+03 4.90893213e+03 4.90919873e+03 4.90948828e+03 4.90922461e+03 4.90893018e+03 4.90887549e+03 4.90887939e+03 4.90900342e+03 4.90932129e+03 4.91240918e+03 4.91727686e+03 4.91310889e+03 4.91767236e+03 4.93244043e+03 4.94710449e+03 4.95440479e+03 4.92202393e+03 4.91602930e+03 6.43184570e+03 9.57873438e+03 1.97853086e+04 2.60824414e+04 4.88113750e+04 -5.68612762e+09 -1515792384. 0. 0. 0. 0. -5.34919168e+09 -5.34919168e+09 1.48798433e+10 1781748480. 1.22399047e+05 -871242112. -2120684288. -5.36598989e+09 975841408. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.50911519e+10 -2.59433395e+09 4.14223281e+04 2.45511289e+04 2.00445859e+04 1.95848574e+04 1.96468477e+04 9.55007910e+03 6.69941797e+03 4.95093115e+03 4.94346680e+03 4.91364600e+03 4.91075732e+03 4.91140430e+03 4.91158740e+03 4.91091748e+03 4.91086768e+03 4.91091992e+03 4.91088965e+03 4.91128516e+03 4.91227246e+03 4.91114893e+03 4.91128613e+03 4.91251367e+03 4.91164746e+03 4.91088477e+03 4.91111133e+03 4.91097119e+03 4.91083252e+03 4.91094922e+03 4.91133154e+03 4.91103809e+03 4.91090479e+03 4.91114893e+03 4.91095947e+03 4.91092871e+03 4.91110010e+03 4.91089258e+03 4.91156934e+03 4.91223047e+03 4.91153320e+03 4.91141309e+03 4.91209277e+03 4.91170068e+03 4.91091016e+03 4.91124170e+03 4.91083887e+03 4.91294043e+03 4.91415967e+03 4.91210596e+03 4.91091309e+03 4.91089648e+03 4.91085986e+03 4.91087500e+03 4.91091699e+03 4.91088574e+03 4.91085791e+03 4.91183496e+03 4.91384424e+03 4.91317871e+03 4.91127393e+03 4.91082861e+03 4.91099219e+03 4.91154004e+03 4.91208643e+03 4.91133887e+03 4.91124316e+03 4.91150537e+03 4.91114307e+03 4.91089746e+03 4.91161768e+03 4.91143799e+03 4.91088770e+03 4.91135742e+03 4.91103857e+03 4.91101270e+03 4.91082520e+03 4.91109131e+03 4.91091943e+03 4.91082910e+03 4.91101270e+03 4.91078760e+03 4.91157568e+03 4.91234033e+03 4.91178711e+03 4.91089062e+03 4.91120801e+03 4.91105469e+03 4.91085254e+03 4.91085986e+03 4.91106494e+03 4.91106445e+03 4.91090625e+03 4.91105322e+03 4.91091016e+03 4.91183887e+03 4.91195557e+03 4.91093799e+03 4.91117432e+03 4.91121289e+03 4.91084229e+03 4.91086572e+03 4.91090430e+03 4.91092822e+03 4.91189404e+03 4.91287891e+03 4.91138770e+03 4.91089258e+03 4.91176465e+03 4.91130615e+03 4.91090430e+03 4.91154395e+03 4.91236328e+03 4.91210742e+03 4.91168701e+03 4.91183643e+03 4.91158398e+03 4.91085889e+03 4.91118164e+03 4.91091846e+03 4.91178223e+03 4.91278369e+03 4.91160303e+03 4.91087451e+03 4.91142822e+03 4.91088965e+03 4.91094531e+03 4.91103027e+03 4.91092432e+03 4.91137207e+03 4.91315820e+03 4.91303711e+03 4.91116943e+03 4.91091309e+03 4.91090625e+03 4.91109229e+03 4.91158154e+03 4.91174512e+03 4.91133594e+03 4.91094824e+03 4.91086816e+03 4.91128613e+03 4.91158691e+03 4.91099902e+03 4.91085352e+03 4.91090674e+03 4.91096387e+03 4.91096777e+03 4.91092334e+03 4.91090674e+03 4.91100049e+03 4.91146094e+03 4.91169824e+03 4.91104443e+03 4.91090967e+03 4.91098682e+03 4.91130615e+03 4.91094043e+03 4.91151416e+03 4.91276807e+03 4.91140088e+03 4.91099268e+03 4.91115332e+03 4.91083496e+03 4.91093311e+03 4.91091064e+03 4.91094678e+03 4.91125537e+03 4.91218311e+03 4.91248389e+03 4.91190088e+03 4.91090283e+03 4.91090137e+03 4.91083057e+03 4.91103760e+03 4.91097314e+03 4.91091943e+03 4.91086035e+03 4.91208154e+03 4.91178369e+03 4.91123145e+03 4.91089307e+03 4.91133301e+03 4.91388525e+03 4.91558789e+03 4.91357617e+03 4.91125635e+03 4.91083301e+03 4.91084473e+03 4.91087354e+03 4.91093213e+03 4.91086084e+03 4.91117383e+03 4.91275879e+03 4.91250586e+03 4.91134033e+03 4.91103955e+03 4.91175342e+03 4.91122119e+03 4.91078271e+03 4.91135840e+03 4.91143164e+03 4.91164697e+03 4.91235986e+03 4.91184619e+03 4.91097607e+03 4.91098242e+03 4.91077295e+03 4.91181104e+03 4.91298389e+03 4.91163428e+03 4.91095117e+03 4.91123389e+03 4.91084912e+03 4.91113281e+03 4.91093750e+03 4.91094336e+03 4.91086475e+03 4.91106445e+03 4.91133154e+03 4.91092090e+03 4.91179443e+03 4.91195654e+03 4.91116357e+03 4.91084277e+03 4.91092188e+03 4.91099170e+03 4.91090381e+03 4.91080713e+03 4.91091943e+03 4.91129150e+03 4.91145508e+03 4.91130127e+03 4.91086133e+03 4.91090039e+03 4.91088818e+03 4.91086963e+03 4.91083887e+03 4.91096484e+03 4.91090771e+03 4.91121777e+03 4.91168311e+03 4.91127490e+03 4.91102832e+03 4.91228223e+03 4.91197949e+03 4.91094141e+03 4.91162158e+03 4.91162207e+03 4.91098340e+03 4.91086426e+03 4.91104346e+03 4.91112012e+03 4.91090674e+03 4.91092529e+03 4.91095557e+03 4.91110693e+03 4.91083838e+03 4.91166260e+03 4.91143896e+03 4.91099219e+03 4.91090283e+03 4.91089648e+03 4.91139014e+03 4.91091553e+03 4.91093506e+03 4.91126514e+03 4.91097070e+03 4.91102637e+03 4.91138086e+03 4.91184277e+03 4.91106396e+03 4.91092871e+03 4.91084668e+03 4.91103174e+03 4.91112158e+03 4.91101270e+03 4.91123096e+03 4.91166455e+03 4.91203613e+03 4.91101953e+03 4.91091455e+03 4.91084033e+03 4.91115234e+03 4.91101953e+03 4.91090430e+03 4.91091748e+03 4.91099756e+03 4.91090332e+03 4.91095020e+03 4.91087207e+03 4.91107178e+03 4.91139355e+03 4.91131250e+03 4.91107910e+03 4.91098047e+03 4.91100488e+03 4.91125684e+03 4.91109131e+03 4.91098633e+03 4.91121924e+03 4.91102002e+03 4.91088818e+03 4.91091211e+03 4.91085693e+03 4.91142920e+03 4.91228369e+03 4.91150684e+03 4.91087061e+03 4.91109961e+03 4.91087598e+03 4.91107129e+03 4.91118408e+03 4.91084961e+03 4.91083203e+03 4.91089795e+03 4.91119727e+03 4.91147754e+03 4.91169434e+03 4.91091504e+03 4.91087500e+03 4.91105127e+03 4.91168604e+03 4.91117236e+03 4.91087451e+03 4.91095898e+03 4.91120459e+03 4.91123682e+03 4.91084473e+03 4.91090527e+03 4.91152051e+03 4.91215771e+03 4.91164648e+03 4.91083936e+03 4.91087793e+03 4.91104443e+03 4.91152197e+03 4.91120947e+03 4.91092334e+03 4.91090137e+03 4.91086523e+03 4.91120898e+03 4.91134473e+03 4.91145557e+03 4.91102100e+03 4.91102734e+03 4.91127686e+03 4.91184863e+03 4.91134570e+03 4.91084912e+03 4.91081250e+03 4.91084131e+03 4.91085791e+03 4.91135889e+03 4.91115674e+03 4.91083691e+03 4.91089600e+03 4.91093799e+03 4.91139014e+03 4.91089893e+03 4.91085938e+03 4.91103809e+03 4.91141406e+03 4.91155957e+03 4.91109961e+03 4.91100732e+03 4.91119775e+03 4.91088330e+03 4.91132617e+03 4.91095752e+03 4.91094580e+03 4.91163867e+03 4.91100879e+03 4.91084619e+03 4.91088330e+03 4.91094385e+03 4.91123486e+03 4.91196191e+03 4.91366650e+03 4.91295410e+03 4.91153174e+03 4.91137109e+03 4.91168555e+03 4.91256348e+03 4.91120410e+03 4.91090576e+03 4.91090479e+03 4.91087891e+03 4.91083838e+03 4.91101758e+03 4.91296387e+03 4.91393701e+03 4.91197754e+03 4.91101221e+03 4.91139600e+03 4.91089160e+03 4.91264355e+03 4.91292090e+03 4.91137158e+03 4.91092041e+03 4.91102344e+03 4.91211426e+03 4.91300830e+03 4.91215430e+03 4.91090527e+03 4.91091650e+03 4.91101660e+03 4.91202979e+03 4.91420752e+03 4.91396680e+03 4.91305420e+03 4.91109814e+03 4.91116650e+03 4.91181445e+03 4.91094043e+03 4.91177637e+03 4.91371143e+03 4.91194043e+03 4.91089941e+03 4.91080615e+03 4.91202881e+03 4.91490527e+03 4.91361865e+03 4.91118066e+03 4.91097949e+03 4.91098779e+03 4.91101123e+03 4.91174658e+03 4.91289111e+03 4.91149658e+03 4.91109521e+03 4.91082861e+03 4.91111377e+03 4.91150195e+03 4.91106055e+03 4.91097070e+03 4.91150586e+03 4.91167725e+03 4.91103564e+03 4.91086133e+03 4.91216943e+03 4.91266309e+03 4.91127100e+03 4.91138330e+03 4.91277734e+03 4.91133105e+03 4.91119824e+03 4.91269678e+03 4.91182178e+03 4.91098828e+03 4.91099805e+03 4.91166406e+03 4.91206299e+03 4.91215186e+03 4.91106885e+03 4.91082324e+03 4.91106250e+03 4.91106787e+03 4.91083984e+03 4.91096582e+03 4.91164697e+03 4.91132764e+03 4.91095557e+03 4.91093213e+03 4.91096631e+03 4.91088965e+03 4.91154590e+03 4.91117188e+03 4.91085205e+03 4.91095801e+03 4.91083936e+03 4.91183984e+03 4.91188623e+03 4.91102734e+03 4.91133496e+03 4.91127930e+03 4.91088232e+03 4.91147314e+03 4.91213330e+03 4.91096436e+03 4.91090576e+03 4.91095557e+03 4.91090137e+03 4.91094629e+03 4.91086816e+03 4.91085254e+03 4.91091113e+03 4.91107178e+03 4.91097363e+03 4.91090576e+03 4.91200049e+03 4.91256055e+03 4.91150977e+03 4.91122754e+03 4.91302686e+03 4.91252734e+03 4.91085449e+03 4.91181836e+03 4.91275635e+03 4.91120410e+03 4.91107031e+03 4.91127734e+03 4.91079150e+03 4.91158154e+03 4.91123633e+03 4.91090869e+03 4.91129590e+03 4.91144336e+03 4.91113672e+03 4.91083203e+03 4.91131982e+03 4.91126709e+03 4.91094287e+03 4.91187793e+03 4.91229053e+03 4.91102588e+03 4.91101855e+03 4.91101855e+03 4.91104980e+03 4.91149268e+03 4.91117236e+03 4.91092627e+03 4.91089990e+03 4.91089209e+03 4.91084814e+03 4.91095264e+03 4.91090479e+03 4.91087207e+03 4.91104248e+03 4.91089160e+03 4.91100635e+03 4.91160352e+03 4.91204395e+03 4.91143604e+03 4.91091406e+03 4.91105273e+03 4.91133203e+03 4.91101074e+03 4.91107568e+03 4.91117334e+03 4.91086621e+03 4.91184326e+03 4.91172852e+03 4.91109131e+03 4.91113428e+03 4.91133350e+03 4.91097607e+03 4.91086523e+03 4.91092334e+03 4.91110986e+03 4.91195898e+03 4.91315283e+03 4.91257666e+03 4.91115430e+03 4.91120264e+03 4.91159863e+03 4.91324463e+03 4.91353418e+03 4.91292139e+03 4.91166455e+03 4.91087793e+03 4.91115332e+03 4.91097266e+03 4.91110352e+03 4.91163867e+03 4.91087500e+03 4.91105762e+03 4.91112891e+03 4.91107959e+03 4.91200293e+03 4.91147803e+03 4.91081201e+03 4.91128174e+03 4.91149365e+03 4.91095947e+03 4.91151611e+03 4.91186523e+03 4.91163770e+03 4.91116260e+03 4.91097559e+03 4.91094727e+03 4.91097754e+03 4.91089502e+03 4.91094678e+03 4.91086865e+03 4.91145361e+03 4.91239941e+03 4.91133350e+03 4.91095020e+03 4.91145020e+03 4.91096582e+03 4.91120215e+03 4.91145605e+03 4.91102832e+03 4.91120752e+03 4.91120557e+03 4.91088428e+03 4.91087646e+03 4.91090869e+03 4.91104980e+03 4.91118457e+03 4.91105518e+03 4.91085840e+03 4.91098730e+03 4.91087744e+03 4.91091553e+03 4.91120264e+03 4.91216260e+03 4.91190820e+03 4.91117871e+03 4.91092969e+03 4.91146436e+03 4.91159717e+03 4.91114111e+03 4.91250146e+03 4.91329688e+03 4.91255518e+03 4.91408984e+03 4.94200098e+03 7.67150781e+03 1.60985557e+04 2.44270797e+09 -1.20164301e+10 7.14900582e+09 -8.75808870e+09 1.30109307e+10 -5.16682957e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 1.99497679e+11 -2.04913459e+10 2054114944. 8.75027149e+09 4.96315699e+09 6.07120078e+04 2.96034668e+04 1.96714043e+04 9.80215137e+03 6.61160498e+03 4.92623438e+03 4.91267188e+03 4.91096680e+03 4.91085352e+03 4.91148340e+03 4.91155713e+03 4.91102588e+03 4.91119385e+03 4.91121631e+03 4.91087598e+03 4.91143115e+03 4.91108057e+03 4.91099072e+03 4.91191260e+03 4.91205078e+03 4.91103418e+03 4.91133252e+03 4.91159033e+03 4.91083887e+03 4.91140186e+03 4.91144287e+03 4.91087354e+03 4.91084863e+03 4.91113037e+03 4.91142041e+03 4.91102100e+03 4.91096094e+03 4.91091553e+03 4.91099121e+03 4.91121875e+03 4.91124902e+03 4.91082520e+03 4.91179395e+03 4.91204248e+03 4.91105420e+03 4.91092236e+03 4.91091406e+03 4.91111670e+03 4.91220557e+03 4.91200098e+03 4.91093115e+03 4.91213770e+03 4.91186426e+03 4.91087842e+03 4.91136328e+03 4.91163135e+03 4.91092285e+03 4.91086523e+03 4.91091553e+03 4.91093066e+03 4.91089209e+03 4.91088086e+03 4.91140723e+03 4.91119287e+03 4.91087598e+03 4.91093262e+03 4.91087695e+03 4.91195215e+03 4.91190771e+03 4.91131787e+03 4.91088037e+03 4.91093506e+03 4.91100830e+03 4.91251758e+03 4.91491016e+03 4.91332178e+03 4.91120557e+03 4.91088379e+03 4.91155078e+03 4.91250537e+03 4.91235400e+03 4.91096484e+03 4.91086377e+03 4.91096777e+03 4.91147656e+03 4.91142285e+03 4.91142969e+03 4.91189600e+03 4.91122607e+03 4.91093750e+03 4.91107812e+03 4.91095703e+03 4.91273730e+03 4.91354150e+03 4.91251172e+03 4.91140381e+03 4.91090137e+03 4.91088770e+03 4.91099756e+03 4.91169434e+03 4.91153418e+03 4.91094287e+03 4.91120361e+03 4.91091260e+03 4.91164990e+03 4.91180908e+03 4.91089062e+03 4.91114941e+03 4.91100977e+03 4.91094141e+03 4.91090332e+03 4.91089795e+03 4.91187695e+03 4.91181494e+03 4.91096729e+03 4.91098682e+03 4.91090771e+03 4.91104785e+03 4.91119141e+03 4.91091357e+03 4.91098340e+03 4.91131885e+03 4.91109961e+03 4.91093066e+03 4.91172852e+03 4.91219434e+03 4.91095801e+03 4.91108789e+03 4.91093408e+03 4.91101709e+03 4.91103564e+03 4.91088086e+03 4.91088965e+03 4.91086279e+03 4.91090869e+03 4.91105420e+03 4.91092236e+03 4.91113281e+03 4.91126514e+03 4.91087842e+03 4.91108203e+03 4.91105713e+03 4.91093311e+03 4.91089600e+03 4.91101367e+03 4.91147803e+03 4.91200684e+03 4.91129102e+03 4.91084277e+03 4.91135059e+03 4.91132178e+03 4.91091553e+03 4.91088281e+03 4.91086816e+03 4.91087793e+03 4.91092822e+03 4.91127930e+03 4.91167822e+03 4.91192041e+03 4.91204346e+03 4.91141455e+03 4.91086865e+03 4.91114844e+03 4.91133154e+03 4.91100586e+03 4.91087402e+03 4.91082861e+03 4.91123389e+03 4.91228516e+03 4.91162207e+03 4.91087402e+03 4.91159082e+03 4.91144238e+03 4.91083057e+03 4.91115820e+03 4.91129736e+03 4.91086768e+03 4.91087646e+03 4.91089014e+03 4.91086963e+03 4.91090283e+03 4.91098682e+03 4.91097119e+03 4.91084717e+03 4.91149805e+03 4.91149072e+03 4.91118750e+03 4.91086670e+03 4.91101611e+03 4.91108301e+03 4.91101953e+03 4.91088477e+03 4.91124805e+03 4.91235352e+03 4.91192432e+03 4.91091162e+03 4.91141846e+03 4.91152344e+03 4.91084180e+03 4.91084473e+03 4.91092627e+03 4.91115771e+03 4.91101172e+03 4.91083252e+03 4.91127588e+03 4.91203613e+03 4.91214697e+03 4.91317236e+03 4.91244922e+03 4.91111719e+03 4.91092871e+03 4.91090137e+03 4.91129639e+03 4.91144678e+03 4.91087256e+03 4.91109912e+03 4.91210352e+03 4.91134766e+03 4.91094141e+03 4.91217139e+03 4.91176904e+03 4.91092969e+03 4.91094531e+03 4.91092090e+03 4.91101807e+03 4.91102686e+03 4.91085303e+03 4.91097363e+03 4.91109766e+03 4.91096045e+03 4.91090820e+03 4.91084570e+03 4.91131494e+03 4.91186279e+03 4.91136572e+03 4.91103467e+03 4.91091846e+03 4.91094531e+03 4.91090283e+03 4.91100537e+03 4.91117090e+03 4.91098877e+03 4.91087939e+03 4.91086133e+03 4.91093311e+03 4.91091650e+03 4.91089648e+03 4.91091992e+03 4.91084668e+03 4.91084814e+03 4.91093359e+03 4.91089941e+03 4.91088184e+03 4.91089600e+03 4.91082764e+03 4.91092188e+03 4.91088916e+03 4.91088672e+03 4.91088623e+03 4.91085791e+03 4.91089600e+03 4.91097461e+03 4.91090820e+03 4.91086133e+03 4.91088721e+03 4.91087158e+03 4.91092480e+03 4.91089697e+03 4.91085840e+03 4.91084473e+03 4.91094141e+03 4.91088135e+03 4.91085840e+03 4.91092822e+03 4.91090820e+03 4.91083057e+03 4.91089600e+03 4.91085742e+03 4.91089893e+03 4.91086182e+03 4.91085889e+03 4.91089209e+03 4.91094824e+03 4.91089014e+03 4.91084766e+03 4.91083496e+03 4.91088672e+03 4.91086621e+03 4.91088770e+03 4.91093604e+03 4.91100781e+03 4.91100146e+03 4.91097900e+03 4.91087891e+03 4.91093604e+03 4.91094727e+03 4.91093799e+03 4.91089990e+03 4.91085986e+03 4.91091064e+03 4.91084668e+03 4.91087891e+03 4.91090381e+03 4.91090479e+03 4.91090723e+03 4.91088574e+03 4.91085449e+03 4.91084326e+03 4.91086523e+03 4.91086914e+03 4.91091846e+03 4.91093359e+03 4.91091895e+03 4.91094092e+03 4.91091455e+03 4.91094287e+03 4.91089404e+03 4.91087842e+03 4.91093799e+03 4.91089502e+03 4.91086133e+03 4.91087354e+03 4.91092822e+03 4.91110498e+03 4.91106738e+03 4.91126172e+03 4.91101562e+03 4.91098047e+03 4.91088721e+03 4.91091260e+03 4.91086133e+03 4.91104834e+03 4.91138916e+03 4.91124268e+03 4.91090234e+03 4.91087549e+03 4.91089893e+03 4.91088330e+03 4.91090674e+03 4.91093115e+03 4.91100244e+03 4.91094922e+03 4.91091846e+03 4.91084424e+03 4.91087598e+03 4.91090137e+03 4.91088916e+03 4.91090479e+03 4.91103711e+03 4.91099854e+03 4.91099707e+03 4.91089551e+03 4.91086523e+03 4.91091406e+03 4.91091113e+03 4.91086279e+03 4.91088330e+03 4.91092285e+03 4.91104932e+03 4.91116748e+03 4.91091455e+03 4.91087500e+03 4.91091064e+03 4.91088525e+03 4.91109326e+03 4.91162646e+03 4.91128857e+03 4.91093066e+03 4.91100098e+03 4.91087012e+03 4.91086279e+03 4.91094141e+03 4.91110010e+03 4.91116064e+03 4.91106641e+03 4.91092529e+03 4.91089355e+03 4.91084668e+03 4.91086816e+03 4.91092676e+03 4.91120410e+03 4.91117236e+03 4.91094482e+03 4.91086035e+03 4.91085693e+03 4.91088867e+03 4.91086426e+03 4.91095703e+03 4.91101855e+03 4.91095410e+03 4.91088525e+03 4.91086963e+03 4.91092725e+03 4.91093750e+03 4.91089502e+03 4.91081348e+03 4.91083984e+03 4.91086328e+03 4.91086768e+03 4.91092627e+03 4.91091162e+03 4911. 4.91114941e+03 4.91095068e+03 4.91087549e+03 4.91087891e+03 4.91091602e+03 4.91102295e+03 4.91106738e+03 4.91116309e+03 4.91108789e+03 4.91103027e+03 4.91088867e+03 4.91087988e+03 4.91088965e+03 4.91090137e+03 4.91086719e+03 4.91091309e+03 4.91089941e+03 4.91085303e+03 4.91092969e+03 4.91117041e+03 4.91117529e+03 4.91094189e+03 4.91090088e+03 4.91087695e+03 4.91091797e+03 4.91088916e+03 4.91087744e+03 4.91087891e+03 4.91088037e+03 4.91101123e+03 4.91122266e+03 4.91128711e+03 4.91110205e+03 4.91093115e+03 4.91090723e+03 4.91088574e+03 4.91088037e+03 4.91085449e+03 4.91088721e+03 4.91118604e+03 4.91161084e+03 4.91167383e+03 4.91106787e+03 4.91091162e+03 4.91094922e+03 4.91107812e+03 4.91164600e+03 4.91418408e+03 4.91620850e+03 4.92208350e+03 4.91852051e+03 4.92829004e+03 7.23846680e+03 6.30401514e+03 1.04175283e+04 1.70346543e+04 4.74029466e+09 4.64450150e+09 -1.89075948e+10 3.42496666e+09 7.51094835e+09 -2.84993894e+09 -2.84861727e+10 -2.14535475e+10 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. 0. 9.98637875e+09 9.98637875e+09 9.98637875e+09 0. 0. 1.78115625e+10 -5.32207514e+09 -2.80256666e+09 6.08834688e+04 3.02518281e+04 1.97488066e+04 1.96333223e+04 9.99037109e+03 6.65780713e+03 4.93074365e+03 4.91219775e+03 4.91119189e+03 4.91165820e+03 4.91158057e+03 4.91121680e+03 4.91095264e+03 4.91100244e+03 4.91102930e+03 4.91096973e+03 4.91099121e+03 4.91119531e+03 4.91151318e+03 4.91113428e+03 4.91087988e+03 4.91093848e+03 4.91092480e+03 4.91111865e+03 4.91096191e+03 4.91089062e+03 4.91093848e+03 4.91102832e+03 4.91124219e+03 4.91128516e+03 4.91120898e+03 4.91101172e+03 4.91092480e+03 4.91094287e+03 4.91105127e+03 4.91087354e+03 4.91095801e+03 4.91109375e+03 4.91098242e+03 4.91089160e+03 4.91086816e+03 4.91090479e+03 4.91092139e+03 4.91101025e+03 4.91108691e+03 4.91118945e+03 4.91123145e+03 4.91128076e+03 4.91110693e+03 4.91096826e+03 4.91090186e+03 4.91101270e+03 4.91111328e+03 4.91107520e+03 4.91098145e+03 4.91102734e+03 4.91107520e+03 4.91116504e+03 4.91104883e+03 4.91090723e+03 4.91112207e+03 4.91128467e+03 4.91098389e+03 4.91089014e+03 4.91092236e+03 4.91094141e+03 4.91105566e+03 4.91095068e+03 4.91084668e+03 4.91094775e+03 4.91095215e+03 4.91097021e+03 4.91115283e+03 4.91168213e+03 4.91135596e+03 4.91095312e+03 4.91100635e+03 4.91087842e+03 4.91094482e+03 4.91090186e+03 4.91093311e+03 4.91090479e+03 4.91099072e+03 4.91095459e+03 4.91088135e+03 4.91089355e+03 4.91087891e+03 4.91087891e+03 4.91088770e+03 4.91091699e+03 4.91102930e+03 4.91137695e+03 4.91111621e+03 4.91093359e+03 4.91089551e+03 4.91093457e+03 4.91098779e+03 4.91107080e+03 4.91112061e+03 4.91096387e+03 4.91088574e+03 4.91091406e+03 4.91092725e+03 4.91109814e+03 4.91102539e+03 4.91098779e+03 4.91090918e+03 4.91091113e+03 4.91087646e+03 4.91091016e+03 4.91088965e+03 4.91092334e+03 4.91085693e+03 4.91088818e+03 4.91093359e+03 4.91092236e+03 4.91109619e+03 4.91104248e+03 4.91086377e+03 4.91096826e+03 4.91093994e+03 4.91096973e+03 4.91093945e+03 4.91093896e+03 4.91096631e+03 4.91100439e+03 4.91096094e+03 4.91116699e+03 4.91122314e+03 4.91093457e+03 4.91086572e+03 4.91091943e+03 4.91097559e+03 4.91093213e+03 4.91084717e+03 4.91082715e+03 4.91090625e+03 4.91090088e+03 4.91093994e+03 4.91091943e+03 4.91087549e+03 4.91086719e+03 4.91083936e+03 4.91092334e+03 4.91089014e+03 4.91092285e+03 4.91091455e+03 4.91087842e+03 4.91091895e+03 4.91087744e+03 4.91089844e+03 4.91092529e+03 4.91089404e+03 4.91088574e+03 4.91092383e+03 4.91093652e+03 4.91087793e+03 4.91096338e+03 4.91093311e+03 4.91092041e+03 4.91099268e+03 4.91131299e+03 4.91135107e+03 4.91110693e+03 4.91092334e+03 4.91088916e+03 4.91087207e+03 4.91087061e+03 4.91091748e+03 4.91089893e+03 4.91090820e+03 4.91087012e+03 4.91092334e+03 4.91085791e+03 4.91101465e+03 4.91132471e+03 4.91182764e+03 4.91169727e+03 4.91119189e+03 4.91095947e+03 4.91094873e+03 4.91091748e+03 4.91094385e+03 4.91090723e+03 4.91097998e+03 4.91085400e+03 4.91089990e+03 4.91087939e+03 4.91096729e+03 4.91095605e+03 4.91095703e+03 4.91089697e+03 4.91084521e+03 4.91089600e+03 4.91085791e+03 4.91092969e+03 4.91096533e+03 4.91091943e+03 4.91090479e+03 4.91092090e+03 4.91128906e+03 4.91154443e+03 4.91167285e+03 4.91154541e+03 4.91172314e+03 4.91123633e+03 4.91089160e+03 4.91100928e+03 4.91103711e+03 4.91092432e+03 4.91090820e+03 4.91091797e+03 4.91091846e+03 4.91096582e+03 4.91098242e+03 4.91091504e+03 4.91090674e+03 4.91087061e+03 4.91089990e+03 4.91112012e+03 4.91156494e+03 4.91146436e+03 4.91105469e+03 4.91091846e+03 4.91090088e+03 4911. 4.91134912e+03 4.91172656e+03 4.91158545e+03 4.91120605e+03 4.91095508e+03 4.91088379e+03 4.91098633e+03 4.91111963e+03 4.91107764e+03 4.91101074e+03 4.91100195e+03 4.91098486e+03 4.91105908e+03 4.91096924e+03 4.91090186e+03 4.91087109e+03 4.91106250e+03 4.91147900e+03 4.91209912e+03 4.91238477e+03 4.91128564e+03 4.91091602e+03 4.91110840e+03 4.91093945e+03 4.91087842e+03 4.91088525e+03 4.91094141e+03 4.91096094e+03 4.91093701e+03 4.91095459e+03 4.91092139e+03 4.91088623e+03 4.91086865e+03 4.91086084e+03 4.91097070e+03 4.91130078e+03 4.91136719e+03 4.91113037e+03 4.91089844e+03 4.91085742e+03 4.91096191e+03 4.91100049e+03 4.91095801e+03 4.91087744e+03 4.91094873e+03 4.91091846e+03 4.91088330e+03 4.91093652e+03 4.91093457e+03 4.91093262e+03 4.91088867e+03 4.91087842e+03 4.91092969e+03 4.91092236e+03 4.91088232e+03 4.91082666e+03 4.91087451e+03 4.91098438e+03 4.91096924e+03 4.91091016e+03 4.91108643e+03 4.91114600e+03 4.91096338e+03 4.91092188e+03 4.91088770e+03 4.91089893e+03 4.91087451e+03 4.91090234e+03 4.91088037e+03 4.91092139e+03 4.91094336e+03 4.91108350e+03 4.91110107e+03 4.91092627e+03 4.91095020e+03 4.91089600e+03 4.91091113e+03 4.91097461e+03 4.91116162e+03 4.91129395e+03 4.91109082e+03 4.91098389e+03 4.91096973e+03 4.91097510e+03 4.91095459e+03 4.91092188e+03 4.91089111e+03 4.91094727e+03 4.91102539e+03 4.91101611e+03 4.91098584e+03 4.91094336e+03 4.91098828e+03 4.91095605e+03 4.91090820e+03 4.91093457e+03 4.91102051e+03 4.91100879e+03 4.91091797e+03 4.91090527e+03 4.91088330e+03 4.91086621e+03 4.91097070e+03 4.91093164e+03 4.91092725e+03 4.91126025e+03 4.91140137e+03 4.91105762e+03 4.91090283e+03 4.91087988e+03 4.91091797e+03 4.91086816e+03 4.91091309e+03 4.91094531e+03 4.91138916e+03 4.91157422e+03 4.91120361e+03 4.91091846e+03 4.91089502e+03 4.91092285e+03 4.91090186e+03 4.91095264e+03 4.91094336e+03 4.91094971e+03 4.91102295e+03 4.91105518e+03 4.91097900e+03 4.91091211e+03 4.91098193e+03 4.91125342e+03 4.91206689e+03 4.91200244e+03 4.91139258e+03 4.91097070e+03 4.91097998e+03 4.91094531e+03 4.91089209e+03 4.91096826e+03 4.91132959e+03 4.91174951e+03 4.91248828e+03 4.91248145e+03 4.91175635e+03 4.91123877e+03 4.91091455e+03 4.91107764e+03 4.91142822e+03 4.91109277e+03 4.91099170e+03 4.91133594e+03 4.91098779e+03 4.91090381e+03 4.91090479e+03 4.91089746e+03 4.91090186e+03 4.91088281e+03 4.91085938e+03 4.91090674e+03 4.91097314e+03 4.91097314e+03 4.91103906e+03 4.91107373e+03 4.91107861e+03 4.91104736e+03 4.91101514e+03 4.91089453e+03 4.91098145e+03 4.91096191e+03 4.91092041e+03 4.91106982e+03 4.91088965e+03 4.91103223e+03 4.91093115e+03 4.91142969e+03 4.91140820e+03 4.91091357e+03 4.91137891e+03 4.91106494e+03 4.91095898e+03 4.91092725e+03 4.91125977e+03 4.91132324e+03 4.91114893e+03 4.91088965e+03 4.91094287e+03 4.91092529e+03 4.91093994e+03 4.91093115e+03 4.91095850e+03 4.91114062e+03 4.91093457e+03 4.91106787e+03 4.91156738e+03 4.91123047e+03 4.91100977e+03 4.91120703e+03 4.91164746e+03 4.91180518e+03 4.91133643e+03 4.91098193e+03 4.91104492e+03 4.91102930e+03 4.91117627e+03 4.91100977e+03 4.91115234e+03 4.91155176e+03 4.91180176e+03 4.91166455e+03 4.91101318e+03 4.91096240e+03 4.91093848e+03 4.91090869e+03 4.91091895e+03 4.91102393e+03 4.91175488e+03 4.91148633e+03 4.91086621e+03 4.91117969e+03 4.91105908e+03 4.91086426e+03 4.91097461e+03 4.91126758e+03 4.91134180e+03 4.91106201e+03 4.91090967e+03 4.91093604e+03 4.91093018e+03 4.91091895e+03 4.91087158e+03 4.91088525e+03 4.91087109e+03 4.91094580e+03 4.91109131e+03 4.91092139e+03 4.91088281e+03 4.91089014e+03 4.91090479e+03 4.91088086e+03 4.91105664e+03 4.91142725e+03 4.91104443e+03 4.91094287e+03 4.91150098e+03 4.91104199e+03 4.91090674e+03 4911. 4.91106885e+03 4.91109814e+03 4.91097510e+03 4.91099512e+03 4.91099658e+03 4.91097168e+03 4.91095557e+03 4.91093115e+03 4.91104053e+03 4.91112598e+03 4.91113428e+03 4.91097217e+03 4.91088184e+03 4.91091260e+03 4.91102295e+03 4.91113525e+03 4.91102344e+03 4.91090479e+03 4.91085840e+03 4.91093701e+03 4.91121582e+03 4.91127930e+03 4.91103955e+03 4.91099658e+03 4.91169727e+03 4.91264697e+03 4.91212354e+03 4.91138281e+03 4.91152197e+03 4.91220508e+03 4.91219678e+03 4.91147705e+03 4.91119043e+03 4.91109814e+03 4.91115967e+03 4.91109619e+03 4.91116357e+03 4.91117090e+03 4.91101025e+03 4.91107129e+03 4.91136133e+03 4.91181201e+03 4.91148584e+03 4.91102979e+03 4.91103613e+03 4.91127734e+03 4.91106494e+03 4.91094727e+03 4.91108252e+03 4.91091309e+03 4.91088330e+03 4.91088232e+03 4.91093945e+03 4.91087451e+03 4.91085498e+03 4.91087305e+03 4.91089600e+03 4.91088037e+03 4.91093457e+03 4.91093652e+03 4.91095508e+03 4.91091748e+03 4.91091504e+03 4.91090771e+03 4.91096875e+03 4.91113525e+03 4.91115039e+03 4.91090479e+03 4.91101758e+03 4.91111475e+03 4.91108936e+03 4.91128369e+03 4.91173926e+03 4.91164453e+03 4.91115527e+03 4.91096729e+03 4.91100928e+03 4.91100391e+03 4.91089795e+03 4.91131934e+03 4.91144385e+03 4.91107568e+03 4.91094092e+03 4.91085303e+03 4.91084717e+03 4.91084814e+03 4.91092285e+03 4.91100098e+03 4.91124658e+03 4.91098633e+03 4.91089893e+03 4.91112744e+03 4.91098291e+03 4.91097266e+03 4.91167578e+03 4.91248486e+03 4.91218750e+03 4.91112402e+03 4.91093604e+03 4.91108496e+03 4.91122803e+03 4.91098584e+03 4.91094385e+03 4.91088818e+03 4.91084961e+03 4.91093115e+03 4.91088770e+03 4.91096045e+03 4.91099805e+03 4.91107080e+03 4.91116211e+03 4.91104150e+03 4.91103711e+03 4.91112988e+03 4.91090869e+03 4.91082764e+03 4.91092090e+03 4.91083154e+03 4.91082910e+03 4.91089258e+03 4.91111523e+03 4.91106885e+03 4.91092969e+03 4.91164160e+03 4.91617090e+03 4.92170605e+03 4.93283057e+03 4.93567480e+03 4.91160986e+03 4.91649170e+03 4.94234473e+03 4.92165088e+03 4.92264893e+03 4.91471924e+03 4.91459277e+03 6.71776172e+03 1.36080889e+04 2.39886003e+09 -3.48396134e+10 0. 0. 0. 0. -5.34919168e+09 -5.34919168e+09 1.48798433e+10 1496276224. 4.26402560e+09 3.79046579e+09 3.79046579e+09 4.72276480e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.50911519e+10 -2.59433395e+09 -3.75015654e+09 1.26727936e+10 -1779914880. 1.76587910e+04 8.35927051e+03 6.13339551e+03 6.20443848e+03 6.67652344e+03 4.93809033e+03 4.92862207e+03 4.92862402e+03 4.92848193e+03 4.92837988e+03 4.92855420e+03 4.92883350e+03 4.92846387e+03 4.92823438e+03 4.92851367e+03 4.92816455e+03 4.92914600e+03 4.92909033e+03 4.92814307e+03 4.92886572e+03 4.92909180e+03 4.92842871e+03 4.92852832e+03 4.92931738e+03 4.92933594e+03 4.92848828e+03 4.92810645e+03 4.92852148e+03 4.93072070e+03 4.93127148e+03 4.92941943e+03 4.92820020e+03 4.92807422e+03 4.92812256e+03 4.92831396e+03 4.92878174e+03 4.92892529e+03 4.92823340e+03 4.92910303e+03 4.93100830e+03 4.93003369e+03 4.92828711e+03 4.92816309e+03 4.92815918e+03 4.92814355e+03 4.92829932e+03 4.92830029e+03 4.92852002e+03 4.92886768e+03 4.92847461e+03 4.92833594e+03 4.93029688e+03 4.92993213e+03 4.92816602e+03 4.92884814e+03 4.92846094e+03 4.92820703e+03 4.92824561e+03 4.92836279e+03 4.92835596e+03 4.92823633e+03 4.92891357e+03 4.92858203e+03 4.92828857e+03 4.92942725e+03 4.92893066e+03 4.92825391e+03 4.92817920e+03 4.92824170e+03 4.92824658e+03 4.92820361e+03 4.92861328e+03 4.92848291e+03 4.92824023e+03 4.92827734e+03 4.92869434e+03 4.92896777e+03 4.92861670e+03 4.92822363e+03 4.92827783e+03 4.92832031e+03 4.92814111e+03 4.92815527e+03 4.92815381e+03 4.92847217e+03 4.92992236e+03 4.93089600e+03 4.92899609e+03 4.92836328e+03 4.92930273e+03 4.92861475e+03 4.92825098e+03 4.92977783e+03 4.93069629e+03 4.93005908e+03 4.92961816e+03 4.92978809e+03 4.92908154e+03 4.92820215e+03 4.92848193e+03 4.92826318e+03 4.92829297e+03 4.92850439e+03 4.92822217e+03 4.92818555e+03 4.92825684e+03 4.92809668e+03 4.92825244e+03 4.92823535e+03 4.92822168e+03 4.92848145e+03 4.92992188e+03 4.93031055e+03 4.92881689e+03 4.92815332e+03 4.92809180e+03 4.92854297e+03 4.92950879e+03 4.92958936e+03 4.92867090e+03 4.92813623e+03 4.92812793e+03 4.92817725e+03 4.92820117e+03 4.92816309e+03 4.92821924e+03 4.92817285e+03 4.92895459e+03 4.92890479e+03 4.92820654e+03 4.92812109e+03 4.92819629e+03 4.92840332e+03 4.92854736e+03 4.92825195e+03 4.92850977e+03 4.92925195e+03 4.92959766e+03 4.92840186e+03 4.92865723e+03 4.92985742e+03 4.92872266e+03 4.92814990e+03 4.92826172e+03 4.92815820e+03 4.92818457e+03 4.92814893e+03 4.92811328e+03 4.92845654e+03 4.92944092e+03 4.92994678e+03 4.92868359e+03 4.92829639e+03 4.92906592e+03 4.92827832e+03 4.92816992e+03 4.92822559e+03 4.92808789e+03 4.92822266e+03 4.92926270e+03 4.92916699e+03 4.92818652e+03 4.92842920e+03 4.92814404e+03 4.92992725e+03 4.93209229e+03 4.93036230e+03 4.92834229e+03 4.92810303e+03 4.92815820e+03 4.92814307e+03 4.92822070e+03 4.92813525e+03 4.92868262e+03 4.93033789e+03 4.92920850e+03 4.92819678e+03 4.92826709e+03 4.92820996e+03 4.92814160e+03 4.92833008e+03 4.92855273e+03 4.92861279e+03 4.92909717e+03 4.92970117e+03 4.92925635e+03 4.92817090e+03 4.92836572e+03 4.92833838e+03 4.92832373e+03 4.92928320e+03 4.92901318e+03 4.92819727e+03 4.92814990e+03 4.92818457e+03 4.92822607e+03 4.92912549e+03 4.92965430e+03 4.92836279e+03 4.92833057e+03 4.92856055e+03 4.92810498e+03 4.92837744e+03 4.92877539e+03 4.92864990e+03 4.92827197e+03 4.92811230e+03 4.92812354e+03 4.92817676e+03 4.92842676e+03 4.92819482e+03 4.92819043e+03 4.92859229e+03 4.92848291e+03 4.92814941e+03 4.92811621e+03 4.92810645e+03 4.92809326e+03 4.92811523e+03 4.92816992e+03 4.92813818e+03 4.92852002e+03 4.92907910e+03 4.92921045e+03 4.92818359e+03 4.92818896e+03 4.92814551e+03 4.92852979e+03 4.92884766e+03 4.92828076e+03 4.92814160e+03 4.92815918e+03 4.92821289e+03 4.92816992e+03 4.92814941e+03 4.92824658e+03 4.92828369e+03 4.92858643e+03 4.92826172e+03 4.92816846e+03 4.92820215e+03 4.92831982e+03 4.92820703e+03 4.92815918e+03 4.92811426e+03 4.92813428e+03 4.92810889e+03 4.92828369e+03 4.92837305e+03 4.92855078e+03 4.92882520e+03 4.92898682e+03 4.92816162e+03 4.92809180e+03 4.92813721e+03 4.92831201e+03 4.92820068e+03 4.92813477e+03 4.92825684e+03 4.92888086e+03 4.92910303e+03 4.92817969e+03 4.92813525e+03 4.92819434e+03 4.92842334e+03 4.92855811e+03 4.92850146e+03 4.92824756e+03 4.92822119e+03 4.92838916e+03 4.92827979e+03 4.92817480e+03 4.92857080e+03 4.92890527e+03 4.92866064e+03 4.92828320e+03 4.92825000e+03 4.92820312e+03 4.92845557e+03 4.92886719e+03 4.92860156e+03 4.92899609e+03 4.92882178e+03 4.92828271e+03 4.92833398e+03 4.92824316e+03 4.92863867e+03 4.92898291e+03 4.92848779e+03 4.92824463e+03 4.92821045e+03 4.92835254e+03 4.92842139e+03 4.92823779e+03 4.92813818e+03 4.92820605e+03 4.92820020e+03 4.92831299e+03 4.92847949e+03 4.92844727e+03 4.92817334e+03 4.92817773e+03 4.92824121e+03 4.92850439e+03 4.92859521e+03 4.92860303e+03 4.92974219e+03 4.93092432e+03 4.93080078e+03 4.93000977e+03 4.93009131e+03 4.93138818e+03 4.93192969e+03 4.93082715e+03 4.92889990e+03 4.92849268e+03 4.92836572e+03 4.92864746e+03 4.92855322e+03 4.92817676e+03 4.92825391e+03 4.92838818e+03 4.92817529e+03 4.92823096e+03 4.92846631e+03 4.92841748e+03 4.92855420e+03 4.92884131e+03 4.92929883e+03 4.92913477e+03 4.92901953e+03 4.92983936e+03 4.93088232e+03 4.93035742e+03 4.92903809e+03 4.92883203e+03 4.92869043e+03 4.92819873e+03 4.92827734e+03 4.92831152e+03 4.92827051e+03 4.92819873e+03 4.92827637e+03 4.92864062e+03 4.92863086e+03 4.92830811e+03 4.92839795e+03 4.92872656e+03 4.92815674e+03 4.92858154e+03 4.92860400e+03 4.92818994e+03 4.92830908e+03 4.92816748e+03 4.92820410e+03 4.92866895e+03 4.92885889e+03 4.92825000e+03 4.92820605e+03 4.92843506e+03 4.92837305e+03 4.92835352e+03 4.92862695e+03 4.92869434e+03 4.92880811e+03 4.92815186e+03 4.92815088e+03 4.92815283e+03 4.92825195e+03 4.92811572e+03 4.92838623e+03 4.93056201e+03 4.93126074e+03 4.92901660e+03 4.92823145e+03 4.92949023e+03 4.92830566e+03 4.92868604e+03 4.92888428e+03 4.92823291e+03 4.93075977e+03 4.93004736e+03 4.92818652e+03 4.92852637e+03 4.92837646e+03 4.92824121e+03 4.92812695e+03 4.92820264e+03 4.92858545e+03 4.92868750e+03 4.92819873e+03 4.92817822e+03 4.92845850e+03 4.92892383e+03 4.92875342e+03 4.92828369e+03 4.92845117e+03 4.92851758e+03 4.92822949e+03 4.92900195e+03 4.92902344e+03 4.92854346e+03 4.93040576e+03 4.92958496e+03 4.92813672e+03 4.92854932e+03 4.92844287e+03 4.92820557e+03 4.92843115e+03 4.92856348e+03 4.92814355e+03 4.92814209e+03 4.92815967e+03 4.92829541e+03 4.92856934e+03 4.92815576e+03 4.92814111e+03 4.92891064e+03 4.92897998e+03 4.92859229e+03 4.92823584e+03 4.92917236e+03 4.92979102e+03 4.92863965e+03 4.92862793e+03 4.92991455e+03 4.92883301e+03 4.92849561e+03 4.92920605e+03 4.92824463e+03 4.93018164e+03 4.93015576e+03 4.92822021e+03 4.92853857e+03 4.92837646e+03 4.92825049e+03 4.92821289e+03 4.92827783e+03 4.92885156e+03 4.92938232e+03 4.92934277e+03 4.92973682e+03 4.92974219e+03 4.92858154e+03 4.92822461e+03 4.92852832e+03 4.92819775e+03 4.92863965e+03 4.92838525e+03 4.92839014e+03 4.92978955e+03 4.92893018e+03 4.92817725e+03 4.92838672e+03 4.92811768e+03 4.92860840e+03 4.92846680e+03 4.92814893e+03 4.92872510e+03 4.92944971e+03 4.92848145e+03 4.92865332e+03 4.92828857e+03 4.92839355e+03 4.92828711e+03 4.92866162e+03 4.92956152e+03 4.92889258e+03 4.92822217e+03 4.92840234e+03 4.92825488e+03 4.92844531e+03 4.92970654e+03 4.92876074e+03 4.92816992e+03 4.92892529e+03 4.92864404e+03 4.92818359e+03 4.92824854e+03 4.92826025e+03 4.92820117e+03 4.92829688e+03 4.92850977e+03 4.92912939e+03 4.93027246e+03 4.92972656e+03 4.92837354e+03 4.92820215e+03 4.92826465e+03 4.92814111e+03 4.92832715e+03 4.92906982e+03 4.92967383e+03 4.92841895e+03 4.92856787e+03 4.92933936e+03 4.92827783e+03 4.92859277e+03 4.92862598e+03 4.92819775e+03 4.93013477e+03 4.92963135e+03 4.92814990e+03 4.92969336e+03 4.93062842e+03 4.92881738e+03 4.92810840e+03 4.92813086e+03 4.92842041e+03 4.92871973e+03 4.92824805e+03 4.92822266e+03 4.92824268e+03 4.92825098e+03 4.92822900e+03 4.92824072e+03 4.92823828e+03 4.92819873e+03 4.92840088e+03 4.92974756e+03 4.92925537e+03 4.92814062e+03 4.92960645e+03 4.92887646e+03 4.92817676e+03 4.92933594e+03 4.92931152e+03 4.92815674e+03 4.92862744e+03 4.92930762e+03 4.92826416e+03 4.92816602e+03 4.92832471e+03 4.92830664e+03 4.92813867e+03 4.92820312e+03 4.92818896e+03 4.92877002e+03 4.92938330e+03 4.92953369e+03 4.92876221e+03 4.92817432e+03 4.92837158e+03 4.92815625e+03 4.92904443e+03 4.92956885e+03 4.92859766e+03 4.92814502e+03 4.92811133e+03 4.92825928e+03 4.92980322e+03 4.93009961e+03 4.92849414e+03 4.92816602e+03 4.92849463e+03 4.92810498e+03 4.92859277e+03 4.92860254e+03 4.92818799e+03 4.92837012e+03 4.92848193e+03 4.92837061e+03 4.92817676e+03 4.92833496e+03 4.92844678e+03 4.92810645e+03 4.92896240e+03 4.93006250e+03 4.92869775e+03 4.92808252e+03 4.92850342e+03 4.92826904e+03 4.92836914e+03 4.92866357e+03 4.92836279e+03 4.92807617e+03 4.92813428e+03 4.92826855e+03 4.92904688e+03 4.92901514e+03 4.92822754e+03 4.92812695e+03 4.92807959e+03 4.92819873e+03 4.92929395e+03 4.92910889e+03 4.92910693e+03 4.92847119e+03 4.92819092e+03 4.92806299e+03 4.92807129e+03 4.92823682e+03 4.92873828e+03 4.92843799e+03 4.92806152e+03 4.92838916e+03 4.92812988e+03 4.92829932e+03 4.92871484e+03 4.92814990e+03 4.92896631e+03 4.92998926e+03 4.92874756e+03 4.92847314e+03 4.92978662e+03 4.92903418e+03 4.92845850e+03 4.92890088e+03 4.92974219e+03 4.93115186e+03 4.93158887e+03 4.93096826e+03 6.46852930e+03 9.65063086e+03 1.97187520e+04 1.97271094e+04 1.97292793e+04 1.97198652e+04 2.59868652e+04 4.68962930e+04 1.30109307e+10 -5.16682957e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 1.99497679e+11 -2.04913459e+10 2054114944. 8.75027149e+09 4.96315699e+09 -7.37925171e+09 -1.67584154e+10 1.70177402e+04 7.79543555e+03 4.98944580e+03 4.93637891e+03 4.93225732e+03 4.93079785e+03 4.92885840e+03 4.92844727e+03 4.92890234e+03 4.92847314e+03 4.92839160e+03 4.92909521e+03 4.92881982e+03 4.92818018e+03 4.92899072e+03 4.92900586e+03 4.92859668e+03 4.92830371e+03 4.92826953e+03 4.92816162e+03 4.92810645e+03 4.92823047e+03 4.92828516e+03 4.92808447e+03 4.92863086e+03 4.92821338e+03 4.92903223e+03 4.93079346e+03 4.92876758e+03 4.92812549e+03 4.92880957e+03 4.92833594e+03 4.92856592e+03 4.93070117e+03 4.93219873e+03 4.92921240e+03 4.92824805e+03 4.92822021e+03 4.92915430e+03 4.93028857e+03 4.92928174e+03 4.92897705e+03 4.92842139e+03 4.92809375e+03 4.92807031e+03 4.92815820e+03 4.93026123e+03 4.93062061e+03 4.92838135e+03 4.92851416e+03 4.92901465e+03 4.92811230e+03 4.92915918e+03 4.92896533e+03 4.92811133e+03 4.92811572e+03 4.92846094e+03 4.93111426e+03 4.93258057e+03 4.93104443e+03 4.92825342e+03 4.92835400e+03 4.92838818e+03 4.92815625e+03 4.92978809e+03 4.93208398e+03 4.93339111e+03 4.93173828e+03 4.92985400e+03 4.92871533e+03 4.92839648e+03 4.92858789e+03 4.92839551e+03 4.92808252e+03 4.92883203e+03 4.92881689e+03 4.92811084e+03 4.92867871e+03 4.92856689e+03 4.92816455e+03 4.92825293e+03 4.92869434e+03 4.92831982e+03 4.92851123e+03 4.92951123e+03 4.92839014e+03 4.92820312e+03 4.92817578e+03 4.92826172e+03 4.92836719e+03 4.92819092e+03 4.92822900e+03 4.92826465e+03 4.92810449e+03 4.92814990e+03 4.92813574e+03 4.92915918e+03 4.92939600e+03 4.92813721e+03 4.92946387e+03 4.93070264e+03 4.92861719e+03 4.92819873e+03 4.92843604e+03 4.92825928e+03 4.92813721e+03 4.92811816e+03 4.92816943e+03 4.92866357e+03 4.92919336e+03 4.92833643e+03 4.92847217e+03 4.92886865e+03 4.92844482e+03 4.92806689e+03 4.92810107e+03 4.92825732e+03 4.92824609e+03 4.92831641e+03 4.93010742e+03 4.92991650e+03 4.92811963e+03 4.92829199e+03 4.92816016e+03 4.92992334e+03 4.93037793e+03 4.92837891e+03 4.92829004e+03 4.92857080e+03 4.92815088e+03 4.92826465e+03 4.92907812e+03 4.92874170e+03 4.92811719e+03 4.92851025e+03 4.92813623e+03 4.92855176e+03 4.92887891e+03 4.92848633e+03 4.92812793e+03 4.92806787e+03 4.92833105e+03 4.92872900e+03 4.92837793e+03 4.92810303e+03 4.92810254e+03 4.92851562e+03 4.92894873e+03 4.92832617e+03 4.92894287e+03 4.93083203e+03 4.92986572e+03 4.92810986e+03 4.92874902e+03 4.92841846e+03 4.92818066e+03 4.92825049e+03 4.92823438e+03 4.92814111e+03 4.92841553e+03 4.92821338e+03 4.92820166e+03 4.92822803e+03 4.92881689e+03 4.92925928e+03 4.92963379e+03 4.92828125e+03 4.92812012e+03 4.92825879e+03 4.92890527e+03 4.92867383e+03 4.92830322e+03 4.92892725e+03 4.92843994e+03 4.92808252e+03 4.92827051e+03 4.92824707e+03 4.92817139e+03 4.92811377e+03 4.92813086e+03 4.92823291e+03 4.92823389e+03 4.92816406e+03 4.92845605e+03 4.92948096e+03 4.93067041e+03 4.93203418e+03 4.92968506e+03 4.92813721e+03 4.92814355e+03 4.92817383e+03 4.92830957e+03 4.92838184e+03 4.92809961e+03 4.92919043e+03 4.92999805e+03 4.92821289e+03 4.92910596e+03 4.93070947e+03 4.92963574e+03 4.92852246e+03 4.92824316e+03 4.92835254e+03 4.92860840e+03 4.92930908e+03 4.92869141e+03 4.92821094e+03 4.92813867e+03 4.92815967e+03 4.92824609e+03 4.92841650e+03 4.92884521e+03 4.92902148e+03 4.92849219e+03 4.92821484e+03 4.92825195e+03 4.92828125e+03 4.92812109e+03 4.92833496e+03 4.92861084e+03 4.92897754e+03 4.92845410e+03 4.92827100e+03 4.92845605e+03 4.92885645e+03 4.92835498e+03 4.92828467e+03 4.92854199e+03 4.92812305e+03 4.92820654e+03 4.92811523e+03 4.92815771e+03 4.92809375e+03 4.92812402e+03 4.92810938e+03 4.92813721e+03 4.92812354e+03 4.92813525e+03 4.92810840e+03 4.92808643e+03 4.92833447e+03 4.92834180e+03 4.92824414e+03 4.92817773e+03 4.92816943e+03 4.92819238e+03 4.92812549e+03 4.92816211e+03 4.92812842e+03 4.92822656e+03 4.92834131e+03 4.92826123e+03 4.92813916e+03 4.92811572e+03 4.92812305e+03 4.92808545e+03 4.92812500e+03 4.92811328e+03 4.92814062e+03 4.92815430e+03 4.92817139e+03 4.92819238e+03 4.92816992e+03 4.92809229e+03 4.92822217e+03 4.92817969e+03 4.92830713e+03 4.92828223e+03 4.92829541e+03 4.92815234e+03 4.92816748e+03 4.92812305e+03 4.92817090e+03 4.92820947e+03 4.92816699e+03 4.92812305e+03 4.92813379e+03 4.92815869e+03 4.92817041e+03 4.92818359e+03 4.92814648e+03 4.92818457e+03 4.92819824e+03 4.92811426e+03 4.92817188e+03 4.92812744e+03 4.92817432e+03 4.92819727e+03 4.92813330e+03 4.92813037e+03 4.92809863e+03 4.92815088e+03 4.92816455e+03 4.92824268e+03 4.92824902e+03 4.92812939e+03 4.92817920e+03 4.92817871e+03 4.92812842e+03 4.92817627e+03 4.92813086e+03 4.92819482e+03 4.92816504e+03 4.92810693e+03 4.92809473e+03 4.92818359e+03 4.92821484e+03 4.92815039e+03 4.92815039e+03 4.92823535e+03 4.92833887e+03 4.92821191e+03 4.92819434e+03 4.92820068e+03 4.92816895e+03 4.92815234e+03 4.92814111e+03 4.92819336e+03 4.92810059e+03 4.92823047e+03 4.92809619e+03 4.92822119e+03 4.92819873e+03 4.92817090e+03 4.92810010e+03 4.92810352e+03 4.92810010e+03 4.92814404e+03 4.92806348e+03 4.92816699e+03 4.92812500e+03 4.92816553e+03 4.92827783e+03 4.92819727e+03 4.92812402e+03 4.92811768e+03 4.92816553e+03 4.92811182e+03 4.92813135e+03 4.92811035e+03 4.92816553e+03 4.92829785e+03 4.92825537e+03 4.92814014e+03 4.92818213e+03 4.92819336e+03 4.92823047e+03 4.92817334e+03 4.92817676e+03 4.92815039e+03 4.92819775e+03 4.92820312e+03 4.92825439e+03 4.92822461e+03 4.92823047e+03 4.92812158e+03 4.92813086e+03 4.92811768e+03 4.92814404e+03 4.92808105e+03 4.92813721e+03 4.92808105e+03 4.92815137e+03 4.92812793e+03 4.92814014e+03 4.92819971e+03 4.92859277e+03 4.92840527e+03 4.92818213e+03 4.92813818e+03 4.92812549e+03 4.92827393e+03 4.92834766e+03 4.92825977e+03 4.92812061e+03 4.92805762e+03 4.92820410e+03 4.92828320e+03 4.92830615e+03 4.92818359e+03 4.92824463e+03 4.92851318e+03 4.92881592e+03 4.92845459e+03 4.92813574e+03 4.92808447e+03 4.92812939e+03 4.92819873e+03 4.92817090e+03 4.92813428e+03 4.92811719e+03 4.92814941e+03 4.92826709e+03 4.92830859e+03 4.92814404e+03 4.92817871e+03 4.92811426e+03 4.92816406e+03 4.92815430e+03 4.92816064e+03 4.92850439e+03 4.92869922e+03 4.92828857e+03 4.92810498e+03 4.92811963e+03 4.92811914e+03 4.92821777e+03 4.92838721e+03 4.92809912e+03 4.92847754e+03 4.92871582e+03 4.92824121e+03 4.92816309e+03 4.92819336e+03 4.92810059e+03 4.92810742e+03 4.92819434e+03 4.92818701e+03 4.92812842e+03 4.92822510e+03 4.92817139e+03 4.92821094e+03 4.92810547e+03 4.92848486e+03 4.92856494e+03 4.92822461e+03 4.92806006e+03 4.92811865e+03 4.92827637e+03 4.92829248e+03 4.92810742e+03 4.92805713e+03 4.92814209e+03 4.92806104e+03 4.92810010e+03 4.92807373e+03 4.92811426e+03 4.92814844e+03 4.92825830e+03 4.92820361e+03 4.92856689e+03 4.92838965e+03 4.93413379e+03 4.94188330e+03 4.96901025e+03 6.66060889e+03 9.88794141e+03 1.97195273e+04 1.97191621e+04 1.97217734e+04 1.97360195e+04 1.97281738e+04 1.97159180e+04 1.97217812e+04 1.97777188e+04 2.98241680e+04 6.08275664e+04 -2.84861727e+10 -2.14535475e+10 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. 0. 9.98637875e+09 9.98637875e+09 9.98637875e+09 0. 0. 1.78115625e+10 -5.32207514e+09 -2.80256666e+09 -3.22159027e+09 1.51473203e+10 -5.95052851e+09 -3.65578675e+09 1.68959727e+04 7.78129736e+03 4.97768506e+03 4.93374756e+03 4.92878857e+03 4.92868701e+03 4.92860938e+03 4.92855713e+03 4.92849707e+03 4.92851416e+03 4.92864404e+03 4.92870898e+03 4.92868896e+03 4.92835938e+03 4.92826025e+03 4.92827441e+03 4.92857227e+03 4.92847754e+03 4.92821143e+03 4.92806445e+03 4.92806104e+03 4.92808350e+03 4.92811230e+03 4.92816113e+03 4.92820459e+03 4.92824854e+03 4.92836426e+03 4.92837891e+03 4.92835400e+03 4.92820850e+03 4.92816943e+03 4.92825195e+03 4.92839014e+03 4.92853125e+03 4.92832520e+03 4.92819629e+03 4.92820459e+03 4.92831592e+03 4.92834424e+03 4.92841553e+03 4.92839453e+03 4.92827686e+03 4.92807568e+03 4.92807568e+03 4.92809521e+03 4.92811279e+03 4.92806738e+03 4.92814746e+03 4.92814307e+03 4.92802930e+03 4.92805713e+03 4.92805762e+03 4.92813477e+03 4.92816943e+03 4.92817969e+03 4.92831787e+03 4.92813867e+03 4.92808984e+03 4.92804980e+03 4.92813623e+03 4.92812744e+03 4.92812939e+03 4.92813428e+03 4.92806152e+03 4.92805566e+03 4.92805078e+03 4.92810498e+03 4.92822168e+03 4.92816553e+03 4.92814844e+03 4.92806885e+03 4.92808594e+03 4.92805859e+03 4.92829980e+03 4.92828369e+03 4.92822363e+03 4.92808105e+03 4.92843750e+03 4.92906885e+03 4.92902930e+03 4.92857812e+03 4.92827295e+03 4.92832520e+03 4.92832373e+03 4.92819629e+03 4.92821582e+03 4.92858447e+03 4.92921924e+03 4.92901904e+03 4.92833740e+03 4.92803662e+03 4.92810791e+03 4.92813770e+03 4.92813428e+03 4.92811865e+03 4.92809668e+03 4.92810156e+03 4.92808154e+03 4.92813525e+03 4.92811621e+03 4.92808008e+03 4.92815430e+03 4.92811670e+03 4.92828760e+03 4.92819482e+03 4.92808105e+03 4.92818018e+03 4.92822949e+03 4.92822900e+03 4.92816309e+03 4.92809912e+03 4.92808057e+03 4.92809229e+03 4.92811133e+03 4.92808545e+03 4.92800830e+03 4.92804199e+03 4.92798438e+03 4.92807812e+03 4.92807324e+03 4.92813428e+03 4.92806934e+03 4.92816162e+03 4.92849902e+03 4.92855176e+03 4.92820654e+03 4.92806787e+03 4.92818555e+03 4.92857275e+03 4.92858838e+03 4.92828027e+03 4.92814258e+03 4.92811475e+03 4.92809668e+03 4.92805908e+03 4.92804590e+03 4.92806201e+03 4.92803174e+03 4.92806836e+03 4.92804590e+03 4.92805518e+03 4.92804785e+03 4.92803418e+03 4.92812988e+03 4.92805176e+03 4.92808545e+03 4.92812695e+03 4.92843799e+03 4.92916406e+03 4.92912354e+03 4.92862207e+03 4.92819971e+03 4.92842139e+03 4.92886328e+03 4.92869580e+03 4.92825732e+03 4.92801270e+03 4.92809180e+03 4.92807275e+03 4.92813086e+03 4.92812012e+03 4.92809717e+03 4.92814893e+03 4.92812939e+03 4.92813086e+03 4.92819336e+03 4.92842871e+03 4.92832031e+03 4.92814990e+03 4.92803418e+03 4.92803809e+03 4.92804395e+03 4.92805127e+03 4.92835645e+03 4.92831494e+03 4.92818994e+03 4.92807031e+03 4.92811182e+03 4.92809961e+03 4.92807666e+03 4.92850049e+03 4.92859863e+03 4.92830469e+03 4.92810107e+03 4.92810254e+03 4.92813330e+03 4.92809180e+03 4.92806641e+03 4.92812988e+03 4.92816699e+03 4.92848047e+03 4.92886523e+03 4.92884814e+03 4.92841016e+03 4.92805762e+03 4.92819189e+03 4.92816016e+03 4.92842627e+03 4.92874561e+03 4.92857422e+03 4.92814209e+03 4.92811523e+03 4.92809229e+03 4.92811328e+03 4.92808936e+03 4.92799707e+03 4.92804053e+03 4.92806543e+03 4.92807178e+03 4.92804150e+03 4.92801270e+03 4.92802979e+03 4.92799609e+03 4.92814844e+03 4.92815771e+03 4.92829150e+03 4.92827002e+03 4.92816064e+03 4.92815576e+03 4.92813232e+03 4.92819141e+03 4.92810645e+03 4.92807861e+03 4.92816797e+03 4.92813574e+03 4.92816162e+03 4.92808203e+03 4.92814062e+03 4.92816113e+03 4.92815820e+03 4.92808984e+03 4.92811719e+03 4.92809668e+03 4.92809424e+03 4.92807422e+03 4.92803564e+03 4.92811475e+03 4.92806738e+03 4.92816455e+03 4.92835205e+03 4.92813623e+03 4.92818262e+03 4.92846289e+03 4.92832520e+03 4.92805371e+03 4.92806885e+03 4.92813379e+03 4.92814648e+03 4.92818750e+03 4.92812598e+03 4.92814795e+03 4.92810352e+03 4.92808008e+03 4.92806738e+03 4.92813037e+03 4.92800293e+03 4.92805273e+03 4.92801855e+03 4.92810254e+03 4.92804932e+03 4.92808252e+03 4.92807812e+03 4.92806006e+03 4.92812451e+03 4.92806885e+03 4.92817969e+03 4.92845361e+03 4.92846143e+03 4.92819043e+03 4.92806836e+03 4.92807178e+03 4.92805322e+03 4.92811182e+03 4.92825098e+03 4.92832178e+03 4.92849170e+03 4.92826562e+03 4.92811719e+03 4.92809277e+03 4.92806641e+03 4.92804639e+03 4.92808252e+03 4.92809570e+03 4.92811572e+03 4.92811328e+03 4.92804688e+03 4.92805957e+03 4.92808154e+03 4.92815625e+03 4.92810449e+03 4.92831299e+03 4.92865088e+03 4.92852734e+03 4.92815576e+03 4.92803027e+03 4.92809668e+03 4.92810938e+03 4.92809033e+03 4.92810400e+03 4.92819824e+03 4.92852539e+03 4.92855518e+03 4.92816113e+03 4.92803418e+03 4.92807080e+03 4.92807471e+03 4.92808838e+03 4.92809473e+03 4.92811426e+03 4.92805322e+03 4.92801465e+03 4.92807617e+03 4.92811865e+03 4.92820557e+03 4.92810986e+03 4.92807275e+03 4.92805908e+03 4.92806787e+03 4.92824902e+03 4.92828467e+03 4.92838574e+03 4.92856738e+03 4.92910107e+03 4.92920850e+03 4.92895703e+03 4.92889111e+03 4.92853174e+03 4.92850342e+03 4.92816162e+03 4.92806689e+03 4.92836572e+03 4.92846729e+03 4.92822412e+03 4.92818018e+03 4.92809668e+03 4.92810400e+03 4.92804346e+03 4.92805029e+03 4.92810254e+03 4.92798047e+03 4.92820557e+03 4.92832910e+03 4.92819580e+03 4.92802783e+03 4.92801172e+03 4.92801904e+03 4.92808105e+03 4.92809912e+03 4.92809863e+03 4.92806592e+03 4.92811426e+03 4.92824902e+03 4.92873438e+03 4.92834814e+03 4.92807568e+03 4.92802295e+03 4.92827002e+03 4.92827295e+03 4.92818652e+03 4.92800684e+03 4.92814062e+03 4.92842041e+03 4.92848779e+03 4.92828271e+03 4.92805713e+03 4.92834619e+03 4.92888428e+03 4.92871631e+03 4.92819238e+03 4.92804980e+03 4.92811670e+03 4.92830078e+03 4.92809082e+03 4.92812988e+03 4.92806885e+03 4.92822559e+03 4.92855176e+03 4.92843457e+03 4.92830420e+03 4.92831348e+03 4.92855615e+03 4.92912012e+03 4.92889502e+03 4.92822705e+03 4.92802490e+03 4.92807666e+03 4.92805127e+03 4.92810498e+03 4.92807666e+03 4.92802588e+03 4.92805664e+03 4.92810156e+03 4.92813867e+03 4.92805908e+03 4.92802588e+03 4.92803320e+03 4.92820947e+03 4.92841797e+03 4.92824219e+03 4.92818799e+03 4.92801611e+03 4.92807422e+03 4.92801709e+03 4.92808105e+03 4.92810596e+03 4.92809131e+03 4.92823584e+03 4.92884814e+03 4.92828369e+03 4.92819727e+03 4.92812646e+03 4.92814307e+03 4.92833398e+03 4.92815674e+03 4.92804297e+03 4.92809766e+03 4.92815283e+03 4.92817383e+03 4.92809766e+03 4.92807617e+03 4.92809912e+03 4.92817676e+03 4.92807080e+03 4.92808301e+03 4.92803809e+03 4.92803516e+03 4.92811279e+03 4.92829590e+03 4.92834619e+03 4.92811865e+03 4.92811084e+03 4.92863867e+03 4.92939551e+03 4.92891309e+03 4.92819287e+03 4.92816748e+03 4.92841309e+03 4.92816992e+03 4.92809033e+03 4.92816992e+03 4.92805518e+03 4.92813184e+03 4.92812939e+03 4.92808203e+03 4.92811572e+03 4.92817090e+03 4.92821631e+03 4.92814893e+03 4.92806787e+03 4.92803711e+03 4.92803857e+03 4.92808838e+03 4.92804541e+03 4.92816943e+03 4.92827490e+03 4.92833887e+03 4.92839600e+03 4.92842725e+03 4.92832861e+03 4.92818311e+03 4.92816357e+03 4.92838037e+03 4.92840234e+03 4.92836328e+03 4.92852100e+03 4.92952734e+03 4.93051611e+03 4.92966992e+03 4.92849268e+03 4.92823779e+03 4.92846533e+03 4.92850049e+03 4.92818115e+03 4.92807275e+03 4.92803662e+03 4.92803418e+03 4.92802490e+03 4.92816357e+03 4.92814600e+03 4.92807129e+03 4.92809619e+03 4.92827051e+03 4.92872266e+03 4.92830664e+03 4.92813330e+03 4.92830859e+03 4.92867188e+03 4.92827783e+03 4.92815723e+03 4.92859766e+03 4.92845166e+03 4.92841211e+03 4.92822852e+03 4.92825293e+03 4.92822998e+03 4.92822363e+03 4.92809131e+03 4.92807178e+03 4.92810059e+03 4.92817334e+03 4.92804736e+03 4.92827197e+03 4.92890088e+03 4.92903711e+03 4.92888330e+03 4.92846924e+03 4.92824951e+03 4.92806299e+03 4.92811572e+03 4.92808740e+03 4.92808203e+03 4.92804590e+03 4.92807666e+03 4.92808057e+03 4.92804248e+03 4.92801318e+03 4.92804785e+03 4.92803174e+03 4.92804980e+03 4.92827539e+03 4.92869971e+03 4.92882227e+03 4.92832910e+03 4.92813379e+03 4.92813037e+03 4.92819482e+03 4.92815332e+03 4.92806934e+03 4.92805908e+03 4.92808691e+03 4.92824902e+03 4.92868896e+03 4.92845703e+03 4.92815674e+03 4.92808057e+03 4.92868799e+03 4.92943701e+03 4.92889551e+03 4.92816895e+03 4.92815479e+03 4.92861377e+03 4.92853418e+03 4.92821924e+03 4.92809082e+03 4.92820459e+03 4.92856494e+03 4.92902979e+03 4.92932373e+03 4.92854199e+03 4.92816992e+03 4.92817822e+03 4.92912939e+03 4.92975342e+03 4.92864355e+03 4.92807178e+03 4.92808887e+03 4.92879297e+03 4.92889893e+03 4.92857080e+03 4.92816602e+03 4.92839941e+03 4.92890625e+03 4.92912988e+03 4.92874609e+03 4.92836914e+03 4.92822607e+03 4.92859277e+03 4.92923193e+03 4.92932178e+03 4.92881201e+03 4.92821777e+03 4.92835156e+03 4.92865625e+03 4.92867969e+03 4.92839795e+03 4.92832373e+03 4.92887012e+03 4.92871484e+03 4.92829883e+03 4.92814600e+03 4.92811865e+03 4.92820117e+03 4.92816699e+03 4.92843408e+03 4.92866455e+03 4.92843994e+03 4.92827637e+03 4.92822900e+03 4.92822705e+03 4.92832568e+03 4.92880029e+03 4.93188281e+03 4.93695459e+03 4.93308301e+03 4.93734375e+03 4.94772412e+03 4.95342529e+03 4.94837842e+03 4.92847705e+03 4.92883984e+03 6.35151270e+03 9.66165332e+03 1.99261543e+04 2.00762051e+04 2.07167090e+04 3.43883828e+04 163293264. 0. 0. 0. 0. 0. 0. -7.72886989e+09 -7.72886989e+09 6.19589258e+04 6.50181992e+04 6.50181992e+04 4.72276480e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5196013. 2.97600469e+04 1.00754023e+04 6.81062012e+03 4.96288379e+03 4.94748584e+03 4.91772510e+03 4.91520312e+03 4.91555225e+03 4.91577637e+03 4.91502344e+03 4.91496045e+03 4.91508252e+03 4.91490137e+03 4.91521484e+03 4.91604199e+03 4.91523633e+03 4.91544141e+03 4.91646387e+03 4.91562256e+03 4.91492139e+03 4.91508398e+03 4.91498730e+03 4.91495361e+03 4.91506006e+03 4.91544043e+03 4.91515137e+03 4.91504688e+03 4.91539014e+03 4.91506250e+03 4.91499805e+03 4.91515137e+03 4.91495605e+03 4.91549805e+03 4.91599658e+03 4.91538086e+03 4.91537207e+03 4.91610693e+03 4.91558301e+03 4.91490967e+03 4.91540576e+03 4.91498535e+03 4.91698438e+03 4.91789648e+03 4.91599658e+03 4.91507373e+03 4.91495508e+03 4.91497656e+03 4.91497998e+03 4.91494482e+03 4.91493896e+03 4.91496191e+03 4.91610498e+03 4.91778760e+03 4.91702930e+03 4.91516309e+03 4.91495508e+03 4.91500781e+03 4.91567383e+03 4.91616406e+03 4.91537891e+03 4.91520508e+03 4.91539502e+03 4.91508740e+03 4.91492383e+03 4.91556787e+03 4.91546777e+03 4.91506982e+03 4.91533594e+03 4.91504102e+03 4.91503662e+03 4.91500391e+03 4.91528223e+03 4.91509424e+03 4.91499951e+03 4.91517139e+03 4.91500977e+03 4.91564746e+03 4.91610107e+03 4.91567773e+03 4.91493555e+03 4.91516455e+03 4.91505664e+03 4.91495898e+03 4.91494482e+03 4.91516211e+03 4.91510010e+03 4.91498828e+03 4.91518213e+03 4.91491504e+03 4.91581396e+03 4.91611035e+03 4.91505371e+03 4.91521826e+03 4.91528906e+03 4.91493359e+03 4.91497607e+03 4.91493750e+03 4.91503613e+03 4.91609277e+03 4.91729053e+03 4.91570410e+03 4.91506836e+03 4.91568359e+03 4.91531885e+03 4.91491699e+03 4.91550879e+03 4.91634082e+03 4.91607959e+03 4.91557617e+03 4.91571143e+03 4.91557373e+03 4.91495654e+03 4.91522803e+03 4.91494482e+03 4.91568018e+03 4.91666064e+03 4.91576611e+03 4.91499463e+03 4.91529443e+03 4.91492969e+03 4.91501904e+03 4.91505127e+03 4.91498828e+03 4.91530762e+03 4.91710547e+03 4.91680420e+03 4.91529443e+03 4.91500684e+03 4.91498047e+03 4.91505518e+03 4.91556201e+03 4.91562988e+03 4.91534961e+03 4.91500537e+03 4.91494727e+03 4.91525537e+03 4.91552490e+03 4.91509961e+03 4.91495117e+03 4.91487500e+03 4.91501367e+03 4.91498730e+03 4.91493506e+03 4.91491211e+03 4.91493750e+03 4.91527441e+03 4.91547217e+03 4.91495605e+03 4.91491602e+03 4.91498438e+03 4.91533691e+03 4.91506885e+03 4.91559668e+03 4.91678760e+03 4.91539062e+03 4.91507324e+03 4.91530859e+03 4.91495801e+03 4.91500732e+03 4.91495410e+03 4.91498291e+03 4.91531592e+03 4.91632812e+03 4.91663232e+03 4.91607227e+03 4.91503564e+03 4.91502246e+03 4.91500146e+03 4.91501367e+03 4.91499219e+03 4.91500391e+03 4.91500195e+03 4.91597314e+03 4.91578174e+03 4.91513086e+03 4.91495557e+03 4.91542285e+03 4.91793359e+03 4.91979688e+03 4.91770312e+03 4.91544580e+03 4.91497021e+03 4.91499268e+03 4.91496582e+03 4.91499072e+03 4.91496484e+03 4.91530273e+03 4.91676562e+03 4.91677100e+03 4.91542480e+03 4.91521045e+03 4.91597168e+03 4.91546973e+03 4.91504834e+03 4.91552344e+03 4.91543604e+03 4.91582422e+03 4.91647852e+03 4.91611133e+03 4.91508496e+03 4.91515283e+03 4.91501416e+03 4.91586768e+03 4.91725928e+03 4.91571240e+03 4.91503076e+03 4.91537158e+03 4.91498584e+03 4.91526221e+03 4.91503125e+03 4.91506250e+03 4.91502539e+03 4.91518164e+03 4.91555713e+03 4.91493994e+03 4.91557715e+03 4.91599902e+03 4.91524854e+03 4.91497559e+03 4.91496240e+03 4.91501172e+03 4.91509180e+03 4.91498340e+03 4.91508740e+03 4.91545605e+03 4.91536816e+03 4.91519189e+03 4.91496143e+03 4.91498389e+03 4.91496143e+03 4.91492822e+03 4.91498242e+03 4.91499902e+03 4.91493408e+03 4.91522070e+03 4.91550928e+03 4.91523145e+03 4.91523389e+03 4.91605029e+03 4.91585156e+03 4.91500146e+03 4.91565234e+03 4.91571924e+03 4.91505615e+03 4.91494824e+03 4.91512402e+03 4.91515088e+03 4.91494873e+03 4.91495166e+03 4.91496387e+03 4.91519678e+03 4.91499365e+03 4.91583447e+03 4.91548828e+03 4.91499756e+03 4.91490576e+03 4.91500391e+03 4.91536523e+03 4.91490576e+03 4.91495850e+03 4.91540479e+03 4.91506348e+03 4.91499463e+03 4.91535742e+03 4.91579346e+03 4.91507910e+03 4.91490576e+03 4.91496533e+03 4.91504053e+03 4.91520068e+03 4.91514014e+03 4.91531445e+03 4.91579102e+03 4.91618750e+03 4.91503027e+03 4.91489893e+03 4.91493652e+03 4.91524316e+03 4.91511230e+03 4.91493896e+03 4.91496533e+03 4.91514551e+03 4.91501074e+03 4.91510693e+03 4.91504736e+03 4.91525830e+03 4.91571289e+03 4.91559180e+03 4.91528613e+03 4.91498486e+03 4.91507715e+03 4.91537354e+03 4.91523145e+03 4.91511475e+03 4.91523193e+03 4.91511719e+03 4.91497412e+03 4.91510352e+03 4.91494092e+03 4.91544775e+03 4.91626270e+03 4.91556982e+03 4.91501123e+03 4.91509375e+03 4.91497119e+03 4.91526514e+03 4.91544971e+03 4.91497021e+03 4.91500049e+03 4.91490918e+03 4.91523828e+03 4.91552881e+03 4.91578809e+03 4.91508984e+03 4.91494971e+03 4.91516016e+03 4.91584326e+03 4.91535449e+03 4.91494629e+03 4.91495996e+03 4.91518994e+03 4.91519629e+03 4.91498340e+03 4.91495703e+03 4.91543311e+03 4.91601221e+03 4.91565430e+03 4.91496143e+03 4.91494434e+03 4.91504297e+03 4.91553516e+03 4.91523096e+03 4.91497412e+03 4.91506641e+03 4.91503516e+03 4.91554297e+03 4.91568555e+03 4.91567969e+03 4.91524170e+03 4.91507373e+03 4.91535352e+03 4.91571240e+03 4.91546680e+03 4.91499756e+03 4.91495850e+03 4.91496387e+03 4.91510107e+03 4.91559766e+03 4.91525977e+03 4.91496045e+03 4.91496338e+03 4.91504248e+03 4.91537109e+03 4.91494434e+03 4.91493848e+03 4.91502686e+03 4.91534131e+03 4.91555371e+03 4.91525781e+03 4.91512305e+03 4.91535645e+03 4.91492236e+03 4.91534375e+03 4.91506348e+03 4.91527832e+03 4.91587012e+03 4.91516846e+03 4.91495215e+03 4.91495508e+03 4.91501709e+03 4.91546826e+03 4.91618311e+03 4.91778369e+03 4.91689453e+03 4.91566357e+03 4.91543652e+03 4.91603906e+03 4.91685107e+03 4.91524072e+03 4.91498438e+03 4.91491846e+03 4.91501025e+03 4.91497510e+03 4.91528467e+03 4.91714355e+03 4.91796777e+03 4.91597803e+03 4.91503760e+03 4.91546973e+03 4.91506934e+03 4.91682910e+03 4.91713818e+03 4.91540723e+03 4.91498193e+03 4.91522900e+03 4.91632129e+03 4.91701318e+03 4.91594531e+03 4.91490723e+03 4.91497217e+03 4.91504883e+03 4.91613428e+03 4.91839648e+03 4.91810156e+03 4.91700146e+03 4.91510889e+03 4.91531055e+03 4.91589990e+03 4.91515234e+03 4.91587939e+03 4.91768652e+03 4.91598584e+03 4.91492432e+03 4.91502783e+03 4.91633252e+03 4.91918750e+03 4.91781787e+03 4.91526465e+03 4.91501416e+03 4.91509375e+03 4.91509033e+03 4.91582422e+03 4.91663916e+03 4.91543994e+03 4.91511963e+03 4.91500342e+03 4.91533252e+03 4.91565869e+03 4.91510010e+03 4.91495850e+03 4.91576660e+03 4.91591357e+03 4.91515820e+03 4.91500098e+03 4.91624268e+03 4.91666309e+03 4.91531738e+03 4.91560059e+03 4.91702051e+03 4.91566943e+03 4.91531836e+03 4.91655469e+03 4.91594336e+03 4.91507959e+03 4.91508008e+03 4.91558350e+03 4.91607227e+03 4.91613477e+03 4.91517920e+03 4.91496582e+03 4.91510938e+03 4.91508203e+03 4.91495898e+03 4.91511865e+03 4.91557568e+03 4.91529297e+03 4.91498779e+03 4.91513574e+03 4.91512256e+03 4.91499219e+03 4.91549951e+03 4.91518311e+03 4.91497656e+03 4.91514014e+03 4.91501758e+03 4.91579492e+03 4.91591260e+03 4.91517139e+03 4.91512695e+03 4.91520117e+03 4.91497559e+03 4.91559131e+03 4.91624463e+03 4.91510205e+03 4.91494531e+03 4.91497803e+03 4.91500244e+03 4.91499365e+03 4.91513135e+03 4.91496436e+03 4.91504980e+03 4.91511914e+03 4.91498242e+03 4.91496729e+03 4.91591455e+03 4.91649463e+03 4.91551172e+03 4.91511230e+03 4.91695654e+03 4.91652051e+03 4.91496973e+03 4.91594922e+03 4.91658643e+03 4.91510010e+03 4.91505859e+03 4.91527539e+03 4.91497217e+03 4.91568701e+03 4.91530713e+03 4.91493848e+03 4.91538330e+03 4.91556250e+03 4.91521582e+03 4.91496094e+03 4.91542773e+03 4.91531836e+03 4.91487158e+03 4.91579248e+03 4.91603564e+03 4.91506738e+03 4.91537988e+03 4.91512305e+03 4.91500293e+03 4.91566650e+03 4.91532568e+03 4.91494775e+03 4.91492041e+03 4.91500195e+03 4.91491260e+03 4.91495898e+03 4.91491699e+03 4.91495166e+03 4.91504541e+03 4.91490137e+03 4.91499658e+03 4.91559326e+03 4.91616846e+03 4.91557227e+03 4.91504785e+03 4.91504932e+03 4.91538916e+03 4.91498975e+03 4.91504688e+03 4.91522363e+03 4.91498096e+03 4.91585986e+03 4.91575342e+03 4.91503857e+03 4.91514893e+03 4.91537256e+03 4.91502686e+03 4.91497314e+03 4.91493555e+03 4.91515479e+03 4.91591748e+03 4.91699072e+03 4.91656787e+03 4.91517627e+03 4.91526123e+03 4.91563379e+03 4.91739258e+03 4.91755518e+03 4.91688770e+03 4.91588525e+03 4.91495459e+03 4.91507324e+03 4.91499414e+03 4.91516504e+03 4.91575586e+03 4.91507959e+03 4.91518994e+03 4.91513428e+03 4.91504443e+03 4.91606152e+03 4.91564014e+03 4.91495020e+03 4.91534668e+03 4.91541260e+03 4.91486670e+03 4.91547949e+03 4.91593457e+03 4.91576367e+03 4.91524268e+03 4.91501270e+03 4.91490723e+03 4.91495068e+03 4.91490479e+03 4.91497656e+03 4.91493457e+03 4.91547949e+03 4.91634473e+03 4.91536230e+03 4.91501172e+03 4.91568799e+03 4.91507764e+03 4.91533594e+03 4.91561377e+03 4.91499609e+03 4.91516113e+03 4.91533936e+03 4.91494336e+03 4.91498389e+03 4.91496924e+03 4.91497412e+03 4.91511133e+03 4.91503906e+03 4.91495557e+03 4.91504932e+03 4.91501221e+03 4.91493994e+03 4.91523682e+03 4.91615332e+03 4.91595605e+03 4.91532080e+03 4.91498633e+03 4.91526660e+03 4.91530420e+03 4.91535303e+03 4.91851611e+03 4.92112256e+03 4.92000684e+03 4.91545801e+03 4.91526904e+03 4.91604248e+03 4.91675293e+03 6.30450586e+03 9.27442578e+03 2.59868652e+04 4.68962930e+04 1.30109307e+10 -5.16682957e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.51698452e+10 1.10737797e+10 1.25791549e+10 -1.26126940e+10 6.87130078e+04 1.39520664e+04 6.76694678e+03 4.92735400e+03 4.91605762e+03 4.91517432e+03 4.91513818e+03 4.91553857e+03 4.91559570e+03 4.91525244e+03 4.91534814e+03 4.91532031e+03 4.91492285e+03 4.91549902e+03 4.91536963e+03 4.91498828e+03 4.91576270e+03 4.91616602e+03 4.91512207e+03 4.91522559e+03 4.91554785e+03 4.91497412e+03 4.91556348e+03 4.91551025e+03 4.91492236e+03 4.91496826e+03 4.91527686e+03 4.91539795e+03 4.91498438e+03 4.91496484e+03 4.91498682e+03 4.91509961e+03 4.91533447e+03 4.91530176e+03 4.91498926e+03 4.91589258e+03 4.91599512e+03 4.91505811e+03 4.91498877e+03 4.91500732e+03 4.91509619e+03 4.91614648e+03 4.91593555e+03 4.91491211e+03 4.91617139e+03 4.91601465e+03 4.91496338e+03 4.91546387e+03 4.91554541e+03 4.91492236e+03 4.91493506e+03 4.91498730e+03 4.91508252e+03 4.91491260e+03 4.91501318e+03 4.91577637e+03 4.91538379e+03 4.91490332e+03 4.91496924e+03 4.91503662e+03 4.91609863e+03 4.91607275e+03 4.91534375e+03 4.91493213e+03 4.91506689e+03 4.91509082e+03 4.91659619e+03 4.91892334e+03 4.91742236e+03 4.91524170e+03 4.91500928e+03 4.91557617e+03 4.91642090e+03 4.91611816e+03 4.91497900e+03 4.91495410e+03 4.91503760e+03 4.91542627e+03 4.91534082e+03 4.91537939e+03 4.91582129e+03 4.91524219e+03 4.91491064e+03 4.91510254e+03 4.91509619e+03 4.91677637e+03 4.91728271e+03 4.91642920e+03 4.91516943e+03 4.91499023e+03 4.91501318e+03 4.91514990e+03 4.91597266e+03 4.91566309e+03 4.91496191e+03 4.91529932e+03 4.91505371e+03 4.91576270e+03 4.91582373e+03 4.91493896e+03 4.91528027e+03 4.91517627e+03 4.91505713e+03 4.91493701e+03 4.91500391e+03 4.91577441e+03 4.91564111e+03 4.91500439e+03 4.91497998e+03 4.91493848e+03 4.91519238e+03 4.91529785e+03 4.91496631e+03 4.91494092e+03 4.91527393e+03 4.91507812e+03 4.91499463e+03 4.91578320e+03 4.91619141e+03 4.91491748e+03 4.91501465e+03 4.91490186e+03 4.91503809e+03 4.91501807e+03 4.91493457e+03 4.91494629e+03 4.91494043e+03 4.91498682e+03 4.91506445e+03 4.91499365e+03 4.91527783e+03 4.91525781e+03 4.91490430e+03 4.91509961e+03 4.91508740e+03 4.91499609e+03 4.91493750e+03 4.91506787e+03 4.91535986e+03 4.91595508e+03 4.91523633e+03 4.91501270e+03 4.91553076e+03 4.91538623e+03 4.91492236e+03 4.91493945e+03 4.91494922e+03 4.91493213e+03 4.91494629e+03 4.91519238e+03 4.91557324e+03 4.91598535e+03 4.91631738e+03 4.91562402e+03 4.91504639e+03 4.91521484e+03 4.91555811e+03 4.91519092e+03 4.91496826e+03 4.91503662e+03 4.91541357e+03 4.91637305e+03 4.91557520e+03 4.91492090e+03 4.91555859e+03 4.91548291e+03 4.91502393e+03 4.91543311e+03 4.91539258e+03 4.91493604e+03 4.91494629e+03 4.91494287e+03 4.91497363e+03 4915. 4.91508252e+03 4.91511084e+03 4.91496680e+03 4.91562354e+03 4.91562939e+03 4.91528564e+03 4.91496582e+03 4.91508301e+03 4.91512061e+03 4.91501904e+03 4.91498535e+03 4.91550098e+03 4.91653467e+03 4.91592676e+03 4.91492529e+03 4.91541895e+03 4.91557227e+03 4.91495264e+03 4.91500244e+03 4.91495605e+03 4.91523584e+03 4.91515088e+03 4.91496143e+03 4.91543311e+03 4.91610254e+03 4.91624707e+03 4.91734863e+03 4.91632471e+03 4.91504102e+03 4.91497070e+03 4.91501025e+03 4.91528955e+03 4.91535889e+03 4.91497510e+03 4.91519873e+03 4.91624805e+03 4.91557275e+03 4.91501562e+03 4.91626807e+03 4.91582861e+03 4.91488672e+03 4.91496729e+03 4.91498828e+03 4.91506445e+03 4.91510645e+03 4.91491650e+03 4.91499561e+03 4.91515771e+03 4.91511719e+03 4.91501074e+03 4.91499072e+03 4.91543164e+03 4.91593604e+03 4.91551172e+03 4.91504297e+03 4.91500049e+03 4.91500732e+03 4.91492627e+03 4.91511328e+03 4.91517676e+03 4.91512256e+03 4.91494678e+03 4.91500098e+03 4.91504980e+03 4.91497412e+03 4.91494531e+03 4.91498486e+03 4.91498975e+03 4.91497900e+03 4.91500244e+03 4.91497314e+03 4.91495410e+03 4.91497510e+03 4.91499463e+03 4.91501416e+03 4.91501807e+03 4.91491064e+03 4.91497998e+03 4.91499707e+03 4.91497119e+03 4.91500879e+03 4.91495654e+03 4.91494629e+03 4.91494873e+03 4.91492920e+03 4.91495166e+03 4.91495557e+03 4.91496240e+03 4.91499561e+03 4.91502637e+03 4.91507324e+03 4.91510010e+03 4.91510352e+03 4.91506934e+03 4.91497998e+03 4.91493311e+03 4.91499707e+03 4.91506104e+03 4.91500879e+03 4.91498975e+03 4.91499707e+03 4.91506738e+03 4.91504395e+03 4.91505859e+03 4.91499707e+03 4.91494922e+03 4.91494043e+03 4.91497070e+03 4.91499805e+03 4.91507910e+03 4.91507129e+03 4.91502734e+03 4.91496143e+03 4.91493262e+03 4.91502490e+03 4.91502246e+03 4.91490771e+03 4.91496680e+03 4.91501611e+03 4.91490625e+03 4.91497705e+03 4.91496875e+03 4.91494971e+03 4.91490869e+03 4.91495850e+03 4.91492432e+03 4.91498486e+03 4.91495166e+03 4.91493652e+03 4.91492725e+03 4.91498389e+03 4.91501074e+03 4.91495996e+03 4.91495508e+03 4.91491064e+03 4.91490527e+03 4.91489746e+03 4.91499707e+03 4.91496875e+03 4.91495410e+03 4.91490576e+03 4.91493457e+03 4.91513086e+03 4.91549365e+03 4.91540039e+03 4.91512891e+03 4.91490039e+03 4.91494189e+03 4.91493164e+03 4.91495410e+03 4.91493945e+03 4.91525781e+03 4.91513916e+03 4.91495020e+03 4.91493506e+03 4.91498926e+03 4.91495264e+03 4.91494482e+03 4.91492725e+03 4.91495264e+03 4.91490430e+03 4.91492188e+03 4.91495068e+03 4.91490527e+03 4.91490527e+03 4.91489795e+03 4.91497754e+03 4.91512109e+03 4.91506934e+03 4.91505420e+03 4.91493896e+03 4.91495654e+03 4.91497656e+03 4.91496240e+03 4.91491992e+03 4.91489844e+03 4.91498340e+03 4.91519141e+03 4.91525488e+03 4.91495996e+03 4.91493896e+03 4.91492480e+03 4.91492529e+03 4.91514746e+03 4.91551465e+03 4.91521973e+03 4.91491895e+03 4.91501660e+03 4.91494580e+03 4.91491260e+03 4.91497217e+03 4.91506152e+03 4.91535498e+03 4.91514453e+03 4.91497070e+03 4.91492090e+03 4.91494531e+03 4.91491016e+03 4.91500342e+03 4.91506055e+03 4.91497949e+03 4.91491602e+03 4.91495459e+03 4.91498486e+03 4.91494678e+03 4.91495605e+03 4.91497705e+03 4.91503369e+03 4.91506055e+03 4.91495020e+03 4.91491748e+03 4.91487451e+03 4.91496143e+03 4.91501123e+03 4.91498730e+03 4.91494775e+03 4.91497363e+03 4.91494824e+03 4.91498877e+03 4.91501172e+03 4.91489258e+03 4.91504834e+03 4.91492871e+03 4.91493652e+03 4.91490234e+03 4.91497266e+03 4.91502881e+03 4.91503125e+03 4.91511084e+03 4.91510059e+03 4.91505078e+03 4.91489111e+03 4.91490234e+03 4.91491602e+03 4.91494189e+03 4.91491064e+03 4.91490918e+03 4.91491211e+03 4.91492090e+03 4.91504492e+03 4.91523926e+03 4.91527881e+03 4.91499219e+03 4.91492773e+03 4.91491504e+03 4.91491943e+03 4.91490137e+03 4.91491699e+03 4.91490723e+03 4.91493896e+03 4.91496143e+03 4.91514893e+03 4.91524268e+03 4.91513184e+03 4.91495557e+03 4.91492627e+03 4.91496729e+03 4.91497559e+03 4.91499219e+03 4.91494385e+03 4.91514404e+03 4.91570996e+03 4.91585205e+03 4.91518604e+03 4.91490234e+03 4.91489307e+03 4.91497461e+03 4.91537598e+03 4.91921387e+03 4.93219580e+03 4.96102393e+03 6.75217285e+03 1.00304316e+04 1.97195273e+04 1.97191621e+04 1.97217734e+04 1.97360195e+04 1.97281738e+04 1.97159180e+04 1.97217812e+04 1.97777188e+04 2.98241680e+04 6.08275664e+04 -2.84861727e+10 -2.14535475e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.92176000e+09 1.04690524e+10 2.72484680e+10 1.60119033e+04 7.36756055e+03 4.93479590e+03 4.91647363e+03 4.91537500e+03 4.91569482e+03 4.91555664e+03 4.91518896e+03 4.91494482e+03 4.91494434e+03 4.91498535e+03 4.91498193e+03 4.91496631e+03 4.91510645e+03 4.91540039e+03 4.91509668e+03 4.91490088e+03 4.91490723e+03 4.91494092e+03 4.91513965e+03 4.91502100e+03 4.91497021e+03 4.91504688e+03 4.91514307e+03 4.91520654e+03 4.91522217e+03 4.91514990e+03 4.91498096e+03 4.91496338e+03 4.91496387e+03 4.91503662e+03 4.91492725e+03 4.91503760e+03 4.91504541e+03 4.91493945e+03 4.91492432e+03 4.91491357e+03 4.91492334e+03 4.91494873e+03 4.91502539e+03 4.91510498e+03 4.91514404e+03 4.91516748e+03 4.91518994e+03 4.91510156e+03 4.91504492e+03 4.91496387e+03 4.91500342e+03 4.91498633e+03 4.91496436e+03 4.91500342e+03 4.91503027e+03 4.91511035e+03 4.91516602e+03 4.91504688e+03 4.91491406e+03 4.91502002e+03 4.91524609e+03 4.91505127e+03 4.91494238e+03 4.91488184e+03 4.91491064e+03 4.91507422e+03 4.91503516e+03 4.91493164e+03 4.91503223e+03 4.91505371e+03 4.91504150e+03 4.91522021e+03 4.91574512e+03 4.91531836e+03 4.91493701e+03 4.91492920e+03 4.91495410e+03 4.91490283e+03 4.91494434e+03 4.91492285e+03 4.91493506e+03 4.91490088e+03 4.91490332e+03 4.91491455e+03 4.91489404e+03 4.91491406e+03 4.91492188e+03 4.91490723e+03 4.91488770e+03 4.91499072e+03 4.91540430e+03 4.91518018e+03 4.91497266e+03 4.91490381e+03 4.91493311e+03 4.91496777e+03 4.91508057e+03 4.91524609e+03 4.91504932e+03 4.91493018e+03 4.91496436e+03 4.91489795e+03 4.91506348e+03 4.91508740e+03 4.91503467e+03 4.91494287e+03 4.91490674e+03 4.91491943e+03 4.91488867e+03 4.91489648e+03 4.91491406e+03 4.91495361e+03 4.91489502e+03 4.91488086e+03 4.91492139e+03 4.91509863e+03 4.91507178e+03 4.91492432e+03 4.91491504e+03 4.91494824e+03 4.91493799e+03 4.91500635e+03 4.91499268e+03 4.91501611e+03 4.91501855e+03 4.91485352e+03 4.91508691e+03 4.91514404e+03 4.91494971e+03 4.91490479e+03 4.91503125e+03 4.91508447e+03 4.91509668e+03 4.91499854e+03 4.91498633e+03 4.91501074e+03 4.91491895e+03 4.91491699e+03 4.91490625e+03 4.91493164e+03 4.91492285e+03 4.91493799e+03 4.91490527e+03 4.91489453e+03 4.91491504e+03 4.91489648e+03 4.91492236e+03 4.91492432e+03 4.91490820e+03 4.91491309e+03 4.91494971e+03 4.91491260e+03 4.91489502e+03 4.91491602e+03 4.91489844e+03 4.91489795e+03 4.91493457e+03 4.91495605e+03 4.91491992e+03 4.91497021e+03 4.91530518e+03 4.91539160e+03 4.91518604e+03 4.91499512e+03 4.91497119e+03 4.91493213e+03 4.91492578e+03 4.91489453e+03 4.91488867e+03 4.91494189e+03 4.91494385e+03 4.91492773e+03 4.91490674e+03 4.91506787e+03 4.91548877e+03 4.91582080e+03 4.91568701e+03 4.91512012e+03 4.91485498e+03 4.91494580e+03 4.91489600e+03 4.91489795e+03 4.91491162e+03 4.91489404e+03 4.91491602e+03 4.91490381e+03 4.91493701e+03 4.91493213e+03 4.91484424e+03 4.91485791e+03 4.91486719e+03 4.91490918e+03 4.91492285e+03 4.91488086e+03 4.91491504e+03 4.91498096e+03 4.91501318e+03 4.91489648e+03 4.91498682e+03 4.91530469e+03 4.91557080e+03 4.91561377e+03 4.91550977e+03 4.91562891e+03 4.91525684e+03 4.91489551e+03 4.91501318e+03 4.91504395e+03 4.91500244e+03 4.91495557e+03 4.91490527e+03 4.91494141e+03 4.91499902e+03 4.91498193e+03 4.91496436e+03 4.91489062e+03 4.91494336e+03 4.91492529e+03 4.91511035e+03 4.91552051e+03 4.91536279e+03 4.91508447e+03 4.91490479e+03 4.91495068e+03 4.91497900e+03 4.91531592e+03 4.91565088e+03 4.91542676e+03 4.91510449e+03 4.91485547e+03 4.91494971e+03 4.91499414e+03 4.91515625e+03 4.91516797e+03 4.91506250e+03 4.91503027e+03 4.91508398e+03 4.91502344e+03 4.91494385e+03 4.91491504e+03 4.91492529e+03 4.91509619e+03 4.91547412e+03 4.91610791e+03 4.91630664e+03 4.91522021e+03 4.91490527e+03 4.91507080e+03 4.91495898e+03 4.91494727e+03 4.91493457e+03 4.91493896e+03 4.91492578e+03 4.91493115e+03 4.91490479e+03 4.91490674e+03 4.91492139e+03 4.91497070e+03 4.91490088e+03 4.91493652e+03 4.91523877e+03 4.91534766e+03 4.91514648e+03 4.91495752e+03 4.91492041e+03 4.91493799e+03 4.91496777e+03 4.91487891e+03 4.91493213e+03 4.91494531e+03 4.91497119e+03 4.91492285e+03 4.91491113e+03 4.91497900e+03 4.91495117e+03 4.91493066e+03 4.91491113e+03 4.91489941e+03 4.91487891e+03 4.91490723e+03 4.91492529e+03 4.91498145e+03 4.91500781e+03 4.91497705e+03 4.91490186e+03 4.91513232e+03 4.91515186e+03 4.91494043e+03 4.91494238e+03 4.91494189e+03 4.91492285e+03 4.91492871e+03 4.91491211e+03 4.91492090e+03 4.91489697e+03 4.91494482e+03 4.91510791e+03 4.91504150e+03 4.91489258e+03 4.91489502e+03 4.91493213e+03 4.91489990e+03 4.91494238e+03 4.91518262e+03 4.91533691e+03 4.91520801e+03 4.91494385e+03 4.91497021e+03 4.91493213e+03 4.91497070e+03 4.91492334e+03 4.91496191e+03 4.91493799e+03 4.91501416e+03 4.91494727e+03 4.91491699e+03 4.91495752e+03 4.91496045e+03 4.91493262e+03 4.91491553e+03 4.91493262e+03 4.91505811e+03 4.91503564e+03 4.91494531e+03 4.91492627e+03 4.91493115e+03 4.91488232e+03 4.91492383e+03 4.91492090e+03 4.91497217e+03 4.91527832e+03 4.91537256e+03 4.91502832e+03 4.91490137e+03 4.91491211e+03 4.91490186e+03 4.91494580e+03 4.91492432e+03 4.91503223e+03 4.91546045e+03 4.91554053e+03 4.91517188e+03 4.91489160e+03 4.91492871e+03 4.91490039e+03 4.91493799e+03 4.91490527e+03 4.91489600e+03 4.91494141e+03 4.91503955e+03 4.91508838e+03 4.91500391e+03 4.91493604e+03 4.91491943e+03 4.91525684e+03 4.91600732e+03 4.91603662e+03 4.91537061e+03 4.91492676e+03 4.91491992e+03 4.91489941e+03 4.91494385e+03 4.91494287e+03 4.91530957e+03 4.91570361e+03 4.91653418e+03 4.91664844e+03 4.91579004e+03 4.91521582e+03 4.91491406e+03 4.91509521e+03 4.91541602e+03 4.91503320e+03 4.91499219e+03 4.91538770e+03 4.91505420e+03 4.91490137e+03 4.91488623e+03 4.91487695e+03 4.91490039e+03 4.91491406e+03 4.91496094e+03 4.91497949e+03 4.91499658e+03 4.91504443e+03 4.91497656e+03 4.91498340e+03 4.91491113e+03 4.91494287e+03 4.91493213e+03 4.91491602e+03 4.91500537e+03 4.91495605e+03 4.91486914e+03 4.91505957e+03 4.91488672e+03 4.91500146e+03 4.91487109e+03 4.91538379e+03 4.91536572e+03 4.91496289e+03 4.91531543e+03 4.91497754e+03 4.91485400e+03 4.91491504e+03 4.91528418e+03 4.91537207e+03 4.91515576e+03 4.91493604e+03 4.91494531e+03 4.91496680e+03 4.91493066e+03 4.91492041e+03 4.91488916e+03 4.91503174e+03 4.91488086e+03 4.91523633e+03 4.91569727e+03 4.91527295e+03 4.91505713e+03 4.91531104e+03 4.91569336e+03 4.91583545e+03 4.91532715e+03 4.91500684e+03 4.91500684e+03 4.91506104e+03 4.91511426e+03 4.91498096e+03 4.91512451e+03 4.91550928e+03 4.91564502e+03 4.91547949e+03 4.91502100e+03 4.91486914e+03 4.91485303e+03 4.91492871e+03 4.91493555e+03 4.91498828e+03 4.91566992e+03 4.91554541e+03 4.91496631e+03 4.91505371e+03 4.91494043e+03 4.91491113e+03 4.91497510e+03 4.91530664e+03 4.91530225e+03 4.91503906e+03 4.91488379e+03 4.91489307e+03 4.91492480e+03 4.91490430e+03 4.91487061e+03 4.91491895e+03 4.91491846e+03 4.91505908e+03 4.91509668e+03 4.91503955e+03 4.91491992e+03 4.91491895e+03 4.91494971e+03 4.91494873e+03 4.91510986e+03 4.91554541e+03 4.91517041e+03 4.91502832e+03 4.91542725e+03 4.91500146e+03 4.91491309e+03 4.91504639e+03 4.91513232e+03 4.91512500e+03 4.91508740e+03 4.91501660e+03 4.91503223e+03 4.91497217e+03 4.91498975e+03 4.91495068e+03 4.91507715e+03 4.91508936e+03 4.91511230e+03 4.91493018e+03 4.91492090e+03 4.91498730e+03 4.91516064e+03 4.91521973e+03 4.91502100e+03 4.91494482e+03 4.91491309e+03 4.91501270e+03 4.91523438e+03 4.91535010e+03 4.91503027e+03 4.91507471e+03 4.91588330e+03 4.91675928e+03 4.91608643e+03 4.91529639e+03 4.91541260e+03 4.91618115e+03 4.91618506e+03 4.91549414e+03 4.91511475e+03 4.91508301e+03 4.91512158e+03 4.91516357e+03 4.91517773e+03 4.91514355e+03 4.91500635e+03 4.91514014e+03 4.91555908e+03 4.91591650e+03 4.91543799e+03 4.91504395e+03 4.91504541e+03 4.91531787e+03 4.91496875e+03 4.91487549e+03 4.91504883e+03 4.91495166e+03 4.91490723e+03 4.91488965e+03 4.91487305e+03 4.91492725e+03 4.91489258e+03 4.91494189e+03 4.91492090e+03 4.91490137e+03 4.91488037e+03 4.91487744e+03 4.91495850e+03 4.91492432e+03 4.91489355e+03 4.91488867e+03 4.91499219e+03 4.91519678e+03 4.91512402e+03 4.91491748e+03 4.91497461e+03 4.91504150e+03 4.91500732e+03 4.91523877e+03 4.91566602e+03 4.91567725e+03 4.91537695e+03 4.91501562e+03 4.91499121e+03 4.91501611e+03 4.91493799e+03 4.91532910e+03 4.91544189e+03 4.91506348e+03 4.91494531e+03 4.91494775e+03 4.91494287e+03 4.91491846e+03 4.91487744e+03 4.91498047e+03 4.91529053e+03 4.91519727e+03 4.91490820e+03 4.91506641e+03 4.91498438e+03 4.91503516e+03 4.91583643e+03 4.91655273e+03 4.91609521e+03 4.91506641e+03 4.91496191e+03 4.91516553e+03 4.91516748e+03 4.91500342e+03 4.91494727e+03 4.91498242e+03 4.91498193e+03 4.91500342e+03 4.91494385e+03 4.91497021e+03 4.91512061e+03 4.91514111e+03 4.91523438e+03 4.91507178e+03 4.91510840e+03 4.91517383e+03 4.91498486e+03 4.91498193e+03 4.91499854e+03 4.91494336e+03 4.91500488e+03 4.91493457e+03 4.91498340e+03 4.91490234e+03 4.91738330e+03 4.92343213e+03 4.92700684e+03 6.51232812e+03 9.71710547e+03 1.97225801e+04 1.97393965e+04 1.97456426e+04 9.13491113e+03 6.15721045e+03 6.66488525e+03 9.61480957e+03 1.99261543e+04 2.00762051e+04 2.07167090e+04 3.43883828e+04 163293264. 0. 0. 0. 0. 0. 0. -7.72886989e+09 -7.72886989e+09 6.19589258e+04 6.50181992e+04 6.50181992e+04 4.72276480e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.48994929e+10 -1.02840535e+10 7.71228365e+09 1.77186660e+04 8.05543115e+03 6.09071680e+03 6.10539453e+03 6.57522070e+03 4.92495996e+03 4.91634326e+03 4.91634424e+03 4.91610400e+03 4.91604980e+03 4.91627686e+03 4.91674365e+03 4.91641211e+03 4.91612744e+03 4.91638965e+03 4.91612500e+03 4.91704492e+03 4.91693604e+03 4.91614404e+03 4.91691602e+03 4.91721729e+03 4.91652979e+03 4.91661475e+03 4.91719141e+03 4.91730225e+03 4.91657715e+03 4.91624854e+03 4.91658936e+03 4.91859717e+03 4.91910986e+03 4.91744043e+03 4.91631543e+03 4.91616943e+03 4.91617578e+03 4.91637451e+03 4.91684961e+03 4.91706543e+03 4.91631934e+03 4.91707422e+03 4.91895166e+03 4.91792383e+03 4.91630518e+03 4.91624268e+03 4.91622510e+03 4.91614551e+03 4.91632959e+03 4.91621045e+03 4.91635156e+03 4.91664307e+03 4.91636523e+03 4.91631885e+03 4.91806348e+03 4.91760107e+03 4.91614551e+03 4.91676416e+03 4.91638184e+03 4.91625098e+03 4.91612207e+03 4.91629443e+03 4.91629297e+03 4.91619727e+03 4.91695996e+03 4.91673486e+03 4.91622168e+03 4.91720166e+03 4.91682080e+03 4.91616162e+03 4.91612939e+03 4.91617529e+03 4.91616895e+03 4.91617139e+03 4.91674561e+03 4.91650586e+03 4.91620508e+03 4.91622803e+03 4.91661572e+03 4.91687744e+03 4.91649902e+03 4.91613184e+03 4.91620996e+03 4.91630273e+03 4.91617188e+03 4.91616504e+03 4.91616846e+03 4.91642480e+03 4.91760938e+03 4.91821191e+03 4.91667822e+03 4.91641309e+03 4.91729395e+03 4.91661865e+03 4.91627637e+03 4.91783594e+03 4.91883447e+03 4.91821826e+03 4.91756250e+03 4.91769580e+03 4.91708057e+03 4.91614307e+03 4.91641162e+03 4.91622803e+03 4.91628613e+03 4.91656592e+03 4.91629980e+03 4.91615088e+03 4.91622559e+03 4.91616992e+03 4.91634863e+03 4.91628662e+03 4.91622754e+03 4.91654346e+03 4.91811768e+03 4.91851660e+03 4.91705078e+03 4.91617236e+03 4.91617969e+03 4.91666504e+03 4.91747656e+03 4.91748340e+03 4.91654736e+03 4.91613965e+03 4.91615625e+03 4.91618945e+03 4.91616309e+03 4.91620215e+03 4.91622998e+03 4.91619971e+03 4.91666992e+03 4.91671826e+03 4.91618604e+03 4.91617285e+03 4.91621533e+03 4.91645410e+03 4.91661133e+03 4.91636377e+03 4.91650244e+03 4.91735205e+03 4.91768604e+03 4.91645898e+03 4.91662109e+03 4.91801025e+03 4.91688428e+03 4.91614990e+03 4.91628369e+03 4.91617432e+03 4.91613281e+03 4.91616260e+03 4.91618848e+03 4.91652686e+03 4.91739307e+03 4.91756885e+03 4.91639697e+03 4.91664697e+03 4.91749707e+03 4.91633789e+03 4.91626270e+03 4.91623828e+03 4.91616406e+03 4.91618408e+03 4.91731104e+03 4.91721631e+03 4.91617383e+03 4.91653760e+03 4.91611426e+03 4.91790039e+03 4.92066797e+03 4.91856494e+03 4.91637939e+03 4.91618213e+03 4.91614893e+03 4.91618164e+03 4.91626807e+03 4.91615771e+03 4.91640576e+03 4.91821436e+03 4.91719238e+03 4.91624805e+03 4.91635303e+03 4.91620996e+03 4.91614209e+03 4.91627197e+03 4.91644482e+03 4.91646240e+03 4.91684277e+03 4.91770068e+03 4.91723975e+03 4.91619971e+03 4.91651514e+03 4.91634277e+03 4.91633789e+03 4.91753125e+03 4.91723486e+03 4.91634717e+03 4.91612598e+03 4.91614160e+03 4.91619629e+03 4.91693799e+03 4.91760645e+03 4.91641309e+03 4.91628418e+03 4.91673340e+03 4.91623779e+03 4.91631543e+03 4.91661914e+03 4.91643018e+03 4.91620264e+03 4.91615430e+03 4.91616406e+03 4.91616260e+03 4.91639111e+03 4.91616992e+03 4.91632324e+03 4.91664209e+03 4.91645020e+03 4.91612402e+03 4.91616455e+03 4.91617676e+03 4.91624219e+03 4.91617676e+03 4.91627441e+03 4.91615479e+03 4.91642041e+03 4.91697070e+03 4.91705469e+03 4.91617041e+03 4.91623584e+03 4.91615088e+03 4.91660352e+03 4.91682959e+03 4.91629736e+03 4.91617139e+03 4.91616162e+03 4.91623145e+03 4.91620752e+03 4.91620947e+03 4.91627246e+03 4.91623877e+03 4.91664795e+03 4.91624854e+03 4.91618457e+03 4.91619727e+03 4.91636719e+03 4.91623047e+03 4.91612109e+03 4.91617334e+03 4.91616602e+03 4.91623145e+03 4.91638135e+03 4.91635840e+03 4.91656396e+03 4.91685986e+03 4.91702930e+03 4.91618262e+03 4.91621143e+03 4.91618018e+03 4.91634375e+03 4.91623877e+03 4.91620312e+03 4.91627393e+03 4.91678809e+03 4.91712158e+03 4.91622363e+03 4.91622949e+03 4.91620215e+03 4.91633203e+03 4.91641406e+03 4.91622363e+03 4.91613574e+03 4.91609961e+03 4.91644287e+03 4.91628564e+03 4.91612500e+03 4.91661865e+03 4.91705176e+03 4.91670898e+03 4.91616113e+03 4.91615625e+03 4.91614941e+03 4.91656396e+03 4.91680859e+03 4.91647803e+03 4.91684521e+03 4.91687109e+03 4.91629590e+03 4.91616162e+03 4.91622607e+03 4.91648779e+03 4.91690771e+03 4.91634814e+03 4.91618896e+03 4.91611963e+03 4.91632764e+03 4.91646240e+03 4.91620508e+03 4.91618262e+03 4.91610791e+03 4.91616309e+03 4.91623193e+03 4.91642578e+03 4.91647559e+03 4.91614160e+03 4.91614844e+03 4.91621533e+03 4.91655029e+03 4.91666992e+03 4.91660498e+03 4.91806689e+03 4.91928174e+03 4.91906885e+03 4.91805957e+03 4.91802783e+03 4.91938281e+03 4.92001416e+03 4.91874023e+03 4.91683789e+03 4.91641406e+03 4.91637354e+03 4.91660547e+03 4.91637451e+03 4.91613672e+03 4.91622656e+03 4.91639941e+03 4.91613916e+03 4.91622949e+03 4.91641504e+03 4.91624902e+03 4.91634131e+03 4.91656299e+03 4.91702246e+03 4.91682568e+03 4.91687061e+03 4.91770557e+03 4.91873975e+03 4.91801904e+03 4.91687012e+03 4.91683984e+03 4.91668018e+03 4.91617236e+03 4.91619775e+03 4.91638428e+03 4.91611865e+03 4.91614893e+03 4.91621240e+03 4.91652246e+03 4.91654053e+03 4.91619629e+03 4.91644482e+03 4.91668457e+03 4.91613574e+03 4.91644336e+03 4.91645117e+03 4.91612500e+03 4.91627783e+03 4.91614893e+03 4.91630811e+03 4.91685059e+03 4.91692578e+03 4.91627734e+03 4.91612598e+03 4.91627832e+03 4.91625586e+03 4.91623242e+03 4.91651562e+03 4.91667871e+03 4.91685986e+03 4.91615186e+03 4.91613818e+03 4.91618408e+03 4.91612402e+03 4.91617188e+03 4.91643750e+03 4.91880127e+03 4.91931787e+03 4.91702051e+03 4.91644482e+03 4.91739307e+03 4.91620947e+03 4.91695801e+03 4.91696045e+03 4.91622949e+03 4.91853271e+03 4.91761914e+03 4.91614355e+03 4.91638477e+03 4.91639307e+03 4.91621484e+03 4.91616260e+03 4.91626416e+03 4.91657129e+03 4.91676221e+03 4.91615479e+03 4.91615918e+03 4.91632861e+03 4.91688428e+03 4.91682373e+03 4.91635498e+03 4.91647412e+03 4.91664648e+03 4.91611865e+03 4.91686914e+03 4.91672852e+03 4.91640234e+03 4.91830762e+03 4.91733643e+03 4.91616113e+03 4.91653662e+03 4.91629590e+03 4.91622900e+03 4.91663281e+03 4.91687109e+03 4.91615527e+03 4.91612793e+03 4.91617139e+03 4.91633496e+03 4.91668311e+03 4.91616602e+03 4.91619434e+03 4.91685010e+03 4.91669971e+03 4.91647363e+03 4.91606201e+03 4.91683105e+03 4.91756543e+03 4.91646826e+03 4.91665967e+03 4.91801709e+03 4.91675977e+03 4.91643408e+03 4.91707520e+03 4.91609717e+03 4.91816406e+03 4.91799561e+03 4.91610596e+03 4.91626025e+03 4.91624805e+03 4.91616602e+03 4.91616016e+03 4.91615039e+03 4.91662207e+03 4.91747998e+03 4.91728955e+03 4.91791162e+03 4.91792383e+03 4.91674951e+03 4.91615283e+03 4.91640674e+03 4.91613086e+03 4.91662158e+03 4.91640820e+03 4.91626709e+03 4.91732617e+03 4.91668604e+03 4.91617969e+03 4.91634619e+03 4.91615576e+03 4.91670459e+03 4.91636084e+03 4.91616309e+03 4.91665527e+03 4.91747607e+03 4.91647559e+03 4.91646289e+03 4.91620996e+03 4.91620361e+03 4.91640381e+03 4.91658252e+03 4.91743457e+03 4.91660400e+03 4.91614062e+03 4.91638818e+03 4.91618164e+03 4.91642090e+03 4.91760352e+03 4.91669482e+03 4.91613818e+03 4.91676904e+03 4.91646338e+03 4.91610938e+03 4.91615918e+03 4.91626709e+03 4.91613428e+03 4.91617578e+03 4.91632471e+03 4.91689697e+03 4.91808398e+03 4.91761230e+03 4.91626904e+03 4.91618115e+03 4.91619971e+03 4.91615283e+03 4.91632520e+03 4.91705078e+03 4.91763330e+03 4.91630713e+03 4.91663379e+03 4.91758740e+03 4.91624561e+03 4.91656641e+03 4.91662256e+03 4.91620068e+03 4918. 4.91763867e+03 4.91614111e+03 4.91749219e+03 4.91879883e+03 4.91697949e+03 4.91623145e+03 4.91621973e+03 4.91645312e+03 4.91679053e+03 4.91631836e+03 4.91631494e+03 4.91620557e+03 4.91610156e+03 4.91616699e+03 4.91616602e+03 4.91630469e+03 4.91620068e+03 4.91637695e+03 4.91792578e+03 4.91746387e+03 4.91617041e+03 4.91743066e+03 4.91699170e+03 4.91623486e+03 4.91722217e+03 4.91728369e+03 4.91617773e+03 4.91662354e+03 4.91734570e+03 4.91631543e+03 4.91615186e+03 4.91629688e+03 4.91624805e+03 4.91619824e+03 4.91623047e+03 4.91626904e+03 4.91701855e+03 4.91764648e+03 4.91760303e+03 4.91667871e+03 4.91616504e+03 4.91633984e+03 4.91615186e+03 4.91698730e+03 4.91752441e+03 4.91654150e+03 4.91617920e+03 4.91617871e+03 4.91634619e+03 4.91782715e+03 4.91802881e+03 4.91651807e+03 4.91620898e+03 4.91659082e+03 4.91616211e+03 4.91660156e+03 4.91666016e+03 4.91615479e+03 4.91629150e+03 4.91633545e+03 4.91630566e+03 4.91615332e+03 4.91636670e+03 4.91653027e+03 4.91617822e+03 4.91706689e+03 4.91806299e+03 4.91672461e+03 4.91618018e+03 4.91669043e+03 4.91621631e+03 4.91626514e+03 4.91678320e+03 4.91645898e+03 4.91616602e+03 4.91614941e+03 4.91637305e+03 4.91714648e+03 4.91723047e+03 4.91627002e+03 4.91618115e+03 4.91617334e+03 4.91639111e+03 4.91743652e+03 4.91722119e+03 4.91703125e+03 4.91662109e+03 4.91623145e+03 4.91617822e+03 4.91618604e+03 4.91639258e+03 4.91691406e+03 4.91665820e+03 4.91619629e+03 4.91637451e+03 4.91616113e+03 4.91648291e+03 4.91704541e+03 4.91628711e+03 4.91702002e+03 4.91856445e+03 4.91702295e+03 4.91644189e+03 4.91805615e+03 4.91708252e+03 4.91621680e+03 4.91634863e+03 4.91642334e+03 4.91660596e+03 4.91734619e+03 4.91652930e+03 4.91934668e+03 4.92416699e+03 6.57040723e+03 9.57210449e+03 2.61571562e+04 4.93980195e+04 -6.61690010e+09 -5.32934738e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.00871856e+11 -2.97785283e+10 4.12020703e+04 2.48232129e+04 1.97955137e+04 1.98899805e+04 1.12473506e+04 6.93697705e+03 4.96540137e+03 4.92344238e+03 4.91965332e+03 4.91809668e+03 4.91650391e+03 4.91618750e+03 4.91659033e+03 4.91634277e+03 4.91613867e+03 4.91661279e+03 4.91646973e+03 4.91607617e+03 4.91700977e+03 4.91702148e+03 4.91656104e+03 4.91628076e+03 4.91624658e+03 4.91627930e+03 4.91614355e+03 4.91625244e+03 4.91629053e+03 4.91626904e+03 4.91677100e+03 4.91624414e+03 4.91699854e+03 4.91871240e+03 4.91686377e+03 4.91621924e+03 4.91695508e+03 4.91642139e+03 4.91652100e+03 4.91854639e+03 4.92012500e+03 4.91733643e+03 4.91633203e+03 4.91627930e+03 4.91714111e+03 4.91835352e+03 4.91731787e+03 4.91719141e+03 4.91652002e+03 4.91621387e+03 4.91619043e+03 4.91619189e+03 4.91822852e+03 4.91846924e+03 4.91649609e+03 4.91663037e+03 4.91701953e+03 4.91615479e+03 4.91729346e+03 4.91718018e+03 4.91623730e+03 4.91618115e+03 4.91643750e+03 4.91897412e+03 4.92036865e+03 4.91883545e+03 4.91631396e+03 4.91638721e+03 4.91640576e+03 4.91619189e+03 4.91780371e+03 4.92005713e+03 4.92158496e+03 4.91991602e+03 4.91788135e+03 4.91670117e+03 4.91636768e+03 4.91659277e+03 4.91643213e+03 4.91624023e+03 4.91706787e+03 4.91684326e+03 4.91615820e+03 4.91683350e+03 4.91655957e+03 4.91622314e+03 4.91639014e+03 4.91678760e+03 4.91632617e+03 4.91641357e+03 4.91730566e+03 4.91640234e+03 4.91621143e+03 4.91616699e+03 4.91623535e+03 4.91637158e+03 4.91617285e+03 4.91628125e+03 4.91627002e+03 4.91616113e+03 4.91624219e+03 4.91614990e+03 4.91728809e+03 4.91744727e+03 4.91617822e+03 4.91741260e+03 4.91864600e+03 4.91661719e+03 4.91616211e+03 4.91649023e+03 4.91628955e+03 4.91613574e+03 4.91616455e+03 4.91618115e+03 4.91664893e+03 4.91720752e+03 4.91639893e+03 4.91637646e+03 4.91677441e+03 4.91634131e+03 4.91617139e+03 4.91615625e+03 4.91631006e+03 4.91633691e+03 4.91631885e+03 4.91805811e+03 4.91788623e+03 4.91615625e+03 4.91636377e+03 4.91623096e+03 4.91780371e+03 4.91818799e+03 4.91637988e+03 4.91632373e+03 4.91654004e+03 4.91626758e+03 4.91643408e+03 4.91729004e+03 4.91682764e+03 4.91614648e+03 4.91669434e+03 4.91622705e+03 4.91659912e+03 4.91701221e+03 4.91655762e+03 4.91623877e+03 4.91615576e+03 4.91649561e+03 4.91689111e+03 4.91650977e+03 4.91617432e+03 4.91615479e+03 4.91657666e+03 4.91696924e+03 4.91622021e+03 4.91691016e+03 4.91891162e+03 4.91762451e+03 4.91615137e+03 4.91671143e+03 4.91649072e+03 4.91613916e+03 4.91622510e+03 4.91609521e+03 4.91614111e+03 4.91640430e+03 4.91622949e+03 4.91614990e+03 4.91619873e+03 4.91669971e+03 4.91717432e+03 4.91739307e+03 4.91625977e+03 4.91615771e+03 4.91632959e+03 4.91704883e+03 4.91659424e+03 4.91625635e+03 4.91683252e+03 4.91640234e+03 4.91618311e+03 4.91632520e+03 4.91628857e+03 4.91615723e+03 4.91616895e+03 4.91622119e+03 4.91635840e+03 4.91623242e+03 4.91613623e+03 4.91644092e+03 4.91762158e+03 4.91871924e+03 4.91997363e+03 4.91795752e+03 4.91628223e+03 4.91621338e+03 4.91620361e+03 4.91627100e+03 4.91633594e+03 4.91625000e+03 4.91723242e+03 4.91803027e+03 4.91629346e+03 4.91695605e+03 4.91860156e+03 4.91763086e+03 4.91652686e+03 4.91625537e+03 4.91630322e+03 4.91663916e+03 4.91727490e+03 4.91681201e+03 4.91617822e+03 4.91617188e+03 4.91619385e+03 4.91635059e+03 4.91647168e+03 4.91682959e+03 4.91690576e+03 4.91646191e+03 4.91622119e+03 4.91621240e+03 4.91628223e+03 4.91618604e+03 4.91636621e+03 4.91685010e+03 4.91715576e+03 4.91644775e+03 4.91619385e+03 4.91644092e+03 4.91693994e+03 4.91635059e+03 4.91625928e+03 4.91646875e+03 4.91613916e+03 4.91627295e+03 4.91622656e+03 4.91616406e+03 4.91616211e+03 4.91615625e+03 4.91616650e+03 4.91614062e+03 4.91615234e+03 4.91614551e+03 4.91619629e+03 4.91620264e+03 4.91644287e+03 4.91633447e+03 4.91624854e+03 4.91611768e+03 4.91616650e+03 4.91618799e+03 4.91617725e+03 4.91615332e+03 4.91621240e+03 4.91638574e+03 4.91644629e+03 4.91629688e+03 4.91615088e+03 4.91614355e+03 4.91614746e+03 4.91616455e+03 4.91614941e+03 4.91616064e+03 4.91615820e+03 4.91614746e+03 4.91616357e+03 4.91617090e+03 4.91615625e+03 4.91619336e+03 4.91622412e+03 4.91624463e+03 4.91623096e+03 4.91626758e+03 4.91619629e+03 4.91618750e+03 4.91616211e+03 4.91616602e+03 4.91615479e+03 4.91622363e+03 4.91622705e+03 4.91621387e+03 4.91614648e+03 4.91613965e+03 4.91610742e+03 4.91615625e+03 4.91612598e+03 4.91619043e+03 4.91616992e+03 4.91617871e+03 4.91613330e+03 4.91614844e+03 4.91613867e+03 4.91614551e+03 4.91615381e+03 4.91613574e+03 4.91620020e+03 4.91614600e+03 4.91613281e+03 4.91618311e+03 4.91619775e+03 4.91622559e+03 4.91619629e+03 4.91616406e+03 4.91614746e+03 4.91616943e+03 4.91615479e+03 4.91614600e+03 4.91615234e+03 4.91624951e+03 4.91618945e+03 4.91614404e+03 4.91612842e+03 4.91612646e+03 4.91618555e+03 4.91637598e+03 4.91638232e+03 4.91622803e+03 4.91614893e+03 4.91612354e+03 4.91615088e+03 4.91613379e+03 4.91619043e+03 4.91613232e+03 4.91617334e+03 4.91613721e+03 4.91616064e+03 4.91620459e+03 4.91623047e+03 4.91615332e+03 4.91615088e+03 4.91614600e+03 4.91618604e+03 4.91614697e+03 4.91617676e+03 4.91617480e+03 4.91622461e+03 4.91621582e+03 4.91626367e+03 4.91621875e+03 4.91617578e+03 4.91616016e+03 4.91614111e+03 4.91616895e+03 4.91622754e+03 4.91620068e+03 4.91615088e+03 4.91624121e+03 4.91617090e+03 4.91613965e+03 4.91622363e+03 4.91620654e+03 4.91614844e+03 4.91613428e+03 4.91615723e+03 4.91619629e+03 4.91624072e+03 4.91630176e+03 4.91616455e+03 4.91614697e+03 4.91610791e+03 4.91617432e+03 4.91614502e+03 4.91615820e+03 4.91612305e+03 4.91615479e+03 4.91615283e+03 4.91619434e+03 4.91613818e+03 4.91614990e+03 4.91614697e+03 4.91624561e+03 4.91661084e+03 4.91645996e+03 4.91618359e+03 4.91619775e+03 4.91612646e+03 4.91620166e+03 4.91635205e+03 4.91620264e+03 4.91615088e+03 4.91617090e+03 4.91623730e+03 4.91637402e+03 4.91637598e+03 4.91631836e+03 4.91636963e+03 4.91659229e+03 4.91674316e+03 4.91643896e+03 4.91617529e+03 4.91616943e+03 4.91618213e+03 4.91622559e+03 4.91620117e+03 4.91614795e+03 4.91616699e+03 4.91618848e+03 4.91635059e+03 4.91628174e+03 4.91618262e+03 4.91618457e+03 4.91617090e+03 4.91615234e+03 4.91614307e+03 4.91618457e+03 4.91651221e+03 4.91675684e+03 4.91633789e+03 4.91615283e+03 4.91618066e+03 4.91616504e+03 4.91628906e+03 4.91633447e+03 4.91616797e+03 4.91674268e+03 4.91688184e+03 4.91626465e+03 4.91614160e+03 4.91616260e+03 4.91617480e+03 4.91620508e+03 4.91630469e+03 4.91620996e+03 4.91615234e+03 4.91623242e+03 4.91625879e+03 4.91628125e+03 4.91615137e+03 4.91642139e+03 4.91654297e+03 4.91625049e+03 4.91619531e+03 4.91624561e+03 4.91631250e+03 4.91633740e+03 4.91617627e+03 4.91616455e+03 4.91614990e+03 4.91616699e+03 4.91620312e+03 4.91622461e+03 4.91626074e+03 4.91623389e+03 4.91619580e+03 4.91623486e+03 4.91630957e+03 4.91637598e+03 4.91625000e+03 4.91627197e+03 4.91763428e+03 4.91967871e+03 4.91755225e+03 4.91657812e+03 4.92093799e+03 6.71583936e+03 1.27700732e+04 -1.32361810e+10 -6.46374349e+09 -6.45408410e+09 1.31119626e+10 -2.18451988e+10 3.98259528e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.92269292e+10 -1.61117041e+10 7.17475859e+04 3.24721523e+04 2.01129238e+04 1.07015596e+04 6.89216113e+03 4.96249316e+03 4.92157959e+03 4.91649219e+03 4.91629102e+03 4.91626025e+03 4.91626709e+03 4.91639697e+03 4.91650244e+03 4.91664209e+03 4.91663281e+03 4.91656982e+03 4.91627539e+03 4.91625732e+03 4.91631152e+03 4.91663770e+03 4.91654248e+03 4.91631396e+03 4.91618994e+03 4.91616895e+03 4.91617139e+03 4.91618799e+03 4.91625000e+03 4.91629297e+03 4.91631592e+03 4.91641211e+03 4.91638672e+03 4.91641113e+03 4.91634033e+03 4.91631934e+03 4.91644678e+03 4.91653662e+03 4.91656641e+03 4.91631396e+03 4.91625049e+03 4.91626074e+03 4.91635742e+03 4.91641504e+03 4.91654395e+03 4.91658203e+03 4.91649609e+03 4.91619580e+03 4.91619482e+03 4.91628516e+03 4.91619434e+03 4.91615918e+03 4.91615088e+03 4.91620898e+03 4.91623242e+03 4.91617480e+03 4.91617334e+03 4.91615039e+03 4.91621582e+03 4.91625488e+03 4.91637793e+03 4.91626074e+03 4.91618750e+03 4.91616455e+03 4.91619678e+03 4.91623730e+03 4.91631396e+03 4.91619482e+03 4.91618066e+03 4.91617578e+03 4.91618848e+03 4.91622168e+03 4.91632129e+03 4.91623389e+03 4.91618066e+03 4.91617285e+03 4.91618457e+03 4.91617480e+03 4.91636182e+03 4.91635645e+03 4.91622070e+03 4.91617480e+03 4.91646436e+03 4.91708691e+03 4.91705469e+03 4.91662158e+03 4.91640576e+03 4.91644531e+03 4.91651318e+03 4.91634570e+03 4.91641602e+03 4.91666699e+03 4.91723291e+03 4.91703516e+03 4.91651318e+03 4.91621191e+03 4.91617041e+03 4.91614795e+03 4.91615137e+03 4.91616748e+03 4.91616553e+03 4.91625732e+03 4.91617578e+03 4.91624121e+03 4.91629590e+03 4.91618555e+03 4.91618555e+03 4.91621973e+03 4.91641113e+03 4.91635205e+03 4.91615479e+03 4.91626709e+03 4.91625293e+03 4.91626660e+03 4.91626855e+03 4.91625146e+03 4.91617139e+03 4.91617627e+03 4.91619043e+03 4.91621680e+03 4.91619287e+03 4.91617920e+03 4.91619385e+03 4.91618994e+03 4.91617090e+03 4.91616016e+03 4.91616211e+03 4.91629688e+03 4.91661768e+03 4.91660059e+03 4.91626855e+03 4.91617285e+03 4.91630518e+03 4.91665723e+03 4.91672607e+03 4.91638916e+03 4.91619482e+03 4.91617285e+03 4.91615674e+03 4.91619385e+03 4.91618848e+03 4.91619580e+03 4.91620264e+03 4.91617139e+03 4.91622266e+03 4.91623877e+03 4.91619482e+03 4.91619775e+03 4.91615967e+03 4.91617480e+03 4.91616016e+03 4.91618945e+03 4.91645557e+03 4.91705176e+03 4.91710645e+03 4.91656787e+03 4.91628613e+03 4.91658057e+03 4.91705664e+03 4.91693018e+03 4.91632666e+03 4.91617822e+03 4.91616992e+03 4.91617725e+03 4.91617676e+03 4.91620215e+03 4.91619580e+03 4.91622607e+03 4.91618604e+03 4.91618896e+03 4.91625049e+03 4.91650098e+03 4.91643457e+03 4.91624756e+03 4.91617920e+03 4.91616748e+03 4.91618896e+03 4.91627002e+03 4.91652637e+03 4.91650439e+03 4.91630518e+03 4.91619629e+03 4.91618652e+03 4.91615381e+03 4.91622559e+03 4.91657422e+03 4.91670557e+03 4.91636084e+03 4.91618604e+03 4.91623389e+03 4.91625195e+03 4.91620020e+03 4.91619092e+03 4.91620752e+03 4.91622021e+03 4.91647168e+03 4.91685645e+03 4.91689209e+03 4.91645654e+03 4.91624121e+03 4.91625977e+03 4.91630371e+03 4.91657910e+03 4.91688086e+03 4.91678809e+03 4.91628467e+03 4.91614795e+03 4.91616064e+03 4.91617578e+03 4.91619385e+03 4.91619141e+03 4.91616602e+03 4.91618652e+03 4.91616113e+03 4.91619434e+03 4.91620215e+03 4.91621582e+03 4.91621436e+03 4.91622607e+03 4.91630762e+03 4.91636084e+03 4.91637646e+03 4.91627441e+03 4.91627637e+03 4.91627051e+03 4.91625244e+03 4.91625391e+03 4.91624170e+03 4.91629785e+03 4.91620312e+03 4.91616797e+03 4.91620166e+03 4.91629395e+03 4.91629297e+03 4.91623145e+03 4.91618408e+03 4.91617236e+03 4.91622314e+03 4.91618066e+03 4.91620166e+03 4.91618066e+03 4.91615381e+03 4.91617920e+03 4.91617139e+03 4.91640625e+03 4.91626074e+03 4.91624072e+03 4.91663086e+03 4.91643896e+03 4.91624365e+03 4.91619336e+03 4.91620117e+03 4.91618750e+03 4.91617188e+03 4.91618213e+03 4.91617480e+03 4.91618359e+03 4.91616016e+03 4.91618457e+03 4.91620312e+03 4.91620264e+03 4.91617676e+03 4.91622412e+03 4.91618994e+03 4.91621289e+03 4.91618604e+03 4.91616016e+03 4.91619238e+03 4.91619385e+03 4.91617529e+03 4.91625195e+03 4.91663037e+03 4.91654785e+03 4.91630518e+03 4.91619043e+03 4.91616309e+03 4.91616943e+03 4.91620410e+03 4.91629150e+03 4.91642529e+03 4.91650098e+03 4.91629150e+03 4.91615771e+03 4.91620166e+03 4.91617139e+03 4.91619629e+03 4.91621191e+03 4.91617334e+03 4.91616016e+03 4.91618262e+03 4.91620068e+03 4.91619092e+03 4.91624707e+03 4.91624561e+03 4.91625195e+03 4.91653516e+03 4.91687451e+03 4.91676953e+03 4.91628027e+03 4.91617627e+03 4.91617529e+03 4.91627344e+03 4.91622998e+03 4.91623389e+03 4.91634131e+03 4.91673633e+03 4.91668311e+03 4.91627539e+03 4.91618652e+03 4.91619434e+03 4.91629834e+03 4.91623242e+03 4.91616650e+03 4.91615186e+03 4.91617383e+03 4.91624365e+03 4.91617920e+03 4.91622119e+03 4.91623145e+03 4.91622070e+03 4.91617920e+03 4.91621533e+03 4.91619287e+03 4.91632861e+03 4.91640674e+03 4.91651172e+03 4.91672705e+03 4.91727881e+03 4.91722852e+03 4.91698828e+03 4.91700244e+03 4.91677246e+03 4.91668750e+03 4.91632715e+03 4.91615430e+03 4.91632666e+03 4.91644824e+03 4.91636377e+03 4.91626074e+03 4.91622998e+03 4.91621826e+03 4.91621680e+03 4.91623975e+03 4.91627002e+03 4.91619043e+03 4.91634326e+03 4.91649414e+03 4.91643799e+03 4.91626416e+03 4.91624561e+03 4.91620459e+03 4.91619238e+03 4.91615820e+03 4.91616162e+03 4.91623486e+03 4.91634229e+03 4.91652686e+03 4.91689990e+03 4.91646191e+03 4.91620801e+03 4.91619824e+03 4.91635156e+03 4.91644922e+03 4.91628760e+03 4.91619873e+03 4.91626514e+03 4.91654492e+03 4.91671875e+03 4.91638672e+03 4.91622266e+03 4.91644092e+03 4.91687842e+03 4.91673926e+03 4.91623877e+03 4.91618457e+03 4.91619922e+03 4.91631006e+03 4.91617188e+03 4.91626465e+03 4.91617725e+03 4.91638574e+03 4.91667627e+03 4.91644678e+03 4.91630664e+03 4.91643457e+03 4.91676660e+03 4.91717822e+03 4.91687402e+03 4.91627490e+03 4.91618604e+03 4.91617773e+03 4.91619385e+03 4.91620801e+03 4.91616846e+03 4.91619775e+03 4.91619336e+03 4.91630420e+03 4.91629248e+03 4.91618701e+03 4.91619287e+03 4.91620215e+03 4.91640771e+03 4.91657812e+03 4.91643848e+03 4.91632324e+03 4.91621484e+03 4.91622168e+03 4.91620410e+03 4.91619287e+03 4.91620605e+03 4.91621289e+03 4.91636523e+03 4.91675342e+03 4.91626758e+03 4.91631934e+03 4.91637158e+03 4.91620752e+03 4.91639062e+03 4.91614990e+03 4.91617920e+03 4.91620361e+03 4.91629443e+03 4.91624902e+03 4.91616260e+03 4.91617480e+03 4.91619238e+03 4.91625195e+03 4.91619287e+03 4.91620996e+03 4.91621387e+03 4.91620557e+03 4.91623633e+03 4.91641455e+03 4.91641357e+03 4.91618457e+03 4.91617236e+03 4.91679102e+03 4.91764502e+03 4.91714600e+03 4.91633203e+03 4.91627588e+03 4.91649951e+03 4.91629688e+03 4.91619336e+03 4.91631982e+03 4.91618457e+03 4.91627734e+03 4.91623975e+03 4.91616553e+03 4.91627441e+03 4.91635791e+03 4.91638477e+03 4.91626953e+03 4.91618115e+03 4.91618848e+03 4.91621387e+03 4.91617969e+03 4.91619092e+03 4.91624219e+03 4.91627051e+03 4.91629834e+03 4.91655078e+03 4.91664404e+03 4.91642236e+03 4.91622705e+03 4.91624805e+03 4.91645410e+03 4.91648486e+03 4.91642725e+03 4.91664453e+03 4.91772461e+03 4.91868262e+03 4.91792236e+03 4.91660010e+03 4.91637695e+03 4.91654688e+03 4.91666406e+03 4.91636768e+03 4.91621777e+03 4.91618359e+03 4.91618750e+03 4.91618506e+03 4.91620801e+03 4.91619238e+03 4.91615186e+03 4.91616357e+03 4.91641357e+03 4.91671436e+03 4.91642822e+03 4.91618701e+03 4.91636035e+03 4.91653320e+03 4.91625879e+03 4.91626709e+03 4.91673877e+03 4.91665234e+03 4.91662891e+03 4.91639551e+03 4.91625732e+03 4.91619287e+03 4.91623340e+03 4.91620361e+03 4.91619092e+03 4.91615527e+03 4.91628613e+03 4.91620947e+03 4.91644336e+03 4.91701758e+03 4.91707861e+03 4.91686816e+03 4.91649219e+03 4.91628711e+03 4.91617773e+03 4.91618750e+03 4.91616895e+03 4.91616650e+03 4.91618262e+03 4.91616650e+03 4.91616504e+03 4.91620752e+03 4.91621484e+03 4.91618701e+03 4.91618994e+03 4.91618848e+03 4.91633203e+03 4.91680371e+03 4.91689697e+03 4.91648438e+03 4.91621045e+03 4.91623486e+03 4.91620850e+03 4.91623779e+03 4.91619434e+03 4.91619336e+03 4.91621191e+03 4.91643066e+03 4.91687500e+03 4.91660645e+03 4.91622559e+03 4.91621289e+03 4.91685400e+03 4.91762695e+03 4.91709326e+03 4.91628467e+03 4.91632422e+03 4.91654639e+03 4.91655176e+03 4.91627197e+03 4.91618066e+03 4.91636865e+03 4.91666992e+03 4.91711182e+03 4.91731152e+03 4.91661377e+03 4.91630859e+03 4.91629346e+03 4.91731934e+03 4.91800537e+03 4.91697217e+03 4.91625391e+03 4.91632275e+03 4.91692285e+03 4.91700537e+03 4.91657764e+03 4.91628711e+03 4.91647998e+03 4.91693506e+03 4.91701709e+03 4.91670215e+03 4.91637988e+03 4.91635156e+03 4.91668945e+03 4.91719580e+03 4.91718604e+03 4.91668506e+03 4.91620508e+03 4.91638281e+03 4.91664648e+03 4.91670703e+03 4.91633350e+03 4.91634814e+03 4.91685889e+03 4.91683789e+03 4.91635059e+03 4.91613623e+03 4.91615332e+03 4.91612988e+03 4.91617578e+03 4.91640527e+03 4.91665479e+03 4.91645459e+03 4.91616357e+03 4.91616309e+03 4.91616064e+03 4.91627246e+03 4.91640479e+03 4.91642334e+03 4.92085742e+03 4.93199756e+03 4.93167529e+03 4.91876367e+03 4.91734229e+03 4.91805762e+03 4.91919775e+03 4.92622070e+03 6.98111133e+03 1.40288428e+04 -1.19150950e+10 -5.24870195e+09 -4.18963174e+09 1.08553718e+10 -1.44837575e+12 0. 0. 0. 0. 0. 0. -7.72886989e+09 -7.72886989e+09 -1.97767496e+10 2.70255964e+10 2.70255964e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.48994929e+10 -1.02840535e+10 7.71228365e+09 6.89568828e+04 3.17437852e+04 1.99541055e+04 1.02004082e+04 6.96885156e+03 5.03554736e+03 4.96556396e+03 4.93704834e+03 4.93284814e+03 4.93311963e+03 4.93270020e+03 4.93271973e+03 4.93283350e+03 4.93276660e+03 4.93311621e+03 4.93395898e+03 4.93297510e+03 4.93325488e+03 4.93431885e+03 4.93342041e+03 4.93277295e+03 4.93296143e+03 4.93283691e+03 4.93272559e+03 4.93284180e+03 4.93313916e+03 4.93282617e+03 4.93288574e+03 4.93327051e+03 4.93295312e+03 4.93278906e+03 4.93293213e+03 4.93274512e+03 4.93315137e+03 4.93365869e+03 4.93312939e+03 4.93319141e+03 4.93384863e+03 4.93324609e+03 4.93277881e+03 4.93325537e+03 4.93273779e+03 4.93485645e+03 4.93595898e+03 4.93391748e+03 4.93292773e+03 4.93277051e+03 4.93277490e+03 4.93274365e+03 4.93277588e+03 4.93278076e+03 4.93277930e+03 4.93398535e+03 4.93588428e+03 4.93500439e+03 4.93304639e+03 4.93274170e+03 4.93276855e+03 4.93330078e+03 4.93413086e+03 4.93320654e+03 4.93298877e+03 4.93317480e+03 4.93295410e+03 4.93283008e+03 4.93361426e+03 4.93325537e+03 4.93282178e+03 4.93317285e+03 4.93289990e+03 4.93304199e+03 4.93280371e+03 4.93289600e+03 4.93283691e+03 4.93284766e+03 4.93303613e+03 4.93275488e+03 4.93333398e+03 4.93407324e+03 4.93356055e+03 4.93278662e+03 4.93300635e+03 4.93285742e+03 4.93273828e+03 4.93277002e+03 4.93302832e+03 4.93294434e+03 4.93276904e+03 4.93296484e+03 4.93279346e+03 4.93364404e+03 4.93386475e+03 4.93276270e+03 4.93298047e+03 4.93306787e+03 4.93277197e+03 4.93280811e+03 4.93277148e+03 4.93292285e+03 4.93412402e+03 4.93518945e+03 4.93364062e+03 4.93276758e+03 4.93342822e+03 4.93312842e+03 4.93277295e+03 4.93337402e+03 4.93438574e+03 4.93403369e+03 4.93371387e+03 4.93370947e+03 4.93343799e+03 4.93273584e+03 4.93300049e+03 4.93277734e+03 4.93389209e+03 4.93506885e+03 4.93390283e+03 4.93271875e+03 4.93306396e+03 4.93282959e+03 4.93277881e+03 4.93282812e+03 4.93285107e+03 4.93329199e+03 4.93523730e+03 4.93509570e+03 4.93322314e+03 4.93280811e+03 4.93282275e+03 4.93291260e+03 4.93350928e+03 4.93352979e+03 4.93313281e+03 4.93277930e+03 4.93273633e+03 4.93305615e+03 4.93340381e+03 4.93295752e+03 4.93273193e+03 4.93276855e+03 4.93281104e+03 4.93282812e+03 4.93276270e+03 4.93278564e+03 4.93279736e+03 4.93313770e+03 4.93331641e+03 4.93286279e+03 4.93278125e+03 4.93285254e+03 4.93323486e+03 4.93286670e+03 4.93325781e+03 4.93450488e+03 4.93310156e+03 4.93299463e+03 4.93319971e+03 4.93276855e+03 4.93286963e+03 4.93285059e+03 4.93284473e+03 4.93322461e+03 4.93430176e+03 4.93471533e+03 4.93402100e+03 4.93286816e+03 4.93282520e+03 4.93274512e+03 4.93285205e+03 4.93281201e+03 4.93289111e+03 4.93275146e+03 4.93381152e+03 4.93362305e+03 4.93304004e+03 4.93276074e+03 4.93314795e+03 4.93575781e+03 4.93766406e+03 4.93563574e+03 4.93308105e+03 4.93275293e+03 4.93275342e+03 4.93273682e+03 4.93277588e+03 4.93274805e+03 4.93314844e+03 4.93522998e+03 4.93500537e+03 4.93332373e+03 4.93302100e+03 4.93364600e+03 4.93297119e+03 4.93278516e+03 4.93336377e+03 4.93319922e+03 4.93354785e+03 4.93409277e+03 4.93389502e+03 4.93280127e+03 4.93307422e+03 4.93276123e+03 4.93356543e+03 4.93516602e+03 4.93352100e+03 4.93287451e+03 4.93325586e+03 4.93275146e+03 4.93297168e+03 4.93281055e+03 4.93291064e+03 4.93277148e+03 4.93293018e+03 4.93320508e+03 4.93279199e+03 4.93331445e+03 4.93355859e+03 4.93301025e+03 4.93274170e+03 4.93275537e+03 4.93281543e+03 4.93285059e+03 4.93277490e+03 4.93291309e+03 4.93341016e+03 4.93343896e+03 4.93322461e+03 4.93277930e+03 4.93275684e+03 4.93277881e+03 4.93279932e+03 4.93276758e+03 4.93281738e+03 4.93279053e+03 4.93315088e+03 4.93343555e+03 4.93304541e+03 4.93296777e+03 4.93396826e+03 4.93390186e+03 4.93280908e+03 4.93336816e+03 4.93366455e+03 4.93290527e+03 4.93280420e+03 4.93299756e+03 4.93290332e+03 4.93274707e+03 4.93278174e+03 4.93281592e+03 4.93300781e+03 4.93271777e+03 4.93363965e+03 4.93347705e+03 4.93287891e+03 4.93275488e+03 4.93283350e+03 4.93348584e+03 4.93285498e+03 4.93276025e+03 4.93305908e+03 4.93279736e+03 4.93280762e+03 4.93307666e+03 4.93332373e+03 4.93276660e+03 4.93277490e+03 4.93275635e+03 4.93288135e+03 4.93306787e+03 4.93305469e+03 4.93323242e+03 4.93366699e+03 4.93408936e+03 4.93287305e+03 4.93277979e+03 4.93275244e+03 4.93315479e+03 4.93321631e+03 4.93285107e+03 4.93275000e+03 4.93293945e+03 4.93284082e+03 4.93280322e+03 4.93281152e+03 4.93307031e+03 4.93343848e+03 4.93339258e+03 4.93311523e+03 4.93284717e+03 4.93279248e+03 4.93308350e+03 4.93286719e+03 4.93289893e+03 4.93307812e+03 4.93290137e+03 4.93278662e+03 4.93279688e+03 4.93276904e+03 4.93336377e+03 4.93405371e+03 4.93321484e+03 4.93284131e+03 4.93306494e+03 4.93276367e+03 4.93290332e+03 4.93306396e+03 4.93280811e+03 4.93274463e+03 4.93274512e+03 4.93293555e+03 4.93318750e+03 4.93331982e+03 4.93280322e+03 4.93272314e+03 4.93294043e+03 4.93355811e+03 4.93298389e+03 4.93272168e+03 4.93275293e+03 4.93297900e+03 4.93292285e+03 4.93268848e+03 4.93275244e+03 4.93331787e+03 4.93372119e+03 4.93333594e+03 4.93274170e+03 4.93277686e+03 4.93287598e+03 4.93311084e+03 4.93290820e+03 4.93272754e+03 4.93272070e+03 4.93280078e+03 4.93347705e+03 4.93383887e+03 4.93364893e+03 4.93301758e+03 4.93283838e+03 4.93299854e+03 4.93339941e+03 4.93313916e+03 4.93270166e+03 4.93271289e+03 4.93273193e+03 4.93280664e+03 4.93333545e+03 4.93313232e+03 4.93272363e+03 4.93277002e+03 4.93276611e+03 4.93327637e+03 4.93277588e+03 4.93277588e+03 4.93289209e+03 4.93315186e+03 4.93331689e+03 4.93289795e+03 4.93299365e+03 4.93326318e+03 4.93276172e+03 4.93311523e+03 4.93281592e+03 4.93298828e+03 4.93363135e+03 4.93295605e+03 4.93273633e+03 4.93275342e+03 4.93288623e+03 4.93335645e+03 4.93401074e+03 4.93554688e+03 4.93488818e+03 4.93350781e+03 4.93323633e+03 4.93370361e+03 4.93479102e+03 4.93324512e+03 4.93283643e+03 4.93276416e+03 4.93273047e+03 4.93276025e+03 4.93304639e+03 4.93487549e+03 4.93572998e+03 4.93377197e+03 4.93293848e+03 4.93330469e+03 4.93285645e+03 4.93499023e+03 4.93533740e+03 4.93334521e+03 4.93279053e+03 4.93300195e+03 4.93412939e+03 4.93506592e+03 4.93396484e+03 4.93279150e+03 4.93277441e+03 4.93288379e+03 4.93387402e+03 4.93614014e+03 4.93590039e+03 4.93487500e+03 4.93297754e+03 4.93309277e+03 4.93359375e+03 4.93282080e+03 4.93374023e+03 4.93551416e+03 4.93386572e+03 4.93279492e+03 4.93275684e+03 4.93430127e+03 4.93736084e+03 4.93578320e+03 4.93303857e+03 4.93293311e+03 4.93292188e+03 4.93289502e+03 4.93338086e+03 4.93447656e+03 4.93325146e+03 4.93299219e+03 4.93281885e+03 4.93311426e+03 4.93365527e+03 4.93293262e+03 4.93281299e+03 4.93346143e+03 4.93360596e+03 4.93300879e+03 4.93274463e+03 4.93408887e+03 4.93428857e+03 4.93314844e+03 4.93340332e+03 4.93475586e+03 4.93336768e+03 4.93306250e+03 4.93458447e+03 4.93401855e+03 4.93303760e+03 4.93301660e+03 4.93353271e+03 4.93402246e+03 4.93411768e+03 4.93300342e+03 4.93277100e+03 4.93301270e+03 4.93296680e+03 4.93281348e+03 4.93278662e+03 4.93325586e+03 4.93318994e+03 4.93280420e+03 4.93294922e+03 4.93297461e+03 4.93276221e+03 4.93334668e+03 4.93300928e+03 4.93275244e+03 4.93288623e+03 4.93275195e+03 4.93379980e+03 4.93380859e+03 4.93298340e+03 4.93298682e+03 4.93300439e+03 4.93278125e+03 4.93318799e+03 4.93407080e+03 4.93303027e+03 4.93283350e+03 4.93282568e+03 4.93283252e+03 4.93286963e+03 4.93291602e+03 4.93277197e+03 4.93282910e+03 4.93299219e+03 4.93289844e+03 4.93276660e+03 4.93369189e+03 4.93454590e+03 4.93351465e+03 4.93290186e+03 4.93475977e+03 4.93438818e+03 4.93275879e+03 4.93382715e+03 4.93473730e+03 4.93313477e+03 4.93293750e+03 4.93318359e+03 4.93274561e+03 4.93330518e+03 4.93305518e+03 4.93279004e+03 4.93317676e+03 4.93331201e+03 4.93296924e+03 4.93276221e+03 4.93331152e+03 4.93313916e+03 4.93281738e+03 4.93358350e+03 4.93375537e+03 4.93286084e+03 4.93309668e+03 4.93294043e+03 4.93291992e+03 4.93359668e+03 4.93315723e+03 4.93277930e+03 4.93276025e+03 4.93284863e+03 4.93275293e+03 4.93280908e+03 4.93276025e+03 4.93277441e+03 4.93295410e+03 4.93279199e+03 4.93291650e+03 4.93347998e+03 4.93411426e+03 4.93344385e+03 4.93293555e+03 4.93280859e+03 4.93300586e+03 4.93279199e+03 4.93303467e+03 4.93312500e+03 4.93275830e+03 4.93354834e+03 4.93347119e+03 4.93289258e+03 4.93299658e+03 4.93326270e+03 4.93294482e+03 4.93273389e+03 4.93278760e+03 4.93292139e+03 4.93359473e+03 4.93475342e+03 4.93427441e+03 4.93307031e+03 4.93305078e+03 4.93350391e+03 4.93510010e+03 4.93544580e+03 4.93460547e+03 4.93362207e+03 4.93274902e+03 4.93289062e+03 4.93281055e+03 4.93312891e+03 4.93358740e+03 4.93279248e+03 4.93286914e+03 4.93297705e+03 4.93302002e+03 4.93381494e+03 4.93344824e+03 4.93274756e+03 4.93317529e+03 4.93330957e+03 4.93280420e+03 4.93332959e+03 4.93369287e+03 4.93355518e+03 4.93318799e+03 4.93287793e+03 4.93280127e+03 4.93280371e+03 4.93277441e+03 4.93283203e+03 4.93274756e+03 4.93338037e+03 4.93433545e+03 4.93314502e+03 4.93286621e+03 4.93336816e+03 4.93277539e+03 4.93323633e+03 4.93353174e+03 4.93291455e+03 4.93314502e+03 4.93330273e+03 4.93279297e+03 4.93276074e+03 4.93283398e+03 4.93291162e+03 4.93299512e+03 4.93293945e+03 4.93276416e+03 4.93289404e+03 4.93283154e+03 4.93285791e+03 4.93302881e+03 4.93390137e+03 4.93376172e+03 4.93317383e+03 4.93285107e+03 4.93309668e+03 4.93304346e+03 4.93274902e+03 4.93507812e+03 4.93704736e+03 4.93639014e+03 4.93255518e+03 4.93257764e+03 4.93355957e+03 4.93438428e+03 6.72654785e+03 1.29315889e+04 5.52160215e+10 6.03233935e+10 2.53760246e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.00871856e+11 -2.97785283e+10 4.12020703e+04 2.48232129e+04 1.97955137e+04 1.98899805e+04 2.01296504e+04 1.97832285e+04 9.69116699e+03 6.54826025e+03 4.94352100e+03 4.93937988e+03 4.93553906e+03 4.93396582e+03 4.93325830e+03 4.93282861e+03 4.93286035e+03 4.93295947e+03 4.93272070e+03 4.93334277e+03 4.93315674e+03 4.93274463e+03 4.93351367e+03 4.93396338e+03 4.93292676e+03 4.93310693e+03 4.93337402e+03 4.93270605e+03 4.93341357e+03 4.93346289e+03 4.93277246e+03 4.93274902e+03 4.93313428e+03 4.93331738e+03 4.93287842e+03 4.93287354e+03 4.93286865e+03 4933. 4.93323047e+03 4.93321582e+03 4.93271582e+03 4.93377246e+03 4.93395020e+03 4.93291309e+03 4.93291650e+03 4.93286230e+03 4.93290674e+03 4.93400781e+03 4.93376221e+03 4.93279004e+03 4.93418555e+03 4.93381787e+03 4.93275000e+03 4.93322852e+03 4.93346826e+03 4.93282422e+03 4.93276318e+03 4.93285400e+03 4.93286377e+03 4.93280078e+03 4.93282080e+03 4.93364795e+03 4.93322656e+03 4.93277393e+03 4.93281299e+03 4.93279980e+03 4.93396631e+03 4.93387842e+03 4.93319238e+03 4.93279102e+03 4.93287061e+03 4.93285352e+03 4.93439795e+03 4.93672998e+03 4.93518701e+03 4.93307959e+03 4.93278271e+03 4.93333691e+03 4.93415039e+03 4.93401758e+03 4.93281738e+03 4.93275146e+03 4.93280371e+03 4.93319678e+03 4.93324463e+03 4.93315479e+03 4.93364844e+03 4.93313574e+03 4.93278076e+03 4.93284570e+03 4.93283789e+03 4.93454346e+03 4.93508008e+03 4.93421826e+03 4.93299609e+03 4.93278906e+03 4.93275635e+03 4.93286621e+03 4.93354102e+03 4.93338818e+03 4.93281934e+03 4.93310547e+03 4.93274170e+03 4.93347412e+03 4.93357764e+03 4.93280371e+03 4.93304590e+03 4.93301465e+03 4.93287256e+03 4.93280859e+03 4.93279980e+03 4.93376025e+03 4.93360400e+03 4.93284326e+03 4.93283936e+03 4.93278516e+03 4.93302490e+03 4.93315479e+03 4.93281445e+03 4.93282617e+03 4.93312402e+03 4.93295215e+03 4.93283789e+03 4.93363525e+03 4.93398584e+03 4.93278809e+03 4.93290967e+03 4.93277588e+03 4.93288525e+03 4.93296826e+03 4.93276367e+03 4.93272852e+03 4.93274365e+03 4.93280518e+03 4.93294727e+03 4.93281104e+03 4.93314209e+03 4.93316064e+03 4.93277539e+03 4.93301562e+03 4.93291309e+03 4.93277783e+03 4.93279102e+03 4.93289648e+03 4.93326123e+03 4.93390234e+03 4.93317676e+03 4.93273291e+03 4.93321924e+03 4.93319482e+03 4.93277441e+03 4.93277637e+03 4.93276025e+03 4.93274463e+03 4.93278174e+03 4.93314111e+03 4.93351562e+03 4.93403516e+03 4.93389893e+03 4.93328662e+03 4.93277197e+03 4.93308643e+03 4.93339502e+03 4.93308350e+03 4.93275439e+03 4.93271240e+03 4.93310449e+03 4.93412695e+03 4.93361914e+03 4.93279053e+03 4.93338916e+03 4.93327930e+03 4.93274414e+03 4.93306396e+03 4.93311670e+03 4.93275098e+03 4.93272217e+03 4.93276611e+03 4.93277148e+03 4.93282031e+03 4.93287793e+03 4.93289209e+03 4.93279004e+03 4.93335547e+03 4.93341309e+03 4.93308008e+03 4.93275195e+03 4.93285254e+03 4.93291895e+03 4.93281445e+03 4.93274756e+03 4.93330371e+03 4.93433984e+03 4.93359570e+03 4.93276807e+03 4.93333154e+03 4.93325879e+03 4.93272998e+03 4.93274756e+03 4.93281201e+03 4.93300391e+03 4.93288623e+03 4.93272461e+03 4.93311914e+03 4.93368799e+03 4.93386621e+03 4.93505859e+03 4.93428906e+03 4.93302344e+03 4.93278223e+03 4.93273389e+03 4.93310010e+03 4.93305029e+03 4.93273096e+03 4.93310156e+03 4.93417188e+03 4.93348145e+03 4.93276367e+03 4.93414795e+03 4.93368945e+03 4.93277832e+03 4.93282764e+03 4.93273438e+03 4.93283691e+03 4.93285791e+03 4.93277344e+03 4.93281055e+03 4.93300928e+03 4.93291113e+03 4.93280518e+03 4.93279004e+03 4.93345410e+03 4.93380420e+03 4.93332812e+03 4.93290137e+03 4.93280029e+03 4.93280713e+03 4.93276758e+03 4.93294678e+03 4.93304102e+03 4.93290674e+03 4.93277051e+03 4.93279004e+03 4.93286914e+03 4.93284180e+03 4.93279053e+03 4.93281396e+03 4.93277881e+03 4.93274609e+03 4.93280127e+03 4.93277979e+03 4.93275830e+03 4.93275293e+03 4.93276562e+03 4.93282764e+03 4.93280566e+03 4.93276758e+03 4.93274365e+03 4.93274512e+03 4.93276562e+03 4.93277930e+03 4.93277734e+03 4.93275000e+03 4.93275049e+03 4.93274658e+03 4.93277539e+03 4.93278564e+03 4.93276807e+03 4.93277344e+03 4.93284424e+03 4.93278662e+03 4.93281055e+03 4.93285596e+03 4.93284570e+03 4.93277344e+03 4.93277002e+03 4.93283008e+03 4.93282520e+03 4.93280029e+03 4.93277881e+03 4.93281641e+03 4.93284814e+03 4.93283740e+03 4.93285107e+03 4.93280518e+03 4.93280713e+03 4.93275830e+03 4.93279980e+03 4.93276074e+03 4.93279297e+03 4.93278076e+03 4.93280957e+03 4.93279834e+03 4.93284619e+03 4.93285400e+03 4.93286719e+03 4.93278223e+03 4.93278223e+03 4.93283936e+03 4.93278125e+03 4.93272803e+03 4.93279883e+03 4.93276172e+03 4.93275098e+03 4.93275781e+03 4.93273682e+03 4.93276904e+03 4.93275146e+03 4.93275293e+03 4.93277246e+03 4.93282129e+03 4.93280859e+03 4.93279248e+03 4.93277100e+03 4.93279883e+03 4.93277051e+03 4.93277979e+03 4.93276709e+03 4.93277393e+03 4.93277197e+03 4.93276416e+03 4.93281494e+03 4.93306592e+03 4.93338672e+03 4.93323047e+03 4.93288672e+03 4.93278174e+03 4.93274756e+03 4.93275488e+03 4.93276270e+03 4.93279199e+03 4.93302246e+03 4.93300391e+03 4.93276758e+03 4.93277637e+03 4.93273730e+03 4.93275781e+03 4.93276611e+03 4.93279932e+03 4.93281641e+03 4.93277197e+03 4.93276123e+03 4.93274072e+03 4.93276514e+03 4.93279053e+03 4.93277051e+03 4.93275732e+03 4.93301514e+03 4.93301660e+03 4.93292920e+03 4.93275342e+03 4.93275391e+03 4.93275732e+03 4.93273975e+03 4.93273877e+03 4.93275684e+03 4.93287598e+03 4.93315771e+03 4.93312500e+03 4.93282812e+03 4.93272168e+03 4.93275586e+03 4.93273779e+03 4.93289258e+03 4.93325488e+03 4.93300830e+03 4.93277002e+03 4.93280371e+03 4.93273486e+03 4.93275439e+03 4.93277930e+03 4.93298047e+03 4.93323242e+03 4.93311133e+03 4.93286621e+03 4.93274121e+03 4.93273193e+03 4.93276416e+03 4.93278809e+03 4.93289014e+03 4.93287256e+03 4.93276318e+03 4.93275293e+03 4.93278076e+03 4.93276611e+03 4.93280127e+03 4.93281934e+03 4.93283740e+03 4.93279053e+03 4.93276025e+03 4.93277295e+03 4.93279053e+03 4.93277783e+03 4.93274365e+03 4.93271240e+03 4.93273926e+03 4.93281201e+03 4.93274561e+03 4.93286182e+03 4.93278564e+03 4.93279785e+03 4.93287646e+03 4.93278027e+03 4.93274219e+03 4.93274365e+03 4.93273535e+03 4.93285010e+03 4.93283594e+03 4.93287354e+03 4.93286133e+03 4.93287549e+03 4.93277588e+03 4.93275244e+03 4.93275586e+03 4.93274707e+03 4.93275586e+03 4.93275635e+03 4.93275439e+03 4.93273877e+03 4.93277637e+03 4.93301416e+03 4.93313330e+03 4.93283252e+03 4.93274121e+03 4.93278711e+03 4.93278320e+03 4.93279785e+03 4.93276221e+03 4.93275098e+03 4.93275635e+03 4.93286621e+03 4.93307373e+03 4.93309961e+03 4.93291553e+03 4.93277246e+03 4.93279004e+03 4.93283154e+03 4.93284375e+03 4.93277197e+03 4.93277344e+03 4.93301709e+03 4.93356982e+03 4.93364844e+03 4.93300342e+03 4.93277832e+03 4.93280859e+03 4.93292383e+03 4.93341064e+03 4.93676367e+03 4.94960400e+03 4.97972900e+03 6.81884473e+03 1.00397920e+04 1.97316816e+04 1.97471328e+04 2.70548438e+04 5.11962344e+04 -1.05618031e+11 -3.64714000e+11 -4.32061743e+11 -5.67811686e+10 -9.73816955e+10 -6.96442946e+11 -2.99451822e+10 5.04543232e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. -3.92269292e+10 -1.61117041e+10 7.17475859e+04 3.24721523e+04 2.01129238e+04 1.98071387e+04 9.87581055e+03 6.71574512e+03 4.96455957e+03 4.94639941e+03 4.93506201e+03 4.93370654e+03 4.93297314e+03 4.93272803e+03 4.93279004e+03 4.93284033e+03 4.93289502e+03 4.93291162e+03 4.93310254e+03 4.93344092e+03 4.93302783e+03 4.93276465e+03 4.93278076e+03 4.93284668e+03 4.93313037e+03 4.93292822e+03 4.93288037e+03 4.93283691e+03 4.93294092e+03 4.93305762e+03 4.93313428e+03 4.93304102e+03 4.93284766e+03 4.93283301e+03 4.93281787e+03 4.93282910e+03 4.93275928e+03 4.93293457e+03 4.93294580e+03 4.93281982e+03 4.93276660e+03 4.93277441e+03 4.93281982e+03 4.93283447e+03 4.93288574e+03 4.93296729e+03 4.93298584e+03 4.93311328e+03 4.93307324e+03 4.93302490e+03 4.93291309e+03 4.93286279e+03 4.93288477e+03 4.93289355e+03 4.93291699e+03 4.93291846e+03 4.93291602e+03 4.93297021e+03 4.93304346e+03 4.93295703e+03 4.93278906e+03 4.93293848e+03 4.93310352e+03 4.93299121e+03 4.93281836e+03 4.93278369e+03 4.93282471e+03 4.93292090e+03 4.93284619e+03 4.93275732e+03 4.93291260e+03 4.93294043e+03 4.93289014e+03 4.93304004e+03 4.93349707e+03 4.93318750e+03 4.93281982e+03 4.93285059e+03 4.93278125e+03 4.93279297e+03 4.93276025e+03 4.93281885e+03 4.93278662e+03 4.93282764e+03 4.93279248e+03 4.93276953e+03 4.93278027e+03 4.93279883e+03 4.93281201e+03 4.93277197e+03 4.93278809e+03 4.93294922e+03 4.93330469e+03 4.93308301e+03 4.93283643e+03 4.93278467e+03 4.93278076e+03 4.93283301e+03 4.93299414e+03 4.93316699e+03 4.93287109e+03 4.93277490e+03 4.93282178e+03 4.93278662e+03 4.93293799e+03 4.93289746e+03 4.93287354e+03 4.93278467e+03 4.93277637e+03 4.93279395e+03 4.93279590e+03 4.93277441e+03 4.93277881e+03 4.93276074e+03 4.93277295e+03 4.93278906e+03 4.93284082e+03 4.93298975e+03 4.93297559e+03 4.93280762e+03 4.93279932e+03 4.93280225e+03 4.93287891e+03 4.93282764e+03 4.93286182e+03 4.93285889e+03 4.93291895e+03 4.93281934e+03 4.93295166e+03 4.93300537e+03 4.93281592e+03 4.93279004e+03 4.93284814e+03 4.93295312e+03 4.93301660e+03 4.93285547e+03 4.93277881e+03 4.93283154e+03 4.93278809e+03 4.93278174e+03 4.93277441e+03 4.93278662e+03 4.93279883e+03 4.93277881e+03 4.93278027e+03 4.93279639e+03 4.93278564e+03 4.93279297e+03 4.93277393e+03 4.93280176e+03 4.93281201e+03 4.93280908e+03 4.93278467e+03 4.93277002e+03 4.93278613e+03 4.93280908e+03 4.93279883e+03 4.93279736e+03 4.93279736e+03 4.93283887e+03 4.93280811e+03 4.93290479e+03 4.93321924e+03 4.93326221e+03 4.93304346e+03 4.93291016e+03 4.93286133e+03 4.93280762e+03 4.93279297e+03 4.93281250e+03 4.93281055e+03 4.93279834e+03 4.93278613e+03 4.93276562e+03 4.93277832e+03 4.93290039e+03 4.93324023e+03 4.93354297e+03 4.93347461e+03 4.93299170e+03 4.93281787e+03 4.93286377e+03 4.93281299e+03 4.93279492e+03 4.93279004e+03 4.93280273e+03 4.93277979e+03 4.93276904e+03 4.93276807e+03 4.93279248e+03 4.93281250e+03 4.93280127e+03 4.93280322e+03 4.93276465e+03 4.93277930e+03 4.93281201e+03 4.93284277e+03 4.93286279e+03 4.93281152e+03 4.93279297e+03 4.93279736e+03 4.93313818e+03 4.93338477e+03 4.93341357e+03 4.93323828e+03 4.93344531e+03 4.93303711e+03 4.93280469e+03 4.93285791e+03 4.93288623e+03 4.93284961e+03 4.93279834e+03 4.93280420e+03 4.93281152e+03 4.93287891e+03 4.93287695e+03 4.93283740e+03 4.93281055e+03 4.93279004e+03 4.93281396e+03 4.93299658e+03 4.93338574e+03 4.93321875e+03 4.93294482e+03 4.93280469e+03 4.93278906e+03 4.93288818e+03 4.93319043e+03 4.93354199e+03 4.93331348e+03 4.93308350e+03 4.93281152e+03 4.93283447e+03 4.93287744e+03 4.93294873e+03 4.93295410e+03 4.93285938e+03 4.93290381e+03 4.93289697e+03 4.93293018e+03 4.93286914e+03 4.93279346e+03 4.93278809e+03 4.93287646e+03 4.93331836e+03 4.93389453e+03 4.93429492e+03 4.93318408e+03 4.93280811e+03 4.93299170e+03 4.93283203e+03 4.93279297e+03 4.93278760e+03 4.93283447e+03 4.93279980e+03 4.93281494e+03 4.93279199e+03 4.93279980e+03 4.93278760e+03 4.93276123e+03 4.93278955e+03 4.93286768e+03 4.93326953e+03 4.93329199e+03 4.93298877e+03 4.93284326e+03 4.93279688e+03 4.93283301e+03 4.93281641e+03 4.93281201e+03 4.93277100e+03 4.93282178e+03 4.93286572e+03 4.93279688e+03 4.93281982e+03 4.93281055e+03 4.93281982e+03 4.93278613e+03 4.93277686e+03 4.93281201e+03 4.93279639e+03 4.93278613e+03 4.93277930e+03 4.93284033e+03 4.93289551e+03 4.93285986e+03 4.93278516e+03 4.93306396e+03 4.93300098e+03 4.93283203e+03 4.93284961e+03 4.93279199e+03 4.93280566e+03 4.93277686e+03 4.93279395e+03 4.93278613e+03 4.93280615e+03 4.93293896e+03 4.93308545e+03 4.93305469e+03 4.93281006e+03 4.93286719e+03 4.93283398e+03 4.93280176e+03 4.93288770e+03 4.93321973e+03 4.93324512e+03 4.93307031e+03 4.93286133e+03 4.93290088e+03 4.93289600e+03 4.93286426e+03 4.93280713e+03 4.93279102e+03 4.93281250e+03 4.93286670e+03 4.93285059e+03 4.93284814e+03 4.93282812e+03 4.93285742e+03 4.93282324e+03 4.93279395e+03 4.93280469e+03 4.93295508e+03 4.93295850e+03 4.93284180e+03 4.93278467e+03 4.93281445e+03 4.93279395e+03 4.93281934e+03 4.93280762e+03 4.93282666e+03 4.93315820e+03 4.93316113e+03 4.93285303e+03 4.93278760e+03 4.93279688e+03 4.93281104e+03 4.93278760e+03 4.93278857e+03 4.93287939e+03 4.93328516e+03 4.93335400e+03 4.93304883e+03 4.93279883e+03 4.93279541e+03 4.93278516e+03 4.93277393e+03 4.93277197e+03 4.93279004e+03 4.93282812e+03 4.93288428e+03 4.93289453e+03 4.93282568e+03 4.93280664e+03 4.93282080e+03 4.93305029e+03 4.93371729e+03 4.93378955e+03 4.93322070e+03 4.93284766e+03 4.93282324e+03 4.93281104e+03 4.93278076e+03 4.93280322e+03 4.93309912e+03 4.93362207e+03 4.93448584e+03 4.93469434e+03 4.93371045e+03 4.93313525e+03 4.93279590e+03 4.93299805e+03 4.93327051e+03 4.93297070e+03 4.93288232e+03 4.93323193e+03 4.93292041e+03 4.93280176e+03 4.93281201e+03 4.93281982e+03 4.93279004e+03 4.93278564e+03 4.93279199e+03 4.93282324e+03 4.93287500e+03 4.93289062e+03 4.93287354e+03 4.93282812e+03 4.93284814e+03 4.93285498e+03 4.93284131e+03 4.93278369e+03 4.93286230e+03 4.93284912e+03 4.93280811e+03 4.93294678e+03 4.93277344e+03 4.93291260e+03 4.93281055e+03 4.93326074e+03 4.93325635e+03 4.93276221e+03 4.93326465e+03 4.93297754e+03 4.93280371e+03 4.93283154e+03 4.93319824e+03 4.93322510e+03 4.93302783e+03 4.93281152e+03 4.93282715e+03 4.93284473e+03 4.93278955e+03 4.93280664e+03 4.93283740e+03 4.93294287e+03 4.93277734e+03 4.93315234e+03 4.93376465e+03 4.93325977e+03 4.93291943e+03 4.93318213e+03 4.93348291e+03 4.93369775e+03 4.93321582e+03 4.93286426e+03 4.93285303e+03 4.93285840e+03 4.93298340e+03 4.93290625e+03 4.93303662e+03 4.93341797e+03 4.93348584e+03 4.93332422e+03 4.93292969e+03 4.93282227e+03 4.93280762e+03 4.93275830e+03 4.93279590e+03 4.93296680e+03 4.93373877e+03 4.93351611e+03 4.93277100e+03 4.93294141e+03 4.93285449e+03 4.93278076e+03 4.93280371e+03 4.93318945e+03 4.93322607e+03 4.93295801e+03 4.93279053e+03 4.93279590e+03 4.93277979e+03 4.93278174e+03 4.93278760e+03 4.93277295e+03 4.93279492e+03 4.93284277e+03 4.93291797e+03 4.93285693e+03 4.93277979e+03 4.93276514e+03 4.93277734e+03 4.93276367e+03 4.93294434e+03 4.93325928e+03 4.93292090e+03 4.93283838e+03 4.93330566e+03 4.93290381e+03 4.93277637e+03 4.93289600e+03 4.93300879e+03 4.93303223e+03 4.93297559e+03 4.93289258e+03 4.93292578e+03 4.93285938e+03 4.93287646e+03 4.93286719e+03 4.93293945e+03 4.93296533e+03 4.93298877e+03 4.93287451e+03 4.93283594e+03 4.93284570e+03 4.93296094e+03 4.93300586e+03 4.93286963e+03 4.93278369e+03 4.93277686e+03 4.93286328e+03 4.93316455e+03 4.93325830e+03 4.93299219e+03 4.93290234e+03 4.93375928e+03 4.93462842e+03 4.93392090e+03 4.93311621e+03 4.93326025e+03 4.93402539e+03 4.93411572e+03 4.93337158e+03 4.93298047e+03 4.93295068e+03 4.93295361e+03 4.93303564e+03 4.93310010e+03 4.93308008e+03 4.93292871e+03 4.93306348e+03 4.93359131e+03 4.93395654e+03 4.93354199e+03 4.93300293e+03 4.93301514e+03 4.93333252e+03 4.93300293e+03 4.93282568e+03 4.93296631e+03 4.93279102e+03 4.93277539e+03 4.93279199e+03 4.93281250e+03 4.93275293e+03 4.93277051e+03 4.93273779e+03 4.93276318e+03 4.93278027e+03 4.93277734e+03 4.93278711e+03 4.93280176e+03 4.93278955e+03 4.93276416e+03 4.93279004e+03 4.93284619e+03 4.93299902e+03 4.93303076e+03 4.93279688e+03 4.93285791e+03 4.93292383e+03 4.93290039e+03 4.93310205e+03 4.93351123e+03 4.93359717e+03 4.93325635e+03 4.93292139e+03 4.93288477e+03 4.93286035e+03 4.93280615e+03 4.93323633e+03 4.93334229e+03 4.93299121e+03 4.93279736e+03 4.93279688e+03 4.93276221e+03 4.93276855e+03 4.93279443e+03 4.93282471e+03 4.93302295e+03 4.93290283e+03 4.93274219e+03 4.93295557e+03 4.93285205e+03 4.93288379e+03 4.93364062e+03 4.93446191e+03 4.93413818e+03 4.93302539e+03 4.93285254e+03 4.93302441e+03 4.93307520e+03 4.93287207e+03 4.93284180e+03 4.93278418e+03 4.93280811e+03 4.93282861e+03 4.93281299e+03 4.93287256e+03 4.93298633e+03 4.93309082e+03 4.93307471e+03 4.93297314e+03 4.93294727e+03 4.93299609e+03 4.93278809e+03 4.93277832e+03 4.93288330e+03 4.93279248e+03 4.93282227e+03 4.93281836e+03 4.93281445e+03 4.93282812e+03 4.93508740e+03 4.94077588e+03 4.94541016e+03 6.60323828e+03 9.85339844e+03 1.97488340e+04 1.97314883e+04 1.97404434e+04 9.30640527e+03 6.11233203e+03 7.85601758e+03 2.32126738e+04 -1.34743237e+11 1.72841812e+11 -2.39559875e+12 -2.39559875e+12 9.50582231e+10 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. -3.48994929e+10 -1.02840535e+10 7.71228365e+09 5.50549606e+09 9.87688550e+09 1.23674778e+10 1.22303896e+04 6.57104590e+03 4.92508936e+03 4.92290820e+03 4.93004297e+03 4.97764844e+03 4.95971045e+03 4.93719824e+03 4.92241846e+03 4.92074707e+03 4.92346387e+03 4.92565869e+03 4.94024072e+03 4.95119092e+03 4.93219873e+03 4.91996191e+03 4.91892480e+03 4.91912598e+03 4.91891113e+03 4.91904688e+03 4.91976953e+03 4.91978662e+03 4.91913965e+03 4.91885547e+03 4.91930566e+03 4.92143848e+03 4.92199658e+03 4.92001074e+03 4.91886230e+03 4.91879297e+03 4.91879297e+03 4.91892188e+03 4.91937354e+03 4.91966504e+03 4.91892725e+03 4.91980811e+03 4.92168799e+03 4.92069385e+03 4.91895020e+03 4.91881738e+03 4.91878760e+03 4.91878320e+03 4.91903125e+03 4.91884326e+03 4.91892627e+03 4.91907568e+03 4.91893604e+03 4.91892334e+03 4.92047363e+03 4.92019385e+03 4.91879150e+03 4.91939209e+03 4.91903760e+03 4.91882666e+03 4.91879346e+03 4.91898877e+03 4.91899902e+03 4.91878857e+03 4.91956250e+03 4.91931055e+03 4.91887891e+03 4.91991309e+03 4.91950439e+03 4.91879688e+03 4.91877148e+03 4.91883789e+03 4.91880469e+03 4.91887646e+03 4.91956104e+03 4.91914209e+03 4.91883447e+03 4.91889453e+03 4.91929541e+03 4.91951904e+03 4.91914795e+03 4.91882568e+03 4.91880029e+03 4.91892188e+03 4.91878809e+03 4.91880273e+03 4.91881299e+03 4.91910059e+03 4.92020215e+03 4.92078271e+03 4.91931445e+03 4.91900439e+03 4.91984473e+03 4.91925830e+03 4.91885107e+03 4.92048535e+03 4.92163477e+03 4.92085498e+03 4.92012402e+03 4.92047900e+03 4.91980664e+03 4.91881445e+03 4.91904932e+03 4.91882812e+03 4.91891455e+03 4.91918555e+03 4.91894775e+03 4.91882568e+03 4.91889111e+03 4.91877100e+03 4.91890674e+03 4.91884912e+03 4.91881201e+03 4.91912256e+03 4.92073096e+03 4.92131152e+03 4.91972607e+03 4.91881592e+03 4.91880664e+03 4.91934717e+03 4.92028516e+03 4.92022559e+03 4.91922656e+03 4.91879834e+03 4.91877686e+03 4.91883252e+03 4.91883301e+03 4.91881445e+03 4.91888477e+03 4.91879297e+03 4.91930566e+03 4.91935107e+03 4.91880664e+03 4.91879053e+03 4.91881445e+03 4.91904199e+03 4.91925000e+03 4.91891992e+03 4.91901807e+03 4.91983594e+03 4.92019482e+03 4.91912500e+03 4.91922803e+03 4.92052539e+03 4.91937793e+03 4.91877637e+03 4.91889453e+03 4.91879541e+03 4.91879834e+03 4.91878662e+03 4.91878857e+03 4.91902295e+03 4.91974072e+03 4.92001367e+03 4.91888867e+03 4.91937109e+03 4.92035156e+03 4.91897559e+03 4.91884912e+03 4.91882324e+03 4.91878027e+03 4.91884229e+03 4.91996582e+03 4.91975732e+03 4.91878076e+03 4.91925195e+03 4.91878174e+03 4.92031250e+03 4.92276416e+03 4.92086377e+03 4.91902295e+03 4.91877197e+03 4.91877734e+03 4.91879883e+03 4.91890088e+03 4.91879150e+03 4.91906982e+03 4.92073096e+03 4.91973242e+03 4.91885889e+03 4.91904395e+03 4.91889551e+03 4.91876514e+03 4.91903711e+03 4.91922363e+03 4.91932227e+03 4.91955664e+03 4.92050098e+03 4.91984326e+03 4.91885107e+03 4.91914404e+03 4.91885791e+03 4.91914551e+03 4.92031836e+03 4.91966553e+03 4.91887549e+03 4.91878467e+03 4.91878223e+03 4.91882715e+03 4.91956836e+03 4.92040625e+03 4.91917969e+03 4.91904395e+03 4.91942529e+03 4.91890186e+03 4.91907568e+03 4.91930469e+03 4.91917334e+03 4.91887158e+03 4.91878613e+03 4.91877344e+03 4.91881787e+03 4.91908105e+03 4.91881738e+03 4.91889014e+03 4.91916943e+03 4.91908545e+03 4.91880762e+03 4.91876562e+03 4.91879688e+03 4.91879443e+03 4.91879395e+03 4.91883447e+03 4.91879492e+03 4.91917480e+03 4.91969971e+03 4.91964795e+03 4.91879443e+03 4.91886963e+03 4.91878271e+03 4.91931934e+03 4.91954297e+03 4.91888281e+03 4.91883252e+03 4.91879541e+03 4.91888867e+03 4.91885205e+03 4.91879492e+03 4.91890479e+03 4.91882080e+03 4.91913623e+03 4.91889258e+03 4.91877051e+03 4.91888770e+03 4.91903809e+03 4.91881543e+03 4.91879980e+03 4.91887305e+03 4.91877637e+03 4.91882812e+03 4.91891016e+03 4.91903906e+03 4.91925586e+03 4.91966162e+03 4.91980566e+03 4.91881104e+03 4.91878857e+03 4.91881055e+03 4.91895703e+03 4.91885059e+03 4.91880566e+03 4.91889160e+03 4.91937305e+03 4.91958887e+03 4.91880029e+03 4.91892236e+03 4.91897852e+03 4.91884180e+03 4.91890869e+03 4.91883203e+03 4.91877881e+03 4.91877734e+03 4.91915576e+03 4.91899219e+03 4.91878564e+03 4.91924854e+03 4.91964111e+03 4.91923926e+03 4.91879932e+03 4.91886768e+03 4.91878125e+03 4.91909961e+03 4.91931738e+03 4.91895752e+03 4.91941260e+03 4.91951709e+03 4.91898926e+03 4.91885693e+03 4.91886230e+03 4.91908301e+03 4.91960449e+03 4.91904443e+03 4.91880713e+03 4.91877539e+03 4.91888184e+03 4.91894336e+03 4.91883447e+03 4.91878027e+03 4.91879590e+03 4.91884619e+03 4.91881250e+03 4.91902637e+03 4.91913477e+03 4.91879980e+03 4.91876807e+03 4.91883594e+03 4.91915576e+03 4.91921631e+03 4.91934473e+03 4.92079736e+03 4.92217383e+03 4.92206104e+03 4.92106152e+03 4.92085596e+03 4.92209082e+03 4.92247949e+03 4.92135547e+03 4.91947217e+03 4.91904297e+03 4.91897852e+03 4.91916260e+03 4.91897119e+03 4.91878955e+03 4.91899316e+03 4.91903662e+03 4.91878418e+03 4.91890820e+03 4.91897021e+03 4.91883936e+03 4.91894287e+03 4.91923193e+03 4.91961230e+03 4.91941260e+03 4.91945947e+03 4.92021875e+03 4.92115381e+03 4.92058154e+03 4.91947363e+03 4.91939453e+03 4.91934180e+03 4.91880811e+03 4.91888525e+03 4.91918311e+03 4.91878467e+03 4.91878613e+03 4.91884619e+03 4.91914600e+03 4.91921826e+03 4.91886230e+03 4.91901611e+03 4.91927979e+03 4.91877490e+03 4.91909619e+03 4.91906592e+03 4.91878271e+03 4.91891064e+03 4.91877734e+03 4.91907373e+03 4.91970654e+03 4.91955078e+03 4.91890430e+03 4.91877588e+03 4.91903418e+03 4.91902783e+03 4.91896924e+03 4.91912598e+03 4.91926807e+03 4.91941260e+03 4.91876904e+03 4.91878564e+03 4.91878516e+03 4.91878174e+03 4.91877246e+03 4.91903418e+03 4.92123291e+03 4.92186914e+03 4.91974658e+03 4.91891650e+03 4.91985693e+03 4.91883252e+03 4.91952930e+03 4.91974463e+03 4.91883203e+03 4.92098486e+03 4.92026562e+03 4.91877881e+03 4.91925146e+03 4.91913574e+03 4.91879199e+03 4.91877930e+03 4.91891064e+03 4.91937256e+03 4.91942725e+03 4.91879590e+03 4.91878174e+03 4.91891455e+03 4.91938477e+03 4.91932324e+03 4.91887598e+03 4.91902246e+03 4.91910889e+03 4.91878516e+03 4.91962549e+03 4.91952148e+03 4.91906104e+03 4.92097803e+03 4.92007812e+03 4.91877979e+03 4.91910840e+03 4.91892139e+03 4.91891162e+03 4.91929932e+03 4.91949512e+03 4.91880908e+03 4.91878906e+03 4.91880371e+03 4.91906055e+03 4.91927930e+03 4.91883984e+03 4.91878955e+03 4.91939258e+03 4.91938525e+03 4.91900928e+03 4.91881104e+03 4.91967920e+03 4.92043994e+03 4.91915625e+03 4.91920703e+03 4.92064355e+03 4.91935840e+03 4.91926318e+03 4.92006885e+03 4.91879590e+03 4.92067236e+03 4.92075049e+03 4.91883496e+03 4.91904443e+03 4.91899365e+03 4.91880957e+03 4.91885254e+03 4.91878271e+03 4.91919043e+03 4.92007910e+03 4.92006396e+03 4.92071729e+03 4.92038525e+03 4.91929590e+03 4.91880078e+03 4.91899561e+03 4.91882471e+03 4.91948291e+03 4.91919922e+03 4.91886426e+03 4.91990723e+03 4.91943945e+03 4.91879102e+03 4.91892090e+03 4.91878174e+03 4.91924268e+03 4.91902393e+03 4.91879785e+03 4.91929297e+03 4.92011816e+03 4.91924707e+03 4.91918262e+03 4.91889307e+03 4.91893262e+03 4.91907812e+03 4.91930957e+03 4.92010352e+03 4.91931250e+03 4.91878906e+03 4.91900977e+03 4.91881250e+03 4.91931982e+03 4.92052100e+03 4.91942285e+03 4.91880664e+03 4.91933838e+03 4.91921777e+03 4.91877637e+03 4.91882227e+03 4.91886426e+03 4.91876367e+03 4.91880420e+03 4.91909326e+03 4.91990479e+03 4.92117480e+03 4.92052637e+03 4.91904639e+03 4.91879590e+03 4.91883350e+03 4.91877881e+03 4.91895703e+03 4.91965381e+03 4.92017090e+03 4.91896924e+03 4.91920752e+03 4.92010791e+03 4.91893408e+03 4.91918555e+03 4.91932910e+03 4.91883350e+03 4.92070947e+03 4.92038623e+03 4.91877197e+03 4.92022607e+03 4.92167139e+03 4.91966699e+03 4.91883057e+03 4.91879004e+03 4.91902441e+03 4.91942432e+03 4.91891064e+03 4.91891602e+03 4.91880176e+03 4.91878906e+03 4.91882764e+03 4.91880713e+03 4.91893506e+03 4.91883984e+03 4.91889893e+03 4.92026514e+03 4.91992871e+03 4.91880225e+03 4.92004639e+03 4.91949316e+03 4.91883350e+03 4.91981348e+03 4.91985986e+03 4.91879688e+03 4.91929150e+03 4.92000586e+03 4.91896777e+03 4.91877393e+03 4.91891846e+03 4.91897510e+03 4.91887109e+03 4.91890723e+03 4.91889990e+03 4.91971094e+03 4.92043164e+03 4.92025342e+03 4.91939600e+03 4.91878467e+03 4.91892090e+03 4.91877246e+03 4.91956201e+03 4.92006641e+03 4.91918359e+03 4.91879785e+03 4.91879199e+03 4.91894629e+03 4.92012988e+03 4.92041553e+03 4.91906250e+03 4.91887207e+03 4.91922852e+03 4.91879053e+03 4.91935889e+03 4.91934863e+03 4.91880078e+03 4.91892773e+03 4.91898633e+03 4.91890234e+03 4.91879102e+03 4.91892432e+03 4.91903711e+03 4.91877148e+03 4.91973535e+03 4.92053711e+03 4.91924170e+03 4.91878906e+03 4.91935205e+03 4.91891162e+03 4.91889648e+03 4.91941211e+03 4.91917041e+03 4.91877783e+03 4.91877783e+03 4.91895068e+03 4.91959912e+03 4.91983447e+03 4.91885938e+03 4.91880664e+03 4.91876465e+03 4.91901074e+03 4.91995459e+03 4.91967725e+03 4.91959717e+03 4.91922217e+03 4.91885205e+03 4.91876758e+03 4.91878027e+03 4.91907910e+03 4.91966992e+03 4.91922998e+03 4.91877100e+03 4.91894482e+03 4.91877197e+03 4.91916016e+03 4.91977148e+03 4.91886328e+03 4.91951807e+03 4.92109521e+03 4.91939600e+03 4.91919775e+03 4.92115039e+03 4.91984814e+03 4.91879248e+03 4.91876660e+03 4.91880908e+03 4.91884961e+03 4.91947314e+03 4.91873535e+03 4.91992188e+03 4.92382129e+03 6.55249951e+03 9.68357617e+03 1.96607129e+04 1.96209414e+04 2.63704141e+04 4.78194219e+04 2.53760246e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.00871856e+11 -2.97785283e+10 1.86240389e+10 -5.09218447e+10 5.88486656e+10 -2.04383846e+10 -7.65048832e+10 -3.68764805e+10 5.75105625e+04 1.34536855e+04 6.76477734e+03 4.94988867e+03 4.93535840e+03 6.28297119e+03 6.05556348e+03 6.26190381e+03 4.92221387e+03 4.91909082e+03 4.92657568e+03 4.92703955e+03 4.92273682e+03 4.92320459e+03 4.92108057e+03 4.91944775e+03 4.91889502e+03 4.91882715e+03 4.91886719e+03 4.91880029e+03 4.91882861e+03 4.91893262e+03 4.91954150e+03 4.91889551e+03 4.91965332e+03 4.92146387e+03 4.91944531e+03 4.91882080e+03 4.91963379e+03 4.91906543e+03 4.91917627e+03 4.92138574e+03 4.92308398e+03 4.92008545e+03 4.91894482e+03 4.91886377e+03 4.91965527e+03 4.92087158e+03 4.91988330e+03 4.91970215e+03 4.91898145e+03 4.91877100e+03 4.91880127e+03 4.91882861e+03 4.92086816e+03 4.92110645e+03 4.91909180e+03 4.91920410e+03 4.91964502e+03 4.91877783e+03 4.91978760e+03 4.91964258e+03 4.91879932e+03 4.91879053e+03 4.91918701e+03 4.92159961e+03 4.92277441e+03 4.92093604e+03 4.91884863e+03 4.91903369e+03 4.91900684e+03 4.91882275e+03 4.92025928e+03 4.92239453e+03 4.92381885e+03 4.92248682e+03 4.92034961e+03 4.91922461e+03 4.91891504e+03 4.91920215e+03 4.91900195e+03 4.91882178e+03 4.91967969e+03 4.91949219e+03 4.91877734e+03 4.91935352e+03 4.91905469e+03 4.91877734e+03 4.91903027e+03 4.91943506e+03 4.91897949e+03 4.91893018e+03 4.91967041e+03 4.91895654e+03 4.91881836e+03 4.91876904e+03 4.91887500e+03 4.91900830e+03 4.91879932e+03 4.91891650e+03 4.91888525e+03 4.91877881e+03 4.91886572e+03 4.91877344e+03 4.91995312e+03 4.92019971e+03 4.91880859e+03 4.91986426e+03 4.92142432e+03 4.91943018e+03 4.91879248e+03 4.91913623e+03 4.91894434e+03 4.91877148e+03 4.91877002e+03 4.91880371e+03 4.91933789e+03 4.91993701e+03 4.91902295e+03 4.91901807e+03 4.91934717e+03 4.91889648e+03 4.91876953e+03 4.91877637e+03 4.91890674e+03 4.91887598e+03 4.91898438e+03 4.92063477e+03 4.92040430e+03 4.91877295e+03 4.91907373e+03 4.91881104e+03 4.92025732e+03 4.92073926e+03 4.91897314e+03 4.91906250e+03 4.91935498e+03 4.91897656e+03 4.91889795e+03 4.91966260e+03 4.91933350e+03 4.91877686e+03 4.91933887e+03 4.91881348e+03 4.91920947e+03 4.91978076e+03 4.91937207e+03 4.91889453e+03 4.91876758e+03 4.91910059e+03 4.91938770e+03 4.91903955e+03 4.91877930e+03 4.91877100e+03 4.91915723e+03 4.91954639e+03 4.91883252e+03 4.91952295e+03 4.92152051e+03 4.92029736e+03 4.91878564e+03 4.91924854e+03 4.91918848e+03 4.91877588e+03 4.91885010e+03 4.91878320e+03 4.91878418e+03 4.91898682e+03 4.91886230e+03 4.91885449e+03 4.91878613e+03 4.91926611e+03 4.91995654e+03 4.92030273e+03 4.91902100e+03 4.91878174e+03 4.91902588e+03 4.91978662e+03 4.91942725e+03 4.91883350e+03 4.91938574e+03 4.91897559e+03 4.91878027e+03 4.91897217e+03 4.91891992e+03 4.91880518e+03 4.91878418e+03 4.91881885e+03 4.91889844e+03 4.91885938e+03 4.91878076e+03 4.91920312e+03 4.92044238e+03 4.92158789e+03 4.92279590e+03 4.92055420e+03 4.91892578e+03 4.91881006e+03 4.91885059e+03 4.91890283e+03 4.91888867e+03 4.91880469e+03 4.91975586e+03 4.92067529e+03 4.91897314e+03 4.91945508e+03 4.92097607e+03 4.92011768e+03 4.91910059e+03 4.91886475e+03 4.91892773e+03 4.91922314e+03 4.91986230e+03 4.91935938e+03 4.91881592e+03 4.91880078e+03 4.91881494e+03 4.91888037e+03 4.91906201e+03 4.91935645e+03 4.91950391e+03 4.91905615e+03 4.91884912e+03 4.91884375e+03 4.91890137e+03 4.91877441e+03 4.91895752e+03 4.91950928e+03 4.91977588e+03 4.91899805e+03 4.91878467e+03 4.91919141e+03 4.91944971e+03 4.91889502e+03 4.91888086e+03 4.91910840e+03 4.91878369e+03 4.91886426e+03 4.91882031e+03 4.91877783e+03 4.91877686e+03 4.91877051e+03 4.91877490e+03 4.91877686e+03 4.91878613e+03 4.91878809e+03 4.91878955e+03 4.91884277e+03 4.91898096e+03 4.91893262e+03 4.91884814e+03 4.91878809e+03 4.91878711e+03 4.91882275e+03 4.91881006e+03 4.91878369e+03 4.91882959e+03 4.91897949e+03 4.91896875e+03 4.91890674e+03 4.91877832e+03 4.91877979e+03 4.91877148e+03 4.91877100e+03 4.91879883e+03 4.91879102e+03 4.91878125e+03 4.91877588e+03 4.91882422e+03 4.91881494e+03 4.91881152e+03 4.91879639e+03 4.91884473e+03 4.91892139e+03 4.91891064e+03 4.91893359e+03 4.91884521e+03 4.91881885e+03 4.91878857e+03 4.91878467e+03 4.91879199e+03 4.91885010e+03 4.91884717e+03 4.91883057e+03 4.91877246e+03 4.91877930e+03 4.91879443e+03 4.91880859e+03 4.91877588e+03 4.91877393e+03 4.91878320e+03 4.91882227e+03 4.91877734e+03 4.91878027e+03 4.91879150e+03 4.91881592e+03 4.91877295e+03 4.91877539e+03 4.91879639e+03 4.91880908e+03 4.91878076e+03 4.91884326e+03 4.91882959e+03 4.91884131e+03 4.91888428e+03 4.91883789e+03 4.91884766e+03 4.91887939e+03 4.91889600e+03 4.91879150e+03 4.91877100e+03 4.91879248e+03 4.91877881e+03 4.91878613e+03 4.91879492e+03 4.91877783e+03 4.91882861e+03 4.91905127e+03 4.91901611e+03 4.91885352e+03 4.91877734e+03 4.91877246e+03 4.91877100e+03 4.91877295e+03 4.91880225e+03 4.91878076e+03 4.91877246e+03 4.91879248e+03 4.91882227e+03 4.91893359e+03 4.91891699e+03 4.91880518e+03 4.91878125e+03 4.91878174e+03 4.91877832e+03 4.91877344e+03 4.91877002e+03 4.91880615e+03 4.91881201e+03 4.91884961e+03 4.91885449e+03 4.91879834e+03 4.91877686e+03 4.91878955e+03 4.91878223e+03 4.91878223e+03 4.91881250e+03 4.91883203e+03 4.91877295e+03 4.91880713e+03 4.91879395e+03 4.91880029e+03 4.91881934e+03 4.91881543e+03 4.91877881e+03 4.91877979e+03 4.91877637e+03 4.91877490e+03 4.91877881e+03 4.91894971e+03 4.91883887e+03 4.91884473e+03 4.91878271e+03 4.91881543e+03 4.91880664e+03 4.91877832e+03 4.91880322e+03 4.91877393e+03 4.91882178e+03 4.91885107e+03 4.91878076e+03 4.91877441e+03 4.91877148e+03 4.91886572e+03 4.91920068e+03 4.91916797e+03 4.91887891e+03 4.91880469e+03 4.91877832e+03 4.91891553e+03 4.91911768e+03 4.91890918e+03 4.91877881e+03 4.91877539e+03 4.91884473e+03 4.91895557e+03 4.91900195e+03 4.91890625e+03 4.91900439e+03 4.91922949e+03 4.91933447e+03 4.91901709e+03 4.91879004e+03 4.91877490e+03 4.91881787e+03 4.91884863e+03 4.91879346e+03 4.91877881e+03 4.91877344e+03 4.91885449e+03 4.91904199e+03 4.91902295e+03 4.91883740e+03 4.91878467e+03 4.91878857e+03 4.91878955e+03 4.91878271e+03 4.91882764e+03 4.91912354e+03 4.91920410e+03 4.91893213e+03 4.91878027e+03 4.91879346e+03 4.91882520e+03 4.91891211e+03 4.91892139e+03 4.91880469e+03 4.91932422e+03 4.91933643e+03 4.91888135e+03 4.91879004e+03 4.91878516e+03 4.91877148e+03 4.91881738e+03 4.91898877e+03 4.91895215e+03 4.91878076e+03 4.91885645e+03 4.91889502e+03 4.91896143e+03 4.91877148e+03 4.91893506e+03 4.91906494e+03 4.91880859e+03 4.91880078e+03 4.91890820e+03 4.91901074e+03 4.91908936e+03 4.91883789e+03 4.91877979e+03 4.91877344e+03 4.91878271e+03 4.91878467e+03 4.91880225e+03 4.91880078e+03 4.91880420e+03 4.91879639e+03 4.91880273e+03 4.91887012e+03 4.91888721e+03 4.91877002e+03 4.91871582e+03 4.92008496e+03 4.92136865e+03 4.91933008e+03 4.91871973e+03 4.92699365e+03 6.26937061e+03 9.26725586e+03 1.96214082e+04 1.96294043e+04 2.89431719e+04 6.13046953e+04 -9.73816955e+10 -6.96442946e+11 -2.99451822e+10 5.04543232e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. -3.92269292e+10 -1.61117041e+10 -4.14971740e+10 -6.83881759e+10 -2.63242588e+10 7.10784154e+09 6.17107031e+04 3.07488887e+04 1.99638262e+04 1.98236094e+04 1.97447871e+04 1.97372012e+04 1.97355996e+04 1.97354570e+04 1.97357246e+04 1.97361426e+04 1.02819111e+04 6.82355811e+03 4.96597168e+03 4.92698975e+03 4.92251025e+03 4.92117725e+03 4.92054492e+03 4.91973633e+03 4.91889990e+03 4.91879004e+03 4.91878174e+03 4.91878320e+03 4.91883350e+03 4.91884424e+03 4.91886816e+03 4.91891211e+03 4.91896436e+03 4.91904492e+03 4.91895898e+03 4.91894434e+03 4.91900781e+03 4.91905420e+03 4.91909277e+03 4.91893896e+03 4.91887744e+03 4.91885059e+03 4.91891211e+03 4.91897314e+03 4.91910498e+03 4.91913525e+03 4.91900879e+03 4.91877734e+03 4.91884766e+03 4.91888232e+03 4.91879395e+03 4.91877930e+03 4.91879443e+03 4.91883496e+03 4.91881934e+03 4.91878906e+03 4.91877441e+03 4.91879248e+03 4.91882861e+03 4.91884277e+03 4.91901514e+03 4.91887061e+03 4.91879102e+03 4.91877051e+03 4.91880859e+03 4.91886084e+03 4.91890234e+03 4.91880176e+03 4.91877539e+03 4.91878076e+03 4.91877002e+03 4.91884912e+03 4.91890869e+03 4.91885303e+03 4.91877490e+03 4.91877930e+03 4.91878320e+03 4.91878027e+03 4.91898438e+03 4.91895801e+03 4.91886572e+03 4.91878516e+03 4.91909180e+03 4.91972021e+03 4.91972998e+03 4.91926221e+03 4.91901367e+03 4.91910547e+03 4.91916992e+03 4.91901904e+03 4.91906201e+03 4.91929297e+03 4.91974023e+03 4.91948779e+03 4.91898682e+03 4.91876514e+03 4.91876855e+03 4.91877832e+03 4.91877539e+03 4.91880615e+03 4.91877686e+03 4.91882178e+03 4.91877881e+03 4.91882764e+03 4.91889746e+03 4.91876807e+03 4.91881641e+03 4.91882129e+03 4.91906396e+03 4.91901025e+03 4.91877539e+03 4.91890088e+03 4.91892090e+03 4.91892090e+03 4.91888086e+03 4.91886768e+03 4.91879688e+03 4.91879053e+03 4.91880615e+03 4.91880859e+03 4.91876953e+03 4.91876562e+03 4.91876367e+03 4.91876123e+03 4.91876318e+03 4.91877051e+03 4.91877441e+03 4.91888574e+03 4.91926953e+03 4.91920801e+03 4.91888037e+03 4.91876953e+03 4.91887549e+03 4.91920850e+03 4.91926709e+03 4.91893604e+03 4.91880029e+03 4.91878516e+03 4.91877832e+03 4.91877539e+03 4.91876270e+03 4.91875342e+03 4.91876660e+03 4.91877246e+03 4.91881104e+03 4.91879297e+03 4.91876074e+03 4.91878467e+03 4.91878711e+03 4.91878027e+03 4.91878418e+03 4.91883496e+03 4.91915820e+03 4.91985840e+03 4.91980518e+03 4.91927002e+03 4.91887451e+03 4.91919580e+03 4.91974756e+03 4.91961816e+03 4.91894287e+03 4.91876416e+03 4.91877197e+03 4.91880859e+03 4.91883154e+03 4.91881885e+03 4.91881250e+03 4.91880957e+03 4.91878906e+03 4.91878027e+03 4.91887842e+03 4.91913965e+03 4.91906348e+03 4.91885205e+03 4.91876953e+03 4.91877100e+03 4.91876904e+03 4.91882715e+03 4.91907129e+03 4.91902148e+03 4.91885498e+03 4.91878564e+03 4.91879443e+03 4.91877295e+03 4.91881689e+03 4.91916260e+03 4.91930957e+03 4.91897852e+03 4.91879688e+03 4.91880273e+03 4.91882031e+03 4.91878320e+03 4.91876611e+03 4.91877979e+03 4.91879150e+03 4.91905078e+03 4.91949463e+03 4.91948828e+03 4.91898535e+03 4.91878906e+03 4.91885645e+03 4.91890283e+03 4.91916211e+03 4.91954053e+03 4.91945703e+03 4.91893799e+03 4.91877832e+03 4.91877734e+03 4.91877881e+03 4.91879443e+03 4.91876709e+03 4.91877051e+03 4.91877393e+03 4.91878369e+03 4.91876123e+03 4.91876172e+03 4.91876172e+03 4.91876221e+03 4.91884570e+03 4.91898242e+03 4.91909033e+03 4.91905908e+03 4.91889502e+03 4.91887354e+03 4.91885059e+03 4.91886523e+03 4.91884326e+03 4.91880762e+03 4.91884814e+03 4.91881201e+03 4.91879443e+03 4.91878857e+03 4.91885889e+03 4.91888232e+03 4.91885889e+03 4.91882764e+03 4.91882910e+03 4.91882959e+03 4.91878662e+03 4.91879199e+03 4.91876465e+03 4.91877832e+03 4.91878809e+03 4.91879102e+03 4.91899951e+03 4.91886035e+03 4.91883252e+03 4.91909814e+03 4.91901416e+03 4.91883691e+03 4.91879590e+03 4.91879639e+03 4.91879248e+03 4.91883984e+03 4.91883594e+03 4.91883740e+03 4.91880176e+03 4.91878076e+03 4.91876953e+03 4.91878174e+03 4.91876367e+03 4.91877930e+03 4.91880371e+03 4.91880518e+03 4.91878418e+03 4.91877930e+03 4.91876611e+03 4.91876465e+03 4.91877734e+03 4.91876416e+03 4.91889502e+03 4.91922852e+03 4.91916992e+03 4.91895166e+03 4.91876514e+03 4.91875977e+03 4.91876221e+03 4.91881543e+03 4.91897070e+03 4.91909961e+03 4.91918799e+03 4.91892480e+03 4.91880957e+03 4.91877734e+03 4.91876855e+03 4.91877588e+03 4.91878857e+03 4.91877490e+03 4.91877295e+03 4.91877197e+03 4.91876416e+03 4.91879541e+03 4.91883203e+03 4.91887500e+03 4.91884814e+03 4.91913135e+03 4.91942578e+03 4.91928906e+03 4.91887793e+03 4.91876465e+03 4.91879639e+03 4.91884424e+03 4.91882422e+03 4.91880225e+03 4.91894727e+03 4.91933691e+03 4.91929395e+03 4.91887842e+03 4.91876807e+03 4.91877734e+03 4.91883057e+03 4.91883057e+03 4.91877051e+03 4.91877246e+03 4.91876660e+03 4.91879932e+03 4.91877490e+03 4.91878076e+03 4.91881738e+03 4.91879688e+03 4.91877539e+03 4.91880762e+03 4.91876562e+03 4.91887549e+03 4.91894971e+03 4.91906396e+03 4.91932812e+03 4.91982764e+03 4.91977246e+03 4.91947949e+03 4.91957324e+03 4.91931445e+03 4.91923584e+03 4.91888672e+03 4.91877295e+03 4.91895801e+03 4.91904541e+03 4.91892529e+03 4.91884814e+03 4.91880859e+03 4.91879102e+03 4.91878906e+03 4.91881885e+03 4.91886816e+03 4.91876465e+03 4.91892383e+03 4.91906885e+03 4.91899609e+03 4.91880127e+03 4.91876465e+03 4.91877148e+03 4.91878516e+03 4.91876807e+03 4.91877148e+03 4.91880664e+03 4.91887305e+03 4.91903613e+03 4.91940283e+03 4.91905859e+03 4.91883252e+03 4.91877686e+03 4.91898535e+03 4.91907715e+03 4.91896240e+03 4.91876953e+03 4.91885254e+03 4.91912549e+03 4.91933398e+03 4.91903174e+03 4.91881787e+03 4.91904639e+03 4.91948389e+03 4.91932373e+03 4.91882959e+03 4.91877246e+03 4.91883691e+03 4.91900244e+03 4.91878857e+03 4.91886523e+03 4.91877197e+03 4.91909668e+03 4.91942139e+03 4.91916211e+03 4.91892969e+03 4.91898633e+03 4.91931152e+03 4.91976172e+03 4.91945996e+03 4.91890283e+03 4.91876855e+03 4.91876758e+03 4.91876465e+03 4.91878223e+03 4.91877148e+03 4.91877393e+03 4.91879102e+03 4.91891797e+03 4.91893896e+03 4.91880273e+03 4.91877197e+03 4.91878857e+03 4.91903271e+03 4.91918994e+03 4.91898242e+03 4.91886084e+03 4.91876660e+03 4.91878125e+03 4.91877051e+03 4.91876758e+03 4.91878516e+03 4.91877344e+03 4.91893115e+03 4.91942627e+03 4.91890527e+03 4.91892139e+03 4.91895898e+03 4.91883838e+03 4.91901465e+03 4.91878516e+03 4.91878809e+03 4.91879736e+03 4.91885645e+03 4.91881982e+03 4.91878174e+03 4.91878271e+03 4.91883252e+03 4.91887939e+03 4.91880078e+03 4.91878516e+03 4.91877588e+03 4.91877783e+03 4.91881738e+03 4.91899023e+03 4.91904102e+03 4.91878955e+03 4.91879688e+03 4.91942480e+03 4.92034912e+03 4.91990820e+03 4.91893848e+03 4.91892090e+03 4.91910889e+03 4.91890918e+03 4.91881885e+03 4.91892773e+03 4.91877588e+03 4.91890918e+03 4.91884766e+03 4.91879639e+03 4.91885205e+03 4.91890332e+03 4.91888525e+03 4.91883740e+03 4.91876562e+03 4.91877441e+03 4.91881348e+03 4.91877490e+03 4.91878076e+03 4.91884277e+03 4.91885254e+03 4.91890576e+03 4.91912646e+03 4.91914307e+03 4.91892285e+03 4.91878516e+03 4.91881006e+03 4.91907812e+03 4.91911133e+03 4.91909668e+03 4.91922803e+03 4.92041064e+03 4.92119629e+03 4.92048486e+03 4.91917480e+03 4.91895459e+03 4.91905078e+03 4.91915967e+03 4.91890186e+03 4.91882666e+03 4.91877246e+03 4.91877344e+03 4.91877002e+03 4.91877930e+03 4.91877393e+03 4.91878711e+03 4.91879150e+03 4.91892188e+03 4.91913770e+03 4.91892334e+03 4.91878223e+03 4.91899316e+03 4.91921045e+03 4.91887842e+03 4.91887354e+03 4.91928076e+03 4.91925684e+03 4.91923389e+03 4.91902588e+03 4.91885938e+03 4.91881152e+03 4.91882959e+03 4.91879688e+03 4.91876611e+03 4.91877148e+03 4.91885693e+03 4.91877734e+03 4.91899463e+03 4.91951270e+03 4.91959229e+03 4.91941895e+03 4.91912793e+03 4.91890283e+03 4.91878174e+03 4.91878320e+03 4.91877197e+03 4.91877344e+03 4.91877100e+03 4.91877734e+03 4.91878564e+03 4.91880420e+03 4.91878906e+03 4.91877197e+03 4.91877246e+03 4.91877197e+03 4.91890820e+03 4.91943896e+03 4.91954785e+03 4.91908350e+03 4.91881934e+03 4.91883350e+03 4.91883350e+03 4.91884619e+03 4.91879395e+03 4.91880762e+03 4.91881055e+03 4.91907373e+03 4.91945459e+03 4.91920264e+03 4.91885205e+03 4.91879541e+03 4.91938135e+03 4.92006543e+03 4.91959424e+03 4.91886523e+03 4.91887305e+03 4.91905762e+03 4.91910547e+03 4.91888037e+03 4.91877783e+03 4.91894922e+03 4.91917725e+03 4.91956982e+03 4.91972510e+03 4.91914453e+03 4.91889062e+03 4.91888623e+03 4.91986963e+03 4.92065283e+03 4.91958057e+03 4.91885156e+03 4.91890918e+03 4.91951221e+03 4.91970166e+03 4.91928125e+03 4.91892627e+03 4.91910547e+03 4.91940967e+03 4.91959082e+03 4.91927979e+03 4.91899121e+03 4.91888135e+03 4.91922705e+03 4.91984033e+03 4.91995361e+03 4.91942578e+03 4.91885400e+03 4.91902637e+03 4.91933545e+03 4.91938623e+03 4.91900732e+03 4.91896582e+03 4.91951416e+03 4.91950879e+03 4.91903955e+03 4.91877100e+03 4.91877539e+03 4.91878711e+03 4.91881592e+03 4.91919434e+03 4.91939795e+03 4.91916309e+03 4.91882129e+03 4.91876221e+03 4.91875781e+03 4.91881396e+03 4.91892285e+03 4.91884326e+03 4.92196240e+03 4.92753760e+03 4.92456299e+03 4.91889111e+03 4.92222314e+03 4.91880957e+03 4.91974658e+03 4.92341309e+03 6.17597949e+03 1.06739951e+04 4.50590391e+04 1697351808. 145294. -2.39559875e+12 9.50582231e+10 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. 0. 0. 0. 1.65203379e+04 7.67623828e+03 5.01736914e+03 4.95090674e+03 4.92291943e+03 4.91962988e+03 4.91970508e+03 4.91909863e+03 4.91907715e+03 4.91914941e+03 4.91904346e+03 4.91953662e+03 4.92051074e+03 4.91938330e+03 4.91953369e+03 4.92076660e+03 4.91975391e+03 4.91903662e+03 4.91917578e+03 4.91909619e+03 4.91906348e+03 4.91912109e+03 4.91944189e+03 4.91916016e+03 4.91912354e+03 4.91946436e+03 4.91919141e+03 4.91907812e+03 4.91914990e+03 4.91905273e+03 4.91954932e+03 4.92008496e+03 4.91954297e+03 4.91964307e+03 4.92044922e+03 4.91970068e+03 4.91905371e+03 4.91967432e+03 4.91905127e+03 4.92090771e+03 4.92214990e+03 4.92021631e+03 4.91913818e+03 4.91904834e+03 4.91906982e+03 4.91905322e+03 4.91904150e+03 4.91903955e+03 4.91907422e+03 4.92049121e+03 4.92253760e+03 4.92140479e+03 4.91933740e+03 4.91906934e+03 4.91912793e+03 4.91979248e+03 4.92060791e+03 4.91952637e+03 4.91932861e+03 4.91956934e+03 4.91930469e+03 4.91904102e+03 4.91973291e+03 4.91955078e+03 4.91913135e+03 4.91944580e+03 4.91915820e+03 4.91919141e+03 4.91912256e+03 4.91911475e+03 4.91909570e+03 4.91907861e+03 4.91928857e+03 4.91906689e+03 4.91966699e+03 4.92061572e+03 4.92005615e+03 4.91904248e+03 4.91930127e+03 4.91919189e+03 4.91905908e+03 4.91904395e+03 4.91927783e+03 4.91923926e+03 4.91906885e+03 4.91928076e+03 4.91904639e+03 4.91985059e+03 4.91997266e+03 4.91906787e+03 4.91943555e+03 4.91935938e+03 4.91903418e+03 4.91905127e+03 4.91905371e+03 4.91912500e+03 4.92027490e+03 4.92135303e+03 4.91987109e+03 4.91910596e+03 4.91982373e+03 4.91939014e+03 4.91904883e+03 4.91981104e+03 4.92091895e+03 4.92052783e+03 4.92009766e+03 4.91995557e+03 4.91973096e+03 4.91906885e+03 4.91933984e+03 4.91905811e+03 4.91990576e+03 4.92108936e+03 4.92004785e+03 4.91906104e+03 4.91950439e+03 4.91913965e+03 4.91906201e+03 4.91914893e+03 4.91911670e+03 4.91953760e+03 4.92138135e+03 4.92155225e+03 4.91961816e+03 4.91906006e+03 4.91906006e+03 4.91922559e+03 4.91975439e+03 4.91990820e+03 4.91949219e+03 4.91916260e+03 4.91905518e+03 4.91937744e+03 4.91970459e+03 4.91923779e+03 4.91904932e+03 4.91904834e+03 4.91906738e+03 4.91907031e+03 4.91907471e+03 4.91904688e+03 4.91908203e+03 4.91934814e+03 4.91954150e+03 4.91912939e+03 4.91904297e+03 4.91908838e+03 4.91944629e+03 4.91917969e+03 4.91966895e+03 4.92082861e+03 4.91931348e+03 4.91928320e+03 4.91934229e+03 4.91904004e+03 4.91920557e+03 4.91909229e+03 4.91909668e+03 4.91946289e+03 4.92038379e+03 4.92062012e+03 4.91992188e+03 4.91910547e+03 4.91908203e+03 4.91906738e+03 4.91920068e+03 4.91912109e+03 4.91903467e+03 4.91906592e+03 4.92019727e+03 4.91992773e+03 4.91933447e+03 4.91903857e+03 4.91935693e+03 4.92184717e+03 4.92399268e+03 4.92201562e+03 4.91931250e+03 4.91904395e+03 4.91905957e+03 4.91906006e+03 4.91914111e+03 4.91905957e+03 4.91958936e+03 4.92164062e+03 4.92161621e+03 4.91969678e+03 4.91923926e+03 4.91983105e+03 4.91928955e+03 4.91916602e+03 4.91953613e+03 4.91946582e+03 4.91988623e+03 4.92052197e+03 4.92024219e+03 4.91906836e+03 4.91930957e+03 4.91910107e+03 4.92012988e+03 4.92138184e+03 4.91981738e+03 4.91913525e+03 4.91949219e+03 4.91906592e+03 4.91931055e+03 4.91908057e+03 4.91911133e+03 4.91908838e+03 4.91922119e+03 4.91934277e+03 4.91903809e+03 4.91984326e+03 4.92010498e+03 4.91939014e+03 4.91905078e+03 4.91904102e+03 4.91910400e+03 4.91919043e+03 4.91904492e+03 4.91910498e+03 4.91942334e+03 4.91955811e+03 4.91948145e+03 4.91908691e+03 4.91904492e+03 4.91908203e+03 4.91907227e+03 4.91906836e+03 4.91911133e+03 4.91904199e+03 4.91936279e+03 4.91975439e+03 4.91948584e+03 4.91924072e+03 4.92019922e+03 4.92002881e+03 4.91910400e+03 4.91985254e+03 4.91998584e+03 4.91921729e+03 4.91906885e+03 4.91925586e+03 4.91923193e+03 4.91905811e+03 4.91908496e+03 4.91906934e+03 4.91927686e+03 4.91907910e+03 4.91991553e+03 4.91975000e+03 4.91917188e+03 4.91904590e+03 4.91917822e+03 4.91993555e+03 4.91923438e+03 4.91904736e+03 4.91932227e+03 4.91916064e+03 4.91916211e+03 4.91951465e+03 4.91975146e+03 4.91908643e+03 4.91904980e+03 4.91907275e+03 4.91932959e+03 4.91933105e+03 4.91932617e+03 4.91937354e+03 4.91990137e+03 4.92024561e+03 4.91920996e+03 4.91905420e+03 4.91907959e+03 4.91937842e+03 4.91940234e+03 4.91912207e+03 4.91908398e+03 4.91928369e+03 4.91914453e+03 4.91917041e+03 4.91912988e+03 4.91938477e+03 4.91974219e+03 4.91957129e+03 4.91933936e+03 4.91910400e+03 4.91919434e+03 4.91958008e+03 4.91930811e+03 4.91919727e+03 4.91935352e+03 4.91918506e+03 4.91911572e+03 4.91918262e+03 4.91905225e+03 4.91983105e+03 4.92040283e+03 4.91953467e+03 4.91917676e+03 4.91939355e+03 4.91911572e+03 4.91917627e+03 4.91938574e+03 4.91908447e+03 4.91908984e+03 4.91906055e+03 4.91928027e+03 4.91959766e+03 4.91966846e+03 4.91917529e+03 4.91906982e+03 4.91920459e+03 4.91973389e+03 4.91937988e+03 4.91906201e+03 4.91908350e+03 4.91937793e+03 4.91942969e+03 4.91917285e+03 4.91916650e+03 4.91996045e+03 4.92032520e+03 4.91966113e+03 4.91907617e+03 4.91906396e+03 4.91918311e+03 4.91938770e+03 4.91929297e+03 4.91908594e+03 4.91913428e+03 4.91912891e+03 4.91958984e+03 4.91995752e+03 4.91996289e+03 4.91949463e+03 4.91929004e+03 4.91960303e+03 4.92014111e+03 4.91973779e+03 4.91911377e+03 4.91906299e+03 4.91905908e+03 4.91909277e+03 4.91954297e+03 4.91932373e+03 4.91906982e+03 4.91908105e+03 4.91913037e+03 4.91971924e+03 4.91910889e+03 4.91905762e+03 4.91917871e+03 4.91946191e+03 4.91952100e+03 4.91922803e+03 4.91930859e+03 4.91950879e+03 4.91904883e+03 4.91945654e+03 4.91917627e+03 4.91931250e+03 4.91992383e+03 4.91920459e+03 4.91905908e+03 4.91906299e+03 4.91920166e+03 4.91969580e+03 4.92041797e+03 4.92201660e+03 4.92130811e+03 4.91983740e+03 4.91953125e+03 4.91999365e+03 4.92080859e+03 4.91944678e+03 4.91910303e+03 4.91905615e+03 4.91906787e+03 4.91906152e+03 4.91941016e+03 4.92144092e+03 4.92231641e+03 4.92004346e+03 4.91922168e+03 4.91969434e+03 4.91917920e+03 4.92112012e+03 4.92137256e+03 4.91955225e+03 4.91911230e+03 4.91930664e+03 4.92036719e+03 4.92127930e+03 4.92026758e+03 4.91905664e+03 4.91906006e+03 4.91915479e+03 4.92011182e+03 4.92224805e+03 4.92229688e+03 4.92131543e+03 4.91929492e+03 4.91925830e+03 4.91974365e+03 4.91911768e+03 4.92007812e+03 4.92186523e+03 4.92015527e+03 4.91904199e+03 4.91908936e+03 4.92057178e+03 4.92353955e+03 4.92175049e+03 4.91921143e+03 4.91919775e+03 4.91923535e+03 4.91912988e+03 4.91977832e+03 4.92082910e+03 4.91960303e+03 4.91924268e+03 4.91906055e+03 4.91935352e+03 4.91972168e+03 4.91916797e+03 4.91903564e+03 4.91978711e+03 4.91998047e+03 4.91934668e+03 4.91907031e+03 4.92044580e+03 4.92084521e+03 4.91954004e+03 4.91951562e+03 4.92071338e+03 4.91952051e+03 4.91949902e+03 4.92104443e+03 4.92022705e+03 4.91926514e+03 4.91927148e+03 4.91983057e+03 4.92047559e+03 4.92053076e+03 4.91929639e+03 4.91904834e+03 4.91943262e+03 4.91938770e+03 4.91908057e+03 4.91909521e+03 4.91951221e+03 4.91942041e+03 4.91904443e+03 4.91920850e+03 4.91919727e+03 4.91907959e+03 4.91977002e+03 4.91932520e+03 4.91905859e+03 4.91922363e+03 4.91907227e+03 4.92025830e+03 4.92013525e+03 4.91922168e+03 4.91929785e+03 4.91932617e+03 4.91906836e+03 4.91965088e+03 4.92053076e+03 4.91930859e+03 4.91908740e+03 4.91905664e+03 4.91911328e+03 4.91916113e+03 4.91922559e+03 4.91904492e+03 4.91906738e+03 4.91931396e+03 4.91927295e+03 4.91904785e+03 4.91975879e+03 4.92057275e+03 4.91961475e+03 4.91918164e+03 4.92101025e+03 4.92070020e+03 4.91905518e+03 4.92018457e+03 4.92111182e+03 4.91937939e+03 4.91923633e+03 4.91949072e+03 4.91904541e+03 4.91959814e+03 4.91925439e+03 4.91904395e+03 4.91941504e+03 4.91951953e+03 4.91923340e+03 4.91904395e+03 4.91940723e+03 4.91932910e+03 4.91902148e+03 4.91986719e+03 4.92018164e+03 4.91920410e+03 4.91931055e+03 4.91923535e+03 4.91909961e+03 4.91965820e+03 4.91929834e+03 4.91904541e+03 4.91905615e+03 4.91908740e+03 4.91905029e+03 4.91913135e+03 4.91903564e+03 4.91908203e+03 4.91926855e+03 4.91903223e+03 4.91912891e+03 4.91971484e+03 4.92033057e+03 4.91961914e+03 4.91919238e+03 4.91911963e+03 4.91933447e+03 4.91905518e+03 4.91924365e+03 4.91936230e+03 4.91906689e+03 4.91977002e+03 4.91965283e+03 4.91915039e+03 4.91916846e+03 4.91938916e+03 4.91918018e+03 4.91904980e+03 4.91910889e+03 4.91912695e+03 4.91967236e+03 4.92103809e+03 4.92058984e+03 4.91935352e+03 4.91929639e+03 4.91969336e+03 4.92120801e+03 4.92172754e+03 4.92093213e+03 4.91986182e+03 4.91903711e+03 4.91916553e+03 4.91904688e+03 4.91938330e+03 4.91990918e+03 4.91917383e+03 4.91918652e+03 4.91916162e+03 4.91927246e+03 4.92025098e+03 4.91982568e+03 4.91904639e+03 4.91946387e+03 4.91952197e+03 4.91901953e+03 4.91955664e+03 4.91993555e+03 4.91982471e+03 4.91943408e+03 4.91916406e+03 4.91903076e+03 4.91904590e+03 4.91904053e+03 4.91909375e+03 4.91904932e+03 4.91982422e+03 4.92070361e+03 4.91942871e+03 4.91914844e+03 4.91971582e+03 4.91908398e+03 4.91952441e+03 4.91977832e+03 4.91911816e+03 4.91937793e+03 4.91960498e+03 4.91906934e+03 4.91905273e+03 4.91909131e+03 4.91909863e+03 4.91917529e+03 4.91913379e+03 4.91906543e+03 4.91912695e+03 4.91906982e+03 4.91902295e+03 4.91951465e+03 4.92064990e+03 4.92008203e+03 4.91951807e+03 4.91908301e+03 4.91918652e+03 4.91915234e+03 4.91964502e+03 4.92181836e+03 4.92220215e+03 4.92021191e+03 4.91936084e+03 4.92529150e+03 4.92603906e+03 4.92042725e+03 6.34341309e+03 9.22126562e+03 2.63704141e+04 4.78194219e+04 2.53760246e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.43718418e+04 7.15501562e+03 4.93576123e+03 4.92867139e+03 4.92313184e+03 4.92162354e+03 4.91996436e+03 4.91943213e+03 4.91935889e+03 4.91933057e+03 4.91906543e+03 4.91959033e+03 4.91942090e+03 4.91913916e+03 4.92013721e+03 4.92040283e+03 4.91917822e+03 4.91943945e+03 4.91974951e+03 4.91906348e+03 4.91972070e+03 4.91975635e+03 4.91905615e+03 4.91908545e+03 4.91948193e+03 4.91960498e+03 4.91915820e+03 4.91908008e+03 4.91909277e+03 4.91920264e+03 4.91950488e+03 4.91943604e+03 4.91906445e+03 4.91989893e+03 4.91991650e+03 4.91913477e+03 4.91914062e+03 4.91911572e+03 4.91924316e+03 4.92053076e+03 4.92025146e+03 4.91902441e+03 4.92051172e+03 4.92022119e+03 4.91905566e+03 4.91965039e+03 4.91969775e+03 4.91904150e+03 4.91904248e+03 4.91907422e+03 4.91914062e+03 4.91903760e+03 4.91907080e+03 4.91993018e+03 4.91943945e+03 4.91902783e+03 4.91911133e+03 4.91908496e+03 4.92017432e+03 4.92014551e+03 4.91945703e+03 4.91903027e+03 4.91917041e+03 4.91914893e+03 4.92079980e+03 4.92318408e+03 4.92160938e+03 4.91936719e+03 4.91909424e+03 4.91969092e+03 4.92057373e+03 4.92034082e+03 4.91907715e+03 4.91903955e+03 4.91913672e+03 4.91957861e+03 4.91951611e+03 4.91947363e+03 4.91983887e+03 4.91935938e+03 4.91903027e+03 4.91911963e+03 4.91919385e+03 4.92096533e+03 4.92139355e+03 4.92039893e+03 4.91918359e+03 4.91905420e+03 4.91909424e+03 4.91921045e+03 4.91983984e+03 4.91968652e+03 4.91905615e+03 4.91932568e+03 4.91907812e+03 4.91976953e+03 4.91971387e+03 4.91904492e+03 4.91930957e+03 4.91920898e+03 4.91913281e+03 4.91905225e+03 4.91908643e+03 4.92007227e+03 4.91993115e+03 4.91912939e+03 4.91906445e+03 4.91906836e+03 4.91923828e+03 4.91928467e+03 4.91905762e+03 4.91904834e+03 4.91937012e+03 4.91922217e+03 4.91907178e+03 4.91977344e+03 4.92008008e+03 4.91903711e+03 4.91915918e+03 4.91903174e+03 4.91911914e+03 4.91916162e+03 4.91904590e+03 4.91904346e+03 4.91904346e+03 4.91912793e+03 4.91915869e+03 4.91910352e+03 4.91945801e+03 4.91945361e+03 4.91903564e+03 4.91926709e+03 4.91922412e+03 4.91905127e+03 4.91904980e+03 4.91914404e+03 4.91941943e+03 4.92022510e+03 4.91950049e+03 4.91905762e+03 4.91944678e+03 4.91930518e+03 4.91905518e+03 4.91910107e+03 4.91905176e+03 4.91906396e+03 4.91904590e+03 4.91949805e+03 4.91991650e+03 4.92042432e+03 4.92047559e+03 4.91964355e+03 4.91913037e+03 4.91933154e+03 4.91960107e+03 4.91941016e+03 4.91905713e+03 4.91907520e+03 4.91949316e+03 4.92047412e+03 4.91979834e+03 4.91904541e+03 4.91974365e+03 4.91967285e+03 4.91908984e+03 4.91951221e+03 4.91941943e+03 4.91904492e+03 4.91906689e+03 4.91910059e+03 4.91908545e+03 4.91909570e+03 4.91913330e+03 4.91916650e+03 4.91904883e+03 4.91965479e+03 4.91959521e+03 4.91927148e+03 4.91904004e+03 4.91915625e+03 4.91927002e+03 4.91907373e+03 4.91908350e+03 4.91950732e+03 4.92063770e+03 4.91985840e+03 4.91903223e+03 4.91952100e+03 4.91955811e+03 4.91905225e+03 4.91908105e+03 4.91909961e+03 4.91917480e+03 4.91913037e+03 4.91908252e+03 4.91961621e+03 4.92024316e+03 4.92024512e+03 4.92126562e+03 4.92053223e+03 4.91931494e+03 4.91903857e+03 4.91906104e+03 4.91928467e+03 4.91935938e+03 4.91907861e+03 4.91935938e+03 4.92053369e+03 4.91975488e+03 4.91910938e+03 4.92039062e+03 4.91970703e+03 4.91904834e+03 4.91910547e+03 4.91910547e+03 4.91922900e+03 4.91922510e+03 4.91903564e+03 4.91907959e+03 4.91928125e+03 4.91923486e+03 4.91910010e+03 4.91909082e+03 4.91973096e+03 4.92006445e+03 4.91962988e+03 4.91914502e+03 4.91908691e+03 4.91908984e+03 4.91903516e+03 4.91916748e+03 4.91925635e+03 4.91914600e+03 4.91905811e+03 4.91907520e+03 4.91911475e+03 4.91904883e+03 4.91902930e+03 4.91906104e+03 4.91906543e+03 4.91910889e+03 4.91916260e+03 4.91905518e+03 4.91906006e+03 4.91905664e+03 4.91906006e+03 4.91908838e+03 4.91906250e+03 4.91903320e+03 4.91905322e+03 4.91904590e+03 4.91903906e+03 4.91905615e+03 4.91903369e+03 4.91905371e+03 4.91904443e+03 4.91904639e+03 4.91907275e+03 4.91910205e+03 4.91907129e+03 4.91905811e+03 4.91908496e+03 4.91916357e+03 4.91912695e+03 4.91918604e+03 4.91914502e+03 4.91912305e+03 4.91904443e+03 4.91906689e+03 4.91907080e+03 4.91908887e+03 4.91905371e+03 4.91908154e+03 4.91910449e+03 4.91909668e+03 4.91911279e+03 4.91910254e+03 4.91905322e+03 4.91905029e+03 4.91905518e+03 4.91909570e+03 4.91911621e+03 4.91910449e+03 4.91917480e+03 4.91912744e+03 4.91915918e+03 4.91909814e+03 4.91910449e+03 4.91902881e+03 4.91908252e+03 4.91913135e+03 4.91907520e+03 4.91905908e+03 4.91907568e+03 4.91905225e+03 4.91904541e+03 4.91904590e+03 4.91905371e+03 4.91908008e+03 4.91910059e+03 4.91905762e+03 4.91903809e+03 4.91903613e+03 4.91906104e+03 4.91904590e+03 4.91904688e+03 4.91906543e+03 4.91904639e+03 4.91903369e+03 4.91910645e+03 4.91908496e+03 4.91909521e+03 4.91904492e+03 4.91913330e+03 4.91942090e+03 4.91951807e+03 4.91933252e+03 4.91913379e+03 4.91905225e+03 4.91905957e+03 4.91905127e+03 4.91905273e+03 4.91909277e+03 4.91930322e+03 4.91924463e+03 4.91907373e+03 4.91904053e+03 4.91905469e+03 4.91904248e+03 4.91904639e+03 4.91905078e+03 4.91903711e+03 4.91904199e+03 4.91906055e+03 4.91908008e+03 4.91904053e+03 4.91904883e+03 4.91903174e+03 4.91916846e+03 4.91946533e+03 4.91947900e+03 4.91928320e+03 4.91907129e+03 4.91909717e+03 4.91914551e+03 4.91914795e+03 4.91912305e+03 4.91906494e+03 4.91919824e+03 4.91930713e+03 4.91937500e+03 4.91908691e+03 4.91906689e+03 4.91909229e+03 4.91906006e+03 4.91923926e+03 4.91965723e+03 4.91930176e+03 4.91904346e+03 4.91908350e+03 4.91906836e+03 4.91909814e+03 4.91911035e+03 4.91936865e+03 4.91953223e+03 4.91940039e+03 4.91915625e+03 4.91904932e+03 4.91906006e+03 4.91903906e+03 4.91909326e+03 4.91926904e+03 4.91927051e+03 4.91909082e+03 4.91904443e+03 4.91905713e+03 4.91904932e+03 4.91904150e+03 4.91907373e+03 4.91910059e+03 4.91907031e+03 4.91904346e+03 4.91902979e+03 4.91903223e+03 4.91905566e+03 4.91906982e+03 4.91906689e+03 4.91906006e+03 4.91906641e+03 4.91904785e+03 4.91908057e+03 4.91907520e+03 4.91911963e+03 4.91926025e+03 4.91907715e+03 4.91905566e+03 4.91904492e+03 4.91906445e+03 4.91913672e+03 4.91914795e+03 4.91924170e+03 4.91916553e+03 4.91913916e+03 4.91904980e+03 4.91904199e+03 4.91907861e+03 4.91905957e+03 4.91904346e+03 4.91904053e+03 4.91905322e+03 4.91907568e+03 4.91910010e+03 4.91935547e+03 4.91953271e+03 4.91910938e+03 4.91905225e+03 4.91903418e+03 4.91903662e+03 4.91904590e+03 4.91906250e+03 4.91903809e+03 4.91907227e+03 4.91917725e+03 4.91946143e+03 4.91942041e+03 4.91925342e+03 4.91907275e+03 4.91906348e+03 4.91908398e+03 4.91912695e+03 4.91912598e+03 4.91906836e+03 4.91930469e+03 4.91981543e+03 4.91981543e+03 4.91923096e+03 4.91904736e+03 4.91903809e+03 4.91907666e+03 4.91952783e+03 4.92259082e+03 4.94470410e+03 4.96950439e+03 4.98045410e+03 5.00590234e+03 6.91670459e+03 1.04095625e+04 1.96352402e+04 1.96196836e+04 1.96214082e+04 1.96294043e+04 2.89431719e+04 6.13046953e+04 -9.73816955e+10 -6.96442946e+11 -2.99451822e+10 5.04543232e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.52427012e+04 7.62884424e+03 4.96986914e+03 4.94107812e+03 4.92355762e+03 4.92115771e+03 4.91986914e+03 4.91916211e+03 4.91916504e+03 4.91915869e+03 4.91912891e+03 4.91914600e+03 4.91935352e+03 4.91979395e+03 4.91935645e+03 4.91905322e+03 4.91903320e+03 4.91918066e+03 4.91952539e+03 4.91927051e+03 4.91916992e+03 4.91916162e+03 4.91921680e+03 4.91938086e+03 4.91935840e+03 4.91930176e+03 4.91914258e+03 4.91914453e+03 4.91909521e+03 4.91909131e+03 4.91904248e+03 4.91920117e+03 4.91920703e+03 4.91906494e+03 4.91903174e+03 4.91903516e+03 4.91909326e+03 4.91912842e+03 4.91922461e+03 4.91926221e+03 4.91924219e+03 4.91933350e+03 4.91935449e+03 4.91926758e+03 4.91919336e+03 4.91911572e+03 4.91916211e+03 4.91912158e+03 4.91910059e+03 4.91913428e+03 4.91914502e+03 4.91924951e+03 4.91931201e+03 4.91920703e+03 4.91902637e+03 4.91918555e+03 4.91939014e+03 4.91921045e+03 4.91906494e+03 4.91901758e+03 4.91904590e+03 4.91917627e+03 4.91913232e+03 4.91903418e+03 4.91915576e+03 4.91915918e+03 4.91913770e+03 4.91924316e+03 4.91971045e+03 4.91934473e+03 4.91903955e+03 4.91910547e+03 4.91908447e+03 4.91901416e+03 4.91904004e+03 4.91904541e+03 4.91907959e+03 4.91910938e+03 4.91906494e+03 4.91902783e+03 4.91905078e+03 4.91906885e+03 4.91907080e+03 4.91903076e+03 4.91902197e+03 4.91914014e+03 4.91952832e+03 4.91940088e+03 4.91913330e+03 4.91902197e+03 4.91905127e+03 4.91912402e+03 4.91929346e+03 4.91940137e+03 4.91914697e+03 4.91903369e+03 4.91903320e+03 4.91902393e+03 4.91915039e+03 4.91909961e+03 4.91907812e+03 4.91903174e+03 4.91903369e+03 4.91902197e+03 4.91901562e+03 4.91902588e+03 4.91903174e+03 4.91903906e+03 4.91903271e+03 4.91901709e+03 4.91905811e+03 4.91926074e+03 4.91926855e+03 4.91907715e+03 4.91904590e+03 4.91910400e+03 4.91912793e+03 4.91909229e+03 4.91910645e+03 4.91916699e+03 4.91920117e+03 4.91900684e+03 4.91924609e+03 4.91937109e+03 4.91916162e+03 4.91902002e+03 4.91908008e+03 4.91917822e+03 4.91919238e+03 4.91907568e+03 4.91905127e+03 4.91907422e+03 4.91905420e+03 4.91904102e+03 4.91902393e+03 4.91904395e+03 4.91903076e+03 4.91903857e+03 4.91902637e+03 4.91901709e+03 4.91902588e+03 4.91901123e+03 4.91903271e+03 4.91901611e+03 4.91903760e+03 4.91903613e+03 4.91904932e+03 4.91903711e+03 4.91903076e+03 4.91903613e+03 4.91902148e+03 4.91903516e+03 4.91904639e+03 4.91908350e+03 4.91902686e+03 4.91914893e+03 4.91948828e+03 4.91956152e+03 4.91931934e+03 4.91914307e+03 4.91910303e+03 4.91903223e+03 4.91903174e+03 4.91905273e+03 4.91905176e+03 4.91906592e+03 4.91903271e+03 4.91905371e+03 4.91902686e+03 4.91913525e+03 4.91949756e+03 4.91986084e+03 4.91967188e+03 4.91919043e+03 4.91901416e+03 4.91910742e+03 4.91906494e+03 4.91904053e+03 4.91901416e+03 4.91900342e+03 4.91901855e+03 4.91902783e+03 4.91903662e+03 4.91902100e+03 4.91900635e+03 4.91901855e+03 4.91901318e+03 4.91903516e+03 4.91902246e+03 4.91903467e+03 4.91905371e+03 4.91905371e+03 4.91906738e+03 4.91903760e+03 4.91906885e+03 4.91934863e+03 4.91967529e+03 4.91964697e+03 4.91956152e+03 4.91964062e+03 4.91928076e+03 4.91903369e+03 4.91910107e+03 4.91914014e+03 4.91908057e+03 4.91903857e+03 4.91902393e+03 4.91905420e+03 4.91912598e+03 4.91907129e+03 4.91904883e+03 4.91901514e+03 4.91903760e+03 4.91903906e+03 4.91919922e+03 4.91965283e+03 4.91942822e+03 4.91915771e+03 4.91901025e+03 4.91904883e+03 4.91911084e+03 4.91940771e+03 4.91976074e+03 4.91962402e+03 4.91929785e+03 4.91902490e+03 4.91908691e+03 4.91915186e+03 4.91920703e+03 4.91913135e+03 4.91907422e+03 4.91912744e+03 4.91916797e+03 4.91916309e+03 4.91907764e+03 4.91903271e+03 4.91903809e+03 4.91915381e+03 4.91956689e+03 4.92011426e+03 4.92048779e+03 4.91933447e+03 4.91901807e+03 4.91922070e+03 4.91908057e+03 4.91902979e+03 4.91902979e+03 4.91906543e+03 4.91902197e+03 4.91901660e+03 4.91901709e+03 4.91902148e+03 4.91902295e+03 4.91902686e+03 4.91901416e+03 4.91911035e+03 4.91947656e+03 4.91963574e+03 4.91928516e+03 4.91908008e+03 4.91901221e+03 4.91903564e+03 4.91909424e+03 4.91902344e+03 4.91903271e+03 4.91905615e+03 4.91905469e+03 4.91902344e+03 4.91904980e+03 4.91908447e+03 4.91907275e+03 4.91907617e+03 4.91904102e+03 4.91902002e+03 4.91900732e+03 4.91902344e+03 4.91904834e+03 4.91911035e+03 4.91911182e+03 4.91906689e+03 4.91902783e+03 4.91929639e+03 4.91922852e+03 4.91903369e+03 4.91906055e+03 4.91902197e+03 4.91901074e+03 4.91903613e+03 4.91902197e+03 4.91905420e+03 4.91905127e+03 4.91919482e+03 4.91932568e+03 4.91928516e+03 4.91904150e+03 4.91904590e+03 4.91905664e+03 4.91903076e+03 4.91908496e+03 4.91938477e+03 4.91946631e+03 4.91932617e+03 4.91909668e+03 4.91912305e+03 4.91911963e+03 4.91910791e+03 4.91907617e+03 4.91905371e+03 4.91906152e+03 4.91908008e+03 4.91907275e+03 4.91903564e+03 4.91906445e+03 4.91907910e+03 4.91908545e+03 4.91904932e+03 4.91903662e+03 4.91918945e+03 4.91914600e+03 4.91905225e+03 4.91901611e+03 4.91901465e+03 4.91901318e+03 4.91905957e+03 4.91905908e+03 4.91906396e+03 4.91936328e+03 4.91941797e+03 4.91909814e+03 4.91901904e+03 4.91902148e+03 4.91902100e+03 4.91903711e+03 4.91901953e+03 4.91911377e+03 4.91948975e+03 4.91951074e+03 4.91920801e+03 4.91901172e+03 4.91902539e+03 4.91902539e+03 4.91904834e+03 4.91902197e+03 4.91901318e+03 4.91902979e+03 4.91908984e+03 4.91913184e+03 4.91908105e+03 4.91905078e+03 4.91903857e+03 4.91930127e+03 4.91993457e+03 4.92007275e+03 4.91949121e+03 4.91906641e+03 4.91902393e+03 4.91900391e+03 4.91902686e+03 4.91905811e+03 4.91941846e+03 4.91988818e+03 4.92057422e+03 4.92067236e+03 4.91982227e+03 4.91936621e+03 4.91904004e+03 4.91920947e+03 4.91946533e+03 4.91915674e+03 4.91908545e+03 4.91941699e+03 4.91913916e+03 4.91901416e+03 4.91900879e+03 4.91900195e+03 4.91902490e+03 4.91902686e+03 4.91905371e+03 4.91904688e+03 4.91905176e+03 4.91909326e+03 4.91906445e+03 4.91907617e+03 4.91905078e+03 4.91907275e+03 4.91905811e+03 4.91902295e+03 4.91910791e+03 4.91908447e+03 4.91901367e+03 4.91917676e+03 4.91903174e+03 4.91914551e+03 4.91901270e+03 4.91941943e+03 4.91952490e+03 4.91904834e+03 4.91948486e+03 4.91921777e+03 4.91900732e+03 4.91909131e+03 4.91943701e+03 4.91953027e+03 4.91927002e+03 4.91905713e+03 4.91905957e+03 4.91908057e+03 4.91904590e+03 4.91903418e+03 4.91904590e+03 4.91918359e+03 4.91902148e+03 4.91937500e+03 4.91989746e+03 4.91948438e+03 4.91919482e+03 4.91943066e+03 4.91973047e+03 4.91987158e+03 4.91953174e+03 4.91915381e+03 4.91913330e+03 4.91915625e+03 4.91924170e+03 4.91913672e+03 4.91928809e+03 4.91960742e+03 4.91978711e+03 4.91962109e+03 4.91916699e+03 4.91903857e+03 4.91901025e+03 4.91903418e+03 4.91902832e+03 4.91918750e+03 4.91999561e+03 4.91980322e+03 4.91906152e+03 4.91917041e+03 4.91908398e+03 4.91902393e+03 4.91909619e+03 4.91947363e+03 4.91950391e+03 4.91920068e+03 4.91901807e+03 4.91901953e+03 4.91903027e+03 4.91901953e+03 4.91901758e+03 4.91902295e+03 4.91903174e+03 4.91911670e+03 4.91917432e+03 4.91910547e+03 4.91903564e+03 4.91902246e+03 4.91903906e+03 4.91903760e+03 4.91918359e+03 4.91950146e+03 4.91920459e+03 4.91917090e+03 4.91955811e+03 4.91916895e+03 4.91904443e+03 4.91918750e+03 4.91932178e+03 4.91930713e+03 4.91922754e+03 4.91911035e+03 4.91914160e+03 4.91907373e+03 4.91910352e+03 4.91911035e+03 4.91919580e+03 4.91927344e+03 4.91929688e+03 4.91912256e+03 4.91902686e+03 4.91904688e+03 4.91918604e+03 4.91929688e+03 4.91910791e+03 4.91903320e+03 4.91902588e+03 4.91907520e+03 4.91938770e+03 4.91940576e+03 4.91922168e+03 4.91914551e+03 4.91998584e+03 4.92092920e+03 4.92022510e+03 4.91936377e+03 4.91945605e+03 4.92019824e+03 4.92044141e+03 4.91969629e+03 4.91923145e+03 4.91918164e+03 4.91916846e+03 4.91929834e+03 4.91933740e+03 4.91933154e+03 4.91917822e+03 4.91930518e+03 4.91986426e+03 4.92014844e+03 4.91976221e+03 4.91921680e+03 4.91925732e+03 4.91960400e+03 4.91922070e+03 4.91901367e+03 4.91917627e+03 4.91906641e+03 4.91902979e+03 4.91902881e+03 4.91901904e+03 4.91903955e+03 4.91902295e+03 4.91904785e+03 4.91903320e+03 4.91903809e+03 4.91902393e+03 4.91902783e+03 4.91906738e+03 4.91905322e+03 4.91902588e+03 4.91902539e+03 4.91908984e+03 4.91927979e+03 4.91926416e+03 4.91903125e+03 4.91910547e+03 4.91915576e+03 4.91913623e+03 4.91934326e+03 4.91986475e+03 4.91992188e+03 4.91956689e+03 4.91919092e+03 4.91913770e+03 4.91908398e+03 4.91907178e+03 4.91946045e+03 4.91963867e+03 4.91926465e+03 4.91905615e+03 4.91905469e+03 4.91904346e+03 4.91903955e+03 4.91902295e+03 4.91902832e+03 4.91925684e+03 4.91918555e+03 4.91905078e+03 4.91923193e+03 4.91908105e+03 4.91909229e+03 4.91981982e+03 4.92073682e+03 4.92037500e+03 4.91925049e+03 4.91910645e+03 4.91928760e+03 4.91939307e+03 4.91917285e+03 4.91902979e+03 4.91903369e+03 4.91908545e+03 4.91918164e+03 4.91908057e+03 4.91902637e+03 4.91912988e+03 4.91921777e+03 4.91924658e+03 4.91912354e+03 4.91913281e+03 4.91920898e+03 4.91905322e+03 4.91907422e+03 4.91915918e+03 4.91903711e+03 4.91906641e+03 4.91905176e+03 4.91908057e+03 4.91905518e+03 4.92109912e+03 4.92526807e+03 4.93641113e+03 4.93522559e+03 6.60739990e+03 9.88275098e+03 9.72683789e+03 6.37755420e+03 6.41236572e+03 6.14627930e+03 9.11116602e+03 2.12034238e+04 4.50590391e+04 1697351808. 145294. -2.39559875e+12 9.50582231e+10 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. 9.12233529e+11 6.32803789e+04 3.00729180e+04 1.98357207e+04 1.97845312e+04 9.29804199e+03 6.30442822e+03 4.94043701e+03 4.93779883e+03 4.94400635e+03 4.99228711e+03 4.97573779e+03 4.95280176e+03 4.93763867e+03 4.93592725e+03 4.93874805e+03 4.94088721e+03 4.95558740e+03 4.96517383e+03 4.94694873e+03 4.93503271e+03 4.93427148e+03 4.93463330e+03 4.93444189e+03 4.93460254e+03 4.93566943e+03 4.93556787e+03 4.93477295e+03 4.93433594e+03 4.93478076e+03 4.93720020e+03 4.93779639e+03 4.93553711e+03 4.93435107e+03 4.93429053e+03 4.93427588e+03 4.93434521e+03 4.93471045e+03 4.93503320e+03 4.93437549e+03 4.93551318e+03 4.93771924e+03 4.93654639e+03 4.93451709e+03 4.93429834e+03 4.93428955e+03 4.93429297e+03 4.93459375e+03 4.93437793e+03 4.93452148e+03 4.93465332e+03 4.93454004e+03 4.93437012e+03 4.93583252e+03 4.93557520e+03 4.93429932e+03 4.93504346e+03 4.93462061e+03 4.93432910e+03 4.93430127e+03 4.93452246e+03 4.93456152e+03 4.93429248e+03 4.93501758e+03 4.93470947e+03 4.93451416e+03 4.93576416e+03 4.93513818e+03 4.93436035e+03 4.93429297e+03 4.93440576e+03 4.93436914e+03 4.93432031e+03 4.93475146e+03 4.93448926e+03 4.93429785e+03 4.93434326e+03 4.93476514e+03 4.93498389e+03 4.93468994e+03 4.93431299e+03 4.93433594e+03 4.93445117e+03 4.93429541e+03 4.93429785e+03 4.93429785e+03 4.93458740e+03 4.93600928e+03 4.93678906e+03 4.93499219e+03 4.93445264e+03 4.93533594e+03 4.93468604e+03 4.93438672e+03 4.93600488e+03 4.93697510e+03 4.93620068e+03 4.93547510e+03 4.93566699e+03 4.93510840e+03 4.93427734e+03 4.93466260e+03 4.93440088e+03 4.93440967e+03 4.93465723e+03 4.93438623e+03 4.93433105e+03 4.93441699e+03 4.93427783e+03 4.93440674e+03 4.93433691e+03 4.93430029e+03 4.93464941e+03 4.93638037e+03 4.93676953e+03 4.93510107e+03 4.93430859e+03 4.93430859e+03 4.93473584e+03 4.93565186e+03 4.93566406e+03 4.93486523e+03 4.93430029e+03 4.93427734e+03 4.93432422e+03 4.93434131e+03 4.93430127e+03 4.93435156e+03 4.93431738e+03 4.93497168e+03 4.93495801e+03 4.93433447e+03 4.93429395e+03 4.93436768e+03 4.93461719e+03 4.93475732e+03 4.93438135e+03 4.93455176e+03 4.93543506e+03 4.93575830e+03 4.93460596e+03 4.93475684e+03 4.93597217e+03 4.93488281e+03 4.93427344e+03 4.93433447e+03 4.93427295e+03 4.93432471e+03 4.93430371e+03 4.93431494e+03 4.93457471e+03 4.93531689e+03 4.93577344e+03 4.93463965e+03 4.93452100e+03 4.93545361e+03 4.93450000e+03 4.93433936e+03 4.93433105e+03 4.93429785e+03 4.93430713e+03 4.93532129e+03 4.93510547e+03 4.93429443e+03 4.93471289e+03 4.93428467e+03 4.93579297e+03 4.93795068e+03 4.93636035e+03 4.93458252e+03 4.93428418e+03 4.93429443e+03 4.93428369e+03 4.93434668e+03 4.93428027e+03 4.93472705e+03 4.93641113e+03 4.93527295e+03 4.93433350e+03 4.93458740e+03 4.93446680e+03 4.93427783e+03 4.93452832e+03 4.93488428e+03 4.93498535e+03 4.93521680e+03 4.93606445e+03 4.93534668e+03 4.93433643e+03 4.93458643e+03 4.93434375e+03 4.93459277e+03 4.93567969e+03 4.93500098e+03 4.93432715e+03 4.93427930e+03 4.93427002e+03 4.93432520e+03 4.93516162e+03 4.93583301e+03 4.93458887e+03 4.93459277e+03 4.93484082e+03 4.93445752e+03 4.93452393e+03 4.93465332e+03 4.93464697e+03 4.93433350e+03 4.93427051e+03 4.93427051e+03 4.93436230e+03 4.93466895e+03 4.93439502e+03 4.93432764e+03 4.93461963e+03 4.93455615e+03 4.93428125e+03 4.93429541e+03 4.93428320e+03 4.93427490e+03 4.93428174e+03 4.93430273e+03 4.93431592e+03 4.93478906e+03 4.93519336e+03 4.93522021e+03 4.93430176e+03 4.93435986e+03 4.93427588e+03 4.93485303e+03 4.93508008e+03 4.93440918e+03 4.93430371e+03 4.93427539e+03 4.93438574e+03 4.93435791e+03 4.93430957e+03 4.93437402e+03 4.93433105e+03 4.93463770e+03 4.93440186e+03 4.93427881e+03 4.93440723e+03 4.93451172e+03 4.93431689e+03 4.93428516e+03 4.93439697e+03 4.93428027e+03 4.93438037e+03 4.93442432e+03 4.93441016e+03 4.93461816e+03 4.93501465e+03 4.93542334e+03 4.93437451e+03 4.93427930e+03 4.93427930e+03 4.93450244e+03 4.93435693e+03 4.93431299e+03 4.93444043e+03 4.93498242e+03 4.93530957e+03 4.93432715e+03 4.93436182e+03 4.93448926e+03 4.93431006e+03 4.93441357e+03 4.93440625e+03 4.93428662e+03 4.93427930e+03 4.93462305e+03 4.93443408e+03 4.93429297e+03 4.93462207e+03 4.93496338e+03 4.93469873e+03 4.93428027e+03 4.93441504e+03 4.93427979e+03 4.93454199e+03 4.93479980e+03 4.93446729e+03 4.93483350e+03 4.93487793e+03 4.93439893e+03 4.93436768e+03 4.93435352e+03 4.93454102e+03 4.93497852e+03 4.93445312e+03 4.93435352e+03 4.93428369e+03 4.93436914e+03 4.93452246e+03 4.93439307e+03 4.93428223e+03 4.93429785e+03 4.93435986e+03 4.93430664e+03 4.93460303e+03 4.93467041e+03 4.93430371e+03 4.93427881e+03 4.93429883e+03 4.93456787e+03 4.93466846e+03 4.93491992e+03 4.93628857e+03 4.93740186e+03 4.93710449e+03 4.93654150e+03 4.93660303e+03 4.93786279e+03 4.93795410e+03 4.93684570e+03 4.93498828e+03 4.93457080e+03 4.93446387e+03 4.93460303e+03 4.93449756e+03 4.93427881e+03 4.93431396e+03 4.93440723e+03 4.93430518e+03 4.93447803e+03 4.93460010e+03 4.93441943e+03 4.93460889e+03 4.93487061e+03 4.93528955e+03 4.93501318e+03 4.93508643e+03 4.93596924e+03 4.93670215e+03 4.93603125e+03 4.93489941e+03 4.93481787e+03 4.93491260e+03 4.93433057e+03 4.93430615e+03 4.93453467e+03 4.93427002e+03 4.93429492e+03 4.93440186e+03 4.93481250e+03 4.93490479e+03 4.93443457e+03 4.93444287e+03 4.93463770e+03 4.93427002e+03 4.93466357e+03 4.93458691e+03 4.93427344e+03 4.93443848e+03 4.93427734e+03 4.93441357e+03 4.93506445e+03 4.93494238e+03 4.93440186e+03 4.93428125e+03 4.93465283e+03 4.93468115e+03 4.93468408e+03 4.93484229e+03 4.93486768e+03 4.93487354e+03 4.93427344e+03 4.93428076e+03 4.93428174e+03 4.93427393e+03 4.93428271e+03 4.93446875e+03 4.93670752e+03 4.93731006e+03 4.93541602e+03 4.93440771e+03 4.93545410e+03 4.93435059e+03 4.93483350e+03 4.93506689e+03 4.93437598e+03 4.93652344e+03 4.93573633e+03 4.93428125e+03 4.93466748e+03 4.93457422e+03 4.93429883e+03 4.93428857e+03 4.93440771e+03 4.93490381e+03 4.93501660e+03 4.93429346e+03 4.93428467e+03 4.93444385e+03 4.93489746e+03 4.93493213e+03 4.93441846e+03 4.93456982e+03 4.93455078e+03 4.93429346e+03 4.93530908e+03 4.93513379e+03 4.93454150e+03 4.93658594e+03 4.93564551e+03 4.93427881e+03 4.93463770e+03 4.93446631e+03 4.93433398e+03 4.93458252e+03 4.93483643e+03 4.93430127e+03 4.93431445e+03 4.93433838e+03 4.93457129e+03 4.93474805e+03 4.93433057e+03 4.93431152e+03 4.93497363e+03 4.93502734e+03 4.93454590e+03 4.93429150e+03 4.93532080e+03 4.93603027e+03 4.93473975e+03 4.93479932e+03 4.93649463e+03 4.93502197e+03 4.93465039e+03 4.93541602e+03 4.93427881e+03 4.93644531e+03 4.93647754e+03 4.93435742e+03 4.93450293e+03 4.93452441e+03 4.93428467e+03 4.93431494e+03 4.93429932e+03 4.93471143e+03 4.93556006e+03 4.93549268e+03 4.93619092e+03 4.93589209e+03 4.93485205e+03 4.93429541e+03 4.93446143e+03 4.93431738e+03 4.93499951e+03 4.93468408e+03 4.93440479e+03 4.93560156e+03 4.93505176e+03 4.93428271e+03 4.93443848e+03 4.93428516e+03 4.93469434e+03 4.93457373e+03 4.93428857e+03 4.93480566e+03 4.93562354e+03 4.93470752e+03 4.93474707e+03 4.93442041e+03 4.93446680e+03 4.93455811e+03 4.93475000e+03 4.93556201e+03 4.93477295e+03 4.93429639e+03 4.93460303e+03 4.93431152e+03 4.93479736e+03 4.93626562e+03 4.93493945e+03 4.93432764e+03 4.93505566e+03 4.93493262e+03 4.93428271e+03 4.93431885e+03 4.93443896e+03 4.93428369e+03 4.93433252e+03 4.93460352e+03 4.93528174e+03 4.93648291e+03 4.93590283e+03 4.93457959e+03 4.93430078e+03 4.93434131e+03 4.93428076e+03 4.93440039e+03 4.93504688e+03 4.93567334e+03 4.93458105e+03 4.93460303e+03 4.93547021e+03 4.93440576e+03 4.93471094e+03 4.93470703e+03 4.93447754e+03 4.93678857e+03 4.93603662e+03 4.93428174e+03 4.93569385e+03 4.93688818e+03 4.93500830e+03 4.93433154e+03 4.93431445e+03 4.93451562e+03 4.93482617e+03 4.93437646e+03 4.93443408e+03 4.93433936e+03 4.93428223e+03 4.93436670e+03 4.93435693e+03 4.93438379e+03 4.93434961e+03 4.93445605e+03 4.93579346e+03 4.93549902e+03 4.93430566e+03 4.93559424e+03 4.93499072e+03 4.93436475e+03 4.93546680e+03 4.93538477e+03 4.93429004e+03 4.93490479e+03 4.93567822e+03 4.93451465e+03 4.93428271e+03 4.93446582e+03 4.93450586e+03 4.93439355e+03 4.93441504e+03 4.93437939e+03 4.93509473e+03 4.93577002e+03 4.93570996e+03 4.93484424e+03 4.93430615e+03 4.93442773e+03 4.93428955e+03 4.93519922e+03 4.93563770e+03 4.93473730e+03 4.93429150e+03 4.93428809e+03 4.93449951e+03 4.93584668e+03 4.93611133e+03 4.93455908e+03 4.93439795e+03 4.93474756e+03 4.93428174e+03 4.93483789e+03 4.93477490e+03 4.93431055e+03 4.93446143e+03 4.93451270e+03 4.93445996e+03 4.93429736e+03 4.93441748e+03 4.93450293e+03 4.93428223e+03 4.93514453e+03 4.93609570e+03 4.93483691e+03 4.93428467e+03 4.93460547e+03 4.93432910e+03 4.93439062e+03 4.93480029e+03 4.93465186e+03 4.93430615e+03 4.93428320e+03 4.93441455e+03 4.93493213e+03 4.93516748e+03 4.93438232e+03 4.93433203e+03 4.93429541e+03 4.93438281e+03 4.93531348e+03 4.93516064e+03 4.93512500e+03 4.93468164e+03 4.93433398e+03 4.93428760e+03 4.93428564e+03 4.93461523e+03 4.93525635e+03 4.93473779e+03 4.93430322e+03 4.93440137e+03 4.93429053e+03 4.93475488e+03 4.93523291e+03 4.93439990e+03 4.93515332e+03 4.93633105e+03 4.93488574e+03 4.93472412e+03 4.93622314e+03 4.93491406e+03 4.93421143e+03 4.93454004e+03 4.93522559e+03 4.93779150e+03 4.93552832e+03 4.93859229e+03 4.93841113e+03 4.93635742e+03 6.69787842e+03 9.79556543e+03 2.62681289e+04 4.85652305e+04 -2.42461599e+12 3.32415605e+12 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.18685354e+11 1.02058058e+11 6.30943945e+04 2.86198848e+04 1.97803125e+04 1.97364961e+04 1.97531035e+04 1.97383145e+04 1.97365332e+04 1.00653330e+04 6.72724902e+03 4.96469678e+03 4.94991162e+03 6.31551221e+03 6.07288818e+03 6.27079688e+03 4.93739111e+03 4.93440723e+03 4.94217627e+03 4.94262939e+03 4.93812061e+03 4.93838965e+03 4.93635156e+03 4.93473486e+03 4.93424268e+03 4.93425732e+03 4.93438525e+03 4.93430029e+03 4.93438818e+03 4.93439453e+03 4.93509521e+03 4.93444336e+03 4.93517529e+03 4.93707129e+03 4.93496533e+03 4.93434473e+03 4.93508496e+03 4.93452979e+03 4.93470312e+03 4.93685254e+03 4.93819678e+03 4.93540234e+03 4.93440381e+03 4.93435156e+03 4.93518018e+03 4.93619189e+03 4.93523389e+03 4.93494482e+03 4.93446680e+03 4.93428613e+03 4.93432373e+03 4.93434863e+03 4.93637842e+03 4.93667090e+03 4.93457861e+03 4.93477197e+03 4.93529541e+03 4.93428271e+03 4.93522656e+03 4.93516602e+03 4.93432324e+03 4.93430371e+03 4.93468799e+03 4.93723828e+03 4.93844482e+03 4.93653564e+03 4.93437305e+03 4.93455176e+03 4.93448975e+03 4.93435791e+03 4.93587793e+03 4.93792627e+03 4.93924170e+03 4.93813330e+03 4.93594922e+03 4.93478516e+03 4.93444824e+03 4.93476318e+03 4.93458984e+03 4.93431787e+03 4.93510303e+03 4.93502393e+03 4.93428369e+03 4.93485107e+03 4.93460400e+03 4.93430664e+03 4.93458008e+03 4.93504053e+03 4.93451660e+03 4.93448584e+03 4.93531543e+03 4.93448926e+03 4.93433301e+03 4.93428857e+03 4.93430908e+03 4.93440479e+03 4.93428320e+03 4.93440869e+03 4.93436865e+03 4.93428564e+03 4.93437988e+03 4.93428418e+03 4.93534863e+03 4.93566797e+03 4.93430957e+03 4.93552783e+03 4.93709082e+03 4.93491504e+03 4.93429883e+03 4.93459521e+03 4.93439600e+03 4.93428076e+03 4.93428271e+03 4.93435156e+03 4.93501416e+03 4.93561572e+03 4.93458643e+03 4.93452979e+03 4.93490088e+03 4.93442432e+03 4.93428711e+03 4.93428760e+03 4.93445410e+03 4.93439258e+03 4.93446045e+03 4.93625342e+03 4.93597900e+03 4.93428760e+03 4.93457031e+03 4.93432227e+03 4.93589062e+03 4.93637354e+03 4.93446094e+03 4.93459277e+03 4.93493555e+03 4.93449707e+03 4.93441699e+03 4.93527490e+03 4.93493848e+03 4.93428320e+03 4.93481934e+03 4.93431836e+03 4.93479150e+03 4.93534814e+03 4.93488281e+03 4.93440039e+03 4.93428516e+03 4.93456396e+03 4.93485840e+03 4.93451318e+03 4.93428271e+03 4.93428662e+03 4.93461670e+03 4.93502686e+03 4.93439062e+03 4.93510938e+03 4.93734766e+03 4.93624414e+03 4.93432666e+03 4.93474707e+03 4.93465186e+03 4.93427637e+03 4.93434424e+03 4.93427051e+03 4.93428906e+03 4.93451367e+03 4.93437500e+03 4.93431934e+03 4.93433154e+03 4.93488916e+03 4.93554590e+03 4.93583984e+03 4.93451221e+03 4.93428613e+03 4.93461279e+03 4.93550000e+03 4.93494580e+03 4.93434766e+03 4.93497656e+03 4.93445264e+03 4.93428076e+03 4.93447168e+03 4.93440625e+03 4.93427344e+03 4.93428467e+03 4.93431396e+03 4.93445264e+03 4.93438672e+03 4.93427002e+03 4.93471191e+03 4.93608398e+03 4.93722998e+03 4.93855371e+03 4.93621094e+03 4.93438623e+03 4.93431543e+03 4.93431836e+03 4.93443408e+03 4.93442822e+03 4.93429053e+03 4.93507275e+03 4.93593945e+03 4.93440869e+03 4.93488818e+03 4.93646338e+03 4.93561084e+03 4.93460938e+03 4.93440625e+03 4.93445459e+03 4.93467285e+03 4.93517822e+03 4.93468506e+03 4.93427832e+03 4.93435596e+03 4.93427441e+03 4.93434570e+03 4.93446729e+03 4.93475537e+03 4.93495361e+03 4.93455127e+03 4.93430859e+03 4.93432129e+03 4.93433545e+03 4.93427734e+03 4.93465771e+03 4.93521143e+03 4.93527637e+03 4.93444678e+03 4.93426709e+03 4.93461621e+03 4.93470947e+03 4.93432764e+03 4.93448193e+03 4.93463086e+03 4.93429102e+03 4.93430713e+03 4.93428906e+03 4.93427344e+03 4.93428564e+03 4.93428271e+03 4.93428760e+03 4.93427539e+03 4.93427002e+03 4.93427002e+03 4.93428223e+03 4.93430371e+03 4.93439893e+03 4.93436865e+03 4.93434375e+03 4.93427539e+03 4.93432031e+03 4.93436572e+03 4.93434229e+03 4.93427002e+03 4.93435010e+03 4.93447363e+03 4.93441455e+03 4.93433008e+03 4.93427490e+03 4.93427930e+03 4.93427637e+03 4.93428369e+03 4.93429199e+03 4.93429932e+03 4.93428613e+03 4.93427148e+03 4.93428320e+03 4.93428906e+03 4.93430664e+03 4.93428955e+03 4.93431592e+03 4.93432812e+03 4.93439111e+03 4.93446484e+03 4.93446240e+03 4.93435400e+03 4.93427734e+03 4.93427637e+03 4.93429590e+03 4.93440234e+03 4.93437451e+03 4.93434424e+03 4.93427197e+03 4.93427734e+03 4.93427441e+03 4.93432422e+03 4.93431348e+03 4.93428369e+03 4.93427197e+03 4.93427930e+03 4.93426953e+03 4.93428125e+03 4.93427490e+03 4.93431787e+03 4.93428320e+03 4.93427539e+03 4.93430566e+03 4.93429443e+03 4.93428125e+03 4.93437695e+03 4.93432959e+03 4.93431152e+03 4.93431299e+03 4.93431201e+03 4.93433545e+03 4.93432080e+03 4.93433252e+03 4.93427441e+03 4.93427783e+03 4.93430469e+03 4.93429541e+03 4.93427295e+03 4.93427783e+03 4.93427148e+03 4.93434424e+03 4.93455713e+03 4.93447656e+03 4.93431982e+03 4.93427393e+03 4.93427100e+03 4.93427539e+03 4.93426953e+03 4.93428125e+03 4.93427002e+03 4.93429248e+03 4.93430762e+03 4.93430322e+03 4.93436133e+03 4.93436279e+03 4.93428467e+03 4.93428027e+03 4.93427539e+03 4.93428467e+03 4.93426904e+03 4.93427979e+03 4.93429639e+03 4.93430518e+03 4.93436816e+03 4.93436816e+03 4.93433008e+03 4.93427734e+03 4.93429736e+03 4.93427832e+03 4.93427588e+03 4.93430371e+03 4.93432861e+03 4.93426807e+03 4.93427734e+03 4.93427002e+03 4.93429590e+03 4.93431543e+03 4.93428418e+03 4.93426367e+03 4.93427734e+03 4.93426904e+03 4.93427832e+03 4.93428174e+03 4.93440137e+03 4.93435498e+03 4.93431982e+03 4.93426416e+03 4.93427637e+03 4.93427441e+03 4.93428027e+03 4.93427197e+03 4.93427979e+03 4.93429395e+03 4.93434521e+03 4.93428564e+03 4.93427100e+03 4.93427051e+03 4.93436230e+03 4.93472168e+03 4.93461523e+03 4.93435059e+03 4.93428076e+03 4.93429395e+03 4.93445996e+03 4.93455371e+03 4.93437305e+03 4.93427686e+03 4.93428809e+03 4.93438574e+03 4.93447900e+03 4.93448242e+03 4.93442041e+03 4.93449268e+03 4.93466699e+03 4.93471338e+03 4.93449561e+03 4.93430469e+03 4.93428271e+03 4.93431836e+03 4.93435498e+03 4.93429834e+03 4.93426660e+03 4.93427539e+03 4.93441309e+03 4.93469482e+03 4.93466992e+03 4.93437891e+03 4.93426660e+03 4.93427588e+03 4.93427637e+03 4.93427588e+03 4.93430713e+03 4.93465332e+03 4.93460938e+03 4.93434180e+03 4.93427637e+03 4.93428711e+03 4.93428906e+03 4.93442334e+03 4.93451465e+03 4.93427686e+03 4.93462256e+03 4.93474121e+03 4.93431348e+03 4.93430469e+03 4.93428564e+03 4.93428418e+03 4.93432080e+03 4.93443164e+03 4.93436719e+03 4.93427100e+03 4.93437891e+03 4.93438135e+03 4.93444824e+03 4.93427881e+03 4.93449170e+03 4.93462256e+03 4.93437061e+03 4.93430029e+03 4.93447754e+03 4.93470264e+03 4.93480225e+03 4.93441455e+03 4.93431152e+03 4.93427100e+03 4.93427686e+03 4.93427100e+03 4.93428906e+03 4.93428906e+03 4.93428516e+03 4.93427051e+03 4.93425635e+03 4.93444092e+03 4.93715674e+03 4.94300488e+03 4.94259912e+03 4.94209521e+03 4.94022656e+03 4.95288721e+03 4.93836768e+03 4.93417334e+03 4.96227832e+03 6.56962305e+03 6.18896826e+03 1.02881973e+04 2.49920742e+04 3.76960156e+11 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.27275851e+13 -1.27275851e+13 2.08604021e+11 6.24344922e+04 2.99281465e+04 1.98275176e+04 1.97933184e+04 1.97412070e+04 1.97389102e+04 1.97382676e+04 1.97381641e+04 1.97369785e+04 1.97371934e+04 1.97380410e+04 1.97372891e+04 1.97369062e+04 1.97369492e+04 1.97369316e+04 1.02709033e+04 6.83827100e+03 4.98230664e+03 4.94283496e+03 4.93802539e+03 4.93666406e+03 4.93596973e+03 4.93521826e+03 4.93440137e+03 4.93432275e+03 4.93427637e+03 4.93427148e+03 4.93430615e+03 4.93431738e+03 4.93439502e+03 4.93443799e+03 4.93446924e+03 4.93449561e+03 4.93443213e+03 4.93445361e+03 4.93450342e+03 4.93462354e+03 4.93476416e+03 4.93460596e+03 4.93443604e+03 4.93437842e+03 4.93439746e+03 4.93448193e+03 4.93454785e+03 4.93464307e+03 4.93454590e+03 4.93430371e+03 4.93432959e+03 4.93435596e+03 4.93428906e+03 4.93428467e+03 4.93428516e+03 4.93434131e+03 4.93435254e+03 4.93430713e+03 4.93429395e+03 4.93430615e+03 4.93435254e+03 4.93438867e+03 4.93457910e+03 4.93440967e+03 4.93430078e+03 4.93428516e+03 4.93430029e+03 4.93435742e+03 4.93441016e+03 4.93431592e+03 4.93428076e+03 4.93427832e+03 4.93428418e+03 4.93442188e+03 4.93451221e+03 4.93443164e+03 4.93429639e+03 4.93428174e+03 4.93428125e+03 4.93433740e+03 4.93460645e+03 4.93457715e+03 4.93440771e+03 4.93430225e+03 4.93464844e+03 4.93526904e+03 4.93524707e+03 4.93469971e+03 4.93444727e+03 4.93451367e+03 4.93457861e+03 4.93449219e+03 4.93453320e+03 4.93479932e+03 4.93518896e+03 4.93501074e+03 4.93446289e+03 4.93428760e+03 4.93429785e+03 4.93427930e+03 4.93427734e+03 4.93431689e+03 4.93428418e+03 4.93439014e+03 4.93431641e+03 4.93431299e+03 4.93438135e+03 4.93427979e+03 4.93432422e+03 4.93433154e+03 4.93457324e+03 4.93456348e+03 4.93428613e+03 4.93442920e+03 4.93447949e+03 4.93442480e+03 4.93435010e+03 4.93432959e+03 4.93429688e+03 4.93428760e+03 4.93429297e+03 4.93429541e+03 4.93428613e+03 4.93429590e+03 4.93429150e+03 4.93427979e+03 4.93428955e+03 4.93428125e+03 4.93428613e+03 4.93440186e+03 4.93479834e+03 4.93472754e+03 4.93436426e+03 4.93428369e+03 4.93438477e+03 4.93474023e+03 4.93479883e+03 4.93446924e+03 4.93430420e+03 4.93429102e+03 4.93428223e+03 4.93427979e+03 4.93428955e+03 4.93429150e+03 4.93429785e+03 4.93427832e+03 4.93431836e+03 4.93430469e+03 4.93428271e+03 4.93429639e+03 4.93428223e+03 4.93428906e+03 4.93428857e+03 4.93433594e+03 4.93460986e+03 4.93525098e+03 4.93522119e+03 4.93475635e+03 4.93435596e+03 4.93461377e+03 4.93512793e+03 4.93515723e+03 4.93445801e+03 4.93428955e+03 4.93428857e+03 4.93432861e+03 4.93436230e+03 4.93433398e+03 4.93433350e+03 4.93433057e+03 4.93428955e+03 4.93429053e+03 4.93436230e+03 4.93466943e+03 4.93463330e+03 4.93440234e+03 4.93428516e+03 4.93428564e+03 4.93428711e+03 4.93435400e+03 4.93458984e+03 4.93456104e+03 4.93438184e+03 4.93431055e+03 4.93430908e+03 4.93428223e+03 4.93433398e+03 4.93465332e+03 4.93484424e+03 4.93453516e+03 4.93430518e+03 4.93429932e+03 4.93431445e+03 4.93430029e+03 4.93430225e+03 4.93431885e+03 4.93433496e+03 4.93466602e+03 4.93516357e+03 4.93509033e+03 4.93452930e+03 4.93431494e+03 4.93438428e+03 4.93439062e+03 4.93466064e+03 4.93504053e+03 4.93496631e+03 4.93442383e+03 4.93429053e+03 4.93428271e+03 4.93430566e+03 4.93433789e+03 4.93430420e+03 4.93428760e+03 4.93429346e+03 4.93429199e+03 4.93429053e+03 4.93429248e+03 4.93429004e+03 4.93429297e+03 4.93435986e+03 4.93445410e+03 4.93454834e+03 4.93450000e+03 4.93439746e+03 4.93436670e+03 4.93435498e+03 4.93436279e+03 4.93436963e+03 4.93434375e+03 4.93438135e+03 4.93434668e+03 4.93431885e+03 4.93433154e+03 4.93442139e+03 4.93444434e+03 4.93437012e+03 4.93432568e+03 4.93431885e+03 4.93433496e+03 4.93429590e+03 4.93430127e+03 4.93429590e+03 4.93428955e+03 4.93428906e+03 4.93431201e+03 4.93447705e+03 4.93434033e+03 4.93435254e+03 4.93461768e+03 4.93449463e+03 4.93433496e+03 4.93430518e+03 4.93431787e+03 4.93433057e+03 4.93438428e+03 4.93440186e+03 4.93436035e+03 4.93433154e+03 4.93429688e+03 4.93428906e+03 4.93429492e+03 4.93429443e+03 4.93430371e+03 4.93432812e+03 4.93431006e+03 4.93430566e+03 4.93431250e+03 4.93429346e+03 4.93429736e+03 4.93428369e+03 4.93429980e+03 4.93443457e+03 4.93478516e+03 4.93481445e+03 4.93455127e+03 4.93433496e+03 4.93429443e+03 4.93429199e+03 4.93435498e+03 4.93450146e+03 4.93461572e+03 4.93465967e+03 4.93443262e+03 4.93431982e+03 4.93428906e+03 4.93428662e+03 4.93430273e+03 4.93430322e+03 4.93429102e+03 4.93428369e+03 4.93429492e+03 4.93429199e+03 4.93433398e+03 4.93439111e+03 4.93439600e+03 4.93436475e+03 4.93458643e+03 4.93495605e+03 4.93476611e+03 4.93439258e+03 4.93428711e+03 4.93433594e+03 4.93441553e+03 4.93438623e+03 4.93434570e+03 4.93449121e+03 4.93487354e+03 4.93479443e+03 4.93437598e+03 4.93429297e+03 4.93429004e+03 4.93432031e+03 4.93432227e+03 4.93428857e+03 4.93428564e+03 4.93428906e+03 4.93431836e+03 4.93429248e+03 4.93430957e+03 4.93431836e+03 4.93431104e+03 4.93429492e+03 4.93432178e+03 4.93429492e+03 4.93445557e+03 4.93448975e+03 4.93457031e+03 4.93480518e+03 4.93536230e+03 4.93539502e+03 4.93504395e+03 4.93510498e+03 4.93476172e+03 4.93472412e+03 4.93439746e+03 4.93428613e+03 4.93442090e+03 4.93450879e+03 4.93440039e+03 4.93434717e+03 4.93431006e+03 4.93431104e+03 4.93430957e+03 4.93432617e+03 4.93434521e+03 4.93429004e+03 4.93451758e+03 4.93468018e+03 4.93452344e+03 4.93432178e+03 4.93429932e+03 4.93429150e+03 4.93429834e+03 4.93428906e+03 4.93428955e+03 4.93433496e+03 4.93436035e+03 4.93453076e+03 4.93489404e+03 4.93460156e+03 4.93434766e+03 4.93431152e+03 4.93455908e+03 4.93467822e+03 4.93448145e+03 4.93429102e+03 4.93439014e+03 4.93466992e+03 4.93491064e+03 4.93457910e+03 4.93436963e+03 4.93463477e+03 4.93501172e+03 4.93483594e+03 4.93434277e+03 4.93429199e+03 4.93434814e+03 4.93445508e+03 4.93429688e+03 4.93438135e+03 4.93428711e+03 4.93465039e+03 4.93496436e+03 4.93465527e+03 4.93440918e+03 4.93446338e+03 4.93482275e+03 4.93541260e+03 4.93518555e+03 4.93446631e+03 4.93429102e+03 4.93428711e+03 4.93428760e+03 4.93430176e+03 4.93429590e+03 4.93430615e+03 4.93431787e+03 4.93443848e+03 4.93446533e+03 4.93431592e+03 4.93429053e+03 4.93428516e+03 4.93439648e+03 4.93451367e+03 4.93445361e+03 4.93435596e+03 4.93429297e+03 4.93429541e+03 4.93429150e+03 4.93428857e+03 4.93432520e+03 4.93430566e+03 4.93449121e+03 4.93507031e+03 4.93445068e+03 4.93443799e+03 4.93452295e+03 4.93433545e+03 4.93454785e+03 4.93429834e+03 4.93429248e+03 4.93433105e+03 4.93441846e+03 4.93435059e+03 4.93427930e+03 4.93430762e+03 4.93436768e+03 4.93442871e+03 4.93434570e+03 4.93428271e+03 4.93428662e+03 4.93428955e+03 4.93436719e+03 4.93453760e+03 4.93455078e+03 4.93432324e+03 4.93431738e+03 4.93508203e+03 4.93599805e+03 4.93560010e+03 4.93449072e+03 4.93444629e+03 4.93465430e+03 4.93443701e+03 4.93431494e+03 4.93440234e+03 4.93428418e+03 4.93440479e+03 4.93434229e+03 4.93428955e+03 4.93437207e+03 4.93444531e+03 4.93445361e+03 4.93436328e+03 4.93427979e+03 4.93430176e+03 4.93433984e+03 4.93428809e+03 4.93429541e+03 4.93434473e+03 4.93439404e+03 4.93449854e+03 4.93467773e+03 4.93468262e+03 4.93443652e+03 4.93428711e+03 4.93430127e+03 4.93451416e+03 4.93461133e+03 4.93455029e+03 4.93473047e+03 4.93578223e+03 4.93666504e+03 4.93598438e+03 4.93473730e+03 4.93450684e+03 4.93460986e+03 4.93466553e+03 4.93442822e+03 4.93432422e+03 4.93429150e+03 4.93428857e+03 4.93428613e+03 4.93430566e+03 4.93431250e+03 4.93429492e+03 4.93430420e+03 4.93437744e+03 4.93461328e+03 4.93440967e+03 4.93429639e+03 4.93459229e+03 4.93497461e+03 4.93448535e+03 4.93432520e+03 4.93470801e+03 4.93468262e+03 4.93465186e+03 4.93447314e+03 4.93440625e+03 4.93435303e+03 4.93441162e+03 4.93431299e+03 4.93428418e+03 4.93427881e+03 4.93439453e+03 4.93432764e+03 4.93457568e+03 4.93519043e+03 4.93533838e+03 4.93495898e+03 4.93467676e+03 4.93439551e+03 4.93429346e+03 4.93428418e+03 4.93428564e+03 4.93428760e+03 4.93428320e+03 4.93429346e+03 4.93428369e+03 4.93430420e+03 4.93431104e+03 4.93428564e+03 4.93428125e+03 4.93428271e+03 4.93448193e+03 4.93499512e+03 4.93499463e+03 4.93453223e+03 4.93431055e+03 4.93432520e+03 4.93432715e+03 4.93434033e+03 4.93430713e+03 4.93431836e+03 4.93432617e+03 4.93456250e+03 4.93494092e+03 4.93478760e+03 4.93439893e+03 4.93433496e+03 4.93494092e+03 4.93574561e+03 4.93525928e+03 4.93440381e+03 4.93437500e+03 4.93457910e+03 4.93456738e+03 4.93434521e+03 4.93428320e+03 4.93439746e+03 4.93466406e+03 4.93509814e+03 4.93526709e+03 4.93475439e+03 4.93440723e+03 4.93440283e+03 4.93532373e+03 4.93612793e+03 4.93507520e+03 4.93433398e+03 4.93437305e+03 4.93493359e+03 4.93523340e+03 4.93483252e+03 4.93445020e+03 4.93458691e+03 4.93488525e+03 4.93506982e+03 4.93473389e+03 4.93448828e+03 4.93439746e+03 4.93474902e+03 4.93536035e+03 4.93536621e+03 4.93487793e+03 4.93433936e+03 4.93453076e+03 4.93485107e+03 4.93502295e+03 4.93462695e+03 4.93453906e+03 4.93493164e+03 4.93489404e+03 4.93448975e+03 4.93428369e+03 4.93428125e+03 4.93428711e+03 4.93430078e+03 4.93461816e+03 4.93485645e+03 4.93459473e+03 4.93431689e+03 4.93426025e+03 4.93424854e+03 4.93453857e+03 4.93984229e+03 4.95023828e+03 4.96022266e+03 4.95106201e+03 6.99104053e+03 1.40869082e+04 1.70509355e+04 9.69073633e+03 1.05247383e+04 2.49483008e+04 3.95288789e+04 7.60338594e+04 -5.51737360e+11 -2.56329859e+11 -2.56329859e+11 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. 9.12233529e+11 6.32803789e+04 3.00729180e+04 1.98357207e+04 1.97845312e+04 1.00459424e+04 6.85404785e+03 4.97699170e+03 4.93752246e+03 4.91929541e+03 4.91990820e+03 4.91993604e+03 4.91912207e+03 4.91906055e+03 4.91913965e+03 4.91905273e+03 4.91969775e+03 4.92068896e+03 4.91940430e+03 4.91957178e+03 4.92072461e+03 4.91983447e+03 4.91903711e+03 4.91911182e+03 4.91904834e+03 4.91906201e+03 4.91908008e+03 4.91938574e+03 4.91915723e+03 4.91911377e+03 4.91932812e+03 4.91911328e+03 4.91911865e+03 4.91921143e+03 4.91903418e+03 4.91943213e+03 4.91999902e+03 4.91943750e+03 4.91952832e+03 4.92026514e+03 4.91973682e+03 4.91902002e+03 4.91964746e+03 4.91904785e+03 4.92075928e+03 4.92196045e+03 4.92025879e+03 4.91910889e+03 4.91902100e+03 4.91903076e+03 4.91905029e+03 4.91903516e+03 4.91901660e+03 4.91904932e+03 4.92041846e+03 4.92216455e+03 4.92119287e+03 4.91922900e+03 4.91904346e+03 4.91911377e+03 4.91992822e+03 4.92059912e+03 4.91944971e+03 4.91926709e+03 4.91954102e+03 4.91931006e+03 4.91902441e+03 4.91967480e+03 4.91957324e+03 4.91909766e+03 4.91937695e+03 4.91913916e+03 4.91915479e+03 4.91907178e+03 4.91913330e+03 4.91907178e+03 4.91910010e+03 4.91935498e+03 4.91905859e+03 4.91957666e+03 4.92037744e+03 4.91982959e+03 4.91900830e+03 4.91931592e+03 4.91919971e+03 4.91903320e+03 4.91904883e+03 4.91933691e+03 4.91921631e+03 4.91907178e+03 4.91926367e+03 4.91902246e+03 4.91988428e+03 4.92004541e+03 4.91905322e+03 4.91936133e+03 4.91936523e+03 4.91900732e+03 4.91902588e+03 4.91902734e+03 4.91909326e+03 4.92024023e+03 4.92145166e+03 4.91972900e+03 4.91912744e+03 4.91987354e+03 4.91938721e+03 4.91901416e+03 4.91969727e+03 4.92070166e+03 4.92042236e+03 4.92005615e+03 4.92002783e+03 4.91971240e+03 4.91905127e+03 4.91929834e+03 4.91904590e+03 4.91964746e+03 4.92073975e+03 4.91990234e+03 4.91903711e+03 4.91939746e+03 4.91905811e+03 4.91908301e+03 4.91916064e+03 4.91911279e+03 4.91955957e+03 4.92143750e+03 4.92140088e+03 4.91953369e+03 4.91905957e+03 4.91905762e+03 4.91916699e+03 4.91973877e+03 4.91992627e+03 4.91947510e+03 4.91911475e+03 4.91903662e+03 4.91940576e+03 4.91978662e+03 4.91927344e+03 4.91903662e+03 4.91902490e+03 4.91904297e+03 4.91904150e+03 4.91906836e+03 4.91903662e+03 4.91903906e+03 4.91930225e+03 4.91942285e+03 4.91906982e+03 4.91902930e+03 4.91904395e+03 4.91930176e+03 4.91910059e+03 4.91976025e+03 4.92078369e+03 4.91931348e+03 4.91930029e+03 4.91940918e+03 4.91903174e+03 4.91916699e+03 4.91908252e+03 4.91907471e+03 4.91935889e+03 4.92012988e+03 4.92055176e+03 4.91993701e+03 4.91909668e+03 4.91906738e+03 4.91907715e+03 4.91927979e+03 4.91917236e+03 4.91902100e+03 4.91904834e+03 4.92005908e+03 4.91992383e+03 4.91932764e+03 4.91901953e+03 4.91937256e+03 4.92183252e+03 4.92386572e+03 4.92194189e+03 4.91932373e+03 4.91902295e+03 4.91902393e+03 4.91902832e+03 4.91910107e+03 4.91903223e+03 4.91936719e+03 4.92079150e+03 4.92046924e+03 4.91931299e+03 4.91937891e+03 4.91994141e+03 4.91951855e+03 4.91905029e+03 4.91935742e+03 4.91943018e+03 4.91985254e+03 4.92056982e+03 4.92002734e+03 4.91903027e+03 4.91925000e+03 4.91902393e+03 4.92006592e+03 4.92134521e+03 4.91981787e+03 4.91904443e+03 4.91945068e+03 4.91904346e+03 4.91925684e+03 4.91906494e+03 4.91915625e+03 4.91908984e+03 4.91917969e+03 4.91936035e+03 4.91901416e+03 4.91989746e+03 4.92013477e+03 4.91937451e+03 4.91903027e+03 4.91902832e+03 4.91912402e+03 4.91910693e+03 4.91902393e+03 4.91905078e+03 4.91939404e+03 4.91953174e+03 4.91946777e+03 4.91903809e+03 4.91902148e+03 4.91904736e+03 4.91905176e+03 4.91907031e+03 4.91907568e+03 4.91904199e+03 4.91931299e+03 4.91970410e+03 4.91938135e+03 4.91919189e+03 4.91991699e+03 4.91975146e+03 4.91911670e+03 4.91982520e+03 4.91992529e+03 4.91924951e+03 4.91906641e+03 4.91932959e+03 4.91928613e+03 4.91903369e+03 4.91903320e+03 4.91908008e+03 4.91935205e+03 4.91903418e+03 4.91987402e+03 4.91955566e+03 4.91907520e+03 4.91900635e+03 4.91908105e+03 4.91973145e+03 4.91910010e+03 4.91902100e+03 4.91928271e+03 4.91908203e+03 4.91920850e+03 4.91956348e+03 4.91992676e+03 4.91912939e+03 4.91901025e+03 4.91902100e+03 4.91921875e+03 4.91922607e+03 4.91920264e+03 4.91921729e+03 4.91964941e+03 4.92000635e+03 4.91913232e+03 4.91900928e+03 4.91905225e+03 4.91920020e+03 4.91911182e+03 4.91902002e+03 4.91905762e+03 4.91916357e+03 4.91906396e+03 4.91911865e+03 4.91909570e+03 4.91928027e+03 4.91951172e+03 4.91932275e+03 4.91916504e+03 4.91901758e+03 4.91929150e+03 4.91967139e+03 4.91933691e+03 4.91917334e+03 4.91932715e+03 4.91914795e+03 4.91904102e+03 4.91909619e+03 4.91900830e+03 4.91981592e+03 4.92057275e+03 4.91980176e+03 4.91904395e+03 4.91915918e+03 4.91902881e+03 4.91929150e+03 4.91945947e+03 4.91903906e+03 4.91904492e+03 4.91900928e+03 4.91928174e+03 4.91962305e+03 4.91958789e+03 4.91908154e+03 4.91902051e+03 4.91918066e+03 4.91984326e+03 4.91946924e+03 4.91902344e+03 4.91903662e+03 4.91934033e+03 4.91948047e+03 4.91914355e+03 4.91913916e+03 4.91982764e+03 4.92036035e+03 4.91968799e+03 4.91905273e+03 4.91904102e+03 4.91916260e+03 4.91946191e+03 4.91930811e+03 4.91910840e+03 4.91913184e+03 4.91907471e+03 4.91939697e+03 4.91966406e+03 4.91978857e+03 4.91933838e+03 4.91921924e+03 4.91955078e+03 4.92007764e+03 4.91951904e+03 4.91904248e+03 4.91903906e+03 4.91902734e+03 4.91905811e+03 4.91949414e+03 4.91930566e+03 4.91902734e+03 4.91902246e+03 4.91910107e+03 4.91965869e+03 4.91906641e+03 4.91903271e+03 4.91921436e+03 4.91960400e+03 4.91977100e+03 4.91935889e+03 4.91913281e+03 4.91935059e+03 4.91901758e+03 4.91941211e+03 4.91911963e+03 4.91929932e+03 4.91998340e+03 4.91923047e+03 4.91903613e+03 4.91904590e+03 4.91918262e+03 4.91962793e+03 4.92032324e+03 4.92219434e+03 4.92138770e+03 4.91994385e+03 4.91957178e+03 4.92014453e+03 4.92100781e+03 4.91945557e+03 4.91908301e+03 4.91902295e+03 4.91903613e+03 4.91906689e+03 4.91947998e+03 4.92174609e+03 4.92222998e+03 4.91988574e+03 4.91927637e+03 4.91975000e+03 4.91915967e+03 4.92092480e+03 4.92101855e+03 4.91939307e+03 4.91906934e+03 4.91921533e+03 4.92027051e+03 4.92123584e+03 4.92029395e+03 4.91902295e+03 4.91908545e+03 4.91907129e+03 4.91991162e+03 4.92238867e+03 4.92233594e+03 4.92131787e+03 4.91925098e+03 4.91923096e+03 4.91977051e+03 4.91912256e+03 4.91994922e+03 4.92173926e+03 4.92007031e+03 4.91902148e+03 4.91905957e+03 4.92041406e+03 4.92370898e+03 4.92202344e+03 4.91931787e+03 4.91912109e+03 4.91917920e+03 4.91915527e+03 4.91991943e+03 4.92097461e+03 4.91960742e+03 4.91917480e+03 4.91903467e+03 4.91927148e+03 4.91966895e+03 4.91915430e+03 4.91901416e+03 4.91974170e+03 4.91980322e+03 4.91930371e+03 4.91905859e+03 4.92024658e+03 4.92067627e+03 4.91945898e+03 4.91946973e+03 4.92077441e+03 4.91959326e+03 4.91938818e+03 4.92080566e+03 4.92007227e+03 4.91918896e+03 4.91919434e+03 4.91975488e+03 4.92029980e+03 4.92040186e+03 4.91924219e+03 4.91902686e+03 4.91928857e+03 4.91926758e+03 4.91904688e+03 4.91905908e+03 4.91948682e+03 4.91946680e+03 4.91903369e+03 4.91916650e+03 4.91919189e+03 4.91905908e+03 4.91976953e+03 4.91935205e+03 4.91901123e+03 4.91916846e+03 4.91904053e+03 4.92003809e+03 4.91993115e+03 4.91919189e+03 4.91927295e+03 4.91924805e+03 4.91906543e+03 4.91965771e+03 4.92046191e+03 4.91920215e+03 4.91903271e+03 4.91906201e+03 4.91909326e+03 4.91910205e+03 4.91916455e+03 4.91902295e+03 4.91906494e+03 4.91933789e+03 4.91933887e+03 4.91903369e+03 4.91954297e+03 4.92041846e+03 4.91949268e+03 4.91921484e+03 4.92106592e+03 4.92063379e+03 4.91903369e+03 4.92021094e+03 4.92111572e+03 4.91931250e+03 4.91918848e+03 4.91937695e+03 4.91903662e+03 4.91965918e+03 4.91928320e+03 4.91901855e+03 4.91920996e+03 4.91927100e+03 4.91913672e+03 4.91903174e+03 4.91936719e+03 4.91926514e+03 4.91901221e+03 4.91989795e+03 4.92014551e+03 4.91917920e+03 4.91925098e+03 4.91916211e+03 4.91909668e+03 4.91960107e+03 4.91917090e+03 4.91901953e+03 4.91907715e+03 4.91911475e+03 4.91902148e+03 4.91907959e+03 4.91901514e+03 4.91906396e+03 4.91929053e+03 4.91901660e+03 4.91907764e+03 4.91964697e+03 4.92019727e+03 4.91950928e+03 4.91909961e+03 4.91925391e+03 4.91949121e+03 4.91909033e+03 4.91916846e+03 4.91924854e+03 4.91907227e+03 4.91979053e+03 4.91956152e+03 4.91908105e+03 4.91921484e+03 4.91943799e+03 4.91913818e+03 4.91902979e+03 4.91912305e+03 4.91907568e+03 4.91956738e+03 4.92085791e+03 4.92050537e+03 4.91933789e+03 4.91937354e+03 4.91962939e+03 4.92104053e+03 4.92122852e+03 4.92079639e+03 4.91978516e+03 4.91902539e+03 4.91917920e+03 4.91904395e+03 4.91935791e+03 4.91989404e+03 4.91915625e+03 4.91918018e+03 4.91921484e+03 4.91913477e+03 4.92004736e+03 4.91967285e+03 4.91902441e+03 4.91943799e+03 4.91950879e+03 4.91900439e+03 4.91967285e+03 4.92006543e+03 4.91981689e+03 4.91935205e+03 4.91911865e+03 4.91900879e+03 4.91902344e+03 4.91902832e+03 4.91909131e+03 4.91902686e+03 4.91956787e+03 4.92029297e+03 4.91932275e+03 4.91913721e+03 4.91966455e+03 4.91908105e+03 4.91949902e+03 4.91973486e+03 4.91912744e+03 4.91930029e+03 4.91942773e+03 4.91904346e+03 4.91904980e+03 4.91907617e+03 4.91906836e+03 4.91919092e+03 4.91912793e+03 4.91904541e+03 4.91913330e+03 4.91905322e+03 4.91901025e+03 4.91949463e+03 4.92040918e+03 4.91993213e+03 4.91943457e+03 4.91906445e+03 4.91912061e+03 4.91909033e+03 4.91988428e+03 4.92199561e+03 4.92155664e+03 4.91957715e+03 4.91921582e+03 4.92498682e+03 4.92672363e+03 4.92021387e+03 6.65339844e+03 1.23191875e+04 9.41732741e+10 5.96064993e+10 3.53341235e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.18685354e+11 1.02058058e+11 6.30943945e+04 2.86198848e+04 1.97803125e+04 1.97364961e+04 1.97531035e+04 1.97383145e+04 9.66016895e+03 6.54185596e+03 4.93070068e+03 4.92814062e+03 4.92145703e+03 4.92040625e+03 4.91996289e+03 4.91944629e+03 4.91930127e+03 4.91929736e+03 4.91903223e+03 4.91955029e+03 4.91938672e+03 4.91909277e+03 4.92008691e+03 4.92036035e+03 4.91920459e+03 4.91939111e+03 4.91975928e+03 4.91904199e+03 4.91964648e+03 4.91979443e+03 4.91903516e+03 4.91903760e+03 4.91928369e+03 4.91943115e+03 4.91909131e+03 4.91905371e+03 4.91905225e+03 4.91911475e+03 4.91936914e+03 4.91937549e+03 4.91905566e+03 4.91979395e+03 4.91977344e+03 4.91909570e+03 4.91912549e+03 4.91909814e+03 4.91918799e+03 4.92038867e+03 4.92022070e+03 4.91900928e+03 4.92042725e+03 4.92017578e+03 4.91905273e+03 4.91958057e+03 4.91960107e+03 4.91900586e+03 4.91903516e+03 4.91906299e+03 4.91913965e+03 4.91903711e+03 4.91904150e+03 4.91990088e+03 4.91943848e+03 4.91901416e+03 4.91912061e+03 4.91906787e+03 4.92019531e+03 4.92020117e+03 4.91944336e+03 4.91901172e+03 4.91915430e+03 4.91913086e+03 4.92061475e+03 4.92299268e+03 4.92171924e+03 4.91937500e+03 4.91907129e+03 4.91957910e+03 4.92055176e+03 4.92045068e+03 4.91907666e+03 4.91902197e+03 4.91908984e+03 4.91948926e+03 4.91943994e+03 4.91946094e+03 4.91978809e+03 4.91928125e+03 4.91901953e+03 4.91913818e+03 4.91915186e+03 4.92090137e+03 4.92134326e+03 4.92036475e+03 4.91914014e+03 4.91903174e+03 4.91907422e+03 4.91922852e+03 4.91979150e+03 4.91975928e+03 4.91903027e+03 4.91930811e+03 4.91905322e+03 4.91983154e+03 4.91977539e+03 4.91901660e+03 4.91927734e+03 4.91916504e+03 4.91911621e+03 4.91903711e+03 4.91904688e+03 4.91992871e+03 4.91988770e+03 4.91910693e+03 4.91906543e+03 4.91908691e+03 4.91915479e+03 4.91920947e+03 4.91902832e+03 4.91905420e+03 4.91938672e+03 4.91921338e+03 4.91904883e+03 4.91973730e+03 4.92008691e+03 4.91902051e+03 4.91915967e+03 4.91901074e+03 4.91910303e+03 4.91912939e+03 4.91904004e+03 4.91902930e+03 4.91902051e+03 4.91910059e+03 4.91911133e+03 4.91905566e+03 4.91952783e+03 4.91939844e+03 4.91901904e+03 4.91925195e+03 4.91916309e+03 4.91905957e+03 4.91904736e+03 4.91910010e+03 4.91931885e+03 4.91992725e+03 4.91934033e+03 4.91903955e+03 4.91942285e+03 4.91932422e+03 4.91902441e+03 4.91905518e+03 4.91901904e+03 4.91903027e+03 4.91904395e+03 4.91937598e+03 4.91976172e+03 4.92014844e+03 4.92025879e+03 4.91959863e+03 4.91910596e+03 4.91928711e+03 4.91965381e+03 4.91939014e+03 4.91904834e+03 4.91905713e+03 4.91948877e+03 4.92051904e+03 4.91982324e+03 4.91902246e+03 4.91960449e+03 4.91946387e+03 4.91912451e+03 4.91971582e+03 4.91952979e+03 4.91903662e+03 4.91905371e+03 4.91910352e+03 4.91909375e+03 4.91912256e+03 4.91913184e+03 4.91914014e+03 4.91905811e+03 4.91985693e+03 4.91973633e+03 4.91941455e+03 4.91903760e+03 4.91909326e+03 4.91920361e+03 4.91907324e+03 4.91907227e+03 4.91935791e+03 4.92029248e+03 4.91979932e+03 4.91903174e+03 4.91957861e+03 4.91969629e+03 4.91905908e+03 4.91905078e+03 4.91905811e+03 4.91927881e+03 4.91918018e+03 4.91907129e+03 4.91955957e+03 4.92018408e+03 4.92025391e+03 4.92119043e+03 4.92038232e+03 4.91924609e+03 4.91905518e+03 4.91907275e+03 4.91922900e+03 4.91932910e+03 4.91904980e+03 4.91933838e+03 4.92055322e+03 4.91972607e+03 4.91906494e+03 4.92028906e+03 4.91972705e+03 4.91904004e+03 4.91910107e+03 4.91908447e+03 4.91921729e+03 4.91919482e+03 4.91903418e+03 4.91916504e+03 4.91931445e+03 4.91928809e+03 4.91907520e+03 4.91906934e+03 4.91965674e+03 4.91992236e+03 4.91957568e+03 4.91914209e+03 4.91908691e+03 4.91906641e+03 4.91904102e+03 4.91927002e+03 4.91937842e+03 4.91922949e+03 4.91903076e+03 4.91903857e+03 4.91906104e+03 4.91902148e+03 4.91902295e+03 4.91903564e+03 4.91905078e+03 4.91912793e+03 4.91913818e+03 4.91906201e+03 4.91903174e+03 4.91903271e+03 4.91906348e+03 4.91908594e+03 4.91904541e+03 4.91902100e+03 4.91904102e+03 4.91904541e+03 4.91903027e+03 4.91905127e+03 4.91901465e+03 4.91903027e+03 4.91904736e+03 4.91902979e+03 4.91905811e+03 4.91910791e+03 4.91907568e+03 4.91906348e+03 4.91908008e+03 4.91910693e+03 4.91907520e+03 4.91910645e+03 4.91907568e+03 4.91906982e+03 4.91903320e+03 4.91906885e+03 4.91907520e+03 4.91907129e+03 4.91904688e+03 4.91905957e+03 4.91908789e+03 4.91908252e+03 4.91911279e+03 4.91907764e+03 4.91903613e+03 4.91903369e+03 4.91906104e+03 4.91908398e+03 4.91911377e+03 4.91907275e+03 4.91913135e+03 4.91910107e+03 4.91914746e+03 4.91912744e+03 4.91913086e+03 4.91901855e+03 4.91910498e+03 4.91925635e+03 4.91912158e+03 4.91905371e+03 4.91904199e+03 4.91903564e+03 4.91902881e+03 4.91903906e+03 4.91904639e+03 4.91904492e+03 4.91906982e+03 4.91904932e+03 4.91902295e+03 4.91902295e+03 4.91904346e+03 4.91902588e+03 4.91903516e+03 4.91903613e+03 4.91902930e+03 4.91901172e+03 4.91908252e+03 4.91906592e+03 4.91907471e+03 4.91902783e+03 4.91912256e+03 4.91949463e+03 4.91963623e+03 4.91939990e+03 4.91912695e+03 4.91903076e+03 4.91904883e+03 4.91903857e+03 4.91904541e+03 4.91904346e+03 4.91921729e+03 4.91920215e+03 4.91905420e+03 4.91903711e+03 4.91905615e+03 4.91902393e+03 4.91904102e+03 4.91903809e+03 4.91903125e+03 4.91904395e+03 4.91905664e+03 4.91909229e+03 4.91903369e+03 4.91902393e+03 4.91903613e+03 4.91910254e+03 4.91930273e+03 4.91931494e+03 4.91927539e+03 4.91909326e+03 4.91913037e+03 4.91915381e+03 4.91912695e+03 4.91907764e+03 4.91903418e+03 4.91911572e+03 4.91921973e+03 4.91935400e+03 4.91909424e+03 4.91905273e+03 4.91906250e+03 4.91906885e+03 4.91928418e+03 4.91966504e+03 4.91926562e+03 4.91903320e+03 4.91906494e+03 4.91905566e+03 4.91906250e+03 4.91907031e+03 4.91930518e+03 4.91949805e+03 4.91933838e+03 4.91911963e+03 4.91903662e+03 4.91905029e+03 4.91902832e+03 4.91906396e+03 4.91923486e+03 4.91927979e+03 4.91908691e+03 4.91903711e+03 4.91903418e+03 4.91903027e+03 4.91902246e+03 4.91907812e+03 4.91910352e+03 4.91910156e+03 4.91905859e+03 4.91902441e+03 4.91902246e+03 4.91903906e+03 4.91905811e+03 4.91906738e+03 4.91905615e+03 4.91906494e+03 4.91904102e+03 4.91906689e+03 4.91906934e+03 4.91915137e+03 4.91932178e+03 4.91910205e+03 4.91904883e+03 4.91903516e+03 4.91904785e+03 4.91913574e+03 4.91928760e+03 4.91940869e+03 4.91923389e+03 4.91911475e+03 4.91903955e+03 4.91903125e+03 4.91907959e+03 4.91905518e+03 4.91903760e+03 4.91902979e+03 4.91903613e+03 4.91905176e+03 4.91911914e+03 4.91936035e+03 4.91951074e+03 4.91915527e+03 4.91905908e+03 4.91903467e+03 4.91903271e+03 4.91902783e+03 4.91904102e+03 4.91905127e+03 4.91907275e+03 4.91912842e+03 4.91941504e+03 4.91933838e+03 4.91917676e+03 4.91905566e+03 4.91905518e+03 4.91910254e+03 4.91913525e+03 4.91912061e+03 4.91906396e+03 4.91929785e+03 4.91986572e+03 4.91992139e+03 4.91928613e+03 4.91904199e+03 4.91902832e+03 4.91907764e+03 4.91962646e+03 4.92312988e+03 4.94548193e+03 4.97085547e+03 4.98184912e+03 5.00778955e+03 6.86101367e+03 1.02277734e+04 1.96560156e+04 2.65576309e+04 2.45545645e+04 4.07103594e+04 6.20213555e+04 4.44326912e+10 1.00954374e+11 3.64830351e+10 6.75832218e+10 5.04543232e+10 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. 0. 0. 0. 0. 0. 0. -1.27275851e+13 -1.27275851e+13 2.08604021e+11 6.24344922e+04 2.99281465e+04 1.98275176e+04 9.80989062e+03 6.72322510e+03 4.98479736e+03 4.96802734e+03 4.94426562e+03 4.92277734e+03 4.91991650e+03 4.91977930e+03 4.91931641e+03 4.91906494e+03 4.91907080e+03 4.91907422e+03 4.91907520e+03 4.91907129e+03 4.91926172e+03 4.91957227e+03 4.91927246e+03 4.91904004e+03 4.91903516e+03 4.91909521e+03 4.91925391e+03 4.91912012e+03 4.91910156e+03 4.91916064e+03 4.91923047e+03 4.91930469e+03 4.91931348e+03 4.91930273e+03 4.91918652e+03 4.91916699e+03 4.91909619e+03 4.91910449e+03 4.91903027e+03 4.91915869e+03 4.91920068e+03 4.91906494e+03 4.91902588e+03 4.91903125e+03 4.91908789e+03 4.91910742e+03 4.91921973e+03 4.91927441e+03 4.91934082e+03 4.91939941e+03 4.91946436e+03 4.91931201e+03 4.91920703e+03 4.91911279e+03 4.91914893e+03 4.91912891e+03 4.91908447e+03 4.91913477e+03 4.91915576e+03 4.91928223e+03 4.91932910e+03 4.91917725e+03 4.91902100e+03 4.91919287e+03 4.91938379e+03 4.91915723e+03 4.91905078e+03 4.91902295e+03 4.91904932e+03 4.91918994e+03 4.91911279e+03 4.91904102e+03 4.91917432e+03 4.91916162e+03 4.91913477e+03 4.91930273e+03 4.91980615e+03 4.91944336e+03 4.91906201e+03 4.91909375e+03 4.91908350e+03 4.91901611e+03 4.91904102e+03 4.91903467e+03 4.91906055e+03 4.91910010e+03 4.91907031e+03 4.91904102e+03 4.91903906e+03 4.91905469e+03 4.91905371e+03 4.91902979e+03 4.91901904e+03 4.91910156e+03 4.91954883e+03 4.91939893e+03 4.91914111e+03 4.91901758e+03 4.91904004e+03 4.91910400e+03 4.91927295e+03 4.91937256e+03 4.91912842e+03 4.91903174e+03 4.91903809e+03 4.91902197e+03 4.91915137e+03 4.91911621e+03 4.91909717e+03 4.91903760e+03 4.91902734e+03 4.91902295e+03 4.91901465e+03 4.91902539e+03 4.91902686e+03 4.91903516e+03 4.91902539e+03 4.91901367e+03 4.91904102e+03 4.91925488e+03 4.91931250e+03 4.91909082e+03 4.91902832e+03 4.91906689e+03 4.91907959e+03 4.91909082e+03 4.91911670e+03 4.91915430e+03 4.91918066e+03 4.91900586e+03 4.91926367e+03 4.91936865e+03 4.91915967e+03 4.91902686e+03 4.91907324e+03 4.91914746e+03 4.91911914e+03 4.91904688e+03 4.91903613e+03 4.91905322e+03 4.91903906e+03 4.91903125e+03 4.91902344e+03 4.91903955e+03 4.91902881e+03 4.91903906e+03 4.91903760e+03 4.91902490e+03 4.91903320e+03 4.91901709e+03 4.91903516e+03 4.91901221e+03 4.91902979e+03 4.91904004e+03 4.91905518e+03 4.91903516e+03 4.91903027e+03 4.91903467e+03 4.91902490e+03 4.91904053e+03 4.91905859e+03 4.91906201e+03 4.91902344e+03 4.91921143e+03 4.91953711e+03 4.91961035e+03 4.91936621e+03 4.91919482e+03 4.91915967e+03 4.91904492e+03 4.91903857e+03 4.91904932e+03 4.91906055e+03 4.91906787e+03 4.91903711e+03 4.91904297e+03 4.91902197e+03 4.91917432e+03 4.91952783e+03 4.91987500e+03 4.91967285e+03 4.91920020e+03 4.91902002e+03 4.91908887e+03 4.91905322e+03 4.91904053e+03 4.91901172e+03 4.91900342e+03 4.91901709e+03 4.91902197e+03 4.91902930e+03 4.91901562e+03 4.91900049e+03 4.91902441e+03 4.91901074e+03 4.91903809e+03 4.91903223e+03 4.91902344e+03 4.91903760e+03 4.91904150e+03 4.91906299e+03 4.91902441e+03 4.91910596e+03 4.91937793e+03 4.91969092e+03 4.91961865e+03 4.91957080e+03 4.91962451e+03 4.91927441e+03 4.91902246e+03 4.91909912e+03 4.91916064e+03 4.91910156e+03 4.91904639e+03 4.91902686e+03 4.91904883e+03 4.91912646e+03 4.91909131e+03 4.91908984e+03 4.91903076e+03 4.91903906e+03 4.91903027e+03 4.91919971e+03 4.91963867e+03 4.91945264e+03 4.91914697e+03 4.91901221e+03 4.91905029e+03 4.91912207e+03 4.91946680e+03 4.91977539e+03 4.91955664e+03 4.91922852e+03 4.91900928e+03 4.91907715e+03 4.91915576e+03 4.91926025e+03 4.91917432e+03 4.91913525e+03 4.91916309e+03 4.91921338e+03 4.91918457e+03 4.91910645e+03 4.91904541e+03 4.91905078e+03 4.91921777e+03 4.91958496e+03 4.92016895e+03 4.92037207e+03 4.91926318e+03 4.91903564e+03 4.91925195e+03 4.91907031e+03 4.91903223e+03 4.91902783e+03 4.91905762e+03 4.91901904e+03 4.91901611e+03 4.91901172e+03 4.91901660e+03 4.91901611e+03 4.91901855e+03 4.91900684e+03 4.91908545e+03 4.91942285e+03 4.91960693e+03 4.91931299e+03 4.91908301e+03 4.91901367e+03 4.91905127e+03 4.91908838e+03 4.91901416e+03 4.91902344e+03 4.91903320e+03 4.91903223e+03 4.91901465e+03 4.91903613e+03 4.91906396e+03 4.91904150e+03 4.91904199e+03 4.91901904e+03 4.91900830e+03 4.91900098e+03 4.91901904e+03 4.91902979e+03 4.91908008e+03 4.91907861e+03 4.91905029e+03 4.91903467e+03 4.91928467e+03 4.91920850e+03 4.91902393e+03 4.91904150e+03 4.91901855e+03 4.91901221e+03 4.91903760e+03 4.91902393e+03 4.91905566e+03 4.91906104e+03 4.91921094e+03 4.91932373e+03 4.91928955e+03 4.91904004e+03 4.91902344e+03 4.91905371e+03 4.91901904e+03 4.91907520e+03 4.91930518e+03 4.91945898e+03 4.91932520e+03 4.91908545e+03 4.91907178e+03 4.91905078e+03 4.91906641e+03 4.91905957e+03 4.91905029e+03 4.91906738e+03 4.91911084e+03 4.91910254e+03 4.91906396e+03 4.91907568e+03 4.91909229e+03 4.91906299e+03 4.91903320e+03 4.91903662e+03 4.91918555e+03 4.91914160e+03 4.91905859e+03 4.91901855e+03 4.91902100e+03 4.91901221e+03 4.91904004e+03 4.91902490e+03 4.91908643e+03 4.91939355e+03 4.91936133e+03 4.91906152e+03 4.91901172e+03 4.91901514e+03 4.91903564e+03 4.91906201e+03 4.91902979e+03 4.91914697e+03 4.91951074e+03 4.91962500e+03 4.91924707e+03 4.91900146e+03 4.91902148e+03 4.91902686e+03 4.91905273e+03 4.91902002e+03 4.91900586e+03 4.91902881e+03 4.91907910e+03 4.91912744e+03 4.91907764e+03 4.91904395e+03 4.91906592e+03 4.91937939e+03 4.92017090e+03 4.92017432e+03 4.91953564e+03 4.91910254e+03 4.91905615e+03 4.91901758e+03 4.91903906e+03 4.91906885e+03 4.91942285e+03 4.91989355e+03 4.92058984e+03 4.92072266e+03 4.92001416e+03 4.91951709e+03 4.91909424e+03 4.91925830e+03 4.91953076e+03 4.91922949e+03 4.91905762e+03 4.91934180e+03 4.91911133e+03 4.91904297e+03 4.91903369e+03 4.91901758e+03 4.91902881e+03 4.91903027e+03 4.91907959e+03 4.91908252e+03 4.91907910e+03 4.91906982e+03 4.91904004e+03 4.91906104e+03 4.91907715e+03 4.91911719e+03 4.91907715e+03 4.91902881e+03 4.91915234e+03 4.91909277e+03 4.91902588e+03 4.91916797e+03 4.91903711e+03 4.91919824e+03 4.91902490e+03 4.91946533e+03 4.91958154e+03 4.91906543e+03 4.91948682e+03 4.91922803e+03 4.91901123e+03 4.91908350e+03 4.91944482e+03 4.91953711e+03 4.91927734e+03 4.91905713e+03 4.91906982e+03 4.91908398e+03 4.91904980e+03 4.91903369e+03 4.91904932e+03 4.91920703e+03 4.91902441e+03 4.91931689e+03 4.91977832e+03 4.91943359e+03 4.91918018e+03 4.91943799e+03 4.91980615e+03 4.91987354e+03 4.91950488e+03 4.91911035e+03 4.91910742e+03 4.91917041e+03 4.91927539e+03 4.91911719e+03 4.91923730e+03 4.91951611e+03 4.91976758e+03 4.91967139e+03 4.91919775e+03 4.91905029e+03 4.91900391e+03 4.91903223e+03 4.91901807e+03 4.91921045e+03 4.91993066e+03 4.91969775e+03 4.91904932e+03 4.91917285e+03 4.91910449e+03 4.91901709e+03 4.91912549e+03 4.91946631e+03 4.91949365e+03 4.91917529e+03 4.91902148e+03 4.91901074e+03 4.91902295e+03 4.91901318e+03 4.91901709e+03 4.91902246e+03 4.91903662e+03 4.91910693e+03 4.91916504e+03 4.91909473e+03 4.91902490e+03 4.91900879e+03 4.91902051e+03 4.91901953e+03 4.91916504e+03 4.91953564e+03 4.91922607e+03 4.91914355e+03 4.91954932e+03 4.91915283e+03 4.91903320e+03 4.91917383e+03 4.91927100e+03 4.91924805e+03 4.91916309e+03 4.91909717e+03 4.91912500e+03 4.91906006e+03 4.91908496e+03 4.91909375e+03 4.91920020e+03 4.91925977e+03 4.91929102e+03 4.91914600e+03 4.91903418e+03 4.91905811e+03 4.91918115e+03 4.91931006e+03 4.91911328e+03 4.91903955e+03 4.91902002e+03 4.91908057e+03 4.91937939e+03 4.91939014e+03 4.91918994e+03 4.91917041e+03 4.92005811e+03 4.92100977e+03 4.92038867e+03 4.91948438e+03 4.91959961e+03 4.92031885e+03 4.92051025e+03 4.91980811e+03 4.91934521e+03 4.91921826e+03 4.91919092e+03 4.91925342e+03 4.91930908e+03 4.91928027e+03 4.91913867e+03 4.91930078e+03 4.91981396e+03 4.92007666e+03 4.91963037e+03 4.91915625e+03 4.91915479e+03 4.91941943e+03 4.91915088e+03 4.91900635e+03 4.91910205e+03 4.91903906e+03 4.91902637e+03 4.91901758e+03 4.91900684e+03 4.91902539e+03 4.91900977e+03 4.91903125e+03 4.91902148e+03 4.91902490e+03 4.91901514e+03 4.91902930e+03 4.91908154e+03 4.91906494e+03 4.91902246e+03 4.91901855e+03 4.91907764e+03 4.91930957e+03 4.91928760e+03 4.91904736e+03 4.91911328e+03 4.91917627e+03 4.91915332e+03 4.91935010e+03 4.91981250e+03 4.91988135e+03 4.91950586e+03 4.91912305e+03 4.91906885e+03 4.91904590e+03 4.91908350e+03 4.91944580e+03 4.91962793e+03 4.91921631e+03 4.91905225e+03 4.91906738e+03 4.91905762e+03 4.91903809e+03 4.91901611e+03 4.91904150e+03 4.91928320e+03 4.91914160e+03 4.91905029e+03 4.91923730e+03 4.91907129e+03 4.91908252e+03 4.91988574e+03 4.92081152e+03 4.92037012e+03 4.91929150e+03 4.91912061e+03 4.91931543e+03 4.91929932e+03 4.91910498e+03 4.91904443e+03 4.91903125e+03 4.91906982e+03 4.91913232e+03 4.91907080e+03 4.91901416e+03 4.91906543e+03 4.91911670e+03 4.91915918e+03 4.91905518e+03 4.91908252e+03 4.91914111e+03 4.91904736e+03 4.91908252e+03 4.91915332e+03 4.91902344e+03 4.91908350e+03 4.91904346e+03 4.91911377e+03 4.91903467e+03 4.92105371e+03 4.92555078e+03 4.93547021e+03 4.93433936e+03 7.07110547e+03 1.43463857e+04 1.43492793e+04 6.78452539e+03 7.21442041e+03 6.18489648e+03 9.87904004e+03 1.49775479e+04 1.82535897e+11 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. 0. 0. 9.12233529e+11 -7.68630129e+11 4.56328413e+11 1.33944443e+11 1.63176123e+04 7.68196924e+03 4.96321680e+03 4.92429248e+03 4.91919775e+03 4.91886963e+03 4.91874316e+03 4.91875146e+03 4.91886133e+03 4.91928223e+03 4.91896289e+03 4.91884961e+03 4.91924561e+03 4.91879248e+03 4.91911963e+03 4.91872559e+03 4.91984033e+03 4.92364209e+03 4.92422803e+03 4.92261084e+03 4.91955908e+03 4.91882129e+03 4.91858545e+03 4.91898828e+03 4.91883789e+03 4.91921094e+03 4.92089893e+03 4.92143848e+03 4.91969141e+03 4.91880957e+03 4.91878223e+03 4.91877490e+03 4.91890430e+03 4.91936035e+03 4.91957617e+03 4.91887256e+03 4.91987402e+03 4.92181641e+03 4.92068555e+03 4.91894629e+03 4.91881885e+03 4.91881055e+03 4.91878076e+03 4.91901074e+03 4.91886621e+03 4919. 4.91923389e+03 4.91907275e+03 4.91883350e+03 4.92049707e+03 4.92013330e+03 4.91877881e+03 4.91950586e+03 4.91903516e+03 4.91884229e+03 4.91879785e+03 4.91896484e+03 4.91897656e+03 4.91880176e+03 4.91944336e+03 4.91911914e+03 4.91900391e+03 4.92006299e+03 4.91949805e+03 4.91880176e+03 4.91877100e+03 4.91887256e+03 4.91885645e+03 4.91881885e+03 4.91936182e+03 4.91908691e+03 4.91881885e+03 4.91886475e+03 4.91932812e+03 4.91964746e+03 4.91934033e+03 4.91881689e+03 4.91883936e+03 4.91893652e+03 4.91876758e+03 4.91880322e+03 4.91878857e+03 4.91906152e+03 4.92031836e+03 4.92128369e+03 4.91947705e+03 4.91887793e+03 4.91962549e+03 4.91904492e+03 4.91894775e+03 4.92067090e+03 4.92170020e+03 4.92070654e+03 4.92010889e+03 4.92022607e+03 4.91989990e+03 4.91878271e+03 4.91906885e+03 4.91890576e+03 4.91892822e+03 4.91944531e+03 4.91905762e+03 4.91876465e+03 4.91881836e+03 4.91880859e+03 4.91897559e+03 4.91889795e+03 4.91883594e+03 4.91929053e+03 4.92122852e+03 4.92162842e+03 4.91976025e+03 4.91879443e+03 4.91879639e+03 4.91915186e+03 4.92005225e+03 4.92006787e+03 4.91928516e+03 4.91878906e+03 4.91878223e+03 4.91879639e+03 4.91879883e+03 4.91881689e+03 4.91882861e+03 4.91882031e+03 4.91950635e+03 4.91942432e+03 4.91880859e+03 4.91879053e+03 4.91883545e+03 4.91911670e+03 4.91929004e+03 4.91897119e+03 4.91921631e+03 4.92004541e+03 4.92037744e+03 4.91915625e+03 4.91920703e+03 4.92038379e+03 4.91941699e+03 4.91878027e+03 4.91881934e+03 4.91877588e+03 4.91893262e+03 4.91890039e+03 4.91892627e+03 4.91912061e+03 4.91994824e+03 4.92038086e+03 4.91941357e+03 4.91891309e+03 4.91977979e+03 4.91901807e+03 4.91881689e+03 4.91881641e+03 4.91878955e+03 4.91879248e+03 4.91984375e+03 4.91967236e+03 4.91882178e+03 4.91909229e+03 4.91877295e+03 4.92057617e+03 4.92291602e+03 4.92110645e+03 4.91908789e+03 4.91879541e+03 4.91878125e+03 4.91879395e+03 4.91889844e+03 4.91879834e+03 4.91915674e+03 4.92098730e+03 4.92001367e+03 4.91884912e+03 4.91901855e+03 4.91892529e+03 4.91878125e+03 4.91898828e+03 4.91927490e+03 4.91924316e+03 4.91951855e+03 4.92023438e+03 4.91986279e+03 4.91879541e+03 4.91917236e+03 4.91891211e+03 4.91917334e+03 4.92047217e+03 4.91969775e+03 4.91885498e+03 4.91880566e+03 4.91877344e+03 4.91884668e+03 4.91947314e+03 4.92001855e+03 4.91900977e+03 4.91903662e+03 4.91938232e+03 4.91897266e+03 4.91895117e+03 4.91924609e+03 4.91912012e+03 4.91882520e+03 4.91879541e+03 4.91878125e+03 4.91888623e+03 4.91915869e+03 4.91889014e+03 4.91884424e+03 4.91912256e+03 4.91899951e+03 4.91877002e+03 4.91881689e+03 4.91876367e+03 4.91878271e+03 4.91877246e+03 4.91881787e+03 4.91879004e+03 4.91913232e+03 4.91949512e+03 4.91958984e+03 4.91878906e+03 4.91884668e+03 4.91877100e+03 4.91930664e+03 4.91962988e+03 4.91892383e+03 4.91879883e+03 4.91878906e+03 4.91882520e+03 4.91883398e+03 4.91882275e+03 4.91883398e+03 4.91882080e+03 4.91926270e+03 4.91889502e+03 4.91877441e+03 4.91891748e+03 4.91906396e+03 4.91885498e+03 4.91876416e+03 4.91879688e+03 4.91877539e+03 4.91888867e+03 4.91897461e+03 4.91888232e+03 4.91897363e+03 4.91930615e+03 4.91969922e+03 4.91884961e+03 4.91877295e+03 4.91879541e+03 4.91892773e+03 4.91884326e+03 4.91881006e+03 4.91891895e+03 4.91941553e+03 4.91980469e+03 4.91881201e+03 4.91882178e+03 4.91892969e+03 4.91886133e+03 4.91896436e+03 4.91884668e+03 4.91877148e+03 4.91876221e+03 4.91902930e+03 4.91884863e+03 4.91875830e+03 4.91922900e+03 4.91963428e+03 4.91938428e+03 4.91880762e+03 4.91884082e+03 4.91876904e+03 4.91908203e+03 4.91939160e+03 4.91898145e+03 4.91934033e+03 4.91931689e+03 4.91891113e+03 4.91889307e+03 4.91890771e+03 4.91900977e+03 4.91948828e+03 4.91897070e+03 4.91886670e+03 4.91877295e+03 4.91892822e+03 4.91914697e+03 4.91895020e+03 4.91876904e+03 4.91875977e+03 4.91879688e+03 4.91886670e+03 4.91916016e+03 4.91925439e+03 4.91881787e+03 4.91877393e+03 4.91884277e+03 4.91918213e+03 4.91926025e+03 4.91949414e+03 4.92102441e+03 4.92203906e+03 4.92161279e+03 4.92095508e+03 4.92112695e+03 4.92239258e+03 4.92250537e+03 4.92142432e+03 4.91949756e+03 4.91913428e+03 4.91898193e+03 4.91913281e+03 4.91895801e+03 4.91876709e+03 4.91881885e+03 4.91890283e+03 4.91880762e+03 4.91896436e+03 4.91904785e+03 4.91888135e+03 4.91899316e+03 4.91919971e+03 4.91967383e+03 4.91952148e+03 4.91958740e+03 4.92055273e+03 4.92136182e+03 4.92085938e+03 4.91947656e+03 4.91930713e+03 4.91929297e+03 4.91883154e+03 4.91878711e+03 4.91888818e+03 4.91885449e+03 4.91886133e+03 4.91894775e+03 4.91927979e+03 4.91931104e+03 4.91891406e+03 4.91896729e+03 4.91914209e+03 4.91878027e+03 4.91919678e+03 4.91911865e+03 4.91876611e+03 4.91898975e+03 4.91881396e+03 4.91888037e+03 4.91946094e+03 4.91939355e+03 4.91890820e+03 4.91876660e+03 4.91903564e+03 4.91912695e+03 4.91914355e+03 4.91934375e+03 4.91931787e+03 4.91936523e+03 4.91877197e+03 4.91876367e+03 4.91877441e+03 4.91876123e+03 4.91877734e+03 4.91893994e+03 4.92106641e+03 4.92172412e+03 4.91978223e+03 4.91897461e+03 4.91998047e+03 4.91887695e+03 4.91927637e+03 4.91942090e+03 4.91889404e+03 4.92100781e+03 4.92033545e+03 4.91878320e+03 4.91907373e+03 4.91899268e+03 4.91886768e+03 4.91887354e+03 4.91881299e+03 4.91917480e+03 4.91947021e+03 4.91877979e+03 4.91876953e+03 4.91893701e+03 4.91938867e+03 4.91938916e+03 4.91889844e+03 4.91914795e+03 4.91919971e+03 4.91876709e+03 4.91980127e+03 4.91959521e+03 4.91904688e+03 4.92110742e+03 4.91999023e+03 4.91876611e+03 4.91920215e+03 4.91895410e+03 4.91883936e+03 4.91912988e+03 4.91935449e+03 4.91878369e+03 4.91877051e+03 4.91879639e+03 4.91902148e+03 4.91938135e+03 4.91884473e+03 4.91880518e+03 4.91937939e+03 4.91939795e+03 4.91901562e+03 4.91875781e+03 4.91984570e+03 4.92073291e+03 4.91932031e+03 4.91919873e+03 4.92089551e+03 4.91948584e+03 4.91910303e+03 4.91982373e+03 4.91874854e+03 4.92065234e+03 4.92067822e+03 4.91879053e+03 4.91898926e+03 4.91896094e+03 4.91879785e+03 4.91883789e+03 4.91877832e+03 4.91913135e+03 4.92000830e+03 4.91993066e+03 4.92071924e+03 4.92047314e+03 4.91939404e+03 4.91878125e+03 4.91896777e+03 4.91880078e+03 4.91946436e+03 4.91917236e+03 4.91887109e+03 4.91992676e+03 4.91941260e+03 4.91880127e+03 4.91900586e+03 4.91876562e+03 4.91924561e+03 4.91909326e+03 4.91876318e+03 4.91925000e+03 4.92003662e+03 4.91918604e+03 4.91908594e+03 4.91887451e+03 4.91896387e+03 4.91907471e+03 4.91925439e+03 4.91992871e+03 4.91925732e+03 4.91877539e+03 4.91906787e+03 4.91882812e+03 4.91914844e+03 4.92037012e+03 4.91930859e+03 4.91881104e+03 4.91943408e+03 4.91933105e+03 4.91876953e+03 4.91880859e+03 4.91890186e+03 4.91877002e+03 4.91879932e+03 4.91901367e+03 4.91957373e+03 4.92051221e+03 4.91998145e+03 4.91893457e+03 4.91883057e+03 4.91885352e+03 4.91876416e+03 4.91887646e+03 4.91951074e+03 4.92010498e+03 4.91901465e+03 4.91911328e+03 4.92003467e+03 4.91888281e+03 4.91905420e+03 4.91905811e+03 4.91902295e+03 4.92101660e+03 4.92043701e+03 4.91877490e+03 4.92016016e+03 4.92155713e+03 4.91956152e+03 4.91883496e+03 4.91881299e+03 4.91907373e+03 4.91942090e+03 4.91896436e+03 4.91904004e+03 4.91887402e+03 4.91876465e+03 4.91882617e+03 4.91885059e+03 4.91888330e+03 4.91885059e+03 4.91892334e+03 4.92027734e+03 4.92009180e+03 4.91880762e+03 4.92006787e+03 4.91956494e+03 4.91882666e+03 4.91985693e+03 4.91989502e+03 4.91878857e+03 4.91931885e+03 4.92002588e+03 4.91897900e+03 4.91876611e+03 4.91897852e+03 4.91894824e+03 4.91883545e+03 4.91884180e+03 4.91888525e+03 4.91962207e+03 4.92040186e+03 4.92038086e+03 4.91938770e+03 4.91876807e+03 4.91892676e+03 4.91877881e+03 4.91967383e+03 4.92015332e+03 4.91923877e+03 4.91878418e+03 4.91878125e+03 4.91896777e+03 4.92043994e+03 4.92085791e+03 4.91908643e+03 4.91885449e+03 4.91920068e+03 4.91876367e+03 4.91913428e+03 4.91912842e+03 4.91881396e+03 4.91883789e+03 4.91891455e+03 4.91895557e+03 4.91878809e+03 4.91892773e+03 4.91909912e+03 4.91876709e+03 4.91969092e+03 4.92048584e+03 4.91927441e+03 4.91876221e+03 4.91908496e+03 4.91882031e+03 4.91887451e+03 4.91934766e+03 4.91914795e+03 4.91877197e+03 4.91876123e+03 4.91888623e+03 4.91942480e+03 4.91960059e+03 4.91881250e+03 4.91885156e+03 4.91882715e+03 4.91888916e+03 4.91980518e+03 4.91986621e+03 4.91968164e+03 4.91921338e+03 4.91883203e+03 4.91876758e+03 4.91876660e+03 4.91908936e+03 4.91972998e+03 4.91941016e+03 4.91885938e+03 4.91881885e+03 4.91880762e+03 4.91930469e+03 4.91982373e+03 4.91890430e+03 4.91970166e+03 4.92104346e+03 4.91947656e+03 4.91936865e+03 4.92104346e+03 4.91956299e+03 4.91891504e+03 4.91909424e+03 4.91934375e+03 4.92067773e+03 4.91947070e+03 4.92281641e+03 4.92262061e+03 4.92004297e+03 6.65203662e+03 9.92716016e+03 1.97379180e+04 1.98099629e+04 2.83481895e+04 8.05040469e+04 3.53341235e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.18685354e+11 1.02058058e+11 -1.29234035e+11 3.30245734e+11 3.03005984e+12 -6.07133450e+10 -1.58061560e+11 1.58207393e+04 7.38605322e+03 4.93991357e+03 4.92111035e+03 4.92506006e+03 4.92067188e+03 4.91868066e+03 4.91918506e+03 4.91910742e+03 4.91882959e+03 4.91935254e+03 4.91911719e+03 4.91886084e+03 4.92018066e+03 4.91991748e+03 4.91895312e+03 4.91880713e+03 4.91877734e+03 4.91874121e+03 4.91873096e+03 4.91869873e+03 4.91878857e+03 4.91883984e+03 4.91940820e+03 4.91892871e+03 4.91934082e+03 4.92075586e+03 4.91911963e+03 4.91889795e+03 4.91978125e+03 4.91910352e+03 4.91907812e+03 4.92094043e+03 4.92246436e+03 4.91982568e+03 4.91891553e+03 4.91887158e+03 4.91972852e+03 4.92072461e+03 4.91970703e+03 4.91943604e+03 4.91897754e+03 4.91877148e+03 4.91877344e+03 4.91884619e+03 4.92092090e+03 4.92108203e+03 4.91901611e+03 4.91932373e+03 4.91995752e+03 4.91876270e+03 4.91969922e+03 4.91973340e+03 4.91883984e+03 4.91876562e+03 4.91911719e+03 4.92157959e+03 4.92298828e+03 4.92139355e+03 4.91890723e+03 4919. 4.91897363e+03 4.91883887e+03 4.92051025e+03 4.92273340e+03 4.92415723e+03 4.92267285e+03 4.92047656e+03 4.91928076e+03 4.91894775e+03 4.91926562e+03 4.91915625e+03 4.91878223e+03 4.91950098e+03 4.91949414e+03 4.91876953e+03 4.91926025e+03 4.91907520e+03 4.91880225e+03 4.91900928e+03 4.91951123e+03 4.91899902e+03 4.91896680e+03 4.91990869e+03 4.91902979e+03 4.91881104e+03 4.91879736e+03 4.91879785e+03 4.91892676e+03 4.91879199e+03 4.91894580e+03 4.91885645e+03 4.91876465e+03 4.91888574e+03 4.91876465e+03 4.91975342e+03 4.91996973e+03 4.91878418e+03 4.92018604e+03 4.92130322e+03 4.91938037e+03 4.91880566e+03 4.91904639e+03 4.91890283e+03 4.91876416e+03 4.91877051e+03 4.91883936e+03 4.91940186e+03 4.91998926e+03 4.91906055e+03 4.91899951e+03 4.91928613e+03 4.91886816e+03 4.91876953e+03 4.91876465e+03 4.91892041e+03 4.91891895e+03 4.91893994e+03 4.92062061e+03 4.92049902e+03 4.91876709e+03 4.91898926e+03 4.91882764e+03 4.92044873e+03 4.92081250e+03 4.91897266e+03 4.91906641e+03 4.91944287e+03 4.91901709e+03 4.91888135e+03 4.91977246e+03 4.91930811e+03 4.91877930e+03 4.91940186e+03 4.91881104e+03 4.91929980e+03 4.91980811e+03 4.91928760e+03 4.91884814e+03 4.91876611e+03 4.91906934e+03 4.91933398e+03 4.91897705e+03 4.91876416e+03 4.91876660e+03 4.91904639e+03 4.91953906e+03 4.91886035e+03 4.91950977e+03 4.92188867e+03 4.92072510e+03 4.91880957e+03 4.91926465e+03 4.91917627e+03 4.91876562e+03 4.91885889e+03 4.91877637e+03 4.91875781e+03 4.91896631e+03 4.91887061e+03 4.91877930e+03 4.91882129e+03 4.91930176e+03 4.91992139e+03 4.92008105e+03 4.91896973e+03 4.91877637e+03 4.91906641e+03 4.91989355e+03 4.91928027e+03 4.91884766e+03 4.91952588e+03 4.91898633e+03 4.91877393e+03 4.91895752e+03 4.91895752e+03 4.91878906e+03 4.91876855e+03 4.91878174e+03 4.91906836e+03 4.91890918e+03 4.91877148e+03 4.91917578e+03 4.92045801e+03 4.92164893e+03 4.92278076e+03 4.92045605e+03 4.91885645e+03 4.91882178e+03 4.91881055e+03 4.91893359e+03 4.91892920e+03 4.91881494e+03 4.91961719e+03 4.92065088e+03 4.91895361e+03 4.91935352e+03 4.92103809e+03 4.92006934e+03 4.91905469e+03 4.91886621e+03 4.91890234e+03 4.91910547e+03 4.91960742e+03 4.91914600e+03 4.91878076e+03 4.91890967e+03 4.91877393e+03 4.91881641e+03 4.91894531e+03 4.91921240e+03 4.91943018e+03 4.91907373e+03 4.91883496e+03 4.91881494e+03 4.91883643e+03 4.91879053e+03 4.91915967e+03 4.91980225e+03 4.92004102e+03 4.91905957e+03 4.91879639e+03 4.91916016e+03 4.91921826e+03 4.91883057e+03 4.91897949e+03 4.91915430e+03 4.91878271e+03 4.91878857e+03 4.91878369e+03 4.91877588e+03 4.91878516e+03 4.91876660e+03 4.91877051e+03 4.91877441e+03 4.91877637e+03 4.91877197e+03 4.91876855e+03 4.91878027e+03 4.91887842e+03 4.91888916e+03 4.91881396e+03 4.91877148e+03 4.91880420e+03 4.91889160e+03 4.91882764e+03 4.91876855e+03 4.91887305e+03 4.91899365e+03 4.91889453e+03 4.91882031e+03 4.91877734e+03 4.91877832e+03 4.91877930e+03 4.91876660e+03 4.91877588e+03 4.91877441e+03 4.91877930e+03 4.91877783e+03 4.91880566e+03 4.91880859e+03 4.91881445e+03 4.91877393e+03 4.91881445e+03 4.91884375e+03 4.91898682e+03 4.91898291e+03 4.91887793e+03 4.91880664e+03 4.91877783e+03 4.91880078e+03 4.91882227e+03 4.91892822e+03 4.91888184e+03 4.91888135e+03 4.91877490e+03 4.91877393e+03 4.91876660e+03 4.91879248e+03 4.91879395e+03 4.91876709e+03 4.91877539e+03 4.91877832e+03 4.91877441e+03 4.91875684e+03 4.91877783e+03 4.91879395e+03 4.91877393e+03 4.91877051e+03 4.91877588e+03 4.91877002e+03 4.91882471e+03 4.91886963e+03 4.91879785e+03 4.91878223e+03 4.91881836e+03 4.91883105e+03 4.91883447e+03 4.91881787e+03 4.91879834e+03 4.91877441e+03 4.91877246e+03 4.91878564e+03 4.91877588e+03 4.91876807e+03 4.91876611e+03 4.91876807e+03 4.91879590e+03 4.91900879e+03 4.91894824e+03 4.91882129e+03 4.91877051e+03 4.91877930e+03 4.91877637e+03 4.91878174e+03 4.91877490e+03 4.91878711e+03 4.91880859e+03 4.91880322e+03 4.91881689e+03 4.91884863e+03 4.91889160e+03 4.91877148e+03 4.91877100e+03 4.91877539e+03 4.91877197e+03 4.91877441e+03 4.91877246e+03 4.91878271e+03 4.91878906e+03 4.91881104e+03 4.91885498e+03 4.91881006e+03 4.91878418e+03 4.91877588e+03 4.91877051e+03 4.91876611e+03 4.91882617e+03 4.91882568e+03 4.91877344e+03 4.91878027e+03 4.91878564e+03 4.91878271e+03 4.91880518e+03 4.91877393e+03 4.91877734e+03 4.91879102e+03 4.91878760e+03 4.91881299e+03 4.91882617e+03 4.91890771e+03 4.91890479e+03 4.91881641e+03 4.91877734e+03 4.91878857e+03 4.91877734e+03 4.91877637e+03 4.91877393e+03 4.91879053e+03 4.91881250e+03 4.91886133e+03 4.91883984e+03 4.91878271e+03 4.91879004e+03 4.91897949e+03 4.91953760e+03 4.91931641e+03 4.91889502e+03 4.91878564e+03 4.91879883e+03 4.91888818e+03 4.91902197e+03 4.91887598e+03 4.91877637e+03 4.91882227e+03 4.91891357e+03 4.91901123e+03 4.91893848e+03 4.91889453e+03 4.91902490e+03 4.91923145e+03 4.91924756e+03 4.91899072e+03 4.91878906e+03 4.91877197e+03 4.91881787e+03 4.91885645e+03 4.91886182e+03 4.91877686e+03 4.91878564e+03 4.91888379e+03 4.91925000e+03 4.91905615e+03 4.91883545e+03 4.91877344e+03 4.91877441e+03 4.91879053e+03 4.91877344e+03 4.91882324e+03 4.91917432e+03 4.91911865e+03 4.91886182e+03 4.91878369e+03 4.91880127e+03 4.91882764e+03 4.91896191e+03 4.91907764e+03 4.91878223e+03 4.91903174e+03 4.91917822e+03 4.91881152e+03 4.91881885e+03 4.91878955e+03 4.91877539e+03 4.91881299e+03 4.91888623e+03 4.91880957e+03 4.91877539e+03 4.91885645e+03 4.91884229e+03 4.91893848e+03 4.91876465e+03 4.91903174e+03 4.91922119e+03 4.91895020e+03 4.91877490e+03 4.91891895e+03 4.91913184e+03 4.91917432e+03 4.91888574e+03 4.91879346e+03 4.91877539e+03 4.91876904e+03 4.91877441e+03 4.91878418e+03 4.91880127e+03 4.91879932e+03 4.91880371e+03 4.91881104e+03 4.91916748e+03 4.92208301e+03 4.92779541e+03 4.92731445e+03 4.92741504e+03 4.92596729e+03 4.93792871e+03 4.92344189e+03 4.92056982e+03 4.92666895e+03 6.27568604e+03 6.05897021e+03 8.68945703e+03 9.86463672e+03 2.03285742e+04 3.41800586e+04 7.64992734e+04 6.75832218e+10 5.04543232e+10 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. 0. 0. 0. 0. 0. 0. -1.27275851e+13 -1.27275851e+13 2.08604021e+11 3.26731039e+11 2.61742608e+11 1.09604389e+11 6.23699727e+04 1.33261533e+04 6.77702588e+03 4.94793115e+03 4.93511719e+03 4.92054199e+03 4.91922754e+03 4.91894629e+03 4.91893555e+03 4.91894287e+03 4.91895850e+03 4.91896582e+03 4.91873682e+03 4.92013184e+03 4.92267871e+03 4.92123633e+03 4.91993164e+03 4.91875391e+03 4.91991162e+03 4.92274756e+03 4.92202734e+03 4.92100879e+03 4.92224756e+03 4.92592236e+03 4.92131836e+03 4.92306885e+03 4.92206445e+03 4.92072900e+03 4.91884424e+03 4.91873340e+03 4.91877686e+03 4.91885107e+03 4.91898584e+03 4.91915283e+03 4.91921875e+03 4.91909180e+03 4.91891162e+03 4.91887939e+03 4.91887598e+03 4.91894727e+03 4.91901660e+03 4.91914111e+03 4.91904199e+03 4.91879932e+03 4.91883887e+03 4.91890771e+03 4.91881738e+03 4.91876270e+03 4.91876855e+03 4.91882324e+03 4.91881641e+03 4.91878955e+03 4.91878223e+03 4.91881055e+03 4.91886328e+03 4.91886621e+03 4.91897998e+03 4.91882910e+03 4.91878369e+03 4.91877637e+03 4.91877930e+03 4.91878955e+03 4.91880469e+03 4.91877832e+03 4.91877148e+03 4.91877148e+03 4.91877637e+03 4.91887646e+03 4.91895508e+03 4.91890723e+03 4.91878662e+03 4.91876855e+03 4.91877051e+03 4.91880566e+03 4.91905908e+03 4.91895557e+03 4.91885547e+03 4.91877686e+03 4.91919580e+03 4.91983887e+03 4.91975098e+03 4.91920703e+03 4.91894482e+03 4.91902441e+03 4.91905420e+03 4.91896338e+03 4.91902002e+03 4.91928125e+03 4.91973584e+03 4.91954736e+03 4.91897314e+03 4.91877197e+03 4.91879199e+03 4.91877197e+03 4.91877441e+03 4.91879492e+03 4.91878027e+03 4.91891113e+03 4.91881787e+03 4.91880957e+03 4.91886621e+03 4.91877979e+03 4.91881836e+03 4.91881982e+03 4.91908496e+03 4.91903125e+03 4.91876221e+03 4.91891357e+03 4.91891895e+03 4.91887891e+03 4.91883594e+03 4.91882520e+03 4.91877637e+03 4.91876709e+03 4.91877637e+03 4.91878174e+03 4.91877393e+03 4.91878271e+03 4.91877686e+03 4.91879883e+03 4.91878711e+03 4.91877148e+03 4.91876172e+03 4.91889160e+03 4.91922754e+03 4.91915332e+03 4.91884814e+03 4.91877490e+03 4.91893262e+03 4.91942578e+03 4.91943408e+03 4.91903760e+03 4.91880908e+03 4.91879639e+03 4.91878809e+03 4.91877881e+03 4.91877979e+03 4.91878516e+03 4.91879492e+03 4.91878076e+03 4.91880566e+03 4.91879199e+03 4.91878271e+03 4.91877783e+03 4.91876660e+03 4.91876465e+03 4.91876953e+03 4.91882959e+03 4.91910303e+03 4.91965088e+03 4.91958447e+03 4.91918945e+03 4.91883594e+03 4.91904004e+03 4.91946191e+03 4.91944141e+03 4.91892529e+03 4.91877539e+03 4.91877148e+03 4.91878271e+03 4.91881982e+03 4.91880469e+03 4.91880469e+03 4.91878516e+03 4.91877344e+03 4.91876855e+03 4.91882471e+03 4.91909424e+03 4.91906836e+03 4.91889111e+03 4.91877393e+03 4.91877246e+03 4.91877002e+03 4.91885059e+03 4.91913184e+03 4.91909375e+03 4.91889160e+03 4.91879248e+03 4.91879541e+03 4.91876953e+03 4.91882227e+03 4.91918115e+03 4.91936572e+03 4.91904248e+03 4.91879834e+03 4.91878711e+03 4.91880029e+03 4.91878809e+03 4.91878613e+03 4.91880371e+03 4.91880615e+03 4.91906689e+03 4.91960645e+03 4.91958691e+03 4.91907373e+03 4.91881348e+03 4.91886621e+03 4.91886865e+03 4.91911914e+03 4.91947412e+03 4.91938037e+03 4.91887109e+03 4.91876514e+03 4.91877441e+03 4.91880566e+03 4.91882520e+03 4.91877246e+03 4.91876660e+03 4.91877539e+03 4.91877344e+03 4.91877197e+03 4.91877881e+03 4.91878125e+03 4.91877832e+03 4.91882422e+03 4.91888477e+03 4.91894385e+03 4.91891309e+03 4.91886426e+03 4.91885840e+03 4.91886719e+03 4.91886377e+03 4.91883008e+03 4.91880469e+03 4.91885205e+03 4.91882129e+03 4.91880273e+03 4.91880566e+03 4.91890088e+03 4.91891895e+03 4.91881396e+03 4.91877246e+03 4.91877100e+03 4.91880859e+03 4.91878271e+03 4.91877393e+03 4.91876367e+03 4.91876562e+03 4.91876660e+03 4.91879932e+03 4.91895264e+03 4.91882227e+03 4.91882520e+03 4.91904639e+03 4.91893115e+03 4.91879102e+03 4.91877246e+03 4.91879541e+03 4.91881348e+03 4.91887939e+03 4.91889355e+03 4.91886182e+03 4.91881250e+03 4.91877344e+03 4.91876318e+03 4.91876172e+03 4.91876660e+03 4.91878027e+03 4.91879443e+03 4.91879590e+03 4.91879590e+03 4.91879199e+03 4.91877734e+03 4.91876953e+03 4.91877246e+03 4.91877539e+03 4.91892920e+03 4.91933740e+03 4.91929297e+03 4.91897217e+03 4.91879199e+03 4.91878223e+03 4.91877246e+03 4.91879834e+03 4.91891895e+03 4.91904932e+03 4.91913818e+03 4.91889893e+03 4.91878076e+03 4.91878711e+03 4.91876562e+03 4.91877686e+03 4.91878174e+03 4.91876416e+03 4.91877344e+03 4.91877539e+03 4.91876807e+03 4.91878857e+03 4.91884033e+03 4.91884717e+03 4.91884229e+03 4.91908008e+03 4.91948486e+03 4.91929785e+03 4.91887207e+03 4.91877539e+03 4.91880859e+03 4.91890430e+03 4.91887549e+03 4.91882812e+03 4.91894775e+03 4.91933496e+03 4.91929297e+03 4.91887402e+03 4.91877539e+03 4.91877051e+03 4.91881152e+03 4.91880566e+03 4.91876367e+03 4.91877002e+03 4.91877051e+03 4.91880273e+03 4.91876904e+03 4.91878223e+03 4.91879150e+03 4.91877441e+03 4.91876416e+03 4.91879199e+03 4.91878662e+03 4.91896826e+03 4.91899268e+03 4.91906836e+03 4.91932520e+03 4.91991699e+03 4.91996777e+03 4.91955615e+03 4.91965479e+03 4.91928320e+03 4.91923438e+03 4.91891113e+03 4.91876660e+03 4.91887451e+03 4.91900781e+03 4.91889355e+03 4.91884570e+03 4.91879688e+03 4.91880078e+03 4.91878906e+03 4.91880762e+03 4.91883887e+03 4.91877246e+03 4.91898193e+03 4.91920898e+03 4.91907031e+03 4.91882812e+03 4.91879639e+03 4.91877490e+03 4.91877295e+03 4.91877637e+03 4.91879297e+03 4.91886279e+03 4.91889160e+03 4.91903662e+03 4.91936963e+03 4.91902539e+03 4.91881641e+03 4.91877783e+03 4.91900342e+03 4.91910449e+03 4.91893604e+03 4.91876904e+03 4.91889307e+03 4.91920410e+03 4.91939990e+03 4.91902979e+03 4.91881836e+03 4.91903369e+03 4.91945117e+03 4.91930859e+03 4.91883545e+03 4.91877637e+03 4.91881689e+03 4.91894629e+03 4.91879492e+03 4.91885742e+03 4.91877295e+03 4.91907129e+03 4.91941748e+03 4.91907178e+03 4.91891699e+03 4.91897559e+03 4.91934814e+03 4.91981445e+03 4.91954297e+03 4.91887402e+03 4.91877148e+03 4.91876953e+03 4.91877881e+03 4.91877783e+03 4.91877637e+03 4.91877734e+03 4.91881738e+03 4.91894336e+03 4.91894238e+03 4.91880566e+03 4.91877979e+03 4.91878711e+03 4.91881934e+03 4.91896533e+03 4.91893408e+03 4.91884717e+03 4.91877637e+03 4.91879639e+03 4.91878125e+03 4.91876465e+03 4.91879932e+03 4.91881006e+03 4.91892090e+03 4.91949658e+03 4.91895312e+03 4.91888135e+03 4.91892725e+03 4.91883887e+03 4.91901270e+03 4.91877002e+03 4.91876172e+03 4.91882422e+03 4.91890625e+03 4.91883154e+03 4.91876367e+03 4.91879590e+03 4.91887402e+03 4.91898389e+03 4.91884521e+03 4.91877979e+03 4.91877246e+03 4.91877002e+03 4.91888232e+03 4.91904541e+03 4.91904736e+03 4.91883154e+03 4.91883057e+03 4.91964307e+03 4.92036621e+03 4.91994482e+03 4.91898145e+03 4.91894971e+03 4.91914746e+03 4.91889258e+03 4.91880127e+03 4.91887939e+03 4.91877539e+03 4.91888916e+03 4.91882324e+03 4.91878076e+03 4.91884277e+03 4.91890430e+03 4.91895117e+03 4.91886084e+03 4.91877979e+03 4.91878906e+03 4.91881348e+03 4.91877441e+03 4.91877637e+03 4.91885645e+03 4.91890918e+03 4.91896191e+03 4.91914209e+03 4.91915869e+03 4.91887500e+03 4.91877148e+03 4.91878418e+03 4.91896484e+03 4.91906396e+03 4.91899414e+03 4.91924023e+03 4.92030273e+03 4.92120508e+03 4.92057031e+03 4.91921533e+03 4.91898975e+03 4.91911328e+03 4.91919971e+03 4.91892676e+03 4.91877832e+03 4.91877881e+03 4.91877490e+03 4.91877197e+03 4.91879004e+03 4.91880225e+03 4.91877393e+03 4.91877686e+03 4.91893799e+03 4.91921533e+03 4.91895557e+03 4.91877979e+03 4.91896582e+03 4.91923633e+03 4.91888916e+03 4.91885400e+03 4.91929102e+03 4.91911719e+03 4.91905518e+03 4.91889697e+03 4.91890479e+03 4.91886768e+03 4.91889160e+03 4.91880322e+03 4.91878125e+03 4.91877393e+03 4.91888184e+03 4.91880713e+03 4.91907666e+03 4.91979590e+03 4.92000635e+03 4.91955469e+03 4.91917871e+03 4.91884033e+03 4.91875684e+03 4.91875684e+03 4.91877100e+03 4.91876953e+03 4.91876953e+03 4.91877588e+03 4.91877344e+03 4.91877490e+03 4.91877393e+03 4.91876904e+03 4.91877881e+03 4.91878467e+03 4.91898242e+03 4.91946289e+03 4.91942773e+03 4.91899316e+03 4.91882373e+03 4.91883154e+03 4.91881445e+03 4.91881641e+03 4.91879492e+03 4.91883301e+03 4.91883545e+03 4.91902783e+03 4.91943018e+03 4.91922852e+03 4.91885205e+03 4.91880420e+03 4.91947900e+03 4.92044727e+03 4.91982520e+03 4.91891895e+03 4.91888477e+03 4.91912598e+03 4.91911621e+03 4.91885400e+03 4.91876758e+03 4.91886084e+03 4.91912451e+03 4.91959961e+03 4.91973633e+03 4.91917969e+03 4.91885547e+03 4.91887305e+03 4.91980566e+03 4.92050293e+03 4.91952979e+03 4.91882617e+03 4.91890430e+03 4.91947949e+03 4.91967578e+03 4.91923291e+03 4.91891064e+03 4.91911670e+03 4.91946240e+03 4.91964697e+03 4.91925342e+03 4.91896631e+03 4.91885352e+03 4.91919824e+03 4.91982568e+03 4.91989014e+03 4.91938525e+03 4.91883350e+03 4.91904590e+03 4.91936670e+03 4.91958398e+03 4.91917773e+03 4.91911279e+03 4.91959473e+03 4.91946582e+03 4.91899707e+03 4.91876904e+03 4.91877979e+03 4.91879004e+03 4.91881152e+03 4.91910303e+03 4.91935107e+03 4.91908398e+03 4.91885059e+03 4.91881299e+03 4.91882764e+03 4.91925293e+03 4.92522656e+03 4.93642188e+03 4.94844629e+03 4.94113477e+03 6.55992725e+03 9.69211133e+03 1.02404980e+04 8.74836523e+03 9.12448242e+03 1.98777988e+04 2.00338359e+04 2.99241875e+04 6.04981055e+04 2.21669724e+10 4.60260045e+09 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. 0. 1.18105416e+10 2.52394680e+10 2.42431345e+10 6.65997422e+04 1.44411143e+04 7.10987451e+03 4.99547998e+03 4.95160205e+03 4.93276904e+03 4.93302344e+03 4.93318408e+03 4.93272266e+03 4.93271777e+03 4.93275098e+03 4.93276611e+03 4.93347168e+03 4.93459863e+03 4.93320361e+03 4.93322510e+03 4.93441260e+03 4.93347363e+03 4.93278662e+03 4.93292090e+03 4.93276611e+03 4.93273291e+03 4.93276953e+03 4.93304053e+03 4.93281055e+03 4.93285693e+03 4.93309033e+03 4.93286084e+03 4.93285303e+03 4.93298145e+03 4.93276367e+03 4.93330127e+03 4.93381494e+03 4.93317578e+03 4.93314648e+03 4.93387695e+03 4.93347998e+03 4.93280713e+03 4.93327441e+03 4.93276025e+03 4.93481836e+03 4.93609033e+03 4.93411768e+03 4.93291113e+03 4.93278809e+03 4.93278174e+03 4.93277881e+03 4.93280859e+03 4.93280127e+03 4.93280713e+03 4.93396094e+03 4.93569580e+03 4.93480225e+03 4.93303369e+03 4.93277979e+03 4.93287256e+03 4.93356592e+03 4.93414160e+03 4.93315430e+03 4.93295068e+03 4.93324365e+03 4.93303564e+03 4.93283057e+03 4.93336230e+03 4.93321338e+03 4.93287305e+03 4.93318457e+03 4.93295459e+03 4.93297510e+03 4.93281396e+03 4.93292969e+03 4.93281885e+03 4.93287598e+03 4.93312061e+03 4.93277197e+03 4.93330371e+03 4.93412891e+03 4.93353174e+03 4.93283105e+03 4.93317041e+03 4.93296240e+03 4.93276660e+03 4.93282471e+03 4.93315674e+03 4.93299268e+03 4.93278760e+03 4.93293555e+03 4.93285645e+03 4.93385498e+03 4.93396143e+03 4.93279102e+03 4.93306494e+03 4.93321143e+03 4.93281299e+03 4.93278613e+03 4.93279395e+03 4.93292676e+03 4.93413135e+03 4.93506982e+03 4.93339746e+03 4.93286768e+03 4.93363916e+03 4.93319922e+03 4.93280322e+03 4.93334961e+03 4.93423975e+03 4.93405957e+03 4.93382373e+03 4.93391797e+03 4.93347314e+03 4.93277051e+03 4.93310596e+03 4.93284229e+03 4.93351465e+03 4.93458887e+03 4.93364551e+03 4.93277490e+03 4.93323291e+03 4.93287012e+03 4.93286328e+03 4.93291064e+03 4.93289795e+03 4.93339551e+03 4.93543896e+03 4.93519189e+03 4.93333350e+03 4.93278076e+03 4.93279443e+03 4.93302588e+03 4.93362549e+03 4.93375146e+03 4.93320361e+03 4.93281592e+03 4.93277002e+03 4.93314062e+03 4.93349170e+03 4.93300879e+03 4.93275684e+03 4.93279834e+03 4.93280859e+03 4.93282715e+03 4.93277832e+03 4.93279150e+03 4.93284131e+03 4.93316455e+03 4.93316504e+03 4.93283105e+03 4.93278516e+03 4.93292871e+03 4.93322461e+03 4.93283643e+03 4.93356494e+03 4.93492969e+03 4.93327539e+03 4.93291309e+03 4.93304541e+03 4.93275928e+03 4.93286230e+03 4.93283887e+03 4.93285547e+03 4.93313428e+03 4.93410596e+03 4.93473242e+03 4.93406982e+03 4.93291504e+03 4.93281592e+03 4.93281152e+03 4.93305713e+03 4.93293896e+03 4.93282568e+03 4.93277881e+03 4.93384131e+03 4.93389844e+03 4.93331348e+03 4.93288330e+03 4.93325488e+03 4.93570459e+03 4.93768213e+03 4.93560205e+03 4.93304834e+03 4.93279395e+03 4.93280127e+03 4.93280957e+03 4.93287842e+03 4.93279150e+03 4.93308398e+03 4.93466016e+03 4.93421973e+03 4.93310596e+03 4.93316602e+03 4.93372510e+03 4.93331055e+03 4.93275195e+03 4.93311133e+03 4.93315039e+03 4.93343701e+03 4.93403857e+03 4.93363135e+03 4.93287598e+03 4.93302637e+03 4.93277148e+03 4.93379102e+03 4.93542090e+03 4.93364844e+03 4.93287402e+03 4.93327490e+03 4.93278174e+03 4.93297363e+03 4.93279883e+03 4.93292627e+03 4.93282129e+03 4.93299707e+03 4.93336475e+03 4.93283789e+03 4.93341895e+03 4.93371094e+03 4.93305469e+03 4.93278760e+03 4.93281299e+03 4.93290674e+03 4.93281396e+03 4.93279980e+03 4.93281445e+03 4.93318994e+03 4.93332568e+03 4.93316553e+03 4.93278613e+03 4.93278711e+03 4.93279736e+03 4.93281494e+03 4.93280127e+03 4.93284814e+03 4.93282227e+03 4.93305615e+03 4.93343164e+03 4.93302197e+03 4.93302100e+03 4.93383984e+03 4.93363867e+03 4.93286963e+03 4.93352246e+03 4.93374316e+03 4.93302539e+03 4.93284863e+03 4.93306250e+03 4.93304736e+03 4.93280225e+03 4.93281104e+03 4.93286768e+03 4.93307471e+03 4.93275195e+03 4.93361963e+03 4.93342090e+03 4.93288037e+03 4.93282373e+03 4.93284424e+03 4.93355518e+03 4.93287646e+03 4.93279443e+03 4.93303564e+03 4.93281543e+03 4.93300537e+03 4.93334277e+03 4.93383203e+03 4.93302051e+03 4.93287256e+03 4.93279297e+03 4.93298828e+03 4.93304492e+03 4.93303076e+03 4.93314209e+03 4.93352002e+03 4.93395312e+03 4.93295361e+03 4.93283838e+03 4.93280420e+03 4.93302100e+03 4.93295508e+03 4.93281885e+03 4.93281396e+03 4.93288623e+03 4.93283887e+03 4.93285400e+03 4.93290186e+03 4.93314258e+03 4.93330371e+03 4.93321338e+03 4.93294678e+03 4.93287109e+03 4.93300830e+03 4.93333691e+03 4.93309424e+03 4.93296973e+03 4.93321436e+03 4.93296777e+03 4.93282275e+03 4.93278027e+03 4.93283008e+03 4.93371484e+03 4.93447998e+03 4.93364355e+03 4.93279248e+03 4.93289893e+03 4.93278369e+03 4.93310938e+03 4.93318115e+03 4.93282959e+03 4.93277686e+03 4.93281689e+03 4.93304980e+03 4.93335938e+03 4.93334814e+03 4.93286670e+03 4.93280225e+03 4.93307568e+03 4.93369775e+03 4.93321191e+03 4.93278125e+03 4.93284326e+03 4.93308643e+03 4.93312451e+03 4.93281104e+03 4.93287891e+03 4.93358936e+03 4.93410352e+03 4.93357812e+03 4.93281934e+03 4.93282471e+03 4.93291113e+03 4.93321240e+03 4.93300049e+03 4.93284863e+03 4.93286377e+03 4.93288916e+03 4.93327393e+03 4.93351025e+03 4.93352148e+03 4.93299609e+03 4.93296094e+03 4.93316309e+03 4.93369189e+03 4.93321777e+03 4.93278809e+03 4.93278125e+03 4.93279102e+03 4.93284521e+03 4.93335254e+03 4.93318750e+03 4.93280225e+03 4.93280859e+03 4.93286035e+03 4.93334570e+03 4.93282666e+03 4.93279395e+03 4.93296729e+03 4.93334424e+03 4.93364600e+03 4.93308984e+03 4.93290771e+03 4.93315283e+03 4.93283154e+03 4.93327832e+03 4.93287500e+03 4.93301172e+03 4.93376074e+03 4.93297266e+03 4.93277490e+03 4.93278271e+03 4.93291650e+03 4.93334131e+03 4.93396729e+03 4.93559424e+03 4.93508691e+03 4.93363770e+03 4.93338428e+03 4.93381104e+03 4.93470947e+03 4.93313916e+03 4.93283545e+03 4.93281299e+03 4.93277100e+03 4.93286084e+03 4.93314209e+03 4.93545215e+03 4.93610059e+03 4.93376758e+03 4.93302197e+03 4.93332129e+03 4.93293652e+03 4.93475488e+03 4.93478613e+03 4.93316357e+03 4.93282959e+03 4.93297900e+03 4.93411133e+03 4.93504834e+03 4.93404492e+03 4.93282324e+03 4.93282861e+03 4.93286426e+03 4.93370801e+03 4.93592920e+03 4.93581592e+03 4.93498242e+03 4.93303174e+03 4.93304834e+03 4.93356152e+03 4.93282959e+03 4.93375537e+03 4.93569824e+03 4.93388135e+03 4.93281396e+03 4.93277393e+03 4.93411230e+03 4.93706982e+03 4.93573730e+03 4.93319580e+03 4.93290869e+03 4.93292529e+03 4.93289893e+03 4.93354004e+03 4.93460303e+03 4.93323047e+03 4.93291992e+03 4.93278662e+03 4.93301221e+03 4.93348096e+03 4.93294189e+03 4.93283154e+03 4.93334375e+03 4.93339258e+03 4.93302588e+03 4.93277734e+03 4.93380127e+03 4.93434473e+03 4.93318848e+03 4.93331348e+03 4.93475781e+03 4.93344873e+03 4.93300439e+03 4.93441553e+03 4.93361963e+03 4.93288525e+03 4.93285498e+03 4.93342969e+03 4.93388623e+03 4.93394092e+03 4.93299170e+03 4.93280127e+03 4.93305957e+03 4.93309766e+03 4.93289551e+03 4.93279297e+03 4.93323877e+03 4.93321631e+03 4.93284570e+03 4.93294678e+03 4.93295117e+03 4.93282129e+03 4.93361426e+03 4.93322363e+03 4.93281787e+03 4.93294678e+03 4.93277783e+03 4.93367920e+03 4.93360303e+03 4.93290869e+03 4.93314258e+03 4.93306885e+03 4.93279688e+03 4.93323730e+03 4.93402197e+03 4.93293945e+03 4.93279639e+03 4.93289941e+03 4.93285840e+03 4.93286768e+03 4.93283350e+03 4.93280176e+03 4.93284229e+03 4.93316016e+03 4.93319238e+03 4.93277539e+03 4.93351172e+03 4.93449316e+03 4.93347852e+03 4.93299756e+03 4.93477100e+03 4.93442139e+03 4.93276123e+03 4.93380078e+03 4.93486230e+03 4.93316016e+03 4.93287207e+03 4.93308252e+03 4.93274609e+03 4.93344678e+03 4.93314551e+03 4.93280811e+03 4.93302344e+03 4.93309277e+03 4.93293311e+03 4.93277246e+03 4.93322803e+03 4.93312744e+03 4.93284473e+03 4.93364893e+03 4.93387549e+03 4.93288867e+03 4.93306396e+03 4.93294727e+03 4.93297607e+03 4.93350635e+03 4.93303711e+03 4.93279541e+03 4.93280664e+03 4.93287891e+03 4.93279199e+03 4.93282617e+03 4.93279541e+03 4.93279395e+03 4.93299268e+03 4.93281250e+03 4.93291699e+03 4.93348291e+03 4.93399170e+03 4.93332178e+03 4.93287207e+03 4.93297949e+03 4.93321143e+03 4.93288477e+03 4.93302881e+03 4.93307129e+03 4.93278662e+03 4.93362256e+03 4.93336182e+03 4.93288477e+03 4.93307715e+03 4.93325977e+03 4.93294482e+03 4.93277393e+03 4.93287500e+03 4.93291650e+03 4.93350146e+03 4.93477295e+03 4.93440381e+03 4.93311377e+03 4.93315918e+03 4.93348193e+03 4.93505127e+03 4.93515527e+03 4.93457373e+03 4.93347119e+03 4.93279639e+03 4.93295654e+03 4.93282959e+03 4.93322168e+03 4.93370996e+03 4.93286768e+03 4.93297266e+03 4.93311328e+03 4.93301611e+03 4.93386572e+03 4.93348242e+03 4.93277148e+03 4.93323877e+03 4.93340039e+03 4.93282764e+03 4.93342725e+03 4.93379785e+03 4.93361426e+03 4.93315820e+03 4.93287305e+03 4.93284375e+03 4.93284619e+03 4.93280859e+03 4.93288477e+03 4.93276953e+03 4.93319727e+03 4.93396875e+03 4.93310791e+03 4.93294971e+03 4.93336670e+03 4.93282617e+03 4.93325391e+03 4.93351270e+03 4.93293994e+03 4.93312695e+03 4.93320605e+03 4.93280127e+03 4.93279785e+03 4.93286426e+03 4.93293115e+03 4.93302881e+03 4.93298242e+03 4.93279736e+03 4.93293457e+03 4.93280420e+03 4.93284619e+03 4.93335791e+03 4.93442188e+03 4.93404639e+03 4.93342578e+03 4.93287451e+03 4.93288379e+03 4.93409961e+03 4.93693848e+03 4.93870459e+03 4.93891016e+03 4.98370166e+03 6.88331494e+03 6.29185498e+03 8.86658398e+03 1.07058906e+04 1.97379180e+04 1.98099629e+04 2.83481895e+04 8.05040469e+04 3.53341235e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.87658865e+10 -1.49587927e+10 2.34069996e+10 -6.16506819e+10 6.36410742e+04 1.28326953e+04 6.62643799e+03 4.94219727e+03 4.94042676e+03 4.93443799e+03 4.93356934e+03 4.93338574e+03 4.93295654e+03 4.93288135e+03 4.93301416e+03 4.93281152e+03 4.93325195e+03 4.93306641e+03 4.93282959e+03 4.93371289e+03 4.93397803e+03 4.93293506e+03 4.93331396e+03 4.93363379e+03 4.93276660e+03 4.93332812e+03 4.93343066e+03 4.93281250e+03 4.93277881e+03 4.93300342e+03 4.93318994e+03 4.93290332e+03 4.93286133e+03 4.93283154e+03 4.93291016e+03 4.93317725e+03 4.93320703e+03 4.93275439e+03 4.93371045e+03 4.93381201e+03 4.93291797e+03 4.93291553e+03 4.93286133e+03 4.93295361e+03 4.93402979e+03 4.93394678e+03 4.93283008e+03 4.93402344e+03 4.93376953e+03 4.93278955e+03 4.93326172e+03 4.93335693e+03 4.93281592e+03 4.93281592e+03 4.93291650e+03 4.93296289e+03 4.93285449e+03 4.93278711e+03 4.93351660e+03 4.93311035e+03 4.93281104e+03 4.93288428e+03 4.93279395e+03 4.93384521e+03 4.93380225e+03 4.93314209e+03 4.93281592e+03 4.93290234e+03 4.93287598e+03 4.93430762e+03 4.93658301e+03 4.93541064e+03 4.93317920e+03 4.93282227e+03 4.93343750e+03 4.93468213e+03 4.93466699e+03 4.93290723e+03 4.93277832e+03 4.93280225e+03 4.93314795e+03 4.93318262e+03 4.93315576e+03 4.93359229e+03 4.93304785e+03 4.93283203e+03 4.93294531e+03 4.93286816e+03 4.93457861e+03 4.93530176e+03 4.93452588e+03 4.93302881e+03 4.93280371e+03 4.93281445e+03 4.93300732e+03 4.93342676e+03 4.93347705e+03 4.93285449e+03 4.93309717e+03 4.93279150e+03 4.93349707e+03 4.93356641e+03 4.93282373e+03 4.93301367e+03 4.93298535e+03 4.93286182e+03 4.93282861e+03 4.93282666e+03 4.93372070e+03 4.93370703e+03 4.93287842e+03 4.93285156e+03 4.93282959e+03 4.93298193e+03 4.93314307e+03 4.93283838e+03 4.93287646e+03 4.93326758e+03 4.93305273e+03 4.93284717e+03 4.93362744e+03 4.93393506e+03 4.93282812e+03 4.93300830e+03 4.93281934e+03 4.93288330e+03 4.93296826e+03 4.93280518e+03 4.93278955e+03 4.93280029e+03 4.93283936e+03 4.93290918e+03 4.93280225e+03 4.93322363e+03 4.93306494e+03 4.93282031e+03 4.93315137e+03 4.93296826e+03 4.93280957e+03 4.93281934e+03 4.93295703e+03 4.93322266e+03 4.93373047e+03 4.93306543e+03 4.93277393e+03 4.93315088e+03 4.93312451e+03 4.93283691e+03 4.93285889e+03 4.93281396e+03 4.93280615e+03 4.93281348e+03 4.93312012e+03 4.93356738e+03 4.93401807e+03 4.93400342e+03 4.93336670e+03 4.93285449e+03 4.93297266e+03 4.93332129e+03 4.93308887e+03 4.93277832e+03 4.93274414e+03 4.93313770e+03 4.93413867e+03 4.93366846e+03 4.93279590e+03 4.93327588e+03 4.93310742e+03 4.93283301e+03 4.93330469e+03 4.93320410e+03 4.93277051e+03 4.93277393e+03 4.93280176e+03 4.93278760e+03 4.93287939e+03 4.93289941e+03 4.93288379e+03 4.93282959e+03 4.93362549e+03 4.93353467e+03 4.93329932e+03 4.93278369e+03 4.93280127e+03 4.93292773e+03 4.93288086e+03 4.93280029e+03 4.93318457e+03 4.93410693e+03 4.93354980e+03 4.93281836e+03 4.93329297e+03 4.93332715e+03 4.93280078e+03 4.93276074e+03 4.93279248e+03 4.93294336e+03 4.93284717e+03 4.93276562e+03 4.93319971e+03 4.93394873e+03 4.93402295e+03 4.93520703e+03 4.93427686e+03 4.93301123e+03 4.93279883e+03 4.93275732e+03 4.93311328e+03 4.93316846e+03 4.93276367e+03 4.93303760e+03 4.93414014e+03 4.93334082e+03 4.93274170e+03 4.93392822e+03 4.93348926e+03 4.93278027e+03 4.93285596e+03 4.93274561e+03 4.93281348e+03 4.93285010e+03 4.93277490e+03 4.93288916e+03 4.93302783e+03 4.93304248e+03 4.93280078e+03 4.93274316e+03 4.93337549e+03 4.93369727e+03 4.93335938e+03 4.93290283e+03 4.93279443e+03 4.93278613e+03 4.93280811e+03 4.93312842e+03 4.93321680e+03 4.93296143e+03 4.93278564e+03 4.93281885e+03 4.93285693e+03 4.93284863e+03 4.93280957e+03 4.93281641e+03 4.93278125e+03 4.93277979e+03 4.93286230e+03 4.93286182e+03 4.93279004e+03 4.93277930e+03 4.93275586e+03 4.93284766e+03 4.93281201e+03 4.93281299e+03 4.93277246e+03 4.93277197e+03 4.93278271e+03 4.93281299e+03 4.93281885e+03 4.93277295e+03 4.93279492e+03 4.93276855e+03 4.93280371e+03 4.93283594e+03 4.93277441e+03 4.93277588e+03 4.93279736e+03 4.93276562e+03 4.93279541e+03 4.93278564e+03 4.93279199e+03 4.93277002e+03 4.93279004e+03 4.93290576e+03 4.93289990e+03 4.93284229e+03 4.93282812e+03 4.93284180e+03 4.93282715e+03 4.93281152e+03 4.93285254e+03 4.93283105e+03 4.93282471e+03 4.93278320e+03 4.93282910e+03 4.93280957e+03 4.93282568e+03 4.93277637e+03 4.93278467e+03 4.93278271e+03 4.93285254e+03 4.93286328e+03 4.93287012e+03 4.93280664e+03 4.93283984e+03 4.93294482e+03 4.93290186e+03 4.93276318e+03 4.93276318e+03 4.93279346e+03 4.93278076e+03 4.93281104e+03 4.93277832e+03 4.93275732e+03 4.93276807e+03 4.93277539e+03 4.93279980e+03 4.93283984e+03 4.93281299e+03 4.93280469e+03 4.93276562e+03 4.93281494e+03 4.93278906e+03 4.93280469e+03 4.93282373e+03 4.93281934e+03 4.93277002e+03 4.93279639e+03 4.93286768e+03 4.93312256e+03 4.93329150e+03 4.93326660e+03 4.93290039e+03 4.93279150e+03 4.93274609e+03 4.93276709e+03 4.93277002e+03 4.93281982e+03 4.93303613e+03 4.93306836e+03 4.93282520e+03 4.93280615e+03 4.93278760e+03 4.93278418e+03 4.93280469e+03 4.93281836e+03 4.93282812e+03 4.93279150e+03 4.93279346e+03 4.93278223e+03 4.93279004e+03 4.93279053e+03 4.93281445e+03 4.93284229e+03 4.93299561e+03 4.93310840e+03 4.93298389e+03 4.93285400e+03 4.93286328e+03 4.93289160e+03 4.93279297e+03 4.93275684e+03 4.93277246e+03 4.93283838e+03 4.93300537e+03 4.93313379e+03 4.93289746e+03 4.93276367e+03 4.93276465e+03 4.93275977e+03 4.93291162e+03 4.93335791e+03 4.93299121e+03 4.93278320e+03 4.93279346e+03 4.93273291e+03 4.93277490e+03 4.93280469e+03 4.93300439e+03 4.93313525e+03 4.93301562e+03 4.93282617e+03 4.93275684e+03 4.93275146e+03 4.93279004e+03 4.93281006e+03 4.93300537e+03 4.93306592e+03 4.93283496e+03 4.93276611e+03 4.93276172e+03 4.93277539e+03 4.93280664e+03 4.93285352e+03 4.93285840e+03 4.93282275e+03 4.93278369e+03 4.93278027e+03 4.93279443e+03 4.93277344e+03 4.93273535e+03 4.93272852e+03 4.93274170e+03 4.93280078e+03 4.93275439e+03 4.93282568e+03 4.93276123e+03 4.93287500e+03 4.93299463e+03 4.93286377e+03 4.93275928e+03 4.93277979e+03 4.93274365e+03 4.93285938e+03 4.93291699e+03 4.93304248e+03 4.93295117e+03 4.93289209e+03 4.93279932e+03 4.93277100e+03 4.93277100e+03 4.93276611e+03 4.93276318e+03 4.93276660e+03 4.93276416e+03 4.93274902e+03 4.93283350e+03 4.93302490e+03 4.93317432e+03 4.93290381e+03 4.93275488e+03 4.93276074e+03 4.93276611e+03 4.93277002e+03 4.93275879e+03 4.93275293e+03 4.93274219e+03 4.93285107e+03 4.93319434e+03 4.93317969e+03 4.93291016e+03 4.93278516e+03 4.93280273e+03 4.93283447e+03 4.93285059e+03 4.93277490e+03 4.93278369e+03 4.93298828e+03 4.93347314e+03 4.93353809e+03 4.93291797e+03 4.93277588e+03 4.93282227e+03 4.93283301e+03 4.93333350e+03 4.93756689e+03 4.93465088e+03 4.94556592e+03 4.93569775e+03 6.51963135e+03 9.53584766e+03 1.97326484e+04 1.97325625e+04 1.97354688e+04 1.97317285e+04 1.97385137e+04 1.97711445e+04 2.03285742e+04 3.41800586e+04 7.64992734e+04 6.75832218e+10 5.04543232e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.72407450e+10 -4.73135800e+10 4.76225659e+10 1.56590225e+04 7.57351123e+03 5.01134277e+03 4.98577734e+03 4.96179688e+03 4.93677393e+03 4.93347510e+03 4.93339990e+03 4.93292578e+03 4.93277295e+03 4.93279248e+03 4.93281445e+03 4.93284131e+03 4.93285254e+03 4.93307715e+03 4.93328809e+03 4.93298779e+03 4.93275732e+03 4.93278027e+03 4.93280566e+03 4.93290234e+03 4.93278809e+03 4.93278027e+03 4.93282666e+03 4.93292188e+03 4.93298145e+03 4.93315088e+03 4.93312207e+03 4.93291650e+03 4.93284229e+03 4.93281543e+03 4.93289648e+03 4.93277100e+03 4.93288623e+03 4.93297998e+03 4.93286328e+03 4.93277148e+03 4.93279102e+03 4.93282275e+03 4.93285352e+03 4.93295996e+03 4.93302539e+03 4.93313916e+03 4.93321289e+03 4.93328223e+03 4.93312500e+03 4.93293994e+03 4.93286963e+03 4.93294434e+03 4.93295898e+03 4.93290381e+03 4.93287646e+03 4.93287939e+03 4.93296436e+03 4.93301416e+03 4.93294287e+03 4.93278857e+03 4.93292285e+03 4.93309277e+03 4.93288477e+03 4.93276660e+03 4.93278955e+03 4.93283887e+03 4.93290332e+03 4.93282764e+03 4.93276025e+03 4.93294678e+03 4.93294775e+03 4.93293652e+03 4.93309668e+03 4.93362305e+03 4.93323633e+03 4.93279688e+03 4.93289697e+03 4.93280176e+03 4.93278711e+03 4.93275439e+03 4.93278223e+03 4.93277197e+03 4.93282764e+03 4.93280762e+03 4.93278711e+03 4.93276465e+03 4.93277686e+03 4.93279248e+03 4.93277832e+03 4.93278027e+03 4.93284521e+03 4.93323242e+03 4.93312256e+03 4.93283594e+03 4.93278857e+03 4.93276514e+03 4.93282959e+03 4.93296094e+03 4.93311523e+03 4.93284766e+03 4.93278906e+03 4.93281836e+03 4.93278418e+03 4.93297461e+03 4.93288525e+03 4.93283545e+03 4.93276172e+03 4.93277002e+03 4.93280273e+03 4.93280859e+03 4.93279443e+03 4.93277930e+03 4.93276465e+03 4.93277881e+03 4.93279736e+03 4.93284912e+03 4.93306543e+03 4.93304346e+03 4.93280273e+03 4.93279102e+03 4.93279590e+03 4.93283789e+03 4.93282178e+03 4.93285840e+03 4.93286084e+03 4.93290479e+03 4.93280518e+03 4.93300977e+03 4.93309375e+03 4.93282031e+03 4.93277734e+03 4.93281348e+03 4.93282959e+03 4.93282031e+03 4.93278174e+03 4.93277490e+03 4.93281689e+03 4.93278125e+03 4.93278613e+03 4.93277734e+03 4.93277490e+03 4.93277930e+03 4.93274561e+03 4.93275000e+03 4.93278076e+03 4.93275928e+03 4.93277734e+03 4.93276611e+03 4.93279639e+03 4.93276807e+03 4.93279199e+03 4.93277783e+03 4.93276611e+03 4.93277979e+03 4.93279639e+03 4.93278613e+03 4.93279443e+03 4.93280664e+03 4.93282129e+03 4.93278857e+03 4.93298877e+03 4.93332959e+03 4.93330664e+03 4.93305371e+03 4.93295459e+03 4.93291357e+03 4.93280518e+03 4.93277783e+03 4.93280615e+03 4.93281982e+03 4.93281201e+03 4.93278711e+03 4.93278320e+03 4.93277783e+03 4.93285889e+03 4.93322070e+03 4.93355225e+03 4.93344531e+03 4.93301904e+03 4.93282227e+03 4.93282910e+03 4.93280518e+03 4.93279004e+03 4.93279883e+03 4.93281543e+03 4.93279590e+03 4.93278076e+03 4.93277002e+03 4.93279346e+03 4.93283105e+03 4.93280615e+03 4.93280127e+03 4.93275732e+03 4.93278320e+03 4.93278955e+03 4.93280127e+03 4.93284619e+03 4.93281299e+03 4.93279639e+03 4.93281738e+03 4.93313770e+03 4.93338330e+03 4.93333691e+03 4.93325000e+03 4.93338916e+03 4.93305713e+03 4.93283008e+03 4.93282715e+03 4.93288184e+03 4.93286133e+03 4.93279736e+03 4.93279297e+03 4.93279248e+03 4.93288086e+03 4.93290527e+03 4.93288818e+03 4.93285938e+03 4.93281738e+03 4.93282031e+03 4.93299414e+03 4.93345654e+03 4.93329492e+03 4.93291846e+03 4.93279297e+03 4.93279346e+03 4.93289111e+03 4.93327979e+03 4.93361963e+03 4.93333203e+03 4.93304834e+03 4.93281738e+03 4.93285400e+03 4.93291211e+03 4.93303418e+03 4.93299316e+03 4.93292236e+03 4.93292432e+03 4.93293652e+03 4.93291797e+03 4.93286914e+03 4.93280127e+03 4.93279980e+03 4.93292773e+03 4.93340869e+03 4.93396826e+03 4.93420605e+03 4.93307959e+03 4.93283008e+03 4.93305078e+03 4.93283154e+03 4.93281836e+03 4.93279443e+03 4.93281055e+03 4.93280469e+03 4.93280762e+03 4.93281445e+03 4.93279639e+03 4.93278857e+03 4.93278662e+03 4.93280322e+03 4.93285645e+03 4.93319189e+03 4.93328223e+03 4.93309766e+03 4.93287061e+03 4.93280664e+03 4.93284082e+03 4.93283057e+03 4.93281055e+03 4.93277051e+03 4.93282227e+03 4.93283398e+03 4.93279102e+03 4.93284180e+03 4.93281396e+03 4.93281006e+03 4.93279688e+03 4.93279590e+03 4.93281445e+03 4.93280762e+03 4.93279980e+03 4.93278760e+03 4.93280371e+03 4.93283838e+03 4.93283545e+03 4.93280859e+03 4.93304199e+03 4.93297852e+03 4.93283203e+03 4.93282666e+03 4.93279150e+03 4.93280225e+03 4.93278857e+03 4.93281396e+03 4.93281348e+03 4.93284473e+03 4.93302979e+03 4.93313379e+03 4.93308545e+03 4.93282617e+03 4.93282520e+03 4.93282422e+03 4.93279443e+03 4.93285596e+03 4.93307275e+03 4.93320361e+03 4.93308008e+03 4.93285547e+03 4.93285059e+03 4.93284912e+03 4.93284033e+03 4.93281934e+03 4.93279053e+03 4.93283594e+03 4.93288867e+03 4.93287256e+03 4.93290771e+03 4.93288184e+03 4.93291162e+03 4.93282910e+03 4.93279492e+03 4.93281494e+03 4.93295410e+03 4.93298047e+03 4.93285547e+03 4.93277979e+03 4.93280322e+03 4.93279150e+03 4.93281152e+03 4.93279492e+03 4.93285742e+03 4.93319971e+03 4.93315820e+03 4.93285059e+03 4.93278906e+03 4.93279443e+03 4.93281396e+03 4.93281787e+03 4.93281250e+03 4.93296240e+03 4.93337012e+03 4.93342285e+03 4.93301367e+03 4.93279492e+03 4.93277393e+03 4.93278760e+03 4.93280615e+03 4.93280225e+03 4.93279785e+03 4.93281543e+03 4.93285107e+03 4.93288037e+03 4.93280762e+03 4.93279297e+03 4.93282568e+03 4.93308496e+03 4.93385010e+03 4.93388232e+03 4.93332568e+03 4.93287109e+03 4.93281885e+03 4.93281348e+03 4.93279150e+03 4.93282031e+03 4.93317090e+03 4.93372949e+03 4.93455859e+03 4.93456787e+03 4.93374951e+03 4.93321338e+03 4.93283154e+03 4.93300195e+03 4.93332764e+03 4.93304590e+03 4.93281250e+03 4.93305078e+03 4.93286133e+03 4.93279883e+03 4.93279199e+03 4.93279785e+03 4.93276807e+03 4.93277100e+03 4.93278711e+03 4.93278467e+03 4.93281592e+03 4.93281104e+03 4.93285547e+03 4.93283350e+03 4.93288477e+03 4.93287354e+03 4.93284521e+03 4.93277295e+03 4.93290576e+03 4.93287842e+03 4.93279102e+03 4.93285986e+03 4.93274561e+03 4.93296338e+03 4.93279492e+03 4.93319922e+03 4.93326855e+03 4.93278613e+03 4.93323926e+03 4.93292334e+03 4.93280273e+03 4.93280469e+03 4.93315039e+03 4.93319678e+03 4.93294141e+03 4.93277148e+03 4.93277734e+03 4.93280811e+03 4.93278027e+03 4.93280127e+03 4.93281592e+03 4.93295410e+03 4.93279004e+03 4.93300342e+03 4.93348535e+03 4.93313623e+03 4.93286621e+03 4.93311816e+03 4.93356592e+03 4.93377783e+03 4.93326807e+03 4.93286230e+03 4.93286621e+03 4.93291992e+03 4.93301611e+03 4.93288232e+03 4.93294238e+03 4.93329834e+03 4.93350098e+03 4.93342188e+03 4.93295654e+03 4.93285400e+03 4.93281055e+03 4.93277246e+03 4.93277539e+03 4.93303076e+03 4.93379980e+03 4.93347314e+03 4.93275488e+03 4.93298877e+03 4.93290137e+03 4.93278809e+03 4.93282422e+03 4.93313623e+03 4.93322461e+03 4.93295166e+03 4.93279248e+03 4.93278955e+03 4.93278809e+03 4.93278516e+03 4.93278809e+03 4.93276660e+03 4.93279443e+03 4.93282812e+03 4.93286816e+03 4.93282129e+03 4.93279492e+03 4.93280762e+03 4.93280518e+03 4.93279297e+03 4.93293457e+03 4.93327197e+03 4.93295068e+03 4.93287500e+03 4.93341699e+03 4.93295557e+03 4.93280371e+03 4.93294971e+03 4.93301416e+03 4.93300049e+03 4.93290479e+03 4.93289258e+03 4.93290967e+03 4.93284180e+03 4.93289062e+03 4.93289307e+03 4.93293945e+03 4.93294434e+03 4.93294287e+03 4.93289941e+03 4.93283008e+03 4.93284668e+03 4.93292090e+03 4.93298389e+03 4.93286963e+03 4.93280225e+03 4.93278613e+03 4.93283350e+03 4.93311621e+03 4.93316699e+03 4.93299268e+03 4.93297070e+03 4934. 4.93496631e+03 4.93429541e+03 4.93334863e+03 4.93355957e+03 4.93445068e+03 4.93462158e+03 4.93374414e+03 4.93321484e+03 4.93306543e+03 4.93308203e+03 4.93307129e+03 4.93311133e+03 4.93301514e+03 4.93291455e+03 4.93303857e+03 4.93355566e+03 4.93384961e+03 4.93342969e+03 4.93294189e+03 4.93297949e+03 4.93321777e+03 4.93297754e+03 4.93281250e+03 4.93289355e+03 4.93277979e+03 4.93280322e+03 4.93278955e+03 4.93280664e+03 4.93277734e+03 4.93280273e+03 4.93276367e+03 4.93278516e+03 4.93278613e+03 4.93280176e+03 4.93282471e+03 4.93283984e+03 4.93281299e+03 4.93280029e+03 4.93280371e+03 4.93283301e+03 4.93305078e+03 4.93311670e+03 4.93284766e+03 4.93286084e+03 4.93297900e+03 4.93299072e+03 4.93318896e+03 4.93362451e+03 4.93374756e+03 4.93329346e+03 4.93291895e+03 4.93287256e+03 4.93287842e+03 4.93280029e+03 4.93322119e+03 4.93337939e+03 4.93299854e+03 4.93281299e+03 4.93281934e+03 4.93278662e+03 4.93276562e+03 4.93280420e+03 4.93281348e+03 4.93296826e+03 4.93285596e+03 4.93278955e+03 4.93301074e+03 4.93287891e+03 4.93290918e+03 4.93374023e+03 4.93463135e+03 4.93410303e+03 4.93305225e+03 4.93289502e+03 4.93308838e+03 4.93310303e+03 4.93283594e+03 4.93285352e+03 4.93279248e+03 4.93281934e+03 4.93282812e+03 4.93281494e+03 4.93282031e+03 4.93285303e+03 4.93292676e+03 4.93293359e+03 4.93285010e+03 4.93289111e+03 4.93294385e+03 4.93280811e+03 4.93278027e+03 4.93284863e+03 4.93279932e+03 4.93282910e+03 4.93277393e+03 4.93286084e+03 4.93286963e+03 4.93287207e+03 4.93292725e+03 4.93357520e+03 4.93736914e+03 4.94312158e+03 4.94984424e+03 4.96615137e+03 4.95524658e+03 4.93323975e+03 4.95043945e+03 5.04491650e+03 7.71656152e+03 1.64933047e+04 2.21669724e+10 4.60260045e+09 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. 4.09971507e+10 1.53690358e+10 6.98392422e+04 3.15821367e+04 1.98365762e+04 1.03304473e+04 6.80723291e+03 4.95296143e+03 4.92146582e+03 4.91677393e+03 4.91646533e+03 4.91629492e+03 4.91622363e+03 4.91636377e+03 4.91672607e+03 4.91647314e+03 4.91630371e+03 4.91663477e+03 4.91626709e+03 4.91653906e+03 4.91625635e+03 4.91737988e+03 4.92122363e+03 4.92153369e+03 4.92006445e+03 4.91743506e+03 4.91684619e+03 4.91655811e+03 4.91694629e+03 4.91671533e+03 4.91697266e+03 4.91850928e+03 4.91890918e+03 4.91719434e+03 4.91625488e+03 4.91617480e+03 4.91617090e+03 4.91624854e+03 4.91681006e+03 4.91698291e+03 4.91628271e+03 4.91731689e+03 4.91943018e+03 4.91828857e+03 4.91634424e+03 4.91619141e+03 4.91616846e+03 4.91615869e+03 4.91639648e+03 4.91625195e+03 4.91641406e+03 4.91662207e+03 4.91644141e+03 4.91622461e+03 4.91772119e+03 4.91734033e+03 4.91621387e+03 4.91691016e+03 4.91641504e+03 4.91624561e+03 4.91620898e+03 4.91644238e+03 4.91647412e+03 4.91615723e+03 4.91680908e+03 4.91654443e+03 4.91635156e+03 4.91737939e+03 4.91675244e+03 4.91617871e+03 4.91616406e+03 4.91623926e+03 4.91623145e+03 4.91627930e+03 4.91694141e+03 4.91663965e+03 4.91624902e+03 4.91625977e+03 4.91666357e+03 4.91709814e+03 4.91683057e+03 4.91625391e+03 4.91620898e+03 4.91637158e+03 4.91618457e+03 4.91624561e+03 4.91617578e+03 4.91636719e+03 4.91761084e+03 4.91867041e+03 4.91699512e+03 4.91630176e+03 4917. 4.91651807e+03 4.91626562e+03 4.91764941e+03 4.91862061e+03 4.91794189e+03 4.91742090e+03 4.91768896e+03 4.91725342e+03 4.91620508e+03 4.91645459e+03 4.91631104e+03 4.91632129e+03 4.91682178e+03 4.91656250e+03 4.91618555e+03 4.91622314e+03 4.91618506e+03 4.91631055e+03 4.91628662e+03 4.91622852e+03 4.91658545e+03 4.91824512e+03 4.91873438e+03 4.91715967e+03 4.91621533e+03 4.91620361e+03 4.91658154e+03 4.91745068e+03 4.91749219e+03 4.91666748e+03 4.91617139e+03 4.91620947e+03 4.91618652e+03 4.91619189e+03 4.91623584e+03 4.91625879e+03 4.91620312e+03 4.91685645e+03 4.91675879e+03 4.91624023e+03 4.91614795e+03 4.91622168e+03 4.91645410e+03 4.91665381e+03 4.91636719e+03 4.91660840e+03 4.91745215e+03 4.91776025e+03 4.91648779e+03 4.91667920e+03 4.91790527e+03 4.91674268e+03 4.91616016e+03 4.91618994e+03 4.91620410e+03 4.91630762e+03 4.91625977e+03 4.91627734e+03 4.91647705e+03 4.91730078e+03 4.91770605e+03 4.91667188e+03 4.91635840e+03 4.91729785e+03 4.91642188e+03 4.91623047e+03 4.91623633e+03 4.91615674e+03 4.91622949e+03 4.91728955e+03 4.91709180e+03 4.91621289e+03 4.91647949e+03 4.91619141e+03 4.91777344e+03 4.92014355e+03 4.91848389e+03 4.91651221e+03 4.91615137e+03 4.91616602e+03 4.91617920e+03 4.91634961e+03 4.91619336e+03 4.91646680e+03 4.91838184e+03 4.91744189e+03 4.91630713e+03 4.91629736e+03 4.91624072e+03 4.91617090e+03 4.91629053e+03 4.91652783e+03 4.91653564e+03 4.91683594e+03 4.91750439e+03 4.91715820e+03 4.91616748e+03 4.91652686e+03 4.91624805e+03 4.91663428e+03 4.91809375e+03 4.91719922e+03 4.91628613e+03 4.91619727e+03 4.91617480e+03 4.91622803e+03 4.91691162e+03 4.91749365e+03 4.91643750e+03 4.91638232e+03 4.91657324e+03 4.91619141e+03 4.91641699e+03 4.91674414e+03 4.91668018e+03 4.91621240e+03 4.91613770e+03 4.91614160e+03 4.91626758e+03 4.91647021e+03 4.91618018e+03 4.91633691e+03 4.91655078e+03 4.91632959e+03 4.91616650e+03 4.91615771e+03 4.91616211e+03 4.91613721e+03 4.91617383e+03 4.91621289e+03 4.91614941e+03 4.91657666e+03 4.91702734e+03 4.91728564e+03 4.91623926e+03 4.91622559e+03 4.91616699e+03 4.91671045e+03 4.91698193e+03 4.91627832e+03 4.91620801e+03 4.91619482e+03 4.91618018e+03 4.91616992e+03 4.91627344e+03 4.91628662e+03 4.91619580e+03 4.91644092e+03 4.91620947e+03 4.91615674e+03 4.91624414e+03 4.91638916e+03 4.91619678e+03 4.91621582e+03 4.91625635e+03 4.91617725e+03 4.91636279e+03 4.91642139e+03 4.91641357e+03 4.91646631e+03 4.91681445e+03 4.91706543e+03 4.91620020e+03 4.91614502e+03 4.91620459e+03 4.91627832e+03 4.91617285e+03 4.91618896e+03 4.91630811e+03 4.91695361e+03 4.91727881e+03 4.91621582e+03 4.91617480e+03 4.91618604e+03 4.91640918e+03 4.91656396e+03 4.91627539e+03 4.91610303e+03 4.91619531e+03 4.91634912e+03 4.91624707e+03 4.91616846e+03 4.91656543e+03 4.91700684e+03 4.91674805e+03 4.91621973e+03 4.91623779e+03 4.91616895e+03 4.91647461e+03 4.91677295e+03 4.91636865e+03 4.91675146e+03 4.91676465e+03 4.91634570e+03 4.91623975e+03 4.91619482e+03 4.91646387e+03 4.91688135e+03 4.91642969e+03 4.91621533e+03 4.91614062e+03 4.91628271e+03 4.91652002e+03 4.91634668e+03 4.91615332e+03 4.91617529e+03 4.91619775e+03 4.91624170e+03 4.91648096e+03 4.91664258e+03 4.91621826e+03 4.91612695e+03 4.91621143e+03 4.91650586e+03 4.91660303e+03 4.91678711e+03 4.91817725e+03 4.91938867e+03 4.91890332e+03 4.91831738e+03 4.91829297e+03 4.91969580e+03 4.92008838e+03 4.91900928e+03 4.91704541e+03 4.91661182e+03 4.91653271e+03 4.91662012e+03 4.91637256e+03 4.91615723e+03 4.91625732e+03 4.91627100e+03 4.91616602e+03 4.91631836e+03 4.91635742e+03 4.91623438e+03 4.91631494e+03 4.91660889e+03 4.91708643e+03 4.91705908e+03 4.91695117e+03 4.91789551e+03 4.91888281e+03 4.91826758e+03 4.91693945e+03 4.91660205e+03 4.91669238e+03 4.91619580e+03 4.91615088e+03 4.91624414e+03 4.91619189e+03 4.91627051e+03 4.91626123e+03 4.91660059e+03 4.91660303e+03 4.91628271e+03 4.91635059e+03 4.91648438e+03 4.91608936e+03 4.91649023e+03 4.91646875e+03 4.91616211e+03 4.91632373e+03 4.91615234e+03 4.91623828e+03 4.91675000e+03 4.91681592e+03 4.91629932e+03 4.91614355e+03 4.91637061e+03 4.91639502e+03 4.91644629e+03 4.91665527e+03 4.91659521e+03 4.91665576e+03 4.91612695e+03 4.91615381e+03 4.91611768e+03 4.91615430e+03 4.91612305e+03 4.91631738e+03 4.91820557e+03 4.91881201e+03 4.91703320e+03 4.91630469e+03 4.91745117e+03 4.91626270e+03 4.91674756e+03 4.91684961e+03 4.91628076e+03 4.91874512e+03 4.91780176e+03 4.91617383e+03 4.91651172e+03 4.91636182e+03 4.91623096e+03 4.91628467e+03 4.91614453e+03 4.91649463e+03 4.91664355e+03 4.91614502e+03 4.91615820e+03 4.91626416e+03 4.91666162e+03 4.91659277e+03 4.91620996e+03 4.91645605e+03 4.91641162e+03 4.91619238e+03 4.91722070e+03 4.91697363e+03 4.91646826e+03 4.91826904e+03 4.91728320e+03 4.91613281e+03 4.91650391e+03 4.91628857e+03 4.91631885e+03 4.91659863e+03 4.91674365e+03 4.91612500e+03 4.91614258e+03 4.91613574e+03 4.91639941e+03 4.91681494e+03 4.91620410e+03 4.91613037e+03 4.91665527e+03 4.91671729e+03 4.91639453e+03 4.91616992e+03 4.91711816e+03 4.91786719e+03 4.91663965e+03 4.91662793e+03 4.91818652e+03 4.91677100e+03 4.91663184e+03 4.91737256e+03 4.91617236e+03 4.91804248e+03 4.91811523e+03 4.91621484e+03 4.91632666e+03 4.91626367e+03 4.91621680e+03 4.91631250e+03 4.91612451e+03 4.91650049e+03 4.91726855e+03 4.91718604e+03 4.91782617e+03 4.91770117e+03 4.91662988e+03 4.91615576e+03 4.91636377e+03 4.91619434e+03 4.91691797e+03 4.91658154e+03 4.91626025e+03 4.91741943e+03 4.91684473e+03 4.91620166e+03 4.91637891e+03 4.91617383e+03 4.91669336e+03 4.91649268e+03 4.91617432e+03 4.91670312e+03 4.91738184e+03 4.91652832e+03 4.91651660e+03 4.91623438e+03 4.91636523e+03 4.91643896e+03 4.91666064e+03 4.91738184e+03 4.91672754e+03 4.91617188e+03 4.91642920e+03 4.91620703e+03 4.91663867e+03 4.91793213e+03 4.91678564e+03 4.91617529e+03 4.91671680e+03 4.91668213e+03 4.91615186e+03 4.91619043e+03 4.91625977e+03 4.91614600e+03 4.91621094e+03 4.91640723e+03 4.91700684e+03 4.91791211e+03 4.91745703e+03 4.91635156e+03 4.91622021e+03 4.91625928e+03 4.91616455e+03 4.91634961e+03 4.91704639e+03 4.91757568e+03 4.91642334e+03 4.91656348e+03 4.91750732e+03 4.91637256e+03 4.91642480e+03 4.91649268e+03 4.91625732e+03 4.91809863e+03 4.91788086e+03 4.91615869e+03 4.91764648e+03 4.91907178e+03 4.91692334e+03 4.91619043e+03 4.91618066e+03 4.91644580e+03 4.91675537e+03 4.91626855e+03 4.91627051e+03 4.91619092e+03 4.91619580e+03 4.91623193e+03 4.91624072e+03 4.91630078e+03 4.91619922e+03 4.91628271e+03 4.91758984e+03 4.91734766e+03 4.91620410e+03 4.91749756e+03 4.91689551e+03 4.91621777e+03 4.91722705e+03 4.91726367e+03 4.91619238e+03 4.91667578e+03 4.91744824e+03 4.91635107e+03 4.91617041e+03 4.91643506e+03 4.91637598e+03 4.91624072e+03 4.91626855e+03 4.91626367e+03 4.91698730e+03 4.91771973e+03 4.91776270e+03 4.91685791e+03 4.91619141e+03 4.91637744e+03 4.91614160e+03 4.91704834e+03 4.91767480e+03 4.91664404e+03 4.91621777e+03 4.91621094e+03 4.91631934e+03 4.91776270e+03 4.91826953e+03 4.91649316e+03 4.91627002e+03 4.91664062e+03 4.91616309e+03 4.91664258e+03 4.91666016e+03 4.91627881e+03 4.91621582e+03 4.91629443e+03 4.91634180e+03 4.91617188e+03 4.91649805e+03 4.91675635e+03 4.91620215e+03 4.91695752e+03 4.91768750e+03 4.91659131e+03 4.91620068e+03 4.91667285e+03 4.91628906e+03 4.91631152e+03 4.91684863e+03 4.91652881e+03 4.91615967e+03 4.91617090e+03 4.91631738e+03 4.91681250e+03 4.91682471e+03 4.91617920e+03 4.91625781e+03 4.91614893e+03 4.91633594e+03 4.91737598e+03 4.91724268e+03 4.91727393e+03 4.91670850e+03 4.91627441e+03 4.91618115e+03 4.91615674e+03 4.91650977e+03 4.91707373e+03 4.91668506e+03 4.91618945e+03 4.91622949e+03 4.91614941e+03 4.91645898e+03 4.91692041e+03 4.91608350e+03 4.91696191e+03 4.91836572e+03 4.91676172e+03 4.91628662e+03 4.91672510e+03 4.91637256e+03 4.91957080e+03 4.91657324e+03 4.91713281e+03 4.91668066e+03 4.91671436e+03 4.95177979e+03 6.23780518e+03 9.53262793e+03 4.26519414e+04 7.30865625e+04 4.18687156e+11 -1.92790200e+10 -4.59317707e+11 -3.99993815e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.11527547e+10 -4.91139113e+10 4.80113516e+04 2.67832891e+04 1.96102637e+04 1.96952129e+04 1.01957871e+04 6.63021533e+03 4.93374658e+03 4.91872705e+03 4.92193896e+03 4.91822900e+03 4.91633496e+03 4.91656689e+03 4.91644629e+03 4.91624707e+03 4.91678906e+03 4.91654248e+03 4.91637451e+03 4.91773975e+03 4.91738867e+03 4.91648193e+03 4.91635693e+03 4.91639551e+03 4.91635938e+03 4.91634326e+03 4.91632861e+03 4.91633789e+03 4.91636572e+03 4.91705078e+03 4.91651074e+03 4.91681836e+03 4.91810986e+03 4.91653174e+03 4.91633301e+03 4.91724072e+03 4.91661133e+03 4.91641211e+03 4.91829688e+03 4.92006104e+03 4.91732227e+03 4.91633350e+03 4.91622461e+03 4.91704102e+03 4.91801172e+03 4.91709180e+03 4.91685059e+03 4.91632373e+03 4.91617578e+03 4.91619385e+03 4.91631543e+03 4.91824805e+03 4.91838477e+03 4.91646387e+03 4.91652637e+03 4.91705029e+03 4.91619824e+03 4.91707910e+03 4.91709131e+03 4.91622900e+03 4.91616797e+03 4.91658203e+03 4.91943750e+03 4.92063721e+03 4.91887061e+03 4.91625049e+03 4.91644727e+03 4.91642773e+03 4.91628174e+03 4.91795117e+03 4.92009766e+03 4.92136816e+03 4.92004053e+03 4.91801025e+03 4.91668604e+03 4.91634473e+03 4.91660449e+03 4.91647852e+03 4.91618311e+03 4.91687451e+03 4.91678467e+03 4.91617285e+03 4.91662451e+03 4.91641650e+03 4.91617969e+03 4.91641113e+03 4.91687109e+03 4.91641162e+03 4.91638867e+03 4.91744043e+03 4.91641846e+03 4.91619727e+03 4.91614697e+03 4.91627002e+03 4.91636035e+03 4.91622314e+03 4.91633740e+03 4.91628174e+03 4.91619238e+03 4.91630518e+03 4.91619922e+03 4.91717773e+03 4.91736572e+03 4.91615723e+03 4.91753320e+03 4.91863037e+03 4.91672949e+03 4.91624902e+03 4.91650098e+03 4.91636426e+03 4.91617139e+03 4.91616699e+03 4.91621289e+03 4.91678467e+03 4.91733496e+03 4.91643555e+03 4.91637500e+03 4.91666357e+03 4.91630078e+03 4.91617871e+03 4.91618457e+03 4.91640186e+03 4.91635303e+03 4.91628760e+03 4.91792725e+03 4.91792188e+03 4.91618115e+03 4.91643213e+03 4.91618408e+03 4.91780176e+03 4.91826758e+03 4.91635254e+03 4.91652002e+03 4.91690869e+03 4.91633545e+03 4.91625977e+03 4.91714258e+03 4.91670410e+03 4.91617041e+03 4.91673242e+03 4.91615771e+03 4.91675488e+03 4.91727100e+03 4.91666602e+03 4.91621094e+03 4.91615527e+03 4.91650879e+03 4.91664062e+03 4.91630371e+03 4.91615234e+03 4.91618262e+03 4.91647461e+03 4.91689551e+03 4.91624219e+03 4.91687207e+03 4.91914990e+03 4.91792627e+03 4.91617236e+03 4.91662158e+03 4.91650537e+03 4.91612158e+03 4.91624219e+03 4.91617676e+03 4.91619336e+03 4.91625488e+03 4.91620264e+03 4.91617041e+03 4.91617041e+03 4.91673096e+03 4.91732275e+03 4.91749316e+03 4.91639160e+03 4.91615137e+03 4.91647412e+03 4.91731836e+03 4.91684277e+03 4.91620166e+03 4.91685596e+03 4.91643018e+03 4.91614453e+03 4.91639941e+03 4.91649414e+03 4.91622803e+03 4.91617822e+03 4.91615527e+03 4.91652637e+03 4.91640283e+03 4.91612256e+03 4.91656738e+03 4.91777246e+03 4.91877344e+03 4.91979004e+03 4.91761084e+03 4.91620459e+03 4.91620215e+03 4.91615234e+03 4.91632129e+03 4.91632227e+03 4.91614355e+03 4.91714355e+03 4.91809424e+03 4.91639697e+03 4.91680811e+03 4.91817139e+03 4.91739990e+03 4.91638135e+03 4.91624854e+03 4.91631982e+03 4.91650293e+03 4.91695068e+03 4.91649219e+03 4.91615479e+03 4.91619287e+03 4.91617383e+03 4.91621436e+03 4.91633740e+03 4.91648730e+03 4.91679590e+03 4.91645020e+03 4.91626367e+03 4.91629199e+03 4.91629297e+03 4.91614062e+03 4.91644482e+03 4.91698926e+03 4.91738037e+03 4.91648438e+03 4.91619385e+03 4.91648145e+03 4.91666455e+03 4.91621582e+03 4.91631738e+03 4.91655176e+03 4.91618359e+03 4.91615527e+03 4.91617627e+03 4.91614551e+03 4.91618213e+03 4.91619385e+03 4.91619873e+03 4.91616553e+03 4.91614697e+03 4.91613330e+03 4.91615479e+03 4.91616455e+03 4.91627490e+03 4.91626709e+03 4.91617969e+03 4.91616748e+03 4.91619482e+03 4.91625098e+03 4.91617969e+03 4.91614893e+03 4.91622754e+03 4.91627930e+03 4.91629590e+03 4.91621680e+03 4.91612988e+03 4.91613623e+03 4.91615771e+03 4.91616406e+03 4.91615381e+03 4.91613770e+03 4.91614600e+03 4.91614746e+03 4.91614551e+03 4.91614990e+03 4.91613867e+03 4.91614648e+03 4.91615576e+03 4.91625928e+03 4.91627637e+03 4.91637061e+03 4.91624072e+03 4.91621729e+03 4.91615771e+03 4.91617090e+03 4.91618066e+03 4.91625098e+03 4.91624414e+03 4.91624023e+03 4.91612939e+03 4.91613281e+03 4.91616797e+03 4.91622363e+03 4.91619531e+03 4.91616602e+03 4.91615039e+03 4.91619678e+03 4.91611719e+03 4.91616553e+03 4.91615039e+03 4.91621338e+03 4.91615869e+03 4.91616650e+03 4.91617627e+03 4.91615869e+03 4.91616992e+03 4.91622998e+03 4.91614307e+03 4.91614990e+03 4.91616553e+03 4.91620410e+03 4.91625537e+03 4.91626416e+03 4.91622998e+03 4.91612354e+03 4.91613574e+03 4.91616650e+03 4.91617236e+03 4.91615723e+03 4.91614453e+03 4.91614893e+03 4.91618262e+03 4.91643701e+03 4.91637842e+03 4.91621289e+03 4.91613379e+03 4.91613672e+03 4.91616846e+03 4.91614453e+03 4.91616748e+03 4.91615674e+03 4.91621143e+03 4.91616797e+03 4.91624365e+03 4.91624170e+03 4.91628320e+03 4.91613867e+03 4.91617725e+03 4.91616357e+03 4.91616846e+03 4.91612891e+03 4.91616846e+03 4.91616113e+03 4.91616797e+03 4.91618311e+03 4.91626465e+03 4.91624609e+03 4.91616992e+03 4.91616992e+03 4.91614502e+03 4.91617090e+03 4.91623584e+03 4.91621240e+03 4.91612598e+03 4.91614502e+03 4.91616602e+03 4.91619922e+03 4.91621533e+03 4.91628125e+03 4.91614062e+03 4.91617334e+03 4.91618555e+03 4.91621729e+03 4.91622754e+03 4.91626562e+03 4.91626270e+03 4.91618164e+03 4.91614844e+03 4.91617285e+03 4.91614453e+03 4.91614209e+03 4.91614746e+03 4.91618066e+03 4.91619189e+03 4.91619580e+03 4.91616455e+03 4.91615430e+03 4.91611816e+03 4.91631934e+03 4.91691455e+03 4.91680664e+03 4.91627100e+03 4.91617188e+03 4.91615869e+03 4.91630859e+03 4.91641162e+03 4.91628418e+03 4.91619043e+03 4.91620898e+03 4.91630566e+03 4.91632520e+03 4.91629297e+03 4.91629443e+03 4.91643164e+03 4.91656641e+03 4.91659180e+03 4.91631152e+03 4.91619873e+03 4.91617773e+03 4.91623975e+03 4.91622510e+03 4.91619922e+03 4.91614600e+03 4.91619824e+03 4.91630615e+03 4.91654004e+03 4.91637061e+03 4.91616455e+03 4.91612500e+03 4.91616602e+03 4.91611914e+03 4.91617041e+03 4.91627979e+03 4.91667432e+03 4.91672363e+03 4.91631592e+03 4.91613770e+03 4.91615527e+03 4.91619287e+03 4.91633984e+03 4.91639258e+03 4.91615918e+03 4.91645703e+03 4.91660449e+03 4.91618604e+03 4.91616992e+03 4.91617285e+03 4.91617432e+03 4.91619922e+03 4.91624609e+03 4.91620410e+03 4.91614746e+03 4.91628857e+03 4.91629688e+03 4.91632324e+03 4.91617676e+03 4.91638428e+03 4.91654395e+03 4.91631250e+03 4.91619189e+03 4.91625244e+03 4.91651025e+03 4.91652295e+03 4.91627441e+03 4.91616455e+03 4.91614307e+03 4.91616113e+03 4.91613672e+03 4.91617188e+03 4.91615430e+03 4.91616406e+03 4.91610791e+03 4.91607715e+03 4.91603857e+03 4.91709326e+03 4.91960352e+03 4.92626172e+03 4.92180371e+03 4.91824512e+03 4.91637402e+03 4.91673828e+03 4.91852783e+03 4.91667139e+03 4.92469971e+03 7.22872266e+03 1.52645576e+04 -3.68119808e+10 -1.31479624e+10 -2.14930268e+10 1.06868818e+11 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.48008294e+09 1.58701445e+10 6.24025430e+04 2.98334961e+04 1.97320762e+04 1.96421133e+04 9.93142969e+03 6.69923633e+03 4.94537598e+03 4.93061377e+03 4.91778320e+03 4.91656641e+03 4.91637744e+03 4.91634619e+03 4.91638086e+03 4.91636182e+03 4.91643359e+03 4.91621582e+03 4.91794629e+03 4.92106250e+03 4.91967773e+03 4.91828027e+03 4.91699121e+03 4.91759521e+03 4.92007178e+03 4.91978613e+03 4.91885547e+03 4.92001074e+03 4.92329150e+03 4.91897168e+03 4.92119092e+03 4.91999463e+03 4.91858594e+03 4.91642334e+03 4.91624365e+03 4.91625830e+03 4.91630615e+03 4.91642041e+03 4.91649219e+03 4.91652148e+03 4.91636523e+03 4.91627051e+03 4.91627295e+03 4.91633154e+03 4.91641650e+03 4.91649268e+03 4.91654395e+03 4.91637451e+03 4.91616992e+03 4.91621582e+03 4.91625586e+03 4.91618262e+03 4.91618066e+03 4.91618408e+03 4.91623633e+03 4.91621387e+03 4.91617236e+03 4.91618408e+03 4.91621729e+03 4.91634277e+03 4.91629443e+03 4.91639111e+03 4.91625586e+03 4.91617334e+03 4.91616748e+03 4.91615332e+03 4.91620166e+03 4.91621484e+03 4.91618799e+03 4.91614648e+03 4.91615039e+03 4.91616699e+03 4.91623242e+03 4.91629590e+03 4.91629736e+03 4.91618604e+03 4.91618750e+03 4.91618018e+03 4.91618262e+03 4.91636621e+03 4.91635791e+03 4.91624854e+03 4.91618555e+03 4.91650732e+03 4.91712695e+03 4.91714453e+03 4.91664844e+03 4.91640137e+03 4.91639453e+03 4.91645557e+03 4.91634570e+03 4.91642236e+03 4.91668604e+03 4.91718262e+03 4.91696582e+03 4.91637842e+03 4.91617041e+03 4.91615381e+03 4.91616602e+03 4.91616992e+03 4.91621143e+03 4.91619971e+03 4.91623682e+03 4.91618164e+03 4.91618994e+03 4.91623096e+03 4.91616162e+03 4.91623682e+03 4.91622510e+03 4.91651367e+03 4.91643262e+03 4.91619385e+03 4.91628467e+03 4.91628711e+03 4.91626025e+03 4.91623145e+03 4.91623633e+03 4.91619531e+03 4.91617676e+03 4.91617725e+03 4.91619189e+03 4.91618945e+03 4.91616455e+03 4.91616895e+03 4.91617334e+03 4.91617725e+03 4.91615771e+03 4.91619141e+03 4.91629248e+03 4.91665820e+03 4.91661963e+03 4.91629053e+03 4.91617627e+03 4.91637402e+03 4.91689795e+03 4.91692871e+03 4.91643506e+03 4.91619678e+03 4.91615674e+03 4.91616846e+03 4.91616113e+03 4.91617578e+03 4.91614453e+03 4.91615918e+03 4.91615527e+03 4.91617920e+03 4.91619873e+03 4.91615381e+03 4.91618457e+03 4.91618115e+03 4.91620410e+03 4.91617773e+03 4.91622754e+03 4.91650537e+03 4.91706348e+03 4.91694580e+03 4.91654932e+03 4.91623145e+03 4.91645264e+03 4.91690723e+03 4.91681689e+03 4.91630811e+03 4.91616455e+03 4.91617725e+03 4.91617090e+03 4.91618408e+03 4.91618604e+03 4.91618945e+03 4.91619189e+03 4.91616016e+03 4.91618604e+03 4.91625537e+03 4.91651172e+03 4.91651270e+03 4.91633398e+03 4.91617529e+03 4.91616699e+03 4.91617480e+03 4.91626123e+03 4.91652734e+03 4.91650293e+03 4.91634473e+03 4.91620508e+03 4.91619336e+03 4.91620068e+03 4.91622803e+03 4.91658887e+03 4.91672119e+03 4.91642090e+03 4.91621973e+03 4.91620361e+03 4.91624023e+03 4.91617969e+03 4.91620410e+03 4.91618066e+03 4.91622363e+03 4.91647705e+03 4.91696973e+03 4.91695898e+03 4.91644482e+03 4.91620850e+03 4.91625391e+03 4.91627441e+03 4.91646338e+03 4.91682129e+03 4.91672803e+03 4.91630420e+03 4.91620898e+03 4.91615283e+03 4.91616455e+03 4.91619824e+03 4.91621484e+03 4.91619043e+03 4.91618018e+03 4.91617627e+03 4.91616602e+03 4.91617139e+03 4.91616162e+03 4.91618359e+03 4.91621191e+03 4.91631104e+03 4.91635596e+03 4.91635791e+03 4.91629395e+03 4.91628906e+03 4.91627832e+03 4.91629150e+03 4.91623145e+03 4.91622900e+03 4.91623047e+03 4.91623096e+03 4.91621436e+03 4.91621875e+03 4.91626465e+03 4.91625684e+03 4.91620801e+03 4.91626123e+03 4.91626807e+03 4.91627832e+03 4.91619922e+03 4.91619336e+03 4.91619971e+03 4.91618994e+03 4.91619287e+03 4.91623389e+03 4.91639355e+03 4.91626318e+03 4.91623389e+03 4.91647998e+03 4.91634326e+03 4.91618604e+03 4.91619189e+03 4.91622510e+03 4.91627100e+03 4.91629834e+03 4.91630615e+03 4.91625146e+03 4.91620850e+03 4.91619971e+03 4.91618799e+03 4.91620312e+03 4.91619092e+03 4.91621240e+03 4.91619629e+03 4.91619580e+03 4.91618506e+03 4.91619189e+03 4.91617969e+03 4.91618457e+03 4.91616602e+03 4.91617236e+03 4.91630322e+03 4.91671484e+03 4.91665283e+03 4.91632324e+03 4.91617871e+03 4.91616309e+03 4.91619238e+03 4.91621240e+03 4.91639697e+03 4.91658984e+03 4.91669287e+03 4.91634375e+03 4.91620166e+03 4.91616650e+03 4.91617822e+03 4.91620801e+03 4.91620166e+03 4.91618604e+03 4.91618604e+03 4.91618701e+03 4.91618213e+03 4.91620459e+03 4.91623291e+03 4.91624023e+03 4.91623486e+03 4.91650000e+03 4.91677393e+03 4.91667480e+03 4.91623438e+03 4.91616211e+03 4.91617773e+03 4.91628809e+03 4.91624902e+03 4.91622021e+03 4.91630078e+03 4.91667139e+03 4.91662646e+03 4.91631689e+03 4.91616895e+03 4.91623340e+03 4.91626758e+03 4.91623291e+03 4.91616846e+03 4.91616895e+03 4.91617822e+03 4.91619922e+03 4.91618652e+03 4.91620312e+03 4.91618408e+03 4.91619580e+03 4.91619189e+03 4.91619092e+03 4.91615381e+03 4.91625391e+03 4.91630664e+03 4.91645801e+03 4.91679102e+03 4.91735352e+03 4.91738574e+03 4.91700439e+03 4.91708008e+03 4.91673193e+03 4.91663037e+03 4.91628418e+03 4.91620801e+03 4.91655762e+03 4.91668018e+03 4.91642090e+03 4.91622070e+03 4.91617529e+03 4.91618213e+03 4.91618506e+03 4.91619971e+03 4.91626318e+03 4.91618799e+03 4.91637646e+03 4.91660156e+03 4.91653760e+03 4.91623633e+03 4.91621387e+03 4.91620654e+03 4.91619580e+03 4.91618018e+03 4.91618066e+03 4.91628906e+03 4.91631543e+03 4.91645508e+03 4.91685156e+03 4.91643799e+03 4.91622363e+03 4.91617236e+03 4.91635449e+03 4.91643311e+03 4.91631787e+03 4.91616943e+03 4.91625635e+03 4.91659668e+03 4.91674414e+03 4.91639990e+03 4.91619141e+03 4.91644043e+03 4.91690869e+03 4.91682129e+03 4.91626562e+03 4.91617920e+03 4.91627637e+03 4.91643262e+03 4.91621533e+03 4.91623096e+03 4.91618164e+03 4.91645752e+03 4.91682471e+03 4.91651025e+03 4.91637305e+03 4.91639551e+03 4.91673047e+03 4.91708789e+03 4.91693896e+03 4.91627734e+03 4.91618164e+03 4.91616553e+03 4.91615430e+03 4.91615479e+03 4.91613916e+03 4.91616211e+03 4.91616309e+03 4.91630273e+03 4.91629395e+03 4.91620264e+03 4.91617627e+03 4.91617627e+03 4.91629199e+03 4.91646777e+03 4.91640967e+03 4.91627539e+03 4.91615674e+03 4.91616309e+03 4.91619775e+03 4.91615674e+03 4.91617578e+03 4.91616211e+03 4.91630225e+03 4.91682666e+03 4.91634424e+03 4.91628174e+03 4.91631055e+03 4.91622021e+03 4.91645605e+03 4.91619775e+03 4.91615137e+03 4.91622461e+03 4.91630322e+03 4.91623975e+03 4.91615625e+03 4.91620752e+03 4.91630908e+03 4.91636084e+03 4.91625488e+03 4.91615137e+03 4.91616748e+03 4.91617334e+03 4.91624951e+03 4.91644238e+03 4.91644434e+03 4.91623145e+03 4.91622559e+03 4.91699121e+03 4.91765918e+03 4.91720361e+03 4.91638623e+03 4.91636963e+03 4.91659766e+03 4.91635254e+03 4.91620361e+03 4.91630225e+03 4.91617432e+03 4.91626904e+03 4.91625391e+03 4.91617920e+03 4.91625879e+03 4.91625635e+03 4.91627051e+03 4.91620996e+03 4.91616455e+03 4.91618408e+03 4.91619531e+03 4.91618701e+03 4.91621826e+03 4.91627100e+03 4.91633301e+03 4.91632373e+03 4.91648438e+03 4.91654248e+03 4.91629150e+03 4.91618555e+03 4.91616455e+03 4.91641650e+03 4.91648682e+03 4.91641260e+03 4.91666357e+03 4.91779248e+03 4.91854150e+03 4.91782373e+03 4.91653906e+03 4.91634863e+03 4.91644922e+03 4.91657129e+03 4.91626318e+03 4.91618066e+03 4.91616748e+03 4.91620898e+03 4.91618311e+03 4.91619824e+03 4.91618799e+03 4.91620996e+03 4.91619971e+03 4.91637744e+03 4.91665674e+03 4.91635840e+03 4.91618652e+03 4.91637402e+03 4.91668701e+03 4.91633057e+03 4.91628174e+03 4.91669824e+03 4.91661523e+03 4.91646533e+03 4.91633643e+03 4.91632324e+03 4.91629785e+03 4.91635938e+03 4.91620947e+03 4.91613916e+03 4.91615430e+03 4.91625879e+03 4.91619287e+03 4.91634082e+03 4.91697510e+03 4.91717334e+03 4.91693555e+03 4.91655713e+03 4.91628271e+03 4.91621387e+03 4.91619189e+03 4.91617041e+03 4.91616992e+03 4.91616699e+03 4.91619287e+03 4.91618164e+03 4.91618701e+03 4.91620215e+03 4.91617139e+03 4.91617578e+03 4.91616309e+03 4.91632031e+03 4.91680127e+03 4.91686426e+03 4.91647705e+03 4.91620703e+03 4.91624170e+03 4.91621484e+03 4.91625879e+03 4.91625879e+03 4.91625244e+03 4.91622656e+03 4.91638770e+03 4.91687598e+03 4.91664014e+03 4.91623682e+03 4.91618994e+03 4.91681006e+03 4.91770508e+03 4.91708447e+03 4.91625439e+03 4.91627490e+03 4.91662646e+03 4.91661914e+03 4.91635547e+03 4.91620459e+03 4.91634961e+03 4.91664062e+03 4.91699756e+03 4.91701855e+03 4.91644043e+03 4.91623975e+03 4.91628027e+03 4.91723340e+03 4.91792578e+03 4.91690576e+03 4.91623779e+03 4.91629639e+03 4.91689453e+03 4.91704053e+03 4.91662256e+03 4.91630371e+03 4.91651709e+03 4.91692188e+03 4.91716699e+03 4.91686084e+03 4.91642090e+03 4.91626465e+03 4.91653662e+03 4.91715479e+03 4.91735693e+03 4.91692432e+03 4.91632031e+03 4.91653271e+03 4.91675098e+03 4.91682764e+03 4.91641064e+03 4.91642334e+03 4.91695605e+03 4.91690771e+03 4.91642725e+03 4.91616455e+03 4.91617236e+03 4.91617969e+03 4.91622607e+03 4.91657324e+03 4.91680176e+03 4.91656152e+03 4.91620605e+03 4.91607031e+03 4.91605518e+03 4.91619873e+03 4.91670898e+03 4.91691504e+03 4.91957471e+03 4.92120020e+03 4.93379102e+03 4.92065527e+03 6.51463818e+03 6.05650879e+03 6.22585352e+03 6.59243994e+03 9.70189453e+03 2.51862461e+04 4.17940781e+04 2.21669724e+10 4.60260045e+09 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. 4.09971507e+10 1.53690358e+10 6.98392422e+04 3.15821367e+04 1.98365762e+04 4.98782617e+03 2.92474219e+03 2.10947583e+03 2.10899536e+03 2.10918750e+03 2.10976562e+03 2.11323584e+03 2.10910278e+03 2.86504785e+03 4.69496387e+03 1.96057637e+04 5.45093457e+03 3.19250122e+03 2.15800439e+03 2.13162231e+03 2.11665625e+03 2.10906860e+03 2.10911182e+03 2.10916357e+03 2.10899365e+03 2.10902979e+03 2.10906909e+03 2.10896362e+03 2.10901050e+03 2.10898047e+03 2.10926123e+03 2.11003223e+03 2.11023877e+03 2.10940796e+03 2.10895703e+03 2.10905054e+03 2.10901294e+03 2.10902197e+03 2.10904468e+03 2.10903833e+03 2.10899487e+03 2.10934912e+03 2.10926318e+03 2.10897559e+03 2.10897632e+03 2.10897070e+03 2.10897827e+03 2.10896899e+03 2.10903052e+03 2.10903491e+03 2.10906592e+03 2.10897974e+03 2.10898486e+03 2.10917725e+03 2.10942285e+03 2.10898730e+03 2.10933447e+03 2.10972974e+03 2.10920459e+03 2.10900635e+03 2.10902759e+03 2.10897290e+03 2.10907666e+03 2.10899585e+03 2.10897168e+03 2.10896460e+03 2.10909009e+03 2.10919653e+03 2.10897510e+03 2.10912817e+03 2.10903638e+03 2.10897778e+03 2.10896216e+03 2.10895898e+03 2.10896387e+03 2.10898926e+03 2.10895898e+03 2.10902979e+03 2.10932227e+03 2.10938354e+03 2.10906055e+03 2.10899121e+03 2.10928320e+03 2.10932349e+03 2.10899658e+03 2.10895679e+03 2.10895728e+03 2.10904272e+03 2.10955078e+03 2.10959131e+03 2.10898926e+03 2.10922437e+03 2.10928296e+03 2.10896069e+03 2.10929370e+03 2.10944922e+03 2.10940039e+03 2.10934741e+03 2.10932007e+03 2.10919995e+03 2.10900073e+03 2.10895972e+03 2.10896313e+03 2.10905835e+03 2.10915649e+03 2.10897827e+03 2.10904443e+03 2.10917188e+03 2.10913135e+03 2.10896313e+03 2.10904712e+03 2.10899609e+03 2.10899536e+03 2.10909497e+03 2.10935254e+03 2.10915186e+03 2.10896045e+03 2.10897900e+03 2.10904199e+03 2.10955591e+03 2.10976221e+03 2.10919751e+03 2.10896851e+03 2.10904395e+03 2.10912817e+03 2.10899658e+03 2.10896729e+03 2.10896191e+03 2.10905664e+03 2.10939722e+03 2.10962500e+03 2.10925659e+03 2.10897559e+03 2.10896997e+03 2.10896582e+03 2.10899951e+03 2.10908130e+03 2.10909741e+03 2.10915234e+03 2.10941333e+03 2.10941895e+03 2.10904517e+03 2.10911499e+03 2.10947461e+03 2.10921680e+03 2.10899048e+03 2.10896338e+03 2.10896509e+03 2.10897778e+03 2.10896118e+03 2.10897412e+03 2.10907666e+03 2.10918311e+03 2.10910303e+03 2.10896460e+03 2.10903052e+03 2.10896655e+03 2.10905200e+03 2.10902124e+03 2.10896313e+03 2.10905200e+03 2.10896191e+03 2.10914746e+03 2.10905566e+03 2.10897534e+03 2.10896436e+03 2.10919531e+03 2.10994189e+03 2.11044214e+03 2.10933228e+03 2.10899829e+03 2.10915894e+03 2.10913525e+03 2.10911914e+03 2.10912915e+03 2.10898511e+03 2.10909009e+03 2.10939453e+03 2.10903345e+03 2.10899561e+03 2.10913403e+03 2.10897461e+03 2.10902295e+03 2.10908569e+03 2.10904663e+03 2.10912036e+03 2.10924707e+03 2.10940259e+03 2.10911377e+03 2.10901343e+03 2.10898071e+03 2.10911938e+03 2.10946240e+03 2.10955249e+03 2.10900342e+03 2.10918555e+03 2.10936328e+03 2.10912573e+03 2.10909546e+03 2.10914795e+03 2.10909229e+03 2.10897412e+03 2.10905200e+03 2.10896021e+03 2.10929541e+03 2.10956934e+03 2.10913086e+03 2.10897925e+03 2.10896753e+03 2.10896582e+03 2.10896460e+03 2.10897290e+03 2.10905322e+03 2.10895898e+03 2.10907715e+03 2.10924097e+03 2.10901514e+03 2.10904883e+03 2.10910815e+03 2.10895630e+03 2.10906763e+03 2.10909668e+03 2.10900195e+03 2.10904614e+03 2.10909888e+03 2.10913452e+03 2.10916382e+03 2.10905151e+03 2.10904102e+03 2.10904224e+03 2.10925903e+03 2.10928784e+03 2.10916870e+03 2.10906567e+03 2.10896875e+03 2.10899390e+03 2.10910547e+03 2.10900415e+03 2.10895703e+03 2.10904395e+03 2.10922559e+03 2.10897217e+03 2.10905054e+03 2.10903882e+03 2.10898682e+03 2.10910229e+03 2.10899683e+03 2.10896118e+03 2.10898169e+03 2.10903125e+03 2.10898804e+03 2.10900952e+03 2.10909375e+03 2.10901929e+03 2.10905249e+03 2.10897974e+03 2.10896362e+03 2.10904272e+03 2.10896436e+03 2.10897314e+03 2.10901978e+03 2.10915869e+03 2.10923853e+03 2.10916895e+03 2.10896680e+03 2.10916064e+03 2.10901099e+03 2.10916846e+03 2.10948633e+03 2.10913647e+03 2.10902905e+03 2.10906909e+03 2.10923706e+03 2.10899731e+03 2.10896216e+03 2.10898706e+03 2.10897754e+03 2.10898462e+03 2.10897314e+03 2.10898950e+03 2.10898022e+03 2.10896851e+03 2.10909937e+03 2.10901709e+03 2.10908838e+03 2.10935229e+03 2.10932007e+03 2.10900049e+03 2.10899756e+03 2.10896997e+03 2.10897510e+03 2.10896582e+03 2.10906104e+03 2.10899683e+03 2.10896606e+03 2.10896753e+03 2.10898975e+03 2.10907324e+03 2.10899902e+03 2.10899976e+03 2.10897363e+03 2.10896948e+03 2.10900317e+03 2.10910107e+03 2.10904468e+03 2.10898096e+03 2.10896606e+03 2.10900537e+03 2.10910107e+03 2.10927588e+03 2.10948657e+03 2.10936377e+03 2.10916382e+03 2.10907104e+03 2.10927368e+03 2.10955078e+03 2.10922974e+03 2.10896045e+03 2.10897144e+03 2.10897803e+03 2.10907275e+03 2.10896411e+03 2.10908398e+03 2.10903052e+03 2.10896240e+03 2.10903979e+03 2.10910303e+03 2.10927319e+03 2.10932666e+03 2.10921191e+03 2.10915063e+03 2.10912451e+03 2.10916455e+03 2.10909448e+03 2.10920410e+03 2.10945386e+03 2.10930029e+03 2.10898340e+03 2.10897339e+03 2.10896362e+03 2.10896851e+03 2.10903735e+03 2.10919287e+03 2.10899512e+03 2.10896680e+03 2.10896851e+03 2.10898389e+03 2.10895654e+03 2.10896313e+03 2.10897705e+03 2.10897656e+03 2.10896509e+03 2.10914282e+03 2.10921533e+03 2.10907520e+03 2.10896582e+03 2.10898218e+03 2.10896558e+03 2.10898242e+03 2.10903931e+03 2.10935718e+03 2.10930444e+03 2.10897485e+03 2.10943799e+03 2.10982324e+03 2.10926880e+03 2.10911328e+03 2.10917627e+03 2.10915625e+03 2.10929468e+03 2.10908276e+03 2.10903857e+03 2.10897754e+03 2.10901514e+03 2.10959668e+03 2.10986523e+03 2.10961523e+03 2.10897339e+03 2.10922974e+03 2.10898047e+03 2.10908423e+03 2.10926782e+03 2.10896411e+03 2.10937451e+03 2.10916479e+03 2.10905176e+03 2.10896582e+03 2.10899609e+03 2.10902710e+03 2.10915210e+03 2.10903711e+03 2.10899854e+03 2.10895703e+03 2.10896753e+03 2.10905737e+03 2.10929199e+03 2.10963599e+03 2.10933691e+03 2.10897070e+03 2.10897559e+03 2.10897998e+03 2.10897314e+03 2.10926050e+03 2.10918530e+03 2.10912964e+03 2.10981665e+03 2.10976294e+03 2.10908569e+03 2.10896924e+03 2.10896948e+03 2.10896606e+03 2.10897705e+03 2.10907397e+03 2.10910718e+03 2.10930103e+03 2.10917725e+03 2.10927515e+03 2.10925024e+03 2.10911060e+03 2.10901025e+03 2.10902905e+03 2.10903931e+03 2.10897314e+03 2.10896582e+03 2.10932031e+03 2.10952002e+03 2.10946143e+03 2.10895166e+03 2.10925146e+03 2.10919385e+03 2.10897607e+03 2.10925293e+03 2.10900659e+03 2.10912891e+03 2.10924390e+03 2.10906299e+03 2.10896777e+03 2.10897314e+03 2.10898218e+03 2.10902368e+03 2.10897437e+03 2.10895996e+03 2.10897583e+03 2.10897241e+03 2.10929248e+03 2.10967822e+03 2.10948071e+03 2.10897705e+03 2.10906299e+03 2.10897827e+03 2.10911597e+03 2.10926562e+03 2.10897046e+03 2.10911963e+03 2.10910181e+03 2.10897314e+03 2.10901050e+03 2.10897510e+03 2.10897266e+03 2.10895898e+03 2.10902002e+03 2.10909570e+03 2.10915381e+03 2.10904346e+03 2.10912646e+03 2.10904980e+03 2.10904565e+03 2.10900269e+03 2.10896899e+03 2.10910107e+03 2.10897681e+03 2.10896777e+03 2.10921118e+03 2.10907129e+03 2.10903198e+03 2.10941455e+03 2.10943726e+03 2.10895898e+03 2.10911987e+03 2.10917261e+03 2.10900391e+03 2.10902246e+03 2.10905640e+03 2.10896338e+03 2.10898755e+03 2.10905127e+03 2.10896851e+03 2.10910962e+03 2.10947070e+03 2.10940234e+03 2.10895190e+03 2.10909912e+03 2.10917065e+03 2.10905786e+03 2.10901587e+03 2.10930933e+03 2.10927759e+03 2.10895972e+03 2.10921777e+03 2.10903003e+03 2.10903125e+03 2.10929834e+03 2.10898779e+03 2.10919482e+03 2.10924438e+03 2.10899268e+03 2.10908838e+03 2.10938550e+03 2.10926440e+03 2.10914087e+03 2.10898242e+03 2.10896167e+03 2.10896094e+03 2.10896484e+03 2.10908325e+03 2.10902539e+03 2.10897095e+03 2.10895190e+03 2.10905176e+03 2.10895947e+03 2.10896362e+03 2.10896387e+03 2.10915771e+03 2.10920215e+03 2.10904736e+03 2.10940552e+03 2.10935498e+03 2.10896289e+03 2.10925415e+03 2.10927295e+03 2.10902808e+03 2.10899951e+03 2.10916992e+03 2.10911963e+03 2.10902979e+03 2.10895654e+03 2.10895996e+03 2.10896045e+03 2.10896338e+03 2.10897241e+03 2.10908765e+03 2.10917871e+03 2.10915894e+03 2.10903101e+03 2.10897852e+03 2.10899634e+03 2.10896753e+03 2.10933179e+03 2.10961523e+03 2.10935400e+03 2.10899902e+03 2.10896729e+03 2.10897949e+03 2.10937744e+03 2.10963403e+03 2.10932837e+03 2.10899658e+03 2.10895410e+03 2.10895972e+03 2.10896582e+03 2.10896777e+03 2.10896362e+03 2.10897925e+03 2.10905615e+03 2.10923804e+03 2.10902905e+03 2.10900415e+03 2.10920874e+03 2.10901318e+03 2.10906519e+03 2.10934326e+03 2.10919678e+03 2.10895728e+03 2.10917676e+03 2.10900122e+03 2.10897144e+03 2.10906372e+03 2.10897485e+03 2.10896167e+03 2.10899536e+03 2.10907007e+03 2.10918042e+03 2.10921313e+03 2.10910229e+03 2.10911108e+03 2.10902808e+03 2.10903345e+03 2.10905640e+03 2.10901343e+03 2.10910400e+03 2.10903320e+03 2.10899194e+03 2.10895312e+03 2.10898413e+03 2.10900146e+03 2.10902856e+03 2.10902734e+03 2.10896143e+03 2.10902344e+03 2.10896729e+03 2.10901953e+03 2.10936035e+03 2.10908862e+03 2.10899561e+03 2.10931982e+03 2.10932544e+03 2.10897705e+03 2.10900635e+03 2.10898145e+03 2.10963208e+03 2.10992407e+03 2.11011035e+03 2.11030664e+03 2.11121704e+03 2.11818457e+03 2.99448413e+03 2.80457227e+03 4.73625000e+03 7.92090332e+03 3.80698829e+09 -5.65081242e+09 4.27043942e+09 -9.59912141e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.11527547e+10 -4.91139113e+10 4.80113516e+04 2.67832891e+04 1.96102637e+04 1.96952129e+04 1.96153340e+04 4.65324561e+03 2.73550171e+03 2.11635278e+03 2.11604858e+03 2.11157886e+03 2.14178345e+03 2.12335205e+03 2.10959253e+03 2.11113696e+03 2.11606372e+03 2.11442871e+03 2.11675098e+03 2.11359155e+03 2.11180566e+03 2.10947021e+03 2.10931885e+03 2.10910889e+03 2.10918188e+03 2.10914160e+03 2.10897437e+03 2.10905811e+03 2.10896265e+03 2.10909912e+03 2.10897754e+03 2.10917285e+03 2.10931885e+03 2.10904639e+03 2.10895654e+03 2.10897803e+03 2.10895532e+03 2.10898438e+03 2.10913037e+03 2.10931738e+03 2.10919165e+03 2.10902686e+03 2.10895898e+03 2.10902124e+03 2.10917993e+03 2.10939795e+03 2.10974268e+03 2.10932837e+03 2.10898096e+03 2.10910693e+03 2.10905762e+03 2.10908081e+03 2.10915161e+03 2.10899487e+03 2.10912061e+03 2.10916724e+03 2.10896167e+03 2.10900415e+03 2.10905078e+03 2.10895532e+03 2.10896021e+03 2.10900391e+03 2.10914624e+03 2.10949902e+03 2.10974731e+03 2.10943555e+03 2.10904565e+03 2.10896265e+03 2.10900391e+03 2.10917529e+03 2.10964771e+03 2.11036279e+03 2.11050732e+03 2.11022583e+03 2.10948853e+03 2.10919116e+03 2.10941113e+03 2.10918066e+03 2.10896606e+03 2.10929199e+03 2.10917969e+03 2.10896631e+03 2.10905151e+03 2.10908130e+03 2.10905835e+03 2.10902417e+03 2.10896118e+03 2.10896118e+03 2.10898608e+03 2.10913013e+03 2.10904150e+03 2.10901685e+03 2.10907983e+03 2.10935278e+03 2.10922852e+03 2.10901587e+03 2.10915674e+03 2.10913867e+03 2.10908179e+03 2.10895386e+03 2.10896631e+03 2.10915942e+03 2.10920044e+03 2.10899463e+03 2.10920288e+03 2.10937305e+03 2.10899170e+03 2.10898096e+03 2.10913599e+03 2.10915356e+03 2.10921997e+03 2.10928345e+03 2.10912231e+03 2.10915747e+03 2.10921948e+03 2.10922461e+03 2.10903003e+03 2.10896411e+03 2.10896191e+03 2.10896216e+03 2.10894995e+03 2.10904517e+03 2.10906470e+03 2.10896973e+03 2.10927075e+03 2.10929858e+03 2.10897656e+03 2.10911279e+03 2.10896704e+03 2.10919971e+03 2.10926392e+03 2.10896191e+03 2.10899048e+03 2.10904761e+03 2.10902271e+03 2.10896777e+03 2.10901196e+03 2.10911816e+03 2.10897656e+03 2.10907056e+03 2.10900635e+03 2.10896899e+03 2.10914868e+03 2.10900464e+03 2.10896680e+03 2.10898193e+03 2.10905664e+03 2.10907373e+03 2.10911230e+03 2.10903052e+03 2.10901660e+03 2.10921289e+03 2.10928223e+03 2.10909277e+03 2.10901929e+03 2.10948291e+03 2.10926709e+03 2.10901416e+03 2.10900342e+03 2.10902173e+03 2.10904761e+03 2.10916333e+03 2.10931567e+03 2.10918359e+03 2.10911182e+03 2.10908789e+03 2.10921021e+03 2.10903613e+03 2.10897412e+03 2.10921094e+03 2.10926782e+03 2.10897119e+03 2109. 2.10896362e+03 2.10914209e+03 2.10905151e+03 2.10898755e+03 2.10901514e+03 2.10904736e+03 2.10902759e+03 2.10899341e+03 2.10896680e+03 2.10897363e+03 2.10897339e+03 2.10904199e+03 2.10898608e+03 2.10898755e+03 2.10903467e+03 2.10933301e+03 2.10986938e+03 2.11016577e+03 2.11045410e+03 2.10942334e+03 2.10902979e+03 2.10896436e+03 2.10897119e+03 2.10908252e+03 2.10906201e+03 2.10897290e+03 2.10916870e+03 2.10925732e+03 2.10897290e+03 2.10921729e+03 2.10959521e+03 2.10928027e+03 2.10928638e+03 2.10932031e+03 2.10930298e+03 2.10923901e+03 2.10935767e+03 2.10935791e+03 2.10916211e+03 2.10897290e+03 2.10898950e+03 2.10896655e+03 2.10896265e+03 2.10909180e+03 2.10949658e+03 2.10941699e+03 2.10904175e+03 2.10897607e+03 2.10898242e+03 2.10898975e+03 2.10908252e+03 2.10932202e+03 2.10944604e+03 2.10910132e+03 2.10897876e+03 2.10917578e+03 2.10923926e+03 2.10898657e+03 2.10901050e+03 2.10904370e+03 2.10896631e+03 2.10898755e+03 2.10895947e+03 2.10896411e+03 2.10896460e+03 2.10896533e+03 2.10895825e+03 2.10896265e+03 2.10897363e+03 2.10896704e+03 2.10896655e+03 2.10896606e+03 2.10900415e+03 2.10903735e+03 2.10898950e+03 2.10896826e+03 2.10896777e+03 2.10897363e+03 2.10896338e+03 2.10896411e+03 2.10903735e+03 2.10912866e+03 2.10912280e+03 2.10900928e+03 2.10896216e+03 2.10896094e+03 2.10896289e+03 2.10896167e+03 2.10897217e+03 2.10897485e+03 2.10897656e+03 2.10897583e+03 2.10896460e+03 2.10896460e+03 2.10895239e+03 2.10896802e+03 2.10897656e+03 2.10898706e+03 2.10899365e+03 2.10898267e+03 2.10896753e+03 2.10897705e+03 2.10900562e+03 2.10901465e+03 2.10897534e+03 2.10897778e+03 2.10898633e+03 2.10898413e+03 2.10896582e+03 2.10896362e+03 2.10899512e+03 2.10902515e+03 2.10900781e+03 2.10900977e+03 2.10906421e+03 2.10905176e+03 2.10899561e+03 2.10896558e+03 2.10896753e+03 2.10896680e+03 2.10896753e+03 2.10896118e+03 2.10897046e+03 2.10896777e+03 2.10900537e+03 2.10900293e+03 2.10897119e+03 2.10896826e+03 2.10896680e+03 2.10895654e+03 2.10895996e+03 2.10896802e+03 2.10897095e+03 2.10896851e+03 2.10897241e+03 2.10895898e+03 2.10896997e+03 2.10901538e+03 2.10899878e+03 2.10897095e+03 2.10896997e+03 2.10896851e+03 2.10897363e+03 2.10897949e+03 2.10896680e+03 2.10897388e+03 2.10896851e+03 2.10897925e+03 2.10896289e+03 2.10898804e+03 2.10899414e+03 2.10896753e+03 2.10898511e+03 2.10900464e+03 2.10900073e+03 2.10897559e+03 2.10896313e+03 2.10904395e+03 2.10908569e+03 2.10900708e+03 2.10896631e+03 2.10896338e+03 2.10896143e+03 2.10896094e+03 2.10895996e+03 2.10895068e+03 2.10895898e+03 2.10895093e+03 2.10896289e+03 2.10896094e+03 2.10896509e+03 2.10899731e+03 2.10905444e+03 2.10906104e+03 2.10909253e+03 2.10902856e+03 2.10900195e+03 2.10897876e+03 2.10900342e+03 2.10896118e+03 2.10896460e+03 2.10897754e+03 2.10896411e+03 2.10896802e+03 2.10897437e+03 2.10896973e+03 2.10897534e+03 2.10896216e+03 2.10896753e+03 2.10899316e+03 2.10913135e+03 2.10896997e+03 2.10904663e+03 2.10915454e+03 2.10899463e+03 2.10898047e+03 2.10897241e+03 2.10896484e+03 2.10896973e+03 2.10896362e+03 2.10896094e+03 2.10896460e+03 2.10896851e+03 2.10898730e+03 2.10898193e+03 2.10896851e+03 2.10903076e+03 2.10897388e+03 2.10896069e+03 2.10900317e+03 2.10898584e+03 2.10899341e+03 2.10902637e+03 2.10912500e+03 2.10920923e+03 2.10910352e+03 2.10898413e+03 2.10896436e+03 2.10896948e+03 2.10896948e+03 2.10897021e+03 2.10896899e+03 2.10896558e+03 2.10896533e+03 2.10898804e+03 2.10897656e+03 2.10900195e+03 2.10897437e+03 2.10897559e+03 2.10897119e+03 2.10896045e+03 2.10900635e+03 2.10928638e+03 2.10942114e+03 2.10927197e+03 2.10905688e+03 2.10898706e+03 2.10897217e+03 2.10896411e+03 2.10897485e+03 2.10899902e+03 2.10902393e+03 2.10901440e+03 2.10897754e+03 2.10896289e+03 2.10898633e+03 2.10908325e+03 2.10915161e+03 2.10908325e+03 2.10900220e+03 2.10898193e+03 2.10896411e+03 2.10896240e+03 2.10899146e+03 2.10896973e+03 2.10896924e+03 2.10896265e+03 2.10896167e+03 2.10897144e+03 2.10896826e+03 2.10898071e+03 2.10898730e+03 2.10897046e+03 2.10895996e+03 2.10896509e+03 2.10896704e+03 2.10897754e+03 2.10898193e+03 2.10897290e+03 2.10896777e+03 2.10898071e+03 2.10898120e+03 2.10897583e+03 2.10900757e+03 2.11026562e+03 2.10984033e+03 2.11385059e+03 2.11043164e+03 2.59399927e+03 3.36342480e+03 4.93143848e+03 4.92911133e+03 4.94744971e+03 7.42305078e+03 1.60267363e+04 5.96207309e+09 1542015488. 2.63869722e+09 9.91550054e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.48008294e+09 1.58701445e+10 6.24025430e+04 2.98334961e+04 1.97320762e+04 1.96421133e+04 1.96088613e+04 1.96056426e+04 1.96037109e+04 1.96031758e+04 1.96030273e+04 1.96038535e+04 1.96044668e+04 1.96033008e+04 1.96032305e+04 1.96031914e+04 1.96033828e+04 1.96032969e+04 5.46874463e+03 3.10371582e+03 2.12382446e+03 2.11029492e+03 2.10952930e+03 2.10922290e+03 2.10919702e+03 2.10907690e+03 2.10897314e+03 2.10897095e+03 2.10900610e+03 2.10900439e+03 2.10898315e+03 2.10896558e+03 2.10896631e+03 2.10898804e+03 2.10901758e+03 2.10901953e+03 2.10898511e+03 2.10897583e+03 2.10896704e+03 2.10898071e+03 2.10896973e+03 2.10896289e+03 2.10896045e+03 2.10896729e+03 2.10899731e+03 2.10904272e+03 2.10909717e+03 2.10904688e+03 2.10907446e+03 2.10909131e+03 2.10909253e+03 2.10901440e+03 2.10897705e+03 2.10898779e+03 2.10900879e+03 2.10898657e+03 2.10897607e+03 2.10896069e+03 2.10897485e+03 2.10897998e+03 2.10896948e+03 2.10896948e+03 2.10896240e+03 2.10904565e+03 2.10908472e+03 2.10910181e+03 2.10907227e+03 2.10919360e+03 2.10921948e+03 2.10910156e+03 2.10900439e+03 2.10896362e+03 2.10897559e+03 2.10899048e+03 2.10903320e+03 2.10913647e+03 2.10922217e+03 2.10918774e+03 2.10904126e+03 2.10896216e+03 2.10895801e+03 2.10896045e+03 2.10896777e+03 2.10898364e+03 2.10907495e+03 2.10927368e+03 2.10941089e+03 2.10929810e+03 2.10913428e+03 2.10899243e+03 2.10898853e+03 2.10899585e+03 2.10915771e+03 2.10933765e+03 2.10926807e+03 2.10904297e+03 2.10896240e+03 2.10896948e+03 2.10898926e+03 2.10902197e+03 2.10906421e+03 2.10897290e+03 2.10898413e+03 2.10902319e+03 2.10897388e+03 2.10896851e+03 2.10896973e+03 2.10896387e+03 2.10900781e+03 2.10909521e+03 2.10924756e+03 2.10918018e+03 2.10902881e+03 2.10896338e+03 2.10905322e+03 2.10906104e+03 2.10900415e+03 2.10896411e+03 2.10896484e+03 2.10898511e+03 2.10899585e+03 2.10898145e+03 2.10897852e+03 2.10896826e+03 2.10896997e+03 2.10896191e+03 2.10896582e+03 2.10895557e+03 2.10901587e+03 2.10925049e+03 2.10928687e+03 2.10907300e+03 2.10897119e+03 2.10903442e+03 2.10917993e+03 2.10934717e+03 2.10935571e+03 2.10919849e+03 2.10902319e+03 2.10896240e+03 2.10896460e+03 2.10896606e+03 2.10896704e+03 2.10896729e+03 2.10897632e+03 2.10899683e+03 2.10898633e+03 2.10895898e+03 2.10895581e+03 2.10896313e+03 2.10895728e+03 2.10895020e+03 2.10897290e+03 2.10907275e+03 2.10929736e+03 2.10927466e+03 2.10906616e+03 2.10896045e+03 2.10902002e+03 2.10920703e+03 2.10938574e+03 2.10941919e+03 2.10940649e+03 2.10946338e+03 2.10920361e+03 2.10909497e+03 2.10898462e+03 2.10897803e+03 2.10895776e+03 2.10895410e+03 2.10896021e+03 2.10896411e+03 2.10898022e+03 2.10897900e+03 2.10898413e+03 2.10896191e+03 2.10901050e+03 2.10918628e+03 2.10913403e+03 2.10897217e+03 2.10897437e+03 2.10898096e+03 2.10897705e+03 2.10896533e+03 2.10896240e+03 2.10895435e+03 2.10907251e+03 2.10909937e+03 2.10900659e+03 2.10895972e+03 2.10896558e+03 2.10895923e+03 2.10896753e+03 2.10896118e+03 2.10896924e+03 2.10896460e+03 2.10899487e+03 2.10903027e+03 2.10902881e+03 2.10900244e+03 2.10897974e+03 2.10896191e+03 2.10899536e+03 2.10898486e+03 2.10896729e+03 2.10899512e+03 2.10895312e+03 2.10896167e+03 2.10896338e+03 2.10896362e+03 2.10895630e+03 2.10895020e+03 2.10896265e+03 2.10896045e+03 2.10895947e+03 2.10897046e+03 2.10896826e+03 2.10896411e+03 2.10896631e+03 2.10895532e+03 2.10895532e+03 2.10896582e+03 2.10896436e+03 2.10895337e+03 2.10895386e+03 2.10895483e+03 2.10899146e+03 2.10902319e+03 2.10902490e+03 2.10899658e+03 2.10896606e+03 2.10897314e+03 2.10896655e+03 2.10899683e+03 2.10900732e+03 2.10901636e+03 2.10898828e+03 2.10897192e+03 2.10898804e+03 2.10898779e+03 2.10896924e+03 2.10895117e+03 2.10897266e+03 2.10896899e+03 2.10897607e+03 2.10908325e+03 2.10912549e+03 2.10898804e+03 2.10901880e+03 2.10923682e+03 2.10921509e+03 2.10902759e+03 2.10896265e+03 2.10903149e+03 2.10917505e+03 2.10917114e+03 2.10899438e+03 2.10895776e+03 2.10895361e+03 2.10895752e+03 2.10895264e+03 2.10895532e+03 2.10895996e+03 2.10896216e+03 2.10896973e+03 2.10896533e+03 2.10898071e+03 2.10895630e+03 2.10896436e+03 2.10898999e+03 2.10896313e+03 2.10898779e+03 2.10904175e+03 2.10903394e+03 2.10902881e+03 2.10898755e+03 2.10898682e+03 2.10896973e+03 2.10903418e+03 2.10910352e+03 2.10906396e+03 2.10897461e+03 2.10896338e+03 2.10895679e+03 2.10895801e+03 2.10896118e+03 2.10896851e+03 2.10895605e+03 2.10902417e+03 2.10902881e+03 2.10897095e+03 2.10896655e+03 2.10896533e+03 2.10896289e+03 2.10896021e+03 2.10895728e+03 2.10903564e+03 2.10918555e+03 2.10915698e+03 2.10903760e+03 2.10895972e+03 2.10896313e+03 2.10896387e+03 2.10896851e+03 2.10896240e+03 2.10899805e+03 2.10914624e+03 2.10920508e+03 2.10910718e+03 2.10896826e+03 2.10897241e+03 2.10896265e+03 2.10897754e+03 2.10895728e+03 2.10896069e+03 2.10896387e+03 2.10898755e+03 2.10896704e+03 2.10895581e+03 2.10896069e+03 2.10896167e+03 2.10895605e+03 2.10896216e+03 2.10896118e+03 2.10896313e+03 2.10895898e+03 2.10898291e+03 2.10913525e+03 2.10931152e+03 2.10940137e+03 2.10934033e+03 2.10932495e+03 2.10907568e+03 2.10900781e+03 2.10896313e+03 2.10896094e+03 2.10895947e+03 2.10896484e+03 2.10904272e+03 2.10903125e+03 2.10899487e+03 2.10897876e+03 2.10904761e+03 2.10906006e+03 2.10901367e+03 2.10896289e+03 2.10896973e+03 2.10899707e+03 2.10906689e+03 2.10914893e+03 2.10907495e+03 2.10897534e+03 2.10899365e+03 2.10896069e+03 2.10896826e+03 2.10899780e+03 2.10899902e+03 2.10898706e+03 2.10897632e+03 2.10896313e+03 2.10897681e+03 2.10897803e+03 2.10897021e+03 2.10896582e+03 2.10897534e+03 2.10898682e+03 2.10897949e+03 2.10896509e+03 2.10895459e+03 2.10897241e+03 2.10896802e+03 2.10907544e+03 2.10927808e+03 2.10915576e+03 2.10896460e+03 2.10896436e+03 2.10900073e+03 2.10914258e+03 2.10903784e+03 2.10896143e+03 2.10901172e+03 2.10916064e+03 2.10921362e+03 2.10907080e+03 2.10899536e+03 2.10898657e+03 2.10900635e+03 2.10907007e+03 2.10908862e+03 2.10900830e+03 2.10895483e+03 2.10895996e+03 2.10896167e+03 2.10897510e+03 2.10897290e+03 2.10898608e+03 2.10901782e+03 2.10913892e+03 2.10900732e+03 2.10899829e+03 2.10898413e+03 2.10898560e+03 2.10917627e+03 2.10902515e+03 2.10896802e+03 2.10898804e+03 2.10901514e+03 2.10897046e+03 2.10897144e+03 2.10903809e+03 2.10901099e+03 2.10899976e+03 2.10896460e+03 2.10906567e+03 2.10901562e+03 2.10897339e+03 2.10898047e+03 2.10901758e+03 2.10906396e+03 2.10896753e+03 2.10898804e+03 2.10897998e+03 2.10896533e+03 2.10900952e+03 2.10915283e+03 2.10904590e+03 2.10895532e+03 2.10901611e+03 2.10897070e+03 2.10896045e+03 2.10895605e+03 2.10896118e+03 2.10896631e+03 2.10898120e+03 2.10897729e+03 2.10896484e+03 2.10896533e+03 2.10899609e+03 2.10915723e+03 2.10915112e+03 2.10903320e+03 2.10908276e+03 2.10938232e+03 2.10921558e+03 2.10896826e+03 2.10905786e+03 2.10904272e+03 2.10897144e+03 2.10898682e+03 2.10901367e+03 2.10897803e+03 2.10896167e+03 2.10898926e+03 2.10897266e+03 2.10896265e+03 2.10896973e+03 2.10899146e+03 2.10899414e+03 2.10897412e+03 2.10897290e+03 2.10896875e+03 2.10897266e+03 2.10896216e+03 2.10901953e+03 2.10898779e+03 2.10897241e+03 2.10898242e+03 2.10895801e+03 2.10895898e+03 2.10900391e+03 2.10898071e+03 2.10906177e+03 2.10962329e+03 2.10967920e+03 2.10930664e+03 2.10921680e+03 2.10931030e+03 2.10924316e+03 2.10905151e+03 2.10898535e+03 2.10900049e+03 2.10899463e+03 2.10899048e+03 2.10904150e+03 2.10904541e+03 2.10896289e+03 2.10897998e+03 2.10895679e+03 2.10902100e+03 2.10901367e+03 2.10895459e+03 2.10896655e+03 2.10910571e+03 2109. 2.10911548e+03 2.10952051e+03 2.10930444e+03 2.10904834e+03 2.10910669e+03 2.10928784e+03 2.10930420e+03 2.10915918e+03 2.10907642e+03 2.10915356e+03 2.10918945e+03 2.10916992e+03 2.10902905e+03 2.10896484e+03 2.10911914e+03 2.10931030e+03 2.10932520e+03 2.10902026e+03 2.10897925e+03 2.10905762e+03 2.10898682e+03 2.10896143e+03 2.10897607e+03 2.10896680e+03 2.10900806e+03 2.10914819e+03 2.10910962e+03 2.10899561e+03 2.10896167e+03 2.10896021e+03 2.10895947e+03 2.10907104e+03 2.10926440e+03 2.10919971e+03 2.10901831e+03 2.10896558e+03 2.10896948e+03 2.10896045e+03 2.10895361e+03 2.10897827e+03 2.10901904e+03 2.10900903e+03 2.10898047e+03 2.10896191e+03 2.10895532e+03 2.10895947e+03 2.10895776e+03 2.10903784e+03 2.10938940e+03 2.10933789e+03 2.10910107e+03 2.10902490e+03 2.10919873e+03 2.10921631e+03 2.10907178e+03 2.10897754e+03 2.10908130e+03 2.10931689e+03 2.10930908e+03 2.10907861e+03 2.10897217e+03 2.10898193e+03 2.10897241e+03 2.10899902e+03 2.10916797e+03 2.10912842e+03 2.10897729e+03 2.10897119e+03 2.10912305e+03 2.10922388e+03 2.10910669e+03 2.10895947e+03 2.10899731e+03 2.10911572e+03 2.10913257e+03 2.10897876e+03 2.10898486e+03 2.10895312e+03 2.10902856e+03 2.10909717e+03 2.10910522e+03 2.10902319e+03 2.10899927e+03 2.10905005e+03 2.10907251e+03 2.10923853e+03 2.10928857e+03 2.10925073e+03 2.10910278e+03 2.10899487e+03 2.10898926e+03 2.10896826e+03 2.10897412e+03 2.10897266e+03 2.10898169e+03 2.10899097e+03 2.10899927e+03 2.10898926e+03 2.10897852e+03 2.10899487e+03 2.10902002e+03 2.10896362e+03 2.10912256e+03 2.10924268e+03 2.10948901e+03 2.11066260e+03 2.11402368e+03 2.11509009e+03 2.16416235e+03 2.13865820e+03 2.12912671e+03 2.14308350e+03 2.15276831e+03 2.82113281e+03 4.82769727e+03 -3.09167744e+09 63040100. 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. 3.02280031e+05 1.24388306e+03 7.98168579e+02 7.94627136e+02 7.88628906e+02 7.82773071e+02 7.79789246e+02 7.76729065e+02 7.76784485e+02 7.76886597e+02 7.76751709e+02 7.76700928e+02 7.76721802e+02 7.79799988e+02 7.83501648e+02 7.87127014e+02 7.84098511e+02 7.82006042e+02 7.77699524e+02 7.76950684e+02 7.76695129e+02 7.76764221e+02 7.76714172e+02 7.76704407e+02 7.76695312e+02 7.76693054e+02 7.76733887e+02 7.76897705e+02 7.76915222e+02 7.76740112e+02 7.76694946e+02 7.76687805e+02 7.76693298e+02 7.76685852e+02 7.76724915e+02 7.76727783e+02 7.76719971e+02 7.76693420e+02 7.76706848e+02 7.76760132e+02 7.76796692e+02 7.76687134e+02 7.76833313e+02 7.76969299e+02 7.76781128e+02 7.76720825e+02 7.76729675e+02 7.76695496e+02 7.76694153e+02 7.76701111e+02 7.76694580e+02 7.76756958e+02 7.76841492e+02 7.76728943e+02 7.76705750e+02 7.76856567e+02 7.76821594e+02 7.76764404e+02 7.76720581e+02 7.76691956e+02 7.76701355e+02 7.76734497e+02 7.76696716e+02 7.76713013e+02 7.76805298e+02 7.76806763e+02 7.76691467e+02 7.76741760e+02 7.76809326e+02 7.76855591e+02 7.76756287e+02 7.76752136e+02 7.76707886e+02 7.76717346e+02 7.76835266e+02 7.76857056e+02 7.76711243e+02 7.76701599e+02 7.76723694e+02 7.76697754e+02 7.76714600e+02 7.76740540e+02 7.76768066e+02 7.76752075e+02 7.76719604e+02 7.76706543e+02 7.76693787e+02 7.76691772e+02 7.76695374e+02 7.76717102e+02 7.76787537e+02 7.76744019e+02 7.76691040e+02 7.76746826e+02 7.76754639e+02 7.76704285e+02 7.76763000e+02 7.76710876e+02 7.76696533e+02 7.76728821e+02 7.76779480e+02 7.76694214e+02 7.76748108e+02 7.76821716e+02 7.76708069e+02 7.76740417e+02 7.76851624e+02 7.76773438e+02 7.76728333e+02 7.76691528e+02 7.76698303e+02 7.76694702e+02 7.76696350e+02 7.76694946e+02 7.76729675e+02 7.76872986e+02 7.76924622e+02 7.76731445e+02 7.76708374e+02 7.76758667e+02 7.76708923e+02 7.76709473e+02 7.76743042e+02 7.76744690e+02 7.76745178e+02 7.76733643e+02 7.76697083e+02 7.76705444e+02 7.76835144e+02 7.76861145e+02 7.76751221e+02 7.76695129e+02 7.76688904e+02 7.76700256e+02 7.76730347e+02 7.76722839e+02 7.76705078e+02 7.76694824e+02 7.76696655e+02 7.76692749e+02 7.76703003e+02 7.76693420e+02 7.76695740e+02 7.76695679e+02 7.76691956e+02 7.76713806e+02 7.76728821e+02 7.76689636e+02 7.76738892e+02 7.76701782e+02 7.76696899e+02 7.76688354e+02 7.76711121e+02 7.76758179e+02 7.76759338e+02 7.76703674e+02 7.76871582e+02 7.76818604e+02 7.76692627e+02 7.76774048e+02 7.76778625e+02 7.76720703e+02 7.76736877e+02 7.76732971e+02 7.76690613e+02 7.76778931e+02 7.76808533e+02 7.76699280e+02 7.76697388e+02 7.76784912e+02 7.76892944e+02 7.76823792e+02 7.76794983e+02 7.76742981e+02 7.76703552e+02 7.76698608e+02 7.76689270e+02 7.76743652e+02 7.76797791e+02 7.76805054e+02 7.76714844e+02 7.76701599e+02 7.76710266e+02 7.76692322e+02 7.76691711e+02 7.76692627e+02 7.76690125e+02 7.76720398e+02 7.76750732e+02 7.76691223e+02 7.76813416e+02 7.76901794e+02 7.76739563e+02 7.76691711e+02 7.76783630e+02 7.76897278e+02 7.76813171e+02 7.76740479e+02 7.76701050e+02 7.76718689e+02 7.76865601e+02 7.76893494e+02 7.76695923e+02 7.76776306e+02 7.76938171e+02 7.76797119e+02 7.76693115e+02 7.76753845e+02 7.76719299e+02 7.76691345e+02 7.76691467e+02 7.76691467e+02 7.76693542e+02 7.76689087e+02 7.76691284e+02 7.76692200e+02 7.76700928e+02 7.76730347e+02 7.76727173e+02 7.76684204e+02 7.76737488e+02 7.76761230e+02 7.76757690e+02 7.76700745e+02 7.76693970e+02 7.76709839e+02 7.76710999e+02 7.76699341e+02 7.76756165e+02 7.76744080e+02 7.76691650e+02 7.76694214e+02 7.76727173e+02 7.76805176e+02 7.76694946e+02 7.76754395e+02 7.76822815e+02 7.76687988e+02 7.76719910e+02 7.76717102e+02 7.76739319e+02 7.76686707e+02 7.76718018e+02 7.76815491e+02 7.76696777e+02 7.76727051e+02 7.76723511e+02 7.76702026e+02 7.76713196e+02 7.76852417e+02 7.76831421e+02 7.76702148e+02 7.76688416e+02 7.76739319e+02 7.76771729e+02 7.76700073e+02 7.76693237e+02 7.76698730e+02 7.76724854e+02 7.76696167e+02 7.76709412e+02 7.76710205e+02 7.76692139e+02 7.76735413e+02 7.76718872e+02 7.76727478e+02 7.76696106e+02 7.76706909e+02 7.76715088e+02 7.76697571e+02 7.76704468e+02 7.76749512e+02 7.76709656e+02 7.76688477e+02 7.76697449e+02 7.76713257e+02 7.76780701e+02 7.76743530e+02 7.76691101e+02 7.76693665e+02 7.76696167e+02 7.76701172e+02 7.76689514e+02 7.76692505e+02 7.76689148e+02 7.76704712e+02 7.76766174e+02 7.76775146e+02 7.76694824e+02 7.76770996e+02 7.76796692e+02 7.76743530e+02 7.76705200e+02 7.76702148e+02 7.76698059e+02 7.76721619e+02 7.76781311e+02 7.76780823e+02 7.76737122e+02 7.76700195e+02 7.76740845e+02 7.76792664e+02 7.76716858e+02 7.76707153e+02 7.76720886e+02 7.76697388e+02 7.76763794e+02 7.76717407e+02 7.76719543e+02 7.76758057e+02 7.76774353e+02 7.76770081e+02 7.76790100e+02 7.76885315e+02 7.76917236e+02 7.76853271e+02 7.76891968e+02 7.76925293e+02 7.76864685e+02 7.76739990e+02 7.76713379e+02 7.76759155e+02 7.76740784e+02 7.76688416e+02 7.76731323e+02 7.76732361e+02 7.76714050e+02 7.76734253e+02 7.76770264e+02 7.76705688e+02 7.76694092e+02 7.76719971e+02 7.76704529e+02 7.76715210e+02 7.76760986e+02 7.76766052e+02 7.76761414e+02 7.76814270e+02 7.76891113e+02 7.76863403e+02 7.76711670e+02 7.76704041e+02 7.76716675e+02 7.76736572e+02 7.76711426e+02 7.76715820e+02 7.76855164e+02 7.76831909e+02 7.76702820e+02 7.76713562e+02 7.76767212e+02 7.76697876e+02 7.76691650e+02 7.76715759e+02 7.76751709e+02 7.76745789e+02 7.76695312e+02 7.76718506e+02 7.76770508e+02 7.76703308e+02 7.76793213e+02 7.76869934e+02 7.76744934e+02 7.76759583e+02 7.76872070e+02 7.76698792e+02 7.76689636e+02 7.76688477e+02 7.76775879e+02 7.76871338e+02 7.76749756e+02 7.76731934e+02 7.76693298e+02 7.76701660e+02 7.76708191e+02 7.76703857e+02 7.76714111e+02 7.76728333e+02 7.76715454e+02 7.76689941e+02 7.76702942e+02 7.76694336e+02 7.76713135e+02 7.76795105e+02 7.76729065e+02 7.76704285e+02 7.76765259e+02 7.76698975e+02 7.76780396e+02 7.76874268e+02 7.76701355e+02 7.76732971e+02 7.76812256e+02 7.76709778e+02 7.76734314e+02 7.76744263e+02 7.76752747e+02 7.76696289e+02 7.76701904e+02 7.76726013e+02 7.76742615e+02 7.76689026e+02 7.76686523e+02 7.76698425e+02 7.76691040e+02 7.76692810e+02 7.76700684e+02 7.76737305e+02 7.76784607e+02 7.76720520e+02 7.76731262e+02 7.76777588e+02 7.76723145e+02 7.76740479e+02 7.76859192e+02 7.76765808e+02 7.76712646e+02 7.76689209e+02 7.76717896e+02 7.76773438e+02 7.76745850e+02 7.76710022e+02 7.76692993e+02 7.76691650e+02 7.76689270e+02 7.76692017e+02 7.76744080e+02 7.76785950e+02 7.76740723e+02 7.76687195e+02 7.76772705e+02 7.76703857e+02 7.76709717e+02 7.76819031e+02 7.76749878e+02 7.76695068e+02 7.76736633e+02 7.76703125e+02 7.76735962e+02 7.76793640e+02 7.76685181e+02 7.76806580e+02 7.77086975e+02 7.76912598e+02 7.76707458e+02 7.76695740e+02 7.76733826e+02 7.76714417e+02 7.76690674e+02 7.76700745e+02 7.76698486e+02 7.76713806e+02 7.76752258e+02 7.76776367e+02 7.76722900e+02 7.76687683e+02 7.76687805e+02 7.76699341e+02 7.76794678e+02 7.76788879e+02 7.76700317e+02 7.76692078e+02 7.76747253e+02 7.76702393e+02 7.76687744e+02 7.76687317e+02 7.76684937e+02 7.76688721e+02 7.76737610e+02 7.76744751e+02 7.76744324e+02 7.76705627e+02 7.76702148e+02 7.76714661e+02 7.76697449e+02 7.76702209e+02 7.76711121e+02 7.76697205e+02 7.76697083e+02 7.76687561e+02 7.76705444e+02 7.76689270e+02 7.76689758e+02 7.76690002e+02 7.76731384e+02 7.76937683e+02 7.76956360e+02 7.76862732e+02 7.76699402e+02 7.76743408e+02 7.76695984e+02 7.76706238e+02 7.76870239e+02 7.76917542e+02 7.76773743e+02 7.76701416e+02 7.76734741e+02 7.76764038e+02 7.76713989e+02 7.76685303e+02 7.76701355e+02 7.76692444e+02 7.76735352e+02 7.76779663e+02 7.76764221e+02 7.76693054e+02 7.76759644e+02 7.76787231e+02 7.76692139e+02 7.76723328e+02 7.76686646e+02 7.76768555e+02 7.76840027e+02 7.76721130e+02 7.76702209e+02 7.76695496e+02 7.76708435e+02 7.76691162e+02 7.76695435e+02 7.76709961e+02 7.76700195e+02 7.76717285e+02 7.76766968e+02 7.76717163e+02 7.76700867e+02 7.76692505e+02 7.76697083e+02 7.76693909e+02 7.76702026e+02 7.76693848e+02 7.76710205e+02 7.76727600e+02 7.76728455e+02 7.76707764e+02 7.76745117e+02 7.76751648e+02 7.76717346e+02 7.76720093e+02 7.76715210e+02 7.76715393e+02 7.76702576e+02 7.76738892e+02 7.76742859e+02 7.76718323e+02 7.76693420e+02 7.76692627e+02 7.76691345e+02 7.76684509e+02 7.76689575e+02 7.76704651e+02 7.76739868e+02 7.76692383e+02 7.76704651e+02 7.76721924e+02 7.76692688e+02 7.76715637e+02 7.76773560e+02 7.76790894e+02 7.76692688e+02 7.76774109e+02 7.76779602e+02 7.76712158e+02 7.76697815e+02 7.76696777e+02 7.76726624e+02 7.76717346e+02 7.76703857e+02 7.76686279e+02 7.76694092e+02 7.76698669e+02 7.76702576e+02 7.76696472e+02 7.76695679e+02 7.76694214e+02 7.76689636e+02 7.76700745e+02 7.76716003e+02 7.76748596e+02 7.76700256e+02 7.76694641e+02 7.76691711e+02 7.76694275e+02 7.76692749e+02 7.76735657e+02 7.76883057e+02 7.76724243e+02 7.76689392e+02 7.76774536e+02 7.76789368e+02 7.76728149e+02 7.76722534e+02 7.76697327e+02 7.76693909e+02 7.76708374e+02 7.76711853e+02 7.76778625e+02 7.76723694e+02 7.76709412e+02 7.76699280e+02 7.76691895e+02 7.76705505e+02 7.76695312e+02 7.76724487e+02 7.76828918e+02 7.76788818e+02 7.76700500e+02 7.76715454e+02 7.76720703e+02 7.76768250e+02 7.77310242e+02 7.76840698e+02 7.76892578e+02 7.76750488e+02 7.77075134e+02 7.85127930e+02 9.27592224e+02 1.23264978e+03 3.52910474e+03 7.44111230e+03 3.80698829e+09 -5.65081242e+09 4.27043942e+09 -9.59912141e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.11527547e+10 -4.91139113e+10 2.57073950e+03 1.22091614e+03 7.96203003e+02 7.89952087e+02 7.87460999e+02 7.82815491e+02 7.79264587e+02 7.76883972e+02 7.76917114e+02 7.76734985e+02 7.76707947e+02 7.76691284e+02 7.76697266e+02 7.76700623e+02 7.76697266e+02 7.76689514e+02 7.76703430e+02 7.76786499e+02 7.76744934e+02 7.76688660e+02 7.76688293e+02 7.76686157e+02 7.76713562e+02 7.76697083e+02 7.76691101e+02 7.76704956e+02 7.76724365e+02 7.76700989e+02 7.76695923e+02 7.76699280e+02 7.76778503e+02 7.76712830e+02 7.76698853e+02 7.76791809e+02 7.76734863e+02 7.76727844e+02 7.76893372e+02 7.76982056e+02 7.76723206e+02 7.76690186e+02 7.76706116e+02 7.76754822e+02 7.76800293e+02 7.76693604e+02 7.76737305e+02 7.76758667e+02 7.76693848e+02 7.76752808e+02 7.76864014e+02 7.76883545e+02 7.76839294e+02 7.76706238e+02 7.76691223e+02 7.76706177e+02 7.76684448e+02 7.76757385e+02 7.76721130e+02 7.76694641e+02 7.76697693e+02 7.76716370e+02 7.76984314e+02 7.76898560e+02 7.76702759e+02 7.76817505e+02 7.76896973e+02 7.76769104e+02 7.76687866e+02 7.76764771e+02 7.76830505e+02 7.76765808e+02 7.76691956e+02 7.76725952e+02 7.76734558e+02 7.76726868e+02 7.76716003e+02 7.76688477e+02 7.76690430e+02 7.76698059e+02 7.76692444e+02 7.76685730e+02 7.76716309e+02 7.76689697e+02 7.76717651e+02 7.76862671e+02 7.76856689e+02 7.76704895e+02 7.76702637e+02 7.76739502e+02 7.76693848e+02 7.76757996e+02 7.76776855e+02 7.76768250e+02 7.76718506e+02 7.76699219e+02 7.76710022e+02 7.76711487e+02 7.76768860e+02 7.76700684e+02 7.76689392e+02 7.76698181e+02 7.76704529e+02 7.76698730e+02 7.76723022e+02 7.76773987e+02 7.76750977e+02 7.76691406e+02 7.76694397e+02 7.76712158e+02 7.76820496e+02 7.76831055e+02 7.76711182e+02 7.76687866e+02 7.76703125e+02 7.76712646e+02 7.76872803e+02 7.76816711e+02 7.76776672e+02 7.76709656e+02 7.76697021e+02 7.76690796e+02 7.76691895e+02 7.76763184e+02 7.76773438e+02 7.76753967e+02 7.76725586e+02 7.76701538e+02 7.76729858e+02 7.76737427e+02 7.76756714e+02 7.76714661e+02 7.76696594e+02 7.76704102e+02 7.76691345e+02 7.76758850e+02 7.76806396e+02 7.76696533e+02 7.76685059e+02 7.76692200e+02 7.76708252e+02 7.76789551e+02 7.76754883e+02 7.76767334e+02 7.76716675e+02 7.76695801e+02 7.76690918e+02 7.76692322e+02 7.76715027e+02 7.76766541e+02 7.76761841e+02 7.76713318e+02 7.76689758e+02 7.76705139e+02 7.76734619e+02 7.76809387e+02 7.76758850e+02 7.76690369e+02 7.76717407e+02 7.76694092e+02 7.76758789e+02 7.76880737e+02 7.76830811e+02 7.76765747e+02 7.76703552e+02 7.76730286e+02 7.76799438e+02 7.76782776e+02 7.76738525e+02 7.76690918e+02 7.76693542e+02 7.76715759e+02 7.76729248e+02 7.76784424e+02 7.76763184e+02 7.76729065e+02 7.76683899e+02 7.76745728e+02 7.76692505e+02 7.76730591e+02 7.76822693e+02 7.76756653e+02 7.76687622e+02 7.76703003e+02 7.76736145e+02 7.76839417e+02 7.76802673e+02 7.76725159e+02 7.76710083e+02 7.76690613e+02 7.76687805e+02 7.76686035e+02 7.76697937e+02 7.76692688e+02 7.76697388e+02 7.76699829e+02 7.76704956e+02 7.76695007e+02 7.76735168e+02 7.76719360e+02 7.76782837e+02 7.76741455e+02 7.76692505e+02 7.76703003e+02 7.76705017e+02 7.76725952e+02 7.76787903e+02 7.76746704e+02 7.76698486e+02 7.76690002e+02 7.76714355e+02 7.76758484e+02 7.76721741e+02 7.76686096e+02 7.76732971e+02 7.76754822e+02 7.76694031e+02 7.76736389e+02 7.76775146e+02 7.76690552e+02 7.76702209e+02 7.76692932e+02 7.76693909e+02 7.76691711e+02 7.76687927e+02 7.76691101e+02 7.76685608e+02 7.76686279e+02 7.76687805e+02 7.76690857e+02 7.76692749e+02 7.76694153e+02 7.76692017e+02 7.76693237e+02 7.76687256e+02 7.76690552e+02 7.76690735e+02 7.76692444e+02 7.76690857e+02 7.76693604e+02 7.76688049e+02 7.76688293e+02 7.76692078e+02 7.76693848e+02 7.76690979e+02 7.76689331e+02 7.76689209e+02 7.76690308e+02 7.76687866e+02 7.76692871e+02 7.76692200e+02 7.76692322e+02 7.76690125e+02 7.76696350e+02 7.76698059e+02 7.76700806e+02 7.76689880e+02 7.76692505e+02 7.76691284e+02 7.76693726e+02 7.76692810e+02 7.76696533e+02 7.76709106e+02 7.76700745e+02 7.76699463e+02 7.76694702e+02 7.76698669e+02 7.76693481e+02 7.76696777e+02 7.76691772e+02 7.76696838e+02 7.76692444e+02 7.76697388e+02 7.76691772e+02 7.76692505e+02 7.76693481e+02 7.76693420e+02 7.76703308e+02 7.76699707e+02 7.76695923e+02 7.76694641e+02 7.76691101e+02 7.76690186e+02 7.76689392e+02 7.76691040e+02 7.76689880e+02 7.76698608e+02 7.76707397e+02 7.76719238e+02 7.76701233e+02 7.76694580e+02 7.76689209e+02 7.76691345e+02 7.76689819e+02 7.76688599e+02 7.76703735e+02 7.76710449e+02 7.76720276e+02 7.76690735e+02 7.76689148e+02 7.76701538e+02 7.76690613e+02 7.76698547e+02 7.76694702e+02 7.76693542e+02 7.76688965e+02 7.76690247e+02 7.76688843e+02 7.76690186e+02 7.76704102e+02 7.76712585e+02 7.76698853e+02 7.76692322e+02 7.76695801e+02 7.76734375e+02 7.76774231e+02 7.76719910e+02 7.76686279e+02 7.76691040e+02 7.76694580e+02 7.76689758e+02 7.76689331e+02 7.76714172e+02 7.76727844e+02 7.76699524e+02 7.76688171e+02 7.76685913e+02 7.76687744e+02 7.76692139e+02 7.76696045e+02 7.76754150e+02 7.76770386e+02 7.76719910e+02 7.76695801e+02 7.76697632e+02 7.76693909e+02 7.76692993e+02 7.76697205e+02 7.76692566e+02 7.76693542e+02 7.76690979e+02 7.76693542e+02 7.76698608e+02 7.76699829e+02 7.76693420e+02 7.76736084e+02 7.76795776e+02 7.76780457e+02 7.76700928e+02 7.76688477e+02 7.76687256e+02 7.76697510e+02 7.76692749e+02 7.76690552e+02 7.76692200e+02 7.76704529e+02 7.76719543e+02 7.76738525e+02 7.76700806e+02 7.76694214e+02 7.76693542e+02 7.76696472e+02 7.76717407e+02 7.76761597e+02 7.76695862e+02 7.76709656e+02 7.76734314e+02 7.76693237e+02 7.76692566e+02 7.76689819e+02 7.76718750e+02 7.76769165e+02 7.76773865e+02 7.76706726e+02 7.76692871e+02 7.76687805e+02 7.76688171e+02 7.76708679e+02 7.76761108e+02 7.76786011e+02 7.76747803e+02 7.76713562e+02 7.76698730e+02 7.76697876e+02 7.76694641e+02 7.76695862e+02 7.76689697e+02 7.76690430e+02 7.76693481e+02 7.76688904e+02 7.76690125e+02 7.76688904e+02 7.76689087e+02 7.76690063e+02 7.76689758e+02 7.76691956e+02 7.76711853e+02 7.76740295e+02 7.76723694e+02 7.76694702e+02 7.76747192e+02 7.76720886e+02 7.76694641e+02 7.76687988e+02 7.76689514e+02 7.76696655e+02 7.76708557e+02 7.76734558e+02 7.76713196e+02 7.76696655e+02 7.76695007e+02 7.76734924e+02 7.76786560e+02 7.76709473e+02 7.76710754e+02 7.76743347e+02 7.76695496e+02 7.76700989e+02 7.76723938e+02 7.76760010e+02 7.76730408e+02 7.76690735e+02 7.76693481e+02 7.76694275e+02 7.76709900e+02 7.76705017e+02 7.76697815e+02 7.76694153e+02 7.76761353e+02 7.76776062e+02 7.76740601e+02 7.76693726e+02 7.76698425e+02 7.76713867e+02 7.76702332e+02 7.76692749e+02 7.76695190e+02 7.76696350e+02 7.76702454e+02 7.76708618e+02 7.76728027e+02 7.76727112e+02 7.76715942e+02 7.76698547e+02 7.76704834e+02 7.76702148e+02 7.76805420e+02 7.77022888e+02 7.77774353e+02 7.77143799e+02 7.76763062e+02 7.76868347e+02 7.76877686e+02 7.76843140e+02 7.76943604e+02 7.76769592e+02 9.58738098e+02 1.52618982e+03 7.52795996e+03 1542015488. 2.63869722e+09 9.91550054e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.48008294e+09 2.20982910e+03 1.11266516e+03 7.88153320e+02 7.89461365e+02 7.87315552e+02 7.87208374e+02 7.87136841e+02 7.87069336e+02 7.87042664e+02 7.87029724e+02 7.87078369e+02 7.87095276e+02 7.87049194e+02 7.87033203e+02 7.87035767e+02 7.87032349e+02 7.87035339e+02 7.83910339e+02 7.80674072e+02 7.76856812e+02 7.76706604e+02 7.76696655e+02 7.76699585e+02 7.76692261e+02 7.76711670e+02 7.76697632e+02 7.76693726e+02 7.76693359e+02 7.76695374e+02 7.76700806e+02 7.76710815e+02 7.76713745e+02 7.76704163e+02 7.76693787e+02 7.76692139e+02 7.76693420e+02 7.76707764e+02 7.76717102e+02 7.76716187e+02 7.76705200e+02 7.76702026e+02 7.76713867e+02 7.76711487e+02 7.76705139e+02 7.76697693e+02 7.76693665e+02 7.76691162e+02 7.76721924e+02 7.76790466e+02 7.76812317e+02 7.76726807e+02 7.76695190e+02 7.76690247e+02 7.76690674e+02 7.76692810e+02 7.76692444e+02 7.76690063e+02 7.76687500e+02 7.76695862e+02 7.76701843e+02 7.76723145e+02 7.76754639e+02 7.76795471e+02 7.76761902e+02 7.76735779e+02 7.76710632e+02 7.76732422e+02 7.76777649e+02 7.76751587e+02 7.76715332e+02 7.76690552e+02 7.76694397e+02 7.76695862e+02 7.76695740e+02 7.76773865e+02 7.76878296e+02 7.76851624e+02 7.76810791e+02 7.76800293e+02 7.76744019e+02 7.76706116e+02 7.76695862e+02 7.76701538e+02 7.76716003e+02 7.76686279e+02 7.76704468e+02 7.76712830e+02 7.76694153e+02 7.76699951e+02 7.76699951e+02 7.76698059e+02 7.76692749e+02 7.76690125e+02 7.76689636e+02 7.76691956e+02 7.76694214e+02 7.76705933e+02 7.76715332e+02 7.76725525e+02 7.76732422e+02 7.76703857e+02 7.76691406e+02 7.76714905e+02 7.76720154e+02 7.76693665e+02 7.76690247e+02 7.76706543e+02 7.76692993e+02 7.76693359e+02 7.76712524e+02 7.76769897e+02 7.76766724e+02 7.76711731e+02 7.76694397e+02 7.76699280e+02 7.76699890e+02 7.76692627e+02 7.76689941e+02 7.76691833e+02 7.76696655e+02 7.76699951e+02 7.76694763e+02 7.76692383e+02 7.76689758e+02 7.76689575e+02 7.76690674e+02 7.76690613e+02 7.76697144e+02 7.76698730e+02 7.76698425e+02 7.76702881e+02 7.76700684e+02 7.76693176e+02 7.76696838e+02 7.76687866e+02 7.76737305e+02 7.76763489e+02 7.76707703e+02 7.76689758e+02 7.76691101e+02 7.76691589e+02 7.76695312e+02 7.76695251e+02 7.76692627e+02 7.76691162e+02 7.76692871e+02 7.76692017e+02 7.76693909e+02 7.76692505e+02 7.76691956e+02 7.76690186e+02 7.76688965e+02 7.76689331e+02 7.76689270e+02 7.76694519e+02 7.76697021e+02 7.76699646e+02 7.76696777e+02 7.76693542e+02 7.76696167e+02 7.76752869e+02 7.76878418e+02 7.76897766e+02 7.76783997e+02 7.76725708e+02 7.76693604e+02 7.76694031e+02 7.76693420e+02 7.76690186e+02 7.76690552e+02 7.76693298e+02 7.76708557e+02 7.76716797e+02 7.76694885e+02 7.76696960e+02 7.76717346e+02 7.76787842e+02 7.76876282e+02 7.76817017e+02 7.76729980e+02 7.76692932e+02 7.76691101e+02 7.76689148e+02 7.76693115e+02 7.76693970e+02 7.76695007e+02 7.76693298e+02 7.76694885e+02 7.76699219e+02 7.76696960e+02 7.76695190e+02 7.76692200e+02 7.76692627e+02 7.76691956e+02 7.76691040e+02 7.76702148e+02 7.76729980e+02 7.76739990e+02 7.76698608e+02 7.76692932e+02 7.76715332e+02 7.76769287e+02 7.76826599e+02 7.76823425e+02 7.76745911e+02 7.76706238e+02 7.76692017e+02 7.76692871e+02 7.76692993e+02 7.76695068e+02 7.76695312e+02 7.76695312e+02 7.76695190e+02 7.76696045e+02 7.76699707e+02 7.76698120e+02 7.76696594e+02 7.76694275e+02 7.76697937e+02 7.76707520e+02 7.76704773e+02 7.76711914e+02 7.76702759e+02 7.76701599e+02 7.76696106e+02 7.76691162e+02 7.76707703e+02 7.76713257e+02 7.76693787e+02 7.76691895e+02 7.76691650e+02 7.76692322e+02 7.76690491e+02 7.76692566e+02 7.76693909e+02 7.76692383e+02 7.76688965e+02 7.76688599e+02 7.76693237e+02 7.76691833e+02 7.76693481e+02 7.76690796e+02 7.76692078e+02 7.76691467e+02 7.76694458e+02 7.76727173e+02 7.76765442e+02 7.76696716e+02 7.76722473e+02 7.76778564e+02 7.76704102e+02 7.76691589e+02 7.76692139e+02 7.76718140e+02 7.76711304e+02 7.76691956e+02 7.76701660e+02 7.76692688e+02 7.76690918e+02 7.76689514e+02 7.76692627e+02 7.76697510e+02 7.76706055e+02 7.76703064e+02 7.76691101e+02 7.76690063e+02 7.76690552e+02 7.76701355e+02 7.76701843e+02 7.76692505e+02 7.76690796e+02 7.76703369e+02 7.76701538e+02 7.76690491e+02 7.76687134e+02 7.76688965e+02 7.76689087e+02 7.76694824e+02 7.76689514e+02 7.76698547e+02 7.76751282e+02 7.76761719e+02 7.76711548e+02 7.76688232e+02 7.76688782e+02 7.76691467e+02 7.76705566e+02 7.76749207e+02 7.76742676e+02 7.76704712e+02 7.76693787e+02 7.76703613e+02 7.76699524e+02 7.76701660e+02 7.76688354e+02 7.76690186e+02 7.76685608e+02 7.76688354e+02 7.76689819e+02 7.76691956e+02 7.76696167e+02 7.76701843e+02 7.76698425e+02 7.76694702e+02 7.76690857e+02 7.76688965e+02 7.76692810e+02 7.76697937e+02 7.76694763e+02 7.76690735e+02 7.76692566e+02 7.76691406e+02 7.76696594e+02 7.76696045e+02 7.76700500e+02 7.76695801e+02 7.76696106e+02 7.76696899e+02 7.76697571e+02 7.76696716e+02 7.76689270e+02 7.76690063e+02 7.76693848e+02 7.76707092e+02 7.76711670e+02 7.76699829e+02 7.76690308e+02 7.76690430e+02 7.76690491e+02 7.76692322e+02 7.76690735e+02 7.76709412e+02 7.76728699e+02 7.76713623e+02 7.76689453e+02 7.76735840e+02 7.76805603e+02 7.76862305e+02 7.76787903e+02 7.76740601e+02 7.76695007e+02 7.76715820e+02 7.76714294e+02 7.76685364e+02 7.76693298e+02 7.76731140e+02 7.76722900e+02 7.76687988e+02 7.76740356e+02 7.76728088e+02 7.76695801e+02 7.76697937e+02 7.76701477e+02 7.76691833e+02 7.76696228e+02 7.76691833e+02 7.76716919e+02 7.76784119e+02 7.76788208e+02 7.76732727e+02 7.76710144e+02 7.76753906e+02 7.76775635e+02 7.76733948e+02 7.76700195e+02 7.76717773e+02 7.76769958e+02 7.76786438e+02 7.76732605e+02 7.76699646e+02 7.76695007e+02 7.76694214e+02 7.76705261e+02 7.76720093e+02 7.76708313e+02 7.76691895e+02 7.76696533e+02 7.76703247e+02 7.76726990e+02 7.76736511e+02 7.76704834e+02 7.76692749e+02 7.76695068e+02 7.76709534e+02 7.76716553e+02 7.76745972e+02 7.76755127e+02 7.76743103e+02 7.76694824e+02 7.76693970e+02 7.76695618e+02 7.76696350e+02 7.76696838e+02 7.76698059e+02 7.76704834e+02 7.76712708e+02 7.76729858e+02 7.76698120e+02 7.76713562e+02 7.76702576e+02 7.76709229e+02 7.76727722e+02 7.76697510e+02 7.76725464e+02 7.76695618e+02 7.76713745e+02 7.76698425e+02 7.76727600e+02 7.76757751e+02 7.76712830e+02 7.76705933e+02 7.76725586e+02 7.76722534e+02 7.76691345e+02 7.76709167e+02 7.76706421e+02 7.76698608e+02 7.76697388e+02 7.76697083e+02 7.76711365e+02 7.76743835e+02 7.76755310e+02 7.76792603e+02 7.76800171e+02 7.76788086e+02 7.76716980e+02 7.76694824e+02 7.76693726e+02 7.76693298e+02 7.76691162e+02 7.76695557e+02 7.76699158e+02 7.76716187e+02 7.76733521e+02 7.76725891e+02 7.76734070e+02 7.76776001e+02 7.76744995e+02 7.76701782e+02 7.76695923e+02 7.76702026e+02 7.76725159e+02 7.76732483e+02 7.76718872e+02 7.76694397e+02 7.76727051e+02 7.76726135e+02 7.76724609e+02 7.76725708e+02 7.76736389e+02 7.76696899e+02 7.76691772e+02 7.76695923e+02 7.76690552e+02 7.76693787e+02 7.76700745e+02 7.76708740e+02 7.76717590e+02 7.76740906e+02 7.76757263e+02 7.76765381e+02 7.76720398e+02 7.76697998e+02 7.76693481e+02 7.76695129e+02 7.76705139e+02 7.76710693e+02 7.76754395e+02 7.76832703e+02 7.76878174e+02 7.76816406e+02 7.76718628e+02 7.76691406e+02 7.76714966e+02 7.76716675e+02 7.76710876e+02 7.76698608e+02 7.76702271e+02 7.76705688e+02 7.76715637e+02 7.76717285e+02 7.76719177e+02 7.76723022e+02 7.76719055e+02 7.76705566e+02 7.76695312e+02 7.76708679e+02 7.76700500e+02 7.76689148e+02 7.76695129e+02 7.76712097e+02 7.76703369e+02 7.76707581e+02 7.76717468e+02 7.76728638e+02 7.76694702e+02 7.76699280e+02 7.76701233e+02 7.76738525e+02 7.76744995e+02 7.76702393e+02 7.76708557e+02 7.76754944e+02 7.76783630e+02 7.76709412e+02 7.76702759e+02 7.76709229e+02 7.76702637e+02 7.76692932e+02 7.76696655e+02 7.76719055e+02 7.76774170e+02 7.76780579e+02 7.76723450e+02 7.76695251e+02 7.76694336e+02 7.76694946e+02 7.76723083e+02 7.76822876e+02 7.76806030e+02 7.76735107e+02 7.76694275e+02 7.76694885e+02 7.76694885e+02 7.76697144e+02 7.76695618e+02 7.76693054e+02 7.76694092e+02 7.76693298e+02 7.76695679e+02 7.76695862e+02 7.76699524e+02 7.76693298e+02 7.76691956e+02 7.76690735e+02 7.76707703e+02 7.76777039e+02 7.76763367e+02 7.76706482e+02 7.76699341e+02 7.76719360e+02 7.76708679e+02 7.76691284e+02 7.76707642e+02 7.76699707e+02 7.76698547e+02 7.76694519e+02 7.76693420e+02 7.76694824e+02 7.76700073e+02 7.76709106e+02 7.76695679e+02 7.76747070e+02 7.76801147e+02 7.76742371e+02 7.76739685e+02 7.76780884e+02 7.76776550e+02 7.76708130e+02 7.76693726e+02 7.76690979e+02 7.76691162e+02 7.76690369e+02 7.76695801e+02 7.76715454e+02 7.76706299e+02 7.76696960e+02 7.76711609e+02 7.76783875e+02 7.76842529e+02 7.76742676e+02 7.76713745e+02 7.76739380e+02 7.76750488e+02 7.76732605e+02 7.76693604e+02 7.76699829e+02 7.76708862e+02 7.76689636e+02 7.76727478e+02 7.76727539e+02 7.76700928e+02 7.76742615e+02 7.76698730e+02 7.76690796e+02 7.76695435e+02 7.76699341e+02 7.76697754e+02 7.76734924e+02 7.76788330e+02 7.76735291e+02 7.76707703e+02 7.76739502e+02 7.76826965e+02 7.76771301e+02 7.76708313e+02 7.76695984e+02 7.77000488e+02 7.77381714e+02 7.79184448e+02 7.77437195e+02 9.77648743e+02 9.25889038e+02 9.47782959e+02 9.94327271e+02 1.34707910e+03 3.36373315e+03 6.93412256e+03 -3.09167744e+09 63040100. 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. -3.02667469e+09 4.40758350e+03 1.90287451e+03 1.23651611e+03 1.22906458e+03 7.07308228e+02 5.07914764e+02 3.97938690e+02 3.97640808e+02 3.97650787e+02 3.98045013e+02 3.98710388e+02 3.97721466e+02 4.97472809e+02 6.81138000e+02 1.22398438e+03 7.42617188e+02 5.31220398e+02 4.03137238e+02 3.99769897e+02 3.98533112e+02 3.97700897e+02 3.97680664e+02 3.97685120e+02 3.97662476e+02 3.97655670e+02 3.97648376e+02 3.97645477e+02 3.97644684e+02 3.97644714e+02 3.97645416e+02 3.97649384e+02 3.97645782e+02 3.97644684e+02 3.97645233e+02 3.97645386e+02 3.97645294e+02 3.97645203e+02 3.97644989e+02 3.97644867e+02 3.97644318e+02 3.97648865e+02 3.97646149e+02 3.97645142e+02 3.97644287e+02 3.97644928e+02 3.97645142e+02 3.97645081e+02 3.97644135e+02 3.97644379e+02 3.97644287e+02 3.97643555e+02 3.97644562e+02 3.97644073e+02 3.97644562e+02 3.97645020e+02 3.97646484e+02 3.97644592e+02 3.97644501e+02 3.97643585e+02 3.97645660e+02 3.97644775e+02 3.97645050e+02 3.97644287e+02 3.97645111e+02 3.97644745e+02 3.97644867e+02 3.97644073e+02 3.97644531e+02 3.97644043e+02 3.97645477e+02 3.97645294e+02 3.97646362e+02 3.97648132e+02 3.97647003e+02 3.97647461e+02 3.97646210e+02 3.97644745e+02 3.97646179e+02 3.97646210e+02 3.97644653e+02 3.97645599e+02 3.97645935e+02 3.97644623e+02 3.97644745e+02 3.97645325e+02 3.97645294e+02 3.97645691e+02 3.97645660e+02 3.97644897e+02 3.97644470e+02 3.97645691e+02 3.97645050e+02 3.97644073e+02 3.97645050e+02 3.97648407e+02 3.97647430e+02 3.97646606e+02 3.97645233e+02 3.97645020e+02 3.97645142e+02 3.97645538e+02 3.97645203e+02 3.97645325e+02 3.97644043e+02 3.97644531e+02 3.97645386e+02 3.97645447e+02 3.97645447e+02 3.97644592e+02 3.97645294e+02 3.97646484e+02 3.97645386e+02 3.97647095e+02 3.97647278e+02 3.97645844e+02 3.97645050e+02 3.97644379e+02 3.97644348e+02 3.97644989e+02 3.97645294e+02 3.97645691e+02 3.97645294e+02 3.97645538e+02 3.97645447e+02 3.97644165e+02 3.97644653e+02 3.97645142e+02 3.97645050e+02 3.97645233e+02 3.97646606e+02 3.97644836e+02 3.97645203e+02 3.97644897e+02 3.97644775e+02 3.97644196e+02 3.97644989e+02 3.97645111e+02 3.97645416e+02 3.97645264e+02 3.97646606e+02 3.97646027e+02 3.97646332e+02 3.97648743e+02 3.97647827e+02 3.97644501e+02 3.97645081e+02 3.97646149e+02 3.97645569e+02 3.97643707e+02 3.97643921e+02 3.97644043e+02 3.97644501e+02 3.97644745e+02 3.97643707e+02 3.97644287e+02 3.97643982e+02 3.97643829e+02 3.97644043e+02 3.97644257e+02 3.97644043e+02 3.97645660e+02 3.97644196e+02 3.97644745e+02 3.97646118e+02 3.97646942e+02 3.97646606e+02 3.97646118e+02 3.97646515e+02 3.97645203e+02 3.97645355e+02 3.97647461e+02 3.97646332e+02 3.97645874e+02 3.97645203e+02 3.97645752e+02 3.97646088e+02 3.97645416e+02 3.97644531e+02 3.97645264e+02 3.97647339e+02 3.97645172e+02 3.97645355e+02 3.97648621e+02 3.97649628e+02 3.97647400e+02 3.97646515e+02 3.97646118e+02 3.97646027e+02 3.97645142e+02 3.97645111e+02 3.97645294e+02 3.97648834e+02 3.97649841e+02 3.97647034e+02 3.97644135e+02 3.97644958e+02 3.97645752e+02 3.97645935e+02 3.97646484e+02 3.97646881e+02 3.97648499e+02 3.97646271e+02 3.97645447e+02 3.97646210e+02 3.97645111e+02 3.97646484e+02 3.97646240e+02 3.97647552e+02 3.97646332e+02 3.97645874e+02 3.97646271e+02 3.97644775e+02 3.97645020e+02 3.97644653e+02 3.97645538e+02 3.97646790e+02 3.97647034e+02 3.97647736e+02 3.97647125e+02 3.97646332e+02 3.97645782e+02 3.97646393e+02 3.97646332e+02 3.97646210e+02 3.97645691e+02 3.97646667e+02 3.97645721e+02 3.97644318e+02 3.97645966e+02 3.97643799e+02 3.97644867e+02 3.97646027e+02 3.97646118e+02 3.97646332e+02 3.97645844e+02 3.97645905e+02 3.97645538e+02 3.97646057e+02 3.97647247e+02 3.97647644e+02 3.97645264e+02 3.97646362e+02 3.97646515e+02 3.97645813e+02 3.97644867e+02 3.97645782e+02 3.97645477e+02 3.97644592e+02 3.97645721e+02 3.97645813e+02 3.97645508e+02 3.97644806e+02 3.97644531e+02 3.97644440e+02 3.97644806e+02 3.97644409e+02 3.97645020e+02 3.97645447e+02 3.97645172e+02 3.97645477e+02 3.97645966e+02 3.97646118e+02 3.97646057e+02 3.97646027e+02 3.97647064e+02 3.97646423e+02 3.97646606e+02 3.97645752e+02 3.97645844e+02 3.97645996e+02 3.97646149e+02 3.97645142e+02 3.97645355e+02 3.97645325e+02 3.97645599e+02 3.97644592e+02 3.97643799e+02 3.97644989e+02 3.97645447e+02 3.97645294e+02 3.97644958e+02 3.97646423e+02 3.97645905e+02 3.97646179e+02 3.97645935e+02 3.97647278e+02 3.97646057e+02 3.97645325e+02 3.97644806e+02 3.97644928e+02 3.97645477e+02 3.97645508e+02 3.97646057e+02 3.97647064e+02 3.97645599e+02 3.97645416e+02 3.97645050e+02 3.97645874e+02 3.97645721e+02 3.97645264e+02 3.97645294e+02 3.97645782e+02 3.97645355e+02 3.97645416e+02 3.97646881e+02 3.97645142e+02 3.97645966e+02 3.97645172e+02 3.97645447e+02 3.97645386e+02 3.97645844e+02 3.97646332e+02 3.97645996e+02 3.97645782e+02 3.97646027e+02 3.97645294e+02 3.97644989e+02 3.97645721e+02 3.97646271e+02 3.97646393e+02 3.97645844e+02 3.97645782e+02 3.97646484e+02 3.97646851e+02 3.97646637e+02 3.97645813e+02 3.97645233e+02 3.97646149e+02 3.97645630e+02 3.97645294e+02 3.97644958e+02 3.97645599e+02 3.97645721e+02 3.97644989e+02 3.97644836e+02 3.97644989e+02 3.97645996e+02 3.97646515e+02 3.97646667e+02 3.97646332e+02 3.97646820e+02 3.97646637e+02 3.97645599e+02 3.97645538e+02 3.97644836e+02 3.97646698e+02 3.97646576e+02 3.97646515e+02 3.97645874e+02 3.97646729e+02 3.97645447e+02 3.97645905e+02 3.97646149e+02 3.97646271e+02 3.97645569e+02 3.97644958e+02 3.97645630e+02 3.97645752e+02 3.97645355e+02 3.97645538e+02 3.97645569e+02 3.97645966e+02 3.97646362e+02 3.97645966e+02 3.97645508e+02 3.97646454e+02 3.97644806e+02 3.97644501e+02 3.97645294e+02 3.97645172e+02 3.97645142e+02 3.97645020e+02 3.97646240e+02 3.97646393e+02 3.97645874e+02 3.97646332e+02 3.97644928e+02 3.97645935e+02 3.97646454e+02 3.97645355e+02 3.97645233e+02 3.97646088e+02 3.97645325e+02 3.97649658e+02 3.97646149e+02 3.97647308e+02 3.97650330e+02 3.97650208e+02 3.97646484e+02 3.97646942e+02 3.97645691e+02 3.97645874e+02 3.97645966e+02 3.97646393e+02 3.97645569e+02 3.97647125e+02 3.97646332e+02 3.97644928e+02 3.97645477e+02 3.97646179e+02 3.97645081e+02 3.97646240e+02 3.97645172e+02 3.97645416e+02 3.97644745e+02 3.97644745e+02 3.97644714e+02 3.97644745e+02 3.97644928e+02 3.97645630e+02 3.97645630e+02 3.97645172e+02 3.97646576e+02 3.97647552e+02 3.97648163e+02 3.97649109e+02 3.97647858e+02 3.97646057e+02 3.97646973e+02 3.97645538e+02 3.97646057e+02 3.97646210e+02 3.97645264e+02 3.97644806e+02 3.97645081e+02 3.97644073e+02 3.97644806e+02 3.97644562e+02 3.97644806e+02 3.97645081e+02 3.97645935e+02 3.97645721e+02 3.97645416e+02 3.97646301e+02 3.97646057e+02 3.97646729e+02 3.97645447e+02 3.97645172e+02 3.97645355e+02 3.97644958e+02 3.97645111e+02 3.97644745e+02 3.97644440e+02 3.97645752e+02 3.97647858e+02 3.97645111e+02 3.97645813e+02 3.97646576e+02 3.97645203e+02 3.97644928e+02 3.97645569e+02 3.97644440e+02 3.97645294e+02 3.97645599e+02 3.97647675e+02 3.97645966e+02 3.97644440e+02 3.97644165e+02 3.97645905e+02 3.97643982e+02 3.97644470e+02 3.97644379e+02 3.97645172e+02 3.97644409e+02 3.97644226e+02 3.97644684e+02 3.97643951e+02 3.97644653e+02 3.97644012e+02 3.97645233e+02 3.97644806e+02 3.97644653e+02 3.97646027e+02 3.97645477e+02 3.97646118e+02 3.97646790e+02 3.97644775e+02 3.97645081e+02 3.97645294e+02 3.97644379e+02 3.97645355e+02 3.97644989e+02 3.97644592e+02 3.97644745e+02 3.97645660e+02 3.97645630e+02 3.97644592e+02 3.97643707e+02 3.97643829e+02 3.97644287e+02 3.97645203e+02 3.97649506e+02 3.97647247e+02 3.97645691e+02 3.97645935e+02 3.97645020e+02 3.97644226e+02 3.97644501e+02 3.97644745e+02 3.97644470e+02 3.97645111e+02 3.97645294e+02 3.97646088e+02 3.97646332e+02 3.97645203e+02 3.97646820e+02 3.97644684e+02 3.97644073e+02 3.97645752e+02 3.97645081e+02 3.97646423e+02 3.97645386e+02 3.97644714e+02 3.97645691e+02 3.97645050e+02 3.97646027e+02 3.97645416e+02 3.97644653e+02 3.97644958e+02 3.97645050e+02 3.97644897e+02 3.97645111e+02 3.97646576e+02 3.97645020e+02 3.97644928e+02 3.97644165e+02 3.97643768e+02 3.97644257e+02 3.97645844e+02 3.97645294e+02 3.97645935e+02 3.97647858e+02 3.97646393e+02 3.97646118e+02 3.97644104e+02 3.97644073e+02 3.97643524e+02 3.97644623e+02 3.97644440e+02 3.97644928e+02 3.97645416e+02 3.97644989e+02 3.97645111e+02 3.97645599e+02 3.97644989e+02 3.97645660e+02 3.97644562e+02 3.97645294e+02 3.97645355e+02 3.97645691e+02 3.97644440e+02 3.97644409e+02 3.97644836e+02 3.97646698e+02 3.97645630e+02 3.97646088e+02 3.97644470e+02 3.97644379e+02 3.97644989e+02 3.97645599e+02 3.97644592e+02 3.97645111e+02 3.97644196e+02 3.97644348e+02 3.97644989e+02 3.97650208e+02 3.97647278e+02 3.97646210e+02 3.97645447e+02 3.97645050e+02 3.97645050e+02 3.97644684e+02 3.97646057e+02 3.97646484e+02 3.97646393e+02 3.97645081e+02 3.97644501e+02 3.97645538e+02 3.97645508e+02 3.97645660e+02 3.97644775e+02 3.97645416e+02 3.97645111e+02 3.97645447e+02 3.97644196e+02 3.97644196e+02 3.97644684e+02 3.97644073e+02 3.97645630e+02 3.97644318e+02 3.97645020e+02 3.97644043e+02 3.97644104e+02 3.97644073e+02 3.97644958e+02 3.97644836e+02 3.97643341e+02 3.97643646e+02 3.97643738e+02 3.97644287e+02 3.97644897e+02 3.97644501e+02 3.97645935e+02 3.97648407e+02 3.97650391e+02 3.97648071e+02 3.97646332e+02 3.97645172e+02 3.97646606e+02 3.97647400e+02 3.97653168e+02 3.97657318e+02 3.97665070e+02 3.97664246e+02 3.97741638e+02 3.97813629e+02 3.99040710e+02 3.99503143e+02 4.00946686e+02 4.10504242e+02 6.72030151e+02 -8.49485703e+04 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 8.80019251e+09 1213870464. 4.36269922e+03 2.05561035e+03 1.24799438e+03 6.69291443e+02 4.80483154e+02 3.98965698e+02 3.98833160e+02 3.98080627e+02 4.02329071e+02 3.99370728e+02 3.97658752e+02 3.98090363e+02 3.98635559e+02 3.98341980e+02 3.98843262e+02 3.98607147e+02 3.98302338e+02 3.97826019e+02 3.97758270e+02 3.97699371e+02 3.97687103e+02 3.97665253e+02 3.97652100e+02 3.97648621e+02 3.97647797e+02 3.97647186e+02 3.97647491e+02 3.97647583e+02 3.97647369e+02 3.97646790e+02 3.97645508e+02 3.97645233e+02 3.97645325e+02 3.97646393e+02 3.97647034e+02 3.97645203e+02 3.97644653e+02 3.97645355e+02 3.97645233e+02 3.97645233e+02 3.97644348e+02 3.97644928e+02 3.97645508e+02 3.97644623e+02 3.97644562e+02 3.97643433e+02 3.97645447e+02 3.97644653e+02 3.97645264e+02 3.97645264e+02 3.97644867e+02 3.97645752e+02 3.97645630e+02 3.97646088e+02 3.97644653e+02 3.97645294e+02 3.97645538e+02 3.97645660e+02 3.97645569e+02 3.97645538e+02 3.97645660e+02 3.97645386e+02 3.97644745e+02 3.97647369e+02 3.97645782e+02 3.97644928e+02 3.97644775e+02 3.97644806e+02 3.97645874e+02 3.97648224e+02 3.97647552e+02 3.97645691e+02 3.97645416e+02 3.97644989e+02 3.97644043e+02 3.97644043e+02 3.97645203e+02 3.97646393e+02 3.97645966e+02 3.97645538e+02 3.97645233e+02 3.97645203e+02 3.97644958e+02 3.97646301e+02 3.97646637e+02 3.97645813e+02 3.97644928e+02 3.97645294e+02 3.97645569e+02 3.97645447e+02 3.97646759e+02 3.97645630e+02 3.97646973e+02 3.97645355e+02 3.97646362e+02 3.97645447e+02 3.97645782e+02 3.97645752e+02 3.97645508e+02 3.97644348e+02 3.97645691e+02 3.97646637e+02 3.97645660e+02 3.97644989e+02 3.97645721e+02 3.97645630e+02 3.97645721e+02 3.97645355e+02 3.97645569e+02 3.97644806e+02 3.97645294e+02 3.97644775e+02 3.97645782e+02 3.97645844e+02 3.97646729e+02 3.97646484e+02 3.97645691e+02 3.97644836e+02 3.97645508e+02 3.97645142e+02 3.97645538e+02 3.97647797e+02 3.97646606e+02 3.97645966e+02 3.97645203e+02 3.97644928e+02 3.97645874e+02 3.97646667e+02 3.97646484e+02 3.97644958e+02 3.97644928e+02 3.97645599e+02 3.97646240e+02 3.97648132e+02 3.97647369e+02 3.97646149e+02 3.97646362e+02 3.97645935e+02 3.97645844e+02 3.97645630e+02 3.97645569e+02 3.97645752e+02 3.97648743e+02 3.97647156e+02 3.97648468e+02 3.97646576e+02 3.97646088e+02 3.97647308e+02 3.97646149e+02 3.97645691e+02 3.97645050e+02 3.97645386e+02 3.97645538e+02 3.97645660e+02 3.97645874e+02 3.97645599e+02 3.97644653e+02 3.97645630e+02 3.97646088e+02 3.97647736e+02 3.97646820e+02 3.97646210e+02 3.97645966e+02 3.97645081e+02 3.97644836e+02 3.97644867e+02 3.97646332e+02 3.97645599e+02 3.97646820e+02 3.97645721e+02 3.97645966e+02 3.97646118e+02 3.97646210e+02 3.97645844e+02 3.97645111e+02 3.97643433e+02 3.97643402e+02 3.97644440e+02 3.97645203e+02 3.97645874e+02 3.97645294e+02 3.97645416e+02 3.97645874e+02 3.97647308e+02 3.97647705e+02 3.97645020e+02 3.97645416e+02 3.97647491e+02 3.97645844e+02 3.97646240e+02 3.97645111e+02 3.97645874e+02 3.97645538e+02 3.97645844e+02 3.97645416e+02 3.97645844e+02 3.97645508e+02 3.97646057e+02 3.97646698e+02 3.97644592e+02 3.97644775e+02 3.97644684e+02 3.97647400e+02 3.97644958e+02 3.97644714e+02 3.97643707e+02 3.97644775e+02 3.97645447e+02 3.97645447e+02 3.97645142e+02 3.97644348e+02 3.97644440e+02 3.97645050e+02 3.97646545e+02 3.97644745e+02 3.97644348e+02 3.97644287e+02 3.97644348e+02 3.97644684e+02 3.97645355e+02 3.97645294e+02 3.97646606e+02 3.97646729e+02 3.97646088e+02 3.97645630e+02 3.97644836e+02 3.97645599e+02 3.97644958e+02 3.97645630e+02 3.97645020e+02 3.97645599e+02 3.97644257e+02 3.97646332e+02 3.97645050e+02 3.97644348e+02 3.97644592e+02 3.97644989e+02 3.97645874e+02 3.97645325e+02 3.97645203e+02 3.97644775e+02 3.97645538e+02 3.97646362e+02 3.97646515e+02 3.97645264e+02 3.97646118e+02 3.97646393e+02 3.97647491e+02 3.97646576e+02 3.97645813e+02 3.97644958e+02 3.97644409e+02 3.97645599e+02 3.97645294e+02 3.97645142e+02 3.97645081e+02 3.97644226e+02 3.97646179e+02 3.97645905e+02 3.97647125e+02 3.97646606e+02 3.97647522e+02 3.97646393e+02 3.97646576e+02 3.97645813e+02 3.97645142e+02 3.97645721e+02 3.97645508e+02 3.97645599e+02 3.97644379e+02 3.97644104e+02 3.97645325e+02 3.97645477e+02 3.97645416e+02 3.97645294e+02 3.97644592e+02 3.97644440e+02 3.97645844e+02 3.97645294e+02 3.97646118e+02 3.97645264e+02 3.97645813e+02 3.97645996e+02 3.97645813e+02 3.97644623e+02 3.97646027e+02 3.97645203e+02 3.97645569e+02 3.97645721e+02 3.97645233e+02 3.97646423e+02 3.97645660e+02 3.97646576e+02 3.97646790e+02 3.97646179e+02 3.97645142e+02 3.97645294e+02 3.97646149e+02 3.97645782e+02 3.97645386e+02 3.97646301e+02 3.97646179e+02 3.97645294e+02 3.97645264e+02 3.97645630e+02 3.97645142e+02 3.97645355e+02 3.97644958e+02 3.97645752e+02 3.97645447e+02 3.97644226e+02 3.97644867e+02 3.97645355e+02 3.97645782e+02 3.97645386e+02 3.97645203e+02 3.97645081e+02 3.97645416e+02 3.97645721e+02 3.97645081e+02 3.97646301e+02 3.97645386e+02 3.97645691e+02 3.97645538e+02 3.97645111e+02 3.97644257e+02 3.97645142e+02 3.97643951e+02 3.97645477e+02 3.97644745e+02 3.97646454e+02 3.97645477e+02 3.97645416e+02 3.97645050e+02 3.97645538e+02 3.97645081e+02 3.97645355e+02 3.97645996e+02 3.97646057e+02 3.97645050e+02 3.97645020e+02 3.97645905e+02 3.97646881e+02 3.97646637e+02 3.97646118e+02 3.97646393e+02 3.97645508e+02 3.97646576e+02 3.97645142e+02 3.97646423e+02 3.97647369e+02 3.97645813e+02 3.97646027e+02 3.97645447e+02 3.97645508e+02 3.97646301e+02 3.97645233e+02 3.97645203e+02 3.97644714e+02 3.97645966e+02 3.97645233e+02 3.97645935e+02 3.97645630e+02 3.97645538e+02 3.97645294e+02 3.97645660e+02 3.97645233e+02 3.97645538e+02 3.97646210e+02 3.97646027e+02 3.97644806e+02 3.97644958e+02 3.97646484e+02 3.97644684e+02 3.97645203e+02 3.97644684e+02 3.97644257e+02 3.97644287e+02 3.97645142e+02 3.97645050e+02 3.97644287e+02 3.97644257e+02 3.97644928e+02 3.97645905e+02 3.97645233e+02 3.97645782e+02 3.97645264e+02 3.97645630e+02 3.97646088e+02 3.97646393e+02 3.97645813e+02 3.97645416e+02 3.97646454e+02 3.97646240e+02 3.97646759e+02 3.97646118e+02 3.97647125e+02 3.97647247e+02 3.97646942e+02 3.97646912e+02 3.97647980e+02 3.97646912e+02 3.97647247e+02 3.97645874e+02 3.97645905e+02 3.97645172e+02 3.97645386e+02 3.97645142e+02 3.97645508e+02 3.97645264e+02 3.97645813e+02 3.97644501e+02 3.97645386e+02 3.97645508e+02 3.97645721e+02 3.97644775e+02 3.97645172e+02 3.97644775e+02 3.97644989e+02 3.97645599e+02 3.97645660e+02 3.97644714e+02 3.97644592e+02 3.97644073e+02 3.97645203e+02 3.97643829e+02 3.97644806e+02 3.97644257e+02 3.97644928e+02 3.97645050e+02 3.97644745e+02 3.97644897e+02 3.97644745e+02 3.97645142e+02 3.97645233e+02 3.97645386e+02 3.97643860e+02 3.97644684e+02 3.97643860e+02 3.97645172e+02 3.97644257e+02 3.97644897e+02 3.97644592e+02 3.97645721e+02 3.97645996e+02 3.97647827e+02 3.97646637e+02 3.97648926e+02 3.97648010e+02 3.97650574e+02 3.97652649e+02 3.97652069e+02 3.97656494e+02 3.98562561e+02 3.99946747e+02 4.00849579e+02 5.82662292e+02 1.12692114e+03 3.66521062e+09 1071069376. 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. 0. 0. 0. 0. 0. 0. 0. 0. -7.59951360e+09 -3.09096141e+09 816435840. 1118660864. 3.94643970e+03 1.88352039e+03 1.23119983e+03 1.22436707e+03 1.22404346e+03 1.22405164e+03 1.22422559e+03 1.22428760e+03 1.22413440e+03 1.22404041e+03 1.22407642e+03 1.22408569e+03 1.22408472e+03 7.39835144e+02 5.23027954e+02 3.99475189e+02 3.97761108e+02 3.97697540e+02 3.97666779e+02 3.97660492e+02 3.97650330e+02 3.97649353e+02 3.97648651e+02 3.97648346e+02 3.97647827e+02 3.97646973e+02 3.97646881e+02 3.97646545e+02 3.97646515e+02 3.97645477e+02 3.97644958e+02 3.97644958e+02 3.97644897e+02 3.97646454e+02 3.97645874e+02 3.97646454e+02 3.97645081e+02 3.97644897e+02 3.97645020e+02 3.97644836e+02 3.97644714e+02 3.97645111e+02 3.97644775e+02 3.97644348e+02 3.97645844e+02 3.97644501e+02 3.97645599e+02 3.97644470e+02 3.97644867e+02 3.97645355e+02 3.97644531e+02 3.97645874e+02 3.97644714e+02 3.97645874e+02 3.97644592e+02 3.97644501e+02 3.97644867e+02 3.97643646e+02 3.97645172e+02 3.97644806e+02 3.97644440e+02 3.97644867e+02 3.97644226e+02 3.97644501e+02 3.97644592e+02 3.97645050e+02 3.97644867e+02 3.97644623e+02 3.97644775e+02 3.97644531e+02 3.97644501e+02 3.97646484e+02 3.97646667e+02 3.97645874e+02 3.97645142e+02 3.97644531e+02 3.97645142e+02 3.97644897e+02 3.97644562e+02 3.97645172e+02 3.97645599e+02 3.97645538e+02 3.97645477e+02 3.97644897e+02 3.97645721e+02 3.97644958e+02 3.97644653e+02 3.97644928e+02 3.97646912e+02 3.97645081e+02 3.97644958e+02 3.97643127e+02 3.97644928e+02 3.97645020e+02 3.97644470e+02 3.97644989e+02 3.97644867e+02 3.97645294e+02 3.97645721e+02 3.97645782e+02 3.97644745e+02 3.97645233e+02 3.97645325e+02 3.97645142e+02 3.97645264e+02 3.97644073e+02 3.97643585e+02 3.97643860e+02 3.97645477e+02 3.97646576e+02 3.97645630e+02 3.97643799e+02 3.97645355e+02 3.97644714e+02 3.97645966e+02 3.97644379e+02 3.97643311e+02 3.97644348e+02 3.97644836e+02 3.97644897e+02 3.97646149e+02 3.97645905e+02 3.97643921e+02 3.97643463e+02 3.97644348e+02 3.97644226e+02 3.97644745e+02 3.97644409e+02 3.97645721e+02 3.97645691e+02 3.97645996e+02 3.97646667e+02 3.97645447e+02 3.97645599e+02 3.97645325e+02 3.97643921e+02 3.97644226e+02 3.97643860e+02 3.97644409e+02 3.97644958e+02 3.97645325e+02 3.97643127e+02 3.97643677e+02 3.97643494e+02 3.97644989e+02 3.97644012e+02 3.97644318e+02 3.97644684e+02 3.97645630e+02 3.97645264e+02 3.97643494e+02 3.97644958e+02 3.97644806e+02 3.97643921e+02 3.97645813e+02 3.97645020e+02 3.97645203e+02 3.97642456e+02 3.97644226e+02 3.97645111e+02 3.97644958e+02 3.97645905e+02 3.97645447e+02 3.97644196e+02 3.97645233e+02 3.97644592e+02 3.97644714e+02 3.97644440e+02 3.97644623e+02 3.97645172e+02 3.97645203e+02 3.97644196e+02 3.97645294e+02 3.97643616e+02 3.97643951e+02 3.97643860e+02 3.97644043e+02 3.97643585e+02 3.97645508e+02 3.97645844e+02 3.97643646e+02 3.97642883e+02 3.97643707e+02 3.97645416e+02 3.97644012e+02 3.97644409e+02 3.97643280e+02 3.97643646e+02 3.97643707e+02 3.97644775e+02 3.97643585e+02 3.97644470e+02 3.97643921e+02 3.97642883e+02 3.97643982e+02 3.97644165e+02 3.97644257e+02 3.97645020e+02 3.97644257e+02 3.97644073e+02 3.97643036e+02 3.97644958e+02 3.97644226e+02 3.97646027e+02 3.97644775e+02 3.97643982e+02 3.97642548e+02 3.97644135e+02 3.97644287e+02 3.97644775e+02 3.97644684e+02 3.97642822e+02 3.97644073e+02 3.97642609e+02 3.97644653e+02 3.97643646e+02 3.97645660e+02 3.97644897e+02 3.97643646e+02 3.97643707e+02 3.97644135e+02 3.97645233e+02 3.97644745e+02 3.97643188e+02 3.97644165e+02 3.97643219e+02 3.97644989e+02 3.97644501e+02 3.97644348e+02 3.97644531e+02 3.97645111e+02 3.97644196e+02 3.97645386e+02 3.97644135e+02 3.97644440e+02 3.97645050e+02 3.97643372e+02 3.97642975e+02 3.97643372e+02 3.97644348e+02 3.97644470e+02 3.97644562e+02 3.97645172e+02 3.97646393e+02 3.97645813e+02 3.97644562e+02 3.97644257e+02 3.97644867e+02 3.97645081e+02 3.97645142e+02 3.97645325e+02 3.97645264e+02 3.97644440e+02 3.97644806e+02 3.97645020e+02 3.97644562e+02 3.97643677e+02 3.97644348e+02 3.97643982e+02 3.97645172e+02 3.97645325e+02 3.97644928e+02 3.97644287e+02 3.97642975e+02 3.97645508e+02 3.97643768e+02 3.97645020e+02 3.97644470e+02 3.97644928e+02 3.97646271e+02 3.97645081e+02 3.97646973e+02 3.97645782e+02 3.97644897e+02 3.97646179e+02 3.97645752e+02 3.97646973e+02 3.97644775e+02 3.97645569e+02 3.97646027e+02 3.97645081e+02 3.97643066e+02 3.97644135e+02 3.97643433e+02 3.97645905e+02 3.97645325e+02 3.97643799e+02 3.97644623e+02 3.97643127e+02 3.97644073e+02 3.97643677e+02 3.97643921e+02 3.97645447e+02 3.97644409e+02 3.97644592e+02 3.97643890e+02 3.97644867e+02 3.97643768e+02 3.97643768e+02 3.97644073e+02 3.97644226e+02 3.97644440e+02 3.97643433e+02 3.97644440e+02 3.97644257e+02 3.97644684e+02 3.97643219e+02 3.97643555e+02 3.97643707e+02 3.97644745e+02 3.97644379e+02 3.97644287e+02 3.97644501e+02 3.97645050e+02 3.97645325e+02 3.97644073e+02 3.97646393e+02 3.97643982e+02 3.97644379e+02 3.97644379e+02 3.97644226e+02 3.97644196e+02 3.97644714e+02 3.97644562e+02 3.97644745e+02 3.97645081e+02 3.97645508e+02 3.97643951e+02 3.97643677e+02 3.97644623e+02 3.97645630e+02 3.97644531e+02 3.97643585e+02 3.97643951e+02 3.97644653e+02 3.97645416e+02 3.97645416e+02 3.97644836e+02 3.97645447e+02 3.97644379e+02 3.97643494e+02 3.97643616e+02 3.97643250e+02 3.97644165e+02 3.97646179e+02 3.97644775e+02 3.97644531e+02 3.97643738e+02 3.97644623e+02 3.97644989e+02 3.97643890e+02 3.97645294e+02 3.97643738e+02 3.97644836e+02 3.97645599e+02 3.97645996e+02 3.97644043e+02 3.97644012e+02 3.97642548e+02 3.97644348e+02 3.97643585e+02 3.97644348e+02 3.97644531e+02 3.97642456e+02 3.97644043e+02 3.97644073e+02 3.97645142e+02 3.97645325e+02 3.97644348e+02 3.97645355e+02 3.97644501e+02 3.97643707e+02 3.97643097e+02 3.97643860e+02 3.97644745e+02 3.97643616e+02 3.97643127e+02 3.97643677e+02 3.97643921e+02 3.97644623e+02 3.97644470e+02 3.97643341e+02 3.97643311e+02 3.97642517e+02 3.97644104e+02 3.97642761e+02 3.97642365e+02 3.97642975e+02 3.97643890e+02 3.97643463e+02 3.97643524e+02 3.97644012e+02 3.97643555e+02 3.97643677e+02 3.97644836e+02 3.97644989e+02 3.97646454e+02 3.97645935e+02 3.97644836e+02 3.97644043e+02 3.97646240e+02 3.97647949e+02 3.97645416e+02 3.97644623e+02 3.97646729e+02 3.97644806e+02 3.97644470e+02 3.97644684e+02 3.97644775e+02 3.97644867e+02 3.97645020e+02 3.97642883e+02 3.97643585e+02 3.97643829e+02 3.97645935e+02 3.97644592e+02 3.97645233e+02 3.97644592e+02 3.97645142e+02 3.97644226e+02 3.97644073e+02 3.97643036e+02 3.97643311e+02 3.97644073e+02 3.97644562e+02 3.97645233e+02 3.97643524e+02 3.97643372e+02 3.97642334e+02 3.97644196e+02 3.97644440e+02 3.97643341e+02 3.97642242e+02 3.97642120e+02 3.97644897e+02 3.97644592e+02 3.97645386e+02 3.97645508e+02 3.97644775e+02 3.97644836e+02 3.97644348e+02 3.97644623e+02 3.97644287e+02 3.97644196e+02 3.97645142e+02 3.97644531e+02 3.97644592e+02 3.97644409e+02 3.97645020e+02 3.97645966e+02 3.97645599e+02 3.97643341e+02 3.97643555e+02 3.97642212e+02 3.97644470e+02 3.97643341e+02 3.97645172e+02 3.97643921e+02 3.97644073e+02 3.97645264e+02 3.97645355e+02 3.97644897e+02 3.97644562e+02 3.97644684e+02 3.97644958e+02 3.97643250e+02 3.97643036e+02 3.97644073e+02 3.97644867e+02 3.97645233e+02 3.97643433e+02 3.97644714e+02 3.97644562e+02 3.97645386e+02 3.97644714e+02 3.97645050e+02 3.97643311e+02 3.97644470e+02 3.97644897e+02 3.97645996e+02 3.97645416e+02 3.97644623e+02 3.97644745e+02 3.97646301e+02 3.97647278e+02 3.97644287e+02 3.97644165e+02 3.97643616e+02 3.97645050e+02 3.97645294e+02 3.97644775e+02 3.97643188e+02 3.97642517e+02 3.97643188e+02 3.97645264e+02 3.97645294e+02 3.97643524e+02 3.97643555e+02 3.97643585e+02 3.97644684e+02 3.97644806e+02 3.97643127e+02 3.97643463e+02 3.97642883e+02 3.97644531e+02 3.97644257e+02 3.97644257e+02 3.97645294e+02 3.97644379e+02 3.97644135e+02 3.97643921e+02 3.97643738e+02 3.97644043e+02 3.97643768e+02 3.97645203e+02 3.97643768e+02 3.97643707e+02 3.97644562e+02 3.97645142e+02 3.97644440e+02 3.97644104e+02 3.97643921e+02 3.97645599e+02 3.97644226e+02 3.97644653e+02 3.97644196e+02 3.97645172e+02 3.97645386e+02 3.97643250e+02 3.97643890e+02 3.97643341e+02 3.97644257e+02 3.97644073e+02 3.97643066e+02 3.97643524e+02 3.97643616e+02 3.97643860e+02 3.97644501e+02 3.97646240e+02 3.97645874e+02 3.97644653e+02 3.97645630e+02 3.97644836e+02 3.97645111e+02 3.97644806e+02 3.97643585e+02 3.97643860e+02 3.97643799e+02 3.97645142e+02 3.97644775e+02 3.97643768e+02 3.97643585e+02 3.97645050e+02 3.97645844e+02 3.97644623e+02 3.97644531e+02 3.97643982e+02 3.97644958e+02 3.97643890e+02 3.97644073e+02 3.97644470e+02 3.97644165e+02 3.97643280e+02 3.97645020e+02 3.97644897e+02 3.97645050e+02 3.97644043e+02 3.97644287e+02 3.97644684e+02 3.97645813e+02 3.97645142e+02 3.97642883e+02 3.97643616e+02 3.97644897e+02 3.97645233e+02 3.97645996e+02 3.97644562e+02 3.97645172e+02 3.97644379e+02 3.97644318e+02 3.97644257e+02 3.97644897e+02 3.97644440e+02 3.97644653e+02 3.97644257e+02 3.97644409e+02 3.97644318e+02 3.97645477e+02 3.97644501e+02 3.97644562e+02 3.97644318e+02 3.97644928e+02 3.97647491e+02 3.97648651e+02 3.97648346e+02 3.97648071e+02 3.97649872e+02 3.97650726e+02 3.97654266e+02 3.97674103e+02 3.97731445e+02 3.97906403e+02 3.99335938e+02 4.00285706e+02 5.67414001e+02 1.26857312e+03 -2.17869184e+09 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. -31247472. 7.31914490e+02 2.68815643e+02 1.65098907e+02 1.59150711e+02 1.57835190e+02 1.57675003e+02 1.57675262e+02 1.57675690e+02 1.57675858e+02 1.57677322e+02 1.57677246e+02 1.57676361e+02 1.57675446e+02 1.57674927e+02 1.57674805e+02 1.57674789e+02 1.57675476e+02 1.57675476e+02 1.57675308e+02 1.57674423e+02 1.57674393e+02 1.57675171e+02 1.57676117e+02 1.57677200e+02 1.57676437e+02 1.57675812e+02 1.57675598e+02 1.57675110e+02 1.57675400e+02 1.57674484e+02 1.57675827e+02 1.57678986e+02 1.57677612e+02 1.57675690e+02 1.57675079e+02 1.57676224e+02 1.57675491e+02 1.57675049e+02 1.57674744e+02 1.57674393e+02 1.57675049e+02 1.57675842e+02 1.57675385e+02 1.57674774e+02 1.57674362e+02 1.57674149e+02 1.57674957e+02 1.57674408e+02 1.57674973e+02 1.57674728e+02 1.57675064e+02 1.57674957e+02 1.57674774e+02 1.57675339e+02 1.57674683e+02 1.57674591e+02 1.57675415e+02 1.57676178e+02 1.57675415e+02 1.57674896e+02 1.57675171e+02 1.57674911e+02 1.57674988e+02 1.57674713e+02 1.57674454e+02 1.57675354e+02 1.57676041e+02 1.57675552e+02 1.57675049e+02 1.57674591e+02 1.57674438e+02 1.57674957e+02 1.57674881e+02 1.57674820e+02 1.57674667e+02 1.57674957e+02 1.57675003e+02 1.57675354e+02 1.57675247e+02 1.57675232e+02 1.57674561e+02 1.57674911e+02 1.57676086e+02 1.57675842e+02 1.57674759e+02 1.57674774e+02 1.57674774e+02 1.57674835e+02 1.57675339e+02 1.57675674e+02 1.57674576e+02 1.57674759e+02 1.57675095e+02 1.57675751e+02 1.57677139e+02 1.57677094e+02 1.57676163e+02 1.57675690e+02 1.57674973e+02 1.57674530e+02 1.57674942e+02 1.57675232e+02 1.57675186e+02 1.57674850e+02 1.57674713e+02 1.57674606e+02 1.57675018e+02 1.57675171e+02 1.57675003e+02 1.57675125e+02 1.57675064e+02 1.57674744e+02 1.57674850e+02 1.57675400e+02 1.57675568e+02 1.57675217e+02 1.57674850e+02 1.57675110e+02 1.57675720e+02 1.57678024e+02 1.57677567e+02 1.57675262e+02 1.57675003e+02 1.57674591e+02 1.57674973e+02 1.57675049e+02 1.57674713e+02 1.57675003e+02 1.57675430e+02 1.57676758e+02 1.57676117e+02 1.57675095e+02 1.57674988e+02 1.57675003e+02 1.57675339e+02 1.57674789e+02 1.57675262e+02 1.57675247e+02 1.57675201e+02 1.57675598e+02 1.57674881e+02 1.57674835e+02 1.57675064e+02 1.57676178e+02 1.57675156e+02 1.57674789e+02 1.57674728e+02 1.57675415e+02 1.57674759e+02 1.57674881e+02 1.57674286e+02 1.57674713e+02 1.57675049e+02 1.57675491e+02 1.57674637e+02 1.57674484e+02 1.57673828e+02 1.57675003e+02 1.57675568e+02 1.57675293e+02 1.57674622e+02 1.57675583e+02 1.57676941e+02 1.57675674e+02 1.57675262e+02 1.57674866e+02 1.57675934e+02 1.57677231e+02 1.57678726e+02 1.57677948e+02 1.57674927e+02 1.57675201e+02 1.57675262e+02 1.57675400e+02 1.57675476e+02 1.57674667e+02 1.57675613e+02 1.57676315e+02 1.57675400e+02 1.57675598e+02 1.57675415e+02 1.57674408e+02 1.57676208e+02 1.57676727e+02 1.57676346e+02 1.57675262e+02 1.57674820e+02 1.57675903e+02 1.57676346e+02 1.57675629e+02 1.57674850e+02 1.57675079e+02 1.57675598e+02 1.57676010e+02 1.57675735e+02 1.57678101e+02 1.57676666e+02 1.57675507e+02 1.57675385e+02 1.57675034e+02 1.57674805e+02 1.57675095e+02 1.57675659e+02 1.57675583e+02 1.57675491e+02 1.57675247e+02 1.57674942e+02 1.57675171e+02 1.57675537e+02 1.57675812e+02 1.57676575e+02 1.57674744e+02 1.57675003e+02 1.57675400e+02 1.57675171e+02 1.57675461e+02 1.57674667e+02 1.57675323e+02 1.57675858e+02 1.57675751e+02 1.57675232e+02 1.57675018e+02 1.57675232e+02 1.57675613e+02 1.57675491e+02 1.57675583e+02 1.57675385e+02 1.57675629e+02 1.57675201e+02 1.57675201e+02 1.57675339e+02 1.57674515e+02 1.57675720e+02 1.57675018e+02 1.57675079e+02 1.57674362e+02 1.57675980e+02 1.57676224e+02 1.57675323e+02 1.57675873e+02 1.57675201e+02 1.57675034e+02 1.57675110e+02 1.57675262e+02 1.57675308e+02 1.57675293e+02 1.57675385e+02 1.57675156e+02 1.57676620e+02 1.57675903e+02 1.57675171e+02 1.57675171e+02 1.57675842e+02 1.57675232e+02 1.57675705e+02 1.57675278e+02 1.57675415e+02 1.57675812e+02 1.57675308e+02 1.57674988e+02 1.57674545e+02 1.57675293e+02 1.57675507e+02 1.57675201e+02 1.57676102e+02 1.57676880e+02 1.57676025e+02 1.57674713e+02 1.57676331e+02 1.57675934e+02 1.57676498e+02 1.57676041e+02 1.57675430e+02 1.57675247e+02 1.57674805e+02 1.57675201e+02 1.57674652e+02 1.57675507e+02 1.57675110e+02 1.57675156e+02 1.57675400e+02 1.57675461e+02 1.57675919e+02 1.57675156e+02 1.57675613e+02 1.57675537e+02 1.57675644e+02 1.57674789e+02 1.57675247e+02 1.57675171e+02 1.57675766e+02 1.57675446e+02 1.57675171e+02 1.57675491e+02 1.57675537e+02 1.57675339e+02 1.57675369e+02 1.57675613e+02 1.57675720e+02 1.57675522e+02 1.57675690e+02 1.57675125e+02 1.57675720e+02 1.57675369e+02 1.57675171e+02 1.57674774e+02 1.57675415e+02 1.57676254e+02 1.57676392e+02 1.57676041e+02 1.57676620e+02 1.57675964e+02 1.57676239e+02 1.57675400e+02 1.57676453e+02 1.57676270e+02 1.57675842e+02 1.57674835e+02 1.57675629e+02 1.57675446e+02 1.57676208e+02 1.57674911e+02 1.57675186e+02 1.57675415e+02 1.57675201e+02 1.57674957e+02 1.57674850e+02 1.57675568e+02 1.57675415e+02 1.57675903e+02 1.57675110e+02 1.57675339e+02 1.57675461e+02 1.57675140e+02 1.57675964e+02 1.57676025e+02 1.57676086e+02 1.57675766e+02 1.57676071e+02 1.57675690e+02 1.57675552e+02 1.57675598e+02 1.57675583e+02 1.57675903e+02 1.57675552e+02 1.57675674e+02 1.57675674e+02 1.57676056e+02 1.57675369e+02 1.57675522e+02 1.57675339e+02 1.57675522e+02 1.57676315e+02 1.57675858e+02 1.57675552e+02 1.57674850e+02 1.57674881e+02 1.57675797e+02 1.57675522e+02 1.57676453e+02 1.57677673e+02 1.57677338e+02 1.57675323e+02 1.57675644e+02 1.57676651e+02 1.57676254e+02 1.57675064e+02 1.57675125e+02 1.57674911e+02 1.57675110e+02 1.57676025e+02 1.57676453e+02 1.57676193e+02 1.57676437e+02 1.57678253e+02 1.57678299e+02 1.57676529e+02 1.57675644e+02 1.57675980e+02 1.57675430e+02 1.57675766e+02 1.57676163e+02 1.57675446e+02 1.57675262e+02 1.57675644e+02 1.57675858e+02 1.57675598e+02 1.57675034e+02 1.57675858e+02 1.57675720e+02 1.57676575e+02 1.57675415e+02 1.57675247e+02 1.57675110e+02 1.57674850e+02 1.57676025e+02 1.57678665e+02 1.57677414e+02 1.57675323e+02 1.57675323e+02 1.57675766e+02 1.57675552e+02 1.57676773e+02 1.57675385e+02 1.57675018e+02 1.57675232e+02 1.57675919e+02 1.57675507e+02 1.57675354e+02 1.57675659e+02 1.57675690e+02 1.57675125e+02 1.57675034e+02 1.57675262e+02 1.57676529e+02 1.57676270e+02 1.57676224e+02 1.57676315e+02 1.57675400e+02 1.57675674e+02 1.57676147e+02 1.57675613e+02 1.57675827e+02 1.57675522e+02 1.57677399e+02 1.57677887e+02 1.57675995e+02 1.57675583e+02 1.57675598e+02 1.57675842e+02 1.57675018e+02 1.57675568e+02 1.57675735e+02 1.57675476e+02 1.57675934e+02 1.57675781e+02 1.57675430e+02 1.57675385e+02 1.57675354e+02 1.57675690e+02 1.57676208e+02 1.57675888e+02 1.57675522e+02 1.57675430e+02 1.57675323e+02 1.57676422e+02 1.57675446e+02 1.57675583e+02 1.57675552e+02 1.57675613e+02 1.57675598e+02 1.57675690e+02 1.57675751e+02 1.57675858e+02 1.57676331e+02 1.57675369e+02 1.57675507e+02 1.57675247e+02 1.57675461e+02 1.57675812e+02 1.57676178e+02 1.57675705e+02 1.57675537e+02 1.57674927e+02 1.57675827e+02 1.57676193e+02 1.57675766e+02 1.57675919e+02 1.57674744e+02 1.57675690e+02 1.57675171e+02 1.57675232e+02 1.57676041e+02 1.57674805e+02 1.57675308e+02 1.57675522e+02 1.57676697e+02 1.57675491e+02 1.57675186e+02 1.57676147e+02 1.57674927e+02 1.57675354e+02 1.57675232e+02 1.57675552e+02 1.57675735e+02 1.57675583e+02 1.57675217e+02 1.57674927e+02 1.57675735e+02 1.57676270e+02 1.57675659e+02 1.57675781e+02 1.57676682e+02 1.57675110e+02 1.57675003e+02 1.57675049e+02 1.57675507e+02 1.57675552e+02 1.57677338e+02 1.57675980e+02 1.57674927e+02 1.57676300e+02 1.57676086e+02 1.57675720e+02 1.57676086e+02 1.57675461e+02 1.57675171e+02 1.57675034e+02 1.57675415e+02 1.57675369e+02 1.57675720e+02 1.57675476e+02 1.57674896e+02 1.57674469e+02 1.57674744e+02 1.57675491e+02 1.57675354e+02 1.57675812e+02 1.57675339e+02 1.57675125e+02 1.57675110e+02 1.57674942e+02 1.57675446e+02 1.57675201e+02 1.57674744e+02 1.57675079e+02 1.57675659e+02 1.57675140e+02 1.57675003e+02 1.57675644e+02 1.57674805e+02 1.57675156e+02 1.57676514e+02 1.57676270e+02 1.57676132e+02 1.57675323e+02 1.57675217e+02 1.57675079e+02 1.57674896e+02 1.57675095e+02 1.57675491e+02 1.57675247e+02 1.57675568e+02 1.57675034e+02 1.57675369e+02 1.57675400e+02 1.57675385e+02 1.57677841e+02 1.57678391e+02 1.57676300e+02 1.57674606e+02 1.57674835e+02 1.57674988e+02 1.57675156e+02 1.57675552e+02 1.57675171e+02 1.57674973e+02 1.57674698e+02 1.57674820e+02 1.57674927e+02 1.57675491e+02 1.57675400e+02 1.57674911e+02 1.57675705e+02 1.57675949e+02 1.57675385e+02 1.57675095e+02 1.57676697e+02 1.57675537e+02 1.57674698e+02 1.57675125e+02 1.57675552e+02 1.57674957e+02 1.57676178e+02 1.57677261e+02 1.57675949e+02 1.57675156e+02 1.57674606e+02 1.57674683e+02 1.57674591e+02 1.57675018e+02 1.57675232e+02 1.57674911e+02 1.57675262e+02 1.57675186e+02 1.57675644e+02 1.57674759e+02 1.57675171e+02 1.57674637e+02 1.57675278e+02 1.57674789e+02 1.57674774e+02 1.57674957e+02 1.57674683e+02 1.57674789e+02 1.57675064e+02 1.57675079e+02 1.57675140e+02 1.57674469e+02 1.57674927e+02 1.57674652e+02 1.57675522e+02 1.57675766e+02 1.57675476e+02 1.57675491e+02 1.57674759e+02 1.57675858e+02 1.57676010e+02 1.57675507e+02 1.57675201e+02 1.57676086e+02 1.57686172e+02 1.57712036e+02 1.57757263e+02 1.57830948e+02 1.58025314e+02 1.59113403e+02 2.04400101e+02 2.68500183e+02 3.98795105e+02 5.92097534e+02 1.29919141e+03 -2.39884979e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1595011840. 4.20809958e+09 5.17460083e+02 2.46927200e+02 1.62540085e+02 1.60223099e+02 1.57864731e+02 1.57712082e+02 1.57678802e+02 1.57676880e+02 1.57677078e+02 1.57676773e+02 1.57676056e+02 1.57675751e+02 1.57676941e+02 1.57677246e+02 1.57677292e+02 1.57675385e+02 1.57675293e+02 1.57674698e+02 1.57675217e+02 1.57675430e+02 1.57676056e+02 1.57675278e+02 1.57675354e+02 1.57674713e+02 1.57675507e+02 1.57675751e+02 1.57675079e+02 1.57674805e+02 1.57674789e+02 1.57675156e+02 1.57675323e+02 1.57675049e+02 1.57674866e+02 1.57674606e+02 1.57675690e+02 1.57675751e+02 1.57675385e+02 1.57674805e+02 1.57674728e+02 1.57675400e+02 1.57675842e+02 1.57676682e+02 1.57676300e+02 1.57676239e+02 1.57677322e+02 1.57677124e+02 1.57675797e+02 1.57676422e+02 1.57675583e+02 1.57674988e+02 1.57674805e+02 1.57675034e+02 1.57676147e+02 1.57675369e+02 1.57675064e+02 1.57674774e+02 1.57675125e+02 1.57674332e+02 1.57674835e+02 1.57675339e+02 1.57675079e+02 1.57674576e+02 1.57675568e+02 1.57675674e+02 1.57675461e+02 1.57675369e+02 1.57675568e+02 1.57676178e+02 1.57675705e+02 1.57675842e+02 1.57675690e+02 1.57676849e+02 1.57676224e+02 1.57675339e+02 1.57676559e+02 1.57676895e+02 1.57676422e+02 1.57675339e+02 1.57674927e+02 1.57675537e+02 1.57675247e+02 1.57674911e+02 1.57674744e+02 1.57675568e+02 1.57675934e+02 1.57675583e+02 1.57675110e+02 1.57674713e+02 1.57674728e+02 1.57675186e+02 1.57675705e+02 1.57676102e+02 1.57676254e+02 1.57675278e+02 1.57676468e+02 1.57677094e+02 1.57676285e+02 1.57676025e+02 1.57674667e+02 1.57675690e+02 1.57675323e+02 1.57675293e+02 1.57675568e+02 1.57674911e+02 1.57675522e+02 1.57675034e+02 1.57675690e+02 1.57675613e+02 1.57676437e+02 1.57676514e+02 1.57675354e+02 1.57674850e+02 1.57674545e+02 1.57675064e+02 1.57675705e+02 1.57675430e+02 1.57675369e+02 1.57675568e+02 1.57674896e+02 1.57675400e+02 1.57675293e+02 1.57675156e+02 1.57675858e+02 1.57675018e+02 1.57675537e+02 1.57675613e+02 1.57675400e+02 1.57675186e+02 1.57674667e+02 1.57676239e+02 1.57676147e+02 1.57675476e+02 1.57674820e+02 1.57675018e+02 1.57675613e+02 1.57675751e+02 1.57675217e+02 1.57674789e+02 1.57674881e+02 1.57675201e+02 1.57675446e+02 1.57675140e+02 1.57675140e+02 1.57674652e+02 1.57675735e+02 1.57675674e+02 1.57675613e+02 1.57675232e+02 1.57674911e+02 1.57675430e+02 1.57675903e+02 1.57675552e+02 1.57675934e+02 1.57675690e+02 1.57675903e+02 1.57675461e+02 1.57675293e+02 1.57675201e+02 1.57675232e+02 1.57675476e+02 1.57675491e+02 1.57675156e+02 1.57675354e+02 1.57675308e+02 1.57676682e+02 1.57676773e+02 1.57675079e+02 1.57675385e+02 1.57674973e+02 1.57675079e+02 1.57675217e+02 1.57675018e+02 1.57675415e+02 1.57674881e+02 1.57675659e+02 1.57675247e+02 1.57674774e+02 1.57674438e+02 1.57674377e+02 1.57675079e+02 1.57675354e+02 1.57675125e+02 1.57675781e+02 1.57675537e+02 1.57676025e+02 1.57676819e+02 1.57678146e+02 1.57678787e+02 1.57677109e+02 1.57678238e+02 1.57677231e+02 1.57675537e+02 1.57675446e+02 1.57675247e+02 1.57675613e+02 1.57675735e+02 1.57675415e+02 1.57677673e+02 1.57676987e+02 1.57675949e+02 1.57675095e+02 1.57675674e+02 1.57675430e+02 1.57675751e+02 1.57675949e+02 1.57676239e+02 1.57675781e+02 1.57675491e+02 1.57675186e+02 1.57675873e+02 1.57675568e+02 1.57675507e+02 1.57675171e+02 1.57674500e+02 1.57674759e+02 1.57676697e+02 1.57676483e+02 1.57675903e+02 1.57675537e+02 1.57675690e+02 1.57675323e+02 1.57675369e+02 1.57676682e+02 1.57677216e+02 1.57676086e+02 1.57675552e+02 1.57676041e+02 1.57675095e+02 1.57675064e+02 1.57675598e+02 1.57675903e+02 1.57675003e+02 1.57675552e+02 1.57675217e+02 1.57675201e+02 1.57674774e+02 1.57675110e+02 1.57674850e+02 1.57675751e+02 1.57675079e+02 1.57675400e+02 1.57675003e+02 1.57674896e+02 1.57674988e+02 1.57675247e+02 1.57675201e+02 1.57675354e+02 1.57674820e+02 1.57675156e+02 1.57674988e+02 1.57675385e+02 1.57674438e+02 1.57674667e+02 1.57674637e+02 1.57675278e+02 1.57675186e+02 1.57675217e+02 1.57675079e+02 1.57674805e+02 1.57675095e+02 1.57675217e+02 1.57674911e+02 1.57675293e+02 1.57675278e+02 1.57675674e+02 1.57675705e+02 1.57674835e+02 1.57675491e+02 1.57675308e+02 1.57675781e+02 1.57675171e+02 1.57675125e+02 1.57675003e+02 1.57675476e+02 1.57675583e+02 1.57675293e+02 1.57675110e+02 1.57674881e+02 1.57674866e+02 1.57675415e+02 1.57675690e+02 1.57676376e+02 1.57675461e+02 1.57675919e+02 1.57675003e+02 1.57675278e+02 1.57674820e+02 1.57675293e+02 1.57674561e+02 1.57675583e+02 1.57675354e+02 1.57675034e+02 1.57675400e+02 1.57675262e+02 1.57675171e+02 1.57675278e+02 1.57675629e+02 1.57675797e+02 1.57675537e+02 1.57675568e+02 1.57675293e+02 1.57675262e+02 1.57675110e+02 1.57675323e+02 1.57675552e+02 1.57675262e+02 1.57675064e+02 1.57674973e+02 1.57675613e+02 1.57675430e+02 1.57675552e+02 1.57674759e+02 1.57674911e+02 1.57674744e+02 1.57675873e+02 1.57675812e+02 1.57675552e+02 1.57674973e+02 1.57675156e+02 1.57675125e+02 1.57675598e+02 1.57675049e+02 1.57675339e+02 1.57675125e+02 1.57675720e+02 1.57675293e+02 1.57675827e+02 1.57675919e+02 1.57676788e+02 1.57675781e+02 1.57675415e+02 1.57674911e+02 1.57675644e+02 1.57675095e+02 1.57675232e+02 1.57675308e+02 1.57675720e+02 1.57675354e+02 1.57675400e+02 1.57675629e+02 1.57675522e+02 1.57675354e+02 1.57675262e+02 1.57675217e+02 1.57675995e+02 1.57675781e+02 1.57675568e+02 1.57675110e+02 1.57675217e+02 1.57675598e+02 1.57675461e+02 1.57675629e+02 1.57675049e+02 1.57675095e+02 1.57675156e+02 1.57675659e+02 1.57675354e+02 1.57675323e+02 1.57674622e+02 1.57675064e+02 1.57674683e+02 1.57676361e+02 1.57675659e+02 1.57675522e+02 1.57675278e+02 1.57675003e+02 1.57674942e+02 1.57675461e+02 1.57674942e+02 1.57675644e+02 1.57674774e+02 1.57675293e+02 1.57674866e+02 1.57675659e+02 1.57675400e+02 1.57676422e+02 1.57675430e+02 1.57674805e+02 1.57674820e+02 1.57675110e+02 1.57675186e+02 1.57675446e+02 1.57674683e+02 1.57674835e+02 1.57675659e+02 1.57675674e+02 1.57675217e+02 1.57674271e+02 1.57674759e+02 1.57675232e+02 1.57675674e+02 1.57675552e+02 1.57675461e+02 1.57675110e+02 1.57675034e+02 1.57675247e+02 1.57675629e+02 1.57675400e+02 1.57675797e+02 1.57675354e+02 1.57675690e+02 1.57675430e+02 1.57676086e+02 1.57676147e+02 1.57675842e+02 1.57675812e+02 1.57675751e+02 1.57675446e+02 1.57675613e+02 1.57674744e+02 1.57675430e+02 1.57675430e+02 1.57675659e+02 1.57675110e+02 1.57674881e+02 1.57675186e+02 1.57674622e+02 1.57675262e+02 1.57675858e+02 1.57675293e+02 1.57674927e+02 1.57675018e+02 1.57674713e+02 1.57674561e+02 1.57675140e+02 1.57675003e+02 1.57675232e+02 1.57674896e+02 1.57674789e+02 1.57674652e+02 1.57675018e+02 1.57675583e+02 1.57675201e+02 1.57674973e+02 1.57674637e+02 1.57675125e+02 1.57675476e+02 1.57675598e+02 1.57674698e+02 1.57674957e+02 1.57674225e+02 1.57675507e+02 1.57674957e+02 1.57675568e+02 1.57675156e+02 1.57676575e+02 1.57678238e+02 1.57674011e+02 1.57680435e+02 1.57713516e+02 1.57756943e+02 1.57823074e+02 1.57813339e+02 1.57900589e+02 1.58560471e+02 2.02116760e+02 2.66043640e+02 3.99504242e+02 3.98611725e+02 5.58024475e+02 1.10857764e+03 1071069376. 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. 0. 0. 0. 0. 0. 0. 0. 817216960. 4.28455841e+02 2.27863358e+02 1.61532166e+02 1.61673401e+02 1.60371811e+02 1.59074966e+02 1.57712982e+02 1.57678101e+02 1.57675659e+02 1.57675430e+02 1.57675705e+02 1.57675598e+02 1.57675812e+02 1.57675934e+02 1.57676117e+02 1.57675598e+02 1.57674866e+02 1.57674652e+02 1.57674805e+02 1.57675644e+02 1.57675262e+02 1.57675095e+02 1.57674667e+02 1.57675003e+02 1.57674530e+02 1.57674744e+02 1.57674805e+02 1.57675064e+02 1.57674713e+02 1.57674973e+02 1.57674942e+02 1.57674973e+02 1.57675003e+02 1.57674713e+02 1.57674835e+02 1.57674652e+02 1.57674881e+02 1.57675247e+02 1.57675201e+02 1.57675140e+02 1.57674896e+02 1.57674820e+02 1.57674927e+02 1.57675171e+02 1.57675156e+02 1.57675049e+02 1.57674759e+02 1.57674500e+02 1.57674713e+02 1.57674759e+02 1.57675018e+02 1.57674927e+02 1.57675476e+02 1.57675201e+02 1.57674881e+02 1.57674942e+02 1.57674973e+02 1.57675018e+02 1.57674652e+02 1.57674438e+02 1.57674637e+02 1.57675125e+02 1.57675629e+02 1.57675369e+02 1.57674927e+02 1.57674500e+02 1.57674637e+02 1.57674988e+02 1.57674927e+02 1.57674530e+02 1.57674911e+02 1.57674973e+02 1.57674728e+02 1.57674591e+02 1.57675049e+02 1.57674881e+02 1.57675537e+02 1.57675003e+02 1.57675262e+02 1.57674713e+02 1.57675064e+02 1.57674561e+02 1.57675049e+02 1.57674988e+02 1.57675415e+02 1.57675339e+02 1.57674820e+02 1.57674835e+02 1.57674988e+02 1.57674789e+02 1.57674789e+02 1.57675034e+02 1.57675003e+02 1.57675079e+02 1.57674423e+02 1.57674637e+02 1.57674820e+02 1.57675171e+02 1.57675110e+02 1.57674911e+02 1.57674438e+02 1.57674728e+02 1.57674454e+02 1.57674835e+02 1.57674362e+02 1.57674973e+02 1.57674698e+02 1.57674957e+02 1.57674759e+02 1.57674881e+02 1.57674637e+02 1.57674713e+02 1.57674957e+02 1.57675339e+02 1.57674866e+02 1.57674667e+02 1.57674774e+02 1.57674789e+02 1.57674973e+02 1.57674820e+02 1.57674591e+02 1.57674911e+02 1.57674454e+02 1.57675079e+02 1.57674652e+02 1.57675034e+02 1.57674927e+02 1.57674850e+02 1.57674774e+02 1.57675552e+02 1.57674896e+02 1.57674591e+02 1.57674316e+02 1.57674591e+02 1.57674759e+02 1.57675354e+02 1.57675613e+02 1.57674744e+02 1.57674866e+02 1.57674683e+02 1.57674164e+02 1.57674515e+02 1.57674774e+02 1.57674835e+02 1.57674789e+02 1.57674591e+02 1.57674667e+02 1.57674301e+02 1.57674957e+02 1.57674591e+02 1.57674744e+02 1.57674835e+02 1.57674866e+02 1.57675430e+02 1.57675568e+02 1.57675049e+02 1.57674805e+02 1.57674805e+02 1.57675140e+02 1.57675247e+02 1.57675308e+02 1.57675903e+02 1.57675613e+02 1.57675720e+02 1.57674957e+02 1.57674805e+02 1.57674622e+02 1.57674606e+02 1.57674805e+02 1.57674728e+02 1.57674622e+02 1.57674530e+02 1.57674530e+02 1.57674713e+02 1.57674408e+02 1.57674133e+02 1.57675400e+02 1.57675095e+02 1.57675079e+02 1.57674316e+02 1.57674698e+02 1.57674500e+02 1.57674515e+02 1.57674789e+02 1.57674362e+02 1.57674149e+02 1.57674454e+02 1.57674622e+02 1.57674805e+02 1.57674469e+02 1.57674362e+02 1.57674744e+02 1.57674301e+02 1.57674881e+02 1.57674515e+02 1.57674728e+02 1.57674377e+02 1.57674393e+02 1.57674881e+02 1.57674927e+02 1.57674423e+02 1.57674301e+02 1.57674133e+02 1.57674622e+02 1.57674225e+02 1.57674530e+02 1.57674438e+02 1.57674667e+02 1.57674713e+02 1.57674484e+02 1.57673904e+02 1.57674271e+02 1.57674347e+02 1.57674728e+02 1.57674301e+02 1.57674164e+02 1.57674484e+02 1.57674179e+02 1.57675003e+02 1.57674347e+02 1.57674835e+02 1.57674454e+02 1.57674545e+02 1.57674850e+02 1.57674744e+02 1.57674576e+02 1.57674347e+02 1.57674240e+02 1.57674713e+02 1.57674698e+02 1.57675003e+02 1.57674377e+02 1.57674500e+02 1.57674652e+02 1.57675049e+02 1.57674652e+02 1.57674744e+02 1.57674515e+02 1.57675079e+02 1.57674973e+02 1.57674515e+02 1.57674805e+02 1.57674652e+02 1.57674469e+02 1.57674561e+02 1.57674484e+02 1.57674835e+02 1.57674927e+02 1.57676056e+02 1.57675278e+02 1.57674683e+02 1.57674469e+02 1.57675293e+02 1.57676056e+02 1.57675156e+02 1.57674530e+02 1.57674896e+02 1.57674881e+02 1.57674667e+02 1.57674683e+02 1.57674515e+02 1.57674622e+02 1.57674408e+02 1.57675079e+02 1.57674820e+02 1.57674896e+02 1.57674347e+02 1.57674423e+02 1.57674927e+02 1.57674911e+02 1.57674835e+02 1.57674515e+02 1.57674408e+02 1.57675323e+02 1.57675156e+02 1.57675415e+02 1.57674866e+02 1.57675217e+02 1.57675171e+02 1.57675415e+02 1.57674759e+02 1.57675018e+02 1.57675156e+02 1.57675049e+02 1.57674866e+02 1.57674469e+02 1.57674622e+02 1.57674667e+02 1.57675125e+02 1.57674820e+02 1.57674454e+02 1.57675125e+02 1.57674606e+02 1.57675446e+02 1.57675262e+02 1.57675507e+02 1.57676102e+02 1.57676422e+02 1.57675369e+02 1.57674759e+02 1.57674911e+02 1.57674515e+02 1.57674835e+02 1.57674622e+02 1.57675217e+02 1.57674667e+02 1.57675171e+02 1.57675064e+02 1.57675125e+02 1.57674881e+02 1.57674469e+02 1.57674744e+02 1.57674728e+02 1.57675217e+02 1.57674927e+02 1.57674850e+02 1.57674988e+02 1.57674438e+02 1.57675034e+02 1.57674286e+02 1.57674881e+02 1.57674774e+02 1.57674698e+02 1.57674988e+02 1.57674500e+02 1.57675232e+02 1.57674789e+02 1.57674988e+02 1.57674713e+02 1.57675537e+02 1.57675659e+02 1.57675964e+02 1.57674835e+02 1.57674759e+02 1.57674683e+02 1.57674545e+02 1.57674850e+02 1.57674530e+02 1.57674911e+02 1.57674850e+02 1.57674683e+02 1.57674866e+02 1.57674759e+02 1.57675323e+02 1.57674271e+02 1.57674576e+02 1.57674683e+02 1.57675400e+02 1.57675491e+02 1.57675613e+02 1.57674881e+02 1.57674713e+02 1.57675110e+02 1.57675354e+02 1.57675598e+02 1.57674667e+02 1.57674606e+02 1.57674896e+02 1.57675354e+02 1.57675949e+02 1.57675247e+02 1.57675339e+02 1.57674957e+02 1.57675247e+02 1.57674789e+02 1.57674835e+02 1.57674988e+02 1.57674698e+02 1.57675262e+02 1.57674805e+02 1.57674911e+02 1.57675278e+02 1.57674454e+02 1.57674622e+02 1.57674683e+02 1.57674713e+02 1.57675308e+02 1.57674820e+02 1.57674759e+02 1.57674606e+02 1.57674484e+02 1.57674820e+02 1.57674713e+02 1.57674850e+02 1.57674683e+02 1.57674667e+02 1.57674850e+02 1.57674255e+02 1.57674744e+02 1.57674515e+02 1.57674622e+02 1.57674484e+02 1.57674789e+02 1.57674820e+02 1.57674744e+02 1.57675247e+02 1.57674637e+02 1.57674210e+02 1.57674530e+02 1.57674728e+02 1.57675293e+02 1.57674973e+02 1.57674759e+02 1.57674500e+02 1.57674988e+02 1.57674591e+02 1.57674393e+02 1.57674210e+02 1.57674973e+02 1.57675186e+02 1.57675278e+02 1.57675018e+02 1.57674576e+02 1.57674728e+02 1.57674454e+02 1.57674744e+02 1.57674545e+02 1.57674301e+02 1.57674576e+02 1.57675262e+02 1.57675598e+02 1.57675629e+02 1.57675140e+02 1.57675735e+02 1.57674866e+02 1.57674728e+02 1.57675110e+02 1.57674896e+02 1.57674942e+02 1.57674866e+02 1.57674545e+02 1.57674423e+02 1.57674240e+02 1.57674850e+02 1.57674805e+02 1.57674652e+02 1.57675308e+02 1.57675293e+02 1.57675430e+02 1.57674744e+02 1.57675400e+02 1.57675766e+02 1.57675308e+02 1.57674530e+02 1.57674255e+02 1.57674805e+02 1.57674835e+02 1.57675095e+02 1.57675156e+02 1.57674667e+02 1.57674667e+02 1.57674789e+02 1.57674652e+02 1.57674744e+02 1.57674820e+02 1.57674820e+02 1.57674957e+02 1.57674545e+02 1.57675110e+02 1.57674820e+02 1.57675034e+02 1.57674774e+02 1.57674118e+02 1.57674545e+02 1.57674545e+02 1.57675262e+02 1.57674683e+02 1.57675003e+02 1.57674973e+02 1.57674652e+02 1.57675278e+02 1.57676529e+02 1.57676987e+02 1.57675583e+02 1.57674911e+02 1.57675507e+02 1.57675125e+02 1.57674545e+02 1.57674713e+02 1.57674652e+02 1.57674744e+02 1.57675415e+02 1.57674866e+02 1.57675018e+02 1.57674500e+02 1.57674393e+02 1.57674973e+02 1.57675415e+02 1.57675232e+02 1.57674530e+02 1.57674805e+02 1.57674820e+02 1.57674881e+02 1.57674637e+02 1.57675949e+02 1.57676498e+02 1.57674530e+02 1.57674530e+02 1.57675308e+02 1.57675140e+02 1.57674957e+02 1.57674393e+02 1.57674606e+02 1.57674866e+02 1.57674911e+02 1.57674591e+02 1.57674454e+02 1.57674088e+02 1.57675064e+02 1.57674591e+02 1.57674622e+02 1.57674362e+02 1.57674393e+02 1.57674820e+02 1.57674667e+02 1.57674713e+02 1.57674500e+02 1.57674393e+02 1.57675323e+02 1.57675369e+02 1.57674423e+02 1.57674545e+02 1.57674377e+02 1.57674606e+02 1.57675476e+02 1.57675323e+02 1.57675034e+02 1.57674164e+02 1.57674850e+02 1.57674530e+02 1.57674850e+02 1.57674850e+02 1.57674408e+02 1.57674652e+02 1.57675003e+02 1.57674606e+02 1.57674561e+02 1.57674500e+02 1.57674973e+02 1.57674789e+02 1.57675674e+02 1.57676041e+02 1.57675430e+02 1.57674942e+02 1.57675125e+02 1.57676056e+02 1.57675186e+02 1.57674744e+02 1.57674820e+02 1.57674515e+02 1.57674301e+02 1.57674362e+02 1.57674881e+02 1.57674835e+02 1.57674820e+02 1.57674759e+02 1.57674744e+02 1.57675507e+02 1.57675949e+02 1.57675079e+02 1.57674988e+02 1.57675232e+02 1.57674942e+02 1.57674820e+02 1.57674728e+02 1.57675079e+02 1.57675003e+02 1.57674545e+02 1.57674850e+02 1.57675583e+02 1.57675064e+02 1.57674576e+02 1.57674881e+02 1.57675125e+02 1.57675064e+02 1.57674576e+02 1.57674667e+02 1.57675018e+02 1.57675293e+02 1.57676086e+02 1.57675354e+02 1.57674866e+02 1.57674606e+02 1.57675278e+02 1.57674927e+02 1.57675079e+02 1.57674805e+02 1.57674652e+02 1.57675278e+02 1.57674927e+02 1.57675201e+02 1.57675278e+02 1.57677216e+02 1.57676849e+02 1.57675827e+02 1.57675278e+02 1.57675034e+02 1.57675110e+02 1.57675400e+02 1.57675369e+02 1.57674393e+02 1.57673920e+02 1.57673462e+02 1.57677994e+02 1.57812790e+02 1.58550797e+02 2.01260529e+02 2.60168976e+02 6.30915466e+02 1.95912854e+03 -2.17869184e+09 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. -31247472. 6.08374146e+02 1.33696945e+02 8.75803299e+01 6.70407867e+01 6.66361923e+01 6.64409332e+01 6.64282837e+01 6.64282913e+01 6.64279938e+01 6.64280701e+01 6.64281921e+01 6.64282150e+01 6.64281845e+01 6.64281921e+01 6.64283295e+01 6.64281464e+01 6.64282379e+01 6.64287186e+01 6.64287567e+01 6.64286728e+01 6.64282074e+01 6.64281921e+01 6.64283524e+01 6.64282532e+01 6.64280853e+01 6.64281082e+01 6.64281921e+01 6.64280853e+01 6.64281158e+01 6.64280319e+01 6.64282150e+01 6.64282837e+01 6.64285278e+01 6.64285355e+01 6.64282150e+01 6.64280777e+01 6.64282455e+01 6.64283295e+01 6.64281464e+01 6.64282684e+01 6.64282532e+01 6.64282684e+01 6.64284363e+01 6.64281464e+01 6.64281616e+01 6.64281845e+01 6.64281311e+01 6.64281845e+01 6.64282837e+01 6.64283142e+01 6.64281464e+01 6.64281616e+01 6.64284744e+01 6.64283371e+01 6.64286346e+01 6.64282837e+01 6.64282761e+01 6.64287109e+01 6.64286194e+01 6.64282227e+01 6.64281464e+01 6.64281235e+01 6.64281845e+01 6.64281158e+01 6.64281845e+01 6.64282455e+01 6.64281769e+01 6.64281845e+01 6.64280319e+01 6.64281158e+01 6.64281693e+01 6.64282150e+01 6.64281769e+01 6.64282608e+01 6.64281311e+01 6.64282761e+01 6.64282074e+01 6.64281769e+01 6.64281616e+01 6.64283447e+01 6.64282303e+01 6.64281464e+01 6.64281998e+01 6.64282074e+01 6.64283066e+01 6.64282913e+01 6.64282227e+01 6.64280853e+01 6.64281082e+01 6.64281235e+01 6.64281311e+01 6.64283371e+01 6.64282913e+01 6.64281921e+01 6.64282837e+01 6.64280624e+01 6.64281235e+01 6.64281082e+01 6.64282303e+01 6.64282532e+01 6.64282150e+01 6.64282227e+01 6.64281845e+01 6.64285049e+01 6.64284668e+01 6.64282303e+01 6.64281387e+01 6.64283524e+01 6.64284744e+01 6.64281540e+01 6.64281921e+01 6.64281616e+01 6.64281464e+01 6.64281387e+01 6.64282074e+01 6.64281998e+01 6.64283676e+01 6.64283752e+01 6.64281616e+01 6.64282379e+01 6.64284821e+01 6.64280853e+01 6.64281235e+01 6.64282150e+01 6.64283142e+01 6.64281769e+01 6.64281540e+01 6.64283447e+01 6.64283752e+01 6.64284744e+01 6.64282913e+01 6.64282303e+01 6.64282379e+01 6.64281540e+01 6.64282455e+01 6.64283218e+01 6.64282455e+01 6.64282379e+01 6.64285965e+01 6.64288788e+01 6.64285049e+01 6.64282455e+01 6.64282608e+01 6.64283447e+01 6.64281540e+01 6.64282227e+01 6.64281998e+01 6.64282684e+01 6.64282227e+01 6.64284134e+01 6.64286499e+01 6.64284821e+01 6.64282761e+01 6.64283524e+01 6.64282684e+01 6.64282837e+01 6.64282837e+01 6.64285965e+01 6.64284668e+01 6.64282303e+01 6.64283752e+01 6.64283447e+01 6.64285660e+01 6.64283218e+01 6.64282761e+01 6.64282761e+01 6.64285126e+01 6.64286499e+01 6.64284210e+01 6.64283295e+01 6.64286575e+01 6.64285049e+01 6.64285202e+01 6.64284592e+01 6.64283066e+01 6.64283676e+01 6.64283905e+01 6.64283218e+01 6.64283905e+01 6.64284439e+01 6.64286728e+01 6.64284439e+01 6.64283829e+01 6.64283752e+01 6.64283066e+01 6.64283295e+01 6.64283829e+01 6.64283371e+01 6.64284286e+01 6.64283676e+01 6.64284821e+01 6.64284515e+01 6.64282837e+01 6.64283752e+01 6.64286652e+01 6.64284897e+01 6.64286652e+01 6.64283295e+01 6.64282913e+01 6.64282150e+01 6.64282684e+01 6.64283142e+01 6.64283600e+01 6.64282990e+01 6.64283676e+01 6.64282532e+01 6.64281387e+01 6.64282303e+01 6.64280701e+01 6.64281540e+01 6.64281387e+01 6.64282074e+01 6.64283295e+01 6.64282074e+01 6.64282150e+01 6.64282990e+01 6.64283371e+01 6.64283295e+01 6.64284821e+01 6.64286270e+01 6.64282303e+01 6.64283676e+01 6.64283524e+01 6.64282684e+01 6.64282761e+01 6.64282379e+01 6.64283752e+01 6.64283676e+01 6.64285202e+01 6.64283142e+01 6.64283142e+01 6.64282684e+01 6.64282150e+01 6.64282608e+01 6.64282684e+01 6.64284592e+01 6.64284134e+01 6.64284210e+01 6.64282150e+01 6.64282532e+01 6.64282761e+01 6.64282532e+01 6.64282837e+01 6.64283142e+01 6.64285049e+01 6.64282684e+01 6.64282074e+01 6.64281769e+01 6.64281693e+01 6.64282532e+01 6.64282684e+01 6.64282684e+01 6.64283524e+01 6.64284058e+01 6.64284668e+01 6.64284439e+01 6.64283905e+01 6.64284668e+01 6.64283676e+01 6.64282990e+01 6.64281921e+01 6.64283752e+01 6.64282913e+01 6.64281845e+01 6.64281311e+01 6.64281693e+01 6.64281006e+01 6.64283981e+01 6.64286118e+01 6.64283752e+01 6.64285355e+01 6.64286194e+01 6.64290390e+01 6.64284134e+01 6.64282837e+01 6.64282455e+01 6.64282761e+01 6.64283905e+01 6.64283600e+01 6.64282150e+01 6.64281311e+01 6.64284821e+01 6.64282532e+01 6.64281769e+01 6.64281235e+01 6.64282608e+01 6.64282379e+01 6.64282913e+01 6.64285202e+01 6.64284515e+01 6.64283066e+01 6.64281769e+01 6.64281845e+01 6.64281921e+01 6.64281998e+01 6.64282303e+01 6.64282227e+01 6.64283371e+01 6.64282303e+01 6.64285965e+01 6.64289474e+01 6.64288864e+01 6.64283829e+01 6.64281616e+01 6.64281311e+01 6.64282913e+01 6.64283066e+01 6.64283066e+01 6.64282074e+01 6.64281235e+01 6.64281998e+01 6.64282074e+01 6.64282608e+01 6.64282227e+01 6.64280701e+01 6.64281006e+01 6.64281616e+01 6.64282761e+01 6.64284210e+01 6.64283905e+01 6.64282150e+01 6.64282227e+01 6.64283600e+01 6.64284210e+01 6.64281464e+01 6.64281082e+01 6.64284744e+01 6.64286118e+01 6.64285965e+01 6.64281464e+01 6.64281769e+01 6.64281616e+01 6.64283066e+01 6.64281769e+01 6.64282303e+01 6.64283066e+01 6.64283218e+01 6.64282455e+01 6.64281387e+01 6.64281158e+01 6.64280014e+01 6.64282379e+01 6.64287949e+01 6.64282455e+01 6.64281387e+01 6.64285049e+01 6.64283752e+01 6.64281845e+01 6.64281464e+01 6.64282227e+01 6.64281693e+01 6.64282455e+01 6.64281235e+01 6.64283524e+01 6.64281540e+01 6.64281921e+01 6.64283447e+01 6.64281845e+01 6.64281158e+01 6.64284058e+01 6.64287643e+01 6.64284744e+01 6.64281998e+01 6.64281769e+01 6.64281616e+01 6.64281998e+01 6.64281693e+01 6.64283752e+01 6.64281845e+01 6.64281845e+01 6.64281311e+01 6.64281311e+01 6.64281158e+01 6.64282684e+01 6.64282913e+01 6.64284439e+01 6.64284210e+01 6.64282455e+01 6.64281769e+01 6.64281921e+01 6.64285049e+01 6.64284286e+01 6.64281235e+01 6.64281693e+01 6.64281769e+01 6.64282761e+01 6.64282379e+01 6.64282532e+01 6.64282150e+01 6.64285583e+01 6.64285049e+01 6.64282608e+01 6.64286804e+01 6.64281158e+01 6.64285889e+01 6.64293289e+01 6.64288559e+01 6.64281998e+01 6.64282379e+01 6.64283142e+01 6.64282227e+01 6.64282074e+01 6.64281616e+01 6.64284668e+01 6.64282608e+01 6.64283829e+01 6.64290848e+01 6.64281235e+01 6.64281158e+01 6.64282303e+01 6.64281464e+01 6.64281998e+01 6.64281998e+01 6.64283829e+01 6.64283218e+01 6.64281616e+01 6.64282150e+01 6.64281464e+01 6.64281769e+01 6.64281540e+01 6.64280624e+01 6.64281540e+01 6.64282227e+01 6.64282608e+01 6.64281540e+01 6.64283905e+01 6.64284058e+01 6.64281311e+01 6.64281921e+01 6.64283829e+01 6.64281311e+01 6.64281006e+01 6.64281616e+01 6.64281998e+01 6.64282761e+01 6.64282150e+01 6.64282761e+01 6.64282303e+01 6.64282074e+01 6.64281693e+01 6.64281616e+01 6.64281464e+01 6.64283752e+01 6.64282455e+01 6.64282455e+01 6.64282684e+01 6.64281387e+01 6.64281845e+01 6.64281006e+01 6.64281616e+01 6.64281235e+01 6.64282837e+01 6.64282303e+01 6.64281616e+01 6.64282532e+01 6.64281540e+01 6.64282379e+01 6.64282684e+01 6.64281769e+01 6.64282684e+01 6.64284286e+01 6.64282684e+01 6.64282532e+01 6.64281693e+01 6.64285583e+01 6.64281616e+01 6.64282303e+01 6.64281311e+01 6.64282379e+01 6.64282532e+01 6.64282455e+01 6.64282074e+01 6.64286194e+01 6.64284134e+01 6.64282913e+01 6.64281693e+01 6.64281921e+01 6.64282608e+01 6.64282837e+01 6.64284210e+01 6.64282074e+01 6.64282303e+01 6.64281769e+01 6.64282761e+01 6.64282761e+01 6.64284363e+01 6.64281998e+01 6.64282150e+01 6.64285278e+01 6.64282990e+01 6.64280777e+01 6.64282227e+01 6.64281540e+01 6.64281769e+01 6.64281540e+01 6.64282150e+01 6.64283524e+01 6.64280243e+01 6.64281921e+01 6.64281998e+01 6.64282837e+01 6.64282303e+01 6.64281616e+01 6.64282532e+01 6.64284515e+01 6.64282837e+01 6.64283752e+01 6.64281158e+01 6.64282227e+01 6.64281845e+01 6.64281616e+01 6.64281311e+01 6.64281006e+01 6.64282532e+01 6.64282990e+01 6.64282379e+01 6.64281464e+01 6.64281006e+01 6.64281921e+01 6.64281158e+01 6.64281845e+01 6.64281921e+01 6.64281540e+01 6.64282227e+01 6.64282608e+01 6.64284134e+01 6.64281387e+01 6.64280090e+01 6.64281540e+01 6.64281845e+01 6.64282837e+01 6.64280701e+01 6.64281769e+01 6.64282608e+01 6.64281464e+01 6.64281540e+01 6.64281921e+01 6.64283371e+01 6.64281845e+01 6.64281921e+01 6.64281235e+01 6.64284515e+01 6.64283676e+01 6.64282303e+01 6.64281006e+01 6.64285355e+01 6.64281845e+01 6.64282761e+01 6.64288025e+01 6.64284515e+01 6.64280319e+01 6.64283447e+01 6.64281769e+01 6.64282074e+01 6.64282532e+01 6.64282074e+01 6.64281235e+01 6.64281540e+01 6.64282227e+01 6.64281769e+01 6.64280853e+01 6.64281769e+01 6.64282379e+01 6.64282379e+01 6.64284286e+01 6.64289398e+01 6.64285431e+01 6.64281693e+01 6.64282227e+01 6.64282227e+01 6.64281769e+01 6.64283066e+01 6.64282455e+01 6.64284363e+01 6.64281921e+01 6.64283218e+01 6.64281998e+01 6.64281464e+01 6.64281540e+01 6.64281235e+01 6.64281540e+01 6.64282379e+01 6.64282532e+01 6.64281387e+01 6.64281998e+01 6.64282379e+01 6.64282913e+01 6.64282684e+01 6.64281769e+01 6.64282303e+01 6.64281921e+01 6.64281769e+01 6.64281235e+01 6.64282532e+01 6.64283142e+01 6.64281998e+01 6.64280853e+01 6.64281540e+01 6.64281998e+01 6.64283600e+01 6.64283142e+01 6.64284286e+01 6.64282608e+01 6.64281693e+01 6.64281311e+01 6.64282150e+01 6.64282150e+01 6.64282379e+01 6.64281769e+01 6.64285507e+01 6.64284515e+01 6.64281921e+01 6.64283371e+01 6.64281311e+01 6.64279022e+01 6.64281921e+01 6.64295273e+01 6.64341888e+01 6.64331207e+01 6.64570694e+01 6.69586182e+01 9.91563416e+01 2.00636612e+02 -883769088. 193475584. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1595011840. 4.20809958e+09 -1.01925243e+10 5.91009216e+02 1.33273209e+02 8.68551483e+01 6.70190430e+01 6.65640335e+01 6.64519348e+01 6.64347229e+01 6.64293213e+01 6.64294968e+01 6.64292908e+01 6.64284058e+01 6.64281540e+01 6.64281082e+01 6.64281921e+01 6.64280777e+01 6.64281158e+01 6.64281769e+01 6.64281998e+01 6.64284439e+01 6.64282532e+01 6.64281845e+01 6.64280014e+01 6.64283829e+01 6.64280548e+01 6.64282074e+01 6.64280243e+01 6.64282074e+01 6.64280472e+01 6.64284058e+01 6.64285126e+01 6.64282455e+01 6.64280319e+01 6.64280777e+01 6.64281311e+01 6.64281464e+01 6.64281464e+01 6.64281845e+01 6.64281082e+01 6.64281387e+01 6.64281921e+01 6.64281616e+01 6.64281921e+01 6.64283600e+01 6.64286270e+01 6.64283752e+01 6.64282227e+01 6.64281235e+01 6.64281235e+01 6.64284439e+01 6.64283371e+01 6.64281464e+01 6.64282227e+01 6.64281998e+01 6.64281616e+01 6.64281464e+01 6.64281464e+01 6.64282990e+01 6.64282074e+01 6.64282227e+01 6.64281845e+01 6.64281616e+01 6.64284058e+01 6.64284134e+01 6.64282455e+01 6.64280853e+01 6.64281464e+01 6.64282074e+01 6.64281616e+01 6.64285660e+01 6.64287720e+01 6.64284821e+01 6.64281693e+01 6.64281235e+01 6.64281616e+01 6.64281616e+01 6.64282074e+01 6.64283600e+01 6.64282455e+01 6.64281235e+01 6.64281616e+01 6.64280930e+01 6.64281540e+01 6.64281235e+01 6.64281693e+01 6.64281311e+01 6.64280167e+01 6.64281082e+01 6.64281158e+01 6.64281387e+01 6.64280930e+01 6.64280090e+01 6.64281311e+01 6.64282227e+01 6.64280701e+01 6.64280472e+01 6.64279938e+01 6.64280014e+01 6.64282303e+01 6.64281082e+01 6.64283142e+01 6.64282379e+01 6.64280930e+01 6.64280930e+01 6.64282379e+01 6.64282455e+01 6.64281998e+01 6.64281769e+01 6.64282608e+01 6.64281693e+01 6.64281769e+01 6.64283600e+01 6.64283142e+01 6.64282990e+01 6.64282455e+01 6.64283524e+01 6.64283371e+01 6.64280701e+01 6.64280472e+01 6.64281845e+01 6.64282303e+01 6.64281845e+01 6.64282150e+01 6.64281998e+01 6.64281006e+01 6.64282684e+01 6.64281998e+01 6.64281311e+01 6.64282150e+01 6.64281464e+01 6.64281921e+01 6.64282608e+01 6.64281769e+01 6.64281311e+01 6.64280090e+01 6.64280853e+01 6.64282227e+01 6.64283142e+01 6.64281082e+01 6.64281158e+01 6.64281311e+01 6.64281998e+01 6.64281387e+01 6.64282227e+01 6.64281769e+01 6.64281082e+01 6.64281235e+01 6.64281921e+01 6.64282074e+01 6.64283371e+01 6.64282074e+01 6.64281158e+01 6.64280243e+01 6.64280777e+01 6.64281082e+01 6.64283447e+01 6.64282684e+01 6.64281387e+01 6.64281998e+01 6.64281311e+01 6.64280777e+01 6.64281769e+01 6.64281921e+01 6.64284515e+01 6.64281845e+01 6.64281464e+01 6.64282074e+01 6.64281464e+01 6.64289703e+01 6.64282837e+01 6.64281921e+01 6.64280548e+01 6.64282379e+01 6.64283600e+01 6.64281616e+01 6.64282455e+01 6.64281464e+01 6.64282608e+01 6.64282608e+01 6.64281769e+01 6.64282532e+01 6.64281158e+01 6.64281540e+01 6.64280930e+01 6.64281464e+01 6.64281845e+01 6.64281693e+01 6.64286194e+01 6.64288559e+01 6.64285812e+01 6.64281158e+01 6.64281921e+01 6.64281387e+01 6.64280777e+01 6.64280853e+01 6.64281921e+01 6.64280777e+01 6.64283524e+01 6.64282379e+01 6.64280548e+01 6.64281387e+01 6.64282455e+01 6.64281693e+01 6.64281921e+01 6.64282684e+01 6.64282608e+01 6.64282074e+01 6.64281845e+01 6.64282990e+01 6.64285660e+01 6.64282532e+01 6.64282303e+01 6.64280624e+01 6.64281158e+01 6.64282303e+01 6.64288177e+01 6.64287643e+01 6.64283752e+01 6.64283447e+01 6.64283905e+01 6.64281921e+01 6.64283524e+01 6.64284134e+01 6.64286118e+01 6.64284134e+01 6.64281311e+01 6.64282303e+01 6.64280624e+01 6.64280090e+01 6.64279861e+01 6.64282532e+01 6.64282455e+01 6.64281998e+01 6.64281769e+01 6.64281082e+01 6.64281158e+01 6.64281158e+01 6.64281006e+01 6.64282532e+01 6.64282227e+01 6.64281464e+01 6.64280701e+01 6.64281616e+01 6.64282150e+01 6.64283752e+01 6.64282150e+01 6.64282532e+01 6.64281082e+01 6.64281158e+01 6.64281845e+01 6.64282150e+01 6.64280167e+01 6.64282074e+01 6.64283142e+01 6.64282761e+01 6.64280930e+01 6.64280853e+01 6.64281845e+01 6.64281769e+01 6.64281998e+01 6.64281998e+01 6.64281616e+01 6.64281311e+01 6.64282150e+01 6.64281311e+01 6.64283066e+01 6.64281158e+01 6.64281998e+01 6.64283676e+01 6.64281158e+01 6.64281082e+01 6.64281693e+01 6.64280396e+01 6.64281235e+01 6.64281082e+01 6.64281769e+01 6.64281006e+01 6.64281006e+01 6.64280777e+01 6.64281006e+01 6.64281235e+01 6.64281921e+01 6.64280777e+01 6.64279938e+01 6.64280701e+01 6.64282227e+01 6.64282608e+01 6.64281311e+01 6.64280548e+01 6.64281082e+01 6.64281464e+01 6.64280548e+01 6.64280167e+01 6.64280396e+01 6.64280930e+01 6.64280701e+01 6.64281464e+01 6.64281693e+01 6.64281464e+01 6.64283447e+01 6.64280548e+01 6.64280624e+01 6.64280853e+01 6.64281616e+01 6.64280777e+01 6.64282074e+01 6.64281845e+01 6.64281235e+01 6.64281921e+01 6.64281464e+01 6.64281769e+01 6.64282074e+01 6.64282608e+01 6.64280930e+01 6.64280853e+01 6.64280701e+01 6.64281540e+01 6.64281387e+01 6.64280548e+01 6.64281387e+01 6.64281998e+01 6.64281158e+01 6.64281769e+01 6.64281464e+01 6.64281158e+01 6.64281387e+01 6.64281921e+01 6.64281464e+01 6.64280472e+01 6.64281464e+01 6.64281387e+01 6.64280930e+01 6.64281998e+01 6.64281158e+01 6.64281540e+01 6.64281082e+01 6.64282455e+01 6.64282074e+01 6.64282379e+01 6.64282532e+01 6.64281998e+01 6.64281006e+01 6.64281921e+01 6.64281845e+01 6.64286804e+01 6.64281311e+01 6.64280624e+01 6.64281464e+01 6.64282303e+01 6.64282379e+01 6.64282913e+01 6.64281158e+01 6.64282150e+01 6.64282379e+01 6.64281464e+01 6.64282837e+01 6.64281845e+01 6.64281158e+01 6.64281464e+01 6.64281235e+01 6.64281769e+01 6.64281235e+01 6.64281006e+01 6.64283142e+01 6.64282074e+01 6.64281387e+01 6.64280777e+01 6.64281769e+01 6.64281387e+01 6.64280624e+01 6.64280853e+01 6.64281311e+01 6.64281769e+01 6.64281082e+01 6.64282684e+01 6.64283066e+01 6.64280701e+01 6.64281006e+01 6.64281082e+01 6.64281769e+01 6.64280777e+01 6.64282150e+01 6.64280624e+01 6.64280930e+01 6.64281464e+01 6.64282227e+01 6.64281235e+01 6.64281158e+01 6.64281464e+01 6.64282532e+01 6.64281998e+01 6.64282074e+01 6.64282379e+01 6.64281387e+01 6.64281235e+01 6.64281082e+01 6.64284973e+01 6.64281693e+01 6.64282837e+01 6.64280930e+01 6.64281769e+01 6.64282150e+01 6.64282150e+01 6.64285202e+01 6.64290924e+01 6.64287262e+01 6.64282303e+01 6.64280624e+01 6.64281158e+01 6.64280701e+01 6.64281082e+01 6.64281006e+01 6.64280548e+01 6.64280701e+01 6.64280930e+01 6.64282761e+01 6.64281769e+01 6.64281616e+01 6.64281921e+01 6.64281311e+01 6.64280701e+01 6.64280090e+01 6.64281769e+01 6.64282837e+01 6.64282455e+01 6.64280930e+01 6.64280853e+01 6.64280624e+01 6.64280243e+01 6.64281158e+01 6.64281769e+01 6.64280930e+01 6.64280396e+01 6.64279938e+01 6.64280548e+01 6.64280472e+01 6.64280319e+01 6.64280853e+01 6.64281235e+01 6.64281311e+01 6.64281311e+01 6.64281769e+01 6.64281616e+01 6.64280853e+01 6.64281235e+01 6.64282532e+01 6.64282532e+01 6.64281158e+01 6.64282455e+01 6.64283218e+01 6.64281616e+01 6.64281235e+01 6.64281464e+01 6.64280243e+01 6.64284058e+01 6.64286118e+01 6.64311676e+01 6.64662476e+01 6.64674301e+01 6.68492355e+01 9.41423874e+01 2.33365997e+02 828031936. 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. 0. 0. 0. 0. 0. 0. 817216960. 365055200. 5.18280579e+02 2.82987946e+02 1.93345413e+02 1.17839317e+02 8.54244843e+01 6.66045303e+01 6.64345245e+01 6.64282990e+01 6.64282837e+01 6.64283600e+01 6.64281616e+01 6.64281082e+01 6.64281082e+01 6.64281616e+01 6.64282303e+01 6.64283600e+01 6.64286728e+01 6.64283829e+01 6.64281921e+01 6.64279251e+01 6.64280548e+01 6.64280243e+01 6.64280777e+01 6.64280243e+01 6.64280472e+01 6.64279633e+01 6.64280319e+01 6.64280167e+01 6.64281158e+01 6.64282684e+01 6.64281998e+01 6.64281845e+01 6.64281464e+01 6.64282455e+01 6.64281006e+01 6.64279938e+01 6.64280930e+01 6.64280243e+01 6.64281693e+01 6.64281693e+01 6.64281845e+01 6.64281158e+01 6.64281082e+01 6.64281158e+01 6.64282074e+01 6.64281845e+01 6.64283142e+01 6.64283295e+01 6.64282990e+01 6.64281921e+01 6.64281158e+01 6.64281311e+01 6.64280167e+01 6.64280853e+01 6.64281921e+01 6.64281082e+01 6.64281769e+01 6.64280777e+01 6.64281921e+01 6.64281769e+01 6.64281921e+01 6.64283600e+01 6.64283371e+01 6.64281693e+01 6.64281540e+01 6.64281616e+01 6.64282761e+01 6.64284058e+01 6.64280930e+01 6.64281845e+01 6.64282455e+01 6.64282227e+01 6.64283447e+01 6.64283600e+01 6.64282455e+01 6.64281845e+01 6.64280548e+01 6.64280319e+01 6.64282227e+01 6.64281158e+01 6.64282074e+01 6.64282074e+01 6.64281998e+01 6.64281311e+01 6.64282990e+01 6.64281769e+01 6.64280624e+01 6.64280319e+01 6.64281158e+01 6.64281921e+01 6.64282074e+01 6.64282227e+01 6.64281998e+01 6.64282150e+01 6.64282074e+01 6.64281235e+01 6.64281540e+01 6.64281540e+01 6.64283142e+01 6.64283600e+01 6.64281845e+01 6.64281235e+01 6.64281082e+01 6.64282074e+01 6.64281693e+01 6.64281693e+01 6.64281082e+01 6.64283600e+01 6.64285660e+01 6.64282990e+01 6.64281998e+01 6.64281845e+01 6.64280777e+01 6.64281540e+01 6.64281769e+01 6.64281082e+01 6.64281082e+01 6.64282913e+01 6.64282455e+01 6.64282074e+01 6.64281387e+01 6.64282074e+01 6.64283066e+01 6.64280853e+01 6.64280396e+01 6.64280701e+01 6.64283295e+01 6.64287415e+01 6.64285202e+01 6.64282379e+01 6.64281006e+01 6.64281311e+01 6.64281464e+01 6.64281845e+01 6.64282761e+01 6.64282913e+01 6.64280701e+01 6.64281082e+01 6.64281845e+01 6.64282455e+01 6.64281998e+01 6.64281158e+01 6.64280548e+01 6.64280701e+01 6.64282150e+01 6.64281006e+01 6.64281921e+01 6.64281693e+01 6.64280930e+01 6.64281540e+01 6.64282074e+01 6.64280319e+01 6.64282074e+01 6.64282990e+01 6.64281845e+01 6.64280090e+01 6.64280930e+01 6.64282990e+01 6.64282990e+01 6.64285049e+01 6.64285202e+01 6.64284744e+01 6.64281921e+01 6.64281845e+01 6.64281006e+01 6.64281235e+01 6.64281235e+01 6.64281616e+01 6.64281464e+01 6.64280853e+01 6.64281998e+01 6.64281006e+01 6.64280701e+01 6.64280548e+01 6.64280701e+01 6.64280853e+01 6.64281769e+01 6.64281387e+01 6.64282455e+01 6.64281387e+01 6.64282150e+01 6.64281769e+01 6.64281540e+01 6.64282227e+01 6.64282150e+01 6.64281616e+01 6.64282684e+01 6.64281158e+01 6.64281082e+01 6.64280396e+01 6.64281616e+01 6.64281693e+01 6.64281769e+01 6.64281921e+01 6.64281693e+01 6.64281082e+01 6.64281769e+01 6.64281616e+01 6.64281235e+01 6.64281311e+01 6.64281693e+01 6.64281921e+01 6.64281158e+01 6.64281311e+01 6.64282150e+01 6.64281616e+01 6.64281235e+01 6.64282150e+01 6.64280777e+01 6.64280701e+01 6.64281998e+01 6.64281616e+01 6.64280701e+01 6.64280624e+01 6.64281387e+01 6.64281082e+01 6.64282379e+01 6.64282074e+01 6.64281921e+01 6.64281387e+01 6.64281006e+01 6.64281387e+01 6.64280853e+01 6.64281693e+01 6.64280624e+01 6.64280777e+01 6.64281158e+01 6.64281845e+01 6.64281387e+01 6.64280930e+01 6.64281464e+01 6.64281540e+01 6.64281845e+01 6.64282303e+01 6.64280701e+01 6.64280624e+01 6.64281616e+01 6.64281845e+01 6.64281311e+01 6.64280853e+01 6.64281235e+01 6.64282379e+01 6.64282455e+01 6.64281693e+01 6.64284058e+01 6.64283295e+01 6.64282379e+01 6.64280701e+01 6.64281082e+01 6.64281006e+01 6.64281769e+01 6.64280624e+01 6.64281311e+01 6.64282303e+01 6.64281693e+01 6.64281921e+01 6.64284744e+01 6.64283295e+01 6.64282913e+01 6.64281235e+01 6.64281769e+01 6.64281387e+01 6.64282074e+01 6.64282837e+01 6.64282074e+01 6.64281387e+01 6.64284134e+01 6.64282074e+01 6.64282990e+01 6.64282455e+01 6.64281845e+01 6.64281921e+01 6.64281006e+01 6.64281693e+01 6.64281387e+01 6.64280624e+01 6.64281769e+01 6.64282303e+01 6.64280624e+01 6.64282150e+01 6.64283447e+01 6.64282074e+01 6.64281616e+01 6.64280319e+01 6.64281387e+01 6.64281693e+01 6.64283752e+01 6.64281921e+01 6.64281387e+01 6.64280930e+01 6.64281616e+01 6.64282150e+01 6.64281464e+01 6.64281540e+01 6.64281693e+01 6.64280396e+01 6.64281769e+01 6.64281311e+01 6.64281769e+01 6.64281998e+01 6.64280472e+01 6.64281616e+01 6.64281693e+01 6.64280701e+01 6.64281158e+01 6.64282532e+01 6.64282990e+01 6.64282608e+01 6.64282532e+01 6.64282608e+01 6.64281464e+01 6.64281921e+01 6.64281158e+01 6.64280548e+01 6.64281082e+01 6.64282150e+01 6.64282303e+01 6.64281464e+01 6.64281311e+01 6.64280930e+01 6.64281769e+01 6.64281082e+01 6.64281769e+01 6.64280624e+01 6.64280853e+01 6.64282684e+01 6.64284286e+01 6.64286194e+01 6.64282837e+01 6.64282608e+01 6.64281235e+01 6.64281235e+01 6.64281693e+01 6.64280472e+01 6.64280930e+01 6.64280319e+01 6.64280930e+01 6.64281921e+01 6.64281158e+01 6.64281235e+01 6.64283524e+01 6.64282608e+01 6.64282913e+01 6.64281082e+01 6.64280777e+01 6.64281158e+01 6.64281387e+01 6.64281158e+01 6.64280167e+01 6.64280396e+01 6.64280853e+01 6.64280319e+01 6.64283676e+01 6.64283447e+01 6.64281998e+01 6.64280624e+01 6.64281921e+01 6.64281082e+01 6.64281006e+01 6.64281158e+01 6.64282074e+01 6.64282150e+01 6.64281693e+01 6.64280853e+01 6.64281006e+01 6.64280853e+01 6.64282455e+01 6.64284134e+01 6.64283447e+01 6.64280777e+01 6.64281540e+01 6.64280624e+01 6.64281921e+01 6.64283218e+01 6.64282608e+01 6.64281693e+01 6.64280853e+01 6.64280243e+01 6.64281311e+01 6.64282074e+01 6.64281845e+01 6.64280624e+01 6.64281235e+01 6.64281464e+01 6.64281235e+01 6.64282455e+01 6.64280853e+01 6.64281006e+01 6.64281540e+01 6.64282455e+01 6.64282990e+01 6.64281845e+01 6.64280930e+01 6.64281693e+01 6.64281540e+01 6.64281464e+01 6.64281464e+01 6.64281158e+01 6.64281235e+01 6.64281387e+01 6.64281998e+01 6.64282608e+01 6.64281921e+01 6.64281616e+01 6.64282074e+01 6.64282074e+01 6.64280243e+01 6.64280014e+01 6.64280777e+01 6.64282455e+01 6.64280472e+01 6.64280319e+01 6.64281693e+01 6.64281311e+01 6.64281311e+01 6.64280472e+01 6.64280396e+01 6.64281006e+01 6.64280930e+01 6.64282074e+01 6.64282303e+01 6.64283981e+01 6.64282455e+01 6.64283142e+01 6.64280701e+01 6.64280853e+01 6.64280243e+01 6.64281158e+01 6.64281006e+01 6.64280701e+01 6.64281006e+01 6.64282074e+01 6.64281387e+01 6.64281540e+01 6.64282684e+01 6.64280930e+01 6.64281921e+01 6.64282150e+01 6.64281616e+01 6.64282150e+01 6.64282913e+01 6.64282761e+01 6.64282074e+01 6.64283142e+01 6.64281540e+01 6.64283066e+01 6.64281158e+01 6.64281616e+01 6.64281006e+01 6.64282150e+01 6.64281158e+01 6.64281693e+01 6.64280853e+01 6.64281616e+01 6.64282455e+01 6.64282684e+01 6.64282455e+01 6.64282913e+01 6.64281158e+01 6.64281693e+01 6.64281158e+01 6.64281693e+01 6.64281845e+01 6.64284744e+01 6.64281464e+01 6.64281387e+01 6.64282532e+01 6.64281769e+01 6.64282379e+01 6.64282455e+01 6.64282379e+01 6.64283066e+01 6.64282913e+01 6.64283142e+01 6.64283524e+01 6.64283829e+01 6.64281998e+01 6.64282837e+01 6.64282608e+01 6.64281921e+01 6.64285202e+01 6.64285355e+01 6.64283676e+01 6.64282990e+01 6.64283829e+01 6.64282684e+01 6.64282761e+01 6.64281540e+01 6.64281540e+01 6.64282913e+01 6.64290924e+01 6.64291458e+01 6.64287796e+01 6.64281464e+01 6.64282455e+01 6.64283066e+01 6.64282379e+01 6.64281235e+01 6.64281998e+01 6.64282684e+01 6.64284363e+01 6.64282990e+01 6.64281921e+01 6.64281387e+01 6.64282761e+01 6.64281616e+01 6.64282074e+01 6.64282532e+01 6.64284210e+01 6.64282990e+01 6.64284286e+01 6.64282990e+01 6.64283371e+01 6.64283600e+01 6.64283142e+01 6.64283524e+01 6.64283218e+01 6.64283524e+01 6.64283066e+01 6.64282608e+01 6.64281464e+01 6.64281082e+01 6.64281311e+01 6.64282074e+01 6.64281387e+01 6.64283295e+01 6.64283524e+01 6.64283447e+01 6.64282074e+01 6.64282150e+01 6.64281387e+01 6.64282303e+01 6.64282608e+01 6.64282684e+01 6.64282837e+01 6.64282074e+01 6.64281387e+01 6.64282303e+01 6.64283371e+01 6.64281540e+01 6.64282379e+01 6.64281311e+01 6.64282379e+01 6.64282303e+01 6.64283905e+01 6.64281235e+01 6.64281006e+01 6.64281082e+01 6.64281845e+01 6.64282761e+01 6.64282990e+01 6.64282227e+01 6.64284668e+01 6.64285812e+01 6.64283981e+01 6.64282761e+01 6.64281616e+01 6.64282379e+01 6.64282227e+01 6.64281540e+01 6.64283676e+01 6.64284821e+01 6.64283447e+01 6.64282227e+01 6.64282532e+01 6.64282837e+01 6.64282608e+01 6.64281540e+01 6.64283600e+01 6.64281464e+01 6.64282227e+01 6.64282150e+01 6.64282455e+01 6.64280777e+01 6.64281158e+01 6.64281693e+01 6.64282074e+01 6.64281769e+01 6.64283829e+01 6.64286575e+01 6.64284821e+01 6.64282990e+01 6.64283218e+01 6.64282837e+01 6.64281616e+01 6.64281158e+01 6.64282303e+01 6.64282608e+01 6.64282990e+01 6.64280548e+01 6.64281845e+01 6.64281616e+01 6.64281082e+01 6.64282074e+01 6.64283295e+01 6.64285889e+01 6.64284897e+01 6.64282761e+01 6.64283295e+01 6.64281845e+01 6.64279480e+01 6.64281998e+01 6.64284058e+01 6.64284821e+01 6.64289246e+01 6.64296188e+01 6.64297409e+01 6.65922775e+01 1.00234192e+02 1.00670281e+05 0. 0. 0. 0. 0. 0. 0. 0. 214226768. -113035232. -113035232. -740302144. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 186625728. -302741760. 1.09390907e+02 4.99316940e+01 3.30479202e+01 3.27652740e+01 3.27555008e+01 3.27552338e+01 3.27555847e+01 3.27556419e+01 3.27555542e+01 3.27556229e+01 3.27557182e+01 3.27556267e+01 3.27554436e+01 3.27554893e+01 3.27554779e+01 3.27555084e+01 3.27554817e+01 3.27554359e+01 3.27555046e+01 3.27556839e+01 3.27557831e+01 3.27555237e+01 3.27554665e+01 3.27554588e+01 3.27554817e+01 3.27555275e+01 3.27556076e+01 3.27555847e+01 3.27554626e+01 3.27554283e+01 3.27554741e+01 3.27554893e+01 3.27555733e+01 3.27555656e+01 3.27554970e+01 3.27554626e+01 3.27554779e+01 3.27555084e+01 3.27554665e+01 3.27555122e+01 3.27555695e+01 3.27554588e+01 3.27555237e+01 3.27555275e+01 3.27555542e+01 3.27555618e+01 3.27555542e+01 3.27554855e+01 3.27555046e+01 3.27555237e+01 3.27555351e+01 3.27555008e+01 3.27554283e+01 3.27554741e+01 3.27554703e+01 3.27555504e+01 3.27554817e+01 3.27557869e+01 3.27560654e+01 3.27556648e+01 3.27554436e+01 3.27554283e+01 3.27554436e+01 3.27554512e+01 3.27554626e+01 3.27554626e+01 3.27554321e+01 3.27554512e+01 3.27554741e+01 3.27554779e+01 3.27555351e+01 3.27554817e+01 3.27554893e+01 3.27554741e+01 3.27554588e+01 3.27555046e+01 3.27554779e+01 3.27554245e+01 3.27554665e+01 3.27557144e+01 3.27556419e+01 3.27555161e+01 3.27554817e+01 3.27554626e+01 3.27555504e+01 3.27554817e+01 3.27555313e+01 3.27555733e+01 3.27555618e+01 3.27556419e+01 3.27555733e+01 3.27555313e+01 3.27558289e+01 3.27560501e+01 3.27556572e+01 3.27554665e+01 3.27554893e+01 3.27554436e+01 3.27555275e+01 3.27557182e+01 3.27555771e+01 3.27555046e+01 3.27555504e+01 3.27554741e+01 3.27555008e+01 3.27556229e+01 3.27554970e+01 3.27554550e+01 3.27554893e+01 3.27554932e+01 3.27554893e+01 3.27554817e+01 3.27554703e+01 3.27554932e+01 3.27554932e+01 3.27555351e+01 3.27555084e+01 3.27554665e+01 3.27554703e+01 3.27554512e+01 3.27554741e+01 3.27555695e+01 3.27555313e+01 3.27554665e+01 3.27554855e+01 3.27555199e+01 3.27554703e+01 3.27555199e+01 3.27555161e+01 3.27555504e+01 3.27556419e+01 3.27556381e+01 3.27555695e+01 3.27555275e+01 3.27556000e+01 3.27555389e+01 3.27554817e+01 3.27554436e+01 3.27554054e+01 3.27555275e+01 3.27555008e+01 3.27556305e+01 3.27554245e+01 3.27554703e+01 3.27555161e+01 3.27556610e+01 3.27557106e+01 3.27554932e+01 3.27553749e+01 3.27554970e+01 3.27554474e+01 3.27555008e+01 3.27554741e+01 3.27554207e+01 3.27553635e+01 3.27555008e+01 3.27555504e+01 3.27555161e+01 3.27554932e+01 3.27554207e+01 3.27554436e+01 3.27556229e+01 3.27556839e+01 3.27555122e+01 3.27554779e+01 3.27554665e+01 3.27555084e+01 3.27554893e+01 3.27555580e+01 3.27556496e+01 3.27554207e+01 3.27554398e+01 3.27555084e+01 3.27554817e+01 3.27554474e+01 3.27554436e+01 3.27554665e+01 3.27555275e+01 3.27555161e+01 3.27554169e+01 3.27555542e+01 3.27555656e+01 3.27555428e+01 3.27554588e+01 3.27553978e+01 3.27553749e+01 3.27554817e+01 3.27555275e+01 3.27554512e+01 3.27554779e+01 3.27554703e+01 3.27557869e+01 3.27565689e+01 3.27565193e+01 3.27559738e+01 3.27553864e+01 3.27554131e+01 3.27554855e+01 3.27554512e+01 3.27553978e+01 3.27553635e+01 3.27554550e+01 3.27554321e+01 3.27554817e+01 3.27555733e+01 3.27554092e+01 3.27554588e+01 3.27554474e+01 3.27554359e+01 3.27553711e+01 3.27553902e+01 3.27554474e+01 3.27554359e+01 3.27557220e+01 3.27555542e+01 3.27553978e+01 3.27553520e+01 3.27554779e+01 3.27556458e+01 3.27555199e+01 3.27554703e+01 3.27554092e+01 3.27554245e+01 3.27554169e+01 3.27554398e+01 3.27554512e+01 3.27554665e+01 3.27554970e+01 3.27554359e+01 3.27555809e+01 3.27556000e+01 3.27555161e+01 3.27554626e+01 3.27553864e+01 3.27554550e+01 3.27554283e+01 3.27554703e+01 3.27553825e+01 3.27553902e+01 3.27554474e+01 3.27553940e+01 3.27555046e+01 3.27554474e+01 3.27555389e+01 3.27555275e+01 3.27553940e+01 3.27554131e+01 3.27554283e+01 3.27554626e+01 3.27553520e+01 3.27555313e+01 3.27555161e+01 3.27555847e+01 3.27554245e+01 3.27554398e+01 3.27554169e+01 3.27553520e+01 3.27553825e+01 3.27556229e+01 3.27554665e+01 3.27554779e+01 3.27554512e+01 3.27553444e+01 3.27553596e+01 3.27553978e+01 3.27554016e+01 3.27554703e+01 3.27555084e+01 3.27557030e+01 3.27556190e+01 3.27554054e+01 3.27553749e+01 3.27554016e+01 3.27557755e+01 3.27556725e+01 3.27556610e+01 3.27554703e+01 3.27554512e+01 3.27554092e+01 3.27554092e+01 3.27553673e+01 3.27554131e+01 3.27553902e+01 3.27554016e+01 3.27554283e+01 3.27554092e+01 3.27555618e+01 3.27555809e+01 3.27554588e+01 3.27554321e+01 3.27554512e+01 3.27554474e+01 3.27554207e+01 3.27554626e+01 3.27553825e+01 3.27554169e+01 3.27555161e+01 3.27555237e+01 3.27554131e+01 3.27554321e+01 3.27555389e+01 3.27554932e+01 3.27554588e+01 3.27554588e+01 3.27556763e+01 3.27555695e+01 3.27555580e+01 3.27554321e+01 3.27554131e+01 3.27554321e+01 3.27554893e+01 3.27554932e+01 3.27554741e+01 3.27554092e+01 3.27554245e+01 3.27554512e+01 3.27555237e+01 3.27554703e+01 3.27554550e+01 3.27554359e+01 3.27554359e+01 3.27554588e+01 3.27554626e+01 3.27555389e+01 3.27555161e+01 3.27554436e+01 3.27554359e+01 3.27554398e+01 3.27553902e+01 3.27555466e+01 3.27554932e+01 3.27555618e+01 3.27555923e+01 3.27556648e+01 3.27556305e+01 3.27555046e+01 3.27555161e+01 3.27553902e+01 3.27553711e+01 3.27553825e+01 3.27553749e+01 3.27554207e+01 3.27553673e+01 3.27554817e+01 3.27553787e+01 3.27554474e+01 3.27555237e+01 3.27554283e+01 3.27555504e+01 3.27554970e+01 3.27554474e+01 3.27554779e+01 3.27554550e+01 3.27556076e+01 3.27558289e+01 3.27556877e+01 3.27554474e+01 3.27554131e+01 3.27554245e+01 3.27553825e+01 3.27554283e+01 3.27554893e+01 3.27554626e+01 3.27555199e+01 3.27555809e+01 3.27556648e+01 3.27554932e+01 3.27554626e+01 3.27554398e+01 3.27554588e+01 3.27554855e+01 3.27553978e+01 3.27554359e+01 3.27554893e+01 3.27556114e+01 3.27554474e+01 3.27554970e+01 3.27556267e+01 3.27554283e+01 3.27554054e+01 3.27554817e+01 3.27555008e+01 3.27554474e+01 3.27554512e+01 3.27555351e+01 3.27554436e+01 3.27553940e+01 3.27554131e+01 3.27555008e+01 3.27554817e+01 3.27555466e+01 3.27554016e+01 3.27553902e+01 3.27554169e+01 3.27554817e+01 3.27555275e+01 3.27554207e+01 3.27554779e+01 3.27554703e+01 3.27554321e+01 3.27554893e+01 3.27555122e+01 3.27553749e+01 3.27553749e+01 3.27554588e+01 3.27556229e+01 3.27557030e+01 3.27558174e+01 3.27554817e+01 3.27554550e+01 3.27554665e+01 3.27556534e+01 3.27554855e+01 3.27555008e+01 3.27554512e+01 3.27554474e+01 3.27554550e+01 3.27554245e+01 3.27554321e+01 3.27556229e+01 3.27556267e+01 3.27553940e+01 3.27555008e+01 3.27553978e+01 3.27554779e+01 3.27554588e+01 3.27554474e+01 3.27555046e+01 3.27555466e+01 3.27554359e+01 3.27554474e+01 3.27555046e+01 3.27557106e+01 3.27555809e+01 3.27554779e+01 3.27554245e+01 3.27554359e+01 3.27554703e+01 3.27555199e+01 3.27555008e+01 3.27556992e+01 3.27555733e+01 3.27553978e+01 3.27553787e+01 3.27554207e+01 3.27557106e+01 3.27556572e+01 3.27557030e+01 3.27555008e+01 3.27555008e+01 3.27554436e+01 3.27554779e+01 3.27556343e+01 3.27554703e+01 3.27554626e+01 3.27554016e+01 3.27555161e+01 3.27553978e+01 3.27554970e+01 3.27554855e+01 3.27554436e+01 3.27554436e+01 3.27554779e+01 3.27554741e+01 3.27555161e+01 3.27554398e+01 3.27554283e+01 3.27555084e+01 3.27554817e+01 3.27555122e+01 3.27554970e+01 3.27554817e+01 3.27554283e+01 3.27555847e+01 3.27555122e+01 3.27553711e+01 3.27555428e+01 3.27554741e+01 3.27554398e+01 3.27554588e+01 3.27554245e+01 3.27554741e+01 3.27554817e+01 3.27554817e+01 3.27554092e+01 3.27554283e+01 3.27554092e+01 3.27555962e+01 3.27554512e+01 3.27555122e+01 3.27554817e+01 3.27555161e+01 3.27555389e+01 3.27555656e+01 3.27556305e+01 3.27554932e+01 3.27555199e+01 3.27555351e+01 3.27554741e+01 3.27554893e+01 3.27555313e+01 3.27557068e+01 3.27555313e+01 3.27554092e+01 3.27554741e+01 3.27553787e+01 3.27554207e+01 3.27553978e+01 3.27554779e+01 3.27554970e+01 3.27554474e+01 3.27553940e+01 3.27554436e+01 3.27554398e+01 3.27554817e+01 3.27554932e+01 3.27554932e+01 3.27554626e+01 3.27553673e+01 3.27555618e+01 3.27554474e+01 3.27554703e+01 3.27554131e+01 3.27554665e+01 3.27555428e+01 3.27554817e+01 3.27554398e+01 3.27554436e+01 3.27553825e+01 3.27554626e+01 3.27553902e+01 3.27554321e+01 3.27554359e+01 3.27554016e+01 3.27554398e+01 3.27554207e+01 3.27555008e+01 3.27555580e+01 3.27554741e+01 3.27554550e+01 3.27553444e+01 3.27553444e+01 3.27553558e+01 3.27554741e+01 3.27555237e+01 3.27554054e+01 3.27554131e+01 3.27553978e+01 3.27554626e+01 3.27555237e+01 3.27554436e+01 3.27555084e+01 3.27554131e+01 3.27554207e+01 3.27555275e+01 3.27555923e+01 3.27555351e+01 3.27554474e+01 3.27554970e+01 3.27554817e+01 3.27555466e+01 3.27555695e+01 3.27555466e+01 3.27554512e+01 3.27554741e+01 3.27554703e+01 3.27555046e+01 3.27555122e+01 3.27554321e+01 3.27554932e+01 3.27555313e+01 3.27555313e+01 3.27555161e+01 3.27554550e+01 3.27554092e+01 3.27554512e+01 3.27557259e+01 3.27556229e+01 3.27555428e+01 3.27557068e+01 3.27557106e+01 3.27556534e+01 3.27555695e+01 3.27556000e+01 3.27556000e+01 3.27555809e+01 3.27554855e+01 3.27555046e+01 3.27554512e+01 3.27555008e+01 3.27554893e+01 3.27555046e+01 3.27554855e+01 3.27554512e+01 3.27556343e+01 3.27554932e+01 3.27555161e+01 3.27555923e+01 3.27555008e+01 3.27555389e+01 3.27554932e+01 3.27555771e+01 3.27558289e+01 3.27556229e+01 3.27555313e+01 3.27554283e+01 3.27554512e+01 3.27554512e+01 3.27554665e+01 3.27554016e+01 3.27555046e+01 3.27552643e+01 3.27552376e+01 3.27550049e+01 3.27550049e+01 3.27554092e+01 3.27564812e+01 3.27608566e+01 3.27599602e+01 3.27922821e+01 3.28898048e+01 4.23561935e+01 5.75011978e+01 1.46918900e+02 3.46041168e+02 193475584. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 952141376. 1.49219635e+02 5.32037735e+01 3.34751778e+01 3.30563087e+01 3.28712158e+01 3.27622299e+01 3.27562714e+01 3.27551689e+01 3.27552834e+01 3.27553558e+01 3.27554512e+01 3.27554245e+01 3.27554207e+01 3.27554016e+01 3.27554779e+01 3.27554359e+01 3.27555008e+01 3.27554512e+01 3.27554512e+01 3.27555161e+01 3.27555313e+01 3.27555923e+01 3.27555122e+01 3.27555199e+01 3.27554855e+01 3.27555046e+01 3.27554855e+01 3.27554703e+01 3.27554932e+01 3.27556343e+01 3.27557297e+01 3.27554398e+01 3.27554474e+01 3.27555275e+01 3.27555656e+01 3.27555199e+01 3.27554512e+01 3.27554703e+01 3.27554436e+01 3.27555161e+01 3.27554779e+01 3.27554169e+01 3.27554245e+01 3.27554703e+01 3.27555962e+01 3.27556763e+01 3.27558632e+01 3.27555046e+01 3.27555695e+01 3.27554932e+01 3.27555466e+01 3.27555008e+01 3.27555161e+01 3.27555351e+01 3.27554703e+01 3.27554970e+01 3.27554436e+01 3.27555122e+01 3.27555199e+01 3.27555962e+01 3.27556267e+01 3.27556877e+01 3.27555771e+01 3.27556839e+01 3.27557030e+01 3.27556152e+01 3.27555046e+01 3.27554092e+01 3.27554512e+01 3.27554474e+01 3.27556229e+01 3.27559586e+01 3.27560806e+01 3.27559052e+01 3.27555237e+01 3.27555046e+01 3.27554665e+01 3.27554436e+01 3.27554779e+01 3.27555504e+01 3.27554779e+01 3.27555161e+01 3.27555389e+01 3.27555161e+01 3.27555504e+01 3.27555428e+01 3.27554436e+01 3.27554779e+01 3.27554626e+01 3.27555122e+01 3.27555122e+01 3.27555199e+01 3.27554207e+01 3.27556877e+01 3.27555847e+01 3.27555389e+01 3.27555237e+01 3.27555428e+01 3.27555275e+01 3.27554855e+01 3.27554970e+01 3.27554779e+01 3.27555237e+01 3.27554703e+01 3.27554703e+01 3.27555656e+01 3.27554703e+01 3.27555008e+01 3.27555046e+01 3.27555199e+01 3.27554893e+01 3.27554588e+01 3.27555847e+01 3.27555275e+01 3.27554703e+01 3.27554741e+01 3.27554741e+01 3.27554970e+01 3.27555962e+01 3.27555923e+01 3.27555237e+01 3.27554665e+01 3.27555084e+01 3.27555199e+01 3.27557259e+01 3.27558746e+01 3.27556152e+01 3.27555275e+01 3.27555084e+01 3.27555351e+01 3.27555962e+01 3.27554626e+01 3.27554893e+01 3.27555161e+01 3.27555847e+01 3.27555733e+01 3.27554321e+01 3.27554932e+01 3.27554779e+01 3.27555618e+01 3.27555161e+01 3.27555084e+01 3.27555084e+01 3.27555008e+01 3.27555275e+01 3.27555771e+01 3.27556076e+01 3.27555962e+01 3.27555847e+01 3.27555504e+01 3.27555199e+01 3.27555351e+01 3.27554779e+01 3.27555428e+01 3.27554550e+01 3.27554970e+01 3.27555389e+01 3.27556229e+01 3.27555122e+01 3.27554970e+01 3.27555351e+01 3.27555695e+01 3.27556000e+01 3.27555389e+01 3.27554398e+01 3.27554550e+01 3.27554779e+01 3.27554665e+01 3.27554665e+01 3.27554779e+01 3.27555389e+01 3.27554436e+01 3.27555275e+01 3.27555733e+01 3.27555161e+01 3.27554932e+01 3.27554398e+01 3.27554131e+01 3.27554703e+01 3.27555389e+01 3.27555466e+01 3.27554588e+01 3.27555695e+01 3.27554398e+01 3.27554932e+01 3.27554550e+01 3.27554436e+01 3.27554131e+01 3.27555542e+01 3.27554703e+01 3.27556992e+01 3.27557335e+01 3.27554512e+01 3.27554893e+01 3.27554855e+01 3.27554665e+01 3.27554588e+01 3.27555046e+01 3.27554550e+01 3.27554855e+01 3.27554970e+01 3.27554550e+01 3.27555046e+01 3.27555008e+01 3.27554741e+01 3.27555122e+01 3.27555008e+01 3.27555122e+01 3.27554512e+01 3.27555428e+01 3.27555962e+01 3.27554474e+01 3.27554665e+01 3.27554970e+01 3.27554588e+01 3.27554779e+01 3.27555008e+01 3.27554436e+01 3.27554054e+01 3.27554359e+01 3.27555618e+01 3.27555962e+01 3.27555313e+01 3.27554932e+01 3.27554512e+01 3.27554817e+01 3.27553711e+01 3.27553596e+01 3.27554092e+01 3.27556686e+01 3.27556114e+01 3.27553749e+01 3.27553558e+01 3.27554092e+01 3.27554169e+01 3.27554588e+01 3.27556038e+01 3.27557869e+01 3.27559280e+01 3.27557335e+01 3.27556343e+01 3.27554741e+01 3.27555008e+01 3.27555389e+01 3.27555962e+01 3.27555428e+01 3.27554703e+01 3.27554321e+01 3.27554855e+01 3.27554970e+01 3.27554741e+01 3.27554512e+01 3.27555199e+01 3.27555923e+01 3.27555389e+01 3.27555733e+01 3.27554855e+01 3.27554855e+01 3.27554817e+01 3.27554512e+01 3.27554932e+01 3.27554932e+01 3.27555161e+01 3.27554436e+01 3.27554970e+01 3.27554436e+01 3.27554817e+01 3.27554169e+01 3.27555313e+01 3.27553902e+01 3.27554626e+01 3.27554779e+01 3.27555618e+01 3.27554626e+01 3.27555161e+01 3.27554893e+01 3.27554321e+01 3.27554588e+01 3.27554932e+01 3.27554779e+01 3.27554779e+01 3.27554474e+01 3.27554970e+01 3.27554779e+01 3.27556000e+01 3.27554321e+01 3.27554970e+01 3.27555046e+01 3.27556686e+01 3.27556305e+01 3.27555504e+01 3.27554207e+01 3.27554321e+01 3.27554512e+01 3.27554932e+01 3.27555275e+01 3.27554817e+01 3.27556458e+01 3.27554398e+01 3.27554817e+01 3.27554855e+01 3.27555008e+01 3.27554588e+01 3.27555122e+01 3.27554932e+01 3.27554398e+01 3.27554207e+01 3.27554932e+01 3.27555275e+01 3.27555542e+01 3.27554169e+01 3.27554436e+01 3.27555237e+01 3.27555275e+01 3.27555733e+01 3.27556000e+01 3.27555466e+01 3.27554741e+01 3.27554512e+01 3.27554970e+01 3.27555046e+01 3.27556343e+01 3.27557602e+01 3.27556305e+01 3.27554398e+01 3.27555580e+01 3.27554817e+01 3.27554779e+01 3.27554741e+01 3.27554741e+01 3.27555122e+01 3.27554932e+01 3.27554588e+01 3.27554893e+01 3.27553940e+01 3.27554703e+01 3.27554665e+01 3.27554893e+01 3.27556267e+01 3.27554970e+01 3.27554817e+01 3.27554283e+01 3.27554626e+01 3.27554855e+01 3.27555084e+01 3.27554741e+01 3.27553940e+01 3.27553940e+01 3.27554626e+01 3.27555618e+01 3.27556114e+01 3.27555046e+01 3.27554550e+01 3.27554512e+01 3.27555084e+01 3.27555275e+01 3.27554626e+01 3.27555237e+01 3.27554588e+01 3.27554474e+01 3.27554970e+01 3.27554703e+01 3.27555008e+01 3.27554474e+01 3.27554283e+01 3.27555695e+01 3.27555084e+01 3.27556152e+01 3.27554970e+01 3.27554169e+01 3.27554626e+01 3.27555161e+01 3.27555161e+01 3.27555351e+01 3.27554970e+01 3.27554321e+01 3.27556343e+01 3.27554474e+01 3.27554283e+01 3.27555084e+01 3.27555008e+01 3.27554474e+01 3.27555161e+01 3.27554893e+01 3.27555275e+01 3.27554855e+01 3.27554359e+01 3.27554817e+01 3.27555580e+01 3.27556152e+01 3.27555237e+01 3.27554245e+01 3.27553673e+01 3.27553902e+01 3.27554245e+01 3.27554779e+01 3.27554665e+01 3.27555389e+01 3.27556610e+01 3.27554932e+01 3.27554817e+01 3.27554817e+01 3.27554703e+01 3.27554626e+01 3.27555580e+01 3.27556267e+01 3.27557030e+01 3.27555161e+01 3.27555199e+01 3.27554741e+01 3.27554245e+01 3.27554932e+01 3.27554131e+01 3.27554703e+01 3.27554550e+01 3.27554550e+01 3.27555008e+01 3.27554321e+01 3.27555275e+01 3.27555809e+01 3.27555656e+01 3.27554626e+01 3.27554436e+01 3.27555161e+01 3.27555008e+01 3.27555504e+01 3.27555504e+01 3.27555504e+01 3.27555161e+01 3.27556343e+01 3.27555885e+01 3.27555237e+01 3.27554932e+01 3.27554665e+01 3.27554970e+01 3.27555199e+01 3.27555695e+01 3.27555161e+01 3.27554932e+01 3.27554092e+01 3.27554741e+01 3.27554665e+01 3.27554855e+01 3.27554855e+01 3.27555313e+01 3.27555084e+01 3.27555428e+01 3.27555580e+01 3.27558022e+01 3.27560883e+01 3.27557335e+01 3.27554359e+01 3.27554665e+01 3.27554054e+01 3.27555275e+01 3.27552071e+01 3.27558937e+01 3.27561951e+01 3.27819061e+01 3.28152504e+01 3.27914314e+01 4.11428566e+01 6.51657715e+01 3.20122589e+02 828031936. 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. 0. 0. 0. 0. 0. 0. 1.08942832e+04 5.11417236e+01 3.29949532e+01 3.29401627e+01 3.27573586e+01 3.27556419e+01 3.27552567e+01 3.27553635e+01 3.27555046e+01 3.27555351e+01 3.27555122e+01 3.27554932e+01 3.27555199e+01 3.27555122e+01 3.27555618e+01 3.27555504e+01 3.27554970e+01 3.27555351e+01 3.27555466e+01 3.27555084e+01 3.27555313e+01 3.27556076e+01 3.27555847e+01 3.27555389e+01 3.27554703e+01 3.27554665e+01 3.27554855e+01 3.27554893e+01 3.27554626e+01 3.27554817e+01 3.27554779e+01 3.27555008e+01 3.27555389e+01 3.27554779e+01 3.27554855e+01 3.27554970e+01 3.27554855e+01 3.27554970e+01 3.27554779e+01 3.27555008e+01 3.27554550e+01 3.27555084e+01 3.27555237e+01 3.27555618e+01 3.27555351e+01 3.27555122e+01 3.27554893e+01 3.27554932e+01 3.27555466e+01 3.27555656e+01 3.27555809e+01 3.27555428e+01 3.27555351e+01 3.27555084e+01 3.27554779e+01 3.27555428e+01 3.27554855e+01 3.27554550e+01 3.27554588e+01 3.27555199e+01 3.27555275e+01 3.27555237e+01 3.27555161e+01 3.27555428e+01 3.27555466e+01 3.27555351e+01 3.27555656e+01 3.27556038e+01 3.27555809e+01 3.27554855e+01 3.27555122e+01 3.27555046e+01 3.27554970e+01 3.27555351e+01 3.27555389e+01 3.27555733e+01 3.27555923e+01 3.27555008e+01 3.27554893e+01 3.27554359e+01 3.27555046e+01 3.27554626e+01 3.27555199e+01 3.27555199e+01 3.27555428e+01 3.27555161e+01 3.27555008e+01 3.27555389e+01 3.27555161e+01 3.27554893e+01 3.27555275e+01 3.27555008e+01 3.27555428e+01 3.27555389e+01 3.27555389e+01 3.27555618e+01 3.27555428e+01 3.27554588e+01 3.27554283e+01 3.27554626e+01 3.27555618e+01 3.27555695e+01 3.27555313e+01 3.27555008e+01 3.27554970e+01 3.27555084e+01 3.27554512e+01 3.27554893e+01 3.27555389e+01 3.27555275e+01 3.27555504e+01 3.27555733e+01 3.27554741e+01 3.27555237e+01 3.27554893e+01 3.27555275e+01 3.27555504e+01 3.27555237e+01 3.27555618e+01 3.27554665e+01 3.27555122e+01 3.27555504e+01 3.27555237e+01 3.27555618e+01 3.27554474e+01 3.27554741e+01 3.27554283e+01 3.27555389e+01 3.27555237e+01 3.27555428e+01 3.27555122e+01 3.27555008e+01 3.27555351e+01 3.27555122e+01 3.27556267e+01 3.27556152e+01 3.27556152e+01 3.27555084e+01 3.27555199e+01 3.27554893e+01 3.27555084e+01 3.27555580e+01 3.27555466e+01 3.27555580e+01 3.27554779e+01 3.27555351e+01 3.27555428e+01 3.27554970e+01 3.27555161e+01 3.27554512e+01 3.27555237e+01 3.27554970e+01 3.27554741e+01 3.27554741e+01 3.27555275e+01 3.27555237e+01 3.27555504e+01 3.27555237e+01 3.27555275e+01 3.27555695e+01 3.27556076e+01 3.27556915e+01 3.27556534e+01 3.27556229e+01 3.27555618e+01 3.27555161e+01 3.27555428e+01 3.27555237e+01 3.27555542e+01 3.27554703e+01 3.27555237e+01 3.27554817e+01 3.27555199e+01 3.27555275e+01 3.27554932e+01 3.27555199e+01 3.27555656e+01 3.27555466e+01 3.27556038e+01 3.27554970e+01 3.27556114e+01 3.27555275e+01 3.27555389e+01 3.27555161e+01 3.27555046e+01 3.27556114e+01 3.27556000e+01 3.27555351e+01 3.27554893e+01 3.27555046e+01 3.27555504e+01 3.27555389e+01 3.27554893e+01 3.27555161e+01 3.27554436e+01 3.27555695e+01 3.27555008e+01 3.27555313e+01 3.27555656e+01 3.27555122e+01 3.27555542e+01 3.27555199e+01 3.27555733e+01 3.27556000e+01 3.27555122e+01 3.27555885e+01 3.27555428e+01 3.27555351e+01 3.27554779e+01 3.27554703e+01 3.27555618e+01 3.27555962e+01 3.27555161e+01 3.27555122e+01 3.27555389e+01 3.27555466e+01 3.27555389e+01 3.27555008e+01 3.27555542e+01 3.27554741e+01 3.27554893e+01 3.27555237e+01 3.27555161e+01 3.27555504e+01 3.27555084e+01 3.27555122e+01 3.27555504e+01 3.27555351e+01 3.27555695e+01 3.27555428e+01 3.27555275e+01 3.27554741e+01 3.27555847e+01 3.27555237e+01 3.27555313e+01 3.27555618e+01 3.27555656e+01 3.27555199e+01 3.27554932e+01 3.27554817e+01 3.27554703e+01 3.27555580e+01 3.27555313e+01 3.27555046e+01 3.27554779e+01 3.27555923e+01 3.27556763e+01 3.27555733e+01 3.27555008e+01 3.27554703e+01 3.27555428e+01 3.27555428e+01 3.27555428e+01 3.27555237e+01 3.27555542e+01 3.27555885e+01 3.27555466e+01 3.27554855e+01 3.27555351e+01 3.27555008e+01 3.27554855e+01 3.27555428e+01 3.27555084e+01 3.27555389e+01 3.27554779e+01 3.27555199e+01 3.27555466e+01 3.27555695e+01 3.27555809e+01 3.27555122e+01 3.27555428e+01 3.27555923e+01 3.27555122e+01 3.27555733e+01 3.27554855e+01 3.27555313e+01 3.27554588e+01 3.27555122e+01 3.27555351e+01 3.27555923e+01 3.27557526e+01 3.27555580e+01 3.27555084e+01 3.27554817e+01 3.27554550e+01 3.27554779e+01 3.27555504e+01 3.27555046e+01 3.27555428e+01 3.27555084e+01 3.27555237e+01 3.27555351e+01 3.27555466e+01 3.27555809e+01 3.27555199e+01 3.27555122e+01 3.27555237e+01 3.27555962e+01 3.27555542e+01 3.27555237e+01 3.27555122e+01 3.27554932e+01 3.27555046e+01 3.27554779e+01 3.27555237e+01 3.27554779e+01 3.27555809e+01 3.27555504e+01 3.27555313e+01 3.27555008e+01 3.27555618e+01 3.27555542e+01 3.27555466e+01 3.27555351e+01 3.27554741e+01 3.27554817e+01 3.27555008e+01 3.27555008e+01 3.27555656e+01 3.27555046e+01 3.27555504e+01 3.27555351e+01 3.27555122e+01 3.27555275e+01 3.27555084e+01 3.27555122e+01 3.27555161e+01 3.27555618e+01 3.27556038e+01 3.27556496e+01 3.27556534e+01 3.27555695e+01 3.27555695e+01 3.27555313e+01 3.27555466e+01 3.27554703e+01 3.27555237e+01 3.27555428e+01 3.27555542e+01 3.27555313e+01 3.27554932e+01 3.27555847e+01 3.27556114e+01 3.27555885e+01 3.27554626e+01 3.27555466e+01 3.27555389e+01 3.27554932e+01 3.27555084e+01 3.27555885e+01 3.27555580e+01 3.27556458e+01 3.27556763e+01 3.27555847e+01 3.27555504e+01 3.27556000e+01 3.27554893e+01 3.27555580e+01 3.27554741e+01 3.27554741e+01 3.27554855e+01 3.27555084e+01 3.27555275e+01 3.27555618e+01 3.27555008e+01 3.27555161e+01 3.27555275e+01 3.27555580e+01 3.27555771e+01 3.27554703e+01 3.27555122e+01 3.27554703e+01 3.27555885e+01 3.27556038e+01 3.27555428e+01 3.27555389e+01 3.27555618e+01 3.27555733e+01 3.27555466e+01 3.27555084e+01 3.27555618e+01 3.27555847e+01 3.27556038e+01 3.27555847e+01 3.27554855e+01 3.27555237e+01 3.27555084e+01 3.27555580e+01 3.27555618e+01 3.27554703e+01 3.27555695e+01 3.27555504e+01 3.27555656e+01 3.27555351e+01 3.27554283e+01 3.27555008e+01 3.27554474e+01 3.27555466e+01 3.27555389e+01 3.27554626e+01 3.27554855e+01 3.27554665e+01 3.27556152e+01 3.27555275e+01 3.27555389e+01 3.27554550e+01 3.27555466e+01 3.27555466e+01 3.27555428e+01 3.27554932e+01 3.27555313e+01 3.27555122e+01 3.27555351e+01 3.27554970e+01 3.27555313e+01 3.27555542e+01 3.27555504e+01 3.27555084e+01 3.27555962e+01 3.27555275e+01 3.27555199e+01 3.27554741e+01 3.27554283e+01 3.27554359e+01 3.27554436e+01 3.27554932e+01 3.27555313e+01 3.27555199e+01 3.27555008e+01 3.27554626e+01 3.27554817e+01 3.27555008e+01 3.27555466e+01 3.27555351e+01 3.27555008e+01 3.27554703e+01 3.27555161e+01 3.27554779e+01 3.27554817e+01 3.27554245e+01 3.27554703e+01 3.27554779e+01 3.27555008e+01 3.27555008e+01 3.27555275e+01 3.27555656e+01 3.27555161e+01 3.27554665e+01 3.27554893e+01 3.27555656e+01 3.27555313e+01 3.27555161e+01 3.27554665e+01 3.27554817e+01 3.27554893e+01 3.27555084e+01 3.27555199e+01 3.27555542e+01 3.27555504e+01 3.27554970e+01 3.27555275e+01 3.27554970e+01 3.27555428e+01 3.27555428e+01 3.27555237e+01 3.27555466e+01 3.27554588e+01 3.27554893e+01 3.27554855e+01 3.27554626e+01 3.27554321e+01 3.27554245e+01 3.27554932e+01 3.27554665e+01 3.27554703e+01 3.27555084e+01 3.27554855e+01 3.27555313e+01 3.27554245e+01 3.27554207e+01 3.27554283e+01 3.27555237e+01 3.27555199e+01 3.27554893e+01 3.27554550e+01 3.27554817e+01 3.27555733e+01 3.27554474e+01 3.27554588e+01 3.27554283e+01 3.27554512e+01 3.27555351e+01 3.27554779e+01 3.27555809e+01 3.27556534e+01 3.27557640e+01 3.27555428e+01 3.27555046e+01 3.27555122e+01 3.27555923e+01 3.27559090e+01 3.27558746e+01 3.27558098e+01 3.27557755e+01 3.27556419e+01 3.27556419e+01 3.27555122e+01 3.27554779e+01 3.27555084e+01 3.27555389e+01 3.27555618e+01 3.27555275e+01 3.27554932e+01 3.27555580e+01 3.27554626e+01 3.27554207e+01 3.27554741e+01 3.27554665e+01 3.27555542e+01 3.27555275e+01 3.27555885e+01 3.27556038e+01 3.27555466e+01 3.27554283e+01 3.27554131e+01 3.27554283e+01 3.27555313e+01 3.27555008e+01 3.27555122e+01 3.27554092e+01 3.27554665e+01 3.27554588e+01 3.27555542e+01 3.27555008e+01 3.27555084e+01 3.27554626e+01 3.27554665e+01 3.27554436e+01 3.27555161e+01 3.27555084e+01 3.27556763e+01 3.27554092e+01 3.27555275e+01 3.27555885e+01 3.27554512e+01 3.27554626e+01 3.27554169e+01 3.27555771e+01 3.27556114e+01 3.27555084e+01 3.27554893e+01 3.27555008e+01 3.27555313e+01 3.27554893e+01 3.27554359e+01 3.27555046e+01 3.27554855e+01 3.27554474e+01 3.27554817e+01 3.27554588e+01 3.27554817e+01 3.27554436e+01 3.27554626e+01 3.27554245e+01 3.27554741e+01 3.27554321e+01 3.27554359e+01 3.27555122e+01 3.27554474e+01 3.27554626e+01 3.27554359e+01 3.27554398e+01 3.27554932e+01 3.27554855e+01 3.27553940e+01 3.27554283e+01 3.27555656e+01 3.27556190e+01 3.27556038e+01 3.27555046e+01 3.27554512e+01 3.27555122e+01 3.27554703e+01 3.27554970e+01 3.27553940e+01 3.27554474e+01 3.27554512e+01 3.27554588e+01 3.27554703e+01 3.27554436e+01 3.27554550e+01 3.27554588e+01 3.27554703e+01 3.27554169e+01 3.27555313e+01 3.27555084e+01 3.27554932e+01 3.27553864e+01 3.27555351e+01 3.27554779e+01 3.27557526e+01 3.27554207e+01 3.27552338e+01 3.27550392e+01 3.27548447e+01 3.27545242e+01 3.27543564e+01 3.27690773e+01 3.27602119e+01 4.91708412e+01 9.78950500e+01 -841836544. 0. 0. 0. 0. 161829888. -157659952. 339223936. 60840276. 4.08942963e+02 7.37141113e+02 9.46356079e+02 -740302144. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 186625728. -302741760. -222815216. 2.08160812e+02 1.04368866e+02 7.25992584e+01 7.23896561e+01 7.22280426e+01 7.22209778e+01 7.22264938e+01 7.22308197e+01 7.22230759e+01 7.22455215e+01 7.22455368e+01 7.22336884e+01 7.22272644e+01 7.22227783e+01 7.22224503e+01 7.22232971e+01 7.22225571e+01 7.22314377e+01 7.22505417e+01 7.22479935e+01 7.22235565e+01 7.22284241e+01 7.22450256e+01 7.22492447e+01 7.22329178e+01 7.22323608e+01 7.22304764e+01 7.22225800e+01 7.22274933e+01 7.22237091e+01 7.22335739e+01 7.22670212e+01 7.22673264e+01 7.22398453e+01 7.22228622e+01 7.22263184e+01 7.22251816e+01 7.22245255e+01 7.22240982e+01 7.22230148e+01 7.22260818e+01 7.22404785e+01 7.22340240e+01 7.22232590e+01 7.22233810e+01 7.22238464e+01 7.22241211e+01 7.22230606e+01 7.22262344e+01 7.22266388e+01 7.22252808e+01 7.22225266e+01 7.22252121e+01 7.22309341e+01 7.22351990e+01 7.22226028e+01 7.22465134e+01 7.22655258e+01 7.22380295e+01 7.22233658e+01 7.22247620e+01 7.22224503e+01 7.22244644e+01 7.22236023e+01 7.22224503e+01 7.22232361e+01 7.22257996e+01 7.22275391e+01 7.22227249e+01 7.22307205e+01 7.22262421e+01 7.22239532e+01 7.22226410e+01 7.22234192e+01 7.22234192e+01 7.22258224e+01 7.22224426e+01 7.22263794e+01 7.22427444e+01 7.22437744e+01 7.22256699e+01 7.22234955e+01 7.22350845e+01 7.22371292e+01 7.22239227e+01 7.22226105e+01 7.22227173e+01 7.22259903e+01 7.22424698e+01 7.22420731e+01 7.22229004e+01 7.22395477e+01 7.22397995e+01 7.22228088e+01 7.22374039e+01 7.22386093e+01 7.22322693e+01 7.22357178e+01 7.22372437e+01 7.22297516e+01 7.22229309e+01 7.22228775e+01 7.22233047e+01 7.22297745e+01 7.22326660e+01 7.22229919e+01 7.22263489e+01 7.22325745e+01 7.22326355e+01 7.22226028e+01 7.22275696e+01 7.22261887e+01 7.22246246e+01 7.22278900e+01 7.22319336e+01 7.22248459e+01 7.22246246e+01 7.22247009e+01 7.22260742e+01 7.22503586e+01 7.22575607e+01 7.22316055e+01 7.22225418e+01 7.22267914e+01 7.22321320e+01 7.22249832e+01 7.22222900e+01 7.22235489e+01 7.22319183e+01 7.22509918e+01 7.22521744e+01 7.22339096e+01 7.22233963e+01 7.22223816e+01 7.22227783e+01 7.22223434e+01 7.22238235e+01 7.22258911e+01 7.22307968e+01 7.22390213e+01 7.22405167e+01 7.22240982e+01 7.22257843e+01 7.22410660e+01 7.22347794e+01 7.22271423e+01 7.22235031e+01 7.22228470e+01 7.22245636e+01 7.22229614e+01 7.22224350e+01 7.22248383e+01 7.22280197e+01 7.22257156e+01 7.22224426e+01 7.22238083e+01 7.22224731e+01 7.22282944e+01 7.22243500e+01 7.22235718e+01 7.22307281e+01 7.22228928e+01 7.22251892e+01 7.22242661e+01 7.22234573e+01 7.22233810e+01 7.22400818e+01 7.22595520e+01 7.22654419e+01 7.22276230e+01 7.22275543e+01 7.22358475e+01 7.22339020e+01 7.22321777e+01 7.22278137e+01 7.22225418e+01 7.22292557e+01 7.22339096e+01 7.22226791e+01 7.22305756e+01 7.22353287e+01 7.22223053e+01 7.22252655e+01 7.22281342e+01 7.22275085e+01 7.22264099e+01 7.22313004e+01 7.22294235e+01 7.22253723e+01 7.22237244e+01 7.22263184e+01 7.22398376e+01 7.22496262e+01 7.22447205e+01 7.22222595e+01 7.22370148e+01 7.22434769e+01 7.22275696e+01 7.22260895e+01 7.22244263e+01 7.22226562e+01 7.22274170e+01 7.22290039e+01 7.22224350e+01 7.22328720e+01 7.22379456e+01 7.22234039e+01 7.22225647e+01 7.22220306e+01 7.22225876e+01 7.22221146e+01 7.22226410e+01 7.22291794e+01 7.22237701e+01 7.22251129e+01 7.22306290e+01 7.22236862e+01 7.22301636e+01 7.22344284e+01 7.22235107e+01 7.22246704e+01 7.22289810e+01 7.22239456e+01 7.22236404e+01 7.22236176e+01 7.22243881e+01 7.22259903e+01 7.22270966e+01 7.22285690e+01 7.22285614e+01 7.22315598e+01 7.22300720e+01 7.22288895e+01 7.22254868e+01 7.22223663e+01 7.22260742e+01 7.22319870e+01 7.22246704e+01 7.22223969e+01 7.22266312e+01 7.22329102e+01 7.22223282e+01 7.22285614e+01 7.22305298e+01 7.22222672e+01 7.22282104e+01 7.22239151e+01 7.22224884e+01 7.22235260e+01 7.22303391e+01 7.22263031e+01 7.22221298e+01 7.22257690e+01 7.22231522e+01 7.22241592e+01 7.22223969e+01 7.22223587e+01 7.22256012e+01 7.22226028e+01 7.22219238e+01 7.22230911e+01 7.22291183e+01 7.22284622e+01 7.22260437e+01 7.22224503e+01 7.22274628e+01 7.22225723e+01 7.22328873e+01 7.22422485e+01 7.22279739e+01 7.22254562e+01 7.22289734e+01 7.22417908e+01 7.22257767e+01 7.22225800e+01 7.22221222e+01 7.22222977e+01 7.22220840e+01 7.22222977e+01 7.22224808e+01 7.22225113e+01 7.22242661e+01 7.22281494e+01 7.22250900e+01 7.22266998e+01 7.22390289e+01 7.22405853e+01 7.22245026e+01 7.22236328e+01 7.22227936e+01 7.22223053e+01 7.22220001e+01 7.22271881e+01 7.22234726e+01 7.22223282e+01 7.22222443e+01 7.22237015e+01 7.22301865e+01 7.22250748e+01 7.22263412e+01 7.22237854e+01 7.22236023e+01 7.22229919e+01 7.22293777e+01 7.22260742e+01 7.22226562e+01 7.22223969e+01 7.22235794e+01 7.22248459e+01 7.22289200e+01 7.22358551e+01 7.22320557e+01 7.22253418e+01 7.22230377e+01 7.22274323e+01 7.22377243e+01 7.22265778e+01 7.22253036e+01 7.22270660e+01 7.22222824e+01 7.22250214e+01 7.22226486e+01 7.22305908e+01 7.22248993e+01 7.22224731e+01 7.22275543e+01 7.22296371e+01 7.22358093e+01 7.22399063e+01 7.22307510e+01 7.22272034e+01 7.22273865e+01 7.22305298e+01 7.22272797e+01 7.22277374e+01 7.22375565e+01 7.22303391e+01 7.22220612e+01 7.22252426e+01 7.22233047e+01 7.22225876e+01 7.22235107e+01 7.22299576e+01 7.22244492e+01 7.22224655e+01 7.22225266e+01 7.22229309e+01 7.22223129e+01 7.22225342e+01 7.22223969e+01 7.22222214e+01 7.22227325e+01 7.22334671e+01 7.22434235e+01 7.22332153e+01 7.22230988e+01 7.22231369e+01 7.22222900e+01 7.22227707e+01 7.22276764e+01 7.22484665e+01 7.22419662e+01 7.22217865e+01 7.22439346e+01 7.22608490e+01 7.22363129e+01 7.22267609e+01 7.22277298e+01 7.22273712e+01 7.22348328e+01 7.22262421e+01 7.22257385e+01 7.22233353e+01 7.22234268e+01 7.22401962e+01 7.22518692e+01 7.22521362e+01 7.22228546e+01 7.22275238e+01 7.22225876e+01 7.22283020e+01 7.22340698e+01 7.22226181e+01 7.22308502e+01 7.22298126e+01 7.22256622e+01 7.22223587e+01 7.22248077e+01 7.22284470e+01 7.22384338e+01 7.22277145e+01 7.22223816e+01 7.22240677e+01 7.22247238e+01 7.22261963e+01 7.22413864e+01 7.22588730e+01 7.22375717e+01 7.22222824e+01 7.22223053e+01 7.22220917e+01 7.22225037e+01 7.22317047e+01 7.22310486e+01 7.22279358e+01 7.22489853e+01 7.22528839e+01 7.22279739e+01 7.22230301e+01 7.22224274e+01 7.22234497e+01 7.22224274e+01 7.22239609e+01 7.22298203e+01 7.22411880e+01 7.22357025e+01 7.22356415e+01 7.22333984e+01 7.22309799e+01 7.22307129e+01 7.22230225e+01 7.22251740e+01 7.22239304e+01 7.22231979e+01 7.22358398e+01 7.22428436e+01 7.22445831e+01 7.22234573e+01 7.22291183e+01 7.22287292e+01 7.22226181e+01 7.22341309e+01 7.22256012e+01 7.22251205e+01 7.22286072e+01 7.22256775e+01 7.22223663e+01 7.22227478e+01 7.22242126e+01 7.22297516e+01 7.22228088e+01 7.22226715e+01 7.22269135e+01 7.22226639e+01 7.22349854e+01 7.22507477e+01 7.22444305e+01 7.22237167e+01 7.22263947e+01 7.22222519e+01 7.22277527e+01 7.22380295e+01 7.22244263e+01 7.22245560e+01 7.22229156e+01 7.22224808e+01 7.22239838e+01 7.22230682e+01 7.22225571e+01 7.22244720e+01 7.22259674e+01 7.22250290e+01 7.22248306e+01 7.22233200e+01 7.22279968e+01 7.22249146e+01 7.22256165e+01 7.22234726e+01 7.22226639e+01 7.22269745e+01 7.22226486e+01 7.22232513e+01 7.22374344e+01 7.22301025e+01 7.22231445e+01 7.22361832e+01 7.22418747e+01 7.22227783e+01 7.22274857e+01 7.22299728e+01 7.22245026e+01 7.22230225e+01 7.22231674e+01 7.22228394e+01 7.22254715e+01 7.22308884e+01 7.22248459e+01 7.22229462e+01 7.22349930e+01 7.22368164e+01 7.22230453e+01 7.22286987e+01 7.22383499e+01 7.22322235e+01 7.22225494e+01 7.22338867e+01 7.22389145e+01 7.22229080e+01 7.22287827e+01 7.22243423e+01 7.22250214e+01 7.22347717e+01 7.22237244e+01 7.22263870e+01 7.22267151e+01 7.22242203e+01 7.22238846e+01 7.22300873e+01 7.22312317e+01 7.22296371e+01 7.22229156e+01 7.22228317e+01 7.22233887e+01 7.22224960e+01 7.22275467e+01 7.22268143e+01 7.22229691e+01 7.22231140e+01 7.22278366e+01 7.22227707e+01 7.22224426e+01 7.22225189e+01 7.22258759e+01 7.22287521e+01 7.22231598e+01 7.22340927e+01 7.22331543e+01 7.22224884e+01 7.22313156e+01 7.22304764e+01 7.22265472e+01 7.22223282e+01 7.22297592e+01 7.22328415e+01 7.22281189e+01 7.22224197e+01 7.22229080e+01 7.22226944e+01 7.22221909e+01 7.22225571e+01 7.22265091e+01 7.22287064e+01 7.22297897e+01 7.22261505e+01 7.22236786e+01 7.22244034e+01 7.22223129e+01 7.22383194e+01 7.22538605e+01 7.22406616e+01 7.22253342e+01 7.22229614e+01 7.22229996e+01 7.22337418e+01 7.22431412e+01 7.22376022e+01 7.22250824e+01 7.22227249e+01 7.22228699e+01 7.22234802e+01 7.22228851e+01 7.22231293e+01 7.22226486e+01 7.22247849e+01 7.22341385e+01 7.22282410e+01 7.22235870e+01 7.22285919e+01 7.22246704e+01 7.22272110e+01 7.22369156e+01 7.22332077e+01 7.22230606e+01 7.22292633e+01 7.22227859e+01 7.22234039e+01 7.22250824e+01 7.22227707e+01 7.22226639e+01 7.22238998e+01 7.22275085e+01 7.22318039e+01 7.22358246e+01 7.22306137e+01 7.22334595e+01 7.22256546e+01 7.22245178e+01 7.22239227e+01 7.22232513e+01 7.22275925e+01 7.22243118e+01 7.22239304e+01 7.22230530e+01 7.22250290e+01 7.22233353e+01 7.22240219e+01 7.22257996e+01 7.22227783e+01 7.22238083e+01 7.22229843e+01 7.22248535e+01 7.22409515e+01 7.22309875e+01 7.22229080e+01 7.22261429e+01 7.22281036e+01 7.22227020e+01 7.22242966e+01 7.22226410e+01 7.22220917e+01 7.22227249e+01 7.22237091e+01 7.22234192e+01 7.22260666e+01 7.22228165e+01 7.22281113e+01 7.22276764e+01 7.22203522e+01 7.22194595e+01 7.22395477e+01 7.22205200e+01 7.23804169e+01 1.11014030e+02 2.46551147e+02 96737792. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 952141376. -391618048. 47199648. 104751112. 2.23915451e+02 1.05253143e+02 7.26167603e+01 7.22818604e+01 7.22197342e+01 7.22287598e+01 7.22222061e+01 7.22219849e+01 7.22222443e+01 7.22222977e+01 7.22233276e+01 7.22269058e+01 7.22261200e+01 7.22234879e+01 7.22226257e+01 7.22228470e+01 7.22270355e+01 7.22293015e+01 7.22338104e+01 7.22296906e+01 7.22275085e+01 7.22229004e+01 7.22233124e+01 7.22261429e+01 7.22295837e+01 7.22241364e+01 7.22278290e+01 7.22237244e+01 7.22281647e+01 7.22347565e+01 7.22272949e+01 7.22231598e+01 7.22228851e+01 7.22226944e+01 7.22227859e+01 7.22232513e+01 7.22259903e+01 7.22261200e+01 7.22243118e+01 7.22223740e+01 7.22244720e+01 7.22286987e+01 7.22382889e+01 7.22574158e+01 7.22428589e+01 7.22258377e+01 7.22298203e+01 7.22297058e+01 7.22243652e+01 7.22258987e+01 7.22233658e+01 7.22279663e+01 7.22258606e+01 7.22224655e+01 7.22236404e+01 7.22251816e+01 7.22228699e+01 7.22226868e+01 7.22230835e+01 7.22237625e+01 7.22347641e+01 7.22526550e+01 7.22489166e+01 7.22298813e+01 7.22228012e+01 7.22239990e+01 7.22279282e+01 7.22383728e+01 7.22637253e+01 7.22752686e+01 7.22739792e+01 7.22439804e+01 7.22318192e+01 7.22381363e+01 7.22276459e+01 7.22228546e+01 7.22347488e+01 7.22271957e+01 7.22233200e+01 7.22248840e+01 7.22259827e+01 7.22249146e+01 7.22265778e+01 7.22237320e+01 7.22227783e+01 7.22226715e+01 7.22241592e+01 7.22244720e+01 7.22248764e+01 7.22288971e+01 7.22411728e+01 7.22354202e+01 7.22258148e+01 7.22322311e+01 7.22325211e+01 7.22305450e+01 7.22228546e+01 7.22228928e+01 7.22308655e+01 7.22319641e+01 7.22257080e+01 7.22269211e+01 7.22310791e+01 7.22227859e+01 7.22238464e+01 7.22301941e+01 7.22309341e+01 7.22378845e+01 7.22385941e+01 7.22296600e+01 7.22299042e+01 7.22308884e+01 7.22329788e+01 7.22284775e+01 7.22231064e+01 7.22245712e+01 7.22248611e+01 7.22236633e+01 7.22260666e+01 7.22245483e+01 7.22231140e+01 7.22315674e+01 7.22348480e+01 7.22235107e+01 7.22289429e+01 7.22237625e+01 7.22290573e+01 7.22292633e+01 7.22229156e+01 7.22245178e+01 7.22268372e+01 7.22270355e+01 7.22248077e+01 7.22225876e+01 7.22254639e+01 7.22224655e+01 7.22253876e+01 7.22253418e+01 7.22225723e+01 7.22249374e+01 7.22223816e+01 7.22239914e+01 7.22248459e+01 7.22288055e+01 7.22295761e+01 7.22329865e+01 7.22299805e+01 7.22280121e+01 7.22364655e+01 7.22335892e+01 7.22300873e+01 7.22235489e+01 7.22316971e+01 7.22296677e+01 7.22249222e+01 7.22233810e+01 7.22253952e+01 7.22303619e+01 7.22371902e+01 7.22372284e+01 7.22329407e+01 7.22295227e+01 7.22324142e+01 7.22368011e+01 7.22285538e+01 7.22227325e+01 7.22311325e+01 7.22387924e+01 7.22221680e+01 7.22250214e+01 7.22238770e+01 7.22240601e+01 7.22242584e+01 7.22232437e+01 7.22224426e+01 7.22247543e+01 7.22249756e+01 7.22245331e+01 7.22223206e+01 7.22235489e+01 7.22230225e+01 7.22276688e+01 7.22264481e+01 7.22252808e+01 7.22261734e+01 7.22340469e+01 7.22523117e+01 7.22665710e+01 7.22760391e+01 7.22351074e+01 7.22232742e+01 7.22233734e+01 7.22228012e+01 7.22300873e+01 7.22289658e+01 7.22235489e+01 7.22312012e+01 7.22301254e+01 7.22222290e+01 7.22288895e+01 7.22359467e+01 7.22293320e+01 7.22356262e+01 7.22411118e+01 7.22380905e+01 7.22330704e+01 7.22337112e+01 7.22377396e+01 7.22324448e+01 7.22239227e+01 7.22233353e+01 7.22237473e+01 7.22231674e+01 7.22275391e+01 7.22508316e+01 7.22450180e+01 7.22257538e+01 7.22225113e+01 7.22230606e+01 7.22227097e+01 7.22261200e+01 7.22351151e+01 7.22421570e+01 7.22297516e+01 7.22226181e+01 7.22279129e+01 7.22319031e+01 7.22233353e+01 7.22242813e+01 7.22254028e+01 7.22223892e+01 7.22230148e+01 7.22225494e+01 7.22225571e+01 7.22228775e+01 7.22228470e+01 7.22226334e+01 7.22222824e+01 7.22223434e+01 7.22227020e+01 7.22231064e+01 7.22239227e+01 7.22250595e+01 7.22260666e+01 7.22222061e+01 7.22221069e+01 7.22225800e+01 7.22225494e+01 7.22225342e+01 7.22225800e+01 7.22243500e+01 7.22269440e+01 7.22279129e+01 7.22241135e+01 7.22226486e+01 7.22224884e+01 7.22224808e+01 7.22227631e+01 7.22226257e+01 7.22233047e+01 7.22230072e+01 7.22225342e+01 7.22227402e+01 7.22227554e+01 7.22227936e+01 7.22241974e+01 7.22230835e+01 7.22232742e+01 7.22231140e+01 7.22242508e+01 7.22235413e+01 7.22230530e+01 7.22232895e+01 7.22228699e+01 7.22224960e+01 7.22231827e+01 7.22232895e+01 7.22231598e+01 7.22221909e+01 7.22226791e+01 7.22237015e+01 7.22252731e+01 7.22231140e+01 7.22247543e+01 7.22272873e+01 7.22286072e+01 7.22236328e+01 7.22228241e+01 7.22225113e+01 7.22228622e+01 7.22226486e+01 7.22227325e+01 7.22227478e+01 7.22234650e+01 7.22277679e+01 7.22238159e+01 7.22229080e+01 7.22227783e+01 7.22230225e+01 7.22229080e+01 7.22232590e+01 7.22225113e+01 7.22221680e+01 7.22222824e+01 7.22225876e+01 7.22226257e+01 7.22234116e+01 7.22249908e+01 7.22236786e+01 7.22225342e+01 7.22226334e+01 7.22233200e+01 7.22244492e+01 7.22247925e+01 7.22226486e+01 7.22225418e+01 7.22226028e+01 7.22226105e+01 7.22229385e+01 7.22251511e+01 7.22243042e+01 7.22221756e+01 7.22232285e+01 7.22226105e+01 7.22231750e+01 7.22232895e+01 7.22236862e+01 7.22283020e+01 7.22299347e+01 7.22249832e+01 7.22229996e+01 7.22222900e+01 7.22225266e+01 7.22225952e+01 7.22228470e+01 7.22233505e+01 7.22229843e+01 7.22231674e+01 7.22227707e+01 7.22227936e+01 7.22227402e+01 7.22254181e+01 7.22271881e+01 7.22316437e+01 7.22279510e+01 7.22268753e+01 7.22233658e+01 7.22250748e+01 7.22251434e+01 7.22237625e+01 7.22224731e+01 7.22237473e+01 7.22226868e+01 7.22226181e+01 7.22221375e+01 7.22224655e+01 7.22222443e+01 7.22226410e+01 7.22226105e+01 7.22246475e+01 7.22290421e+01 7.22233963e+01 7.22297058e+01 7.22335968e+01 7.22243576e+01 7.22224808e+01 7.22224655e+01 7.22228546e+01 7.22227936e+01 7.22226868e+01 7.22230530e+01 7.22227478e+01 7.22231598e+01 7.22282104e+01 7.22250214e+01 7.22228928e+01 7.22267380e+01 7.22238083e+01 7.22226562e+01 7.22239227e+01 7.22230759e+01 7.22235794e+01 7.22238083e+01 7.22288971e+01 7.22321472e+01 7.22295609e+01 7.22234192e+01 7.22225494e+01 7.22224197e+01 7.22223969e+01 7.22220764e+01 7.22226639e+01 7.22224579e+01 7.22227402e+01 7.22228088e+01 7.22237473e+01 7.22243805e+01 7.22248154e+01 7.22232819e+01 7.22227936e+01 7.22224350e+01 7.22253494e+01 7.22428131e+01 7.22516251e+01 7.22365799e+01 7.22253799e+01 7.22225266e+01 7.22224960e+01 7.22229156e+01 7.22233276e+01 7.22237778e+01 7.22234802e+01 7.22229385e+01 7.22232056e+01 7.22228165e+01 7.22241821e+01 7.22299042e+01 7.22316132e+01 7.22251434e+01 7.22226562e+01 7.22227402e+01 7.22227554e+01 7.22230377e+01 7.22233887e+01 7.22236786e+01 7.22235794e+01 7.22237320e+01 7.22238846e+01 7.22232437e+01 7.22230225e+01 7.22232361e+01 7.22246933e+01 7.22240829e+01 7.22231674e+01 7.22226944e+01 7.22228241e+01 7.22235336e+01 7.22241592e+01 7.22231979e+01 7.22226410e+01 7.22230911e+01 7.22232513e+01 7.22228851e+01 7.22235184e+01 7.22267303e+01 7.22319794e+01 7.22288895e+01 7.22231903e+01 7.22230301e+01 7.22243576e+01 7.22261581e+01 7.22300034e+01 7.22274399e+01 7.22238998e+01 7.22217407e+01 7.22193756e+01 7.22478180e+01 7.22393570e+01 7.22665939e+01 1.03899048e+02 2.33273590e+02 414015968. 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. 0. 0. 0. 0. 0. 0. 237957728. -907942144. 2.16416489e+02 1.03141655e+02 7.25093536e+01 7.23454666e+01 7.22584686e+01 7.22262955e+01 7.22243652e+01 7.22229691e+01 7.22269287e+01 7.22350159e+01 7.22341385e+01 7.22299652e+01 7.22273560e+01 7.22288284e+01 7.22293930e+01 7.22297516e+01 7.22300797e+01 7.22277832e+01 7.22267838e+01 7.22244492e+01 7.22234650e+01 7.22230682e+01 7.22233047e+01 7.22240372e+01 7.22225037e+01 7.22227402e+01 7.22228241e+01 7.22227478e+01 7.22228699e+01 7.22226410e+01 7.22225189e+01 7.22226257e+01 7.22234497e+01 7.22236481e+01 7.22235947e+01 7.22237167e+01 7.22233658e+01 7.22237167e+01 7.22226868e+01 7.22228394e+01 7.22228775e+01 7.22227020e+01 7.22236557e+01 7.22246094e+01 7.22259903e+01 7.22245331e+01 7.22268524e+01 7.22294083e+01 7.22305908e+01 7.22270126e+01 7.22237930e+01 7.22236633e+01 7.22245483e+01 7.22246017e+01 7.22243576e+01 7.22233810e+01 7.22234955e+01 7.22233658e+01 7.22228775e+01 7.22229996e+01 7.22245560e+01 7.22315674e+01 7.22329788e+01 7.22298203e+01 7.22267609e+01 7.22324829e+01 7.22361526e+01 7.22304382e+01 7.22248154e+01 7.22226410e+01 7.22231674e+01 7.22234497e+01 7.22261734e+01 7.22336121e+01 7.22409592e+01 7.22396088e+01 7.22299118e+01 7.22247696e+01 7.22234039e+01 7.22223663e+01 7.22230377e+01 7.22229004e+01 7.22250137e+01 7.22333374e+01 7.22370453e+01 7.22329483e+01 7.22265396e+01 7.22234039e+01 7.22234344e+01 7.22241516e+01 7.22297516e+01 7.22374573e+01 7.22343140e+01 7.22262268e+01 7.22232666e+01 7.22230530e+01 7.22240143e+01 7.22255936e+01 7.22293167e+01 7.22239838e+01 7.22233734e+01 7.22256775e+01 7.22240829e+01 7.22226028e+01 7.22224808e+01 7.22232056e+01 7.22252731e+01 7.22288361e+01 7.22353439e+01 7.22322769e+01 7.22251511e+01 7.22228699e+01 7.22255707e+01 7.22249756e+01 7.22246552e+01 7.22236862e+01 7.22233582e+01 7.22241898e+01 7.22245178e+01 7.22244949e+01 7.22232819e+01 7.22229614e+01 7.22224045e+01 7.22225266e+01 7.22223892e+01 7.22228699e+01 7.22267609e+01 7.22358551e+01 7.22346649e+01 7.22270737e+01 7.22230301e+01 7.22245560e+01 7.22272720e+01 7.22359543e+01 7.22410583e+01 7.22355804e+01 7.22255020e+01 7.22225494e+01 7.22227478e+01 7.22226791e+01 7.22224197e+01 7.22229843e+01 7.22230682e+01 7.22238541e+01 7.22234344e+01 7.22225418e+01 7.22227020e+01 7.22226028e+01 7.22233047e+01 7.22229767e+01 7.22227249e+01 7.22263107e+01 7.22356873e+01 7.22330551e+01 7.22255783e+01 7.22227783e+01 7.22256622e+01 7.22328720e+01 7.22412262e+01 7.22432480e+01 7.22464218e+01 7.22473145e+01 7.22333069e+01 7.22260666e+01 7.22230606e+01 7.22229080e+01 7.22228775e+01 7.22226105e+01 7.22230225e+01 7.22229309e+01 7.22230606e+01 7.22231827e+01 7.22234573e+01 7.22236023e+01 7.22243576e+01 7.22331696e+01 7.22332153e+01 7.22240143e+01 7.22230606e+01 7.22237244e+01 7.22233963e+01 7.22228470e+01 7.22228241e+01 7.22234116e+01 7.22272720e+01 7.22275772e+01 7.22232208e+01 7.22227249e+01 7.22228088e+01 7.22233734e+01 7.22229843e+01 7.22229462e+01 7.22228699e+01 7.22227402e+01 7.22236176e+01 7.22233963e+01 7.22232666e+01 7.22229385e+01 7.22228622e+01 7.22233582e+01 7.22266769e+01 7.22260361e+01 7.22231750e+01 7.22227783e+01 7.22231216e+01 7.22229767e+01 7.22227478e+01 7.22230606e+01 7.22234802e+01 7.22230682e+01 7.22226868e+01 7.22226639e+01 7.22229309e+01 7.22236023e+01 7.22230911e+01 7.22224808e+01 7.22227783e+01 7.22229080e+01 7.22230225e+01 7.22234344e+01 7.22234192e+01 7.22233353e+01 7.22229385e+01 7.22229462e+01 7.22237701e+01 7.22259674e+01 7.22267914e+01 7.22247391e+01 7.22233429e+01 7.22235336e+01 7.22237701e+01 7.22245407e+01 7.22254639e+01 7.22260361e+01 7.22257538e+01 7.22243347e+01 7.22249908e+01 7.22247925e+01 7.22240143e+01 7.22232056e+01 7.22228394e+01 7.22230606e+01 7.22239761e+01 7.22302170e+01 7.22331543e+01 7.22271271e+01 7.22242661e+01 7.22339249e+01 7.22332306e+01 7.22239304e+01 7.22225113e+01 7.22256622e+01 7.22332458e+01 7.22318420e+01 7.22233658e+01 7.22233353e+01 7.22236710e+01 7.22234650e+01 7.22230911e+01 7.22231979e+01 7.22227859e+01 7.22230530e+01 7.22229996e+01 7.22228470e+01 7.22231750e+01 7.22227936e+01 7.22235947e+01 7.22237320e+01 7.22226715e+01 7.22235260e+01 7.22233200e+01 7.22232208e+01 7.22230835e+01 7.22230835e+01 7.22235184e+01 7.22231445e+01 7.22275696e+01 7.22309113e+01 7.22298813e+01 7.22237473e+01 7.22232437e+01 7.22232666e+01 7.22226028e+01 7.22228851e+01 7.22232361e+01 7.22234192e+01 7.22273788e+01 7.22263336e+01 7.22236328e+01 7.22227173e+01 7.22229156e+01 7.22231674e+01 7.22235031e+01 7.22230225e+01 7.22246094e+01 7.22310791e+01 7.22317047e+01 7.22256165e+01 7.22228775e+01 7.22227478e+01 7.22227631e+01 7.22226944e+01 7.22226562e+01 7.22242355e+01 7.22307892e+01 7.22316742e+01 7.22293854e+01 7.22242432e+01 7.22248840e+01 7.22240524e+01 7.22237473e+01 7.22230759e+01 7.22230606e+01 7.22238922e+01 7.22249680e+01 7.22242126e+01 7.22230606e+01 7.22226715e+01 7.22229462e+01 7.22230988e+01 7.22234421e+01 7.22231598e+01 7.22227478e+01 7.22228241e+01 7.22243042e+01 7.22302170e+01 7.22395782e+01 7.22414932e+01 7.22402039e+01 7.22365112e+01 7.22256317e+01 7.22232056e+01 7.22229385e+01 7.22228012e+01 7.22228928e+01 7.22237473e+01 7.22284775e+01 7.22276001e+01 7.22239532e+01 7.22238922e+01 7.22288437e+01 7.22290268e+01 7.22254257e+01 7.22228470e+01 7.22227173e+01 7.22228394e+01 7.22263641e+01 7.22334366e+01 7.22288284e+01 7.22231750e+01 7.22253952e+01 7.22232285e+01 7.22234955e+01 7.22258453e+01 7.22256775e+01 7.22234955e+01 7.22226791e+01 7.22245865e+01 7.22246475e+01 7.22244720e+01 7.22241211e+01 7.22243805e+01 7.22238693e+01 7.22239609e+01 7.22230606e+01 7.22229919e+01 7.22232132e+01 7.22230072e+01 7.22230225e+01 7.22249374e+01 7.22347031e+01 7.22280960e+01 7.22228775e+01 7.22246017e+01 7.22239456e+01 7.22286987e+01 7.22254639e+01 7.22230988e+01 7.22259293e+01 7.22299500e+01 7.22312622e+01 7.22254715e+01 7.22228699e+01 7.22229080e+01 7.22232971e+01 7.22256851e+01 7.22243576e+01 7.22229843e+01 7.22229004e+01 7.22225952e+01 7.22230377e+01 7.22231674e+01 7.22230225e+01 7.22236252e+01 7.22248383e+01 7.22299728e+01 7.22239380e+01 7.22237473e+01 7.22233124e+01 7.22261581e+01 7.22350845e+01 7.22246780e+01 7.22227631e+01 7.22232590e+01 7.22258987e+01 7.22231979e+01 7.22244034e+01 7.22285309e+01 7.22263412e+01 7.22267075e+01 7.22230225e+01 7.22239151e+01 7.22239304e+01 7.22232208e+01 7.22235870e+01 7.22246323e+01 7.22253571e+01 7.22227554e+01 7.22248459e+01 7.22246323e+01 7.22245483e+01 7.22281723e+01 7.22326431e+01 7.22285233e+01 7.22231827e+01 7.22242966e+01 7.22229156e+01 7.22226105e+01 7.22225647e+01 7.22229919e+01 7.22230988e+01 7.22232361e+01 7.22228012e+01 7.22236023e+01 7.22244186e+01 7.22229996e+01 7.22270966e+01 7.22289963e+01 7.22256393e+01 7.22278824e+01 7.22404556e+01 7.22343216e+01 7.22234726e+01 7.22269745e+01 7.22279434e+01 7.22247086e+01 7.22249832e+01 7.22259598e+01 7.22244492e+01 7.22227936e+01 7.22231216e+01 7.22227859e+01 7.22224579e+01 7.22229691e+01 7.22249069e+01 7.22253189e+01 7.22236557e+01 7.22231293e+01 7.22235107e+01 7.22244949e+01 7.22229385e+01 7.22239914e+01 7.22230225e+01 7.22234497e+01 7.22235184e+01 7.22224350e+01 7.22224121e+01 7.22250671e+01 7.22244720e+01 7.22232819e+01 7.22384644e+01 7.22425308e+01 7.22347336e+01 7.22330933e+01 7.22353897e+01 7.22335434e+01 7.22256699e+01 7.22230453e+01 7.22231140e+01 7.22238007e+01 7.22254105e+01 7.22293091e+01 7.22281647e+01 7.22232666e+01 7.22235260e+01 7.22224274e+01 7.22236786e+01 7.22234802e+01 7.22224808e+01 7.22225952e+01 7.22281570e+01 7.22239380e+01 7.22267914e+01 7.22438049e+01 7.22349091e+01 7.22252121e+01 7.22271500e+01 7.22349243e+01 7.22391129e+01 7.22312851e+01 7.22263260e+01 7.22289810e+01 7.22307587e+01 7.22322464e+01 7.22264709e+01 7.22225189e+01 7.22272034e+01 7.22345657e+01 7.22359619e+01 7.22235489e+01 7.22237015e+01 7.22298203e+01 7.22240524e+01 7.22220993e+01 7.22220154e+01 7.22223282e+01 7.22250748e+01 7.22350616e+01 7.22327805e+01 7.22252274e+01 7.22227020e+01 7.22225571e+01 7.22225266e+01 7.22265625e+01 7.22319107e+01 7.22296906e+01 7.22245636e+01 7.22222824e+01 7.22224274e+01 7.22224960e+01 7.22227097e+01 7.22229156e+01 7.22233276e+01 7.22231598e+01 7.22227020e+01 7.22224197e+01 7.22226715e+01 7.22228851e+01 7.22227020e+01 7.22241440e+01 7.22358932e+01 7.22362747e+01 7.22273941e+01 7.22266159e+01 7.22326355e+01 7.22325287e+01 7.22262955e+01 7.22230377e+01 7.22267685e+01 7.22323608e+01 7.22294083e+01 7.22234192e+01 7.22237701e+01 7.22243042e+01 7.22242813e+01 7.22225571e+01 7.22258682e+01 7.22250977e+01 7.22226105e+01 7.22232819e+01 7.22301865e+01 7.22326508e+01 7.22255249e+01 7.22222748e+01 7.22229996e+01 7.22288666e+01 7.22277298e+01 7.22225037e+01 7.22259369e+01 7.22227402e+01 7.22234421e+01 7.22240982e+01 7.22235718e+01 7.22233200e+01 7.22250366e+01 7.22269440e+01 7.22265930e+01 7.22323227e+01 7.22351379e+01 7.22346802e+01 7.22266617e+01 7.22234116e+01 7.22228546e+01 7.22228165e+01 7.22224655e+01 7.22225342e+01 7.22228165e+01 7.22235260e+01 7.22228775e+01 7.22224045e+01 7.22225494e+01 7.22254715e+01 7.22322006e+01 7.22248306e+01 7.22255249e+01 7.22309494e+01 7.22226334e+01 7.22232056e+01 7.22240753e+01 7.22228851e+01 7.22223816e+01 7.22210236e+01 7.22198410e+01 7.22192078e+01 7.22196884e+01 7.22941208e+01 7.26539536e+01 1.12033447e+02 2.69287811e+02 -420918272. 0. 0. 0. 0. 161829888. -157659952. 339223936. 60840276. 3.38469391e+02 5.19607056e+02 5.46256409e+02 -370151072. 0. 0.
================================================ FILE: config/m2dgr/ring32_v.xml ================================================ 32 1800
"3f"
0. 0. 0. 0. 0. 0. 0. 0. 1.87887499e-40 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. 0. 0. 0. 0. 0. -9.05177236e-01 4.53008078e-02 -4.22618151e-01 -9.05049205e-01 4.76490222e-02 -4.22613263e-01 -9.04901981e-01 5.05062006e-02 -4.22615260e-01 -9.04693842e-01 5.41161150e-02 -4.22614664e-01 -9.04510319e-01 5.70213459e-02 -4.22613591e-01 -9.04309869e-01 6.00650758e-02 -4.22613055e-01 -9.04082537e-01 6.33378029e-02 -4.22612816e-01 -9.03852940e-01 6.65895939e-02 -4.22613144e-01 -9.03615952e-01 6.97344244e-02 -4.22613144e-01 -9.03367460e-01 7.28907883e-02 -4.22613084e-01 -9.03106391e-01 7.60501102e-02 -4.22613114e-01 -9.02847946e-01 7.91096166e-02 -4.22613591e-01 -9.02561843e-01 8.22299421e-02 -4.22612786e-01 -9.02263522e-01 8.54805261e-02 -4.22613084e-01 -9.01970387e-01 8.85461122e-02 -4.22613382e-01 -9.01649654e-01 9.16829929e-02 -4.22612727e-01 -9.01320279e-01 9.49296132e-02 -4.22613233e-01 -9.00983155e-01 9.80614796e-02 -4.22613114e-01 -9.00636375e-01 1.01204477e-01 -4.22613144e-01 -9.00280297e-01 1.04314059e-01 -4.22613204e-01 -8.99918854e-01 1.07388183e-01 -4.22613263e-01 -8.99544477e-01 1.10483065e-01 -4.22613084e-01 -8.99143815e-01 1.13685891e-01 -4.22612846e-01 -8.98729384e-01 1.16917305e-01 -4.22613084e-01 -8.98329973e-01 1.19972982e-01 -4.22613412e-01 -8.97903860e-01 1.23090290e-01 -4.22612846e-01 -8.97459269e-01 1.26306757e-01 -4.22613174e-01 -8.97028267e-01 1.29345462e-01 -4.22613412e-01 -8.96562994e-01 1.32493556e-01 -4.22612876e-01 -8.96101236e-01 1.35616496e-01 -4.22613382e-01 -8.95635366e-01 1.38649195e-01 -4.22613204e-01 -8.95127892e-01 1.41859621e-01 -4.22612756e-01 -8.94615769e-01 1.45080447e-01 -4.22613114e-01 -8.94102633e-01 1.48212522e-01 -4.22613114e-01 -8.93579543e-01 1.51339427e-01 -4.22613084e-01 -8.93047988e-01 1.54433936e-01 -4.22613144e-01 -8.92505348e-01 1.57564268e-01 -4.22613055e-01 -8.91944706e-01 1.60699993e-01 -4.22613114e-01 -8.91371429e-01 1.63822159e-01 -4.22613025e-01 -8.90817046e-01 1.66849837e-01 -4.22613651e-01 -8.90250206e-01 1.69823110e-01 -4.22613114e-01 -8.89627814e-01 1.73028603e-01 -4.22612756e-01 -8.89005125e-01 1.76228404e-01 -4.22613233e-01 -8.88385475e-01 1.79324925e-01 -4.22613084e-01 -8.87752891e-01 1.82432428e-01 -4.22613084e-01 -8.87108743e-01 1.85531884e-01 -4.22613114e-01 -8.86474907e-01 1.88560203e-01 -4.22613591e-01 -8.85809600e-01 1.91632792e-01 -4.22612786e-01 -8.85114431e-01 1.94824159e-01 -4.22613114e-01 -8.84449422e-01 1.97839871e-01 -4.22613412e-01 -8.83750260e-01 2.00909957e-01 -4.22612846e-01 -8.83024991e-01 2.04092950e-01 -4.22613055e-01 -8.82307649e-01 2.07177445e-01 -4.22613144e-01 -8.81578565e-01 2.10258961e-01 -4.22613114e-01 -8.80864739e-01 2.13247031e-01 -4.22613591e-01 -8.80136371e-01 2.16209695e-01 -4.22613084e-01 -8.79344404e-01 2.19387904e-01 -4.22612756e-01 -8.78550708e-01 2.22557947e-01 -4.22613084e-01 -8.77766609e-01 2.25635752e-01 -4.22613084e-01 -8.77001286e-01 2.28606746e-01 -4.22613591e-01 -8.76205385e-01 2.31621623e-01 -4.22612906e-01 -8.75390053e-01 2.34697744e-01 -4.22613233e-01 -8.74553204e-01 2.37780750e-01 -4.22612906e-01 -8.73697937e-01 2.40905464e-01 -4.22613114e-01 -8.72875214e-01 2.43892014e-01 -4.22613412e-01 -8.72042179e-01 2.46836171e-01 -4.22613114e-01 -8.71149063e-01 2.49957636e-01 -4.22612786e-01 -8.70248616e-01 2.53091067e-01 -4.22613144e-01 -8.69367838e-01 2.56100744e-01 -4.22613233e-01 -8.68479848e-01 2.59095997e-01 -4.22613204e-01 -8.67562771e-01 2.62135327e-01 -4.22612906e-01 -8.66659224e-01 2.65130430e-01 -4.22613591e-01 -8.65726829e-01 2.68137574e-01 -4.22612786e-01 -8.64761531e-01 2.71247298e-01 -4.22613204e-01 -8.63834321e-01 2.74190933e-01 -4.22613353e-01 -8.62868071e-01 2.77199000e-01 -4.22612846e-01 -8.61877978e-01 2.80269891e-01 -4.22613144e-01 -8.60891283e-01 2.83285886e-01 -4.22613114e-01 -8.59896779e-01 2.86290884e-01 -4.22613084e-01 -8.58891666e-01 2.89301604e-01 -4.22613174e-01 -8.57903957e-01 2.92217523e-01 -4.22613531e-01 -8.56903374e-01 2.95132369e-01 -4.22613114e-01 -8.55842710e-01 2.98183292e-01 -4.22612816e-01 -8.54768932e-01 3.01257879e-01 -4.22613114e-01 -8.53743613e-01 3.04162443e-01 -4.22613531e-01 -8.52670789e-01 3.07135433e-01 -4.22612756e-01 -8.51565242e-01 3.10198963e-01 -4.22613144e-01 -8.50478828e-01 3.13152879e-01 -4.22613144e-01 -8.49379420e-01 3.16112250e-01 -4.22613144e-01 -8.48295391e-01 3.19018394e-01 -4.22613382e-01 -8.47214222e-01 3.21885705e-01 -4.22613174e-01 -8.46062839e-01 3.24907482e-01 -4.22612876e-01 -8.44882727e-01 3.27953935e-01 -4.22613055e-01 -8.43729079e-01 3.30919892e-01 -4.22613084e-01 -8.42571497e-01 3.33853841e-01 -4.22613055e-01 -8.41401637e-01 3.36792618e-01 -4.22613114e-01 -8.40221882e-01 3.39721829e-01 -4.22613114e-01 -8.39035332e-01 3.42643976e-01 -4.22613084e-01 -8.37831438e-01 3.45574021e-01 -4.22613114e-01 -8.36652875e-01 3.48429233e-01 -4.22613412e-01 -8.35466921e-01 3.51256132e-01 -4.22613144e-01 -8.34202528e-01 3.54239732e-01 -4.22612846e-01 -8.32928479e-01 3.57228160e-01 -4.22613114e-01 -8.31682324e-01 3.60125154e-01 -4.22613233e-01 -8.30430448e-01 3.63005131e-01 -4.22613055e-01 -8.29178870e-01 3.65857244e-01 -4.22613353e-01 -8.27913821e-01 3.68705690e-01 -4.22613084e-01 -8.26593161e-01 3.71654421e-01 -4.22612906e-01 -8.25264037e-01 3.74600619e-01 -4.22613084e-01 -8.23985219e-01 3.77406418e-01 -4.22613591e-01 -8.22668195e-01 3.80256265e-01 -4.22612756e-01 -8.21299791e-01 3.83207828e-01 -4.22613084e-01 -8.19969594e-01 3.86051625e-01 -4.22613204e-01 -8.18624556e-01 3.88896316e-01 -4.22613144e-01 -8.17263186e-01 3.91746193e-01 -4.22613174e-01 -8.15927923e-01 3.94532233e-01 -4.22613293e-01 -8.14528346e-01 3.97401184e-01 -4.22612816e-01 -8.13094795e-01 4.00328308e-01 -4.22613144e-01 -8.11702669e-01 4.03145432e-01 -4.22613174e-01 -8.10286641e-01 4.05979097e-01 -4.22613084e-01 -8.08864772e-01 4.08808380e-01 -4.22613144e-01 -8.07474792e-01 4.11554247e-01 -4.22613591e-01 -8.06070268e-01 4.14290756e-01 -4.22613114e-01 -8.04587841e-01 4.17158097e-01 -4.22612906e-01 -8.03186476e-01 4.19872135e-01 -4.22614336e-01 -8.02036047e-01 4.22055781e-01 -4.22618330e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.90363252e-01 4.43530977e-01 -4.22618270e-01 -7.89245963e-01 4.45516020e-01 -4.22618300e-01 -7.88108051e-01 4.47525591e-01 -4.22618330e-01 -7.86717772e-01 4.49964970e-01 -4.22618270e-01 -7.85162151e-01 4.52674121e-01 -4.22618300e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. -7.62876511e-01 4.89298373e-01 -4.22618330e-01 -7.61389911e-01 4.91615772e-01 -4.22616929e-01 -7.60054708e-01 4.93659347e-01 -4.22612965e-01 -7.58315027e-01 4.96332735e-01 -4.22613323e-01 -7.56641448e-01 4.98889297e-01 -4.22615290e-01 -7.54777789e-01 5.01696885e-01 -4.22613502e-01 -7.53050327e-01 5.04282653e-01 -4.22613114e-01 -7.51340210e-01 5.06836176e-01 -4.22613591e-01 -7.49550998e-01 5.09461403e-01 -4.22612727e-01 -7.47715056e-01 5.12159824e-01 -4.22613114e-01 -7.45929360e-01 5.14757931e-01 -4.22613114e-01 -7.44178116e-01 5.17291963e-01 -4.22613591e-01 -7.42373049e-01 5.19865930e-01 -4.22612786e-01 -7.40523994e-01 5.22508800e-01 -4.22613293e-01 -7.38684356e-01 5.25096655e-01 -4.22612876e-01 -7.36829162e-01 5.27704597e-01 -4.22613204e-01 -7.35037267e-01 5.30196488e-01 -4.22613591e-01 -7.33215928e-01 5.32707751e-01 -4.22612965e-01 -7.31292486e-01 5.35343587e-01 -4.22612965e-01 -7.29380190e-01 5.37948549e-01 -4.22613025e-01 -7.27490366e-01 5.40502548e-01 -4.22613114e-01 -7.25597084e-01 5.43040633e-01 -4.22613084e-01 -7.23706841e-01 5.45558989e-01 -4.22613144e-01 -7.21802771e-01 5.48076987e-01 -4.22613114e-01 -7.19883919e-01 5.50594211e-01 -4.22613114e-01 -7.17959166e-01 5.53099275e-01 -4.22613114e-01 -7.16074824e-01 5.55544019e-01 -4.22613591e-01 -7.14129269e-01 5.58026493e-01 -4.22612727e-01 -7.12109387e-01 5.60613632e-01 -4.22613174e-01 -7.10150361e-01 5.63090265e-01 -4.22613114e-01 -7.08175302e-01 5.65576315e-01 -4.22613114e-01 -7.06193864e-01 5.68047464e-01 -4.22613174e-01 -7.04217196e-01 5.70494473e-01 -4.22613084e-01 -7.02291906e-01 5.72866380e-01 -4.22613591e-01 -7.00287223e-01 5.75308144e-01 -4.22612756e-01 -6.98207140e-01 5.77835798e-01 -4.22613114e-01 -6.96250260e-01 5.80196559e-01 -4.22613591e-01 -6.94222450e-01 5.82610250e-01 -4.22612756e-01 -6.92132592e-01 5.85099518e-01 -4.22613233e-01 -6.90099180e-01 5.87491751e-01 -4.22613114e-01 -6.88021123e-01 5.89923918e-01 -4.22612995e-01 -6.85970664e-01 5.92313230e-01 -4.22613263e-01 -6.83962882e-01 5.94630003e-01 -4.22613263e-01 -6.81848109e-01 5.97043097e-01 -4.22612727e-01 -6.79681838e-01 5.99513590e-01 -4.22613025e-01 -6.77576244e-01 6.01893306e-01 -4.22613084e-01 -6.75479114e-01 6.04249239e-01 -4.22613174e-01 -6.73374832e-01 6.06589615e-01 -4.22613144e-01 -6.71259642e-01 6.08934700e-01 -4.22613174e-01 -6.69129550e-01 6.11269951e-01 -4.22613144e-01 -6.66997850e-01 6.13598406e-01 -4.22613174e-01 -6.64913177e-01 6.15860939e-01 -4.22613591e-01 -6.62751615e-01 6.18173838e-01 -4.22612756e-01 -6.60513103e-01 6.20570540e-01 -4.22613084e-01 -6.58339262e-01 6.22875988e-01 -4.22613114e-01 -6.56158149e-01 6.25174284e-01 -4.22613084e-01 -6.53977215e-01 6.27450645e-01 -4.22613174e-01 -6.51797473e-01 6.29726231e-01 -4.22613114e-01 -6.49643540e-01 6.31951213e-01 -4.22613412e-01 -6.47441328e-01 6.34196460e-01 -4.22612846e-01 -6.45165026e-01 6.36515915e-01 -4.22613025e-01 -6.42986476e-01 6.38725221e-01 -4.22613591e-01 -6.40751481e-01 6.40939713e-01 -4.22612846e-01 -6.38462484e-01 6.43242121e-01 -4.22613144e-01 -6.36212468e-01 6.45467103e-01 -4.22613114e-01 -6.33953333e-01 6.47682846e-01 -4.22613144e-01 -6.31711423e-01 6.49874151e-01 -4.22613204e-01 -6.29501283e-01 6.52018070e-01 -4.22613323e-01 -6.27206445e-01 6.54208064e-01 -4.22612816e-01 -6.24850452e-01 6.56469226e-01 -4.22613114e-01 -6.22554183e-01 6.58642292e-01 -4.22613084e-01 -6.20246470e-01 6.60817325e-01 -4.22613174e-01 -6.17939591e-01 6.62971854e-01 -4.22613114e-01 -6.15633368e-01 6.65119171e-01 -4.22613233e-01 -6.13310635e-01 6.67261064e-01 -4.22612995e-01 -6.10966027e-01 6.69406593e-01 -4.22613144e-01 -6.08623683e-01 6.71540499e-01 -4.22613144e-01 -6.06344163e-01 6.73601687e-01 -4.22613591e-01 -6.03992701e-01 6.75701857e-01 -4.22612786e-01 -6.01559937e-01 6.77875161e-01 -4.22613174e-01 -5.99185169e-01 6.79973304e-01 -4.22613114e-01 -5.96811056e-01 6.82056904e-01 -4.22613144e-01 -5.94429016e-01 6.84135735e-01 -4.22613144e-01 -5.92089236e-01 6.86164379e-01 -4.22613382e-01 -5.89685559e-01 6.88224316e-01 -4.22612876e-01 -5.87225795e-01 6.90328360e-01 -4.22613144e-01 -5.84868908e-01 6.92330956e-01 -4.22613591e-01 -5.82460344e-01 6.94348752e-01 -4.22612816e-01 -5.79970539e-01 6.96435094e-01 -4.22613114e-01 -5.77541828e-01 6.98448956e-01 -4.22613174e-01 -5.75092793e-01 7.00468361e-01 -4.22613055e-01 -5.72708607e-01 7.02420592e-01 -4.22613591e-01 -5.70252180e-01 7.04411030e-01 -4.22612816e-01 -5.67718327e-01 7.06457019e-01 -4.22613114e-01 -5.65314472e-01 7.08386004e-01 -4.22613472e-01 -5.62827826e-01 7.10355461e-01 -4.22612786e-01 -5.60350776e-01 7.12321103e-01 -4.22613591e-01 -5.57890236e-01 7.14239955e-01 -4.22612756e-01 -5.55301368e-01 7.16259599e-01 -4.22613084e-01 -5.52856565e-01 7.18153238e-01 -4.22613591e-01 -5.50382853e-01 7.20041454e-01 -4.22612816e-01 -5.47830939e-01 7.21992373e-01 -4.22613531e-01 -5.45312464e-01 7.23891199e-01 -4.22612906e-01 -5.42784095e-01 7.25793779e-01 -4.22613472e-01 -5.40258110e-01 7.27667212e-01 -4.22612786e-01 -5.37622571e-01 7.29620397e-01 -4.22613055e-01 -5.35080612e-01 7.31486738e-01 -4.22613084e-01 -5.32598495e-01 7.33302414e-01 -4.22613591e-01 -5.30083299e-01 7.35113502e-01 -4.22612965e-01 -5.27432919e-01 7.37020373e-01 -4.22612965e-01 -5.24884522e-01 7.38843441e-01 -4.22613591e-01 -5.22322357e-01 7.40651727e-01 -4.22612876e-01 -5.19726396e-01 7.42479324e-01 -4.22613591e-01 -5.17141163e-01 7.44274139e-01 -4.22612846e-01 -5.14464557e-01 7.46132135e-01 -4.22613114e-01 -5.11846900e-01 7.47930527e-01 -4.22613114e-01 -5.09301424e-01 7.49666989e-01 -4.22613412e-01 -5.06753325e-01 7.51390457e-01 -4.22613084e-01 -5.04049420e-01 7.53202677e-01 -4.22612846e-01 -5.01416862e-01 7.54962981e-01 -4.22613412e-01 -4.98794168e-01 7.56694555e-01 -4.22612906e-01 -4.96149480e-01 7.58435965e-01 -4.22613412e-01 -4.93529469e-01 7.60136962e-01 -4.22612876e-01 -4.90798950e-01 7.61905909e-01 -4.22613114e-01 -4.88115817e-01 7.63627112e-01 -4.22613084e-01 -4.85430211e-01 7.65336990e-01 -4.22613144e-01 -4.82746631e-01 7.67034292e-01 -4.22613114e-01 -4.80072379e-01 7.68712997e-01 -4.22613263e-01 -4.77464527e-01 7.70338655e-01 -4.22613591e-01 -4.74783182e-01 7.71984637e-01 -4.22612786e-01 -4.71980214e-01 7.73705900e-01 -4.22613025e-01 -4.69260126e-01 7.75357425e-01 -4.22613084e-01 -4.66641068e-01 7.76942492e-01 -4.22613591e-01 -4.63935971e-01 7.78551817e-01 -4.22612756e-01 -4.61116940e-01 7.80229568e-01 -4.22613174e-01 -4.58484113e-01 7.81784117e-01 -4.22613591e-01 -4.55767453e-01 7.83363402e-01 -4.22612846e-01 -4.53010827e-01 7.84968734e-01 -4.22613591e-01 -4.50278938e-01 7.86530077e-01 -4.22612816e-01 -4.47450191e-01 7.88147271e-01 -4.22613174e-01 -4.44717884e-01 7.89694309e-01 -4.22613263e-01 -4.42044348e-01 7.91190922e-01 -4.22613233e-01 -4.39254284e-01 7.92738318e-01 -4.22612816e-01 -4.36415881e-01 7.94313550e-01 -4.22613591e-01 -4.33726430e-01 7.95786560e-01 -4.22613591e-01 -4.30940866e-01 7.97287762e-01 -4.22612667e-01 -4.28131938e-01 7.98807979e-01 -4.22613442e-01 -4.25370961e-01 8.00276279e-01 -4.22612935e-01 -4.22562599e-01 8.01767945e-01 -4.22613382e-01 -4.19775754e-01 8.03224206e-01 -4.22612906e-01 -4.16910172e-01 8.04719627e-01 -4.22613144e-01 -4.14092928e-01 8.06172788e-01 -4.22613144e-01 -4.11266714e-01 8.07616830e-01 -4.22613084e-01 -4.08499420e-01 8.09024930e-01 -4.22613502e-01 -4.05686766e-01 8.10432971e-01 -4.22612965e-01 -4.02796954e-01 8.11873972e-01 -4.22613084e-01 -3.99944425e-01 8.13283443e-01 -4.22613114e-01 -3.97163093e-01 8.14649403e-01 -4.22613531e-01 -3.94327253e-01 8.16021025e-01 -4.22612846e-01 -3.91414046e-01 8.17422628e-01 -4.22613114e-01 -3.88553590e-01 8.18785906e-01 -4.22613084e-01 -3.85697037e-01 8.20137084e-01 -4.22613204e-01 -3.82899374e-01 8.21449101e-01 -4.22613412e-01 -3.80022824e-01 8.22778940e-01 -4.22612906e-01 -3.77078980e-01 8.24132085e-01 -4.22613084e-01 -3.74200523e-01 8.25445652e-01 -4.22613174e-01 -3.71415913e-01 8.26707423e-01 -4.22613591e-01 -3.68545979e-01 8.27983439e-01 -4.22612846e-01 -3.65565747e-01 8.29306662e-01 -4.22613174e-01 -3.62728208e-01 8.30555499e-01 -4.22613412e-01 -3.59829694e-01 8.31808507e-01 -4.22612906e-01 -3.56918156e-01 8.33063483e-01 -4.22613502e-01 -3.54091644e-01 8.34268630e-01 -4.22613174e-01 -3.51158917e-01 8.35508108e-01 -4.22613114e-01 -3.48186076e-01 8.36747706e-01 -4.22612906e-01 -3.45189184e-01 8.37991357e-01 -4.22613144e-01 -3.42269987e-01 8.39188337e-01 -4.22613144e-01 -3.39339346e-01 8.40377629e-01 -4.22613114e-01 -3.36439788e-01 8.41543734e-01 -4.22613323e-01 -3.33503306e-01 8.42708707e-01 -4.22612935e-01 -3.30521554e-01 8.43884885e-01 -4.22613084e-01 -3.27555537e-01 8.45036805e-01 -4.22613204e-01 -3.24690998e-01 8.46152961e-01 -4.22613591e-01 -3.21750760e-01 8.47264290e-01 -4.22612906e-01 -3.18719000e-01 8.48405719e-01 -4.22613055e-01 -3.15737963e-01 8.49519074e-01 -4.22613114e-01 -3.12860459e-01 8.50589216e-01 -4.22613591e-01 -3.09976786e-01 8.51646960e-01 -4.22613204e-01 -3.06929499e-01 8.52745473e-01 -4.22612816e-01 -3.03932309e-01 8.53826106e-01 -4.22613531e-01 -3.00977767e-01 8.54865670e-01 -4.22612906e-01 -2.97986537e-01 8.55918944e-01 -4.22613412e-01 -2.95004547e-01 8.56944859e-01 -4.22612906e-01 -2.91960150e-01 8.57989490e-01 -4.22613174e-01 -2.89018184e-01 8.58987212e-01 -4.22613353e-01 -2.86015838e-01 8.59985411e-01 -4.22612906e-01 -2.82996714e-01 8.60988796e-01 -4.22613353e-01 -2.79983252e-01 8.61968279e-01 -4.22612816e-01 -2.76982903e-01 8.62945259e-01 -4.22613502e-01 -2.73967892e-01 8.63900900e-01 -4.22612876e-01 -2.70892143e-01 8.64871919e-01 -4.22613174e-01 -2.67866820e-01 8.65813494e-01 -4.22613144e-01 -2.64840126e-01 8.66742969e-01 -4.22613084e-01 -2.61824399e-01 8.67659569e-01 -4.22613204e-01 -2.58805633e-01 8.68565083e-01 -4.22613114e-01 -2.55764753e-01 8.69467318e-01 -4.22613174e-01 -2.52725422e-01 8.70355189e-01 -4.22613114e-01 -2.49754697e-01 8.71212423e-01 -4.22613353e-01 -2.46702030e-01 8.72078836e-01 -4.22612876e-01 -2.43606403e-01 8.72950792e-01 -4.22613204e-01 -2.40558490e-01 8.73795390e-01 -4.22613114e-01 -2.37562120e-01 8.74619424e-01 -4.22613412e-01 -2.34588832e-01 8.75417650e-01 -4.22613114e-01 -2.31476843e-01 8.76242876e-01 -4.22612935e-01 -2.28409991e-01 8.77052367e-01 -4.22613353e-01 -2.25348234e-01 8.77838612e-01 -4.22612906e-01 -2.22292960e-01 8.78621221e-01 -4.22613591e-01 -2.19210252e-01 8.79389524e-01 -4.22612786e-01 -2.16038078e-01 8.80179644e-01 -4.22613114e-01 -2.13055402e-01 8.80910337e-01 -4.22613591e-01 -2.09971607e-01 8.81643176e-01 -4.22612756e-01 -2.06904247e-01 8.82375121e-01 -4.22613680e-01 -2.03842029e-01 8.83078933e-01 -4.22612816e-01 -2.00745597e-01 8.83795381e-01 -4.22613591e-01 -1.97764859e-01 8.84464443e-01 -4.22613114e-01 -1.94562048e-01 8.85169387e-01 -4.22612727e-01 -1.91370055e-01 8.85869384e-01 -4.22613174e-01 -1.88274518e-01 8.86531591e-01 -4.22613084e-01 -1.85190231e-01 8.87183309e-01 -4.22613204e-01 -1.82196155e-01 8.87805104e-01 -4.22613591e-01 -1.79072991e-01 8.88431966e-01 -4.22612727e-01 -1.75872490e-01 8.89075220e-01 -4.22613114e-01 -1.72765657e-01 8.89684618e-01 -4.22613174e-01 -1.69660226e-01 8.90281916e-01 -4.22613114e-01 -1.66643277e-01 8.90854001e-01 -4.22613591e-01 -1.63545549e-01 8.91419888e-01 -4.22612816e-01 -1.60425499e-01 8.91999364e-01 -4.22613382e-01 -1.57308608e-01 8.92548442e-01 -4.22612786e-01 -1.54102176e-01 8.93105567e-01 -4.22613174e-01 -1.51066348e-01 8.93628955e-01 -4.22613591e-01 -1.47953942e-01 8.94142449e-01 -4.22612816e-01 -1.44823462e-01 8.94659996e-01 -4.22613591e-01 -1.41718045e-01 8.95151675e-01 -4.22612846e-01 -1.38484746e-01 8.95660579e-01 -4.22613114e-01 -1.35448769e-01 8.96127641e-01 -4.22613591e-01 -1.32324532e-01 8.96588326e-01 -4.22612786e-01 -1.29183173e-01 8.97051573e-01 -4.22613412e-01 -1.26049191e-01 8.97493541e-01 -4.22612816e-01 -1.22828498e-01 8.97943735e-01 -4.22613174e-01 -1.19769752e-01 8.98355961e-01 -4.22613442e-01 -1.16638966e-01 8.98763299e-01 -4.22612816e-01 -1.13406844e-01 8.99181247e-01 -4.22613174e-01 -1.10278748e-01 8.99568260e-01 -4.22613114e-01 -1.07224472e-01 8.99941146e-01 -4.22613591e-01 -1.04169175e-01 9.00295675e-01 -4.22613114e-01 -1.00938365e-01 9.00662124e-01 -4.22612846e-01 -9.77093130e-02 9.01020527e-01 -4.22613204e-01 -9.45500731e-02 9.01356399e-01 -4.22612995e-01 -9.13983434e-02 9.01680171e-01 -4.22613084e-01 -8.83359388e-02 9.01991963e-01 -4.22613591e-01 -8.52080286e-02 9.02287006e-01 -4.22612816e-01 -8.20537955e-02 9.02585983e-01 -4.22613591e-01 -7.89082199e-02 9.02858913e-01 -4.22612756e-01 -7.56485015e-02 9.03140664e-01 -4.22613144e-01 -7.25948662e-02 9.03394878e-01 -4.22613591e-01 -6.94585219e-02 9.03635502e-01 -4.22612876e-01 -6.62908629e-02 9.03880179e-01 -4.22613591e-01 -6.31205887e-02 9.04098809e-01 -4.22612727e-01 -5.98691404e-02 9.04323637e-01 -4.22613084e-01 -5.67119457e-02 9.04525936e-01 -4.22613204e-01 -5.35510704e-02 9.04718399e-01 -4.22613114e-01 -5.04675359e-02 9.04902875e-01 -4.22613591e-01 -4.73200716e-02 9.05061126e-01 -4.22612756e-01 -4.41484042e-02 9.05231357e-01 -4.22613442e-01 -4.10911776e-02 9.05371964e-01 -4.22613144e-01 -3.78418937e-02 9.05509233e-01 -4.22612846e-01 -3.45906690e-02 9.05641437e-01 -4.22613114e-01 -3.14256586e-02 9.05756891e-01 -4.22613114e-01 -2.82519720e-02 9.05861914e-01 -4.22613084e-01 -2.51771510e-02 9.05957639e-01 -4.22613591e-01 -2.21110582e-02 9.06035781e-01 -4.22613084e-01 -1.88530926e-02 9.06100094e-01 -4.22612876e-01 -1.55870561e-02 9.06174719e-01 -4.22613174e-01 -1.24443425e-02 9.06213045e-01 -4.22613144e-01 -9.37697757e-03 9.06258404e-01 -4.22613591e-01 -6.21881941e-03 9.06286120e-01 -4.22612816e-01 -3.01904604e-03 9.06305432e-01 -4.22613412e-01 1.20470322e-04 9.06301200e-01 -4.22612846e-01 3.36656906e-03 9.06303108e-01 -4.22613174e-01 6.45639608e-03 9.06288385e-01 -4.22613412e-01 9.61752702e-03 9.06250060e-01 -4.22612906e-01 1.27820512e-02 9.06211734e-01 -4.22613412e-01 1.59303434e-02 9.06166852e-01 -4.22612876e-01 1.91165879e-02 9.06103313e-01 -4.22613591e-01 2.21970621e-02 9.06032503e-01 -4.22613144e-01 2.54300516e-02 9.05945420e-01 -4.22612846e-01 2.86764428e-02 9.05850649e-01 -4.22613144e-01 3.18406112e-02 9.05745804e-01 -4.22613174e-01 3.49813513e-02 9.05629933e-01 -4.22613204e-01 3.80700529e-02 9.05507445e-01 -4.22613382e-01 4.12288159e-02 9.05361354e-01 -4.22612846e-01 4.44771498e-02 9.05212343e-01 -4.22613114e-01 4.76313010e-02 9.05048013e-01 -4.22613174e-01 5.07741645e-02 9.04881358e-01 -4.22613144e-01 5.38619161e-02 9.04704750e-01 -4.22613561e-01 5.70094250e-02 9.04502571e-01 -4.22612816e-01 6.02581948e-02 9.04296339e-01 -4.22613144e-01 6.34275749e-02 9.04078782e-01 -4.22613084e-01 6.65949658e-02 9.03853595e-01 -4.22613114e-01 6.96609393e-02 9.03625131e-01 -4.22613591e-01 7.28041083e-02 9.03370202e-01 -4.22612756e-01 7.59792924e-02 9.03117061e-01 -4.22613591e-01 7.91010484e-02 9.02841926e-01 -4.22612816e-01 8.23681355e-02 9.02551532e-01 -4.22613025e-01 8.54318514e-02 9.02271330e-01 -4.22613591e-01 8.85507539e-02 9.01962996e-01 -4.22612786e-01 9.17321369e-02 9.01652336e-01 -4.22613591e-01 9.48542356e-02 9.01322842e-01 -4.22612846e-01 9.80275720e-02 9.00990546e-01 -4.22613621e-01 1.01150990e-01 9.00638700e-01 -4.22612816e-01 1.04389139e-01 9.00270343e-01 -4.22613144e-01 1.07526854e-01 8.99901211e-01 -4.22613144e-01 1.10655688e-01 8.99522424e-01 -4.22613144e-01 1.13734528e-01 8.99143755e-01 -4.22613382e-01 1.16785251e-01 8.98746729e-01 -4.22613174e-01 1.19985059e-01 8.98323834e-01 -4.22612906e-01 1.23200268e-01 8.97891223e-01 -4.22613114e-01 1.26357600e-01 8.97451937e-01 -4.22613144e-01 1.29481599e-01 8.97006154e-01 -4.22613174e-01 1.32549003e-01 8.96560848e-01 -4.22613591e-01 1.35660827e-01 8.96089196e-01 -4.22612816e-01 1.38798773e-01 8.95614862e-01 -4.22613472e-01 1.41916990e-01 8.95118237e-01 -4.22612756e-01 1.45128101e-01 8.94607782e-01 -4.22613114e-01 1.48173675e-01 8.94112706e-01 -4.22613591e-01 1.51277304e-01 8.93587053e-01 -4.22612846e-01 1.54397488e-01 8.93057346e-01 -4.22613412e-01 1.57444209e-01 8.92526686e-01 -4.22613174e-01 1.60624400e-01 8.91956031e-01 -4.22612876e-01 1.63827568e-01 8.91372800e-01 -4.22613204e-01 1.66944966e-01 8.90794337e-01 -4.22613114e-01 1.69950366e-01 8.90227973e-01 -4.22613353e-01 1.73072070e-01 8.89621854e-01 -4.22612935e-01 1.76176503e-01 8.89018714e-01 -4.22613442e-01 1.79196969e-01 8.88410211e-01 -4.22613114e-01 1.82372987e-01 8.87762725e-01 -4.22612876e-01 1.85556427e-01 8.87103558e-01 -4.22613114e-01 1.88646823e-01 8.86453629e-01 -4.22613174e-01 1.91744134e-01 8.85787427e-01 -4.22613084e-01 1.94758549e-01 8.85130882e-01 -4.22613531e-01 1.97827995e-01 8.84447813e-01 -4.22612816e-01 2.01003388e-01 8.83732378e-01 -4.22613174e-01 2.04091325e-01 8.83025229e-01 -4.22613114e-01 2.07178265e-01 8.82307768e-01 -4.22613114e-01 2.10176885e-01 8.81601274e-01 -4.22613591e-01 2.13159814e-01 8.80883217e-01 -4.22613084e-01 2.16244444e-01 8.80128026e-01 -4.22613174e-01 2.19376862e-01 8.79348040e-01 -4.22612876e-01 2.22525448e-01 8.78559709e-01 -4.22613144e-01 2.25534648e-01 8.77795875e-01 -4.22613412e-01 2.28585660e-01 8.77000451e-01 -4.22612816e-01 2.31652021e-01 8.76203120e-01 -4.22613591e-01 2.34683499e-01 8.75389278e-01 -4.22612846e-01 2.37835661e-01 8.74540985e-01 -4.22613084e-01 2.40821928e-01 8.73725474e-01 -4.22613591e-01 2.43860453e-01 8.72875512e-01 -4.22612756e-01 2.46928513e-01 8.72020423e-01 -4.22613591e-01 2.49942973e-01 8.71153057e-01 -4.22612786e-01 2.53073245e-01 8.70254755e-01 -4.22613233e-01 2.56025612e-01 8.69391859e-01 -4.22613382e-01 2.59055674e-01 8.68488431e-01 -4.22612816e-01 2.62184978e-01 8.67550910e-01 -4.22613174e-01 2.65185624e-01 8.66641283e-01 -4.22613263e-01 2.68116504e-01 8.65740716e-01 -4.22613591e-01 2.71059871e-01 8.64820361e-01 -4.22613144e-01 2.74088860e-01 8.63863945e-01 -4.22613025e-01 2.77197778e-01 8.62866700e-01 -4.22612786e-01 2.80309707e-01 8.61864865e-01 -4.22613025e-01 2.83299446e-01 8.60887289e-01 -4.22613114e-01 2.86236167e-01 8.59920800e-01 -4.22613680e-01 2.89139897e-01 8.58944893e-01 -4.22613144e-01 2.92134374e-01 8.57929766e-01 -4.22613204e-01 2.95183808e-01 8.56882334e-01 -4.22612846e-01 2.98265278e-01 8.55816364e-01 -4.22613055e-01 3.01190138e-01 8.54797006e-01 -4.22613591e-01 3.04159582e-01 8.53738129e-01 -4.22612816e-01 3.07156205e-01 8.52668643e-01 -4.22613412e-01 3.10098380e-01 8.51599038e-01 -4.22612846e-01 3.13171446e-01 8.50471258e-01 -4.22613084e-01 3.16126525e-01 8.49375069e-01 -4.22613233e-01 3.19088966e-01 8.48266304e-01 -4.22613025e-01 3.21991622e-01 8.47176433e-01 -4.22613442e-01 3.24932396e-01 8.46052706e-01 -4.22612846e-01 3.27891797e-01 8.44910324e-01 -4.22613591e-01 3.30746591e-01 8.43796790e-01 -4.22613144e-01 3.33771110e-01 8.42601180e-01 -4.22612816e-01 3.36794376e-01 8.41400266e-01 -4.22613144e-01 3.39708984e-01 8.40226531e-01 -4.22613144e-01 3.42629522e-01 8.39041650e-01 -4.22613174e-01 3.45506281e-01 8.37862372e-01 -4.22613442e-01 3.48343492e-01 8.36683929e-01 -4.22613055e-01 3.51341039e-01 8.35426629e-01 -4.22612816e-01 3.54325235e-01 8.34168792e-01 -4.22613204e-01 3.57220948e-01 8.32931995e-01 -4.22613114e-01 3.60077530e-01 8.31705034e-01 -4.22613412e-01 3.62915009e-01 8.30469906e-01 -4.22613114e-01 3.65796179e-01 8.29204381e-01 -4.22613174e-01 3.68742257e-01 8.27895045e-01 -4.22612816e-01 3.71697128e-01 8.26576173e-01 -4.22613114e-01 3.74521554e-01 8.25301588e-01 -4.22613353e-01 3.77331316e-01 8.24016392e-01 -4.22613084e-01 3.80188018e-01 8.22703481e-01 -4.22613144e-01 3.83062661e-01 8.21369529e-01 -4.22613114e-01 3.85922670e-01 8.20029974e-01 -4.22613114e-01 3.88812631e-01 8.18662047e-01 -4.22612995e-01 3.91734779e-01 8.17266881e-01 -4.22612995e-01 3.94599110e-01 8.15892816e-01 -4.22613174e-01 3.97387117e-01 8.14540744e-01 -4.22613353e-01 4.00182098e-01 8.13166440e-01 -4.22613114e-01 4.03001845e-01 8.11774731e-01 -4.22613204e-01 4.05887812e-01 8.10330689e-01 -4.22612876e-01 4.08776611e-01 8.08881521e-01 -4.22613174e-01 4.11599487e-01 8.07446778e-01 -4.22613084e-01 4.14360642e-01 8.06037605e-01 -4.22613591e-01 4.17096972e-01 8.04620326e-01 -4.22613114e-01 4.19896185e-01 8.03165853e-01 -4.22613114e-01 4.22759861e-01 8.01657438e-01 -4.22612846e-01 4.25614327e-01 8.00149262e-01 -4.22613174e-01 4.28403884e-01 7.98659861e-01 -4.22613114e-01 4.31133956e-01 7.97190368e-01 -4.22613382e-01 4.33858097e-01 7.95712233e-01 -4.22613204e-01 4.36629653e-01 7.94192672e-01 -4.22613144e-01 4.39440399e-01 7.92634785e-01 -4.22612846e-01 4.42286164e-01 7.91054904e-01 -4.22613084e-01 4.44991201e-01 7.89539814e-01 -4.22613353e-01 4.47706878e-01 7.87996650e-01 -4.22612786e-01 4.50488299e-01 7.86419928e-01 -4.22613591e-01 4.53154624e-01 7.84880936e-01 -4.22613204e-01 4.55966562e-01 7.83248782e-01 -4.22612906e-01 4.58698183e-01 7.81656563e-01 -4.22613353e-01 4.61416602e-01 7.80048370e-01 -4.22612816e-01 4.64139760e-01 7.78437734e-01 -4.22613591e-01 4.66842592e-01 7.76813626e-01 -4.22612876e-01 4.69575882e-01 7.75168478e-01 -4.22613353e-01 4.72193837e-01 7.73577690e-01 -4.22613233e-01 4.74947959e-01 7.71883726e-01 -4.22612786e-01 4.77658868e-01 7.70217121e-01 -4.22613412e-01 4.80336398e-01 7.68542886e-01 -4.22612846e-01 4.83042032e-01 7.66852260e-01 -4.22613472e-01 4.85620171e-01 7.65219927e-01 -4.22613263e-01 4.88308012e-01 7.63504803e-01 -4.22613025e-01 4.90966916e-01 7.61799693e-01 -4.22613293e-01 4.93666500e-01 7.60048449e-01 -4.22612846e-01 4.96396422e-01 7.58271337e-01 -4.22612995e-01 4.98980045e-01 7.56579816e-01 -4.22613531e-01 5.01533449e-01 7.54882097e-01 -4.22613144e-01 5.04161179e-01 7.53131211e-01 -4.22613114e-01 5.06851614e-01 7.51323402e-01 -4.22612935e-01 5.09525418e-01 7.49512434e-01 -4.22613144e-01 5.12099862e-01 7.47759402e-01 -4.22613293e-01 5.14654338e-01 7.46000648e-01 -4.22613174e-01 5.17239034e-01 7.44211555e-01 -4.22613144e-01 5.19866705e-01 7.42373765e-01 -4.22612935e-01 5.22480130e-01 7.40545094e-01 -4.22613382e-01 5.24998546e-01 7.38757968e-01 -4.22613233e-01 5.27636826e-01 7.36872256e-01 -4.22612816e-01 5.30214965e-01 7.35023260e-01 -4.22613412e-01 5.32754958e-01 7.33180821e-01 -4.22612906e-01 5.35319388e-01 7.31315970e-01 -4.22613591e-01 5.37788808e-01 7.29499996e-01 -4.22613204e-01 5.40415883e-01 7.27552354e-01 -4.22612906e-01 5.43017924e-01 7.25614130e-01 -4.22613144e-01 5.45548856e-01 7.23714888e-01 -4.22613114e-01 5.48057377e-01 7.21819758e-01 -4.22613323e-01 5.50271869e-01 7.20137894e-01 -4.22619194e-01 5.52135944e-01 7.18706310e-01 -4.22618359e-01 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. 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. 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. 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. 0. 0. 6.46239579e-01 6.35427535e-01 -4.22618300e-01 6.48090303e-01 6.33545876e-01 -4.22618538e-01 6.49892688e-01 6.31700695e-01 -4.22613978e-01 6.52079642e-01 6.29440427e-01 -4.22614932e-01 6.54227376e-01 6.27199709e-01 -4.22614664e-01 6.56333447e-01 6.24993622e-01 -4.22613293e-01 6.58497512e-01 6.22709095e-01 -4.22613174e-01 6.60714149e-01 6.20352089e-01 -4.22612876e-01 6.62944317e-01 6.17971778e-01 -4.22613114e-01 6.65062547e-01 6.15697801e-01 -4.22613442e-01 6.67145789e-01 6.13438725e-01 -4.22613174e-01 6.69277668e-01 6.11108005e-01 -4.22613174e-01 6.71410084e-01 6.08767092e-01 -4.22613174e-01 6.73577905e-01 6.06362820e-01 -4.22612756e-01 6.75751567e-01 6.03939772e-01 -4.22613114e-01 6.77799225e-01 6.01650417e-01 -4.22613591e-01 6.79832399e-01 5.99344671e-01 -4.22613084e-01 6.81928515e-01 5.96957743e-01 -4.22613114e-01 6.84009194e-01 5.94573021e-01 -4.22613084e-01 6.86128974e-01 5.92122912e-01 -4.22612906e-01 6.88192904e-01 5.89730620e-01 -4.22613412e-01 6.90190375e-01 5.87384224e-01 -4.22613055e-01 6.92244411e-01 5.84965408e-01 -4.22613144e-01 6.94324970e-01 5.82489312e-01 -4.22612846e-01 6.96360350e-01 5.80064893e-01 -4.22613412e-01 6.98320925e-01 5.77696383e-01 -4.22613144e-01 7.00394392e-01 5.75180113e-01 -4.22612846e-01 7.02448130e-01 5.72670281e-01 -4.22613084e-01 7.04439580e-01 5.70221126e-01 -4.22613144e-01 7.06372976e-01 5.67827642e-01 -4.22613472e-01 7.08301783e-01 5.65416992e-01 -4.22613114e-01 7.10256159e-01 5.62957466e-01 -4.22613204e-01 7.12272346e-01 5.60401320e-01 -4.22612756e-01 7.14289486e-01 5.57830453e-01 -4.22613055e-01 7.16222703e-01 5.55348158e-01 -4.22613144e-01 7.18108892e-01 5.52912116e-01 -4.22613591e-01 7.19994307e-01 5.50448418e-01 -4.22613055e-01 7.21920967e-01 5.47922015e-01 -4.22613144e-01 7.23858714e-01 5.45355260e-01 -4.22612876e-01 7.25812554e-01 5.42751491e-01 -4.22613084e-01 7.27661431e-01 5.40276706e-01 -4.22613412e-01 7.29486942e-01 5.37805736e-01 -4.22613174e-01 7.31357753e-01 5.35255373e-01 -4.22613084e-01 7.33272910e-01 5.32627285e-01 -4.22612786e-01 7.35130012e-01 5.30068576e-01 -4.22613412e-01 7.36917436e-01 5.27578056e-01 -4.22613084e-01 7.38799214e-01 5.24933934e-01 -4.22612816e-01 7.40657032e-01 5.22320926e-01 -4.22613293e-01 7.42472708e-01 5.19724309e-01 -4.22612816e-01 7.44277716e-01 5.17150342e-01 -4.22613680e-01 7.46014178e-01 5.14636755e-01 -4.22613114e-01 7.47850657e-01 5.11959136e-01 -4.22612786e-01 7.49687374e-01 5.09268999e-01 -4.22613144e-01 7.51463473e-01 5.06643414e-01 -4.22613055e-01 7.53186345e-01 5.04083931e-01 -4.22613591e-01 7.54880786e-01 5.01538515e-01 -4.22613174e-01 7.56631613e-01 4.98891473e-01 -4.22613055e-01 7.58416176e-01 4.96168911e-01 -4.22612786e-01 7.60197937e-01 4.93440419e-01 -4.22613144e-01 7.61868000e-01 4.90865886e-01 -4.22613591e-01 7.63513803e-01 4.88296419e-01 -4.22613174e-01 7.65209973e-01 4.85631973e-01 -4.22613144e-01 7.66908824e-01 4.82946813e-01 -4.22613084e-01 7.68640041e-01 4.80177522e-01 -4.22612697e-01 7.70380497e-01 4.77391750e-01 -4.22613233e-01 7.71991253e-01 4.74782914e-01 -4.22613591e-01 7.73595035e-01 4.72163618e-01 -4.22613055e-01 7.75230229e-01 4.69471425e-01 -4.22613144e-01 7.76859760e-01 4.66771513e-01 -4.22613144e-01 7.78484881e-01 4.64051515e-01 -4.22613025e-01 7.80123174e-01 4.61294532e-01 -4.22612995e-01 7.81728625e-01 4.58575428e-01 -4.22613353e-01 7.83300042e-01 4.55879480e-01 -4.22613055e-01 7.84927130e-01 4.53066796e-01 -4.22612816e-01 7.86522508e-01 4.50306684e-01 -4.22613591e-01 7.88032293e-01 4.47646916e-01 -4.22612935e-01 7.89654374e-01 4.44779605e-01 -4.22612756e-01 7.91252375e-01 4.41930145e-01 -4.22612995e-01 7.92786181e-01 4.39177215e-01 -4.22613293e-01 7.94268787e-01 4.36495900e-01 -4.22613412e-01 7.95751274e-01 4.33783799e-01 -4.22613144e-01 7.97263384e-01 4.30992723e-01 -4.22613055e-01 7.98765004e-01 4.28209603e-01 -4.22613204e-01 8.00284088e-01 4.25350785e-01 -4.22612786e-01 8.01812112e-01 4.22472060e-01 -4.22613114e-01 8.03248525e-01 4.19742554e-01 -4.22613531e-01 8.04658294e-01 4.17024970e-01 -4.22613084e-01 8.06114495e-01 4.14204627e-01 -4.22613055e-01 8.07593405e-01 4.11305755e-01 -4.22612816e-01 8.09062958e-01 4.08414900e-01 -4.22613084e-01 8.10453832e-01 4.05654639e-01 -4.22613591e-01 8.11816573e-01 4.02913421e-01 -4.22613114e-01 8.13206971e-01 4.00099337e-01 -4.22613055e-01 8.14637721e-01 3.97176772e-01 -4.22612876e-01 8.16034436e-01 3.94312412e-01 -4.22613442e-01 8.17360759e-01 3.91540498e-01 -4.22613084e-01 8.18750381e-01 3.88620794e-01 -4.22612876e-01 8.20109069e-01 3.85759443e-01 -4.22613382e-01 8.21442008e-01 3.82902563e-01 -4.22612816e-01 8.22790146e-01 3.80010426e-01 -4.22613442e-01 8.24066281e-01 3.77226263e-01 -4.22613204e-01 8.25407743e-01 3.74274969e-01 -4.22612816e-01 8.26750636e-01 3.71306509e-01 -4.22613025e-01 8.28038931e-01 3.68428826e-01 -4.22613174e-01 8.29296589e-01 3.65589231e-01 -4.22613353e-01 8.30536008e-01 3.62764448e-01 -4.22613204e-01 8.31788957e-01 3.59878570e-01 -4.22613144e-01 8.33039939e-01 3.56967777e-01 -4.22613114e-01 8.34309101e-01 3.53986502e-01 -4.22612786e-01 8.35552931e-01 3.51058632e-01 -4.22613591e-01 8.36729467e-01 3.48237276e-01 -4.22613114e-01 8.37938011e-01 3.45316797e-01 -4.22613084e-01 8.39144349e-01 3.42377752e-01 -4.22613144e-01 8.40357244e-01 3.39381725e-01 -4.22612816e-01 8.41576636e-01 3.36355954e-01 -4.22613114e-01 8.42721522e-01 3.33489835e-01 -4.22613591e-01 8.43840539e-01 3.30636442e-01 -4.22613025e-01 8.44987869e-01 3.27677965e-01 -4.22613174e-01 8.46157014e-01 3.24658334e-01 -4.22612846e-01 8.47295046e-01 3.21676791e-01 -4.22613353e-01 8.48376989e-01 3.18797320e-01 -4.22613204e-01 8.49504650e-01 3.15767556e-01 -4.22612786e-01 8.50637913e-01 3.12723488e-01 -4.22613174e-01 8.51725161e-01 3.09765011e-01 -4.22613144e-01 8.52772236e-01 3.06865484e-01 -4.22613412e-01 8.53808701e-01 3.03969324e-01 -4.22613084e-01 8.54887068e-01 3.00913244e-01 -4.22612756e-01 8.55971217e-01 2.97820896e-01 -4.22613055e-01 8.57011437e-01 2.94822127e-01 -4.22613144e-01 8.58006060e-01 2.91917711e-01 -4.22613591e-01 8.58983099e-01 2.89026111e-01 -4.22613174e-01 8.59985173e-01 2.86025852e-01 -4.22613114e-01 8.60982358e-01 2.83010215e-01 -4.22613114e-01 8.61984074e-01 2.79940486e-01 -4.22612876e-01 8.62991452e-01 2.76821107e-01 -4.22613055e-01 8.63931656e-01 2.73886502e-01 -4.22613412e-01 8.64854932e-01 2.70948380e-01 -4.22613055e-01 8.65795016e-01 2.67928421e-01 -4.22613204e-01 8.66737545e-01 2.64850974e-01 -4.22612756e-01 8.67684841e-01 2.61737943e-01 -4.22613114e-01 8.68576825e-01 2.58776337e-01 -4.22613382e-01 8.69449198e-01 2.55823255e-01 -4.22613084e-01 8.70337307e-01 2.52785534e-01 -4.22613144e-01 8.71218681e-01 2.49718204e-01 -4.22612935e-01 8.72099578e-01 2.46644989e-01 -4.22613323e-01 8.72935295e-01 2.43663803e-01 -4.22613144e-01 8.73779774e-01 2.40609944e-01 -4.22613055e-01 8.74613702e-01 2.37575740e-01 -4.22613204e-01 8.75447690e-01 2.34459013e-01 -4.22612846e-01 8.76278341e-01 2.31358901e-01 -4.22613382e-01 8.77055168e-01 2.28392497e-01 -4.22613204e-01 8.77843499e-01 2.25335449e-01 -4.22613055e-01 8.78640831e-01 2.22187325e-01 -4.22612816e-01 8.79428148e-01 2.19066888e-01 -4.22613144e-01 8.80187333e-01 2.16009796e-01 -4.22613174e-01 8.80921483e-01 2.13004261e-01 -4.22613353e-01 8.81639123e-01 2.10000753e-01 -4.22613084e-01 8.82365048e-01 2.06930190e-01 -4.22613114e-01 8.83099437e-01 2.03751922e-01 -4.22612786e-01 8.83809507e-01 2.00678319e-01 -4.22613591e-01 8.84490371e-01 1.97648987e-01 -4.22613084e-01 8.85174572e-01 1.94553673e-01 -4.22613174e-01 8.85852575e-01 1.91438287e-01 -4.22613025e-01 8.86514843e-01 1.88359439e-01 -4.22613263e-01 8.87172282e-01 1.85226381e-01 -4.22612846e-01 8.87820065e-01 1.82120651e-01 -4.22613502e-01 8.88440669e-01 1.79040343e-01 -4.22612876e-01 8.89077902e-01 1.75857276e-01 -4.22613114e-01 8.89689088e-01 1.72736898e-01 -4.22613025e-01 8.90274286e-01 1.69706300e-01 -4.22613412e-01 8.90843511e-01 1.66689500e-01 -4.22613174e-01 8.91426980e-01 1.63509831e-01 -4.22612816e-01 8.92015338e-01 1.60322413e-01 -4.22613204e-01 8.92567813e-01 1.57208964e-01 -4.22613025e-01 8.93100560e-01 1.54143184e-01 -4.22613382e-01 8.93618524e-01 1.51113123e-01 -4.22613144e-01 8.94137740e-01 1.47994682e-01 -4.22613084e-01 8.94649804e-01 1.44871771e-01 -4.22613144e-01 8.95158947e-01 1.41676709e-01 -4.22612876e-01 8.95662427e-01 1.38470158e-01 -4.22613144e-01 8.96131814e-01 1.35412276e-01 -4.22613412e-01 8.96581173e-01 1.32394671e-01 -4.22613114e-01 8.97038579e-01 1.29248023e-01 -4.22613084e-01 8.97494316e-01 1.26037911e-01 -4.22612846e-01 8.97942305e-01 1.22831732e-01 -4.22613144e-01 8.98355901e-01 1.19775243e-01 -4.22613382e-01 8.98757398e-01 1.16709314e-01 -4.22613114e-01 8.99158835e-01 1.13582738e-01 -4.22613144e-01 8.99546564e-01 1.10459201e-01 -4.22613144e-01 8.99928153e-01 1.07302882e-01 -4.22613084e-01 9.00299013e-01 1.04127936e-01 -4.22612965e-01 9.00666535e-01 1.00904264e-01 -4.22612906e-01 9.01015818e-01 9.77855548e-02 -4.22613591e-01 9.01344121e-01 9.46505442e-02 -4.22612816e-01 9.01674867e-01 9.14895907e-02 -4.22613382e-01 9.01978076e-01 8.84276107e-02 -4.22613114e-01 9.02288914e-01 8.52047950e-02 -4.22612846e-01 9.02588964e-01 8.19761977e-02 -4.22613144e-01 9.02869403e-01 7.88361207e-02 -4.22613174e-01 9.03133869e-01 7.57434368e-02 -4.22613263e-01 9.03387487e-01 7.26561546e-02 -4.22613204e-01 9.03631628e-01 6.95261583e-02 -4.22613144e-01 9.03873146e-01 6.62764907e-02 -4.22612846e-01 9.04105663e-01 6.30490929e-02 -4.22613114e-01 9.04318213e-01 5.99956699e-02 -4.22613591e-01 9.04512644e-01 5.69232516e-02 -4.22613055e-01 9.04707313e-01 5.37390411e-02 -4.22613114e-01 9.04891849e-01 5.05837724e-02 -4.22613084e-01 9.05061245e-01 4.73603718e-02 -4.22612816e-01 9.05230761e-01 4.40978073e-02 -4.22613144e-01 9.05377567e-01 4.10296954e-02 -4.22613591e-01 9.05507803e-01 3.79670486e-02 -4.22613114e-01 9.05634284e-01 3.48056741e-02 -4.22613084e-01 9.05750275e-01 3.15325931e-02 -4.22612786e-01 9.05862629e-01 2.83599477e-02 -4.22613502e-01 9.05951858e-01 2.53053866e-02 -4.22613144e-01 9.06034112e-01 2.21392158e-02 -4.22613025e-01 9.06101823e-01 1.89613868e-02 -4.22613144e-01 9.06170964e-01 1.58052389e-02 -4.22613144e-01 9.06209707e-01 1.26418481e-02 -4.22613114e-01 9.06255603e-01 9.47325956e-03 -4.22613144e-01 9.06286538e-01 6.22920087e-03 -4.22612756e-01 9.06303167e-01 2.96419137e-03 -4.22613174e-01 9.06303406e-01 -1.96676017e-04 -4.22613084e-01 9.06302512e-01 -3.37200984e-03 -4.22613114e-01 9.06290174e-01 -6.43543527e-03 -4.22613591e-01 9.06254530e-01 -9.49654356e-03 -4.22613025e-01 9.06208754e-01 -1.26669621e-02 -4.22613084e-01 9.06165779e-01 -1.59360226e-02 -4.22612786e-01 9.06096816e-01 -1.92050803e-02 -4.22613114e-01 9.06030118e-01 -2.23374628e-02 -4.22613204e-01 9.05952215e-01 -2.54038367e-02 -4.22613591e-01 9.05849099e-01 -2.85758153e-02 -4.22612756e-01 9.05750871e-01 -3.17575671e-02 -4.22613412e-01 9.05633032e-01 -3.48333493e-02 -4.22613055e-01 9.05508757e-01 -3.79810371e-02 -4.22613144e-01 9.05361533e-01 -4.12244760e-02 -4.22612786e-01 9.05212283e-01 -4.44772951e-02 -4.22613144e-01 9.05048728e-01 -4.76329327e-02 -4.22613084e-01 9.04885590e-01 -5.07231504e-02 -4.22613502e-01 9.04705346e-01 -5.37851416e-02 -4.22613144e-01 9.04510975e-01 -5.69290109e-02 -4.22613114e-01 9.04299438e-01 -6.01790026e-02 -4.22612816e-01 9.04078960e-01 -6.34279698e-02 -4.22613025e-01 9.03853297e-01 -6.66064024e-02 -4.22613084e-01 9.03624773e-01 -6.96753487e-02 -4.22613591e-01 9.03381348e-01 -7.27276430e-02 -4.22613174e-01 9.03120518e-01 -7.58771151e-02 -4.22613055e-01 9.02841330e-01 -7.91200101e-02 -4.22612816e-01 9.02562976e-01 -8.22818950e-02 -4.22613591e-01 9.02278125e-01 -8.53151530e-02 -4.22613055e-01 9.01975393e-01 -8.84817690e-02 -4.22613174e-01 9.01657164e-01 -9.16391015e-02 -4.22613055e-01 9.01332259e-01 -9.48002040e-02 -4.22613144e-01 9.00987267e-01 -9.79935899e-02 -4.22612846e-01 9.00645316e-01 -1.01146437e-01 -4.22613382e-01 9.00292993e-01 -1.04205057e-01 -4.22613144e-01 8.99914503e-01 -1.07404903e-01 -4.22612906e-01 8.99538696e-01 -1.10555105e-01 -4.22613472e-01 8.99139464e-01 -1.13706231e-01 -4.22612727e-01 8.98730159e-01 -1.16920941e-01 -4.22613293e-01 8.98331463e-01 -1.19954586e-01 -4.22613293e-01 8.97900045e-01 -1.23116612e-01 -4.22612846e-01 8.97457898e-01 -1.26324177e-01 -4.22613174e-01 8.97022724e-01 -1.29385963e-01 -4.22613382e-01 8.96560311e-01 -1.32506222e-01 -4.22612786e-01 8.96093190e-01 -1.35661677e-01 -4.22613353e-01 8.95612776e-01 -1.38777688e-01 -4.22612846e-01 8.95129144e-01 -1.41899019e-01 -4.22613442e-01 8.94624174e-01 -1.45014599e-01 -4.22612876e-01 8.94118190e-01 -1.48137331e-01 -4.22613591e-01 8.93590689e-01 -1.51254654e-01 -4.22612846e-01 8.93044829e-01 -1.54447466e-01 -4.22613114e-01 8.92502725e-01 -1.57578304e-01 -4.22613114e-01 8.91963840e-01 -1.60612792e-01 -4.22613353e-01 8.91404092e-01 -1.63644135e-01 -4.22613084e-01 8.90829206e-01 -1.66757897e-01 -4.22613084e-01 8.90221536e-01 -1.69951856e-01 -4.22612816e-01 8.89616549e-01 -1.73121557e-01 -4.22613204e-01 8.89006853e-01 -1.76211044e-01 -4.22613084e-01 8.88403416e-01 -1.79246441e-01 -4.22613382e-01 8.87784421e-01 -1.82278097e-01 -4.22613114e-01 8.87140036e-01 -1.85381323e-01 -4.22613114e-01 8.86468351e-01 -1.88559115e-01 -4.22612846e-01 8.85816872e-01 -1.91631466e-01 -4.22613591e-01 8.85134816e-01 -1.94720432e-01 -4.22612816e-01 8.84453475e-01 -1.97825402e-01 -4.22613412e-01 8.83756340e-01 -2.00891301e-01 -4.22612906e-01 8.83052647e-01 -2.03980818e-01 -4.22613353e-01 8.82328331e-01 -2.07076818e-01 -4.22612816e-01 8.81604850e-01 -2.10161194e-01 -4.22613591e-01 8.80890787e-01 -2.13122383e-01 -4.22613114e-01 8.80115449e-01 -2.16285005e-01 -4.22612876e-01 8.79358351e-01 -2.19360322e-01 -4.22613591e-01 8.78580213e-01 -2.22427472e-01 -4.22612756e-01 8.77788603e-01 -2.25556135e-01 -4.22613263e-01 8.77020955e-01 -2.28523418e-01 -4.22613263e-01 8.76207590e-01 -2.31611162e-01 -4.22612816e-01 8.75396788e-01 -2.34678805e-01 -4.22613502e-01 8.74598384e-01 -2.37623170e-01 -4.22613144e-01 8.73731792e-01 -2.40766972e-01 -4.22612756e-01 8.72891426e-01 -2.43834764e-01 -4.22613591e-01 8.72033596e-01 -2.46857181e-01 -4.22612816e-01 8.71140599e-01 -2.49999151e-01 -4.22613084e-01 8.70286763e-01 -2.52969027e-01 -4.22613591e-01 8.69428039e-01 -2.55892217e-01 -4.22613144e-01 8.68505538e-01 -2.59000361e-01 -4.22612816e-01 8.67569745e-01 -2.62117237e-01 -4.22613055e-01 8.66639793e-01 -2.65181303e-01 -4.22613025e-01 8.65735292e-01 -2.68134654e-01 -4.22613591e-01 8.64824235e-01 -2.71046937e-01 -4.22613174e-01 8.63875270e-01 -2.74056524e-01 -4.22613084e-01 8.62888575e-01 -2.77137190e-01 -4.22612876e-01 8.61888170e-01 -2.80240357e-01 -4.22613114e-01 8.60905826e-01 -2.83241570e-01 -4.22613084e-01 8.59933496e-01 -2.86189973e-01 -4.22613353e-01 8.58956099e-01 -2.89104462e-01 -4.22613174e-01 8.57943177e-01 -2.92095125e-01 -4.22613084e-01 8.56895804e-01 -2.95144945e-01 -4.22612876e-01 8.55860710e-01 -2.98148751e-01 -4.22613412e-01 8.54811192e-01 -3.01131159e-01 -4.22612876e-01 8.53764534e-01 -3.04104835e-01 -4.22613591e-01 8.52693617e-01 -3.07074308e-01 -4.22612786e-01 8.51613522e-01 -3.10078233e-01 -4.22613382e-01 8.50520790e-01 -3.13032478e-01 -4.22612876e-01 8.49420071e-01 -3.16007465e-01 -4.22613382e-01 8.48342478e-01 -3.18885863e-01 -4.22613084e-01 8.47223759e-01 -3.21858436e-01 -4.22613114e-01 8.46070230e-01 -3.24887633e-01 -4.22612816e-01 8.44921470e-01 -3.27859491e-01 -4.22613412e-01 8.43774021e-01 -3.30799788e-01 -4.22612786e-01 8.42617810e-01 -3.33750546e-01 -4.22613591e-01 8.41450095e-01 -3.36662233e-01 -4.22612816e-01 8.40268672e-01 -3.39616239e-01 -4.22613472e-01 8.39115858e-01 -3.42447490e-01 -4.22613174e-01 8.37879360e-01 -3.45450372e-01 -4.22612786e-01 8.36668849e-01 -3.48391742e-01 -4.22613591e-01 8.35443020e-01 -3.51301610e-01 -4.22612756e-01 8.34173679e-01 -3.54311109e-01 -4.22613144e-01 8.32967579e-01 -3.57144654e-01 -4.22613412e-01 8.31753075e-01 -3.59960139e-01 -4.22613114e-01 8.30462754e-01 -3.62926155e-01 -4.22612876e-01 8.29158545e-01 -3.65899324e-01 -4.22613114e-01 8.27869952e-01 -3.68803829e-01 -4.22613055e-01 8.26606870e-01 -3.71637523e-01 -4.22613382e-01 8.25337291e-01 -3.74437362e-01 -4.22613204e-01 8.24036717e-01 -3.77285808e-01 -4.22613144e-01 8.22678685e-01 -3.80237252e-01 -4.22612876e-01 8.21316600e-01 -3.83174449e-01 -4.22613114e-01 8.19968998e-01 -3.86051267e-01 -4.22613144e-01 8.18646252e-01 -3.88855994e-01 -4.22613353e-01 8.17313790e-01 -3.91638309e-01 -4.22613144e-01 8.15936744e-01 -3.94505382e-01 -4.22612995e-01 8.14516425e-01 -3.97427440e-01 -4.22612876e-01 8.13125730e-01 -4.00269300e-01 -4.22613353e-01 8.11726153e-01 -4.03090417e-01 -4.22612876e-01 8.10318768e-01 -4.05923635e-01 -4.22613382e-01 8.08941364e-01 -4.08659041e-01 -4.22613174e-01 8.07519734e-01 -4.11460638e-01 -4.22613144e-01 8.06029081e-01 -4.14366513e-01 -4.22612816e-01 8.04572225e-01 -4.17197436e-01 -4.22613591e-01 8.03158998e-01 -4.19906855e-01 -4.22613084e-01 8.01686943e-01 -4.22707945e-01 -4.22613114e-01 8.00148785e-01 -4.25607651e-01 -4.22612756e-01 7.98665464e-01 -4.28401828e-01 -4.22613591e-01 7.97179222e-01 -4.31145072e-01 -4.22612786e-01 7.95657933e-01 -4.33963299e-01 -4.22613591e-01 7.94186056e-01 -4.36639756e-01 -4.22613055e-01 7.92651713e-01 -4.39415365e-01 -4.22613084e-01 7.91072011e-01 -4.42250460e-01 -4.22612816e-01 7.89527893e-01 -4.45015132e-01 -4.22613591e-01 7.87974358e-01 -4.47748452e-01 -4.22612935e-01 7.86408186e-01 -4.50506300e-01 -4.22613412e-01 7.84825265e-01 -4.53244507e-01 -4.22612846e-01 7.83213615e-01 -4.56032783e-01 -4.22613233e-01 7.81648099e-01 -4.58710581e-01 -4.22613233e-01 7.80072689e-01 -4.61384326e-01 -4.22613204e-01 7.78460383e-01 -4.64094192e-01 -4.22613144e-01 7.76793420e-01 -4.66875255e-01 -4.22612816e-01 7.75108635e-01 -4.69669521e-01 -4.22613025e-01 7.73508787e-01 -4.72311407e-01 -4.22613591e-01 7.71897972e-01 -4.74928856e-01 -4.22613084e-01 7.70239294e-01 -4.77620482e-01 -4.22613114e-01 7.68526554e-01 -4.80361223e-01 -4.22612786e-01 7.66797483e-01 -4.83123124e-01 -4.22613144e-01 7.65118837e-01 -4.85777110e-01 -4.22613204e-01 7.63475358e-01 -4.88359153e-01 -4.22613353e-01 7.61753440e-01 -4.91032511e-01 -4.22612846e-01 7.59986162e-01 -4.93768394e-01 -4.22613174e-01 7.58252144e-01 -4.96424288e-01 -4.22613084e-01 7.56516337e-01 -4.99069303e-01 -4.22613144e-01 7.54816711e-01 -5.01637042e-01 -4.22613591e-01 7.53116846e-01 -5.04182220e-01 -4.22613114e-01 7.51344264e-01 -5.06821215e-01 -4.22612995e-01 7.49521971e-01 -5.09507596e-01 -4.22612906e-01 7.47704804e-01 -5.12175381e-01 -4.22613084e-01 7.45912373e-01 -5.14786065e-01 -4.22613174e-01 7.44149685e-01 -5.17330766e-01 -4.22613353e-01 7.42343783e-01 -5.19908249e-01 -4.22612846e-01 7.40528345e-01 -5.22504985e-01 -4.22613382e-01 7.38694310e-01 -5.25082827e-01 -4.22612876e-01 7.36855030e-01 -5.27672291e-01 -4.22613382e-01 7.35050499e-01 -5.30171692e-01 -4.22613084e-01 7.33182669e-01 -5.32756746e-01 -4.22613055e-01 7.31319666e-01 -5.35311282e-01 -4.22613233e-01 7.29414284e-01 -5.37897468e-01 -4.22612846e-01 7.27474153e-01 -5.40524244e-01 -4.22613114e-01 7.25647569e-01 -5.42978525e-01 -4.22613591e-01 7.23758101e-01 -5.45486450e-01 -4.22612816e-01 7.21837878e-01 -5.48033774e-01 -4.22613382e-01 7.19930589e-01 -5.50529420e-01 -4.22612935e-01 7.18012691e-01 -5.53034127e-01 -4.22613353e-01 7.16112554e-01 -5.55487573e-01 -4.22613084e-01 7.14122772e-01 -5.58041930e-01 -4.22612995e-01 7.12126791e-01 -5.60588777e-01 -4.22612995e-01 7.10197568e-01 -5.63036680e-01 -4.22613591e-01 7.08279073e-01 -5.65443814e-01 -4.22613084e-01 7.06309617e-01 -5.67902267e-01 -4.22613114e-01 7.04267800e-01 -5.70428133e-01 -4.22612786e-01 7.02267170e-01 -5.72895467e-01 -4.22613442e-01 7.00315773e-01 -5.75274587e-01 -4.22613025e-01 6.98300779e-01 -5.77723324e-01 -4.22613204e-01 6.96296096e-01 -5.80136180e-01 -4.22613114e-01 6.94268227e-01 -5.82562327e-01 -4.22613144e-01 6.92160666e-01 -5.85058630e-01 -4.22612816e-01 6.90112293e-01 -5.87483108e-01 -4.22613591e-01 6.88125432e-01 -5.89803576e-01 -4.22613114e-01 6.86065614e-01 -5.92199266e-01 -4.22613084e-01 6.83975577e-01 -5.94612062e-01 -4.22613055e-01 6.81846917e-01 -5.97046137e-01 -4.22612876e-01 6.79713547e-01 -5.99477172e-01 -4.22613055e-01 6.77657068e-01 -6.01807058e-01 -4.22613412e-01 6.75602794e-01 -6.04108870e-01 -4.22613144e-01 6.73443198e-01 -6.06511533e-01 -4.22612876e-01 6.71334803e-01 -6.08853698e-01 -4.22613382e-01 6.69199288e-01 -6.11189485e-01 -4.22612846e-01 6.67066813e-01 -6.13525748e-01 -4.22613412e-01 6.64979637e-01 -6.15782559e-01 -4.22613114e-01 6.62821412e-01 -6.18103445e-01 -4.22613114e-01 6.60605550e-01 -6.20467424e-01 -4.22612816e-01 6.58432305e-01 -6.22781575e-01 -4.22613412e-01 6.56260014e-01 -6.25065923e-01 -4.22612846e-01 6.54069185e-01 -6.27358615e-01 -4.22613591e-01 6.51889324e-01 -6.29627287e-01 -4.22612756e-01 6.49677336e-01 -6.31916463e-01 -4.22613591e-01 6.47520483e-01 -6.34118676e-01 -4.22613114e-01 6.45257473e-01 -6.36418760e-01 -4.22612846e-01 6.43028259e-01 -6.38683617e-01 -4.22613561e-01 6.40783012e-01 -6.40907943e-01 -4.22612816e-01 6.38486266e-01 -6.43217564e-01 -4.22613025e-01 6.36303425e-01 -6.45382822e-01 -4.22613621e-01 6.34121776e-01 -6.47517443e-01 -4.22613114e-01 6.31857097e-01 -6.49730086e-01 -4.22613114e-01 6.29525304e-01 -6.51987970e-01 -4.22612816e-01 6.27220094e-01 -6.54200494e-01 -4.22613412e-01 6.24946415e-01 -6.56375706e-01 -4.22612995e-01 6.22680724e-01 -6.58526599e-01 -4.22613412e-01 6.20419383e-01 -6.60655618e-01 -4.22613174e-01 6.18413210e-01 -6.62544847e-01 -4.22616333e-01 6.16348326e-01 -6.64460838e-01 -4.22618479e-01 6.14117444e-01 -6.66523457e-01 -4.22618270e-01 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.21261156e-01 -7.41404414e-01 -4.22618270e-01 5.19227386e-01 -7.42833197e-01 -4.22617018e-01 5.17061412e-01 -7.44338870e-01 -4.22613680e-01 5.14585376e-01 -7.46058285e-01 -4.22614366e-01 5.12087524e-01 -7.47772515e-01 -4.22615677e-01 5.09350359e-01 -7.49637544e-01 -4.22613680e-01 5.06779671e-01 -7.51373589e-01 -4.22613204e-01 5.04152715e-01 -7.53137112e-01 -4.22613144e-01 5.01473010e-01 -7.54920542e-01 -4.22612906e-01 4.98815835e-01 -7.56685138e-01 -4.22613353e-01 4.96211678e-01 -7.58391380e-01 -4.22613055e-01 4.93515849e-01 -7.60148406e-01 -4.22612906e-01 4.90854323e-01 -7.61874557e-01 -4.22613442e-01 4.88254994e-01 -7.63538420e-01 -4.22613055e-01 4.85578686e-01 -7.65243709e-01 -4.22613144e-01 4.82903570e-01 -7.66935945e-01 -4.22613144e-01 4.80228513e-01 -7.68611789e-01 -4.22613084e-01 4.77542877e-01 -7.70287693e-01 -4.22613174e-01 4.74854290e-01 -7.71943808e-01 -4.22613114e-01 4.72170264e-01 -7.73592353e-01 -4.22613144e-01 4.69468445e-01 -7.75231898e-01 -4.22613144e-01 4.66749012e-01 -7.76872337e-01 -4.22613084e-01 4.63992625e-01 -7.78517842e-01 -4.22612906e-01 4.61270988e-01 -7.80140340e-01 -4.22613293e-01 4.58600461e-01 -7.81711519e-01 -4.22613144e-01 4.55869436e-01 -7.83306897e-01 -4.22613114e-01 4.53067631e-01 -7.84927547e-01 -4.22612846e-01 4.50329453e-01 -7.86507905e-01 -4.22613442e-01 4.47656155e-01 -7.88028240e-01 -4.22613084e-01 4.44907486e-01 -7.89586484e-01 -4.22613114e-01 4.42162573e-01 -7.91124821e-01 -4.22613174e-01 4.39386338e-01 -7.92667627e-01 -4.22613144e-01 4.36621308e-01 -7.94196606e-01 -4.22613084e-01 4.33854699e-01 -7.95712233e-01 -4.22613114e-01 4.31067288e-01 -7.97224820e-01 -4.22613114e-01 4.28289741e-01 -7.98720062e-01 -4.22613114e-01 4.25489664e-01 -8.00214052e-01 -4.22613084e-01 4.22676325e-01 -8.01704764e-01 -4.22613084e-01 4.19828504e-01 -8.03195536e-01 -4.22612846e-01 4.17008847e-01 -8.04669857e-01 -4.22613412e-01 4.14265603e-01 -8.06083858e-01 -4.22613084e-01 4.11439717e-01 -8.07528615e-01 -4.22613114e-01 4.08619463e-01 -8.08960378e-01 -4.22613144e-01 4.05793428e-01 -8.10381055e-01 -4.22613114e-01 4.02974010e-01 -8.11786473e-01 -4.22613144e-01 4.00151134e-01 -8.13180864e-01 -4.22613055e-01 3.97294790e-01 -8.14582229e-01 -4.22613114e-01 3.94458562e-01 -8.15959811e-01 -4.22613144e-01 3.91587645e-01 -8.17338169e-01 -4.22613084e-01 3.88670534e-01 -8.18728685e-01 -4.22612906e-01 3.85802865e-01 -8.20089161e-01 -4.22613382e-01 3.82921666e-01 -8.21432948e-01 -4.22612786e-01 3.80036056e-01 -8.22778463e-01 -4.22613591e-01 3.77255887e-01 -8.24051261e-01 -4.22613144e-01 3.74384284e-01 -8.25362384e-01 -4.22613144e-01 3.71508509e-01 -8.26660991e-01 -4.22613144e-01 3.68515879e-01 -8.27995658e-01 -4.22612727e-01 3.65608335e-01 -8.29292178e-01 -4.22613680e-01 3.62818480e-01 -8.30511749e-01 -4.22613055e-01 3.59920710e-01 -8.31770658e-01 -4.22613114e-01 3.56999487e-01 -8.33025992e-01 -4.22613114e-01 3.54052722e-01 -8.34283888e-01 -4.22613025e-01 3.51157933e-01 -8.35510314e-01 -4.22613263e-01 3.48159522e-01 -8.36757481e-01 -4.22612727e-01 3.45222950e-01 -8.37980390e-01 -4.22613591e-01 3.42414051e-01 -8.39130402e-01 -4.22613144e-01 3.39430332e-01 -8.40338290e-01 -4.22612935e-01 3.36412370e-01 -8.41551423e-01 -4.22612965e-01 3.33429158e-01 -8.42741191e-01 -4.22613144e-01 3.30554724e-01 -8.43876064e-01 -4.22613591e-01 3.27696890e-01 -8.44980717e-01 -4.22613114e-01 3.24738324e-01 -8.46129775e-01 -4.22613084e-01 3.21787894e-01 -8.47251773e-01 -4.22613174e-01 3.18842262e-01 -8.48359346e-01 -4.22613084e-01 3.15857857e-01 -8.49473715e-01 -4.22613084e-01 3.12897354e-01 -8.50573540e-01 -4.22613204e-01 3.09938252e-01 -8.51660967e-01 -4.22613144e-01 3.06976080e-01 -8.52731228e-01 -4.22613174e-01 3.03983778e-01 -8.53804111e-01 -4.22613144e-01 3.00933987e-01 -8.54879618e-01 -4.22612846e-01 2.97932446e-01 -8.55935991e-01 -4.22613412e-01 2.94959664e-01 -8.56959522e-01 -4.22612846e-01 2.91949362e-01 -8.57994974e-01 -4.22613412e-01 2.89032191e-01 -8.58981192e-01 -4.22613144e-01 2.85953909e-01 -8.60005915e-01 -4.22612876e-01 2.82937497e-01 -8.61007571e-01 -4.22613412e-01 2.79930055e-01 -8.61986160e-01 -4.22612876e-01 2.76909530e-01 -8.62968862e-01 -4.22613412e-01 2.73975670e-01 -8.63899350e-01 -4.22613114e-01 2.70972967e-01 -8.64847183e-01 -4.22613114e-01 2.67950922e-01 -8.65788043e-01 -4.22613144e-01 2.64925867e-01 -8.66718650e-01 -4.22613084e-01 2.61822939e-01 -8.67656350e-01 -4.22612906e-01 2.58708209e-01 -8.68594229e-01 -4.22613144e-01 2.55765617e-01 -8.69469881e-01 -4.22613561e-01 2.52727956e-01 -8.70352030e-01 -4.22612846e-01 2.49604061e-01 -8.71254325e-01 -4.22613144e-01 2.46562406e-01 -8.72119188e-01 -4.22613084e-01 2.43602604e-01 -8.72955799e-01 -4.22613412e-01 2.40625456e-01 -8.73776257e-01 -4.22613144e-01 2.37577885e-01 -8.74611855e-01 -4.22613144e-01 2.34508723e-01 -8.75437140e-01 -4.22613084e-01 2.31472179e-01 -8.76245618e-01 -4.22613144e-01 2.28417605e-01 -8.77048969e-01 -4.22613084e-01 2.25286096e-01 -8.77854407e-01 -4.22612965e-01 2.22214788e-01 -8.78640234e-01 -4.22613353e-01 2.19164491e-01 -8.79401743e-01 -4.22612876e-01 2.16072187e-01 -8.80173504e-01 -4.22613382e-01 2.13065326e-01 -8.80904078e-01 -4.22613144e-01 2.09918469e-01 -8.81658196e-01 -4.22612876e-01 2.06846878e-01 -8.82386804e-01 -4.22613382e-01 2.03765079e-01 -8.83097112e-01 -4.22612846e-01 2.00608537e-01 -8.83822501e-01 -4.22613144e-01 1.97610885e-01 -8.84501517e-01 -4.22613502e-01 1.94603369e-01 -8.85162592e-01 -4.22613084e-01 1.91520587e-01 -8.85836065e-01 -4.22613144e-01 1.88426912e-01 -8.86498392e-01 -4.22613084e-01 1.85231239e-01 -8.87170613e-01 -4.22612786e-01 1.82121396e-01 -8.87820780e-01 -4.22613591e-01 1.79116324e-01 -8.88428211e-01 -4.22613144e-01 1.76023617e-01 -8.89044821e-01 -4.22613114e-01 1.72903448e-01 -8.89658868e-01 -4.22613144e-01 1.69712409e-01 -8.90267909e-01 -4.22612786e-01 1.66591942e-01 -8.90864253e-01 -4.22613591e-01 1.63484976e-01 -8.91430974e-01 -4.22612727e-01 1.60356805e-01 -8.92012894e-01 -4.22613591e-01 1.57340318e-01 -8.92545402e-01 -4.22613144e-01 1.54228225e-01 -8.93081963e-01 -4.22613084e-01 1.51096389e-01 -8.93620551e-01 -4.22613174e-01 1.47895932e-01 -8.94151032e-01 -4.22612816e-01 1.44772783e-01 -8.94669712e-01 -4.22613591e-01 1.41743153e-01 -8.95151913e-01 -4.22613174e-01 1.38614908e-01 -8.95640552e-01 -4.22613114e-01 1.35484055e-01 -8.96117568e-01 -4.22613084e-01 1.32274836e-01 -8.96596968e-01 -4.22612906e-01 1.29131585e-01 -8.97059202e-01 -4.22613382e-01 1.26005799e-01 -8.97499502e-01 -4.22612816e-01 1.22780792e-01 -8.97949815e-01 -4.22613114e-01 1.19722351e-01 -8.98363769e-01 -4.22613591e-01 1.16689876e-01 -8.98759484e-01 -4.22613144e-01 1.13548450e-01 -8.99164677e-01 -4.22613204e-01 1.10415742e-01 -8.99552405e-01 -4.22613114e-01 1.07191704e-01 -8.99938762e-01 -4.22612786e-01 1.04035623e-01 -9.00315046e-01 -4.22613591e-01 1.00999482e-01 -9.00657892e-01 -4.22613144e-01 9.78593007e-02 -9.01004076e-01 -4.22613144e-01 9.47192535e-02 -9.01338696e-01 -4.22613084e-01 9.14713964e-02 -9.01670575e-01 -4.22612816e-01 8.83083791e-02 -9.01993632e-01 -4.22613412e-01 8.51829350e-02 -9.02290106e-01 -4.22612846e-01 8.20227116e-02 -9.02586758e-01 -4.22613591e-01 7.88683072e-02 -9.02863026e-01 -4.22612846e-01 7.56290406e-02 -9.03141201e-01 -4.22613114e-01 7.25379363e-02 -9.03401434e-01 -4.22613591e-01 6.94078207e-02 -9.03639376e-01 -4.22612786e-01 6.62299693e-02 -9.03883159e-01 -4.22613472e-01 6.31698743e-02 -9.04097080e-01 -4.22613055e-01 6.00274056e-02 -9.04312015e-01 -4.22613084e-01 5.68707101e-02 -9.04516935e-01 -4.22613144e-01 5.36160655e-02 -9.04712558e-01 -4.22612816e-01 5.04619814e-02 -9.04901445e-01 -4.22613591e-01 4.73120399e-02 -9.05064166e-01 -4.22612876e-01 4.41475548e-02 -9.05230999e-01 -4.22613561e-01 4.10033204e-02 -9.05371785e-01 -4.22612786e-01 3.77407596e-02 -9.05517519e-01 -4.22613114e-01 3.46590653e-02 -9.05642927e-01 -4.22613591e-01 3.15978937e-02 -9.05751228e-01 -4.22613114e-01 2.83583868e-02 -9.05856848e-01 -4.22612906e-01 2.51841601e-02 -9.05957043e-01 -4.22613382e-01 2.20272709e-02 -9.06035066e-01 -4.22612846e-01 1.88505687e-02 -9.06106830e-01 -4.22613412e-01 1.57724880e-02 -9.06171203e-01 -4.22613114e-01 1.25564998e-02 -9.06206846e-01 -4.22612816e-01 9.36558843e-03 -9.06258762e-01 -4.22613412e-01 6.28340291e-03 -9.06288326e-01 -4.22613114e-01 3.12060281e-03 -9.06303287e-01 -4.22613174e-01 -2.47570879e-05 -9.06304002e-01 -4.22613144e-01 -3.16976570e-03 -9.06301975e-01 -4.22613055e-01 -6.34765951e-03 -9.06287849e-01 -4.22613114e-01 -9.59167723e-03 -9.06251431e-01 -4.22612786e-01 -1.27606103e-02 -9.06212628e-01 -4.22613591e-01 -1.59155335e-02 -9.06167090e-01 -4.22612846e-01 -1.91816054e-02 -9.06096935e-01 -4.22613055e-01 -2.22680904e-02 -9.06034052e-01 -4.22613591e-01 -2.53267474e-02 -9.05950785e-01 -4.22613144e-01 -2.84762904e-02 -9.05855954e-01 -4.22613114e-01 -3.17244045e-02 -9.05744553e-01 -4.22612756e-01 -3.49988565e-02 -9.05627728e-01 -4.22613114e-01 -3.80763113e-02 -9.05507684e-01 -4.22613591e-01 -4.11329940e-02 -9.05369103e-01 -4.22613114e-01 -4.43092249e-02 -9.05219972e-01 -4.22613084e-01 -4.74660397e-02 -9.05058622e-01 -4.22613174e-01 -5.06891683e-02 -9.04882371e-01 -4.22612846e-01 -5.38681187e-02 -9.04704154e-01 -4.22613531e-01 -5.70033193e-02 -9.04505491e-01 -4.22612846e-01 -6.01870902e-02 -9.04304624e-01 -4.22613412e-01 -6.32585511e-02 -9.04091120e-01 -4.22613144e-01 -6.64785206e-02 -9.03858781e-01 -4.22612876e-01 -6.96518719e-02 -9.03625727e-01 -4.22613442e-01 -7.27890283e-02 -9.03373301e-01 -4.22612846e-01 -7.59496540e-02 -9.03116524e-01 -4.22613323e-01 -7.90278092e-02 -9.02851045e-01 -4.22613084e-01 -8.21815804e-02 -9.02568519e-01 -4.22613114e-01 -8.53259787e-02 -9.02277589e-01 -4.22613084e-01 -8.85488763e-02 -9.01965737e-01 -4.22612846e-01 -9.16995108e-02 -9.01656270e-01 -4.22613591e-01 -9.48230028e-02 -9.01326835e-01 -4.22612846e-01 -9.80498493e-02 -9.00983930e-01 -4.22613204e-01 -1.01134025e-01 -9.00646687e-01 -4.22613442e-01 -1.04196414e-01 -9.00293946e-01 -4.22613144e-01 -1.07330300e-01 -8.99924397e-01 -4.22613114e-01 -1.10473074e-01 -8.99544179e-01 -4.22613084e-01 -1.13694482e-01 -8.99142504e-01 -4.22612816e-01 -1.16840512e-01 -8.98742795e-01 -4.22613591e-01 -1.19889438e-01 -8.98339033e-01 -4.22613114e-01 -1.23024024e-01 -8.97915006e-01 -4.22613174e-01 -1.26149833e-01 -8.97482157e-01 -4.22613114e-01 -1.29367977e-01 -8.97020221e-01 -4.22612816e-01 -1.32497698e-01 -8.96567941e-01 -4.22613591e-01 -1.35618687e-01 -8.96095693e-01 -4.22612906e-01 -1.38737351e-01 -8.95624578e-01 -4.22613591e-01 -1.41778171e-01 -8.95144343e-01 -4.22613174e-01 -1.44905686e-01 -8.94644558e-01 -4.22613144e-01 -1.48024067e-01 -8.94134164e-01 -4.22613114e-01 -1.51252449e-01 -8.93590093e-01 -4.22612786e-01 -1.54366165e-01 -8.93062472e-01 -4.22613591e-01 -1.57386392e-01 -8.92537177e-01 -4.22613174e-01 -1.60512567e-01 -8.91977608e-01 -4.22613084e-01 -1.63624614e-01 -8.91408503e-01 -4.22613144e-01 -1.66813970e-01 -8.90817881e-01 -4.22612816e-01 -1.69931650e-01 -8.90232921e-01 -4.22613412e-01 -1.72955364e-01 -8.89646232e-01 -4.22613144e-01 -1.76043078e-01 -8.89042437e-01 -4.22613174e-01 -1.79224879e-01 -8.88403118e-01 -4.22612816e-01 -1.82331726e-01 -8.87776613e-01 -4.22613591e-01 -1.85337305e-01 -8.87150466e-01 -4.22613144e-01 -1.88452408e-01 -8.86494160e-01 -4.22613114e-01 -1.91613227e-01 -8.85814130e-01 -4.22612876e-01 -1.94722414e-01 -8.85140240e-01 -4.22613591e-01 -1.97711349e-01 -8.84476066e-01 -4.22613114e-01 -2.00808451e-01 -8.83776367e-01 -4.22613084e-01 -2.03904063e-01 -8.83066058e-01 -4.22613114e-01 -2.07069382e-01 -8.82329941e-01 -4.22612756e-01 -2.10165396e-01 -8.81603360e-01 -4.22613591e-01 -2.13134766e-01 -8.80887806e-01 -4.22613174e-01 -2.16214895e-01 -8.80134881e-01 -4.22613144e-01 -2.19290584e-01 -8.79372716e-01 -4.22613144e-01 -2.22404957e-01 -8.78586769e-01 -4.22612906e-01 -2.25505516e-01 -8.77802789e-01 -4.22613353e-01 -2.28579059e-01 -8.77001107e-01 -4.22612816e-01 -2.31641784e-01 -8.76205027e-01 -4.22613591e-01 -2.34676301e-01 -8.75391424e-01 -4.22612876e-01 -2.37819195e-01 -8.74545157e-01 -4.22613055e-01 -2.40807056e-01 -8.73729110e-01 -4.22613591e-01 -2.43840724e-01 -8.72882068e-01 -4.22612816e-01 -2.46896639e-01 -8.72029245e-01 -4.22613591e-01 -2.49841556e-01 -8.71186018e-01 -4.22613174e-01 -2.52875954e-01 -8.70310247e-01 -4.22613084e-01 -2.55913675e-01 -8.69421601e-01 -4.22613144e-01 -2.58931160e-01 -8.68529677e-01 -4.22613204e-01 -2.61968583e-01 -8.67614329e-01 -4.22613055e-01 -2.65009403e-01 -8.66690397e-01 -4.22613114e-01 -2.68101275e-01 -8.65738928e-01 -4.22612816e-01 -2.71130741e-01 -8.64801049e-01 -4.22613591e-01 -2.74150789e-01 -8.63842726e-01 -4.22612876e-01 -2.77168959e-01 -8.62884998e-01 -4.22613531e-01 -2.80093253e-01 -8.61936212e-01 -4.22613174e-01 -2.83190161e-01 -8.60920608e-01 -4.22612816e-01 -2.86183000e-01 -8.59935582e-01 -4.22613353e-01 -2.89184242e-01 -8.58927906e-01 -4.22612876e-01 -2.92188168e-01 -8.57914209e-01 -4.22613412e-01 -2.95097739e-01 -8.56915772e-01 -4.22613174e-01 -2.98121542e-01 -8.55864465e-01 -4.22612935e-01 -3.01107854e-01 -8.54824245e-01 -4.22613293e-01 -3.04128051e-01 -8.53748381e-01 -4.22612816e-01 -3.07122439e-01 -8.52681518e-01 -4.22613531e-01 -3.10074180e-01 -8.51610005e-01 -4.22612876e-01 -3.13063204e-01 -8.50514352e-01 -4.22613531e-01 -3.15947950e-01 -8.49440217e-01 -4.22613114e-01 -3.18966240e-01 -8.48310709e-01 -4.22612876e-01 -3.21928620e-01 -8.47199500e-01 -4.22613412e-01 -3.24885368e-01 -8.46071005e-01 -4.22612846e-01 -3.27918351e-01 -8.44896197e-01 -4.22613084e-01 -3.30786616e-01 -8.43785226e-01 -4.22613591e-01 -3.33645821e-01 -8.42654586e-01 -4.22613084e-01 -3.36588144e-01 -8.41482282e-01 -4.22613114e-01 -3.39533627e-01 -8.40299487e-01 -4.22613144e-01 -3.42530161e-01 -8.39077353e-01 -4.22612756e-01 -3.45482618e-01 -8.37872326e-01 -4.22613591e-01 -3.48324209e-01 -8.36694300e-01 -4.22613144e-01 -3.51224154e-01 -8.35480154e-01 -4.22613144e-01 -3.54139000e-01 -8.34246933e-01 -4.22613084e-01 -3.57123792e-01 -8.32970321e-01 -4.22612846e-01 -3.60038698e-01 -8.31722081e-01 -4.22613561e-01 -3.62930536e-01 -8.30460548e-01 -4.22612816e-01 -3.65846336e-01 -8.29183757e-01 -4.22613382e-01 -3.68661463e-01 -8.27934206e-01 -4.22613114e-01 -3.71616095e-01 -8.26610327e-01 -4.22612846e-01 -3.74511808e-01 -8.25307608e-01 -4.22613591e-01 -3.77358019e-01 -8.24000716e-01 -4.22612846e-01 -3.80241483e-01 -8.22683036e-01 -4.22613591e-01 -3.83031219e-01 -8.21383655e-01 -4.22613084e-01 -3.85903209e-01 -8.20037901e-01 -4.22613114e-01 -3.88846695e-01 -8.18645000e-01 -4.22612816e-01 -3.91695738e-01 -8.17289650e-01 -4.22613442e-01 -3.94472748e-01 -8.15953612e-01 -4.22613055e-01 -3.97385508e-01 -8.14535022e-01 -4.22612786e-01 -4.00312096e-01 -8.13102901e-01 -4.22613174e-01 -4.03077185e-01 -8.11738312e-01 -4.22613353e-01 -4.05834496e-01 -8.10361326e-01 -4.22613144e-01 -4.08654600e-01 -8.08942378e-01 -4.22613055e-01 -4.11486208e-01 -8.07506084e-01 -4.22613174e-01 -4.14364547e-01 -8.06028843e-01 -4.22612846e-01 -4.17173952e-01 -8.04584742e-01 -4.22613591e-01 -4.19895530e-01 -8.03164959e-01 -4.22613084e-01 -4.22707498e-01 -8.01688135e-01 -4.22613084e-01 -4.25498128e-01 -8.00210059e-01 -4.22613114e-01 -4.28362936e-01 -7.98678517e-01 -4.22612816e-01 -4.31153506e-01 -7.97180414e-01 -4.22613412e-01 -4.33915824e-01 -7.95676589e-01 -4.22612876e-01 -4.36709553e-01 -7.94151664e-01 -4.22613412e-01 -4.39466000e-01 -7.92621434e-01 -4.22612876e-01 -4.42293316e-01 -7.91050196e-01 -4.22613114e-01 -4.44987923e-01 -7.89542198e-01 -4.22613353e-01 -4.47717339e-01 -7.87992239e-01 -4.22612965e-01 -4.50462788e-01 -7.86431909e-01 -4.22613293e-01 -4.53165203e-01 -7.84873784e-01 -4.22613114e-01 -4.55968499e-01 -7.83245325e-01 -4.22612756e-01 -4.58716989e-01 -7.81647563e-01 -4.22613591e-01 -4.61428374e-01 -7.80040920e-01 -4.22612816e-01 -4.64151829e-01 -7.78430879e-01 -4.22613591e-01 -4.66843575e-01 -7.76812792e-01 -4.22612876e-01 -4.69574809e-01 -7.75170326e-01 -4.22613472e-01 -4.72266048e-01 -7.73530245e-01 -4.22612876e-01 -4.75044817e-01 -7.71827996e-01 -4.22613084e-01 -4.77669984e-01 -7.70210505e-01 -4.22613472e-01 -4.80265439e-01 -7.68590569e-01 -4.22613114e-01 -4.83027279e-01 -7.66852677e-01 -4.22612756e-01 -4.85772878e-01 -7.65119791e-01 -4.22613025e-01 -4.88440812e-01 -7.63420582e-01 -4.22613144e-01 -4.91035014e-01 -7.61757135e-01 -4.22613412e-01 -4.93623823e-01 -7.60079682e-01 -4.22613084e-01 -4.96284217e-01 -7.58344412e-01 -4.22613114e-01 -4.98914391e-01 -7.56618738e-01 -4.22613174e-01 -5.01542866e-01 -7.54875958e-01 -4.22613144e-01 -5.04174292e-01 -7.53122687e-01 -4.22613144e-01 -5.06867170e-01 -7.51311064e-01 -4.22612786e-01 -5.09543836e-01 -7.49501705e-01 -4.22613233e-01 -5.12079000e-01 -7.47774422e-01 -4.22613293e-01 -5.14712632e-01 -7.45957017e-01 -4.22612786e-01 -5.17324746e-01 -7.44157016e-01 -4.22613591e-01 -5.19909859e-01 -7.42341101e-01 -4.22612756e-01 -5.22586882e-01 -7.40466177e-01 -4.22613114e-01 -5.25097787e-01 -7.38691330e-01 -4.22613591e-01 -5.27646244e-01 -7.36866176e-01 -4.22612846e-01 -5.30214131e-01 -7.35023379e-01 -4.22613382e-01 -5.32766640e-01 -7.33173013e-01 -4.22612876e-01 -5.35407662e-01 -7.31247306e-01 -4.22613084e-01 -5.37968814e-01 -7.29365885e-01 -4.22613114e-01 -5.40449619e-01 -7.27534175e-01 -4.22613591e-01 -5.42903125e-01 -7.25699902e-01 -4.22613084e-01 -5.45440912e-01 -7.23795295e-01 -4.22613144e-01 -5.48022270e-01 -7.21839786e-01 -4.22612846e-01 -5.50555587e-01 -7.19917059e-01 -4.22613591e-01 -5.53058743e-01 -7.17985392e-01 -4.22612697e-01 -5.55576086e-01 -7.16049969e-01 -4.22613591e-01 -5.57992876e-01 -7.14162052e-01 -4.22613025e-01 -5.60554862e-01 -7.12151885e-01 -4.22612816e-01 -5.63042760e-01 -7.10191727e-01 -4.22613412e-01 -5.65507352e-01 -7.08225727e-01 -4.22612846e-01 -5.67999184e-01 -7.06234932e-01 -4.22613382e-01 -5.70388138e-01 -7.04305828e-01 -4.22613204e-01 -5.72897792e-01 -7.02258825e-01 -4.22612816e-01 -5.75366437e-01 -7.00247049e-01 -4.22613591e-01 -5.77730119e-01 -6.98294163e-01 -4.22613114e-01 -5.80166698e-01 -6.96271002e-01 -4.22613084e-01 -5.82635880e-01 -6.94201112e-01 -4.22612846e-01 -5.85132837e-01 -6.92101657e-01 -4.22613055e-01 -5.87495267e-01 -6.90099120e-01 -4.22613353e-01 -5.89827240e-01 -6.88105285e-01 -4.22613114e-01 -5.92229068e-01 -6.86040461e-01 -4.22613114e-01 -5.94670236e-01 -6.83921218e-01 -4.22612816e-01 -5.97113907e-01 -6.81791008e-01 -4.22613114e-01 -5.99448740e-01 -6.79744124e-01 -4.22613442e-01 -6.01743758e-01 -6.77710354e-01 -4.22613174e-01 -6.04099572e-01 -6.75610483e-01 -4.22613144e-01 -6.06459618e-01 -6.73492193e-01 -4.22613084e-01 -6.08869374e-01 -6.71312630e-01 -4.22612786e-01 -6.11232042e-01 -6.69166803e-01 -4.22613412e-01 -6.13540709e-01 -6.67047918e-01 -4.22612906e-01 -6.15865052e-01 -6.64907157e-01 -4.22613561e-01 -6.18167400e-01 -6.62758350e-01 -4.22612727e-01 -6.20545387e-01 -6.60536110e-01 -4.22613174e-01 -6.22794688e-01 -6.58418834e-01 -4.22613353e-01 -6.25080287e-01 -6.56246245e-01 -4.22612846e-01 -6.27374709e-01 -6.54053450e-01 -4.22613591e-01 -6.29597425e-01 -6.51922822e-01 -4.22613084e-01 -6.31890237e-01 -6.49698019e-01 -4.22612935e-01 -6.34159029e-01 -6.47483528e-01 -4.22613323e-01 -6.36383832e-01 -6.45296574e-01 -4.22613084e-01 -6.38626099e-01 -6.43079937e-01 -4.22613114e-01 -6.40909910e-01 -6.40782595e-01 -4.22612906e-01 -6.43162310e-01 -6.38546169e-01 -4.22613323e-01 -6.45390272e-01 -6.36285484e-01 -4.22612846e-01 -6.47613227e-01 -6.34028018e-01 -4.22613412e-01 -6.49763525e-01 -6.31823480e-01 -4.22613114e-01 -6.51982069e-01 -6.29534900e-01 -4.22612995e-01 -6.54216945e-01 -6.27196014e-01 -4.22612876e-01 -6.56412423e-01 -6.24913871e-01 -4.22613382e-01 -6.58583283e-01 -6.22613430e-01 -4.22612876e-01 -6.60741866e-01 -6.20330811e-01 -4.22613591e-01 -6.62826478e-01 -6.18096650e-01 -4.22613144e-01 -6.65018559e-01 -6.15737975e-01 -4.22612906e-01 -6.67240024e-01 -6.13333404e-01 -4.22612965e-01 -6.69341624e-01 -6.11043811e-01 -4.22613591e-01 -6.71389878e-01 -6.08787179e-01 -4.22613055e-01 -6.73515856e-01 -6.06436014e-01 -4.22613144e-01 -6.75688386e-01 -6.04006588e-01 -4.22612697e-01 -6.77821457e-01 -6.01624191e-01 -4.22613591e-01 -6.79893196e-01 -5.99271536e-01 -4.22612846e-01 -6.81980968e-01 -5.96902788e-01 -4.22613591e-01 -6.84055626e-01 -5.94514787e-01 -4.22612846e-01 -6.86188281e-01 -5.92057586e-01 -4.22613114e-01 -6.88207626e-01 -5.89712620e-01 -4.22613353e-01 -6.90203249e-01 -5.87370515e-01 -4.22613144e-01 -6.92249060e-01 -5.84961116e-01 -4.22613114e-01 -6.94318831e-01 -5.82497895e-01 -4.22612965e-01 -6.96397483e-01 -5.80014169e-01 -4.22613025e-01 -6.98397756e-01 -5.77605903e-01 -4.22613353e-01 -7.00356662e-01 -5.75229108e-01 -4.22613084e-01 -7.02366412e-01 -5.72770476e-01 -4.22613114e-01 -7.04356134e-01 -5.70323825e-01 -4.22613174e-01 -7.06384242e-01 -5.67803204e-01 -4.22612756e-01 -7.08429039e-01 -5.65255761e-01 -4.22613084e-01 -7.10393548e-01 -5.62784016e-01 -4.22613084e-01 -7.12303817e-01 -5.60371757e-01 -4.22613591e-01 -7.14183629e-01 -5.57968259e-01 -4.22613114e-01 -7.16188788e-01 -5.55386305e-01 -4.22612816e-01 -7.18162239e-01 -5.52839637e-01 -4.22613233e-01 -7.20084190e-01 -5.50328970e-01 -4.22612876e-01 -7.21989214e-01 -5.47834873e-01 -4.22613561e-01 -7.23830581e-01 -5.45397103e-01 -4.22613144e-01 -7.25771844e-01 -5.42802751e-01 -4.22612876e-01 -7.27677047e-01 -5.40255427e-01 -4.22613412e-01 -7.29509175e-01 -5.37772417e-01 -4.22613025e-01 -7.31383860e-01 -5.35223484e-01 -4.22613263e-01 -7.33262002e-01 -5.32644093e-01 -4.22612906e-01 -7.35160947e-01 -5.30018270e-01 -4.22612995e-01 -7.36997008e-01 -5.27473450e-01 -4.22613412e-01 -7.38783062e-01 -5.24961829e-01 -4.22613084e-01 -7.40608692e-01 -5.22386909e-01 -4.22613114e-01 -7.42434800e-01 -5.19782901e-01 -4.22613055e-01 -7.44278491e-01 -5.17136872e-01 -4.22612906e-01 -7.46085584e-01 -5.14537930e-01 -4.22613353e-01 -7.47827649e-01 -5.11997223e-01 -4.22613144e-01 -7.49597847e-01 -5.09401321e-01 -4.22613144e-01 -7.51364470e-01 -5.06794512e-01 -4.22613144e-01 -7.53171146e-01 -5.04094183e-01 -4.22612697e-01 -7.54944384e-01 -5.01446426e-01 -4.22613591e-01 -7.56683052e-01 -4.98808801e-01 -4.22612756e-01 -7.58438408e-01 -4.96147573e-01 -4.22613591e-01 -7.60103106e-01 -4.93589163e-01 -4.22613233e-01 -7.61819065e-01 -4.90933567e-01 -4.22613114e-01 -7.63567507e-01 -4.88203883e-01 -4.22612816e-01 -7.65294433e-01 -4.85503495e-01 -4.22613382e-01 -7.66933680e-01 -4.82909173e-01 -4.22613144e-01 -7.68594146e-01 -4.80257452e-01 -4.22613114e-01 -7.70280004e-01 -4.77552444e-01 -4.22613084e-01 -7.71939635e-01 -4.74861354e-01 -4.22613084e-01 -7.73598373e-01 -4.72160190e-01 -4.22613174e-01 -7.75241375e-01 -4.69453603e-01 -4.22613084e-01 -7.76914775e-01 -4.66674149e-01 -4.22612786e-01 -7.78590024e-01 -4.63876635e-01 -4.22613114e-01 -7.80164778e-01 -4.61228937e-01 -4.22613412e-01 -7.81759262e-01 -4.58511919e-01 -4.22612816e-01 -7.83367038e-01 -4.55769986e-01 -4.22613472e-01 -7.84922957e-01 -4.53079045e-01 -4.22612965e-01 -7.86495864e-01 -4.50348288e-01 -4.22613293e-01 -7.88039982e-01 -4.47635502e-01 -4.22613144e-01 -7.89593339e-01 -4.44895148e-01 -4.22613055e-01 -7.91143894e-01 -4.42128181e-01 -4.22613174e-01 -7.92680025e-01 -4.39362913e-01 -4.22613055e-01 -7.94240117e-01 -4.36538875e-01 -4.22612876e-01 -7.95790255e-01 -4.33714271e-01 -4.22613144e-01 -7.97275007e-01 -4.30976599e-01 -4.22613293e-01 -7.98738956e-01 -4.28254724e-01 -4.22613114e-01 -8.00256491e-01 -4.25405115e-01 -4.22612846e-01 -8.01781416e-01 -4.22528386e-01 -4.22613055e-01 -8.03245425e-01 -4.19744462e-01 -4.22613204e-01 -8.04667652e-01 -4.17011917e-01 -4.22613382e-01 -8.06083322e-01 -4.14268047e-01 -4.22613144e-01 -8.07551086e-01 -4.11390543e-01 -4.22612816e-01 -8.09037089e-01 -4.08466071e-01 -4.22613025e-01 -8.10421586e-01 -4.05719548e-01 -4.22613591e-01 -8.11781645e-01 -4.02982950e-01 -4.22613114e-01 -8.13176811e-01 -4.00161028e-01 -4.22613114e-01 -8.14573050e-01 -3.97314847e-01 -4.22613114e-01 -8.15994442e-01 -3.94378573e-01 -4.22612756e-01 -8.17412138e-01 -3.91434580e-01 -4.22613084e-01 -8.18750024e-01 -3.88637066e-01 -4.22613412e-01 -8.20055664e-01 -3.85866016e-01 -4.22613144e-01 -8.21391463e-01 -3.83018166e-01 -4.22613204e-01 -8.22758615e-01 -3.80064428e-01 -4.22612727e-01 -8.24106216e-01 -3.77145141e-01 -4.22613353e-01 -8.25376093e-01 -3.74358863e-01 -4.22613263e-01 -8.26659739e-01 -3.71510446e-01 -4.22613144e-01 -8.27947080e-01 -3.68634373e-01 -4.22613084e-01 -8.29271495e-01 -3.65634769e-01 -4.22612697e-01 -8.30589175e-01 -3.62644315e-01 -4.22613204e-01 -8.31843376e-01 -3.59756351e-01 -4.22613174e-01 -8.33092451e-01 -3.56842577e-01 -4.22613114e-01 -8.34305286e-01 -3.54013890e-01 -4.22613591e-01 -8.35498154e-01 -3.51179510e-01 -4.22613055e-01 -8.36725116e-01 -3.48246425e-01 -4.22613144e-01 -8.37964118e-01 -3.45248014e-01 -4.22612906e-01 -8.39172781e-01 -3.42318624e-01 -4.22613591e-01 -8.40325892e-01 -3.39468241e-01 -4.22613174e-01 -8.41533601e-01 -3.36451977e-01 -4.22612846e-01 -8.42707634e-01 -3.33519191e-01 -4.22613412e-01 -8.43837559e-01 -3.30646157e-01 -4.22613144e-01 -8.44980478e-01 -3.27697814e-01 -4.22613114e-01 -8.46131325e-01 -3.24731469e-01 -4.22613025e-01 -8.47287416e-01 -3.21688592e-01 -4.22612906e-01 -8.48394156e-01 -3.18756342e-01 -4.22613412e-01 -8.49468887e-01 -3.15871924e-01 -4.22613084e-01 -8.50597441e-01 -3.12824100e-01 -4.22612816e-01 -8.51725101e-01 -3.09761643e-01 -4.22613144e-01 -8.52793694e-01 -3.06802392e-01 -4.22613144e-01 -8.53837967e-01 -3.03897858e-01 -4.22613591e-01 -8.54881287e-01 -3.00930142e-01 -4.22612876e-01 -8.55939746e-01 -2.97921628e-01 -4.22613382e-01 -8.56940925e-01 -2.95024723e-01 -4.22613174e-01 -8.57962608e-01 -2.92034060e-01 -4.22613144e-01 -8.58977318e-01 -2.89039701e-01 -4.22613114e-01 -8.60009968e-01 -2.85942286e-01 -4.22612786e-01 -8.61012161e-01 -2.82932937e-01 -4.22613591e-01 -8.61961544e-01 -2.80017078e-01 -4.22613114e-01 -8.62951696e-01 -2.76938736e-01 -4.22612846e-01 -8.63921344e-01 -2.73917973e-01 -4.22613531e-01 -8.64860058e-01 -2.70926118e-01 -4.22612906e-01 -8.65808904e-01 -2.67890990e-01 -4.22613382e-01 -8.66735041e-01 -2.64861137e-01 -4.22612876e-01 -8.67677391e-01 -2.61762679e-01 -4.22613114e-01 -8.68569255e-01 -2.58800209e-01 -4.22613412e-01 -8.69461238e-01 -2.55774945e-01 -4.22612935e-01 -8.70353639e-01 -2.52739936e-01 -4.22613412e-01 -8.71223509e-01 -2.49697551e-01 -4.22612816e-01 -8.72095644e-01 -2.46657982e-01 -4.22613412e-01 -8.72928321e-01 -2.43687704e-01 -4.22613144e-01 -8.73774707e-01 -2.40632966e-01 -4.22613114e-01 -8.74610484e-01 -2.37581268e-01 -4.22613144e-01 -8.75450015e-01 -2.34451905e-01 -4.22612816e-01 -8.76289248e-01 -2.31308565e-01 -4.22613114e-01 -8.77091587e-01 -2.28247225e-01 -4.22613114e-01 -8.77865732e-01 -2.25269690e-01 -4.22613591e-01 -8.78612757e-01 -2.22311392e-01 -4.22613114e-01 -8.79403114e-01 -2.19151989e-01 -4.22612786e-01 -8.80193114e-01 -2.15985030e-01 -4.22613174e-01 -8.80939722e-01 -2.12922156e-01 -4.22613084e-01 -8.81659210e-01 -2.09931463e-01 -4.22613561e-01 -8.82364571e-01 -2.06932202e-01 -4.22613114e-01 -8.83092880e-01 -2.03779802e-01 -4.22612816e-01 -8.83828998e-01 -2.00580761e-01 -4.22613114e-01 -8.84507477e-01 -1.97584420e-01 -4.22613472e-01 -8.85182261e-01 -1.94505066e-01 -4.22612816e-01 -8.85865450e-01 -1.91398740e-01 -4.22613591e-01 -8.86500239e-01 -1.88415512e-01 -4.22613025e-01 -8.87173772e-01 -1.85219362e-01 -4.22612816e-01 -8.87837529e-01 -1.82020053e-01 -4.22613084e-01 -8.88454735e-01 -1.78998157e-01 -4.22613472e-01 -8.89050186e-01 -1.75994858e-01 -4.22613084e-01 -8.89660478e-01 -1.72891170e-01 -4.22613114e-01 -8.90268147e-01 -1.69713169e-01 -4.22612846e-01 -8.90879869e-01 -1.66498110e-01 -4.22613084e-01 -8.91441166e-01 -1.63466677e-01 -4.22613591e-01 -8.91991317e-01 -1.60454348e-01 -4.22613174e-01 -8.92546177e-01 -1.57333523e-01 -4.22613144e-01 -8.93093526e-01 -1.54144883e-01 -4.22612727e-01 -8.93645883e-01 -1.50940999e-01 -4.22613144e-01 -8.94156516e-01 -1.47904813e-01 -4.22613382e-01 -8.94662559e-01 -1.44775763e-01 -4.22612816e-01 -8.95168722e-01 -1.41653329e-01 -4.22613591e-01 -8.95648181e-01 -1.38547242e-01 -4.22612876e-01 -8.96132052e-01 -1.35411695e-01 -4.22613323e-01 -8.96592498e-01 -1.32302433e-01 -4.22612906e-01 -8.97054851e-01 -1.29156545e-01 -4.22613353e-01 -8.97487223e-01 -1.26105607e-01 -4.22613114e-01 -8.97929490e-01 -1.22910984e-01 -4.22612876e-01 -8.98359358e-01 -1.19749695e-01 -4.22613382e-01 -8.98764193e-01 -1.16632223e-01 -4.22612906e-01 -8.99172843e-01 -1.13487713e-01 -4.22613323e-01 -8.99550557e-01 -1.10432245e-01 -4.22613144e-01 -8.99935961e-01 -1.07216001e-01 -4.22612846e-01 -9.00310099e-01 -1.04073256e-01 -4.22613412e-01 -9.00655329e-01 -1.01021662e-01 -4.22613084e-01 -9.01011109e-01 -9.77645740e-02 -4.22612816e-01 -9.01358962e-01 -9.45427865e-02 -4.22613144e-01 -9.01678324e-01 -9.14284363e-02 -4.22613114e-01 -9.01990354e-01 -8.83423612e-02 -4.22613591e-01 -9.02287722e-01 -8.52087438e-02 -4.22612786e-01 -9.02586401e-01 -8.20373222e-02 -4.22613472e-01 -9.02855933e-01 -7.89882988e-02 -4.22613144e-01 -9.03124154e-01 -7.58350790e-02 -4.22613084e-01 -9.03385103e-01 -7.26727918e-02 -4.22613114e-01 -9.03636336e-01 -6.94467127e-02 -4.22612816e-01 -9.03881073e-01 -6.62620887e-02 -4.22613561e-01 -9.04094279e-01 -6.32173344e-02 -4.22613114e-01 -9.04312789e-01 -5.99730983e-02 -4.22612756e-01 -9.04525757e-01 -5.67100719e-02 -4.22613114e-01 -9.04718459e-01 -5.35597801e-02 -4.22613114e-01 -9.04899478e-01 -5.04919328e-02 -4.22613412e-01 -9.05060589e-01 -4.73539792e-02 -4.22612816e-01 -9.05230403e-01 -4.41215262e-02 -4.22613204e-01 -9.05355692e-01 -4.15744856e-02 -4.22619641e-01 -9.05507565e-01 -3.80707793e-02 -4.22618330e-01 -9.05619323e-01 -3.53182107e-02 -4.22618270e-01 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.62077141e-01 4.16687205e-02 -2.69575357e-01 -9.61953282e-01 4.44895960e-02 -2.69576311e-01 -9.61814642e-01 4.70973663e-02 -2.69576311e-01 -9.61630702e-01 5.06534465e-02 -2.69574612e-01 -9.61460054e-01 5.39587252e-02 -2.69573241e-01 -9.61264849e-01 5.73103800e-02 -2.69572526e-01 -9.61058438e-01 6.06606565e-02 -2.69572616e-01 -9.60843146e-01 6.40178323e-02 -2.69572407e-01 -9.60614741e-01 6.73077255e-02 -2.69573331e-01 -9.60384607e-01 7.05642328e-02 -2.69572407e-01 -9.60129619e-01 7.39822686e-02 -2.69572139e-01 -9.59854960e-01 7.74332434e-02 -2.69572407e-01 -9.59584355e-01 8.06956291e-02 -2.69573241e-01 -9.59303081e-01 8.40250552e-02 -2.69571990e-01 -9.58992779e-01 8.74649808e-02 -2.69572526e-01 -9.58687007e-01 9.07559767e-02 -2.69572824e-01 -9.58363473e-01 9.41234455e-02 -2.69572228e-01 -9.58032966e-01 9.74114835e-02 -2.69573182e-01 -9.57698524e-01 1.00656465e-01 -2.69572616e-01 -9.57333326e-01 1.04088433e-01 -2.69571990e-01 -9.56951976e-01 1.07534572e-01 -2.69572437e-01 -9.56567287e-01 1.10886365e-01 -2.69572407e-01 -9.56174016e-01 1.14231311e-01 -2.69572407e-01 -9.55772579e-01 1.17542788e-01 -2.69572467e-01 -9.55360293e-01 1.20861903e-01 -2.69572586e-01 -9.54930186e-01 1.24210984e-01 -2.69572198e-01 -9.54482853e-01 1.27594560e-01 -2.69572228e-01 -9.54041719e-01 1.30835146e-01 -2.69573569e-01 -9.53602731e-01 1.34021372e-01 -2.69572407e-01 -9.53114331e-01 1.37454823e-01 -2.69571990e-01 -9.52611268e-01 1.40879720e-01 -2.69572675e-01 -9.52114046e-01 1.44201860e-01 -2.69572407e-01 -9.51605856e-01 1.47529721e-01 -2.69572407e-01 -9.51086104e-01 1.50843903e-01 -2.69572467e-01 -9.50563133e-01 1.54088661e-01 -2.69573301e-01 -9.50026631e-01 1.57396257e-01 -2.69571990e-01 -9.49451685e-01 1.60816073e-01 -2.69572467e-01 -9.48894858e-01 1.64051667e-01 -2.69573182e-01 -9.48326111e-01 1.67347938e-01 -2.69571990e-01 -9.47715998e-01 1.70760408e-01 -2.69572318e-01 -9.47107911e-01 1.74072862e-01 -2.69572496e-01 -9.46495414e-01 1.77383214e-01 -2.69572437e-01 -9.45885658e-01 1.80587754e-01 -2.69573480e-01 -9.45274472e-01 1.83770716e-01 -2.69572407e-01 -9.44606602e-01 1.87189981e-01 -2.69571990e-01 -9.43925261e-01 1.90589771e-01 -2.69572407e-01 -9.43251073e-01 1.93896249e-01 -2.69572407e-01 -9.42586482e-01 1.97087914e-01 -2.69573420e-01 -9.41900730e-01 2.00368896e-01 -2.69571990e-01 -9.41171408e-01 2.03755781e-01 -2.69572467e-01 -9.40467060e-01 2.06959441e-01 -2.69573420e-01 -9.39752400e-01 2.10217506e-01 -2.69571990e-01 -9.39000309e-01 2.13525310e-01 -2.69573271e-01 -9.38275576e-01 2.16693461e-01 -2.69572437e-01 -9.37499166e-01 2.20052257e-01 -2.69571990e-01 -9.36697066e-01 2.23426491e-01 -2.69572496e-01 -9.35919881e-01 2.26663888e-01 -2.69572705e-01 -9.35123086e-01 2.29924813e-01 -2.69572318e-01 -9.34306145e-01 2.33214334e-01 -2.69572318e-01 -9.33504939e-01 2.36391321e-01 -2.69573480e-01 -9.32684660e-01 2.39627555e-01 -2.69571990e-01 -9.31815684e-01 2.42978722e-01 -2.69572616e-01 -9.30982351e-01 2.46150374e-01 -2.69573122e-01 -9.30121005e-01 2.49395087e-01 -2.69571990e-01 -9.29225922e-01 2.52705812e-01 -2.69572496e-01 -9.28333461e-01 2.55956620e-01 -2.69572407e-01 -9.27436590e-01 2.59197086e-01 -2.69572407e-01 -9.26538587e-01 2.62375981e-01 -2.69573331e-01 -9.25630033e-01 2.65575618e-01 -2.69572139e-01 -9.24691498e-01 2.68813878e-01 -2.69573182e-01 -9.23755169e-01 2.72027194e-01 -2.69571990e-01 -9.22769785e-01 2.75348216e-01 -2.69572407e-01 -9.21824098e-01 2.78482944e-01 -2.69573331e-01 -9.20852900e-01 2.81694800e-01 -2.69571990e-01 -9.19832110e-01 2.85004526e-01 -2.69572526e-01 -9.18839872e-01 2.88188070e-01 -2.69572556e-01 -9.17833269e-01 2.91376799e-01 -2.69572467e-01 -9.16822433e-01 2.94540644e-01 -2.69573301e-01 -9.15822029e-01 2.97633767e-01 -2.69572616e-01 -9.14755404e-01 3.00903589e-01 -2.69572139e-01 -9.13665771e-01 3.04193854e-01 -2.69572407e-01 -9.12592232e-01 3.07399452e-01 -2.69572407e-01 -9.11515594e-01 3.10577035e-01 -2.69572377e-01 -9.10431385e-01 3.13742757e-01 -2.69572556e-01 -9.09350574e-01 3.16853136e-01 -2.69572943e-01 -9.08245623e-01 3.20017755e-01 -2.69572049e-01 -9.07095909e-01 3.23260456e-01 -2.69572496e-01 -9.05986547e-01 3.26347023e-01 -2.69573271e-01 -9.04880166e-01 3.29412431e-01 -2.69572526e-01 -9.03693080e-01 3.32645774e-01 -2.69572049e-01 -9.02489126e-01 3.35880935e-01 -2.69572467e-01 -9.01306510e-01 3.39046180e-01 -2.69572496e-01 -9.00128722e-01 3.42172086e-01 -2.69572526e-01 -8.98962796e-01 3.45240235e-01 -2.69573063e-01 -8.97768736e-01 3.48318279e-01 -2.69572526e-01 -8.96527827e-01 3.51512343e-01 -2.69572079e-01 -8.95262241e-01 3.54718149e-01 -2.69572467e-01 -8.94048333e-01 3.57755661e-01 -2.69573420e-01 -8.92807007e-01 3.60856712e-01 -2.69571990e-01 -8.91507506e-01 3.64053041e-01 -2.69572407e-01 -8.90237153e-01 3.67139757e-01 -2.69572705e-01 -8.88958633e-01 3.70228291e-01 -2.69572526e-01 -8.87684047e-01 3.73270243e-01 -2.69573241e-01 -8.86407137e-01 3.76296133e-01 -2.69572407e-01 -8.85053456e-01 3.79467160e-01 -2.69571990e-01 -8.83685529e-01 3.82645398e-01 -2.69572496e-01 -8.82352769e-01 3.85710686e-01 -2.69572526e-01 -8.80998015e-01 3.88796210e-01 -2.69572407e-01 -8.79634917e-01 3.91869068e-01 -2.69572526e-01 -8.78267467e-01 3.94924223e-01 -2.69572526e-01 -8.76910806e-01 3.97922665e-01 -2.69573122e-01 -8.75525534e-01 4.00963038e-01 -2.69572139e-01 -8.74090314e-01 4.04083937e-01 -2.69572407e-01 -8.72703612e-01 4.07066405e-01 -2.69573182e-01 -8.71290922e-01 4.10088032e-01 -2.69572139e-01 -8.69815886e-01 4.13206875e-01 -2.69572467e-01 -8.68366480e-01 4.16240841e-01 -2.69572467e-01 -8.66912425e-01 4.19268012e-01 -2.69572467e-01 -8.65464032e-01 4.22245502e-01 -2.69573122e-01 -8.64030361e-01 4.25167680e-01 -2.69572467e-01 -8.62512946e-01 4.28242236e-01 -2.69572139e-01 -8.60976160e-01 4.31319952e-01 -2.69572407e-01 -8.59461904e-01 4.34333354e-01 -2.69572407e-01 -8.57938707e-01 4.37333584e-01 -2.69572496e-01 -8.56420875e-01 4.40299392e-01 -2.69572467e-01 -8.54880273e-01 4.43277776e-01 -2.69572675e-01 -8.53328347e-01 4.46260303e-01 -2.69572407e-01 -8.51764560e-01 4.49242115e-01 -2.69572467e-01 -8.50223601e-01 4.52144802e-01 -2.69573331e-01 -8.48688066e-01 4.55026060e-01 -2.69572467e-01 -8.47056746e-01 4.58059639e-01 -2.69571990e-01 -8.45409632e-01 4.61089402e-01 -2.69572586e-01 -8.43797505e-01 4.64034706e-01 -2.69572347e-01 -8.42162728e-01 4.66984630e-01 -2.69572526e-01 -8.40536833e-01 4.69907641e-01 -2.69572526e-01 -8.38907182e-01 4.72814947e-01 -2.69572586e-01 -8.37246537e-01 4.75752652e-01 -2.69572139e-01 -8.35558355e-01 4.78708029e-01 -2.69572318e-01 -8.33925724e-01 4.81542200e-01 -2.69573301e-01 -8.32251251e-01 4.84439105e-01 -2.69571990e-01 -8.30559313e-01 4.87325013e-01 -2.69573390e-01 -8.28848720e-01 4.90237623e-01 -2.69571990e-01 -8.27078879e-01 4.93211627e-01 -2.69572467e-01 -8.25354755e-01 4.96093065e-01 -2.69572407e-01 -8.23615491e-01 4.98971432e-01 -2.69572526e-01 -8.21867168e-01 5.01854777e-01 -2.69572318e-01 -8.20105195e-01 5.04722953e-01 -2.69572437e-01 -8.18346024e-01 5.07576048e-01 -2.69572467e-01 -8.16613197e-01 5.10350645e-01 -2.69573390e-01 -8.14841330e-01 5.13182580e-01 -2.69571990e-01 -8.13002348e-01 5.16086578e-01 -2.69572765e-01 -8.11188042e-01 5.18935800e-01 -2.69572139e-01 -8.09353650e-01 5.21788299e-01 -2.69572705e-01 -8.07538986e-01 5.24592638e-01 -2.69572645e-01 -8.05758238e-01 5.27319729e-01 -2.69573182e-01 -8.03907633e-01 5.30146897e-01 -2.69571990e-01 -8.01983535e-01 5.33046603e-01 -2.69572258e-01 -8.00112247e-01 5.35852790e-01 -2.69572467e-01 -7.98276484e-01 5.38583517e-01 -2.69573152e-01 -7.96453595e-01 5.41274488e-01 -2.69572675e-01 -7.94542074e-01 5.44083595e-01 -2.69572139e-01 -7.92589307e-01 5.46922028e-01 -2.69572288e-01 -7.90651143e-01 5.49718559e-01 -2.69572496e-01 -7.88771808e-01 5.52401960e-01 -2.69573539e-01 -7.86850750e-01 5.55151761e-01 -2.69571990e-01 -7.84828782e-01 5.57995319e-01 -2.69572616e-01 -7.82884657e-01 5.60723007e-01 -2.69572526e-01 -7.80909479e-01 5.63465357e-01 -2.69572526e-01 -7.78939068e-01 5.66189945e-01 -2.69572586e-01 -7.76976228e-01 5.68879962e-01 -2.69572526e-01 -7.75055528e-01 5.71489036e-01 -2.69573510e-01 -7.73048937e-01 5.74206710e-01 -2.69571990e-01 -7.70972252e-01 5.76990366e-01 -2.69572467e-01 -7.69013882e-01 5.79595268e-01 -2.69573569e-01 -7.66997635e-01 5.82270205e-01 -2.69571990e-01 -7.64891386e-01 5.85030198e-01 -2.69572645e-01 -7.62848377e-01 5.87688804e-01 -2.69572467e-01 -7.60775685e-01 5.90369165e-01 -2.69572407e-01 -7.58736253e-01 5.92988193e-01 -2.69573003e-01 -7.56728768e-01 5.95549166e-01 -2.69572765e-01 -7.54613578e-01 5.98230660e-01 -2.69571990e-01 -7.52437294e-01 6.00966096e-01 -2.69572288e-01 -7.50334978e-01 6.03587329e-01 -2.69572526e-01 -7.48220801e-01 6.06203556e-01 -2.69573152e-01 -7.46164501e-01 6.08728468e-01 -2.69573301e-01 -7.44046926e-01 6.11322880e-01 -2.69572139e-01 -7.41851568e-01 6.13982022e-01 -2.69572645e-01 -7.39704669e-01 6.16566300e-01 -2.69572705e-01 -7.37607896e-01 6.19071066e-01 -2.69573450e-01 -7.35443830e-01 6.21646821e-01 -2.69571990e-01 -7.33183324e-01 6.24306500e-01 -2.69572407e-01 -7.31000304e-01 6.26863062e-01 -2.69572467e-01 -7.28804052e-01 6.29418075e-01 -2.69572407e-01 -7.26613820e-01 6.31940722e-01 -2.69572526e-01 -7.24456728e-01 6.34411454e-01 -2.69573241e-01 -7.22297251e-01 6.36870503e-01 -2.69572407e-01 -7.20020831e-01 6.39446318e-01 -2.69571990e-01 -7.17722893e-01 6.42025828e-01 -2.69572288e-01 -7.15518832e-01 6.44472361e-01 -2.69573420e-01 -7.13281751e-01 6.46959364e-01 -2.69571990e-01 -7.10956514e-01 6.49504125e-01 -2.69572526e-01 -7.08692014e-01 6.51978493e-01 -2.69572467e-01 -7.06411004e-01 6.54448628e-01 -2.69572556e-01 -7.04173148e-01 6.56852663e-01 -2.69573152e-01 -7.01943278e-01 6.59236610e-01 -2.69572526e-01 -6.99582994e-01 6.61741495e-01 -2.69571990e-01 -6.97208941e-01 6.64244235e-01 -2.69572467e-01 -6.94871247e-01 6.66683853e-01 -2.69572407e-01 -6.92550063e-01 6.69107437e-01 -2.69572526e-01 -6.90271616e-01 6.71452701e-01 -2.69573271e-01 -6.87933326e-01 6.73849583e-01 -2.69572139e-01 -6.85509682e-01 6.76314354e-01 -2.69572318e-01 -6.83142543e-01 6.78708613e-01 -2.69572526e-01 -6.80765808e-01 6.81072414e-01 -2.69572645e-01 -6.78451538e-01 6.83395624e-01 -2.69573152e-01 -6.76053464e-01 6.85771763e-01 -2.69571990e-01 -6.73597157e-01 6.88178003e-01 -2.69572586e-01 -6.71186984e-01 6.90531850e-01 -2.69572467e-01 -6.68776631e-01 6.92870438e-01 -2.69572437e-01 -6.66392863e-01 6.95146680e-01 -2.69573033e-01 -6.64010286e-01 6.97433293e-01 -2.69572526e-01 -6.61526978e-01 6.99786007e-01 -2.69572139e-01 -6.59030735e-01 7.02134967e-01 -2.69572467e-01 -6.56613588e-01 7.04391599e-01 -2.69573241e-01 -6.54171467e-01 7.06670225e-01 -2.69572139e-01 -6.51647568e-01 7.08996952e-01 -2.69572467e-01 -6.49219751e-01 7.11215317e-01 -2.69573271e-01 -6.46734536e-01 7.13483632e-01 -2.69571990e-01 -6.44247472e-01 7.15722799e-01 -2.69573420e-01 -6.41816854e-01 7.17906713e-01 -2.69572467e-01 -6.39245927e-01 7.20201075e-01 -2.69571990e-01 -6.36713862e-01 7.22433865e-01 -2.69573301e-01 -6.34184062e-01 7.24659145e-01 -2.69571990e-01 -6.31647766e-01 7.26866484e-01 -2.69573629e-01 -6.29136562e-01 7.29047120e-01 -2.69571990e-01 -6.26486897e-01 7.31322765e-01 -2.69572467e-01 -6.23915553e-01 7.33516216e-01 -2.69572526e-01 -6.21376872e-01 7.35669196e-01 -2.69572586e-01 -6.18876994e-01 7.37770319e-01 -2.69573480e-01 -6.16310537e-01 7.39922464e-01 -2.69571990e-01 -6.13706052e-01 7.42076933e-01 -2.69573331e-01 -6.11129105e-01 7.44208515e-01 -2.69571990e-01 -6.08429730e-01 7.46412039e-01 -2.69572407e-01 -6.05824053e-01 7.48529911e-01 -2.69572347e-01 -6.03272319e-01 7.50582576e-01 -2.69573510e-01 -6.00731373e-01 7.52623618e-01 -2.69572318e-01 -5.98022521e-01 7.54777730e-01 -2.69572049e-01 -5.95384359e-01 7.56856799e-01 -2.69573390e-01 -5.92762351e-01 7.58917987e-01 -2.69572139e-01 -5.90102434e-01 7.60983169e-01 -2.69573450e-01 -5.87482393e-01 7.63009906e-01 -2.69572198e-01 -5.84747016e-01 7.65108764e-01 -2.69572228e-01 -5.82026064e-01 7.67180741e-01 -2.69572467e-01 -5.79407632e-01 7.69156933e-01 -2.69573182e-01 -5.76748669e-01 7.71154702e-01 -2.69572020e-01 -5.73970735e-01 7.73224831e-01 -2.69572318e-01 -5.71266055e-01 7.75224030e-01 -2.69572526e-01 -5.68566144e-01 7.77205348e-01 -2.69572526e-01 -5.65908313e-01 7.79143333e-01 -2.69573271e-01 -5.63202858e-01 7.81103432e-01 -2.69571990e-01 -5.60391068e-01 7.83122599e-01 -2.69572675e-01 -5.57657421e-01 7.85072029e-01 -2.69572407e-01 -5.54893613e-01 7.87028611e-01 -2.69572496e-01 -5.52207530e-01 7.88910329e-01 -2.69573331e-01 -5.49475491e-01 7.90819108e-01 -2.69572139e-01 -5.46696424e-01 7.92742074e-01 -2.69573420e-01 -5.43949187e-01 7.94634700e-01 -2.69571990e-01 -5.41050792e-01 7.96605289e-01 -2.69572884e-01 -5.38268268e-01 7.98488021e-01 -2.69573122e-01 -5.35585821e-01 8.00287485e-01 -2.69573301e-01 -5.32773852e-01 8.02166760e-01 -2.69571990e-01 -5.29865623e-01 8.04090381e-01 -2.69572526e-01 -5.27132988e-01 8.05878162e-01 -2.69573808e-01 -5.24349868e-01 8.07699323e-01 -2.69572079e-01 -5.21498144e-01 8.09537888e-01 -2.69573510e-01 -5.18686652e-01 8.11347485e-01 -2.69571990e-01 -5.15763819e-01 8.13206553e-01 -2.69572586e-01 -5.12913167e-01 8.15008461e-01 -2.69572407e-01 -5.10148644e-01 8.16738963e-01 -2.69573241e-01 -5.07314146e-01 8.18510830e-01 -2.69571990e-01 -5.04377127e-01 8.20315182e-01 -2.69573420e-01 -5.01547694e-01 8.22050393e-01 -2.69573033e-01 -4.98676002e-01 8.23798358e-01 -2.69571990e-01 -4.95816648e-01 8.25518608e-01 -2.69573271e-01 -4.92967218e-01 8.27225983e-01 -2.69572139e-01 -4.90059286e-01 8.28947365e-01 -2.69573212e-01 -4.87241238e-01 8.30611527e-01 -2.69572526e-01 -4.84289140e-01 8.32337201e-01 -2.69572139e-01 -4.81304437e-01 8.34065557e-01 -2.69572526e-01 -4.78382498e-01 8.35744262e-01 -2.69572407e-01 -4.75465626e-01 8.37406516e-01 -2.69572586e-01 -4.72545415e-01 8.39060247e-01 -2.69572526e-01 -4.69613612e-01 8.40703130e-01 -2.69572347e-01 -4.66658950e-01 8.42344463e-01 -2.69572467e-01 -4.63773251e-01 8.43937755e-01 -2.69573361e-01 -4.60848391e-01 8.45542431e-01 -2.69571990e-01 -4.57825631e-01 8.47178996e-01 -2.69572407e-01 -4.54857945e-01 8.48777473e-01 -2.69572467e-01 -4.51898336e-01 8.50356400e-01 -2.69572526e-01 -4.48992550e-01 8.51893008e-01 -2.69573212e-01 -4.46010172e-01 8.53460133e-01 -2.69572139e-01 -4.42957968e-01 8.55047762e-01 -2.69572347e-01 -4.39968228e-01 8.56590331e-01 -2.69572526e-01 -4.37076241e-01 8.58065665e-01 -2.69573510e-01 -4.34103906e-01 8.59578550e-01 -2.69571990e-01 -4.31006998e-01 8.61133754e-01 -2.69572526e-01 -4.27997380e-01 8.62632692e-01 -2.69572467e-01 -4.24975127e-01 8.64126444e-01 -2.69572526e-01 -4.22021866e-01 8.65572512e-01 -2.69573301e-01 -4.19025332e-01 8.67030621e-01 -2.69572139e-01 -4.15965080e-01 8.68496239e-01 -2.69573182e-01 -4.12951171e-01 8.69937599e-01 -2.69572139e-01 -4.09834325e-01 8.71409059e-01 -2.69572496e-01 -4.06851709e-01 8.72804105e-01 -2.69573241e-01 -4.03811574e-01 8.74218822e-01 -2.69572139e-01 -4.00747746e-01 8.75621617e-01 -2.69573212e-01 -3.97699147e-01 8.77016723e-01 -2.69571990e-01 -3.94569248e-01 8.78428161e-01 -2.69572407e-01 -3.91483128e-01 8.79807234e-01 -2.69572645e-01 -3.88492972e-01 8.81129622e-01 -2.69573390e-01 -3.85465145e-01 8.82461607e-01 -2.69572318e-01 -3.82307619e-01 8.83833945e-01 -2.69572169e-01 -3.79173696e-01 8.85177791e-01 -2.69572467e-01 -3.76173347e-01 8.86457860e-01 -2.69573331e-01 -3.73166770e-01 8.87728751e-01 -2.69572586e-01 -3.69991302e-01 8.89059961e-01 -2.69571990e-01 -3.66831541e-01 8.90365064e-01 -2.69572914e-01 -3.63749951e-01 8.91629517e-01 -2.69572318e-01 -3.60662580e-01 8.92881513e-01 -2.69573241e-01 -3.57551038e-01 8.94134462e-01 -2.69572109e-01 -3.54367852e-01 8.95400167e-01 -2.69572645e-01 -3.51241380e-01 8.96632552e-01 -2.69572407e-01 -3.48098367e-01 8.97851408e-01 -2.69572526e-01 -3.45018804e-01 8.99046183e-01 -2.69573152e-01 -3.41878682e-01 9.00243759e-01 -2.69571990e-01 -3.38740319e-01 9.01418030e-01 -2.69573301e-01 -3.35594296e-01 9.02597785e-01 -2.69572109e-01 -3.32375675e-01 9.03789699e-01 -2.69572526e-01 -3.29283357e-01 9.04926360e-01 -2.69573301e-01 -3.26127559e-01 9.06070530e-01 -2.69571990e-01 -3.22931319e-01 9.07212019e-01 -2.69573063e-01 -3.19777191e-01 9.08330023e-01 -2.69572228e-01 -3.16559881e-01 9.09454644e-01 -2.69572556e-01 -3.13381702e-01 9.10555780e-01 -2.69572437e-01 -3.10274512e-01 9.11615789e-01 -2.69573152e-01 -3.07081729e-01 9.12700593e-01 -2.69572139e-01 -3.03836852e-01 9.13783133e-01 -2.69572794e-01 -3.00648153e-01 9.14837778e-01 -2.69572496e-01 -2.97514945e-01 9.15859282e-01 -2.69573361e-01 -2.94313639e-01 9.16896999e-01 -2.69572318e-01 -2.91058272e-01 9.17933345e-01 -2.69572705e-01 -2.87860036e-01 9.18943226e-01 -2.69572467e-01 -2.84654826e-01 9.19940472e-01 -2.69572616e-01 -2.81515390e-01 9.20903683e-01 -2.69573480e-01 -2.78272510e-01 9.21890140e-01 -2.69572139e-01 -2.74960101e-01 9.22883868e-01 -2.69572496e-01 -2.71743655e-01 9.23836708e-01 -2.69572616e-01 -2.68509358e-01 9.24782813e-01 -2.69572347e-01 -2.65375912e-01 9.25682068e-01 -2.69573659e-01 -2.62166560e-01 9.26601946e-01 -2.69571990e-01 -2.58916318e-01 9.27512765e-01 -2.69573480e-01 -2.55793393e-01 9.28379178e-01 -2.69572526e-01 -2.52428979e-01 9.29303288e-01 -2.69571990e-01 -2.49077022e-01 9.30202305e-01 -2.69572645e-01 -2.45827019e-01 9.31068063e-01 -2.69572467e-01 -2.42582694e-01 9.31917965e-01 -2.69572884e-01 -2.39440113e-01 9.32727754e-01 -2.69573599e-01 -2.36161172e-01 9.33566153e-01 -2.69571990e-01 -2.32795939e-01 9.34410036e-01 -2.69572526e-01 -2.29524583e-01 9.35219884e-01 -2.69572705e-01 -2.26261541e-01 9.36017036e-01 -2.69572586e-01 -2.23089680e-01 9.36775386e-01 -2.69573599e-01 -2.19832927e-01 9.37549472e-01 -2.69571990e-01 -2.16546342e-01 9.38308954e-01 -2.69573271e-01 -2.13268280e-01 9.39062178e-01 -2.69571990e-01 -2.09897056e-01 9.39820945e-01 -2.69572645e-01 -2.06615731e-01 9.40544724e-01 -2.69572526e-01 -2.03330413e-01 9.41261172e-01 -2.69572496e-01 -2.00134933e-01 9.41943765e-01 -2.69573510e-01 -1.96864009e-01 9.42639351e-01 -2.69572049e-01 -1.93461135e-01 9.43341672e-01 -2.69572467e-01 -1.90186396e-01 9.44005132e-01 -2.69572645e-01 -1.86889857e-01 9.44663644e-01 -2.69572347e-01 -1.83656141e-01 9.45296407e-01 -2.69573301e-01 -1.80358842e-01 9.45934474e-01 -2.69571990e-01 -1.77049324e-01 9.46554601e-01 -2.69573480e-01 -1.73835397e-01 9.47151601e-01 -2.69572437e-01 -1.70433208e-01 9.47777033e-01 -2.69571990e-01 -1.67022064e-01 9.48382378e-01 -2.69572645e-01 -1.63723111e-01 9.48953092e-01 -2.69572526e-01 -1.60415173e-01 9.49518979e-01 -2.69572526e-01 -1.57182992e-01 9.50056434e-01 -2.69573420e-01 -1.53962031e-01 9.50584531e-01 -2.69572645e-01 -1.50564209e-01 9.51131463e-01 -2.69572139e-01 -1.47127464e-01 9.51669574e-01 -2.69572288e-01 -1.43795475e-01 9.52175260e-01 -2.69572467e-01 -1.40464067e-01 9.52674568e-01 -2.69572437e-01 -1.37144074e-01 9.53156471e-01 -2.69572586e-01 -1.33928657e-01 9.53611851e-01 -2.69573569e-01 -1.30604059e-01 9.54079628e-01 -2.69571990e-01 -1.27156645e-01 9.54541028e-01 -2.69572526e-01 -1.23930730e-01 9.54962075e-01 -2.69573450e-01 -1.20612778e-01 9.55391884e-01 -2.69572139e-01 -1.17266878e-01 9.55804050e-01 -2.69573450e-01 -1.13911711e-01 9.56215262e-01 -2.69571990e-01 -1.10472843e-01 9.56615984e-01 -2.69572467e-01 -1.07133962e-01 9.56993997e-01 -2.69572705e-01 -1.03786901e-01 9.57363725e-01 -2.69572467e-01 -1.00438274e-01 9.57719505e-01 -2.69572765e-01 -9.71000567e-02 9.58064795e-01 -2.69572407e-01 -9.38388705e-02 9.58388746e-01 -2.69573301e-01 -9.06049460e-02 9.58702445e-01 -2.69572526e-01 -8.71604830e-02 9.59022403e-01 -2.69571990e-01 -8.37174729e-02 9.59328413e-01 -2.69572437e-01 -8.03638697e-02 9.59614635e-01 -2.69572407e-01 -7.70003125e-02 9.59890366e-01 -2.69572407e-01 -7.37408549e-02 9.60142195e-01 -2.69573480e-01 -7.04004765e-02 9.60399389e-01 -2.69571990e-01 -6.69295713e-02 9.60642993e-01 -2.69572616e-01 -6.35734349e-02 9.60872948e-01 -2.69572526e-01 -6.02408648e-02 9.61085916e-01 -2.69572526e-01 -5.69890402e-02 9.61283386e-01 -2.69573331e-01 -5.36380708e-02 9.61482048e-01 -2.69571990e-01 -5.02428263e-02 9.61657405e-01 -2.69573241e-01 -4.69087400e-02 9.61834252e-01 -2.69572020e-01 -4.34643142e-02 9.61990893e-01 -2.69572526e-01 -4.01126184e-02 9.62137759e-01 -2.69572467e-01 -3.67447808e-02 9.62270796e-01 -2.69572526e-01 -3.34719345e-02 9.62389588e-01 -2.69573241e-01 -3.01268715e-02 9.62502658e-01 -2.69571990e-01 -2.67416071e-02 9.62599754e-01 -2.69573331e-01 -2.33931560e-02 9.62694466e-01 -2.69572079e-01 -1.99457798e-02 9.62762833e-01 -2.69572437e-01 -1.66660510e-02 9.62831438e-01 -2.69573390e-01 -1.33189335e-02 9.62877691e-01 -2.69572079e-01 -9.94992536e-03 9.62920666e-01 -2.69573331e-01 -6.67896122e-03 9.62956905e-01 -2.69572467e-01 -3.23252613e-03 9.62974727e-01 -2.69571990e-01 2.20955131e-04 9.62974072e-01 -2.69572467e-01 3.57347517e-03 9.62972403e-01 -2.69572586e-01 6.91785477e-03 9.62954402e-01 -2.69572526e-01 1.02037368e-02 9.62916911e-01 -2.69573390e-01 1.34664252e-02 9.62874413e-01 -2.69572467e-01 1.69160217e-02 9.62832987e-01 -2.69572139e-01 2.03823596e-02 9.62755740e-01 -2.69572467e-01 2.37623081e-02 9.62680697e-01 -2.69572496e-01 2.71282624e-02 9.62594271e-01 -2.69572437e-01 3.04928198e-02 9.62491691e-01 -2.69572467e-01 3.37600932e-02 9.62380350e-01 -2.69573599e-01 3.70864943e-02 9.62261558e-01 -2.69571990e-01 4.05658372e-02 9.62120354e-01 -2.69572407e-01 4.39352319e-02 9.61970150e-01 -2.69572675e-01 4.72772717e-02 9.61812913e-01 -2.69572467e-01 5.05555309e-02 9.61640477e-01 -2.69573361e-01 5.38886748e-02 9.61466432e-01 -2.69571990e-01 5.72716072e-02 9.61265445e-01 -2.69573629e-01 6.06049411e-02 9.61064219e-01 -2.69571990e-01 6.40604571e-02 9.60840285e-01 -2.69572467e-01 6.74095675e-02 9.60609853e-01 -2.69572496e-01 7.07479343e-02 9.60371971e-01 -2.69572526e-01 7.41130710e-02 9.60116923e-01 -2.69572407e-01 7.73920715e-02 9.59855795e-01 -2.69573420e-01 8.07067528e-02 9.59586978e-01 -2.69572139e-01 8.41425732e-02 9.59291160e-01 -2.69572437e-01 8.75175744e-02 9.58988011e-01 -2.69572467e-01 9.08565596e-02 9.58678067e-01 -2.69572586e-01 9.41338614e-02 9.58359897e-01 -2.69573420e-01 9.74599272e-02 9.58030701e-01 -2.69571990e-01 1.00812592e-01 9.57680523e-01 -2.69573271e-01 1.04149632e-01 9.57328498e-01 -2.69571990e-01 1.07585669e-01 9.56943870e-01 -2.69572467e-01 1.10841610e-01 9.56570208e-01 -2.69573390e-01 1.14167348e-01 9.56183612e-01 -2.69571990e-01 1.17504902e-01 9.55775321e-01 -2.69573271e-01 1.20839350e-01 9.55363691e-01 -2.69572139e-01 1.24258161e-01 9.54921424e-01 -2.69572526e-01 1.27598584e-01 9.54481602e-01 -2.69572705e-01 1.30935147e-01 9.54032063e-01 -2.69572407e-01 1.34154171e-01 9.53583062e-01 -2.69573152e-01 1.37500837e-01 9.53106701e-01 -2.69572139e-01 1.40823856e-01 9.52618361e-01 -2.69573331e-01 1.44137457e-01 9.52124953e-01 -2.69572049e-01 1.47556648e-01 9.51602161e-01 -2.69572526e-01 1.50804430e-01 9.51088548e-01 -2.69573301e-01 1.54100254e-01 9.50564921e-01 -2.69572139e-01 1.57430455e-01 9.50017571e-01 -2.69573271e-01 1.60648361e-01 9.49479282e-01 -2.69572407e-01 1.64040610e-01 9.48900461e-01 -2.69571990e-01 1.67450607e-01 9.48307097e-01 -2.69572526e-01 1.70760185e-01 9.47717071e-01 -2.69572407e-01 1.74074322e-01 9.47109282e-01 -2.69572467e-01 1.77292794e-01 9.46509778e-01 -2.69573450e-01 1.80498615e-01 9.45906341e-01 -2.69572407e-01 1.83812574e-01 9.45267260e-01 -2.69572556e-01 1.87176034e-01 9.44608629e-01 -2.69571990e-01 1.90556049e-01 9.43931222e-01 -2.69572467e-01 1.93863586e-01 9.43257809e-01 -2.69572467e-01 1.97162434e-01 9.42572653e-01 -2.69572407e-01 2.00361431e-01 9.41897392e-01 -2.69573420e-01 2.03626767e-01 9.41199422e-01 -2.69571990e-01 2.07012177e-01 9.40459371e-01 -2.69572407e-01 2.10314497e-01 9.39727724e-01 -2.69572467e-01 2.13605821e-01 9.38983321e-01 -2.69572407e-01 2.16792211e-01 9.38250661e-01 -2.69573480e-01 2.20038727e-01 9.37502801e-01 -2.69571990e-01 2.23328024e-01 9.36717629e-01 -2.69573510e-01 2.26492301e-01 9.35962260e-01 -2.69572407e-01 2.29850262e-01 9.35143054e-01 -2.69571990e-01 2.33215928e-01 9.34305072e-01 -2.69572586e-01 2.36446381e-01 9.33492064e-01 -2.69572824e-01 2.39689842e-01 9.32667434e-01 -2.69572467e-01 2.42878303e-01 9.31839287e-01 -2.69573420e-01 2.46041045e-01 9.31012928e-01 -2.69572228e-01 2.49396831e-01 9.30120051e-01 -2.69571990e-01 2.52748132e-01 9.29216027e-01 -2.69572228e-01 2.55953342e-01 9.28333282e-01 -2.69572556e-01 2.59115517e-01 9.27456975e-01 -2.69573450e-01 2.62335092e-01 9.26553905e-01 -2.69572139e-01 2.65575767e-01 9.25627410e-01 -2.69573301e-01 2.68792301e-01 9.24702168e-01 -2.69571990e-01 2.72118539e-01 9.23727036e-01 -2.69572347e-01 2.75275379e-01 9.22789812e-01 -2.69573420e-01 2.78482854e-01 9.21827435e-01 -2.69571990e-01 2.81715125e-01 9.20842707e-01 -2.69573241e-01 2.84867227e-01 9.19876933e-01 -2.69572228e-01 2.88179010e-01 9.18844223e-01 -2.69572228e-01 2.91332036e-01 9.17843938e-01 -2.69573539e-01 2.94522822e-01 9.16831493e-01 -2.69571990e-01 2.97743410e-01 9.15785849e-01 -2.69573301e-01 3.00927848e-01 9.14748311e-01 -2.69572049e-01 3.04124922e-01 9.13686156e-01 -2.69573390e-01 3.07212800e-01 9.12655592e-01 -2.69572586e-01 3.10489088e-01 9.11548018e-01 -2.69571990e-01 3.13754290e-01 9.10426319e-01 -2.69572526e-01 3.16904515e-01 9.09334421e-01 -2.69572586e-01 3.20071220e-01 9.08225060e-01 -2.69572586e-01 3.23183626e-01 9.07121897e-01 -2.69573301e-01 3.26320022e-01 9.06000972e-01 -2.69571990e-01 3.29577804e-01 9.04819489e-01 -2.69572407e-01 3.32732230e-01 9.03656960e-01 -2.69572705e-01 3.35872948e-01 9.02492046e-01 -2.69572467e-01 3.38968843e-01 9.01332498e-01 -2.69573241e-01 3.42098653e-01 9.00159538e-01 -2.69572139e-01 3.45231622e-01 8.98965716e-01 -2.69573331e-01 3.48361135e-01 8.97754431e-01 -2.69571990e-01 3.51563752e-01 8.96504760e-01 -2.69572526e-01 3.54627192e-01 8.95295560e-01 -2.69573122e-01 3.57742041e-01 8.94057572e-01 -2.69572139e-01 3.60853344e-01 8.92803729e-01 -2.69573271e-01 3.63955587e-01 8.91547680e-01 -2.69572139e-01 3.67069572e-01 8.90265524e-01 -2.69573122e-01 3.70165646e-01 8.88986111e-01 -2.69572139e-01 3.73344064e-01 8.87655139e-01 -2.69572407e-01 3.76363367e-01 8.86376202e-01 -2.69573271e-01 3.79446030e-01 8.85062337e-01 -2.69572139e-01 3.82550925e-01 8.83723259e-01 -2.69573301e-01 3.85546327e-01 8.82426202e-01 -2.69572556e-01 3.88694882e-01 8.81044030e-01 -2.69572079e-01 3.91830802e-01 8.79651070e-01 -2.69572705e-01 3.94900560e-01 8.78278315e-01 -2.69572407e-01 3.97976846e-01 8.76888216e-01 -2.69572526e-01 4.00964230e-01 8.75521958e-01 -2.69573241e-01 4.03934300e-01 8.74158800e-01 -2.69572467e-01 4.07051682e-01 8.72713983e-01 -2.69571990e-01 4.10155714e-01 8.71256351e-01 -2.69572526e-01 4.13192034e-01 8.69822562e-01 -2.69572407e-01 4.16167974e-01 8.68398249e-01 -2.69573182e-01 4.19186056e-01 8.66952956e-01 -2.69572228e-01 4.22210097e-01 8.65482092e-01 -2.69573092e-01 4.25226182e-01 8.64003658e-01 -2.69571990e-01 4.28322136e-01 8.62472117e-01 -2.69572467e-01 4.31337059e-01 8.60969245e-01 -2.69572288e-01 4.34313267e-01 8.59472573e-01 -2.69572407e-01 4.37262297e-01 8.57972383e-01 -2.69573510e-01 4.40224022e-01 8.56459916e-01 -2.69572228e-01 4.43235487e-01 8.54900479e-01 -2.69573122e-01 4.46158379e-01 8.53383243e-01 -2.69572407e-01 4.49197441e-01 8.51788640e-01 -2.69571990e-01 4.52216387e-01 8.50186050e-01 -2.69572735e-01 4.55175936e-01 8.48608136e-01 -2.69572318e-01 4.58158553e-01 8.46999526e-01 -2.69572437e-01 4.61029500e-01 8.45441282e-01 -2.69573301e-01 4.63980526e-01 8.43829036e-01 -2.69571990e-01 4.67018276e-01 8.42146099e-01 -2.69572318e-01 4.69959438e-01 8.40508580e-01 -2.69572526e-01 4.72884834e-01 8.38867128e-01 -2.69572616e-01 4.75713164e-01 8.37263405e-01 -2.69573420e-01 4.78645176e-01 8.35596561e-01 -2.69571990e-01 4.81556833e-01 8.33917081e-01 -2.69573450e-01 4.84460205e-01 8.32239151e-01 -2.69571990e-01 4.87451047e-01 8.30489874e-01 -2.69572228e-01 4.90275234e-01 8.28821242e-01 -2.69573241e-01 4.93152767e-01 8.27117920e-01 -2.69571990e-01 4.96035725e-01 8.25387120e-01 -2.69573241e-01 4.98906136e-01 8.23656917e-01 -2.69572139e-01 5.01839876e-01 8.21874440e-01 -2.69572496e-01 5.04643857e-01 8.20151389e-01 -2.69573122e-01 5.07512927e-01 8.18386734e-01 -2.69571990e-01 5.10366499e-01 8.16604137e-01 -2.69573212e-01 5.13188958e-01 8.14836502e-01 -2.69572139e-01 5.16057491e-01 8.13018322e-01 -2.69573182e-01 5.18878043e-01 8.11223924e-01 -2.69572139e-01 5.21781683e-01 8.09357822e-01 -2.69572318e-01 5.24542511e-01 8.07570279e-01 -2.69573182e-01 5.27337611e-01 8.05750191e-01 -2.69572109e-01 5.30151248e-01 8.03898990e-01 -2.69573301e-01 5.32870173e-01 8.02099407e-01 -2.69572526e-01 5.35760939e-01 8.00175726e-01 -2.69572109e-01 5.38546622e-01 7.98301935e-01 -2.69573301e-01 5.41326106e-01 7.96420753e-01 -2.69571990e-01 5.44200122e-01 7.94458032e-01 -2.69572586e-01 5.46880782e-01 7.92613149e-01 -2.69573778e-01 5.49547732e-01 7.90767908e-01 -2.69572765e-01 5.52294672e-01 7.88849711e-01 -2.69572794e-01 5.55141687e-01 7.86856472e-01 -2.69572318e-01 5.57957649e-01 7.84855723e-01 -2.69572705e-01 5.60615599e-01 7.82958269e-01 -2.69573778e-01 5.63351572e-01 7.80994654e-01 -2.69572407e-01 5.65942943e-01 7.79115200e-01 -2.69576311e-01 5.68774283e-01 7.77060211e-01 -2.69576311e-01 5.70882082e-01 7.75515258e-01 -2.69575208e-01 5.73814631e-01 7.73347080e-01 -2.69575357e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.84190154e-01 6.77651405e-01 -2.69575208e-01 6.85931444e-01 6.75893605e-01 -2.69576222e-01 6.88163817e-01 6.73606753e-01 -2.69576311e-01 6.90387547e-01 6.71331644e-01 -2.69573569e-01 6.92850292e-01 6.68782055e-01 -2.69574702e-01 6.95108294e-01 6.66436315e-01 -2.69572139e-01 6.97499871e-01 6.63940132e-01 -2.69572705e-01 6.99732304e-01 6.61578834e-01 -2.69573331e-01 7.02039599e-01 6.59135461e-01 -2.69571990e-01 7.04395473e-01 6.56614065e-01 -2.69572645e-01 7.06651330e-01 6.54187679e-01 -2.69572765e-01 7.08877981e-01 6.51776671e-01 -2.69572765e-01 7.11113870e-01 6.49333000e-01 -2.69572526e-01 7.13449121e-01 6.46773040e-01 -2.69571990e-01 7.15748727e-01 6.44222915e-01 -2.69572467e-01 7.17987299e-01 6.41725361e-01 -2.69572467e-01 7.20170498e-01 6.39274120e-01 -2.69573301e-01 7.22343564e-01 6.36819661e-01 -2.69572467e-01 7.24586070e-01 6.34264350e-01 -2.69572228e-01 7.26832807e-01 6.31690502e-01 -2.69572407e-01 7.29062796e-01 6.29117250e-01 -2.69572139e-01 7.31260598e-01 6.26558781e-01 -2.69572765e-01 7.33378112e-01 6.24074340e-01 -2.69573301e-01 7.35533834e-01 6.21538937e-01 -2.69572318e-01 7.37708509e-01 6.18954301e-01 -2.69572526e-01 7.39897966e-01 6.16339862e-01 -2.69572049e-01 7.42104471e-01 6.13675594e-01 -2.69572407e-01 7.44192541e-01 6.11141503e-01 -2.69573241e-01 7.46305823e-01 6.08562112e-01 -2.69572139e-01 7.48466015e-01 6.05901599e-01 -2.69572437e-01 7.50592887e-01 6.03266537e-01 -2.69572228e-01 7.52650619e-01 6.00694060e-01 -2.69573241e-01 7.54678965e-01 5.98147333e-01 -2.69572407e-01 7.56819785e-01 5.95440686e-01 -2.69571990e-01 7.58944571e-01 5.92723608e-01 -2.69572467e-01 7.61017680e-01 5.90062618e-01 -2.69572228e-01 7.63025522e-01 5.87456048e-01 -2.69573659e-01 7.65001953e-01 5.84885299e-01 -2.69572437e-01 7.67094970e-01 5.82142830e-01 -2.69571990e-01 7.69174278e-01 5.79386950e-01 -2.69572586e-01 7.71194279e-01 5.76694548e-01 -2.69572228e-01 7.73160458e-01 5.74054182e-01 -2.69573331e-01 7.75092065e-01 5.71443796e-01 -2.69572526e-01 7.77130723e-01 5.68673193e-01 -2.69571990e-01 7.79171526e-01 5.65871596e-01 -2.69572228e-01 7.81156480e-01 5.63123405e-01 -2.69572467e-01 7.83113360e-01 5.60403705e-01 -2.69572526e-01 7.84998715e-01 5.57756722e-01 -2.69573450e-01 7.86889136e-01 5.55092931e-01 -2.69572407e-01 7.88830817e-01 5.52327454e-01 -2.69572467e-01 7.90810049e-01 5.49491704e-01 -2.69571990e-01 7.92747438e-01 5.46686351e-01 -2.69573510e-01 7.94584274e-01 5.44016242e-01 -2.69572467e-01 7.96537638e-01 5.41157603e-01 -2.69571990e-01 7.98421502e-01 5.38364053e-01 -2.69573569e-01 8.00261140e-01 5.35631001e-01 -2.69572139e-01 8.02129865e-01 5.32826185e-01 -2.69572824e-01 8.03954482e-01 5.30071437e-01 -2.69572407e-01 8.05849910e-01 5.27186096e-01 -2.69572139e-01 8.07739496e-01 5.24284780e-01 -2.69572318e-01 8.09518754e-01 5.21528482e-01 -2.69573450e-01 8.11279297e-01 5.18791199e-01 -2.69572675e-01 8.13074768e-01 5.15972257e-01 -2.69572139e-01 8.14947963e-01 5.13015866e-01 -2.69571990e-01 8.16787958e-01 5.10074496e-01 -2.69572228e-01 8.18556607e-01 5.07230997e-01 -2.69572973e-01 8.20263565e-01 5.04460037e-01 -2.69573182e-01 8.21984589e-01 5.01659095e-01 -2.69572467e-01 8.23734879e-01 4.98778045e-01 -2.69572318e-01 8.25469136e-01 4.95901883e-01 -2.69572645e-01 8.27238798e-01 4.92947757e-01 -2.69571990e-01 8.29002798e-01 4.89971697e-01 -2.69572467e-01 8.30664456e-01 4.87146080e-01 -2.69573271e-01 8.32352340e-01 4.84265208e-01 -2.69571990e-01 8.34042430e-01 4.81342435e-01 -2.69573301e-01 8.35714996e-01 4.78437304e-01 -2.69571990e-01 8.37404430e-01 4.75465238e-01 -2.69572794e-01 8.39013696e-01 4.72625345e-01 -2.69573063e-01 8.40674520e-01 4.69666660e-01 -2.69571990e-01 8.42311323e-01 4.66715902e-01 -2.69572973e-01 8.43935609e-01 4.63782668e-01 -2.69572139e-01 8.45545948e-01 4.60834831e-01 -2.69573182e-01 8.47113431e-01 4.57949400e-01 -2.69572407e-01 8.48743081e-01 4.54925537e-01 -2.69571990e-01 8.50373387e-01 4.51868981e-01 -2.69572228e-01 8.51948798e-01 4.48888481e-01 -2.69572526e-01 8.53466511e-01 4.45993423e-01 -2.69573271e-01 8.54969740e-01 4.43107516e-01 -2.69572616e-01 8.56552362e-01 4.40047115e-01 -2.69571990e-01 8.58126283e-01 4.36965972e-01 -2.69572318e-01 8.59641433e-01 4.33976531e-01 -2.69572556e-01 8.61159325e-01 4.30958033e-01 -2.69572318e-01 8.62626791e-01 4.28003609e-01 -2.69573510e-01 8.64101827e-01 4.25029635e-01 -2.69571990e-01 8.65587652e-01 4.21990693e-01 -2.69573301e-01 8.67053032e-01 4.18979526e-01 -2.69571990e-01 8.68552148e-01 4.15854394e-01 -2.69572467e-01 8.69954348e-01 4.12908256e-01 -2.69573301e-01 8.71380031e-01 4.09899384e-01 -2.69571990e-01 8.72815490e-01 4.06828463e-01 -2.69573241e-01 8.74229550e-01 4.03791398e-01 -2.69571990e-01 8.75672162e-01 4.00643408e-01 -2.69572437e-01 8.77029419e-01 3.97657692e-01 -2.69573510e-01 8.78403008e-01 3.94627690e-01 -2.69571990e-01 8.79781902e-01 3.91534626e-01 -2.69573271e-01 8.81145298e-01 3.88467431e-01 -2.69571990e-01 8.82497787e-01 3.85374725e-01 -2.69573271e-01 8.83803129e-01 3.82375777e-01 -2.69572467e-01 8.85166883e-01 3.79205525e-01 -2.69571990e-01 8.86518896e-01 3.76032263e-01 -2.69572586e-01 8.87821198e-01 3.72948825e-01 -2.69572467e-01 8.89082968e-01 3.69925529e-01 -2.69573241e-01 8.90333831e-01 3.66907656e-01 -2.69572407e-01 8.91642869e-01 3.63722146e-01 -2.69571990e-01 8.92952383e-01 3.60495359e-01 -2.69572318e-01 8.94207537e-01 3.57364774e-01 -2.69572467e-01 8.95413399e-01 3.54332417e-01 -2.69573331e-01 8.96603703e-01 3.51316810e-01 -2.69572526e-01 8.97849560e-01 3.48111242e-01 -2.69571990e-01 8.99074078e-01 3.44946563e-01 -2.69573182e-01 9.00259614e-01 3.41833025e-01 -2.69572020e-01 9.01484430e-01 3.38572919e-01 -2.69572318e-01 9.02626693e-01 3.35503340e-01 -2.69573241e-01 9.03794765e-01 3.32372755e-01 -2.69571990e-01 9.04955745e-01 3.29200178e-01 -2.69573390e-01 9.06093001e-01 3.26066315e-01 -2.69571990e-01 9.07256663e-01 3.22808653e-01 -2.69572467e-01 9.08352017e-01 3.19708884e-01 -2.69573122e-01 9.09454525e-01 3.16567093e-01 -2.69571990e-01 9.10579920e-01 3.13310385e-01 -2.69572467e-01 9.11656141e-01 3.10160488e-01 -2.69572586e-01 9.12719846e-01 3.07018161e-01 -2.69573003e-01 9.13762391e-01 3.03900331e-01 -2.69572526e-01 9.14843738e-01 3.00640523e-01 -2.69571990e-01 9.15907979e-01 2.97373503e-01 -2.69572526e-01 9.16940570e-01 2.94177294e-01 -2.69572407e-01 9.17939484e-01 2.91036725e-01 -2.69573390e-01 9.18920219e-01 2.87933052e-01 -2.69572407e-01 9.19948697e-01 2.84632355e-01 -2.69571990e-01 9.20965910e-01 2.81317145e-01 -2.69572407e-01 9.21931505e-01 2.78135061e-01 -2.69572526e-01 9.22872841e-01 2.74987161e-01 -2.69573241e-01 9.23808336e-01 2.71842808e-01 -2.69572467e-01 9.24776137e-01 2.68545389e-01 -2.69571990e-01 9.25701857e-01 2.65308410e-01 -2.69573301e-01 9.26629663e-01 2.62071669e-01 -2.69571990e-01 9.27553356e-01 2.58771688e-01 -2.69572526e-01 9.28427696e-01 2.55610257e-01 -2.69573420e-01 9.29318488e-01 2.52372891e-01 -2.69571990e-01 9.30216789e-01 2.49023482e-01 -2.69572556e-01 9.31074023e-01 2.45806530e-01 -2.69572526e-01 9.31927621e-01 2.42551267e-01 -2.69572377e-01 9.32751000e-01 2.39358515e-01 -2.69573271e-01 9.33575869e-01 2.36122966e-01 -2.69571990e-01 9.34395850e-01 2.32851520e-01 -2.69573152e-01 9.35210407e-01 2.29583159e-01 -2.69571990e-01 9.36003029e-01 2.26310223e-01 -2.69573182e-01 9.36765909e-01 2.23139882e-01 -2.69572526e-01 9.37558889e-01 2.19796374e-01 -2.69571990e-01 9.38332856e-01 2.16443196e-01 -2.69572586e-01 9.39084947e-01 2.13167563e-01 -2.69572228e-01 9.39828873e-01 2.09865063e-01 -2.69572407e-01 9.40533102e-01 2.06662089e-01 -2.69573271e-01 9.41248834e-01 2.03396082e-01 -2.69571990e-01 9.41971779e-01 2.00017720e-01 -2.69572467e-01 9.42665815e-01 1.96729124e-01 -2.69572496e-01 9.43346024e-01 1.93441272e-01 -2.69572467e-01 9.43998039e-01 1.90219685e-01 -2.69573182e-01 9.44651246e-01 1.86956137e-01 -2.69571990e-01 9.45302308e-01 1.83629215e-01 -2.69573212e-01 9.45937037e-01 1.80343702e-01 -2.69571990e-01 9.46574390e-01 1.76961958e-01 -2.69572467e-01 9.47166562e-01 1.73740312e-01 -2.69573122e-01 9.47779596e-01 1.70425996e-01 -2.69571990e-01 9.48379278e-01 1.67042688e-01 -2.69572586e-01 9.48946953e-01 1.63757637e-01 -2.69572467e-01 9.49502468e-01 1.60501644e-01 -2.69573122e-01 9.50045109e-01 1.57267749e-01 -2.69572347e-01 9.50603127e-01 1.53867647e-01 -2.69571990e-01 9.51145947e-01 1.50461122e-01 -2.69572467e-01 9.51664984e-01 1.47142515e-01 -2.69572407e-01 9.52159524e-01 1.43894434e-01 -2.69573152e-01 9.52645838e-01 1.40661359e-01 -2.69572407e-01 9.53143239e-01 1.37257680e-01 -2.69571990e-01 9.53627348e-01 1.33846506e-01 -2.69572467e-01 9.54087853e-01 1.30528450e-01 -2.69572526e-01 9.54538822e-01 1.27189115e-01 -2.69572228e-01 9.54965234e-01 1.23912677e-01 -2.69573390e-01 9.55392599e-01 1.20613046e-01 -2.69572020e-01 9.55818892e-01 1.17169052e-01 -2.69572407e-01 9.56220448e-01 1.13838546e-01 -2.69572407e-01 9.56610978e-01 1.10512011e-01 -2.69572467e-01 9.56980228e-01 1.07253164e-01 -2.69573241e-01 9.57353413e-01 1.03901125e-01 -2.69571990e-01 9.57707703e-01 1.00550100e-01 -2.69573241e-01 9.58051324e-01 9.72388759e-02 -2.69571990e-01 9.58395481e-01 9.37848091e-02 -2.69572467e-01 9.58706260e-01 9.05356184e-02 -2.69573510e-01 9.59019780e-01 8.72025043e-02 -2.69571990e-01 9.59315538e-01 8.38452876e-02 -2.69573241e-01 9.59606707e-01 8.04772004e-02 -2.69571990e-01 9.59878922e-01 7.71149620e-02 -2.69573271e-01 9.60144341e-01 7.37921372e-02 -2.69571990e-01 9.60401356e-01 7.03379959e-02 -2.69572228e-01 9.60640907e-01 6.69630468e-02 -2.69572526e-01 9.60870206e-01 6.36157393e-02 -2.69572407e-01 9.61077511e-01 6.03454337e-02 -2.69573331e-01 9.61278200e-01 5.70913889e-02 -2.69572496e-01 9.61481214e-01 5.36496677e-02 -2.69571990e-01 9.61664617e-01 5.01865298e-02 -2.69572526e-01 9.61835325e-01 4.68318835e-02 -2.69572377e-01 9.61984456e-01 4.35650125e-02 -2.69573480e-01 9.62129414e-01 4.03275266e-02 -2.69572496e-01 9.62264001e-01 3.69588509e-02 -2.69572288e-01 9.62386787e-01 3.35921496e-02 -2.69572377e-01 9.62504625e-01 3.01203635e-02 -2.69571990e-01 9.62606013e-01 2.66489014e-02 -2.69572407e-01 9.62689638e-01 2.34062355e-02 -2.69573450e-01 9.62759137e-01 2.01595556e-02 -2.69572467e-01 9.62833285e-01 1.67835243e-02 -2.69572318e-01 9.62875009e-01 1.34161497e-02 -2.69572318e-01 9.62923586e-01 1.00388657e-02 -2.69572318e-01 9.62957382e-01 6.69184839e-03 -2.69572467e-01 9.62975502e-01 3.24237300e-03 -2.69571990e-01 9.62971807e-01 -1.29833832e-04 -2.69573331e-01 9.62975144e-01 -3.47408210e-03 -2.69571990e-01 9.62952852e-01 -6.86395355e-03 -2.69573271e-01 9.62922037e-01 -1.01218559e-02 -2.69572467e-01 9.62873936e-01 -1.35462983e-02 -2.69571990e-01 9.62829053e-01 -1.70192979e-02 -2.69572347e-01 9.62755442e-01 -2.02946942e-02 -2.69573122e-01 9.62687075e-01 -2.36626975e-02 -2.69571990e-01 9.62592304e-01 -2.70414930e-02 -2.69573450e-01 9.62496340e-01 -3.03726289e-02 -2.69572139e-01 9.62382019e-01 -3.37397903e-02 -2.69573063e-01 9.62261736e-01 -3.70175764e-02 -2.69572407e-01 9.62127686e-01 -4.03704122e-02 -2.69572437e-01 9.61979508e-01 -4.37877402e-02 -2.69571990e-01 9.61814582e-01 -4.72572818e-02 -2.69572526e-01 9.61640477e-01 -5.06112427e-02 -2.69572407e-01 9.61461544e-01 -5.39039560e-02 -2.69573182e-01 9.61275637e-01 -5.71525656e-02 -2.69572467e-01 9.61068988e-01 -6.05036318e-02 -2.69572407e-01 9.60850835e-01 -6.39395416e-02 -2.69571990e-01 9.60613191e-01 -6.73666745e-02 -2.69572526e-01 9.60374355e-01 -7.07176402e-02 -2.69572467e-01 9.60124135e-01 -7.40086585e-02 -2.69572943e-01 9.59866643e-01 -7.72891119e-02 -2.69572407e-01 9.59591508e-01 -8.06251019e-02 -2.69572467e-01 9.59300637e-01 -8.40540379e-02 -2.69571990e-01 9.58995819e-01 -8.74096379e-02 -2.69573331e-01 9.58696544e-01 -9.06704962e-02 -2.69572437e-01 9.58374321e-01 -9.40100849e-02 -2.69572318e-01 9.58031952e-01 -9.74482149e-02 -2.69571990e-01 9.57680643e-01 -1.00803025e-01 -2.69573331e-01 9.57330048e-01 -1.04115762e-01 -2.69571990e-01 9.56955969e-01 -1.07468247e-01 -2.69573480e-01 9.56589341e-01 -1.10696957e-01 -2.69572407e-01 9.56188142e-01 -1.14140145e-01 -2.69571990e-01 9.55779374e-01 -1.17474362e-01 -2.69573241e-01 9.55369711e-01 -1.20813146e-01 -2.69571990e-01 9.54923928e-01 -1.24243177e-01 -2.69572228e-01 9.54493046e-01 -1.27505377e-01 -2.69573241e-01 9.54051673e-01 -1.30800068e-01 -2.69571990e-01 9.53573465e-01 -1.34229869e-01 -2.69572228e-01 9.53106582e-01 -1.37487739e-01 -2.69573301e-01 9.52627301e-01 -1.40789196e-01 -2.69571990e-01 9.52126443e-01 -1.44114524e-01 -2.69573152e-01 9.51620817e-01 -1.47435784e-01 -2.69572020e-01 9.51093912e-01 -1.50779471e-01 -2.69573122e-01 9.50567961e-01 -1.54075146e-01 -2.69572139e-01 9.50030148e-01 -1.57353535e-01 -2.69572973e-01 9.49472785e-01 -1.60707429e-01 -2.69571990e-01 9.48885560e-01 -1.64104283e-01 -2.69572496e-01 9.48314548e-01 -1.67405888e-01 -2.69572467e-01 9.47735548e-01 -1.70641020e-01 -2.69573063e-01 9.47142839e-01 -1.73883632e-01 -2.69572407e-01 9.46532428e-01 -1.77194014e-01 -2.69572318e-01 9.45897818e-01 -1.80544168e-01 -2.69572139e-01 9.45244074e-01 -1.83931917e-01 -2.69572407e-01 9.44596052e-01 -1.87233374e-01 -2.69572467e-01 9.43949938e-01 -1.90458179e-01 -2.69573033e-01 9.43299472e-01 -1.93660438e-01 -2.69572526e-01 9.42621887e-01 -1.96940154e-01 -2.69572318e-01 9.41910625e-01 -2.00322255e-01 -2.69571990e-01 9.41198945e-01 -2.03617096e-01 -2.69573271e-01 9.40497220e-01 -2.06846729e-01 -2.69572139e-01 9.39766228e-01 -2.10137412e-01 -2.69572973e-01 9.39022720e-01 -2.13441744e-01 -2.69571990e-01 9.38265085e-01 -2.16733083e-01 -2.69573301e-01 9.37510073e-01 -2.20005989e-01 -2.69571990e-01 9.36727166e-01 -2.23293081e-01 -2.69573331e-01 9.35973883e-01 -2.26440519e-01 -2.69572467e-01 9.35157716e-01 -2.29788482e-01 -2.69571990e-01 9.34343159e-01 -2.33061403e-01 -2.69573122e-01 9.33519006e-01 -2.36352026e-01 -2.69571990e-01 9.32662904e-01 -2.39702120e-01 -2.69572496e-01 9.31845486e-01 -2.42853507e-01 -2.69573420e-01 9.31000113e-01 -2.46100962e-01 -2.69571990e-01 9.30127859e-01 -2.49353603e-01 -2.69573510e-01 9.29283857e-01 -2.52491564e-01 -2.69572467e-01 9.28375900e-01 -2.55812109e-01 -2.69571990e-01 9.27466333e-01 -2.59086877e-01 -2.69573092e-01 9.26561117e-01 -2.62308717e-01 -2.69572109e-01 9.25611496e-01 -2.65631497e-01 -2.69572228e-01 9.24702287e-01 -2.68773913e-01 -2.69573480e-01 9.23789144e-01 -2.71902442e-01 -2.69572407e-01 9.22811747e-01 -2.75211930e-01 -2.69572079e-01 9.21822309e-01 -2.78494120e-01 -2.69572556e-01 9.20847058e-01 -2.81709343e-01 -2.69572258e-01 9.19873297e-01 -2.84870714e-01 -2.69573122e-01 9.18902636e-01 -2.87987173e-01 -2.69572526e-01 9.17893231e-01 -2.91190505e-01 -2.69572407e-01 9.16846812e-01 -2.94471800e-01 -2.69571990e-01 9.15772974e-01 -2.97789425e-01 -2.69572318e-01 9.14727032e-01 -3.00985873e-01 -2.69572526e-01 9.13698912e-01 -3.04088801e-01 -2.69573212e-01 9.12667453e-01 -3.07175875e-01 -2.69572467e-01 9.11592364e-01 -3.10353637e-01 -2.69572467e-01 9.10477102e-01 -3.13611954e-01 -2.69571990e-01 9.09359276e-01 -3.16829205e-01 -2.69573003e-01 9.08281147e-01 -3.19911152e-01 -2.69572645e-01 9.07167971e-01 -3.23053867e-01 -2.69572467e-01 9.06010270e-01 -3.26296508e-01 -2.69571990e-01 9.04856145e-01 -3.29475254e-01 -2.69573182e-01 9.03701007e-01 -3.32626581e-01 -2.69571990e-01 9.02521312e-01 -3.35786909e-01 -2.69573241e-01 9.01382446e-01 -3.38843584e-01 -2.69572467e-01 9.00190532e-01 -3.42014015e-01 -2.69572228e-01 8.98991287e-01 -3.45164806e-01 -2.69572645e-01 8.97784233e-01 -3.48281354e-01 -2.69572377e-01 8.96543026e-01 -3.51477951e-01 -2.69571990e-01 8.95301640e-01 -3.54610294e-01 -2.69573361e-01 8.94073486e-01 -3.57705384e-01 -2.69571990e-01 8.92805994e-01 -3.60847056e-01 -2.69573331e-01 8.91583920e-01 -3.63863051e-01 -2.69572467e-01 8.90274107e-01 -3.67057920e-01 -2.69572049e-01 8.88976395e-01 -3.70184183e-01 -2.69573092e-01 8.87683988e-01 -3.73281986e-01 -2.69571990e-01 8.86334896e-01 -3.76465291e-01 -2.69572228e-01 8.85042548e-01 -3.79486710e-01 -2.69573301e-01 8.83769214e-01 -3.82452279e-01 -2.69572467e-01 8.82397592e-01 -3.85616302e-01 -2.69571990e-01 8.80989492e-01 -3.88816953e-01 -2.69572228e-01 8.79620194e-01 -3.91901493e-01 -2.69572556e-01 8.78264427e-01 -3.94930720e-01 -2.69572645e-01 8.76913190e-01 -3.97918075e-01 -2.69573241e-01 8.75553191e-01 -4.00899082e-01 -2.69572467e-01 8.74120831e-01 -4.04022783e-01 -2.69571990e-01 8.72659206e-01 -4.07161534e-01 -2.69572467e-01 8.71216714e-01 -4.10241693e-01 -2.69572318e-01 8.69820595e-01 -4.13188279e-01 -2.69573480e-01 8.68432760e-01 -4.16101545e-01 -2.69572407e-01 8.66968036e-01 -4.19151902e-01 -2.69572407e-01 8.65465343e-01 -4.22253609e-01 -2.69571990e-01 8.63947570e-01 -4.25336093e-01 -2.69572794e-01 8.62464249e-01 -4.28339481e-01 -2.69572139e-01 8.60981882e-01 -4.31303710e-01 -2.69573420e-01 8.59522939e-01 -4.34210360e-01 -2.69572586e-01 8.58002603e-01 -4.37208503e-01 -2.69572467e-01 8.56433153e-01 -4.40277874e-01 -2.69571990e-01 8.54870021e-01 -4.43296641e-01 -2.69572973e-01 8.53328645e-01 -4.46262270e-01 -2.69572198e-01 8.51778269e-01 -4.49209362e-01 -2.69573212e-01 8.50236416e-01 -4.52121377e-01 -2.69572467e-01 8.48656476e-01 -4.55083966e-01 -2.69572467e-01 8.47021937e-01 -4.58123624e-01 -2.69571990e-01 8.45404327e-01 -4.61095989e-01 -2.69573331e-01 8.43836904e-01 -4.63959932e-01 -2.69572407e-01 8.42212796e-01 -4.66898531e-01 -2.69572467e-01 8.40546608e-01 -4.69896346e-01 -2.69571990e-01 8.38890851e-01 -4.72839534e-01 -2.69573301e-01 8.37239623e-01 -4.75764513e-01 -2.69571990e-01 8.35572481e-01 -4.78680789e-01 -2.69573390e-01 8.33910346e-01 -4.81576473e-01 -2.69571990e-01 8.32208753e-01 -4.84504044e-01 -2.69573301e-01 8.30558598e-01 -4.87333834e-01 -2.69572437e-01 8.28826904e-01 -4.90272582e-01 -2.69572139e-01 8.27088356e-01 -4.93196607e-01 -2.69572526e-01 8.25352550e-01 -4.96099561e-01 -2.69572139e-01 8.23588669e-01 -4.99018252e-01 -2.69572318e-01 8.21876347e-01 -5.01832783e-01 -2.69573271e-01 8.20169449e-01 -5.04618347e-01 -2.69572437e-01 8.18411410e-01 -5.07467449e-01 -2.69572586e-01 8.16594362e-01 -5.10386705e-01 -2.69571990e-01 8.14763963e-01 -5.13301969e-01 -2.69572467e-01 8.13007474e-01 -5.16073763e-01 -2.69573152e-01 8.11242938e-01 -5.18846631e-01 -2.69572437e-01 8.09383392e-01 -5.21747708e-01 -2.69571990e-01 8.07510793e-01 -5.24638057e-01 -2.69572407e-01 8.05676699e-01 -5.27446806e-01 -2.69572586e-01 8.03836405e-01 -5.30252099e-01 -2.69572407e-01 8.02012026e-01 -5.32997906e-01 -2.69573331e-01 8.00196826e-01 -5.35724819e-01 -2.69572467e-01 7.98341095e-01 -5.38491189e-01 -2.69572526e-01 7.96400607e-01 -5.41357398e-01 -2.69571990e-01 7.94452786e-01 -5.44208825e-01 -2.69572794e-01 7.92575717e-01 -5.46941757e-01 -2.69572467e-01 7.90697455e-01 -5.49647510e-01 -2.69573152e-01 7.88779974e-01 -5.52401125e-01 -2.69572049e-01 7.86829889e-01 -5.55171072e-01 -2.69573271e-01 7.84887493e-01 -5.57919741e-01 -2.69571990e-01 7.82924592e-01 -5.60665131e-01 -2.69573390e-01 7.80988038e-01 -5.63360214e-01 -2.69572139e-01 7.78977573e-01 -5.66140056e-01 -2.69572228e-01 7.76973248e-01 -5.68884611e-01 -2.69572407e-01 7.74971724e-01 -5.71610749e-01 -2.69572228e-01 7.72958696e-01 -5.74326515e-01 -2.69572467e-01 7.71005511e-01 -5.76941788e-01 -2.69573480e-01 7.69005775e-01 -5.79614699e-01 -2.69571990e-01 7.66967416e-01 -5.82300901e-01 -2.69573480e-01 7.64933765e-01 -5.84978521e-01 -2.69571990e-01 7.62876749e-01 -5.87651014e-01 -2.69573420e-01 7.60889888e-01 -5.90223014e-01 -2.69572407e-01 7.58774459e-01 -5.92944264e-01 -2.69571990e-01 7.56639361e-01 -5.95663011e-01 -2.69572467e-01 7.54605770e-01 -5.98233402e-01 -2.69573182e-01 7.52572417e-01 -6.00794733e-01 -2.69572407e-01 7.50422180e-01 -6.03480875e-01 -2.69572139e-01 7.48257399e-01 -6.06161118e-01 -2.69572467e-01 7.46167004e-01 -6.08725190e-01 -2.69573122e-01 7.44103730e-01 -6.11251712e-01 -2.69572467e-01 7.41971493e-01 -6.13838375e-01 -2.69572526e-01 7.39833057e-01 -6.16414428e-01 -2.69572437e-01 7.37678647e-01 -6.18990242e-01 -2.69572467e-01 7.35460937e-01 -6.21625602e-01 -2.69571990e-01 7.33280182e-01 -6.24189496e-01 -2.69573122e-01 7.31155515e-01 -6.26681387e-01 -2.69572407e-01 7.28970408e-01 -6.29221857e-01 -2.69572586e-01 7.26746976e-01 -6.31792247e-01 -2.69572169e-01 7.24470079e-01 -6.34401321e-01 -2.69572139e-01 7.22213447e-01 -6.36965990e-01 -2.69572526e-01 7.20035255e-01 -6.39425814e-01 -2.69573241e-01 7.17872739e-01 -6.41855061e-01 -2.69572467e-01 7.15578079e-01 -6.44415498e-01 -2.69571990e-01 7.13318467e-01 -6.46910906e-01 -2.69573361e-01 7.11056292e-01 -6.49400711e-01 -2.69571990e-01 7.08775580e-01 -6.51883006e-01 -2.69573569e-01 7.06578553e-01 -6.54267788e-01 -2.69572496e-01 7.04290986e-01 -6.56727016e-01 -2.69572437e-01 7.01934099e-01 -6.59249723e-01 -2.69571990e-01 6.99602187e-01 -6.61715686e-01 -2.69573331e-01 6.97285950e-01 -6.64167762e-01 -2.69571990e-01 6.94950461e-01 -6.66595519e-01 -2.69573569e-01 6.92650855e-01 -6.69007778e-01 -2.69571990e-01 6.90291822e-01 -6.71429396e-01 -2.69573569e-01 6.88028812e-01 -6.73748970e-01 -2.69572526e-01 6.85645401e-01 -6.76179349e-01 -2.69572169e-01 6.83252037e-01 -6.78597927e-01 -2.69572645e-01 6.80829346e-01 -6.81010783e-01 -2.69572228e-01 6.78405106e-01 -6.83444560e-01 -2.69572467e-01 6.76076591e-01 -6.85741425e-01 -2.69573539e-01 6.73741162e-01 -6.88037515e-01 -2.69572228e-01 6.71338260e-01 -6.90383792e-01 -2.69572943e-01 6.68857932e-01 -6.92794919e-01 -2.69571990e-01 6.66415930e-01 -6.95121706e-01 -2.69573510e-01 6.64000094e-01 -6.97443783e-01 -2.69572318e-01 6.61755741e-01 -6.99569225e-01 -2.69576311e-01 6.59508944e-01 -7.01698184e-01 -2.69576222e-01 6.57442510e-01 -7.03631818e-01 -2.69575298e-01 6.54657722e-01 -7.06223905e-01 -2.69575357e-01 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. 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. 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. 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. 5.54173350e-01 -7.87540138e-01 -2.69575208e-01 5.52018225e-01 -7.89055109e-01 -2.69576252e-01 5.49466610e-01 -7.90816963e-01 -2.69575387e-01 5.46770334e-01 -7.92685866e-01 -2.69575417e-01 5.43900430e-01 -7.94658482e-01 -2.69574106e-01 5.41241407e-01 -7.96476245e-01 -2.69572645e-01 5.38464189e-01 -7.98358202e-01 -2.69572526e-01 5.35664320e-01 -8.00238848e-01 -2.69572407e-01 5.32805324e-01 -8.02146256e-01 -2.69571990e-01 5.29975116e-01 -8.04016054e-01 -2.69573033e-01 5.27247667e-01 -8.05807769e-01 -2.69572705e-01 5.24453282e-01 -8.07629943e-01 -2.69572496e-01 5.21635532e-01 -8.09453726e-01 -2.69572467e-01 5.18813550e-01 -8.11263561e-01 -2.69572437e-01 5.15981793e-01 -8.13068271e-01 -2.69572407e-01 5.13145804e-01 -8.14864457e-01 -2.69572407e-01 5.10310352e-01 -8.16637933e-01 -2.69572526e-01 5.07451057e-01 -8.18422258e-01 -2.69572467e-01 5.04590988e-01 -8.20186198e-01 -2.69572407e-01 5.01730144e-01 -8.21941912e-01 -2.69572437e-01 4.98851508e-01 -8.23688745e-01 -2.69572467e-01 4.95981216e-01 -8.25422645e-01 -2.69572467e-01 4.93019909e-01 -8.27195942e-01 -2.69571990e-01 4.90100503e-01 -8.28924537e-01 -2.69573182e-01 4.87303257e-01 -8.30574095e-01 -2.69572407e-01 4.84391570e-01 -8.32275748e-01 -2.69572467e-01 4.81408864e-01 -8.34007323e-01 -2.69571990e-01 4.78471130e-01 -8.35691571e-01 -2.69573301e-01 4.75639641e-01 -8.37307155e-01 -2.69572526e-01 4.72716093e-01 -8.38965118e-01 -2.69572407e-01 4.69792247e-01 -8.40602934e-01 -2.69572467e-01 4.66866314e-01 -8.42229784e-01 -2.69572318e-01 4.63912159e-01 -8.43864679e-01 -2.69572407e-01 4.60974187e-01 -8.45472753e-01 -2.69572467e-01 4.58000660e-01 -8.47084880e-01 -2.69572407e-01 4.55044240e-01 -8.48676383e-01 -2.69572526e-01 4.52076435e-01 -8.50261092e-01 -2.69572407e-01 4.49111551e-01 -8.51832271e-01 -2.69572526e-01 4.46053088e-01 -8.53438556e-01 -2.69571990e-01 4.43055540e-01 -8.54993701e-01 -2.69573450e-01 4.40155268e-01 -8.56494725e-01 -2.69572467e-01 4.37174886e-01 -8.58019054e-01 -2.69572526e-01 4.34171855e-01 -8.59543025e-01 -2.69572407e-01 4.31165993e-01 -8.61052692e-01 -2.69572526e-01 4.28152889e-01 -8.62557232e-01 -2.69572318e-01 4.25143093e-01 -8.64044607e-01 -2.69572407e-01 4.22108978e-01 -8.65531206e-01 -2.69572437e-01 4.19073373e-01 -8.67005467e-01 -2.69572437e-01 4.16067868e-01 -8.68448436e-01 -2.69572526e-01 4.12921131e-01 -8.69952261e-01 -2.69571990e-01 4.09859478e-01 -8.71394098e-01 -2.69573420e-01 4.06852633e-01 -8.72807503e-01 -2.69571990e-01 4.03781295e-01 -8.74227941e-01 -2.69573420e-01 4.00835395e-01 -8.75583589e-01 -2.69572407e-01 3.97774100e-01 -8.76980543e-01 -2.69572467e-01 3.94702047e-01 -8.78367126e-01 -2.69572437e-01 3.91552061e-01 -8.79778922e-01 -2.69571990e-01 3.88451189e-01 -8.81147265e-01 -2.69573241e-01 3.85479182e-01 -8.82454813e-01 -2.69572526e-01 3.82404655e-01 -8.83789778e-01 -2.69572377e-01 3.79299819e-01 -8.85125220e-01 -2.69572318e-01 3.76185238e-01 -8.86454940e-01 -2.69572407e-01 3.73098016e-01 -8.87759268e-01 -2.69572735e-01 3.70012492e-01 -8.89049709e-01 -2.69572318e-01 3.66893411e-01 -8.90339792e-01 -2.69572765e-01 3.63831937e-01 -8.91597092e-01 -2.69572496e-01 3.60713005e-01 -8.92863691e-01 -2.69572318e-01 3.57509732e-01 -8.94152105e-01 -2.69571990e-01 3.54353964e-01 -8.95404756e-01 -2.69573092e-01 3.51311058e-01 -8.96606266e-01 -2.69572526e-01 3.48186821e-01 -8.97816241e-01 -2.69572467e-01 3.45052361e-01 -8.99034441e-01 -2.69572407e-01 3.41900438e-01 -9.00231540e-01 -2.69572526e-01 3.38755131e-01 -9.01415884e-01 -2.69572407e-01 3.35597664e-01 -9.02595460e-01 -2.69572407e-01 3.32388163e-01 -9.03788924e-01 -2.69571990e-01 3.29212993e-01 -9.04951513e-01 -2.69573271e-01 3.26093316e-01 -9.06081557e-01 -2.69572139e-01 3.22921395e-01 -9.07215059e-01 -2.69573212e-01 3.19731414e-01 -9.08346951e-01 -2.69571990e-01 3.16560119e-01 -9.09451902e-01 -2.69573301e-01 3.13387871e-01 -9.10555005e-01 -2.69571990e-01 3.10193419e-01 -9.11642373e-01 -2.69573301e-01 3.07096988e-01 -9.12694752e-01 -2.69572407e-01 3.03900331e-01 -9.13763046e-01 -2.69572228e-01 3.00696194e-01 -9.14820254e-01 -2.69572765e-01 2.97529221e-01 -9.15856600e-01 -2.69572526e-01 2.94312000e-01 -9.16897774e-01 -2.69572407e-01 2.91134298e-01 -9.17909741e-01 -2.69572496e-01 2.87933290e-01 -9.18921053e-01 -2.69572347e-01 2.84715712e-01 -9.19920862e-01 -2.69572645e-01 2.81504184e-01 -9.20910776e-01 -2.69572407e-01 2.78232813e-01 -9.21901941e-01 -2.69572139e-01 2.74990231e-01 -9.22873199e-01 -2.69573152e-01 2.71837503e-01 -9.23809111e-01 -2.69572526e-01 2.68534541e-01 -9.24776733e-01 -2.69572109e-01 2.65231341e-01 -9.25727546e-01 -2.69572407e-01 2.61985660e-01 -9.26651120e-01 -2.69572526e-01 2.58852422e-01 -9.27529573e-01 -2.69573450e-01 2.55719572e-01 -9.28400099e-01 -2.69572437e-01 2.52466351e-01 -9.29292381e-01 -2.69572407e-01 2.49229610e-01 -9.30161953e-01 -2.69572526e-01 2.45895386e-01 -9.31052089e-01 -2.69571990e-01 2.42620647e-01 -9.31907535e-01 -2.69573390e-01 2.39376649e-01 -9.32747960e-01 -2.69571990e-01 2.36102387e-01 -9.33577716e-01 -2.69573390e-01 2.32876405e-01 -9.34391677e-01 -2.69571990e-01 2.29582831e-01 -9.35204566e-01 -2.69573331e-01 2.26405010e-01 -9.35982406e-01 -2.69572467e-01 2.23104298e-01 -9.36775684e-01 -2.69572228e-01 2.19828591e-01 -9.37548041e-01 -2.69572645e-01 2.16595858e-01 -9.38300073e-01 -2.69572467e-01 2.13211402e-01 -9.39075291e-01 -2.69571990e-01 2.09923476e-01 -9.39813554e-01 -2.69573301e-01 2.06735522e-01 -9.40519333e-01 -2.69572645e-01 2.03444839e-01 -9.41237688e-01 -2.69572467e-01 2.00171962e-01 -9.41939354e-01 -2.69572526e-01 1.96804389e-01 -9.42651868e-01 -2.69572139e-01 1.93496257e-01 -9.43332016e-01 -2.69573331e-01 1.90293938e-01 -9.43984389e-01 -2.69572407e-01 1.86992243e-01 -9.44643080e-01 -2.69572645e-01 1.83690324e-01 -9.45291698e-01 -2.69572407e-01 1.80310115e-01 -9.45943534e-01 -2.69571990e-01 1.76998511e-01 -9.46564674e-01 -2.69573420e-01 1.73706993e-01 -9.47177052e-01 -2.69571990e-01 1.70387343e-01 -9.47781801e-01 -2.69573420e-01 1.67174473e-01 -9.48355317e-01 -2.69572645e-01 1.63871109e-01 -9.48926508e-01 -2.69572467e-01 1.60559624e-01 -9.49494660e-01 -2.69572467e-01 1.57245845e-01 -9.50047076e-01 -2.69572467e-01 1.53932407e-01 -9.50590253e-01 -2.69572526e-01 1.50620967e-01 -9.51121330e-01 -2.69572467e-01 1.47305697e-01 -9.51640725e-01 -2.69572407e-01 1.43968090e-01 -9.52149391e-01 -2.69572467e-01 1.40620917e-01 -9.52651143e-01 -2.69572228e-01 1.37293503e-01 -9.53133464e-01 -2.69572705e-01 1.33990377e-01 -9.53604400e-01 -2.69572526e-01 1.30562261e-01 -9.54083681e-01 -2.69571990e-01 1.27225339e-01 -9.54529762e-01 -2.69573331e-01 1.23969935e-01 -9.54959869e-01 -2.69572824e-01 1.20651580e-01 -9.55386698e-01 -2.69572467e-01 1.17309101e-01 -9.55801606e-01 -2.69572407e-01 1.13876745e-01 -9.56219077e-01 -2.69571990e-01 1.10536627e-01 -9.56605017e-01 -2.69573390e-01 1.07300177e-01 -9.56976414e-01 -2.69572586e-01 1.03943065e-01 -9.57346082e-01 -2.69572616e-01 1.00622043e-01 -9.57700849e-01 -2.69572526e-01 9.71843898e-02 -9.58056271e-01 -2.69572139e-01 9.38339680e-02 -9.58388329e-01 -2.69573420e-01 9.05073136e-02 -9.58714545e-01 -2.69571990e-01 8.71327296e-02 -9.59021628e-01 -2.69573420e-01 8.38044062e-02 -9.59321678e-01 -2.69572139e-01 8.03732499e-02 -9.59612429e-01 -2.69572586e-01 7.70980045e-02 -9.59880352e-01 -2.69573480e-01 7.38398209e-02 -9.60137725e-01 -2.69572467e-01 7.04865679e-02 -9.60390508e-01 -2.69572526e-01 6.71313480e-02 -9.60628808e-01 -2.69572496e-01 6.37745410e-02 -9.60859120e-01 -2.69572526e-01 6.04416542e-02 -9.61075246e-01 -2.69572467e-01 5.70704006e-02 -9.61280167e-01 -2.69572526e-01 5.37085794e-02 -9.61475015e-01 -2.69572526e-01 5.03557883e-02 -9.61653531e-01 -2.69572705e-01 4.70146351e-02 -9.61825907e-01 -2.69572645e-01 4.36778553e-02 -9.61983323e-01 -2.69572407e-01 4.02088948e-02 -9.62134421e-01 -2.69571990e-01 3.68472748e-02 -9.62265015e-01 -2.69573510e-01 3.36062759e-02 -9.62385893e-01 -2.69572526e-01 3.01419850e-02 -9.62502539e-01 -2.69572109e-01 2.67654173e-02 -9.62600350e-01 -2.69573331e-01 2.34056525e-02 -9.62694049e-01 -2.69571990e-01 2.00297385e-02 -9.62759435e-01 -2.69573539e-01 1.67981237e-02 -9.62831795e-01 -2.69572526e-01 1.33444937e-02 -9.62876797e-01 -2.69571990e-01 9.95689724e-03 -9.62919891e-01 -2.69573480e-01 6.70260610e-03 -9.62956607e-01 -2.69572526e-01 3.34039936e-03 -9.62972939e-01 -2.69572526e-01 -3.79221165e-05 -9.62974012e-01 -2.69572467e-01 -3.48500791e-03 -9.62974370e-01 -2.69572139e-01 -6.84620207e-03 -9.62953389e-01 -2.69573450e-01 -1.01966197e-02 -9.62922275e-01 -2.69572139e-01 -1.35514084e-02 -9.62871552e-01 -2.69573331e-01 -1.69041194e-02 -9.62833405e-01 -2.69572139e-01 -2.03542747e-02 -9.62755919e-01 -2.69572526e-01 -2.36488376e-02 -9.62683141e-01 -2.69573241e-01 -2.69338377e-02 -9.62597311e-01 -2.69572586e-01 -3.02853826e-02 -9.62498903e-01 -2.69572496e-01 -3.36404890e-02 -9.62387681e-01 -2.69572407e-01 -3.70923504e-02 -9.62260723e-01 -2.69571990e-01 -4.04650569e-02 -9.62121069e-01 -2.69573390e-01 -4.37196791e-02 -9.61980045e-01 -2.69572467e-01 -4.70730327e-02 -9.61823404e-01 -2.69572586e-01 -5.04194051e-02 -9.61650372e-01 -2.69572616e-01 -5.38484380e-02 -9.61469769e-01 -2.69572079e-01 -5.72190359e-02 -9.61269915e-01 -2.69573450e-01 -6.05758689e-02 -9.61065292e-01 -2.69572139e-01 -6.39324561e-02 -9.60845947e-01 -2.69573301e-01 -6.71952888e-02 -9.60625231e-01 -2.69572467e-01 -7.06247315e-02 -9.60382104e-01 -2.69571990e-01 -7.39859417e-02 -9.60124791e-01 -2.69573152e-01 -7.73219913e-02 -9.59865212e-01 -2.69572139e-01 -8.06887895e-02 -9.59584296e-01 -2.69573182e-01 -8.39528367e-02 -9.59306717e-01 -2.69572586e-01 -8.73783976e-02 -9.59002495e-01 -2.69571990e-01 -9.07428414e-02 -9.58686173e-01 -2.69573331e-01 -9.40687135e-02 -9.58369434e-01 -2.69571990e-01 -9.74285007e-02 -9.58029747e-01 -2.69573569e-01 -1.00750506e-01 -9.57691252e-01 -2.69571990e-01 -1.04204156e-01 -9.57318664e-01 -2.69572675e-01 -1.07446365e-01 -9.56958294e-01 -2.69573420e-01 -1.10681422e-01 -9.56591606e-01 -2.69572467e-01 -1.14042543e-01 -9.56196070e-01 -2.69572467e-01 -1.17362715e-01 -9.55795586e-01 -2.69572407e-01 -1.20794475e-01 -9.55370367e-01 -2.69571990e-01 -1.24153823e-01 -9.54933524e-01 -2.69573241e-01 -1.27377778e-01 -9.54512656e-01 -2.69572496e-01 -1.30698532e-01 -9.54063237e-01 -2.69572496e-01 -1.34028003e-01 -9.53601718e-01 -2.69572318e-01 -1.37462005e-01 -9.53112662e-01 -2.69571990e-01 -1.40784070e-01 -9.52623248e-01 -2.69573480e-01 -1.44092336e-01 -9.52132523e-01 -2.69571990e-01 -1.47421300e-01 -9.51621294e-01 -2.69573420e-01 -1.50643900e-01 -9.51116860e-01 -2.69572526e-01 -1.53987080e-01 -9.50582504e-01 -2.69572407e-01 -1.57282263e-01 -9.50043261e-01 -2.69572645e-01 -1.60700709e-01 -9.49473560e-01 -2.69571990e-01 -1.64028212e-01 -9.48897064e-01 -2.69573450e-01 -1.67241454e-01 -9.48343813e-01 -2.69572407e-01 -1.70608282e-01 -9.47743714e-01 -2.69572139e-01 -1.73919499e-01 -9.47134733e-01 -2.69572824e-01 -1.77259356e-01 -9.46521878e-01 -2.69571990e-01 -1.80574000e-01 -9.45888460e-01 -2.69573480e-01 -1.83777407e-01 -9.45274413e-01 -2.69572467e-01 -1.87083885e-01 -9.44625497e-01 -2.69572467e-01 -1.90438092e-01 -9.43957508e-01 -2.69572020e-01 -1.93770796e-01 -9.43274558e-01 -2.69573182e-01 -1.96976140e-01 -9.42611814e-01 -2.69572526e-01 -2.00249851e-01 -9.41924632e-01 -2.69572467e-01 -2.03619003e-01 -9.41202581e-01 -2.69572139e-01 -2.06917033e-01 -9.40476537e-01 -2.69573182e-01 -2.10114866e-01 -9.39771652e-01 -2.69572526e-01 -2.13396400e-01 -9.39031720e-01 -2.69572407e-01 -2.16669753e-01 -9.38280404e-01 -2.69572526e-01 -2.20012397e-01 -9.37508404e-01 -2.69572079e-01 -2.23294541e-01 -9.36726689e-01 -2.69573241e-01 -2.26470172e-01 -9.35966611e-01 -2.69572467e-01 -2.29804277e-01 -9.35154200e-01 -2.69572139e-01 -2.33084440e-01 -9.34336841e-01 -2.69573152e-01 -2.36350760e-01 -9.33518827e-01 -2.69571990e-01 -2.39603013e-01 -9.32687521e-01 -2.69573331e-01 -2.42750868e-01 -9.31874514e-01 -2.69572526e-01 -2.46029079e-01 -9.31015372e-01 -2.69572526e-01 -2.49346808e-01 -9.30133402e-01 -2.69571990e-01 -2.52687246e-01 -9.29230154e-01 -2.69572526e-01 -2.55861789e-01 -9.28357601e-01 -2.69573271e-01 -2.58982986e-01 -9.27496910e-01 -2.69572228e-01 -2.62252659e-01 -9.26576316e-01 -2.69572467e-01 -2.65480548e-01 -9.25655246e-01 -2.69572467e-01 -2.68700570e-01 -9.24726784e-01 -2.69572645e-01 -2.71921486e-01 -9.23784554e-01 -2.69572407e-01 -2.75137424e-01 -9.22833562e-01 -2.69572467e-01 -2.78358012e-01 -9.21863437e-01 -2.69572467e-01 -2.81576842e-01 -9.20885265e-01 -2.69572407e-01 -2.84868389e-01 -9.19877410e-01 -2.69572109e-01 -2.88106918e-01 -9.18862641e-01 -2.69573212e-01 -2.91305244e-01 -9.17858660e-01 -2.69572109e-01 -2.94497132e-01 -9.16836262e-01 -2.69573301e-01 -2.97596306e-01 -9.15835381e-01 -2.69572496e-01 -3.00872415e-01 -9.14766669e-01 -2.69571990e-01 -3.04129690e-01 -9.13686275e-01 -2.69572705e-01 -3.07307869e-01 -9.12624955e-01 -2.69572318e-01 -3.10444534e-01 -9.11557913e-01 -2.69573390e-01 -3.13528687e-01 -9.10504162e-01 -2.69572586e-01 -3.16747308e-01 -9.09389138e-01 -2.69572318e-01 -3.19917709e-01 -9.08279717e-01 -2.69572467e-01 -3.23129535e-01 -9.07142460e-01 -2.69572139e-01 -3.26305181e-01 -9.06001508e-01 -2.69573241e-01 -3.29448819e-01 -9.04868364e-01 -2.69572139e-01 -3.32608998e-01 -9.03701305e-01 -2.69573241e-01 -3.35694134e-01 -9.02558386e-01 -2.69572467e-01 -3.38837743e-01 -9.01383817e-01 -2.69572526e-01 -3.41986030e-01 -9.00200307e-01 -2.69572407e-01 -3.45210195e-01 -8.98976326e-01 -2.69571990e-01 -3.48436385e-01 -8.97722483e-01 -2.69572407e-01 -3.51489276e-01 -8.96532118e-01 -2.69573450e-01 -3.54517639e-01 -8.95340979e-01 -2.69572526e-01 -3.57629538e-01 -8.94101620e-01 -2.69572467e-01 -3.60747606e-01 -8.92848611e-01 -2.69572705e-01 -3.63941908e-01 -8.91553104e-01 -2.69571990e-01 -3.67147475e-01 -8.90234470e-01 -2.69572526e-01 -3.70176435e-01 -8.88978601e-01 -2.69573301e-01 -3.73171449e-01 -8.87728453e-01 -2.69572407e-01 -3.76283884e-01 -8.86413455e-01 -2.69572407e-01 -3.79447788e-01 -8.85061562e-01 -2.69571990e-01 -3.82566273e-01 -8.83716643e-01 -2.69573450e-01 -3.85633051e-01 -8.82389963e-01 -2.69571990e-01 -3.88710558e-01 -8.81032050e-01 -2.69573420e-01 -3.91710192e-01 -8.79705906e-01 -2.69572467e-01 -3.94779623e-01 -8.78332853e-01 -2.69572616e-01 -3.97830456e-01 -8.76953423e-01 -2.69572586e-01 -4.00954634e-01 -8.75530660e-01 -2.69571990e-01 -4.04011548e-01 -8.74120593e-01 -2.69573271e-01 -4.06993896e-01 -8.72738659e-01 -2.69572407e-01 -4.10032272e-01 -8.71315718e-01 -2.69572467e-01 -4.13155764e-01 -8.69841039e-01 -2.69571990e-01 -4.16191489e-01 -8.68386924e-01 -2.69573301e-01 -4.19136912e-01 -8.66976082e-01 -2.69572496e-01 -4.22170430e-01 -8.65502834e-01 -2.69572526e-01 -4.25252050e-01 -8.63991439e-01 -2.69572139e-01 -4.28261429e-01 -8.62500787e-01 -2.69573390e-01 -4.31188434e-01 -8.61042857e-01 -2.69572407e-01 -4.34201419e-01 -8.59528959e-01 -2.69572467e-01 -4.37192291e-01 -8.58011305e-01 -2.69572467e-01 -4.40268844e-01 -8.56438458e-01 -2.69571990e-01 -4.43255156e-01 -8.54889750e-01 -2.69573271e-01 -4.46153462e-01 -8.53386462e-01 -2.69572467e-01 -4.49115992e-01 -8.51828933e-01 -2.69572586e-01 -4.52078611e-01 -8.50260735e-01 -2.69572407e-01 -4.55121040e-01 -8.48638833e-01 -2.69572139e-01 -4.58108962e-01 -8.47023785e-01 -2.69573420e-01 -4.61052150e-01 -8.45432043e-01 -2.69572139e-01 -4.64003563e-01 -8.43810439e-01 -2.69573390e-01 -4.66946274e-01 -8.42189014e-01 -2.69571990e-01 -4.69973087e-01 -8.40501606e-01 -2.69572556e-01 -4.72826183e-01 -8.38897705e-01 -2.69573390e-01 -4.75731403e-01 -8.37259889e-01 -2.69571990e-01 -4.78670478e-01 -8.35578263e-01 -2.69573420e-01 -4.81497288e-01 -8.33953619e-01 -2.69572467e-01 -4.84412968e-01 -8.32263947e-01 -2.69572467e-01 -4.87324327e-01 -8.30562174e-01 -2.69572526e-01 -4.90207762e-01 -8.28863442e-01 -2.69572556e-01 -4.93088186e-01 -8.27152610e-01 -2.69572616e-01 -4.95974064e-01 -8.25425684e-01 -2.69572586e-01 -4.98883128e-01 -8.23671043e-01 -2.69572228e-01 -5.01837373e-01 -8.21878135e-01 -2.69572139e-01 -5.04745722e-01 -8.20091307e-01 -2.69572407e-01 -5.07541478e-01 -8.18362415e-01 -2.69573331e-01 -5.10306060e-01 -8.16644549e-01 -2.69572526e-01 -5.13231933e-01 -8.14809263e-01 -2.69571990e-01 -5.16091824e-01 -8.12996328e-01 -2.69573390e-01 -5.18911958e-01 -8.11202884e-01 -2.69571990e-01 -5.21756172e-01 -8.09372067e-01 -2.69573450e-01 -5.24475932e-01 -8.07615340e-01 -2.69572467e-01 -5.27369797e-01 -8.05729687e-01 -2.69571990e-01 -5.30198455e-01 -8.03868771e-01 -2.69573539e-01 -5.32903373e-01 -8.02077055e-01 -2.69572467e-01 -5.35707355e-01 -8.00209761e-01 -2.69572556e-01 -5.38579404e-01 -7.98283398e-01 -2.69571990e-01 -5.41378796e-01 -7.96378255e-01 -2.69573539e-01 -5.44061959e-01 -7.94555128e-01 -2.69572526e-01 -5.46832740e-01 -7.92649567e-01 -2.69572526e-01 -5.49590707e-01 -7.90740013e-01 -2.69572377e-01 -5.52434027e-01 -7.88757265e-01 -2.69571990e-01 -5.55294514e-01 -7.86747634e-01 -2.69572407e-01 -5.57957768e-01 -7.84853995e-01 -2.69573510e-01 -5.60592055e-01 -7.82979846e-01 -2.69572407e-01 -5.63322306e-01 -7.81012118e-01 -2.69572496e-01 -5.66061318e-01 -7.79033601e-01 -2.69572407e-01 -5.68847060e-01 -7.77001858e-01 -2.69572139e-01 -5.71627080e-01 -7.74957418e-01 -2.69572496e-01 -5.74265778e-01 -7.73001909e-01 -2.69573480e-01 -5.76876581e-01 -7.71057189e-01 -2.69572467e-01 -5.79568923e-01 -7.69037485e-01 -2.69572407e-01 -5.82307696e-01 -7.66969442e-01 -2.69571990e-01 -5.85006118e-01 -7.64907360e-01 -2.69573182e-01 -5.87665677e-01 -7.62869537e-01 -2.69571990e-01 -5.90322375e-01 -7.60810852e-01 -2.69573390e-01 -5.92902899e-01 -7.58804083e-01 -2.69572467e-01 -5.95616221e-01 -7.56681204e-01 -2.69571990e-01 -5.98254085e-01 -7.54589438e-01 -2.69573420e-01 -6.00881577e-01 -7.52505660e-01 -2.69571990e-01 -6.03509545e-01 -7.50393093e-01 -2.69573510e-01 -6.06040597e-01 -7.48355269e-01 -2.69572526e-01 -6.08655274e-01 -7.46227264e-01 -2.69572407e-01 -6.11244977e-01 -7.44108737e-01 -2.69572526e-01 -6.13905907e-01 -7.41918623e-01 -2.69571990e-01 -6.16498768e-01 -7.39758134e-01 -2.69573390e-01 -6.19006634e-01 -7.37664998e-01 -2.69572526e-01 -6.21641815e-01 -7.35448956e-01 -2.69571990e-01 -6.24210715e-01 -7.33261824e-01 -2.69573480e-01 -6.26694441e-01 -7.31145203e-01 -2.69572377e-01 -6.29252374e-01 -7.28945673e-01 -2.69572526e-01 -6.31785631e-01 -7.26751328e-01 -2.69572526e-01 -6.34390116e-01 -7.24478960e-01 -2.69571990e-01 -6.36914432e-01 -7.22256243e-01 -2.69573331e-01 -6.39358759e-01 -7.20096350e-01 -2.69572526e-01 -6.41876757e-01 -7.17852473e-01 -2.69572407e-01 -6.44363999e-01 -7.15620756e-01 -2.69572467e-01 -6.46921754e-01 -7.13312924e-01 -2.69572139e-01 -6.49412334e-01 -7.11038828e-01 -2.69573092e-01 -6.51895344e-01 -7.08771825e-01 -2.69572020e-01 -6.54367864e-01 -7.06483066e-01 -2.69573331e-01 -6.56823456e-01 -7.04203784e-01 -2.69571990e-01 -6.59348011e-01 -7.01839805e-01 -2.69572407e-01 -6.61730528e-01 -6.99588478e-01 -2.69573420e-01 -6.64143741e-01 -6.97308004e-01 -2.69572049e-01 -6.66594684e-01 -6.94951296e-01 -2.69573390e-01 -6.68940365e-01 -6.92711771e-01 -2.69572467e-01 -6.71351254e-01 -6.90372288e-01 -2.69572526e-01 -6.73747301e-01 -6.88029766e-01 -2.69572586e-01 -6.76223874e-01 -6.85601830e-01 -2.69571990e-01 -6.78631723e-01 -6.83214366e-01 -2.69573599e-01 -6.80915236e-01 -6.80924118e-01 -2.69572318e-01 -6.83303058e-01 -6.78546071e-01 -2.69572526e-01 -6.85741901e-01 -6.76083803e-01 -2.69571990e-01 -6.88118398e-01 -6.73654079e-01 -2.69573480e-01 -6.90383673e-01 -6.71339571e-01 -2.69572526e-01 -6.92712009e-01 -6.68939590e-01 -2.69572467e-01 -6.95101738e-01 -6.66444838e-01 -2.69571990e-01 -6.97498798e-01 -6.63942277e-01 -2.69572467e-01 -6.99815929e-01 -6.61495030e-01 -2.69572288e-01 -7.02070355e-01 -6.59096360e-01 -2.69573480e-01 -7.04293728e-01 -6.56724155e-01 -2.69572467e-01 -7.06639946e-01 -6.54202938e-01 -2.69572139e-01 -7.08924532e-01 -6.51722968e-01 -2.69573271e-01 -7.11139917e-01 -6.49306715e-01 -2.69572407e-01 -7.13404357e-01 -6.46818995e-01 -2.69572407e-01 -7.15662956e-01 -6.44317448e-01 -2.69572496e-01 -7.17901468e-01 -6.41820967e-01 -2.69572526e-01 -7.20139503e-01 -6.39313817e-01 -2.69572318e-01 -7.22431481e-01 -6.36720777e-01 -2.69571990e-01 -7.24638999e-01 -6.34201288e-01 -2.69573331e-01 -7.26851463e-01 -6.31671250e-01 -2.69571990e-01 -7.29117513e-01 -6.29050672e-01 -2.69572526e-01 -7.31248736e-01 -6.26571000e-01 -2.69573569e-01 -7.33414590e-01 -6.24038994e-01 -2.69571990e-01 -7.35601604e-01 -6.21456325e-01 -2.69573241e-01 -7.37703204e-01 -6.18960738e-01 -2.69572407e-01 -7.39912093e-01 -6.16322637e-01 -2.69572139e-01 -7.42064118e-01 -6.13722086e-01 -2.69573420e-01 -7.44153500e-01 -6.11191928e-01 -2.69572526e-01 -7.46276498e-01 -6.08594239e-01 -2.69572467e-01 -7.48397529e-01 -6.05985343e-01 -2.69572824e-01 -7.50559926e-01 -6.03308260e-01 -2.69571990e-01 -7.52716482e-01 -6.00613594e-01 -2.69572496e-01 -7.54813135e-01 -5.97974598e-01 -2.69572496e-01 -7.56849110e-01 -5.95395267e-01 -2.69573182e-01 -7.58864760e-01 -5.92827976e-01 -2.69572467e-01 -7.60977268e-01 -5.90115845e-01 -2.69572139e-01 -7.63028324e-01 -5.87455332e-01 -2.69573331e-01 -7.65074372e-01 -5.84794104e-01 -2.69571990e-01 -7.67118037e-01 -5.82103729e-01 -2.69573390e-01 -7.69079566e-01 -5.79514682e-01 -2.69572556e-01 -7.71086216e-01 -5.76838672e-01 -2.69572526e-01 -7.73092210e-01 -5.74147880e-01 -2.69572228e-01 -7.75146961e-01 -5.71372807e-01 -2.69571990e-01 -7.77146459e-01 -5.68645895e-01 -2.69573152e-01 -7.79140532e-01 -5.65916836e-01 -2.69571990e-01 -7.81162262e-01 -5.63114285e-01 -2.69572824e-01 -7.83063591e-01 -5.60470760e-01 -2.69573271e-01 -7.85009027e-01 -5.57747006e-01 -2.69571990e-01 -7.86961138e-01 -5.54984868e-01 -2.69573331e-01 -7.88837850e-01 -5.52316606e-01 -2.69572407e-01 -7.90812314e-01 -5.49489081e-01 -2.69571990e-01 -7.92735934e-01 -5.46703458e-01 -2.69573569e-01 -7.94571102e-01 -5.44037580e-01 -2.69572228e-01 -7.96478212e-01 -5.41237772e-01 -2.69572526e-01 -7.98366070e-01 -5.38452566e-01 -2.69572407e-01 -8.00289750e-01 -5.35590589e-01 -2.69571990e-01 -8.02164137e-01 -5.32770157e-01 -2.69573271e-01 -8.04014385e-01 -5.29983699e-01 -2.69571990e-01 -8.05867970e-01 -5.27153373e-01 -2.69573241e-01 -8.07650387e-01 -5.24423361e-01 -2.69572496e-01 -8.09470117e-01 -5.21609485e-01 -2.69572407e-01 -8.11277092e-01 -5.18793464e-01 -2.69572526e-01 -8.13128710e-01 -5.15888512e-01 -2.69572049e-01 -8.14919353e-01 -5.13051987e-01 -2.69573271e-01 -8.16660464e-01 -5.10275483e-01 -2.69572705e-01 -8.18440676e-01 -5.07420897e-01 -2.69572407e-01 -8.20205033e-01 -5.04559577e-01 -2.69572407e-01 -8.22003126e-01 -5.01632452e-01 -2.69571990e-01 -8.23755920e-01 -4.98738945e-01 -2.69573182e-01 -8.25482428e-01 -4.95884955e-01 -2.69572139e-01 -8.27206612e-01 -4.92992282e-01 -2.69573152e-01 -8.28880668e-01 -4.90178764e-01 -2.69572467e-01 -8.30613136e-01 -4.87241387e-01 -2.69572139e-01 -8.32315445e-01 -4.84321028e-01 -2.69573152e-01 -8.33961487e-01 -4.81483847e-01 -2.69572467e-01 -8.35625589e-01 -4.78588670e-01 -2.69572496e-01 -8.37300360e-01 -4.75653023e-01 -2.69572318e-01 -8.38955641e-01 -4.72732008e-01 -2.69572407e-01 -8.40596795e-01 -4.69801724e-01 -2.69572467e-01 -8.42222869e-01 -4.66878772e-01 -2.69572407e-01 -8.43900383e-01 -4.63849604e-01 -2.69571990e-01 -8.45520556e-01 -4.60883319e-01 -2.69573301e-01 -8.47073793e-01 -4.58021104e-01 -2.69572467e-01 -8.48679960e-01 -4.55041200e-01 -2.69572288e-01 -8.50313425e-01 -4.51983094e-01 -2.69571990e-01 -8.51928532e-01 -4.48925197e-01 -2.69572586e-01 -8.53439987e-01 -4.46043909e-01 -2.69573301e-01 -8.54943395e-01 -4.43159729e-01 -2.69572407e-01 -8.56488466e-01 -4.40166891e-01 -2.69572467e-01 -8.58068347e-01 -4.37081575e-01 -2.69571990e-01 -8.59586895e-01 -4.34080213e-01 -2.69573390e-01 -8.61051917e-01 -4.31171268e-01 -2.69572288e-01 -8.62594366e-01 -4.28083003e-01 -2.69571990e-01 -8.64086032e-01 -4.25051868e-01 -2.69573420e-01 -8.65529537e-01 -4.22114909e-01 -2.69572407e-01 -8.67037296e-01 -4.19013083e-01 -2.69571990e-01 -8.68533194e-01 -4.15893316e-01 -2.69572407e-01 -8.69981825e-01 -4.12855327e-01 -2.69572467e-01 -8.71381998e-01 -4.09884989e-01 -2.69573420e-01 -8.72766793e-01 -4.06935900e-01 -2.69572467e-01 -8.74222338e-01 -4.03803200e-01 -2.69572049e-01 -8.75665843e-01 -4.00655776e-01 -2.69572467e-01 -8.77016127e-01 -3.97689313e-01 -2.69573212e-01 -8.78369510e-01 -3.94697338e-01 -2.69572467e-01 -8.79740059e-01 -3.91632020e-01 -2.69572437e-01 -8.81133556e-01 -3.88493776e-01 -2.69571990e-01 -8.82489324e-01 -3.85396302e-01 -2.69573301e-01 -8.83826137e-01 -3.82327884e-01 -2.69571990e-01 -8.85158062e-01 -3.79213989e-01 -2.69573212e-01 -8.86438787e-01 -3.76221657e-01 -2.69572467e-01 -8.87784004e-01 -3.73044640e-01 -2.69571990e-01 -8.89079809e-01 -3.69934201e-01 -2.69573331e-01 -8.90365124e-01 -3.66838813e-01 -2.69571990e-01 -8.91642392e-01 -3.63713086e-01 -2.69573331e-01 -8.92875731e-01 -3.60679150e-01 -2.69572407e-01 -8.94158840e-01 -3.57490122e-01 -2.69571990e-01 -8.95404816e-01 -3.54351729e-01 -2.69573420e-01 -8.96632612e-01 -3.51248264e-01 -2.69571990e-01 -8.97857845e-01 -3.48074466e-01 -2.69573212e-01 -8.99037898e-01 -3.45045894e-01 -2.69572467e-01 -9.00261760e-01 -3.41830641e-01 -2.69571990e-01 -9.01440501e-01 -3.38680685e-01 -2.69573331e-01 -9.02583301e-01 -3.35629612e-01 -2.69572407e-01 -9.03778553e-01 -3.32413256e-01 -2.69572109e-01 -9.04942334e-01 -3.29238176e-01 -2.69573092e-01 -9.06088591e-01 -3.26074600e-01 -2.69571990e-01 -9.07221675e-01 -3.22902083e-01 -2.69573152e-01 -9.08337474e-01 -3.19755316e-01 -2.69572139e-01 -9.09450769e-01 -3.16563934e-01 -2.69573182e-01 -9.10525441e-01 -3.13468426e-01 -2.69572496e-01 -9.11612391e-01 -3.10292840e-01 -2.69572407e-01 -9.12685215e-01 -3.07122916e-01 -2.69572407e-01 -9.13778961e-01 -3.03853601e-01 -2.69572139e-01 -9.14835870e-01 -3.00646245e-01 -2.69573122e-01 -9.15858030e-01 -2.97528774e-01 -2.69572467e-01 -9.16917264e-01 -2.94254094e-01 -2.69571990e-01 -9.17937160e-01 -2.91043401e-01 -2.69573331e-01 -9.18948293e-01 -2.87852347e-01 -2.69571990e-01 -9.19943750e-01 -2.84633309e-01 -2.69573361e-01 -9.20930743e-01 -2.81439811e-01 -2.69571990e-01 -9.21906173e-01 -2.78211683e-01 -2.69573420e-01 -9.22840774e-01 -2.75102466e-01 -2.69572467e-01 -9.23826277e-01 -2.71787703e-01 -2.69571990e-01 -9.24768507e-01 -2.68551797e-01 -2.69573301e-01 -9.25676107e-01 -2.65407085e-01 -2.69572407e-01 -9.26595569e-01 -2.62183100e-01 -2.69572407e-01 -9.27510977e-01 -2.58926898e-01 -2.69572467e-01 -9.28405881e-01 -2.55699277e-01 -2.69572407e-01 -9.29294229e-01 -2.52458900e-01 -2.69572467e-01 -9.30166721e-01 -2.49211669e-01 -2.69572407e-01 -9.31055546e-01 -2.45886087e-01 -2.69571990e-01 -9.31936860e-01 -2.42514387e-01 -2.69572407e-01 -9.32756066e-01 -2.39337489e-01 -2.69573241e-01 -9.33560491e-01 -2.36178488e-01 -2.69572407e-01 -9.34402168e-01 -2.32838213e-01 -2.69571990e-01 -9.35234904e-01 -2.29471534e-01 -2.69572407e-01 -9.36005294e-01 -2.26297170e-01 -2.69573510e-01 -9.36766863e-01 -2.23133579e-01 -2.69572467e-01 -9.37539279e-01 -2.19862908e-01 -2.69572407e-01 -9.38320339e-01 -2.16505557e-01 -2.69572139e-01 -9.39072251e-01 -2.13208497e-01 -2.69573301e-01 -9.39791322e-01 -2.10033119e-01 -2.69572288e-01 -9.40535128e-01 -2.06676304e-01 -2.69571990e-01 -9.41249669e-01 -2.03375623e-01 -2.69573152e-01 -9.41941023e-01 -2.00164303e-01 -2.69572407e-01 -9.42631662e-01 -1.96888924e-01 -2.69572496e-01 -9.43331659e-01 -1.93523094e-01 -2.69572139e-01 -9.44016159e-01 -1.90145507e-01 -2.69572288e-01 -9.44655120e-01 -1.86926365e-01 -2.69573331e-01 -9.45290327e-01 -1.83705539e-01 -2.69572407e-01 -9.45937753e-01 -1.80342048e-01 -2.69572049e-01 -9.46573853e-01 -1.76963732e-01 -2.69572467e-01 -9.47171867e-01 -1.73712090e-01 -2.69573122e-01 -9.47764158e-01 -1.70498371e-01 -2.69572526e-01 -9.48354304e-01 -1.67191789e-01 -2.69572407e-01 -9.48937833e-01 -1.63819268e-01 -2.69572139e-01 -9.49518204e-01 -1.60418808e-01 -2.69572407e-01 -9.50057030e-01 -1.57178164e-01 -2.69573241e-01 -9.50587273e-01 -1.53958008e-01 -2.69572407e-01 -9.51122940e-01 -1.50608942e-01 -2.69572526e-01 -9.51655924e-01 -1.47220671e-01 -2.69571990e-01 -9.52156007e-01 -1.43917978e-01 -2.69573301e-01 -9.52659070e-01 -1.40580118e-01 -2.69571990e-01 -9.53139424e-01 -1.37250841e-01 -2.69573450e-01 -9.53603208e-01 -1.34016261e-01 -2.69572526e-01 -9.54079151e-01 -1.30601510e-01 -2.69571990e-01 -9.54525769e-01 -1.27260178e-01 -2.69573182e-01 -9.54968154e-01 -1.23932667e-01 -2.69571990e-01 -9.55391169e-01 -1.20597951e-01 -2.69573271e-01 -9.55797434e-01 -1.17335990e-01 -2.69572496e-01 -9.56211567e-01 -1.13928817e-01 -2.69571990e-01 -9.56601083e-01 -1.10570416e-01 -2.69573241e-01 -9.56986427e-01 -1.07231028e-01 -2.69571990e-01 -9.57363009e-01 -1.03800498e-01 -2.69572467e-01 -9.57705140e-01 -1.00553989e-01 -2.69573301e-01 -9.58052397e-01 -9.72313136e-02 -2.69571990e-01 -9.58386540e-01 -9.38626155e-02 -2.69573182e-01 -9.58713651e-01 -9.05153826e-02 -2.69571990e-01 -9.59019601e-01 -8.71476829e-02 -2.69573331e-01 -9.59311187e-01 -8.39209929e-02 -2.69572467e-01 -9.59596515e-01 -8.05666223e-02 -2.69572407e-01 -9.59874928e-01 -7.72076696e-02 -2.69572467e-01 -9.60146844e-01 -7.37675950e-02 -2.69571990e-01 -9.60392714e-01 -7.04276711e-02 -2.69573539e-01 -9.60625470e-01 -6.71807155e-02 -2.69572407e-01 -9.60864902e-01 -6.37239963e-02 -2.69571990e-01 -9.61076975e-01 -6.03446327e-02 -2.69573569e-01 -9.61282074e-01 -5.70406169e-02 -2.69572318e-01 -9.61461902e-01 -5.39967716e-02 -2.69576311e-01 -9.61624265e-01 -5.10658994e-02 -2.69575208e-01 -9.61840153e-01 -4.68174666e-02 -2.69575357e-01 -9.61968660e-01 -4.41034772e-02 -2.69575357e-01 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. 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. 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. -9.79185224e-01 5.22880182e-02 -1.96117282e-01 -9.79014218e-01 5.54008149e-02 -1.96117356e-01 -9.78814662e-01 5.88582419e-02 -1.96116924e-01 -9.78635371e-01 6.18062578e-02 -1.96116909e-01 -9.78428960e-01 6.50135726e-02 -1.96118057e-01 -9.78187323e-01 6.85403422e-02 -1.96118414e-01 -9.77935851e-01 7.20563903e-02 -1.96118325e-01 -9.77679074e-01 7.54538029e-02 -1.96118325e-01 -9.77411747e-01 7.88696408e-02 -1.96118370e-01 -9.77127433e-01 8.22952241e-02 -1.96118370e-01 -9.76844013e-01 8.56013820e-02 -1.96117967e-01 -9.76542354e-01 8.89762193e-02 -1.96118176e-01 -9.76216495e-01 9.24927071e-02 -1.96118385e-01 -9.75896537e-01 9.58087295e-02 -1.96118101e-01 -9.75557148e-01 9.91965905e-02 -1.96118042e-01 -9.75194514e-01 1.02711558e-01 -1.96118325e-01 -9.74831283e-01 1.06100835e-01 -1.96118385e-01 -9.74456191e-01 1.09499134e-01 -1.96118385e-01 -9.74069953e-01 1.12862617e-01 -1.96118325e-01 -9.73678589e-01 1.16188683e-01 -1.96118325e-01 -9.73275125e-01 1.19539835e-01 -1.96118400e-01 -9.72843528e-01 1.23008393e-01 -1.96118236e-01 -9.72393274e-01 1.26499385e-01 -1.96118385e-01 -9.71957743e-01 1.29807025e-01 -1.96118101e-01 -9.71502721e-01 1.33178920e-01 -1.96118250e-01 -9.71018255e-01 1.36660144e-01 -1.96118370e-01 -9.70548928e-01 1.39949888e-01 -1.96118087e-01 -9.70052123e-01 1.43352270e-01 -1.96118295e-01 -9.69546854e-01 1.46728858e-01 -1.96118101e-01 -9.69044924e-01 1.50012702e-01 -1.96118370e-01 -9.68500018e-01 1.53488740e-01 -1.96118072e-01 -9.67941284e-01 1.56976730e-01 -1.96118385e-01 -9.67386782e-01 1.60362482e-01 -1.96118400e-01 -9.66820955e-01 1.63745403e-01 -1.96118400e-01 -9.66245174e-01 1.67094648e-01 -1.96118370e-01 -9.65658963e-01 1.70482188e-01 -1.96118400e-01 -9.65051472e-01 1.73876658e-01 -1.96118385e-01 -9.64432359e-01 1.77253872e-01 -1.96118400e-01 -9.63826537e-01 1.80529237e-01 -1.96117997e-01 -9.63218331e-01 1.83746740e-01 -1.96118385e-01 -9.62548614e-01 1.87214151e-01 -1.96117982e-01 -9.61870790e-01 1.90672368e-01 -1.96118370e-01 -9.61201131e-01 1.94025427e-01 -1.96118400e-01 -9.60517466e-01 1.97383553e-01 -1.96118400e-01 -9.59821939e-01 2.00730011e-01 -1.96118385e-01 -9.59131122e-01 2.04010352e-01 -1.96118057e-01 -9.58418190e-01 2.07337841e-01 -1.96118116e-01 -9.57661688e-01 2.10793912e-01 -1.96118385e-01 -9.56939936e-01 2.14053884e-01 -1.96118101e-01 -9.56188679e-01 2.17379794e-01 -1.96118146e-01 -9.55401063e-01 2.20825702e-01 -1.96118400e-01 -9.54624116e-01 2.24162012e-01 -1.96118385e-01 -9.53835547e-01 2.27497831e-01 -1.96118385e-01 -9.53059912e-01 2.30725154e-01 -1.96118042e-01 -9.52275276e-01 2.33935177e-01 -1.96118400e-01 -9.51421559e-01 2.37375125e-01 -1.96118027e-01 -9.50559795e-01 2.40803972e-01 -1.96118400e-01 -9.49711621e-01 2.44132236e-01 -1.96118400e-01 -9.48879004e-01 2.47347295e-01 -1.96118057e-01 -9.48020458e-01 2.50624716e-01 -1.96118206e-01 -9.47131634e-01 2.53963292e-01 -1.96118116e-01 -9.46236134e-01 2.57276893e-01 -1.96118429e-01 -9.45310593e-01 2.60649323e-01 -1.96118385e-01 -9.44415689e-01 2.63883650e-01 -1.96118101e-01 -9.43516791e-01 2.67074138e-01 -1.96118385e-01 -9.42555308e-01 2.70446628e-01 -1.96118161e-01 -9.41577256e-01 2.73836195e-01 -1.96118370e-01 -9.40624535e-01 2.77089506e-01 -1.96118325e-01 -9.39661562e-01 2.80339003e-01 -1.96118370e-01 -9.38672602e-01 2.83625931e-01 -1.96118414e-01 -9.37692642e-01 2.86853313e-01 -1.96118057e-01 -9.36689794e-01 2.90114105e-01 -1.96118116e-01 -9.35641289e-01 2.93475747e-01 -1.96118325e-01 -9.34633374e-01 2.96669722e-01 -1.96118101e-01 -9.33594525e-01 2.99922526e-01 -1.96118236e-01 -9.32518661e-01 3.03249091e-01 -1.96118370e-01 -9.31452692e-01 3.06508631e-01 -1.96118385e-01 -9.30376589e-01 3.09759110e-01 -1.96118385e-01 -9.29287434e-01 3.13020110e-01 -1.96118370e-01 -9.28215563e-01 3.16175461e-01 -1.96118057e-01 -9.27138925e-01 3.19323301e-01 -1.96118370e-01 -9.25989568e-01 3.22635859e-01 -1.96118355e-01 -9.24826860e-01 3.25956404e-01 -1.96118370e-01 -9.23713923e-01 3.29099923e-01 -1.96118057e-01 -9.22559977e-01 3.32318544e-01 -1.96118072e-01 -9.21361804e-01 3.35627079e-01 -1.96118370e-01 -9.20185804e-01 3.38824034e-01 -1.96118370e-01 -9.18996572e-01 3.42025667e-01 -1.96118370e-01 -9.17821944e-01 3.45167518e-01 -1.96118101e-01 -9.16654766e-01 3.48267555e-01 -1.96118370e-01 -9.15412068e-01 3.51540267e-01 -1.96118325e-01 -9.14134264e-01 3.54832143e-01 -1.96118400e-01 -9.12884355e-01 3.58043313e-01 -1.96118385e-01 -9.11631942e-01 3.61220807e-01 -1.96118400e-01 -9.10367429e-01 3.64394158e-01 -1.96118385e-01 -9.09089565e-01 3.67568582e-01 -1.96118385e-01 -9.07806695e-01 3.70728374e-01 -1.96118400e-01 -9.06503916e-01 3.73898059e-01 -1.96118385e-01 -9.05225813e-01 3.76985520e-01 -1.96118101e-01 -9.03945088e-01 3.80046815e-01 -1.96118385e-01 -9.02580678e-01 3.83273214e-01 -1.96118280e-01 -9.01201427e-01 3.86502653e-01 -1.96118385e-01 -8.99861038e-01 3.89614761e-01 -1.96118101e-01 -8.98512542e-01 3.92722040e-01 -1.96118414e-01 -8.97140682e-01 3.95840287e-01 -1.96118101e-01 -8.95769179e-01 3.98936063e-01 -1.96118400e-01 -8.94341171e-01 4.02128458e-01 -1.96118429e-01 -8.92905116e-01 4.05306756e-01 -1.96118385e-01 -8.91519725e-01 4.08337325e-01 -1.96118057e-01 -8.90103638e-01 4.11419481e-01 -1.96118191e-01 -8.88616979e-01 4.14618343e-01 -1.96118385e-01 -8.87174189e-01 4.17699069e-01 -1.96118370e-01 -8.85717332e-01 4.20782119e-01 -1.96118370e-01 -8.84253502e-01 4.23846722e-01 -1.96118325e-01 -8.82808745e-01 4.26856339e-01 -1.96118265e-01 -8.81291687e-01 4.29978281e-01 -1.96118236e-01 -8.79740417e-01 4.33137447e-01 -1.96118325e-01 -8.78228486e-01 4.36197013e-01 -1.96118325e-01 -8.76701772e-01 4.39254344e-01 -1.96118400e-01 -8.75166237e-01 4.42308575e-01 -1.96118325e-01 -8.73654902e-01 4.45286989e-01 -1.96118072e-01 -8.72135699e-01 4.48254347e-01 -1.96118385e-01 -8.70536745e-01 4.51352149e-01 -1.96118355e-01 -8.68915081e-01 4.54466581e-01 -1.96118385e-01 -8.67357612e-01 4.57432866e-01 -1.96118101e-01 -8.65763187e-01 4.60439533e-01 -1.96118355e-01 -8.64114463e-01 4.63528246e-01 -1.96118385e-01 -8.62492025e-01 4.66538697e-01 -1.96118370e-01 -8.60855162e-01 4.69556779e-01 -1.96118370e-01 -8.59203637e-01 4.72570449e-01 -1.96118385e-01 -8.57595801e-01 4.75476116e-01 -1.96118101e-01 -8.55937898e-01 4.78458226e-01 -1.96118370e-01 -8.54224324e-01 4.81513530e-01 -1.96118400e-01 -8.52530241e-01 4.84503806e-01 -1.96118385e-01 -8.50829780e-01 4.87486601e-01 -1.96118325e-01 -8.49142730e-01 4.90419060e-01 -1.96118370e-01 -8.47433865e-01 4.93364036e-01 -1.96118206e-01 -8.45700204e-01 4.96330917e-01 -1.96118385e-01 -8.43960643e-01 4.99281347e-01 -1.96118385e-01 -8.42252135e-01 5.02159536e-01 -1.96118057e-01 -8.40530157e-01 5.05037606e-01 -1.96118400e-01 -8.38713586e-01 5.08045316e-01 -1.96118429e-01 -8.36911678e-01 5.11012733e-01 -1.96118355e-01 -8.35121274e-01 5.13929605e-01 -1.96118400e-01 -8.33322048e-01 5.16846716e-01 -1.96118370e-01 -8.31518710e-01 5.19738853e-01 -1.96118370e-01 -8.29742610e-01 5.22571862e-01 -1.96118057e-01 -8.27907264e-01 5.25473654e-01 -1.96118161e-01 -8.26014698e-01 5.28443873e-01 -1.96118400e-01 -8.24217379e-01 5.31239748e-01 -1.96118057e-01 -8.22361171e-01 5.34109592e-01 -1.96118206e-01 -8.20462525e-01 5.37021041e-01 -1.96118280e-01 -8.18580449e-01 5.39888084e-01 -1.96118385e-01 -8.16667736e-01 5.42774677e-01 -1.96118355e-01 -8.14772367e-01 5.45617044e-01 -1.96118370e-01 -8.12919676e-01 5.48375368e-01 -1.96118012e-01 -8.10991645e-01 5.51220655e-01 -1.96118072e-01 -8.09002340e-01 5.54137468e-01 -1.96118370e-01 -8.07069540e-01 5.56949377e-01 -1.96118370e-01 -8.05172324e-01 5.59686840e-01 -1.96118057e-01 -8.03227901e-01 5.62471926e-01 -1.96118236e-01 -8.01214218e-01 5.65341473e-01 -1.96118295e-01 -7.99226761e-01 5.68144262e-01 -1.96118429e-01 -7.97221661e-01 5.70957363e-01 -1.96118325e-01 -7.95283139e-01 5.73648214e-01 -1.96118042e-01 -7.93315530e-01 5.76370835e-01 -1.96118400e-01 -7.91238010e-01 5.79215884e-01 -1.96118400e-01 -7.89164066e-01 5.82041204e-01 -1.96118400e-01 -7.87114501e-01 5.84808946e-01 -1.96118325e-01 -7.85070360e-01 5.87549567e-01 -1.96118385e-01 -7.83025205e-01 5.90274513e-01 -1.96118370e-01 -7.80965269e-01 5.92999518e-01 -1.96118385e-01 -7.78887987e-01 5.95722735e-01 -1.96118370e-01 -7.76814699e-01 5.98423541e-01 -1.96118325e-01 -7.74761438e-01 6.01078451e-01 -1.96117878e-01 -7.72668898e-01 6.03764474e-01 -1.96118057e-01 -7.70476878e-01 6.06563509e-01 -1.96118340e-01 -7.68360138e-01 6.09241009e-01 -1.96118370e-01 -7.66220093e-01 6.11933112e-01 -1.96118370e-01 -7.64081120e-01 6.14600658e-01 -1.96118370e-01 -7.61948943e-01 6.17240727e-01 -1.96118370e-01 -7.59847164e-01 6.19822919e-01 -1.96117967e-01 -7.57696450e-01 6.22455597e-01 -1.96118295e-01 -7.55438983e-01 6.25192463e-01 -1.96118370e-01 -7.53320336e-01 6.27741754e-01 -1.96117923e-01 -7.51129687e-01 6.30362749e-01 -1.96118161e-01 -7.48864174e-01 6.33052409e-01 -1.96118265e-01 -7.46656895e-01 6.35651112e-01 -1.96118385e-01 -7.44405568e-01 6.38288498e-01 -1.96118400e-01 -7.42178261e-01 6.40878439e-01 -1.96118355e-01 -7.40004838e-01 6.43387437e-01 -1.96118101e-01 -7.37743855e-01 6.45975530e-01 -1.96118146e-01 -7.35392869e-01 6.48652315e-01 -1.96118400e-01 -7.33113825e-01 6.51227355e-01 -1.96118385e-01 -7.30844438e-01 6.53774500e-01 -1.96118325e-01 -7.28569627e-01 6.56305909e-01 -1.96118370e-01 -7.26280034e-01 6.58843338e-01 -1.96118370e-01 -7.23973632e-01 6.61371410e-01 -1.96118370e-01 -7.21667528e-01 6.63891852e-01 -1.96118325e-01 -7.19405234e-01 6.66341305e-01 -1.96118057e-01 -7.17072368e-01 6.68848813e-01 -1.96118161e-01 -7.14653492e-01 6.71433568e-01 -1.96118385e-01 -7.12303936e-01 6.73924565e-01 -1.96118370e-01 -7.09935963e-01 6.76419854e-01 -1.96118385e-01 -7.07583010e-01 6.78874850e-01 -1.96118370e-01 -7.05223739e-01 6.81339860e-01 -1.96118370e-01 -7.02889204e-01 6.83746278e-01 -1.96118057e-01 -7.00510740e-01 6.86179340e-01 -1.96118325e-01 -6.98051393e-01 6.88682079e-01 -1.96118385e-01 -6.95690095e-01 6.91070497e-01 -1.96117967e-01 -6.93273008e-01 6.93475664e-01 -1.96118414e-01 -6.90797031e-01 6.95961058e-01 -1.96118325e-01 -6.88360751e-01 6.98369741e-01 -1.96118325e-01 -6.85925722e-01 7.00758576e-01 -1.96118265e-01 -6.83477104e-01 7.03150451e-01 -1.96118146e-01 -6.81108415e-01 7.05444813e-01 -1.96118027e-01 -6.78607643e-01 7.07841039e-01 -1.96118414e-01 -6.76072598e-01 7.10270882e-01 -1.96118325e-01 -6.73587561e-01 7.12622106e-01 -1.96118325e-01 -6.71078146e-01 7.14984953e-01 -1.96118176e-01 -6.68590724e-01 7.17310190e-01 -1.96118370e-01 -6.66087866e-01 7.19638109e-01 -1.96118221e-01 -6.63568854e-01 7.21964419e-01 -1.96118385e-01 -6.61038995e-01 7.24277496e-01 -1.96118325e-01 -6.58511162e-01 7.26580143e-01 -1.96118325e-01 -6.56042159e-01 7.28808224e-01 -1.96118057e-01 -6.53501689e-01 7.31086612e-01 -1.96118176e-01 -6.50867641e-01 7.33434379e-01 -1.96118325e-01 -6.48300588e-01 7.35703409e-01 -1.96118370e-01 -6.45734787e-01 7.37954974e-01 -1.96118370e-01 -6.43166363e-01 7.40196288e-01 -1.96118101e-01 -6.40601456e-01 7.42417276e-01 -1.96118057e-01 -6.38022959e-01 7.44633734e-01 -1.96118400e-01 -6.35353446e-01 7.46913552e-01 -1.96118340e-01 -6.32798135e-01 7.49079823e-01 -1.96118027e-01 -6.30203843e-01 7.51262486e-01 -1.96118250e-01 -6.27510011e-01 7.53515840e-01 -1.96118370e-01 -6.24882281e-01 7.55694151e-01 -1.96118325e-01 -6.22245431e-01 7.57869482e-01 -1.96118191e-01 -6.19634390e-01 7.60001838e-01 -1.96117938e-01 -6.16985500e-01 7.62157977e-01 -1.96118429e-01 -6.14255130e-01 7.64357507e-01 -1.96118370e-01 -6.11653447e-01 7.66440988e-01 -1.96118057e-01 -6.08972788e-01 7.68573165e-01 -1.96118236e-01 -6.06282413e-01 7.70696700e-01 -1.96117938e-01 -6.03630483e-01 7.72775471e-01 -1.96118400e-01 -6.00827157e-01 7.74958313e-01 -1.96118206e-01 -5.98167360e-01 7.77013004e-01 -1.96117908e-01 -5.95500588e-01 7.79058933e-01 -1.96118265e-01 -5.92735350e-01 7.81163931e-01 -1.96118042e-01 -5.90014160e-01 7.83222556e-01 -1.96118414e-01 -5.87273896e-01 7.85276949e-01 -1.96118057e-01 -5.84559023e-01 7.87299573e-01 -1.96118385e-01 -5.81685960e-01 7.89425552e-01 -1.96118101e-01 -5.78928232e-01 7.91450024e-01 -1.96118370e-01 -5.76243937e-01 7.93407738e-01 -1.96117967e-01 -5.73539674e-01 7.95362592e-01 -1.96118400e-01 -5.70673287e-01 7.97424018e-01 -1.96118400e-01 -5.67919254e-01 7.99388707e-01 -1.96117938e-01 -5.65131187e-01 8.01363647e-01 -1.96118414e-01 -5.62325954e-01 8.03331196e-01 -1.96117997e-01 -5.59519529e-01 8.05286527e-01 -1.96118400e-01 -5.56633651e-01 8.07286918e-01 -1.96118370e-01 -5.53803027e-01 8.09231699e-01 -1.96118340e-01 -5.51047444e-01 8.11107755e-01 -1.96118057e-01 -5.48284233e-01 8.12981427e-01 -1.96118355e-01 -5.45368791e-01 8.14938188e-01 -1.96118400e-01 -5.42511463e-01 8.16841900e-01 -1.96118057e-01 -5.39678156e-01 8.18718970e-01 -1.96118429e-01 -5.36811948e-01 8.20599794e-01 -1.96118057e-01 -5.33981264e-01 8.22443783e-01 -1.96118414e-01 -5.31027377e-01 8.24353933e-01 -1.96118325e-01 -5.28128505e-01 8.26215208e-01 -1.96118370e-01 -5.25219262e-01 8.28067005e-01 -1.96118370e-01 -5.22311270e-01 8.29905093e-01 -1.96118370e-01 -5.19416869e-01 8.31719935e-01 -1.96118221e-01 -5.16599238e-01 8.33474219e-01 -1.96118027e-01 -5.13694704e-01 8.35266471e-01 -1.96118400e-01 -5.10660291e-01 8.37125897e-01 -1.96118385e-01 -5.07720649e-01 8.38910341e-01 -1.96118385e-01 -5.04895747e-01 8.40614021e-01 -1.96117923e-01 -5.01953542e-01 8.42374802e-01 -1.96118429e-01 -4.98905569e-01 8.44183743e-01 -1.96118265e-01 -4.96060640e-01 8.45858872e-01 -1.96117952e-01 -4.93125141e-01 8.47573400e-01 -1.96118325e-01 -4.90133554e-01 8.49307775e-01 -1.96118027e-01 -4.87189412e-01 8.50998819e-01 -1.96118221e-01 -4.84124303e-01 8.52747023e-01 -1.96118325e-01 -4.81169879e-01 8.54419053e-01 -1.96118295e-01 -4.78277206e-01 8.56038392e-01 -1.96118325e-01 -4.75256503e-01 8.57718587e-01 -1.96118236e-01 -4.72184420e-01 8.59415591e-01 -1.96118057e-01 -4.69270289e-01 8.61010492e-01 -1.96117967e-01 -4.66269612e-01 8.62638533e-01 -1.96117908e-01 -4.63225275e-01 8.64276707e-01 -1.96118057e-01 -4.60242420e-01 8.65869224e-01 -1.96118400e-01 -4.57201958e-01 8.67478609e-01 -1.96118101e-01 -4.54188943e-01 8.69058907e-01 -1.96118400e-01 -4.51094985e-01 8.70669842e-01 -1.96118370e-01 -4.48033780e-01 8.72249126e-01 -1.96118340e-01 -4.44973558e-01 8.73814046e-01 -1.96118385e-01 -4.41983968e-01 8.75330746e-01 -1.96118057e-01 -4.38938528e-01 8.76861393e-01 -1.96118400e-01 -4.35817719e-01 8.78416836e-01 -1.96118370e-01 -4.32722241e-01 8.79944742e-01 -1.96118057e-01 -4.29705679e-01 8.81422818e-01 -1.96117863e-01 -4.26649302e-01 8.82908285e-01 -1.96118385e-01 -4.23496991e-01 8.84420931e-01 -1.96118370e-01 -4.20399159e-01 8.85897875e-01 -1.96118370e-01 -4.17308331e-01 8.87358844e-01 -1.96118295e-01 -4.14283574e-01 8.88774574e-01 -1.96118087e-01 -4.11173582e-01 8.90218973e-01 -1.96118429e-01 -4.07982200e-01 8.91683578e-01 -1.96118385e-01 -4.04868335e-01 8.93103600e-01 -1.96118325e-01 -4.01856601e-01 8.94463599e-01 -1.96117967e-01 -3.98750722e-01 8.95852745e-01 -1.96118355e-01 -3.95525813e-01 8.97280812e-01 -1.96118355e-01 -3.92457426e-01 8.98628652e-01 -1.96118057e-01 -3.89325321e-01 8.99988532e-01 -1.96118385e-01 -3.86175871e-01 9.01339889e-01 -1.96118057e-01 -3.83098304e-01 9.02655065e-01 -1.96118370e-01 -3.79927933e-01 9.03995991e-01 -1.96118325e-01 -3.76729280e-01 9.05331850e-01 -1.96118400e-01 -3.73480082e-01 9.06677365e-01 -1.96118325e-01 -3.70309949e-01 9.07977164e-01 -1.96118101e-01 -3.67147803e-01 9.09260988e-01 -1.96118355e-01 -3.64011675e-01 9.10519540e-01 -1.96118101e-01 -3.60839009e-01 9.11782742e-01 -1.96118400e-01 -3.57611567e-01 9.13053989e-01 -1.96118370e-01 -3.54406148e-01 9.14297462e-01 -1.96118206e-01 -3.51300538e-01 9.15504754e-01 -1.96118027e-01 -3.48118424e-01 9.16712940e-01 -1.96118414e-01 -3.44837040e-01 9.17946517e-01 -1.96118370e-01 -3.41612548e-01 9.19150531e-01 -1.96118325e-01 -3.38508874e-01 9.20299649e-01 -1.96117908e-01 -3.35376054e-01 9.21454668e-01 -1.96118027e-01 -3.32061857e-01 9.22651887e-01 -1.96118400e-01 -3.28840971e-01 9.23806667e-01 -1.96118027e-01 -3.25644314e-01 9.24936950e-01 -1.96118414e-01 -3.22405457e-01 9.26071227e-01 -1.96118057e-01 -3.19186300e-01 9.27185714e-01 -1.96118400e-01 -3.15892339e-01 9.28312361e-01 -1.96118325e-01 -3.12703460e-01 9.29392040e-01 -1.96118057e-01 -3.09456557e-01 9.30476606e-01 -1.96118400e-01 -3.06193709e-01 9.31555867e-01 -1.96118057e-01 -3.02928388e-01 9.32623565e-01 -1.96118414e-01 -2.99682707e-01 9.33673024e-01 -1.96118012e-01 -2.96429008e-01 9.34710205e-01 -1.96118414e-01 -2.93082893e-01 9.35763419e-01 -1.96118101e-01 -2.89815724e-01 9.36781228e-01 -1.96118325e-01 -2.86535293e-01 9.37789023e-01 -1.96118325e-01 -2.83285290e-01 9.38775599e-01 -1.96118295e-01 -2.80007988e-01 9.39759016e-01 -1.96118370e-01 -2.76724100e-01 9.40733552e-01 -1.96118325e-01 -2.73435742e-01 9.41693962e-01 -1.96118325e-01 -2.70230055e-01 9.42616999e-01 -1.96118057e-01 -2.66930103e-01 9.43558574e-01 -1.96118414e-01 -2.63581604e-01 9.44498241e-01 -1.96118101e-01 -2.60278493e-01 9.45414543e-01 -1.96118355e-01 -2.57038146e-01 9.46302533e-01 -1.96118057e-01 -2.53816545e-01 9.47170794e-01 -1.96118370e-01 -2.50446171e-01 9.48066115e-01 -1.96118414e-01 -2.47125179e-01 9.48938429e-01 -1.96118101e-01 -2.43813336e-01 9.49793637e-01 -1.96118414e-01 -2.40508884e-01 9.50634062e-01 -1.96118057e-01 -2.37177923e-01 9.51471508e-01 -1.96118280e-01 -2.33746946e-01 9.52322721e-01 -1.96118370e-01 -2.30513602e-01 9.53110158e-01 -1.96118027e-01 -2.27182791e-01 9.53909814e-01 -1.96118131e-01 -2.23865688e-01 9.54692066e-01 -1.96117938e-01 -2.20551640e-01 9.55462992e-01 -1.96118250e-01 -2.17196956e-01 9.56231236e-01 -1.96118012e-01 -2.13974729e-01 9.56959009e-01 -1.96118370e-01 -2.10509807e-01 9.57725644e-01 -1.96118116e-01 -2.07065463e-01 9.58476305e-01 -1.96118325e-01 -2.03713998e-01 9.59193826e-01 -1.96118370e-01 -2.00369805e-01 9.59899366e-01 -1.96118206e-01 -1.97140455e-01 9.60566580e-01 -1.96117982e-01 -1.93756744e-01 9.61254299e-01 -1.96118176e-01 -1.90287173e-01 9.61947560e-01 -1.96118370e-01 -1.86934918e-01 9.62604821e-01 -1.96118325e-01 -1.83570504e-01 9.63252127e-01 -1.96118370e-01 -1.80306405e-01 9.63866949e-01 -1.96117967e-01 -1.76951081e-01 9.64487791e-01 -1.96118280e-01 -1.73576549e-01 9.65107858e-01 -1.96118057e-01 -1.70206189e-01 9.65708077e-01 -1.96118325e-01 -1.66733906e-01 9.66307342e-01 -1.96118295e-01 -1.63446471e-01 9.66870725e-01 -1.96118027e-01 -1.60083070e-01 9.67433333e-01 -1.96118340e-01 -1.56697839e-01 9.67985272e-01 -1.96117967e-01 -1.53337285e-01 9.68524396e-01 -1.96118414e-01 -1.49836317e-01 9.69072580e-01 -1.96118370e-01 -1.46554872e-01 9.69573736e-01 -1.96118027e-01 -1.43171072e-01 9.70079720e-01 -1.96118385e-01 -1.39767841e-01 9.70574737e-01 -1.96118057e-01 -1.36375383e-01 9.71059620e-01 -1.96118325e-01 -1.32900238e-01 9.71541703e-01 -1.96118325e-01 -1.29582807e-01 9.71985996e-01 -1.96118042e-01 -1.26205057e-01 9.72432435e-01 -1.96118400e-01 -1.22707568e-01 9.72880363e-01 -1.96118325e-01 -1.19321860e-01 9.73300278e-01 -1.96118325e-01 -1.16020739e-01 9.73698676e-01 -1.96118027e-01 -1.12716161e-01 9.74086642e-01 -1.96118325e-01 -1.09215215e-01 9.74486589e-01 -1.96118414e-01 -1.05718076e-01 9.74870801e-01 -1.96118101e-01 -1.02302231e-01 9.75236297e-01 -1.96118385e-01 -9.88909006e-02 9.75586176e-01 -1.96118370e-01 -9.55782086e-02 9.75918829e-01 -1.96117997e-01 -9.21901911e-02 9.76245403e-01 -1.96118385e-01 -8.87844414e-02 9.76560652e-01 -1.96117938e-01 -8.53815675e-02 9.76864159e-01 -1.96118250e-01 -8.18478540e-02 9.77165818e-01 -1.96118325e-01 -7.85527378e-02 9.77436721e-01 -1.96117997e-01 -7.51534626e-02 9.77703333e-01 -1.96118414e-01 -7.17270374e-02 9.77961063e-01 -1.96117997e-01 -6.83007985e-02 9.78205740e-01 -1.96118146e-01 -6.47748560e-02 9.78446126e-01 -1.96118370e-01 -6.13633990e-02 9.78663325e-01 -1.96118206e-01 -5.79396412e-02 9.78873491e-01 -1.96118370e-01 -5.46027683e-02 9.79067206e-01 -1.96117938e-01 -5.12089469e-02 9.79246914e-01 -1.96118340e-01 -4.77695242e-02 9.79424179e-01 -1.96118027e-01 -4.44609001e-02 9.79579270e-01 -1.96118325e-01 -4.09437902e-02 9.79731143e-01 -1.96118385e-01 -3.74249518e-02 9.79872346e-01 -1.96118340e-01 -3.40005867e-02 9.79997039e-01 -1.96118370e-01 -3.05715110e-02 9.80110765e-01 -1.96118370e-01 -2.72381473e-02 9.80209231e-01 -1.96117997e-01 -2.39301492e-02 9.80298102e-01 -1.96118370e-01 -2.04024371e-02 9.80370760e-01 -1.96118400e-01 -1.68662835e-02 9.80447829e-01 -1.96118325e-01 -1.34626571e-02 9.80490267e-01 -1.96118325e-01 -1.01661403e-02 9.80533779e-01 -1.96117967e-01 -6.72981841e-03 9.80571091e-01 -1.96118385e-01 -3.25447251e-03 9.80586767e-01 -1.96117997e-01 1.26918836e-04 9.80588198e-01 -1.96118429e-01 3.64781730e-03 9.80586648e-01 -1.96118325e-01 6.98954798e-03 9.80567873e-01 -1.96118057e-01 1.04066795e-02 9.80532348e-01 -1.96118414e-01 1.38281798e-02 9.80486035e-01 -1.96118027e-01 1.72393378e-02 9.80442405e-01 -1.96118429e-01 2.06840914e-02 9.80368078e-01 -1.96118027e-01 2.40223408e-02 9.80294347e-01 -1.96118325e-01 2.75164749e-02 9.80203152e-01 -1.96118400e-01 3.10212504e-02 9.80097115e-01 -1.96118325e-01 3.44494395e-02 9.79983747e-01 -1.96118325e-01 3.78504619e-02 9.79857743e-01 -1.96118325e-01 4.11969423e-02 9.79723513e-01 -1.96118057e-01 4.46078293e-02 9.79571462e-01 -1.96118310e-01 4.81320471e-02 9.79406774e-01 -1.96118370e-01 5.15392907e-02 9.79228735e-01 -1.96118370e-01 5.49310185e-02 9.79049385e-01 -1.96118370e-01 5.82737885e-02 9.78854477e-01 -1.96118057e-01 6.16821535e-02 9.78642881e-01 -1.96118280e-01 6.51948899e-02 9.78416502e-01 -1.96118325e-01 6.86214641e-02 9.78181601e-01 -1.96118370e-01 7.20511749e-02 9.77937341e-01 -1.96118370e-01 7.53716826e-02 9.77685869e-01 -1.96118057e-01 7.87669197e-02 9.77418244e-01 -1.96118087e-01 8.22031647e-02 9.77135658e-01 -1.96117967e-01 8.55650157e-02 9.76846635e-01 -1.96118414e-01 8.91253352e-02 9.76528764e-01 -1.96118385e-01 9.24233571e-02 9.76220965e-01 -1.96117833e-01 9.58035067e-02 9.75895941e-01 -1.96118191e-01 9.92545411e-02 9.75551605e-01 -1.96118057e-01 1.02631003e-01 9.75201666e-01 -1.96118340e-01 1.06064096e-01 9.74834383e-01 -1.96117967e-01 1.09437920e-01 9.74462450e-01 -1.96118325e-01 1.12939164e-01 9.74060476e-01 -1.96118340e-01 1.16342045e-01 9.73660290e-01 -1.96118370e-01 1.19726822e-01 9.73250568e-01 -1.96118370e-01 1.23052724e-01 9.72838819e-01 -1.96118101e-01 1.26356035e-01 9.72411513e-01 -1.96118340e-01 1.29824877e-01 9.71955538e-01 -1.96118385e-01 1.33301228e-01 9.71485972e-01 -1.96118370e-01 1.36712283e-01 9.71010983e-01 -1.96118370e-01 1.40094191e-01 9.70527768e-01 -1.96118325e-01 1.43412784e-01 9.70042884e-01 -1.96118027e-01 1.46772429e-01 9.69540656e-01 -1.96118206e-01 1.50175914e-01 9.69019771e-01 -1.96118057e-01 1.53554961e-01 9.68488872e-01 -1.96118072e-01 1.57026649e-01 9.67932880e-01 -1.96118370e-01 1.60319820e-01 9.67393935e-01 -1.96118057e-01 1.63681671e-01 9.66831267e-01 -1.96118295e-01 1.67054489e-01 9.66252506e-01 -1.96118087e-01 1.70345321e-01 9.65682089e-01 -1.96118370e-01 1.73787177e-01 9.65067625e-01 -1.96118280e-01 1.77256688e-01 9.64432120e-01 -1.96118325e-01 1.80628985e-01 9.63807404e-01 -1.96118385e-01 1.83878735e-01 9.63192642e-01 -1.96118101e-01 1.87258691e-01 9.62540925e-01 -1.96118400e-01 1.90615788e-01 9.61883247e-01 -1.96118101e-01 1.93886414e-01 9.61227655e-01 -1.96118385e-01 1.97326362e-01 9.60529208e-01 -1.96118355e-01 2.00763673e-01 9.59814668e-01 -1.96118385e-01 2.04108015e-01 9.59110320e-01 -1.96118370e-01 2.07461923e-01 9.58390296e-01 -1.96118385e-01 2.10721940e-01 9.57676351e-01 -1.96118101e-01 2.14043573e-01 9.56943929e-01 -1.96118191e-01 2.17477813e-01 9.56166387e-01 -1.96118370e-01 2.20814407e-01 9.55403149e-01 -1.96118370e-01 2.24155515e-01 9.54626262e-01 -1.96118370e-01 2.27404967e-01 9.53856528e-01 -1.96118027e-01 2.30630919e-01 9.53084111e-01 -1.96118370e-01 2.33970091e-01 9.52265799e-01 -1.96118325e-01 2.37360939e-01 9.51424897e-01 -1.96118340e-01 2.40761086e-01 9.50570762e-01 -1.96118370e-01 2.44019926e-01 9.49741066e-01 -1.96118101e-01 2.47326240e-01 9.48884845e-01 -1.96118250e-01 2.50640363e-01 9.48016226e-01 -1.96118057e-01 2.53922462e-01 9.47141826e-01 -1.96118265e-01 2.57336169e-01 9.46220458e-01 -1.96118385e-01 2.60560900e-01 9.45335627e-01 -1.96118057e-01 2.63848573e-01 9.44423854e-01 -1.96118101e-01 2.67164558e-01 9.43490982e-01 -1.96117893e-01 2.70425111e-01 9.42561507e-01 -1.96118176e-01 2.73798108e-01 9.41588283e-01 -1.96118146e-01 2.77015924e-01 9.40646291e-01 -1.96118072e-01 2.80289769e-01 9.39676225e-01 -1.96118206e-01 2.83673048e-01 9.38658476e-01 -1.96118370e-01 2.86925346e-01 9.37671959e-01 -1.96118265e-01 2.90088058e-01 9.36697900e-01 -1.96118057e-01 2.93276340e-01 9.35704410e-01 -1.96118370e-01 2.96549499e-01 9.34672415e-01 -1.96118400e-01 2.99918711e-01 9.33594227e-01 -1.96118087e-01 3.03286493e-01 9.32507217e-01 -1.96118400e-01 3.06520432e-01 9.31449234e-01 -1.96118400e-01 3.09701025e-01 9.30397093e-01 -1.96117997e-01 3.12850356e-01 9.29343581e-01 -1.96118385e-01 3.16084921e-01 9.28246558e-01 -1.96118370e-01 3.19379449e-01 9.27118540e-01 -1.96118280e-01 3.22711647e-01 9.25963283e-01 -1.96118400e-01 3.25875968e-01 9.24856246e-01 -1.96118057e-01 3.29089969e-01 9.23717558e-01 -1.96118131e-01 3.32332164e-01 9.22553480e-01 -1.96118101e-01 3.35517347e-01 9.21401858e-01 -1.96118221e-01 3.38842750e-01 9.20178831e-01 -1.96118400e-01 3.42038989e-01 9.18991625e-01 -1.96118370e-01 3.45242590e-01 9.17794704e-01 -1.96118400e-01 3.48383784e-01 9.16610718e-01 -1.96118101e-01 3.51566374e-01 9.15401399e-01 -1.96118176e-01 3.54766756e-01 9.14159000e-01 -1.96118072e-01 3.57855618e-01 9.12957489e-01 -1.96118385e-01 3.61137897e-01 9.11664367e-01 -1.96118385e-01 3.64401400e-01 9.10363734e-01 -1.96118370e-01 3.67555380e-01 9.09093916e-01 -1.96118370e-01 3.70716542e-01 9.07811046e-01 -1.96118325e-01 3.73824865e-01 9.06533539e-01 -1.96118087e-01 3.76897275e-01 9.05261636e-01 -1.96118385e-01 3.80138278e-01 9.03905451e-01 -1.96118221e-01 3.83362144e-01 9.02541935e-01 -1.96118325e-01 3.86498600e-01 9.01203394e-01 -1.96118385e-01 3.89591128e-01 8.99871707e-01 -1.96118101e-01 3.92660141e-01 8.98539126e-01 -1.96118370e-01 3.95775408e-01 8.97170186e-01 -1.96118340e-01 3.98965716e-01 8.95756423e-01 -1.96118146e-01 4.02161568e-01 8.94326150e-01 -1.96118385e-01 4.05221343e-01 8.92942786e-01 -1.96118101e-01 4.08257544e-01 8.91556859e-01 -1.96118385e-01 4.11349356e-01 8.90135646e-01 -1.96118370e-01 4.14463162e-01 8.88691127e-01 -1.96118400e-01 4.17554855e-01 8.87242794e-01 -1.96118385e-01 4.20679599e-01 8.85765016e-01 -1.96118400e-01 4.23839718e-01 8.84256601e-01 -1.96118400e-01 4.26931620e-01 8.82771194e-01 -1.96118370e-01 4.29942310e-01 8.81309152e-01 -1.96118221e-01 4.32973444e-01 8.79821658e-01 -1.96118370e-01 4.36026543e-01 8.78313422e-01 -1.96118325e-01 4.39160645e-01 8.76750052e-01 -1.96118385e-01 4.42283541e-01 8.75179112e-01 -1.96118370e-01 4.45333391e-01 8.73630285e-01 -1.96118385e-01 4.48321581e-01 8.72100651e-01 -1.96118057e-01 4.51280862e-01 8.70572448e-01 -1.96118385e-01 4.54316109e-01 8.68994832e-01 -1.96118385e-01 4.57410276e-01 8.67367864e-01 -1.96118250e-01 4.60499585e-01 8.65732372e-01 -1.96118370e-01 4.63518947e-01 8.64120841e-01 -1.96118400e-01 4.66470689e-01 8.62528324e-01 -1.96118101e-01 4.69421655e-01 8.60929847e-01 -1.96118370e-01 4.72423762e-01 8.59284699e-01 -1.96118385e-01 4.75463092e-01 8.57603371e-01 -1.96118221e-01 4.78543311e-01 8.55889857e-01 -1.96118400e-01 4.81464893e-01 8.54251027e-01 -1.96118101e-01 4.84406412e-01 8.52585971e-01 -1.96118131e-01 4.87410843e-01 8.50873768e-01 -1.96118042e-01 4.90294635e-01 8.49213004e-01 -1.96118370e-01 4.93343711e-01 8.47446740e-01 -1.96118355e-01 4.96296555e-01 8.45720291e-01 -1.96118101e-01 4.99240726e-01 8.43984902e-01 -1.96118206e-01 5.02181172e-01 8.42238545e-01 -1.96118057e-01 5.05111217e-01 8.40485871e-01 -1.96118250e-01 5.08078814e-01 8.38693440e-01 -1.96118250e-01 5.10914683e-01 8.36970985e-01 -1.96118325e-01 5.13877630e-01 8.35153878e-01 -1.96118057e-01 5.16814172e-01 8.33340824e-01 -1.96118101e-01 5.19714355e-01 8.31534147e-01 -1.96118221e-01 5.22625625e-01 8.29707205e-01 -1.96118101e-01 5.25413215e-01 8.27945769e-01 -1.96118370e-01 5.28332949e-01 8.26085329e-01 -1.96118400e-01 5.31212628e-01 8.24236512e-01 -1.96118191e-01 5.34133375e-01 8.22345912e-01 -1.96118280e-01 5.37081897e-01 8.20424557e-01 -1.96118400e-01 5.39877355e-01 8.18588734e-01 -1.96118101e-01 5.42642295e-01 8.16753864e-01 -1.96118370e-01 5.45488656e-01 8.14858496e-01 -1.96118385e-01 5.48398733e-01 8.12905252e-01 -1.96118429e-01 5.51289022e-01 8.10945034e-01 -1.96118355e-01 5.54078698e-01 8.09042573e-01 -1.96118101e-01 5.56841671e-01 8.07143569e-01 -1.96118206e-01 5.59639215e-01 8.05205941e-01 -1.96118265e-01 5.62485695e-01 8.03218484e-01 -1.96118385e-01 5.65311790e-01 8.01234543e-01 -1.96117997e-01 5.68032682e-01 7.99306512e-01 -1.96118012e-01 5.70816875e-01 7.97319949e-01 -1.96117908e-01 5.73646188e-01 7.95285821e-01 -1.96115524e-01 5.76406479e-01 7.93286920e-01 -1.96115568e-01 5.79146683e-01 7.91285574e-01 -1.96115881e-01 5.81481099e-01 7.89565861e-01 -1.96117371e-01 5.84357202e-01 7.87441552e-01 -1.96117356e-01 5.86705208e-01 7.85693884e-01 -1.96117297e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.03768075e-01 6.82823420e-01 -1.96117356e-01 7.05712736e-01 6.80816174e-01 -1.96116850e-01 7.07779586e-01 6.78671002e-01 -1.96116075e-01 7.10286915e-01 6.76050484e-01 -1.96116954e-01 7.12467015e-01 6.73751056e-01 -1.96118027e-01 7.14864373e-01 6.71208382e-01 -1.96118370e-01 7.17280984e-01 6.68624640e-01 -1.96118101e-01 7.19570935e-01 6.66160464e-01 -1.96117908e-01 7.21827269e-01 6.63717985e-01 -1.96118146e-01 7.24133015e-01 6.61198080e-01 -1.96118325e-01 7.26437867e-01 6.58667266e-01 -1.96118325e-01 7.28787899e-01 6.56066537e-01 -1.96118087e-01 7.31139243e-01 6.53440595e-01 -1.96118385e-01 7.33352780e-01 6.50959313e-01 -1.96118027e-01 7.35549569e-01 6.48474753e-01 -1.96118385e-01 7.37815678e-01 6.45893812e-01 -1.96118385e-01 7.40073621e-01 6.43306613e-01 -1.96118385e-01 7.42365360e-01 6.40662074e-01 -1.96118414e-01 7.44594038e-01 6.38070107e-01 -1.96118057e-01 7.46758103e-01 6.35532916e-01 -1.96118385e-01 7.48978794e-01 6.32916987e-01 -1.96118370e-01 7.51230359e-01 6.30242288e-01 -1.96118325e-01 7.53434479e-01 6.27606750e-01 -1.96118101e-01 7.55556464e-01 6.25049114e-01 -1.96118385e-01 7.57803082e-01 6.22328103e-01 -1.96118206e-01 7.60021448e-01 6.19612336e-01 -1.96118385e-01 7.62178004e-01 6.16957664e-01 -1.96118385e-01 7.64267266e-01 6.14366531e-01 -1.96118057e-01 7.66357720e-01 6.11760259e-01 -1.96118385e-01 7.68469751e-01 6.09101355e-01 -1.96118370e-01 7.70657122e-01 6.06334448e-01 -1.96118072e-01 7.72836626e-01 6.03552639e-01 -1.96118400e-01 7.74925888e-01 6.00868523e-01 -1.96118385e-01 7.76959896e-01 5.98234713e-01 -1.96118057e-01 7.79005527e-01 5.95570266e-01 -1.96118400e-01 7.81087041e-01 5.92837870e-01 -1.96118385e-01 7.83188105e-01 5.90059102e-01 -1.96118325e-01 7.85306275e-01 5.87234378e-01 -1.96118400e-01 7.87300646e-01 5.84559619e-01 -1.96118101e-01 7.89278269e-01 5.81885159e-01 -1.96118370e-01 7.91301489e-01 5.79130292e-01 -1.96118400e-01 7.93377817e-01 5.76284051e-01 -1.96118131e-01 7.95383990e-01 5.73510051e-01 -1.96118101e-01 7.97317505e-01 5.70822179e-01 -1.96118400e-01 7.99356759e-01 5.67962289e-01 -1.96118176e-01 8.01348031e-01 5.65151751e-01 -1.96118101e-01 8.03315878e-01 5.62347353e-01 -1.96118057e-01 8.05276990e-01 5.59535444e-01 -1.96117967e-01 8.07159483e-01 5.56819141e-01 -1.96118385e-01 8.09151351e-01 5.53922057e-01 -1.96118146e-01 8.11135709e-01 5.51008642e-01 -1.96118370e-01 8.13058972e-01 5.48168182e-01 -1.96118400e-01 8.14918280e-01 5.45397699e-01 -1.96118057e-01 8.16749871e-01 5.42650878e-01 -1.96118370e-01 8.18645418e-01 5.39787292e-01 -1.96118400e-01 8.20580900e-01 5.36840975e-01 -1.96118131e-01 8.22507918e-01 5.33884704e-01 -1.96118385e-01 8.24309587e-01 5.31097710e-01 -1.96118027e-01 8.26093435e-01 5.28320074e-01 -1.96118370e-01 8.27930152e-01 5.25435686e-01 -1.96118370e-01 8.29769433e-01 5.22529006e-01 -1.96118400e-01 8.31645250e-01 5.19537210e-01 -1.96117952e-01 8.33522260e-01 5.16521275e-01 -1.96118325e-01 8.35264862e-01 5.13693869e-01 -1.96118057e-01 8.37000966e-01 5.10864973e-01 -1.96118400e-01 8.38770151e-01 5.07952929e-01 -1.96118370e-01 8.40532005e-01 5.05033970e-01 -1.96118370e-01 8.42293978e-01 5.02088428e-01 -1.96118400e-01 8.44066381e-01 4.99103695e-01 -1.96118400e-01 8.45801353e-01 4.96158153e-01 -1.96118101e-01 8.47502291e-01 4.93247479e-01 -1.96118400e-01 8.49265993e-01 4.90202874e-01 -1.96118206e-01 8.50984216e-01 4.87215787e-01 -1.96118027e-01 8.52623880e-01 4.84339207e-01 -1.96118400e-01 8.54379654e-01 4.81238574e-01 -1.96118012e-01 8.56107533e-01 4.78153825e-01 -1.96118400e-01 8.57764602e-01 4.75172698e-01 -1.96118250e-01 8.59367013e-01 4.72272605e-01 -1.96118101e-01 8.60974848e-01 4.69337136e-01 -1.96118385e-01 8.62611413e-01 4.66318250e-01 -1.96118400e-01 8.64232481e-01 4.63309646e-01 -1.96118370e-01 8.65881860e-01 4.60216075e-01 -1.96118101e-01 8.67532074e-01 4.57099378e-01 -1.96118385e-01 8.69083107e-01 4.54145223e-01 -1.96118072e-01 8.70610714e-01 4.51208442e-01 -1.96118385e-01 8.72192502e-01 4.48144883e-01 -1.96118400e-01 8.73796999e-01 4.45005715e-01 -1.96118295e-01 8.75378489e-01 4.41888779e-01 -1.96118385e-01 8.76880646e-01 4.38898385e-01 -1.96118057e-01 8.78363788e-01 4.35923487e-01 -1.96118385e-01 8.79863739e-01 4.32888359e-01 -1.96118385e-01 8.81410182e-01 4.29733545e-01 -1.96118310e-01 8.82916093e-01 4.26632494e-01 -1.96118101e-01 8.84355366e-01 4.23633486e-01 -1.96118400e-01 8.85861158e-01 4.20474708e-01 -1.96118250e-01 8.87325943e-01 4.17376667e-01 -1.96118101e-01 8.88773203e-01 4.14290249e-01 -1.96118161e-01 8.90227556e-01 4.11154419e-01 -1.96118101e-01 8.91608000e-01 4.08147305e-01 -1.96118370e-01 8.93064499e-01 4.04953092e-01 -1.96118176e-01 8.94515812e-01 4.01739478e-01 -1.96118400e-01 8.95907700e-01 3.98626357e-01 -1.96118370e-01 8.97267103e-01 3.95553142e-01 -1.96118101e-01 8.98610115e-01 3.92496407e-01 -1.96118370e-01 8.99966180e-01 3.89373988e-01 -1.96118385e-01 9.01319504e-01 3.86225402e-01 -1.96118385e-01 9.02693868e-01 3.83006901e-01 -1.96118131e-01 9.04035628e-01 3.79829109e-01 -1.96118057e-01 9.05310869e-01 3.76782268e-01 -1.96118400e-01 9.06620145e-01 3.73618364e-01 -1.96118400e-01 9.07925487e-01 3.70436996e-01 -1.96118370e-01 9.09239054e-01 3.67202252e-01 -1.96118146e-01 9.10555243e-01 3.63926440e-01 -1.96118400e-01 9.11790371e-01 3.60821366e-01 -1.96118027e-01 9.13002431e-01 3.57745737e-01 -1.96118400e-01 9.14243639e-01 3.54542404e-01 -1.96118370e-01 9.15515006e-01 3.51267666e-01 -1.96118206e-01 9.16746438e-01 3.48026484e-01 -1.96118325e-01 9.17919934e-01 3.44906211e-01 -1.96118325e-01 9.19136405e-01 3.41651708e-01 -1.96118101e-01 9.20358360e-01 3.38356882e-01 -1.96118370e-01 9.21535552e-01 3.35155129e-01 -1.96118385e-01 9.22666669e-01 3.32014591e-01 -1.96118101e-01 9.23790574e-01 3.28884721e-01 -1.96118400e-01 9.24961269e-01 3.25577736e-01 -1.96118042e-01 9.26131546e-01 3.22229445e-01 -1.96118400e-01 9.27256048e-01 3.18985552e-01 -1.96118385e-01 9.28328276e-01 3.15843076e-01 -1.96118057e-01 9.29388821e-01 3.12714279e-01 -1.96118370e-01 9.30480421e-01 3.09447974e-01 -1.96118400e-01 9.31560159e-01 3.06183100e-01 -1.96118370e-01 9.32638049e-01 3.02887470e-01 -1.96118250e-01 9.33728158e-01 2.99505323e-01 -1.96118400e-01 9.34739590e-01 2.96335280e-01 -1.96118101e-01 9.35743451e-01 2.93154329e-01 -1.96118400e-01 9.36762154e-01 2.89876431e-01 -1.96118370e-01 9.37785029e-01 2.86553830e-01 -1.96118027e-01 9.38803613e-01 2.83192217e-01 -1.96118385e-01 9.39767420e-01 2.79982239e-01 -1.96118101e-01 9.40714061e-01 2.76788086e-01 -1.96118400e-01 9.41672862e-01 2.73507208e-01 -1.96118385e-01 9.42630231e-01 2.70182997e-01 -1.96118414e-01 9.43578780e-01 2.66859204e-01 -1.96118221e-01 9.44484711e-01 2.63634592e-01 -1.96118385e-01 9.45399761e-01 2.60329187e-01 -1.96118400e-01 9.46300864e-01 2.57044911e-01 -1.96118370e-01 9.47204709e-01 2.53681928e-01 -1.96118176e-01 9.48100269e-01 2.50316113e-01 -1.96118101e-01 9.48943734e-01 2.47104377e-01 -1.96118355e-01 9.49795008e-01 2.43807822e-01 -1.96118400e-01 9.50659811e-01 2.40403578e-01 -1.96118236e-01 9.51509476e-01 2.37021968e-01 -1.96118385e-01 9.52330112e-01 2.33716071e-01 -1.96118370e-01 9.53123510e-01 2.30459675e-01 -1.96118101e-01 9.53902483e-01 2.27210268e-01 -1.96118385e-01 9.54687059e-01 2.23892301e-01 -1.96118385e-01 9.55485582e-01 2.20452502e-01 -1.96118057e-01 9.56249714e-01 2.17112407e-01 -1.96118087e-01 9.56988215e-01 2.13843271e-01 -1.96118370e-01 9.57724869e-01 2.10508347e-01 -1.96118385e-01 9.58461761e-01 2.07129136e-01 -1.96118400e-01 9.59175587e-01 2.03798503e-01 -1.96118325e-01 9.59891438e-01 2.00407535e-01 -1.96118221e-01 9.60586131e-01 1.97046757e-01 -1.96118101e-01 9.61263418e-01 1.93716228e-01 -1.96118250e-01 9.61950362e-01 1.90272674e-01 -1.96118385e-01 9.62612808e-01 1.86896116e-01 -1.96118400e-01 9.63241398e-01 1.83618128e-01 -1.96118101e-01 9.63859737e-01 1.80352315e-01 -1.96118370e-01 9.64495420e-01 1.76912367e-01 -1.96118057e-01 9.65127766e-01 1.73463374e-01 -1.96118370e-01 9.65727389e-01 1.70094490e-01 -1.96118400e-01 9.66299951e-01 1.66776419e-01 -1.96118101e-01 9.66863573e-01 1.63495049e-01 -1.96118385e-01 9.67425585e-01 1.60124063e-01 -1.96118400e-01 9.67978716e-01 1.56748042e-01 -1.96118385e-01 9.68532205e-01 1.53290048e-01 -1.96118221e-01 9.69074011e-01 1.49822563e-01 -1.96118385e-01 9.69579339e-01 1.46512106e-01 -1.96118101e-01 9.70068216e-01 1.43247992e-01 -1.96118385e-01 9.70564187e-01 1.39839977e-01 -1.96118400e-01 9.71059740e-01 1.36367127e-01 -1.96118176e-01 9.71541047e-01 1.32899120e-01 -1.96118385e-01 9.71985877e-01 1.29595503e-01 -1.96118101e-01 9.72422957e-01 1.26277938e-01 -1.96118385e-01 9.72857714e-01 1.22889638e-01 -1.96118385e-01 9.73277509e-01 1.19507909e-01 -1.96118400e-01 9.73690927e-01 1.16091900e-01 -1.96118385e-01 9.74091649e-01 1.12674884e-01 -1.96118414e-01 9.74489689e-01 1.09186091e-01 -1.96118191e-01 9.74863231e-01 1.05799690e-01 -1.96118101e-01 9.75225389e-01 1.02406405e-01 -1.96118191e-01 9.75577056e-01 9.89883468e-02 -1.96118101e-01 9.75908160e-01 9.56747606e-02 -1.96118385e-01 9.76247013e-01 9.21915621e-02 -1.96118161e-01 9.76568758e-01 8.86954144e-02 -1.96118385e-01 9.76871848e-01 8.52958634e-02 -1.96118370e-01 9.77157295e-01 8.19478258e-02 -1.96118295e-01 9.77432311e-01 7.86068141e-02 -1.96118370e-01 9.77696896e-01 7.52246454e-02 -1.96118385e-01 9.77961361e-01 7.17088208e-02 -1.96118161e-01 9.78209794e-01 6.82176650e-02 -1.96118400e-01 9.78435934e-01 6.49115667e-02 -1.96118057e-01 9.78650451e-01 6.15926869e-02 -1.96118400e-01 9.78860855e-01 5.81449233e-02 -1.96118400e-01 9.79060531e-01 5.47342151e-02 -1.96118400e-01 9.79247153e-01 5.12396842e-02 -1.96118176e-01 9.79427159e-01 4.77071479e-02 -1.96118385e-01 9.79581416e-01 4.43873815e-02 -1.96118027e-01 9.79727209e-01 4.10761498e-02 -1.96118385e-01 9.79864120e-01 3.76589522e-02 -1.96118400e-01 9.79992867e-01 3.41170803e-02 -1.96117997e-01 9.80107427e-01 3.06859743e-02 -1.96118101e-01 9.80207086e-01 2.73818094e-02 -1.96118385e-01 9.80297446e-01 2.39522196e-02 -1.96118400e-01 9.80369449e-01 2.05151979e-02 -1.96118385e-01 9.80444193e-01 1.71005167e-02 -1.96118400e-01 9.80486453e-01 1.36774583e-02 -1.96118400e-01 9.80535805e-01 1.02513339e-02 -1.96118385e-01 9.80573058e-01 6.74228743e-03 -1.96118012e-01 9.80587065e-01 3.20849358e-03 -1.96118385e-01 9.80588257e-01 -2.11387349e-04 -1.96118400e-01 9.80586767e-01 -3.64892278e-03 -1.96118385e-01 9.80568767e-01 -6.96607353e-03 -1.96118057e-01 9.80535805e-01 -1.02766939e-02 -1.96118400e-01 9.80485916e-01 -1.37048531e-02 -1.96118400e-01 9.80442286e-01 -1.72420237e-02 -1.96118072e-01 9.80364442e-01 -2.07827482e-02 -1.96118385e-01 9.80291367e-01 -2.41696425e-02 -1.96118370e-01 9.80203986e-01 -2.74871010e-02 -1.96118057e-01 9.80100036e-01 -3.09187453e-02 -1.96117938e-01 9.79986846e-01 -3.43611538e-02 -1.96118101e-01 9.79862928e-01 -3.76951024e-02 -1.96118400e-01 9.79727864e-01 -4.11016420e-02 -1.96118385e-01 9.79572356e-01 -4.46021594e-02 -1.96118057e-01 9.79406595e-01 -4.81270999e-02 -1.96118385e-01 9.79230464e-01 -5.15380353e-02 -1.96118400e-01 9.79050338e-01 -5.48813753e-02 -1.96118101e-01 9.78858769e-01 -5.81907034e-02 -1.96118385e-01 9.78648484e-01 -6.15935661e-02 -1.96118400e-01 9.78422940e-01 -6.51117489e-02 -1.96118027e-01 9.78182137e-01 -6.86259568e-02 -1.96118414e-01 9.77937281e-01 -7.20662326e-02 -1.96118400e-01 9.77685392e-01 -7.53859058e-02 -1.96118057e-01 9.77425694e-01 -7.86878169e-02 -1.96118385e-01 9.77144718e-01 -8.20956677e-02 -1.96118400e-01 9.76845264e-01 -8.56053084e-02 -1.96118042e-01 9.76537108e-01 -8.90253112e-02 -1.96118101e-01 9.76233304e-01 -9.23080072e-02 -1.96118400e-01 9.75904405e-01 -9.57331359e-02 -1.96118385e-01 9.75561619e-01 -9.91487056e-02 -1.96118400e-01 9.75209057e-01 -1.02568530e-01 -1.96118385e-01 9.74838555e-01 -1.06027186e-01 -1.96118161e-01 9.74462807e-01 -1.09436974e-01 -1.96118101e-01 9.74084258e-01 -1.12747081e-01 -1.96118385e-01 9.73677576e-01 -1.16208538e-01 -1.96118236e-01 9.73265290e-01 -1.19615689e-01 -1.96118101e-01 9.72841024e-01 -1.23025388e-01 -1.96117863e-01 9.72391427e-01 -1.26509249e-01 -1.96118325e-01 9.71959651e-01 -1.29792556e-01 -1.96118250e-01 9.71498489e-01 -1.33208588e-01 -1.96118176e-01 9.71016407e-01 -1.36679366e-01 -1.96118370e-01 9.70543504e-01 -1.39990091e-01 -1.96118101e-01 9.70049262e-01 -1.43369645e-01 -1.96118072e-01 9.69538450e-01 -1.46777377e-01 -1.96118116e-01 9.69022930e-01 -1.50156766e-01 -1.96118206e-01 9.68494177e-01 -1.53529987e-01 -1.96118101e-01 9.67953920e-01 -1.56900257e-01 -1.96118206e-01 9.67400551e-01 -1.60277084e-01 -1.96118101e-01 9.66835797e-01 -1.63654506e-01 -1.96118161e-01 9.66242313e-01 -1.67108297e-01 -1.96118400e-01 9.65655982e-01 -1.70493439e-01 -1.96118400e-01 9.65070605e-01 -1.73776075e-01 -1.96118161e-01 9.64467645e-01 -1.77057162e-01 -1.96118400e-01 9.63845432e-01 -1.80427268e-01 -1.96118400e-01 9.63190794e-01 -1.83882430e-01 -1.96118087e-01 9.62531984e-01 -1.87313139e-01 -1.96118370e-01 9.61873949e-01 -1.90653920e-01 -1.96118400e-01 9.61217940e-01 -1.93937451e-01 -1.96118101e-01 9.60550845e-01 -1.97219282e-01 -1.96118400e-01 9.59853828e-01 -2.00575829e-01 -1.96118400e-01 9.59129512e-01 -2.04016641e-01 -1.96118161e-01 9.58418489e-01 -2.07338423e-01 -1.96118101e-01 9.57687914e-01 -2.10679159e-01 -1.96118116e-01 9.56943810e-01 -2.14039624e-01 -1.96118101e-01 9.56194818e-01 -2.17359081e-01 -1.96118325e-01 9.55428779e-01 -2.20699951e-01 -1.96118191e-01 9.54650581e-01 -2.24051595e-01 -1.96118072e-01 9.53862250e-01 -2.27382258e-01 -1.96118101e-01 9.53092873e-01 -2.30588332e-01 -1.96118400e-01 9.52255845e-01 -2.34013453e-01 -1.96118236e-01 9.51430321e-01 -2.37341270e-01 -1.96118101e-01 9.50595319e-01 -2.40661725e-01 -1.96117997e-01 9.49730337e-01 -2.44058907e-01 -1.96118370e-01 9.48899329e-01 -2.47270495e-01 -1.96118280e-01 9.48028445e-01 -2.50595838e-01 -1.96118101e-01 9.47144926e-01 -2.53911436e-01 -1.96118101e-01 9.46283698e-01 -2.57100940e-01 -1.96118385e-01 9.45350528e-01 -2.60501087e-01 -1.96117952e-01 9.44433570e-01 -2.63820022e-01 -1.96118101e-01 9.43512499e-01 -2.67090410e-01 -1.96118116e-01 9.42543745e-01 -2.70489246e-01 -1.96118400e-01 9.41615462e-01 -2.73702353e-01 -1.96118101e-01 9.40688908e-01 -2.76867986e-01 -1.96118385e-01 9.39694643e-01 -2.80231029e-01 -1.96118116e-01 9.38680291e-01 -2.83601046e-01 -1.96118400e-01 9.37674880e-01 -2.86914676e-01 -1.96118400e-01 9.36688662e-01 -2.90118515e-01 -1.96118101e-01 9.35705721e-01 -2.93271184e-01 -1.96118370e-01 9.34682965e-01 -2.96518266e-01 -1.96118400e-01 9.33618069e-01 -2.99850225e-01 -1.96118236e-01 9.32532847e-01 -3.03207368e-01 -1.96118400e-01 9.31470215e-01 -3.06455880e-01 -1.96118400e-01 9.30413485e-01 -3.09650421e-01 -1.96118116e-01 9.29359198e-01 -3.12800258e-01 -1.96118385e-01 9.28264201e-01 -3.16037178e-01 -1.96118400e-01 9.27132964e-01 -3.19337219e-01 -1.96118250e-01 9.26008403e-01 -3.22582364e-01 -1.96118101e-01 9.24877405e-01 -3.25813591e-01 -1.96118236e-01 9.23739672e-01 -3.29027086e-01 -1.96118057e-01 9.22587574e-01 -3.32243741e-01 -1.96118027e-01 9.21413004e-01 -3.35491985e-01 -1.96118116e-01 9.20235038e-01 -3.38691443e-01 -1.96118250e-01 9.19039726e-01 -3.41906279e-01 -1.96118101e-01 9.17876542e-01 -3.45022678e-01 -1.96118400e-01 9.16665614e-01 -3.48240435e-01 -1.96118400e-01 9.15419996e-01 -3.51520330e-01 -1.96118131e-01 9.14170504e-01 -3.54734540e-01 -1.96118101e-01 9.12935495e-01 -3.57916623e-01 -1.96118057e-01 9.11678612e-01 -3.61103296e-01 -1.96118057e-01 9.10421133e-01 -3.64260048e-01 -1.96118176e-01 9.09139693e-01 -3.67446095e-01 -1.96118101e-01 9.07893538e-01 -3.70513916e-01 -1.96118385e-01 9.06559408e-01 -3.73765945e-01 -1.96118042e-01 9.05242324e-01 -3.76945525e-01 -1.96118087e-01 9.03921545e-01 -3.80100012e-01 -1.96118012e-01 9.02545333e-01 -3.83353025e-01 -1.96118385e-01 9.01237428e-01 -3.86417300e-01 -1.96118101e-01 8.99927139e-01 -3.89463395e-01 -1.96118385e-01 8.98533762e-01 -3.92672628e-01 -1.96118221e-01 8.97120655e-01 -3.95887703e-01 -1.96118385e-01 8.95725310e-01 -3.99034232e-01 -1.96118400e-01 8.94356966e-01 -4.02096182e-01 -1.96118101e-01 8.92983437e-01 -4.05129343e-01 -1.96118325e-01 8.91577542e-01 -4.08209682e-01 -1.96118385e-01 8.90109897e-01 -4.11406159e-01 -1.96118206e-01 8.88631821e-01 -4.14588571e-01 -1.96118385e-01 8.87177765e-01 -4.17691141e-01 -1.96118385e-01 8.85743976e-01 -4.20726269e-01 -1.96118116e-01 8.84304583e-01 -4.23737228e-01 -1.96118385e-01 8.82818580e-01 -4.26835001e-01 -1.96118400e-01 8.81284297e-01 -4.29994404e-01 -1.96118206e-01 8.79762948e-01 -4.33091879e-01 -1.96118295e-01 8.78251195e-01 -4.36149746e-01 -1.96118400e-01 8.76732588e-01 -4.39194769e-01 -1.96118101e-01 8.75246286e-01 -4.42151397e-01 -1.96118370e-01 8.73708665e-01 -4.45181966e-01 -1.96118385e-01 8.72099221e-01 -4.48327959e-01 -1.96118131e-01 8.70516300e-01 -4.51387763e-01 -1.96118057e-01 8.68986666e-01 -4.54329282e-01 -1.96118400e-01 8.67391944e-01 -4.57363933e-01 -1.96118370e-01 8.65736961e-01 -4.60491270e-01 -1.96118012e-01 8.64125729e-01 -4.63509142e-01 -1.96118057e-01 8.62521768e-01 -4.66486603e-01 -1.96118072e-01 8.60869408e-01 -4.69531924e-01 -1.96118057e-01 8.59282494e-01 -4.72426862e-01 -1.96118400e-01 8.57621133e-01 -4.75431263e-01 -1.96118400e-01 8.55915368e-01 -4.78498012e-01 -1.96118221e-01 8.54239643e-01 -4.81484920e-01 -1.96118072e-01 8.52561057e-01 -4.84449655e-01 -1.96118385e-01 8.50863516e-01 -4.87428963e-01 -1.96118101e-01 8.49157155e-01 -4.90393192e-01 -1.96118176e-01 8.47413063e-01 -4.93401200e-01 -1.96118325e-01 8.45718145e-01 -4.96300817e-01 -1.96118370e-01 8.44008744e-01 -4.99202162e-01 -1.96118370e-01 8.42265189e-01 -5.02134740e-01 -1.96118385e-01 8.40464175e-01 -5.05145669e-01 -1.96118131e-01 8.38642120e-01 -5.08163333e-01 -1.96118400e-01 8.36904407e-01 -5.11023939e-01 -1.96118057e-01 8.35166514e-01 -5.13857186e-01 -1.96118400e-01 8.33370745e-01 -5.16768157e-01 -1.96118385e-01 8.31522584e-01 -5.19734442e-01 -1.96118057e-01 8.29648077e-01 -5.22720516e-01 -1.96118385e-01 8.27829123e-01 -5.25596142e-01 -1.96118385e-01 8.26047659e-01 -5.28389633e-01 -1.96118146e-01 8.24193001e-01 -5.31280041e-01 -1.96118161e-01 8.22279513e-01 -5.34236789e-01 -1.96118370e-01 8.20403636e-01 -5.37111044e-01 -1.96118400e-01 8.18523288e-01 -5.39975524e-01 -1.96118385e-01 8.16683054e-01 -5.42749107e-01 -1.96118101e-01 8.14847708e-01 -5.45504928e-01 -1.96118400e-01 8.12929034e-01 -5.48362613e-01 -1.96118414e-01 8.10958803e-01 -5.51268339e-01 -1.96118325e-01 8.08989882e-01 -5.54155290e-01 -1.96118400e-01 8.07050407e-01 -5.56978822e-01 -1.96118370e-01 8.05141270e-01 -5.59731841e-01 -1.96118131e-01 8.03191483e-01 -5.62524080e-01 -1.96118206e-01 8.01222920e-01 -5.65330625e-01 -1.96118101e-01 7.99242795e-01 -5.68122506e-01 -1.96118206e-01 7.97248006e-01 -5.70921481e-01 -1.96118101e-01 7.95298040e-01 -5.73627949e-01 -1.96118400e-01 7.93282986e-01 -5.76416671e-01 -1.96118400e-01 7.91268229e-01 -5.79176784e-01 -1.96118370e-01 7.89202571e-01 -5.81988692e-01 -1.96118206e-01 7.87098765e-01 -5.84831834e-01 -1.96118385e-01 7.85120964e-01 -5.87482214e-01 -1.96118057e-01 7.83080935e-01 -5.90202332e-01 -1.96118072e-01 7.80997217e-01 -5.92955828e-01 -1.96118101e-01 7.78939366e-01 -5.95656395e-01 -1.96118325e-01 7.76863754e-01 -5.98360002e-01 -1.96118101e-01 7.74806917e-01 -6.01020277e-01 -1.96118400e-01 7.72656083e-01 -6.03782594e-01 -1.96118429e-01 7.70496190e-01 -6.06537879e-01 -1.96118414e-01 7.68405497e-01 -6.09182894e-01 -1.96118057e-01 7.66332924e-01 -6.11789823e-01 -1.96118385e-01 7.64202297e-01 -6.14449859e-01 -1.96118400e-01 7.61996329e-01 -6.17184877e-01 -1.96118072e-01 7.59825885e-01 -6.19849563e-01 -1.96118101e-01 7.57726550e-01 -6.22415960e-01 -1.96118400e-01 7.55545616e-01 -6.25063717e-01 -1.96118385e-01 7.53366947e-01 -6.27687454e-01 -1.96118400e-01 7.51174867e-01 -6.30309105e-01 -1.96118385e-01 7.48895884e-01 -6.33013725e-01 -1.96118131e-01 7.46673286e-01 -6.35633707e-01 -1.96118057e-01 7.44525611e-01 -6.38147950e-01 -1.96118400e-01 7.42297828e-01 -6.40738785e-01 -1.96118400e-01 7.40023792e-01 -6.43364489e-01 -1.96118429e-01 7.37720728e-01 -6.46003187e-01 -1.96118385e-01 7.35425174e-01 -6.48614943e-01 -1.96118400e-01 7.33197033e-01 -6.51132882e-01 -1.96118101e-01 7.30975986e-01 -6.53626323e-01 -1.96118385e-01 7.28646398e-01 -6.56222820e-01 -1.96118265e-01 7.26359725e-01 -6.58754289e-01 -1.96118101e-01 7.24051714e-01 -6.61287248e-01 -1.96118221e-01 7.21740007e-01 -6.63810790e-01 -1.96118072e-01 7.19484568e-01 -6.66254401e-01 -1.96118385e-01 7.17147708e-01 -6.68766856e-01 -1.96118385e-01 7.14756966e-01 -6.71322823e-01 -1.96118131e-01 7.12396860e-01 -6.73825085e-01 -1.96118101e-01 7.10055351e-01 -6.76297486e-01 -1.96118221e-01 7.07675815e-01 -6.78777397e-01 -1.96118057e-01 7.05326080e-01 -6.81234241e-01 -1.96118027e-01 7.02926159e-01 -6.83706343e-01 -1.96118057e-01 7.00594664e-01 -6.86092913e-01 -1.96118385e-01 6.98148012e-01 -6.88584507e-01 -1.96118176e-01 6.95720792e-01 -6.91039920e-01 -1.96118101e-01 6.93296313e-01 -6.93450868e-01 -1.96118250e-01 6.90821826e-01 -6.95937276e-01 -1.96118400e-01 6.88457608e-01 -6.98273957e-01 -1.96117997e-01 6.86098635e-01 -7.00587988e-01 -1.96118370e-01 6.83653176e-01 -7.02978969e-01 -1.96118370e-01 6.81135893e-01 -7.05420554e-01 -1.96118414e-01 6.78635776e-01 -7.07811415e-01 -1.96117833e-01 6.76271319e-01 -7.10074425e-01 -1.96116507e-01 6.73698246e-01 -7.12514520e-01 -1.96115822e-01 6.71269357e-01 -7.14801967e-01 -1.96116000e-01 6.68974757e-01 -7.16946602e-01 -1.96117178e-01 6.66537046e-01 -7.19211698e-01 -1.96117371e-01 6.64303601e-01 -7.21275389e-01 -1.96117297e-01 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. 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. 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. 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. 0. 0. 5.58505774e-01 -8.05983424e-01 -1.96117282e-01 5.56041181e-01 -8.07685375e-01 -1.96117356e-01 5.53731561e-01 -8.09270859e-01 -1.96117267e-01 5.51171899e-01 -8.11019301e-01 -1.96116433e-01 5.48138142e-01 -8.13078344e-01 -1.96117371e-01 5.45462072e-01 -8.14875782e-01 -1.96118325e-01 5.42571604e-01 -8.16801667e-01 -1.96118414e-01 5.39697528e-01 -8.18704844e-01 -1.96118101e-01 5.36884427e-01 -8.20552528e-01 -1.96118385e-01 5.33967674e-01 -8.22454691e-01 -1.96118429e-01 5.31085610e-01 -8.24318051e-01 -1.96118057e-01 5.28273702e-01 -8.26123357e-01 -1.96118400e-01 5.25375009e-01 -8.27967465e-01 -1.96118385e-01 5.22485971e-01 -8.29796135e-01 -1.96118385e-01 5.19589305e-01 -8.31611454e-01 -1.96118400e-01 5.16681015e-01 -8.33424687e-01 -1.96118385e-01 5.13772249e-01 -8.35217535e-01 -1.96118385e-01 5.10867596e-01 -8.37000847e-01 -1.96118385e-01 5.07947564e-01 -8.38773191e-01 -1.96118385e-01 5.05007684e-01 -8.40548337e-01 -1.96118400e-01 5.02037048e-01 -8.42323661e-01 -1.96118429e-01 4.99091953e-01 -8.44073713e-01 -1.96118325e-01 4.96187836e-01 -8.45784664e-01 -1.96118385e-01 4.93234366e-01 -8.47510576e-01 -1.96118400e-01 4.90207046e-01 -8.49263966e-01 -1.96118236e-01 4.87240255e-01 -8.50969493e-01 -1.96118101e-01 4.84347314e-01 -8.52618575e-01 -1.96118400e-01 4.81373698e-01 -8.54303956e-01 -1.96118400e-01 4.78402048e-01 -8.55968654e-01 -1.96118385e-01 4.75399733e-01 -8.57638299e-01 -1.96118385e-01 4.72404242e-01 -8.59295011e-01 -1.96118400e-01 4.69413728e-01 -8.60933304e-01 -1.96118385e-01 4.66394901e-01 -8.62571061e-01 -1.96118385e-01 4.63393450e-01 -8.64186704e-01 -1.96118400e-01 4.60365951e-01 -8.65803003e-01 -1.96118400e-01 4.57319528e-01 -8.67416561e-01 -1.96118400e-01 4.54249978e-01 -8.69026601e-01 -1.96118221e-01 4.51193690e-01 -8.70617926e-01 -1.96118101e-01 4.48219329e-01 -8.72155011e-01 -1.96118400e-01 4.45160836e-01 -8.73718321e-01 -1.96118385e-01 4.42110121e-01 -8.75266433e-01 -1.96118385e-01 4.39053088e-01 -8.76803756e-01 -1.96118400e-01 4.36003566e-01 -8.78323853e-01 -1.96118385e-01 4.32949424e-01 -8.79833341e-01 -1.96118400e-01 4.29858416e-01 -8.81349146e-01 -1.96118400e-01 4.26790804e-01 -8.82838368e-01 -1.96118385e-01 4.23683345e-01 -8.84331226e-01 -1.96118400e-01 4.20527905e-01 -8.85837317e-01 -1.96118265e-01 4.17420924e-01 -8.87305737e-01 -1.96118101e-01 4.14310962e-01 -8.88763189e-01 -1.96118042e-01 4.11184967e-01 -8.90212953e-01 -1.96118101e-01 4.08179104e-01 -8.91592741e-01 -1.96118385e-01 4.05070901e-01 -8.93012047e-01 -1.96118385e-01 4.01958019e-01 -8.94417465e-01 -1.96118385e-01 3.98722529e-01 -8.95865619e-01 -1.96117893e-01 3.95572454e-01 -8.97259772e-01 -1.96118027e-01 3.92556995e-01 -8.98584187e-01 -1.96118400e-01 3.89419556e-01 -8.99946809e-01 -1.96118385e-01 3.86260569e-01 -9.01304305e-01 -1.96118400e-01 3.83065104e-01 -9.02669370e-01 -1.96118414e-01 3.79928142e-01 -9.03995454e-01 -1.96118295e-01 3.76694441e-01 -9.05346632e-01 -1.96117938e-01 3.73514652e-01 -9.06662107e-01 -1.96118057e-01 3.70478213e-01 -9.07909393e-01 -1.96118385e-01 3.67248356e-01 -9.09219205e-01 -1.96118385e-01 3.63982528e-01 -9.10531878e-01 -1.96118414e-01 3.60758424e-01 -9.11815584e-01 -1.96118370e-01 3.57652336e-01 -9.13038015e-01 -1.96118057e-01 3.54556948e-01 -9.14238632e-01 -1.96118385e-01 3.51356238e-01 -9.15482342e-01 -1.96118400e-01 3.48164797e-01 -9.16694283e-01 -1.96118370e-01 3.44976425e-01 -9.17894602e-01 -1.96118400e-01 3.41748655e-01 -9.19099867e-01 -1.96118400e-01 3.38544071e-01 -9.20289099e-01 -1.96118370e-01 3.35338801e-01 -9.21467721e-01 -1.96118385e-01 3.32134634e-01 -9.22624946e-01 -1.96118385e-01 3.28897417e-01 -9.23785448e-01 -1.96118370e-01 3.25599194e-01 -9.24952328e-01 -1.96118221e-01 3.22350562e-01 -9.26089227e-01 -1.96118101e-01 3.19133759e-01 -9.27203298e-01 -1.96118280e-01 3.15873861e-01 -9.28318202e-01 -1.96118101e-01 3.12718689e-01 -9.29387867e-01 -1.96118385e-01 3.09391826e-01 -9.30498421e-01 -1.96118250e-01 3.06143463e-01 -9.31571007e-01 -1.96118027e-01 3.02867502e-01 -9.32642519e-01 -1.96118414e-01 2.99607724e-01 -9.33697224e-01 -1.96118101e-01 2.96430975e-01 -9.34708536e-01 -1.96118400e-01 2.93187052e-01 -9.35732424e-01 -1.96118385e-01 2.89916724e-01 -9.36750352e-01 -1.96118385e-01 2.86640793e-01 -9.37758744e-01 -1.96118400e-01 2.83279717e-01 -9.38776255e-01 -1.96118385e-01 2.79910475e-01 -9.39788342e-01 -1.96118385e-01 2.76726991e-01 -9.40732479e-01 -1.96118057e-01 2.73442268e-01 -9.41692829e-01 -1.96118250e-01 2.70063162e-01 -9.42665756e-01 -1.96118370e-01 2.66773015e-01 -9.43601787e-01 -1.96118400e-01 2.63569206e-01 -9.44503665e-01 -1.96118101e-01 2.60348111e-01 -9.45394099e-01 -1.96118370e-01 2.57053852e-01 -9.46297824e-01 -1.96118370e-01 2.53731549e-01 -9.47191358e-01 -1.96118385e-01 2.50443250e-01 -9.48066294e-01 -1.96118370e-01 2.47137383e-01 -9.48936045e-01 -1.96118400e-01 2.43754089e-01 -9.49808180e-01 -1.96118414e-01 2.40429237e-01 -9.50654209e-01 -1.96118101e-01 2.37128392e-01 -9.51483548e-01 -1.96118340e-01 2.33783215e-01 -9.52313185e-01 -1.96118101e-01 2.30525926e-01 -9.53107059e-01 -1.96118370e-01 2.27125123e-01 -9.53924835e-01 -1.96118370e-01 2.23803014e-01 -9.54707563e-01 -1.96118101e-01 2.20464483e-01 -9.55482900e-01 -1.96118280e-01 2.17048690e-01 -9.56264436e-01 -1.96118370e-01 2.13803217e-01 -9.56996322e-01 -1.96118072e-01 2.10552618e-01 -9.57714915e-01 -1.96118400e-01 2.07217067e-01 -9.58442926e-01 -1.96118370e-01 2.03871459e-01 -9.59159970e-01 -1.96118385e-01 2.00415090e-01 -9.59890068e-01 -1.96118161e-01 1.97048083e-01 -9.60586250e-01 -1.96118027e-01 1.93795800e-01 -9.61247504e-01 -1.96118370e-01 1.90452784e-01 -9.61914480e-01 -1.96118370e-01 1.87077805e-01 -9.62577641e-01 -1.96118325e-01 1.83628574e-01 -9.63240325e-01 -1.96118265e-01 1.80246904e-01 -9.63879228e-01 -1.96118027e-01 1.76881611e-01 -9.64501202e-01 -1.96118027e-01 1.73498243e-01 -9.65122402e-01 -1.96118057e-01 1.70230910e-01 -9.65703011e-01 -1.96118370e-01 1.66866139e-01 -9.66283619e-01 -1.96118385e-01 1.63470581e-01 -9.66866195e-01 -1.96118325e-01 1.60017222e-01 -9.67442513e-01 -1.96118295e-01 1.56641290e-01 -9.67996001e-01 -1.96118057e-01 1.53359026e-01 -9.68521595e-01 -1.96118325e-01 1.49968788e-01 -9.69052255e-01 -1.96118370e-01 1.46583468e-01 -9.69568431e-01 -1.96118385e-01 1.43114403e-01 -9.70088422e-01 -1.96118429e-01 1.39712393e-01 -9.70583797e-01 -1.96118101e-01 1.36333019e-01 -9.71065462e-01 -1.96118250e-01 1.32844642e-01 -9.71549571e-01 -1.96118385e-01 1.29531667e-01 -9.71993744e-01 -1.96118057e-01 1.26258150e-01 -9.72424924e-01 -1.96118370e-01 1.22857936e-01 -9.72862542e-01 -1.96118325e-01 1.19470201e-01 -9.73283112e-01 -1.96118370e-01 1.15978122e-01 -9.73704815e-01 -1.96118206e-01 1.12559050e-01 -9.74104941e-01 -1.96118027e-01 1.09273560e-01 -9.74479616e-01 -1.96118355e-01 1.05875090e-01 -9.74854290e-01 -1.96118325e-01 1.02481268e-01 -9.75217223e-01 -1.96118370e-01 9.89672691e-02 -9.75578845e-01 -1.96118250e-01 9.55474973e-02 -9.75921631e-01 -1.96118042e-01 9.21639204e-02 -9.76248324e-01 -1.96118385e-01 8.87473300e-02 -9.76562560e-01 -1.96118027e-01 8.53346735e-02 -9.76868391e-01 -1.96118355e-01 8.18332061e-02 -9.77165997e-01 -1.96118370e-01 7.84836188e-02 -9.77443099e-01 -1.96117938e-01 7.50998631e-02 -9.77708697e-01 -1.96118236e-01 7.16566816e-02 -9.77965534e-01 -1.96118057e-01 6.83467835e-02 -9.78201032e-01 -1.96118370e-01 6.49510249e-02 -9.78433311e-01 -1.96118385e-01 6.15292042e-02 -9.78654742e-01 -1.96118370e-01 5.80125712e-02 -9.78869617e-01 -1.96118325e-01 5.45961484e-02 -9.79066968e-01 -1.96118027e-01 5.11921160e-02 -9.79249656e-01 -1.96118325e-01 4.77707237e-02 -9.79423821e-01 -1.96118042e-01 4.43699993e-02 -9.79582846e-01 -1.96118206e-01 4.08411622e-02 -9.79736984e-01 -1.96118370e-01 3.75008509e-02 -9.79869246e-01 -1.96118027e-01 3.41870449e-02 -9.79990721e-01 -1.96118370e-01 3.06792147e-02 -9.80106890e-01 -1.96118414e-01 2.72491518e-02 -9.80210125e-01 -1.96118101e-01 2.38367077e-02 -9.80300188e-01 -1.96118355e-01 2.03986559e-02 -9.80372369e-01 -1.96118057e-01 1.70646887e-02 -9.80444193e-01 -1.96118370e-01 1.35813514e-02 -9.80487168e-01 -1.96118280e-01 1.01346420e-02 -9.80536044e-01 -1.96118057e-01 6.79764990e-03 -9.80571151e-01 -1.96118370e-01 3.37402825e-03 -9.80586827e-01 -1.96118325e-01 -2.77875388e-05 -9.80588198e-01 -1.96118370e-01 -3.42926849e-03 -9.80586886e-01 -1.96118400e-01 -6.86681829e-03 -9.80570614e-01 -1.96118370e-01 -1.03779426e-02 -9.80534494e-01 -1.96118206e-01 -1.38080344e-02 -9.80485857e-01 -1.96118027e-01 -1.72205735e-02 -9.80442584e-01 -1.96118340e-01 -2.07477193e-02 -9.80365396e-01 -1.96118400e-01 -2.40876023e-02 -9.80293036e-01 -1.96118057e-01 -2.73963176e-02 -9.80206013e-01 -1.96118370e-01 -3.08089051e-02 -9.80104089e-01 -1.96118370e-01 -3.43203954e-02 -9.79987144e-01 -1.96118087e-01 -3.78626585e-02 -9.79857206e-01 -1.96118370e-01 -4.11960706e-02 -9.79722857e-01 -1.96118057e-01 -4.45033275e-02 -9.79577005e-01 -1.96118385e-01 -4.79464121e-02 -9.79415476e-01 -1.96118385e-01 -5.13597801e-02 -9.79240239e-01 -1.96118370e-01 -5.48505671e-02 -9.79052722e-01 -1.96118325e-01 -5.82880825e-02 -9.78853643e-01 -1.96118057e-01 -6.16776831e-02 -9.78645325e-01 -1.96118280e-01 -6.51262775e-02 -9.78421509e-01 -1.96118087e-01 -6.84477314e-02 -9.78193402e-01 -1.96118370e-01 -7.19310120e-02 -9.77945328e-01 -1.96118370e-01 -7.53664374e-02 -9.77686763e-01 -1.96118057e-01 -7.87583664e-02 -9.77420151e-01 -1.96118280e-01 -8.21785778e-02 -9.77137089e-01 -1.96118101e-01 -8.55080709e-02 -9.76852119e-01 -1.96118385e-01 -8.89173076e-02 -9.76546943e-01 -1.96118385e-01 -9.23215896e-02 -9.76232171e-01 -1.96118400e-01 -9.58103687e-02 -9.75897014e-01 -1.96118310e-01 -9.92130265e-02 -9.75556016e-01 -1.96118057e-01 -1.02593780e-01 -9.75206137e-01 -1.96118236e-01 -1.06088169e-01 -9.74831402e-01 -1.96118325e-01 -1.09420687e-01 -9.74464238e-01 -1.96118101e-01 -1.12734854e-01 -9.74085689e-01 -1.96118385e-01 -1.16125435e-01 -9.73686337e-01 -1.96118385e-01 -1.19528823e-01 -9.73274827e-01 -1.96118400e-01 -1.23012222e-01 -9.72843468e-01 -1.96118146e-01 -1.26417920e-01 -9.72403109e-01 -1.96118027e-01 -1.29717916e-01 -9.71970320e-01 -1.96118385e-01 -1.33109316e-01 -9.71510828e-01 -1.96118370e-01 -1.36491880e-01 -9.71043050e-01 -1.96118385e-01 -1.39974982e-01 -9.70546544e-01 -1.96118176e-01 -1.43358961e-01 -9.70050514e-01 -1.96118101e-01 -1.46736473e-01 -9.69545484e-01 -1.96118429e-01 -1.50107428e-01 -9.69030380e-01 -1.96118072e-01 -1.53407052e-01 -9.68512356e-01 -1.96118370e-01 -1.56786591e-01 -9.67972457e-01 -1.96118385e-01 -1.60155758e-01 -9.67421234e-01 -1.96118385e-01 -1.63653448e-01 -9.66835380e-01 -1.96118161e-01 -1.67018279e-01 -9.66257989e-01 -1.96118057e-01 -1.70283809e-01 -9.65693116e-01 -1.96118370e-01 -1.73672289e-01 -9.65087593e-01 -1.96118400e-01 -1.77033648e-01 -9.64472175e-01 -1.96118370e-01 -1.80485800e-01 -9.63836432e-01 -1.96118191e-01 -1.83859035e-01 -9.63196933e-01 -1.96118101e-01 -1.87132984e-01 -9.62564230e-01 -1.96118370e-01 -1.90475777e-01 -9.61910844e-01 -1.96118370e-01 -1.93919286e-01 -9.61222768e-01 -1.96118236e-01 -1.97275281e-01 -9.60538745e-01 -1.96118057e-01 -2.00530902e-01 -9.59864080e-01 -1.96118370e-01 -2.03897685e-01 -9.59155083e-01 -1.96118385e-01 -2.07324192e-01 -9.58420634e-01 -1.96118310e-01 -2.10682228e-01 -9.57685530e-01 -1.96118027e-01 -2.13916555e-01 -9.56971467e-01 -1.96118385e-01 -2.17271775e-01 -9.56213832e-01 -1.96118385e-01 -2.20622838e-01 -9.55444872e-01 -1.96118385e-01 -2.24043131e-01 -9.54653323e-01 -1.96118101e-01 -2.27392673e-01 -9.53858912e-01 -1.96118057e-01 -2.30604544e-01 -9.53088343e-01 -1.96118370e-01 -2.33942240e-01 -9.52272952e-01 -1.96118370e-01 -2.37266615e-01 -9.51448977e-01 -1.96118370e-01 -2.40630478e-01 -9.50602949e-01 -1.96118429e-01 -2.43990153e-01 -9.49748456e-01 -1.96118101e-01 -2.47320607e-01 -9.48885381e-01 -1.96118236e-01 -2.50629067e-01 -9.48018491e-01 -1.96118057e-01 -2.53914475e-01 -9.47143972e-01 -1.96118414e-01 -2.57312357e-01 -9.46227014e-01 -1.96118385e-01 -2.60532349e-01 -9.45343196e-01 -1.96118027e-01 -2.63815790e-01 -9.44433689e-01 -1.96118414e-01 -2.67146289e-01 -9.43496406e-01 -1.96117967e-01 -2.70330518e-01 -9.42588747e-01 -1.96118370e-01 -2.73606867e-01 -9.41643357e-01 -1.96118400e-01 -2.76892632e-01 -9.40681934e-01 -1.96118370e-01 -2.80161262e-01 -9.39715207e-01 -1.96118340e-01 -2.83443958e-01 -9.38727200e-01 -1.96118400e-01 -2.86733180e-01 -9.37727451e-01 -1.96118385e-01 -2.90077180e-01 -9.36701477e-01 -1.96118191e-01 -2.93353051e-01 -9.35678959e-01 -1.96118027e-01 -2.96625227e-01 -9.34648156e-01 -1.96118370e-01 -2.99885809e-01 -9.33607459e-01 -1.96118057e-01 -3.03049594e-01 -9.32583869e-01 -1.96118370e-01 -3.06399941e-01 -9.31488991e-01 -1.96118236e-01 -3.09631586e-01 -9.30419385e-01 -1.96118101e-01 -3.12889040e-01 -9.29330945e-01 -1.96118429e-01 -3.16138119e-01 -9.28228736e-01 -1.96118057e-01 -3.19284678e-01 -9.27151740e-01 -1.96118355e-01 -3.22560847e-01 -9.26015198e-01 -1.96118429e-01 -3.25794578e-01 -9.24885452e-01 -1.96118101e-01 -3.29039842e-01 -9.23734069e-01 -1.96118325e-01 -3.32278371e-01 -9.22573328e-01 -1.96118101e-01 -3.35487276e-01 -9.21414971e-01 -1.96118340e-01 -3.38715106e-01 -9.20224667e-01 -1.96118057e-01 -3.41835827e-01 -9.19066727e-01 -1.96118385e-01 -3.45108926e-01 -9.17844772e-01 -1.96118385e-01 -3.48314166e-01 -9.16636407e-01 -1.96118072e-01 -3.51505101e-01 -9.15425837e-01 -1.96118325e-01 -3.54790837e-01 -9.14149404e-01 -1.96118385e-01 -3.57887089e-01 -9.12945211e-01 -1.96117982e-01 -3.60991538e-01 -9.11722720e-01 -1.96118370e-01 -3.64170164e-01 -9.10456359e-01 -1.96118370e-01 -3.67354274e-01 -9.09176826e-01 -1.96118355e-01 -3.70603800e-01 -9.07856584e-01 -1.96118131e-01 -3.73796701e-01 -9.06544507e-01 -1.96118027e-01 -3.76871973e-01 -9.05274034e-01 -1.96118370e-01 -3.80011261e-01 -9.03959155e-01 -1.96118325e-01 -3.83163899e-01 -9.02626514e-01 -1.96118370e-01 -3.86392504e-01 -9.01248336e-01 -1.96118414e-01 -3.89542609e-01 -8.99892271e-01 -1.96117997e-01 -3.92669857e-01 -8.98535371e-01 -1.96118325e-01 -3.95837635e-01 -8.97142172e-01 -1.96118057e-01 -3.98876965e-01 -8.95795763e-01 -1.96118385e-01 -4.02073771e-01 -8.94366443e-01 -1.96118295e-01 -4.05204087e-01 -8.92950594e-01 -1.96118027e-01 -4.08285379e-01 -8.91543150e-01 -1.96118325e-01 -4.11403328e-01 -8.90110314e-01 -1.96118027e-01 -4.14428860e-01 -8.88706863e-01 -1.96118370e-01 -4.17528749e-01 -8.87253821e-01 -1.96118370e-01 -4.20718819e-01 -8.85747194e-01 -1.96118400e-01 -4.23802823e-01 -8.84273410e-01 -1.96118027e-01 -4.26811874e-01 -8.82829309e-01 -1.96118370e-01 -4.29961383e-01 -8.81298900e-01 -1.96118265e-01 -4.33125347e-01 -8.79746377e-01 -1.96118325e-01 -4.36115980e-01 -8.78268123e-01 -1.96118101e-01 -4.39098150e-01 -8.76781762e-01 -1.96118370e-01 -4.42151874e-01 -8.75245810e-01 -1.96118400e-01 -4.45213258e-01 -8.73691618e-01 -1.96118340e-01 -4.48330909e-01 -8.72095585e-01 -1.96118385e-01 -4.51361775e-01 -8.70530009e-01 -1.96118042e-01 -4.54310089e-01 -8.68997455e-01 -1.96118385e-01 -4.57354367e-01 -8.67398500e-01 -1.96118385e-01 -4.60368395e-01 -8.65801752e-01 -1.96118385e-01 -4.63480949e-01 -8.64140928e-01 -1.96118400e-01 -4.66493100e-01 -8.62516463e-01 -1.96118101e-01 -4.69484061e-01 -8.60895097e-01 -1.96118400e-01 -4.72502947e-01 -8.59240413e-01 -1.96118101e-01 -4.75487739e-01 -8.57589841e-01 -1.96118400e-01 -4.78550613e-01 -8.55885565e-01 -1.96118370e-01 -4.81461406e-01 -8.54253292e-01 -1.96118101e-01 -4.84431267e-01 -8.52571845e-01 -1.96118385e-01 -4.87398297e-01 -8.50880623e-01 -1.96118101e-01 -4.90311235e-01 -8.49203587e-01 -1.96118385e-01 -4.93346334e-01 -8.47444892e-01 -1.96118072e-01 -4.96315449e-01 -8.45709920e-01 -1.96118057e-01 -4.99252915e-01 -8.43978047e-01 -1.96118161e-01 -5.02199829e-01 -8.42226982e-01 -1.96118057e-01 -5.05111158e-01 -8.40484798e-01 -1.96118310e-01 -5.08067846e-01 -8.38699937e-01 -1.96118057e-01 -5.10974765e-01 -8.36935222e-01 -1.96118355e-01 -5.13980508e-01 -8.35090518e-01 -1.96118370e-01 -5.16824305e-01 -8.33334804e-01 -1.96118057e-01 -5.19632757e-01 -8.31585765e-01 -1.96118370e-01 -5.22623837e-01 -8.29708695e-01 -1.96118429e-01 -5.25591373e-01 -8.27831924e-01 -1.96118400e-01 -5.28476179e-01 -8.25992942e-01 -1.96118370e-01 -5.31281650e-01 -8.24191153e-01 -1.96118101e-01 -5.34084797e-01 -8.22377980e-01 -1.96118400e-01 -5.36964774e-01 -8.20499122e-01 -1.96118385e-01 -5.39814234e-01 -8.18629324e-01 -1.96118370e-01 -5.42655408e-01 -8.16745520e-01 -1.96118370e-01 -5.45503199e-01 -8.14848125e-01 -1.96118370e-01 -5.48413217e-01 -8.12895000e-01 -1.96118161e-01 -5.51291347e-01 -8.10943186e-01 -1.96118250e-01 -5.54031968e-01 -8.09076548e-01 -1.96118370e-01 -5.56898534e-01 -8.07105124e-01 -1.96118116e-01 -5.59730947e-01 -8.05143833e-01 -1.96118057e-01 -5.62523305e-01 -8.03191781e-01 -1.96118087e-01 -5.65420151e-01 -8.01158667e-01 -1.96118385e-01 -5.68134069e-01 -7.99233973e-01 -1.96118057e-01 -5.70886433e-01 -7.97271550e-01 -1.96118385e-01 -5.73660612e-01 -7.95273483e-01 -1.96118101e-01 -5.76434731e-01 -7.93269694e-01 -1.96118295e-01 -5.79295456e-01 -7.91181445e-01 -1.96118385e-01 -5.82067490e-01 -7.89144337e-01 -1.96118400e-01 -5.84751308e-01 -7.87158132e-01 -1.96118027e-01 -5.87396622e-01 -7.85184860e-01 -1.96118385e-01 -5.90149224e-01 -7.83118606e-01 -1.96118385e-01 -5.92940032e-01 -7.81008959e-01 -1.96118250e-01 -5.95681250e-01 -7.78920054e-01 -1.96118057e-01 -5.98390818e-01 -7.76838243e-01 -1.96117938e-01 -6.01111352e-01 -7.74736822e-01 -1.96118042e-01 -6.03730679e-01 -7.72697091e-01 -1.96118400e-01 -6.06501877e-01 -7.70525575e-01 -1.96118206e-01 -6.09188855e-01 -7.68400550e-01 -1.96118101e-01 -6.11860812e-01 -7.66276360e-01 -1.96118236e-01 -6.14553273e-01 -7.64118671e-01 -1.96118101e-01 -6.17139399e-01 -7.62031913e-01 -1.96118370e-01 -6.19852483e-01 -7.59825528e-01 -1.96118206e-01 -6.22522831e-01 -7.57639587e-01 -1.96118057e-01 -6.25082076e-01 -7.55529881e-01 -1.96118385e-01 -6.27718091e-01 -7.53341734e-01 -1.96118400e-01 -6.30385876e-01 -7.51108885e-01 -1.96118355e-01 -6.33082509e-01 -7.48838007e-01 -1.96118400e-01 -6.35638833e-01 -7.46667922e-01 -1.96118057e-01 -6.38181508e-01 -7.44496524e-01 -1.96118355e-01 -6.40770555e-01 -7.42271483e-01 -1.96118385e-01 -6.43417716e-01 -7.39977717e-01 -1.96118116e-01 -6.46060646e-01 -7.37670302e-01 -1.96118385e-01 -6.48579359e-01 -7.35456347e-01 -1.96118101e-01 -6.51064694e-01 -7.33258665e-01 -1.96118370e-01 -6.53613329e-01 -7.30986655e-01 -1.96118385e-01 -6.56168282e-01 -7.28693366e-01 -1.96118400e-01 -6.58778071e-01 -7.26338148e-01 -1.96118116e-01 -6.61328375e-01 -7.24012673e-01 -1.96118101e-01 -6.63830698e-01 -7.21723676e-01 -1.96118280e-01 -6.66341066e-01 -7.19403923e-01 -1.96118057e-01 -6.68838918e-01 -7.17083097e-01 -1.96117893e-01 -6.71409369e-01 -7.14674532e-01 -1.96118370e-01 -6.73838258e-01 -7.12384999e-01 -1.96118101e-01 -6.76318407e-01 -7.10035443e-01 -1.96118176e-01 -6.78795576e-01 -7.07658887e-01 -1.96118072e-01 -6.81201637e-01 -7.05357969e-01 -1.96118400e-01 -6.83686495e-01 -7.02947438e-01 -1.96118385e-01 -6.86137915e-01 -7.00550556e-01 -1.96118221e-01 -6.88543737e-01 -6.98188484e-01 -1.96118400e-01 -6.90968156e-01 -6.95791304e-01 -1.96118385e-01 -6.93442523e-01 -6.93305612e-01 -1.96118340e-01 -6.95878744e-01 -6.90880597e-01 -1.96118161e-01 -6.98290706e-01 -6.88440323e-01 -1.96118236e-01 -7.00692415e-01 -6.85992777e-01 -1.96118087e-01 -7.03019023e-01 -6.83611631e-01 -1.96118400e-01 -7.05413818e-01 -6.81143582e-01 -1.96118400e-01 -7.07830012e-01 -6.78617537e-01 -1.96118161e-01 -7.10219502e-01 -6.76125467e-01 -1.96118101e-01 -7.12576091e-01 -6.73635364e-01 -1.96118325e-01 -7.14902341e-01 -6.71166182e-01 -1.96118057e-01 -7.17153311e-01 -6.68760300e-01 -1.96118385e-01 -7.19523013e-01 -6.66212559e-01 -1.96118400e-01 -7.21921384e-01 -6.63617373e-01 -1.96118414e-01 -7.24201083e-01 -6.61122978e-01 -1.96118012e-01 -7.26423740e-01 -6.58682346e-01 -1.96118400e-01 -7.28719115e-01 -6.56142175e-01 -1.96118370e-01 -7.31074095e-01 -6.53516471e-01 -1.96117923e-01 -7.33372271e-01 -6.50936842e-01 -1.96118027e-01 -7.35617280e-01 -6.48398519e-01 -1.96118355e-01 -7.37877309e-01 -6.45823777e-01 -1.96118057e-01 -7.40126967e-01 -6.43244147e-01 -1.96118250e-01 -7.42428303e-01 -6.40588105e-01 -1.96118370e-01 -7.44612753e-01 -6.38047755e-01 -1.96118101e-01 -7.46772289e-01 -6.35516405e-01 -1.96118370e-01 -7.48991847e-01 -6.32903457e-01 -1.96118370e-01 -7.51223028e-01 -6.30250275e-01 -1.96118400e-01 -7.53471613e-01 -6.27562165e-01 -1.96118400e-01 -7.55636215e-01 -6.24950826e-01 -1.96118101e-01 -7.57760763e-01 -6.22379065e-01 -1.96118385e-01 -7.59934843e-01 -6.19717002e-01 -1.96118385e-01 -7.62090862e-01 -6.17065966e-01 -1.96118370e-01 -7.64286041e-01 -6.14346206e-01 -1.96118072e-01 -7.66495228e-01 -6.11587107e-01 -1.96118400e-01 -7.68618405e-01 -6.08913839e-01 -1.96118400e-01 -7.70681620e-01 -6.06302500e-01 -1.96118057e-01 -7.72722721e-01 -6.03699505e-01 -1.96118385e-01 -7.74891615e-01 -6.00911975e-01 -1.96118161e-01 -7.77037263e-01 -5.98135948e-01 -1.96118370e-01 -7.79120266e-01 -5.95419347e-01 -1.96118370e-01 -7.81162441e-01 -5.92736781e-01 -1.96118057e-01 -7.83158958e-01 -5.90100408e-01 -1.96118370e-01 -7.85261035e-01 -5.87295353e-01 -1.96118310e-01 -7.87317991e-01 -5.84535778e-01 -1.96118072e-01 -7.89310694e-01 -5.81841946e-01 -1.96118400e-01 -7.91340470e-01 -5.79078078e-01 -1.96118131e-01 -7.93363631e-01 -5.76304615e-01 -1.96118370e-01 -7.95415401e-01 -5.73466361e-01 -1.96118414e-01 -7.97403753e-01 -5.70702434e-01 -1.96118101e-01 -7.99336493e-01 -5.67991138e-01 -1.96118400e-01 -8.01312625e-01 -5.65204322e-01 -1.96118385e-01 -8.03300083e-01 -5.62370062e-01 -1.96118400e-01 -8.05299222e-01 -5.59504211e-01 -1.96118429e-01 -8.07234704e-01 -5.56710660e-01 -1.96118131e-01 -8.09122562e-01 -5.53961754e-01 -1.96118385e-01 -8.11040223e-01 -5.51149905e-01 -1.96118385e-01 -8.12951744e-01 -5.48328757e-01 -1.96118385e-01 -8.14910054e-01 -5.45410335e-01 -1.96117923e-01 -8.16819906e-01 -5.42544425e-01 -1.96118057e-01 -8.18707943e-01 -5.39694369e-01 -1.96118012e-01 -8.20601046e-01 -5.36809206e-01 -1.96118057e-01 -8.22404683e-01 -5.34043431e-01 -1.96118325e-01 -8.24262142e-01 -5.31172514e-01 -1.96118385e-01 -8.26156199e-01 -5.28219104e-01 -1.96118176e-01 -8.28024685e-01 -5.25286019e-01 -1.96118101e-01 -8.29799652e-01 -5.22482872e-01 -1.96118325e-01 -8.31588745e-01 -5.19625008e-01 -1.96118370e-01 -8.33416760e-01 -5.16693950e-01 -1.96118385e-01 -8.35215032e-01 -5.13777196e-01 -1.96118385e-01 -8.37006330e-01 -5.10857761e-01 -1.96118370e-01 -8.38784099e-01 -5.07930994e-01 -1.96118385e-01 -8.40598822e-01 -5.04923642e-01 -1.96118101e-01 -8.42406869e-01 -5.01896799e-01 -1.96118385e-01 -8.44108462e-01 -4.99029547e-01 -1.96118101e-01 -8.45839798e-01 -4.96092081e-01 -1.96118131e-01 -8.47572029e-01 -4.93124545e-01 -1.96118101e-01 -8.49258959e-01 -4.90217328e-01 -1.96118429e-01 -8.50957274e-01 -4.87262368e-01 -1.96118310e-01 -8.52631748e-01 -4.84324187e-01 -1.96118385e-01 -8.54313910e-01 -4.81358469e-01 -1.96118400e-01 -8.55989873e-01 -4.78364974e-01 -1.96118370e-01 -8.57653379e-01 -4.75373209e-01 -1.96118400e-01 -8.59342575e-01 -4.72319096e-01 -1.96118221e-01 -8.61012757e-01 -4.69269365e-01 -1.96118370e-01 -8.62616062e-01 -4.66309994e-01 -1.96118325e-01 -8.64207506e-01 -4.63355750e-01 -1.96118385e-01 -8.65852892e-01 -4.60271806e-01 -1.96118221e-01 -8.67501020e-01 -4.57157463e-01 -1.96118400e-01 -8.69077981e-01 -4.54154938e-01 -1.96118325e-01 -8.70614409e-01 -4.51199800e-01 -1.96118146e-01 -8.72154474e-01 -4.48219627e-01 -1.96118385e-01 -8.73745322e-01 -4.45108920e-01 -1.96118146e-01 -8.75349939e-01 -4.41945910e-01 -1.96118400e-01 -8.76845479e-01 -4.38969254e-01 -1.96118087e-01 -8.78322542e-01 -4.36004758e-01 -1.96118385e-01 -8.79830062e-01 -4.32956487e-01 -1.96118400e-01 -8.81339550e-01 -4.29878503e-01 -1.96118385e-01 -8.82880151e-01 -4.26704645e-01 -1.96118027e-01 -8.84410083e-01 -4.23520267e-01 -1.96118400e-01 -8.85854661e-01 -4.20491278e-01 -1.96118101e-01 -8.87271702e-01 -4.17490810e-01 -1.96118385e-01 -8.88716400e-01 -4.14409697e-01 -1.96118370e-01 -8.90199482e-01 -4.11217064e-01 -1.96117938e-01 -8.91652822e-01 -4.08052683e-01 -1.96118191e-01 -8.93029392e-01 -4.05034781e-01 -1.96118295e-01 -8.94415140e-01 -4.01962101e-01 -1.96118385e-01 -8.95810127e-01 -3.98847848e-01 -1.96118400e-01 -8.97245705e-01 -3.95606190e-01 -1.96117818e-01 -8.98665965e-01 -3.92370194e-01 -1.96118370e-01 -9.00024772e-01 -3.89242887e-01 -1.96118385e-01 -9.01377559e-01 -3.86087984e-01 -1.96118400e-01 -9.02685404e-01 -3.83027643e-01 -1.96118101e-01 -9.03982580e-01 -3.79957259e-01 -1.96118400e-01 -9.05308485e-01 -3.76785159e-01 -1.96118385e-01 -9.06649411e-01 -3.73546720e-01 -1.96118250e-01 -9.07951772e-01 -3.70373189e-01 -1.96118057e-01 -9.09201443e-01 -3.67293477e-01 -1.96118385e-01 -9.10512209e-01 -3.64029169e-01 -1.96118176e-01 -9.11775410e-01 -3.60856652e-01 -1.96118101e-01 -9.13003206e-01 -3.57743084e-01 -1.96118385e-01 -9.14238453e-01 -3.54557812e-01 -1.96118385e-01 -9.15486813e-01 -3.51342946e-01 -1.96118414e-01 -9.16737974e-01 -3.48052084e-01 -1.96118340e-01 -9.17930901e-01 -3.44876558e-01 -1.96118101e-01 -9.19095218e-01 -3.41761857e-01 -1.96118400e-01 -9.20319438e-01 -3.38464528e-01 -1.96118131e-01 -9.21535850e-01 -3.35151613e-01 -1.96118385e-01 -9.22692597e-01 -3.31947207e-01 -1.96118385e-01 -9.23819602e-01 -3.28802407e-01 -1.96118057e-01 -9.24954414e-01 -3.25594366e-01 -1.96118221e-01 -9.26093161e-01 -3.22340131e-01 -1.96118101e-01 -9.27180231e-01 -3.19201499e-01 -1.96118370e-01 -9.28285062e-01 -3.15968990e-01 -1.96118385e-01 -9.29384112e-01 -3.12727153e-01 -1.96118385e-01 -9.30503309e-01 -3.09380889e-01 -1.96118101e-01 -9.31581914e-01 -3.06117952e-01 -1.96118057e-01 -9.32613015e-01 -3.02964300e-01 -1.96118385e-01 -9.33686495e-01 -2.99636304e-01 -1.96118161e-01 -9.34728861e-01 -2.96366870e-01 -1.96118101e-01 -9.35750067e-01 -2.93132573e-01 -1.96118310e-01 -9.36772048e-01 -2.89845645e-01 -1.96118101e-01 -9.37777996e-01 -2.86574274e-01 -1.96118236e-01 -9.38794374e-01 -2.83222198e-01 -1.96118385e-01 -9.39757049e-01 -2.80013740e-01 -1.96118101e-01 -9.40727711e-01 -2.76740372e-01 -1.96118400e-01 -9.41688061e-01 -2.73455650e-01 -1.96118101e-01 -9.42635119e-01 -2.70165533e-01 -1.96118146e-01 -9.43573415e-01 -2.66873598e-01 -1.96118101e-01 -9.44476604e-01 -2.63662010e-01 -1.96118385e-01 -9.45392966e-01 -2.60356188e-01 -1.96118400e-01 -9.46296811e-01 -2.57055074e-01 -1.96118385e-01 -9.47209001e-01 -2.53667861e-01 -1.96118161e-01 -9.48113501e-01 -2.50268131e-01 -1.96118385e-01 -9.48981225e-01 -2.46956244e-01 -1.96118385e-01 -9.49815273e-01 -2.43734121e-01 -1.96118057e-01 -9.50627923e-01 -2.40530908e-01 -1.96118385e-01 -9.51486707e-01 -2.37113833e-01 -1.96118072e-01 -9.52337623e-01 -2.33684450e-01 -1.96118370e-01 -9.53144908e-01 -2.30376482e-01 -1.96118400e-01 -9.53920364e-01 -2.27137402e-01 -1.96118057e-01 -9.54686642e-01 -2.23894194e-01 -1.96118385e-01 -9.55476880e-01 -2.20487967e-01 -1.96118206e-01 -9.56272364e-01 -2.17016354e-01 -1.96118385e-01 -9.57003117e-01 -2.13773862e-01 -1.96118101e-01 -9.57739353e-01 -2.10445419e-01 -1.96118131e-01 -9.58471477e-01 -2.07083583e-01 -1.96118057e-01 -9.59163070e-01 -2.03856260e-01 -1.96118400e-01 -9.59893107e-01 -2.00401708e-01 -1.96118116e-01 -9.60608423e-01 -1.96940944e-01 -1.96118400e-01 -9.61272120e-01 -1.93671867e-01 -1.96118072e-01 -9.61920917e-01 -1.90419495e-01 -1.96118385e-01 -9.62580323e-01 -1.87063426e-01 -1.96118385e-01 -9.63241100e-01 -1.83624104e-01 -1.96118310e-01 -9.63899314e-01 -1.80151284e-01 -1.96118385e-01 -9.64503348e-01 -1.76867187e-01 -1.96118057e-01 -9.65101361e-01 -1.73609704e-01 -1.96118370e-01 -9.65702415e-01 -1.70231834e-01 -1.96118385e-01 -9.66299474e-01 -1.66778103e-01 -1.96117908e-01 -9.66893017e-01 -1.63308457e-01 -1.96118385e-01 -9.67442453e-01 -1.60026148e-01 -1.96118101e-01 -9.67996359e-01 -1.56641260e-01 -1.96118101e-01 -9.68536913e-01 -1.53262809e-01 -1.96118057e-01 -9.69060838e-01 -1.49908423e-01 -1.96118325e-01 -9.69580293e-01 -1.46511883e-01 -1.96118101e-01 -9.70083237e-01 -1.43146724e-01 -1.96118414e-01 -9.70579088e-01 -1.39741316e-01 -1.96118101e-01 -9.71048176e-01 -1.36446819e-01 -1.96118385e-01 -9.71530378e-01 -1.32984161e-01 -1.96118295e-01 -9.71989751e-01 -1.29566059e-01 -1.96118101e-01 -9.72432733e-01 -1.26196280e-01 -1.96118355e-01 -9.72870529e-01 -1.22789681e-01 -1.96118101e-01 -9.73281324e-01 -1.19485855e-01 -1.96118370e-01 -9.73700762e-01 -1.16006628e-01 -1.96118280e-01 -9.74100053e-01 -1.12606280e-01 -1.96118057e-01 -9.74476874e-01 -1.09303519e-01 -1.96118370e-01 -9.74864960e-01 -1.05775386e-01 -1.96118325e-01 -9.75237548e-01 -1.02293938e-01 -1.96118370e-01 -9.75584388e-01 -9.89173949e-02 -1.96118385e-01 -9.75917637e-01 -9.55803767e-02 -1.96118042e-01 -9.76246715e-01 -9.21884328e-02 -1.96118310e-01 -9.76562321e-01 -8.87632221e-02 -1.96118027e-01 -9.76856828e-01 -8.54669064e-02 -1.96118325e-01 -9.77148533e-01 -8.20503682e-02 -1.96118370e-01 -9.77430105e-01 -7.86339939e-02 -1.96118370e-01 -9.77704644e-01 -7.51423240e-02 -1.96118400e-01 -9.77963448e-01 -7.16908649e-02 -1.96117863e-01 -9.78197217e-01 -6.83985129e-02 -1.96118057e-01 -9.78434265e-01 -6.49396703e-02 -1.96118101e-01 -9.78661478e-01 -6.13861382e-02 -1.96117133e-01 -9.78862762e-01 -5.81182688e-02 -1.96115509e-01 -9.79039967e-01 -5.49114123e-02 -1.96117371e-01 -9.79234219e-01 -5.13801388e-02 -1.96117371e-01 -9.79357719e-01 -4.89531122e-02 -1.96117297e-01 -9.79539692e-01 -4.51661460e-02 -1.96117297e-01 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. -9.80531931e-01 -9.75504983e-03 -1.96117282e-01 -9.80545998e-01 -8.21491610e-03 -1.96117297e-01 -9.80568767e-01 -4.79209376e-03 -1.96117297e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.86889422e-01 4.91575412e-02 -1.53727457e-01 -9.86730039e-01 5.22537790e-02 -1.53727189e-01 -9.86538589e-01 5.56443036e-02 -1.53727263e-01 -9.86348271e-01 5.88212870e-02 -1.53727576e-01 -9.86141741e-01 6.22688793e-02 -1.53728053e-01 -9.85924244e-01 6.56932443e-02 -1.53728411e-01 -9.85688686e-01 6.90772906e-02 -1.53728083e-01 -9.85454559e-01 7.24055097e-02 -1.53728411e-01 -9.85192955e-01 7.59123564e-02 -1.53728634e-01 -9.84910429e-01 7.94578865e-02 -1.53728411e-01 -9.84633505e-01 8.28010365e-02 -1.53728202e-01 -9.84345257e-01 8.62199962e-02 -1.53728664e-01 -9.84025776e-01 8.97529870e-02 -1.53728411e-01 -9.83712256e-01 9.31277350e-02 -1.53728351e-01 -9.83381033e-01 9.65759084e-02 -1.53728500e-01 -9.83041346e-01 9.99529287e-02 -1.53728187e-01 -9.82698679e-01 1.03281245e-01 -1.53728351e-01 -9.82323468e-01 1.06813081e-01 -1.53728694e-01 -9.81931984e-01 1.10340931e-01 -1.53728411e-01 -9.81538177e-01 1.13778584e-01 -1.53728500e-01 -9.81134057e-01 1.17213793e-01 -1.53728500e-01 -9.80721772e-01 1.20614268e-01 -1.53728411e-01 -9.80298877e-01 1.24019787e-01 -1.53728411e-01 -9.79857147e-01 1.27459064e-01 -1.53728500e-01 -9.79398906e-01 1.30922139e-01 -1.53728500e-01 -9.78946567e-01 1.34237543e-01 -1.53727949e-01 -9.78494644e-01 1.37523532e-01 -1.53728411e-01 -9.77995336e-01 1.41040847e-01 -1.53728694e-01 -9.77477252e-01 1.44560248e-01 -1.53728306e-01 -9.76968348e-01 1.47965401e-01 -1.53728485e-01 -9.76446629e-01 1.51382536e-01 -1.53728500e-01 -9.75913882e-01 1.54773995e-01 -1.53728366e-01 -9.75376666e-01 1.58108518e-01 -1.53728113e-01 -9.74826872e-01 1.61504120e-01 -1.53728694e-01 -9.74236012e-01 1.65013134e-01 -1.53728411e-01 -9.73663449e-01 1.68338075e-01 -1.53728142e-01 -9.73079741e-01 1.71728045e-01 -1.53728664e-01 -9.72453952e-01 1.75227478e-01 -1.53728500e-01 -9.71830904e-01 1.78619668e-01 -1.53728440e-01 -9.71203148e-01 1.82012379e-01 -1.53728426e-01 -9.70576048e-01 1.85301155e-01 -1.53728038e-01 -9.69949007e-01 1.88571855e-01 -1.53728411e-01 -9.69265580e-01 1.92074940e-01 -1.53728694e-01 -9.68564570e-01 1.95570126e-01 -1.53728470e-01 -9.67873871e-01 1.98957354e-01 -1.53728470e-01 -9.67190623e-01 2.02235997e-01 -1.53728098e-01 -9.66489673e-01 2.05595836e-01 -1.53728709e-01 -9.65739250e-01 2.09077135e-01 -1.53728411e-01 -9.65015054e-01 2.12368220e-01 -1.53728083e-01 -9.64283943e-01 2.15703994e-01 -1.53728664e-01 -9.63512540e-01 2.19096139e-01 -1.53728157e-01 -9.62767243e-01 2.22352177e-01 -1.53728396e-01 -9.61972177e-01 2.25796282e-01 -1.53728664e-01 -9.61148500e-01 2.29259580e-01 -1.53728411e-01 -9.60349619e-01 2.32585475e-01 -1.53728321e-01 -9.59533632e-01 2.35926211e-01 -1.53728500e-01 -9.58694279e-01 2.39307463e-01 -1.53728500e-01 -9.57871854e-01 2.42565319e-01 -1.53728053e-01 -9.57029939e-01 2.45890990e-01 -1.53728694e-01 -9.56138134e-01 2.49326542e-01 -1.53728351e-01 -9.55284119e-01 2.52576798e-01 -1.53728187e-01 -9.54401672e-01 2.55904227e-01 -1.53728664e-01 -9.53482449e-01 2.59302467e-01 -1.53728411e-01 -9.52566981e-01 2.62638301e-01 -1.53728500e-01 -9.51645553e-01 2.65966922e-01 -1.53728411e-01 -9.50724363e-01 2.69226372e-01 -1.53728113e-01 -9.49792564e-01 2.72507727e-01 -1.53728634e-01 -9.48827028e-01 2.75840014e-01 -1.53728217e-01 -9.47867453e-01 2.79136926e-01 -1.53728664e-01 -9.46857810e-01 2.82536238e-01 -1.53728470e-01 -9.45886612e-01 2.85754651e-01 -1.53728142e-01 -9.44892287e-01 2.89045602e-01 -1.53728724e-01 -9.43844259e-01 2.92441845e-01 -1.53728411e-01 -9.42827165e-01 2.95703590e-01 -1.53728351e-01 -9.41791356e-01 2.98988193e-01 -1.53728500e-01 -9.40755785e-01 3.02226752e-01 -1.53728217e-01 -9.39730465e-01 3.05396438e-01 -1.53728351e-01 -9.38635886e-01 3.08755994e-01 -1.53728649e-01 -9.37516212e-01 3.12135398e-01 -1.53728500e-01 -9.36411738e-01 3.15432757e-01 -1.53728455e-01 -9.35309291e-01 3.18686157e-01 -1.53728500e-01 -9.34196413e-01 3.21935773e-01 -1.53728411e-01 -9.33089077e-01 3.25123072e-01 -1.53728306e-01 -9.31954920e-01 3.28371465e-01 -1.53728649e-01 -9.30774748e-01 3.31699759e-01 -1.53728411e-01 -9.29635108e-01 3.34868819e-01 -1.53728187e-01 -9.28499758e-01 3.38015795e-01 -1.53728411e-01 -9.27284539e-01 3.41327101e-01 -1.53728664e-01 -9.26044881e-01 3.44656855e-01 -1.53728440e-01 -9.24832463e-01 3.47900897e-01 -1.53728411e-01 -9.23629105e-01 3.51093709e-01 -1.53728351e-01 -9.22435522e-01 3.54237288e-01 -1.53728306e-01 -9.21204627e-01 3.57409954e-01 -1.53728411e-01 -9.19926763e-01 3.60698640e-01 -1.53728634e-01 -9.18633819e-01 3.63974869e-01 -1.53728455e-01 -9.17385280e-01 3.67095441e-01 -1.53727993e-01 -9.16115403e-01 3.70270789e-01 -1.53728664e-01 -9.14778113e-01 3.73560667e-01 -1.53728500e-01 -9.13471818e-01 3.76734257e-01 -1.53728411e-01 -9.12156761e-01 3.79907638e-01 -1.53728306e-01 -9.10856307e-01 3.83012950e-01 -1.53728142e-01 -9.09549892e-01 3.86110574e-01 -1.53728485e-01 -9.08160925e-01 3.89365196e-01 -1.53728664e-01 -9.06754017e-01 3.92631501e-01 -1.53728351e-01 -9.05386031e-01 3.95778745e-01 -1.53728396e-01 -9.03998256e-01 3.98939788e-01 -1.53728500e-01 -9.02596354e-01 4.02099550e-01 -1.53728411e-01 -9.01191771e-01 4.05237496e-01 -1.53728411e-01 -8.99803340e-01 4.08304900e-01 -1.53728157e-01 -8.98380756e-01 4.11429614e-01 -1.53728634e-01 -8.96905839e-01 4.14636046e-01 -1.53728426e-01 -8.95483911e-01 4.17693824e-01 -1.53728187e-01 -8.94037426e-01 4.20789301e-01 -1.53728664e-01 -8.92520785e-01 4.23994780e-01 -1.53728411e-01 -8.91034305e-01 4.27105069e-01 -1.53728411e-01 -8.89540136e-01 4.30216044e-01 -1.53728411e-01 -8.88054967e-01 4.33269322e-01 -1.53728187e-01 -8.86582732e-01 4.36270893e-01 -1.53728396e-01 -8.85026872e-01 4.39424664e-01 -1.53728530e-01 -8.83451402e-01 4.42578614e-01 -1.53728411e-01 -8.81898642e-01 4.45669144e-01 -1.53728426e-01 -8.80334437e-01 4.48749542e-01 -1.53728411e-01 -8.78776252e-01 4.51793373e-01 -1.53728411e-01 -8.77198100e-01 4.54845190e-01 -1.53728306e-01 -8.75607014e-01 4.57903832e-01 -1.53728500e-01 -8.73997748e-01 4.60970968e-01 -1.53728411e-01 -8.72415721e-01 4.63949561e-01 -1.53728053e-01 -8.70843649e-01 4.66901064e-01 -1.53728411e-01 -8.69170308e-01 4.70012426e-01 -1.53728619e-01 -8.67477596e-01 4.73126113e-01 -1.53728306e-01 -8.65826905e-01 4.76142853e-01 -1.53728500e-01 -8.64148915e-01 4.79170471e-01 -1.53728351e-01 -8.62477243e-01 4.82175946e-01 -1.53728411e-01 -8.60800982e-01 4.85166550e-01 -1.53728396e-01 -8.59096646e-01 4.88179952e-01 -1.53728500e-01 -8.57372344e-01 4.91200566e-01 -1.53728500e-01 -8.55693400e-01 4.94114578e-01 -1.53728157e-01 -8.53977740e-01 4.97084111e-01 -1.53728664e-01 -8.52238297e-01 5.00049472e-01 -1.53728157e-01 -8.50485563e-01 5.03034234e-01 -1.53728694e-01 -8.48667800e-01 5.06089211e-01 -1.53728470e-01 -8.46897125e-01 5.09048104e-01 -1.53728500e-01 -8.45112860e-01 5.12001157e-01 -1.53728411e-01 -8.43318522e-01 5.14960051e-01 -1.53728500e-01 -8.41514051e-01 5.17897189e-01 -1.53728500e-01 -8.39705884e-01 5.20829856e-01 -1.53728500e-01 -8.37927699e-01 5.23676217e-01 -1.53728113e-01 -8.36113453e-01 5.26577473e-01 -1.53728694e-01 -8.34224224e-01 5.29557765e-01 -1.53728321e-01 -8.32365632e-01 5.32480121e-01 -1.53728634e-01 -8.30484271e-01 5.35403669e-01 -1.53728351e-01 -8.28618705e-01 5.38286865e-01 -1.53728396e-01 -8.26794028e-01 5.41081131e-01 -1.53728217e-01 -8.24892700e-01 5.43985844e-01 -1.53728664e-01 -8.22918475e-01 5.46961963e-01 -1.53728500e-01 -8.21000218e-01 5.49839199e-01 -1.53728411e-01 -8.19114983e-01 5.52642882e-01 -1.53728187e-01 -8.17240000e-01 5.55411339e-01 -1.53728351e-01 -8.15277278e-01 5.58294713e-01 -1.53728634e-01 -8.13273609e-01 5.61207473e-01 -1.53728500e-01 -8.11290383e-01 5.64066648e-01 -1.53728411e-01 -8.09359789e-01 5.66825211e-01 -1.53728068e-01 -8.07393074e-01 5.69640696e-01 -1.53728724e-01 -8.05315137e-01 5.72561443e-01 -1.53728351e-01 -8.03320229e-01 5.75362384e-01 -1.53728411e-01 -8.01292837e-01 5.78175783e-01 -1.53728351e-01 -7.99274266e-01 5.80968797e-01 -1.53728381e-01 -7.97259152e-01 5.83728254e-01 -1.53728351e-01 -7.95288146e-01 5.86404383e-01 -1.53727993e-01 -7.93222070e-01 5.89206100e-01 -1.53728634e-01 -7.91098058e-01 5.92051327e-01 -1.53728411e-01 -7.89088130e-01 5.94723642e-01 -1.53727993e-01 -7.87013113e-01 5.97477496e-01 -1.53728664e-01 -7.84851670e-01 6.00309312e-01 -1.53728306e-01 -7.82762170e-01 6.03029668e-01 -1.53728396e-01 -7.80628860e-01 6.05786264e-01 -1.53728306e-01 -7.78541803e-01 6.08467400e-01 -1.53728217e-01 -7.76479602e-01 6.11098051e-01 -1.53728276e-01 -7.74315715e-01 6.13842905e-01 -1.53728664e-01 -7.72076845e-01 6.16656721e-01 -1.53728500e-01 -7.69912302e-01 6.19355023e-01 -1.53728500e-01 -7.67757356e-01 6.22023225e-01 -1.53728306e-01 -7.65637040e-01 6.24621987e-01 -1.53727964e-01 -7.63481736e-01 6.27264261e-01 -1.53728500e-01 -7.61213303e-01 6.30013227e-01 -1.53728351e-01 -7.59018183e-01 6.32655740e-01 -1.53728366e-01 -7.56862283e-01 6.35231078e-01 -1.53728038e-01 -7.54642189e-01 6.37874246e-01 -1.53728664e-01 -7.52326369e-01 6.40599132e-01 -1.53728455e-01 -7.50083804e-01 6.43224537e-01 -1.53728411e-01 -7.47832060e-01 6.45843446e-01 -1.53728411e-01 -7.45595396e-01 6.48418665e-01 -1.53728202e-01 -7.43362546e-01 6.50976062e-01 -1.53728083e-01 -7.41155207e-01 6.53491259e-01 -1.53728411e-01 -7.38815606e-01 6.56139672e-01 -1.53728634e-01 -7.36455321e-01 6.58787489e-01 -1.53728440e-01 -7.34200597e-01 6.61289394e-01 -1.53728008e-01 -7.31905103e-01 6.63842440e-01 -1.53728634e-01 -7.29521513e-01 6.66451573e-01 -1.53728351e-01 -7.27183640e-01 6.69006050e-01 -1.53728306e-01 -7.24846423e-01 6.71536982e-01 -1.53728351e-01 -7.22552598e-01 6.74000382e-01 -1.53728142e-01 -7.20268309e-01 6.76444054e-01 -1.53728351e-01 -7.17857361e-01 6.79002345e-01 -1.53728604e-01 -7.15400875e-01 6.81589067e-01 -1.53728217e-01 -7.13013172e-01 6.84082031e-01 -1.53728411e-01 -7.10632980e-01 6.86567247e-01 -1.53728306e-01 -7.08293200e-01 6.88974977e-01 -1.53728053e-01 -7.05887854e-01 6.91441596e-01 -1.53728500e-01 -7.03403056e-01 6.93970740e-01 -1.53728411e-01 -7.00985730e-01 6.96412921e-01 -1.53728306e-01 -6.98550642e-01 6.98835850e-01 -1.53728217e-01 -6.96176350e-01 7.01219380e-01 -1.53728157e-01 -6.93706512e-01 7.03667045e-01 -1.53728634e-01 -6.91182435e-01 7.06139743e-01 -1.53728306e-01 -6.88706279e-01 7.08557487e-01 -1.53728351e-01 -6.86241329e-01 7.10948586e-01 -1.53728351e-01 -6.83793962e-01 7.13286579e-01 -1.53728142e-01 -6.81353927e-01 7.15628147e-01 -1.53728411e-01 -6.78799748e-01 7.18049228e-01 -1.53728500e-01 -6.76235020e-01 7.20461607e-01 -1.53728351e-01 -6.73753202e-01 7.22778082e-01 -1.53728083e-01 -6.71242476e-01 7.25121021e-01 -1.53728500e-01 -6.68653727e-01 7.27506876e-01 -1.53728306e-01 -6.66161835e-01 7.29784131e-01 -1.53728098e-01 -6.63607836e-01 7.32115865e-01 -1.53728589e-01 -6.61071658e-01 7.34399021e-01 -1.53728038e-01 -6.58579648e-01 7.36637712e-01 -1.53728321e-01 -6.55933380e-01 7.38999963e-01 -1.53728664e-01 -6.53331757e-01 7.41293252e-01 -1.53728083e-01 -6.50736451e-01 7.43576944e-01 -1.53728604e-01 -6.48141325e-01 7.45834827e-01 -1.53727934e-01 -6.45563960e-01 7.48073995e-01 -1.53728679e-01 -6.42839253e-01 7.50414014e-01 -1.53728366e-01 -6.40210927e-01 7.52656102e-01 -1.53728411e-01 -6.37598753e-01 7.54870057e-01 -1.53728276e-01 -6.35028780e-01 7.57030189e-01 -1.53727993e-01 -6.32401943e-01 7.59234309e-01 -1.53728634e-01 -6.29722714e-01 7.61450171e-01 -1.53728053e-01 -6.27084076e-01 7.63634384e-01 -1.53728664e-01 -6.24313235e-01 7.65894890e-01 -1.53728411e-01 -6.21635735e-01 7.68071473e-01 -1.53728470e-01 -6.19020104e-01 7.70174086e-01 -1.53728008e-01 -6.16425395e-01 7.72259891e-01 -1.53728411e-01 -6.13644361e-01 7.74471223e-01 -1.53728634e-01 -6.10928178e-01 7.76611686e-01 -1.53728053e-01 -6.08236253e-01 7.78727293e-01 -1.53728500e-01 -6.05503321e-01 7.80847788e-01 -1.53727964e-01 -6.02818429e-01 7.82926142e-01 -1.53728455e-01 -6.00010157e-01 7.85081327e-01 -1.53728440e-01 -5.97224593e-01 7.87201941e-01 -1.53728351e-01 -5.94536006e-01 7.89231360e-01 -1.53728083e-01 -5.91813743e-01 7.91276515e-01 -1.53728500e-01 -5.88944674e-01 7.93415487e-01 -1.53728411e-01 -5.86189628e-01 7.95450687e-01 -1.53728276e-01 -5.83412051e-01 7.97490418e-01 -1.53728306e-01 -5.80687046e-01 7.99476027e-01 -1.53728053e-01 -5.77906311e-01 8.01491082e-01 -1.53728634e-01 -5.75015724e-01 8.03567469e-01 -1.53728276e-01 -5.72208405e-01 8.05568993e-01 -1.53728411e-01 -5.69375753e-01 8.07574689e-01 -1.53728351e-01 -5.66627145e-01 8.09499562e-01 -1.53728053e-01 -5.63826442e-01 8.11457098e-01 -1.53728500e-01 -5.60963094e-01 8.13436449e-01 -1.53728008e-01 -5.58148980e-01 8.15376818e-01 -1.53728634e-01 -5.55174530e-01 8.17399085e-01 -1.53728262e-01 -5.52322567e-01 8.19328845e-01 -1.53728262e-01 -5.49559116e-01 8.21182966e-01 -1.53728083e-01 -5.46686947e-01 8.23103309e-01 -1.53728634e-01 -5.43695390e-01 8.25080216e-01 -1.53728276e-01 -5.40898383e-01 8.26910913e-01 -1.53727978e-01 -5.38033426e-01 8.28785837e-01 -1.53728634e-01 -5.35112858e-01 8.30667257e-01 -1.53727949e-01 -5.32228172e-01 8.32524836e-01 -1.53728634e-01 -5.29232979e-01 8.34429204e-01 -1.53728306e-01 -5.26300907e-01 8.36283207e-01 -1.53728396e-01 -5.23461759e-01 8.38060260e-01 -1.53728142e-01 -5.20559490e-01 8.39874685e-01 -1.53728634e-01 -5.17543018e-01 8.41727197e-01 -1.53728053e-01 -5.14644563e-01 8.43506098e-01 -1.53728157e-01 -5.11696458e-01 8.45301211e-01 -1.53728634e-01 -5.08757949e-01 8.47067535e-01 -1.53728068e-01 -5.05842924e-01 8.48815382e-01 -1.53728500e-01 -5.02850890e-01 8.50585401e-01 -1.53728113e-01 -4.99962032e-01 8.52292538e-01 -1.53728351e-01 -4.96923000e-01 8.54068816e-01 -1.53728500e-01 -4.93870437e-01 8.55835736e-01 -1.53728351e-01 -4.90871966e-01 8.57559443e-01 -1.53728411e-01 -4.87878084e-01 8.59263957e-01 -1.53728247e-01 -4.84872609e-01 8.60966623e-01 -1.53728276e-01 -4.81867850e-01 8.62650037e-01 -1.53728411e-01 -4.78833467e-01 8.64336550e-01 -1.53728351e-01 -4.75873768e-01 8.65969718e-01 -1.53728098e-01 -4.72870588e-01 8.67618978e-01 -1.53728634e-01 -4.69772190e-01 8.69295537e-01 -1.53728411e-01 -4.66735184e-01 8.70929420e-01 -1.53728276e-01 -4.63716328e-01 8.72541904e-01 -1.53728306e-01 -4.60706800e-01 8.74133408e-01 -1.53728098e-01 -4.57661420e-01 8.75734866e-01 -1.53728634e-01 -4.54515874e-01 8.77370358e-01 -1.53728411e-01 -4.51454848e-01 8.78949583e-01 -1.53728351e-01 -4.48483229e-01 8.80464971e-01 -1.53727993e-01 -4.45439458e-01 8.82014871e-01 -1.53728634e-01 -4.42257792e-01 8.83612633e-01 -1.53728351e-01 -4.39165056e-01 8.85152459e-01 -1.53728381e-01 -4.36066061e-01 8.86684239e-01 -1.53728351e-01 -4.33037251e-01 8.88166606e-01 -1.53728083e-01 -4.29956466e-01 8.89667332e-01 -1.53728634e-01 -4.26823735e-01 8.91166091e-01 -1.53728083e-01 -4.23729867e-01 8.92646551e-01 -1.53728530e-01 -4.20533001e-01 8.94155502e-01 -1.53728351e-01 -4.17473555e-01 8.95586908e-01 -1.53728142e-01 -4.14351314e-01 8.97039950e-01 -1.53728619e-01 -4.11215186e-01 8.98474693e-01 -1.53728083e-01 -4.08080608e-01 8.99909496e-01 -1.53728500e-01 -4.04863626e-01 9.01359975e-01 -1.53728351e-01 -4.01699424e-01 9.02773619e-01 -1.53728262e-01 -3.98633778e-01 9.04129326e-01 -1.53728023e-01 -3.95530045e-01 9.05495882e-01 -1.53728500e-01 -3.92288238e-01 9.06905293e-01 -1.53728500e-01 -3.89060795e-01 9.08288360e-01 -1.53728366e-01 -3.85977894e-01 9.09603417e-01 -1.53728038e-01 -3.82910967e-01 9.10900235e-01 -1.53728306e-01 -3.79651994e-01 9.12267029e-01 -1.53728634e-01 -3.76407981e-01 9.13605273e-01 -1.53728187e-01 -3.73237908e-01 9.14906025e-01 -1.53728306e-01 -3.70071441e-01 9.16191041e-01 -1.53728098e-01 -3.66870672e-01 9.17480588e-01 -1.53728634e-01 -3.63616735e-01 9.18774247e-01 -1.53728351e-01 -3.60417306e-01 9.20034468e-01 -1.53728351e-01 -3.57187271e-01 9.21287119e-01 -1.53728306e-01 -3.54028195e-01 9.22513723e-01 -1.53728172e-01 -3.50805491e-01 9.23741877e-01 -1.53728634e-01 -3.47579360e-01 9.24948275e-01 -1.53728068e-01 -3.44345659e-01 9.26161766e-01 -1.53728604e-01 -3.41065377e-01 9.27375197e-01 -1.53728276e-01 -3.37879926e-01 9.28545892e-01 -1.53727949e-01 -3.34619462e-01 9.29728329e-01 -1.53728500e-01 -3.31361145e-01 9.30891931e-01 -1.53728023e-01 -3.28108460e-01 9.32046056e-01 -1.53728411e-01 -3.24816644e-01 9.33195412e-01 -1.53728276e-01 -3.21553916e-01 9.34327483e-01 -1.53728336e-01 -3.18378210e-01 9.35409725e-01 -1.53728098e-01 -3.15094173e-01 9.36526477e-01 -1.53728500e-01 -3.11761111e-01 9.37637448e-01 -1.53728142e-01 -3.08486670e-01 9.38720942e-01 -1.53728336e-01 -3.05277288e-01 9.39767897e-01 -1.53728113e-01 -3.02000880e-01 9.40831721e-01 -1.53728634e-01 -2.98659712e-01 9.41892803e-01 -1.53728232e-01 -2.95367509e-01 9.42931712e-01 -1.53728306e-01 -2.92085022e-01 9.43954766e-01 -1.53728351e-01 -2.88865775e-01 9.44941044e-01 -1.53727978e-01 -2.85552830e-01 9.45950866e-01 -1.53728634e-01 -2.82141119e-01 9.46973145e-01 -1.53728321e-01 -2.78834701e-01 9.47952926e-01 -1.53728351e-01 -2.75515497e-01 9.48922694e-01 -1.53728351e-01 -2.72308081e-01 9.49843585e-01 -1.53727934e-01 -2.69006580e-01 9.50791180e-01 -1.53728634e-01 -2.65668392e-01 9.51724768e-01 -1.53728008e-01 -2.62461752e-01 9.52615201e-01 -1.53728351e-01 -2.59021670e-01 9.53560948e-01 -1.53728664e-01 -2.55574971e-01 9.54484880e-01 -1.53728306e-01 -2.52248794e-01 9.55371141e-01 -1.53728411e-01 -2.48926491e-01 9.56241488e-01 -1.53728306e-01 -2.45680228e-01 9.57077086e-01 -1.53727964e-01 -2.42324725e-01 9.57936883e-01 -1.53728694e-01 -2.38877952e-01 9.58800197e-01 -1.53728351e-01 -2.35520974e-01 9.59631324e-01 -1.53728306e-01 -2.32169703e-01 9.60450649e-01 -1.53728411e-01 -2.28920743e-01 9.61225808e-01 -1.53727978e-01 -2.25572214e-01 9.62023258e-01 -1.53728664e-01 -2.22205982e-01 9.62800920e-01 -1.53728142e-01 -2.18834579e-01 9.63576019e-01 -1.53728664e-01 -2.15372905e-01 9.64354753e-01 -1.53728351e-01 -2.12004557e-01 9.65096831e-01 -1.53728351e-01 -2.08634511e-01 9.65832233e-01 -1.53728306e-01 -2.05359012e-01 9.66532052e-01 -1.53728038e-01 -2.02006921e-01 9.67245400e-01 -1.53728634e-01 -1.98514268e-01 9.67966199e-01 -1.53728411e-01 -1.95153013e-01 9.68645751e-01 -1.53728276e-01 -1.91774622e-01 9.69321609e-01 -1.53728411e-01 -1.88454404e-01 9.69970524e-01 -1.53728053e-01 -1.85062125e-01 9.70628202e-01 -1.53728634e-01 -1.81677222e-01 9.71261263e-01 -1.53728008e-01 -1.78385258e-01 9.71871972e-01 -1.53728247e-01 -1.74879864e-01 9.72517729e-01 -1.53728545e-01 -1.71392515e-01 9.73136246e-01 -1.53728306e-01 -1.67992502e-01 9.73724723e-01 -1.53728351e-01 -1.64603978e-01 9.74304736e-01 -1.53728381e-01 -1.61281630e-01 9.74857092e-01 -1.53728083e-01 -1.57978818e-01 9.75398839e-01 -1.53728321e-01 -1.54496372e-01 9.75959897e-01 -1.53728530e-01 -1.50976896e-01 9.76510465e-01 -1.53728500e-01 -1.47559732e-01 9.77028787e-01 -1.53728411e-01 -1.44136146e-01 9.77541387e-01 -1.53728351e-01 -1.40721619e-01 9.78038073e-01 -1.53728351e-01 -1.37418404e-01 9.78504777e-01 -1.53727978e-01 -1.34022102e-01 9.78984118e-01 -1.53728664e-01 -1.30484253e-01 9.79456544e-01 -1.53728351e-01 -1.27168015e-01 9.79889333e-01 -1.53728023e-01 -1.23768732e-01 9.80330169e-01 -1.53728515e-01 -1.20335326e-01 9.80752945e-01 -1.53728038e-01 -1.16878934e-01 9.81177390e-01 -1.53728694e-01 -1.13350466e-01 9.81587589e-01 -1.53728411e-01 -1.09931462e-01 9.81975436e-01 -1.53728351e-01 -1.06499121e-01 9.82354045e-01 -1.53728411e-01 -1.03059977e-01 9.82719421e-01 -1.53728276e-01 -9.96381417e-02 9.83073592e-01 -1.53728411e-01 -9.62876081e-02 9.83405054e-01 -1.53728023e-01 -9.29731578e-02 9.83726799e-01 -1.53728306e-01 -8.94354507e-02 9.84057188e-01 -1.53728634e-01 -8.58954042e-02 9.84370530e-01 -1.53728396e-01 -8.24607387e-02 9.84663844e-01 -1.53728411e-01 -7.90147260e-02 9.84946609e-01 -1.53728411e-01 -7.56681412e-02 9.85203743e-01 -1.53727993e-01 -7.22492114e-02 9.85468805e-01 -1.53728634e-01 -6.86736256e-02 9.85718727e-01 -1.53728232e-01 -6.52306080e-02 9.85955179e-01 -1.53728306e-01 -6.18064664e-02 9.86173868e-01 -1.53728351e-01 -5.84730916e-02 9.86376524e-01 -1.53728098e-01 -5.50338961e-02 9.86580551e-01 -1.53728664e-01 -5.15584350e-02 9.86758471e-01 -1.53727978e-01 -4.81299870e-02 9.86941755e-01 -1.53728634e-01 -4.45978940e-02 9.87102032e-01 -1.53728351e-01 -4.11596373e-02 9.87253368e-01 -1.53728411e-01 -3.77072394e-02 9.87389863e-01 -1.53728381e-01 -3.43469307e-02 9.87511337e-01 -1.53728113e-01 -3.09207235e-02 9.87627625e-01 -1.53728634e-01 -2.74417996e-02 9.87725914e-01 -1.53728038e-01 -2.40113176e-02 9.87824619e-01 -1.53728634e-01 -2.04649381e-02 9.87895370e-01 -1.53728411e-01 -1.71060171e-02 9.87963796e-01 -1.53728068e-01 -1.36634689e-02 9.88013506e-01 -1.53728634e-01 -1.02195134e-02 9.88053977e-01 -1.53727993e-01 -6.85480656e-03 9.88091230e-01 -1.53728247e-01 -3.31218494e-03 9.88111198e-01 -1.53728500e-01 2.18624293e-04 9.88111317e-01 -1.53728411e-01 3.66299320e-03 9.88108814e-01 -1.53728276e-01 7.09156087e-03 9.88090694e-01 -1.53728381e-01 1.04668802e-02 9.88051236e-01 -1.53728023e-01 1.38243483e-02 9.88008857e-01 -1.53728351e-01 1.73524581e-02 9.87966716e-01 -1.53728634e-01 2.09187400e-02 9.87887561e-01 -1.53728411e-01 2.43782457e-02 9.87810254e-01 -1.53728411e-01 2.78262086e-02 9.87721860e-01 -1.53728411e-01 3.12863477e-02 9.87616360e-01 -1.53728411e-01 3.46383043e-02 9.87501264e-01 -1.53727993e-01 3.80544811e-02 9.87380981e-01 -1.53728649e-01 4.16142233e-02 9.87235844e-01 -1.53728411e-01 4.50925902e-02 9.87078905e-01 -1.53728142e-01 4.85144146e-02 9.86920059e-01 -1.53728411e-01 5.18735088e-02 9.86743093e-01 -1.53728098e-01 5.52895069e-02 9.86565053e-01 -1.53728634e-01 5.87594807e-02 9.86357570e-01 -1.53727964e-01 6.21735007e-02 9.86152411e-01 -1.53728634e-01 6.57335445e-02 9.85921085e-01 -1.53728306e-01 6.91714659e-02 9.85685289e-01 -1.53728396e-01 7.25780278e-02 9.85442281e-01 -1.53728321e-01 7.60611966e-02 9.85177755e-01 -1.53728351e-01 7.94089586e-02 9.84911323e-01 -1.53728023e-01 8.28036740e-02 9.84636724e-01 -1.53728500e-01 8.63370448e-02 9.84331191e-01 -1.53728306e-01 8.97974074e-02 9.84022021e-01 -1.53728411e-01 9.32355449e-02 9.83700454e-01 -1.53728187e-01 9.65869054e-02 9.83376205e-01 -1.53728053e-01 9.99975130e-02 9.83039916e-01 -1.53728664e-01 1.03442028e-01 9.82679069e-01 -1.53728098e-01 1.06869452e-01 9.82318819e-01 -1.53728694e-01 1.10393949e-01 9.81923521e-01 -1.53728411e-01 1.13738075e-01 9.81538832e-01 -1.53728038e-01 1.17156625e-01 9.81142163e-01 -1.53728634e-01 1.20576680e-01 9.80723798e-01 -1.53728113e-01 1.23993702e-01 9.80302989e-01 -1.53728634e-01 1.27500236e-01 9.79848921e-01 -1.53728411e-01 1.30928338e-01 9.79397357e-01 -1.53728351e-01 1.34353980e-01 9.78935897e-01 -1.53728411e-01 1.37664258e-01 9.78474259e-01 -1.53728247e-01 1.41094774e-01 9.77986336e-01 -1.53728575e-01 1.44510955e-01 9.77482855e-01 -1.53728038e-01 1.47900224e-01 9.76979375e-01 -1.53728634e-01 1.51410237e-01 9.76442218e-01 -1.53728351e-01 1.54740870e-01 9.75915670e-01 -1.53728157e-01 1.58123910e-01 9.75378036e-01 -1.53728515e-01 1.61540240e-01 9.74816382e-01 -1.53728157e-01 1.64839625e-01 9.74264622e-01 -1.53728411e-01 1.68326870e-01 9.73670423e-01 -1.53728664e-01 1.71821475e-01 9.73061085e-01 -1.53728351e-01 1.75223455e-01 9.72454786e-01 -1.53728411e-01 1.78608909e-01 9.71832335e-01 -1.53728217e-01 1.81924403e-01 9.71215427e-01 -1.53727978e-01 1.85208410e-01 9.70597744e-01 -1.53728366e-01 1.88606352e-01 9.69942808e-01 -1.53728336e-01 1.92061052e-01 9.69266415e-01 -1.53728545e-01 1.95526719e-01 9.68572319e-01 -1.53728411e-01 1.98926389e-01 9.67879891e-01 -1.53728411e-01 2.02306554e-01 9.67178166e-01 -1.53728411e-01 2.05593631e-01 9.66483891e-01 -1.53728053e-01 2.08942503e-01 9.65769112e-01 -1.53728634e-01 2.12412387e-01 9.65009391e-01 -1.53728411e-01 2.15811580e-01 9.64256465e-01 -1.53728411e-01 2.19168633e-01 9.63495731e-01 -1.53728276e-01 2.22440615e-01 9.62742627e-01 -1.53727815e-01 2.25793332e-01 9.61971223e-01 -1.53728500e-01 2.29162827e-01 9.61166739e-01 -1.53727949e-01 2.32404247e-01 9.60394084e-01 -1.53728351e-01 2.35849813e-01 9.59553003e-01 -1.53728500e-01 2.39323094e-01 9.58688080e-01 -1.53728276e-01 2.42624432e-01 9.57857728e-01 -1.53728247e-01 2.45951667e-01 9.57011163e-01 -1.53728276e-01 2.49212593e-01 9.56165075e-01 -1.53728098e-01 2.52473533e-01 9.55313325e-01 -1.53728470e-01 2.55909026e-01 9.54399824e-01 -1.53728664e-01 2.59348959e-01 9.53471541e-01 -1.53728500e-01 2.62652874e-01 9.52561140e-01 -1.53728381e-01 2.65891701e-01 9.51662600e-01 -1.53728008e-01 2.69175977e-01 9.50742185e-01 -1.53728545e-01 2.72523612e-01 9.49783981e-01 -1.53728008e-01 2.75800198e-01 9.48842168e-01 -1.53728545e-01 2.79247522e-01 9.47830856e-01 -1.53728351e-01 2.82459885e-01 9.46878791e-01 -1.53728142e-01 2.85751790e-01 9.45891500e-01 -1.53728664e-01 2.89074957e-01 9.44877744e-01 -1.53728113e-01 2.92310506e-01 9.43888009e-01 -1.53728634e-01 2.95711756e-01 9.42826211e-01 -1.53728500e-01 2.98934817e-01 9.41803753e-01 -1.53728068e-01 3.02208424e-01 9.40766096e-01 -1.53728724e-01 3.05516094e-01 9.39690888e-01 -1.53728142e-01 3.08776766e-01 9.38629866e-01 -1.53728664e-01 3.12062800e-01 9.37536299e-01 -1.53728083e-01 3.15223813e-01 9.36482251e-01 -1.53728411e-01 3.18585545e-01 9.35346305e-01 -1.53728664e-01 3.21942717e-01 9.34192896e-01 -1.53728381e-01 3.25183094e-01 9.33069527e-01 -1.53728411e-01 3.28420669e-01 9.31935549e-01 -1.53728411e-01 3.31609368e-01 9.30805266e-01 -1.53728142e-01 3.34837943e-01 9.29651737e-01 -1.53728664e-01 3.38184148e-01 9.28437889e-01 -1.53728455e-01 3.41421604e-01 9.27244961e-01 -1.53728411e-01 3.44638437e-01 9.26051676e-01 -1.53728440e-01 3.47823679e-01 9.24857855e-01 -1.53728157e-01 3.51037145e-01 9.23654020e-01 -1.53728634e-01 3.54244143e-01 9.22432125e-01 -1.53728142e-01 3.57456386e-01 9.21189249e-01 -1.53728664e-01 3.60745043e-01 9.19906080e-01 -1.53728411e-01 3.63887548e-01 9.18665111e-01 -1.53728247e-01 3.67080480e-01 9.17396963e-01 -1.53728634e-01 3.70279461e-01 9.16106582e-01 -1.53728217e-01 3.73461574e-01 9.14818645e-01 -1.53728634e-01 3.76649767e-01 9.13505197e-01 -1.53728217e-01 3.79823744e-01 9.12194431e-01 -1.53728634e-01 3.83087575e-01 9.10827816e-01 -1.53728500e-01 3.86189848e-01 9.09512520e-01 -1.53728098e-01 3.89352471e-01 9.08165932e-01 -1.53728634e-01 3.92533362e-01 9.06793118e-01 -1.53728142e-01 3.95608395e-01 9.05462325e-01 -1.53728411e-01 3.98845732e-01 9.04040933e-01 -1.53728634e-01 4.02057230e-01 9.02614892e-01 -1.53728411e-01 4.05202746e-01 9.01207507e-01 -1.53728500e-01 4.08364773e-01 8.99778783e-01 -1.53728411e-01 4.11430240e-01 8.98376465e-01 -1.53728142e-01 4.14472878e-01 8.96980166e-01 -1.53728411e-01 4.17681903e-01 8.95493507e-01 -1.53728634e-01 4.20854151e-01 8.94003391e-01 -1.53728411e-01 4.23978478e-01 8.92527997e-01 -1.53728411e-01 4.27019656e-01 8.91069651e-01 -1.53727949e-01 4.30132508e-01 8.89581859e-01 -1.53728500e-01 4.33232456e-01 8.88073742e-01 -1.53728247e-01 4.36324567e-01 8.86559188e-01 -1.53728664e-01 4.39503700e-01 8.84985745e-01 -1.53728411e-01 4.42599058e-01 8.83442938e-01 -1.53728500e-01 4.45653468e-01 8.81907105e-01 -1.53728500e-01 4.48671550e-01 8.80370796e-01 -1.53728053e-01 4.51711357e-01 8.78818750e-01 -1.53728500e-01 4.54801142e-01 8.77218783e-01 -1.53728217e-01 4.57804084e-01 8.75660121e-01 -1.53728411e-01 4.60925698e-01 8.74022841e-01 -1.53728664e-01 4.64025557e-01 8.72377396e-01 -1.53728306e-01 4.67060536e-01 8.70758772e-01 -1.53728500e-01 4.70118612e-01 8.69109511e-01 -1.53728411e-01 4.73061860e-01 8.67511094e-01 -1.53728113e-01 4.76093590e-01 8.65855396e-01 -1.53728664e-01 4.79209960e-01 8.64128292e-01 -1.53728411e-01 4.82230604e-01 8.62447262e-01 -1.53728381e-01 4.85212743e-01 8.60773444e-01 -1.53728262e-01 4.88127708e-01 8.59116971e-01 -1.53727815e-01 4.91149455e-01 8.57403219e-01 -1.53728560e-01 4.94134307e-01 8.55680883e-01 -1.53728023e-01 4.97093290e-01 8.53970289e-01 -1.53728500e-01 5.00191391e-01 8.52157593e-01 -1.53728306e-01 5.03077447e-01 8.50453019e-01 -1.53728068e-01 5.06019890e-01 8.48712206e-01 -1.53728634e-01 5.08980274e-01 8.46934617e-01 -1.53728113e-01 5.11927783e-01 8.45159471e-01 -1.53728634e-01 5.14937103e-01 8.43331277e-01 -1.53728426e-01 5.17820001e-01 8.41558576e-01 -1.53728232e-01 5.20766854e-01 8.39747071e-01 -1.53728664e-01 5.23690104e-01 8.37919414e-01 -1.53728187e-01 5.26590347e-01 8.36105525e-01 -1.53728649e-01 5.29529929e-01 8.34240735e-01 -1.53728232e-01 5.32419980e-01 8.32401872e-01 -1.53728634e-01 5.35404325e-01 8.30484867e-01 -1.53728500e-01 5.38234174e-01 8.28651488e-01 -1.53728217e-01 5.41098833e-01 8.26786637e-01 -1.53728634e-01 5.43986559e-01 8.24885786e-01 -1.53728083e-01 5.46779037e-01 8.23037744e-01 -1.53728351e-01 5.49747586e-01 8.21061790e-01 -1.53728500e-01 5.52610278e-01 8.19133699e-01 -1.53727949e-01 5.55454910e-01 8.17211211e-01 -1.53728500e-01 5.58399379e-01 8.15199137e-01 -1.53728142e-01 5.61081946e-01 8.13347936e-01 -1.53726980e-01 5.63888371e-01 8.11403573e-01 -1.53726384e-01 5.66696882e-01 8.09445500e-01 -1.53726399e-01 5.69592297e-01 8.07412088e-01 -1.53726414e-01 5.72522223e-01 8.05338025e-01 -1.53726786e-01 5.75215042e-01 8.03418398e-01 -1.53727338e-01 5.77729881e-01 8.01620007e-01 -1.53727368e-01 5.80761671e-01 7.99426675e-01 -1.53727457e-01 5.83492219e-01 7.97435820e-01 -1.53727427e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.04192877e-01 6.93166316e-01 -1.53727472e-01 7.06283391e-01 6.91035628e-01 -1.53727114e-01 7.08523214e-01 6.88732147e-01 -1.53727189e-01 7.10913241e-01 6.86255217e-01 -1.53726563e-01 7.13330746e-01 6.83739603e-01 -1.53727621e-01 7.15706944e-01 6.81265652e-01 -1.53727964e-01 7.17986107e-01 6.78857207e-01 -1.53727859e-01 7.20352471e-01 6.76355124e-01 -1.53728500e-01 7.22776890e-01 6.73758566e-01 -1.53728157e-01 7.25087523e-01 6.71274006e-01 -1.53728157e-01 7.27377355e-01 6.68794453e-01 -1.53728187e-01 7.29675412e-01 6.66283548e-01 -1.53728306e-01 7.32067525e-01 6.63661599e-01 -1.53728634e-01 7.34436691e-01 6.61034703e-01 -1.53728411e-01 7.36731887e-01 6.58472896e-01 -1.53728336e-01 7.38967299e-01 6.55963182e-01 -1.53728098e-01 7.41197228e-01 6.53444290e-01 -1.53728351e-01 7.43497193e-01 6.50824487e-01 -1.53728500e-01 7.45798647e-01 6.48188174e-01 -1.53728411e-01 7.48082161e-01 6.45552993e-01 -1.53728545e-01 7.50340104e-01 6.42925084e-01 -1.53728276e-01 7.52518177e-01 6.40368581e-01 -1.53728113e-01 7.54733264e-01 6.37764275e-01 -1.53728411e-01 7.56964207e-01 6.35111272e-01 -1.53728306e-01 7.59214938e-01 6.32424712e-01 -1.53728634e-01 7.61476398e-01 6.29694939e-01 -1.53728411e-01 7.63620019e-01 6.27091467e-01 -1.53728083e-01 7.65787244e-01 6.24448299e-01 -1.53728530e-01 7.68009663e-01 6.21711433e-01 -1.53728411e-01 7.70191967e-01 6.19006872e-01 -1.53728500e-01 7.72296548e-01 6.16374254e-01 -1.53728113e-01 7.74375677e-01 6.13763869e-01 -1.53728411e-01 7.76578486e-01 6.10978127e-01 -1.53728634e-01 7.78757513e-01 6.08193934e-01 -1.53728351e-01 7.80880094e-01 6.05469644e-01 -1.53728500e-01 7.82942653e-01 6.02790654e-01 -1.53727949e-01 7.84972131e-01 6.00152731e-01 -1.53728411e-01 7.87118971e-01 5.97337067e-01 -1.53728664e-01 7.89259434e-01 5.94502449e-01 -1.53728351e-01 7.91330695e-01 5.91741621e-01 -1.53728500e-01 7.93346107e-01 5.89033604e-01 -1.53728113e-01 7.95329154e-01 5.86354792e-01 -1.53728306e-01 7.97425032e-01 5.83508134e-01 -1.53728664e-01 7.99522936e-01 5.80627263e-01 -1.53728500e-01 8.01547229e-01 5.77823997e-01 -1.53728396e-01 8.03553343e-01 5.75035036e-01 -1.53728306e-01 8.05482209e-01 5.72326720e-01 -1.53728053e-01 8.07441652e-01 5.69567561e-01 -1.53728500e-01 8.09435129e-01 5.66725552e-01 -1.53728306e-01 8.11452031e-01 5.63839674e-01 -1.53728738e-01 8.13439488e-01 5.60958326e-01 -1.53728023e-01 8.15323889e-01 5.58220148e-01 -1.53728411e-01 8.17330956e-01 5.55284619e-01 -1.53728738e-01 8.19260478e-01 5.52420676e-01 -1.53728008e-01 8.21150124e-01 5.49616039e-01 -1.53728634e-01 8.23071301e-01 5.46730280e-01 -1.53728276e-01 8.24941099e-01 5.43907940e-01 -1.53728426e-01 8.26889157e-01 5.40943563e-01 -1.53728634e-01 8.28821242e-01 5.37975371e-01 -1.53728455e-01 8.30639064e-01 5.35159588e-01 -1.53728053e-01 8.32449436e-01 5.32345414e-01 -1.53728351e-01 8.34298491e-01 5.29442787e-01 -1.53728515e-01 8.36219728e-01 5.26410818e-01 -1.53728694e-01 8.38109195e-01 5.23389041e-01 -1.53728500e-01 8.39920342e-01 5.20476639e-01 -1.53728276e-01 8.41673493e-01 5.17629802e-01 -1.53728157e-01 8.43438625e-01 5.14759421e-01 -1.53728411e-01 8.45235229e-01 5.11803269e-01 -1.53728500e-01 8.47016752e-01 5.08848488e-01 -1.53728411e-01 8.48831177e-01 5.05819559e-01 -1.53728694e-01 8.50643337e-01 5.02761781e-01 -1.53728411e-01 8.52347851e-01 4.99863595e-01 -1.53728127e-01 8.54076266e-01 4.96913403e-01 -1.53728664e-01 8.55810881e-01 4.93912071e-01 -1.53728113e-01 8.57530832e-01 4.90926802e-01 -1.53728664e-01 8.59254479e-01 4.87892032e-01 -1.53728276e-01 8.60907257e-01 4.84978050e-01 -1.53728306e-01 8.62621307e-01 4.81924832e-01 -1.53728664e-01 8.64307463e-01 4.78885323e-01 -1.53728306e-01 8.65976036e-01 4.75869179e-01 -1.53728500e-01 8.67622435e-01 4.72855091e-01 -1.53728127e-01 8.69226098e-01 4.69904155e-01 -1.53728411e-01 8.70898485e-01 4.66801226e-01 -1.53728634e-01 8.72573435e-01 4.63662535e-01 -1.53728500e-01 8.74188483e-01 4.60605502e-01 -1.53728381e-01 8.75745237e-01 4.57635403e-01 -1.53728142e-01 8.77286553e-01 4.54676241e-01 -1.53728351e-01 8.78911674e-01 4.51535374e-01 -1.53728664e-01 8.80526900e-01 4.48373497e-01 -1.53728500e-01 8.82082582e-01 4.45302784e-01 -1.53728411e-01 8.83641601e-01 4.42202419e-01 -1.53728500e-01 8.85145903e-01 4.39173579e-01 -1.53728053e-01 8.86661172e-01 4.36119348e-01 -1.53728634e-01 8.88180852e-01 4.33009148e-01 -1.53728113e-01 8.89688015e-01 4.29914832e-01 -1.53728664e-01 8.91224265e-01 4.26711679e-01 -1.53728455e-01 8.92664433e-01 4.23684448e-01 -1.53728142e-01 8.94127965e-01 4.20597881e-01 -1.53728664e-01 8.95601332e-01 4.17443693e-01 -1.53728187e-01 8.97050977e-01 4.14331585e-01 -1.53728664e-01 8.98530960e-01 4.11101699e-01 -1.53728440e-01 8.99925351e-01 4.08032626e-01 -1.53728068e-01 9.01337266e-01 4.04921144e-01 -1.53728694e-01 9.02747333e-01 4.01754200e-01 -1.53728142e-01 9.04147208e-01 3.98608625e-01 -1.53728694e-01 9.05534029e-01 3.95435184e-01 -1.53728187e-01 9.06872869e-01 3.92360389e-01 -1.53728500e-01 9.08274949e-01 3.89102906e-01 -1.53728724e-01 9.09661591e-01 3.85847062e-01 -1.53728426e-01 9.10995901e-01 3.82687479e-01 -1.53728411e-01 9.12292242e-01 3.79581332e-01 -1.53728217e-01 9.13573027e-01 3.76491904e-01 -1.53728500e-01 9.14919674e-01 3.73215973e-01 -1.53728724e-01 9.16264296e-01 3.69900554e-01 -1.53728500e-01 9.17550683e-01 3.66693377e-01 -1.53728440e-01 9.18788850e-01 3.63577902e-01 -1.53728142e-01 9.20009136e-01 3.60487819e-01 -1.53728411e-01 9.21288192e-01 3.57197523e-01 -1.53728694e-01 9.22543526e-01 3.53951544e-01 -1.53728217e-01 9.23760653e-01 3.50755572e-01 -1.53728664e-01 9.25017536e-01 3.47409219e-01 -1.53728500e-01 9.26187932e-01 3.44263673e-01 -1.53728217e-01 9.27388787e-01 3.41046304e-01 -1.53728694e-01 9.28579926e-01 3.37791145e-01 -1.53728113e-01 9.29745793e-01 3.34580064e-01 -1.53728738e-01 9.30942535e-01 3.31229031e-01 -1.53728500e-01 9.32063282e-01 3.28055114e-01 -1.53728232e-01 9.33197856e-01 3.24825257e-01 -1.53728664e-01 9.34349656e-01 3.21489692e-01 -1.53728485e-01 9.35454071e-01 3.18257272e-01 -1.53728396e-01 9.36544657e-01 3.15035284e-01 -1.53728276e-01 9.37614918e-01 3.11835617e-01 -1.53728470e-01 9.38724101e-01 3.08491498e-01 -1.53728664e-01 9.39816177e-01 3.05139303e-01 -1.53728411e-01 9.40875292e-01 3.01861286e-01 -1.53728500e-01 9.41901565e-01 2.98633397e-01 -1.53728142e-01 9.42909002e-01 2.95445234e-01 -1.53728485e-01 9.43965137e-01 2.92058468e-01 -1.53728709e-01 9.45006609e-01 2.88663179e-01 -1.53728500e-01 9.45999801e-01 2.85389185e-01 -1.53728411e-01 9.46964383e-01 2.82161951e-01 -1.53728157e-01 9.47924852e-01 2.78935730e-01 -1.53728485e-01 9.48918223e-01 2.75549293e-01 -1.53728664e-01 9.49866652e-01 2.72232950e-01 -1.53728157e-01 9.50820684e-01 2.68906713e-01 -1.53728724e-01 9.51767325e-01 2.65524805e-01 -1.53728411e-01 9.52665031e-01 2.62275219e-01 -1.53728113e-01 9.53580320e-01 2.58954763e-01 -1.53728724e-01 9.54502225e-01 2.55514473e-01 -1.53728411e-01 9.55380440e-01 2.52217799e-01 -1.53728411e-01 9.56256688e-01 2.48876169e-01 -1.53728500e-01 9.57100093e-01 2.45604798e-01 -1.53728187e-01 9.57947373e-01 2.42283046e-01 -1.53728664e-01 9.58786607e-01 2.38933548e-01 -1.53728232e-01 9.59623694e-01 2.35576540e-01 -1.53728724e-01 9.60436463e-01 2.32217178e-01 -1.53728232e-01 9.61219549e-01 2.28964880e-01 -1.53728411e-01 9.62034345e-01 2.25530311e-01 -1.53728694e-01 9.62827563e-01 2.22093731e-01 -1.53728411e-01 9.63599622e-01 2.18729690e-01 -1.53728500e-01 9.64361906e-01 2.15345442e-01 -1.53728500e-01 9.65085149e-01 2.12054089e-01 -1.53728157e-01 9.65819955e-01 2.08705992e-01 -1.53728694e-01 9.66562629e-01 2.05233708e-01 -1.53728500e-01 9.67273653e-01 2.01862067e-01 -1.53728411e-01 9.67971683e-01 1.98487923e-01 -1.53728411e-01 9.68639612e-01 1.95187584e-01 -1.53728247e-01 9.69311059e-01 1.91836566e-01 -1.53728694e-01 9.69979227e-01 1.88417405e-01 -1.53728217e-01 9.70630765e-01 1.85049981e-01 -1.53728694e-01 9.71284628e-01 1.81578636e-01 -1.53728485e-01 9.71892059e-01 1.78273991e-01 -1.53728276e-01 9.72521067e-01 1.74876034e-01 -1.53728694e-01 9.73135710e-01 1.71404496e-01 -1.53728411e-01 9.73718941e-01 1.68032676e-01 -1.53728500e-01 9.74288583e-01 1.64691389e-01 -1.53728276e-01 9.74845946e-01 1.61371037e-01 -1.53728500e-01 9.75417912e-01 1.57888070e-01 -1.53728694e-01 9.75974679e-01 1.54391512e-01 -1.53728500e-01 9.76506889e-01 1.50987580e-01 -1.53728500e-01 9.77014899e-01 1.47651300e-01 -1.53728262e-01 9.77513731e-01 1.44333899e-01 -1.53728500e-01 9.78024960e-01 1.40841350e-01 -1.53728694e-01 9.78521168e-01 1.37337729e-01 -1.53728470e-01 9.78993416e-01 1.33935988e-01 -1.53728411e-01 9.79456604e-01 1.30508780e-01 -1.53728634e-01 9.79893029e-01 1.27152085e-01 -1.53728127e-01 9.80332732e-01 1.23763412e-01 -1.53728664e-01 9.80769038e-01 1.20233774e-01 -1.53728500e-01 9.81181622e-01 1.16809480e-01 -1.53728411e-01 9.81582642e-01 1.13396272e-01 -1.53728470e-01 9.81961548e-01 1.10052109e-01 -1.53728217e-01 9.82345164e-01 1.06614277e-01 -1.53728724e-01 9.82707322e-01 1.03180811e-01 -1.53728217e-01 9.83061671e-01 9.97734889e-02 -1.53728709e-01 9.83414233e-01 9.62308422e-02 -1.53728500e-01 9.83732462e-01 9.28978026e-02 -1.53728098e-01 9.84054625e-01 8.94794017e-02 -1.53728694e-01 9.84357178e-01 8.60344544e-02 -1.53728172e-01 9.84657168e-01 8.25740919e-02 -1.53728694e-01 9.84934926e-01 7.91274384e-02 -1.53728098e-01 9.85208690e-01 7.57151842e-02 -1.53728664e-01 9.85472441e-01 7.21733347e-02 -1.53728589e-01 9.85717654e-01 6.87134638e-02 -1.53728455e-01 9.85953450e-01 6.52775839e-02 -1.53728500e-01 9.86165464e-01 6.19231090e-02 -1.53728187e-01 9.86371994e-01 5.85820265e-02 -1.53728500e-01 9.86580551e-01 5.50489351e-02 -1.53728724e-01 9.86768663e-01 5.14940657e-02 -1.53728500e-01 9.86943662e-01 4.80538867e-02 -1.53728500e-01 9.87095773e-01 4.47007306e-02 -1.53728083e-01 9.87245560e-01 4.13775519e-02 -1.53728470e-01 9.87383544e-01 3.79251465e-02 -1.53728530e-01 9.87509489e-01 3.44712362e-02 -1.53728500e-01 9.87630606e-01 3.09070535e-02 -1.53728724e-01 9.87734556e-01 2.73452941e-02 -1.53728500e-01 9.87820029e-01 2.40137614e-02 -1.53728142e-01 9.87891793e-01 2.06851978e-02 -1.53728500e-01 9.87967372e-01 1.72227807e-02 -1.53728500e-01 9.88010526e-01 1.37705272e-02 -1.53728500e-01 9.88060057e-01 1.03044491e-02 -1.53728500e-01 9.88094807e-01 6.86437078e-03 -1.53728500e-01 9.88113880e-01 3.32206767e-03 -1.53728724e-01 9.88109231e-01 -1.33361027e-04 -1.53728157e-01 9.88113582e-01 -3.56567698e-03 -1.53728724e-01 9.88089621e-01 -7.03970529e-03 -1.53728187e-01 9.88058388e-01 -1.03823468e-02 -1.53728500e-01 9.88009870e-01 -1.39001608e-02 -1.53728694e-01 9.87963319e-01 -1.74628459e-02 -1.53728500e-01 9.87887442e-01 -2.08271518e-02 -1.53728276e-01 9.87818003e-01 -2.42851526e-02 -1.53728738e-01 9.87719715e-01 -2.77482904e-02 -1.53728113e-01 9.87622440e-01 -3.11602969e-02 -1.53728664e-01 9.87504065e-01 -3.46213207e-02 -1.53728276e-01 9.87381101e-01 -3.79869565e-02 -1.53728500e-01 9.87243831e-01 -4.14256305e-02 -1.53728500e-01 9.87091959e-01 -4.49324772e-02 -1.53728738e-01 9.86922383e-01 -4.84879389e-02 -1.53728426e-01 9.86743748e-01 -5.19335605e-02 -1.53728500e-01 9.86559868e-01 -5.53102717e-02 -1.53728262e-01 9.86369371e-01 -5.86446226e-02 -1.53728500e-01 9.86157119e-01 -6.20841235e-02 -1.53728500e-01 9.85933661e-01 -6.56092688e-02 -1.53728694e-01 9.85689223e-01 -6.91287294e-02 -1.53728455e-01 9.85444665e-01 -7.25649148e-02 -1.53728500e-01 9.85187650e-01 -7.59403184e-02 -1.53728351e-01 9.84923601e-01 -7.93063939e-02 -1.53728500e-01 9.84641731e-01 -8.27258378e-02 -1.53728500e-01 9.84342396e-01 -8.62534493e-02 -1.53728664e-01 9.84029412e-01 -8.96927193e-02 -1.53728202e-01 9.83722568e-01 -9.30407196e-02 -1.53728500e-01 9.83392417e-01 -9.64618400e-02 -1.53728500e-01 9.83040810e-01 -9.99960974e-02 -1.53728709e-01 9.82679665e-01 -1.03434324e-01 -1.53728157e-01 9.82321382e-01 -1.06829695e-01 -1.53728724e-01 9.81936276e-01 -1.10275477e-01 -1.53728113e-01 9.81560349e-01 -1.13586709e-01 -1.53728500e-01 9.81149137e-01 -1.17119007e-01 -1.53728694e-01 9.80728805e-01 -1.20542258e-01 -1.53728187e-01 9.80309010e-01 -1.23969257e-01 -1.53728694e-01 9.79852021e-01 -1.27484560e-01 -1.53728545e-01 9.79408681e-01 -1.30836740e-01 -1.53728247e-01 9.78956878e-01 -1.34215206e-01 -1.53728664e-01 9.78465915e-01 -1.37735128e-01 -1.53728500e-01 9.77986097e-01 -1.41078904e-01 -1.53728187e-01 9.77495253e-01 -1.44465610e-01 -1.53728694e-01 9.76980150e-01 -1.47880837e-01 -1.53728217e-01 9.76462066e-01 -1.51289880e-01 -1.53728664e-01 9.75921512e-01 -1.54714137e-01 -1.53728262e-01 9.75382030e-01 -1.58099130e-01 -1.53728619e-01 9.74829376e-01 -1.61461532e-01 -1.53728276e-01 9.74258840e-01 -1.64898977e-01 -1.53728694e-01 9.73655105e-01 -1.68391973e-01 -1.53728485e-01 9.73070681e-01 -1.71770811e-01 -1.53728440e-01 9.72475350e-01 -1.75094560e-01 -1.53728276e-01 9.71867323e-01 -1.78422958e-01 -1.53728500e-01 9.71242905e-01 -1.81810528e-01 -1.53728500e-01 9.70591962e-01 -1.85248822e-01 -1.53728664e-01 9.69919741e-01 -1.88731074e-01 -1.53728485e-01 9.69254434e-01 -1.92119911e-01 -1.53728411e-01 9.68591034e-01 -1.95429191e-01 -1.53728276e-01 9.67924118e-01 -1.98715538e-01 -1.53728455e-01 9.67228293e-01 -2.02080801e-01 -1.53728500e-01 9.66499686e-01 -2.05549896e-01 -1.53728724e-01 9.65768576e-01 -2.08930939e-01 -1.53728187e-01 9.65050161e-01 -2.12238207e-01 -1.53728634e-01 9.64300752e-01 -2.15612143e-01 -1.53728351e-01 9.63535130e-01 -2.19016612e-01 -1.53728724e-01 9.62757885e-01 -2.22390741e-01 -1.53728217e-01 9.61984754e-01 -2.25745708e-01 -1.53728738e-01 9.61179733e-01 -2.29121119e-01 -1.53728172e-01 9.60406780e-01 -2.32353553e-01 -1.53728500e-01 9.59569573e-01 -2.35789746e-01 -1.53728724e-01 9.58733261e-01 -2.39145666e-01 -1.53728276e-01 9.57888305e-01 -2.42523178e-01 -1.53728738e-01 9.57009375e-01 -2.45959714e-01 -1.53728440e-01 9.56170082e-01 -2.49194324e-01 -1.53728157e-01 9.55302894e-01 -2.52529293e-01 -1.53728753e-01 9.54408467e-01 -2.55861312e-01 -1.53728113e-01 9.53542411e-01 -2.59083033e-01 -1.53728500e-01 9.52611685e-01 -2.62488514e-01 -1.53728738e-01 9.51676130e-01 -2.65853375e-01 -1.53728276e-01 9.50749040e-01 -2.69156277e-01 -1.53728664e-01 9.49775338e-01 -2.72562027e-01 -1.53728545e-01 9.48839247e-01 -2.75795281e-01 -1.53728113e-01 9.47902620e-01 -2.79006213e-01 -1.53728500e-01 9.46900606e-01 -2.82400101e-01 -1.53728664e-01 9.45886016e-01 -2.85762519e-01 -1.53728411e-01 9.44886923e-01 -2.89058834e-01 -1.53728500e-01 9.43885326e-01 -2.92308509e-01 -1.53728276e-01 9.42890048e-01 -2.95505822e-01 -1.53728440e-01 9.41854179e-01 -2.98791677e-01 -1.53728500e-01 9.40780997e-01 -3.02159190e-01 -1.53728724e-01 9.39679682e-01 -3.05560350e-01 -1.53728500e-01 9.38605964e-01 -3.08841556e-01 -1.53728411e-01 9.37551796e-01 -3.12021077e-01 -1.53728217e-01 9.36491787e-01 -3.15196663e-01 -1.53728500e-01 9.35388863e-01 -3.18455100e-01 -1.53728500e-01 9.34244931e-01 -3.21798831e-01 -1.53728694e-01 9.33101237e-01 -3.25086981e-01 -1.53728217e-01 9.31997418e-01 -3.28245640e-01 -1.53728411e-01 9.30850923e-01 -3.31481606e-01 -1.53728455e-01 9.29663420e-01 -3.34808797e-01 -1.53728724e-01 9.28474963e-01 -3.38080227e-01 -1.53728262e-01 9.27290082e-01 -3.41313452e-01 -1.53728664e-01 9.26078498e-01 -3.44557941e-01 -1.53728217e-01 9.24913704e-01 -3.47686112e-01 -1.53728500e-01 9.23696995e-01 -3.50919574e-01 -1.53728500e-01 9.22468364e-01 -3.54152113e-01 -1.53728485e-01 9.21220601e-01 -3.57372224e-01 -1.53728500e-01 9.19945896e-01 -3.60655874e-01 -1.53728694e-01 9.18672502e-01 -3.63867134e-01 -1.53728127e-01 9.17412281e-01 -3.67045194e-01 -1.53728679e-01 9.16112542e-01 -3.70263934e-01 -1.53728142e-01 9.14858103e-01 -3.73361945e-01 -1.53728500e-01 9.13514614e-01 -3.76639903e-01 -1.53728664e-01 9.12181795e-01 -3.79848808e-01 -1.53728276e-01 9.10856664e-01 -3.83027285e-01 -1.53728694e-01 9.09471691e-01 -3.86294037e-01 -1.53728545e-01 9.08145010e-01 -3.89394909e-01 -1.53728187e-01 9.06839371e-01 -3.92435730e-01 -1.53728485e-01 9.05433059e-01 -3.95681590e-01 -1.53728738e-01 9.03988779e-01 -3.98963004e-01 -1.53728500e-01 9.02581573e-01 -4.02132571e-01 -1.53728411e-01 9.01192904e-01 -4.05236632e-01 -1.53728411e-01 8.99806201e-01 -4.08301383e-01 -1.53728247e-01 8.98409247e-01 -4.11364555e-01 -1.53728485e-01 8.96939933e-01 -4.14568245e-01 -1.53728724e-01 8.95441413e-01 -4.17787224e-01 -1.53728500e-01 8.93960655e-01 -4.20948923e-01 -1.53728500e-01 8.92526090e-01 -4.23974395e-01 -1.53728098e-01 8.91103148e-01 -4.26963240e-01 -1.53728500e-01 8.89600992e-01 -4.30092067e-01 -1.53728500e-01 8.88058126e-01 -4.33277130e-01 -1.53728738e-01 8.86499941e-01 -4.36440438e-01 -1.53728411e-01 8.84975433e-01 -4.39527899e-01 -1.53728634e-01 8.83457959e-01 -4.42560434e-01 -1.53728142e-01 8.81960273e-01 -4.45544988e-01 -1.53728411e-01 8.80401075e-01 -4.48620498e-01 -1.53728500e-01 8.78787518e-01 -4.51776713e-01 -1.53728664e-01 8.77186239e-01 -4.54867959e-01 -1.53728306e-01 8.75607669e-01 -4.57905650e-01 -1.53728604e-01 8.74013186e-01 -4.60935533e-01 -1.53728217e-01 8.72434020e-01 -4.63919401e-01 -1.53728500e-01 8.70810747e-01 -4.66963619e-01 -1.53728500e-01 8.69133413e-01 -4.70083028e-01 -1.53728738e-01 8.67473245e-01 -4.73132163e-01 -1.53728157e-01 8.65866005e-01 -4.76069421e-01 -1.53728500e-01 8.64201009e-01 -4.79081988e-01 -1.53728500e-01 8.62492740e-01 -4.82156128e-01 -1.53728709e-01 8.60791862e-01 -4.85178947e-01 -1.53728217e-01 8.59096646e-01 -4.88182127e-01 -1.53728724e-01 8.57386708e-01 -4.91172820e-01 -1.53728157e-01 8.55678201e-01 -4.94149923e-01 -1.53728694e-01 8.53931963e-01 -4.97152984e-01 -1.53728217e-01 8.52235794e-01 -5.00061035e-01 -1.53728500e-01 8.50474775e-01 -5.03051758e-01 -1.53728530e-01 8.48691523e-01 -5.06051958e-01 -1.53728500e-01 8.46897066e-01 -5.09051144e-01 -1.53728634e-01 8.45087409e-01 -5.12045741e-01 -1.53728500e-01 8.43327761e-01 -5.14938653e-01 -1.53728187e-01 8.41580272e-01 -5.17790139e-01 -1.53728500e-01 8.39774966e-01 -5.20715714e-01 -1.53728411e-01 8.37910771e-01 -5.23711681e-01 -1.53728694e-01 8.36033344e-01 -5.26701629e-01 -1.53728500e-01 8.34232926e-01 -5.29542565e-01 -1.53728247e-01 8.32418740e-01 -5.32392979e-01 -1.53728500e-01 8.30510974e-01 -5.35369456e-01 -1.53728679e-01 8.28590989e-01 -5.38332343e-01 -1.53728500e-01 8.26709270e-01 -5.41214049e-01 -1.53728470e-01 8.24819028e-01 -5.44095814e-01 -1.53728500e-01 8.22948277e-01 -5.46911061e-01 -1.53728187e-01 8.21085751e-01 -5.49710572e-01 -1.53728500e-01 8.19180369e-01 -5.52551210e-01 -1.53728470e-01 8.17191601e-01 -5.55488884e-01 -1.53728753e-01 8.15188408e-01 -5.58420599e-01 -1.53728411e-01 8.13260078e-01 -5.61227500e-01 -1.53728500e-01 8.11337709e-01 -5.63996732e-01 -1.53728276e-01 8.09379876e-01 -5.66808879e-01 -1.53728664e-01 8.07382643e-01 -5.69646478e-01 -1.53728276e-01 8.05378914e-01 -5.72481751e-01 -1.53728724e-01 8.03363979e-01 -5.75297832e-01 -1.53728187e-01 8.01386595e-01 -5.78049958e-01 -1.53728634e-01 7.99322009e-01 -5.80908895e-01 -1.53728664e-01 7.97259867e-01 -5.83729386e-01 -1.53728500e-01 7.95205474e-01 -5.86528122e-01 -1.53728634e-01 7.93135643e-01 -5.89321196e-01 -1.53728500e-01 7.91131198e-01 -5.92003942e-01 -1.53728142e-01 7.89081633e-01 -5.94745040e-01 -1.53728738e-01 7.86989868e-01 -5.97500265e-01 -1.53728142e-01 7.84903586e-01 -6.00247681e-01 -1.53728724e-01 7.82790422e-01 -6.02990746e-01 -1.53728127e-01 7.80744672e-01 -6.05642080e-01 -1.53728500e-01 7.78578639e-01 -6.08426988e-01 -1.53728664e-01 7.76392579e-01 -6.11211121e-01 -1.53728500e-01 7.74306059e-01 -6.13848031e-01 -1.53728247e-01 7.72218108e-01 -6.16479218e-01 -1.53728500e-01 7.70017385e-01 -6.19226456e-01 -1.53728664e-01 7.67791808e-01 -6.21982574e-01 -1.53728500e-01 7.65647292e-01 -6.24614000e-01 -1.53728306e-01 7.63524413e-01 -6.27212882e-01 -1.53728500e-01 7.61336803e-01 -6.29866779e-01 -1.53728455e-01 7.59145975e-01 -6.32505596e-01 -1.53728500e-01 7.56935656e-01 -6.35148764e-01 -1.53728500e-01 7.54662037e-01 -6.37851238e-01 -1.53728694e-01 7.52426028e-01 -6.40480042e-01 -1.53728276e-01 7.50242889e-01 -6.43039286e-01 -1.53728500e-01 7.48000085e-01 -6.45647526e-01 -1.53728426e-01 7.45715439e-01 -6.48288488e-01 -1.53728634e-01 7.43377268e-01 -6.50967777e-01 -1.53728664e-01 7.41068423e-01 -6.53591633e-01 -1.53728455e-01 7.38830686e-01 -6.56117976e-01 -1.53728217e-01 7.36610770e-01 -6.58612072e-01 -1.53728500e-01 7.34255552e-01 -6.61240458e-01 -1.53728664e-01 7.31941462e-01 -6.63795888e-01 -1.53728172e-01 7.29618967e-01 -6.66353583e-01 -1.53728753e-01 7.27283955e-01 -6.68893278e-01 -1.53728083e-01 7.25026786e-01 -6.71342254e-01 -1.53728500e-01 7.22676754e-01 -6.73870802e-01 -1.53728500e-01 7.20257401e-01 -6.76460028e-01 -1.53728724e-01 7.17863500e-01 -6.78991318e-01 -1.53728247e-01 7.15490520e-01 -6.81505263e-01 -1.53728738e-01 7.13093162e-01 -6.83995008e-01 -1.53728098e-01 7.10735202e-01 -6.86469615e-01 -1.53728738e-01 7.08316743e-01 -6.88950360e-01 -1.53728038e-01 7.05993116e-01 -6.91331983e-01 -1.53728411e-01 7.03544617e-01 -6.93829894e-01 -1.53728634e-01 7.01090336e-01 -6.96309566e-01 -1.53728411e-01 6.98612750e-01 -6.98776126e-01 -1.53728500e-01 6.96133375e-01 -7.01256335e-01 -1.53727829e-01 6.93763793e-01 -7.03595161e-01 -1.53726384e-01 6.91329598e-01 -7.05985606e-01 -1.53726399e-01 6.88889384e-01 -7.08367944e-01 -1.53726563e-01 6.86363757e-01 -7.10811555e-01 -1.53726950e-01 6.83856666e-01 -7.13231862e-01 -1.53727651e-01 6.81599438e-01 -7.15394318e-01 -1.53727174e-01 6.79090381e-01 -7.17776835e-01 -1.53727487e-01 6.76670909e-01 -7.20058024e-01 -1.53727457e-01 6.74458921e-01 -7.22130775e-01 -1.53727442e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 5.65874100e-01 -8.10033619e-01 -1.53727472e-01 5.63453496e-01 -8.11718822e-01 -1.53727174e-01 5.60862482e-01 -8.13507676e-01 -1.53727591e-01 5.57989478e-01 -8.15474153e-01 -1.53726935e-01 5.55271208e-01 -8.17323744e-01 -1.53727442e-01 5.52510262e-01 -8.19204271e-01 -1.53728276e-01 5.49642086e-01 -8.21131110e-01 -1.53728411e-01 5.46713471e-01 -8.23086321e-01 -1.53728664e-01 5.43813109e-01 -8.25001359e-01 -1.53728187e-01 5.41017592e-01 -8.26837838e-01 -1.53728351e-01 5.38151264e-01 -8.28708231e-01 -1.53728470e-01 5.35250306e-01 -8.30585063e-01 -1.53728455e-01 5.32355368e-01 -8.32441926e-01 -1.53728500e-01 5.29449105e-01 -8.34294438e-01 -1.53728500e-01 5.26542068e-01 -8.36135089e-01 -1.53728500e-01 5.23632050e-01 -8.37955654e-01 -1.53728470e-01 5.20698428e-01 -8.39786351e-01 -1.53728500e-01 5.17766476e-01 -8.41594279e-01 -1.53728500e-01 5.14828026e-01 -8.43397915e-01 -1.53728500e-01 5.11870861e-01 -8.45193326e-01 -1.53728500e-01 5.08921266e-01 -8.46973181e-01 -1.53728455e-01 5.05891442e-01 -8.48789513e-01 -1.53728724e-01 5.02895653e-01 -8.50562811e-01 -1.53728276e-01 5.00027657e-01 -8.52254152e-01 -1.53728500e-01 4.97037798e-01 -8.54000092e-01 -1.53728500e-01 4.93977338e-01 -8.55778396e-01 -1.53728694e-01 4.90958214e-01 -8.57508421e-01 -1.53728157e-01 4.88050073e-01 -8.59167695e-01 -1.53728411e-01 4.85054046e-01 -8.60867560e-01 -1.53728500e-01 4.82064009e-01 -8.62541735e-01 -1.53728500e-01 4.79055166e-01 -8.64215136e-01 -1.53728530e-01 4.76020485e-01 -8.65894258e-01 -1.53728500e-01 4.73006010e-01 -8.67543757e-01 -1.53728411e-01 4.69951719e-01 -8.69200289e-01 -1.53728500e-01 4.66922164e-01 -8.70831311e-01 -1.53728426e-01 4.63883013e-01 -8.72453988e-01 -1.53728500e-01 4.60836887e-01 -8.74068618e-01 -1.53728485e-01 4.57709402e-01 -8.75711381e-01 -1.53728724e-01 4.54633951e-01 -8.77306879e-01 -1.53728217e-01 4.51651990e-01 -8.78849387e-01 -1.53728485e-01 4.48588431e-01 -8.80416989e-01 -1.53728500e-01 4.45505202e-01 -8.81981313e-01 -1.53728500e-01 4.42421108e-01 -8.83530438e-01 -1.53728440e-01 4.39333051e-01 -8.85072410e-01 -1.53728500e-01 4.36245292e-01 -8.86597931e-01 -1.53728500e-01 4.33130085e-01 -8.88124824e-01 -1.53728500e-01 4.30012256e-01 -8.89638722e-01 -1.53728500e-01 4.26923335e-01 -8.91121745e-01 -1.53728426e-01 4.23702329e-01 -8.92661810e-01 -1.53728753e-01 4.20562118e-01 -8.94139469e-01 -1.53728142e-01 4.17480111e-01 -8.95588934e-01 -1.53728724e-01 4.14311558e-01 -8.97053242e-01 -1.53728157e-01 4.11292046e-01 -8.98443460e-01 -1.53728470e-01 4.08151060e-01 -8.99876356e-01 -1.53728411e-01 4.05004978e-01 -9.01297092e-01 -1.53728500e-01 4.01769847e-01 -9.02747095e-01 -1.53728724e-01 3.98592532e-01 -9.04148638e-01 -1.53728217e-01 3.95541102e-01 -9.05491114e-01 -1.53728411e-01 3.92387211e-01 -9.06860828e-01 -1.53728500e-01 3.89199883e-01 -9.08231318e-01 -1.53728500e-01 3.86005074e-01 -9.09595311e-01 -1.53728500e-01 3.82832110e-01 -9.10935938e-01 -1.53728411e-01 3.79674017e-01 -9.12257552e-01 -1.53728500e-01 3.76471549e-01 -9.13581014e-01 -1.53728351e-01 3.73327374e-01 -9.14872646e-01 -1.53728455e-01 3.70124906e-01 -9.16173339e-01 -1.53728530e-01 3.66843641e-01 -9.17493105e-01 -1.53728694e-01 3.63598466e-01 -9.18780684e-01 -1.53728276e-01 3.60476732e-01 -9.20012891e-01 -1.53728411e-01 3.57273906e-01 -9.21253920e-01 -1.53728411e-01 3.54058981e-01 -9.22503889e-01 -1.53728500e-01 3.50824535e-01 -9.23731804e-01 -1.53728411e-01 3.47599655e-01 -9.24946368e-01 -1.53728500e-01 3.44359219e-01 -9.26156342e-01 -1.53728500e-01 3.41069162e-01 -9.27380621e-01 -1.53728664e-01 3.37804735e-01 -9.28575337e-01 -1.53728187e-01 3.34594041e-01 -9.29739356e-01 -1.53728664e-01 3.31334651e-01 -9.30902839e-01 -1.53728187e-01 3.28074872e-01 -9.32060122e-01 -1.53728664e-01 3.24829012e-01 -9.33190107e-01 -1.53728157e-01 3.21567148e-01 -9.34325576e-01 -1.53728664e-01 3.18286330e-01 -9.35441196e-01 -1.53728187e-01 3.15110087e-01 -9.36521173e-01 -1.53728500e-01 3.11836660e-01 -9.37614977e-01 -1.53728500e-01 3.08546484e-01 -9.38700795e-01 -1.53728351e-01 3.05296481e-01 -9.39764440e-01 -1.53728411e-01 3.01996887e-01 -9.40832257e-01 -1.53728500e-01 2.98733443e-01 -9.41871583e-01 -1.53728500e-01 2.95451313e-01 -9.42907870e-01 -1.53728500e-01 2.92156398e-01 -9.43932235e-01 -1.53728381e-01 2.88854450e-01 -9.44949687e-01 -1.53728500e-01 2.85497636e-01 -9.45967853e-01 -1.53728664e-01 2.82173246e-01 -9.46962595e-01 -1.53728247e-01 2.78936923e-01 -9.47923720e-01 -1.53728440e-01 2.75552630e-01 -9.48915541e-01 -1.53728664e-01 2.72150695e-01 -9.49894249e-01 -1.53728500e-01 2.68821746e-01 -9.50841308e-01 -1.53728411e-01 2.65616387e-01 -9.51739430e-01 -1.53728098e-01 2.62398452e-01 -9.52634275e-01 -1.53728500e-01 2.59055972e-01 -9.53551173e-01 -1.53728500e-01 2.55731612e-01 -9.54444051e-01 -1.53728411e-01 2.52316028e-01 -9.55356538e-01 -1.53728694e-01 2.48957336e-01 -9.56233501e-01 -1.53728187e-01 2.45627254e-01 -9.57096875e-01 -1.53728664e-01 2.42267832e-01 -9.57947135e-01 -1.53728113e-01 2.38962889e-01 -9.58781779e-01 -1.53728664e-01 2.35579491e-01 -9.59616125e-01 -1.53728142e-01 2.32315004e-01 -9.60415721e-01 -1.53728500e-01 2.28938550e-01 -9.61227357e-01 -1.53728500e-01 2.25576505e-01 -9.62020040e-01 -1.53728411e-01 2.22249478e-01 -9.62794125e-01 -1.53728500e-01 2.18772441e-01 -9.63590741e-01 -1.53728694e-01 2.15406299e-01 -9.64345396e-01 -1.53728157e-01 2.12128311e-01 -9.65071738e-01 -1.53728411e-01 2.08752811e-01 -9.65808451e-01 -1.53728411e-01 2.05393776e-01 -9.66528654e-01 -1.53728411e-01 2.01942280e-01 -9.67259228e-01 -1.53728664e-01 1.98541790e-01 -9.67957973e-01 -1.53728157e-01 1.95259035e-01 -9.68627095e-01 -1.53728500e-01 1.91875398e-01 -9.69302177e-01 -1.53728411e-01 1.88481644e-01 -9.69969094e-01 -1.53728500e-01 1.85017854e-01 -9.70636904e-01 -1.53728694e-01 1.81618378e-01 -9.71273839e-01 -1.53728127e-01 1.78239539e-01 -9.71902907e-01 -1.53728649e-01 1.74828649e-01 -9.72523808e-01 -1.53728113e-01 1.71536535e-01 -9.73111451e-01 -1.53728396e-01 1.68148130e-01 -9.73697662e-01 -1.53728440e-01 1.64747342e-01 -9.74281311e-01 -1.53728440e-01 1.61351219e-01 -9.74847794e-01 -1.53728500e-01 1.57951221e-01 -9.75404620e-01 -1.53728411e-01 1.54552102e-01 -9.75950122e-01 -1.53728426e-01 1.51147053e-01 -9.76483703e-01 -1.53728500e-01 1.47731021e-01 -9.77004111e-01 -1.53728500e-01 1.44277349e-01 -9.77522194e-01 -1.53728634e-01 1.40870005e-01 -9.78014827e-01 -1.53728306e-01 1.37489483e-01 -9.78497803e-01 -1.53728411e-01 1.33968964e-01 -9.78989720e-01 -1.53728664e-01 1.30546033e-01 -9.79446530e-01 -1.53728157e-01 1.27211571e-01 -9.79887843e-01 -1.53728381e-01 1.23808078e-01 -9.80325222e-01 -1.53728411e-01 1.20367430e-01 -9.80752409e-01 -1.53728500e-01 1.16849251e-01 -9.81181085e-01 -1.53728694e-01 1.13420725e-01 -9.81576383e-01 -1.53728142e-01 1.10102683e-01 -9.81957436e-01 -1.53728411e-01 1.06657520e-01 -9.82336760e-01 -1.53728411e-01 1.03249654e-01 -9.82700765e-01 -1.53728411e-01 9.97220129e-02 -9.83066261e-01 -1.53728664e-01 9.62879658e-02 -9.83405352e-01 -1.53728113e-01 9.28717479e-02 -9.83741462e-01 -1.53728694e-01 8.94116610e-02 -9.84055281e-01 -1.53728113e-01 8.59901607e-02 -9.84364569e-01 -1.53728634e-01 8.24711844e-02 -9.84662473e-01 -1.53728411e-01 7.91084692e-02 -9.84936655e-01 -1.53728068e-01 7.57659376e-02 -9.85201478e-01 -1.53728411e-01 7.23268092e-02 -9.85460997e-01 -1.53728411e-01 6.88830316e-02 -9.85705614e-01 -1.53728485e-01 6.54416084e-02 -9.85941768e-01 -1.53728426e-01 6.20149672e-02 -9.86163676e-01 -1.53728500e-01 5.85600957e-02 -9.86373961e-01 -1.53728411e-01 5.51076904e-02 -9.86573398e-01 -1.53728411e-01 5.16650081e-02 -9.86757219e-01 -1.53728411e-01 4.82469499e-02 -9.86933112e-01 -1.53728366e-01 4.48177643e-02 -9.87095237e-01 -1.53728500e-01 4.12558354e-02 -9.87250924e-01 -1.53728694e-01 3.78053114e-02 -9.87383544e-01 -1.53728053e-01 3.44768129e-02 -9.87508774e-01 -1.53728411e-01 3.09278704e-02 -9.87628162e-01 -1.53728634e-01 2.74625123e-02 -9.87727582e-01 -1.53728142e-01 2.40138546e-02 -9.87824619e-01 -1.53728664e-01 2.05518454e-02 -9.87891197e-01 -1.53728008e-01 1.72405224e-02 -9.87965107e-01 -1.53728411e-01 1.36911115e-02 -9.88012850e-01 -1.53728694e-01 1.02193402e-02 -9.88055289e-01 -1.53728083e-01 6.87534735e-03 -9.88093674e-01 -1.53728411e-01 3.42249195e-03 -9.88110483e-01 -1.53728411e-01 -3.98638695e-05 -9.88111854e-01 -1.53728470e-01 -3.57997627e-03 -9.88112211e-01 -1.53728634e-01 -7.02496618e-03 -9.88090217e-01 -1.53728113e-01 -1.04582477e-02 -9.88058746e-01 -1.53728664e-01 -1.39067695e-02 -9.88006353e-01 -1.53728142e-01 -1.73499323e-02 -9.87967014e-01 -1.53728634e-01 -2.08872762e-02 -9.87887859e-01 -1.53728411e-01 -2.42662728e-02 -9.87812579e-01 -1.53728187e-01 -2.76317354e-02 -9.87725019e-01 -1.53728411e-01 -3.10749840e-02 -9.87624049e-01 -1.53728426e-01 -3.45210694e-02 -9.87510085e-01 -1.53728500e-01 -3.80594805e-02 -9.87380385e-01 -1.53728664e-01 -4.15240973e-02 -9.87236440e-01 -1.53728157e-01 -4.48600017e-02 -9.87091720e-01 -1.53728411e-01 -4.83009517e-02 -9.86931264e-01 -1.53728411e-01 -5.17306328e-02 -9.86753941e-01 -1.53728411e-01 -5.52587509e-02 -9.86568689e-01 -1.53728664e-01 -5.87148890e-02 -9.86362636e-01 -1.53728098e-01 -6.21567033e-02 -9.86153364e-01 -1.53728634e-01 -6.56064674e-02 -9.85927343e-01 -1.53728157e-01 -6.89482540e-02 -9.85701919e-01 -1.53728485e-01 -7.24706799e-02 -9.85452473e-01 -1.53728664e-01 -7.59247988e-02 -9.85186696e-01 -1.53728187e-01 -7.93469250e-02 -9.84921575e-01 -1.53728634e-01 -8.27973932e-02 -9.84633386e-01 -1.53728247e-01 -8.61443803e-02 -9.84348595e-01 -1.53728411e-01 -8.96657482e-02 -9.84036624e-01 -1.53728694e-01 -9.31150764e-02 -9.83710885e-01 -1.53728157e-01 -9.65240076e-02 -9.83387828e-01 -1.53728694e-01 -9.99715775e-02 -9.83037770e-01 -1.53728023e-01 -1.03377655e-01 -9.82692063e-01 -1.53728724e-01 -1.06923342e-01 -9.82308269e-01 -1.53728351e-01 -1.10248722e-01 -9.81939018e-01 -1.53728157e-01 -1.13576397e-01 -9.81561780e-01 -1.53728485e-01 -1.17024548e-01 -9.81156528e-01 -1.53728500e-01 -1.20426036e-01 -9.80746329e-01 -1.53728500e-01 -1.23941429e-01 -9.80310798e-01 -1.53728694e-01 -1.27396211e-01 -9.79860604e-01 -1.53728187e-01 -1.30709082e-01 -9.79428470e-01 -1.53728426e-01 -1.34106174e-01 -9.78968680e-01 -1.53728411e-01 -1.37527674e-01 -9.78495121e-01 -1.53728500e-01 -1.41054437e-01 -9.77992713e-01 -1.53728664e-01 -1.44452810e-01 -9.77491379e-01 -1.53728083e-01 -1.47851467e-01 -9.76988316e-01 -1.53728694e-01 -1.51266187e-01 -9.76463020e-01 -1.53728142e-01 -1.54577509e-01 -9.75944638e-01 -1.53728411e-01 -1.58004627e-01 -9.75397110e-01 -1.53728470e-01 -1.61381185e-01 -9.74844694e-01 -1.53728411e-01 -1.64893523e-01 -9.74259436e-01 -1.53728664e-01 -1.68303847e-01 -9.73667860e-01 -1.53728083e-01 -1.71602726e-01 -9.73100007e-01 -1.53728485e-01 -1.75061539e-01 -9.72483695e-01 -1.53728530e-01 -1.78452730e-01 -9.71860290e-01 -1.53728351e-01 -1.81886256e-01 -9.71230745e-01 -1.53728664e-01 -1.85282484e-01 -9.70580697e-01 -1.53728083e-01 -1.88577428e-01 -9.69949186e-01 -1.53728411e-01 -1.91962689e-01 -9.69285190e-01 -1.53728411e-01 -1.95412561e-01 -9.68598485e-01 -1.53728664e-01 -1.98827282e-01 -9.67897475e-01 -1.53728157e-01 -2.02115282e-01 -9.67218220e-01 -1.53728411e-01 -2.05476239e-01 -9.66513455e-01 -1.53728426e-01 -2.08936542e-01 -9.65771735e-01 -1.53728634e-01 -2.12317869e-01 -9.65026259e-01 -1.53728172e-01 -2.15592861e-01 -9.64305162e-01 -1.53728411e-01 -2.18964115e-01 -9.63544726e-01 -1.53728426e-01 -2.22314313e-01 -9.62776124e-01 -1.53728411e-01 -2.25758180e-01 -9.61981177e-01 -1.53728664e-01 -2.29123324e-01 -9.61178541e-01 -1.53728157e-01 -2.32377529e-01 -9.60400343e-01 -1.53728411e-01 -2.35800296e-01 -9.59566176e-01 -1.53728634e-01 -2.39165723e-01 -9.58727181e-01 -1.53728157e-01 -2.42512003e-01 -9.57890332e-01 -1.53728664e-01 -2.45861679e-01 -9.57032740e-01 -1.53728098e-01 -2.49089137e-01 -9.56199288e-01 -1.53728351e-01 -2.52449155e-01 -9.55319226e-01 -1.53728411e-01 -2.55861759e-01 -9.54412162e-01 -1.53728664e-01 -2.59278476e-01 -9.53488290e-01 -1.53728411e-01 -2.62535632e-01 -9.52592850e-01 -1.53728142e-01 -2.65737802e-01 -9.51710224e-01 -1.53728500e-01 -2.69094199e-01 -9.50765014e-01 -1.53728411e-01 -2.72406489e-01 -9.49820042e-01 -1.53728411e-01 -2.75713801e-01 -9.48866487e-01 -1.53728411e-01 -2.79018670e-01 -9.47900057e-01 -1.53728500e-01 -2.82314658e-01 -9.46924746e-01 -1.53728485e-01 -2.85628498e-01 -9.45926726e-01 -1.53728411e-01 -2.88928628e-01 -9.44923937e-01 -1.53728500e-01 -2.92302847e-01 -9.43891525e-01 -1.53728664e-01 -2.95629680e-01 -9.42848265e-01 -1.53728232e-01 -2.98909754e-01 -9.41818833e-01 -1.53728664e-01 -3.02180260e-01 -9.40770268e-01 -1.53728142e-01 -3.05365056e-01 -9.39742446e-01 -1.53728411e-01 -3.08724701e-01 -9.38647091e-01 -1.53728679e-01 -3.12063307e-01 -9.37538445e-01 -1.53728351e-01 -3.15327317e-01 -9.36448872e-01 -1.53728426e-01 -3.18553418e-01 -9.35351074e-01 -1.53728068e-01 -3.21707040e-01 -9.34274614e-01 -1.53728411e-01 -3.25007200e-01 -9.33131218e-01 -1.53728500e-01 -3.28261971e-01 -9.31992114e-01 -1.53728470e-01 -3.31564099e-01 -9.30823207e-01 -1.53728589e-01 -3.34813893e-01 -9.29655254e-01 -1.53728247e-01 -3.38042170e-01 -9.28492069e-01 -1.53728634e-01 -3.41292381e-01 -9.27290678e-01 -1.53728202e-01 -3.44451904e-01 -9.26120460e-01 -1.53728411e-01 -3.47678721e-01 -9.24914896e-01 -1.53728411e-01 -3.50907534e-01 -9.23701167e-01 -1.53728500e-01 -3.54219437e-01 -9.22444463e-01 -1.53728664e-01 -3.57532024e-01 -9.21157062e-01 -1.53728500e-01 -3.60659212e-01 -9.19936895e-01 -1.53728053e-01 -3.63775313e-01 -9.18711901e-01 -1.53728411e-01 -3.66964638e-01 -9.17441845e-01 -1.53728411e-01 -3.70162040e-01 -9.16156650e-01 -1.53728411e-01 -3.73442799e-01 -9.14826989e-01 -1.53728664e-01 -3.76724035e-01 -9.13476050e-01 -1.53728411e-01 -3.79837751e-01 -9.12184775e-01 -1.53728113e-01 -3.82916629e-01 -9.10899699e-01 -1.53728411e-01 -3.86106938e-01 -9.09552157e-01 -1.53728470e-01 -3.89355779e-01 -9.08164501e-01 -1.53728664e-01 -3.92549455e-01 -9.06785548e-01 -1.53728038e-01 -3.95693511e-01 -9.05426383e-01 -1.53728634e-01 -3.98867786e-01 -9.04025018e-01 -1.53728023e-01 -4.01927441e-01 -9.02673602e-01 -1.53728500e-01 -4.05087471e-01 -9.01259661e-01 -1.53728351e-01 -4.08217818e-01 -8.99844408e-01 -1.53728366e-01 -4.11418289e-01 -8.98387432e-01 -1.53728664e-01 -4.14558351e-01 -8.96938443e-01 -1.53728217e-01 -4.17610615e-01 -8.95524919e-01 -1.53728470e-01 -4.20728922e-01 -8.94064069e-01 -1.53728485e-01 -4.23932344e-01 -8.92552316e-01 -1.53728664e-01 -4.27052796e-01 -8.91056418e-01 -1.53728157e-01 -4.30077165e-01 -8.89608502e-01 -1.53728440e-01 -4.33191210e-01 -8.88095438e-01 -1.53728411e-01 -4.36352342e-01 -8.86545897e-01 -1.53728634e-01 -4.39437658e-01 -8.85017455e-01 -1.53728142e-01 -4.42443222e-01 -8.83520365e-01 -1.53728500e-01 -4.45536286e-01 -8.81966352e-01 -1.53728411e-01 -4.48602825e-01 -8.80410433e-01 -1.53728485e-01 -4.51760411e-01 -8.78796041e-01 -1.53728679e-01 -4.54826832e-01 -8.77205372e-01 -1.53728172e-01 -4.57801133e-01 -8.75663042e-01 -1.53728500e-01 -4.60844934e-01 -8.74063075e-01 -1.53728411e-01 -4.63880450e-01 -8.72456014e-01 -1.53728500e-01 -4.67001677e-01 -8.70792747e-01 -1.53728634e-01 -4.70072091e-01 -8.69131505e-01 -1.53728157e-01 -4.73086178e-01 -8.67502868e-01 -1.53728664e-01 -4.76109415e-01 -8.65840733e-01 -1.53728157e-01 -4.79137629e-01 -8.64173770e-01 -1.53728738e-01 -4.82243150e-01 -8.62440825e-01 -1.53728411e-01 -4.85168189e-01 -8.60797405e-01 -1.53728187e-01 -4.88147736e-01 -8.59117866e-01 -1.53728738e-01 -4.91161913e-01 -8.57391834e-01 -1.53728142e-01 -4.94070649e-01 -8.55721354e-01 -1.53728500e-01 -4.97059673e-01 -8.53989363e-01 -1.53728500e-01 -5.00048339e-01 -8.52242589e-01 -1.53728455e-01 -5.03008246e-01 -8.50498438e-01 -1.53728411e-01 -5.05962610e-01 -8.48744452e-01 -1.53728485e-01 -5.08920252e-01 -8.46973360e-01 -1.53728470e-01 -5.11898696e-01 -8.45177054e-01 -1.53728589e-01 -5.14920712e-01 -8.43343437e-01 -1.53728634e-01 -5.17916024e-01 -8.41502249e-01 -1.53728500e-01 -5.20786762e-01 -8.39727283e-01 -1.53728187e-01 -5.23625851e-01 -8.37963283e-01 -1.53728500e-01 -5.26627123e-01 -8.36082280e-01 -1.53728724e-01 -5.29561460e-01 -8.34220767e-01 -1.53728187e-01 -5.32460034e-01 -8.32378507e-01 -1.53728694e-01 -5.35367906e-01 -8.30505729e-01 -1.53728113e-01 -5.38173437e-01 -8.28691602e-01 -1.53728351e-01 -5.41133106e-01 -8.26765358e-01 -1.53728724e-01 -5.44037580e-01 -8.24853063e-01 -1.53728083e-01 -5.46811759e-01 -8.23016703e-01 -1.53728500e-01 -5.49689949e-01 -8.21099639e-01 -1.53728411e-01 -5.52639365e-01 -8.19123089e-01 -1.53728738e-01 -5.55510283e-01 -8.17167163e-01 -1.53728083e-01 -5.58259428e-01 -8.15299988e-01 -1.53728455e-01 -5.61111987e-01 -8.13338697e-01 -1.53728455e-01 -5.63937187e-01 -8.11381817e-01 -1.53728500e-01 -5.66855073e-01 -8.09348524e-01 -1.53728738e-01 -5.69791913e-01 -8.07284176e-01 -1.53728500e-01 -5.72525442e-01 -8.05340290e-01 -1.53728098e-01 -5.75227499e-01 -8.03417623e-01 -1.53728500e-01 -5.78024387e-01 -8.01402688e-01 -1.53728470e-01 -5.80839634e-01 -7.99370348e-01 -1.53728500e-01 -5.83694756e-01 -7.97287583e-01 -1.53728664e-01 -5.86551607e-01 -7.95185924e-01 -1.53728485e-01 -5.89254260e-01 -7.93181479e-01 -1.53728083e-01 -5.91933668e-01 -7.91186213e-01 -1.53728500e-01 -5.94700694e-01 -7.89111018e-01 -1.53728500e-01 -5.97513795e-01 -7.86987722e-01 -1.53728694e-01 -6.00281537e-01 -7.84871578e-01 -1.53728247e-01 -6.03005171e-01 -7.82785535e-01 -1.53728724e-01 -6.05729759e-01 -7.80672908e-01 -1.53728187e-01 -6.08378232e-01 -7.78613687e-01 -1.53728500e-01 -6.11164331e-01 -7.76434362e-01 -1.53728724e-01 -6.13866389e-01 -7.74290919e-01 -1.53728157e-01 -6.16569042e-01 -7.72148788e-01 -1.53728694e-01 -6.19263589e-01 -7.69982159e-01 -1.53728113e-01 -6.21861279e-01 -7.67890930e-01 -1.53728500e-01 -6.24539256e-01 -7.65711010e-01 -1.53728500e-01 -6.27200484e-01 -7.63534307e-01 -1.53728500e-01 -6.29932880e-01 -7.61286020e-01 -1.53728694e-01 -6.32589757e-01 -7.59070694e-01 -1.53728157e-01 -6.35154724e-01 -7.56930709e-01 -1.53728411e-01 -6.37866676e-01 -7.54649758e-01 -1.53728738e-01 -6.40505850e-01 -7.52402365e-01 -1.53728113e-01 -6.43058360e-01 -7.50227690e-01 -1.53728500e-01 -6.45679057e-01 -7.47974157e-01 -1.53728500e-01 -6.48280382e-01 -7.45720685e-01 -1.53728455e-01 -6.50955081e-01 -7.43387341e-01 -1.53728724e-01 -6.53542936e-01 -7.41107821e-01 -1.53728157e-01 -6.56048656e-01 -7.38894522e-01 -1.53728426e-01 -6.58633351e-01 -7.36591816e-01 -1.53728500e-01 -6.61185682e-01 -7.34301507e-01 -1.53728500e-01 -6.63815022e-01 -7.31929123e-01 -1.53728634e-01 -6.66366458e-01 -7.29598403e-01 -1.53728276e-01 -6.68914616e-01 -7.27272749e-01 -1.53728679e-01 -6.71449840e-01 -7.24923611e-01 -1.53728157e-01 -6.73970044e-01 -7.22586870e-01 -1.53728694e-01 -6.76562011e-01 -7.20158696e-01 -1.53728500e-01 -6.79006755e-01 -7.17849016e-01 -1.53728172e-01 -6.81483030e-01 -7.15510070e-01 -1.53728694e-01 -6.83995545e-01 -7.13092446e-01 -1.53728232e-01 -6.86406791e-01 -7.10790873e-01 -1.53728500e-01 -6.88876212e-01 -7.08394587e-01 -1.53728485e-01 -6.91330254e-01 -7.05996573e-01 -1.53728411e-01 -6.93877280e-01 -7.03499675e-01 -1.53728738e-01 -6.96344733e-01 -7.01050758e-01 -1.53728053e-01 -6.98689401e-01 -6.98700070e-01 -1.53728500e-01 -7.01140940e-01 -6.96258724e-01 -1.53728440e-01 -7.03642726e-01 -6.93733513e-01 -1.53728753e-01 -7.06079602e-01 -6.91240907e-01 -1.53728127e-01 -7.08404779e-01 -6.88865483e-01 -1.53728485e-01 -7.10797369e-01 -6.86399341e-01 -1.53728500e-01 -7.13243544e-01 -6.83846056e-01 -1.53728694e-01 -7.15707302e-01 -6.81273520e-01 -1.53728485e-01 -7.18086362e-01 -6.78760111e-01 -1.53728500e-01 -7.20398843e-01 -6.76300168e-01 -1.53728127e-01 -7.22677588e-01 -6.73867941e-01 -1.53728470e-01 -7.25088835e-01 -6.71278775e-01 -1.53728664e-01 -7.27427363e-01 -6.68739438e-01 -1.53728217e-01 -7.29699194e-01 -6.66262269e-01 -1.53728500e-01 -7.32030749e-01 -6.63699508e-01 -1.53728500e-01 -7.34345496e-01 -6.61136508e-01 -1.53728455e-01 -7.36642778e-01 -6.58575237e-01 -1.53728411e-01 -7.38937616e-01 -6.56002581e-01 -1.53728500e-01 -7.41288781e-01 -6.53345048e-01 -1.53728694e-01 -7.43557096e-01 -6.50755286e-01 -1.53728187e-01 -7.45825052e-01 -6.48161590e-01 -1.53728709e-01 -7.48146176e-01 -6.45476401e-01 -1.53728411e-01 -7.50337660e-01 -6.42925680e-01 -1.53728083e-01 -7.52557874e-01 -6.40332222e-01 -1.53728724e-01 -7.54805803e-01 -6.37676239e-01 -1.53728217e-01 -7.56959975e-01 -6.35118484e-01 -1.53728500e-01 -7.59226263e-01 -6.32414222e-01 -1.53728664e-01 -7.61438549e-01 -6.29738152e-01 -1.53728142e-01 -7.63579607e-01 -6.27146721e-01 -1.53728500e-01 -7.65759528e-01 -6.24479473e-01 -1.53728500e-01 -7.67933786e-01 -6.21805012e-01 -1.53728411e-01 -7.70154238e-01 -6.19058609e-01 -1.53728724e-01 -7.72363186e-01 -6.16295755e-01 -1.53728500e-01 -7.74514556e-01 -6.13587439e-01 -1.53728455e-01 -7.76607394e-01 -6.10935450e-01 -1.53728276e-01 -7.78674841e-01 -6.08303666e-01 -1.53728500e-01 -7.80841351e-01 -6.05522573e-01 -1.53728664e-01 -7.82945335e-01 -6.02792025e-01 -1.53728157e-01 -7.85045505e-01 -6.00061834e-01 -1.53728694e-01 -7.87146270e-01 -5.97294152e-01 -1.53728157e-01 -7.89155006e-01 -5.94642758e-01 -1.53728411e-01 -7.91212916e-01 -5.91899574e-01 -1.53728440e-01 -7.93270469e-01 -5.89138627e-01 -1.53728500e-01 -7.95381188e-01 -5.86289763e-01 -1.53728664e-01 -7.97438920e-01 -5.83481729e-01 -1.53728262e-01 -7.99479425e-01 -5.80691695e-01 -1.53728724e-01 -8.01553071e-01 -5.77815652e-01 -1.53728351e-01 -8.03507328e-01 -5.75098574e-01 -1.53728217e-01 -8.05499732e-01 -5.72311282e-01 -1.53728709e-01 -8.07504475e-01 -5.69472134e-01 -1.53728172e-01 -8.09428155e-01 -5.66738188e-01 -1.53728500e-01 -8.11454773e-01 -5.63834608e-01 -1.53728738e-01 -8.13431680e-01 -5.60971379e-01 -1.53728068e-01 -8.15313518e-01 -5.58239162e-01 -1.53728619e-01 -8.17270815e-01 -5.55366278e-01 -1.53728500e-01 -8.19206178e-01 -5.52510083e-01 -1.53728500e-01 -8.21182728e-01 -5.49570799e-01 -1.53728738e-01 -8.23106289e-01 -5.46674252e-01 -1.53728172e-01 -8.25002491e-01 -5.43819606e-01 -1.53728709e-01 -8.26904356e-01 -5.40914059e-01 -1.53728247e-01 -8.28734398e-01 -5.38113058e-01 -1.53728500e-01 -8.30599308e-01 -5.35228014e-01 -1.53728500e-01 -8.32453549e-01 -5.32338977e-01 -1.53728500e-01 -8.34356010e-01 -5.29354513e-01 -1.53728664e-01 -8.36190939e-01 -5.26445687e-01 -1.53728157e-01 -8.37979436e-01 -5.23595214e-01 -1.53728411e-01 -8.39803100e-01 -5.20672381e-01 -1.53728500e-01 -8.41614723e-01 -5.17733514e-01 -1.53728500e-01 -8.43459368e-01 -5.14730453e-01 -1.53728664e-01 -8.45257640e-01 -5.11760533e-01 -1.53728202e-01 -8.47030282e-01 -5.08831322e-01 -1.53728664e-01 -8.48799586e-01 -5.05864024e-01 -1.53728276e-01 -8.50516260e-01 -5.02978265e-01 -1.53728500e-01 -8.52297068e-01 -4.99960870e-01 -1.53728664e-01 -8.54040861e-01 -4.96965170e-01 -1.53728276e-01 -8.55730414e-01 -4.94055539e-01 -1.53728500e-01 -8.57438147e-01 -4.91084397e-01 -1.53728500e-01 -8.59155297e-01 -4.88073975e-01 -1.53728500e-01 -8.60854864e-01 -4.85075235e-01 -1.53728500e-01 -8.62540722e-01 -4.82065171e-01 -1.53728500e-01 -8.64206433e-01 -4.79070514e-01 -1.53728500e-01 -8.65930855e-01 -4.75958824e-01 -1.53728724e-01 -8.67593229e-01 -4.72912580e-01 -1.53728217e-01 -8.69186580e-01 -4.69977319e-01 -1.53728500e-01 -8.70835364e-01 -4.66918409e-01 -1.53728500e-01 -8.72513711e-01 -4.63777006e-01 -1.53728709e-01 -8.74168932e-01 -4.60641712e-01 -1.53728411e-01 -8.75718772e-01 -4.57686990e-01 -1.53728217e-01 -8.77261221e-01 -4.54728633e-01 -1.53728500e-01 -8.78847480e-01 -4.51656759e-01 -1.53728500e-01 -8.80469143e-01 -4.48491156e-01 -1.53728738e-01 -8.82027864e-01 -4.45406020e-01 -1.53728142e-01 -8.83528888e-01 -4.42427516e-01 -1.53728500e-01 -8.85113895e-01 -4.39254463e-01 -1.53728709e-01 -8.86644423e-01 -4.36142594e-01 -1.53728157e-01 -8.88125181e-01 -4.33131605e-01 -1.53728500e-01 -8.89672875e-01 -4.29947615e-01 -1.53728694e-01 -8.91206026e-01 -4.26749825e-01 -1.53728500e-01 -8.92694473e-01 -4.23629045e-01 -1.53728500e-01 -8.94127905e-01 -4.20584679e-01 -1.53728113e-01 -8.95551801e-01 -4.17554408e-01 -1.53728470e-01 -8.97044420e-01 -4.14342582e-01 -1.53728664e-01 -8.98525715e-01 -4.11113143e-01 -1.53728500e-01 -8.99908960e-01 -4.08072293e-01 -1.53728217e-01 -9.01297748e-01 -4.05002564e-01 -1.53728455e-01 -9.02705967e-01 -4.01854277e-01 -1.53728500e-01 -9.04134512e-01 -3.98637325e-01 -1.53728694e-01 -9.05524790e-01 -3.95458788e-01 -1.53728172e-01 -9.06898260e-01 -3.92308682e-01 -1.53728738e-01 -9.08263385e-01 -3.89115214e-01 -1.53728217e-01 -9.09577072e-01 -3.86046976e-01 -1.53728500e-01 -9.10958886e-01 -3.82783920e-01 -1.53728694e-01 -9.12286460e-01 -3.79595220e-01 -1.53728157e-01 -9.13607180e-01 -3.76416326e-01 -1.53728664e-01 -9.14916933e-01 -3.73209000e-01 -1.53728157e-01 -9.16183233e-01 -3.70095640e-01 -1.53728500e-01 -9.17501748e-01 -3.66819829e-01 -1.53728694e-01 -9.18778896e-01 -3.63600701e-01 -1.53728157e-01 -9.20040727e-01 -3.60414922e-01 -1.53728724e-01 -9.21295226e-01 -3.57161343e-01 -1.53728202e-01 -9.22505319e-01 -3.54057431e-01 -1.53728500e-01 -9.23763633e-01 -3.50751668e-01 -1.53728724e-01 -9.24972117e-01 -3.47520769e-01 -1.53728157e-01 -9.26145673e-01 -3.44388336e-01 -1.53728500e-01 -9.27371502e-01 -3.41091037e-01 -1.53728664e-01 -9.28564906e-01 -3.37834626e-01 -1.53728276e-01 -9.29742754e-01 -3.34583998e-01 -1.53728664e-01 -9.30904746e-01 -3.31328839e-01 -1.53728276e-01 -9.32047844e-01 -3.28106791e-01 -1.53728664e-01 -9.33191478e-01 -3.24826360e-01 -1.53728217e-01 -9.34294164e-01 -3.21650773e-01 -1.53728440e-01 -9.35409844e-01 -3.18391651e-01 -1.53728500e-01 -9.36510563e-01 -3.15139920e-01 -1.53728500e-01 -9.37633693e-01 -3.11784655e-01 -1.53728664e-01 -9.38716531e-01 -3.08494985e-01 -1.53728247e-01 -9.39765275e-01 -3.05297196e-01 -1.53728485e-01 -9.40854132e-01 -3.01933140e-01 -1.53728694e-01 -9.41898048e-01 -2.98643768e-01 -1.53728157e-01 -9.42935884e-01 -2.95370519e-01 -1.53728694e-01 -9.43956375e-01 -2.92067319e-01 -1.53728113e-01 -9.44970906e-01 -2.88788974e-01 -1.53728724e-01 -9.45969939e-01 -2.85479516e-01 -1.53728142e-01 -9.46931481e-01 -2.82282233e-01 -1.53728500e-01 -9.47940946e-01 -2.78888553e-01 -1.53728694e-01 -9.48909461e-01 -2.75558293e-01 -1.53728157e-01 -9.49840665e-01 -2.72332847e-01 -1.53728426e-01 -9.50784504e-01 -2.69024968e-01 -1.53728500e-01 -9.51723218e-01 -2.65686184e-01 -1.53728500e-01 -9.52640653e-01 -2.62376159e-01 -1.53728500e-01 -9.53552186e-01 -2.59051532e-01 -1.53728426e-01 -9.54447925e-01 -2.55717993e-01 -1.53728500e-01 -9.55360115e-01 -2.52308786e-01 -1.53728753e-01 -9.56264675e-01 -2.48845190e-01 -1.53728500e-01 -9.57104266e-01 -2.45587930e-01 -1.53728247e-01 -9.57930982e-01 -2.42342621e-01 -1.53728500e-01 -9.58794236e-01 -2.38918588e-01 -1.53728724e-01 -9.59648550e-01 -2.35461950e-01 -1.53728500e-01 -9.60439205e-01 -2.32203111e-01 -1.53728098e-01 -9.61219609e-01 -2.28961408e-01 -1.53728411e-01 -9.62013125e-01 -2.25602835e-01 -1.53728500e-01 -9.62815762e-01 -2.22153082e-01 -1.53728634e-01 -9.63584602e-01 -2.18777478e-01 -1.53728157e-01 -9.64323938e-01 -2.15515301e-01 -1.53728500e-01 -9.65087652e-01 -2.12072521e-01 -1.53728694e-01 -9.65820551e-01 -2.08683088e-01 -1.53728247e-01 -9.66529906e-01 -2.05389321e-01 -1.53728500e-01 -9.67238963e-01 -2.02026367e-01 -1.53728411e-01 -9.67956364e-01 -1.98577210e-01 -1.53728649e-01 -9.68659282e-01 -1.95108190e-01 -1.53728500e-01 -9.69315231e-01 -1.91801637e-01 -1.53728142e-01 -9.69966233e-01 -1.88499838e-01 -1.53728485e-01 -9.70630407e-01 -1.85051024e-01 -1.53728634e-01 -9.71284091e-01 -1.81579620e-01 -1.53728411e-01 -9.71897781e-01 -1.78240046e-01 -1.53728217e-01 -9.72504377e-01 -1.74951345e-01 -1.53728411e-01 -9.73109007e-01 -1.71561450e-01 -1.53728440e-01 -9.73708391e-01 -1.68099225e-01 -1.53728634e-01 -9.74304378e-01 -1.64606079e-01 -1.53728411e-01 -9.74856257e-01 -1.61281481e-01 -1.53728098e-01 -9.75400746e-01 -1.57981589e-01 -1.53728411e-01 -9.75950956e-01 -1.54539004e-01 -1.53728411e-01 -9.76496994e-01 -1.51071757e-01 -1.53728664e-01 -9.77011085e-01 -1.47672698e-01 -1.53728172e-01 -9.77529049e-01 -1.44242406e-01 -1.53728694e-01 -9.78021145e-01 -1.40827119e-01 -1.53728127e-01 -9.78496790e-01 -1.37511075e-01 -1.53728426e-01 -9.78984892e-01 -1.34012088e-01 -1.53728664e-01 -9.79441285e-01 -1.30587012e-01 -1.53728157e-01 -9.79897320e-01 -1.27166063e-01 -1.53728664e-01 -9.80330110e-01 -1.23747349e-01 -1.53728142e-01 -9.80747461e-01 -1.20400943e-01 -1.53728411e-01 -9.81173277e-01 -1.16901740e-01 -1.53728664e-01 -9.81573164e-01 -1.13446288e-01 -1.53728157e-01 -9.81966436e-01 -1.10045597e-01 -1.53728649e-01 -9.82354045e-01 -1.06507309e-01 -1.53728411e-01 -9.82704282e-01 -1.03178658e-01 -1.53728053e-01 -9.83057201e-01 -9.97989178e-02 -1.53728411e-01 -9.83393073e-01 -9.63494107e-02 -1.53727427e-01 -9.83724892e-01 -9.29019228e-02 -1.53727144e-01 -9.84050989e-01 -8.93942937e-02 -1.53726667e-01 -9.84342933e-01 -8.61101747e-02 -1.53727159e-01 -9.84636128e-01 -8.26812536e-02 -1.53727069e-01 -9.84920800e-01 -7.92363659e-02 -1.53726757e-01 -9.85195696e-01 -7.57031292e-02 -1.53726622e-01 -9.85452116e-01 -7.23471344e-02 -1.53726786e-01 -9.85692561e-01 -6.90529495e-02 -1.53727651e-01 -9.85941827e-01 -6.54620007e-02 -1.53727338e-01 -9.86158550e-01 -6.21198602e-02 -1.53727233e-01 -9.86314774e-01 -5.95864877e-02 -1.53727457e-01 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. 0. 0. 0. 0. 0. -9.87963319e-01 -1.71957016e-02 -1.53727442e-01 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. 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. 0. -9.90544498e-01 5.36459573e-02 -1.26268223e-01 -9.90427017e-01 5.57635799e-02 -1.26268238e-01 -9.90201235e-01 5.96537068e-02 -1.26268312e-01 -9.90015805e-01 6.26531467e-02 -1.26267761e-01 -9.89807129e-01 6.59221634e-02 -1.26267567e-01 -9.89564359e-01 6.93671405e-02 -1.26267478e-01 -9.89313304e-01 7.28998482e-02 -1.26267493e-01 -9.89051282e-01 7.63489977e-02 -1.26267493e-01 -9.88778293e-01 7.97951594e-02 -1.26267478e-01 -9.88491774e-01 8.32466260e-02 -1.26267478e-01 -9.88208234e-01 8.65986273e-02 -1.26267493e-01 -9.87896979e-01 9.00089070e-02 -1.26267478e-01 -9.87569332e-01 9.35659930e-02 -1.26267478e-01 -9.87248838e-01 9.69235823e-02 -1.26267478e-01 -9.86898839e-01 1.00349456e-01 -1.26267478e-01 -9.86536741e-01 1.03902996e-01 -1.26267478e-01 -9.86167550e-01 1.07339993e-01 -1.26267478e-01 -9.85788047e-01 1.10781729e-01 -1.26267478e-01 -9.85398114e-01 1.14179790e-01 -1.26267478e-01 -9.85001862e-01 1.17550164e-01 -1.26267478e-01 -9.84594285e-01 1.20929398e-01 -1.26267478e-01 -9.84155297e-01 1.24432862e-01 -1.26267478e-01 -9.83701468e-01 1.27974302e-01 -1.26267478e-01 -9.83265221e-01 1.31312057e-01 -1.26267493e-01 -9.82799411e-01 1.34723961e-01 -1.26267478e-01 -9.82310414e-01 1.38257250e-01 -1.26267478e-01 -9.81838942e-01 1.41579047e-01 -1.26267478e-01 -9.81330097e-01 1.45020649e-01 -1.26267478e-01 -9.80824292e-01 1.48434460e-01 -1.26267478e-01 -9.80314851e-01 1.51755899e-01 -1.26267478e-01 -9.79760587e-01 1.55267328e-01 -1.26267478e-01 -9.79198277e-01 1.58801138e-01 -1.26267478e-01 -9.78636444e-01 1.62227795e-01 -1.26267478e-01 -9.78064060e-01 1.65647164e-01 -1.26267478e-01 -9.77482259e-01 1.69040650e-01 -1.26267478e-01 -9.76886928e-01 1.72469497e-01 -1.26267478e-01 -9.76274133e-01 1.75899148e-01 -1.26267478e-01 -9.75646913e-01 1.79316953e-01 -1.26267478e-01 -9.75040615e-01 1.82623848e-01 -1.26267493e-01 -9.74419832e-01 1.85880601e-01 -1.26267478e-01 -9.73740339e-01 1.89384311e-01 -1.26267478e-01 -9.73056138e-01 1.92894638e-01 -1.26267478e-01 -9.72380877e-01 1.96272090e-01 -1.26267478e-01 -9.71686304e-01 1.99682564e-01 -1.26267478e-01 -9.70982611e-01 2.03070894e-01 -1.26267478e-01 -9.70286846e-01 2.06388369e-01 -1.26267478e-01 -9.69559431e-01 2.09754780e-01 -1.26267478e-01 -9.68798459e-01 2.13242739e-01 -1.26267478e-01 -9.68070447e-01 2.16545179e-01 -1.26267478e-01 -9.67307389e-01 2.19900802e-01 -1.26267478e-01 -9.66512680e-01 2.23384961e-01 -1.26267478e-01 -9.65727389e-01 2.26760611e-01 -1.26267478e-01 -9.64928567e-01 2.30140671e-01 -1.26267478e-01 -9.64148283e-01 2.33403847e-01 -1.26267478e-01 -9.63348687e-01 2.36656010e-01 -1.26267478e-01 -9.62482512e-01 2.40134940e-01 -1.26267478e-01 -9.61615145e-01 2.43597567e-01 -1.26267478e-01 -9.60758507e-01 2.46962428e-01 -1.26267478e-01 -9.59920287e-01 2.50212282e-01 -1.26267478e-01 -9.59042907e-01 2.53536910e-01 -1.26267478e-01 -9.58148420e-01 2.56910980e-01 -1.26267478e-01 -9.57235694e-01 2.60278583e-01 -1.26267478e-01 -9.56302941e-01 2.63682038e-01 -1.26267478e-01 -9.55402195e-01 2.66947001e-01 -1.26267478e-01 -9.54490900e-01 2.70172447e-01 -1.26267478e-01 -9.53514159e-01 2.73588032e-01 -1.26267478e-01 -9.52527165e-01 2.77019739e-01 -1.26267478e-01 -9.51563179e-01 2.80314922e-01 -1.26267478e-01 -9.50589657e-01 2.83601016e-01 -1.26267478e-01 -9.49587762e-01 2.86920339e-01 -1.26267478e-01 -9.48598206e-01 2.90195286e-01 -1.26267478e-01 -9.47580874e-01 2.93483436e-01 -1.26267478e-01 -9.46525514e-01 2.96883643e-01 -1.26267478e-01 -9.45503950e-01 3.00120801e-01 -1.26267478e-01 -9.44448471e-01 3.03409606e-01 -1.26267478e-01 -9.43364203e-01 3.06771159e-01 -1.26267478e-01 -9.42285299e-01 3.10070187e-01 -1.26267478e-01 -9.41194892e-01 3.13364595e-01 -1.26267478e-01 -9.40095425e-01 3.16659898e-01 -1.26267478e-01 -9.39016044e-01 3.19844544e-01 -1.26267478e-01 -9.37920809e-01 3.23037893e-01 -1.26267478e-01 -9.36759591e-01 3.26376975e-01 -1.26267478e-01 -9.35584068e-01 3.29739988e-01 -1.26267478e-01 -9.34459805e-01 3.32924455e-01 -1.26267478e-01 -9.33291614e-01 3.36166412e-01 -1.26267478e-01 -9.32077289e-01 3.39532226e-01 -1.26267478e-01 -9.30887103e-01 3.42763513e-01 -1.26267478e-01 -9.29684162e-01 3.46002638e-01 -1.26267478e-01 -9.28501070e-01 3.49173129e-01 -1.26267478e-01 -9.27314043e-01 3.52320194e-01 -1.26267478e-01 -9.26056564e-01 3.55625749e-01 -1.26267478e-01 -9.24762785e-01 3.58961284e-01 -1.26267478e-01 -9.23500836e-01 3.62207174e-01 -1.26267478e-01 -9.22235370e-01 3.65415126e-01 -1.26267478e-01 -9.20953631e-01 3.68633777e-01 -1.26267478e-01 -9.19660568e-01 3.71845216e-01 -1.26267478e-01 -9.18365359e-01 3.75034451e-01 -1.26267478e-01 -9.17047679e-01 3.78244191e-01 -1.26267478e-01 -9.15759265e-01 3.81360292e-01 -1.26267478e-01 -9.14455950e-01 3.84470344e-01 -1.26267478e-01 -9.13073659e-01 3.87732893e-01 -1.26267478e-01 -9.11679208e-01 3.91002744e-01 -1.26267478e-01 -9.10324991e-01 3.94152224e-01 -1.26267478e-01 -9.08955276e-01 3.97300243e-01 -1.26267478e-01 -9.07572806e-01 4.00449991e-01 -1.26267478e-01 -9.06185508e-01 4.03575480e-01 -1.26267478e-01 -9.04741347e-01 4.06802058e-01 -1.26267478e-01 -9.03288066e-01 4.10020471e-01 -1.26267478e-01 -9.01890457e-01 4.13086802e-01 -1.26267478e-01 -9.00451005e-01 4.16205764e-01 -1.26267478e-01 -8.98951292e-01 4.19438154e-01 -1.26267478e-01 -8.97498548e-01 4.22542781e-01 -1.26267478e-01 -8.96023154e-01 4.25663114e-01 -1.26267478e-01 -8.94529343e-01 4.28790569e-01 -1.26267478e-01 -8.93070161e-01 4.31834877e-01 -1.26267478e-01 -8.91541958e-01 4.34968770e-01 -1.26267478e-01 -8.89967144e-01 4.38181907e-01 -1.26267478e-01 -8.88445854e-01 4.41261590e-01 -1.26267478e-01 -8.86898279e-01 4.44358289e-01 -1.26267478e-01 -8.85341942e-01 4.47455078e-01 -1.26267478e-01 -8.83818507e-01 4.50464904e-01 -1.26267478e-01 -8.82279932e-01 4.53464001e-01 -1.26267478e-01 -8.80658805e-01 4.56598788e-01 -1.26267478e-01 -8.79024267e-01 4.59744871e-01 -1.26267478e-01 -8.77449393e-01 4.62748617e-01 -1.26267478e-01 -8.75832379e-01 4.65788215e-01 -1.26267478e-01 -8.74163687e-01 4.68918055e-01 -1.26267478e-01 -8.72522593e-01 4.71963435e-01 -1.26267478e-01 -8.70868504e-01 4.75013793e-01 -1.26267478e-01 -8.69194686e-01 4.78066832e-01 -1.26267478e-01 -8.67573023e-01 4.81003612e-01 -1.26267478e-01 -8.65896225e-01 4.84009564e-01 -1.26267478e-01 -8.64157677e-01 4.87112612e-01 -1.26267478e-01 -8.62446010e-01 4.90135491e-01 -1.26267478e-01 -8.60728502e-01 4.93147582e-01 -1.26267478e-01 -8.59025240e-01 4.96112257e-01 -1.26267478e-01 -8.57285678e-01 4.99108821e-01 -1.26267478e-01 -8.55536163e-01 5.02099514e-01 -1.26267478e-01 -8.53776097e-01 5.05089581e-01 -1.26267478e-01 -8.52043688e-01 5.08009315e-01 -1.26267478e-01 -8.50299120e-01 5.10918975e-01 -1.26267478e-01 -8.48464906e-01 5.13952971e-01 -1.26267478e-01 -8.46642256e-01 5.16959965e-01 -1.26267478e-01 -8.44833255e-01 5.19904852e-01 -1.26267478e-01 -8.43004942e-01 5.22870958e-01 -1.26267478e-01 -8.41189504e-01 5.25782824e-01 -1.26267478e-01 -8.39395404e-01 5.28646350e-01 -1.26267478e-01 -8.37536037e-01 5.31578243e-01 -1.26267478e-01 -8.35619271e-01 5.34591198e-01 -1.26267478e-01 -8.33797157e-01 5.37432671e-01 -1.26267478e-01 -8.31922233e-01 5.40319860e-01 -1.26267478e-01 -8.30011725e-01 5.43257177e-01 -1.26267478e-01 -8.28098595e-01 5.46167195e-01 -1.26267478e-01 -8.26170802e-01 5.49077332e-01 -1.26267478e-01 -8.24247062e-01 5.51963508e-01 -1.26267478e-01 -8.22372139e-01 5.54760516e-01 -1.26267478e-01 -8.20425868e-01 5.57621002e-01 -1.26267478e-01 -8.18410575e-01 5.60581267e-01 -1.26267478e-01 -8.16459119e-01 5.63421965e-01 -1.26267478e-01 -8.14538002e-01 5.66200256e-01 -1.26267493e-01 -8.12567770e-01 5.69011271e-01 -1.26267478e-01 -8.10539007e-01 5.71908236e-01 -1.26267478e-01 -8.08519781e-01 5.74751854e-01 -1.26267478e-01 -8.06493223e-01 5.77598989e-01 -1.26267478e-01 -8.04533780e-01 5.80323875e-01 -1.26267493e-01 -8.02534938e-01 5.83081424e-01 -1.26267478e-01 -8.00432503e-01 5.85961401e-01 -1.26267478e-01 -7.98345387e-01 5.88804781e-01 -1.26267478e-01 -7.96272695e-01 5.91604650e-01 -1.26267478e-01 -7.94202268e-01 5.94380736e-01 -1.26267478e-01 -7.92130232e-01 5.97141623e-01 -1.26267478e-01 -7.90045798e-01 5.99898815e-01 -1.26267478e-01 -7.87945628e-01 6.02652013e-01 -1.26267478e-01 -7.85854876e-01 6.05375707e-01 -1.26267478e-01 -7.83778131e-01 6.08070552e-01 -1.26267493e-01 -7.81648636e-01 6.10789001e-01 -1.26267478e-01 -7.79437125e-01 6.13617539e-01 -1.26267478e-01 -7.77292907e-01 6.16329670e-01 -1.26267478e-01 -7.75130570e-01 6.19050801e-01 -1.26267478e-01 -7.72975564e-01 6.21738613e-01 -1.26267478e-01 -7.70791709e-01 6.24442279e-01 -1.26267478e-01 -7.68694639e-01 6.27025664e-01 -1.26267493e-01 -7.66511917e-01 6.29687667e-01 -1.26267478e-01 -7.64219284e-01 6.32471859e-01 -1.26267478e-01 -7.62079954e-01 6.35051072e-01 -1.26267493e-01 -7.59864986e-01 6.37690127e-01 -1.26267478e-01 -7.57569551e-01 6.40422106e-01 -1.26267478e-01 -7.55349457e-01 6.43033266e-01 -1.26267478e-01 -7.53067791e-01 6.45705223e-01 -1.26267478e-01 -7.50824571e-01 6.48317754e-01 -1.26267478e-01 -7.48626947e-01 6.50853992e-01 -1.26267478e-01 -7.46326923e-01 6.53480172e-01 -1.26267478e-01 -7.43939579e-01 6.56203032e-01 -1.26267478e-01 -7.41643965e-01 6.58795714e-01 -1.26267478e-01 -7.39347339e-01 6.61374748e-01 -1.26267478e-01 -7.37041473e-01 6.63939893e-01 -1.26267478e-01 -7.34724760e-01 6.66508675e-01 -1.26267478e-01 -7.32382357e-01 6.69076085e-01 -1.26267478e-01 -7.30062544e-01 6.71609938e-01 -1.26267478e-01 -7.27792263e-01 6.74073279e-01 -1.26267493e-01 -7.25404322e-01 6.76632226e-01 -1.26267478e-01 -7.22961903e-01 6.79243922e-01 -1.26267478e-01 -7.20590889e-01 6.81759119e-01 -1.26267478e-01 -7.18198419e-01 6.84280038e-01 -1.26267478e-01 -7.15805769e-01 6.86778128e-01 -1.26267478e-01 -7.13428020e-01 6.89260066e-01 -1.26267478e-01 -7.11059332e-01 6.91706896e-01 -1.26267478e-01 -7.08652735e-01 6.94160700e-01 -1.26267478e-01 -7.06169486e-01 6.96690738e-01 -1.26267478e-01 -7.03785896e-01 6.99106514e-01 -1.26267478e-01 -7.01339364e-01 7.01532841e-01 -1.26267478e-01 -6.98836267e-01 7.04050660e-01 -1.26267478e-01 -6.96367145e-01 7.06492126e-01 -1.26267478e-01 -6.93902373e-01 7.08911419e-01 -1.26267478e-01 -6.91433787e-01 7.11320937e-01 -1.26267478e-01 -6.89035475e-01 7.13648319e-01 -1.26267493e-01 -6.86499119e-01 7.16071308e-01 -1.26267478e-01 -6.83925986e-01 7.18539178e-01 -1.26267478e-01 -6.81419194e-01 7.20910907e-01 -1.26267478e-01 -6.78888619e-01 7.23295927e-01 -1.26267478e-01 -6.76364839e-01 7.25652695e-01 -1.26267478e-01 -6.73823893e-01 7.28017509e-01 -1.26267478e-01 -6.71281636e-01 7.30363250e-01 -1.26267478e-01 -6.68730736e-01 7.32697546e-01 -1.26267478e-01 -6.66169345e-01 7.35031724e-01 -1.26267478e-01 -6.63674414e-01 7.37286389e-01 -1.26267493e-01 -6.61099851e-01 7.39589691e-01 -1.26267478e-01 -6.58429384e-01 7.41972208e-01 -1.26267478e-01 -6.55835271e-01 7.44263709e-01 -1.26267478e-01 -6.53249264e-01 7.46535003e-01 -1.26267478e-01 -6.50630713e-01 7.48819172e-01 -1.26267478e-01 -6.48065686e-01 7.51041651e-01 -1.26267478e-01 -6.45433545e-01 7.53298998e-01 -1.26267478e-01 -6.42754614e-01 7.55589962e-01 -1.26267478e-01 -6.40158713e-01 7.57794917e-01 -1.26267493e-01 -6.37524545e-01 7.60002375e-01 -1.26267478e-01 -6.34807646e-01 7.62278676e-01 -1.26267478e-01 -6.32168233e-01 7.64470220e-01 -1.26267478e-01 -6.29469037e-01 7.66695738e-01 -1.26267478e-01 -6.26842856e-01 7.68844247e-01 -1.26267493e-01 -6.24170601e-01 7.71009922e-01 -1.26267478e-01 -6.21401906e-01 7.73245156e-01 -1.26267478e-01 -6.18776500e-01 7.75352895e-01 -1.26267493e-01 -6.16051912e-01 7.77509630e-01 -1.26267478e-01 -6.13339901e-01 7.79661357e-01 -1.26267493e-01 -6.10642314e-01 7.81765699e-01 -1.26267478e-01 -6.07822001e-01 7.83967674e-01 -1.26267478e-01 -6.05130434e-01 7.86050677e-01 -1.26267493e-01 -6.02430284e-01 7.88114667e-01 -1.26267478e-01 -5.99651456e-01 7.90237486e-01 -1.26267493e-01 -5.96883655e-01 7.92323053e-01 -1.26267478e-01 -5.94110548e-01 7.94408083e-01 -1.26267478e-01 -5.91343462e-01 7.96462834e-01 -1.26267478e-01 -5.88465214e-01 7.98594296e-01 -1.26267478e-01 -5.85673332e-01 8.00645351e-01 -1.26267478e-01 -5.82952142e-01 8.02635133e-01 -1.26267493e-01 -5.80205321e-01 8.04614365e-01 -1.26267478e-01 -5.77300489e-01 8.06703687e-01 -1.26267478e-01 -5.74505508e-01 8.08702290e-01 -1.26267493e-01 -5.71716726e-01 8.10671210e-01 -1.26267478e-01 -5.68867981e-01 8.12677145e-01 -1.26267493e-01 -5.66036403e-01 8.14642727e-01 -1.26267478e-01 -5.63100934e-01 8.16680908e-01 -1.26267478e-01 -5.60251236e-01 8.18640232e-01 -1.26267478e-01 -5.57460666e-01 8.20540965e-01 -1.26267478e-01 -5.54657996e-01 8.22436750e-01 -1.26267478e-01 -5.51700413e-01 8.24421227e-01 -1.26267478e-01 -5.48821330e-01 8.26345384e-01 -1.26267478e-01 -5.45956492e-01 8.28237414e-01 -1.26267478e-01 -5.43057978e-01 8.30144048e-01 -1.26267478e-01 -5.40193498e-01 8.32005501e-01 -1.26267478e-01 -5.37212729e-01 8.33935618e-01 -1.26267478e-01 -5.34270823e-01 8.35823298e-01 -1.26267478e-01 -5.31327963e-01 8.37696970e-01 -1.26267478e-01 -5.28391480e-01 8.39553714e-01 -1.26267478e-01 -5.25465012e-01 8.41389656e-01 -1.26267478e-01 -5.22622287e-01 8.43165159e-01 -1.26267493e-01 -5.19668341e-01 8.44977975e-01 -1.26267478e-01 -5.16595602e-01 8.46863568e-01 -1.26267478e-01 -5.13623774e-01 8.48667562e-01 -1.26267478e-01 -5.10764003e-01 8.50396931e-01 -1.26267493e-01 -5.07799089e-01 8.52163613e-01 -1.26267478e-01 -5.04716218e-01 8.53997290e-01 -1.26267478e-01 -5.01820326e-01 8.55707645e-01 -1.26267493e-01 -4.98857915e-01 8.57429206e-01 -1.26267478e-01 -4.95843083e-01 8.59184623e-01 -1.26267493e-01 -4.92849171e-01 8.60895872e-01 -1.26267478e-01 -4.89755481e-01 8.62664223e-01 -1.26267478e-01 -4.86761123e-01 8.64358783e-01 -1.26267478e-01 -4.83830005e-01 8.66000354e-01 -1.26267478e-01 -4.80782986e-01 8.67691517e-01 -1.26267478e-01 -4.77670133e-01 8.69419694e-01 -1.26267493e-01 -4.74742442e-01 8.71022701e-01 -1.26267493e-01 -4.71681982e-01 8.72671902e-01 -1.26267478e-01 -4.68618393e-01 8.74328434e-01 -1.26267478e-01 -4.65602249e-01 8.75936091e-01 -1.26267478e-01 -4.62521076e-01 8.77569914e-01 -1.26267478e-01 -4.59460884e-01 8.79170477e-01 -1.26267478e-01 -4.56335694e-01 8.80798399e-01 -1.26267478e-01 -4.53241706e-01 8.82395267e-01 -1.26267478e-01 -4.50147510e-01 8.83976460e-01 -1.26267478e-01 -4.47127044e-01 8.85512590e-01 -1.26267478e-01 -4.44051892e-01 8.87053609e-01 -1.26267478e-01 -4.40883756e-01 8.88634503e-01 -1.26267478e-01 -4.37763214e-01 8.90174806e-01 -1.26267478e-01 -4.34723020e-01 8.91667187e-01 -1.26267478e-01 -4.31624383e-01 8.93167317e-01 -1.26267478e-01 -4.28421825e-01 8.94707680e-01 -1.26267478e-01 -4.25276458e-01 8.96209180e-01 -1.26267478e-01 -4.22152638e-01 8.97686064e-01 -1.26267478e-01 -4.19102967e-01 8.99114370e-01 -1.26267478e-01 -4.15949732e-01 9.00572598e-01 -1.26267478e-01 -4.12726790e-01 9.02054250e-01 -1.26267478e-01 -4.09581125e-01 9.03488815e-01 -1.26267478e-01 -4.06526625e-01 9.04871881e-01 -1.26267493e-01 -4.03381675e-01 9.06271338e-01 -1.26267478e-01 -4.00132358e-01 9.07714248e-01 -1.26267478e-01 -3.97024035e-01 9.09082353e-01 -1.26267493e-01 -3.93847197e-01 9.10455823e-01 -1.26267478e-01 -3.90645385e-01 9.11835492e-01 -1.26267493e-01 -3.87554526e-01 9.13152993e-01 -1.26267478e-01 -3.84356171e-01 9.14505363e-01 -1.26267478e-01 -3.81108642e-01 9.15859103e-01 -1.26267478e-01 -3.77838194e-01 9.17216480e-01 -1.26267478e-01 -3.74616593e-01 9.18538094e-01 -1.26267478e-01 -3.71425092e-01 9.19832706e-01 -1.26267478e-01 -3.68250638e-01 9.21108723e-01 -1.26267478e-01 -3.65035564e-01 9.22384799e-01 -1.26267478e-01 -3.61774266e-01 9.23670948e-01 -1.26267478e-01 -3.58533800e-01 9.24930334e-01 -1.26267478e-01 -3.55387837e-01 9.26156342e-01 -1.26267493e-01 -3.52162123e-01 9.27373827e-01 -1.26267478e-01 -3.48848671e-01 9.28620756e-01 -1.26267478e-01 -3.45594168e-01 9.29836631e-01 -1.26267478e-01 -3.42444569e-01 9.31007028e-01 -1.26267493e-01 -3.39276820e-01 9.32174504e-01 -1.26267478e-01 -3.35930705e-01 9.33377981e-01 -1.26267478e-01 -3.32676291e-01 9.34550524e-01 -1.26267478e-01 -3.29448283e-01 9.35686827e-01 -1.26267478e-01 -3.26166481e-01 9.36840951e-01 -1.26267493e-01 -3.22888315e-01 9.37970459e-01 -1.26267478e-01 -3.19563568e-01 9.39109862e-01 -1.26267478e-01 -3.16353321e-01 9.40198839e-01 -1.26267478e-01 -3.13058406e-01 9.41295028e-01 -1.26267478e-01 -3.09753090e-01 9.42392290e-01 -1.26267478e-01 -3.06454808e-01 9.43466008e-01 -1.26267478e-01 -3.03164989e-01 9.44535494e-01 -1.26267478e-01 -2.99874932e-01 9.45580184e-01 -1.26267478e-01 -2.96491385e-01 9.46648479e-01 -1.26267478e-01 -2.93193221e-01 9.47674215e-01 -1.26267478e-01 -2.89880931e-01 9.48691368e-01 -1.26267478e-01 -2.86580801e-01 9.49693680e-01 -1.26267478e-01 -2.83279061e-01 9.50684011e-01 -1.26267478e-01 -2.79943258e-01 9.51673806e-01 -1.26267478e-01 -2.76621282e-01 9.52644289e-01 -1.26267478e-01 -2.73373783e-01 9.53581572e-01 -1.26267478e-01 -2.70019144e-01 9.54534054e-01 -1.26267478e-01 -2.66638219e-01 9.55486000e-01 -1.26267478e-01 -2.63300568e-01 9.56410646e-01 -1.26267478e-01 -2.60021091e-01 9.57312286e-01 -1.26267478e-01 -2.56761134e-01 9.58188117e-01 -1.26267478e-01 -2.53371984e-01 9.59086478e-01 -1.26267478e-01 -2.50009269e-01 9.59973276e-01 -1.26267478e-01 -2.46652067e-01 9.60837066e-01 -1.26267478e-01 -2.43309066e-01 9.61692691e-01 -1.26267493e-01 -2.39933088e-01 9.62534726e-01 -1.26267478e-01 -2.36463651e-01 9.63398337e-01 -1.26267478e-01 -2.33189985e-01 9.64198411e-01 -1.26267478e-01 -2.29833588e-01 9.64999020e-01 -1.26267478e-01 -2.26459116e-01 9.65801895e-01 -1.26267493e-01 -2.23121718e-01 9.66570377e-01 -1.26267478e-01 -2.19720691e-01 9.67355311e-01 -1.26267478e-01 -2.16459036e-01 9.68088746e-01 -1.26267478e-01 -2.12953433e-01 9.68860805e-01 -1.26267478e-01 -2.09461674e-01 9.69625533e-01 -1.26267478e-01 -2.06077576e-01 9.70349252e-01 -1.26267478e-01 -2.02714205e-01 9.71060216e-01 -1.26267478e-01 -1.99430972e-01 9.71741736e-01 -1.26267493e-01 -1.96005732e-01 9.72430587e-01 -1.26267478e-01 -1.92494914e-01 9.73135531e-01 -1.26267478e-01 -1.89100057e-01 9.73801970e-01 -1.26267478e-01 -1.85706019e-01 9.74454701e-01 -1.26267478e-01 -1.82413459e-01 9.75078821e-01 -1.26267493e-01 -1.79021776e-01 9.75700974e-01 -1.26267478e-01 -1.75577775e-01 9.76339340e-01 -1.26267493e-01 -1.72182798e-01 9.76936758e-01 -1.26267478e-01 -1.68671563e-01 9.77545917e-01 -1.26267478e-01 -1.65362209e-01 9.78116393e-01 -1.26267478e-01 -1.61953658e-01 9.78679597e-01 -1.26267478e-01 -1.58517912e-01 9.79246676e-01 -1.26267493e-01 -1.55114874e-01 9.79786575e-01 -1.26267478e-01 -1.51573911e-01 9.80343640e-01 -1.26267478e-01 -1.48256823e-01 9.80853140e-01 -1.26267478e-01 -1.44836560e-01 9.81358707e-01 -1.26267478e-01 -1.41398400e-01 9.81863976e-01 -1.26267478e-01 -1.37971327e-01 9.82348979e-01 -1.26267478e-01 -1.34449631e-01 9.82840061e-01 -1.26267478e-01 -1.31087974e-01 9.83292758e-01 -1.26267478e-01 -1.27663314e-01 9.83740628e-01 -1.26267478e-01 -1.24130271e-01 9.84195769e-01 -1.26267478e-01 -1.20707422e-01 9.84619379e-01 -1.26267478e-01 -1.17361717e-01 9.85026360e-01 -1.26267478e-01 -1.14025481e-01 9.85415399e-01 -1.26267478e-01 -1.10480689e-01 9.85817015e-01 -1.26267478e-01 -1.06952623e-01 9.86208022e-01 -1.26267478e-01 -1.03497297e-01 9.86576796e-01 -1.26267478e-01 -1.00038305e-01 9.86932456e-01 -1.26267478e-01 -9.66890976e-02 9.87272024e-01 -1.26267493e-01 -9.32708085e-02 9.87595558e-01 -1.26267478e-01 -8.98159817e-02 9.87922013e-01 -1.26267493e-01 -8.63681883e-02 9.88222003e-01 -1.26267478e-01 -8.28058571e-02 9.88530159e-01 -1.26267478e-01 -7.94607997e-02 9.88808870e-01 -1.26267493e-01 -7.60404319e-02 9.89071071e-01 -1.26267478e-01 -7.25542530e-02 9.89338696e-01 -1.26267493e-01 -6.90879300e-02 9.89579201e-01 -1.26267478e-01 -6.55227453e-02 9.89825845e-01 -1.26267478e-01 -6.20732680e-02 9.90045905e-01 -1.26267478e-01 -5.86206913e-02 9.90258217e-01 -1.26267478e-01 -5.52493446e-02 9.90456820e-01 -1.26267493e-01 -5.17920144e-02 9.90633130e-01 -1.26267478e-01 -4.83151972e-02 9.90818322e-01 -1.26267478e-01 -4.49724831e-02 9.90973592e-01 -1.26267478e-01 -4.14195135e-02 9.91123378e-01 -1.26267478e-01 -3.78618501e-02 9.91268039e-01 -1.26267478e-01 -3.43918689e-02 9.91394222e-01 -1.26267478e-01 -3.09255254e-02 9.91509020e-01 -1.26267478e-01 -2.75672264e-02 9.91612017e-01 -1.26267493e-01 -2.42005195e-02 9.91698384e-01 -1.26267478e-01 -2.06351746e-02 9.91770148e-01 -1.26267478e-01 -1.70508195e-02 9.91850972e-01 -1.26267478e-01 -1.36231584e-02 9.91893768e-01 -1.26267478e-01 -1.02640148e-02 9.91941035e-01 -1.26267478e-01 -6.81187212e-03 9.91972446e-01 -1.26267478e-01 -3.30409664e-03 9.91993248e-01 -1.26267478e-01 1.30262924e-04 9.91990149e-01 -1.26267478e-01 3.68215167e-03 9.91991997e-01 -1.26267478e-01 7.06109125e-03 9.91974533e-01 -1.26267478e-01 1.05203893e-02 9.91934121e-01 -1.26267478e-01 1.39810266e-02 9.91892397e-01 -1.26267478e-01 1.74424406e-02 9.91842806e-01 -1.26267478e-01 2.09278129e-02 9.91774261e-01 -1.26267493e-01 2.43007243e-02 9.91695344e-01 -1.26267478e-01 2.78417170e-02 9.91600275e-01 -1.26267478e-01 3.13927531e-02 9.91496027e-01 -1.26267478e-01 3.48482542e-02 9.91381824e-01 -1.26267478e-01 3.82860489e-02 9.91254687e-01 -1.26267478e-01 4.16695960e-02 9.91120219e-01 -1.26267478e-01 4.51316945e-02 9.90961373e-01 -1.26267478e-01 4.86889221e-02 9.90796626e-01 -1.26267478e-01 5.21273687e-02 9.90617990e-01 -1.26267478e-01 5.55728227e-02 9.90435660e-01 -1.26267478e-01 5.89488298e-02 9.90241468e-01 -1.26267478e-01 6.24123625e-02 9.90020871e-01 -1.26267478e-01 6.59462661e-02 9.89796519e-01 -1.26267478e-01 6.94258437e-02 9.89557028e-01 -1.26267478e-01 7.28971064e-02 9.89309967e-01 -1.26267478e-01 7.62462765e-02 9.89059269e-01 -1.26267478e-01 7.96860009e-02 9.88782823e-01 -1.26267478e-01 8.31634030e-02 9.88503397e-01 -1.26267493e-01 8.65909755e-02 9.88202631e-01 -1.26267478e-01 9.01478678e-02 9.87886429e-01 -1.26267478e-01 9.34884995e-02 9.87580895e-01 -1.26267493e-01 9.69323739e-02 9.87242579e-01 -1.26267478e-01 1.00405119e-01 9.86901045e-01 -1.26267478e-01 1.03817351e-01 9.86541569e-01 -1.26267478e-01 1.07292071e-01 9.86176848e-01 -1.26267493e-01 1.10718720e-01 9.85791683e-01 -1.26267478e-01 1.14258401e-01 9.85388637e-01 -1.26267478e-01 1.17699996e-01 9.84983206e-01 -1.26267478e-01 1.21120587e-01 9.84569252e-01 -1.26267478e-01 1.24485619e-01 9.84154820e-01 -1.26267478e-01 1.27828956e-01 9.83721018e-01 -1.26267478e-01 1.31331891e-01 9.83257532e-01 -1.26267478e-01 1.34848922e-01 9.82784271e-01 -1.26267478e-01 1.38303965e-01 9.82303262e-01 -1.26267478e-01 1.41729891e-01 9.81814682e-01 -1.26267478e-01 1.45088777e-01 9.81327116e-01 -1.26267493e-01 1.48482844e-01 9.80812311e-01 -1.26267478e-01 1.51922062e-01 9.80292082e-01 -1.26267478e-01 1.55329049e-01 9.79751647e-01 -1.26267478e-01 1.58854499e-01 9.79189992e-01 -1.26267478e-01 1.62175864e-01 9.78649139e-01 -1.26267478e-01 1.65582910e-01 9.78073001e-01 -1.26267478e-01 1.69000044e-01 9.77492094e-01 -1.26267478e-01 1.72325402e-01 9.76913154e-01 -1.26267478e-01 1.75808087e-01 9.76288974e-01 -1.26267478e-01 1.79304034e-01 9.75653827e-01 -1.26267478e-01 1.82732776e-01 9.75015461e-01 -1.26267478e-01 1.86019704e-01 9.74395871e-01 -1.26267478e-01 1.89437181e-01 9.73733187e-01 -1.26267478e-01 1.92839652e-01 9.73071039e-01 -1.26267478e-01 1.96137458e-01 9.72406924e-01 -1.26267478e-01 1.99613020e-01 9.71698999e-01 -1.26267478e-01 2.03102708e-01 9.70975876e-01 -1.26267478e-01 2.06479564e-01 9.70265210e-01 -1.26267478e-01 2.09870785e-01 9.69536901e-01 -1.26267478e-01 2.13174731e-01 9.68815923e-01 -1.26267478e-01 2.16529295e-01 9.68070209e-01 -1.26267478e-01 2.20007747e-01 9.67287898e-01 -1.26267478e-01 2.23398164e-01 9.66512382e-01 -1.26267478e-01 2.26765364e-01 9.65728045e-01 -1.26267478e-01 2.30050445e-01 9.64953721e-01 -1.26267493e-01 2.33315349e-01 9.64167297e-01 -1.26267478e-01 2.36699939e-01 9.63338733e-01 -1.26267478e-01 2.40129083e-01 9.62486088e-01 -1.26267478e-01 2.43562162e-01 9.61625218e-01 -1.26267478e-01 2.46859759e-01 9.60788488e-01 -1.26267478e-01 2.50201494e-01 9.59917605e-01 -1.26267478e-01 2.53558248e-01 9.59042728e-01 -1.26267478e-01 2.56876320e-01 9.58155155e-01 -1.26267478e-01 2.60328084e-01 9.57224727e-01 -1.26267478e-01 2.63597280e-01 9.56330776e-01 -1.26267478e-01 2.66916245e-01 9.55403507e-01 -1.26267478e-01 2.70263761e-01 9.54470515e-01 -1.26267493e-01 2.73570448e-01 9.53519940e-01 -1.26267478e-01 2.76990891e-01 9.52538013e-01 -1.26267478e-01 2.80236274e-01 9.51587737e-01 -1.26267478e-01 2.83548862e-01 9.50601637e-01 -1.26267478e-01 2.86971837e-01 9.49575007e-01 -1.26267478e-01 2.90263355e-01 9.48577225e-01 -1.26267478e-01 2.93464988e-01 9.47592676e-01 -1.26267478e-01 2.96684086e-01 9.46587145e-01 -1.26267478e-01 2.99996495e-01 9.45541143e-01 -1.26267478e-01 3.03406864e-01 9.44447756e-01 -1.26267478e-01 3.06810200e-01 9.43351448e-01 -1.26267478e-01 3.10087353e-01 9.42280471e-01 -1.26267478e-01 3.13298255e-01 9.41222310e-01 -1.26267478e-01 3.16480070e-01 9.40153658e-01 -1.26267478e-01 3.19756359e-01 9.39043224e-01 -1.26267478e-01 3.23091120e-01 9.37898934e-01 -1.26267478e-01 3.26462060e-01 9.36731339e-01 -1.26267478e-01 3.29667777e-01 9.35614109e-01 -1.26267478e-01 3.32917511e-01 9.34456587e-01 -1.26267478e-01 3.36201131e-01 9.33283091e-01 -1.26267478e-01 3.39420199e-01 9.32114244e-01 -1.26267478e-01 3.42777640e-01 9.30881262e-01 -1.26267478e-01 3.46012533e-01 9.29680943e-01 -1.26267478e-01 3.49259883e-01 9.28465784e-01 -1.26267478e-01 3.52439523e-01 9.27271008e-01 -1.26267478e-01 3.55649441e-01 9.26046610e-01 -1.26267478e-01 3.58894438e-01 9.24791813e-01 -1.26267478e-01 3.62015635e-01 9.23575163e-01 -1.26267478e-01 3.65337312e-01 9.22265470e-01 -1.26267478e-01 3.68637055e-01 9.20951843e-01 -1.26267478e-01 3.71828198e-01 9.19667184e-01 -1.26267478e-01 3.75030279e-01 9.18368280e-01 -1.26267478e-01 3.78172636e-01 9.17078197e-01 -1.26267478e-01 3.81273508e-01 9.15791571e-01 -1.26267478e-01 3.84554386e-01 9.14416075e-01 -1.26267478e-01 3.87820959e-01 9.13037598e-01 -1.26267478e-01 3.90995353e-01 9.11683083e-01 -1.26267478e-01 3.94126117e-01 9.10337448e-01 -1.26267478e-01 3.97222549e-01 9.08990026e-01 -1.26267478e-01 4.00382489e-01 9.07602489e-01 -1.26267478e-01 4.03609097e-01 9.06168640e-01 -1.26267478e-01 4.06835049e-01 9.04727399e-01 -1.26267478e-01 4.09930497e-01 9.03330564e-01 -1.26267478e-01 4.13005114e-01 9.01925147e-01 -1.26267478e-01 4.16138262e-01 9.00484860e-01 -1.26267478e-01 4.19275194e-01 8.99029315e-01 -1.26267478e-01 4.22403276e-01 8.97566080e-01 -1.26267478e-01 4.25583333e-01 8.96060467e-01 -1.26267478e-01 4.28784132e-01 8.94532323e-01 -1.26267478e-01 4.31907415e-01 8.93032908e-01 -1.26267478e-01 4.34948474e-01 8.91557276e-01 -1.26267478e-01 4.38024759e-01 8.90044689e-01 -1.26267478e-01 4.41104144e-01 8.88524652e-01 -1.26267478e-01 4.44262713e-01 8.86945546e-01 -1.26267478e-01 4.47429597e-01 8.85355353e-01 -1.26267478e-01 4.50512320e-01 8.83789361e-01 -1.26267478e-01 4.53534514e-01 8.82245958e-01 -1.26267478e-01 4.56538409e-01 8.80691111e-01 -1.26267478e-01 4.59598094e-01 8.79102290e-01 -1.26267478e-01 4.62724924e-01 8.77454937e-01 -1.26267478e-01 4.65861470e-01 8.75797033e-01 -1.26267478e-01 4.68906194e-01 8.74171197e-01 -1.26267478e-01 4.71894890e-01 8.72562110e-01 -1.26267478e-01 4.74881232e-01 8.70942712e-01 -1.26267478e-01 4.77915794e-01 8.69278431e-01 -1.26267478e-01 4.80986208e-01 8.67576718e-01 -1.26267478e-01 4.84113574e-01 8.65840435e-01 -1.26267478e-01 4.87062961e-01 8.64188433e-01 -1.26267478e-01 4.90037322e-01 8.62498760e-01 -1.26267478e-01 4.93082196e-01 8.60771239e-01 -1.26267478e-01 4.95997965e-01 8.59088957e-01 -1.26267478e-01 4.99087542e-01 8.57295811e-01 -1.26267478e-01 5.02072394e-01 8.55555177e-01 -1.26267478e-01 5.05042315e-01 8.53799403e-01 -1.26267478e-01 5.08026958e-01 8.52033317e-01 -1.26267478e-01 5.10985017e-01 8.50257218e-01 -1.26267478e-01 5.14001071e-01 8.48440111e-01 -1.26267478e-01 5.16859710e-01 8.46703589e-01 -1.26267478e-01 5.19857764e-01 8.44860315e-01 -1.26267478e-01 5.22832096e-01 8.43029439e-01 -1.26267478e-01 5.25762320e-01 8.41199934e-01 -1.26267478e-01 5.28711200e-01 8.39355648e-01 -1.26267478e-01 5.31528831e-01 8.37572396e-01 -1.26267478e-01 5.34483910e-01 8.35686862e-01 -1.26267478e-01 5.37402093e-01 8.33815694e-01 -1.26267478e-01 5.40342152e-01 8.31908286e-01 -1.26267478e-01 5.43323398e-01 8.29967856e-01 -1.26267478e-01 5.46167850e-01 8.28104734e-01 -1.26267478e-01 5.48957109e-01 8.26249599e-01 -1.26267478e-01 5.51822782e-01 8.24342191e-01 -1.26267478e-01 5.54777324e-01 8.22357833e-01 -1.26267478e-01 5.57697654e-01 8.20379674e-01 -1.26267478e-01 5.60503960e-01 8.18470180e-01 -1.26267493e-01 5.63301086e-01 8.16552997e-01 -1.26267552e-01 5.66133976e-01 8.14590871e-01 -1.26267567e-01 5.69029927e-01 8.12569022e-01 -1.26267567e-01 5.71876764e-01 8.10569644e-01 -1.26267567e-01 5.74615955e-01 8.08628559e-01 -1.26267567e-01 5.77513397e-01 8.06561589e-01 -1.26267567e-01 5.80329299e-01 8.04537356e-01 -1.26267731e-01 5.82960308e-01 8.02628338e-01 -1.26267776e-01 5.85806608e-01 8.00552964e-01 -1.26268297e-01 5.88355005e-01 7.98682928e-01 -1.26268283e-01 5.91263711e-01 7.96531737e-01 -1.26268253e-01 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. 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. 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. 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. 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. 0. 0. 0. 0. 7.18841374e-01 6.83610380e-01 -1.26268238e-01 7.21001625e-01 6.81327164e-01 -1.26268312e-01 7.23275959e-01 6.78919733e-01 -1.26267642e-01 7.25651026e-01 6.76382303e-01 -1.26267567e-01 7.27947772e-01 6.73912823e-01 -1.26267567e-01 7.30235398e-01 6.71433508e-01 -1.26267567e-01 7.32597411e-01 6.68854713e-01 -1.26267552e-01 7.34888315e-01 6.66329443e-01 -1.26267478e-01 7.37260103e-01 6.63697064e-01 -1.26267478e-01 7.39647746e-01 6.61035776e-01 -1.26267478e-01 7.41883159e-01 6.58534169e-01 -1.26267493e-01 7.44099975e-01 6.56020999e-01 -1.26267478e-01 7.46397555e-01 6.53405309e-01 -1.26267478e-01 7.48672962e-01 6.50798142e-01 -1.26267478e-01 7.51000941e-01 6.48108482e-01 -1.26267478e-01 7.53257930e-01 6.45491660e-01 -1.26267493e-01 7.55443513e-01 6.42924547e-01 -1.26267478e-01 7.57686853e-01 6.40282750e-01 -1.26267478e-01 7.59962916e-01 6.37574077e-01 -1.26267478e-01 7.62202322e-01 6.34905756e-01 -1.26267493e-01 7.64342666e-01 6.32320285e-01 -1.26267478e-01 7.66609073e-01 6.29569769e-01 -1.26267478e-01 7.68858075e-01 6.26820982e-01 -1.26267478e-01 7.71041691e-01 6.24136627e-01 -1.26267478e-01 7.73159921e-01 6.21512294e-01 -1.26267493e-01 7.75268853e-01 6.18877888e-01 -1.26267478e-01 7.77404189e-01 6.16190910e-01 -1.26267478e-01 7.79616952e-01 6.13385499e-01 -1.26267478e-01 7.81828165e-01 6.10566139e-01 -1.26267478e-01 7.83938706e-01 6.07856572e-01 -1.26267478e-01 7.86000907e-01 6.05192482e-01 -1.26267493e-01 7.88059890e-01 6.02503300e-01 -1.26267478e-01 7.90168881e-01 5.99735975e-01 -1.26267478e-01 7.92298198e-01 5.96917272e-01 -1.26267478e-01 7.94442713e-01 5.94060063e-01 -1.26267478e-01 7.96458662e-01 5.91359854e-01 -1.26267478e-01 7.98456669e-01 5.88656008e-01 -1.26267478e-01 8.00507486e-01 5.85859954e-01 -1.26267478e-01 8.02599490e-01 5.82989872e-01 -1.26267478e-01 8.04631352e-01 5.80188870e-01 -1.26267478e-01 8.06590021e-01 5.77462316e-01 -1.26267478e-01 8.08652937e-01 5.74564278e-01 -1.26267478e-01 8.10667932e-01 5.71729064e-01 -1.26267478e-01 8.12652647e-01 5.68890035e-01 -1.26267478e-01 8.14649105e-01 5.66042960e-01 -1.26267493e-01 8.16547155e-01 5.63296735e-01 -1.26267478e-01 8.18555653e-01 5.60367823e-01 -1.26267478e-01 8.20572913e-01 5.57413161e-01 -1.26267478e-01 8.22508037e-01 5.54552436e-01 -1.26267478e-01 8.24404240e-01 5.51735580e-01 -1.26267493e-01 8.26252997e-01 5.48957944e-01 -1.26267478e-01 8.28167558e-01 5.46064317e-01 -1.26267478e-01 8.30120265e-01 5.43086767e-01 -1.26267478e-01 8.32071424e-01 5.40097237e-01 -1.26267478e-01 8.33899379e-01 5.37276864e-01 -1.26267493e-01 8.35702240e-01 5.34461677e-01 -1.26267478e-01 8.37558150e-01 5.31549156e-01 -1.26267478e-01 8.39417815e-01 5.28609931e-01 -1.26267478e-01 8.41316700e-01 5.25571764e-01 -1.26267478e-01 8.43214035e-01 5.22534907e-01 -1.26267478e-01 8.44979823e-01 5.19673169e-01 -1.26267478e-01 8.46735597e-01 5.16806841e-01 -1.26267478e-01 8.48529160e-01 5.13853252e-01 -1.26267478e-01 8.50302815e-01 5.10913551e-01 -1.26267478e-01 8.52088571e-01 5.07928431e-01 -1.26267478e-01 8.53877366e-01 5.04916430e-01 -1.26267478e-01 8.55627596e-01 5.01950443e-01 -1.26267478e-01 8.57351720e-01 4.98994708e-01 -1.26267478e-01 8.59137654e-01 4.95909125e-01 -1.26267478e-01 8.60881925e-01 4.92887110e-01 -1.26267493e-01 8.62535596e-01 4.89975482e-01 -1.26267478e-01 8.64312768e-01 4.86836076e-01 -1.26267478e-01 8.66060317e-01 4.83719051e-01 -1.26267478e-01 8.67737889e-01 4.80707973e-01 -1.26267478e-01 8.69360983e-01 4.77771789e-01 -1.26267478e-01 8.70988071e-01 4.74796534e-01 -1.26267478e-01 8.72639656e-01 4.71747130e-01 -1.26267478e-01 8.74284089e-01 4.68698084e-01 -1.26267478e-01 8.75947535e-01 4.65571404e-01 -1.26267478e-01 8.77617359e-01 4.62425590e-01 -1.26267478e-01 8.79190624e-01 4.59433168e-01 -1.26267478e-01 8.80732894e-01 4.56462711e-01 -1.26267478e-01 8.82332861e-01 4.53361779e-01 -1.26267478e-01 8.83953393e-01 4.50186998e-01 -1.26267478e-01 8.85553300e-01 4.47037041e-01 -1.26267478e-01 8.87080669e-01 4.44005847e-01 -1.26267493e-01 8.88579845e-01 4.40991759e-01 -1.26267478e-01 8.90096545e-01 4.37922567e-01 -1.26267478e-01 8.91657233e-01 4.34734046e-01 -1.26267478e-01 8.93184304e-01 4.31601644e-01 -1.26267478e-01 8.94634843e-01 4.28571820e-01 -1.26267478e-01 8.96160841e-01 4.25368726e-01 -1.26267478e-01 8.97649825e-01 4.22229946e-01 -1.26267493e-01 8.99110138e-01 4.19101626e-01 -1.26267478e-01 9.00581717e-01 4.15939420e-01 -1.26267478e-01 9.01977718e-01 4.12895948e-01 -1.26267478e-01 9.03446496e-01 4.09666240e-01 -1.26267478e-01 9.04916286e-01 4.06418473e-01 -1.26267478e-01 9.06329870e-01 4.03256983e-01 -1.26267478e-01 9.07706499e-01 4.00150239e-01 -1.26267478e-01 9.09059167e-01 3.97070795e-01 -1.26267478e-01 9.10433352e-01 3.93900990e-01 -1.26267478e-01 9.11801219e-01 3.90718460e-01 -1.26267478e-01 9.13190901e-01 3.87457937e-01 -1.26267478e-01 9.14548934e-01 3.84256661e-01 -1.26267478e-01 9.15840328e-01 3.81162226e-01 -1.26267478e-01 9.17164147e-01 3.77960950e-01 -1.26267478e-01 9.18484986e-01 3.74743730e-01 -1.26267478e-01 9.19810355e-01 3.71471703e-01 -1.26267478e-01 9.21143413e-01 3.68161112e-01 -1.26267478e-01 9.22399580e-01 3.65015268e-01 -1.26267493e-01 9.23620522e-01 3.61905128e-01 -1.26267478e-01 9.24867749e-01 3.58686775e-01 -1.26267478e-01 9.26160276e-01 3.55351448e-01 -1.26267478e-01 9.27400649e-01 3.52095187e-01 -1.26267478e-01 9.28587258e-01 3.48939419e-01 -1.26267478e-01 9.29823399e-01 3.45621705e-01 -1.26267478e-01 9.31062162e-01 3.42290103e-01 -1.26267478e-01 9.32256341e-01 3.39044005e-01 -1.26267478e-01 9.33394551e-01 3.35890085e-01 -1.26267478e-01 9.34533656e-01 3.32709283e-01 -1.26267478e-01 9.35713530e-01 3.29366833e-01 -1.26267478e-01 9.36899781e-01 3.25979561e-01 -1.26267478e-01 9.38037813e-01 3.22701067e-01 -1.26267478e-01 9.39126790e-01 3.19519073e-01 -1.26267478e-01 9.40198481e-01 3.16349715e-01 -1.26267478e-01 9.41298246e-01 3.13054204e-01 -1.26267478e-01 9.42393124e-01 3.09746951e-01 -1.26267478e-01 9.43482995e-01 3.06406587e-01 -1.26267478e-01 9.44585979e-01 3.02990437e-01 -1.26267478e-01 9.45613801e-01 2.99778372e-01 -1.26267478e-01 9.46626723e-01 2.96557456e-01 -1.26267478e-01 9.47654545e-01 2.93256193e-01 -1.26267478e-01 9.48684633e-01 2.89893895e-01 -1.26267478e-01 9.49721754e-01 2.86483288e-01 -1.26267478e-01 9.50698078e-01 2.83242136e-01 -1.26267478e-01 9.51653242e-01 2.80008256e-01 -1.26267478e-01 9.52625334e-01 2.76682138e-01 -1.26267478e-01 9.53591049e-01 2.73325115e-01 -1.26267478e-01 9.54553843e-01 2.69962490e-01 -1.26267478e-01 9.55465913e-01 2.66711026e-01 -1.26267478e-01 9.56393600e-01 2.63353825e-01 -1.26267478e-01 9.57308888e-01 2.60025322e-01 -1.26267478e-01 9.58220720e-01 2.56619066e-01 -1.26267478e-01 9.59125996e-01 2.53238082e-01 -1.26267478e-01 9.59976494e-01 2.49990493e-01 -1.26267478e-01 9.60841000e-01 2.46638089e-01 -1.26267478e-01 9.61714506e-01 2.43191227e-01 -1.26267478e-01 9.62575793e-01 2.39775002e-01 -1.26267478e-01 9.63405907e-01 2.36432642e-01 -1.26267478e-01 9.64208841e-01 2.33143955e-01 -1.26267478e-01 9.64993596e-01 2.29859293e-01 -1.26267478e-01 9.65790093e-01 2.26493135e-01 -1.26267478e-01 9.66593683e-01 2.23017424e-01 -1.26267478e-01 9.67371762e-01 2.19645381e-01 -1.26267478e-01 9.68117535e-01 2.16328114e-01 -1.26267478e-01 9.68867183e-01 2.12937698e-01 -1.26267478e-01 9.69605505e-01 2.09545523e-01 -1.26267478e-01 9.70330715e-01 2.06170976e-01 -1.26267478e-01 9.71052587e-01 2.02733696e-01 -1.26267478e-01 9.71760392e-01 1.99337825e-01 -1.26267478e-01 9.72440898e-01 1.95965603e-01 -1.26267478e-01 9.73136663e-01 1.92484334e-01 -1.26267478e-01 9.73806083e-01 1.89070731e-01 -1.26267478e-01 9.74446177e-01 1.85751468e-01 -1.26267478e-01 9.75069582e-01 1.82447299e-01 -1.26267478e-01 9.75709081e-01 1.78968117e-01 -1.26267478e-01 9.76352215e-01 1.75478190e-01 -1.26267478e-01 9.76958215e-01 1.72065288e-01 -1.26267478e-01 9.77539599e-01 1.68718591e-01 -1.26267478e-01 9.78107572e-01 1.65395096e-01 -1.26267478e-01 9.78676081e-01 1.61980733e-01 -1.26267478e-01 9.79235590e-01 1.58570349e-01 -1.26267478e-01 9.79793847e-01 1.55069485e-01 -1.26267478e-01 9.80343461e-01 1.51567712e-01 -1.26267478e-01 9.80857611e-01 1.48214236e-01 -1.26267478e-01 9.81349945e-01 1.44910306e-01 -1.26267478e-01 9.81850207e-01 1.41467765e-01 -1.26267478e-01 9.82351899e-01 1.37951836e-01 -1.26267478e-01 9.82838631e-01 1.34451017e-01 -1.26267478e-01 9.83292162e-01 1.31098479e-01 -1.26267478e-01 9.83731210e-01 1.27747118e-01 -1.26267478e-01 9.84172285e-01 1.24317825e-01 -1.26267478e-01 9.84596193e-01 1.20899901e-01 -1.26267478e-01 9.85014617e-01 1.17438190e-01 -1.26267478e-01 9.85417545e-01 1.13987260e-01 -1.26267478e-01 9.85819399e-01 1.10460550e-01 -1.26267478e-01 9.86202240e-01 1.07031137e-01 -1.26267478e-01 9.86563504e-01 1.03597715e-01 -1.26267478e-01 9.86924648e-01 1.00139163e-01 -1.26267478e-01 9.87256944e-01 9.67847481e-02 -1.26267478e-01 9.87597287e-01 9.32602510e-02 -1.26267478e-01 9.87925112e-01 8.97285119e-02 -1.26267478e-01 9.88233507e-01 8.62802044e-02 -1.26267478e-01 9.88522649e-01 8.29092935e-02 -1.26267478e-01 9.88799036e-01 7.95283541e-02 -1.26267478e-01 9.89065647e-01 7.61058778e-02 -1.26267478e-01 9.89331543e-01 7.25444108e-02 -1.26267478e-01 9.89584804e-01 6.90148920e-02 -1.26267478e-01 9.89817262e-01 6.56644329e-02 -1.26267478e-01 9.90030825e-01 6.23082593e-02 -1.26267478e-01 9.90244091e-01 5.88216931e-02 -1.26267478e-01 9.90445554e-01 5.53664006e-02 -1.26267478e-01 9.90631878e-01 5.18391207e-02 -1.26267478e-01 9.90816772e-01 4.82641384e-02 -1.26267478e-01 9.90976930e-01 4.49063219e-02 -1.26267478e-01 9.91119921e-01 4.15574685e-02 -1.26267478e-01 9.91258621e-01 3.80982794e-02 -1.26267478e-01 9.91386533e-01 3.45122665e-02 -1.26267478e-01 9.91507947e-01 3.10431235e-02 -1.26267478e-01 9.91605997e-01 2.76952833e-02 -1.26267478e-01 9.91696477e-01 2.42302939e-02 -1.26267478e-01 9.91770446e-01 2.07556020e-02 -1.26267478e-01 9.91845489e-01 1.72970239e-02 -1.26267478e-01 9.91888404e-01 1.38405832e-02 -1.26267478e-01 9.91938174e-01 1.03676543e-02 -1.26267478e-01 9.91973042e-01 6.81714574e-03 -1.26267478e-01 9.91990268e-01 3.24323098e-03 -1.26267478e-01 9.91990745e-01 -2.16555913e-04 -1.26267478e-01 9.91989791e-01 -3.69239273e-03 -1.26267478e-01 9.91975307e-01 -7.03873346e-03 -1.26267478e-01 9.91937160e-01 -1.03992699e-02 -1.26267478e-01 9.91887689e-01 -1.38624832e-02 -1.26267478e-01 9.91840243e-01 -1.74472127e-02 -1.26267478e-01 9.91765261e-01 -2.10228562e-02 -1.26267478e-01 9.91691291e-01 -2.44560055e-02 -1.26267478e-01 9.91605401e-01 -2.78057083e-02 -1.26267478e-01 9.91493940e-01 -3.12769003e-02 -1.26267478e-01 9.91385579e-01 -3.47558670e-02 -1.26267478e-01 9.91256177e-01 -3.81347351e-02 -1.26267478e-01 9.91120815e-01 -4.15782370e-02 -1.26267478e-01 9.90960240e-01 -4.51241918e-02 -1.26267478e-01 9.90796089e-01 -4.86795940e-02 -1.26267478e-01 9.90617454e-01 -5.21321185e-02 -1.26267478e-01 9.90438282e-01 -5.55206314e-02 -1.26267478e-01 9.90241706e-01 -5.88715374e-02 -1.26267478e-01 9.90028501e-01 -6.23123869e-02 -1.26267478e-01 9.89797473e-01 -6.58677146e-02 -1.26267478e-01 9.89555955e-01 -6.94247186e-02 -1.26267478e-01 9.89309013e-01 -7.29099065e-02 -1.26267478e-01 9.89058018e-01 -7.62715638e-02 -1.26267478e-01 9.88792062e-01 -7.96032920e-02 -1.26267478e-01 9.88506734e-01 -8.30534026e-02 -1.26267478e-01 9.88201678e-01 -8.66000578e-02 -1.26267478e-01 9.87895846e-01 -9.00612697e-02 -1.26267478e-01 9.87584889e-01 -9.33815464e-02 -1.26267478e-01 9.87253189e-01 -9.68481526e-02 -1.26267478e-01 9.86905634e-01 -1.00302659e-01 -1.26267478e-01 9.86549139e-01 -1.03764839e-01 -1.26267478e-01 9.86172497e-01 -1.07254155e-01 -1.26267478e-01 9.85797524e-01 -1.10707350e-01 -1.26267478e-01 9.85412061e-01 -1.14054330e-01 -1.26267478e-01 9.84998405e-01 -1.17557339e-01 -1.26267478e-01 9.84586000e-01 -1.21009119e-01 -1.26267478e-01 9.84150589e-01 -1.24454960e-01 -1.26267478e-01 9.83701229e-01 -1.27975643e-01 -1.26267478e-01 9.83263075e-01 -1.31315261e-01 -1.26267478e-01 9.82793748e-01 -1.34754390e-01 -1.26267478e-01 9.82309341e-01 -1.38266876e-01 -1.26267478e-01 9.81832743e-01 -1.41613573e-01 -1.26267478e-01 9.81326580e-01 -1.45040616e-01 -1.26267478e-01 9.80814517e-01 -1.48488685e-01 -1.26267478e-01 9.80289757e-01 -1.51900366e-01 -1.26267478e-01 9.79760587e-01 -1.55308172e-01 -1.26267478e-01 9.79207277e-01 -1.58727735e-01 -1.26267478e-01 9.78653669e-01 -1.62140578e-01 -1.26267478e-01 9.78076577e-01 -1.65555969e-01 -1.26267478e-01 9.77480352e-01 -1.69041008e-01 -1.26267478e-01 9.76885974e-01 -1.72472358e-01 -1.26267478e-01 9.76294041e-01 -1.75805286e-01 -1.26267478e-01 9.75683272e-01 -1.79113731e-01 -1.26267478e-01 9.75052774e-01 -1.82529569e-01 -1.26267478e-01 9.74390209e-01 -1.86015323e-01 -1.26267478e-01 9.73725975e-01 -1.89492136e-01 -1.26267478e-01 9.73058999e-01 -1.92874774e-01 -1.26267478e-01 9.72396791e-01 -1.96201041e-01 -1.26267478e-01 9.71720219e-01 -1.99516147e-01 -1.26267478e-01 9.71018195e-01 -2.02900425e-01 -1.26267478e-01 9.70277786e-01 -2.06409946e-01 -1.26267478e-01 9.69565570e-01 -2.09755957e-01 -1.26267478e-01 9.68821585e-01 -2.13131800e-01 -1.26267478e-01 9.68074858e-01 -2.16527820e-01 -1.26267478e-01 9.67312574e-01 -2.19884515e-01 -1.26267478e-01 9.66544211e-01 -2.23257005e-01 -1.26267478e-01 9.65750813e-01 -2.26649299e-01 -1.26267478e-01 9.64958370e-01 -2.30023906e-01 -1.26267478e-01 9.64175940e-01 -2.33270779e-01 -1.26267478e-01 9.63326454e-01 -2.36737624e-01 -1.26267478e-01 9.62497950e-01 -2.40097791e-01 -1.26267478e-01 9.61646259e-01 -2.43461952e-01 -1.26267478e-01 9.60779488e-01 -2.46884257e-01 -1.26267478e-01 9.59938526e-01 -2.50134021e-01 -1.26267478e-01 9.59050238e-01 -2.53508210e-01 -1.26267478e-01 9.58162069e-01 -2.56862789e-01 -1.26267478e-01 9.57287967e-01 -2.60092199e-01 -1.26267478e-01 9.56341326e-01 -2.63525903e-01 -1.26267478e-01 9.55418169e-01 -2.66892463e-01 -1.26267478e-01 9.54481483e-01 -2.70197928e-01 -1.26267478e-01 9.53503728e-01 -2.73634732e-01 -1.26267478e-01 9.52569366e-01 -2.76882559e-01 -1.26267478e-01 9.51628089e-01 -2.80087620e-01 -1.26267478e-01 9.50619996e-01 -2.83486873e-01 -1.26267478e-01 9.49594021e-01 -2.86902219e-01 -1.26267478e-01 9.48578238e-01 -2.90249676e-01 -1.26267478e-01 9.47585881e-01 -2.93488115e-01 -1.26267478e-01 9.46589231e-01 -2.96674043e-01 -1.26267478e-01 9.45550382e-01 -2.99968839e-01 -1.26267478e-01 9.44472015e-01 -3.03339005e-01 -1.26267478e-01 9.43375051e-01 -3.06738973e-01 -1.26267478e-01 9.42301631e-01 -3.10020179e-01 -1.26267478e-01 9.41236138e-01 -3.13248217e-01 -1.26267478e-01 9.40167129e-01 -3.16437721e-01 -1.26267478e-01 9.39059138e-01 -3.19709301e-01 -1.26267478e-01 9.37913477e-01 -3.23048025e-01 -1.26267478e-01 9.36778247e-01 -3.26336980e-01 -1.26267478e-01 9.35630858e-01 -3.29601854e-01 -1.26267478e-01 9.34483826e-01 -3.32857430e-01 -1.26267478e-01 9.33312774e-01 -3.36108327e-01 -1.26267478e-01 9.32128072e-01 -3.39399129e-01 -1.26267478e-01 9.30932164e-01 -3.42635483e-01 -1.26267478e-01 9.29727376e-01 -3.45889688e-01 -1.26267478e-01 9.28549170e-01 -3.49036366e-01 -1.26267478e-01 9.27323580e-01 -3.52293789e-01 -1.26267478e-01 9.26060259e-01 -3.55614871e-01 -1.26267478e-01 9.24804389e-01 -3.58858258e-01 -1.26267478e-01 9.23550069e-01 -3.62075001e-01 -1.26267478e-01 9.22284603e-01 -3.65301698e-01 -1.26267478e-01 9.21005666e-01 -3.68494898e-01 -1.26267478e-01 9.19715822e-01 -3.71716857e-01 -1.26267478e-01 9.18452561e-01 -3.74820769e-01 -1.26267478e-01 9.17098403e-01 -3.78111690e-01 -1.26267478e-01 9.15771663e-01 -3.81332040e-01 -1.26267478e-01 9.14432108e-01 -3.84515882e-01 -1.26267478e-01 9.13041651e-01 -3.87809575e-01 -1.26267478e-01 9.11720276e-01 -3.90912652e-01 -1.26267478e-01 9.10389245e-01 -3.93999279e-01 -1.26267478e-01 9.08981442e-01 -3.97235811e-01 -1.26267478e-01 9.07549739e-01 -4.00499612e-01 -1.26267478e-01 9.06140208e-01 -4.03676808e-01 -1.26267478e-01 9.04756844e-01 -4.06776965e-01 -1.26267478e-01 9.03365016e-01 -4.09850717e-01 -1.26267478e-01 9.01948035e-01 -4.12953109e-01 -1.26267478e-01 9.00457680e-01 -4.16191012e-01 -1.26267478e-01 8.98966074e-01 -4.19410437e-01 -1.26267478e-01 8.97491574e-01 -4.22555476e-01 -1.26267478e-01 8.96043062e-01 -4.25626397e-01 -1.26267478e-01 8.94587696e-01 -4.28666890e-01 -1.26267478e-01 8.93080950e-01 -4.31803912e-01 -1.26267478e-01 8.91521513e-01 -4.35012162e-01 -1.26267478e-01 8.89990985e-01 -4.38136309e-01 -1.26267478e-01 8.88458669e-01 -4.41229075e-01 -1.26267478e-01 8.86930704e-01 -4.44302052e-01 -1.26267478e-01 8.85421634e-01 -4.47300971e-01 -1.26267478e-01 8.83867919e-01 -4.50361431e-01 -1.26267478e-01 8.82235765e-01 -4.53544408e-01 -1.26267478e-01 8.80641043e-01 -4.56641197e-01 -1.26267478e-01 8.79099846e-01 -4.59600717e-01 -1.26267478e-01 8.77483904e-01 -4.62675095e-01 -1.26267478e-01 8.75802100e-01 -4.65845168e-01 -1.26267478e-01 8.74178290e-01 -4.68899161e-01 -1.26267478e-01 8.72548401e-01 -4.71911132e-01 -1.26267478e-01 8.70887876e-01 -4.74985451e-01 -1.26267478e-01 8.69275093e-01 -4.77918506e-01 -1.26267478e-01 8.67595017e-01 -4.80958223e-01 -1.26267478e-01 8.65870237e-01 -4.84054744e-01 -1.26267478e-01 8.64177704e-01 -4.87082422e-01 -1.26267478e-01 8.62474680e-01 -4.90081012e-01 -1.26267478e-01 8.60759497e-01 -4.93100435e-01 -1.26267478e-01 8.59028459e-01 -4.96096760e-01 -1.26267478e-01 8.57259393e-01 -4.99155194e-01 -1.26267478e-01 8.55549932e-01 -5.02078891e-01 -1.26267478e-01 8.53825629e-01 -5.05004704e-01 -1.26267478e-01 8.52061212e-01 -5.07970870e-01 -1.26267478e-01 8.50239754e-01 -5.11012018e-01 -1.26267478e-01 8.48394275e-01 -5.14070213e-01 -1.26267478e-01 8.46639991e-01 -5.16968012e-01 -1.26267478e-01 8.44876468e-01 -5.19834042e-01 -1.26267478e-01 8.43060553e-01 -5.22780657e-01 -1.26267478e-01 8.41191292e-01 -5.25773942e-01 -1.26267478e-01 8.39298189e-01 -5.28795958e-01 -1.26267478e-01 8.37454438e-01 -5.31709313e-01 -1.26267478e-01 8.35654438e-01 -5.34537911e-01 -1.26267478e-01 8.33777785e-01 -5.37453115e-01 -1.26267478e-01 8.31838131e-01 -5.40454566e-01 -1.26267478e-01 8.29940438e-01 -5.43361127e-01 -1.26267478e-01 8.28039706e-01 -5.46255827e-01 -1.26267478e-01 8.26182306e-01 -5.49062610e-01 -1.26267478e-01 8.24321628e-01 -5.51849961e-01 -1.26267478e-01 8.22379470e-01 -5.54741085e-01 -1.26267478e-01 8.20389211e-01 -5.57675064e-01 -1.26267478e-01 8.18393290e-01 -5.60605526e-01 -1.26267478e-01 8.16436172e-01 -5.63454449e-01 -1.26267478e-01 8.14505160e-01 -5.66242993e-01 -1.26267478e-01 8.12536418e-01 -5.69054365e-01 -1.26267478e-01 8.10537755e-01 -5.71910799e-01 -1.26267478e-01 8.08530748e-01 -5.74734271e-01 -1.26267478e-01 8.06521535e-01 -5.77560782e-01 -1.26267478e-01 8.04545701e-01 -5.80298722e-01 -1.26267478e-01 8.02510679e-01 -5.83115637e-01 -1.26267478e-01 8.00473928e-01 -5.85907221e-01 -1.26267478e-01 7.98375487e-01 -5.88757813e-01 -1.26267478e-01 7.96253085e-01 -5.91630280e-01 -1.26267478e-01 7.94251144e-01 -5.94317794e-01 -1.26267478e-01 7.92183697e-01 -5.97065568e-01 -1.26267478e-01 7.90077746e-01 -5.99858344e-01 -1.26267478e-01 7.87999332e-01 -6.02578282e-01 -1.26267478e-01 7.85899401e-01 -6.05318606e-01 -1.26267478e-01 7.83823013e-01 -6.08001113e-01 -1.26267478e-01 7.81644702e-01 -6.10798120e-01 -1.26267478e-01 7.79454529e-01 -6.13592625e-01 -1.26267478e-01 7.77338147e-01 -6.16275787e-01 -1.26267478e-01 7.75243580e-01 -6.18903935e-01 -1.26267478e-01 7.73088634e-01 -6.21595263e-01 -1.26267478e-01 7.70854592e-01 -6.24360085e-01 -1.26267478e-01 7.68663049e-01 -6.27061009e-01 -1.26267478e-01 7.66536117e-01 -6.29657030e-01 -1.26267478e-01 7.64329135e-01 -6.32334828e-01 -1.26267478e-01 7.62125731e-01 -6.34987354e-01 -1.26267478e-01 7.59909987e-01 -6.37639165e-01 -1.26267478e-01 7.57604480e-01 -6.40370011e-01 -1.26267478e-01 7.55359113e-01 -6.43025875e-01 -1.26267478e-01 7.53181934e-01 -6.45570099e-01 -1.26267478e-01 7.50924170e-01 -6.48196399e-01 -1.26267478e-01 7.48627663e-01 -6.50846422e-01 -1.26267478e-01 7.46301353e-01 -6.53511286e-01 -1.26267478e-01 7.43977249e-01 -6.56157315e-01 -1.26267478e-01 7.41724133e-01 -6.58707321e-01 -1.26267478e-01 7.39475906e-01 -6.61227763e-01 -1.26267478e-01 7.37114370e-01 -6.63856149e-01 -1.26267478e-01 7.34807551e-01 -6.66417360e-01 -1.26267478e-01 7.32469678e-01 -6.68976188e-01 -1.26267478e-01 7.30135679e-01 -6.71530664e-01 -1.26267478e-01 7.27848291e-01 -6.74004853e-01 -1.26267478e-01 7.25487113e-01 -6.76543832e-01 -1.26267478e-01 7.23067462e-01 -6.79125607e-01 -1.26267478e-01 7.20686257e-01 -6.81659579e-01 -1.26267478e-01 7.18305349e-01 -6.84164524e-01 -1.26267478e-01 7.15911567e-01 -6.86668634e-01 -1.26267478e-01 7.13528097e-01 -6.89151764e-01 -1.26267478e-01 7.11098969e-01 -6.91662312e-01 -1.26267478e-01 7.08737791e-01 -6.94075167e-01 -1.26267478e-01 7.06260800e-01 -6.96593642e-01 -1.26267478e-01 7.03817010e-01 -6.99074268e-01 -1.26267478e-01 7.01364517e-01 -7.01507628e-01 -1.26267478e-01 6.98897958e-01 -7.03992844e-01 -1.26267478e-01 6.96482062e-01 -7.06389189e-01 -1.26267567e-01 6.94076538e-01 -7.08749533e-01 -1.26267567e-01 6.91579759e-01 -7.11187184e-01 -1.26267567e-01 6.89076066e-01 -7.13607430e-01 -1.26267567e-01 6.86560094e-01 -7.16029584e-01 -1.26267627e-01 6.84061706e-01 -7.18413889e-01 -1.26267746e-01 6.81627750e-01 -7.20719814e-01 -1.26267970e-01 6.79244995e-01 -7.22965419e-01 -1.26268312e-01 6.76662147e-01 -7.25385666e-01 -1.26268312e-01 6.74138248e-01 -7.27731884e-01 -1.26268283e-01 6.72049642e-01 -7.29660988e-01 -1.26268253e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.51001549e-01 -8.24895799e-01 -1.26268253e-01 5.48470497e-01 -8.26578021e-01 -1.26268312e-01 5.45863748e-01 -8.28307331e-01 -1.26267746e-01 5.43065488e-01 -8.30145001e-01 -1.26267567e-01 5.40136695e-01 -8.32055509e-01 -1.26267567e-01 5.37203372e-01 -8.33951950e-01 -1.26267523e-01 5.34415841e-01 -8.35730493e-01 -1.26267478e-01 5.31481266e-01 -8.37597966e-01 -1.26267478e-01 5.28554142e-01 -8.39451075e-01 -1.26267478e-01 5.25627375e-01 -8.41284394e-01 -1.26267478e-01 5.22689462e-01 -8.43116879e-01 -1.26267478e-01 5.19746363e-01 -8.44930649e-01 -1.26267478e-01 5.16813815e-01 -8.46731663e-01 -1.26267478e-01 5.13858080e-01 -8.48525763e-01 -1.26267478e-01 5.10877192e-01 -8.50324273e-01 -1.26267478e-01 5.07864356e-01 -8.52124214e-01 -1.26267478e-01 5.04881799e-01 -8.53900135e-01 -1.26267478e-01 5.01953185e-01 -8.55623782e-01 -1.26267478e-01 4.98963028e-01 -8.57370138e-01 -1.26267478e-01 4.95903164e-01 -8.59141588e-01 -1.26267478e-01 4.92908508e-01 -8.60868633e-01 -1.26267478e-01 4.89980459e-01 -8.62533450e-01 -1.26267478e-01 4.86973643e-01 -8.64238501e-01 -1.26267478e-01 4.83970374e-01 -8.65921080e-01 -1.26267478e-01 4.80932742e-01 -8.67610633e-01 -1.26267478e-01 4.77887422e-01 -8.69294167e-01 -1.26267478e-01 4.74870205e-01 -8.70946705e-01 -1.26267478e-01 4.71819848e-01 -8.72601748e-01 -1.26267478e-01 4.68775481e-01 -8.74239683e-01 -1.26267478e-01 4.65714514e-01 -8.75874221e-01 -1.26267478e-01 4.62648451e-01 -8.77498448e-01 -1.26267478e-01 4.59526211e-01 -8.79133046e-01 -1.26267478e-01 4.56443816e-01 -8.80743086e-01 -1.26267478e-01 4.53434497e-01 -8.82295370e-01 -1.26267478e-01 4.50333327e-01 -8.83881092e-01 -1.26267478e-01 4.47253227e-01 -8.85444641e-01 -1.26267478e-01 4.44160491e-01 -8.86998713e-01 -1.26267478e-01 4.41076756e-01 -8.88536572e-01 -1.26267478e-01 4.37984377e-01 -8.90063703e-01 -1.26267478e-01 4.34859216e-01 -8.91597092e-01 -1.26267478e-01 4.31753576e-01 -8.93105507e-01 -1.26267478e-01 4.28607583e-01 -8.94616187e-01 -1.26267478e-01 4.25434351e-01 -8.96130443e-01 -1.26267478e-01 4.22301084e-01 -8.97613406e-01 -1.26267478e-01 4.19128627e-01 -8.99095416e-01 -1.26267478e-01 4.15962994e-01 -9.00570333e-01 -1.26267478e-01 4.12922144e-01 -9.01964128e-01 -1.26267478e-01 4.09781903e-01 -9.03396547e-01 -1.26267478e-01 4.06636685e-01 -9.04817283e-01 -1.26267478e-01 4.03357685e-01 -9.06280458e-01 -1.26267478e-01 4.00172949e-01 -9.07698393e-01 -1.26267493e-01 3.97120029e-01 -9.09035265e-01 -1.26267478e-01 3.93939435e-01 -9.10416067e-01 -1.26267478e-01 3.90749365e-01 -9.11786616e-01 -1.26267478e-01 3.87516797e-01 -9.13167477e-01 -1.26267478e-01 3.84344637e-01 -9.14510489e-01 -1.26267478e-01 3.81080419e-01 -9.15869534e-01 -1.26267478e-01 3.77856523e-01 -9.17210340e-01 -1.26267478e-01 3.74785691e-01 -9.18468714e-01 -1.26267478e-01 3.71530026e-01 -9.19786394e-01 -1.26267478e-01 3.68218929e-01 -9.21117723e-01 -1.26267478e-01 3.64950538e-01 -9.22421098e-01 -1.26267478e-01 3.61803412e-01 -9.23662364e-01 -1.26267478e-01 3.58675212e-01 -9.24872458e-01 -1.26267478e-01 3.55436325e-01 -9.26130414e-01 -1.26267478e-01 3.52206498e-01 -9.27357674e-01 -1.26267478e-01 3.48983318e-01 -9.28570569e-01 -1.26267478e-01 3.45726639e-01 -9.29786682e-01 -1.26267478e-01 3.42475116e-01 -9.30993676e-01 -1.26267478e-01 3.39238882e-01 -9.32183862e-01 -1.26267478e-01 3.35984737e-01 -9.33358908e-01 -1.26267478e-01 3.32713336e-01 -9.34532523e-01 -1.26267478e-01 3.29376608e-01 -9.35709596e-01 -1.26267478e-01 3.26097727e-01 -9.36862290e-01 -1.26267478e-01 3.22847605e-01 -9.37983155e-01 -1.26267478e-01 3.19545776e-01 -9.39117432e-01 -1.26267478e-01 3.16353559e-01 -9.40196872e-01 -1.26267478e-01 3.12994331e-01 -9.41315472e-01 -1.26267478e-01 3.09684575e-01 -9.42412913e-01 -1.26267478e-01 3.06391329e-01 -9.43485856e-01 -1.26267478e-01 3.03090543e-01 -9.44558442e-01 -1.26267478e-01 2.99869925e-01 -9.45580900e-01 -1.26267478e-01 2.96589047e-01 -9.46616590e-01 -1.26267478e-01 2.93282568e-01 -9.47646141e-01 -1.26267478e-01 2.89961904e-01 -9.48667884e-01 -1.26267478e-01 2.86570013e-01 -9.49692607e-01 -1.26267478e-01 2.83164322e-01 -9.50717688e-01 -1.26267478e-01 2.79948533e-01 -9.51675057e-01 -1.26267478e-01 2.76624680e-01 -9.52640355e-01 -1.26267478e-01 2.73198336e-01 -9.53629971e-01 -1.26267478e-01 2.69879580e-01 -9.54573870e-01 -1.26267478e-01 2.66635358e-01 -9.55490351e-01 -1.26267478e-01 2.63377100e-01 -9.56388652e-01 -1.26267478e-01 2.60041356e-01 -9.57303166e-01 -1.26267478e-01 2.56682366e-01 -9.58206058e-01 -1.26267478e-01 2.53366619e-01 -9.59089279e-01 -1.26267478e-01 2.50012815e-01 -9.59971070e-01 -1.26267478e-01 2.46590912e-01 -9.60852265e-01 -1.26267478e-01 2.43223011e-01 -9.61712956e-01 -1.26267478e-01 2.39888743e-01 -9.62546051e-01 -1.26267478e-01 2.36505926e-01 -9.63388979e-01 -1.26267478e-01 2.33210921e-01 -9.64190006e-01 -1.26267478e-01 2.29770929e-01 -9.65014994e-01 -1.26267478e-01 2.26406083e-01 -9.65812445e-01 -1.26267478e-01 2.23038122e-01 -9.66590345e-01 -1.26267478e-01 2.19578505e-01 -9.67384636e-01 -1.26267478e-01 2.16299385e-01 -9.68126416e-01 -1.26267478e-01 2.13000700e-01 -9.68852460e-01 -1.26267478e-01 2.09619984e-01 -9.69590187e-01 -1.26267478e-01 2.06235617e-01 -9.70315397e-01 -1.26267478e-01 2.02736720e-01 -9.71051872e-01 -1.26267478e-01 1.99333087e-01 -9.71762598e-01 -1.26267478e-01 1.96050525e-01 -9.72425699e-01 -1.26267478e-01 1.92669004e-01 -9.73100066e-01 -1.26267478e-01 1.89247310e-01 -9.73773062e-01 -1.26267478e-01 1.85760036e-01 -9.74440038e-01 -1.26267478e-01 1.82351783e-01 -9.75090742e-01 -1.26267478e-01 1.78938851e-01 -9.75715280e-01 -1.26267478e-01 1.75517887e-01 -9.76348758e-01 -1.26267478e-01 1.72205597e-01 -9.76934373e-01 -1.26267478e-01 1.68800548e-01 -9.77521300e-01 -1.26267478e-01 1.65380433e-01 -9.78108943e-01 -1.26267478e-01 1.61879465e-01 -9.78690028e-01 -1.26267478e-01 1.58457994e-01 -9.79256570e-01 -1.26267478e-01 1.55143753e-01 -9.79785144e-01 -1.26267478e-01 1.51719898e-01 -9.80320394e-01 -1.26267478e-01 1.48298040e-01 -9.80841756e-01 -1.26267478e-01 1.44776687e-01 -9.81367886e-01 -1.26267478e-01 1.41342893e-01 -9.81872439e-01 -1.26267478e-01 1.37917697e-01 -9.82355654e-01 -1.26267478e-01 1.34385109e-01 -9.82847750e-01 -1.26267478e-01 1.31038740e-01 -9.83300269e-01 -1.26267478e-01 1.27725467e-01 -9.83734131e-01 -1.26267478e-01 1.24283545e-01 -9.84177232e-01 -1.26267478e-01 1.20856561e-01 -9.84601617e-01 -1.26267478e-01 1.17324129e-01 -9.85025883e-01 -1.26267478e-01 1.13867827e-01 -9.85436320e-01 -1.26267478e-01 1.10543028e-01 -9.85813022e-01 -1.26267478e-01 1.07111447e-01 -9.86190975e-01 -1.26267478e-01 1.03668444e-01 -9.86558616e-01 -1.26267478e-01 1.00119062e-01 -9.86921966e-01 -1.26267478e-01 9.66643766e-02 -9.87273633e-01 -1.26267478e-01 9.32404026e-02 -9.87598598e-01 -1.26267478e-01 8.97791609e-02 -9.87922966e-01 -1.26267478e-01 8.63292888e-02 -9.88226116e-01 -1.26267478e-01 8.27862471e-02 -9.88529742e-01 -1.26267478e-01 7.93890804e-02 -9.88814235e-01 -1.26267493e-01 7.59666190e-02 -9.89076018e-01 -1.26267478e-01 7.24862367e-02 -9.89341915e-01 -1.26267478e-01 6.91375509e-02 -9.89576519e-01 -1.26267478e-01 6.57053739e-02 -9.89811301e-01 -1.26267478e-01 6.22512586e-02 -9.90035355e-01 -1.26267478e-01 5.86760305e-02 -9.90251780e-01 -1.26267478e-01 5.52343316e-02 -9.90456760e-01 -1.26267478e-01 5.17776534e-02 -9.90636349e-01 -1.26267478e-01 4.83244024e-02 -9.90816832e-01 -1.26267478e-01 4.48821969e-02 -9.90972281e-01 -1.26267478e-01 4.13138792e-02 -9.91131186e-01 -1.26267478e-01 3.79311293e-02 -9.91267979e-01 -1.26267478e-01 3.45799811e-02 -9.91387904e-01 -1.26267478e-01 3.10368016e-02 -9.91502941e-01 -1.26267478e-01 2.75597498e-02 -9.91611362e-01 -1.26267478e-01 2.41155233e-02 -9.91697907e-01 -1.26267478e-01 2.06351932e-02 -9.91776645e-01 -1.26267478e-01 1.72644258e-02 -9.91846085e-01 -1.26267478e-01 1.37415770e-02 -9.91886795e-01 -1.26267478e-01 1.02485828e-02 -9.91941810e-01 -1.26267478e-01 6.88500283e-03 -9.91974533e-01 -1.26267478e-01 3.42094596e-03 -9.91991222e-01 -1.26267478e-01 -3.18525963e-05 -9.91992056e-01 -1.26267478e-01 -3.47323599e-03 -9.91989851e-01 -1.26267478e-01 -6.94911461e-03 -9.91973758e-01 -1.26267478e-01 -1.05029773e-02 -9.91934240e-01 -1.26267478e-01 -1.39722610e-02 -9.91891503e-01 -1.26267478e-01 -1.74195115e-02 -9.91842151e-01 -1.26267478e-01 -2.09966674e-02 -9.91765916e-01 -1.26267478e-01 -2.43779775e-02 -9.91696239e-01 -1.26267478e-01 -2.77186204e-02 -9.91605222e-01 -1.26267478e-01 -3.11638713e-02 -9.91502047e-01 -1.26267478e-01 -3.47257555e-02 -9.91380274e-01 -1.26267478e-01 -3.82970795e-02 -9.91252720e-01 -1.26267478e-01 -4.16766182e-02 -9.91119444e-01 -1.26267478e-01 -4.50359210e-02 -9.90968287e-01 -1.26267478e-01 -4.85004894e-02 -9.90805268e-01 -1.26267478e-01 -5.19559793e-02 -9.90628660e-01 -1.26267478e-01 -5.54817878e-02 -9.90436673e-01 -1.26267478e-01 -5.89640252e-02 -9.90240514e-01 -1.26267478e-01 -6.24016374e-02 -9.90023017e-01 -1.26267478e-01 -6.58829808e-02 -9.89802897e-01 -1.26267478e-01 -6.92363977e-02 -9.89570379e-01 -1.26267478e-01 -7.27619156e-02 -9.89316404e-01 -1.26267478e-01 -7.62481391e-02 -9.89059091e-01 -1.26267478e-01 -7.96757340e-02 -9.88784194e-01 -1.26267478e-01 -8.31297487e-02 -9.88502622e-01 -1.26267478e-01 -8.65038335e-02 -9.88212228e-01 -1.26267478e-01 -8.99592936e-02 -9.87903237e-01 -1.26267478e-01 -9.33992267e-02 -9.87584472e-01 -1.26267478e-01 -9.69269425e-02 -9.87243891e-01 -1.26267478e-01 -1.00367434e-01 -9.86905158e-01 -1.26267478e-01 -1.03791118e-01 -9.86544073e-01 -1.26267478e-01 -1.07312486e-01 -9.86169815e-01 -1.26267478e-01 -1.10693358e-01 -9.85799789e-01 -1.26267478e-01 -1.14049144e-01 -9.85413551e-01 -1.26267478e-01 -1.17476501e-01 -9.85009253e-01 -1.26267478e-01 -1.20913602e-01 -9.84593272e-01 -1.26267478e-01 -1.24442175e-01 -9.84153986e-01 -1.26267478e-01 -1.27883032e-01 -9.83715951e-01 -1.26267478e-01 -1.31231591e-01 -9.83272672e-01 -1.26267478e-01 -1.34652391e-01 -9.82809842e-01 -1.26267478e-01 -1.38082594e-01 -9.82334912e-01 -1.26267478e-01 -1.41597643e-01 -9.81831372e-01 -1.26267478e-01 -1.45020127e-01 -9.81335402e-01 -1.26267478e-01 -1.48442373e-01 -9.80818331e-01 -1.26267478e-01 -1.51859879e-01 -9.80301380e-01 -1.26267478e-01 -1.55182958e-01 -9.79777515e-01 -1.26267478e-01 -1.58606336e-01 -9.79229867e-01 -1.26267478e-01 -1.62024230e-01 -9.78670955e-01 -1.26267478e-01 -1.65554196e-01 -9.78076220e-01 -1.26267478e-01 -1.68964773e-01 -9.77497041e-01 -1.26267478e-01 -1.72264189e-01 -9.76923883e-01 -1.26267478e-01 -1.75690636e-01 -9.76311326e-01 -1.26267478e-01 -1.79099709e-01 -9.75687265e-01 -1.26267478e-01 -1.82579219e-01 -9.75043416e-01 -1.26267478e-01 -1.85997188e-01 -9.74400640e-01 -1.26267478e-01 -1.89309284e-01 -9.73758399e-01 -1.26267478e-01 -1.92688227e-01 -9.73097861e-01 -1.26267478e-01 -1.96176842e-01 -9.72397923e-01 -1.26267478e-01 -1.99573189e-01 -9.71711576e-01 -1.26267478e-01 -2.02861398e-01 -9.71027374e-01 -1.26267478e-01 -2.06273034e-01 -9.70308304e-01 -1.26267478e-01 -2.09729180e-01 -9.69565272e-01 -1.26267478e-01 -2.13139549e-01 -9.68824387e-01 -1.26267478e-01 -2.16407150e-01 -9.68099356e-01 -1.26267478e-01 -2.19798207e-01 -9.67333555e-01 -1.26267478e-01 -2.23181844e-01 -9.66557384e-01 -1.26267478e-01 -2.26651236e-01 -9.65751231e-01 -1.26267478e-01 -2.30040938e-01 -9.64953840e-01 -1.26267478e-01 -2.33284563e-01 -9.64172840e-01 -1.26267478e-01 -2.36665741e-01 -9.63347018e-01 -1.26267478e-01 -2.40026131e-01 -9.62513447e-01 -1.26267478e-01 -2.43421152e-01 -9.61657941e-01 -1.26267478e-01 -2.46830001e-01 -9.60794568e-01 -1.26267478e-01 -2.50197500e-01 -9.59917724e-01 -1.26267478e-01 -2.53545493e-01 -9.59046125e-01 -1.26267478e-01 -2.56866872e-01 -9.58156228e-01 -1.26267478e-01 -2.60302633e-01 -9.57230866e-01 -1.26267478e-01 -2.63576180e-01 -9.56335962e-01 -1.26267478e-01 -2.66891122e-01 -9.55411434e-01 -1.26267478e-01 -2.70241261e-01 -9.54475224e-01 -1.26267478e-01 -2.73464620e-01 -9.53552485e-01 -1.26267478e-01 -2.76787400e-01 -9.52593446e-01 -1.26267478e-01 -2.80117959e-01 -9.51619804e-01 -1.26267478e-01 -2.83418089e-01 -9.50643957e-01 -1.26267478e-01 -2.86737740e-01 -9.49643850e-01 -1.26267478e-01 -2.90069044e-01 -9.48631465e-01 -1.26267478e-01 -2.93449104e-01 -9.47591901e-01 -1.26267478e-01 -2.96765834e-01 -9.46563542e-01 -1.26267478e-01 -3.00076485e-01 -9.45514321e-01 -1.26267478e-01 -3.03379267e-01 -9.44465578e-01 -1.26267478e-01 -3.06577027e-01 -9.43428099e-01 -1.26267478e-01 -3.09963405e-01 -9.42318022e-01 -1.26267478e-01 -3.13234866e-01 -9.41240966e-01 -1.26267478e-01 -3.16523701e-01 -9.40138340e-01 -1.26267478e-01 -3.19816470e-01 -9.39025640e-01 -1.26267478e-01 -3.22993249e-01 -9.37935889e-01 -1.26267478e-01 -3.26321274e-01 -9.36779261e-01 -1.26267478e-01 -3.29589158e-01 -9.35641289e-01 -1.26267478e-01 -3.32881808e-01 -9.34468329e-01 -1.26267478e-01 -3.36151093e-01 -9.33301687e-01 -1.26267478e-01 -3.39390755e-01 -9.32127416e-01 -1.26267478e-01 -3.42656642e-01 -9.30928409e-01 -1.26267478e-01 -3.45806211e-01 -9.29756343e-01 -1.26267478e-01 -3.49122077e-01 -9.28515911e-01 -1.26267478e-01 -3.52360189e-01 -9.27300572e-01 -1.26267478e-01 -3.55589271e-01 -9.26070750e-01 -1.26267478e-01 -3.58914733e-01 -9.24780965e-01 -1.26267478e-01 -3.62057567e-01 -9.23562348e-01 -1.26267478e-01 -3.65188807e-01 -9.22325552e-01 -1.26267478e-01 -3.68400604e-01 -9.21046019e-01 -1.26267478e-01 -3.71632040e-01 -9.19747412e-01 -1.26267478e-01 -3.74912471e-01 -9.18411255e-01 -1.26267478e-01 -3.78136754e-01 -9.17093337e-01 -1.26267478e-01 -3.81252170e-01 -9.15802658e-01 -1.26267478e-01 -3.84422362e-01 -9.14475679e-01 -1.26267478e-01 -3.87618005e-01 -9.13124323e-01 -1.26267478e-01 -3.90882969e-01 -9.11728084e-01 -1.26267478e-01 -3.94064307e-01 -9.10364091e-01 -1.26267478e-01 -3.97228867e-01 -9.08985317e-01 -1.26267478e-01 -4.00433838e-01 -9.07581925e-01 -1.26267478e-01 -4.03512329e-01 -9.06214237e-01 -1.26267478e-01 -4.06747758e-01 -9.04765248e-01 -1.26267478e-01 -4.09911960e-01 -9.03340042e-01 -1.26267478e-01 -4.13040340e-01 -9.01905179e-01 -1.26267478e-01 -4.16198105e-01 -9.00460482e-01 -1.26267478e-01 -4.19242322e-01 -8.99044156e-01 -1.26267478e-01 -4.22383130e-01 -8.97572875e-01 -1.26267478e-01 -4.25609529e-01 -8.96046579e-01 -1.26267478e-01 -4.28731143e-01 -8.94560456e-01 -1.26267478e-01 -4.31769550e-01 -8.93098414e-01 -1.26267478e-01 -4.34958190e-01 -8.91546309e-01 -1.26267478e-01 -4.38160926e-01 -8.89977813e-01 -1.26267478e-01 -4.41187024e-01 -8.88484359e-01 -1.26267478e-01 -4.44200695e-01 -8.86980236e-01 -1.26267478e-01 -4.47288781e-01 -8.85426700e-01 -1.26267478e-01 -4.50391591e-01 -8.83851945e-01 -1.26267478e-01 -4.53541487e-01 -8.82236540e-01 -1.26267478e-01 -4.56616253e-01 -8.80654097e-01 -1.26267478e-01 -4.59594041e-01 -8.79102588e-01 -1.26267478e-01 -4.62677598e-01 -8.77482414e-01 -1.26267478e-01 -4.65731412e-01 -8.75864744e-01 -1.26267478e-01 -4.68856871e-01 -8.74194801e-01 -1.26267478e-01 -4.71926063e-01 -8.72545600e-01 -1.26267478e-01 -4.74947244e-01 -8.70902061e-01 -1.26267478e-01 -4.78000015e-01 -8.69234145e-01 -1.26267478e-01 -4.81019765e-01 -8.67559016e-01 -1.26267478e-01 -4.84113663e-01 -8.65839243e-01 -1.26267478e-01 -4.87064630e-01 -8.64187300e-01 -1.26267478e-01 -4.90063608e-01 -8.62484336e-01 -1.26267478e-01 -4.93064791e-01 -8.60778809e-01 -1.26267478e-01 -4.96013433e-01 -8.59078228e-01 -1.26267478e-01 -4.99082863e-01 -8.57296169e-01 -1.26267478e-01 -5.02084553e-01 -8.55550289e-01 -1.26267478e-01 -5.05054235e-01 -8.53792131e-01 -1.26267478e-01 -5.08035123e-01 -8.52027893e-01 -1.26267478e-01 -5.10984600e-01 -8.50256324e-01 -1.26267478e-01 -5.13972640e-01 -8.48458052e-01 -1.26267478e-01 -5.16916096e-01 -8.46665919e-01 -1.26267478e-01 -5.19959569e-01 -8.44800174e-01 -1.26267478e-01 -5.22838175e-01 -8.43026042e-01 -1.26267478e-01 -5.25671184e-01 -8.41258585e-01 -1.26267478e-01 -5.28696895e-01 -8.39355826e-01 -1.26267478e-01 -5.31703174e-01 -8.37458134e-01 -1.26267478e-01 -5.34621477e-01 -8.35598946e-01 -1.26267478e-01 -5.37462175e-01 -8.33777487e-01 -1.26267478e-01 -5.40294349e-01 -8.31941545e-01 -1.26267478e-01 -5.43208539e-01 -8.30040157e-01 -1.26267478e-01 -5.46094179e-01 -8.28147888e-01 -1.26267478e-01 -5.48969209e-01 -8.26241732e-01 -1.26267478e-01 -5.51849067e-01 -8.24322581e-01 -1.26267478e-01 -5.54792404e-01 -8.22342217e-01 -1.26267478e-01 -5.57697356e-01 -8.20378900e-01 -1.26267478e-01 -5.60476005e-01 -8.18484128e-01 -1.26267478e-01 -5.63379645e-01 -8.16483080e-01 -1.26267478e-01 -5.66238701e-01 -8.14511061e-01 -1.26267478e-01 -5.69064200e-01 -8.12529206e-01 -1.26267478e-01 -5.71998298e-01 -8.10472608e-01 -1.26267478e-01 -5.74741721e-01 -8.08531344e-01 -1.26267478e-01 -5.77525973e-01 -8.06540012e-01 -1.26267478e-01 -5.80333650e-01 -8.04523408e-01 -1.26267478e-01 -5.83140850e-01 -8.02490056e-01 -1.26267478e-01 -5.86031556e-01 -8.00382316e-01 -1.26267478e-01 -5.88838696e-01 -7.98318624e-01 -1.26267478e-01 -5.91556907e-01 -7.96312034e-01 -1.26267478e-01 -5.94230413e-01 -7.94312716e-01 -1.26267478e-01 -5.97011328e-01 -7.92226791e-01 -1.26267478e-01 -5.99838197e-01 -7.90086448e-01 -1.26267478e-01 -6.02608919e-01 -7.87982285e-01 -1.26267478e-01 -6.05351031e-01 -7.85867274e-01 -1.26267478e-01 -6.08110666e-01 -7.83743799e-01 -1.26267478e-01 -6.10746026e-01 -7.81686485e-01 -1.26267478e-01 -6.13553405e-01 -7.79483020e-01 -1.26267478e-01 -6.16280198e-01 -7.77333856e-01 -1.26267478e-01 -6.18978739e-01 -7.75181592e-01 -1.26267478e-01 -6.21702313e-01 -7.73005486e-01 -1.26267478e-01 -6.24314666e-01 -7.70895600e-01 -1.26267478e-01 -6.27060831e-01 -7.68657565e-01 -1.26267478e-01 -6.29760861e-01 -7.66454577e-01 -1.26267478e-01 -6.32357359e-01 -7.64310300e-01 -1.26267478e-01 -6.35014832e-01 -7.62104750e-01 -1.26267478e-01 -6.37719512e-01 -7.59839535e-01 -1.26267478e-01 -6.40447021e-01 -7.57543862e-01 -1.26267478e-01 -6.43041074e-01 -7.55344391e-01 -1.26267478e-01 -6.45589888e-01 -7.53165781e-01 -1.26267478e-01 -6.48222029e-01 -7.50903368e-01 -1.26267478e-01 -6.50897980e-01 -7.48580635e-01 -1.26267478e-01 -6.53568864e-01 -7.46251822e-01 -1.26267478e-01 -6.56123102e-01 -7.44011998e-01 -1.26267478e-01 -6.58636570e-01 -7.41785169e-01 -1.26267478e-01 -6.61213458e-01 -7.39487112e-01 -1.26267478e-01 -6.63796484e-01 -7.37170160e-01 -1.26267478e-01 -6.66435897e-01 -7.34783053e-01 -1.26267478e-01 -6.69012189e-01 -7.32443035e-01 -1.26267478e-01 -6.71548069e-01 -7.30116904e-01 -1.26267478e-01 -6.74090087e-01 -7.27772951e-01 -1.26267478e-01 -6.76612020e-01 -7.25420594e-01 -1.26267478e-01 -6.79216027e-01 -7.22987711e-01 -1.26267478e-01 -6.81676149e-01 -7.20670223e-01 -1.26267478e-01 -6.84178591e-01 -7.18292892e-01 -1.26267478e-01 -6.86692953e-01 -7.15888500e-01 -1.26267478e-01 -6.89122498e-01 -7.13560224e-01 -1.26267478e-01 -6.91628873e-01 -7.11129367e-01 -1.26267478e-01 -6.94111705e-01 -7.08703756e-01 -1.26267478e-01 -6.96553767e-01 -7.06304669e-01 -1.26267478e-01 -6.99006379e-01 -7.03879893e-01 -1.26267478e-01 -7.01506734e-01 -7.01364756e-01 -1.26267478e-01 -7.03969121e-01 -6.98919177e-01 -1.26267478e-01 -7.06408978e-01 -6.96444213e-01 -1.26267478e-01 -7.08843231e-01 -6.93971574e-01 -1.26267478e-01 -7.11193442e-01 -6.91561401e-01 -1.26267478e-01 -7.13620603e-01 -6.89058423e-01 -1.26267478e-01 -7.16068625e-01 -6.86496317e-01 -1.26267478e-01 -7.18479872e-01 -6.83988988e-01 -1.26267478e-01 -7.20861614e-01 -6.81466818e-01 -1.26267478e-01 -7.23213255e-01 -6.78977728e-01 -1.26267478e-01 -7.25495100e-01 -6.76535845e-01 -1.26267478e-01 -7.27891564e-01 -6.73955739e-01 -1.26267478e-01 -7.30325460e-01 -6.71320617e-01 -1.26267478e-01 -7.32625782e-01 -6.68814242e-01 -1.26267478e-01 -7.34868586e-01 -6.66343868e-01 -1.26267478e-01 -7.37192810e-01 -6.63772404e-01 -1.26267478e-01 -7.39572108e-01 -6.61113262e-01 -1.26267478e-01 -7.41899788e-01 -6.58513546e-01 -1.26267478e-01 -7.44174600e-01 -6.55930698e-01 -1.26267478e-01 -7.46459067e-01 -6.53335929e-01 -1.26267478e-01 -7.48730481e-01 -6.50724828e-01 -1.26267478e-01 -7.51057804e-01 -6.48041964e-01 -1.26267478e-01 -7.53275394e-01 -6.45466685e-01 -1.26267478e-01 -7.55458474e-01 -6.42904222e-01 -1.26267478e-01 -7.57694662e-01 -6.40272558e-01 -1.26267478e-01 -7.59963751e-01 -6.37572110e-01 -1.26267478e-01 -7.62237966e-01 -6.34853899e-01 -1.26267478e-01 -7.64427245e-01 -6.32216871e-01 -1.26267478e-01 -7.66576469e-01 -6.29611015e-01 -1.26267478e-01 -7.68769920e-01 -6.26927316e-01 -1.26267478e-01 -7.70946264e-01 -6.24250948e-01 -1.26267478e-01 -7.73171067e-01 -6.21487200e-01 -1.26267478e-01 -7.75407195e-01 -6.18699253e-01 -1.26267478e-01 -7.77559876e-01 -6.15990818e-01 -1.26267478e-01 -7.79648125e-01 -6.13352060e-01 -1.26267478e-01 -7.81710446e-01 -6.10718369e-01 -1.26267478e-01 -7.83897817e-01 -6.07899964e-01 -1.26267478e-01 -7.86071301e-01 -6.05093777e-01 -1.26267478e-01 -7.88180172e-01 -6.02341175e-01 -1.26267478e-01 -7.90249228e-01 -5.99630535e-01 -1.26267478e-01 -7.92264223e-01 -5.96964657e-01 -1.26267478e-01 -7.94391513e-01 -5.94122648e-01 -1.26267478e-01 -7.96477795e-01 -5.91331065e-01 -1.26267478e-01 -7.98485637e-01 -5.88611543e-01 -1.26267478e-01 -8.00538480e-01 -5.85819781e-01 -1.26267478e-01 -8.02594721e-01 -5.82995951e-01 -1.26267478e-01 -8.04673851e-01 -5.80121100e-01 -1.26267478e-01 -8.06678057e-01 -5.77341139e-01 -1.26267478e-01 -8.08631957e-01 -5.74594676e-01 -1.26267478e-01 -8.10629785e-01 -5.71776628e-01 -1.26267478e-01 -8.12637210e-01 -5.68914652e-01 -1.26267478e-01 -8.14660013e-01 -5.66012383e-01 -1.26267478e-01 -8.16623211e-01 -5.63186407e-01 -1.26267478e-01 -8.18533242e-01 -5.60401201e-01 -1.26267478e-01 -8.20468664e-01 -5.57563484e-01 -1.26267478e-01 -8.22401226e-01 -5.54711282e-01 -1.26267478e-01 -8.24380636e-01 -5.51755011e-01 -1.26267478e-01 -8.26320469e-01 -5.48856556e-01 -1.26267478e-01 -8.28222632e-01 -5.45972228e-01 -1.26267478e-01 -8.30145359e-01 -5.43053925e-01 -1.26267478e-01 -8.31965089e-01 -5.40258348e-01 -1.26267478e-01 -8.33846688e-01 -5.37349641e-01 -1.26267478e-01 -8.35756481e-01 -5.34367740e-01 -1.26267478e-01 -8.37653041e-01 -5.31399190e-01 -1.26267478e-01 -8.39451551e-01 -5.28556585e-01 -1.26267478e-01 -8.41257989e-01 -5.25669098e-01 -1.26267478e-01 -8.43111813e-01 -5.22695363e-01 -1.26267478e-01 -8.44927311e-01 -5.19751966e-01 -1.26267478e-01 -8.46740186e-01 -5.16799152e-01 -1.26267478e-01 -8.48534763e-01 -5.13842702e-01 -1.26267478e-01 -8.50367367e-01 -5.10799766e-01 -1.26267478e-01 -8.52199912e-01 -5.07737577e-01 -1.26267478e-01 -8.53924394e-01 -5.04837453e-01 -1.26267478e-01 -8.55672717e-01 -5.01860559e-01 -1.26267478e-01 -8.57428670e-01 -4.98863995e-01 -1.26267478e-01 -8.59135509e-01 -4.95913148e-01 -1.26267478e-01 -8.60855937e-01 -4.92925495e-01 -1.26267478e-01 -8.62545073e-01 -4.89959002e-01 -1.26267478e-01 -8.64247203e-01 -4.86956686e-01 -1.26267478e-01 -8.65943968e-01 -4.83927786e-01 -1.26267478e-01 -8.67624938e-01 -4.80902135e-01 -1.26267478e-01 -8.69330823e-01 -4.77814019e-01 -1.26267478e-01 -8.71022642e-01 -4.74732131e-01 -1.26267478e-01 -8.72645795e-01 -4.71736819e-01 -1.26267478e-01 -8.74256909e-01 -4.68743563e-01 -1.26267478e-01 -8.75918448e-01 -4.65624362e-01 -1.26267478e-01 -8.77588570e-01 -4.62472975e-01 -1.26267478e-01 -8.79185855e-01 -4.59436178e-01 -1.26267478e-01 -8.80740106e-01 -4.56447124e-01 -1.26267478e-01 -8.82294357e-01 -4.53435838e-01 -1.26267478e-01 -8.83903086e-01 -4.50283289e-01 -1.26267478e-01 -8.85529697e-01 -4.47082162e-01 -1.26267478e-01 -8.87044728e-01 -4.44074184e-01 -1.26267478e-01 -8.88535142e-01 -4.41076845e-01 -1.26267478e-01 -8.90060246e-01 -4.37992454e-01 -1.26267478e-01 -8.91587317e-01 -4.34879094e-01 -1.26267478e-01 -8.93143892e-01 -4.31664854e-01 -1.26267478e-01 -8.94694269e-01 -4.28444505e-01 -1.26267478e-01 -8.96158099e-01 -4.25382048e-01 -1.26267478e-01 -8.97589922e-01 -4.22344685e-01 -1.26267478e-01 -8.99051487e-01 -4.19228762e-01 -1.26267478e-01 -9.00549173e-01 -4.15995777e-01 -1.26267478e-01 -9.02020097e-01 -4.12805527e-01 -1.26267478e-01 -9.03409958e-01 -4.09756809e-01 -1.26267478e-01 -9.04817224e-01 -4.06633526e-01 -1.26267478e-01 -9.06227767e-01 -4.03482378e-01 -1.26267478e-01 -9.07677710e-01 -4.00201201e-01 -1.26267478e-01 -9.09117997e-01 -3.96930069e-01 -1.26267478e-01 -9.10489261e-01 -3.93772840e-01 -1.26267478e-01 -9.11857843e-01 -3.90579849e-01 -1.26267478e-01 -9.13184941e-01 -3.87482971e-01 -1.26267478e-01 -9.14490223e-01 -3.84384662e-01 -1.26267478e-01 -9.15832698e-01 -3.81174505e-01 -1.26267478e-01 -9.17190135e-01 -3.77890468e-01 -1.26267478e-01 -9.18511808e-01 -3.74684453e-01 -1.26267478e-01 -9.19774890e-01 -3.71564150e-01 -1.26267478e-01 -9.21097815e-01 -3.68262172e-01 -1.26267478e-01 -9.22382057e-01 -3.65049452e-01 -1.26267478e-01 -9.23618436e-01 -3.61907661e-01 -1.26267478e-01 -9.24871624e-01 -3.58676553e-01 -1.26267478e-01 -9.26129639e-01 -3.55433017e-01 -1.26267478e-01 -9.27394569e-01 -3.52103829e-01 -1.26267478e-01 -9.28604245e-01 -3.48897427e-01 -1.26267478e-01 -9.29781139e-01 -3.45739663e-01 -1.26267478e-01 -9.31019664e-01 -3.42396319e-01 -1.26267478e-01 -9.32251155e-01 -3.39052290e-01 -1.26267478e-01 -9.33422506e-01 -3.35806370e-01 -1.26267478e-01 -9.34565425e-01 -3.32625866e-01 -1.26267478e-01 -9.35707688e-01 -3.29381973e-01 -1.26267478e-01 -9.36865509e-01 -3.26086164e-01 -1.26267478e-01 -9.37961340e-01 -3.22916478e-01 -1.26267478e-01 -9.39079940e-01 -3.19642335e-01 -1.26267478e-01 -9.40190375e-01 -3.16365510e-01 -1.26267478e-01 -9.41319942e-01 -3.12979221e-01 -1.26267478e-01 -9.42418158e-01 -3.09677303e-01 -1.26267478e-01 -9.43456352e-01 -3.06491792e-01 -1.26267478e-01 -9.44540441e-01 -3.03122759e-01 -1.26267478e-01 -9.45599377e-01 -2.99819708e-01 -1.26267478e-01 -9.46629345e-01 -2.96543866e-01 -1.26267478e-01 -9.47668552e-01 -2.93214291e-01 -1.26267478e-01 -9.48683321e-01 -2.89899617e-01 -1.26267478e-01 -9.49714124e-01 -2.86505640e-01 -1.26267478e-01 -9.50691819e-01 -2.83258259e-01 -1.26267478e-01 -9.51665223e-01 -2.79959738e-01 -1.26267478e-01 -9.52641368e-01 -2.76637316e-01 -1.26267478e-01 -9.53596652e-01 -2.73300916e-01 -1.26267478e-01 -9.54551101e-01 -2.69969046e-01 -1.26267478e-01 -9.55462813e-01 -2.66719788e-01 -1.26267478e-01 -9.56389010e-01 -2.63377249e-01 -1.26267478e-01 -9.57301676e-01 -2.60045022e-01 -1.26267478e-01 -9.58222926e-01 -2.56614745e-01 -1.26267478e-01 -9.59142923e-01 -2.53168225e-01 -1.26267478e-01 -9.60017681e-01 -2.49824718e-01 -1.26267478e-01 -9.60864484e-01 -2.46566743e-01 -1.26267478e-01 -9.61682558e-01 -2.43330792e-01 -1.26267478e-01 -9.62547898e-01 -2.39875272e-01 -1.26267478e-01 -9.63410676e-01 -2.36410782e-01 -1.26267478e-01 -9.64228570e-01 -2.33059049e-01 -1.26267478e-01 -9.65019763e-01 -2.29769558e-01 -1.26267478e-01 -9.65789199e-01 -2.26497591e-01 -1.26267478e-01 -9.66588497e-01 -2.23039165e-01 -1.26267478e-01 -9.67394769e-01 -2.19534293e-01 -1.26267478e-01 -9.68134463e-01 -2.16262281e-01 -1.26267478e-01 -9.68875110e-01 -2.12888852e-01 -1.26267478e-01 -9.69618678e-01 -2.09502250e-01 -1.26267478e-01 -9.70318735e-01 -2.06218243e-01 -1.26267478e-01 -9.71052468e-01 -2.02736899e-01 -1.26267478e-01 -9.71778810e-01 -1.99233532e-01 -1.26267478e-01 -9.72455323e-01 -1.95918337e-01 -1.26267478e-01 -9.73107576e-01 -1.92633376e-01 -1.26267478e-01 -9.73774374e-01 -1.89242244e-01 -1.26267478e-01 -9.74439859e-01 -1.85764194e-01 -1.26267478e-01 -9.75109041e-01 -1.82243928e-01 -1.26267478e-01 -9.75723922e-01 -1.78918049e-01 -1.26267478e-01 -9.76325572e-01 -1.75627500e-01 -1.26267478e-01 -9.76933599e-01 -1.72209784e-01 -1.26267478e-01 -9.77534592e-01 -1.68711990e-01 -1.26267478e-01 -9.78137672e-01 -1.65210500e-01 -1.26267478e-01 -9.78694022e-01 -1.61899880e-01 -1.26267478e-01 -9.79250848e-01 -1.58461258e-01 -1.26267478e-01 -9.79805350e-01 -1.55035943e-01 -1.26267478e-01 -9.80329275e-01 -1.51648179e-01 -1.26267478e-01 -9.80857849e-01 -1.48215398e-01 -1.26267478e-01 -9.81361866e-01 -1.44818619e-01 -1.26267478e-01 -9.81867909e-01 -1.41371951e-01 -1.26267478e-01 -9.82341230e-01 -1.38031110e-01 -1.26267478e-01 -9.82825756e-01 -1.34536415e-01 -1.26267478e-01 -9.83294845e-01 -1.31079316e-01 -1.26267478e-01 -9.83740270e-01 -1.27655432e-01 -1.26267478e-01 -9.84185040e-01 -1.24224849e-01 -1.26267478e-01 -9.84600246e-01 -1.20868839e-01 -1.26267478e-01 -9.85022128e-01 -1.17354758e-01 -1.26267478e-01 -9.85430360e-01 -1.13923483e-01 -1.26267478e-01 -9.85808849e-01 -1.10579729e-01 -1.26267478e-01 -9.86198962e-01 -1.07010432e-01 -1.26267478e-01 -9.86579359e-01 -1.03487663e-01 -1.26267478e-01 -9.86930311e-01 -1.00064635e-01 -1.26267478e-01 -9.87271130e-01 -9.66993347e-02 -1.26267493e-01 -9.87597942e-01 -9.32582840e-02 -1.26267478e-01 -9.87924159e-01 -8.97959843e-02 -1.26267493e-01 -9.88220274e-01 -8.64596739e-02 -1.26267478e-01 -9.88514602e-01 -8.30090865e-02 -1.26267478e-01 -9.88801897e-01 -7.95651153e-02 -1.26267493e-01 -9.89080369e-01 -7.60463774e-02 -1.26267567e-01 -9.89343226e-01 -7.25441203e-02 -1.26267567e-01 -9.89580214e-01 -6.92310035e-02 -1.26267567e-01 -9.89822209e-01 -6.56697527e-02 -1.26267612e-01 -9.90052640e-01 -6.20812029e-02 -1.26267761e-01 -9.90255237e-01 -5.87221310e-02 -1.26267955e-01 -9.90433156e-01 -5.56552410e-02 -1.26268297e-01 -9.90584612e-01 -5.28968722e-02 -1.26268223e-01 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. 0. 0. -9.91896927e-01 -1.40237967e-02 -1.26268238e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.93152976e-01 4.66621257e-02 -1.07097045e-01 -9.93056536e-01 4.86633368e-02 -1.07097037e-01 -9.92841005e-01 5.28604500e-02 -1.07096940e-01 -9.92682636e-01 5.59013858e-02 -1.07097417e-01 -9.92489219e-01 5.92753999e-02 -1.07095934e-01 -9.92280900e-01 6.26456365e-02 -1.07095703e-01 -9.92058098e-01 6.61121309e-02 -1.07095674e-01 -9.91823733e-01 6.95094466e-02 -1.07095711e-01 -9.91585672e-01 7.28568956e-02 -1.07095793e-01 -9.91320193e-01 7.63898790e-02 -1.07096076e-01 -9.91038084e-01 7.99557865e-02 -1.07095867e-01 -9.90761280e-01 8.33207592e-02 -1.07095681e-01 -9.90466177e-01 8.67647827e-02 -1.07096106e-01 -9.90148902e-01 9.03076530e-02 -1.07095800e-01 -9.89834368e-01 9.36972052e-02 -1.07095785e-01 -9.89498138e-01 9.71820280e-02 -1.07095987e-01 -9.89159763e-01 1.00576073e-01 -1.07095674e-01 -9.88813639e-01 1.03920281e-01 -1.07095793e-01 -9.88433003e-01 1.07470691e-01 -1.07096195e-01 -9.88040864e-01 1.11031234e-01 -1.07095875e-01 -9.87644970e-01 1.14484526e-01 -1.07095934e-01 -9.87237632e-01 1.17945716e-01 -1.07095927e-01 -9.86824036e-01 1.21361114e-01 -1.07095845e-01 -9.86397088e-01 1.24800645e-01 -1.07095852e-01 -9.85952258e-01 1.28254905e-01 -1.07096009e-01 -9.85490739e-01 1.31745756e-01 -1.07095987e-01 -9.85040486e-01 1.35080397e-01 -1.07095703e-01 -9.84580755e-01 1.38393253e-01 -1.07095875e-01 -9.84076798e-01 1.41923159e-01 -1.07096262e-01 -9.83559847e-01 1.45458728e-01 -1.07095793e-01 -9.83047068e-01 1.48882404e-01 -1.07095934e-01 -9.82520998e-01 1.52326152e-01 -1.07095852e-01 -9.81983840e-01 1.55754119e-01 -1.07095845e-01 -9.81448174e-01 1.59088969e-01 -1.07095681e-01 -9.80889618e-01 1.62505567e-01 -1.07096180e-01 -9.80295718e-01 1.66049287e-01 -1.07095882e-01 -9.79724407e-01 1.69381738e-01 -1.07095681e-01 -9.79132891e-01 1.72788590e-01 -1.07096113e-01 -9.78504598e-01 1.76313013e-01 -1.07095934e-01 -9.77877676e-01 1.79728925e-01 -1.07095867e-01 -9.77245867e-01 1.83145657e-01 -1.07095934e-01 -9.76618409e-01 1.86453491e-01 -1.07095681e-01 -9.75984275e-01 1.89743072e-01 -1.07095867e-01 -9.75294590e-01 1.93264887e-01 -1.07096247e-01 -9.74590898e-01 1.96785718e-01 -1.07095920e-01 -9.73895371e-01 2.00196862e-01 -1.07095920e-01 -9.73211288e-01 2.03494444e-01 -1.07095681e-01 -9.72499430e-01 2.06879586e-01 -1.07096225e-01 -9.71747100e-01 2.10381731e-01 -1.07095867e-01 -9.71023917e-01 2.13681579e-01 -1.07095681e-01 -9.70280230e-01 2.17051879e-01 -1.07096203e-01 -9.69510078e-01 2.20457315e-01 -1.07095674e-01 -9.68757510e-01 2.23737657e-01 -1.07095867e-01 -9.67954576e-01 2.27202728e-01 -1.07096247e-01 -9.67129529e-01 2.30682701e-01 -1.07095867e-01 -9.66327846e-01 2.34023407e-01 -1.07095771e-01 -9.65501964e-01 2.37399250e-01 -1.07095964e-01 -9.64658678e-01 2.40795270e-01 -1.07095964e-01 -9.63835835e-01 2.44070426e-01 -1.07095681e-01 -9.62981701e-01 2.47420862e-01 -1.07096203e-01 -9.62090194e-01 2.50869423e-01 -1.07095808e-01 -9.61229742e-01 2.54147798e-01 -1.07095689e-01 -9.60337877e-01 2.57495582e-01 -1.07096091e-01 -9.59416151e-01 2.60910898e-01 -1.07095867e-01 -9.58493888e-01 2.64269322e-01 -1.07095905e-01 -9.57567811e-01 2.67617047e-01 -1.07095934e-01 -9.56644535e-01 2.70894140e-01 -1.07095681e-01 -9.55700517e-01 2.74202377e-01 -1.07096113e-01 -9.54732478e-01 2.77554482e-01 -1.07095681e-01 -9.53764260e-01 2.80866206e-01 -1.07096180e-01 -9.52749670e-01 2.84291148e-01 -1.07095920e-01 -9.51772988e-01 2.87535369e-01 -1.07095681e-01 -9.50767338e-01 2.90846944e-01 -1.07096270e-01 -9.49716926e-01 2.94261903e-01 -1.07095823e-01 -9.48694885e-01 2.97541797e-01 -1.07095711e-01 -9.47649479e-01 3.00851703e-01 -1.07095838e-01 -9.46611762e-01 3.04105073e-01 -1.07095674e-01 -9.45576370e-01 3.07301700e-01 -1.07095785e-01 -9.44474638e-01 3.10673982e-01 -1.07096106e-01 -9.43346024e-01 3.14083070e-01 -1.07095867e-01 -9.42239285e-01 3.17390591e-01 -1.07095830e-01 -9.41127717e-01 3.20670545e-01 -1.07095934e-01 -9.40013289e-01 3.23927671e-01 -1.07095785e-01 -9.38892901e-01 3.27153862e-01 -1.07095748e-01 -9.37749267e-01 3.30418766e-01 -1.07096024e-01 -9.36567903e-01 3.33757371e-01 -1.07095845e-01 -9.35420394e-01 3.36954713e-01 -1.07095681e-01 -9.34279084e-01 3.40112895e-01 -1.07095838e-01 -9.33050692e-01 3.43453079e-01 -1.07096091e-01 -9.31809843e-01 3.46791416e-01 -1.07095860e-01 -9.30588484e-01 3.50060463e-01 -1.07095838e-01 -9.29377258e-01 3.53274763e-01 -1.07095808e-01 -9.28175926e-01 3.56441319e-01 -1.07095733e-01 -9.26932037e-01 3.59644711e-01 -1.07095912e-01 -9.25652921e-01 3.62931103e-01 -1.07096061e-01 -9.24351513e-01 3.66232753e-01 -1.07095808e-01 -9.23100352e-01 3.69372010e-01 -1.07095703e-01 -9.21809137e-01 3.72583538e-01 -1.07096180e-01 -9.20475483e-01 3.75869334e-01 -1.07095867e-01 -9.19155419e-01 3.79078299e-01 -1.07095748e-01 -9.17832673e-01 3.82272691e-01 -1.07095771e-01 -9.16526318e-01 3.85395348e-01 -1.07095681e-01 -9.15207326e-01 3.88516068e-01 -1.07095920e-01 -9.13810611e-01 3.91782910e-01 -1.07096106e-01 -9.12392437e-01 3.95083100e-01 -1.07095793e-01 -9.11020577e-01 3.98238569e-01 -1.07095823e-01 -9.09622729e-01 4.01420265e-01 -1.07095934e-01 -9.08211708e-01 4.04602289e-01 -1.07095890e-01 -9.06799793e-01 4.07757282e-01 -1.07095838e-01 -9.05402362e-01 4.10848796e-01 -1.07095681e-01 -9.03970420e-01 4.13985759e-01 -1.07096083e-01 -9.02485728e-01 4.17216331e-01 -1.07095875e-01 -9.01059449e-01 4.20288414e-01 -1.07095674e-01 -8.99596989e-01 4.23409313e-01 -1.07096121e-01 -8.98073792e-01 4.26632911e-01 -1.07095882e-01 -8.96577895e-01 4.29763913e-01 -1.07095852e-01 -8.95073891e-01 4.32895094e-01 -1.07095875e-01 -8.93582165e-01 4.35966104e-01 -1.07095696e-01 -8.92108202e-01 4.38967735e-01 -1.07095800e-01 -8.90534759e-01 4.42152530e-01 -1.07096106e-01 -8.88945282e-01 4.45337176e-01 -1.07095897e-01 -8.87386143e-01 4.48440343e-01 -1.07095882e-01 -8.85808170e-01 4.51548815e-01 -1.07095860e-01 -8.84246171e-01 4.54600871e-01 -1.07095778e-01 -8.82657230e-01 4.57673371e-01 -1.07095689e-01 -8.81052434e-01 4.60757047e-01 -1.07095800e-01 -8.79437447e-01 4.63836998e-01 -1.07095808e-01 -8.77846658e-01 4.66838062e-01 -1.07095681e-01 -8.76258194e-01 4.69813883e-01 -1.07095815e-01 -8.74580920e-01 4.72928315e-01 -1.07096091e-01 -8.72878313e-01 4.76065785e-01 -1.07095756e-01 -8.71212304e-01 4.79107291e-01 -1.07095920e-01 -8.69523108e-01 4.82157260e-01 -1.07095756e-01 -8.67846012e-01 4.85171199e-01 -1.07095778e-01 -8.66160631e-01 4.88179028e-01 -1.07095808e-01 -8.64444494e-01 4.91210133e-01 -1.07095964e-01 -8.62705648e-01 4.94257927e-01 -1.07095845e-01 -8.61022115e-01 4.97185022e-01 -1.07095681e-01 -8.59289467e-01 5.00174224e-01 -1.07096054e-01 -8.57538760e-01 5.03168046e-01 -1.07095703e-01 -8.55775833e-01 5.06161153e-01 -1.07096106e-01 -8.53954077e-01 5.09228349e-01 -1.07095845e-01 -8.52165401e-01 5.12216151e-01 -1.07095852e-01 -8.50376368e-01 5.15178084e-01 -1.07095771e-01 -8.48568201e-01 5.18157721e-01 -1.07095934e-01 -8.46753240e-01 5.21114171e-01 -1.07095875e-01 -8.44929814e-01 5.24070144e-01 -1.07095845e-01 -8.43147695e-01 5.26930153e-01 -1.07095696e-01 -8.41318190e-01 5.29844642e-01 -1.07096203e-01 -8.39417577e-01 5.32849371e-01 -1.07095711e-01 -8.37542772e-01 5.35792708e-01 -1.07096009e-01 -8.35646808e-01 5.38742304e-01 -1.07095748e-01 -8.33776355e-01 5.41634321e-01 -1.07095748e-01 -8.31933796e-01 5.44458210e-01 -1.07095681e-01 -8.30020487e-01 5.47373235e-01 -1.07096076e-01 -8.28039169e-01 5.50362110e-01 -1.07095920e-01 -8.26106668e-01 5.53262770e-01 -1.07095875e-01 -8.24210525e-01 5.56084633e-01 -1.07095674e-01 -8.22324991e-01 5.58866739e-01 -1.07095741e-01 -8.20360243e-01 5.61749339e-01 -1.07096009e-01 -8.18337679e-01 5.64692497e-01 -1.07095897e-01 -8.16339612e-01 5.67574501e-01 -1.07095793e-01 -8.14401031e-01 5.70348561e-01 -1.07095703e-01 -8.12411129e-01 5.73187411e-01 -1.07096180e-01 -8.10325325e-01 5.76126099e-01 -1.07095808e-01 -8.08313489e-01 5.78948498e-01 -1.07095808e-01 -8.06277931e-01 5.81775010e-01 -1.07095771e-01 -8.04246902e-01 5.84583819e-01 -1.07095748e-01 -8.02227736e-01 5.87350070e-01 -1.07095741e-01 -8.00237775e-01 5.90057909e-01 -1.07095703e-01 -7.98159897e-01 5.92864811e-01 -1.07096151e-01 -7.96023071e-01 5.95731258e-01 -1.07095890e-01 -7.93995619e-01 5.98432899e-01 -1.07095726e-01 -7.91909933e-01 6.01191342e-01 -1.07096195e-01 -7.89737165e-01 6.04042947e-01 -1.07095778e-01 -7.87634134e-01 6.06780231e-01 -1.07095830e-01 -7.85495758e-01 6.09544992e-01 -1.07095674e-01 -7.83380806e-01 6.12262070e-01 -1.07095681e-01 -7.81312108e-01 6.14900410e-01 -1.07095674e-01 -7.79125631e-01 6.17667496e-01 -1.07096180e-01 -7.76880324e-01 6.20492399e-01 -1.07095934e-01 -7.74709225e-01 6.23199940e-01 -1.07095741e-01 -7.72530198e-01 6.25899196e-01 -1.07095703e-01 -7.70414472e-01 6.28498256e-01 -1.07095703e-01 -7.68231392e-01 6.31167412e-01 -1.07095897e-01 -7.65961349e-01 6.33920491e-01 -1.07095681e-01 -7.63734519e-01 6.36599898e-01 -1.07095703e-01 -7.61576116e-01 6.39181674e-01 -1.07095741e-01 -7.59333134e-01 6.41844511e-01 -1.07096083e-01 -7.56998777e-01 6.44593954e-01 -1.07095756e-01 -7.54748106e-01 6.47230268e-01 -1.07095771e-01 -7.52482116e-01 6.49865150e-01 -1.07095890e-01 -7.50217974e-01 6.52474701e-01 -1.07095733e-01 -7.47991562e-01 6.55026913e-01 -1.07095689e-01 -7.45773256e-01 6.57549500e-01 -1.07095748e-01 -7.43401349e-01 6.60231054e-01 -1.07096002e-01 -7.41038740e-01 6.62883520e-01 -1.07095852e-01 -7.38768637e-01 6.65409207e-01 -1.07095703e-01 -7.36447990e-01 6.67981505e-01 -1.07095979e-01 -7.34052777e-01 6.70608699e-01 -1.07095771e-01 -7.31722355e-01 6.73154414e-01 -1.07095748e-01 -7.29344726e-01 6.75729692e-01 -1.07095674e-01 -7.27045178e-01 6.78199828e-01 -1.07095681e-01 -7.24762261e-01 6.80640399e-01 -1.07095674e-01 -7.22299933e-01 6.83251262e-01 -1.07095905e-01 -7.19859481e-01 6.85824156e-01 -1.07095696e-01 -7.17448652e-01 6.88340008e-01 -1.07095823e-01 -7.15055108e-01 6.90839708e-01 -1.07095785e-01 -7.12691903e-01 6.93274140e-01 -1.07095718e-01 -7.10278153e-01 6.95745170e-01 -1.07096046e-01 -7.07779646e-01 6.98287368e-01 -1.07095964e-01 -7.05343544e-01 7.00750947e-01 -1.07095800e-01 -7.02878535e-01 7.03205168e-01 -1.07095674e-01 -7.00510919e-01 7.05582142e-01 -1.07095689e-01 -6.98027194e-01 7.08038270e-01 -1.07096158e-01 -6.95487976e-01 7.10529208e-01 -1.07095785e-01 -6.92987442e-01 7.12970912e-01 -1.07095771e-01 -6.90520883e-01 7.15362132e-01 -1.07095696e-01 -6.88038170e-01 7.17737257e-01 -1.07095726e-01 -6.85581982e-01 7.20092297e-01 -1.07095711e-01 -6.83015406e-01 7.22522616e-01 -1.07096039e-01 -6.80442095e-01 7.24945962e-01 -1.07095711e-01 -6.77948415e-01 7.27275908e-01 -1.07095696e-01 -6.75432742e-01 7.29618371e-01 -1.07096054e-01 -6.72819197e-01 7.32030272e-01 -1.07095860e-01 -6.70314312e-01 7.34321833e-01 -1.07095696e-01 -6.67729378e-01 7.36675501e-01 -1.07095972e-01 -6.65182889e-01 7.38974750e-01 -1.07095696e-01 -6.62677824e-01 7.41221428e-01 -1.07095696e-01 -6.60020292e-01 7.43589520e-01 -1.07095934e-01 -6.57403946e-01 7.45902956e-01 -1.07095703e-01 -6.54790878e-01 7.48196781e-01 -1.07096091e-01 -6.52167320e-01 7.50486553e-01 -1.07095733e-01 -6.49577379e-01 7.52728939e-01 -1.07096106e-01 -6.46831155e-01 7.55090177e-01 -1.07095711e-01 -6.44196808e-01 7.57337987e-01 -1.07095711e-01 -6.41555011e-01 7.59577692e-01 -1.07095681e-01 -6.38983011e-01 7.61742771e-01 -1.07095703e-01 -6.36344790e-01 7.63948679e-01 -1.07095823e-01 -6.33626044e-01 7.66204119e-01 -1.07095711e-01 -6.30990446e-01 7.68378496e-01 -1.07096128e-01 -6.28210723e-01 7.70649493e-01 -1.07095674e-01 -6.25497401e-01 7.72854209e-01 -1.07095741e-01 -6.22869849e-01 7.74972022e-01 -1.07095718e-01 -6.20263577e-01 7.77062774e-01 -1.07095793e-01 -6.17451429e-01 7.79296756e-01 -1.07095867e-01 -6.14716649e-01 7.81456947e-01 -1.07095771e-01 -6.12028480e-01 7.83564687e-01 -1.07095994e-01 -6.09278977e-01 7.85704970e-01 -1.07095703e-01 -6.06584132e-01 7.87786305e-01 -1.07095778e-01 -6.03753269e-01 7.89957464e-01 -1.07095748e-01 -6.00931466e-01 7.92107344e-01 -1.07095681e-01 -5.98236084e-01 7.94144690e-01 -1.07095703e-01 -5.95483959e-01 7.96208918e-01 -1.07095972e-01 -5.92622817e-01 7.98341155e-01 -1.07095845e-01 -5.89828491e-01 8.00406992e-01 -1.07095696e-01 -5.87047517e-01 8.02448630e-01 -1.07095703e-01 -5.84292471e-01 8.04459572e-01 -1.07095718e-01 -5.81503391e-01 8.06474686e-01 -1.07096046e-01 -5.78598142e-01 8.08565795e-01 -1.07095748e-01 -5.75773060e-01 8.10578287e-01 -1.07095771e-01 -5.72923779e-01 8.12596560e-01 -1.07095771e-01 -5.70144653e-01 8.14545274e-01 -1.07095703e-01 -5.67333341e-01 8.16505909e-01 -1.07096009e-01 -5.64464927e-01 8.18494022e-01 -1.07095741e-01 -5.61610043e-01 8.20455253e-01 -1.07096076e-01 -5.58640003e-01 8.22478473e-01 -1.07095674e-01 -5.55762351e-01 8.24426413e-01 -1.07095681e-01 -5.52976966e-01 8.26296210e-01 -1.07095718e-01 -5.50082028e-01 8.28225970e-01 -1.07096031e-01 -5.47091782e-01 8.30206037e-01 -1.07095711e-01 -5.44268191e-01 8.32057655e-01 -1.07095726e-01 -5.41381896e-01 8.33939493e-01 -1.07096054e-01 -5.38438797e-01 8.35842609e-01 -1.07095718e-01 -5.35538077e-01 8.37704301e-01 -1.07096061e-01 -5.32518625e-01 8.39627028e-01 -1.07095741e-01 -5.29574037e-01 8.41489077e-01 -1.07095756e-01 -5.26722491e-01 8.43275011e-01 -1.07095681e-01 -5.23786426e-01 8.45104992e-01 -1.07096009e-01 -5.20769954e-01 8.46963704e-01 -1.07095741e-01 -5.17849207e-01 8.48755181e-01 -1.07095696e-01 -5.14895499e-01 8.50548744e-01 -1.07095957e-01 -5.11907041e-01 8.52350533e-01 -1.07095741e-01 -5.08975804e-01 8.54103744e-01 -1.07095793e-01 -5.05994022e-01 8.55872571e-01 -1.07095703e-01 -5.03075778e-01 8.57594430e-01 -1.07095674e-01 -5.00019431e-01 8.59379411e-01 -1.07095949e-01 -4.96925920e-01 8.61172020e-01 -1.07095681e-01 -4.93921012e-01 8.62898290e-01 -1.07095808e-01 -4.90922570e-01 8.64607215e-01 -1.07095674e-01 -4.87893283e-01 8.66322935e-01 -1.07095674e-01 -4.84872282e-01 8.68013918e-01 -1.07095733e-01 -4.81826454e-01 8.69707525e-01 -1.07095748e-01 -4.78836417e-01 8.71359587e-01 -1.07095703e-01 -4.75832492e-01 8.73004019e-01 -1.07096016e-01 -4.72705722e-01 8.74698639e-01 -1.07095815e-01 -4.69633132e-01 8.76353502e-01 -1.07095681e-01 -4.66579467e-01 8.77984285e-01 -1.07095696e-01 -4.63582069e-01 8.79570782e-01 -1.07095726e-01 -4.60501075e-01 8.81186068e-01 -1.07095875e-01 -4.57364410e-01 8.82817566e-01 -1.07095674e-01 -4.54266161e-01 8.84417534e-01 -1.07095681e-01 -4.51270878e-01 8.85948420e-01 -1.07095718e-01 -4.48217809e-01 8.87497544e-01 -1.07096031e-01 -4.45018977e-01 8.89106333e-01 -1.07095674e-01 -4.41899538e-01 8.90659750e-01 -1.07095711e-01 -4.38791990e-01 8.92195523e-01 -1.07095733e-01 -4.35731679e-01 8.93695474e-01 -1.07095703e-01 -4.32638854e-01 8.95197332e-01 -1.07095934e-01 -4.29487944e-01 8.96710336e-01 -1.07095681e-01 -4.26390201e-01 8.98187459e-01 -1.07095890e-01 -4.23146397e-01 8.99720609e-01 -1.07095711e-01 -4.20075804e-01 9.01159346e-01 -1.07095741e-01 -4.16925609e-01 9.02621031e-01 -1.07095905e-01 -4.13771182e-01 9.04069364e-01 -1.07095703e-01 -4.10618931e-01 9.05507803e-01 -1.07096039e-01 -4.07391906e-01 9.06964779e-01 -1.07095718e-01 -4.04208392e-01 9.08387780e-01 -1.07095674e-01 -4.01122451e-01 9.09754515e-01 -1.07095703e-01 -3.97995532e-01 9.11126792e-01 -1.07095674e-01 -3.94735605e-01 9.12543595e-01 -1.07095845e-01 -3.91487151e-01 9.13937509e-01 -1.07095756e-01 -3.88386667e-01 9.15262997e-01 -1.07095703e-01 -3.85279804e-01 9.16574657e-01 -1.07095674e-01 -3.82015169e-01 9.17940438e-01 -1.07096113e-01 -3.78773540e-01 9.19281662e-01 -1.07095681e-01 -3.75554055e-01 9.20601964e-01 -1.07095800e-01 -3.72381717e-01 9.21891391e-01 -1.07095703e-01 -3.69170129e-01 9.23180997e-01 -1.07095934e-01 -3.65882307e-01 9.24489915e-01 -1.07095733e-01 -3.62660587e-01 9.25758898e-01 -1.07095793e-01 -3.59417975e-01 9.27016854e-01 -1.07095674e-01 -3.56239110e-01 9.28253829e-01 -1.07095703e-01 -3.52987021e-01 9.29486990e-01 -1.07096039e-01 -3.49756777e-01 9.30700004e-01 -1.07095741e-01 -3.46488386e-01 9.31922495e-01 -1.07096002e-01 -3.43193650e-01 9.33144152e-01 -1.07095674e-01 -3.39986831e-01 9.34326470e-01 -1.07095785e-01 -3.36705178e-01 9.35510159e-01 -1.07095793e-01 -3.33419323e-01 9.36689138e-01 -1.07095703e-01 -3.30169052e-01 9.37837958e-01 -1.07095711e-01 -3.26838255e-01 9.39003348e-01 -1.07095681e-01 -3.23562831e-01 9.40138638e-01 -1.07095681e-01 -3.20352495e-01 9.41235185e-01 -1.07095748e-01 -3.17056835e-01 9.42351580e-01 -1.07095897e-01 -3.13712329e-01 9.43469703e-01 -1.07095681e-01 -3.10419083e-01 9.44557548e-01 -1.07095674e-01 -3.07183057e-01 9.45615649e-01 -1.07095711e-01 -3.03879589e-01 9.46683645e-01 -1.07096016e-01 -3.00513923e-01 9.47756052e-01 -1.07095674e-01 -2.97224432e-01 9.48793650e-01 -1.07095681e-01 -2.93894261e-01 9.49830651e-01 -1.07095674e-01 -2.90668041e-01 9.50822651e-01 -1.07095741e-01 -2.87331134e-01 9.51834381e-01 -1.07096046e-01 -2.83890665e-01 9.52867806e-01 -1.07095696e-01 -2.80577779e-01 9.53849435e-01 -1.07095674e-01 -2.77227432e-01 9.54828084e-01 -1.07095823e-01 -2.74002671e-01 9.55758393e-01 -1.07095756e-01 -2.70685285e-01 9.56703424e-01 -1.07096076e-01 -2.67330289e-01 9.57647204e-01 -1.07095741e-01 -2.64099151e-01 9.58541572e-01 -1.07095748e-01 -2.60626078e-01 9.59493399e-01 -1.07096151e-01 -2.57173210e-01 9.60422695e-01 -1.07095681e-01 -2.53809601e-01 9.61317837e-01 -1.07095756e-01 -2.50480175e-01 9.62191045e-01 -1.07095696e-01 -2.47209027e-01 9.63036239e-01 -1.07095718e-01 -2.43830904e-01 9.63894367e-01 -1.07096158e-01 -2.40349486e-01 9.64770198e-01 -1.07095703e-01 -2.36983299e-01 9.65603530e-01 -1.07095674e-01 -2.33597562e-01 9.66430366e-01 -1.07095718e-01 -2.30339900e-01 9.67211604e-01 -1.07095711e-01 -2.26973712e-01 9.68007147e-01 -1.07096121e-01 -2.23588690e-01 9.68793213e-01 -1.07095703e-01 -2.20211387e-01 9.69564855e-01 -1.07095987e-01 -2.16719180e-01 9.70354021e-01 -1.07095733e-01 -2.13327140e-01 9.71101284e-01 -1.07095711e-01 -2.09939629e-01 9.71840680e-01 -1.07095748e-01 -2.06633791e-01 9.72549617e-01 -1.07095718e-01 -2.03265846e-01 9.73260999e-01 -1.07096054e-01 -1.99743420e-01 9.73989904e-01 -1.07095830e-01 -1.96365371e-01 9.74674404e-01 -1.07095674e-01 -1.92943662e-01 9.75357890e-01 -1.07095800e-01 -1.89619288e-01 9.76010025e-01 -1.07095703e-01 -1.86217010e-01 9.76664841e-01 -1.07096076e-01 -1.82806626e-01 9.77308273e-01 -1.07095703e-01 -1.79486796e-01 9.77921903e-01 -1.07095681e-01 -1.75964221e-01 9.78568137e-01 -1.07095949e-01 -1.72454789e-01 9.79192197e-01 -1.07095681e-01 -1.69049740e-01 9.79781747e-01 -1.07095733e-01 -1.65635362e-01 9.80365574e-01 -1.07095733e-01 -1.62294596e-01 9.80923831e-01 -1.07095711e-01 -1.58957958e-01 9.81469274e-01 -1.07095703e-01 -1.55464619e-01 9.82029855e-01 -1.07095920e-01 -1.51917249e-01 9.82585728e-01 -1.07095867e-01 -1.48467317e-01 9.83109713e-01 -1.07095748e-01 -1.45047531e-01 9.83622074e-01 -1.07095711e-01 -1.41590953e-01 9.84124899e-01 -1.07095674e-01 -1.38286665e-01 9.84594941e-01 -1.07095741e-01 -1.34864181e-01 9.85071421e-01 -1.07096121e-01 -1.31292507e-01 9.85551834e-01 -1.07095711e-01 -1.27958164e-01 9.85989690e-01 -1.07095718e-01 -1.24542803e-01 9.86427605e-01 -1.07095987e-01 -1.21077821e-01 9.86858904e-01 -1.07095726e-01 -1.17611520e-01 9.87277985e-01 -1.07096076e-01 -1.14069894e-01 9.87693548e-01 -1.07095763e-01 -1.10609844e-01 9.88086641e-01 -1.07095674e-01 -1.07164010e-01 9.88465488e-01 -1.07095681e-01 -1.03709616e-01 9.88833964e-01 -1.07095681e-01 -1.00252651e-01 9.89191115e-01 -1.07095748e-01 -9.68866050e-02 9.89526629e-01 -1.07095726e-01 -9.35525522e-02 9.89847720e-01 -1.07095674e-01 -8.99959877e-02 9.90177214e-01 -1.07096024e-01 -8.64364728e-02 9.90495145e-01 -1.07095771e-01 -8.29791725e-02 9.90790248e-01 -1.07095756e-01 -7.94945657e-02 9.91075516e-01 -1.07095778e-01 -7.61493519e-02 9.91336644e-01 -1.07095726e-01 -7.26973265e-02 9.91598606e-01 -1.07096024e-01 -6.91193268e-02 9.91851747e-01 -1.07095674e-01 -6.56470060e-02 9.92089808e-01 -1.07095674e-01 -6.22067414e-02 9.92308974e-01 -1.07095681e-01 -5.88428564e-02 9.92516398e-01 -1.07095703e-01 -5.53844124e-02 9.92715955e-01 -1.07096061e-01 -5.18740527e-02 9.92902994e-01 -1.07095741e-01 -4.84402329e-02 9.93079603e-01 -1.07095934e-01 -4.48824130e-02 9.93243635e-01 -1.07095674e-01 -4.14277092e-02 9.93395567e-01 -1.07095733e-01 -3.79469469e-02 9.93533373e-01 -1.07095733e-01 -3.45644690e-02 9.93658245e-01 -1.07095711e-01 -3.11118513e-02 9.93770599e-01 -1.07095964e-01 -2.76260972e-02 9.93873775e-01 -1.07095741e-01 -2.41453405e-02 9.93969679e-01 -1.07095979e-01 -2.06010286e-02 9.94041860e-01 -1.07095852e-01 -1.72152240e-02 9.94113386e-01 -1.07095703e-01 -1.37552917e-02 9.94159102e-01 -1.07096009e-01 -1.02935443e-02 9.94204223e-01 -1.07095741e-01 -6.88976515e-03 9.94240344e-01 -1.07095681e-01 -3.32670868e-03 9.94258165e-01 -1.07095905e-01 2.30937760e-04 9.94259417e-01 -1.07095696e-01 3.67413322e-03 9.94257867e-01 -1.07095674e-01 7.14431098e-03 9.94237721e-01 -1.07095674e-01 1.05343824e-02 9.94201899e-01 -1.07095741e-01 1.39086563e-02 9.94157255e-01 -1.07095674e-01 1.74649879e-02 9.94110823e-01 -1.07095920e-01 2.10424475e-02 9.94035006e-01 -1.07095711e-01 2.45306790e-02 9.93956149e-01 -1.07095674e-01 2.80050207e-02 9.93866682e-01 -1.07095756e-01 3.14891338e-02 9.93760824e-01 -1.07095741e-01 3.48513573e-02 9.93649185e-01 -1.07095741e-01 3.82956602e-02 9.93521988e-01 -1.07095964e-01 4.18920256e-02 9.93377268e-01 -1.07095763e-01 4.53500338e-02 9.93223667e-01 -1.07095674e-01 4.88124378e-02 9.93060470e-01 -1.07095718e-01 5.21942414e-02 9.92885530e-01 -1.07095741e-01 5.56363240e-02 9.92700994e-01 -1.07095987e-01 5.91317303e-02 9.92498636e-01 -1.07095756e-01 6.25682175e-02 9.92286086e-01 -1.07096054e-01 6.61350712e-02 9.92056966e-01 -1.07095748e-01 6.96051791e-02 9.91817951e-01 -1.07095711e-01 7.30571821e-02 9.91572201e-01 -1.07095696e-01 7.65227973e-02 9.91308749e-01 -1.07095718e-01 7.98994154e-02 9.91043210e-01 -1.07095748e-01 8.33231956e-02 9.90761280e-01 -1.07095964e-01 8.68835747e-02 9.90455925e-01 -1.07095830e-01 9.03537646e-02 9.90144551e-01 -1.07095756e-01 9.37886015e-02 9.89825666e-01 -1.07095681e-01 9.71940011e-02 9.89497066e-01 -1.07095718e-01 1.00627773e-01 9.89153206e-01 -1.07096024e-01 1.04082108e-01 9.88796175e-01 -1.07095703e-01 1.07531406e-01 9.88427818e-01 -1.07096203e-01 1.11077704e-01 9.88033652e-01 -1.07095793e-01 1.14453457e-01 9.87648070e-01 -1.07095741e-01 1.17880270e-01 9.87245321e-01 -1.07096054e-01 1.21315598e-01 9.86829519e-01 -1.07095703e-01 1.24764107e-01 9.86400068e-01 -1.07096016e-01 1.28301442e-01 9.85944569e-01 -1.07095763e-01 1.31753042e-01 9.85490263e-01 -1.07095696e-01 1.35194555e-01 9.85025823e-01 -1.07095808e-01 1.38511240e-01 9.84565079e-01 -1.07095681e-01 1.41971275e-01 9.84070301e-01 -1.07096002e-01 1.45404905e-01 9.83568788e-01 -1.07095703e-01 1.48821309e-01 9.83056426e-01 -1.07095972e-01 1.52362376e-01 9.82516766e-01 -1.07095674e-01 1.55698612e-01 9.81990159e-01 -1.07095703e-01 1.59108967e-01 9.81445134e-01 -1.07095972e-01 1.62541479e-01 9.80884314e-01 -1.07095696e-01 1.65856913e-01 9.80327427e-01 -1.07095793e-01 1.69383362e-01 9.79724526e-01 -1.07096046e-01 1.72883466e-01 9.79117036e-01 -1.07095703e-01 1.76309168e-01 9.78506565e-01 -1.07095800e-01 1.79721296e-01 9.77880836e-01 -1.07095733e-01 1.83046788e-01 9.77264166e-01 -1.07095741e-01 1.86358377e-01 9.76637781e-01 -1.07095838e-01 1.89782530e-01 9.75977898e-01 -1.07095808e-01 1.93244964e-01 9.75298345e-01 -1.07096076e-01 1.96747914e-01 9.74597991e-01 -1.07095815e-01 2.00166717e-01 9.73901451e-01 -1.07095845e-01 2.03562737e-01 9.73196387e-01 -1.07095860e-01 2.06868991e-01 9.72501278e-01 -1.07095681e-01 2.10234940e-01 9.71777737e-01 -1.07096061e-01 2.13727638e-01 9.71015275e-01 -1.07095852e-01 2.17150971e-01 9.70256567e-01 -1.07095785e-01 2.20535144e-01 9.69491065e-01 -1.07095674e-01 2.23827615e-01 9.68737781e-01 -1.07095771e-01 2.27195546e-01 9.67955887e-01 -1.07095987e-01 2.30586320e-01 9.67151999e-01 -1.07095741e-01 2.33855948e-01 9.66368735e-01 -1.07095771e-01 2.37326935e-01 9.65519726e-01 -1.07096024e-01 2.40800425e-01 9.64657545e-01 -1.07095726e-01 2.44132042e-01 9.63819087e-01 -1.07095681e-01 2.47468844e-01 9.62970734e-01 -1.07095741e-01 2.50773698e-01 9.62114513e-01 -1.07095703e-01 2.54034936e-01 9.61259723e-01 -1.07095905e-01 2.57495254e-01 9.60336924e-01 -1.07096143e-01 2.60960281e-01 9.59403634e-01 -1.07095905e-01 2.64283717e-01 9.58489537e-01 -1.07095696e-01 2.67527074e-01 9.57592249e-01 -1.07095793e-01 2.70859748e-01 9.56653714e-01 -1.07095972e-01 2.74211228e-01 9.55699563e-01 -1.07095741e-01 2.77524024e-01 9.54742134e-01 -1.07096016e-01 2.80978233e-01 9.53730345e-01 -1.07095763e-01 2.84221739e-01 9.52771604e-01 -1.07095703e-01 2.87540942e-01 9.51770782e-01 -1.07096143e-01 2.90880382e-01 9.50757146e-01 -1.07095681e-01 2.94112176e-01 9.49764371e-01 -1.07095994e-01 2.97531873e-01 9.48697984e-01 -1.07096061e-01 3.00789833e-01 9.47667837e-01 -1.07095703e-01 3.04087281e-01 9.46616650e-01 -1.07096188e-01 3.07422787e-01 9.45537567e-01 -1.07095681e-01 3.10707957e-01 9.44463730e-01 -1.07096136e-01 3.14000666e-01 9.43374097e-01 -1.07095681e-01 3.17204148e-01 9.42302823e-01 -1.07095830e-01 3.20574105e-01 9.41161036e-01 -1.07096151e-01 3.23948026e-01 9.40005124e-01 -1.07095823e-01 3.27206969e-01 9.38874483e-01 -1.07095793e-01 3.30466479e-01 9.37733293e-01 -1.07095800e-01 3.33673418e-01 9.36598837e-01 -1.07095681e-01 3.36914867e-01 9.35435593e-01 -1.07096113e-01 3.40280920e-01 9.34216619e-01 -1.07095867e-01 3.43539298e-01 9.33016658e-01 -1.07095830e-01 3.46784413e-01 9.31812525e-01 -1.07095875e-01 3.49976361e-01 9.30618882e-01 -1.07095681e-01 3.53220016e-01 9.29399669e-01 -1.07096091e-01 3.56453657e-01 9.28172171e-01 -1.07095681e-01 3.59681427e-01 9.26917791e-01 -1.07096121e-01 3.62985462e-01 9.25630808e-01 -1.07095882e-01 3.66162300e-01 9.24377918e-01 -1.07095696e-01 3.69369596e-01 9.23101068e-01 -1.07096024e-01 3.72573346e-01 9.21812773e-01 -1.07095681e-01 3.75787526e-01 9.20507491e-01 -1.07096083e-01 3.78996402e-01 9.19189632e-01 -1.07095674e-01 3.82190019e-01 9.17867184e-01 -1.07096106e-01 3.85474414e-01 9.16493356e-01 -1.07095890e-01 3.88586313e-01 9.15176868e-01 -1.07095681e-01 3.91772866e-01 9.13815618e-01 -1.07096121e-01 3.94984603e-01 9.12433922e-01 -1.07095681e-01 3.98068607e-01 9.11096752e-01 -1.07095867e-01 4.01321471e-01 9.09666717e-01 -1.07096143e-01 4.04563636e-01 9.08228874e-01 -1.07095815e-01 4.07732069e-01 9.06810522e-01 -1.07095912e-01 4.10904974e-01 9.05377805e-01 -1.07095823e-01 4.13992912e-01 9.03967500e-01 -1.07095681e-01 4.17060345e-01 9.02557015e-01 -1.07095852e-01 4.20273602e-01 9.01066840e-01 -1.07096121e-01 4.23461735e-01 8.99570704e-01 -1.07095733e-01 4.26635414e-01 8.98071647e-01 -1.07095674e-01 4.29680139e-01 8.96617413e-01 -1.07095703e-01 4.32805300e-01 8.95117104e-01 -1.07095934e-01 4.35922176e-01 8.93603742e-01 -1.07095681e-01 4.39047933e-01 8.92068565e-01 -1.07096113e-01 4.42238033e-01 8.90492380e-01 -1.07095920e-01 4.45354939e-01 8.88937831e-01 -1.07095994e-01 4.48433608e-01 8.87390018e-01 -1.07095934e-01 4.51472133e-01 8.85847688e-01 -1.07095703e-01 4.54519361e-01 8.84287298e-01 -1.07095972e-01 4.57638860e-01 8.82674098e-01 -1.07095741e-01 4.60675776e-01 8.81097198e-01 -1.07095674e-01 4.63790089e-01 8.79460514e-01 -1.07096121e-01 4.66914713e-01 8.77805471e-01 -1.07095681e-01 4.69969928e-01 8.76173913e-01 -1.07095905e-01 4.73044991e-01 8.74516726e-01 -1.07095897e-01 4.76004630e-01 8.72912228e-01 -1.07095681e-01 4.79043901e-01 8.71246040e-01 -1.07096195e-01 4.82192814e-01 8.69503796e-01 -1.07095882e-01 4.85232204e-01 8.67812514e-01 -1.07095845e-01 4.88245577e-01 8.66122723e-01 -1.07095845e-01 4.91166979e-01 8.64467978e-01 -1.07095696e-01 4.94193137e-01 8.62743318e-01 -1.07096136e-01 4.97193843e-01 8.61017823e-01 -1.07095703e-01 5.00204504e-01 8.59272361e-01 -1.07096091e-01 5.03287077e-01 8.57469976e-01 -1.07095912e-01 5.06210685e-01 8.55746210e-01 -1.07095681e-01 5.09170771e-01 8.53989542e-01 -1.07096091e-01 5.12145042e-01 8.52207959e-01 -1.07095681e-01 5.15113652e-01 8.50416124e-01 -1.07096016e-01 5.18142998e-01 8.48576128e-01 -1.07095845e-01 5.21045089e-01 8.46794486e-01 -1.07095674e-01 5.24005294e-01 8.44970584e-01 -1.07096136e-01 5.26949704e-01 8.43134940e-01 -1.07095681e-01 5.29860973e-01 8.41308713e-01 -1.07096069e-01 5.32817602e-01 8.39437664e-01 -1.07095674e-01 5.35722375e-01 8.37585390e-01 -1.07096009e-01 5.38735628e-01 8.35651159e-01 -1.07095972e-01 5.41585386e-01 8.33808243e-01 -1.07095674e-01 5.44470191e-01 8.31925511e-01 -1.07096046e-01 5.47374964e-01 8.30018401e-01 -1.07095703e-01 5.50172389e-01 8.28164637e-01 -1.07095681e-01 5.53183436e-01 8.26159120e-01 -1.07095674e-01 5.56057572e-01 8.24228823e-01 -1.07095838e-01 5.58916569e-01 8.22290659e-01 -1.07095703e-01 5.61875701e-01 8.20272088e-01 -1.07095897e-01 5.64637065e-01 8.18373263e-01 -1.07096188e-01 5.67386091e-01 8.16469371e-01 -1.07096143e-01 5.70227683e-01 8.14485788e-01 -1.07096456e-01 5.73152661e-01 8.12430322e-01 -1.07096754e-01 5.76086760e-01 8.10350835e-01 -1.07097395e-01 5.78692436e-01 8.08488131e-01 -1.07097365e-01 5.81438780e-01 8.06508720e-01 -1.07097141e-01 5.84084272e-01 8.04595828e-01 -1.07097119e-01 5.87225974e-01 8.02306116e-01 -1.07097037e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.08800435e-01 6.97231591e-01 -1.07097045e-01 7.10687160e-01 6.95307076e-01 -1.07097015e-01 7.13074207e-01 6.92868114e-01 -1.07097372e-01 7.15261936e-01 6.90608680e-01 -1.07097432e-01 7.17767596e-01 6.88008249e-01 -1.07096374e-01 7.20192254e-01 6.85474455e-01 -1.07096069e-01 7.22472548e-01 6.83068037e-01 -1.07096009e-01 7.24865019e-01 6.80528522e-01 -1.07095696e-01 7.27276981e-01 6.77950144e-01 -1.07095703e-01 7.29606628e-01 6.75445139e-01 -1.07095681e-01 7.31904328e-01 6.72957838e-01 -1.07095674e-01 7.34215915e-01 6.70430243e-01 -1.07095785e-01 7.36624837e-01 6.67786300e-01 -1.07096046e-01 7.39000142e-01 6.65154815e-01 -1.07095785e-01 7.41311252e-01 6.62575483e-01 -1.07095771e-01 7.43567824e-01 6.60045266e-01 -1.07095681e-01 7.45811462e-01 6.57507181e-01 -1.07095696e-01 7.48119295e-01 6.54877901e-01 -1.07095912e-01 7.50442684e-01 6.52216494e-01 -1.07095808e-01 7.52731204e-01 6.49574578e-01 -1.07095942e-01 7.55017340e-01 6.46916687e-01 -1.07095674e-01 7.57204115e-01 6.44352674e-01 -1.07095696e-01 7.59436607e-01 6.41723633e-01 -1.07095867e-01 7.61681437e-01 6.39056504e-01 -1.07095674e-01 7.63940096e-01 6.36355340e-01 -1.07096002e-01 7.66217053e-01 6.33608460e-01 -1.07095793e-01 7.68363416e-01 6.31007612e-01 -1.07095681e-01 7.70543754e-01 6.28341138e-01 -1.07095897e-01 7.72779882e-01 6.25589788e-01 -1.07095793e-01 7.74980545e-01 6.22861981e-01 -1.07095867e-01 7.77111173e-01 6.20202482e-01 -1.07095703e-01 7.79193997e-01 6.17581964e-01 -1.07095823e-01 7.81403244e-01 6.14786029e-01 -1.07096106e-01 7.83613205e-01 6.11965239e-01 -1.07095785e-01 7.85744011e-01 6.09229326e-01 -1.07095867e-01 7.87818372e-01 6.06542170e-01 -1.07095741e-01 7.89853334e-01 6.03889942e-01 -1.07095852e-01 7.92015910e-01 6.01051688e-01 -1.07096091e-01 7.94161499e-01 5.98213732e-01 -1.07095718e-01 7.96248138e-01 5.95431864e-01 -1.07095830e-01 7.98281789e-01 5.92702687e-01 -1.07095681e-01 8.00273538e-01 5.90009987e-01 -1.07095741e-01 8.02379489e-01 5.87143779e-01 -1.07096121e-01 8.04494679e-01 5.84242344e-01 -1.07095830e-01 8.06533575e-01 5.81421435e-01 -1.07095785e-01 8.08550775e-01 5.78617096e-01 -1.07095733e-01 8.10496390e-01 5.75889528e-01 -1.07095703e-01 8.12464833e-01 5.73110461e-01 -1.07095882e-01 8.14468801e-01 5.70255518e-01 -1.07095726e-01 8.16500664e-01 5.67341864e-01 -1.07096151e-01 8.18506420e-01 5.64446807e-01 -1.07095718e-01 8.20399642e-01 5.61689556e-01 -1.07095756e-01 8.22408676e-01 5.58744490e-01 -1.07096203e-01 8.24360847e-01 5.55859625e-01 -1.07095741e-01 8.26262057e-01 5.53027391e-01 -1.07095927e-01 8.28197479e-01 5.50126791e-01 -1.07095681e-01 8.30070376e-01 5.47297597e-01 -1.07095815e-01 8.32029819e-01 5.44312894e-01 -1.07095972e-01 8.33966792e-01 5.41340292e-01 -1.07095711e-01 8.35807264e-01 5.38493454e-01 -1.07095718e-01 8.37635279e-01 5.35647511e-01 -1.07095718e-01 8.39486778e-01 5.32737017e-01 -1.07095897e-01 8.41421604e-01 5.29681861e-01 -1.07096061e-01 8.43327224e-01 5.26639104e-01 -1.07095875e-01 8.45149636e-01 5.23711860e-01 -1.07095681e-01 8.46918583e-01 5.20842731e-01 -1.07095703e-01 8.48693192e-01 5.17950475e-01 -1.07095696e-01 8.50493491e-01 5.14986217e-01 -1.07095756e-01 8.52281690e-01 5.12022913e-01 -1.07095674e-01 8.54111195e-01 5.08963645e-01 -1.07096083e-01 8.55936468e-01 5.05889177e-01 -1.07095696e-01 8.57650101e-01 5.02980232e-01 -1.07095703e-01 8.59391630e-01 4.99998003e-01 -1.07096054e-01 8.61139596e-01 4.96982992e-01 -1.07095711e-01 8.62865090e-01 4.93977696e-01 -1.07096039e-01 8.64605308e-01 4.90922004e-01 -1.07095681e-01 8.66271198e-01 4.87985253e-01 -1.07095681e-01 8.67987871e-01 4.84918743e-01 -1.07096039e-01 8.69687259e-01 4.81862277e-01 -1.07095681e-01 8.71364355e-01 4.78828430e-01 -1.07095830e-01 8.73017192e-01 4.75808769e-01 -1.07095703e-01 8.74634206e-01 4.72827464e-01 -1.07095733e-01 8.76311839e-01 4.69712049e-01 -1.07095957e-01 8.78003836e-01 4.66542125e-01 -1.07095808e-01 8.79628837e-01 4.63470846e-01 -1.07095681e-01 8.81194055e-01 4.60489482e-01 -1.07095711e-01 8.82740915e-01 4.57513034e-01 -1.07095674e-01 8.84372354e-01 4.54353631e-01 -1.07096054e-01 8.86005878e-01 4.51159656e-01 -1.07095838e-01 8.87569189e-01 4.48078185e-01 -1.07095681e-01 8.89135242e-01 4.44961250e-01 -1.07095763e-01 8.90654027e-01 4.41910446e-01 -1.07095741e-01 8.92175198e-01 4.38834518e-01 -1.07096046e-01 8.93707871e-01 4.35705870e-01 -1.07095703e-01 8.95222425e-01 4.32585657e-01 -1.07096024e-01 8.96770835e-01 4.29363668e-01 -1.07095785e-01 8.98221016e-01 4.26321030e-01 -1.07095696e-01 8.99686456e-01 4.23217833e-01 -1.07096083e-01 9.01172757e-01 4.20047104e-01 -1.07095703e-01 9.02628183e-01 4.16911602e-01 -1.07096083e-01 9.04125929e-01 4.13648188e-01 -1.07095808e-01 9.05521989e-01 4.10584539e-01 -1.07095733e-01 9.06938314e-01 4.07449275e-01 -1.07096091e-01 9.08369362e-01 4.04246747e-01 -1.07095703e-01 9.09772217e-01 4.01081741e-01 -1.07096046e-01 9.11171019e-01 3.97894770e-01 -1.07095703e-01 9.12517369e-01 3.94794971e-01 -1.07095733e-01 9.13918972e-01 3.91531736e-01 -1.07096113e-01 9.15324867e-01 3.88241321e-01 -1.07095674e-01 9.16661799e-01 3.85073721e-01 -1.07095703e-01 9.17968810e-01 3.81944686e-01 -1.07095718e-01 9.19256568e-01 3.78832668e-01 -1.07095756e-01 9.20611858e-01 3.75530034e-01 -1.07096113e-01 9.21963513e-01 3.72203588e-01 -1.07095793e-01 9.23258722e-01 3.68976027e-01 -1.07095741e-01 9.24507856e-01 3.65841448e-01 -1.07095703e-01 9.25734222e-01 3.62726331e-01 -1.07095771e-01 9.27018166e-01 3.59417856e-01 -1.07096091e-01 9.28286076e-01 3.56154114e-01 -1.07095696e-01 9.29506660e-01 3.52934569e-01 -1.07096061e-01 9.30772245e-01 3.49569589e-01 -1.07095912e-01 9.31954920e-01 3.46397489e-01 -1.07095696e-01 9.33156908e-01 3.43163878e-01 -1.07096031e-01 9.34360027e-01 3.39893073e-01 -1.07095696e-01 9.35527444e-01 3.36659819e-01 -1.07096158e-01 9.36735451e-01 3.33287209e-01 -1.07095875e-01 9.37860489e-01 3.30106616e-01 -1.07095681e-01 9.39000666e-01 3.26847911e-01 -1.07096091e-01 9.40162003e-01 3.23492616e-01 -1.07095845e-01 9.41273630e-01 3.20239991e-01 -1.07095771e-01 9.42370713e-01 3.17003012e-01 -1.07095711e-01 9.43449140e-01 3.13773662e-01 -1.07095815e-01 9.44562018e-01 3.10410053e-01 -1.07096091e-01 9.45669115e-01 3.07021648e-01 -1.07095808e-01 9.46729958e-01 3.03736418e-01 -1.07095875e-01 9.47764874e-01 3.00489694e-01 -1.07095696e-01 9.48776603e-01 2.97279239e-01 -1.07095838e-01 9.49832857e-01 2.93884456e-01 -1.07096151e-01 9.50884044e-01 2.90463805e-01 -1.07095867e-01 9.51886237e-01 2.87163466e-01 -1.07095800e-01 9.52858090e-01 2.83920169e-01 -1.07095696e-01 9.53820467e-01 2.80676275e-01 -1.07095830e-01 9.54817832e-01 2.77268022e-01 -1.07096128e-01 9.55779731e-01 2.73923784e-01 -1.07095681e-01 9.56733704e-01 2.70579010e-01 -1.07096173e-01 9.57690179e-01 2.67172456e-01 -1.07095778e-01 9.58592176e-01 2.63917446e-01 -1.07095703e-01 9.59509313e-01 2.60569364e-01 -1.07096173e-01 9.60439742e-01 2.57109702e-01 -1.07095800e-01 9.61322904e-01 2.53793567e-01 -1.07095808e-01 9.62205231e-01 2.50426918e-01 -1.07095905e-01 9.63057816e-01 2.47132763e-01 -1.07095681e-01 9.63903189e-01 2.43797153e-01 -1.07096113e-01 9.64755952e-01 2.40411639e-01 -1.07095681e-01 9.65592623e-01 2.37036690e-01 -1.07096218e-01 9.66413260e-01 2.33664319e-01 -1.07095681e-01 9.67200339e-01 2.30389595e-01 -1.07095852e-01 9.68016803e-01 2.26934016e-01 -1.07096173e-01 9.68817472e-01 2.23478973e-01 -1.07095808e-01 9.69594955e-01 2.20087141e-01 -1.07096009e-01 9.70362782e-01 2.16678932e-01 -1.07095912e-01 9.71091509e-01 2.13375047e-01 -1.07095681e-01 9.71827507e-01 2.09998161e-01 -1.07096195e-01 9.72576678e-01 2.06507608e-01 -1.07095867e-01 9.73290503e-01 2.03125969e-01 -1.07095852e-01 9.73994136e-01 1.99722722e-01 -1.07095852e-01 9.74668741e-01 1.96398467e-01 -1.07095681e-01 9.75339115e-01 1.93031520e-01 -1.07096180e-01 9.76016045e-01 1.89590678e-01 -1.07095681e-01 9.76666331e-01 1.86203063e-01 -1.07096165e-01 9.77325678e-01 1.82716712e-01 -1.07095845e-01 9.77939963e-01 1.79386854e-01 -1.07095674e-01 9.78568971e-01 1.75965771e-01 -1.07096180e-01 9.79190171e-01 1.72472492e-01 -1.07095756e-01 9.79776621e-01 1.69078663e-01 -1.07095860e-01 9.80352581e-01 1.65711641e-01 -1.07095674e-01 9.80910659e-01 1.62371725e-01 -1.07095912e-01 9.81484652e-01 1.58865482e-01 -1.07096158e-01 9.82047081e-01 1.55349165e-01 -1.07095867e-01 9.82581079e-01 1.51932567e-01 -1.07095890e-01 9.83093858e-01 1.48576587e-01 -1.07095674e-01 9.83594477e-01 1.45233437e-01 -1.07095890e-01 9.84106958e-01 1.41717225e-01 -1.07096158e-01 9.84609067e-01 1.38191849e-01 -1.07095875e-01 9.85084713e-01 1.34767085e-01 -1.07095793e-01 9.85548437e-01 1.31327316e-01 -1.07095972e-01 9.85992372e-01 1.27945974e-01 -1.07095703e-01 9.86430049e-01 1.24531999e-01 -1.07096054e-01 9.86871839e-01 1.20971240e-01 -1.07095890e-01 9.87285554e-01 1.17538609e-01 -1.07095890e-01 9.87688601e-01 1.14110246e-01 -1.07095875e-01 9.88072336e-01 1.10741928e-01 -1.07095674e-01 9.88453031e-01 1.07285149e-01 -1.07096195e-01 9.88823175e-01 1.03823483e-01 -1.07095681e-01 9.89174962e-01 1.00399330e-01 -1.07096180e-01 9.89531457e-01 9.68392193e-02 -1.07095845e-01 9.89855051e-01 9.34807658e-02 -1.07095703e-01 9.90173697e-01 9.00475010e-02 -1.07096151e-01 9.90483284e-01 8.65768641e-02 -1.07095681e-01 9.90780354e-01 8.30902383e-02 -1.07096091e-01 9.91066098e-01 7.96125159e-02 -1.07095681e-01 9.91335630e-01 7.61928037e-02 -1.07096128e-01 9.91602004e-01 7.26310983e-02 -1.07095979e-01 9.91850138e-01 6.91379085e-02 -1.07095815e-01 9.92086887e-01 6.56855330e-02 -1.07095838e-01 9.92303729e-01 6.23020343e-02 -1.07095681e-01 9.92508650e-01 5.89451566e-02 -1.07095867e-01 9.92716074e-01 5.53886220e-02 -1.07096225e-01 9.92907763e-01 5.18128239e-02 -1.07095808e-01 9.93083358e-01 4.83477637e-02 -1.07095890e-01 9.93239641e-01 4.49894406e-02 -1.07095696e-01 9.93387222e-01 4.16359194e-02 -1.07095860e-01 9.93525863e-01 3.81664038e-02 -1.07095964e-01 9.93653774e-01 3.46797481e-02 -1.07095852e-01 9.93772388e-01 3.11053991e-02 -1.07096195e-01 9.93879020e-01 2.75131147e-02 -1.07095882e-01 9.93968189e-01 2.41598003e-02 -1.07095703e-01 9.94038105e-01 2.08131969e-02 -1.07095860e-01 9.94113386e-01 1.73172336e-02 -1.07095927e-01 9.94157374e-01 1.38491429e-02 -1.07095949e-01 9.94206071e-01 1.03614293e-02 -1.07095942e-01 9.94241893e-01 6.90500159e-03 -1.07095905e-01 9.94258642e-01 3.34965275e-03 -1.07096240e-01 9.94259238e-01 -1.33109104e-04 -1.07095681e-01 9.94258344e-01 -3.58603592e-03 -1.07096203e-01 9.94239211e-01 -7.08724232e-03 -1.07095681e-01 9.94205475e-01 -1.04541341e-02 -1.07095890e-01 9.94154811e-01 -1.39889782e-02 -1.07096158e-01 9.94108915e-01 -1.75743550e-02 -1.07095957e-01 9.94035602e-01 -2.09590793e-02 -1.07095674e-01 9.93961155e-01 -2.44255811e-02 -1.07096247e-01 9.93867576e-01 -2.79236864e-02 -1.07095681e-01 9.93764579e-01 -3.13605852e-02 -1.07096091e-01 9.93649423e-01 -3.48383151e-02 -1.07095696e-01 9.93523538e-01 -3.82181965e-02 -1.07095942e-01 9.93385613e-01 -4.16825488e-02 -1.07095964e-01 9.93230343e-01 -4.52077314e-02 -1.07096270e-01 9.93062139e-01 -4.87962477e-02 -1.07095897e-01 9.92882729e-01 -5.22492379e-02 -1.07095979e-01 9.92699802e-01 -5.56504726e-02 -1.07095674e-01 9.92505670e-01 -5.90095818e-02 -1.07095920e-01 9.92292345e-01 -6.24704361e-02 -1.07095934e-01 9.92065072e-01 -6.60227090e-02 -1.07096173e-01 9.91821706e-01 -6.95589632e-02 -1.07095920e-01 9.91576016e-01 -7.30102509e-02 -1.07095942e-01 9.91316020e-01 -7.64357895e-02 -1.07095674e-01 9.91050661e-01 -7.98049346e-02 -1.07095905e-01 9.90767419e-01 -8.32413137e-02 -1.07095964e-01 9.90464985e-01 -8.67831036e-02 -1.07096195e-01 9.90153253e-01 -9.02559683e-02 -1.07095674e-01 9.89842713e-01 -9.36166793e-02 -1.07095942e-01 9.89509702e-01 -9.70662162e-02 -1.07095972e-01 9.89154756e-01 -1.00611433e-01 -1.07096247e-01 9.88795757e-01 -1.04082890e-01 -1.07095681e-01 9.88429844e-01 -1.07498966e-01 -1.07096232e-01 9.88048434e-01 -1.10961020e-01 -1.07095681e-01 9.87668216e-01 -1.14284001e-01 -1.07095920e-01 9.87251222e-01 -1.17844701e-01 -1.07096165e-01 9.86832261e-01 -1.21295258e-01 -1.07095681e-01 9.86406147e-01 -1.24737054e-01 -1.07096180e-01 9.85946596e-01 -1.28283441e-01 -1.07096039e-01 9.85504389e-01 -1.31648049e-01 -1.07095681e-01 9.85045254e-01 -1.35051146e-01 -1.07096180e-01 9.84552622e-01 -1.38594568e-01 -1.07096016e-01 9.84073400e-01 -1.41955122e-01 -1.07095681e-01 9.83570993e-01 -1.45385385e-01 -1.07096024e-01 9.83061790e-01 -1.48792222e-01 -1.07095674e-01 9.82536376e-01 -1.52220070e-01 -1.07096165e-01 9.81993973e-01 -1.55684829e-01 -1.07095674e-01 9.81450200e-01 -1.59077957e-01 -1.07096031e-01 9.80895638e-01 -1.62469760e-01 -1.07095748e-01 9.80317533e-01 -1.65924802e-01 -1.07096210e-01 9.79712963e-01 -1.69438988e-01 -1.07095830e-01 9.79124248e-01 -1.72842026e-01 -1.07095890e-01 9.78526294e-01 -1.76190466e-01 -1.07095711e-01 9.77913976e-01 -1.79530784e-01 -1.07095957e-01 9.77285385e-01 -1.82938918e-01 -1.07095964e-01 9.76630747e-01 -1.86393142e-01 -1.07096076e-01 9.75953519e-01 -1.89907342e-01 -1.07095890e-01 9.75283682e-01 -1.93319231e-01 -1.07095905e-01 9.74618316e-01 -1.96647942e-01 -1.07095696e-01 9.73945916e-01 -1.99950591e-01 -1.07095867e-01 9.73246694e-01 -2.03332260e-01 -1.07095972e-01 9.72505748e-01 -2.06851184e-01 -1.07096098e-01 9.71778452e-01 -2.10235626e-01 -1.07095674e-01 9.71051812e-01 -2.13562444e-01 -1.07096151e-01 9.70298529e-01 -2.16965616e-01 -1.07095778e-01 9.69526887e-01 -2.20379069e-01 -1.07096218e-01 9.68748689e-01 -2.23780096e-01 -1.07095681e-01 9.67966735e-01 -2.27149934e-01 -1.07096255e-01 9.67163146e-01 -2.30542496e-01 -1.07095681e-01 9.66382384e-01 -2.33795851e-01 -1.07095890e-01 9.65536654e-01 -2.37257361e-01 -1.07096218e-01 9.64700460e-01 -2.40631610e-01 -1.07095674e-01 9.63844955e-01 -2.44032323e-01 -1.07096262e-01 9.62964833e-01 -2.47485742e-01 -1.07095860e-01 9.62122202e-01 -2.50742674e-01 -1.07095681e-01 9.61243093e-01 -2.54101276e-01 -1.07096307e-01 9.60354745e-01 -2.57431060e-01 -1.07095711e-01 9.59469855e-01 -2.60712594e-01 -1.07095838e-01 9.58535731e-01 -2.64119625e-01 -1.07096285e-01 9.57600534e-01 -2.67499924e-01 -1.07095674e-01 9.56659496e-01 -2.70840019e-01 -1.07096106e-01 9.55679059e-01 -2.74272919e-01 -1.07095972e-01 9.54744339e-01 -2.77513355e-01 -1.07095703e-01 9.53801572e-01 -2.80735523e-01 -1.07095912e-01 9.52789783e-01 -2.84155965e-01 -1.07096136e-01 9.51770186e-01 -2.87542343e-01 -1.07095785e-01 9.50765073e-01 -2.90856302e-01 -1.07095994e-01 9.49759305e-01 -2.94127643e-01 -1.07095674e-01 9.48758543e-01 -2.97336251e-01 -1.07095867e-01 9.47715878e-01 -3.00643891e-01 -1.07095949e-01 9.46639717e-01 -3.04013044e-01 -1.07096046e-01 9.45523679e-01 -3.07465941e-01 -1.07095912e-01 9.44446981e-01 -3.10758591e-01 -1.07095852e-01 9.43385005e-01 -3.13968807e-01 -1.07095681e-01 9.42318738e-01 -3.17154318e-01 -1.07095890e-01 9.41207290e-01 -3.20437312e-01 -1.07095867e-01 9.40055966e-01 -3.23798239e-01 -1.07096173e-01 9.38906968e-01 -3.27114135e-01 -1.07095674e-01 9.37792897e-01 -3.30296814e-01 -1.07095808e-01 9.36637044e-01 -3.33558351e-01 -1.07095875e-01 9.35444951e-01 -3.36890727e-01 -1.07096173e-01 9.34255242e-01 -3.40179533e-01 -1.07095674e-01 9.33056712e-01 -3.43436837e-01 -1.07096165e-01 9.31843460e-01 -3.46698940e-01 -1.07095674e-01 9.30668890e-01 -3.49845976e-01 -1.07095852e-01 9.29444611e-01 -3.53097767e-01 -1.07095852e-01 9.28212821e-01 -3.56342018e-01 -1.07095838e-01 9.26951468e-01 -3.59594613e-01 -1.07095957e-01 9.25665975e-01 -3.62901866e-01 -1.07096151e-01 9.24391091e-01 -3.66130710e-01 -1.07095696e-01 9.23119247e-01 -3.69324207e-01 -1.07096151e-01 9.21815217e-01 -3.72566879e-01 -1.07095681e-01 9.20547426e-01 -3.75690460e-01 -1.07095867e-01 9.19194818e-01 -3.78985405e-01 -1.07096128e-01 9.17858601e-01 -3.82211864e-01 -1.07095674e-01 9.16523933e-01 -3.85404438e-01 -1.07096106e-01 9.15128767e-01 -3.88698131e-01 -1.07095994e-01 9.13798451e-01 -3.91815037e-01 -1.07095681e-01 9.12480354e-01 -3.94879729e-01 -1.07095838e-01 9.11063492e-01 -3.98142546e-01 -1.07096232e-01 9.09612536e-01 -4.01443541e-01 -1.07095987e-01 9.08200860e-01 -4.04626429e-01 -1.07095808e-01 9.06800210e-01 -4.07757103e-01 -1.07095681e-01 9.05401409e-01 -4.10851598e-01 -1.07095681e-01 9.04000461e-01 -4.13920522e-01 -1.07095890e-01 9.02518392e-01 -4.17144060e-01 -1.07096203e-01 9.01017547e-01 -4.20375764e-01 -1.07095875e-01 8.99521232e-01 -4.23569143e-01 -1.07095964e-01 8.98083091e-01 -4.26610738e-01 -1.07095681e-01 8.96645129e-01 -4.29622352e-01 -1.07095920e-01 8.95135164e-01 -4.32768583e-01 -1.07095920e-01 8.93580616e-01 -4.35970426e-01 -1.07096262e-01 8.92025888e-01 -4.39133883e-01 -1.07095681e-01 8.90484750e-01 -4.42251682e-01 -1.07096031e-01 8.88958156e-01 -4.45311815e-01 -1.07095681e-01 8.87448728e-01 -4.48316038e-01 -1.07095815e-01 8.85875404e-01 -4.51417506e-01 -1.07095920e-01 8.84254634e-01 -4.54582185e-01 -1.07096173e-01 8.82642329e-01 -4.57703590e-01 -1.07095756e-01 8.81056845e-01 -4.60750967e-01 -1.07095875e-01 8.79447341e-01 -4.63815749e-01 -1.07095681e-01 8.77854884e-01 -4.66818452e-01 -1.07095890e-01 8.76228034e-01 -4.69868869e-01 -1.07095912e-01 8.74535739e-01 -4.73010987e-01 -1.07096292e-01 8.72869790e-01 -4.76081669e-01 -1.07095681e-01 8.71251523e-01 -4.79032695e-01 -1.07095949e-01 8.69579434e-01 -4.82057989e-01 -1.07095741e-01 8.67856741e-01 -4.85154420e-01 -1.07096158e-01 8.66151094e-01 -4.88195777e-01 -1.07095674e-01 8.64440501e-01 -4.91215944e-01 -1.07096270e-01 8.62721503e-01 -4.94233370e-01 -1.07095681e-01 8.60998273e-01 -4.97225851e-01 -1.07096203e-01 8.59244704e-01 -5.00250041e-01 -1.07095711e-01 8.57541382e-01 -5.03166437e-01 -1.07095920e-01 8.55761230e-01 -5.06187141e-01 -1.07096091e-01 8.53974402e-01 -5.09194493e-01 -1.07095860e-01 8.52172017e-01 -5.12204885e-01 -1.07096121e-01 8.50347102e-01 -5.15226722e-01 -1.07095979e-01 8.48578155e-01 -5.18140316e-01 -1.07095674e-01 8.46816480e-01 -5.21009684e-01 -1.07095897e-01 8.44999611e-01 -5.23956954e-01 -1.07095838e-01 8.43122900e-01 -5.26966512e-01 -1.07096151e-01 8.41236651e-01 -5.29974937e-01 -1.07095852e-01 8.39421988e-01 -5.32841980e-01 -1.07095681e-01 8.37604105e-01 -5.35694361e-01 -1.07095875e-01 8.35678339e-01 -5.38696110e-01 -1.07096195e-01 8.33744466e-01 -5.41683435e-01 -1.07095934e-01 8.31849337e-01 -5.44587374e-01 -1.07095845e-01 8.29951286e-01 -5.47479630e-01 -1.07095957e-01 8.28069270e-01 -5.50315917e-01 -1.07095681e-01 8.26196611e-01 -5.53125381e-01 -1.07095912e-01 8.24277878e-01 -5.55987060e-01 -1.07095875e-01 8.22272837e-01 -5.58942676e-01 -1.07096262e-01 8.20260346e-01 -5.61894119e-01 -1.07095771e-01 8.18321168e-01 -5.64717233e-01 -1.07095890e-01 8.16386700e-01 -5.67507088e-01 -1.07095674e-01 8.14414084e-01 -5.70332944e-01 -1.07096076e-01 8.12402427e-01 -5.73197842e-01 -1.07095674e-01 8.10389042e-01 -5.76039076e-01 -1.07096203e-01 8.08364868e-01 -5.78878462e-01 -1.07095681e-01 8.06377769e-01 -5.81636727e-01 -1.07096002e-01 8.04302514e-01 -5.84508955e-01 -1.07096113e-01 8.02218020e-01 -5.87363958e-01 -1.07095897e-01 8.00147772e-01 -5.90182304e-01 -1.07096016e-01 7.98069477e-01 -5.92987955e-01 -1.07095957e-01 7.96057463e-01 -5.95686138e-01 -1.07095681e-01 7.93990076e-01 -5.98441601e-01 -1.07096232e-01 7.91887999e-01 -6.01219535e-01 -1.07095681e-01 7.89783061e-01 -6.03982389e-01 -1.07096180e-01 7.87663698e-01 -6.06741846e-01 -1.07095681e-01 7.85607040e-01 -6.09401941e-01 -1.07095927e-01 7.83421159e-01 -6.12211406e-01 -1.07096180e-01 7.81220675e-01 -6.15016103e-01 -1.07095927e-01 7.79122829e-01 -6.17670357e-01 -1.07095674e-01 7.77019918e-01 -6.20317757e-01 -1.07095927e-01 7.74801672e-01 -6.23085797e-01 -1.07096158e-01 7.72567928e-01 -6.25852942e-01 -1.07095934e-01 7.70409942e-01 -6.28502011e-01 -1.07095696e-01 7.68275857e-01 -6.31113887e-01 -1.07095897e-01 7.66073823e-01 -6.33784831e-01 -1.07095890e-01 7.63867676e-01 -6.36441052e-01 -1.07095934e-01 7.61649013e-01 -6.39095247e-01 -1.07095934e-01 7.59350717e-01 -6.41823530e-01 -1.07096151e-01 7.57102370e-01 -6.44473553e-01 -1.07095674e-01 7.54904568e-01 -6.47047222e-01 -1.07095957e-01 7.52648771e-01 -6.49671555e-01 -1.07095890e-01 7.50350595e-01 -6.52324498e-01 -1.07096069e-01 7.48001158e-01 -6.55015647e-01 -1.07096151e-01 7.45679438e-01 -6.57657146e-01 -1.07095897e-01 7.43427634e-01 -6.60202384e-01 -1.07095674e-01 7.41196632e-01 -6.62706017e-01 -1.07095912e-01 7.38821983e-01 -6.65352941e-01 -1.07096173e-01 7.36495256e-01 -6.67929173e-01 -1.07095674e-01 7.34153688e-01 -6.70500278e-01 -1.07096352e-01 7.31801629e-01 -6.73067093e-01 -1.07095696e-01 7.29534984e-01 -6.75522089e-01 -1.07095867e-01 7.27169514e-01 -6.78066254e-01 -1.07095934e-01 7.24734902e-01 -6.80667758e-01 -1.07096262e-01 7.22334623e-01 -6.83213055e-01 -1.07095681e-01 7.19934583e-01 -6.85747385e-01 -1.07096300e-01 7.17535198e-01 -6.88249111e-01 -1.07095681e-01 7.15154827e-01 -6.90738738e-01 -1.07096292e-01 7.12725043e-01 -6.93240881e-01 -1.07095689e-01 7.10386932e-01 -6.95632756e-01 -1.07095897e-01 7.07940817e-01 -6.98125184e-01 -1.07095920e-01 7.05470502e-01 -7.00619400e-01 -1.07096002e-01 7.02944100e-01 -7.03142703e-01 -1.07096128e-01 7.00439811e-01 -7.05643713e-01 -1.07096389e-01 6.98036373e-01 -7.08025336e-01 -1.07096724e-01 6.95610940e-01 -7.10405827e-01 -1.07096665e-01 6.93144798e-01 -7.12812424e-01 -1.07096940e-01 6.90598130e-01 -7.15273619e-01 -1.07097089e-01 6.88100636e-01 -7.17677236e-01 -1.07097402e-01 6.85707033e-01 -7.19956219e-01 -1.07097276e-01 6.83237553e-01 -7.22297788e-01 -1.07096978e-01 6.80954993e-01 -7.24451482e-01 -1.07097097e-01 6.78747952e-01 -7.26519465e-01 -1.07097045e-01 6.76169932e-01 -7.28920043e-01 -1.07097052e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 5.66548467e-01 -8.17039073e-01 -1.07097067e-01 5.64162195e-01 -8.18688750e-01 -1.07097238e-01 5.61559498e-01 -8.20482075e-01 -1.07097402e-01 5.58752716e-01 -8.22399259e-01 -1.07096776e-01 5.55894196e-01 -8.24336886e-01 -1.07096329e-01 5.53012908e-01 -8.26272666e-01 -1.07095778e-01 5.50103903e-01 -8.28211904e-01 -1.07096106e-01 5.47191799e-01 -8.30139279e-01 -1.07095674e-01 5.44381738e-01 -8.31983685e-01 -1.07095733e-01 5.41498959e-01 -8.33863616e-01 -1.07095823e-01 5.38562298e-01 -8.35764766e-01 -1.07095785e-01 5.35669684e-01 -8.37618709e-01 -1.07095875e-01 5.32745004e-01 -8.39483023e-01 -1.07095964e-01 5.29814899e-01 -8.41339171e-01 -1.07095972e-01 5.26886880e-01 -8.43171597e-01 -1.07095890e-01 5.23937106e-01 -8.45011592e-01 -1.07095912e-01 5.20984828e-01 -8.46831977e-01 -1.07095979e-01 5.18032253e-01 -8.48644733e-01 -1.07095934e-01 5.15059948e-01 -8.50448549e-01 -1.07095949e-01 5.12089729e-01 -8.52242112e-01 -1.07095890e-01 5.09039581e-01 -8.54067683e-01 -1.07096232e-01 5.06029785e-01 -8.55853140e-01 -1.07095681e-01 5.03140390e-01 -8.57555151e-01 -1.07095927e-01 5.00121951e-01 -8.59318197e-01 -1.07095920e-01 4.97046649e-01 -8.61102283e-01 -1.07096203e-01 4.94012684e-01 -8.62846017e-01 -1.07095681e-01 4.91091013e-01 -8.64510357e-01 -1.07095890e-01 4.88070399e-01 -8.66224051e-01 -1.07095942e-01 4.85058814e-01 -8.67910802e-01 -1.07095897e-01 4.82032567e-01 -8.69592905e-01 -1.07095987e-01 4.78983104e-01 -8.71280253e-01 -1.07095920e-01 4.75960106e-01 -8.72934759e-01 -1.07095778e-01 4.72874135e-01 -8.74608278e-01 -1.07095964e-01 4.69828248e-01 -8.76248419e-01 -1.07095852e-01 4.66759622e-01 -8.77886891e-01 -1.07095934e-01 4.63701487e-01 -8.79507899e-01 -1.07095890e-01 4.60549712e-01 -8.81160438e-01 -1.07096240e-01 4.57458109e-01 -8.82769227e-01 -1.07095681e-01 4.54458684e-01 -8.84319246e-01 -1.07095905e-01 4.51380014e-01 -8.85893881e-01 -1.07095897e-01 4.48278755e-01 -8.87467086e-01 -1.07095942e-01 4.45176214e-01 -8.89026225e-01 -1.07095860e-01 4.42061722e-01 -8.90580237e-01 -1.07096009e-01 4.38954175e-01 -8.92116308e-01 -1.07095934e-01 4.35824811e-01 -8.93650055e-01 -1.07095912e-01 4.32687730e-01 -8.95173311e-01 -1.07095920e-01 4.29578364e-01 -8.96666765e-01 -1.07095845e-01 4.26331639e-01 -8.98214698e-01 -1.07096300e-01 4.23179597e-01 -8.99704874e-01 -1.07095681e-01 4.20072168e-01 -9.01160598e-01 -1.07096240e-01 4.16895837e-01 -9.02634203e-01 -1.07095681e-01 4.13855851e-01 -9.04030323e-01 -1.07095897e-01 4.10696805e-01 -9.05472696e-01 -1.07095905e-01 4.07518029e-01 -9.06906784e-01 -1.07095912e-01 4.04272437e-01 -9.08359051e-01 -1.07096232e-01 4.01073843e-01 -9.09775198e-01 -1.07095674e-01 3.98003101e-01 -9.11123931e-01 -1.07095867e-01 3.94829959e-01 -9.12501454e-01 -1.07095979e-01 3.91626269e-01 -9.13878798e-01 -1.07095957e-01 3.88408840e-01 -9.15253222e-01 -1.07095972e-01 3.85222822e-01 -9.16600406e-01 -1.07095823e-01 3.82028669e-01 -9.17935252e-01 -1.07096002e-01 3.78808916e-01 -9.19268012e-01 -1.07095815e-01 3.75648350e-01 -9.20565188e-01 -1.07095912e-01 3.72429848e-01 -9.21871603e-01 -1.07096024e-01 3.69126588e-01 -9.23198521e-01 -1.07096188e-01 3.65870655e-01 -9.24494743e-01 -1.07095696e-01 3.62720639e-01 -9.25736606e-01 -1.07095867e-01 3.59497160e-01 -9.26985502e-01 -1.07095905e-01 3.56257230e-01 -9.28244412e-01 -1.07095964e-01 3.53003412e-01 -9.29480374e-01 -1.07095867e-01 3.49763036e-01 -9.30700243e-01 -1.07095964e-01 3.46498072e-01 -9.31919158e-01 -1.07095920e-01 3.43186647e-01 -9.33149278e-01 -1.07096225e-01 3.39908361e-01 -9.34354305e-01 -1.07095681e-01 3.36688429e-01 -9.35516596e-01 -1.07096098e-01 3.33412856e-01 -9.36690748e-01 -1.07095674e-01 3.30119342e-01 -9.37855840e-01 -1.07096173e-01 3.26841503e-01 -9.39001203e-01 -1.07095681e-01 3.23566914e-01 -9.40136433e-01 -1.07096188e-01 3.20268005e-01 -9.41263378e-01 -1.07095674e-01 3.17071080e-01 -9.42347288e-01 -1.07095979e-01 3.13765585e-01 -9.43451405e-01 -1.07096009e-01 3.10463905e-01 -9.44542706e-01 -1.07095771e-01 3.07196945e-01 -9.45610881e-01 -1.07095912e-01 3.03880364e-01 -9.46683586e-01 -1.07095934e-01 3.00589979e-01 -9.47732151e-01 -1.07095890e-01 2.97289550e-01 -9.48773861e-01 -1.07095942e-01 2.93967634e-01 -9.49807644e-01 -1.07095867e-01 2.90647089e-01 -9.50829864e-01 -1.07095905e-01 2.87275851e-01 -9.51850235e-01 -1.07096121e-01 2.83927023e-01 -9.52856719e-01 -1.07095674e-01 2.80672640e-01 -9.53820825e-01 -1.07095897e-01 2.77264446e-01 -9.54817653e-01 -1.07096180e-01 2.73844332e-01 -9.55803752e-01 -1.07095987e-01 2.70495892e-01 -9.56756830e-01 -1.07095867e-01 2.67267555e-01 -9.57664430e-01 -1.07095681e-01 2.64031917e-01 -9.58560705e-01 -1.07095897e-01 2.60672420e-01 -9.59482074e-01 -1.07095934e-01 2.57326782e-01 -9.60381567e-01 -1.07095920e-01 2.53878415e-01 -9.61299658e-01 -1.07096240e-01 2.50507057e-01 -9.62185025e-01 -1.07095681e-01 2.47155160e-01 -9.63049352e-01 -1.07096165e-01 2.43777379e-01 -9.63909388e-01 -1.07095681e-01 2.40448326e-01 -9.64745045e-01 -1.07096158e-01 2.37043276e-01 -9.65589762e-01 -1.07095681e-01 2.33768702e-01 -9.66388583e-01 -1.07095905e-01 2.30358765e-01 -9.67207670e-01 -1.07095987e-01 2.26976380e-01 -9.68006909e-01 -1.07095845e-01 2.23627716e-01 -9.68785226e-01 -1.07095890e-01 2.20132500e-01 -9.69583571e-01 -1.07096158e-01 2.16748357e-01 -9.70346987e-01 -1.07095681e-01 2.13453159e-01 -9.71075594e-01 -1.07095808e-01 2.10044071e-01 -9.71819222e-01 -1.07095838e-01 2.06673473e-01 -9.72541988e-01 -1.07095860e-01 2.03196853e-01 -9.73275542e-01 -1.07096106e-01 1.99768797e-01 -9.73984540e-01 -1.07095681e-01 1.96475014e-01 -9.74653125e-01 -1.07095897e-01 1.93064094e-01 -9.75334466e-01 -1.07095845e-01 1.89650223e-01 -9.76004601e-01 -1.07095934e-01 1.86162069e-01 -9.76674736e-01 -1.07096218e-01 1.82749122e-01 -9.77319181e-01 -1.07095681e-01 1.79351047e-01 -9.77947295e-01 -1.07095972e-01 1.75921485e-01 -9.78575885e-01 -1.07095681e-01 1.72606766e-01 -9.79165912e-01 -1.07095823e-01 1.69189483e-01 -9.79756415e-01 -1.07095912e-01 1.65779069e-01 -9.80341852e-01 -1.07095905e-01 1.62353158e-01 -9.80913043e-01 -1.07095942e-01 1.58934593e-01 -9.81473505e-01 -1.07095845e-01 1.55514747e-01 -9.82022047e-01 -1.07095897e-01 1.52091742e-01 -9.82557774e-01 -1.07095934e-01 1.48652956e-01 -9.83081758e-01 -1.07095860e-01 1.45181805e-01 -9.83601332e-01 -1.07096061e-01 1.41753301e-01 -9.84100103e-01 -1.07095726e-01 1.38336033e-01 -9.84587193e-01 -1.07095852e-01 1.34798914e-01 -9.85078990e-01 -1.07096158e-01 1.31360427e-01 -9.85542536e-01 -1.07095674e-01 1.28001735e-01 -9.85985100e-01 -1.07095785e-01 1.24572590e-01 -9.86425221e-01 -1.07095852e-01 1.21122047e-01 -9.86853123e-01 -1.07095897e-01 1.17577985e-01 -9.87282276e-01 -1.07096218e-01 1.14127807e-01 -9.87685740e-01 -1.07095681e-01 1.10790014e-01 -9.88067031e-01 -1.07095823e-01 1.07321516e-01 -9.88448679e-01 -1.07095793e-01 1.03888735e-01 -9.88815725e-01 -1.07095815e-01 1.00345634e-01 -9.89179969e-01 -1.07096083e-01 9.68874767e-02 -9.89526808e-01 -1.07095703e-01 9.34468806e-02 -9.89859700e-01 -1.07096180e-01 8.99720043e-02 -9.90180254e-01 -1.07095681e-01 8.65296721e-02 -9.90486979e-01 -1.07096061e-01 8.29850584e-02 -9.90789115e-01 -1.07095852e-01 7.96073079e-02 -9.91067410e-01 -1.07095681e-01 7.62423873e-02 -9.91330624e-01 -1.07095905e-01 7.27739185e-02 -9.91592824e-01 -1.07095830e-01 6.93161264e-02 -9.91838098e-01 -1.07095912e-01 6.58428520e-02 -9.92076218e-01 -1.07095890e-01 6.24000393e-02 -9.92299080e-01 -1.07095934e-01 5.89215495e-02 -9.92510974e-01 -1.07095875e-01 5.54497465e-02 -9.92712080e-01 -1.07095912e-01 5.19947782e-02 -9.92896557e-01 -1.07095815e-01 4.85408828e-02 -9.93074536e-01 -1.07095808e-01 4.50954959e-02 -9.93236244e-01 -1.07095905e-01 4.15127911e-02 -9.93390977e-01 -1.07096165e-01 3.80380750e-02 -9.93530214e-01 -1.07095681e-01 3.46894860e-02 -9.93652821e-01 -1.07095830e-01 3.11212353e-02 -9.93771076e-01 -1.07096083e-01 2.76312456e-02 -9.93875444e-01 -1.07095681e-01 2.41664462e-02 -9.93968129e-01 -1.07096195e-01 2.06785426e-02 -9.94041562e-01 -1.07095703e-01 1.73432380e-02 -9.94112313e-01 -1.07095852e-01 1.37744481e-02 -9.94157374e-01 -1.07096210e-01 1.02750361e-02 -9.94205356e-01 -1.07095689e-01 6.91741472e-03 -9.94241238e-01 -1.07095808e-01 3.43887182e-03 -9.94258344e-01 -1.07095860e-01 -3.72444192e-05 -9.94259417e-01 -1.07095890e-01 -3.60244606e-03 -9.94258225e-01 -1.07096143e-01 -7.06548570e-03 -9.94240165e-01 -1.07095681e-01 -1.05257547e-02 -9.94203866e-01 -1.07096113e-01 -1.39942039e-02 -9.94156003e-01 -1.07095681e-01 -1.74544342e-02 -9.94112074e-01 -1.07096121e-01 -2.10163016e-02 -9.94034886e-01 -1.07095830e-01 -2.44179592e-02 -9.93960798e-01 -1.07095674e-01 -2.78041214e-02 -9.93871152e-01 -1.07095845e-01 -3.12603265e-02 -9.93768752e-01 -1.07095905e-01 -3.47313918e-02 -9.93653715e-01 -1.07095987e-01 -3.82886827e-02 -9.93521571e-01 -1.07096203e-01 -4.17839736e-02 -9.93381262e-01 -1.07095674e-01 -4.51408736e-02 -9.93232965e-01 -1.07095897e-01 -4.85998392e-02 -9.93071735e-01 -1.07095890e-01 -5.20588048e-02 -9.92893219e-01 -1.07095860e-01 -5.55982366e-02 -9.92704809e-01 -1.07096151e-01 -5.90804853e-02 -9.92502332e-01 -1.07095681e-01 -6.25490695e-02 -9.92287040e-01 -1.07096106e-01 -6.60132319e-02 -9.92063999e-01 -1.07095674e-01 -6.93773627e-02 -9.91834402e-01 -1.07095852e-01 -7.29168504e-02 -9.91581857e-01 -1.07096173e-01 -7.63888210e-02 -9.91319180e-01 -1.07095681e-01 -7.98388198e-02 -9.91048276e-01 -1.07096083e-01 -8.33146572e-02 -9.90761042e-01 -1.07095674e-01 -8.66824910e-02 -9.90472853e-01 -1.07095867e-01 -9.02246162e-02 -9.90156174e-01 -1.07096180e-01 -9.36969668e-02 -9.89833236e-01 -1.07095681e-01 -9.71253365e-02 -9.89503443e-01 -1.07096180e-01 -1.00594148e-01 -9.89157438e-01 -1.07095703e-01 -1.04023278e-01 -9.88802969e-01 -1.07096270e-01 -1.07589714e-01 -9.88420665e-01 -1.07095815e-01 -1.10940427e-01 -9.88050103e-01 -1.07095681e-01 -1.14279442e-01 -9.87669110e-01 -1.07095867e-01 -1.17742926e-01 -9.87261772e-01 -1.07095912e-01 -1.21179052e-01 -9.86847043e-01 -1.07095920e-01 -1.24719508e-01 -9.86406624e-01 -1.07096203e-01 -1.28188118e-01 -9.85959411e-01 -1.07095674e-01 -1.31519377e-01 -9.85522389e-01 -1.07095890e-01 -1.34951711e-01 -9.85058129e-01 -1.07095830e-01 -1.38379797e-01 -9.84582961e-01 -1.07095979e-01 -1.41925007e-01 -9.84076560e-01 -1.07096136e-01 -1.45363808e-01 -9.83574450e-01 -1.07095681e-01 -1.48776650e-01 -9.83063579e-01 -1.07096195e-01 -1.52212441e-01 -9.82540071e-01 -1.07095681e-01 -1.55542463e-01 -9.82016385e-01 -1.07095875e-01 -1.58993766e-01 -9.81464684e-01 -1.07095920e-01 -1.62389636e-01 -9.80909348e-01 -1.07095823e-01 -1.65929303e-01 -9.80316937e-01 -1.07096225e-01 -1.69357643e-01 -9.79727805e-01 -1.07095681e-01 -1.72672004e-01 -9.79153812e-01 -1.07095949e-01 -1.76152691e-01 -9.78532612e-01 -1.07096069e-01 -1.79566249e-01 -9.77907181e-01 -1.07095718e-01 -1.83014348e-01 -9.77271676e-01 -1.07096165e-01 -1.86436698e-01 -9.76622343e-01 -1.07095689e-01 -1.89742401e-01 -9.75985646e-01 -1.07095845e-01 -1.93157986e-01 -9.75315750e-01 -1.07095860e-01 -1.96624950e-01 -9.74623322e-01 -1.07096121e-01 -2.00061604e-01 -9.73922074e-01 -1.07095681e-01 -2.03368753e-01 -9.73237514e-01 -1.07095867e-01 -2.06751123e-01 -9.72527444e-01 -1.07095934e-01 -2.10236281e-01 -9.71778691e-01 -1.07096121e-01 -2.13640898e-01 -9.71032202e-01 -1.07095674e-01 -2.16932356e-01 -9.70305681e-01 -1.07095852e-01 -2.20328256e-01 -9.69539046e-01 -1.07095920e-01 -2.23705754e-01 -9.68765080e-01 -1.07095845e-01 -2.27158844e-01 -9.67965245e-01 -1.07096128e-01 -2.30545148e-01 -9.67162073e-01 -1.07095674e-01 -2.33829066e-01 -9.66374338e-01 -1.07095890e-01 -2.37273782e-01 -9.65533137e-01 -1.07096106e-01 -2.40656242e-01 -9.64694023e-01 -1.07095674e-01 -2.44012475e-01 -9.63849545e-01 -1.07096083e-01 -2.47377083e-01 -9.62993920e-01 -1.07095681e-01 -2.50642508e-01 -9.62148130e-01 -1.07095793e-01 -2.54026383e-01 -9.61261690e-01 -1.07095830e-01 -2.57452667e-01 -9.60348427e-01 -1.07096180e-01 -2.60904551e-01 -9.59417284e-01 -1.07095808e-01 -2.64175326e-01 -9.58520234e-01 -1.07095681e-01 -2.67395288e-01 -9.57629263e-01 -1.07095949e-01 -2.70768076e-01 -9.56680536e-01 -1.07095838e-01 -2.74102807e-01 -9.55728829e-01 -1.07095830e-01 -2.77433455e-01 -9.54768836e-01 -1.07095838e-01 -2.80755758e-01 -9.53796208e-01 -1.07095897e-01 -2.84077018e-01 -9.52814102e-01 -1.07095890e-01 -2.87402213e-01 -9.51813340e-01 -1.07095890e-01 -2.90721327e-01 -9.50804234e-01 -1.07095934e-01 -2.94121623e-01 -9.49761808e-01 -1.07096165e-01 -2.97477603e-01 -9.48713720e-01 -1.07095674e-01 -3.00782979e-01 -9.47671831e-01 -1.07096091e-01 -3.04065436e-01 -9.46624577e-01 -1.07095681e-01 -3.07273775e-01 -9.45586622e-01 -1.07095852e-01 -3.10645819e-01 -9.44484293e-01 -1.07096180e-01 -3.14017892e-01 -9.43368256e-01 -1.07095771e-01 -3.17300022e-01 -9.42271590e-01 -1.07095905e-01 -3.20530564e-01 -9.41175401e-01 -1.07095681e-01 -3.23701441e-01 -9.40090060e-01 -1.07095875e-01 -3.27018321e-01 -9.38939810e-01 -1.07095942e-01 -3.30301076e-01 -9.37791586e-01 -1.07095860e-01 -3.33620310e-01 -9.36615169e-01 -1.07096076e-01 -3.36888641e-01 -9.35443997e-01 -1.07095674e-01 -3.40146333e-01 -9.34266627e-01 -1.07096061e-01 -3.43418896e-01 -9.33061004e-01 -1.07095674e-01 -3.46594930e-01 -9.31882262e-01 -1.07095852e-01 -3.49840134e-01 -9.30670261e-01 -1.07095852e-01 -3.53097975e-01 -9.29444969e-01 -1.07095912e-01 -3.56421202e-01 -9.28182662e-01 -1.07096158e-01 -3.59759927e-01 -9.26886141e-01 -1.07095890e-01 -3.62901628e-01 -9.25664663e-01 -1.07095681e-01 -3.66033077e-01 -9.24430370e-01 -1.07095852e-01 -3.69239599e-01 -9.23152864e-01 -1.07095875e-01 -3.72460574e-01 -9.21859205e-01 -1.07095830e-01 -3.75770539e-01 -9.20514584e-01 -1.07096173e-01 -3.79069924e-01 -9.19158876e-01 -1.07095845e-01 -3.82198811e-01 -9.17863965e-01 -1.07095681e-01 -3.85291904e-01 -9.16570127e-01 -1.07095912e-01 -3.88510585e-01 -9.15210307e-01 -1.07095934e-01 -3.91772985e-01 -9.13814425e-01 -1.07096180e-01 -3.94990623e-01 -9.12431598e-01 -1.07095696e-01 -3.98156554e-01 -9.11056936e-01 -1.07096009e-01 -4.01351064e-01 -9.09653068e-01 -1.07095703e-01 -4.04419690e-01 -9.08293247e-01 -1.07095905e-01 -4.07603711e-01 -9.06869531e-01 -1.07095793e-01 -4.10753548e-01 -9.05445218e-01 -1.07095823e-01 -4.13977355e-01 -9.03974831e-01 -1.07096165e-01 -4.17137682e-01 -9.02521193e-01 -1.07095681e-01 -4.20216709e-01 -9.01092470e-01 -1.07095890e-01 -4.23345000e-01 -8.99627268e-01 -1.07095897e-01 -4.26567852e-01 -8.98104250e-01 -1.07096158e-01 -4.29710001e-01 -8.96603167e-01 -1.07095674e-01 -4.32751358e-01 -8.95144105e-01 -1.07095890e-01 -4.35893804e-01 -8.93617630e-01 -1.07095852e-01 -4.39066976e-01 -8.92059684e-01 -1.07096128e-01 -4.42178786e-01 -8.90522838e-01 -1.07095674e-01 -4.45191950e-01 -8.89019370e-01 -1.07095964e-01 -4.48303759e-01 -8.87456119e-01 -1.07095912e-01 -4.51393545e-01 -8.85888100e-01 -1.07095934e-01 -4.54568595e-01 -8.84262323e-01 -1.07096225e-01 -4.57653165e-01 -8.82666826e-01 -1.07095681e-01 -4.60637957e-01 -8.81117225e-01 -1.07095890e-01 -4.63713348e-01 -8.79500926e-01 -1.07095852e-01 -4.66767848e-01 -8.77883255e-01 -1.07095957e-01 -4.69902784e-01 -8.76210809e-01 -1.07096136e-01 -4.72992986e-01 -8.74543726e-01 -1.07095681e-01 -4.76030558e-01 -8.72897089e-01 -1.07096151e-01 -4.79077816e-01 -8.71227503e-01 -1.07095681e-01 -4.82123017e-01 -8.69544089e-01 -1.07096292e-01 -4.85244930e-01 -8.67805958e-01 -1.07095875e-01 -4.88193303e-01 -8.66152108e-01 -1.07095681e-01 -4.91186917e-01 -8.64458203e-01 -1.07096329e-01 -4.94218975e-01 -8.62728536e-01 -1.07095681e-01 -4.97144192e-01 -8.61046135e-01 -1.07095942e-01 -5.00151396e-01 -8.59302521e-01 -1.07095942e-01 -5.03155887e-01 -8.57546985e-01 -1.07095890e-01 -5.06138682e-01 -8.55789185e-01 -1.07095882e-01 -5.09113610e-01 -8.54023099e-01 -1.07095852e-01 -5.12081325e-01 -8.52246583e-01 -1.07095905e-01 -5.15078485e-01 -8.50437760e-01 -1.07096061e-01 -5.18129885e-01 -8.48585188e-01 -1.07096128e-01 -5.21140277e-01 -8.46736848e-01 -1.07095949e-01 -5.24028480e-01 -8.44953716e-01 -1.07095674e-01 -5.26879787e-01 -8.43178630e-01 -1.07095927e-01 -5.29900253e-01 -8.41282785e-01 -1.07096270e-01 -5.32855868e-01 -8.39413643e-01 -1.07095674e-01 -5.35770118e-01 -8.37555587e-01 -1.07096225e-01 -5.38704634e-01 -8.35671127e-01 -1.07095681e-01 -5.41505516e-01 -8.33858967e-01 -1.07095927e-01 -5.44498801e-01 -8.31906617e-01 -1.07096247e-01 -5.47425508e-01 -8.29986572e-01 -1.07095681e-01 -5.50212264e-01 -8.28137696e-01 -1.07095905e-01 -5.53105354e-01 -8.26211274e-01 -1.07095838e-01 -5.56079686e-01 -8.24214518e-01 -1.07096225e-01 -5.58972716e-01 -8.22250783e-01 -1.07095681e-01 -5.61731815e-01 -8.20372820e-01 -1.07095875e-01 -5.64600110e-01 -8.18400979e-01 -1.07095897e-01 -5.67441940e-01 -8.16432297e-01 -1.07095994e-01 -5.70382953e-01 -8.14378977e-01 -1.07096314e-01 -5.73331952e-01 -8.12308967e-01 -1.07096009e-01 -5.76086223e-01 -8.10354769e-01 -1.07095681e-01 -5.78800797e-01 -8.08418989e-01 -1.07095957e-01 -5.81625402e-01 -8.06385159e-01 -1.07095875e-01 -5.84450841e-01 -8.04343879e-01 -1.07095972e-01 -5.87325156e-01 -8.02245975e-01 -1.07096165e-01 -5.90200782e-01 -8.00132573e-01 -1.07095920e-01 -5.92921734e-01 -7.98119843e-01 -1.07095681e-01 -5.95615327e-01 -7.96109319e-01 -1.07095920e-01 -5.98395526e-01 -7.94023454e-01 -1.07095987e-01 -6.01230800e-01 -7.91880488e-01 -1.07096232e-01 -6.04016483e-01 -7.89756477e-01 -1.07095681e-01 -6.06756389e-01 -7.87652910e-01 -1.07096247e-01 -6.09497607e-01 -7.85533488e-01 -1.07095674e-01 -6.12171173e-01 -7.83451796e-01 -1.07095920e-01 -6.14965796e-01 -7.81261504e-01 -1.07096240e-01 -6.17689013e-01 -7.79109240e-01 -1.07095674e-01 -6.20403290e-01 -7.76950479e-01 -1.07096225e-01 -6.23115718e-01 -7.74776876e-01 -1.07095681e-01 -6.25724316e-01 -7.72673845e-01 -1.07095942e-01 -6.28431737e-01 -7.70468891e-01 -1.07095994e-01 -6.31104410e-01 -7.68282831e-01 -1.07095897e-01 -6.33849084e-01 -7.66021311e-01 -1.07096247e-01 -6.36533439e-01 -7.63789833e-01 -1.07095681e-01 -6.39106214e-01 -7.61639655e-01 -1.07095897e-01 -6.41841471e-01 -7.59335816e-01 -1.07096300e-01 -6.44493341e-01 -7.57085383e-01 -1.07095681e-01 -6.47059858e-01 -7.54893184e-01 -1.07096016e-01 -6.49702072e-01 -7.52622843e-01 -1.07095890e-01 -6.52314365e-01 -7.50359893e-01 -1.07095897e-01 -6.55006528e-01 -7.48006999e-01 -1.07096277e-01 -6.57608569e-01 -7.45722413e-01 -1.07095674e-01 -6.60133541e-01 -7.43488252e-01 -1.07095890e-01 -6.62731409e-01 -7.41173208e-01 -1.07095942e-01 -6.65295899e-01 -7.38872647e-01 -1.07095927e-01 -6.67938948e-01 -7.36486614e-01 -1.07096121e-01 -6.70513690e-01 -7.34138310e-01 -1.07095718e-01 -6.73076212e-01 -7.31795490e-01 -1.07096180e-01 -6.75632477e-01 -7.29432225e-01 -1.07095674e-01 -6.78158879e-01 -7.27082372e-01 -1.07096225e-01 -6.80769324e-01 -7.24640846e-01 -1.07095964e-01 -6.83231175e-01 -7.22318232e-01 -1.07095674e-01 -6.85720205e-01 -7.19960570e-01 -1.07096210e-01 -6.88253522e-01 -7.17529953e-01 -1.07095674e-01 -6.90676630e-01 -7.15213358e-01 -1.07095957e-01 -6.93162143e-01 -7.12801814e-01 -1.07095942e-01 -6.95639908e-01 -7.10380733e-01 -1.07095920e-01 -6.98191762e-01 -7.07874954e-01 -1.07096314e-01 -7.00679302e-01 -7.05415189e-01 -1.07095681e-01 -7.03036368e-01 -7.03046620e-01 -1.07096054e-01 -7.05498159e-01 -7.00595498e-01 -1.07095942e-01 -7.08018899e-01 -6.98046565e-01 -1.07096344e-01 -7.10475504e-01 -6.95542693e-01 -1.07095681e-01 -7.12816179e-01 -6.93146944e-01 -1.07095920e-01 -7.15214968e-01 -6.90674305e-01 -1.07095912e-01 -7.17678428e-01 -6.88099742e-01 -1.07096225e-01 -7.20161259e-01 -6.85510635e-01 -1.07095957e-01 -7.22554922e-01 -6.82980657e-01 -1.07096054e-01 -7.24876344e-01 -6.80516839e-01 -1.07095681e-01 -7.27172315e-01 -6.78062379e-01 -1.07095934e-01 -7.29595959e-01 -6.75457060e-01 -1.07096173e-01 -7.31953561e-01 -6.72902465e-01 -1.07095674e-01 -7.34242082e-01 -6.70403302e-01 -1.07095979e-01 -7.36585617e-01 -6.67828262e-01 -1.07096009e-01 -7.38919079e-01 -6.65244102e-01 -1.07095957e-01 -7.41223454e-01 -6.62675679e-01 -1.07095830e-01 -7.43536770e-01 -6.60080910e-01 -1.07095987e-01 -7.45897710e-01 -6.57409132e-01 -1.07096218e-01 -7.48186946e-01 -6.54802799e-01 -1.07095674e-01 -7.50465691e-01 -6.52190685e-01 -1.07096270e-01 -7.52804458e-01 -6.49488270e-01 -1.07095897e-01 -7.55006969e-01 -6.46929562e-01 -1.07095696e-01 -7.57241070e-01 -6.44310296e-01 -1.07096285e-01 -7.59504318e-01 -6.41643643e-01 -1.07095674e-01 -7.61671066e-01 -6.39068007e-01 -1.07095972e-01 -7.63950348e-01 -6.36345267e-01 -1.07096195e-01 -7.66175270e-01 -6.33660734e-01 -1.07095674e-01 -7.68331885e-01 -6.31046534e-01 -1.07095957e-01 -7.70525038e-01 -6.28363431e-01 -1.07095964e-01 -7.72711515e-01 -6.25674307e-01 -1.07095860e-01 -7.74942517e-01 -6.22909188e-01 -1.07096277e-01 -7.77167976e-01 -6.20130420e-01 -1.07095934e-01 -7.79335260e-01 -6.17402852e-01 -1.07095942e-01 -7.81442285e-01 -6.14736080e-01 -1.07095718e-01 -7.83522308e-01 -6.12082601e-01 -1.07095942e-01 -7.85697818e-01 -6.09288514e-01 -1.07096225e-01 -7.87819564e-01 -6.06541514e-01 -1.07095674e-01 -7.89930105e-01 -6.03790402e-01 -1.07096314e-01 -7.92041600e-01 -6.01018071e-01 -1.07095674e-01 -7.94066012e-01 -5.98340809e-01 -1.07095920e-01 -7.96139836e-01 -5.95575690e-01 -1.07095927e-01 -7.98207462e-01 -5.92800796e-01 -1.07096024e-01 -8.00325632e-01 -5.89938283e-01 -1.07096232e-01 -8.02398860e-01 -5.87117374e-01 -1.07095733e-01 -8.04451525e-01 -5.84301949e-01 -1.07096285e-01 -8.06543231e-01 -5.81408024e-01 -1.07095845e-01 -8.08506370e-01 -5.78680336e-01 -1.07095674e-01 -8.10513675e-01 -5.75863361e-01 -1.07096255e-01 -8.12529802e-01 -5.73017955e-01 -1.07095674e-01 -8.14464688e-01 -5.70261478e-01 -1.07096016e-01 -8.16503108e-01 -5.67337394e-01 -1.07096337e-01 -8.18496168e-01 -5.64462125e-01 -1.07095681e-01 -8.20383906e-01 -5.61712921e-01 -1.07096076e-01 -8.22357655e-01 -5.58818638e-01 -1.07095934e-01 -8.24303210e-01 -5.55947840e-01 -1.07095979e-01 -8.26286614e-01 -5.52992165e-01 -1.07096307e-01 -8.28228593e-01 -5.50077975e-01 -1.07095674e-01 -8.30135226e-01 -5.47197163e-01 -1.07096262e-01 -8.32051933e-01 -5.44278622e-01 -1.07095696e-01 -8.33888888e-01 -5.41461527e-01 -1.07095934e-01 -8.35767746e-01 -5.38556218e-01 -1.07096024e-01 -8.37635636e-01 -5.35646021e-01 -1.07095942e-01 -8.39541256e-01 -5.32653809e-01 -1.07096188e-01 -8.41395617e-01 -5.29721558e-01 -1.07095696e-01 -8.43189776e-01 -5.26858568e-01 -1.07095897e-01 -8.45027447e-01 -5.23912013e-01 -1.07095979e-01 -8.46851170e-01 -5.20951867e-01 -1.07095942e-01 -8.48708689e-01 -5.17926335e-01 -1.07096195e-01 -8.50517094e-01 -5.14947593e-01 -1.07095689e-01 -8.52300286e-01 -5.11992633e-01 -1.07096225e-01 -8.54078174e-01 -5.09018362e-01 -1.07095696e-01 -8.55806231e-01 -5.06109416e-01 -1.07095957e-01 -8.57598186e-01 -5.03068626e-01 -1.07096210e-01 -8.59356105e-01 -5.00057518e-01 -1.07095718e-01 -8.61055255e-01 -4.97128665e-01 -1.07095942e-01 -8.62771690e-01 -4.94140655e-01 -1.07095957e-01 -8.64498496e-01 -4.91112202e-01 -1.07096061e-01 -8.66210639e-01 -4.88092363e-01 -1.07095987e-01 -8.67905855e-01 -4.85065520e-01 -1.07095964e-01 -8.69584799e-01 -4.82046813e-01 -1.07095979e-01 -8.71314466e-01 -4.78919983e-01 -1.07096262e-01 -8.72990668e-01 -4.75860298e-01 -1.07095674e-01 -8.74593318e-01 -4.72903103e-01 -1.07095912e-01 -8.76251817e-01 -4.69824433e-01 -1.07096046e-01 -8.77937317e-01 -4.66666520e-01 -1.07096277e-01 -8.79607737e-01 -4.63508427e-01 -1.07095875e-01 -8.81169498e-01 -4.60534841e-01 -1.07095674e-01 -8.82718921e-01 -4.57557678e-01 -1.07095957e-01 -8.84314954e-01 -4.54466313e-01 -1.07095927e-01 -8.85945201e-01 -4.51277882e-01 -1.07096285e-01 -8.87514651e-01 -4.48185444e-01 -1.07095674e-01 -8.89026105e-01 -4.45177615e-01 -1.07096039e-01 -8.90616059e-01 -4.41991121e-01 -1.07096218e-01 -8.92160594e-01 -4.38861579e-01 -1.07095681e-01 -8.93649697e-01 -4.35827106e-01 -1.07095957e-01 -8.95204306e-01 -4.32624310e-01 -1.07096247e-01 -8.96751046e-01 -4.29403245e-01 -1.07096009e-01 -8.98248434e-01 -4.26263332e-01 -1.07095957e-01 -8.99697244e-01 -4.23195153e-01 -1.07095681e-01 -9.01123405e-01 -4.20153141e-01 -1.07095934e-01 -9.02622044e-01 -4.16923404e-01 -1.07096210e-01 -9.04114008e-01 -4.13676023e-01 -1.07095934e-01 -9.05509233e-01 -4.10613567e-01 -1.07095689e-01 -9.06908810e-01 -4.07514900e-01 -1.07095927e-01 -9.08322752e-01 -4.04351324e-01 -1.07095957e-01 -9.09757316e-01 -4.01116431e-01 -1.07096247e-01 -9.11161840e-01 -3.97918016e-01 -1.07095681e-01 -9.12535131e-01 -3.94754440e-01 -1.07096262e-01 -9.13916528e-01 -3.91536325e-01 -1.07095674e-01 -9.15236771e-01 -3.88446927e-01 -1.07095912e-01 -9.16621983e-01 -3.85169715e-01 -1.07096270e-01 -9.17966545e-01 -3.81952733e-01 -1.07095681e-01 -9.19288635e-01 -3.78759354e-01 -1.07096203e-01 -9.20608759e-01 -3.75538707e-01 -1.07095681e-01 -9.21879649e-01 -3.72406155e-01 -1.07095927e-01 -9.23208892e-01 -3.69099319e-01 -1.07096128e-01 -9.24498260e-01 -3.65862280e-01 -1.07095681e-01 -9.25759435e-01 -3.62662554e-01 -1.07096240e-01 -9.27028060e-01 -3.59386712e-01 -1.07095681e-01 -9.28245783e-01 -3.56257319e-01 -1.07095905e-01 -9.29508746e-01 -3.52931052e-01 -1.07096203e-01 -9.30729985e-01 -3.49680364e-01 -1.07095681e-01 -9.31906164e-01 -3.46533120e-01 -1.07095934e-01 -9.33139503e-01 -3.43210906e-01 -1.07096165e-01 -9.34346497e-01 -3.39929909e-01 -1.07095681e-01 -9.35522020e-01 -3.36673617e-01 -1.07096165e-01 -9.36696827e-01 -3.33395690e-01 -1.07095674e-01 -9.37845826e-01 -3.30145091e-01 -1.07096136e-01 -9.38998640e-01 -3.26849520e-01 -1.07095674e-01 -9.40107465e-01 -3.23651224e-01 -1.07095920e-01 -9.41230118e-01 -3.20370495e-01 -1.07095912e-01 -9.42337453e-01 -3.17098111e-01 -1.07095927e-01 -9.43464398e-01 -3.13725293e-01 -1.07096128e-01 -9.44558978e-01 -3.10413808e-01 -1.07095696e-01 -9.45613980e-01 -3.07190120e-01 -1.07095912e-01 -9.46704626e-01 -3.03812444e-01 -1.07096195e-01 -9.47760224e-01 -3.00503522e-01 -1.07095681e-01 -9.48800743e-01 -2.97204047e-01 -1.07096203e-01 -9.49834943e-01 -2.93875813e-01 -1.07095681e-01 -9.50848341e-01 -2.90581495e-01 -1.07096225e-01 -9.51860726e-01 -2.87247628e-01 -1.07095681e-01 -9.52824473e-01 -2.84032971e-01 -1.07095912e-01 -9.53837454e-01 -2.80618757e-01 -1.07096240e-01 -9.54814374e-01 -2.77277917e-01 -1.07095681e-01 -9.55750048e-01 -2.74028271e-01 -1.07095912e-01 -9.56698775e-01 -2.70701170e-01 -1.07095897e-01 -9.57646430e-01 -2.67331153e-01 -1.07095867e-01 -9.58566606e-01 -2.64008433e-01 -1.07095905e-01 -9.59483683e-01 -2.60667443e-01 -1.07095890e-01 -9.60385799e-01 -2.57309347e-01 -1.07095942e-01 -9.61300015e-01 -2.53879011e-01 -1.07096218e-01 -9.62213457e-01 -2.50395209e-01 -1.07095920e-01 -9.63061690e-01 -2.47113228e-01 -1.07095681e-01 -9.63887095e-01 -2.43862391e-01 -1.07095942e-01 -9.64757264e-01 -2.40401268e-01 -1.07096218e-01 -9.65617657e-01 -2.36931533e-01 -1.07095912e-01 -9.66416061e-01 -2.33652905e-01 -1.07095681e-01 -9.67202246e-01 -2.30377614e-01 -1.07095882e-01 -9.67998922e-01 -2.27002591e-01 -1.07095897e-01 -9.68801498e-01 -2.23547369e-01 -1.07096091e-01 -9.69584882e-01 -2.20127389e-01 -1.07095681e-01 -9.70323563e-01 -2.16852471e-01 -1.07095905e-01 -9.71089125e-01 -2.13393107e-01 -1.07096113e-01 -9.71829474e-01 -2.09990919e-01 -1.07095681e-01 -9.72545207e-01 -2.06658766e-01 -1.07095830e-01 -9.73256886e-01 -2.03283548e-01 -1.07095838e-01 -9.73978937e-01 -1.99801371e-01 -1.07096046e-01 -9.74685013e-01 -1.96321830e-01 -1.07095912e-01 -9.75348592e-01 -1.92996323e-01 -1.07095696e-01 -9.76000190e-01 -1.89674929e-01 -1.07095860e-01 -9.76667285e-01 -1.86202228e-01 -1.07096091e-01 -9.77327168e-01 -1.82709709e-01 -1.07095867e-01 -9.77946043e-01 -1.79353431e-01 -1.07095674e-01 -9.78555918e-01 -1.76035225e-01 -1.07095771e-01 -9.79165435e-01 -1.72615752e-01 -1.07095860e-01 -9.79764879e-01 -1.69143900e-01 -1.07095987e-01 -9.80366170e-01 -1.65632203e-01 -1.07095800e-01 -9.80924547e-01 -1.62285477e-01 -1.07095681e-01 -9.81468499e-01 -1.58969551e-01 -1.07095890e-01 -9.82023358e-01 -1.55503288e-01 -1.07095823e-01 -9.82571065e-01 -1.52006671e-01 -1.07096113e-01 -9.83092666e-01 -1.48587584e-01 -1.07095681e-01 -9.83607292e-01 -1.45147815e-01 -1.07096203e-01 -9.84107554e-01 -1.41709834e-01 -1.07095696e-01 -9.84583080e-01 -1.38374910e-01 -1.07095875e-01 -9.85072374e-01 -1.34852335e-01 -1.07096121e-01 -9.85536873e-01 -1.31403983e-01 -1.07095681e-01 -9.85991895e-01 -1.27957225e-01 -1.07096158e-01 -9.86431420e-01 -1.24520302e-01 -1.07095681e-01 -9.86850977e-01 -1.21140815e-01 -1.07095852e-01 -9.87276196e-01 -1.17621809e-01 -1.07096180e-01 -9.87681806e-01 -1.14156492e-01 -1.07095681e-01 -9.88074303e-01 -1.10727735e-01 -1.07096113e-01 -9.88466084e-01 -1.07174397e-01 -1.07095808e-01 -9.88820672e-01 -1.03833005e-01 -1.07095703e-01 -9.89175498e-01 -1.00397103e-01 -1.07095934e-01 -9.89524901e-01 -9.69052389e-02 -1.07095748e-01 -9.89859045e-01 -9.34487283e-02 -1.07095771e-01 -9.90178108e-01 -8.99884030e-02 -1.07095823e-01 -9.90477622e-01 -8.66421163e-02 -1.07095785e-01 -9.90768552e-01 -8.32225680e-02 -1.07096002e-01 -9.91056979e-01 -7.97193870e-02 -1.07096307e-01 -9.91334319e-01 -7.61647150e-02 -1.07096344e-01 -9.91593957e-01 -7.27135316e-02 -1.07096948e-01 -9.91827726e-01 -6.94419444e-02 -1.07097432e-01 -9.92041826e-01 -6.62232712e-02 -1.07097276e-01 -9.92254972e-01 -6.29263520e-02 -1.07097052e-01 -9.92552817e-01 -5.80413491e-02 -1.07097052e-01 -9.92727280e-01 -5.49805835e-02 -1.07097059e-01 -9.92793620e-01 -5.37677668e-02 -1.07097052e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.93960142e-01 -2.39447504e-02 -1.07097052e-01 -9.94028568e-01 -2.09086705e-02 -1.07097052e-01 -9.94100153e-01 -1.71785895e-02 -1.07097052e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.95670080e-01 1.56381482e-03 -9.29440707e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.94084656e-01 5.61869778e-02 -9.29440707e-02 -9.93895233e-01 5.94397746e-02 -9.29440707e-02 -9.93674815e-01 6.30152002e-02 -9.29440483e-02 -9.93428469e-01 6.67486265e-02 -9.29436758e-02 -9.93216276e-01 6.97929412e-02 -9.29440334e-02 -9.92977202e-01 7.31592998e-02 -9.29432139e-02 -9.92725134e-01 7.65231922e-02 -9.29431766e-02 -9.92464840e-01 7.98831210e-02 -9.29431021e-02 -9.92182612e-01 8.33326131e-02 -9.29430500e-02 -9.91879940e-01 8.68918821e-02 -9.29428339e-02 -9.91558552e-01 9.04443115e-02 -9.29430798e-02 -9.91244316e-01 9.38071609e-02 -9.29431096e-02 -9.90916073e-01 9.72586721e-02 -9.29428414e-02 -9.90559697e-01 1.00821517e-01 -9.29429904e-02 -9.90203679e-01 1.04238689e-01 -9.29430947e-02 -9.89836276e-01 1.07696541e-01 -9.29428414e-02 -9.89455581e-01 1.11108400e-01 -9.29431170e-02 -9.89075541e-01 1.14452995e-01 -9.29429308e-02 -9.88658845e-01 1.18022226e-01 -9.29428264e-02 -9.88225937e-01 1.21572442e-01 -9.29430351e-02 -9.87798572e-01 1.25012398e-01 -9.29430202e-02 -9.87353981e-01 1.28462926e-01 -9.29429308e-02 -9.86898839e-01 1.31917790e-01 -9.29430127e-02 -9.86444294e-01 1.35252029e-01 -9.29431170e-02 -9.85974848e-01 1.38673648e-01 -9.29428264e-02 -9.85465407e-01 1.42226011e-01 -9.29429904e-02 -9.84974563e-01 1.45571113e-01 -9.29431021e-02 -9.84468520e-01 1.48994267e-01 -9.29428264e-02 -9.83922243e-01 1.52537718e-01 -9.29430500e-02 -9.83386099e-01 1.55952916e-01 -9.29430202e-02 -9.82837439e-01 1.59378543e-01 -9.29430053e-02 -9.82276976e-01 1.62798449e-01 -9.29430574e-02 -9.81714487e-01 1.66146055e-01 -9.29430798e-02 -9.81140554e-01 1.69514045e-01 -9.29429606e-02 -9.80537117e-01 1.73002869e-01 -9.29428339e-02 -9.79908228e-01 1.76518053e-01 -9.29429680e-02 -9.79294598e-01 1.79850414e-01 -9.29430872e-02 -9.78673458e-01 1.83237672e-01 -9.29428264e-02 -9.78003740e-01 1.86758250e-01 -9.29430202e-02 -9.77354050e-01 1.90128505e-01 -9.29430202e-02 -9.76679802e-01 1.93563700e-01 -9.29429978e-02 -9.76006925e-01 1.96916640e-01 -9.29431021e-02 -9.75341201e-01 2.00204879e-01 -9.29430500e-02 -9.74622190e-01 2.03690886e-01 -9.29428264e-02 -9.73876059e-01 2.07212970e-01 -9.29430202e-02 -9.73150253e-01 2.10599869e-01 -9.29429904e-02 -9.72404301e-01 2.14016989e-01 -9.29429233e-02 -9.71653402e-01 2.17395544e-01 -9.29430276e-02 -9.70907271e-01 2.20689014e-01 -9.29431170e-02 -9.70136642e-01 2.24079564e-01 -9.29428264e-02 -9.69315410e-01 2.27605209e-01 -9.29428786e-02 -9.68533278e-01 2.30888650e-01 -9.29431319e-02 -9.67763126e-01 2.34117910e-01 -9.29430053e-02 -9.66913462e-01 2.37609312e-01 -9.29428264e-02 -9.66045320e-01 2.41090193e-01 -9.29430574e-02 -9.65201378e-01 2.44450048e-01 -9.29429233e-02 -9.64349568e-01 2.47790635e-01 -9.29430500e-02 -9.63502884e-01 2.51059085e-01 -9.29430798e-02 -9.62635577e-01 2.54377276e-01 -9.29429755e-02 -9.61721241e-01 2.57818252e-01 -9.29428264e-02 -9.60783660e-01 2.61286318e-01 -9.29430127e-02 -9.59884107e-01 2.64552504e-01 -9.29431021e-02 -9.58966136e-01 2.67886639e-01 -9.29428264e-02 -9.57992375e-01 2.71343172e-01 -9.29428935e-02 -9.57035840e-01 2.74687499e-01 -9.29430202e-02 -9.56070423e-01 2.78031021e-01 -9.29429457e-02 -9.55118120e-01 2.81273454e-01 -9.29431096e-02 -9.54165280e-01 2.84505159e-01 -9.29430202e-02 -9.53137696e-01 2.87930727e-01 -9.29428264e-02 -9.52091873e-01 2.91366190e-01 -9.29429457e-02 -9.51067030e-01 2.94691622e-01 -9.29430202e-02 -9.50057566e-01 2.97914445e-01 -9.29431394e-02 -9.49019909e-01 3.01229388e-01 -9.29428264e-02 -9.47941899e-01 3.04594129e-01 -9.29430798e-02 -9.46900070e-01 3.07808638e-01 -9.29431021e-02 -9.45819259e-01 3.11132044e-01 -9.29428339e-02 -9.44712341e-01 3.14458907e-01 -9.29431170e-02 -9.43646848e-01 3.17650676e-01 -9.29430798e-02 -9.42497134e-01 3.21050227e-01 -9.29428339e-02 -9.41343546e-01 3.24410945e-01 -9.29430872e-02 -9.40206468e-01 3.27685922e-01 -9.29430872e-02 -9.39065814e-01 3.30947012e-01 -9.29430202e-02 -9.37910378e-01 3.34208518e-01 -9.29430649e-02 -9.36769128e-01 3.37385803e-01 -9.29431021e-02 -9.35576200e-01 3.40697616e-01 -9.29428264e-02 -9.34341729e-01 3.44043255e-01 -9.29430649e-02 -9.33155775e-01 3.47232044e-01 -9.29430872e-02 -9.31944549e-01 3.50489557e-01 -9.29428339e-02 -9.30699408e-01 3.53785157e-01 -9.29430500e-02 -9.29459155e-01 3.57052535e-01 -9.29430202e-02 -9.28200603e-01 3.60292494e-01 -9.29429978e-02 -9.26954806e-01 3.63483071e-01 -9.29431170e-02 -9.25719857e-01 3.66622418e-01 -9.29430798e-02 -9.24439967e-01 3.69836718e-01 -9.29430500e-02 -9.23118055e-01 3.73132318e-01 -9.29428339e-02 -9.21771288e-01 3.76444906e-01 -9.29429904e-02 -9.20478165e-01 3.79579723e-01 -9.29431096e-02 -9.19158518e-01 3.82782280e-01 -9.29428264e-02 -9.17777240e-01 3.86074603e-01 -9.29430872e-02 -9.16431904e-01 3.89255226e-01 -9.29430500e-02 -9.15068269e-01 3.92448753e-01 -9.29430351e-02 -9.13720191e-01 3.95576179e-01 -9.29431170e-02 -9.12376881e-01 3.98674488e-01 -9.29430574e-02 -9.10945714e-01 4.01936650e-01 -9.29428414e-02 -9.09495652e-01 4.05206680e-01 -9.29430351e-02 -9.08067286e-01 4.08393472e-01 -9.29430351e-02 -9.06636178e-01 4.11563367e-01 -9.29429755e-02 -9.05196130e-01 4.14712280e-01 -9.29430425e-02 -9.03763950e-01 4.17822540e-01 -9.29430872e-02 -9.02310133e-01 4.20963049e-01 -9.29428414e-02 -9.00808871e-01 4.24159378e-01 -9.29430351e-02 -8.99349689e-01 4.27241057e-01 -9.29431170e-02 -8.97904158e-01 4.30273056e-01 -9.29430574e-02 -8.96366060e-01 4.33481961e-01 -9.29428339e-02 -8.94808412e-01 4.36685294e-01 -9.29430202e-02 -8.93282712e-01 4.39788997e-01 -9.29430798e-02 -8.91754448e-01 4.42884296e-01 -9.29429904e-02 -8.90220702e-01 4.45951402e-01 -9.29431096e-02 -8.88700724e-01 4.48980153e-01 -9.29430574e-02 -8.87089789e-01 4.52159435e-01 -9.29428339e-02 -8.85462344e-01 4.55334872e-01 -9.29430351e-02 -8.83897126e-01 4.58353311e-01 -9.29431170e-02 -8.82323384e-01 4.61393803e-01 -9.29428339e-02 -8.80644798e-01 4.64583665e-01 -9.29430351e-02 -8.79025638e-01 4.67636734e-01 -9.29430649e-02 -8.77392232e-01 4.70696360e-01 -9.29430649e-02 -8.75785053e-01 4.73672062e-01 -9.29431096e-02 -8.74168932e-01 4.76661354e-01 -9.29430351e-02 -8.72460544e-01 4.79782522e-01 -9.29428414e-02 -8.70725989e-01 4.82909620e-01 -9.29430723e-02 -8.69047999e-01 4.85925257e-01 -9.29430649e-02 -8.67346108e-01 4.88964379e-01 -9.29430053e-02 -8.65628660e-01 4.91991073e-01 -9.29430723e-02 -8.63928854e-01 4.94971871e-01 -9.29431021e-02 -8.62237751e-01 4.97912079e-01 -9.29431021e-02 -8.60485971e-01 5.00937998e-01 -9.29428414e-02 -8.58689308e-01 5.04009485e-01 -9.29430500e-02 -8.56960654e-01 5.06935954e-01 -9.29431170e-02 -8.55203211e-01 5.09903729e-01 -9.29428563e-02 -8.53373826e-01 5.12956142e-01 -9.29430500e-02 -8.51570547e-01 5.15941501e-01 -9.29430649e-02 -8.49771142e-01 5.18906653e-01 -9.29430351e-02 -8.47943246e-01 5.21884203e-01 -9.29430202e-02 -8.46167088e-01 5.24757087e-01 -9.29431021e-02 -8.44344854e-01 5.27689993e-01 -9.29428488e-02 -8.42451274e-01 5.30706108e-01 -9.29430202e-02 -8.40586185e-01 5.33654273e-01 -9.29430053e-02 -8.38713229e-01 5.36592066e-01 -9.29430351e-02 -8.36849451e-01 5.39492846e-01 -9.29430500e-02 -8.34964931e-01 5.42403460e-01 -9.29430649e-02 -8.33064973e-01 5.45319617e-01 -9.29429904e-02 -8.31159174e-01 5.48218846e-01 -9.29430798e-02 -8.29276025e-01 5.51055968e-01 -9.29431170e-02 -8.27413917e-01 5.53857505e-01 -9.29429904e-02 -8.25430095e-01 5.56816697e-01 -9.29428264e-02 -8.23428214e-01 5.59764087e-01 -9.29430574e-02 -8.21484685e-01 5.62614679e-01 -9.29430500e-02 -8.19506586e-01 5.65495849e-01 -9.29430202e-02 -8.17522407e-01 5.68353713e-01 -9.29430649e-02 -8.15576375e-01 5.71138263e-01 -9.29431021e-02 -8.13574135e-01 5.73999226e-01 -9.29429084e-02 -8.11511338e-01 5.76902092e-01 -9.29430351e-02 -8.09548497e-01 5.79653859e-01 -9.29431170e-02 -8.07523549e-01 5.82476139e-01 -9.29428414e-02 -8.05446088e-01 5.85343719e-01 -9.29430723e-02 -8.03391218e-01 5.88158488e-01 -9.29430723e-02 -8.01336169e-01 5.90955675e-01 -9.29430574e-02 -7.99260199e-01 5.93759120e-01 -9.29430798e-02 -7.97248721e-01 5.96454203e-01 -9.29431170e-02 -7.95154214e-01 5.99256873e-01 -9.29428264e-02 -7.92985976e-01 6.02117717e-01 -9.29430574e-02 -7.90880322e-01 6.04879200e-01 -9.29430500e-02 -7.88823068e-01 6.07554436e-01 -9.29431170e-02 -7.86713839e-01 6.10288203e-01 -9.29428637e-02 -7.84515858e-01 6.13109112e-01 -9.29430723e-02 -7.82407701e-01 6.15794361e-01 -9.29431245e-02 -7.80274212e-01 6.18502080e-01 -9.29428488e-02 -7.78097153e-01 6.21231675e-01 -9.29431319e-02 -7.76003480e-01 6.23851180e-01 -9.29430500e-02 -7.73741901e-01 6.26658380e-01 -9.29428563e-02 -7.71500826e-01 6.29408360e-01 -9.29430798e-02 -7.69297063e-01 6.32100940e-01 -9.29430500e-02 -7.67069101e-01 6.34800971e-01 -9.29431096e-02 -7.64838576e-01 6.37487471e-01 -9.29430723e-02 -7.62623549e-01 6.40136898e-01 -9.29430500e-02 -7.60374248e-01 6.42806232e-01 -9.29430947e-02 -7.58136272e-01 6.45443797e-01 -9.29430574e-02 -7.55920589e-01 6.48032606e-01 -9.29431543e-02 -7.53669858e-01 6.50662065e-01 -9.29428264e-02 -7.51316965e-01 6.53370380e-01 -9.29430723e-02 -7.49025166e-01 6.55996501e-01 -9.29430202e-02 -7.46732354e-01 6.58604503e-01 -9.29430723e-02 -7.44415224e-01 6.61222935e-01 -9.29430947e-02 -7.42112577e-01 6.63807631e-01 -9.29430723e-02 -7.39866197e-01 6.66301668e-01 -9.29431692e-02 -7.37556756e-01 6.68874919e-01 -9.29428264e-02 -7.35133350e-01 6.71528637e-01 -9.29430276e-02 -7.32847452e-01 6.74016595e-01 -9.29431543e-02 -7.30507493e-01 6.76560700e-01 -9.29428563e-02 -7.28068471e-01 6.79177940e-01 -9.29431021e-02 -7.25720704e-01 6.81687653e-01 -9.29430574e-02 -7.23302543e-01 6.84254110e-01 -9.29429904e-02 -7.20953405e-01 6.86725438e-01 -9.29431468e-02 -7.18617916e-01 6.89167261e-01 -9.29430500e-02 -7.16158986e-01 6.91744387e-01 -9.29428264e-02 -7.13648438e-01 6.94325686e-01 -9.29430202e-02 -7.11204290e-01 6.96823001e-01 -9.29430574e-02 -7.08786368e-01 6.99284256e-01 -9.29430723e-02 -7.06393361e-01 7.01701045e-01 -9.29431096e-02 -7.03933418e-01 7.04155385e-01 -9.29428637e-02 -7.01433480e-01 7.06661701e-01 -9.29430649e-02 -6.98961854e-01 7.09104836e-01 -9.29430872e-02 -6.96553767e-01 7.11464226e-01 -9.29431394e-02 -6.94060206e-01 7.13909447e-01 -9.29428339e-02 -6.91481352e-01 7.16406643e-01 -9.29430351e-02 -6.88967645e-01 7.18807220e-01 -9.29430723e-02 -6.86448276e-01 7.21224546e-01 -9.29430500e-02 -6.83941007e-01 7.23596156e-01 -9.29431021e-02 -6.81449771e-01 7.25940168e-01 -9.29431096e-02 -6.78917110e-01 7.28312850e-01 -9.29429904e-02 -6.76324129e-01 7.30722964e-01 -9.29430723e-02 -6.73766196e-01 7.33086288e-01 -9.29430351e-02 -6.71264589e-01 7.35368013e-01 -9.29431394e-02 -6.68707192e-01 7.37704456e-01 -9.29428488e-02 -6.66050315e-01 7.40099370e-01 -9.29430723e-02 -6.63528204e-01 7.42356598e-01 -9.29431170e-02 -6.60940886e-01 7.44667888e-01 -9.29429904e-02 -6.58290923e-01 7.47009337e-01 -9.29430798e-02 -6.55741155e-01 7.49245584e-01 -9.29431170e-02 -6.53122783e-01 7.51535356e-01 -9.29428488e-02 -6.50419295e-01 7.53873348e-01 -9.29430500e-02 -6.47779763e-01 7.56144404e-01 -9.29430351e-02 -6.45134866e-01 7.58398592e-01 -9.29430649e-02 -6.42495811e-01 7.60637760e-01 -9.29430574e-02 -6.39837325e-01 7.62875676e-01 -9.29430351e-02 -6.37155890e-01 7.65118897e-01 -9.29430351e-02 -6.34493053e-01 7.67324746e-01 -9.29430649e-02 -6.31883264e-01 7.69473255e-01 -9.29431543e-02 -6.29262745e-01 7.71620154e-01 -9.29430500e-02 -6.26495063e-01 7.73874581e-01 -9.29428414e-02 -6.23735607e-01 7.76093304e-01 -9.29431021e-02 -6.21032000e-01 7.78262377e-01 -9.29429904e-02 -6.18284762e-01 7.80443013e-01 -9.29430872e-02 -6.15554631e-01 7.82601893e-01 -9.29430649e-02 -6.12893462e-01 7.84682631e-01 -9.29431170e-02 -6.10163629e-01 7.86815822e-01 -9.29428339e-02 -6.07326388e-01 7.89001524e-01 -9.29430723e-02 -6.04628325e-01 7.91067719e-01 -9.29431394e-02 -6.01882458e-01 7.93166220e-01 -9.29428414e-02 -5.99022031e-01 7.95325696e-01 -9.29430500e-02 -5.96255600e-01 7.97400117e-01 -9.29430649e-02 -5.93483925e-01 7.99466133e-01 -9.29430723e-02 -5.90767980e-01 8.01472247e-01 -9.29431170e-02 -5.87997735e-01 8.03509176e-01 -9.29430425e-02 -5.85128248e-01 8.05605590e-01 -9.29428488e-02 -5.82302451e-01 8.07640553e-01 -9.29431468e-02 -5.79477966e-01 8.09679627e-01 -9.29428414e-02 -5.76634228e-01 8.11699808e-01 -9.29431617e-02 -5.73837936e-01 8.13690662e-01 -9.29428264e-02 -5.70885777e-01 8.15756619e-01 -9.29430500e-02 -5.68083763e-01 8.17706287e-01 -9.29431319e-02 -5.65270841e-01 8.19660604e-01 -9.29428488e-02 -5.62406778e-01 8.21620703e-01 -9.29431617e-02 -5.59532106e-01 8.23588252e-01 -9.29429010e-02 -5.56634426e-01 8.25544775e-01 -9.29431170e-02 -5.53814113e-01 8.27443540e-01 -9.29429531e-02 -5.50833046e-01 8.29428911e-01 -9.29429159e-02 -5.47882378e-01 8.31381440e-01 -9.29430425e-02 -5.45041800e-01 8.33241582e-01 -9.29431468e-02 -5.42245090e-01 8.35070074e-01 -9.29430351e-02 -5.39237440e-01 8.37018132e-01 -9.29428339e-02 -5.36295056e-01 8.38898480e-01 -9.29431319e-02 -5.33397734e-01 8.40749741e-01 -9.29428414e-02 -5.30450642e-01 8.42607677e-01 -9.29431319e-02 -5.27516484e-01 8.44451308e-01 -9.29428414e-02 -5.24488091e-01 8.46335471e-01 -9.29430574e-02 -5.21511078e-01 8.48170877e-01 -9.29430574e-02 -5.18620193e-01 8.49941909e-01 -9.29431096e-02 -5.15696585e-01 8.51721525e-01 -9.29428786e-02 -5.12618124e-01 8.53577852e-01 -9.29428935e-02 -5.09681046e-01 8.55331004e-01 -9.29431170e-02 -5.06716132e-01 8.57096553e-01 -9.29428414e-02 -5.03717363e-01 8.58857393e-01 -9.29431170e-02 -5.00737369e-01 8.60604644e-01 -9.29428339e-02 -4.97637630e-01 8.62396538e-01 -9.29430872e-02 -4.94713277e-01 8.64074349e-01 -9.29431170e-02 -4.91685808e-01 8.65805745e-01 -9.29428414e-02 -4.88630474e-01 8.67530644e-01 -9.29431096e-02 -4.85617101e-01 8.69223118e-01 -9.29428563e-02 -4.82526988e-01 8.70937109e-01 -9.29430872e-02 -4.79502946e-01 8.72612238e-01 -9.29428563e-02 -4.76394057e-01 8.74314725e-01 -9.29429904e-02 -4.73304778e-01 8.75986874e-01 -9.29430053e-02 -4.70341682e-01 8.77576351e-01 -9.29431468e-02 -4.67398405e-01 8.79151762e-01 -9.29430723e-02 -4.64224547e-01 8.80835354e-01 -9.29428339e-02 -4.61141974e-01 8.82447183e-01 -9.29431617e-02 -4.58063066e-01 8.84055376e-01 -9.29428414e-02 -4.54913259e-01 8.85675609e-01 -9.29431021e-02 -4.51821625e-01 8.87259126e-01 -9.29429457e-02 -4.48690891e-01 8.88845146e-01 -9.29430574e-02 -4.45570201e-01 8.90415728e-01 -9.29430351e-02 -4.42552269e-01 8.91915441e-01 -9.29431170e-02 -4.39530402e-01 8.93411279e-01 -9.29430351e-02 -4.36339051e-01 8.94973934e-01 -9.29430798e-02 -4.33199465e-01 8.96496475e-01 -9.29431543e-02 -4.30067241e-01 8.98006618e-01 -9.29428264e-02 -4.26911384e-01 8.99505854e-01 -9.29431394e-02 -4.23803389e-01 9.00976539e-01 -9.29430351e-02 -4.20643091e-01 9.02455509e-01 -9.29431170e-02 -4.17500645e-01 9.03919339e-01 -9.29428563e-02 -4.14278805e-01 9.05394256e-01 -9.29430872e-02 -4.11108822e-01 9.06839728e-01 -9.29430649e-02 -4.07943666e-01 9.08271194e-01 -9.29430649e-02 -4.04816955e-01 9.09663796e-01 -9.29431543e-02 -4.01666313e-01 9.11062956e-01 -9.29429606e-02 -3.98417115e-01 9.12489414e-01 -9.29430649e-02 -3.95219952e-01 9.13876116e-01 -9.29430723e-02 -3.92088830e-01 9.15216744e-01 -9.29431394e-02 -3.88951629e-01 9.16561902e-01 -9.29430500e-02 -3.85711730e-01 9.17932570e-01 -9.29429233e-02 -3.82499158e-01 9.19270813e-01 -9.29431170e-02 -3.79313052e-01 9.20594513e-01 -9.29429457e-02 -3.76061291e-01 9.21921611e-01 -9.29431841e-02 -3.72846842e-01 9.23233569e-01 -9.29428414e-02 -3.69544238e-01 9.24556851e-01 -9.29430649e-02 -3.66311997e-01 9.25845027e-01 -9.29430425e-02 -3.63193452e-01 9.27066445e-01 -9.29431543e-02 -3.59983265e-01 9.28320825e-01 -9.29428488e-02 -3.56640369e-01 9.29615915e-01 -9.29430723e-02 -3.53452086e-01 9.30821359e-01 -9.29431170e-02 -3.50209951e-01 9.32047427e-01 -9.29428861e-02 -3.46948266e-01 9.33258832e-01 -9.29431319e-02 -3.43722522e-01 9.34460878e-01 -9.29429904e-02 -3.40407878e-01 9.35676277e-01 -9.29431543e-02 -3.37139845e-01 9.36858714e-01 -9.29430649e-02 -3.33808661e-01 9.38052654e-01 -9.29430947e-02 -3.30540568e-01 9.39207733e-01 -9.29430947e-02 -3.27255577e-01 9.40357625e-01 -9.29430723e-02 -3.24033022e-01 9.41472113e-01 -9.29431170e-02 -3.20763528e-01 9.42594707e-01 -9.29428414e-02 -3.17403495e-01 9.43730593e-01 -9.29430649e-02 -3.14077854e-01 9.44838524e-01 -9.29431021e-02 -3.10872227e-01 9.45897043e-01 -9.29431543e-02 -3.07654619e-01 9.46951807e-01 -9.29431021e-02 -3.04279268e-01 9.48046625e-01 -9.29428414e-02 -3.00949365e-01 9.49101031e-01 -9.29431468e-02 -2.97741383e-01 9.50113535e-01 -9.29431170e-02 -2.94434369e-01 9.51143086e-01 -9.29431096e-02 -2.91031957e-01 9.52194512e-01 -9.29428935e-02 -2.87679970e-01 9.53206003e-01 -9.29431543e-02 -2.84364462e-01 9.54205155e-01 -9.29429606e-02 -2.81036168e-01 9.55188513e-01 -9.29431170e-02 -2.77709097e-01 9.56165671e-01 -9.29428563e-02 -2.74319559e-01 9.57140863e-01 -9.29430798e-02 -2.71042556e-01 9.58071291e-01 -9.29431170e-02 -2.67691672e-01 9.59017813e-01 -9.29429829e-02 -2.64308721e-01 9.59951222e-01 -9.29431096e-02 -2.60946453e-01 9.60878074e-01 -9.29428563e-02 -2.57608593e-01 9.61769581e-01 -9.29431543e-02 -2.54261881e-01 9.62666452e-01 -9.29429084e-02 -2.50827700e-01 9.63564694e-01 -9.29430723e-02 -2.47465774e-01 9.64432120e-01 -9.29430723e-02 -2.44090110e-01 9.65290844e-01 -9.29430723e-02 -2.40801498e-01 9.66113925e-01 -9.29431543e-02 -2.37452969e-01 9.66948986e-01 -9.29429159e-02 -2.33978331e-01 9.67794538e-01 -9.29431021e-02 -2.30600551e-01 9.68605280e-01 -9.29430872e-02 -2.27284625e-01 9.69384909e-01 -9.29431170e-02 -2.23977521e-01 9.70157027e-01 -9.29430872e-02 -2.20534399e-01 9.70947206e-01 -9.29429308e-02 -2.17145890e-01 9.71707642e-01 -9.29431021e-02 -2.13823378e-01 9.72444296e-01 -9.29430574e-02 -2.10438952e-01 9.73183334e-01 -9.29430574e-02 -2.06973195e-01 9.73928034e-01 -9.29429233e-02 -2.03566030e-01 9.74643052e-01 -9.29431021e-02 -2.00174049e-01 9.75348592e-01 -9.29430202e-02 -1.96776927e-01 9.76033628e-01 -9.29431468e-02 -1.93335325e-01 9.76727188e-01 -9.29428339e-02 -1.89827174e-01 9.77412164e-01 -9.29430574e-02 -1.86507970e-01 9.78048027e-01 -9.29431543e-02 -1.83096319e-01 9.78699565e-01 -9.29428339e-02 -1.79696277e-01 9.79316592e-01 -9.29432437e-02 -1.76272795e-01 9.79953468e-01 -9.29429159e-02 -1.72846705e-01 9.80558634e-01 -9.29431543e-02 -1.69539899e-01 9.81134415e-01 -9.29430574e-02 -1.65989086e-01 9.81746435e-01 -9.29428339e-02 -1.62454188e-01 9.82331991e-01 -9.29430723e-02 -1.59007087e-01 9.82897162e-01 -9.29430574e-02 -1.55695856e-01 9.83422339e-01 -9.29431692e-02 -1.52394950e-01 9.83943224e-01 -9.29430798e-02 -1.48820490e-01 9.84492898e-01 -9.29428339e-02 -1.45279989e-01 9.85019028e-01 -9.29430649e-02 -1.41833127e-01 9.85520542e-01 -9.29430872e-02 -1.38491839e-01 9.85993147e-01 -9.29431543e-02 -1.35164738e-01 9.86459672e-01 -9.29430872e-02 -1.31692171e-01 9.86928344e-01 -9.29430574e-02 -1.28249124e-01 9.87380624e-01 -9.29430574e-02 -1.24703228e-01 9.87839162e-01 -9.29428414e-02 -1.21167973e-01 9.88274217e-01 -9.29430798e-02 -1.17822915e-01 9.88674700e-01 -9.29431468e-02 -1.14368349e-01 9.89086032e-01 -9.29428339e-02 -1.10909849e-01 9.89476025e-01 -9.29431468e-02 -1.07559063e-01 9.89847898e-01 -9.29430723e-02 -1.03982598e-01 9.90233481e-01 -9.29428488e-02 -1.00429945e-01 9.90595996e-01 -9.29430723e-02 -9.69658121e-02 9.90941882e-01 -9.29430798e-02 -9.35231671e-02 9.91275847e-01 -9.29430500e-02 -9.00516286e-02 9.91595268e-01 -9.29430574e-02 -8.66932347e-02 9.91892457e-01 -9.29431394e-02 -8.33212510e-02 9.92182791e-01 -9.29430574e-02 -7.97592700e-02 9.92477834e-01 -9.29428414e-02 -7.61927590e-02 9.92755353e-01 -9.29430872e-02 -7.27239475e-02 9.93018031e-01 -9.29430351e-02 -6.93708882e-02 9.93252516e-01 -9.29431394e-02 -6.59914985e-02 9.93486762e-01 -9.29430649e-02 -6.25222102e-02 9.93707836e-01 -9.29430872e-02 -5.89590818e-02 9.93929088e-01 -9.29429010e-02 -5.53944409e-02 9.94134665e-01 -9.29430425e-02 -5.18977419e-02 9.94318902e-01 -9.29431021e-02 -4.85271551e-02 9.94488776e-01 -9.29431617e-02 -4.50807847e-02 9.94654894e-01 -9.29428563e-02 -4.16084453e-02 9.94803309e-01 -9.29431543e-02 -3.81371975e-02 9.94946837e-01 -9.29428339e-02 -3.45428325e-02 9.95074689e-01 -9.29430872e-02 -3.11834086e-02 9.95183945e-01 -9.29431394e-02 -2.77322158e-02 9.95291114e-01 -9.29428563e-02 -2.42365915e-02 9.95380044e-01 -9.29431543e-02 -2.07438730e-02 9.95458484e-01 -9.29428264e-02 -1.71608478e-02 9.95532751e-01 -9.29430500e-02 -1.36896595e-02 9.95576501e-01 -9.29430872e-02 -1.02147749e-02 9.95622635e-01 -9.29430798e-02 -6.83149276e-03 9.95650947e-01 -9.29432064e-02 -3.34306923e-03 9.95676696e-01 -9.29428861e-02 1.28141619e-04 9.95672464e-01 -9.29431543e-02 3.47359478e-03 9.95673656e-01 -9.29430947e-02 7.06827547e-03 9.95657265e-01 -9.29429904e-02 1.06386039e-02 9.95616198e-01 -9.29430872e-02 1.41282445e-02 9.95569408e-01 -9.29431096e-02 1.76127702e-02 9.95523870e-01 -9.29430723e-02 2.09897570e-02 9.95449960e-01 -9.29431617e-02 2.43702531e-02 9.95377719e-01 -9.29430798e-02 2.79429108e-02 9.95286286e-01 -9.29428563e-02 3.15188281e-02 9.95175779e-01 -9.29430872e-02 3.48861180e-02 9.95061457e-01 -9.29431543e-02 3.82447690e-02 9.94941056e-01 -9.29430798e-02 4.18222547e-02 9.94798124e-01 -9.29428786e-02 4.53272872e-02 9.94639397e-01 -9.29431319e-02 4.87575233e-02 9.94484603e-01 -9.29429010e-02 5.23353666e-02 9.94293511e-01 -9.29431543e-02 5.57553023e-02 9.94112313e-01 -9.29431021e-02 5.92355356e-02 9.93911982e-01 -9.29430351e-02 6.27457500e-02 9.93693471e-01 -9.29430872e-02 6.61948100e-02 9.93471205e-01 -9.29430872e-02 6.95995912e-02 9.93233263e-01 -9.29431617e-02 7.30722025e-02 9.92991984e-01 -9.29429233e-02 7.66177624e-02 9.92721975e-01 -9.29430649e-02 8.00707936e-02 9.92450535e-01 -9.29430872e-02 8.35156143e-02 9.92164433e-01 -9.29431021e-02 8.69876221e-02 9.91866469e-01 -9.29431021e-02 9.03599411e-02 9.91564035e-01 -9.29431170e-02 9.38015431e-02 9.91248488e-01 -9.29430500e-02 9.73811224e-02 9.90899146e-01 -9.29431170e-02 1.00824006e-01 9.90557075e-01 -9.29431021e-02 1.04217060e-01 9.90204871e-01 -9.29431170e-02 1.07591115e-01 9.89842951e-01 -9.29431021e-02 1.11050628e-01 9.89466190e-01 -9.29429010e-02 1.14599153e-01 9.89057958e-01 -9.29430574e-02 1.18121438e-01 9.88643348e-01 -9.29430649e-02 1.21570662e-01 9.88225818e-01 -9.29430500e-02 1.24921292e-01 9.87805665e-01 -9.29431468e-02 1.28356308e-01 9.87368822e-01 -9.29428414e-02 1.31839544e-01 9.86904621e-01 -9.29431766e-02 1.35247082e-01 9.86450016e-01 -9.29428414e-02 1.38817072e-01 9.85952199e-01 -9.29430649e-02 1.42191693e-01 9.85465586e-01 -9.29431841e-02 1.45588472e-01 9.84974742e-01 -9.29428488e-02 1.49111092e-01 9.84445274e-01 -9.29430947e-02 1.52574390e-01 9.83916759e-01 -9.29430798e-02 1.55918613e-01 9.83385563e-01 -9.29431915e-02 1.59322590e-01 9.82847691e-01 -9.29428563e-02 1.62868410e-01 9.82264102e-01 -9.29430947e-02 1.66196451e-01 9.81703341e-01 -9.29431468e-02 1.69574112e-01 9.81129766e-01 -9.29429904e-02 1.73063293e-01 9.80520129e-01 -9.29431468e-02 1.76370010e-01 9.79932487e-01 -9.29430798e-02 1.79868624e-01 9.79292274e-01 -9.29430872e-02 1.83380067e-01 9.78641748e-01 -9.29430872e-02 1.86813951e-01 9.77991879e-01 -9.29430872e-02 1.90221518e-01 9.77334321e-01 -9.29430798e-02 1.93561986e-01 9.76678431e-01 -9.29431319e-02 1.96871430e-01 9.76017535e-01 -9.29430649e-02 2.00276628e-01 9.75322604e-01 -9.29431021e-02 2.03767002e-01 9.74606097e-01 -9.29428339e-02 2.07256496e-01 9.73866761e-01 -9.29430574e-02 2.10632548e-01 9.73141789e-01 -9.29431021e-02 2.14009449e-01 9.72404361e-01 -9.29430202e-02 2.17337355e-01 9.71662879e-01 -9.29431170e-02 2.20735729e-01 9.70897675e-01 -9.29430649e-02 2.24197656e-01 9.70105052e-01 -9.29431021e-02 2.27579072e-01 9.69316304e-01 -9.29431319e-02 2.30980918e-01 9.68515396e-01 -9.29430723e-02 2.34266296e-01 9.67722416e-01 -9.29431170e-02 2.37673670e-01 9.66894627e-01 -9.29429904e-02 2.41034210e-01 9.66056943e-01 -9.29431319e-02 2.44380742e-01 9.65219319e-01 -9.29428563e-02 2.47861505e-01 9.64331508e-01 -9.29430798e-02 2.51206547e-01 9.63463306e-01 -9.29430872e-02 2.54541099e-01 9.62590158e-01 -9.29430649e-02 2.57944316e-01 9.61683333e-01 -9.29430723e-02 2.61210680e-01 9.60798740e-01 -9.29431692e-02 2.64560848e-01 9.59884822e-01 -9.29428563e-02 2.67984718e-01 9.58934188e-01 -9.29430798e-02 2.71328866e-01 9.57994223e-01 -9.29430723e-02 2.74636358e-01 9.57048535e-01 -9.29431021e-02 2.77932942e-01 9.56097305e-01 -9.29430872e-02 2.81341434e-01 9.55101550e-01 -9.29429904e-02 2.84622192e-01 9.54125524e-01 -9.29431543e-02 2.87923962e-01 9.53137755e-01 -9.29428563e-02 2.91325510e-01 9.52103078e-01 -9.29430723e-02 2.94567019e-01 9.51102138e-01 -9.29431319e-02 2.97887087e-01 9.50073481e-01 -9.29428339e-02 3.01215112e-01 9.49016154e-01 -9.29431319e-02 3.04489225e-01 9.47976351e-01 -9.29429159e-02 3.07906806e-01 9.46870446e-01 -9.29430351e-02 3.11241716e-01 9.45779324e-01 -9.29430351e-02 3.14547926e-01 9.44685221e-01 -9.29430574e-02 3.17758113e-01 9.43607152e-01 -9.29431543e-02 3.21015447e-01 9.42510188e-01 -9.29428264e-02 3.24410200e-01 9.41344738e-01 -9.29431021e-02 3.27598244e-01 9.40236390e-01 -9.29431021e-02 3.30856085e-01 9.39099431e-01 -9.29428414e-02 3.34251612e-01 9.37896848e-01 -9.29430574e-02 3.37498456e-01 9.36727822e-01 -9.29431021e-02 3.40749353e-01 9.35553610e-01 -9.29430500e-02 3.43939960e-01 9.34376061e-01 -9.29431170e-02 3.47180337e-01 9.33179736e-01 -9.29428414e-02 3.50470573e-01 9.31945205e-01 -9.29430872e-02 3.53740633e-01 9.30720985e-01 -9.29428264e-02 3.57059300e-01 9.29456711e-01 -9.29430500e-02 3.60226423e-01 9.28219438e-01 -9.29431468e-02 3.63435060e-01 9.26979244e-01 -9.29428563e-02 3.66675436e-01 9.25693274e-01 -9.29431841e-02 3.69893134e-01 9.24419701e-01 -9.29428488e-02 3.73211175e-01 9.23083127e-01 -9.29430500e-02 3.76464188e-01 9.21761632e-01 -9.29430798e-02 3.79675061e-01 9.20442224e-01 -9.29430500e-02 3.82806718e-01 9.19142604e-01 -9.29431170e-02 3.85976374e-01 9.17821407e-01 -9.29428339e-02 3.89289469e-01 9.16417837e-01 -9.29430276e-02 3.92471880e-01 9.15056884e-01 -9.29430947e-02 3.95667285e-01 9.13683653e-01 -9.29430276e-02 3.98788750e-01 9.12325263e-01 -9.29431170e-02 4.01965529e-01 9.10933375e-01 -9.29428414e-02 4.05145228e-01 9.09518003e-01 -9.29431170e-02 4.08206046e-01 9.08152819e-01 -9.29430500e-02 4.11457956e-01 9.06684518e-01 -9.29428414e-02 4.14631277e-01 9.05229449e-01 -9.29431468e-02 4.17764753e-01 9.03795481e-01 -9.29428414e-02 4.20921773e-01 9.02324259e-01 -9.29431170e-02 4.23990875e-01 9.00885940e-01 -9.29431170e-02 4.27152187e-01 8.99392426e-01 -9.29430872e-02 4.30358738e-01 8.97863984e-01 -9.29430351e-02 4.33573246e-01 8.96318674e-01 -9.29430798e-02 4.36610371e-01 8.94841671e-01 -9.29431170e-02 4.39681888e-01 8.93337190e-01 -9.29430276e-02 4.42794055e-01 8.91797245e-01 -9.29430798e-02 4.45876062e-01 8.90262008e-01 -9.29430276e-02 4.49059904e-01 8.88664246e-01 -9.29428339e-02 4.52221453e-01 8.87056649e-01 -9.29430351e-02 4.55236942e-01 8.85509312e-01 -9.29431096e-02 4.58341449e-01 8.83906245e-01 -9.29430798e-02 4.61424232e-01 8.82301927e-01 -9.29431543e-02 4.64475602e-01 8.80702794e-01 -9.29428563e-02 4.67550427e-01 8.79068732e-01 -9.29431170e-02 4.70606178e-01 8.77443135e-01 -9.29428488e-02 4.73733604e-01 8.75755548e-01 -9.29429904e-02 4.76722181e-01 8.74132395e-01 -9.29431096e-02 4.79754835e-01 8.72474194e-01 -9.29428488e-02 4.82812375e-01 8.70777905e-01 -9.29431170e-02 4.85759169e-01 8.69141877e-01 -9.29430723e-02 4.88870412e-01 8.67397845e-01 -9.29430649e-02 4.91964102e-01 8.65643382e-01 -9.29430723e-02 4.94983345e-01 8.63923967e-01 -9.29430276e-02 4.97933686e-01 8.62223864e-01 -9.29431319e-02 5.00867128e-01 8.60525846e-01 -9.29430574e-02 5.03859401e-01 8.58777046e-01 -9.29430500e-02 5.06923020e-01 8.56974125e-01 -9.29428339e-02 5.09978414e-01 8.55156064e-01 -9.29430723e-02 5.12960255e-01 8.53371918e-01 -9.29430202e-02 5.15875041e-01 8.51608694e-01 -9.29431096e-02 5.18823385e-01 8.49822998e-01 -9.29429680e-02 5.21786690e-01 8.47999930e-01 -9.29431021e-02 5.24740696e-01 8.46183598e-01 -9.29428339e-02 5.27776718e-01 8.44287157e-01 -9.29430500e-02 5.30659437e-01 8.42476130e-01 -9.29431170e-02 5.33567309e-01 8.40645373e-01 -9.29428264e-02 5.36510110e-01 8.38760376e-01 -9.29431543e-02 5.39427340e-01 8.36893201e-01 -9.29429531e-02 5.42365849e-01 8.34988832e-01 -9.29431021e-02 5.45279920e-01 8.33093047e-01 -9.29428339e-02 5.48274696e-01 8.31123531e-01 -9.29430574e-02 5.51070213e-01 8.29264998e-01 -9.29431543e-02 5.53975403e-01 8.27335238e-01 -9.29429010e-02 5.56837022e-01 8.25406432e-01 -9.29431915e-02 5.59619367e-01 8.23524356e-01 -9.29431021e-02 5.62570751e-01 8.21513653e-01 -9.29430723e-02 5.65439522e-01 8.19532335e-01 -9.29433554e-02 5.68288505e-01 8.17559302e-01 -9.29432362e-02 5.71172237e-01 8.15545380e-01 -9.29435864e-02 5.73916852e-01 8.13618302e-01 -9.29436311e-02 5.76755106e-01 8.11608315e-01 -9.29438099e-02 5.79573989e-01 8.09596539e-01 -9.29440260e-02 5.82473099e-01 8.07512820e-01 -9.29440781e-02 5.85303426e-01 8.05465519e-01 -9.29442272e-02 5.87972581e-01 8.03518891e-01 -9.29436833e-02 5.90680420e-01 8.01533341e-01 -9.29440930e-02 5.93428731e-01 7.99501479e-01 -9.29441005e-02 5.96038997e-01 7.97557592e-01 -9.29440632e-02 5.97960055e-01 7.96118796e-01 -9.29440707e-02 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. 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. 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. 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. 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. 7.21680641e-01 6.85957313e-01 -9.29441079e-02 7.23712385e-01 6.83809757e-01 -9.29436609e-02 7.25900471e-01 6.81483924e-01 -9.29443315e-02 7.28366077e-01 6.78848147e-01 -9.29442719e-02 7.30679691e-01 6.76357388e-01 -9.29437205e-02 7.33007491e-01 6.73842072e-01 -9.29431841e-02 7.35343337e-01 6.71284318e-01 -9.29433852e-02 7.37673104e-01 6.68732941e-01 -9.29431170e-02 7.40024924e-01 6.66122854e-01 -9.29432735e-02 7.42253304e-01 6.63644373e-01 -9.29431170e-02 7.44637132e-01 6.60977900e-01 -9.29428488e-02 7.46950805e-01 6.58352375e-01 -9.29431543e-02 7.49229252e-01 6.55766070e-01 -9.29428339e-02 7.51502573e-01 6.53153956e-01 -9.29431319e-02 7.53729761e-01 6.50584400e-01 -9.29430872e-02 7.55990446e-01 6.47955358e-01 -9.29431021e-02 7.58243799e-01 6.45314991e-01 -9.29431096e-02 7.60551453e-01 6.42600417e-01 -9.29429978e-02 7.62863159e-01 6.39849424e-01 -9.29431096e-02 7.65039563e-01 6.37239993e-01 -9.29432139e-02 7.67195702e-01 6.34648144e-01 -9.29430872e-02 7.69402862e-01 6.31972909e-01 -9.29430872e-02 7.71658003e-01 6.29218459e-01 -9.29428488e-02 7.73917198e-01 6.26437187e-01 -9.29430649e-02 7.76032329e-01 6.23804867e-01 -9.29431766e-02 7.78132856e-01 6.21192455e-01 -9.29430872e-02 7.80305147e-01 6.18460476e-01 -9.29430351e-02 7.82537341e-01 6.15638554e-01 -9.29428488e-02 7.84735322e-01 6.12828672e-01 -9.29430872e-02 7.86854565e-01 6.10107303e-01 -9.29430649e-02 7.88987160e-01 6.07346535e-01 -9.29430500e-02 7.91045964e-01 6.04658186e-01 -9.29431394e-02 7.93152034e-01 6.01901650e-01 -9.29428488e-02 7.95238674e-01 5.99135578e-01 -9.29431170e-02 7.97273517e-01 5.96423090e-01 -9.29430947e-02 7.99409449e-01 5.93562901e-01 -9.29428861e-02 8.01470637e-01 5.90769470e-01 -9.29431170e-02 8.03521276e-01 5.87984145e-01 -9.29428637e-02 8.05626452e-01 5.85093737e-01 -9.29430798e-02 8.07617784e-01 5.82336128e-01 -9.29431319e-02 8.09575021e-01 5.79620063e-01 -9.29430872e-02 8.11662614e-01 5.76699674e-01 -9.29428339e-02 8.13731015e-01 5.73774874e-01 -9.29430351e-02 8.15708280e-01 5.70953131e-01 -9.29430723e-02 8.17644179e-01 5.68171859e-01 -9.29431543e-02 8.19582999e-01 5.65381229e-01 -9.29430649e-02 8.21559787e-01 5.62503695e-01 -9.29430276e-02 8.23558927e-01 5.59575677e-01 -9.29428414e-02 8.25563788e-01 5.56608140e-01 -9.29430723e-02 8.27453375e-01 5.53789854e-01 -9.29431468e-02 8.29369426e-01 5.50923407e-01 -9.29428861e-02 8.31282437e-01 5.48029065e-01 -9.29431021e-02 8.33210170e-01 5.45100927e-01 -9.29428339e-02 8.35100830e-01 5.42192101e-01 -9.29431319e-02 8.36934686e-01 5.39361119e-01 -9.29430276e-02 8.38860571e-01 5.36364853e-01 -9.29428339e-02 8.40717375e-01 5.33439696e-01 -9.29431170e-02 8.42585921e-01 5.30498207e-01 -9.29428264e-02 8.44488382e-01 5.27454078e-01 -9.29430947e-02 8.46260369e-01 5.24604201e-01 -9.29431170e-02 8.48098874e-01 5.21635354e-01 -9.29428339e-02 8.49913836e-01 5.18664360e-01 -9.29431394e-02 8.51714611e-01 5.15709817e-01 -9.29428339e-02 8.53518367e-01 5.12708485e-01 -9.29431170e-02 8.55245233e-01 5.09826422e-01 -9.29430872e-02 8.57028723e-01 5.06826162e-01 -9.29430351e-02 8.58787656e-01 5.03840387e-01 -9.29430649e-02 8.60593855e-01 5.00754774e-01 -9.29428339e-02 8.62383425e-01 4.97659206e-01 -9.29430798e-02 8.64054978e-01 4.94744390e-01 -9.29431543e-02 8.65726233e-01 4.91818696e-01 -9.29430649e-02 8.67445350e-01 4.88788426e-01 -9.29430649e-02 8.69208395e-01 4.85647380e-01 -9.29428339e-02 8.70955884e-01 4.82493013e-01 -9.29431021e-02 8.72577906e-01 4.79552746e-01 -9.29431543e-02 8.74203980e-01 4.76590574e-01 -9.29430723e-02 8.75859916e-01 4.73536491e-01 -9.29431021e-02 8.77549410e-01 4.70406830e-01 -9.29428488e-02 8.79189312e-01 4.67322975e-01 -9.29431543e-02 8.80821109e-01 4.64251220e-01 -9.29428414e-02 8.82475972e-01 4.61086273e-01 -9.29431543e-02 8.84033740e-01 4.58083928e-01 -9.29431915e-02 8.85617495e-01 4.55034763e-01 -9.29428861e-02 8.87208760e-01 4.51909244e-01 -9.29431841e-02 8.88731301e-01 4.48917568e-01 -9.29430500e-02 8.90356004e-01 4.45690095e-01 -9.29428414e-02 8.91909063e-01 4.42562371e-01 -9.29431394e-02 8.93435419e-01 4.39478636e-01 -9.29430425e-02 8.95003736e-01 4.36278105e-01 -9.29431021e-02 8.96492362e-01 4.33208853e-01 -9.29431543e-02 8.97967100e-01 4.30140078e-01 -9.29430723e-02 8.99453759e-01 4.27022427e-01 -9.29431170e-02 9.00985420e-01 4.23787594e-01 -9.29429904e-02 9.02496397e-01 4.20559287e-01 -9.29430872e-02 9.03921723e-01 4.17476535e-01 -9.29431692e-02 9.05328572e-01 4.14422244e-01 -9.29431021e-02 9.06771362e-01 4.11258966e-01 -9.29431021e-02 9.08239067e-01 4.08013254e-01 -9.29429904e-02 9.09708440e-01 4.04716760e-01 -9.29431096e-02 9.11076009e-01 4.01625127e-01 -9.29431692e-02 9.12456632e-01 3.98495108e-01 -9.29429904e-02 9.13843691e-01 3.95289451e-01 -9.29431319e-02 9.15216148e-01 3.92105818e-01 -9.29429084e-02 9.16582704e-01 3.88890296e-01 -9.29431692e-02 9.17901337e-01 3.85779768e-01 -9.29430872e-02 9.19279516e-01 3.82493079e-01 -9.29428563e-02 9.20601845e-01 3.79280478e-01 -9.29431170e-02 9.21924233e-01 3.76073033e-01 -9.29428339e-02 9.23270047e-01 3.72749954e-01 -9.29430649e-02 9.24528301e-01 3.69607419e-01 -9.29431543e-02 9.25814092e-01 3.66394460e-01 -9.29428339e-02 9.27087545e-01 3.63148391e-01 -9.29431096e-02 9.28335428e-01 3.59943062e-01 -9.29428563e-02 9.29636955e-01 3.56586009e-01 -9.29429978e-02 9.30839539e-01 3.53398055e-01 -9.29431543e-02 9.32029247e-01 3.50250334e-01 -9.29430500e-02 9.33245242e-01 3.46996099e-01 -9.29430500e-02 9.34489012e-01 3.43654245e-01 -9.29428414e-02 9.35726106e-01 3.40282410e-01 -9.29430574e-02 9.36862826e-01 3.37117016e-01 -9.29431096e-02 9.38025832e-01 3.33892316e-01 -9.29428414e-02 9.39195514e-01 3.30568224e-01 -9.29431543e-02 9.40344512e-01 3.27300996e-01 -9.29428414e-02 9.41516399e-01 3.23914766e-01 -9.29430500e-02 9.42604661e-01 3.20717484e-01 -9.29431394e-02 9.43715215e-01 3.17454576e-01 -9.29428339e-02 9.44823444e-01 3.14124435e-01 -9.29431170e-02 9.45915937e-01 3.10835302e-01 -9.29428414e-02 9.46994066e-01 3.07521224e-01 -9.29431170e-02 9.48031068e-01 3.04316163e-01 -9.29430723e-02 9.49124813e-01 3.00898761e-01 -9.29428264e-02 9.50162411e-01 2.97579288e-01 -9.29431543e-02 9.51191485e-01 2.94293195e-01 -9.29428488e-02 9.52240109e-01 2.90880680e-01 -9.29430202e-02 9.53224599e-01 2.87623078e-01 -9.29431096e-02 9.54223752e-01 2.84312695e-01 -9.29428264e-02 9.55219328e-01 2.80935198e-01 -9.29431096e-02 9.56192136e-01 2.77623773e-01 -9.29428339e-02 9.57174420e-01 2.74198741e-01 -9.29430574e-02 9.58098710e-01 2.70948082e-01 -9.29431096e-02 9.59013760e-01 2.67706990e-01 -9.29430500e-02 9.59944963e-01 2.64341831e-01 -9.29430351e-02 9.60884452e-01 2.60917068e-01 -9.29428414e-02 9.61819589e-01 2.57441580e-01 -9.29429755e-02 9.62686956e-01 2.54161984e-01 -9.29431170e-02 9.63567436e-01 2.50831485e-01 -9.29428339e-02 9.64433789e-01 2.47454420e-01 -9.29431170e-02 9.65287983e-01 2.44112268e-01 -9.29428264e-02 9.66159046e-01 2.40634471e-01 -9.29430500e-02 9.66995955e-01 2.37260923e-01 -9.29430351e-02 9.67814088e-01 2.33903900e-01 -9.29430574e-02 9.68605101e-01 2.30590716e-01 -9.29431170e-02 9.69398081e-01 2.27253005e-01 -9.29429084e-02 9.70188677e-01 2.23838463e-01 -9.29430947e-02 9.70948815e-01 2.20513269e-01 -9.29430798e-02 9.71731961e-01 2.17063725e-01 -9.29428339e-02 9.72473741e-01 2.13670641e-01 -9.29431319e-02 9.73217607e-01 2.10288689e-01 -9.29428414e-02 9.73947048e-01 2.06864595e-01 -9.29431170e-02 9.74637568e-01 2.03596711e-01 -9.29430872e-02 9.75353062e-01 2.00149760e-01 -9.29430574e-02 9.76067364e-01 1.96645081e-01 -9.29428339e-02 9.76753414e-01 1.93190500e-01 -9.29430351e-02 9.77419913e-01 1.89788207e-01 -9.29430723e-02 9.78060484e-01 1.86449111e-01 -9.29431021e-02 9.78691816e-01 1.83118433e-01 -9.29430500e-02 9.79320586e-01 1.79714307e-01 -9.29430574e-02 9.79969501e-01 1.76188484e-01 -9.29429457e-02 9.80586231e-01 1.72694832e-01 -9.29431021e-02 9.81161475e-01 1.69357687e-01 -9.29431319e-02 9.81738746e-01 1.66011199e-01 -9.29430872e-02 9.82314944e-01 1.62553251e-01 -9.29430798e-02 9.82871532e-01 1.59160674e-01 -9.29430574e-02 9.83437240e-01 1.55656785e-01 -9.29428414e-02 9.83986497e-01 1.52114153e-01 -9.29430798e-02 9.84510660e-01 1.48688152e-01 -9.29430351e-02 9.85009193e-01 1.45338699e-01 -9.29431096e-02 9.85519171e-01 1.41866520e-01 -9.29428339e-02 9.86017942e-01 1.38361454e-01 -9.29429680e-02 9.86479700e-01 1.34999141e-01 -9.29431170e-02 9.86944497e-01 1.31588310e-01 -9.29428339e-02 9.87395525e-01 1.28112525e-01 -9.29431543e-02 9.87841189e-01 1.24687411e-01 -9.29428339e-02 9.88268554e-01 1.21209204e-01 -9.29431096e-02 9.88676548e-01 1.17850237e-01 -9.29430500e-02 9.89080369e-01 1.14406675e-01 -9.29429531e-02 9.89486992e-01 1.10878550e-01 -9.29428264e-02 9.89873409e-01 1.07333593e-01 -9.29430351e-02 9.90241826e-01 1.03886403e-01 -9.29430202e-02 9.90589082e-01 1.00498497e-01 -9.29431021e-02 9.90935147e-01 9.70750526e-02 -9.29428264e-02 9.91267622e-01 9.35815498e-02 -9.29430872e-02 9.91590679e-01 9.01375115e-02 -9.29428339e-02 9.91903365e-01 8.65935385e-02 -9.29430500e-02 9.92190421e-01 8.32042843e-02 -9.29431096e-02 9.92473066e-01 7.98188299e-02 -9.29430202e-02 9.92741287e-01 7.63808489e-02 -9.29429978e-02 9.93009388e-01 7.28574097e-02 -9.29428339e-02 9.93253887e-01 6.93630278e-02 -9.29430947e-02 9.93489325e-01 6.59665614e-02 -9.29429606e-02 9.93718684e-01 6.24233000e-02 -9.29428264e-02 9.93927121e-01 5.89428768e-02 -9.29431021e-02 9.94132638e-01 5.54844327e-02 -9.29428264e-02 9.94321942e-01 5.19232042e-02 -9.29428861e-02 9.94491637e-01 4.85311337e-02 -9.29430872e-02 9.94658530e-01 4.50757407e-02 -9.29428264e-02 9.94806349e-01 4.15982492e-02 -9.29430947e-02 9.94947016e-01 3.81575711e-02 -9.29428339e-02 9.95077193e-01 3.45714167e-02 -9.29428414e-02 9.95186269e-01 3.11586075e-02 -9.29431021e-02 9.95290577e-01 2.77967826e-02 -9.29429084e-02 9.95383143e-01 2.42992491e-02 -9.29429084e-02 9.95458901e-01 2.07532980e-02 -9.29428264e-02 9.95527685e-01 1.72989462e-02 -9.29431096e-02 9.95574713e-01 1.39183635e-02 -9.29428563e-02 9.95624542e-01 1.04140919e-02 -9.29429308e-02 9.95659947e-01 6.94644917e-03 -9.29428786e-02 9.95679080e-01 3.39947245e-03 -9.29428264e-02 9.95677769e-01 -1.88399994e-04 -9.29429159e-02 9.95675802e-01 -3.65588535e-03 -9.29429978e-02 9.95658636e-01 -7.12596858e-03 -9.29428563e-02 9.95620131e-01 -1.05078304e-02 -9.29430798e-02 9.95575249e-01 -1.40033495e-02 -9.29428264e-02 9.95525241e-01 -1.74942557e-02 -9.29430872e-02 9.95455682e-01 -2.08475851e-02 -9.29428712e-02 9.95382428e-01 -2.44203806e-02 -9.29428190e-02 9.95282292e-01 -2.79264301e-02 -9.29431096e-02 9.95185733e-01 -3.13804597e-02 -9.29428264e-02 9.95064676e-01 -3.48716415e-02 -9.29430947e-02 9.94943202e-01 -3.82329710e-02 -9.29428935e-02 9.94803488e-01 -4.17985916e-02 -9.29428190e-02 9.94643152e-01 -4.53870445e-02 -9.29429159e-02 9.94478762e-01 -4.88584787e-02 -9.29428414e-02 9.94298339e-01 -5.23377955e-02 -9.29428861e-02 9.94115055e-01 -5.56950718e-02 -9.29431021e-02 9.93923843e-01 -5.90591095e-02 -9.29428488e-02 9.93710279e-01 -6.25350997e-02 -9.29428414e-02 9.93483245e-01 -6.61156178e-02 -9.29428190e-02 9.93232548e-01 -6.97050989e-02 -9.29428563e-02 9.92987633e-01 -7.31388107e-02 -9.29429457e-02 9.92731392e-01 -7.64953792e-02 -9.29430947e-02 9.92469430e-01 -7.98737556e-02 -9.29428488e-02 9.92183566e-01 -8.33433867e-02 -9.29428414e-02 9.91879821e-01 -8.69218782e-02 -9.29428190e-02 9.91562128e-01 -9.03905854e-02 -9.29431021e-02 9.91255879e-01 -9.37278196e-02 -9.29428786e-02 9.90922749e-01 -9.71851051e-02 -9.29429308e-02 9.90570545e-01 -1.00738592e-01 -9.29428264e-02 9.90205467e-01 -1.04222097e-01 -9.29430947e-02 9.89842355e-01 -1.07661031e-01 -9.29428264e-02 9.89455521e-01 -1.11120582e-01 -9.29431021e-02 9.89074528e-01 -1.14472859e-01 -9.29429382e-02 9.88660574e-01 -1.18020162e-01 -9.29428264e-02 9.88232851e-01 -1.21503867e-01 -9.29431021e-02 9.87813175e-01 -1.24922462e-01 -9.29428264e-02 9.87354696e-01 -1.28464162e-01 -9.29429978e-02 9.86908197e-01 -1.31828398e-01 -9.29430872e-02 9.86448228e-01 -1.35274947e-01 -9.29428264e-02 9.85952497e-01 -1.38819560e-01 -9.29429531e-02 9.85474706e-01 -1.42151088e-01 -9.29430947e-02 9.84977543e-01 -1.45578742e-01 -9.29428339e-02 9.84457970e-01 -1.49025440e-01 -9.29430872e-02 9.83937681e-01 -1.52461544e-01 -9.29428264e-02 9.83391583e-01 -1.55906245e-01 -9.29431021e-02 9.82851148e-01 -1.59319386e-01 -9.29428264e-02 9.82279539e-01 -1.62770480e-01 -9.29431021e-02 9.81716633e-01 -1.66156739e-01 -9.29428339e-02 9.81111586e-01 -1.69672266e-01 -9.29429904e-02 9.80518162e-01 -1.73113316e-01 -9.29428414e-02 9.79910076e-01 -1.76493168e-01 -9.29431021e-02 9.79307115e-01 -1.79790065e-01 -9.29429904e-02 9.78675008e-01 -1.83219731e-01 -9.29429531e-02 9.78015840e-01 -1.86704218e-01 -9.29428563e-02 9.77341235e-01 -1.90192148e-01 -9.29429084e-02 9.76670086e-01 -1.93622574e-01 -9.29428935e-02 9.76000190e-01 -1.96955144e-01 -9.29430798e-02 9.75332141e-01 -2.00251058e-01 -9.29430202e-02 9.74629343e-01 -2.03642488e-01 -9.29429233e-02 9.73895669e-01 -2.07139030e-01 -9.29428264e-02 9.73161578e-01 -2.10535735e-01 -9.29431021e-02 9.72431362e-01 -2.13895470e-01 -9.29428414e-02 9.71677065e-01 -2.17287377e-01 -9.29430872e-02 9.70909119e-01 -2.20710769e-01 -9.29428264e-02 9.70125079e-01 -2.24113435e-01 -9.29430872e-02 9.69345033e-01 -2.27495238e-01 -9.29428264e-02 9.68537807e-01 -2.30880350e-01 -9.29431021e-02 9.67751205e-01 -2.34174609e-01 -9.29428563e-02 9.66909766e-01 -2.37619072e-01 -9.29428339e-02 9.66068447e-01 -2.40994647e-01 -9.29430872e-02 9.65228081e-01 -2.44349673e-01 -9.29428339e-02 9.64348733e-01 -2.47794792e-01 -9.29430500e-02 9.63496447e-01 -2.51086235e-01 -9.29430723e-02 9.62612212e-01 -2.54480958e-01 -9.29428264e-02 9.61723149e-01 -2.57794082e-01 -9.29431096e-02 9.60837424e-01 -2.61090845e-01 -9.29428935e-02 9.59897280e-01 -2.64522791e-01 -9.29428264e-02 9.58962023e-01 -2.67885566e-01 -9.29430947e-02 9.58030760e-01 -2.71216571e-01 -9.29428264e-02 9.57045376e-01 -2.74658978e-01 -9.29428488e-02 9.56099331e-01 -2.77920932e-01 -9.29431021e-02 9.55162942e-01 -2.81134456e-01 -9.29429606e-02 9.54149604e-01 -2.84565389e-01 -9.29428264e-02 9.53122854e-01 -2.87973791e-01 -9.29429904e-02 9.52110350e-01 -2.91308731e-01 -9.29428488e-02 9.51108158e-01 -2.94550091e-01 -9.29431021e-02 9.50109661e-01 -2.97764242e-01 -9.29428563e-02 9.49062288e-01 -3.01089972e-01 -9.29429680e-02 9.47970450e-01 -3.04507941e-01 -9.29428339e-02 9.46879506e-01 -3.07878584e-01 -9.29430351e-02 9.45797920e-01 -3.11192095e-01 -9.29428488e-02 9.44731355e-01 -3.14401954e-01 -9.29431021e-02 9.43667889e-01 -3.17592442e-01 -9.29429680e-02 9.42550242e-01 -3.20894986e-01 -9.29429159e-02 9.41391766e-01 -3.24278206e-01 -9.29428264e-02 9.40237164e-01 -3.27596754e-01 -9.29430947e-02 9.39103305e-01 -3.30844849e-01 -9.29429010e-02 9.37953711e-01 -3.34088176e-01 -9.29430872e-02 9.36769962e-01 -3.37403059e-01 -9.29428264e-02 9.35575187e-01 -3.40689629e-01 -9.29431021e-02 9.34392214e-01 -3.43920916e-01 -9.29428264e-02 9.33168590e-01 -3.47194523e-01 -9.29431021e-02 9.31998134e-01 -3.50336760e-01 -9.29430053e-02 9.30765748e-01 -3.53614271e-01 -9.29428861e-02 9.29505229e-01 -3.56936336e-01 -9.29428339e-02 9.28240001e-01 -3.60183060e-01 -9.29430872e-02 9.26991165e-01 -3.63410920e-01 -9.29428264e-02 9.25709724e-01 -3.66647929e-01 -9.29430947e-02 9.24436390e-01 -3.69855106e-01 -9.29428264e-02 9.23131704e-01 -3.73087794e-01 -9.29431021e-02 9.21855271e-01 -3.76235306e-01 -9.29430202e-02 9.20517981e-01 -3.79500210e-01 -9.29428339e-02 9.19174552e-01 -3.82736355e-01 -9.29430649e-02 9.17826176e-01 -3.85968775e-01 -9.29428264e-02 9.16438520e-01 -3.89241815e-01 -9.29430500e-02 9.15116549e-01 -3.92333627e-01 -9.29430872e-02 9.13782656e-01 -3.95441115e-01 -9.29429308e-02 9.12358403e-01 -3.98727536e-01 -9.29428264e-02 9.10911083e-01 -4.02010798e-01 -9.29430202e-02 9.09503341e-01 -4.05187458e-01 -9.29429457e-02 9.08111870e-01 -4.08289611e-01 -9.29431021e-02 9.06732798e-01 -4.11347777e-01 -9.29430127e-02 9.05297935e-01 -4.14491713e-01 -9.29429904e-02 9.03810859e-01 -4.17736977e-01 -9.29428264e-02 9.02300239e-01 -4.20981646e-01 -9.29429382e-02 9.00819242e-01 -4.24139470e-01 -9.29429606e-02 8.99372518e-01 -4.27195460e-01 -9.29431021e-02 8.97921741e-01 -4.30241078e-01 -9.29428563e-02 8.96418750e-01 -4.33371127e-01 -9.29429829e-02 8.94873738e-01 -4.36553597e-01 -9.29428339e-02 8.93320024e-01 -4.39712316e-01 -9.29430872e-02 8.91789138e-01 -4.42819446e-01 -9.29428339e-02 8.90233874e-01 -4.45926696e-01 -9.29431021e-02 8.88711572e-01 -4.48965043e-01 -9.29428563e-02 8.87136757e-01 -4.52065229e-01 -9.29429233e-02 8.85511875e-01 -4.55241859e-01 -9.29428339e-02 8.83923054e-01 -4.58306491e-01 -9.29431021e-02 8.82366598e-01 -4.61304843e-01 -9.29430574e-02 8.80757570e-01 -4.64367747e-01 -9.29430500e-02 8.79101992e-01 -4.67495650e-01 -9.29428488e-02 8.77457440e-01 -4.70576972e-01 -9.29430053e-02 8.75782371e-01 -4.73689467e-01 -9.29428264e-02 8.74127984e-01 -4.76731539e-01 -9.29430947e-02 8.72509480e-01 -4.79686558e-01 -9.29429904e-02 8.70830357e-01 -4.82724428e-01 -9.29430351e-02 8.69133115e-01 -4.85778302e-01 -9.29428563e-02 8.67410541e-01 -4.88848001e-01 -9.29428712e-02 8.65663171e-01 -4.91939604e-01 -9.29428264e-02 8.63947868e-01 -4.94937032e-01 -9.29431096e-02 8.62222314e-01 -4.97947901e-01 -9.29428264e-02 8.60462606e-01 -5.00970781e-01 -9.29431021e-02 8.58780086e-01 -5.03856599e-01 -9.29429084e-02 8.57007921e-01 -5.06864011e-01 -9.29429084e-02 8.55221570e-01 -5.09870291e-01 -9.29429382e-02 8.53399634e-01 -5.12922704e-01 -9.29428264e-02 8.51550400e-01 -5.15977740e-01 -9.29429457e-02 8.49782526e-01 -5.18883109e-01 -9.29430947e-02 8.48027349e-01 -5.21749675e-01 -9.29428786e-02 8.46198678e-01 -5.24714112e-01 -9.29429457e-02 8.44314218e-01 -5.27743101e-01 -9.29428264e-02 8.42413366e-01 -5.30765533e-01 -9.29430202e-02 8.40599835e-01 -5.33626497e-01 -9.29431021e-02 8.38788033e-01 -5.36474764e-01 -9.29429904e-02 8.36870670e-01 -5.39465368e-01 -9.29428264e-02 8.34931970e-01 -5.42457461e-01 -9.29429159e-02 8.33021939e-01 -5.45386136e-01 -9.29428563e-02 8.31112444e-01 -5.48291445e-01 -9.29430649e-02 8.29248369e-01 -5.51098704e-01 -9.29431021e-02 8.27375472e-01 -5.53916097e-01 -9.29429233e-02 8.25431943e-01 -5.56811631e-01 -9.29428488e-02 8.23436320e-01 -5.59760630e-01 -9.29428264e-02 8.21454525e-01 -5.62655985e-01 -9.29431021e-02 8.19504499e-01 -5.65501213e-01 -9.29428264e-02 8.17518532e-01 -5.68359375e-01 -9.29430947e-02 8.15553844e-01 -5.71177959e-01 -9.29428414e-02 8.13549459e-01 -5.74030161e-01 -9.29430872e-02 8.11544061e-01 -5.76865017e-01 -9.29428264e-02 8.09514642e-01 -5.79703629e-01 -9.29431021e-02 8.07519972e-01 -5.82477450e-01 -9.29428637e-02 8.05470705e-01 -5.85314155e-01 -9.29428637e-02 8.03390443e-01 -5.88165164e-01 -9.29428414e-02 8.01288307e-01 -5.91023326e-01 -9.29428935e-02 7.99235761e-01 -5.93794644e-01 -9.29430202e-02 7.97206879e-01 -5.96515059e-01 -9.29430425e-02 7.95113146e-01 -5.99310040e-01 -9.29428339e-02 7.93016076e-01 -6.02075100e-01 -9.29430798e-02 7.90920496e-01 -6.04833007e-01 -9.29428339e-02 7.88794518e-01 -6.07595086e-01 -9.29430798e-02 7.86721230e-01 -6.10280633e-01 -9.29429382e-02 7.84537554e-01 -6.13088548e-01 -9.29428264e-02 7.82333434e-01 -6.15894794e-01 -9.29429904e-02 7.80224621e-01 -6.18559957e-01 -9.29430872e-02 7.78123319e-01 -6.21207893e-01 -9.29429010e-02 7.75948822e-01 -6.23920619e-01 -9.29429606e-02 7.73717105e-01 -6.26691699e-01 -9.29428264e-02 7.71509290e-01 -6.29394770e-01 -9.29431021e-02 7.69358099e-01 -6.32030427e-01 -9.29429084e-02 7.67166078e-01 -6.34688258e-01 -9.29430202e-02 7.64946520e-01 -6.37362361e-01 -9.29428488e-02 7.62714744e-01 -6.40031755e-01 -9.29429606e-02 7.60433197e-01 -6.42742693e-01 -9.29428339e-02 7.58189201e-01 -6.45381093e-01 -9.29430798e-02 7.55987048e-01 -6.47962868e-01 -9.29429606e-02 7.53703892e-01 -6.50617182e-01 -9.29429978e-02 7.51372337e-01 -6.53314292e-01 -9.29428264e-02 7.49023855e-01 -6.56000137e-01 -9.29429904e-02 7.46719897e-01 -6.58622146e-01 -9.29428488e-02 7.44478285e-01 -6.61149025e-01 -9.29431021e-02 7.42243171e-01 -6.63662434e-01 -9.29429829e-02 7.39861429e-01 -6.66322410e-01 -9.29428190e-02 7.37514794e-01 -6.68912113e-01 -9.29431021e-02 7.35194862e-01 -6.71464980e-01 -9.29428264e-02 7.32841611e-01 -6.74027145e-01 -9.29430947e-02 7.30552793e-01 -6.76510155e-01 -9.29429904e-02 7.28125274e-01 -6.79123938e-01 -9.29428264e-02 7.25681782e-01 -6.81730688e-01 -9.29429382e-02 7.23348558e-01 -6.84199929e-01 -9.29431021e-02 7.20989227e-01 -6.86701059e-01 -9.29428264e-02 7.18554914e-01 -6.89229846e-01 -9.29431021e-02 7.16179788e-01 -6.91720665e-01 -9.29428264e-02 7.13708341e-01 -6.94263041e-01 -9.29429904e-02 7.11320698e-01 -6.96704030e-01 -9.29430500e-02 7.08876789e-01 -6.99197650e-01 -9.29428339e-02 7.06416130e-01 -7.01683223e-01 -9.29430798e-02 7.03983605e-01 -7.04106331e-01 -9.29428414e-02 7.01478481e-01 -7.06603825e-01 -9.29432958e-02 6.99055016e-01 -7.09002137e-01 -9.29436684e-02 6.96640909e-01 -7.11370051e-01 -9.29436684e-02 6.94140732e-01 -7.13811934e-01 -9.29438621e-02 6.91581428e-01 -7.16287255e-01 -9.29439217e-02 6.89042091e-01 -7.18731642e-01 -9.29443240e-02 6.86578631e-01 -7.21083224e-01 -9.29443166e-02 6.84142888e-01 -7.23397315e-01 -9.29440111e-02 6.81728005e-01 -7.25673497e-01 -9.29436982e-02 6.79299951e-01 -7.27950633e-01 -9.29441229e-02 6.76561832e-01 -7.30496585e-01 -9.29441079e-02 6.74055994e-01 -7.32808590e-01 -9.29441005e-02 6.71903431e-01 -7.34783590e-01 -9.29440632e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.56283891e-01 -8.25777888e-01 -9.29440558e-02 5.53417087e-01 -8.27700794e-01 -9.29439291e-02 5.50852239e-01 -8.29406559e-01 -9.29440930e-02 5.47825813e-01 -8.31407607e-01 -9.29443315e-02 5.45120955e-01 -8.33182156e-01 -9.29436460e-02 5.42171717e-01 -8.35111558e-01 -9.29431543e-02 5.39224327e-01 -8.37018728e-01 -9.29431543e-02 5.36421239e-01 -8.38823617e-01 -9.29429978e-02 5.33494473e-01 -8.40685666e-01 -9.29429159e-02 5.30562043e-01 -8.42543721e-01 -9.29429680e-02 5.27606666e-01 -8.44394088e-01 -9.29429308e-02 5.24658561e-01 -8.46232474e-01 -9.29428786e-02 5.21698475e-01 -8.48057926e-01 -9.29429755e-02 5.18743038e-01 -8.49871635e-01 -9.29429457e-02 5.15724480e-01 -8.51705432e-01 -9.29428339e-02 5.12729049e-01 -8.53508890e-01 -9.29430723e-02 5.09798348e-01 -8.55263472e-01 -9.29429159e-02 5.06795585e-01 -8.57047141e-01 -9.29429904e-02 5.03793716e-01 -8.58817220e-01 -9.29428786e-02 5.00804245e-01 -8.60561788e-01 -9.29429904e-02 4.97727454e-01 -8.62348318e-01 -9.29428339e-02 4.94709313e-01 -8.64079535e-01 -9.29430798e-02 4.91755277e-01 -8.65763068e-01 -9.29429904e-02 4.88730818e-01 -8.67477655e-01 -9.29430202e-02 4.85684216e-01 -8.69184554e-01 -9.29429904e-02 4.82660890e-01 -8.70865345e-01 -9.29429755e-02 4.79631215e-01 -8.72541428e-01 -9.29429978e-02 4.76587862e-01 -8.74206841e-01 -9.29430127e-02 4.73536789e-01 -8.75862479e-01 -9.29429606e-02 4.70472246e-01 -8.77514422e-01 -9.29428488e-02 4.67397660e-01 -8.79153669e-01 -9.29428935e-02 4.64329511e-01 -8.80780637e-01 -9.29428935e-02 4.61270899e-01 -8.82384717e-01 -9.29429457e-02 4.58196819e-01 -8.83983731e-01 -9.29429382e-02 4.55102205e-01 -8.85582030e-01 -9.29429755e-02 4.52021539e-01 -8.87157738e-01 -9.29428488e-02 4.48929667e-01 -8.88727725e-01 -9.29428712e-02 4.45819169e-01 -8.90291214e-01 -9.29429010e-02 4.42724317e-01 -8.91833067e-01 -9.29430202e-02 4.39599931e-01 -8.93378377e-01 -9.29429457e-02 4.36482459e-01 -8.94908667e-01 -9.29428861e-02 4.33362603e-01 -8.96421373e-01 -9.29429159e-02 4.30231005e-01 -8.97926092e-01 -9.29429084e-02 4.27006751e-01 -8.99468362e-01 -9.29428264e-02 4.23843145e-01 -9.00956094e-01 -9.29431021e-02 4.20675308e-01 -9.02448893e-01 -9.29428190e-02 4.17530805e-01 -9.03899729e-01 -9.29431096e-02 4.14476812e-01 -9.05305624e-01 -9.29429904e-02 4.11314547e-01 -9.06748831e-01 -9.29428563e-02 4.08130854e-01 -9.08186316e-01 -9.29428637e-02 4.04870540e-01 -9.09646749e-01 -9.29428264e-02 4.01682824e-01 -9.11053658e-01 -9.29430947e-02 3.98619592e-01 -9.12402689e-01 -9.29429084e-02 3.95440549e-01 -9.13784146e-01 -9.29428414e-02 3.92237842e-01 -9.15158749e-01 -9.29429084e-02 3.88959557e-01 -9.16563690e-01 -9.29428264e-02 3.85725856e-01 -9.17924345e-01 -9.29430872e-02 3.82531285e-01 -9.19264853e-01 -9.29428264e-02 3.79296660e-01 -9.20597434e-01 -9.29431021e-02 3.76195967e-01 -9.21874166e-01 -9.29429606e-02 3.72972280e-01 -9.23181772e-01 -9.29428488e-02 3.69651377e-01 -9.24518704e-01 -9.29428264e-02 3.66330475e-01 -9.25838351e-01 -9.29429010e-02 3.63188684e-01 -9.27072048e-01 -9.29431021e-02 3.60044539e-01 -9.28295732e-01 -9.29428637e-02 3.56801063e-01 -9.29555118e-01 -9.29429904e-02 3.53545755e-01 -9.30792391e-01 -9.29428563e-02 3.50302398e-01 -9.32012081e-01 -9.29429233e-02 3.47035289e-01 -9.33233380e-01 -9.29428861e-02 3.43758553e-01 -9.34448719e-01 -9.29429680e-02 3.40520322e-01 -9.35638785e-01 -9.29429606e-02 3.37123871e-01 -9.36870694e-01 -9.29428190e-02 3.33836555e-01 -9.38042343e-01 -9.29431021e-02 3.30604345e-01 -9.39190209e-01 -9.29428264e-02 3.27299356e-01 -9.40340817e-01 -9.29431170e-02 3.24055851e-01 -9.41470325e-01 -9.29428264e-02 3.20729941e-01 -9.42602038e-01 -9.29431096e-02 3.17527205e-01 -9.43688571e-01 -9.29429904e-02 3.14233959e-01 -9.44789588e-01 -9.29429159e-02 3.10923398e-01 -9.45884764e-01 -9.29428786e-02 3.07627827e-01 -9.46961462e-01 -9.29430127e-02 3.04335296e-01 -9.48028147e-01 -9.29428786e-02 3.00996840e-01 -9.49090421e-01 -9.29429308e-02 2.97692418e-01 -9.50132430e-01 -9.29430276e-02 2.94387490e-01 -9.51162338e-01 -9.29428786e-02 2.91075438e-01 -9.52180982e-01 -9.29430127e-02 2.87660748e-01 -9.53216970e-01 -9.29428339e-02 2.84242511e-01 -9.54241991e-01 -9.29429606e-02 2.80990094e-01 -9.55205202e-01 -9.29430872e-02 2.77659506e-01 -9.56184506e-01 -9.29428264e-02 2.74224043e-01 -9.57169175e-01 -9.29429159e-02 2.70897299e-01 -9.58115876e-01 -9.29429978e-02 2.67626762e-01 -9.59033728e-01 -9.29431021e-02 2.64359385e-01 -9.59941447e-01 -9.29429904e-02 2.60990947e-01 -9.60865080e-01 -9.29429978e-02 2.57639766e-01 -9.61766303e-01 -9.29428563e-02 2.54276961e-01 -9.62661147e-01 -9.29429084e-02 2.50928342e-01 -9.63541865e-01 -9.29429606e-02 2.47482836e-01 -9.64431405e-01 -9.29428264e-02 2.44099855e-01 -9.65287626e-01 -9.29431021e-02 2.40734592e-01 -9.66137707e-01 -9.29428339e-02 2.37342373e-01 -9.66972649e-01 -9.29431021e-02 2.34091535e-01 -9.67769861e-01 -9.29429233e-02 2.30689079e-01 -9.68585670e-01 -9.29429829e-02 2.27315292e-01 -9.69382763e-01 -9.29430202e-02 2.23925143e-01 -9.70171452e-01 -9.29429829e-02 2.20484599e-01 -9.70959365e-01 -9.29428339e-02 2.17054576e-01 -9.71728802e-01 -9.29431021e-02 2.13754371e-01 -9.72460270e-01 -9.29430500e-02 2.10341662e-01 -9.73204792e-01 -9.29429904e-02 2.06964627e-01 -9.73928511e-01 -9.29430202e-02 2.03497663e-01 -9.74664092e-01 -9.29428264e-02 2.00006068e-01 -9.75381911e-01 -9.29430500e-02 1.96691483e-01 -9.76053774e-01 -9.29430872e-02 1.93354383e-01 -9.76721823e-01 -9.29428935e-02 1.89927399e-01 -9.77396309e-01 -9.29429531e-02 1.86449945e-01 -9.78064716e-01 -9.29428339e-02 1.83030665e-01 -9.78705883e-01 -9.29431096e-02 1.79625720e-01 -9.79340076e-01 -9.29428339e-02 1.76190510e-01 -9.79966581e-01 -9.29431096e-02 1.72894821e-01 -9.80554760e-01 -9.29429904e-02 1.69468150e-01 -9.81148124e-01 -9.29429159e-02 1.66029543e-01 -9.81737733e-01 -9.29428786e-02 1.62502095e-01 -9.82328534e-01 -9.29428264e-02 1.59055874e-01 -9.82886434e-01 -9.29431096e-02 1.55741781e-01 -9.83422160e-01 -9.29429308e-02 1.52308539e-01 -9.83959198e-01 -9.29429680e-02 1.48862705e-01 -9.84484017e-01 -9.29429904e-02 1.45433560e-01 -9.84999120e-01 -9.29429010e-02 1.41988277e-01 -9.85500157e-01 -9.29430202e-02 1.38542965e-01 -9.85992074e-01 -9.29429904e-02 1.35012537e-01 -9.86485481e-01 -9.29428264e-02 1.31560341e-01 -9.86944258e-01 -9.29430947e-02 1.28213599e-01 -9.87387240e-01 -9.29429457e-02 1.24746740e-01 -9.87831652e-01 -9.29430127e-02 1.21310696e-01 -9.88259614e-01 -9.29428712e-02 1.17765509e-01 -9.88689959e-01 -9.29428339e-02 1.14289962e-01 -9.89091516e-01 -9.29431021e-02 1.10943101e-01 -9.89476204e-01 -9.29429904e-02 1.07489899e-01 -9.89856601e-01 -9.29430500e-02 1.04033686e-01 -9.90226150e-01 -9.29429904e-02 1.00506350e-01 -9.90591288e-01 -9.29428339e-02 9.70187187e-02 -9.90934491e-01 -9.29431096e-02 9.35600400e-02 -9.91275847e-01 -9.29428264e-02 9.00965855e-02 -9.91589904e-01 -9.29431021e-02 8.66470560e-02 -9.91903245e-01 -9.29428264e-02 8.30614418e-02 -9.92204368e-01 -9.29430500e-02 7.97048211e-02 -9.92478788e-01 -9.29431096e-02 7.63385221e-02 -9.92744505e-01 -9.29430202e-02 7.28758201e-02 -9.93006945e-01 -9.29429010e-02 6.94183782e-02 -9.93253112e-01 -9.29429457e-02 6.59588501e-02 -9.93490160e-01 -9.29428861e-02 6.24909773e-02 -9.93712962e-01 -9.29429904e-02 5.90239614e-02 -9.93925333e-01 -9.29429904e-02 5.55656180e-02 -9.94126260e-01 -9.29428563e-02 5.20809181e-02 -9.94312644e-01 -9.29429680e-02 4.85992134e-02 -9.94491994e-01 -9.29428637e-02 4.50436845e-02 -9.94660437e-01 -9.29428264e-02 4.14893255e-02 -9.94811356e-01 -9.29430351e-02 3.80782783e-02 -9.94947255e-01 -9.29430649e-02 3.46946456e-02 -9.95071054e-01 -9.29430351e-02 3.11357211e-02 -9.95189965e-01 -9.29428414e-02 2.76556145e-02 -9.95290041e-01 -9.29431021e-02 2.41912659e-02 -9.95388389e-01 -9.29428264e-02 2.06924956e-02 -9.95456696e-01 -9.29431021e-02 1.73410252e-02 -9.95530188e-01 -9.29429978e-02 1.37764532e-02 -9.95577812e-01 -9.29428264e-02 1.02714300e-02 -9.95621026e-01 -9.29431021e-02 6.91728666e-03 -9.95659590e-01 -9.29429829e-02 3.43482452e-03 -9.95675981e-01 -9.29429904e-02 -3.45407971e-05 -9.95677829e-01 -9.29428786e-02 -3.50338337e-03 -9.95676816e-01 -9.29428563e-02 -6.99207187e-03 -9.95660067e-01 -9.29429159e-02 -1.04628261e-02 -9.95622098e-01 -9.29430053e-02 -1.39351459e-02 -9.95573938e-01 -9.29429904e-02 -1.74879674e-02 -9.95530605e-01 -9.29428339e-02 -2.10688375e-02 -9.95452166e-01 -9.29428563e-02 -2.44690366e-02 -9.95374560e-01 -9.29431021e-02 -2.78373193e-02 -9.95288491e-01 -9.29429457e-02 -3.13246027e-02 -9.95185614e-01 -9.29428637e-02 -3.47750969e-02 -9.95071113e-01 -9.29429159e-02 -3.83501798e-02 -9.94940460e-01 -9.29428264e-02 -4.18353155e-02 -9.94796813e-01 -9.29430872e-02 -4.52126078e-02 -9.94649291e-01 -9.29430202e-02 -4.86627370e-02 -9.94487524e-01 -9.29429531e-02 -5.21150716e-02 -9.94310975e-01 -9.29428563e-02 -5.57055995e-02 -9.94119763e-01 -9.29428264e-02 -5.91748580e-02 -9.93913531e-01 -9.29431096e-02 -6.26133755e-02 -9.93708074e-01 -9.29428264e-02 -6.61084279e-02 -9.93475676e-01 -9.29431096e-02 -6.94766119e-02 -9.93248761e-01 -9.29428563e-02 -7.30523989e-02 -9.92996514e-01 -9.29428264e-02 -7.65310079e-02 -9.92726564e-01 -9.29431170e-02 -7.99652711e-02 -9.92463291e-01 -9.29428264e-02 -8.34441110e-02 -9.92170930e-01 -9.29431096e-02 -8.67995918e-02 -9.91886377e-01 -9.29429680e-02 -9.02565196e-02 -9.91577923e-01 -9.29429159e-02 -9.37167257e-02 -9.91257310e-01 -9.29429606e-02 -9.71992835e-02 -9.90921438e-01 -9.29429904e-02 -1.00654177e-01 -9.90575194e-01 -9.29430574e-02 -1.04101866e-01 -9.90219593e-01 -9.29429904e-02 -1.07646354e-01 -9.89843547e-01 -9.29428264e-02 -1.11092791e-01 -9.89457369e-01 -9.29431021e-02 -1.14474386e-01 -9.89072919e-01 -9.29429010e-02 -1.17932133e-01 -9.88665998e-01 -9.29430202e-02 -1.21371076e-01 -9.88253117e-01 -9.29429904e-02 -1.24916039e-01 -9.87812877e-01 -9.29428264e-02 -1.28369913e-01 -9.87363756e-01 -9.29430947e-02 -1.31716952e-01 -9.86927390e-01 -9.29428488e-02 -1.35168195e-01 -9.86460030e-01 -9.29428786e-02 -1.38614804e-01 -9.85981643e-01 -9.29429010e-02 -1.42143488e-01 -9.85479891e-01 -9.29428264e-02 -1.45586595e-01 -9.84971583e-01 -9.29431096e-02 -1.48996741e-01 -9.84465301e-01 -9.29428339e-02 -1.52436435e-01 -9.83936846e-01 -9.29431021e-02 -1.55780479e-01 -9.83413577e-01 -9.29430202e-02 -1.59305677e-01 -9.82852340e-01 -9.29428339e-02 -1.62731856e-01 -9.82286215e-01 -9.29430947e-02 -1.66152909e-01 -9.81718183e-01 -9.29428264e-02 -1.69597372e-01 -9.81122732e-01 -9.29430872e-02 -1.72922790e-01 -9.80549991e-01 -9.29429233e-02 -1.76346779e-01 -9.79938328e-01 -9.29430351e-02 -1.79774135e-01 -9.79309738e-01 -9.29429904e-02 -1.83196783e-01 -9.78678882e-01 -9.29430500e-02 -1.86592475e-01 -9.78036582e-01 -9.29429904e-02 -1.90011412e-01 -9.77376521e-01 -9.29429904e-02 -1.93411961e-01 -9.76710737e-01 -9.29429457e-02 -1.96913227e-01 -9.76012290e-01 -9.29428339e-02 -2.00295806e-01 -9.75318849e-01 -9.29431021e-02 -2.03615457e-01 -9.74634528e-01 -9.29430202e-02 -2.07026690e-01 -9.73917365e-01 -9.29429978e-02 -2.10497215e-01 -9.73175108e-01 -9.29428264e-02 -2.13926539e-01 -9.72419858e-01 -9.29431021e-02 -2.17204332e-01 -9.71697986e-01 -9.29429531e-02 -2.20601484e-01 -9.70931232e-01 -9.29429904e-02 -2.24005088e-01 -9.70151126e-01 -9.29428563e-02 -2.27487341e-01 -9.69347060e-01 -9.29428264e-02 -2.30867863e-01 -9.68540370e-01 -9.29431170e-02 -2.34134302e-01 -9.67760265e-01 -9.29428861e-02 -2.37533256e-01 -9.66929734e-01 -9.29430351e-02 -2.40888193e-01 -9.66095805e-01 -9.29430351e-02 -2.44249344e-01 -9.65252221e-01 -9.29429904e-02 -2.47617170e-01 -9.64394748e-01 -9.29429904e-02 -2.51075149e-01 -9.63503420e-01 -9.29428264e-02 -2.54467726e-01 -9.62608874e-01 -9.29431021e-02 -2.57798612e-01 -9.61725652e-01 -9.29428264e-02 -2.61266381e-01 -9.60789144e-01 -9.29429457e-02 -2.64519811e-01 -9.59891975e-01 -9.29431096e-02 -2.67775953e-01 -9.58994687e-01 -9.29429084e-02 -2.71136343e-01 -9.58049953e-01 -9.29429084e-02 -2.74484664e-01 -9.57094729e-01 -9.29428861e-02 -2.77815342e-01 -9.56133425e-01 -9.29429382e-02 -2.81151652e-01 -9.55156744e-01 -9.29430202e-02 -2.84491003e-01 -9.54169869e-01 -9.29429904e-02 -2.87822306e-01 -9.53167975e-01 -9.29429755e-02 -2.91123241e-01 -9.52165723e-01 -9.29430202e-02 -2.94551104e-01 -9.51116204e-01 -9.29428264e-02 -2.97968030e-01 -9.50046778e-01 -9.29429010e-02 -3.01294237e-01 -9.48996186e-01 -9.29429382e-02 -3.04524809e-01 -9.47962224e-01 -9.29431170e-02 -3.07723731e-01 -9.46930647e-01 -9.29429904e-02 -3.11110705e-01 -9.45825875e-01 -9.29428339e-02 -3.14418972e-01 -9.44725931e-01 -9.29431096e-02 -3.17713201e-01 -9.43628311e-01 -9.29428339e-02 -3.20998460e-01 -9.42510605e-01 -9.29431096e-02 -3.24194044e-01 -9.41420257e-01 -9.29429382e-02 -3.27482611e-01 -9.40279484e-01 -9.29430053e-02 -3.30737412e-01 -9.39140677e-01 -9.29430351e-02 -3.34112316e-01 -9.37948585e-01 -9.29428264e-02 -3.37401003e-01 -9.36763525e-01 -9.29431021e-02 -3.40651959e-01 -9.35594618e-01 -9.29428264e-02 -3.43921393e-01 -9.34383094e-01 -9.29431096e-02 -3.47101837e-01 -9.33207154e-01 -9.29430202e-02 -3.50354940e-01 -9.31991160e-01 -9.29430202e-02 -3.53594303e-01 -9.30771530e-01 -9.29430500e-02 -3.56948018e-01 -9.29501534e-01 -9.29428264e-02 -3.60251516e-01 -9.28217292e-01 -9.29428637e-02 -3.63434881e-01 -9.26975548e-01 -9.29431021e-02 -3.66580486e-01 -9.25738811e-01 -9.29430127e-02 -3.69799018e-01 -9.24455762e-01 -9.29429978e-02 -3.73018652e-01 -9.23162460e-01 -9.29429755e-02 -3.76314163e-01 -9.21826541e-01 -9.29428339e-02 -3.79544169e-01 -9.20492768e-01 -9.29431096e-02 -3.82663697e-01 -9.19205725e-01 -9.29429755e-02 -3.85864288e-01 -9.17865992e-01 -9.29429904e-02 -3.89075756e-01 -9.16509807e-01 -9.29430053e-02 -3.92353326e-01 -9.15112972e-01 -9.29428264e-02 -3.95541519e-01 -9.13734734e-01 -9.29431096e-02 -3.98715854e-01 -9.12361145e-01 -9.29428414e-02 -4.01914448e-01 -9.10949945e-01 -9.29431170e-02 -4.04985189e-01 -9.09593284e-01 -9.29429755e-02 -4.08162326e-01 -9.08172131e-01 -9.29430202e-02 -4.11332160e-01 -9.06740427e-01 -9.29429382e-02 -4.14503127e-01 -9.05292034e-01 -9.29429457e-02 -4.17672396e-01 -9.03834641e-01 -9.29430202e-02 -4.20826763e-01 -9.02372837e-01 -9.29428563e-02 -4.23977911e-01 -9.00894642e-01 -9.29430500e-02 -4.27201778e-01 -8.99374366e-01 -9.29428264e-02 -4.30328846e-01 -8.97874475e-01 -9.29431096e-02 -4.33372706e-01 -8.96418214e-01 -9.29429382e-02 -4.36582327e-01 -8.94861937e-01 -9.29428264e-02 -4.39784110e-01 -8.93287361e-01 -9.29430351e-02 -4.42833871e-01 -8.91777873e-01 -9.29430872e-02 -4.45856869e-01 -8.90271604e-01 -9.29429233e-02 -4.48968947e-01 -8.88707638e-01 -9.29429904e-02 -4.52066928e-01 -8.87135863e-01 -9.29429755e-02 -4.55242068e-01 -8.85511637e-01 -9.29428264e-02 -4.58318084e-01 -8.83916974e-01 -9.29431021e-02 -4.61300820e-01 -8.82369876e-01 -9.29430351e-02 -4.64384526e-01 -8.80750000e-01 -9.29429308e-02 -4.67467338e-01 -8.79116714e-01 -9.29430053e-02 -4.70617861e-01 -8.77439260e-01 -9.29428264e-02 -4.73665178e-01 -8.75787497e-01 -9.29431096e-02 -4.76729333e-01 -8.74134481e-01 -9.29428264e-02 -4.79788780e-01 -8.72451961e-01 -9.29430947e-02 -4.82818484e-01 -8.70780647e-01 -9.29428339e-02 -4.85938787e-01 -8.69042456e-01 -9.29429233e-02 -4.88893479e-01 -8.67382348e-01 -9.29431021e-02 -4.91833746e-01 -8.65720272e-01 -9.29428637e-02 -4.94862944e-01 -8.63993227e-01 -9.29430276e-02 -4.97867584e-01 -8.62265110e-01 -9.29430202e-02 -5.00862002e-01 -8.60529006e-01 -9.29429904e-02 -5.03862500e-01 -8.58777881e-01 -9.29429382e-02 -5.06865501e-01 -8.57006073e-01 -9.29429606e-02 -5.09847820e-01 -8.55235994e-01 -9.29428935e-02 -5.12841165e-01 -8.53445411e-01 -9.29429904e-02 -5.15811026e-01 -8.51651192e-01 -9.29429457e-02 -5.18782079e-01 -8.49846840e-01 -9.29429978e-02 -5.21814883e-01 -8.47988009e-01 -9.29428339e-02 -5.24764240e-01 -8.46163094e-01 -9.29431021e-02 -5.27637184e-01 -8.44377875e-01 -9.29429308e-02 -5.30652583e-01 -8.42488229e-01 -9.29428264e-02 -5.33604562e-01 -8.40615273e-01 -9.29430947e-02 -5.36527872e-01 -8.38757217e-01 -9.29428264e-02 -5.39463937e-01 -8.36867154e-01 -9.29430947e-02 -5.42286336e-01 -8.35044742e-01 -9.29428861e-02 -5.45203269e-01 -8.33139598e-01 -9.29429904e-02 -5.48106372e-01 -8.31235230e-01 -9.29430202e-02 -5.50994694e-01 -8.29321742e-01 -9.29428861e-02 -5.53892493e-01 -8.27390134e-01 -9.29429755e-02 -5.56866586e-01 -8.25396240e-01 -9.29428264e-02 -5.59741020e-01 -8.23441625e-01 -9.29431021e-02 -5.62531292e-01 -8.21543157e-01 -9.29430202e-02 -5.65396369e-01 -8.19573939e-01 -9.29428861e-02 -5.68243325e-01 -8.17601442e-01 -9.29429904e-02 -5.71182907e-01 -8.15553367e-01 -9.29428264e-02 -5.74103892e-01 -8.13501000e-01 -9.29428563e-02 -5.76865315e-01 -8.11537445e-01 -9.29431021e-02 -5.79618335e-01 -8.09579253e-01 -9.29428712e-02 -5.82443476e-01 -8.07544351e-01 -9.29429010e-02 -5.85270703e-01 -8.05501580e-01 -9.29429606e-02 -5.88133931e-01 -8.03413749e-01 -9.29428264e-02 -5.90929389e-01 -8.01353872e-01 -9.29431021e-02 -5.93646109e-01 -7.99346924e-01 -9.29429531e-02 -5.96433401e-01 -7.97269464e-01 -9.29428861e-02 -5.99223673e-01 -7.95175493e-01 -9.29429233e-02 -6.02066815e-01 -7.93029726e-01 -9.29428264e-02 -6.04879856e-01 -7.90879250e-01 -9.29430723e-02 -6.07631207e-01 -7.88770199e-01 -9.29428339e-02 -6.10349536e-01 -7.86663949e-01 -9.29431021e-02 -6.13013566e-01 -7.84593642e-01 -9.29429159e-02 -6.15746915e-01 -7.82450318e-01 -9.29429531e-02 -6.18477523e-01 -7.80293405e-01 -9.29429308e-02 -6.21184468e-01 -7.78140724e-01 -9.29428712e-02 -6.23898804e-01 -7.75967002e-01 -9.29429010e-02 -6.26610219e-01 -7.73780167e-01 -9.29429904e-02 -6.29305661e-01 -7.71585226e-01 -9.29429531e-02 -6.31995261e-01 -7.69385397e-01 -9.29429606e-02 -6.34678483e-01 -7.67174006e-01 -9.29429233e-02 -6.37358427e-01 -7.64949322e-01 -9.29429904e-02 -6.40086651e-01 -7.62670755e-01 -9.29428264e-02 -6.42832577e-01 -7.60355413e-01 -9.29429531e-02 -6.45410836e-01 -7.58161426e-01 -9.29430872e-02 -6.47960305e-01 -7.55988836e-01 -9.29429978e-02 -6.50625467e-01 -7.53698766e-01 -9.29428712e-02 -6.53248727e-01 -7.51425922e-01 -9.29429755e-02 -6.55932128e-01 -7.49085844e-01 -9.29428264e-02 -6.58552825e-01 -7.46776521e-01 -9.29431021e-02 -6.61091030e-01 -7.44534969e-01 -9.29429010e-02 -6.63686216e-01 -7.42222250e-01 -9.29430053e-02 -6.66267276e-01 -7.39906013e-01 -9.29429382e-02 -6.68918610e-01 -7.37515330e-01 -9.29428264e-02 -6.71487927e-01 -7.35166788e-01 -9.29431021e-02 -6.74052119e-01 -7.32829094e-01 -9.29428264e-02 -6.76611900e-01 -7.30455339e-01 -9.29430798e-02 -6.79157853e-01 -7.28094399e-01 -9.29428264e-02 -6.81754291e-01 -7.25661099e-01 -9.29428414e-02 -6.84220970e-01 -7.23331094e-01 -9.29430872e-02 -6.86675310e-01 -7.21011043e-01 -9.29428488e-02 -6.89186811e-01 -7.18600810e-01 -9.29428563e-02 -6.91679418e-01 -7.16215849e-01 -9.29428935e-02 -6.94187284e-01 -7.13783383e-01 -9.29428563e-02 -6.96668386e-01 -7.11358070e-01 -9.29429531e-02 -6.99138701e-01 -7.08933771e-01 -9.29428712e-02 -7.01615095e-01 -7.06485271e-01 -9.29428637e-02 -7.04139411e-01 -7.03952134e-01 -9.29428190e-02 -7.06600785e-01 -7.01495051e-01 -9.29430947e-02 -7.08969235e-01 -6.99102879e-01 -9.29428786e-02 -7.11401820e-01 -6.96623981e-01 -9.29428712e-02 -7.13827252e-01 -6.94144487e-01 -9.29428339e-02 -7.16242135e-01 -6.91651642e-01 -9.29429010e-02 -7.18714535e-01 -6.89072490e-01 -9.29428190e-02 -7.21138060e-01 -6.86537325e-01 -9.29430872e-02 -7.23506153e-01 -6.84042752e-01 -9.29428264e-02 -7.25902557e-01 -6.81494176e-01 -9.29430574e-02 -7.28207290e-01 -6.79032028e-01 -9.29428488e-02 -7.30628371e-01 -6.76432312e-01 -9.29428264e-02 -7.32988358e-01 -6.73870146e-01 -9.29430649e-02 -7.35269189e-01 -6.71380877e-01 -9.29429010e-02 -7.37629175e-01 -6.68789566e-01 -9.29429159e-02 -7.39956796e-01 -6.66212082e-01 -9.29428488e-02 -7.42333233e-01 -6.63565397e-01 -9.29428264e-02 -7.44641244e-01 -6.60967708e-01 -9.29431021e-02 -7.46885836e-01 -6.58434272e-01 -9.29428563e-02 -7.49176919e-01 -6.55825377e-01 -9.29429010e-02 -7.51525402e-01 -6.53137505e-01 -9.29428264e-02 -7.53848672e-01 -6.50449395e-01 -9.29429755e-02 -7.56062984e-01 -6.47871017e-01 -9.29430872e-02 -7.58256853e-01 -6.45305037e-01 -9.29428488e-02 -7.60503292e-01 -6.42658055e-01 -9.29430127e-02 -7.62724280e-01 -6.40018404e-01 -9.29429755e-02 -7.65027165e-01 -6.37271702e-01 -9.29428190e-02 -7.67255425e-01 -6.34572804e-01 -9.29431170e-02 -7.69386888e-01 -6.31998658e-01 -9.29428414e-02 -7.71595359e-01 -6.29294038e-01 -9.29429084e-02 -7.73785710e-01 -6.26602829e-01 -9.29428488e-02 -7.76035428e-01 -6.23818994e-01 -9.29428264e-02 -7.78216779e-01 -6.21084571e-01 -9.29431021e-02 -7.80368030e-01 -6.18387222e-01 -9.29428264e-02 -7.82527328e-01 -6.15645766e-01 -9.29431021e-02 -7.84600437e-01 -6.13006234e-01 -9.29428563e-02 -7.86807597e-01 -6.10177100e-01 -9.29428190e-02 -7.88950264e-01 -6.07391417e-01 -9.29431021e-02 -7.91053116e-01 -6.04661405e-01 -9.29428264e-02 -7.93157578e-01 -6.01887524e-01 -9.29431096e-02 -7.95195162e-01 -5.99200308e-01 -9.29428488e-02 -7.97351718e-01 -5.96327662e-01 -9.29428190e-02 -7.99437165e-01 -5.93523145e-01 -9.29430798e-02 -8.01446259e-01 -5.90810418e-01 -9.29428786e-02 -8.03497612e-01 -5.88016689e-01 -9.29429382e-02 -8.05595636e-01 -5.85147023e-01 -9.29428190e-02 -8.07696581e-01 -5.82234025e-01 -9.29428563e-02 -8.09667349e-01 -5.79492390e-01 -9.29430798e-02 -8.11617553e-01 -5.76755524e-01 -9.29428563e-02 -8.13621402e-01 -5.73932350e-01 -9.29428786e-02 -8.15628946e-01 -5.71070969e-01 -9.29428861e-02 -8.17664862e-01 -5.68156421e-01 -9.29428190e-02 -8.19654822e-01 -5.65277457e-01 -9.29430798e-02 -8.21570396e-01 -5.62493443e-01 -9.29428414e-02 -8.23529661e-01 -5.59617579e-01 -9.29428712e-02 -8.25477779e-01 -5.56740999e-01 -9.29428563e-02 -8.27470958e-01 -5.53779602e-01 -9.29428190e-02 -8.29399228e-01 -5.50876677e-01 -9.29430798e-02 -8.31304550e-01 -5.48006117e-01 -9.29428264e-02 -8.33212674e-01 -5.45091927e-01 -9.29430723e-02 -8.35065305e-01 -5.42255938e-01 -9.29428488e-02 -8.36963952e-01 -5.39319217e-01 -9.29428488e-02 -8.38839054e-01 -5.36398053e-01 -9.29428488e-02 -8.40746641e-01 -5.33406317e-01 -9.29428264e-02 -8.42604637e-01 -5.30459583e-01 -9.29430947e-02 -8.44394326e-01 -5.27607620e-01 -9.29428935e-02 -8.46289217e-01 -5.24574578e-01 -9.29428264e-02 -8.48113954e-01 -5.21600246e-01 -9.29431021e-02 -8.49873960e-01 -5.18739760e-01 -9.29429606e-02 -8.51668179e-01 -5.15782297e-01 -9.29429308e-02 -8.53514612e-01 -5.12733221e-01 -9.29428190e-02 -8.55306387e-01 -5.09722352e-01 -9.29431021e-02 -8.57034683e-01 -5.06819129e-01 -9.29428488e-02 -8.58856857e-01 -5.03731489e-01 -9.29428190e-02 -8.60609055e-01 -5.00717700e-01 -9.29431170e-02 -8.62291873e-01 -4.97823030e-01 -9.29428786e-02 -8.64020348e-01 -4.94815022e-01 -9.29428712e-02 -8.65745783e-01 -4.91788328e-01 -9.29428712e-02 -8.67466211e-01 -4.88754183e-01 -9.29428488e-02 -8.69155645e-01 -4.85739052e-01 -9.29428563e-02 -8.70846272e-01 -4.82696265e-01 -9.29429755e-02 -8.72573316e-01 -4.79585171e-01 -9.29428190e-02 -8.74255061e-01 -4.76495743e-01 -9.29431021e-02 -8.75869513e-01 -4.73523796e-01 -9.29428637e-02 -8.77516985e-01 -4.70465988e-01 -9.29428563e-02 -8.79199266e-01 -4.67318535e-01 -9.29428264e-02 -8.80870104e-01 -4.64157164e-01 -9.29428563e-02 -8.82444263e-01 -4.61152345e-01 -9.29430798e-02 -8.84005189e-01 -4.58158433e-01 -9.29429010e-02 -8.85596752e-01 -4.55075622e-01 -9.29428488e-02 -8.87202144e-01 -4.51937824e-01 -9.29428339e-02 -8.88780475e-01 -4.48819757e-01 -9.29430798e-02 -8.90300453e-01 -4.45801526e-01 -9.29428414e-02 -8.91853452e-01 -4.42685097e-01 -9.29429606e-02 -8.93389881e-01 -4.39579040e-01 -9.29428563e-02 -8.94921958e-01 -4.36452776e-01 -9.29428563e-02 -8.96475315e-01 -4.33258384e-01 -9.29428264e-02 -8.97991002e-01 -4.30094391e-01 -9.29430649e-02 -8.99446249e-01 -4.27049071e-01 -9.29428563e-02 -9.00929213e-01 -4.23908174e-01 -9.29428563e-02 -9.02398527e-01 -4.20771062e-01 -9.29429010e-02 -9.03885603e-01 -4.17579144e-01 -9.29428264e-02 -9.05337155e-01 -4.14403528e-01 -9.29430798e-02 -9.06750619e-01 -4.11310196e-01 -9.29429308e-02 -9.08170223e-01 -4.08168018e-01 -9.29429010e-02 -9.09599364e-01 -4.04974580e-01 -9.29428563e-02 -9.11042511e-01 -4.01723146e-01 -9.29428264e-02 -9.12439764e-01 -3.98529559e-01 -9.29431021e-02 -9.13821399e-01 -3.95361125e-01 -9.29428264e-02 -9.15196657e-01 -3.92140269e-01 -9.29431021e-02 -9.16521549e-01 -3.89051884e-01 -9.29428414e-02 -9.17916775e-01 -3.85755271e-01 -9.29428264e-02 -9.19269264e-01 -3.82508636e-01 -9.29430872e-02 -9.20560360e-01 -3.79395902e-01 -9.29429308e-02 -9.21868861e-01 -3.76204133e-01 -9.29430351e-02 -9.23174143e-01 -3.72988671e-01 -9.29429084e-02 -9.24515247e-01 -3.69660914e-01 -9.29428264e-02 -9.25801396e-01 -3.66412461e-01 -9.29431170e-02 -9.27061856e-01 -3.63227248e-01 -9.29428339e-02 -9.28309679e-01 -3.60002965e-01 -9.29430649e-02 -9.29594100e-01 -3.56706440e-01 -9.29428190e-02 -9.30861413e-01 -3.53356332e-01 -9.29430202e-02 -9.32041883e-01 -3.50208759e-01 -9.29431096e-02 -9.33229268e-01 -3.47040296e-01 -9.29430202e-02 -9.34475362e-01 -3.43695045e-01 -9.29428264e-02 -9.35679078e-01 -3.40406001e-01 -9.29431021e-02 -9.36855793e-01 -3.37158948e-01 -9.29428264e-02 -9.38030720e-01 -3.33867818e-01 -9.29431096e-02 -9.39190209e-01 -3.30602765e-01 -9.29428264e-02 -9.40337300e-01 -3.27310503e-01 -9.29431021e-02 -9.41444933e-01 -3.24122757e-01 -9.29429904e-02 -9.42565918e-01 -3.20845693e-01 -9.29428563e-02 -9.43689525e-01 -3.17528069e-01 -9.29429829e-02 -9.44820821e-01 -3.14148605e-01 -9.29428264e-02 -9.45908785e-01 -3.10841978e-01 -9.29431021e-02 -9.46961641e-01 -3.07628155e-01 -9.29430202e-02 -9.48055148e-01 -3.04255068e-01 -9.29428190e-02 -9.49113905e-01 -3.00915271e-01 -9.29430947e-02 -9.50129569e-01 -2.97701806e-01 -9.29430500e-02 -9.51160550e-01 -2.94385999e-01 -9.29430351e-02 -9.52211142e-01 -2.90987432e-01 -9.29428264e-02 -9.53220725e-01 -2.87637085e-01 -9.29431021e-02 -9.54192698e-01 -2.84405857e-01 -9.29429531e-02 -9.55208957e-01 -2.80988097e-01 -9.29428264e-02 -9.56181049e-01 -2.77644962e-01 -9.29431021e-02 -9.57146347e-01 -2.74316490e-01 -9.29428264e-02 -9.58098054e-01 -2.70954430e-01 -9.29431021e-02 -9.59019303e-01 -2.67689824e-01 -9.29428637e-02 -9.59942818e-01 -2.64351338e-01 -9.29429531e-02 -9.60859239e-01 -2.61011273e-01 -9.29429010e-02 -9.61760044e-01 -2.57660538e-01 -9.29429904e-02 -9.62680280e-01 -2.54215240e-01 -9.29428264e-02 -9.63555753e-01 -2.50855058e-01 -9.29431096e-02 -9.64406550e-01 -2.47575343e-01 -9.29428563e-02 -9.65263247e-01 -2.44199559e-01 -9.29430276e-02 -9.66132462e-01 -2.40752444e-01 -9.29428264e-02 -9.66987193e-01 -2.37299204e-01 -9.29430202e-02 -9.67794001e-01 -2.33985126e-01 -9.29430947e-02 -9.68585134e-01 -2.30693281e-01 -9.29429904e-02 -9.69383121e-01 -2.27314577e-01 -9.29429606e-02 -9.70183432e-01 -2.23871469e-01 -9.29428264e-02 -9.70981836e-01 -2.20376164e-01 -9.29430351e-02 -9.71729040e-01 -2.17051163e-01 -9.29431021e-02 -9.72461641e-01 -2.13749856e-01 -9.29430202e-02 -9.73201931e-01 -2.10357189e-01 -9.29429904e-02 -9.73926365e-01 -2.06977725e-01 -9.29430127e-02 -9.74643171e-01 -2.03580961e-01 -9.29430202e-02 -9.75344896e-01 -2.00189382e-01 -9.29430276e-02 -9.76037562e-01 -1.96784630e-01 -9.29430351e-02 -9.76715505e-01 -1.93386748e-01 -9.29430127e-02 -9.77386951e-01 -1.89965203e-01 -9.29430202e-02 -9.78063047e-01 -1.86467141e-01 -9.29428264e-02 -9.78704393e-01 -1.83039144e-01 -9.29431021e-02 -9.79323566e-01 -1.79706842e-01 -9.29429904e-02 -9.79947269e-01 -1.76306099e-01 -9.29429904e-02 -9.80560660e-01 -1.72860876e-01 -9.29430202e-02 -9.81169343e-01 -1.69359371e-01 -9.29428264e-02 -9.81754243e-01 -1.65903285e-01 -9.29431319e-02 -9.82311249e-01 -1.62589744e-01 -9.29430202e-02 -9.82870638e-01 -1.59174278e-01 -9.29429904e-02 -9.83424664e-01 -1.55722216e-01 -9.29429904e-02 -9.83979523e-01 -1.52189538e-01 -9.29428264e-02 -9.84500349e-01 -1.48739249e-01 -9.29431170e-02 -9.85016584e-01 -1.45325214e-01 -9.29428264e-02 -9.85514462e-01 -1.41861826e-01 -9.29431021e-02 -9.85990345e-01 -1.38539493e-01 -9.29430351e-02 -9.86487448e-01 -1.34985879e-01 -9.29428264e-02 -9.86945927e-01 -1.31541997e-01 -9.29431096e-02 -9.87389207e-01 -1.28191516e-01 -9.29430574e-02 -9.87833917e-01 -1.24739505e-01 -9.29429904e-02 -9.88259315e-01 -1.21303625e-01 -9.29429978e-02 -9.88686860e-01 -1.17777288e-01 -9.29428339e-02 -9.89089727e-01 -1.14307597e-01 -9.29430947e-02 -9.89479125e-01 -1.10922277e-01 -9.29429904e-02 -9.89866972e-01 -1.07417211e-01 -9.29428339e-02 -9.90230620e-01 -1.03967540e-01 -9.29431096e-02 -9.90592420e-01 -1.00507356e-01 -9.29428264e-02 -9.90934253e-01 -9.70288292e-02 -9.29431021e-02 -9.91270602e-01 -9.35891271e-02 -9.29428414e-02 -9.91585195e-01 -9.01333466e-02 -9.29431170e-02 -9.91886497e-01 -8.67555961e-02 -9.29431096e-02 -9.92177784e-01 -8.33026990e-02 -9.29432660e-02 -9.92461503e-01 -7.98458308e-02 -9.29435641e-02 -9.92737234e-01 -7.62984455e-02 -9.29436013e-02 -9.92999613e-01 -7.28358775e-02 -9.29442197e-02 -9.93240416e-01 -6.94562048e-02 -9.29443166e-02 -9.93483245e-01 -6.58959672e-02 -9.29443315e-02 -9.93709028e-01 -6.24207594e-02 -9.29441452e-02 -9.93911922e-01 -5.91223277e-02 -9.29439813e-02 -9.94097531e-01 -5.59073910e-02 -9.29437876e-02 -9.94253933e-01 -5.31126633e-02 -9.29440781e-02 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. 0. 0. -9.95568156e-01 -1.43360216e-02 -9.29440707e-02 -9.95611131e-01 -1.09477220e-02 -9.29440781e-02 -9.95643318e-01 -7.47229625e-03 -9.29440707e-02 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. 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. -9.94970918e-01 5.84150739e-02 -8.13644677e-02 -9.94656265e-01 6.35410845e-02 -8.13645497e-02 -9.94481087e-01 6.62004203e-02 -8.13639984e-02 -9.94244397e-01 6.97283819e-02 -8.13639984e-02 -9.93991852e-01 7.33063146e-02 -8.13646540e-02 -9.93733525e-01 7.67111480e-02 -8.13649669e-02 -9.93464231e-01 8.01641867e-02 -8.13650116e-02 -9.93175268e-01 8.36460069e-02 -8.13650191e-02 -9.92887557e-01 8.69945139e-02 -8.13649148e-02 -9.92582262e-01 9.04311463e-02 -8.13652053e-02 -9.92249191e-01 9.40095186e-02 -8.13651234e-02 -9.91923332e-01 9.73901004e-02 -8.13649967e-02 -9.91579533e-01 1.00831881e-01 -8.13652575e-02 -9.91209745e-01 1.04400434e-01 -8.13650414e-02 -9.90840256e-01 1.07851170e-01 -8.13650936e-02 -9.90460098e-01 1.11303806e-01 -8.13650489e-02 -9.90066409e-01 1.14718951e-01 -8.13649446e-02 -9.89666939e-01 1.18103802e-01 -8.13648552e-02 -9.89258170e-01 1.21501088e-01 -8.13648999e-02 -9.88824964e-01 1.24976553e-01 -8.13648179e-02 -9.88363862e-01 1.28560603e-01 -8.13646242e-02 -9.87917006e-01 1.31946087e-01 -8.13644677e-02 -9.87456620e-01 1.35370359e-01 -8.13648701e-02 -9.86967385e-01 1.38893381e-01 -8.13647583e-02 -9.86487687e-01 1.42249331e-01 -8.13646838e-02 -9.85984206e-01 1.45701125e-01 -8.13649669e-02 -9.85465407e-01 1.49164855e-01 -8.13647509e-02 -9.84965920e-01 1.52424514e-01 -8.13647062e-02 -9.84399796e-01 1.56035930e-01 -8.13644826e-02 -9.83831286e-01 1.59588426e-01 -8.13646093e-02 -9.83267009e-01 1.63034946e-01 -8.13648477e-02 -9.82697070e-01 1.66447431e-01 -8.13650414e-02 -9.82114196e-01 1.69842631e-01 -8.13651457e-02 -9.81518626e-01 1.73282281e-01 -8.13651979e-02 -9.80903685e-01 1.76725075e-01 -8.13651830e-02 -9.80270863e-01 1.80175871e-01 -8.13652202e-02 -9.79658365e-01 1.83483109e-01 -8.13650340e-02 -9.79038298e-01 1.86763361e-01 -8.13652128e-02 -9.78358328e-01 1.90288872e-01 -8.13655034e-02 -9.77668643e-01 1.93802640e-01 -8.13651532e-02 -9.76989031e-01 1.97209120e-01 -8.13651979e-02 -9.76293147e-01 2.00628176e-01 -8.13652277e-02 -9.75584626e-01 2.04034820e-01 -8.13651979e-02 -9.74882483e-01 2.07369640e-01 -8.13650563e-02 -9.74158466e-01 2.10751265e-01 -8.13653842e-02 -9.73390877e-01 2.14255229e-01 -8.13651979e-02 -9.72658873e-01 2.17560828e-01 -8.13651085e-02 -9.71893907e-01 2.20951706e-01 -8.13653991e-02 -9.71093297e-01 2.24449947e-01 -8.13652351e-02 -9.70303714e-01 2.27842391e-01 -8.13652053e-02 -9.69503045e-01 2.31229693e-01 -8.13652351e-02 -9.68714058e-01 2.34509900e-01 -8.13650563e-02 -9.67918336e-01 2.37766698e-01 -8.13652202e-02 -9.67050791e-01 2.41264597e-01 -8.13655108e-02 -9.66172338e-01 2.44759217e-01 -8.13652053e-02 -9.65312839e-01 2.48133138e-01 -8.13652351e-02 -9.64464307e-01 2.51407683e-01 -8.13650712e-02 -9.63591337e-01 2.54743069e-01 -8.13653842e-02 -9.62687314e-01 2.58134156e-01 -8.13651681e-02 -9.61776555e-01 2.61506736e-01 -8.13652873e-02 -9.60836053e-01 2.64933974e-01 -8.13652128e-02 -9.59925294e-01 2.68223643e-01 -8.13651159e-02 -9.59014416e-01 2.71459252e-01 -8.13652202e-02 -9.58035767e-01 2.74891376e-01 -8.13654363e-02 -9.57042575e-01 2.78329909e-01 -8.13651830e-02 -9.56069827e-01 2.81651855e-01 -8.13651681e-02 -9.55092788e-01 2.84951746e-01 -8.13651830e-02 -9.54088748e-01 2.88289338e-01 -8.13652724e-02 -9.53092396e-01 2.91568398e-01 -8.13650861e-02 -9.52075541e-01 2.94876188e-01 -8.13653618e-02 -9.51008141e-01 2.98297584e-01 -8.13651532e-02 -9.49987471e-01 3.01530242e-01 -8.13651383e-02 -9.48926568e-01 3.04855675e-01 -8.13653842e-02 -9.47834790e-01 3.08229357e-01 -8.13651830e-02 -9.46748972e-01 3.11548799e-01 -8.13651904e-02 -9.45662260e-01 3.14832181e-01 -8.13651532e-02 -9.44552124e-01 3.18156838e-01 -8.13651681e-02 -9.43462133e-01 3.21363419e-01 -8.13650936e-02 -9.42363918e-01 3.24577034e-01 -8.13651979e-02 -9.41202521e-01 3.27924341e-01 -8.13653618e-02 -9.40018773e-01 3.31302971e-01 -8.13651979e-02 -9.38885212e-01 3.34507138e-01 -8.13650861e-02 -9.37716544e-01 3.37766618e-01 -8.13654587e-02 -9.36492622e-01 3.41146320e-01 -8.13651979e-02 -9.35297787e-01 3.44391704e-01 -8.13651904e-02 -9.34091091e-01 3.47640097e-01 -8.13651830e-02 -9.32895124e-01 3.50837946e-01 -8.13651383e-02 -9.31708395e-01 3.53992730e-01 -8.13651979e-02 -9.30447519e-01 3.57316256e-01 -8.13653395e-02 -9.29144740e-01 3.60669225e-01 -8.13652351e-02 -9.27878618e-01 3.63923758e-01 -8.13652128e-02 -9.26603436e-01 3.67158413e-01 -8.13652277e-02 -9.25316513e-01 3.70386094e-01 -8.13651904e-02 -9.24022198e-01 3.73601675e-01 -8.13651681e-02 -9.22717035e-01 3.76817077e-01 -8.13651979e-02 -9.21397626e-01 3.80027771e-01 -8.13651904e-02 -9.20093834e-01 3.83173823e-01 -8.13650638e-02 -9.18789744e-01 3.86293799e-01 -8.13652053e-02 -9.17407215e-01 3.89564812e-01 -8.13653618e-02 -9.16001916e-01 3.92852783e-01 -8.13651904e-02 -9.14637446e-01 3.96021158e-01 -8.13651457e-02 -9.13264453e-01 3.99185658e-01 -8.13652351e-02 -9.11870062e-01 4.02354032e-01 -8.13651159e-02 -9.10479665e-01 4.05493647e-01 -8.13652501e-02 -9.09031570e-01 4.08731490e-01 -8.13653097e-02 -9.07568514e-01 4.11967427e-01 -8.13651830e-02 -9.06160593e-01 4.15047824e-01 -8.13650414e-02 -9.04719651e-01 4.18185741e-01 -8.13653693e-02 -9.03211057e-01 4.21431094e-01 -8.13652128e-02 -9.01743829e-01 4.24561530e-01 -8.13651532e-02 -9.00272489e-01 4.27676648e-01 -8.13651830e-02 -8.98773134e-01 4.30814803e-01 -8.13651532e-02 -8.97308111e-01 4.33868110e-01 -8.13651606e-02 -8.95770192e-01 4.37033385e-01 -8.13653618e-02 -8.94192517e-01 4.40246046e-01 -8.13651979e-02 -8.92655075e-01 4.43356782e-01 -8.13651681e-02 -8.91100526e-01 4.46470022e-01 -8.13651979e-02 -8.89538884e-01 4.49576527e-01 -8.13651830e-02 -8.88000786e-01 4.52606410e-01 -8.13651159e-02 -8.86459589e-01 4.55618143e-01 -8.13651755e-02 -8.84835184e-01 4.58764404e-01 -8.13653097e-02 -8.83187115e-01 4.61930603e-01 -8.13651979e-02 -8.81602466e-01 4.64947551e-01 -8.13650712e-02 -8.79989743e-01 4.67991263e-01 -8.13652799e-02 -8.78308654e-01 4.71139044e-01 -8.13651830e-02 -8.76655638e-01 4.74205673e-01 -8.13651979e-02 -8.74999166e-01 4.77261215e-01 -8.13651830e-02 -8.73313725e-01 4.80335534e-01 -8.13652053e-02 -8.71683598e-01 4.83280003e-01 -8.13650787e-02 -8.70002270e-01 4.86306161e-01 -8.13653246e-02 -8.68250132e-01 4.89430189e-01 -8.13652128e-02 -8.66531730e-01 4.92462307e-01 -8.13651830e-02 -8.64809573e-01 4.95483577e-01 -8.13651681e-02 -8.63091528e-01 4.98471737e-01 -8.13651830e-02 -8.61350656e-01 5.01470983e-01 -8.13651532e-02 -8.59591126e-01 5.04481375e-01 -8.13651830e-02 -8.57818305e-01 5.07489979e-01 -8.13651904e-02 -8.56085241e-01 5.10406971e-01 -8.13650787e-02 -8.54326248e-01 5.13348639e-01 -8.13652501e-02 -8.52478147e-01 5.16409099e-01 -8.13652575e-02 -8.50662410e-01 5.19398391e-01 -8.13651606e-02 -8.48838031e-01 5.22369146e-01 -8.13652277e-02 -8.47003460e-01 5.25343955e-01 -8.13651681e-02 -8.45174432e-01 5.28277457e-01 -8.13651681e-02 -8.43366206e-01 5.31160712e-01 -8.13651010e-02 -8.41505706e-01 5.34104466e-01 -8.13654214e-02 -8.39580953e-01 5.37122726e-01 -8.13652128e-02 -8.37749362e-01 5.39972544e-01 -8.13650489e-02 -8.35863829e-01 5.42889476e-01 -8.13653842e-02 -8.33943665e-01 5.45833409e-01 -8.13651755e-02 -8.32030833e-01 5.48746049e-01 -8.13652202e-02 -8.30079675e-01 5.51690519e-01 -8.13651979e-02 -8.28159392e-01 5.54572284e-01 -8.13652351e-02 -8.26270401e-01 5.57383060e-01 -8.13650638e-02 -8.24315906e-01 5.60268939e-01 -8.13654363e-02 -8.22294772e-01 5.63231051e-01 -8.13651606e-02 -8.20330799e-01 5.66089272e-01 -8.13651755e-02 -8.18395436e-01 5.68880916e-01 -8.13650191e-02 -8.16414118e-01 5.71720958e-01 -8.13652948e-02 -8.14377546e-01 5.74621439e-01 -8.13651457e-02 -8.12354803e-01 5.77473223e-01 -8.13652873e-02 -8.10316741e-01 5.80332518e-01 -8.13651532e-02 -8.08343232e-01 5.83070636e-01 -8.13650340e-02 -8.06350589e-01 5.85831523e-01 -8.13651904e-02 -8.04229379e-01 5.88736355e-01 -8.13651979e-02 -8.02120864e-01 5.91607809e-01 -8.13652128e-02 -8.00048411e-01 5.94405532e-01 -8.13651755e-02 -7.97968507e-01 5.97195089e-01 -8.13651830e-02 -7.95887411e-01 5.99968076e-01 -8.13651532e-02 -7.93792963e-01 6.02737963e-01 -8.13651830e-02 -7.91673601e-01 6.05517268e-01 -8.13651830e-02 -7.89572179e-01 6.08252704e-01 -8.13651383e-02 -7.87479103e-01 6.10959470e-01 -8.13649893e-02 -7.85364151e-01 6.13675892e-01 -8.13654065e-02 -7.83123910e-01 6.16534889e-01 -8.13651532e-02 -7.80972838e-01 6.19255662e-01 -8.13651755e-02 -7.78804302e-01 6.21984661e-01 -8.13651979e-02 -7.76627302e-01 6.24698341e-01 -8.13651383e-02 -7.74456799e-01 6.27388120e-01 -8.13651830e-02 -7.72325099e-01 6.30004525e-01 -8.13650116e-02 -7.70137072e-01 6.32684588e-01 -8.13652724e-02 -7.67844021e-01 6.35463715e-01 -8.13651681e-02 -7.65683353e-01 6.38062179e-01 -8.13650265e-02 -7.63466239e-01 6.40716195e-01 -8.13653395e-02 -7.61160731e-01 6.43453300e-01 -8.13651159e-02 -7.58915305e-01 6.46097898e-01 -8.13651904e-02 -7.56634951e-01 6.48768365e-01 -8.13652202e-02 -7.54391670e-01 6.51378095e-01 -8.13651383e-02 -7.52180576e-01 6.53928995e-01 -8.13651457e-02 -7.49861360e-01 6.56586051e-01 -8.13653842e-02 -7.47480512e-01 6.59295857e-01 -8.13651979e-02 -7.45154679e-01 6.61922336e-01 -8.13651457e-02 -7.42844820e-01 6.64515138e-01 -8.13651457e-02 -7.40531683e-01 6.67090356e-01 -8.13651830e-02 -7.38214910e-01 6.69657350e-01 -8.13651532e-02 -7.35856950e-01 6.72241747e-01 -8.13651010e-02 -7.33517110e-01 6.74798727e-01 -8.13651681e-02 -7.31217563e-01 6.77287757e-01 -8.13650489e-02 -7.28848755e-01 6.79836035e-01 -8.13653320e-02 -7.26383746e-01 6.82468474e-01 -8.13651830e-02 -7.23998547e-01 6.84998095e-01 -8.13651830e-02 -7.21600533e-01 6.87525570e-01 -8.13651830e-02 -7.19201803e-01 6.90028429e-01 -8.13651830e-02 -7.16801226e-01 6.92535162e-01 -8.13651830e-02 -7.14434147e-01 6.94974184e-01 -8.13650861e-02 -7.12019444e-01 6.97446525e-01 -8.13652724e-02 -7.09516048e-01 6.99994028e-01 -8.13651904e-02 -7.07113147e-01 7.02422678e-01 -8.13650340e-02 -7.04656959e-01 7.04868436e-01 -8.13652948e-02 -7.02140331e-01 7.07394719e-01 -8.13651830e-02 -6.99659467e-01 7.09847748e-01 -8.13651830e-02 -6.97185338e-01 7.12274075e-01 -8.13651532e-02 -6.94719076e-01 7.14683473e-01 -8.13651532e-02 -6.92272961e-01 7.17052698e-01 -8.13650638e-02 -6.89749539e-01 7.19470322e-01 -8.13652501e-02 -6.87172592e-01 7.21939802e-01 -8.13651904e-02 -6.84645891e-01 7.24330902e-01 -8.13651904e-02 -6.82111919e-01 7.26716816e-01 -8.13651681e-02 -6.79573596e-01 7.29089618e-01 -8.13651830e-02 -6.77025914e-01 7.31458902e-01 -8.13651532e-02 -6.74469233e-01 7.33821213e-01 -8.13652501e-02 -6.71903729e-01 7.36167371e-01 -8.13651681e-02 -6.69334292e-01 7.38506794e-01 -8.13651904e-02 -6.66814089e-01 7.40781069e-01 -8.13650563e-02 -6.64237142e-01 7.43093669e-01 -8.13653842e-02 -6.61560357e-01 7.45478451e-01 -8.13651681e-02 -6.58947289e-01 7.47787952e-01 -8.13652053e-02 -6.56333208e-01 7.50082433e-01 -8.13651830e-02 -6.53715372e-01 7.52366126e-01 -8.13651979e-02 -6.51137531e-01 7.54597843e-01 -8.13651159e-02 -6.48497701e-01 7.56868422e-01 -8.13653097e-02 -6.45795047e-01 7.59176254e-01 -8.13652128e-02 -6.43192172e-01 7.61381209e-01 -8.13650638e-02 -6.40555501e-01 7.63599932e-01 -8.13653022e-02 -6.37811244e-01 7.65895188e-01 -8.13651606e-02 -6.35140419e-01 7.68110096e-01 -8.13651681e-02 -6.32443964e-01 7.70334303e-01 -8.13652053e-02 -6.29827201e-01 7.72471189e-01 -8.13650638e-02 -6.27131581e-01 7.74666190e-01 -8.13653842e-02 -6.24336660e-01 7.76917577e-01 -8.13651681e-02 -6.21697009e-01 7.79030859e-01 -8.13650638e-02 -6.18972540e-01 7.81198204e-01 -8.13653916e-02 -6.16242945e-01 7.83351898e-01 -8.13650191e-02 -6.13528669e-01 7.85481155e-01 -8.13653693e-02 -6.10693395e-01 7.87688136e-01 -8.13651830e-02 -6.07993364e-01 7.89773107e-01 -8.13650265e-02 -6.05282128e-01 7.91854501e-01 -8.13653618e-02 -6.02478623e-01 7.93987274e-01 -8.13650638e-02 -5.99702060e-01 7.96088696e-01 -8.13653320e-02 -5.96914411e-01 7.98178732e-01 -8.13650712e-02 -5.94139040e-01 8.00247729e-01 -8.13653842e-02 -5.91239929e-01 8.02390754e-01 -8.13652128e-02 -5.88449478e-01 8.04439545e-01 -8.13651979e-02 -5.85707128e-01 8.06439698e-01 -8.13650340e-02 -5.82957923e-01 8.08427632e-01 -8.13652277e-02 -5.80037892e-01 8.10527563e-01 -8.13652128e-02 -5.77218175e-01 8.12537432e-01 -8.13650638e-02 -5.74417949e-01 8.14523101e-01 -8.13653618e-02 -5.71563661e-01 8.16523552e-01 -8.13650340e-02 -5.68722606e-01 8.18505168e-01 -8.13653097e-02 -5.65778077e-01 8.20544660e-01 -8.13652053e-02 -5.62889040e-01 8.22529435e-01 -8.13651532e-02 -5.60092211e-01 8.24433744e-01 -8.13651159e-02 -5.57297766e-01 8.26327920e-01 -8.13651830e-02 -5.54320395e-01 8.28326702e-01 -8.13652053e-02 -5.51424563e-01 8.30255091e-01 -8.13650489e-02 -5.48547268e-01 8.32162619e-01 -8.13652575e-02 -5.45629621e-01 8.34075987e-01 -8.13650787e-02 -5.42754292e-01 8.35951149e-01 -8.13652724e-02 -5.39749861e-01 8.37893724e-01 -8.13651979e-02 -5.36799371e-01 8.39787126e-01 -8.13652053e-02 -5.33854663e-01 8.41661811e-01 -8.13651755e-02 -5.30900180e-01 8.43530238e-01 -8.13651830e-02 -5.27949631e-01 8.45379829e-01 -8.13651532e-02 -5.25079012e-01 8.47166181e-01 -8.13650563e-02 -5.22135973e-01 8.48982751e-01 -8.13654363e-02 -5.19056261e-01 8.50870609e-01 -8.13652128e-02 -5.16055584e-01 8.52691829e-01 -8.13651830e-02 -5.13167799e-01 8.54432523e-01 -8.13650265e-02 -5.10200441e-01 8.56209636e-01 -8.13653842e-02 -5.07099211e-01 8.58048320e-01 -8.13651606e-02 -5.04196048e-01 8.59757900e-01 -8.13650340e-02 -5.01223505e-01 8.61495256e-01 -8.13653022e-02 -4.98175263e-01 8.63261342e-01 -8.13650340e-02 -4.95182574e-01 8.64980340e-01 -8.13653097e-02 -4.92077798e-01 8.66750956e-01 -8.13651532e-02 -4.89071786e-01 8.68452251e-01 -8.13651383e-02 -4.86147285e-01 8.70089829e-01 -8.13651457e-02 -4.83071715e-01 8.71801794e-01 -8.13653395e-02 -4.79940087e-01 8.73530269e-01 -8.13650489e-02 -4.76992399e-01 8.75144124e-01 -8.13650340e-02 -4.73918587e-01 8.76812696e-01 -8.13655108e-02 -4.70822662e-01 8.78476679e-01 -8.13650563e-02 -4.67803419e-01 8.80090237e-01 -8.13652277e-02 -4.64717031e-01 8.81723285e-01 -8.13650936e-02 -4.61638391e-01 8.83339226e-01 -8.13652351e-02 -4.58491296e-01 8.84976447e-01 -8.13651755e-02 -4.55393761e-01 8.86574686e-01 -8.13651532e-02 -4.52293515e-01 8.88160169e-01 -8.13651681e-02 -4.49241132e-01 8.89707983e-01 -8.13650340e-02 -4.46148634e-01 8.91262949e-01 -8.13652277e-02 -4.42973644e-01 8.92845809e-01 -8.13651681e-02 -4.39849645e-01 8.94387484e-01 -8.13651681e-02 -4.36781257e-01 8.95890415e-01 -8.13650489e-02 -4.33652908e-01 8.97410512e-01 -8.13652724e-02 -4.30457324e-01 8.98945510e-01 -8.13651681e-02 -4.27313834e-01 9.00443792e-01 -8.13651681e-02 -4.24160779e-01 9.01933908e-01 -8.13651234e-02 -4.21090454e-01 9.03370559e-01 -8.13650489e-02 -4.17927861e-01 9.04839516e-01 -8.13652351e-02 -4.14682597e-01 9.06329632e-01 -8.13652053e-02 -4.11529303e-01 9.07766938e-01 -8.13651606e-02 -4.08456743e-01 9.09153521e-01 -8.13650340e-02 -4.05298948e-01 9.10566390e-01 -8.13652873e-02 -4.02025402e-01 9.12016511e-01 -8.13651532e-02 -3.98908108e-01 9.13385689e-01 -8.13650638e-02 -3.95711273e-01 9.14773524e-01 -8.13652351e-02 -3.92499655e-01 9.16151583e-01 -8.13650489e-02 -3.89388204e-01 9.17482078e-01 -8.13651830e-02 -3.86174887e-01 9.18840230e-01 -8.13651457e-02 -3.82924408e-01 9.20199037e-01 -8.13652351e-02 -3.79624158e-01 9.21564400e-01 -8.13651606e-02 -3.76402497e-01 9.22885835e-01 -8.13651457e-02 -3.73183459e-01 9.24192607e-01 -8.13651755e-02 -3.69988531e-01 9.25474703e-01 -8.13651085e-02 -3.66771132e-01 9.26756501e-01 -8.13652724e-02 -3.63493562e-01 9.28046823e-01 -8.13651830e-02 -3.60225022e-01 9.29314375e-01 -8.13651308e-02 -3.57077360e-01 9.30538774e-01 -8.13650712e-02 -3.53843749e-01 9.31765556e-01 -8.13652501e-02 -3.50508779e-01 9.33019102e-01 -8.13651681e-02 -3.47230554e-01 9.34243560e-01 -8.13651606e-02 -3.44064623e-01 9.35416222e-01 -8.13650489e-02 -3.40891331e-01 9.36586380e-01 -8.13651532e-02 -3.37539405e-01 9.37797070e-01 -8.13652724e-02 -3.34250748e-01 9.38976109e-01 -8.13650191e-02 -3.31005245e-01 9.40124333e-01 -8.13652426e-02 -3.27697933e-01 9.41281617e-01 -8.13650563e-02 -3.24434757e-01 9.42412615e-01 -8.13652501e-02 -3.21083963e-01 9.43557918e-01 -8.13651755e-02 -3.17844748e-01 9.44654822e-01 -8.13650936e-02 -3.14541698e-01 9.45758700e-01 -8.13652351e-02 -3.11232805e-01 9.46852028e-01 -8.13651159e-02 -3.07914078e-01 9.47938383e-01 -8.13653320e-02 -3.04605633e-01 9.49006855e-01 -8.13650489e-02 -3.01301479e-01 9.50061023e-01 -8.13651681e-02 -2.97896773e-01 9.51132894e-01 -8.13651606e-02 -2.94571936e-01 9.52167928e-01 -8.13651532e-02 -2.91253507e-01 9.53188300e-01 -8.13651681e-02 -2.87921488e-01 9.54198897e-01 -8.13651457e-02 -2.84597069e-01 9.55196977e-01 -8.13651681e-02 -2.81279594e-01 9.56179917e-01 -8.13651234e-02 -2.77942598e-01 9.57155526e-01 -8.13651606e-02 -2.74667203e-01 9.58099425e-01 -8.13650638e-02 -2.71306217e-01 9.59058225e-01 -8.13652650e-02 -2.67895937e-01 9.60014880e-01 -8.13651383e-02 -2.64553517e-01 9.60942030e-01 -8.13651681e-02 -2.61256903e-01 9.61845338e-01 -8.13650414e-02 -2.57986307e-01 9.62726831e-01 -8.13651681e-02 -2.54560322e-01 9.63637352e-01 -8.13652575e-02 -2.51191288e-01 9.64521468e-01 -8.13650638e-02 -2.47818962e-01 9.65393543e-01 -8.13653246e-02 -2.44452685e-01 9.66248631e-01 -8.13650191e-02 -2.41081223e-01 9.67096984e-01 -8.13652873e-02 -2.37578213e-01 9.67965782e-01 -8.13651532e-02 -2.34300926e-01 9.68763590e-01 -8.13650340e-02 -2.30909809e-01 9.69579041e-01 -8.13653618e-02 -2.27537885e-01 9.70372379e-01 -8.13650116e-02 -2.24180460e-01 9.71155286e-01 -8.13652948e-02 -2.20757231e-01 9.71937358e-01 -8.13650414e-02 -2.17488796e-01 9.72676277e-01 -8.13651830e-02 -2.13963047e-01 9.73456800e-01 -8.13653618e-02 -2.10453585e-01 9.74221408e-01 -8.13651457e-02 -2.07057163e-01 9.74948823e-01 -8.13651830e-02 -2.03673229e-01 9.75661576e-01 -8.13651234e-02 -2.00365081e-01 9.76345003e-01 -8.13650340e-02 -1.96932048e-01 9.77043927e-01 -8.13653767e-02 -1.93405688e-01 9.77747917e-01 -8.13651606e-02 -1.90001577e-01 9.78415370e-01 -8.13651532e-02 -1.86577305e-01 9.79074776e-01 -8.13651830e-02 -1.83277428e-01 9.79695320e-01 -8.13649669e-02 -1.79848745e-01 9.80330408e-01 -8.13652202e-02 -1.76425502e-01 9.80958700e-01 -8.13650563e-02 -1.72991723e-01 9.81571198e-01 -8.13653246e-02 -1.69479027e-01 9.82177138e-01 -8.13651383e-02 -1.66137606e-01 9.82749403e-01 -8.13650340e-02 -1.62719935e-01 9.83321190e-01 -8.13652948e-02 -1.59279093e-01 9.83882010e-01 -8.13650116e-02 -1.55861303e-01 9.84431267e-01 -8.13653097e-02 -1.52284846e-01 9.84990656e-01 -8.13651532e-02 -1.48960724e-01 9.85497773e-01 -8.13650340e-02 -1.45522043e-01 9.86013055e-01 -8.13653097e-02 -1.42065942e-01 9.86514747e-01 -8.13650340e-02 -1.38637796e-01 9.87005711e-01 -8.13652501e-02 -1.35092616e-01 9.87496853e-01 -8.13651383e-02 -1.31706491e-01 9.87950444e-01 -8.13650340e-02 -1.28271058e-01 9.88405347e-01 -8.13652128e-02 -1.24729291e-01 9.88858342e-01 -8.13651159e-02 -1.21277906e-01 9.89286363e-01 -8.13651457e-02 -1.17922910e-01 9.89690661e-01 -8.13650340e-02 -1.14575595e-01 9.90084291e-01 -8.13651681e-02 -1.11009732e-01 9.90492046e-01 -8.13652501e-02 -1.07453279e-01 9.90882218e-01 -8.13651234e-02 -1.03980765e-01 9.91254032e-01 -8.13651532e-02 -1.00518413e-01 9.91609633e-01 -8.13651457e-02 -9.71320197e-02 9.91948009e-01 -8.13650116e-02 -9.37057957e-02 9.92278993e-01 -8.13652873e-02 -9.02476460e-02 9.92598832e-01 -8.13649893e-02 -8.67809132e-02 9.92909431e-01 -8.13653022e-02 -8.31843168e-02 9.93215978e-01 -8.13651159e-02 -7.98376948e-02 9.93490815e-01 -8.13650116e-02 -7.64003992e-02 9.93760049e-01 -8.13651830e-02 -7.28750378e-02 9.94024396e-01 -8.13649744e-02 -6.94277585e-02 9.94271874e-01 -8.13653469e-02 -6.58246353e-02 9.94517744e-01 -8.13651606e-02 -6.23449683e-02 9.94738638e-01 -8.13651308e-02 -5.88966347e-02 9.94950891e-01 -8.13651606e-02 -5.55377826e-02 9.95143592e-01 -8.13649669e-02 -5.20405695e-02 9.95331645e-01 -8.13652501e-02 -4.85541373e-02 9.95509028e-01 -8.13650265e-02 -4.51996997e-02 9.95667100e-01 -8.13651457e-02 -4.16335650e-02 9.95822549e-01 -8.13652650e-02 -3.80407088e-02 9.95965838e-01 -8.13651159e-02 -3.45677473e-02 9.96092618e-01 -8.13651532e-02 -3.10761817e-02 9.96208251e-01 -8.13651606e-02 -2.76966896e-02 9.96306658e-01 -8.13650265e-02 -2.43226625e-02 9.96398270e-01 -8.13651606e-02 -2.07408536e-02 9.96473730e-01 -8.13652724e-02 -1.71337109e-02 9.96550500e-01 -8.13651532e-02 -1.36864837e-02 9.96594727e-01 -8.13651532e-02 -1.03268605e-02 9.96636450e-01 -8.13649669e-02 -6.84824167e-03 9.96675134e-01 -8.13651681e-02 -3.32388468e-03 9.96691406e-01 -8.13650265e-02 1.29880747e-04 9.96693909e-01 -8.13652128e-02 3.70001560e-03 9.96691585e-01 -8.13650861e-02 7.09634973e-03 9.96671140e-01 -8.13650116e-02 1.05818668e-02 9.96636629e-01 -8.13652128e-02 1.40483715e-02 9.96590436e-01 -8.13650042e-02 1.75157860e-02 9.96544778e-01 -8.13652351e-02 2.10218467e-02 9.96470034e-01 -8.13649893e-02 2.44136825e-02 9.96394694e-01 -8.13651457e-02 2.79494859e-02 9.96302426e-01 -8.13652351e-02 3.15446518e-02 9.96192992e-01 -8.13650936e-02 3.50052901e-02 9.96078908e-01 -8.13651383e-02 3.84801105e-02 9.95950580e-01 -8.13651159e-02 4.18707766e-02 9.95814025e-01 -8.13650340e-02 4.53515984e-02 9.95659947e-01 -8.13652277e-02 4.89244983e-02 9.95492280e-01 -8.13651681e-02 5.23757152e-02 9.95311856e-01 -8.13651234e-02 5.58306277e-02 9.95129049e-01 -8.13651532e-02 5.92254996e-02 9.94931996e-01 -8.13650265e-02 6.26838803e-02 9.94717479e-01 -8.13652575e-02 6.62671626e-02 9.94486392e-01 -8.13651383e-02 6.97564855e-02 9.94247079e-01 -8.13651457e-02 7.32479468e-02 9.93998170e-01 -8.13651383e-02 7.66164437e-02 9.93742466e-01 -8.13650414e-02 8.00666958e-02 9.93471801e-01 -8.13653097e-02 8.35446790e-02 9.93184149e-01 -8.13649520e-02 8.69849622e-02 9.92889822e-01 -8.13652575e-02 9.05563310e-02 9.92570341e-01 -8.13651457e-02 9.39513147e-02 9.92252290e-01 -8.13648924e-02 9.73962247e-02 9.91923332e-01 -8.13652202e-02 1.00880571e-01 9.91574585e-01 -8.13650191e-02 1.04313686e-01 9.91219103e-01 -8.13652351e-02 1.07803047e-01 9.90844905e-01 -8.13650042e-02 1.11238226e-01 9.90467370e-01 -8.13653097e-02 1.14797756e-01 9.90058184e-01 -8.13651457e-02 1.18250467e-01 9.89651620e-01 -8.13651532e-02 1.21675789e-01 9.89237309e-01 -8.13651457e-02 1.25089422e-01 9.88813698e-01 -8.13650340e-02 1.28445089e-01 9.88381088e-01 -8.13651532e-02 1.31950438e-01 9.87920463e-01 -8.13652351e-02 1.35482952e-01 9.87442434e-01 -8.13651532e-02 1.38964340e-01 9.86958623e-01 -8.13651681e-02 1.42406046e-01 9.86465991e-01 -8.13651159e-02 1.45778596e-01 9.85973001e-01 -8.13649893e-02 1.49175420e-01 9.85465109e-01 -8.13652202e-02 1.52643666e-01 9.84934926e-01 -8.13650042e-02 1.56084567e-01 9.84395683e-01 -8.13653320e-02 1.59609586e-01 9.83830094e-01 -8.13651681e-02 1.62949204e-01 9.83282447e-01 -8.13650489e-02 1.66352227e-01 9.82713640e-01 -8.13652351e-02 1.69809401e-01 9.82120037e-01 -8.13650489e-02 1.73128918e-01 9.81544852e-01 -8.13651532e-02 1.76618576e-01 9.80922699e-01 -8.13652202e-02 1.80173844e-01 9.80271161e-01 -8.13650936e-02 1.83602631e-01 9.79635954e-01 -8.13651532e-02 1.86903760e-01 9.79010880e-01 -8.13650712e-02 1.90328494e-01 9.78351176e-01 -8.13652277e-02 1.93746924e-01 9.77681220e-01 -8.13650936e-02 1.97078466e-01 9.77013350e-01 -8.13651681e-02 2.00552687e-01 9.76308167e-01 -8.13652351e-02 2.04063073e-01 9.75578904e-01 -8.13651159e-02 2.07453340e-01 9.74864900e-01 -8.13651383e-02 2.10855931e-01 9.74134684e-01 -8.13651606e-02 2.14186192e-01 9.73404169e-01 -8.13650191e-02 2.17557997e-01 9.72661197e-01 -8.13652128e-02 2.21047059e-01 9.71870065e-01 -8.13650638e-02 2.24462077e-01 9.71089959e-01 -8.13651234e-02 2.27853879e-01 9.70300734e-01 -8.13651457e-02 2.31148332e-01 9.69519556e-01 -8.13649669e-02 2.34426588e-01 9.68735337e-01 -8.13651532e-02 2.37822309e-01 9.67903852e-01 -8.13651532e-02 2.41258502e-01 9.67052460e-01 -8.13652277e-02 2.44727254e-01 9.66180205e-01 -8.13651383e-02 2.48031467e-01 9.65338528e-01 -8.13650340e-02 2.51391917e-01 9.64468956e-01 -8.13652277e-02 2.54755437e-01 9.63586390e-01 -8.13650340e-02 2.58095115e-01 9.62697625e-01 -8.13652575e-02 2.61561126e-01 9.61761713e-01 -8.13651457e-02 2.64841795e-01 9.60861385e-01 -8.13650414e-02 2.68188477e-01 9.59934294e-01 -8.13653693e-02 2.71556735e-01 9.58985209e-01 -8.13649669e-02 2.74857104e-01 9.58045602e-01 -8.13652873e-02 2.78327584e-01 9.57041800e-01 -8.13650489e-02 2.81557292e-01 9.56097662e-01 -8.13650712e-02 2.84886718e-01 9.55112815e-01 -8.13652873e-02 2.88334846e-01 9.54073787e-01 -8.13651532e-02 2.91634977e-01 9.53073442e-01 -8.13651532e-02 2.94841766e-01 9.52085555e-01 -8.13650489e-02 2.98093498e-01 9.51072574e-01 -8.13651681e-02 3.01430255e-01 9.50020194e-01 -8.13652128e-02 3.04837912e-01 9.48930442e-01 -8.13653022e-02 3.08264226e-01 9.47824001e-01 -8.13652277e-02 3.11551154e-01 9.46748435e-01 -8.13651830e-02 3.14790964e-01 9.45676029e-01 -8.13650191e-02 3.17974120e-01 9.44612563e-01 -8.13651681e-02 3.21262658e-01 9.43496406e-01 -8.13651532e-02 3.24632585e-01 9.42344308e-01 -8.13652650e-02 3.28023940e-01 9.41166759e-01 -8.13651830e-02 3.31224680e-01 9.40046847e-01 -8.13650489e-02 3.34509254e-01 9.38884497e-01 -8.13653618e-02 3.37795645e-01 9.37703073e-01 -8.13650563e-02 3.41020852e-01 9.36538637e-01 -8.13652575e-02 3.44408453e-01 9.35290575e-01 -8.13651606e-02 3.47650230e-01 9.34086740e-01 -8.13651383e-02 3.50915015e-01 9.32867527e-01 -8.13652128e-02 3.54106516e-01 9.31663573e-01 -8.13650712e-02 3.57344866e-01 9.30435956e-01 -8.13652501e-02 3.60591859e-01 9.29172516e-01 -8.13650340e-02 3.63719225e-01 9.27956879e-01 -8.13651457e-02 3.67073327e-01 9.26636636e-01 -8.13652501e-02 3.70381892e-01 9.25318182e-01 -8.13651532e-02 3.73586774e-01 9.24027622e-01 -8.13651681e-02 3.76799464e-01 9.22724009e-01 -8.13651606e-02 3.79958600e-01 9.21424627e-01 -8.13650712e-02 3.83090019e-01 9.20129299e-01 -8.13651904e-02 3.86380970e-01 9.18752372e-01 -8.13653767e-02 3.89662147e-01 9.17364180e-01 -8.13651681e-02 3.92842919e-01 9.16007102e-01 -8.13652053e-02 3.95993292e-01 9.14650083e-01 -8.13650936e-02 3.99108589e-01 9.13297772e-01 -8.13651681e-02 4.02290612e-01 9.11898911e-01 -8.13651681e-02 4.05524880e-01 9.10465598e-01 -8.13652873e-02 4.08769071e-01 9.09013450e-01 -8.13651904e-02 4.11872953e-01 9.07610059e-01 -8.13651159e-02 4.14968997e-01 9.06197369e-01 -8.13651904e-02 4.18109626e-01 9.04752672e-01 -8.13651606e-02 4.21257615e-01 9.03293312e-01 -8.13651681e-02 4.24431860e-01 9.01804924e-01 -8.13650489e-02 4.27576542e-01 9.00318205e-01 -8.13651681e-02 4.30817574e-01 8.98771226e-01 -8.13651681e-02 4.33951795e-01 8.97266209e-01 -8.13651830e-02 4.37013596e-01 8.95778954e-01 -8.13650712e-02 4.40088809e-01 8.94270062e-01 -8.13651904e-02 4.43190068e-01 8.92738044e-01 -8.13651681e-02 4.46369410e-01 8.91152442e-01 -8.13652873e-02 4.49554801e-01 8.89550090e-01 -8.13651830e-02 4.52642679e-01 8.87982070e-01 -8.13652053e-02 4.55677509e-01 8.86427820e-01 -8.13649744e-02 4.58709687e-01 8.84860337e-01 -8.13650638e-02 4.61771041e-01 8.83271873e-01 -8.13651830e-02 4.64919686e-01 8.81616950e-01 -8.13652575e-02 4.68069464e-01 8.79948795e-01 -8.13651383e-02 4.71137702e-01 8.78310025e-01 -8.13651830e-02 4.74128276e-01 8.76696408e-01 -8.13650638e-02 4.77139622e-01 8.75066042e-01 -8.13651606e-02 4.80178148e-01 8.73399854e-01 -8.13651383e-02 4.83268887e-01 8.71690750e-01 -8.13653320e-02 4.86391157e-01 8.69954407e-01 -8.13651681e-02 4.89386231e-01 8.68273318e-01 -8.13650191e-02 4.92364109e-01 8.66588473e-01 -8.13653618e-02 4.95412320e-01 8.64850104e-01 -8.13650340e-02 4.98356849e-01 8.63155842e-01 -8.13651457e-02 5.01446128e-01 8.61366332e-01 -8.13652277e-02 5.04451215e-01 8.59608591e-01 -8.13651159e-02 5.07450163e-01 8.57842028e-01 -8.13653618e-02 5.10435462e-01 8.56067896e-01 -8.13650638e-02 5.13413608e-01 8.54287148e-01 -8.13652575e-02 5.16425490e-01 8.52467477e-01 -8.13651234e-02 5.19303620e-01 8.50718260e-01 -8.13651383e-02 5.22323906e-01 8.48867357e-01 -8.13653544e-02 5.25297701e-01 8.47031176e-01 -8.13650936e-02 5.28244257e-01 8.45196366e-01 -8.13653171e-02 5.31218290e-01 8.43328893e-01 -8.13650936e-02 5.34040511e-01 8.41545403e-01 -8.13651532e-02 5.37015557e-01 8.39649975e-01 -8.13652202e-02 5.39946496e-01 8.37767839e-01 -8.13651159e-02 5.42908549e-01 8.35851312e-01 -8.13652351e-02 5.45894027e-01 8.33905578e-01 -8.13651830e-02 5.48741639e-01 8.32034528e-01 -8.13650712e-02 5.51564693e-01 8.30161989e-01 -8.13651532e-02 5.54446638e-01 8.28243077e-01 -8.13651532e-02 5.57390153e-01 8.26266527e-01 -8.13651383e-02 5.60321152e-01 8.24277878e-01 -8.13649669e-02 5.63149154e-01 8.22346807e-01 -8.13646019e-02 5.65984011e-01 8.20398688e-01 -8.13645199e-02 5.68819880e-01 8.18433344e-01 -8.13643932e-02 5.71723461e-01 8.16407502e-01 -8.13644454e-02 5.74566066e-01 8.14409375e-01 -8.13639984e-02 5.77342331e-01 8.12440574e-01 -8.13639984e-02 5.80256104e-01 8.10362995e-01 -8.13639984e-02 5.83049953e-01 8.08349729e-01 -8.13640207e-02 5.85729301e-01 8.06407571e-01 -8.13641623e-02 5.88601112e-01 8.04318607e-01 -8.13645050e-02 5.91078758e-01 8.02498400e-01 -8.13645273e-02 5.94207585e-01 8.00185144e-01 -8.13644603e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.14654863e-01 6.94728911e-01 -8.13644752e-02 7.17075408e-01 6.92230225e-01 -8.13644677e-02 7.20008552e-01 6.89178467e-01 -8.13644752e-02 7.22273886e-01 6.86804414e-01 -8.13644677e-02 7.24312007e-01 6.84654295e-01 -8.13642442e-02 7.26723552e-01 6.82091832e-01 -8.13639984e-02 7.29090512e-01 6.79566860e-01 -8.13639984e-02 7.31404126e-01 6.77077532e-01 -8.13639984e-02 7.33705401e-01 6.74585104e-01 -8.13640803e-02 7.36051440e-01 6.72027171e-01 -8.13645720e-02 7.38371968e-01 6.69478416e-01 -8.13646987e-02 7.40771353e-01 6.66825712e-01 -8.13650489e-02 7.43167460e-01 6.64150298e-01 -8.13650265e-02 7.45383859e-01 6.61663115e-01 -8.13648403e-02 7.47600317e-01 6.59158170e-01 -8.13649669e-02 7.49895155e-01 6.56540632e-01 -8.13644603e-02 7.52215087e-01 6.53881311e-01 -8.13640729e-02 7.54557729e-01 6.51178062e-01 -8.13639984e-02 7.56839931e-01 6.48519218e-01 -8.13639984e-02 7.59045303e-01 6.45936668e-01 -8.13639984e-02 7.61300445e-01 6.43281221e-01 -8.13640431e-02 7.63608813e-01 6.40539467e-01 -8.13644826e-02 7.65819013e-01 6.37897134e-01 -8.13645199e-02 7.67975152e-01 6.35299385e-01 -8.13647285e-02 7.70255744e-01 6.32539630e-01 -8.13649669e-02 7.72494912e-01 6.29797518e-01 -8.13648254e-02 7.74676144e-01 6.27112031e-01 -8.13646913e-02 7.76801527e-01 6.24475718e-01 -8.13645497e-02 7.78921962e-01 6.21832371e-01 -8.13646242e-02 7.81088054e-01 6.19105101e-01 -8.13645571e-02 7.83324480e-01 6.16277814e-01 -8.13649446e-02 7.85542428e-01 6.13447368e-01 -8.13650042e-02 7.87659645e-01 6.10727429e-01 -8.13650116e-02 7.89734423e-01 6.08042181e-01 -8.13649669e-02 7.91804552e-01 6.05346084e-01 -8.13651457e-02 7.93919563e-01 6.02569222e-01 -8.13651532e-02 7.96055317e-01 5.99747777e-01 -8.13652873e-02 7.98197448e-01 5.96888304e-01 -8.13651457e-02 8.00229609e-01 5.94160855e-01 -8.13650340e-02 8.02239776e-01 5.91444254e-01 -8.13651308e-02 8.04301322e-01 5.88636160e-01 -8.13651457e-02 8.06409597e-01 5.85748255e-01 -8.13652873e-02 8.08451593e-01 5.82922876e-01 -8.13650340e-02 8.10413003e-01 5.80197453e-01 -8.13651532e-02 8.12490165e-01 5.77285469e-01 -8.13652724e-02 8.14508379e-01 5.74435055e-01 -8.13650563e-02 8.16518068e-01 5.71572721e-01 -8.13653842e-02 8.18499625e-01 5.68728805e-01 -8.13649669e-02 8.20417106e-01 5.65963805e-01 -8.13651532e-02 8.22444260e-01 5.63016176e-01 -8.13653320e-02 8.24457645e-01 5.60059011e-01 -8.13651606e-02 8.26407433e-01 5.57178795e-01 -8.13651755e-02 8.28307569e-01 5.54347217e-01 -8.13650191e-02 8.30166042e-01 5.51561236e-01 -8.13651457e-02 8.32085013e-01 5.48664331e-01 -8.13651681e-02 8.34046721e-01 5.45676649e-01 -8.13652799e-02 8.36023867e-01 5.42642057e-01 -8.13651010e-02 8.37856114e-01 5.39806008e-01 -8.13650191e-02 8.39660764e-01 5.36997139e-01 -8.13651308e-02 8.41525972e-01 5.34068882e-01 -8.13651457e-02 8.43399942e-01 5.31109810e-01 -8.13651681e-02 8.45312715e-01 5.28055966e-01 -8.13653618e-02 8.47211897e-01 5.25005102e-01 -8.13651159e-02 8.48982751e-01 5.22131920e-01 -8.13650340e-02 8.50751936e-01 5.19252181e-01 -8.13651681e-02 8.52542043e-01 5.16302586e-01 -8.13651457e-02 8.54341149e-01 5.13320625e-01 -8.13651681e-02 8.56127560e-01 5.10335922e-01 -8.13651830e-02 8.57920587e-01 5.07317603e-01 -8.13652202e-02 8.59687805e-01 5.04316628e-01 -8.13650936e-02 8.61425519e-01 5.01342297e-01 -8.13652128e-02 8.63218009e-01 4.98250455e-01 -8.13652873e-02 8.64958584e-01 4.95220542e-01 -8.13650340e-02 8.66625726e-01 4.92297679e-01 -8.13652501e-02 8.68412435e-01 4.89144057e-01 -8.13653469e-02 8.70167255e-01 4.86008853e-01 -8.13651830e-02 8.71850550e-01 4.82980371e-01 -8.13650936e-02 8.73476684e-01 4.80037630e-01 -8.13650489e-02 8.75115156e-01 4.77046579e-01 -8.13651457e-02 8.76780689e-01 4.73974764e-01 -8.13651681e-02 8.78427684e-01 4.70916241e-01 -8.13651159e-02 8.80103946e-01 4.67777401e-01 -8.13652724e-02 8.81777108e-01 4.64615911e-01 -8.13651159e-02 8.83360326e-01 4.61596608e-01 -8.13649967e-02 8.84909451e-01 4.58617806e-01 -8.13651159e-02 8.86517048e-01 4.55506206e-01 -8.13652053e-02 8.88153553e-01 4.52304482e-01 -8.13652202e-02 8.89752924e-01 4.49150920e-01 -8.13651532e-02 8.91280949e-01 4.46109474e-01 -8.13650191e-02 8.92786443e-01 4.43091631e-01 -8.13651681e-02 8.94315064e-01 4.39997882e-01 -8.13651383e-02 8.95889759e-01 4.36785668e-01 -8.13652202e-02 8.97414684e-01 4.33644354e-01 -8.13650265e-02 8.98875237e-01 4.30601060e-01 -8.13651681e-02 9.00403917e-01 4.27395791e-01 -8.13651681e-02 9.01902139e-01 4.24225420e-01 -8.13650265e-02 9.03370321e-01 4.21094686e-01 -8.13652426e-02 9.04846251e-01 4.17908996e-01 -8.13650340e-02 9.06253457e-01 4.14849043e-01 -8.13651159e-02 9.07729149e-01 4.11611199e-01 -8.13652501e-02 9.09201860e-01 4.08350587e-01 -8.13651159e-02 9.10627723e-01 4.05160904e-01 -8.13651383e-02 9.12006974e-01 4.02041376e-01 -8.13650638e-02 9.13368344e-01 3.98945868e-01 -8.13651383e-02 9.14744735e-01 3.95774961e-01 -8.13651532e-02 9.16128099e-01 3.92556816e-01 -8.13651457e-02 9.17524159e-01 3.89288813e-01 -8.13652873e-02 9.18880999e-01 3.86073679e-01 -8.13650489e-02 9.20179665e-01 3.82971674e-01 -8.13651681e-02 9.21508074e-01 3.79759490e-01 -8.13651606e-02 9.22835946e-01 3.76525134e-01 -8.13651532e-02 9.24173772e-01 3.73229891e-01 -8.13652724e-02 9.25508618e-01 3.69907558e-01 -8.13651457e-02 9.26763117e-01 3.66753966e-01 -8.13650265e-02 9.27998304e-01 3.63621473e-01 -8.13652128e-02 9.29260314e-01 3.60363811e-01 -8.13651755e-02 9.30553734e-01 3.57033879e-01 -8.13653246e-02 9.31795061e-01 3.53758305e-01 -8.13650936e-02 9.32991564e-01 3.50581437e-01 -8.13651532e-02 9.34234023e-01 3.47256929e-01 -8.13652575e-02 9.35472667e-01 3.43915701e-01 -8.13651457e-02 9.36670601e-01 3.40663433e-01 -8.13651755e-02 9.37820137e-01 3.37467462e-01 -8.13650861e-02 9.38956439e-01 3.34305704e-01 -8.13651532e-02 9.40152884e-01 3.30924422e-01 -8.13653320e-02 9.41340923e-01 3.27526778e-01 -8.13651830e-02 9.42484915e-01 3.24226499e-01 -8.13651532e-02 9.43577051e-01 3.21025759e-01 -8.13650563e-02 9.44652021e-01 3.17855030e-01 -8.13651681e-02 9.45761561e-01 3.14536601e-01 -8.13651830e-02 9.46861506e-01 3.11208099e-01 -8.13651755e-02 9.47955668e-01 3.07865351e-01 -8.13653320e-02 9.49065149e-01 3.04421663e-01 -8.13651979e-02 9.50092018e-01 3.01201135e-01 -8.13651010e-02 9.51112390e-01 2.97966957e-01 -8.13651830e-02 9.52142894e-01 2.94652194e-01 -8.13651457e-02 9.53186214e-01 2.91262686e-01 -8.13653842e-02 9.54224646e-01 2.87836969e-01 -8.13651830e-02 9.55201924e-01 2.84581751e-01 -8.13651234e-02 9.56167459e-01 2.81324118e-01 -8.13651904e-02 9.57140744e-01 2.77990788e-01 -8.13651606e-02 9.58113372e-01 2.74618834e-01 -8.13652426e-02 9.59074378e-01 2.71248370e-01 -8.13651085e-02 9.59998071e-01 2.67960370e-01 -8.13651606e-02 9.60925519e-01 2.64612406e-01 -8.13651904e-02 9.61845458e-01 2.61258364e-01 -8.13651606e-02 9.62760568e-01 2.57852703e-01 -8.13653097e-02 9.63670015e-01 2.54434884e-01 -8.13650861e-02 9.64527607e-01 2.51169056e-01 -8.13651532e-02 9.65396762e-01 2.47805312e-01 -8.13652053e-02 9.66279209e-01 2.44333550e-01 -8.13653618e-02 9.67135012e-01 2.40925297e-01 -8.13651159e-02 9.67973650e-01 2.37543672e-01 -8.13651532e-02 9.68775809e-01 2.34252453e-01 -8.13651234e-02 9.69569921e-01 2.30941817e-01 -8.13651830e-02 9.70367432e-01 2.27566212e-01 -8.13651755e-02 9.71178055e-01 2.24078804e-01 -8.13653842e-02 9.71957684e-01 2.20666230e-01 -8.13650340e-02 9.72706020e-01 2.17355981e-01 -8.13651681e-02 9.73458529e-01 2.13948935e-01 -8.13651606e-02 9.74207401e-01 2.10515410e-01 -8.13652202e-02 9.74930584e-01 2.07140923e-01 -8.13651457e-02 9.75654900e-01 2.03709781e-01 -8.13653320e-02 9.76365209e-01 2.00272888e-01 -8.13650861e-02 9.77051556e-01 1.96899638e-01 -8.13653320e-02 9.77750182e-01 1.93395525e-01 -8.13651904e-02 9.78423357e-01 1.89965770e-01 -8.13652277e-02 9.79060471e-01 1.86641484e-01 -8.13650787e-02 9.79690969e-01 1.83310598e-01 -8.13651681e-02 9.80337679e-01 1.79815367e-01 -8.13653618e-02 9.80979145e-01 1.76314145e-01 -8.13651755e-02 9.81588185e-01 1.72892541e-01 -8.13652501e-02 9.82169628e-01 1.69522539e-01 -8.13651383e-02 9.82744217e-01 1.66178361e-01 -8.13652053e-02 9.83314455e-01 1.62753910e-01 -8.13652128e-02 9.83877897e-01 1.59317166e-01 -8.13651979e-02 9.84439015e-01 1.55815691e-01 -8.13653767e-02 9.84989762e-01 1.52287871e-01 -8.13651830e-02 9.85504508e-01 1.48911655e-01 -8.13650712e-02 9.86000240e-01 1.45605549e-01 -8.13652128e-02 9.86505628e-01 1.42134845e-01 -8.13652501e-02 9.87008452e-01 1.38614342e-01 -8.13653842e-02 9.87498164e-01 1.35081783e-01 -8.13651681e-02 9.87948239e-01 1.31725296e-01 -8.13650340e-02 9.88395751e-01 1.28343016e-01 -8.13652053e-02 9.88835037e-01 1.24917522e-01 -8.13651830e-02 9.89263952e-01 1.21468708e-01 -8.13652053e-02 9.89683688e-01 1.17996477e-01 -8.13652501e-02 9.90089536e-01 1.14538573e-01 -8.13652724e-02 9.90494132e-01 1.10994212e-01 -8.13654810e-02 9.90874052e-01 1.07544228e-01 -8.13651383e-02 9.91242230e-01 1.04096726e-01 -8.13654512e-02 9.91599917e-01 1.00618042e-01 -8.13651457e-02 9.91936862e-01 9.72493887e-02 -8.13652426e-02 9.92281675e-01 9.37036797e-02 -8.13653693e-02 9.92608726e-01 9.01434645e-02 -8.13652128e-02 9.92915928e-01 8.66994262e-02 -8.13651904e-02 9.93205070e-01 8.33092704e-02 -8.13651234e-02 9.93485391e-01 7.99065679e-02 -8.13651979e-02 9.93755519e-01 7.64507726e-02 -8.13652053e-02 9.94024396e-01 7.28867278e-02 -8.13653842e-02 9.94275808e-01 6.93464056e-02 -8.13652202e-02 9.94505763e-01 6.59789890e-02 -8.13650936e-02 9.94724274e-01 6.26071841e-02 -8.13652277e-02 9.94938672e-01 5.90926781e-02 -8.13652202e-02 9.95140731e-01 5.56326844e-02 -8.13652277e-02 9.95330989e-01 5.20835444e-02 -8.13654959e-02 9.95513499e-01 4.84957881e-02 -8.13652277e-02 9.95669842e-01 4.51252162e-02 -8.13650936e-02 9.95818377e-01 4.17591818e-02 -8.13652351e-02 9.95957911e-01 3.82779203e-02 -8.13652351e-02 9.96089399e-01 3.46772783e-02 -8.13655108e-02 9.96205091e-01 3.11869346e-02 -8.13651457e-02 9.96306658e-01 2.78321635e-02 -8.13652277e-02 9.96398389e-01 2.43489929e-02 -8.13653022e-02 9.96472180e-01 2.08496470e-02 -8.13652501e-02 9.96547341e-01 1.73767470e-02 -8.13652277e-02 9.96591210e-01 1.39003433e-02 -8.13652351e-02 9.96640027e-01 1.04224170e-02 -8.13652128e-02 9.96679068e-01 6.84378808e-03 -8.13655257e-02 9.96692717e-01 3.26191541e-03 -8.13652202e-02 9.96694148e-01 -2.14277723e-04 -8.13652873e-02 9.96692538e-01 -3.70547781e-03 -8.13652501e-02 9.96673346e-01 -7.07441242e-03 -8.13651010e-02 9.96640384e-01 -1.04387561e-02 -8.13652948e-02 9.96590555e-01 -1.39312334e-02 -8.13652277e-02 9.96545732e-01 -1.75177138e-02 -8.13655108e-02 9.96466994e-01 -2.11134031e-02 -8.13652351e-02 9.96392131e-01 -2.45607365e-02 -8.13652053e-02 9.96302724e-01 -2.79364455e-02 -8.13651159e-02 9.96198118e-01 -3.14271413e-02 -8.13655332e-02 9.96082366e-01 -3.49292010e-02 -8.13651457e-02 9.95956957e-01 -3.83104645e-02 -8.13653171e-02 9.95819330e-01 -4.17798236e-02 -8.13652202e-02 9.95661855e-01 -4.53353338e-02 -8.13655257e-02 9.95493412e-01 -4.89112660e-02 -8.13652351e-02 9.95313764e-01 -5.23854382e-02 -8.13652501e-02 9.95130420e-01 -5.57815731e-02 -8.13651457e-02 9.94936168e-01 -5.91503978e-02 -8.13652575e-02 9.94722009e-01 -6.26122281e-02 -8.13652501e-02 9.94493961e-01 -6.61740229e-02 -8.13654885e-02 9.94248867e-01 -6.97491169e-02 -8.13653022e-02 9.93999779e-01 -7.32466429e-02 -8.13652351e-02 9.93742585e-01 -7.66250119e-02 -8.13650936e-02 9.93478656e-01 -7.99861103e-02 -8.13652202e-02 9.93193805e-01 -8.34496692e-02 -8.13652501e-02 9.92890000e-01 -8.70053917e-02 -8.13654438e-02 9.92573440e-01 -9.05126855e-02 -8.13650563e-02 9.92265940e-01 -9.38382223e-02 -8.13652351e-02 9.91933048e-01 -9.73077863e-02 -8.13651979e-02 9.91584361e-01 -1.00786202e-01 -8.13652724e-02 9.91226196e-01 -1.04254059e-01 -8.13652053e-02 9.90850151e-01 -1.07764736e-01 -8.13654140e-02 9.90467668e-01 -1.11235619e-01 -8.13651457e-02 9.90083754e-01 -1.14592075e-01 -8.13652128e-02 9.89670157e-01 -1.18112616e-01 -8.13653842e-02 9.89249647e-01 -1.21586785e-01 -8.13651010e-02 9.88820076e-01 -1.25047252e-01 -8.13655332e-02 9.88362610e-01 -1.28584221e-01 -8.13651606e-02 9.87922430e-01 -1.31931782e-01 -8.13651532e-02 9.87455726e-01 -1.35392144e-01 -8.13654587e-02 9.86965001e-01 -1.38923451e-01 -8.13651904e-02 9.86482799e-01 -1.42294914e-01 -8.13651383e-02 9.85982060e-01 -1.45726144e-01 -8.13654959e-02 9.85462904e-01 -1.49186268e-01 -8.13651532e-02 9.84940767e-01 -1.52612060e-01 -8.13653842e-02 9.84401166e-01 -1.56048074e-01 -8.13651234e-02 9.83850479e-01 -1.59490198e-01 -8.13653842e-02 9.83289301e-01 -1.62910700e-01 -8.13651159e-02 9.82716024e-01 -1.66341379e-01 -8.13653842e-02 9.82112288e-01 -1.69853449e-01 -8.13652277e-02 9.81515944e-01 -1.73295259e-01 -8.13652053e-02 9.80920672e-01 -1.76630750e-01 -8.13651457e-02 9.80307698e-01 -1.79969624e-01 -8.13652277e-02 9.79677141e-01 -1.83387339e-01 -8.13652053e-02 9.79012132e-01 -1.86896160e-01 -8.13654214e-02 9.78342235e-01 -1.90382257e-01 -8.13651830e-02 9.77671921e-01 -1.93787843e-01 -8.13652351e-02 9.77004766e-01 -1.97125658e-01 -8.13651383e-02 9.76326168e-01 -2.00462177e-01 -8.13652053e-02 9.75618899e-01 -2.03871891e-01 -8.13652202e-02 9.74883080e-01 -2.07368836e-01 -8.13654959e-02 9.74161088e-01 -2.10738257e-01 -8.13651234e-02 9.73416090e-01 -2.14147121e-01 -8.13654810e-02 9.72661078e-01 -2.17552900e-01 -8.13651457e-02 9.71900523e-01 -2.20927224e-01 -8.13653842e-02 9.71122384e-01 -2.24321201e-01 -8.13651532e-02 9.70330954e-01 -2.27729365e-01 -8.13654661e-02 9.69528139e-01 -2.31119931e-01 -8.13651383e-02 9.68744934e-01 -2.34384581e-01 -8.13652351e-02 9.67895329e-01 -2.37860501e-01 -8.13653991e-02 9.67057645e-01 -2.41236776e-01 -8.13651159e-02 9.66208816e-01 -2.44614825e-01 -8.13655257e-02 9.65330005e-01 -2.48063549e-01 -8.13651755e-02 9.64486599e-01 -2.51321614e-01 -8.13651606e-02 9.63600993e-01 -2.54706353e-01 -8.13654885e-02 9.62700129e-01 -2.58085698e-01 -8.13651457e-02 9.61825728e-01 -2.61325151e-01 -8.13652351e-02 9.60875928e-01 -2.64788061e-01 -8.13655034e-02 9.59943891e-01 -2.68156976e-01 -8.13651234e-02 9.59010065e-01 -2.71475852e-01 -8.13654959e-02 9.58023131e-01 -2.74937898e-01 -8.13652724e-02 9.57080603e-01 -2.78196692e-01 -8.13651159e-02 9.56137836e-01 -2.81420112e-01 -8.13652202e-02 9.55128849e-01 -2.84834146e-01 -8.13654810e-02 9.54096377e-01 -2.88263202e-01 -8.13652575e-02 9.53072846e-01 -2.91637003e-01 -8.13652799e-02 9.52074945e-01 -2.94876933e-01 -8.13651159e-02 9.51077044e-01 -2.98078060e-01 -8.13652128e-02 9.50032115e-01 -3.01396310e-01 -8.13652501e-02 9.48949754e-01 -3.04784894e-01 -8.13654512e-02 9.47851241e-01 -3.08181822e-01 -8.13652351e-02 9.46771145e-01 -3.11483711e-01 -8.13652575e-02 9.45696592e-01 -3.14731449e-01 -8.13651681e-02 9.44624722e-01 -3.17934662e-01 -8.13652202e-02 9.43510056e-01 -3.21228951e-01 -8.13652873e-02 9.42361951e-01 -3.24580520e-01 -8.13653842e-02 9.41216052e-01 -3.27882975e-01 -8.13651159e-02 9.40067530e-01 -3.31168741e-01 -8.13653618e-02 9.38910842e-01 -3.34432721e-01 -8.13650936e-02 9.37740862e-01 -3.37701172e-01 -8.13655108e-02 9.36543465e-01 -3.41010183e-01 -8.13651383e-02 9.35350657e-01 -3.44250888e-01 -8.13653618e-02 9.34136271e-01 -3.47516358e-01 -8.13651457e-02 9.32952166e-01 -3.50688457e-01 -8.13652277e-02 9.31724846e-01 -3.53948295e-01 -8.13651979e-02 9.30453837e-01 -3.57300192e-01 -8.13654065e-02 9.29184496e-01 -3.60560685e-01 -8.13651383e-02 9.27930474e-01 -3.63794476e-01 -8.13654587e-02 9.26652133e-01 -3.67034137e-01 -8.13651159e-02 9.25376594e-01 -3.70237917e-01 -8.13653842e-02 9.24069822e-01 -3.73485088e-01 -8.13651159e-02 9.22802448e-01 -3.76606762e-01 -8.13651979e-02 9.21449840e-01 -3.79903078e-01 -8.13655108e-02 9.20111418e-01 -3.83133382e-01 -8.13651159e-02 9.18767571e-01 -3.86345565e-01 -8.13655183e-02 9.17370021e-01 -3.89647901e-01 -8.13652128e-02 9.16041017e-01 -3.92761081e-01 -8.13651308e-02 9.14706409e-01 -3.95864189e-01 -8.13652202e-02 9.13293242e-01 -3.99119526e-01 -8.13653842e-02 9.11854506e-01 -4.02393073e-01 -8.13652128e-02 9.10442412e-01 -4.05577153e-01 -8.13652575e-02 9.09049392e-01 -4.08690661e-01 -8.13650638e-02 9.07651722e-01 -4.11780089e-01 -8.13651532e-02 9.06221569e-01 -4.14914191e-01 -8.13651979e-02 9.04728472e-01 -4.18164760e-01 -8.13653618e-02 9.03228223e-01 -4.21395838e-01 -8.13652202e-02 9.01747704e-01 -4.24554884e-01 -8.13652128e-02 9.00290191e-01 -4.27638590e-01 -8.13651383e-02 8.98829222e-01 -4.30696160e-01 -8.13652202e-02 8.97324324e-01 -4.33833599e-01 -8.13652575e-02 8.95750463e-01 -4.37073290e-01 -8.13653097e-02 8.94217730e-01 -4.40194428e-01 -8.13651755e-02 8.92684460e-01 -4.43297356e-01 -8.13653618e-02 8.91135275e-01 -4.46402103e-01 -8.13651457e-02 8.89620602e-01 -4.49416041e-01 -8.13652053e-02 8.88056219e-01 -4.52499568e-01 -8.13652277e-02 8.86420906e-01 -4.55695480e-01 -8.13655108e-02 8.84808958e-01 -4.58809614e-01 -8.13651159e-02 8.83261979e-01 -4.61787611e-01 -8.13652277e-02 8.81644249e-01 -4.64864850e-01 -8.13652202e-02 8.79956424e-01 -4.68056381e-01 -8.13655183e-02 8.78317118e-01 -4.71122682e-01 -8.13650861e-02 8.76688480e-01 -4.74149376e-01 -8.13655108e-02 8.75009120e-01 -4.77243751e-01 -8.13651159e-02 8.73396218e-01 -4.80185896e-01 -8.13652724e-02 8.71706843e-01 -4.83240962e-01 -8.13652351e-02 8.69969308e-01 -4.86365378e-01 -8.13653916e-02 8.68264735e-01 -4.89402354e-01 -8.13651383e-02 8.66566241e-01 -4.92402405e-01 -8.13653693e-02 8.64835382e-01 -4.95439857e-01 -8.13651383e-02 8.63101542e-01 -4.98452991e-01 -8.13654587e-02 8.61330628e-01 -5.01507103e-01 -8.13651830e-02 8.59614789e-01 -5.04440725e-01 -8.13652053e-02 8.57874513e-01 -5.07395089e-01 -8.13652053e-02 8.56104016e-01 -5.10373652e-01 -8.13652351e-02 8.54272783e-01 -5.13437331e-01 -8.13654959e-02 8.52413714e-01 -5.16513109e-01 -8.13652799e-02 8.50651264e-01 -5.19415915e-01 -8.13651308e-02 8.48884761e-01 -5.22293627e-01 -8.13652575e-02 8.47057462e-01 -5.25257766e-01 -8.13652351e-02 8.45182478e-01 -5.28267741e-01 -8.13655183e-02 8.43277931e-01 -5.31301022e-01 -8.13652053e-02 8.41424048e-01 -5.34230232e-01 -8.13651979e-02 8.39615107e-01 -5.37068009e-01 -8.13651457e-02 8.37733090e-01 -5.40001869e-01 -8.13654587e-02 8.35777879e-01 -5.43021500e-01 -8.13652128e-02 8.33879471e-01 -5.45930982e-01 -8.13652501e-02 8.31964016e-01 -5.48848212e-01 -8.13652128e-02 8.30096543e-01 -5.51663101e-01 -8.13651159e-02 8.28233302e-01 -5.54460347e-01 -8.13652277e-02 8.26285243e-01 -5.57363212e-01 -8.13652724e-02 8.24279964e-01 -5.60322106e-01 -8.13653320e-02 8.22276711e-01 -5.63257754e-01 -8.13652202e-02 8.20302844e-01 -5.66131055e-01 -8.13651904e-02 8.18363369e-01 -5.68926513e-01 -8.13651383e-02 8.16380680e-01 -5.71767330e-01 -8.13653842e-02 8.14388096e-01 -5.74606657e-01 -8.13651457e-02 8.12375486e-01 -5.77447474e-01 -8.13653842e-02 8.10343921e-01 -5.80295146e-01 -8.13651383e-02 8.08359444e-01 -5.83050966e-01 -8.13652426e-02 8.06311965e-01 -5.85884273e-01 -8.13652351e-02 8.04262638e-01 -5.88690698e-01 -8.13651830e-02 8.02161634e-01 -5.91552496e-01 -8.13653842e-02 8.00033748e-01 -5.94427109e-01 -8.13652053e-02 7.98018575e-01 -5.97126424e-01 -8.13650861e-02 7.95941830e-01 -5.99896848e-01 -8.13655034e-02 7.93820143e-01 -6.02700591e-01 -8.13651383e-02 7.91735947e-01 -6.05434775e-01 -8.13653320e-02 7.89623916e-01 -6.08185470e-01 -8.13651383e-02 7.87533641e-01 -6.10891044e-01 -8.13652277e-02 7.85349131e-01 -6.13696873e-01 -8.13652501e-02 7.83146739e-01 -6.16506696e-01 -8.13652724e-02 7.81028032e-01 -6.19186223e-01 -8.13650638e-02 7.78911650e-01 -6.21848226e-01 -8.13652128e-02 7.76755154e-01 -6.24540567e-01 -8.13652277e-02 7.74512768e-01 -6.27320468e-01 -8.13654959e-02 7.72300720e-01 -6.30036533e-01 -8.13651383e-02 7.70166397e-01 -6.32646322e-01 -8.13652426e-02 7.67952621e-01 -6.35332823e-01 -8.13651830e-02 7.65745461e-01 -6.37990296e-01 -8.13652128e-02 7.63504267e-01 -6.40672266e-01 -8.13652202e-02 7.61195481e-01 -6.43411994e-01 -8.13654065e-02 7.58937657e-01 -6.46071911e-01 -8.13650936e-02 7.56761312e-01 -6.48620248e-01 -8.13652277e-02 7.54484415e-01 -6.51269197e-01 -8.13652202e-02 7.52171516e-01 -6.53939962e-01 -8.13652650e-02 7.49833524e-01 -6.56617761e-01 -8.13653097e-02 7.47503638e-01 -6.59269571e-01 -8.13652426e-02 7.45240390e-01 -6.61825061e-01 -8.13651010e-02 7.42982924e-01 -6.64360583e-01 -8.13652053e-02 7.40618885e-01 -6.66996837e-01 -8.13653618e-02 7.38290668e-01 -6.69572055e-01 -8.13651308e-02 7.35939443e-01 -6.72154129e-01 -8.13653842e-02 7.33590662e-01 -6.74717188e-01 -8.13651159e-02 7.31299400e-01 -6.77199483e-01 -8.13652053e-02 7.28925824e-01 -6.79752171e-01 -8.13652128e-02 7.26488054e-01 -6.82357490e-01 -8.13653842e-02 7.24097192e-01 -6.84892356e-01 -8.13651159e-02 7.21714735e-01 -6.87409818e-01 -8.13654065e-02 7.19301045e-01 -6.89923465e-01 -8.13651010e-02 7.16911077e-01 -6.92423761e-01 -8.13655108e-02 7.14473367e-01 -6.94933593e-01 -8.13651159e-02 7.12105393e-01 -6.97357655e-01 -8.13652202e-02 7.09620535e-01 -6.99888408e-01 -8.13653842e-02 7.07167387e-01 -7.02367544e-01 -8.13649669e-02 7.04710007e-01 -7.04815984e-01 -8.13649595e-02 7.02167332e-01 -7.07360148e-01 -8.13646391e-02 6.99774802e-01 -7.09726572e-01 -8.13642219e-02 6.97357178e-01 -7.12099731e-01 -8.13642591e-02 6.94878817e-01 -7.14517772e-01 -8.13639984e-02 6.92311168e-01 -7.16998279e-01 -8.13639984e-02 6.89767599e-01 -7.19444394e-01 -8.13639984e-02 6.87277734e-01 -7.21819699e-01 -8.13639984e-02 6.84792459e-01 -7.24178493e-01 -8.13641623e-02 6.82463288e-01 -7.26378262e-01 -8.13643560e-02 6.80070937e-01 -7.28615701e-01 -8.13645273e-02 6.77487671e-01 -7.31019616e-01 -8.13644752e-02 6.75058424e-01 -7.33263850e-01 -8.13644677e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.50445497e-01 -8.30896914e-01 -8.13644752e-02 5.48074603e-01 -8.32462490e-01 -8.13645050e-02 5.45289397e-01 -8.34289134e-01 -8.13645497e-02 5.42542100e-01 -8.36075962e-01 -8.13641623e-02 5.39703786e-01 -8.37909043e-01 -8.13641101e-02 5.36954105e-01 -8.39673579e-01 -8.13640654e-02 5.33882558e-01 -8.41628432e-01 -8.13641027e-02 5.30940115e-01 -8.43487561e-01 -8.13640431e-02 5.28064609e-01 -8.45298767e-01 -8.13639984e-02 5.25099099e-01 -8.47135842e-01 -8.13639984e-02 5.22492766e-01 -8.48753750e-01 -8.13642293e-02 5.19576013e-01 -8.50541115e-01 -8.13644454e-02 5.16199589e-01 -8.52594197e-01 -8.13644901e-02 5.13153970e-01 -8.54430914e-01 -8.13644603e-02 5.09958923e-01 -8.56341541e-01 -8.13644603e-02 5.07153809e-01 -8.58005941e-01 -8.13644677e-02 5.03730536e-01 -8.60020101e-01 -8.13644752e-02 5.00731647e-01 -8.61769736e-01 -8.13644677e-02 4.98161316e-01 -8.63258183e-01 -8.13644677e-02 4.94937897e-01 -8.65110219e-01 -8.13644677e-02 4.91781622e-01 -8.66908610e-01 -8.13644901e-02 4.88912344e-01 -8.68529916e-01 -8.13644901e-02 4.85870868e-01 -8.70234966e-01 -8.13644826e-02 4.82662469e-01 -8.72017682e-01 -8.13645273e-02 4.79908139e-01 -8.73534739e-01 -8.13641623e-02 4.76994008e-01 -8.75133514e-01 -8.13639984e-02 4.73992258e-01 -8.76767099e-01 -8.13643187e-02 4.70949411e-01 -8.78406703e-01 -8.13646615e-02 4.67891157e-01 -8.80042076e-01 -8.13649446e-02 4.64791447e-01 -8.81684601e-01 -8.13650861e-02 4.61680830e-01 -8.83317053e-01 -8.13652575e-02 4.58600700e-01 -8.84918511e-01 -8.13651159e-02 4.55573887e-01 -8.86483192e-01 -8.13652351e-02 4.52470034e-01 -8.88069630e-01 -8.13652128e-02 4.49366629e-01 -8.89645159e-01 -8.13652277e-02 4.46269780e-01 -8.91202331e-01 -8.13652501e-02 4.43163365e-01 -8.92750442e-01 -8.13652202e-02 4.40062404e-01 -8.94283533e-01 -8.13652724e-02 4.36926335e-01 -8.95821154e-01 -8.13652501e-02 4.33799177e-01 -8.97339702e-01 -8.13652501e-02 4.30644870e-01 -8.98855269e-01 -8.13652501e-02 4.27429140e-01 -9.00390327e-01 -8.13653320e-02 4.24281478e-01 -9.01876271e-01 -8.13651532e-02 4.21111971e-01 -9.03362632e-01 -8.13654959e-02 4.17938888e-01 -9.04833257e-01 -8.13651010e-02 4.14883733e-01 -9.06237006e-01 -8.13652128e-02 4.11725998e-01 -9.07678783e-01 -8.13652277e-02 4.08553600e-01 -9.09110665e-01 -8.13652202e-02 4.05269742e-01 -9.10581052e-01 -8.13655332e-02 4.02065694e-01 -9.11997914e-01 -8.13650414e-02 3.98996770e-01 -9.13346648e-01 -8.13652724e-02 3.95810902e-01 -9.14730132e-01 -8.13652351e-02 3.92605036e-01 -9.16107774e-01 -8.13652351e-02 3.89345169e-01 -9.17500973e-01 -8.13653618e-02 3.86164606e-01 -9.18844283e-01 -8.13651532e-02 3.82891297e-01 -9.20213163e-01 -8.13655406e-02 3.79655242e-01 -9.21550870e-01 -8.13651159e-02 3.76559526e-01 -9.22822773e-01 -8.13652575e-02 3.73289049e-01 -9.24150109e-01 -8.13653842e-02 3.69968176e-01 -9.25484538e-01 -8.13653544e-02 3.66684407e-01 -9.26791489e-01 -8.13652277e-02 3.63527745e-01 -9.28033590e-01 -8.13651457e-02 3.60380918e-01 -9.29254055e-01 -8.13652351e-02 3.57129127e-01 -9.30518150e-01 -8.13652724e-02 3.53881091e-01 -9.31751072e-01 -8.13652277e-02 3.50645810e-01 -9.32968915e-01 -8.13652501e-02 3.47362757e-01 -9.34195220e-01 -8.13652575e-02 3.44101667e-01 -9.35404658e-01 -8.13651979e-02 3.40844959e-01 -9.36603248e-01 -8.13652202e-02 3.37589145e-01 -9.37778711e-01 -8.13652277e-02 3.34302813e-01 -9.38957453e-01 -8.13652202e-02 3.30947429e-01 -9.40144062e-01 -8.13653842e-02 3.27646822e-01 -9.41298723e-01 -8.13651457e-02 3.24375153e-01 -9.42433119e-01 -8.13654363e-02 3.21061730e-01 -9.43565309e-01 -8.13651532e-02 3.17864507e-01 -9.44649696e-01 -8.13652202e-02 3.14471275e-01 -9.45782483e-01 -8.13654140e-02 3.11150968e-01 -9.46878076e-01 -8.13651457e-02 3.07851136e-01 -9.47958529e-01 -8.13654140e-02 3.04527849e-01 -9.49033022e-01 -8.13651457e-02 3.01305532e-01 -9.50059116e-01 -8.13652501e-02 2.98001021e-01 -9.51101840e-01 -8.13652351e-02 2.94674307e-01 -9.52137649e-01 -8.13652202e-02 2.91359305e-01 -9.53157485e-01 -8.13652277e-02 2.87942678e-01 -9.54192698e-01 -8.13653544e-02 2.84504712e-01 -9.55224574e-01 -8.13652202e-02 2.81276166e-01 -9.56182003e-01 -8.13651085e-02 2.77936250e-01 -9.57158625e-01 -8.13653842e-02 2.74498254e-01 -9.58148956e-01 -8.13652277e-02 2.71152318e-01 -9.59100664e-01 -8.13652501e-02 2.67903954e-01 -9.60014403e-01 -8.13651234e-02 2.64629424e-01 -9.60919976e-01 -8.13651904e-02 2.61280745e-01 -9.61838782e-01 -8.13652202e-02 2.57900327e-01 -9.62748289e-01 -8.13652724e-02 2.54563093e-01 -9.63636339e-01 -8.13652128e-02 2.51205474e-01 -9.64519501e-01 -8.13652277e-02 2.47759387e-01 -9.65408504e-01 -8.13653469e-02 2.44383320e-01 -9.66267049e-01 -8.13651383e-02 2.41023451e-01 -9.67111647e-01 -8.13653842e-02 2.37624094e-01 -9.67954040e-01 -8.13651606e-02 2.34318480e-01 -9.68760014e-01 -8.13652202e-02 2.30862781e-01 -9.69591260e-01 -8.13653693e-02 2.27484107e-01 -9.70386446e-01 -8.13651457e-02 2.24098623e-01 -9.71173823e-01 -8.13653842e-02 2.20614091e-01 -9.71970499e-01 -8.13652053e-02 2.17317119e-01 -9.72713470e-01 -8.13650936e-02 2.14013100e-01 -9.73444462e-01 -8.13652277e-02 2.10619450e-01 -9.74184930e-01 -8.13651979e-02 2.07218215e-01 -9.74913955e-01 -8.13652277e-02 2.03694955e-01 -9.75658774e-01 -8.13654959e-02 2.00281635e-01 -9.76363242e-01 -8.13650563e-02 1.96990341e-01 -9.77032840e-01 -8.13652053e-02 1.93580464e-01 -9.77713466e-01 -8.13652202e-02 1.90146089e-01 -9.78388309e-01 -8.13652128e-02 1.86641529e-01 -9.79062498e-01 -8.13654736e-02 1.83221623e-01 -9.79706764e-01 -8.13650340e-02 1.79797620e-01 -9.80341136e-01 -8.13653618e-02 1.76342875e-01 -9.80974317e-01 -8.13650489e-02 1.73028931e-01 -9.81564164e-01 -8.13652351e-02 1.69617340e-01 -9.82152820e-01 -8.13652351e-02 1.66159093e-01 -9.82746124e-01 -8.13652202e-02 1.62640646e-01 -9.83333886e-01 -8.13654438e-02 1.59207508e-01 -9.83895242e-01 -8.13651159e-02 1.55876890e-01 -9.84429657e-01 -8.13652202e-02 1.52437374e-01 -9.84967709e-01 -8.13652202e-02 1.48985073e-01 -9.85494137e-01 -8.13652351e-02 1.45470127e-01 -9.86020982e-01 -8.13653618e-02 1.42012879e-01 -9.86523926e-01 -8.13651383e-02 1.38568848e-01 -9.87015843e-01 -8.13654736e-02 1.35024235e-01 -9.87506747e-01 -8.13652351e-02 1.31661311e-01 -9.87957120e-01 -8.13651159e-02 1.28327355e-01 -9.88397539e-01 -8.13652202e-02 1.24874540e-01 -9.88841355e-01 -8.13651830e-02 1.21433049e-01 -9.89268482e-01 -8.13651979e-02 1.17890336e-01 -9.89697099e-01 -8.13654512e-02 1.14400230e-01 -9.90104556e-01 -8.13650861e-02 1.11065887e-01 -9.90485489e-01 -8.13652053e-02 1.07619844e-01 -9.90865231e-01 -8.13651830e-02 1.04162581e-01 -9.91235018e-01 -8.13652053e-02 1.00599691e-01 -9.91602302e-01 -8.13653097e-02 9.71198753e-02 -9.91950095e-01 -8.13651159e-02 9.36786085e-02 -9.92282927e-01 -8.13653842e-02 9.02049989e-02 -9.92601752e-01 -8.13650936e-02 8.67380500e-02 -9.92913008e-01 -8.13653842e-02 8.31722394e-02 -9.93216336e-01 -8.13652351e-02 7.97684938e-02 -9.93496418e-01 -8.13650861e-02 7.63247311e-02 -9.93768036e-01 -8.13654885e-02 7.28366375e-02 -9.94027793e-01 -8.13651383e-02 6.94731325e-02 -9.94267464e-01 -8.13652724e-02 6.60194680e-02 -9.94504154e-01 -8.13652351e-02 6.25417009e-02 -9.94728208e-01 -8.13652053e-02 5.89568652e-02 -9.94948268e-01 -8.13653991e-02 5.54922484e-02 -9.95147586e-01 -8.13651234e-02 5.20378090e-02 -9.95333493e-01 -8.13653618e-02 4.85528447e-02 -9.95510161e-01 -8.13651159e-02 4.50911894e-02 -9.95673120e-01 -8.13654959e-02 4.15032245e-02 -9.95829463e-01 -8.13652053e-02 3.81164961e-02 -9.95962858e-01 -8.13650638e-02 3.47455889e-02 -9.96086538e-01 -8.13651904e-02 3.11847385e-02 -9.96204793e-01 -8.13652873e-02 2.76933145e-02 -9.96308923e-01 -8.13651457e-02 2.42258795e-02 -9.96401489e-01 -8.13653693e-02 2.07328442e-02 -9.96474504e-01 -8.13651234e-02 1.73450429e-02 -9.96547222e-01 -8.13652202e-02 1.38083957e-02 -9.96591568e-01 -8.13654959e-02 1.03067905e-02 -9.96640325e-01 -8.13651159e-02 6.91425009e-03 -9.96676385e-01 -8.13652202e-02 3.43326014e-03 -9.96692598e-01 -8.13652128e-02 -3.15147881e-05 -9.96693730e-01 -8.13652053e-02 -3.48739256e-03 -9.96692657e-01 -8.13652501e-02 -6.97604660e-03 -9.96676028e-01 -8.13652277e-02 -1.05534662e-02 -9.96639729e-01 -8.13654438e-02 -1.40380478e-02 -9.96589303e-01 -8.13650712e-02 -1.75083000e-02 -9.96545851e-01 -8.13653842e-02 -2.10946500e-02 -9.96467769e-01 -8.13652650e-02 -2.44821515e-02 -9.96393681e-01 -8.13651159e-02 -2.78490484e-02 -9.96305406e-01 -8.13652351e-02 -3.13234106e-02 -9.96201515e-01 -8.13652501e-02 -3.48887928e-02 -9.96083260e-01 -8.13655183e-02 -3.84923853e-02 -9.95950758e-01 -8.13652351e-02 -4.18727510e-02 -9.95814145e-01 -8.13651085e-02 -4.52351123e-02 -9.95666087e-01 -8.13652351e-02 -4.87177819e-02 -9.95502651e-01 -8.13652351e-02 -5.21974675e-02 -9.95324016e-01 -8.13652053e-02 -5.57410121e-02 -9.95134413e-01 -8.13654512e-02 -5.92429005e-02 -9.94930744e-01 -8.13650936e-02 -6.26806840e-02 -9.94719923e-01 -8.13654587e-02 -6.61912709e-02 -9.94491398e-01 -8.13651383e-02 -6.95633590e-02 -9.94260550e-01 -8.13652202e-02 -7.31123388e-02 -9.94007826e-01 -8.13653693e-02 -7.66038373e-02 -9.93744075e-01 -8.13651010e-02 -8.00547823e-02 -9.93473649e-01 -8.13653842e-02 -8.35196152e-02 -9.93186474e-01 -8.13651457e-02 -8.69110897e-02 -9.92896795e-01 -8.13652351e-02 -9.03811455e-02 -9.92586195e-01 -8.13652277e-02 -9.38364714e-02 -9.92266774e-01 -8.13652575e-02 -9.73854363e-02 -9.91926193e-01 -8.13653916e-02 -1.00849196e-01 -9.91578460e-01 -8.13650861e-02 -1.04278177e-01 -9.91223693e-01 -8.13654438e-02 -1.07824869e-01 -9.90842938e-01 -8.13651979e-02 -1.11218236e-01 -9.90468979e-01 -8.13651383e-02 -1.14589319e-01 -9.90084171e-01 -8.13652351e-02 -1.18038453e-01 -9.89678025e-01 -8.13652501e-02 -1.21490106e-01 -9.89260197e-01 -8.13652501e-02 -1.25027165e-01 -9.88822937e-01 -8.13655183e-02 -1.28490254e-01 -9.88374710e-01 -8.13651159e-02 -1.31849363e-01 -9.87934351e-01 -8.13652351e-02 -1.35294244e-01 -9.87467766e-01 -8.13652501e-02 -1.38735324e-01 -9.86991704e-01 -8.13652351e-02 -1.42272919e-01 -9.86488044e-01 -8.13654959e-02 -1.45716712e-01 -9.85982418e-01 -8.13651308e-02 -1.49146959e-01 -9.85469759e-01 -8.13653842e-02 -1.52571112e-01 -9.84946072e-01 -8.13651383e-02 -1.55927971e-01 -9.84419703e-01 -8.13652128e-02 -1.59359291e-01 -9.83870983e-01 -8.13652277e-02 -1.62785843e-01 -9.83310878e-01 -8.13652501e-02 -1.66339487e-01 -9.82715845e-01 -8.13654885e-02 -1.69765040e-01 -9.82127130e-01 -8.13651383e-02 -1.73082724e-01 -9.81553972e-01 -8.13652277e-02 -1.76525041e-01 -9.80939150e-01 -8.13652501e-02 -1.79948434e-01 -9.80311930e-01 -8.13652128e-02 -1.83452368e-01 -9.79666829e-01 -8.13654363e-02 -1.86879277e-01 -9.79016542e-01 -8.13651457e-02 -1.90208077e-01 -9.78373647e-01 -8.13652053e-02 -1.93601996e-01 -9.77709770e-01 -8.13651979e-02 -1.97100863e-01 -9.77011383e-01 -8.13654810e-02 -2.00522110e-01 -9.76312816e-01 -8.13650936e-02 -2.03827947e-01 -9.75628555e-01 -8.13652053e-02 -2.07262099e-01 -9.74906027e-01 -8.13651904e-02 -2.10725769e-01 -9.74163234e-01 -8.13653842e-02 -2.14148685e-01 -9.73413169e-01 -8.13651085e-02 -2.17431948e-01 -9.72688854e-01 -8.13652426e-02 -2.20837250e-01 -9.71920133e-01 -8.13652724e-02 -2.24243805e-01 -9.71138239e-01 -8.13652501e-02 -2.27725431e-01 -9.70332801e-01 -8.13655034e-02 -2.31120661e-01 -9.69526947e-01 -8.13651159e-02 -2.34395713e-01 -9.68741119e-01 -8.13652053e-02 -2.37779066e-01 -9.67915297e-01 -8.13652277e-02 -2.41158724e-01 -9.67077255e-01 -8.13652277e-02 -2.44590402e-01 -9.66214776e-01 -8.13653842e-02 -2.47991934e-01 -9.65348423e-01 -8.13651457e-02 -2.51382291e-01 -9.64471102e-01 -8.13654885e-02 -2.54745036e-01 -9.63589370e-01 -8.13651234e-02 -2.58082539e-01 -9.62701142e-01 -8.13653618e-02 -2.61536628e-01 -9.61768866e-01 -8.13652724e-02 -2.64821768e-01 -9.60866690e-01 -8.13651085e-02 -2.68159986e-01 -9.59942698e-01 -8.13655108e-02 -2.71520823e-01 -9.58996236e-01 -8.13651159e-02 -2.74768770e-01 -9.58070755e-01 -8.13652277e-02 -2.78102577e-01 -9.57108974e-01 -8.13652575e-02 -2.81434923e-01 -9.56133842e-01 -8.13652277e-02 -2.84753501e-01 -9.55152094e-01 -8.13651830e-02 -2.88087606e-01 -9.54149246e-01 -8.13652724e-02 -2.91439116e-01 -9.53130126e-01 -8.13652575e-02 -2.94839650e-01 -9.52087343e-01 -8.13654959e-02 -2.98170090e-01 -9.51046944e-01 -8.13651159e-02 -3.01496297e-01 -9.49999750e-01 -8.13653842e-02 -3.04818809e-01 -9.48938847e-01 -8.13651383e-02 -3.08033705e-01 -9.47899282e-01 -8.13652277e-02 -3.11440974e-01 -9.46785569e-01 -8.13654289e-02 -3.14722180e-01 -9.45699215e-01 -8.13651457e-02 -3.18026096e-01 -9.44595933e-01 -8.13653842e-02 -3.21322113e-01 -9.43476975e-01 -8.13651457e-02 -3.24524403e-01 -9.42381322e-01 -8.13652128e-02 -3.27858031e-01 -9.41225410e-01 -8.13653842e-02 -3.31146538e-01 -9.40075815e-01 -8.13651606e-02 -3.34450722e-01 -9.38904345e-01 -8.13654363e-02 -3.37745577e-01 -9.37722147e-01 -8.13651308e-02 -3.40999663e-01 -9.36548471e-01 -8.13653842e-02 -3.44277918e-01 -9.35338438e-01 -8.13651159e-02 -3.47458601e-01 -9.34158504e-01 -8.13652053e-02 -3.50779861e-01 -9.32919264e-01 -8.13653842e-02 -3.54032815e-01 -9.31691527e-01 -8.13651085e-02 -3.57279539e-01 -9.30461526e-01 -8.13653842e-02 -3.60614121e-01 -9.29165602e-01 -8.13652351e-02 -3.63775373e-01 -9.27936196e-01 -8.13651159e-02 -3.66923928e-01 -9.26696301e-01 -8.13652351e-02 -3.70157212e-01 -9.25407410e-01 -8.13652053e-02 -3.73395115e-01 -9.24106538e-01 -8.13652053e-02 -3.76693785e-01 -9.22767103e-01 -8.13654959e-02 -3.79932016e-01 -9.21435177e-01 -8.13651159e-02 -3.83062840e-01 -9.20141935e-01 -8.13652053e-02 -3.86250287e-01 -9.18807805e-01 -8.13651979e-02 -3.89459461e-01 -9.17450905e-01 -8.13652501e-02 -3.92741472e-01 -9.16050375e-01 -8.13654810e-02 -3.95941496e-01 -9.14671361e-01 -8.13650936e-02 -3.99126977e-01 -9.13290322e-01 -8.13654140e-02 -4.02332276e-01 -9.11879778e-01 -8.13651159e-02 -4.05425847e-01 -9.10510004e-01 -8.13652351e-02 -4.08679038e-01 -9.09055471e-01 -8.13653842e-02 -4.11857545e-01 -9.07617211e-01 -8.13651010e-02 -4.14993554e-01 -9.06186044e-01 -8.13654736e-02 -4.18159753e-01 -9.04729605e-01 -8.13651010e-02 -4.21233565e-01 -9.03304577e-01 -8.13652351e-02 -4.24390763e-01 -9.01825190e-01 -8.13652351e-02 -4.27627534e-01 -9.00297284e-01 -8.13654661e-02 -4.30760860e-01 -8.98798287e-01 -8.13651383e-02 -4.33811694e-01 -8.97334754e-01 -8.13652724e-02 -4.37027544e-01 -8.95772576e-01 -8.13655108e-02 -4.40240830e-01 -8.94194841e-01 -8.13652053e-02 -4.43280429e-01 -8.92692447e-01 -8.13651532e-02 -4.46311355e-01 -8.91181707e-01 -8.13651904e-02 -4.49410856e-01 -8.89623344e-01 -8.13652575e-02 -4.52527851e-01 -8.88040543e-01 -8.13652053e-02 -4.55686718e-01 -8.86423528e-01 -8.13653618e-02 -4.58772570e-01 -8.84829044e-01 -8.13651010e-02 -4.61771935e-01 -8.83270204e-01 -8.13652128e-02 -4.64867085e-01 -8.81645322e-01 -8.13652053e-02 -4.67940003e-01 -8.80016148e-01 -8.13651830e-02 -4.71086442e-01 -8.78338158e-01 -8.13653767e-02 -4.74163264e-01 -8.76677811e-01 -8.13651159e-02 -4.77196962e-01 -8.75034630e-01 -8.13653320e-02 -4.80263650e-01 -8.73352349e-01 -8.13651308e-02 -4.83294249e-01 -8.71677577e-01 -8.13653320e-02 -4.86406505e-01 -8.69945168e-01 -8.13652128e-02 -4.89374042e-01 -8.68280947e-01 -8.13651532e-02 -4.92383510e-01 -8.66577804e-01 -8.13653842e-02 -4.95405734e-01 -8.64854336e-01 -8.13651532e-02 -4.98366684e-01 -8.63150477e-01 -8.13652501e-02 -5.01445949e-01 -8.61366868e-01 -8.13654959e-02 -5.04466236e-01 -8.59600723e-01 -8.13651234e-02 -5.07446766e-01 -8.57843459e-01 -8.13655108e-02 -5.10447264e-01 -8.56060147e-01 -8.13651383e-02 -5.13411343e-01 -8.54288101e-01 -8.13654438e-02 -5.16412318e-01 -8.52475107e-01 -8.13651234e-02 -5.19365489e-01 -8.50682855e-01 -8.13654214e-02 -5.22423387e-01 -8.48806620e-01 -8.13652501e-02 -5.25307000e-01 -8.47024918e-01 -8.13651234e-02 -5.28166473e-01 -8.45244706e-01 -8.13652053e-02 -5.31207681e-01 -8.43336821e-01 -8.13655183e-02 -5.34227073e-01 -8.41426611e-01 -8.13652724e-02 -5.37154853e-01 -8.39560926e-01 -8.13652277e-02 -5.40005624e-01 -8.37729156e-01 -8.13651457e-02 -5.42858541e-01 -8.35884571e-01 -8.13652277e-02 -5.45786560e-01 -8.33973110e-01 -8.13652277e-02 -5.48678815e-01 -8.32076550e-01 -8.13652128e-02 -5.51570952e-01 -8.30159187e-01 -8.13652128e-02 -5.54454029e-01 -8.28237832e-01 -8.13652202e-02 -5.57417214e-01 -8.26248765e-01 -8.13654959e-02 -5.60356915e-01 -8.24255228e-01 -8.13651755e-02 -5.63151538e-01 -8.22350085e-01 -8.13651830e-02 -5.66046834e-01 -8.20360065e-01 -8.13655034e-02 -5.68909764e-01 -8.18377733e-01 -8.13651457e-02 -5.71765542e-01 -8.16383243e-01 -8.13655183e-02 -5.74705005e-01 -8.14317584e-01 -8.13652202e-02 -5.77468097e-01 -8.12359631e-01 -8.13651159e-02 -5.80270290e-01 -8.10362160e-01 -8.13654438e-02 -5.83087444e-01 -8.08332622e-01 -8.13651532e-02 -5.85909843e-01 -8.06293726e-01 -8.13653842e-02 -5.88807762e-01 -8.04178596e-01 -8.13652501e-02 -5.91625094e-01 -8.02107692e-01 -8.13652426e-02 -5.94353318e-01 -8.00088048e-01 -8.13650861e-02 -5.97050548e-01 -7.98076987e-01 -8.13652501e-02 -5.99840045e-01 -7.95982778e-01 -8.13652202e-02 -6.02686584e-01 -7.93832421e-01 -8.13653916e-02 -6.05461895e-01 -7.91714609e-01 -8.13651159e-02 -6.08226240e-01 -7.89592803e-01 -8.13655332e-02 -6.10984325e-01 -7.87461281e-01 -8.13650787e-02 -6.13646567e-01 -7.85388887e-01 -8.13652501e-02 -6.16466582e-01 -7.83179402e-01 -8.13654587e-02 -6.19194686e-01 -7.81019688e-01 -8.13651383e-02 -6.21912241e-01 -7.78862000e-01 -8.13654959e-02 -6.24647498e-01 -7.76667476e-01 -8.13651532e-02 -6.27276778e-01 -7.74547398e-01 -8.13652053e-02 -6.30034685e-01 -7.72303700e-01 -8.13654140e-02 -6.32742047e-01 -7.70087540e-01 -8.13651234e-02 -6.35350525e-01 -7.67937243e-01 -8.13652351e-02 -6.38022840e-01 -7.65719473e-01 -8.13652351e-02 -6.40747011e-01 -7.63440549e-01 -8.13653097e-02 -6.43483579e-01 -7.61134267e-01 -8.13652724e-02 -6.46084964e-01 -7.58926153e-01 -8.13651532e-02 -6.48646712e-01 -7.56739557e-01 -8.13652202e-02 -6.51291609e-01 -7.54465520e-01 -8.13652277e-02 -6.53980136e-01 -7.52136707e-01 -8.13654959e-02 -6.56666696e-01 -7.49790788e-01 -8.13652575e-02 -6.59230471e-01 -7.47536719e-01 -8.13651383e-02 -6.61757827e-01 -7.45302022e-01 -8.13652128e-02 -6.64351702e-01 -7.42989242e-01 -8.13652202e-02 -6.66950583e-01 -7.40657747e-01 -8.13652128e-02 -6.69597447e-01 -7.38268256e-01 -8.13654959e-02 -6.72182739e-01 -7.35911071e-01 -8.13651383e-02 -6.74724042e-01 -7.33587980e-01 -8.13654140e-02 -6.77286804e-01 -7.31217384e-01 -8.13651159e-02 -6.79820001e-01 -7.28864551e-01 -8.13655332e-02 -6.82432592e-01 -7.26416945e-01 -8.13652128e-02 -6.84906960e-01 -7.24084377e-01 -8.13651532e-02 -6.87422216e-01 -7.21702218e-01 -8.13654810e-02 -6.89940393e-01 -7.19284773e-01 -8.13651383e-02 -6.92392230e-01 -7.16940820e-01 -8.13652873e-02 -6.94913030e-01 -7.14496195e-01 -8.13653842e-02 -6.97409511e-01 -7.12054908e-01 -8.13651755e-02 -6.99858487e-01 -7.09650993e-01 -8.13652799e-02 -7.02321827e-01 -7.07214296e-01 -8.13652575e-02 -7.04834044e-01 -7.04692364e-01 -8.13653842e-02 -7.07304835e-01 -7.02231586e-01 -8.13651681e-02 -7.09760487e-01 -6.99747384e-01 -8.13654363e-02 -7.12199092e-01 -6.97261691e-01 -8.13651532e-02 -7.14563489e-01 -6.94842696e-01 -8.13652724e-02 -7.17003584e-01 -6.92327321e-01 -8.13653618e-02 -7.19466925e-01 -6.89750791e-01 -8.13654289e-02 -7.21875370e-01 -6.87238872e-01 -8.13651532e-02 -7.24260151e-01 -6.84721887e-01 -8.13654140e-02 -7.26629257e-01 -6.82204962e-01 -8.13651457e-02 -7.28932261e-01 -6.79744184e-01 -8.13652202e-02 -7.31347382e-01 -6.77148938e-01 -8.13654363e-02 -7.33789980e-01 -6.74503982e-01 -8.13653320e-02 -7.36090362e-01 -6.71986997e-01 -8.13650638e-02 -7.38350034e-01 -6.69506073e-01 -8.13652724e-02 -7.40682423e-01 -6.66924477e-01 -8.13652501e-02 -7.43079960e-01 -6.64252400e-01 -8.13655332e-02 -7.45415032e-01 -6.61630571e-01 -8.13651159e-02 -7.47704089e-01 -6.59042716e-01 -8.13654512e-02 -7.49993443e-01 -6.56433642e-01 -8.13651383e-02 -7.52284408e-01 -6.53808773e-01 -8.13654512e-02 -7.54625380e-01 -6.51106179e-01 -8.13652351e-02 -7.56848872e-01 -6.48519695e-01 -8.13651606e-02 -7.59043574e-01 -6.45947993e-01 -8.13652351e-02 -7.61289120e-01 -6.43303216e-01 -8.13652202e-02 -7.63567030e-01 -6.40595496e-01 -8.13653618e-02 -7.65856504e-01 -6.37859464e-01 -8.13653097e-02 -7.68053353e-01 -6.35207951e-01 -8.13651606e-02 -7.70209730e-01 -6.32597983e-01 -8.13652501e-02 -7.72417068e-01 -6.29895508e-01 -8.13652053e-02 -7.74603426e-01 -6.27205968e-01 -8.13652351e-02 -7.76837409e-01 -6.24439120e-01 -8.13655108e-02 -7.79086053e-01 -6.21629953e-01 -8.13652501e-02 -7.81240225e-01 -6.18918657e-01 -8.13652501e-02 -7.83337831e-01 -6.16262794e-01 -8.13651234e-02 -7.85414517e-01 -6.13615274e-01 -8.13652351e-02 -7.87617147e-01 -6.10784292e-01 -8.13654959e-02 -7.89797902e-01 -6.07961893e-01 -8.13652202e-02 -7.91919112e-01 -6.05197370e-01 -8.13653842e-02 -7.93994665e-01 -6.02469444e-01 -8.13651383e-02 -7.96018958e-01 -5.99795461e-01 -8.13652351e-02 -7.98162222e-01 -5.96937418e-01 -8.13654363e-02 -8.00247669e-01 -5.94138145e-01 -8.13651532e-02 -8.02265704e-01 -5.91410458e-01 -8.13653097e-02 -8.04328084e-01 -5.88602006e-01 -8.13652053e-02 -8.06399405e-01 -5.85763097e-01 -8.13653842e-02 -8.08481336e-01 -5.82882702e-01 -8.13653320e-02 -8.10500443e-01 -5.80075741e-01 -8.13651457e-02 -8.12469602e-01 -5.77315450e-01 -8.13652873e-02 -8.14471364e-01 -5.74491501e-01 -8.13652650e-02 -8.16484511e-01 -5.71621418e-01 -8.13653320e-02 -8.18513453e-01 -5.68711579e-01 -8.13653842e-02 -8.20491135e-01 -5.65856755e-01 -8.13651681e-02 -8.22413623e-01 -5.63058317e-01 -8.13652202e-02 -8.24357688e-01 -5.60208201e-01 -8.13652501e-02 -8.26300383e-01 -5.57340860e-01 -8.13652575e-02 -8.28291297e-01 -5.54374456e-01 -8.13655406e-02 -8.30238163e-01 -5.51450908e-01 -8.13651159e-02 -8.32158387e-01 -5.48554063e-01 -8.13655332e-02 -8.34079564e-01 -5.45624554e-01 -8.13651383e-02 -8.35913301e-01 -5.42811930e-01 -8.13651979e-02 -8.37800086e-01 -5.39897978e-01 -8.13652724e-02 -8.39722991e-01 -5.36899447e-01 -8.13655108e-02 -8.41632128e-01 -5.33902645e-01 -8.13651532e-02 -8.43436182e-01 -5.31051636e-01 -8.13651979e-02 -8.45250368e-01 -5.28153419e-01 -8.13652351e-02 -8.47108662e-01 -5.25174856e-01 -8.13652501e-02 -8.48930359e-01 -5.22219718e-01 -8.13652501e-02 -8.50753009e-01 -5.19250929e-01 -8.13651904e-02 -8.52556586e-01 -5.16279519e-01 -8.13652501e-02 -8.54399741e-01 -5.13227344e-01 -8.13655332e-02 -8.56245697e-01 -5.10136783e-01 -8.13652501e-02 -8.57973278e-01 -5.07224381e-01 -8.13651606e-02 -8.59730124e-01 -5.04244328e-01 -8.13655257e-02 -8.61492217e-01 -5.01225412e-01 -8.13651532e-02 -8.63211632e-01 -4.98263329e-01 -8.13653693e-02 -8.64938855e-01 -4.95256305e-01 -8.13651830e-02 -8.66632760e-01 -4.92284417e-01 -8.13652501e-02 -8.68346632e-01 -4.89262819e-01 -8.13653097e-02 -8.70047927e-01 -4.86223429e-01 -8.13652426e-02 -8.71743262e-01 -4.83174592e-01 -8.13652724e-02 -8.73455465e-01 -4.80078518e-01 -8.13654214e-02 -8.75156701e-01 -4.76973116e-01 -8.13651979e-02 -8.76778483e-01 -4.73979443e-01 -8.13651830e-02 -8.78399312e-01 -4.70970184e-01 -8.13652501e-02 -8.80074024e-01 -4.67832834e-01 -8.13653842e-02 -8.81746292e-01 -4.64672625e-01 -8.13652873e-02 -8.83353472e-01 -4.61613864e-01 -8.13651830e-02 -8.84914160e-01 -4.58608687e-01 -8.13651532e-02 -8.86477649e-01 -4.55584973e-01 -8.13652202e-02 -8.88097048e-01 -4.52417910e-01 -8.13654512e-02 -8.89729619e-01 -4.49199528e-01 -8.13652650e-02 -8.91248763e-01 -4.46174800e-01 -8.13651159e-02 -8.92747581e-01 -4.43169475e-01 -8.13652351e-02 -8.94284725e-01 -4.40060049e-01 -8.13652351e-02 -8.95812035e-01 -4.36944932e-01 -8.13652501e-02 -8.97384226e-01 -4.33708429e-01 -8.13655183e-02 -8.98937583e-01 -4.30473208e-01 -8.13652202e-02 -9.00405645e-01 -4.27393705e-01 -8.13651457e-02 -9.01841462e-01 -4.24354732e-01 -8.13651979e-02 -9.03315544e-01 -4.21210617e-01 -8.13652053e-02 -9.04817462e-01 -4.17978644e-01 -8.13655108e-02 -9.06299889e-01 -4.14750099e-01 -8.13651532e-02 -9.07696426e-01 -4.11688030e-01 -8.13651755e-02 -9.09104288e-01 -4.08567101e-01 -8.13652501e-02 -9.10524547e-01 -4.05396998e-01 -8.13652799e-02 -9.11982477e-01 -4.02106196e-01 -8.13655481e-02 -9.13428426e-01 -3.98810476e-01 -8.13652202e-02 -9.14802432e-01 -3.95647079e-01 -8.13652277e-02 -9.16182399e-01 -3.92427504e-01 -8.13652277e-02 -9.17509913e-01 -3.89321744e-01 -8.13651159e-02 -9.18830454e-01 -3.86197686e-01 -8.13653097e-02 -9.20180082e-01 -3.82968694e-01 -8.13652351e-02 -9.21538413e-01 -3.79688233e-01 -8.13654363e-02 -9.22862053e-01 -3.76461416e-01 -8.13651234e-02 -9.24135923e-01 -3.73323143e-01 -8.13652202e-02 -9.25466597e-01 -3.70010942e-01 -8.13654289e-02 -9.26753104e-01 -3.66779029e-01 -8.13651383e-02 -9.27995980e-01 -3.63626510e-01 -8.13652351e-02 -9.29254353e-01 -3.60381871e-01 -8.13652202e-02 -9.30518746e-01 -3.57127130e-01 -8.13652501e-02 -9.31789696e-01 -3.53783131e-01 -8.13653842e-02 -9.33003426e-01 -3.50550026e-01 -8.13651159e-02 -9.34191883e-01 -3.47371489e-01 -8.13652202e-02 -9.35433805e-01 -3.44028115e-01 -8.13654289e-02 -9.36668396e-01 -3.40665847e-01 -8.13652202e-02 -9.37847376e-01 -3.37397933e-01 -8.13652277e-02 -9.38990533e-01 -3.34209651e-01 -8.13651159e-02 -9.40144002e-01 -3.30949157e-01 -8.13653618e-02 -9.41303313e-01 -3.27634782e-01 -8.13651532e-02 -9.42408681e-01 -3.24446142e-01 -8.13652053e-02 -9.43530619e-01 -3.21161598e-01 -8.13652351e-02 -9.44650769e-01 -3.17857921e-01 -8.13652128e-02 -9.45788324e-01 -3.14457744e-01 -8.13654959e-02 -9.46882427e-01 -3.11143667e-01 -8.13651010e-02 -9.47933257e-01 -3.07931602e-01 -8.13652202e-02 -9.49020803e-01 -3.04562807e-01 -8.13654214e-02 -9.50080812e-01 -3.01235378e-01 -8.13651159e-02 -9.51121271e-01 -2.97941685e-01 -8.13653246e-02 -9.52159464e-01 -2.94600636e-01 -8.13651234e-02 -9.53177273e-01 -2.91293442e-01 -8.13653842e-02 -9.54214573e-01 -2.87872344e-01 -8.13652202e-02 -9.55193520e-01 -2.84607023e-01 -8.13651010e-02 -9.56178546e-01 -2.81287193e-01 -8.13653171e-02 -9.57155764e-01 -2.77941227e-01 -8.13651234e-02 -9.58118379e-01 -2.74601579e-01 -8.13654363e-02 -9.59071398e-01 -2.71254450e-01 -8.13651383e-02 -9.59989607e-01 -2.67992258e-01 -8.13652053e-02 -9.60922182e-01 -2.64625132e-01 -8.13651979e-02 -9.61841285e-01 -2.61269748e-01 -8.13651979e-02 -9.62766349e-01 -2.57837296e-01 -8.13654065e-02 -9.63685155e-01 -2.54382491e-01 -8.13652053e-02 -9.64568675e-01 -2.51007169e-01 -8.13651979e-02 -9.65418637e-01 -2.47723639e-01 -8.13650861e-02 -9.66241419e-01 -2.44483277e-01 -8.13652053e-02 -9.67114985e-01 -2.41008073e-01 -8.13654065e-02 -9.67979372e-01 -2.37521365e-01 -8.13651830e-02 -9.68804002e-01 -2.34142929e-01 -8.13652202e-02 -9.69588578e-01 -2.30865791e-01 -8.13650787e-02 -9.70368981e-01 -2.27563307e-01 -8.13651979e-02 -9.71173286e-01 -2.24096745e-01 -8.13653618e-02 -9.71978426e-01 -2.20579758e-01 -8.13651830e-02 -9.72718894e-01 -2.17292219e-01 -8.13650712e-02 -9.73467946e-01 -2.13912860e-01 -8.13653991e-02 -9.74214137e-01 -2.10482284e-01 -8.13650489e-02 -9.74915981e-01 -2.07209960e-01 -8.13652053e-02 -9.75658655e-01 -2.03696072e-01 -8.13653618e-02 -9.76386487e-01 -2.00173452e-01 -8.13651904e-02 -9.77060795e-01 -1.96850538e-01 -8.13650712e-02 -9.77720797e-01 -1.93543136e-01 -8.13652053e-02 -9.78391111e-01 -1.90130994e-01 -8.13651830e-02 -9.79062259e-01 -1.86638787e-01 -8.13653618e-02 -9.79731798e-01 -1.83102414e-01 -8.13651979e-02 -9.80344296e-01 -1.79770738e-01 -8.13650712e-02 -9.80953157e-01 -1.76455230e-01 -8.13651830e-02 -9.81563330e-01 -1.73026055e-01 -8.13651681e-02 -9.82169747e-01 -1.69519797e-01 -8.13653842e-02 -9.82772112e-01 -1.65997505e-01 -8.13651755e-02 -9.83331442e-01 -1.62656769e-01 -8.13650787e-02 -9.83894587e-01 -1.59219012e-01 -8.13653842e-02 -9.84444082e-01 -1.55780151e-01 -8.13650489e-02 -9.84978259e-01 -1.52365059e-01 -8.13653097e-02 -9.85505521e-01 -1.48911387e-01 -8.13651383e-02 -9.86015677e-01 -1.45502776e-01 -8.13653097e-02 -9.86519635e-01 -1.42039031e-01 -8.13651234e-02 -9.86997366e-01 -1.38688117e-01 -8.13651830e-02 -9.87486184e-01 -1.35176808e-01 -8.13653618e-02 -9.87953603e-01 -1.31692752e-01 -8.13650936e-02 -9.88404334e-01 -1.28271639e-01 -8.13652873e-02 -9.88848627e-01 -1.24809608e-01 -8.13651159e-02 -9.89266634e-01 -1.21443994e-01 -8.13651681e-02 -9.89694834e-01 -1.17901444e-01 -8.13653395e-02 -9.90099370e-01 -1.14447251e-01 -8.13651159e-02 -9.90482211e-01 -1.11095332e-01 -8.13652202e-02 -9.90876377e-01 -1.07517116e-01 -8.13653842e-02 -9.91255045e-01 -1.03977419e-01 -8.13652128e-02 -9.91607308e-01 -1.00549690e-01 -8.13651979e-02 -9.91945386e-01 -9.71586853e-02 -8.13650489e-02 -9.92279887e-01 -9.37075466e-02 -8.13652202e-02 -9.92601693e-01 -9.02153775e-02 -8.13649669e-02 -9.92898524e-01 -8.68856385e-02 -8.13649669e-02 -9.93194222e-01 -8.34131911e-02 -8.13647434e-02 -9.93479609e-01 -7.99261108e-02 -8.13644081e-02 -9.93758440e-01 -7.63621852e-02 -8.13643038e-02 -9.94019926e-01 -7.28597566e-02 -8.13639984e-02 -9.94258821e-01 -6.95092082e-02 -8.13639984e-02 -9.94501293e-01 -6.59555867e-02 -8.13639984e-02 -9.94730532e-01 -6.23595417e-02 -8.13639984e-02 -9.94926631e-01 -5.91182858e-02 -8.13641548e-02 -9.95103836e-01 -5.60931116e-02 -8.13645273e-02 -9.95244622e-01 -5.35522364e-02 -8.13644826e-02 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. 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. 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. -9.96497273e-01 4.61220965e-02 -6.97564632e-02 -9.96343136e-01 4.93394434e-02 -6.97564632e-02 -9.96179163e-01 5.25369085e-02 -6.97564706e-02 -9.95952427e-01 5.66256605e-02 -6.97562620e-02 -9.95785654e-01 5.94535619e-02 -6.97559863e-02 -9.95573878e-01 6.28823042e-02 -6.97559267e-02 -9.95351672e-01 6.63174912e-02 -6.97559044e-02 -9.95116234e-01 6.97383955e-02 -6.97559044e-02 -9.94876325e-01 7.31004253e-02 -6.97559044e-02 -9.94609475e-01 7.66472965e-02 -6.97559044e-02 -9.94327486e-01 8.02177712e-02 -6.97559044e-02 -9.94049132e-01 8.35992247e-02 -6.97559044e-02 -9.93753970e-01 8.70430768e-02 -6.97559044e-02 -9.93436038e-01 9.05956924e-02 -6.97559044e-02 -9.93119538e-01 9.40036178e-02 -6.97559044e-02 -9.92783070e-01 9.74910781e-02 -6.97559044e-02 -9.92442608e-01 1.00911848e-01 -6.97559044e-02 -9.92093861e-01 1.04279876e-01 -6.97559044e-02 -9.91713881e-01 1.07820846e-01 -6.97559044e-02 -9.91320133e-01 1.11398354e-01 -6.97559044e-02 -9.90922809e-01 1.14864945e-01 -6.97559044e-02 -9.90511537e-01 1.18354268e-01 -6.97559044e-02 -9.90098596e-01 1.21769197e-01 -6.97559044e-02 -9.89672542e-01 1.25198379e-01 -6.97559044e-02 -9.89227414e-01 1.28657803e-01 -6.97559044e-02 -9.88763332e-01 1.32167488e-01 -6.97559044e-02 -9.88310039e-01 1.35527208e-01 -6.97559044e-02 -9.87851858e-01 1.38830408e-01 -6.97559044e-02 -9.87342119e-01 1.42398521e-01 -6.97559044e-02 -9.86826062e-01 1.45929068e-01 -6.97559044e-02 -9.86312509e-01 1.49356008e-01 -6.97559044e-02 -9.85782325e-01 1.52827337e-01 -6.97559044e-02 -9.85244215e-01 1.56262264e-01 -6.97559044e-02 -9.84707236e-01 1.59607485e-01 -6.97559044e-02 -9.84143972e-01 1.63051412e-01 -6.97559044e-02 -9.83549178e-01 1.66598722e-01 -6.97559044e-02 -9.82975364e-01 1.69949815e-01 -6.97559044e-02 -9.82381880e-01 1.73364282e-01 -6.97559044e-02 -9.81751680e-01 1.76898122e-01 -6.97559044e-02 -9.81123388e-01 1.80323169e-01 -6.97559044e-02 -9.80492473e-01 1.83734417e-01 -6.97559044e-02 -9.79863048e-01 1.87056735e-01 -6.97559044e-02 -9.79223609e-01 1.90372542e-01 -6.97559044e-02 -9.78531480e-01 1.93904594e-01 -6.97559044e-02 -9.77824271e-01 1.97442874e-01 -6.97559044e-02 -9.77127433e-01 2.00861990e-01 -6.97559044e-02 -9.76442516e-01 2.04164073e-01 -6.97559044e-02 -9.75724220e-01 2.07578152e-01 -6.97559044e-02 -9.74973559e-01 2.11073399e-01 -6.97559044e-02 -9.74247932e-01 2.14386001e-01 -6.97559044e-02 -9.73503113e-01 2.17756897e-01 -6.97559044e-02 -9.72728133e-01 2.21185431e-01 -6.97559044e-02 -9.71975088e-01 2.24468619e-01 -6.97559044e-02 -9.71167564e-01 2.27953762e-01 -6.97559044e-02 -9.70337272e-01 2.31454864e-01 -6.97559044e-02 -9.69534516e-01 2.34802485e-01 -6.97559044e-02 -9.68704581e-01 2.38192841e-01 -6.97559044e-02 -9.67860997e-01 2.41590530e-01 -6.97559044e-02 -9.67033744e-01 2.44883657e-01 -6.97559044e-02 -9.66177583e-01 2.48241767e-01 -6.97559044e-02 -9.65283155e-01 2.51701176e-01 -6.97559044e-02 -9.64419246e-01 2.54995912e-01 -6.97559044e-02 -9.63524580e-01 2.58350104e-01 -6.97559044e-02 -9.62599456e-01 2.61779964e-01 -6.97559044e-02 -9.61676359e-01 2.65141428e-01 -6.97559044e-02 -9.60744977e-01 2.68508017e-01 -6.97559044e-02 -9.59815919e-01 2.71806598e-01 -6.97559044e-02 -9.58871067e-01 2.75116742e-01 -6.97559044e-02 -9.57903266e-01 2.78467387e-01 -6.97559044e-02 -9.56925511e-01 2.81810224e-01 -6.97559044e-02 -9.55905616e-01 2.85255939e-01 -6.97559044e-02 -9.54934895e-01 2.88481653e-01 -6.97559044e-02 -9.53923285e-01 2.91810602e-01 -6.97559044e-02 -9.52865899e-01 2.95247138e-01 -6.97559044e-02 -9.51842427e-01 2.98530489e-01 -6.97559044e-02 -9.50792432e-01 3.01856339e-01 -6.97559044e-02 -9.49752271e-01 3.05117875e-01 -6.97559044e-02 -9.48712170e-01 3.08327675e-01 -6.97559044e-02 -9.47608948e-01 3.11704159e-01 -6.97559044e-02 -9.46479380e-01 3.15118134e-01 -6.97559044e-02 -9.45368707e-01 3.18437189e-01 -6.97559044e-02 -9.44254696e-01 3.21725100e-01 -6.97559044e-02 -9.43134665e-01 3.24998170e-01 -6.97559044e-02 -9.42012727e-01 3.28229845e-01 -6.97559044e-02 -9.40860748e-01 3.31516474e-01 -6.97559044e-02 -9.39677060e-01 3.34863782e-01 -6.97559044e-02 -9.38525081e-01 3.38072300e-01 -6.97559044e-02 -9.37380135e-01 3.41239661e-01 -6.97559044e-02 -9.36148047e-01 3.44589025e-01 -6.97559044e-02 -9.34901476e-01 3.47943366e-01 -6.97559044e-02 -9.33680356e-01 3.51211905e-01 -6.97559044e-02 -9.32466924e-01 3.54433268e-01 -6.97559044e-02 -9.31260407e-01 3.57614756e-01 -6.97559044e-02 -9.30006444e-01 3.60842735e-01 -6.97559044e-02 -9.28724706e-01 3.64135146e-01 -6.97559044e-02 -9.27419901e-01 3.67447048e-01 -6.97559044e-02 -9.26161230e-01 3.70605618e-01 -6.97559044e-02 -9.24868643e-01 3.73818606e-01 -6.97559044e-02 -9.23527420e-01 3.77123773e-01 -6.97559044e-02 -9.22213256e-01 3.80319327e-01 -6.97559044e-02 -9.20886993e-01 3.83522362e-01 -6.97559044e-02 -9.19572234e-01 3.86664182e-01 -6.97559044e-02 -9.18247163e-01 3.89799684e-01 -6.97559044e-02 -9.16842699e-01 3.93084675e-01 -6.97559044e-02 -9.15423989e-01 3.96387041e-01 -6.97559044e-02 -9.14046347e-01 3.99555683e-01 -6.97559044e-02 -9.12639916e-01 4.02755946e-01 -6.97559044e-02 -9.11228836e-01 4.05938983e-01 -6.97559044e-02 -9.09808874e-01 4.09111351e-01 -6.97559044e-02 -9.08410609e-01 4.12205875e-01 -6.97559044e-02 -9.06975091e-01 4.15350258e-01 -6.97559044e-02 -9.05478656e-01 4.18604910e-01 -6.97559044e-02 -9.04047430e-01 4.21688795e-01 -6.97559044e-02 -9.02578652e-01 4.24822420e-01 -6.97559044e-02 -9.01052773e-01 4.28051054e-01 -6.97559044e-02 -8.99548352e-01 4.31200534e-01 -6.97559044e-02 -8.98042142e-01 4.34337348e-01 -6.97559044e-02 -8.96546960e-01 4.37415272e-01 -6.97559044e-02 -8.95061851e-01 4.40438867e-01 -6.97559044e-02 -8.93486679e-01 4.43627179e-01 -6.97559044e-02 -8.91894639e-01 4.46816564e-01 -6.97559044e-02 -8.90328050e-01 4.49935198e-01 -6.97559044e-02 -8.88752639e-01 4.53037798e-01 -6.97559044e-02 -8.87179852e-01 4.56111461e-01 -6.97559044e-02 -8.85581911e-01 4.59200978e-01 -6.97559044e-02 -8.83973420e-01 4.62292820e-01 -6.97559044e-02 -8.82350266e-01 4.65388358e-01 -6.97559044e-02 -8.80757749e-01 4.68392402e-01 -6.97559044e-02 -8.79170418e-01 4.71365392e-01 -6.97559044e-02 -8.77479315e-01 4.74504918e-01 -6.97559044e-02 -8.75775516e-01 4.77645069e-01 -6.97559044e-02 -8.74099374e-01 4.80704576e-01 -6.97559044e-02 -8.72412860e-01 4.83750790e-01 -6.97559044e-02 -8.70720446e-01 4.86791551e-01 -6.97559044e-02 -8.69038582e-01 4.89793241e-01 -6.97559044e-02 -8.67320180e-01 4.92828637e-01 -6.97559044e-02 -8.65571618e-01 4.95893717e-01 -6.97559044e-02 -8.63874435e-01 4.98845845e-01 -6.97559044e-02 -8.62137079e-01 5.01842141e-01 -6.97559044e-02 -8.60391855e-01 5.04827201e-01 -6.97559044e-02 -8.58614802e-01 5.07843435e-01 -6.97559044e-02 -8.56780708e-01 5.10930240e-01 -6.97559044e-02 -8.54996562e-01 5.13910115e-01 -6.97559044e-02 -8.53192806e-01 5.16896605e-01 -6.97559044e-02 -8.51382017e-01 5.19880056e-01 -6.97559044e-02 -8.49561930e-01 5.22846282e-01 -6.97559044e-02 -8.47737849e-01 5.25801897e-01 -6.97559044e-02 -8.45944047e-01 5.28680861e-01 -6.97559044e-02 -8.44103515e-01 5.31613588e-01 -6.97559044e-02 -8.42202127e-01 5.34619868e-01 -6.97559044e-02 -8.40332866e-01 5.37554801e-01 -6.97559044e-02 -8.38424742e-01 5.40524423e-01 -6.97559044e-02 -8.36536050e-01 5.43441653e-01 -6.97559044e-02 -8.34694207e-01 5.46265900e-01 -6.97559044e-02 -8.32780480e-01 5.49181759e-01 -6.97559044e-02 -8.30788851e-01 5.52186668e-01 -6.97559044e-02 -8.28849137e-01 5.55098176e-01 -6.97559044e-02 -8.26951802e-01 5.57922602e-01 -6.97559044e-02 -8.25064778e-01 5.60706437e-01 -6.97559044e-02 -8.23065162e-01 5.63639343e-01 -6.97559044e-02 -8.21046412e-01 5.66576004e-01 -6.97559044e-02 -8.19043994e-01 5.69465578e-01 -6.97559044e-02 -8.17099214e-01 5.72249889e-01 -6.97559044e-02 -8.15106511e-01 5.75090349e-01 -6.97559044e-02 -8.13017249e-01 5.78034103e-01 -6.97559044e-02 -8.10993552e-01 5.80873013e-01 -6.97559044e-02 -8.08955252e-01 5.83704591e-01 -6.97559044e-02 -8.06906819e-01 5.86537778e-01 -6.97559044e-02 -8.04881513e-01 5.89311481e-01 -6.97559044e-02 -8.02894771e-01 5.92014730e-01 -6.97559044e-02 -8.00811112e-01 5.94829202e-01 -6.97559044e-02 -7.98655987e-01 5.97720563e-01 -6.97559044e-02 -7.96636641e-01 6.00411594e-01 -6.97559044e-02 -7.94534028e-01 6.03193045e-01 -6.97559044e-02 -7.92364776e-01 6.06039882e-01 -6.97559044e-02 -7.90243745e-01 6.08799160e-01 -6.97559044e-02 -7.88089037e-01 6.11586034e-01 -6.97559044e-02 -7.85984099e-01 6.14291012e-01 -6.97559044e-02 -7.83898473e-01 6.16949379e-01 -6.97559044e-02 -7.81716168e-01 6.19710147e-01 -6.97559044e-02 -7.79459536e-01 6.22550845e-01 -6.97559044e-02 -7.77271509e-01 6.25278711e-01 -6.97559044e-02 -7.75092661e-01 6.27979040e-01 -6.97559044e-02 -7.72970259e-01 6.30585253e-01 -6.97559044e-02 -7.70787179e-01 6.33254647e-01 -6.97559044e-02 -7.68507421e-01 6.36019468e-01 -6.97559044e-02 -7.66267180e-01 6.38715148e-01 -6.97559044e-02 -7.64106452e-01 6.41301274e-01 -6.97559044e-02 -7.61862695e-01 6.43962026e-01 -6.97559044e-02 -7.59510934e-01 6.46732807e-01 -6.97559044e-02 -7.57248938e-01 6.49382710e-01 -6.97559044e-02 -7.54986644e-01 6.52013481e-01 -6.97559044e-02 -7.52711713e-01 6.54636741e-01 -6.97559044e-02 -7.50477493e-01 6.57196760e-01 -6.97559044e-02 -7.48237312e-01 6.59745276e-01 -6.97559044e-02 -7.45886207e-01 6.62402630e-01 -6.97559044e-02 -7.43507147e-01 6.65073574e-01 -6.97559044e-02 -7.41214335e-01 6.67624891e-01 -6.97559044e-02 -7.38895059e-01 6.70195699e-01 -6.97559044e-02 -7.36496449e-01 6.72826111e-01 -6.97559044e-02 -7.34142184e-01 6.75397575e-01 -6.97559044e-02 -7.31766582e-01 6.77970707e-01 -6.97559044e-02 -7.29456484e-01 6.80453360e-01 -6.97559044e-02 -7.27156639e-01 6.82911515e-01 -6.97559044e-02 -7.24721372e-01 6.85492456e-01 -6.97559044e-02 -7.22238123e-01 6.88111186e-01 -6.97559044e-02 -7.19821572e-01 6.90632820e-01 -6.97559044e-02 -7.17427671e-01 6.93132877e-01 -6.97559044e-02 -7.15057135e-01 6.95575118e-01 -6.97559044e-02 -7.12639570e-01 6.98049486e-01 -6.97559044e-02 -7.10122526e-01 7.00611055e-01 -6.97559044e-02 -7.07682610e-01 7.03078866e-01 -6.97559044e-02 -7.05218315e-01 7.05532074e-01 -6.97559044e-02 -7.02821434e-01 7.07938790e-01 -6.97559044e-02 -7.00338542e-01 7.10393727e-01 -6.97559044e-02 -6.97794497e-01 7.12889075e-01 -6.97559044e-02 -6.95301175e-01 7.15323985e-01 -6.97559044e-02 -6.92804933e-01 7.17742980e-01 -6.97559044e-02 -6.90325320e-01 7.20116377e-01 -6.97559044e-02 -6.87865734e-01 7.22474515e-01 -6.97559044e-02 -6.85291469e-01 7.24911988e-01 -6.97559044e-02 -6.82702303e-01 7.27349877e-01 -6.97559044e-02 -6.80202007e-01 7.29687154e-01 -6.97559044e-02 -6.77664161e-01 7.32048571e-01 -6.97559044e-02 -6.75051570e-01 7.34460592e-01 -6.97559044e-02 -6.72522247e-01 7.36774504e-01 -6.97559044e-02 -6.69945657e-01 7.39119589e-01 -6.97559044e-02 -6.67394578e-01 7.41423607e-01 -6.97559044e-02 -6.64864361e-01 7.43693531e-01 -6.97559044e-02 -6.62199557e-01 7.46067703e-01 -6.97559044e-02 -6.59590662e-01 7.48374224e-01 -6.97559044e-02 -6.56960070e-01 7.50683248e-01 -6.97559044e-02 -6.54329658e-01 7.52979934e-01 -6.97559044e-02 -6.51720583e-01 7.55237281e-01 -6.97559044e-02 -6.48985326e-01 7.57589877e-01 -6.97559044e-02 -6.46329105e-01 7.59856045e-01 -6.97559044e-02 -6.43694460e-01 7.62090445e-01 -6.97559044e-02 -6.41108155e-01 7.64267683e-01 -6.97559044e-02 -6.38454974e-01 7.66485631e-01 -6.97559044e-02 -6.35739267e-01 7.68738627e-01 -6.97559044e-02 -6.33070529e-01 7.70940721e-01 -6.97559044e-02 -6.30284488e-01 7.73216665e-01 -6.97559044e-02 -6.27577722e-01 7.75415838e-01 -6.97559044e-02 -6.24942482e-01 7.77540088e-01 -6.97559044e-02 -6.22329652e-01 7.79635191e-01 -6.97559044e-02 -6.19521677e-01 7.81866729e-01 -6.97559044e-02 -6.16766810e-01 7.84044087e-01 -6.97559044e-02 -6.14050210e-01 7.86173284e-01 -6.97559044e-02 -6.11299217e-01 7.88314402e-01 -6.97559044e-02 -6.08596861e-01 7.90401161e-01 -6.97559044e-02 -6.05742574e-01 7.92590499e-01 -6.97559044e-02 -6.02923334e-01 7.94737697e-01 -6.97559044e-02 -6.00225806e-01 7.96777308e-01 -6.97559044e-02 -5.97451389e-01 7.98856974e-01 -6.97559044e-02 -5.94580770e-01 8.00997257e-01 -6.97559044e-02 -5.91796875e-01 8.03055525e-01 -6.97559044e-02 -5.88995993e-01 8.05112064e-01 -6.97559044e-02 -5.86248875e-01 8.07117462e-01 -6.97559044e-02 -5.83422542e-01 8.09158742e-01 -6.97559044e-02 -5.80512345e-01 8.11252594e-01 -6.97559044e-02 -5.77681303e-01 8.13270152e-01 -6.97559044e-02 -5.74824989e-01 8.15292597e-01 -6.97559044e-02 -5.72041333e-01 8.17246735e-01 -6.97559044e-02 -5.69212496e-01 8.19218099e-01 -6.97559044e-02 -5.66325784e-01 8.21219921e-01 -6.97559044e-02 -5.63467443e-01 8.23182762e-01 -6.97559044e-02 -5.60487032e-01 8.25213671e-01 -6.97559044e-02 -5.57616591e-01 8.27155769e-01 -6.97559044e-02 -5.54831445e-01 8.29026222e-01 -6.97559044e-02 -5.51920414e-01 8.30966175e-01 -6.97559044e-02 -5.48898578e-01 8.32967043e-01 -6.97559044e-02 -5.46069801e-01 8.34822774e-01 -6.97559044e-02 -5.43178797e-01 8.36706817e-01 -6.97559044e-02 -5.40236533e-01 8.38609874e-01 -6.97559044e-02 -5.37308872e-01 8.40487957e-01 -6.97559044e-02 -5.34291983e-01 8.42410684e-01 -6.97559044e-02 -5.31339645e-01 8.44275117e-01 -6.97559044e-02 -5.28472781e-01 8.46072912e-01 -6.97559044e-02 -5.25547624e-01 8.47895861e-01 -6.97559044e-02 -5.22484064e-01 8.49783719e-01 -6.97559044e-02 -5.19568801e-01 8.51571620e-01 -6.97559044e-02 -5.16588807e-01 8.53379846e-01 -6.97559044e-02 -5.13627529e-01 8.55166376e-01 -6.97559044e-02 -5.10669470e-01 8.56936932e-01 -6.97559044e-02 -5.07668197e-01 8.58716547e-01 -6.97559044e-02 -5.04729867e-01 8.60449851e-01 -6.97559044e-02 -5.01692474e-01 8.62223446e-01 -6.97559044e-02 -4.98571128e-01 8.64032686e-01 -6.97559044e-02 -4.95559156e-01 8.65762651e-01 -6.97559044e-02 -4.92545694e-01 8.67480159e-01 -6.97559044e-02 -4.89519686e-01 8.69194448e-01 -6.97559044e-02 -4.86479431e-01 8.70896101e-01 -6.97559044e-02 -4.83424425e-01 8.72594416e-01 -6.97559044e-02 -4.80435967e-01 8.74246240e-01 -6.97559044e-02 -4.77398694e-01 8.75909150e-01 -6.97559044e-02 -4.74265456e-01 8.77606511e-01 -6.97559044e-02 -4.71199483e-01 8.79258096e-01 -6.97559044e-02 -4.68133122e-01 8.80895555e-01 -6.97559044e-02 -4.65111673e-01 8.82494986e-01 -6.97559044e-02 -4.62022662e-01 8.84114087e-01 -6.97559044e-02 -4.58872646e-01 8.85753214e-01 -6.97559044e-02 -4.55780417e-01 8.87349904e-01 -6.97559044e-02 -4.52768028e-01 8.88889372e-01 -6.97559267e-02 -4.49684441e-01 8.90453279e-01 -6.97559044e-02 -4.46514964e-01 8.92047286e-01 -6.97559044e-02 -4.43368673e-01 8.93614888e-01 -6.97559044e-02 -4.40253168e-01 8.95154297e-01 -6.97559044e-02 -4.37185228e-01 8.96658063e-01 -6.97559044e-02 -4.34084922e-01 8.98163319e-01 -6.97559044e-02 -4.30895180e-01 8.99695337e-01 -6.97559044e-02 -4.27770466e-01 9.01184678e-01 -6.97559044e-02 -4.24565941e-01 9.02700007e-01 -6.97559044e-02 -4.21459109e-01 9.04155493e-01 -6.97559044e-02 -4.18312877e-01 9.05614972e-01 -6.97559044e-02 -4.15144354e-01 9.07070518e-01 -6.97559044e-02 -4.11982208e-01 9.08512533e-01 -6.97559044e-02 -4.08734739e-01 9.09979045e-01 -6.97559044e-02 -4.05545712e-01 9.11404490e-01 -6.97559044e-02 -4.02447760e-01 9.12776649e-01 -6.97559044e-02 -3.99315059e-01 9.14151371e-01 -6.97559044e-02 -3.96063477e-01 9.15564537e-01 -6.97559044e-02 -3.92775118e-01 9.16975558e-01 -6.97559044e-02 -3.89654785e-01 9.18309867e-01 -6.97559044e-02 -3.86571258e-01 9.19611275e-01 -6.97559044e-02 -3.83290827e-01 9.20983911e-01 -6.97559044e-02 -3.80004019e-01 9.22343373e-01 -6.97559044e-02 -3.76790822e-01 9.23661768e-01 -6.97559044e-02 -3.73609036e-01 9.24954772e-01 -6.97559044e-02 -3.70389074e-01 9.26247418e-01 -6.97559044e-02 -3.67090046e-01 9.27560747e-01 -6.97559044e-02 -3.63868862e-01 9.28829551e-01 -6.97559044e-02 -3.60610038e-01 9.30093706e-01 -6.97559044e-02 -3.57417643e-01 9.31336343e-01 -6.97559044e-02 -3.54164124e-01 9.32570040e-01 -6.97559044e-02 -3.50910485e-01 9.33791935e-01 -6.97559044e-02 -3.47648978e-01 9.35011506e-01 -6.97559044e-02 -3.44326943e-01 9.36243236e-01 -6.97559044e-02 -3.41128826e-01 9.37422633e-01 -6.97559044e-02 -3.37811798e-01 9.38618541e-01 -6.97559044e-02 -3.34527165e-01 9.39797640e-01 -6.97559044e-02 -3.31257999e-01 9.40952957e-01 -6.97559044e-02 -3.27924162e-01 9.42119181e-01 -6.97559044e-02 -3.24641734e-01 9.43257391e-01 -6.97559044e-02 -3.21419328e-01 9.44358408e-01 -6.97559044e-02 -3.18118840e-01 9.45476234e-01 -6.97559044e-02 -3.14749479e-01 9.46602523e-01 -6.97559044e-02 -3.11452538e-01 9.47691202e-01 -6.97559044e-02 -3.08197439e-01 9.48755682e-01 -6.97559044e-02 -3.04899603e-01 9.49821889e-01 -6.97559044e-02 -3.01520556e-01 9.50899005e-01 -6.97559044e-02 -2.98197985e-01 9.51947093e-01 -6.97559044e-02 -2.94858217e-01 9.52986896e-01 -6.97559044e-02 -2.91626811e-01 9.53980446e-01 -6.97559044e-02 -2.88265526e-01 9.54998612e-01 -6.97559044e-02 -2.84836799e-01 9.56029356e-01 -6.97559044e-02 -2.81511456e-01 9.57014561e-01 -6.97559044e-02 -2.78151244e-01 9.57995594e-01 -6.97559044e-02 -2.74923384e-01 9.58927691e-01 -6.97559044e-02 -2.71585256e-01 9.59877849e-01 -6.97559044e-02 -2.68220246e-01 9.60825086e-01 -6.97559044e-02 -2.64968812e-01 9.61724818e-01 -6.97559044e-02 -2.61480391e-01 9.62680042e-01 -6.97559044e-02 -2.58024037e-01 9.63610828e-01 -6.97559044e-02 -2.54655153e-01 9.64507580e-01 -6.97559044e-02 -2.51299918e-01 9.65387583e-01 -6.97559044e-02 -2.48026580e-01 9.66233909e-01 -6.97559044e-02 -2.44645536e-01 9.67092216e-01 -6.97559044e-02 -2.41145819e-01 9.67972517e-01 -6.97559044e-02 -2.37761617e-01 9.68810380e-01 -6.97559044e-02 -2.34368846e-01 9.69639063e-01 -6.97559044e-02 -2.31094971e-01 9.70423877e-01 -6.97559044e-02 -2.27714300e-01 9.71222103e-01 -6.97559044e-02 -2.24326968e-01 9.72009659e-01 -6.97559044e-02 -2.20928192e-01 9.72785950e-01 -6.97559044e-02 -2.17442155e-01 9.73573744e-01 -6.97559044e-02 -2.14025155e-01 9.74326611e-01 -6.97559044e-02 -2.10617706e-01 9.75070238e-01 -6.97559044e-02 -2.07311168e-01 9.75779474e-01 -6.97559044e-02 -2.03943431e-01 9.76490140e-01 -6.97559044e-02 -2.00401038e-01 9.77223516e-01 -6.97559044e-02 -1.96993709e-01 9.77913976e-01 -6.97559044e-02 -1.93588287e-01 9.78594005e-01 -6.97559044e-02 -1.90257460e-01 9.79247570e-01 -6.97559044e-02 -1.86834052e-01 9.79906261e-01 -6.97559044e-02 -1.83408231e-01 9.80552793e-01 -6.97559044e-02 -1.80075228e-01 9.81169105e-01 -6.97559044e-02 -1.76540971e-01 9.81816709e-01 -6.97559044e-02 -1.73022985e-01 9.82442856e-01 -6.97559044e-02 -1.69599563e-01 9.83035743e-01 -6.97559044e-02 -1.66178763e-01 9.83620346e-01 -6.97559044e-02 -1.62835613e-01 9.84178722e-01 -6.97559044e-02 -1.59492463e-01 9.84726071e-01 -6.97559044e-02 -1.55963913e-01 9.85291719e-01 -6.97559044e-02 -1.52421355e-01 9.85846639e-01 -6.97559044e-02 -1.48968861e-01 9.86371160e-01 -6.97559044e-02 -1.45500928e-01 9.86890554e-01 -6.97559044e-02 -1.42070070e-01 9.87389207e-01 -6.97559044e-02 -1.38743207e-01 9.87863660e-01 -6.97559044e-02 -1.35299638e-01 9.88341928e-01 -6.97559044e-02 -1.31731316e-01 9.88822460e-01 -6.97559044e-02 -1.28378645e-01 9.89262819e-01 -6.97559044e-02 -1.24950238e-01 9.89701867e-01 -6.97559044e-02 -1.21470556e-01 9.90135849e-01 -6.97559044e-02 -1.18001789e-01 9.90554392e-01 -6.97559044e-02 -1.14449412e-01 9.90971386e-01 -6.97559044e-02 -1.10983439e-01 9.91365314e-01 -6.97559044e-02 -1.07517406e-01 9.91746545e-01 -6.97559044e-02 -1.04049861e-01 9.92115915e-01 -6.97559044e-02 -1.00581944e-01 9.92474377e-01 -6.97559044e-02 -9.72014964e-02 9.92811739e-01 -6.97559044e-02 -9.38673019e-02 9.93132532e-01 -6.97559044e-02 -9.02891830e-02 9.93463814e-01 -6.97559044e-02 -8.67135525e-02 9.93783653e-01 -6.97559044e-02 -8.32530335e-02 9.94078636e-01 -6.97559044e-02 -7.97586590e-02 9.94364619e-01 -6.97559044e-02 -7.63978809e-02 9.94627416e-01 -6.97559044e-02 -7.29329810e-02 9.94889259e-01 -6.97559044e-02 -6.93442971e-02 9.95143950e-01 -6.97559044e-02 -6.58634454e-02 9.95382130e-01 -6.97559044e-02 -6.24081790e-02 9.95602906e-01 -6.97559044e-02 -5.90314083e-02 9.95811045e-01 -6.97559044e-02 -5.55727333e-02 9.96010125e-01 -6.97559044e-02 -5.20466454e-02 9.96198595e-01 -6.97559044e-02 -4.85875197e-02 9.96376276e-01 -6.97559044e-02 -4.50321510e-02 9.96540368e-01 -6.97559044e-02 -4.15666774e-02 9.96692657e-01 -6.97559044e-02 -3.80715728e-02 9.96830881e-01 -6.97559044e-02 -3.46722528e-02 9.96956527e-01 -6.97559044e-02 -3.12172659e-02 9.97068465e-01 -6.97559044e-02 -2.77100895e-02 9.97173309e-01 -6.97559044e-02 -2.42232569e-02 9.97268200e-01 -6.97559044e-02 -2.06713248e-02 9.97341454e-01 -6.97559044e-02 -1.72643363e-02 9.97413158e-01 -6.97559044e-02 -1.38023533e-02 9.97458696e-01 -6.97559044e-02 -1.02929287e-02 9.97505009e-01 -6.97559044e-02 -6.91584172e-03 9.97540832e-01 -6.97559044e-02 -3.35964118e-03 9.97557878e-01 -6.97559044e-02 2.29859870e-04 9.97559190e-01 -6.97559044e-02 3.69394850e-03 9.97557759e-01 -6.97559044e-02 7.14988075e-03 9.97537792e-01 -6.97559044e-02 1.05717136e-02 9.97501910e-01 -6.97559044e-02 1.39482934e-02 9.97456849e-01 -6.97559044e-02 1.75167359e-02 9.97409821e-01 -6.97559044e-02 2.10982263e-02 9.97334123e-01 -6.97559044e-02 2.45988555e-02 9.97255564e-01 -6.97559044e-02 2.81042382e-02 9.97164369e-01 -6.97559044e-02 3.15828100e-02 9.97059107e-01 -6.97559044e-02 3.49658504e-02 9.96947169e-01 -6.97559044e-02 3.84087637e-02 9.96819735e-01 -6.97559044e-02 4.20311205e-02 9.96674001e-01 -6.97559044e-02 4.55010943e-02 9.96519804e-01 -6.97559044e-02 4.89764623e-02 9.96356308e-01 -6.97559044e-02 5.23692556e-02 9.96180654e-01 -6.97559044e-02 5.58238588e-02 9.95995522e-01 -6.97559044e-02 5.93207181e-02 9.95793819e-01 -6.97559044e-02 6.27746135e-02 9.95579064e-01 -6.97559044e-02 6.63606375e-02 9.95348990e-01 -6.97559044e-02 6.98154494e-02 9.95110869e-01 -6.97559044e-02 7.32965246e-02 9.94863331e-01 -6.97559044e-02 7.67732486e-02 9.94598806e-01 -6.97559044e-02 8.01789537e-02 9.94331717e-01 -6.97559044e-02 8.35941285e-02 9.94050145e-01 -6.97559044e-02 8.71578678e-02 9.93744254e-01 -6.97559044e-02 9.06531811e-02 9.93430674e-01 -6.97559044e-02 9.41015407e-02 9.93110657e-01 -6.97559044e-02 9.75106359e-02 9.92782176e-01 -6.97559267e-02 1.00962229e-01 9.92435992e-01 -6.97559044e-02 1.04421973e-01 9.92078841e-01 -6.97559044e-02 1.07890628e-01 9.91707325e-01 -6.97559044e-02 1.11438543e-01 9.91313934e-01 -6.97559044e-02 1.14816956e-01 9.90928233e-01 -6.97559044e-02 1.18265763e-01 9.90522563e-01 -6.97559044e-02 1.21725962e-01 9.90103960e-01 -6.97559044e-02 1.25172213e-01 9.89674509e-01 -6.97559044e-02 1.28720522e-01 9.89217937e-01 -6.97559044e-02 1.32176936e-01 9.88762975e-01 -6.97559044e-02 1.35646835e-01 9.88294184e-01 -6.97559044e-02 1.38988599e-01 9.87830758e-01 -6.97559044e-02 1.42447963e-01 9.87335622e-01 -6.97559044e-02 1.45899549e-01 9.86831307e-01 -6.97559044e-02 1.49313882e-01 9.86318767e-01 -6.97559044e-02 1.52833790e-01 9.85783100e-01 -6.97559044e-02 1.56212121e-01 9.85250413e-01 -6.97559044e-02 1.59645736e-01 9.84701633e-01 -6.97559044e-02 1.63101211e-01 9.84136403e-01 -6.97559044e-02 1.66417643e-01 9.83579218e-01 -6.97559044e-02 1.69926658e-01 9.82979417e-01 -6.97559044e-02 1.73475459e-01 9.82363284e-01 -6.97559044e-02 1.76890031e-01 9.81754899e-01 -6.97559044e-02 1.80321753e-01 9.81125355e-01 -6.97559044e-02 1.83660448e-01 9.80506539e-01 -6.97559044e-02 1.86991602e-01 9.79876041e-01 -6.97559044e-02 1.90410793e-01 9.79217350e-01 -6.97559044e-02 1.93891078e-01 9.78534043e-01 -6.97559044e-02 1.97401538e-01 9.77832317e-01 -6.97559044e-02 2.00831309e-01 9.77133870e-01 -6.97559044e-02 2.04239070e-01 9.76426125e-01 -6.97559044e-02 2.07565159e-01 9.75727558e-01 -6.97559044e-02 2.10936502e-01 9.75001931e-01 -6.97559044e-02 2.14439169e-01 9.74237382e-01 -6.97559044e-02 2.17865601e-01 9.73478019e-01 -6.97559044e-02 2.21279413e-01 9.72705781e-01 -6.97559044e-02 2.24568054e-01 9.71953869e-01 -6.97559044e-02 2.27937117e-01 9.71170962e-01 -6.97559044e-02 2.31358737e-01 9.70360398e-01 -6.97559044e-02 2.34634191e-01 9.69575286e-01 -6.97559044e-02 2.38118306e-01 9.68723059e-01 -6.97559044e-02 2.41593048e-01 9.67860639e-01 -6.97559044e-02 2.44931415e-01 9.67020810e-01 -6.97559044e-02 2.48297989e-01 9.66165066e-01 -6.97559044e-02 2.51605839e-01 9.65307951e-01 -6.97559044e-02 2.54883349e-01 9.64448810e-01 -6.97559044e-02 2.58352876e-01 9.63523030e-01 -6.97559044e-02 2.61812329e-01 9.62590814e-01 -6.97559044e-02 2.65144467e-01 9.61675823e-01 -6.97559044e-02 2.68429816e-01 9.60767150e-01 -6.97559044e-02 2.71749407e-01 9.59830821e-01 -6.97559044e-02 2.75107682e-01 9.58875835e-01 -6.97559044e-02 2.78439343e-01 9.57911909e-01 -6.97559044e-02 2.81909466e-01 9.56895769e-01 -6.97559044e-02 2.85167992e-01 9.55932856e-01 -6.97559044e-02 2.88492173e-01 9.54929948e-01 -6.97559044e-02 2.91847914e-01 9.53911960e-01 -6.97559044e-02 2.95083970e-01 9.52917695e-01 -6.97559044e-02 2.98527747e-01 9.51843977e-01 -6.97559044e-02 3.01790982e-01 9.50812638e-01 -6.97559044e-02 3.05103600e-01 9.49755788e-01 -6.97559044e-02 3.08448672e-01 9.48674500e-01 -6.97559044e-02 3.11737120e-01 9.47599113e-01 -6.97559044e-02 3.15050542e-01 9.46502149e-01 -6.97559044e-02 3.18240404e-01 9.45436239e-01 -6.97559044e-02 3.21641147e-01 9.44283366e-01 -6.97559044e-02 3.25015604e-01 9.43127751e-01 -6.97559044e-02 3.28297287e-01 9.41988945e-01 -6.97559044e-02 3.31563294e-01 9.40845490e-01 -6.97559044e-02 3.34793597e-01 9.39703345e-01 -6.97559044e-02 3.38040650e-01 9.38536763e-01 -6.97559044e-02 3.41422319e-01 9.37313259e-01 -6.97559044e-02 3.44680905e-01 9.36112583e-01 -6.97559044e-02 3.47935498e-01 9.34904635e-01 -6.97559044e-02 3.51146519e-01 9.33703542e-01 -6.97559044e-02 3.54387343e-01 9.32485163e-01 -6.97559044e-02 3.57625157e-01 9.31257665e-01 -6.97559044e-02 3.60870898e-01 9.29995537e-01 -6.97559044e-02 3.64184588e-01 9.28704381e-01 -6.97559044e-02 3.67383003e-01 9.27443981e-01 -6.97559044e-02 3.70595843e-01 9.26163852e-01 -6.97559044e-02 3.73814940e-01 9.24870253e-01 -6.97559044e-02 3.77033055e-01 9.23562944e-01 -6.97559044e-02 3.80253285e-01 9.22240198e-01 -6.97559044e-02 3.83458227e-01 9.20913756e-01 -6.97559044e-02 3.86756510e-01 9.19533968e-01 -6.97559044e-02 3.89876664e-01 9.18214381e-01 -6.97559044e-02 3.93070161e-01 9.16849613e-01 -6.97559044e-02 3.96286696e-01 9.15466249e-01 -6.97559044e-02 3.99389058e-01 9.14120555e-01 -6.97559044e-02 4.02643532e-01 9.12689626e-01 -6.97559044e-02 4.05904502e-01 9.11244273e-01 -6.97559044e-02 4.09078568e-01 9.09822941e-01 -6.97559044e-02 4.12259400e-01 9.08386767e-01 -6.97559044e-02 4.15357649e-01 9.06972110e-01 -6.97559044e-02 4.18443948e-01 9.05552328e-01 -6.97559044e-02 4.21659470e-01 9.04061258e-01 -6.97559044e-02 4.24883068e-01 9.02549207e-01 -6.97559044e-02 4.28037852e-01 9.01058316e-01 -6.97559044e-02 4.31105316e-01 8.99593353e-01 -6.97559044e-02 4.34262812e-01 8.98077786e-01 -6.97559044e-02 4.37359720e-01 8.96574497e-01 -6.97559044e-02 4.40498978e-01 8.95032227e-01 -6.97559044e-02 4.43710834e-01 8.93445134e-01 -6.97559044e-02 4.46842253e-01 8.91883016e-01 -6.97559044e-02 4.49918807e-01 8.90336454e-01 -6.97559044e-02 4.52969551e-01 8.88788521e-01 -6.97559044e-02 4.56022561e-01 8.87225032e-01 -6.97559044e-02 4.59168822e-01 8.85598421e-01 -6.97559044e-02 4.62187707e-01 8.84030402e-01 -6.97559044e-02 4.65332717e-01 8.82377207e-01 -6.97559044e-02 4.68461394e-01 8.80720735e-01 -6.97559044e-02 4.71523553e-01 8.79085422e-01 -6.97559044e-02 4.74618554e-01 8.77417505e-01 -6.97559044e-02 4.77588475e-01 8.75807643e-01 -6.97559044e-02 4.80647117e-01 8.74130249e-01 -6.97559044e-02 4.83794749e-01 8.72389317e-01 -6.97559044e-02 4.86834794e-01 8.70697558e-01 -6.97559044e-02 4.89877909e-01 8.68991017e-01 -6.97559044e-02 4.92812723e-01 8.67328346e-01 -6.97559044e-02 4.95835781e-01 8.65604579e-01 -6.97559044e-02 4.98847038e-01 8.63874078e-01 -6.97559044e-02 5.01871109e-01 8.62119496e-01 -6.97559044e-02 5.04961610e-01 8.60312581e-01 -6.97559044e-02 5.07898271e-01 8.58581841e-01 -6.97559044e-02 5.10859489e-01 8.56823921e-01 -6.97559044e-02 5.13851881e-01 8.55032146e-01 -6.97559044e-02 5.16825259e-01 8.53236854e-01 -6.97559044e-02 5.19858420e-01 8.51394415e-01 -6.97559044e-02 5.22773504e-01 8.49605262e-01 -6.97559044e-02 5.25745451e-01 8.47773015e-01 -6.97559044e-02 5.28700650e-01 8.45932305e-01 -6.97559044e-02 5.31610012e-01 8.44105959e-01 -6.97559044e-02 5.34602284e-01 8.42213094e-01 -6.97559044e-02 5.37498832e-01 8.40367317e-01 -6.97559044e-02 5.40523171e-01 8.38425279e-01 -6.97559044e-02 5.43387532e-01 8.36572528e-01 -6.97559044e-02 5.46254158e-01 8.34701419e-01 -6.97559044e-02 5.49172163e-01 8.32785845e-01 -6.97559863e-02 5.51937163e-01 8.30956995e-01 -6.97559863e-02 5.54871678e-01 8.29000652e-01 -6.97561279e-02 5.57798564e-01 8.27036202e-01 -6.97563663e-02 5.60713708e-01 8.25062990e-01 -6.97564557e-02 5.63682377e-01 8.23041141e-01 -6.97564855e-02 5.66488326e-01 8.21111083e-01 -6.97564855e-02 5.69164574e-01 8.19258749e-01 -6.97564855e-02 5.71807981e-01 8.17415953e-01 -6.97564632e-02 5.75027645e-01 8.15153837e-01 -6.97564706e-02 5.78389645e-01 8.12771440e-01 -6.97564706e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.12001145e-01 6.98704898e-01 -6.97564632e-02 7.16002226e-01 6.94603980e-01 -6.97564557e-02 7.17992961e-01 6.92546189e-01 -6.97564855e-02 7.20212996e-01 6.90231681e-01 -6.97561875e-02 7.22595930e-01 6.87733829e-01 -6.97559863e-02 7.24837303e-01 6.85371816e-01 -6.97559863e-02 7.27267027e-01 6.82790995e-01 -6.97559863e-02 7.29722798e-01 6.80166423e-01 -6.97559863e-02 7.32052624e-01 6.77660286e-01 -6.97559714e-02 7.34342277e-01 6.75181270e-01 -6.97559044e-02 7.36656606e-01 6.72650218e-01 -6.97559044e-02 7.39067018e-01 6.70005143e-01 -6.97559044e-02 7.41448224e-01 6.67367578e-01 -6.97559044e-02 7.43774414e-01 6.64771497e-01 -6.97559044e-02 7.46036589e-01 6.62235439e-01 -6.97559044e-02 7.48291135e-01 6.59684837e-01 -6.97559044e-02 7.50603795e-01 6.57048702e-01 -6.97559044e-02 7.52930343e-01 6.54384792e-01 -6.97559044e-02 7.55232751e-01 6.51725948e-01 -6.97559044e-02 7.57517219e-01 6.49070442e-01 -6.97559044e-02 7.59707212e-01 6.46503150e-01 -6.97559044e-02 7.61956155e-01 6.43854380e-01 -6.97559044e-02 7.64203250e-01 6.41185164e-01 -6.97559044e-02 7.66478896e-01 6.38462484e-01 -6.97559044e-02 7.68755734e-01 6.35717332e-01 -6.97559044e-02 7.70920217e-01 6.33093476e-01 -6.97559044e-02 7.73118019e-01 6.30405128e-01 -6.97559044e-02 7.75353134e-01 6.27654731e-01 -6.97559044e-02 7.77552843e-01 6.24928474e-01 -6.97559044e-02 7.79682994e-01 6.22269392e-01 -6.97559044e-02 7.81773567e-01 6.19640172e-01 -6.97559044e-02 7.83988655e-01 6.16836131e-01 -6.97559044e-02 7.86194563e-01 6.14022315e-01 -6.97559044e-02 7.88345098e-01 6.11259043e-01 -6.97559044e-02 7.90435672e-01 6.08552694e-01 -6.97559267e-02 7.92482376e-01 6.05885029e-01 -6.97559044e-02 7.94640541e-01 6.03051901e-01 -6.97559044e-02 7.96802044e-01 6.00193083e-01 -6.97559044e-02 7.98897326e-01 5.97398102e-01 -6.97559044e-02 8.00933719e-01 5.94667196e-01 -6.97559044e-02 8.02927911e-01 5.91969669e-01 -6.97559044e-02 8.05037796e-01 5.89097917e-01 -6.97559044e-02 8.07154417e-01 5.86194813e-01 -6.97559044e-02 8.09206426e-01 5.83356082e-01 -6.97559044e-02 8.11238587e-01 5.80531299e-01 -6.97559044e-02 8.13190281e-01 5.77795148e-01 -6.97559267e-02 8.15155923e-01 5.75019836e-01 -6.97559044e-02 8.17165077e-01 5.72157741e-01 -6.97559044e-02 8.19193661e-01 5.69248199e-01 -6.97559044e-02 8.21220040e-01 5.66325247e-01 -6.97559267e-02 8.23135912e-01 5.63533723e-01 -6.97559044e-02 8.25137377e-01 5.60599089e-01 -6.97559044e-02 8.27099085e-01 5.57700574e-01 -6.97559044e-02 8.28996062e-01 5.54875255e-01 -6.97559044e-02 8.30934346e-01 5.51970363e-01 -6.97559044e-02 8.32822442e-01 5.49118280e-01 -6.97559044e-02 8.34786713e-01 5.46125233e-01 -6.97559044e-02 8.36746931e-01 5.43118536e-01 -6.97559044e-02 8.38582993e-01 5.40277898e-01 -6.97559044e-02 8.40408802e-01 5.37436008e-01 -6.97559044e-02 8.42271507e-01 5.34508407e-01 -6.97559044e-02 8.44218194e-01 5.31432569e-01 -6.97559044e-02 8.46134424e-01 5.28374970e-01 -6.97559044e-02 8.47955942e-01 5.25447965e-01 -6.97559044e-02 8.49722326e-01 5.22582889e-01 -6.97559044e-02 8.51507664e-01 5.19674003e-01 -6.97559044e-02 8.53319228e-01 5.16691446e-01 -6.97559044e-02 8.55111957e-01 5.13718605e-01 -6.97559044e-02 8.56945753e-01 5.10653913e-01 -6.97559044e-02 8.58769953e-01 5.07578969e-01 -6.97559044e-02 8.60497892e-01 5.04646361e-01 -6.97559044e-02 8.62238228e-01 5.01666665e-01 -6.97559044e-02 8.64000261e-01 4.98628289e-01 -6.97559267e-02 8.65724564e-01 4.95625168e-01 -6.97559044e-02 8.67468119e-01 4.92564380e-01 -6.97559044e-02 8.69140804e-01 4.89614367e-01 -6.97559044e-02 8.70871723e-01 4.86522466e-01 -6.97559044e-02 8.72567117e-01 4.83472973e-01 -6.97559044e-02 8.74255419e-01 4.80419070e-01 -6.97559044e-02 8.75912011e-01 4.77394462e-01 -6.97559267e-02 8.77546608e-01 4.74378407e-01 -6.97559044e-02 8.79220247e-01 4.71271932e-01 -6.97559044e-02 8.80914807e-01 4.68097806e-01 -6.97559044e-02 8.82553577e-01 4.65000629e-01 -6.97559044e-02 8.84119570e-01 4.62015659e-01 -6.97559044e-02 8.85673165e-01 4.59025949e-01 -6.97559044e-02 8.87310565e-01 4.55856085e-01 -6.97559044e-02 8.88949513e-01 4.52650100e-01 -6.97559044e-02 8.90521705e-01 4.49550927e-01 -6.97559044e-02 8.92087579e-01 4.46435481e-01 -6.97559044e-02 8.93612266e-01 4.43374336e-01 -6.97559044e-02 8.95135641e-01 4.40290838e-01 -6.97559044e-02 8.96679223e-01 4.37142313e-01 -6.97559044e-02 8.98193777e-01 4.34020549e-01 -6.97559044e-02 8.99746180e-01 4.30790842e-01 -6.97559044e-02 9.01196361e-01 4.27749813e-01 -6.97559044e-02 9.02682722e-01 4.24600720e-01 -6.97559044e-02 9.04165983e-01 4.21436578e-01 -6.97559044e-02 9.05623674e-01 4.18294102e-01 -6.97559044e-02 9.07118917e-01 4.15037155e-01 -6.97559044e-02 9.08534288e-01 4.11932528e-01 -6.97559267e-02 9.09945488e-01 4.08808380e-01 -6.97559044e-02 9.11385834e-01 4.05585051e-01 -6.97559044e-02 9.12784517e-01 4.02427793e-01 -6.97559044e-02 9.14190233e-01 3.99228573e-01 -6.97559044e-02 9.15549457e-01 3.96095991e-01 -6.97559044e-02 9.16954935e-01 3.92824590e-01 -6.97559044e-02 9.18361008e-01 3.89533520e-01 -6.97559044e-02 9.19706345e-01 3.86346370e-01 -6.97559044e-02 9.21015024e-01 3.83215249e-01 -6.97559044e-02 9.22313094e-01 3.80076975e-01 -6.97559044e-02 9.23666596e-01 3.76778305e-01 -6.97559044e-02 9.25022185e-01 3.73441637e-01 -6.97559044e-02 9.26318765e-01 3.70210528e-01 -6.97559044e-02 9.27576423e-01 3.67054641e-01 -6.97559044e-02 9.28806424e-01 3.63930345e-01 -6.97559044e-02 9.30092871e-01 3.60614747e-01 -6.97559044e-02 9.31370139e-01 3.57329577e-01 -6.97559044e-02 9.32590902e-01 3.54104728e-01 -6.97559044e-02 9.33856428e-01 3.50739837e-01 -6.97559044e-02 9.35048640e-01 3.47545475e-01 -6.97559044e-02 9.36250806e-01 3.44310254e-01 -6.97559044e-02 9.37461734e-01 3.41021448e-01 -6.97559044e-02 9.38629627e-01 3.37782919e-01 -6.97559044e-02 9.39836919e-01 3.34413797e-01 -6.97559044e-02 9.40978825e-01 3.31186324e-01 -6.97559044e-02 9.42116141e-01 3.27933580e-01 -6.97559044e-02 9.43282843e-01 3.24566245e-01 -6.97559044e-02 9.44400012e-01 3.21295589e-01 -6.97559044e-02 9.45499480e-01 3.18051189e-01 -6.97559044e-02 9.46578383e-01 3.14820886e-01 -6.97559044e-02 9.47699606e-01 3.11431050e-01 -6.97559044e-02 9.48806405e-01 3.08044255e-01 -6.97559044e-02 9.49871957e-01 3.04742485e-01 -6.97559044e-02 9.50912774e-01 3.01478773e-01 -6.97559044e-02 9.51923668e-01 2.98270524e-01 -6.97559044e-02 9.52986836e-01 2.94854522e-01 -6.97559044e-02 9.54040766e-01 2.91423410e-01 -6.97559044e-02 9.55044985e-01 2.88118005e-01 -6.97559044e-02 9.56020653e-01 2.84861565e-01 -6.97559044e-02 9.56984162e-01 2.81612635e-01 -6.97559044e-02 9.57990050e-01 2.78174490e-01 -6.97559044e-02 9.58950937e-01 2.74837911e-01 -6.97559044e-02 9.59908664e-01 2.71478236e-01 -6.97559044e-02 9.60865438e-01 2.68071085e-01 -6.97559044e-02 9.61774468e-01 2.64789194e-01 -6.97559044e-02 9.62689042e-01 2.61450291e-01 -6.97559044e-02 9.63628054e-01 2.57961363e-01 -6.97559044e-02 9.64515507e-01 2.54627943e-01 -6.97559044e-02 9.65397537e-01 2.51261413e-01 -6.97559044e-02 9.66255188e-01 2.47948602e-01 -6.97559044e-02 9.67103124e-01 2.44605079e-01 -6.97559044e-02 9.67960715e-01 2.41197437e-01 -6.97559044e-02 9.68793929e-01 2.37832099e-01 -6.97559044e-02 9.69621181e-01 2.34439477e-01 -6.97559044e-02 9.70409572e-01 2.31156379e-01 -6.97559044e-02 9.71227586e-01 2.27695957e-01 -6.97559044e-02 9.72032011e-01 2.24224418e-01 -6.97559044e-02 9.72813129e-01 2.20813334e-01 -6.97559044e-02 9.73584116e-01 2.17394426e-01 -6.97559044e-02 9.74313796e-01 2.14085340e-01 -6.97559044e-02 9.75052893e-01 2.10696727e-01 -6.97559044e-02 9.75804269e-01 2.07193747e-01 -6.97559044e-02 9.76518869e-01 2.03808889e-01 -6.97559044e-02 9.77226615e-01 2.00384423e-01 -6.97559044e-02 9.77905154e-01 1.97043270e-01 -6.97559044e-02 9.78575289e-01 1.93674654e-01 -6.97559044e-02 9.79256809e-01 1.90213159e-01 -6.97559044e-02 9.79905903e-01 1.86830863e-01 -6.97559044e-02 9.80569303e-01 1.83320969e-01 -6.97559044e-02 9.81186450e-01 1.79977491e-01 -6.97559044e-02 9.81816113e-01 1.76551372e-01 -6.97559044e-02 9.82439280e-01 1.73046723e-01 -6.97559044e-02 9.83029366e-01 1.69635102e-01 -6.97559044e-02 9.83606875e-01 1.66258365e-01 -6.97559044e-02 9.84166503e-01 1.62909225e-01 -6.97559044e-02 9.84739721e-01 1.59404472e-01 -6.97559044e-02 9.85307097e-01 1.55860856e-01 -6.97559044e-02 9.85842228e-01 1.52435511e-01 -6.97559044e-02 9.86357927e-01 1.49061829e-01 -6.97559044e-02 9.86858070e-01 1.45718455e-01 -6.97559044e-02 9.87370312e-01 1.42205000e-01 -6.97559044e-02 9.87876475e-01 1.38650522e-01 -6.97559044e-02 9.88352954e-01 1.35220781e-01 -6.97559044e-02 9.88817990e-01 1.31770507e-01 -6.97559044e-02 9.89265680e-01 1.28365412e-01 -6.97559044e-02 9.89704013e-01 1.24938332e-01 -6.97559044e-02 9.90145087e-01 1.21389441e-01 -6.97559044e-02 9.90563214e-01 1.17919959e-01 -6.97559044e-02 9.90968049e-01 1.14475153e-01 -6.97559044e-02 9.91352320e-01 1.11103907e-01 -6.97559044e-02 9.91734207e-01 1.07630908e-01 -6.97559044e-02 9.92105186e-01 1.04169212e-01 -6.97559044e-02 9.92457509e-01 1.00735731e-01 -6.97559044e-02 9.92815912e-01 9.71560776e-02 -6.97559044e-02 9.93139923e-01 9.37939957e-02 -6.97559044e-02 9.93460655e-01 9.03329998e-02 -6.97559044e-02 9.93771315e-01 8.68564695e-02 -6.97559044e-02 9.94067967e-01 8.33702385e-02 -6.97559044e-02 9.94354844e-01 7.98863545e-02 -6.97559044e-02 9.94625688e-01 7.64367059e-02 -6.97559044e-02 9.94894028e-01 7.28565603e-02 -6.97559044e-02 9.95141983e-01 6.93712160e-02 -6.97559044e-02 9.95379210e-01 6.59077540e-02 -6.97559044e-02 9.95597124e-01 6.25094622e-02 -6.97559044e-02 9.95802641e-01 5.91391288e-02 -6.97559044e-02 9.96010423e-01 5.55689409e-02 -6.97559044e-02 9.96203542e-01 5.19784614e-02 -6.97559044e-02 9.96379018e-01 4.85126153e-02 -6.97559044e-02 9.96536434e-01 4.51338738e-02 -6.97559044e-02 9.96684253e-01 4.17755544e-02 -6.97559044e-02 9.96823072e-01 3.82919423e-02 -6.97559044e-02 9.96950924e-01 3.48049626e-02 -6.97559044e-02 9.97070670e-01 3.11989076e-02 -6.97559044e-02 9.97177422e-01 2.76085474e-02 -6.97559044e-02 9.97267187e-01 2.42443308e-02 -6.97559044e-02 9.97337639e-01 2.08686031e-02 -6.97559044e-02 9.97412384e-01 1.73841584e-02 -6.97559044e-02 9.97456491e-01 1.39026698e-02 -6.97559044e-02 9.97505784e-01 1.03932573e-02 -6.97559044e-02 9.97541308e-01 6.93720533e-03 -6.97559044e-02 9.97558117e-01 3.36034922e-03 -6.97559044e-02 9.97559190e-01 -1.30766333e-04 -6.97559044e-02 9.97557878e-01 -3.59895336e-03 -6.97559044e-02 9.97539163e-01 -7.11059524e-03 -6.97559044e-02 9.97504830e-01 -1.04796737e-02 -6.97559044e-02 9.97454166e-01 -1.40317092e-02 -6.97559044e-02 9.97407854e-01 -1.76294986e-02 -6.97559044e-02 9.97334957e-01 -2.10263077e-02 -6.97559044e-02 9.97259140e-01 -2.45150719e-02 -6.97559044e-02 9.97165859e-01 -2.80102212e-02 -6.97559044e-02 9.97062564e-01 -3.14619057e-02 -6.97559044e-02 9.96947289e-01 -3.49535644e-02 -6.97559044e-02 9.96820748e-01 -3.83496694e-02 -6.97559044e-02 9.96682644e-01 -4.18198407e-02 -6.97559044e-02 9.96526361e-01 -4.53602821e-02 -6.97559044e-02 9.96358454e-01 -4.89493385e-02 -6.97559044e-02 9.96177971e-01 -5.24268784e-02 -6.97559044e-02 9.95994270e-01 -5.58363311e-02 -6.97559044e-02 9.95798767e-01 -5.92117012e-02 -6.97559044e-02 9.95585978e-01 -6.26761466e-02 -6.97559044e-02 9.95358229e-01 -6.62316829e-02 -6.97559044e-02 9.95113432e-01 -6.97845295e-02 -6.97559044e-02 9.94866490e-01 -7.32573494e-02 -6.97559044e-02 9.94608402e-01 -7.66629726e-02 -6.97559044e-02 9.94340539e-01 -8.00597668e-02 -6.97559044e-02 9.94054735e-01 -8.35283473e-02 -6.97559044e-02 9.93751526e-01 -8.70693102e-02 -6.97559044e-02 9.93439794e-01 -9.05535817e-02 -6.97559044e-02 9.93127942e-01 -9.39224362e-02 -6.97559044e-02 9.92794037e-01 -9.73851606e-02 -6.97559044e-02 9.92436290e-01 -1.00955859e-01 -6.97559044e-02 9.92079973e-01 -1.04407057e-01 -6.97559044e-02 9.91709828e-01 -1.07856080e-01 -6.97559044e-02 9.91328239e-01 -1.11326285e-01 -6.97559044e-02 9.90945339e-01 -1.14669427e-01 -6.97559044e-02 9.90527093e-01 -1.18238010e-01 -6.97559044e-02 9.90107656e-01 -1.21698052e-01 -6.97559044e-02 9.89678621e-01 -1.25155270e-01 -6.97559044e-02 9.89219427e-01 -1.28706574e-01 -6.97559044e-02 9.88774776e-01 -1.32087931e-01 -6.97559044e-02 9.88313913e-01 -1.35504052e-01 -6.97559044e-02 9.87820804e-01 -1.39048502e-01 -6.97559044e-02 9.87339258e-01 -1.42425269e-01 -6.97559044e-02 9.86837626e-01 -1.45856723e-01 -6.97559044e-02 9.86324012e-01 -1.49290740e-01 -6.97559044e-02 9.85795915e-01 -1.52731344e-01 -6.97559044e-02 9.85254228e-01 -1.56192571e-01 -6.97559044e-02 9.84711230e-01 -1.59584358e-01 -6.97559044e-02 9.84152675e-01 -1.62999198e-01 -6.97559044e-02 9.83570337e-01 -1.66477963e-01 -6.97559044e-02 9.82965589e-01 -1.69995084e-01 -6.97559044e-02 9.82373238e-01 -1.73417881e-01 -6.97559044e-02 9.81773734e-01 -1.76776335e-01 -6.97559044e-02 9.81159329e-01 -1.80127650e-01 -6.97559044e-02 9.80527878e-01 -1.83550775e-01 -6.97559044e-02 9.79871929e-01 -1.87010705e-01 -6.97559044e-02 9.79192495e-01 -1.90537915e-01 -6.97559044e-02 9.78521109e-01 -1.93958387e-01 -6.97559044e-02 9.77854311e-01 -1.97291926e-01 -6.97559044e-02 9.77178514e-01 -2.00614214e-01 -6.97559044e-02 9.76474166e-01 -2.04016685e-01 -6.97559044e-02 9.75737572e-01 -2.07514822e-01 -6.97559044e-02 9.75003719e-01 -2.10933223e-01 -6.97559044e-02 9.74276245e-01 -2.14259461e-01 -6.97559044e-02 9.73520398e-01 -2.17679590e-01 -6.97559044e-02 9.72749531e-01 -2.21087664e-01 -6.97559044e-02 9.71964598e-01 -2.24521056e-01 -6.97559044e-02 9.71176744e-01 -2.27912530e-01 -6.97559044e-02 9.70373511e-01 -2.31305152e-01 -6.97559044e-02 9.69590783e-01 -2.34568059e-01 -6.97559044e-02 9.68737721e-01 -2.38056108e-01 -6.97559044e-02 9.67902422e-01 -2.41429299e-01 -6.97559044e-02 9.67044115e-01 -2.44839042e-01 -6.97559044e-02 9.66159225e-01 -2.48313323e-01 -6.97559044e-02 9.65313494e-01 -2.51581371e-01 -6.97559044e-02 9.64434862e-01 -2.54937738e-01 -6.97559044e-02 9.63537097e-01 -2.58306265e-01 -6.97559044e-02 9.62658405e-01 -2.61562198e-01 -6.97559044e-02 9.61717069e-01 -2.64994591e-01 -6.97559044e-02 9.60775673e-01 -2.68399119e-01 -6.97559044e-02 9.59835589e-01 -2.71734029e-01 -6.97559044e-02 9.58853304e-01 -2.75174648e-01 -6.97559044e-02 9.57914472e-01 -2.78429240e-01 -6.97559044e-02 9.56964910e-01 -2.81676054e-01 -6.97559044e-02 9.55949783e-01 -2.85105854e-01 -6.97559044e-02 9.54930365e-01 -2.88491577e-01 -6.97559044e-02 9.53919888e-01 -2.91823357e-01 -6.97559044e-02 9.52914596e-01 -2.95093507e-01 -6.97559044e-02 9.51905012e-01 -2.98330754e-01 -6.97559044e-02 9.50860679e-01 -3.01643342e-01 -6.97559044e-02 9.49768901e-01 -3.05060834e-01 -6.97559044e-02 9.48666096e-01 -3.08472097e-01 -6.97559044e-02 9.47582543e-01 -3.11786890e-01 -6.97559044e-02 9.46515679e-01 -3.15011859e-01 -6.97559044e-02 9.45446610e-01 -3.18205982e-01 -6.97559044e-02 9.44329321e-01 -3.21506470e-01 -6.97559044e-02 9.43176150e-01 -3.24872136e-01 -6.97559044e-02 9.42021728e-01 -3.28204393e-01 -6.97559044e-02 9.40905809e-01 -3.31392050e-01 -6.97559044e-02 9.39746380e-01 -3.34663093e-01 -6.97559044e-02 9.38547730e-01 -3.38012397e-01 -6.97559044e-02 9.37352777e-01 -3.41317147e-01 -6.97559044e-02 9.36154306e-01 -3.44572961e-01 -6.97559044e-02 9.34935391e-01 -3.47851127e-01 -6.97559044e-02 9.33754861e-01 -3.51013899e-01 -6.97559044e-02 9.32527900e-01 -3.54272693e-01 -6.97559044e-02 9.31289792e-01 -3.57534975e-01 -6.97559044e-02 9.30023253e-01 -3.60798687e-01 -6.97559044e-02 9.28738177e-01 -3.64105046e-01 -6.97559044e-02 9.27459359e-01 -3.67344916e-01 -6.97559044e-02 9.26182032e-01 -3.70551378e-01 -6.97559044e-02 9.24871981e-01 -3.73809755e-01 -6.97559044e-02 9.23601389e-01 -3.76940459e-01 -6.97559044e-02 9.22246575e-01 -3.80239725e-01 -6.97559044e-02 9.20905650e-01 -3.83478642e-01 -6.97559044e-02 9.19564068e-01 -3.86686355e-01 -6.97559044e-02 9.18170333e-01 -3.89978051e-01 -6.97559044e-02 9.16832447e-01 -3.93113434e-01 -6.97559044e-02 9.15510535e-01 -3.96185994e-01 -6.97559044e-02 9.14085329e-01 -3.99468452e-01 -6.97559044e-02 9.12626266e-01 -4.02786821e-01 -6.97559044e-02 9.11212623e-01 -4.05974746e-01 -6.97559044e-02 9.09809470e-01 -4.09111142e-01 -6.97559044e-02 9.08405721e-01 -4.12216038e-01 -6.97559044e-02 9.06997800e-01 -4.15300548e-01 -6.97559044e-02 9.05514777e-01 -4.18526262e-01 -6.97559044e-02 9.04003143e-01 -4.21780765e-01 -6.97559044e-02 9.02507603e-01 -4.24973160e-01 -6.97559044e-02 9.01063681e-01 -4.28027123e-01 -6.97559044e-02 8.99626374e-01 -4.31036979e-01 -6.97559044e-02 8.98104727e-01 -4.34206277e-01 -6.97559044e-02 8.96559119e-01 -4.37388629e-01 -6.97559044e-02 8.94975066e-01 -4.40616250e-01 -6.97559044e-02 8.93441498e-01 -4.43717510e-01 -6.97559044e-02 8.91905248e-01 -4.46797580e-01 -6.97559044e-02 8.90396297e-01 -4.49800074e-01 -6.97559044e-02 8.88815701e-01 -4.52915460e-01 -6.97559044e-02 8.87196422e-01 -4.56077218e-01 -6.97559044e-02 8.85573924e-01 -4.59217250e-01 -6.97559044e-02 8.83978367e-01 -4.62285995e-01 -6.97559044e-02 8.82371306e-01 -4.65346396e-01 -6.97559044e-02 8.80773127e-01 -4.68360275e-01 -6.97559044e-02 8.79138947e-01 -4.71423805e-01 -6.97559044e-02 8.77431750e-01 -4.74591255e-01 -6.97559044e-02 8.75769436e-01 -4.77656901e-01 -6.97559044e-02 8.74145627e-01 -4.80618000e-01 -6.97559044e-02 8.72468650e-01 -4.83652174e-01 -6.97559044e-02 8.70734334e-01 -4.86769319e-01 -6.97559044e-02 8.69025588e-01 -4.89815861e-01 -6.97559044e-02 8.67306530e-01 -4.92851645e-01 -6.97559044e-02 8.65586877e-01 -4.95869100e-01 -6.97559044e-02 8.63858759e-01 -4.98870492e-01 -6.97559044e-02 8.62103879e-01 -5.01898289e-01 -6.97559044e-02 8.60386670e-01 -5.04836559e-01 -6.97559044e-02 8.58604014e-01 -5.07861495e-01 -6.97559044e-02 8.56804252e-01 -5.10891497e-01 -6.97559044e-02 8.55000436e-01 -5.13904035e-01 -6.97559044e-02 8.53165448e-01 -5.16942501e-01 -6.97559044e-02 8.51395786e-01 -5.19857526e-01 -6.97559044e-02 8.49630535e-01 -5.22733212e-01 -6.97559044e-02 8.47805381e-01 -5.25692523e-01 -6.97559044e-02 8.45916688e-01 -5.28722525e-01 -6.97559044e-02 8.44029963e-01 -5.31731248e-01 -6.97559044e-02 8.42209697e-01 -5.34607291e-01 -6.97559044e-02 8.40380251e-01 -5.37478447e-01 -6.97559044e-02 8.38445842e-01 -5.40491641e-01 -6.97559044e-02 8.36511731e-01 -5.43480873e-01 -6.97559044e-02 8.34613085e-01 -5.46389699e-01 -6.97559044e-02 8.32701445e-01 -5.49302757e-01 -6.97559044e-02 8.30815434e-01 -5.52145541e-01 -6.97559044e-02 8.28936279e-01 -5.54965198e-01 -6.97559044e-02 8.27010274e-01 -5.57837188e-01 -6.97559044e-02 8.25006306e-01 -5.60789704e-01 -6.97559044e-02 8.22970927e-01 -5.63776553e-01 -6.97559044e-02 8.21040809e-01 -5.66585720e-01 -6.97559044e-02 8.19094300e-01 -5.69392800e-01 -6.97559044e-02 8.17116201e-01 -5.72227657e-01 -6.97559044e-02 8.15098822e-01 -5.75100720e-01 -6.97559044e-02 8.13072145e-01 -5.77959478e-01 -6.97559044e-02 8.11042786e-01 -5.80806136e-01 -6.97559044e-02 8.09045255e-01 -5.83579123e-01 -6.97559044e-02 8.06965649e-01 -5.86455405e-01 -6.97559044e-02 8.04877102e-01 -5.89317858e-01 -6.97559044e-02 8.02800059e-01 -5.92144966e-01 -6.97559044e-02 8.00718367e-01 -5.94956517e-01 -6.97559044e-02 7.98698843e-01 -5.97663999e-01 -6.97559044e-02 7.96625912e-01 -6.00425899e-01 -6.97559044e-02 7.94519544e-01 -6.03210390e-01 -6.97559044e-02 7.92402744e-01 -6.05988026e-01 -6.97559044e-02 7.90274501e-01 -6.08760595e-01 -6.97559044e-02 7.88217545e-01 -6.11421227e-01 -6.97559044e-02 7.86029220e-01 -6.14231348e-01 -6.97559044e-02 7.83812702e-01 -6.17058396e-01 -6.97559044e-02 7.81703711e-01 -6.19726360e-01 -6.97559044e-02 7.79597461e-01 -6.22377694e-01 -6.97559044e-02 7.77373612e-01 -6.25151694e-01 -6.97559044e-02 7.75130332e-01 -6.27932489e-01 -6.97559044e-02 7.72969961e-01 -6.30585372e-01 -6.97559044e-02 7.70830214e-01 -6.33201420e-01 -6.97559044e-02 7.68619895e-01 -6.35883868e-01 -6.97559044e-02 7.66399562e-01 -6.38557911e-01 -6.97559044e-02 7.64171779e-01 -6.41221821e-01 -6.97559044e-02 7.61874795e-01 -6.43948436e-01 -6.97559044e-02 7.59618878e-01 -6.46608353e-01 -6.97559044e-02 7.57417142e-01 -6.49185717e-01 -6.97559044e-02 7.55145133e-01 -6.51828527e-01 -6.97559044e-02 7.52838373e-01 -6.54492199e-01 -6.97559044e-02 7.50485122e-01 -6.57187402e-01 -6.97559044e-02 7.48150110e-01 -6.59844160e-01 -6.97559044e-02 7.45897830e-01 -6.62390053e-01 -6.97559044e-02 7.43655562e-01 -6.64906800e-01 -6.97559044e-02 7.41271257e-01 -6.67563081e-01 -6.97559044e-02 7.38938093e-01 -6.70147479e-01 -6.97559044e-02 7.36590743e-01 -6.72723353e-01 -6.97559044e-02 7.34227955e-01 -6.75303936e-01 -6.97559044e-02 7.31954992e-01 -6.77765369e-01 -6.97559044e-02 7.29580343e-01 -6.80318654e-01 -6.97559044e-02 7.27142274e-01 -6.82924271e-01 -6.97559044e-02 7.24734545e-01 -6.85479105e-01 -6.97559044e-02 7.22321451e-01 -6.88024998e-01 -6.97559044e-02 7.19918311e-01 -6.90531552e-01 -6.97559044e-02 7.17545807e-01 -6.93011940e-01 -6.97559044e-02 7.15119660e-01 -6.95510626e-01 -6.97559640e-02 7.12875664e-01 -6.97808683e-01 -6.97559863e-02 7.10530043e-01 -7.00196087e-01 -6.97562397e-02 7.08222508e-01 -7.02533484e-01 -6.97564855e-02 7.05630183e-01 -7.05137730e-01 -6.97564706e-02 7.02794075e-01 -7.07964718e-01 -6.97564632e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.65390110e-01 -8.21868896e-01 -6.97564632e-02 5.63182354e-01 -8.23380411e-01 -6.97564855e-02 5.60514748e-01 -8.25195134e-01 -6.97560683e-02 5.57771444e-01 -8.27052474e-01 -6.97559863e-02 5.54851115e-01 -8.29014063e-01 -6.97559863e-02 5.51883161e-01 -8.30991268e-01 -6.97559863e-02 5.48970938e-01 -8.32918704e-01 -6.97559714e-02 5.46178758e-01 -8.34752023e-01 -6.97559267e-02 5.43275476e-01 -8.36645067e-01 -6.97559044e-02 5.40369630e-01 -8.38524997e-01 -6.97559044e-02 5.37451208e-01 -8.40396106e-01 -6.97559044e-02 5.34513056e-01 -8.42269003e-01 -6.97559044e-02 5.31571209e-01 -8.44132185e-01 -6.97559044e-02 5.28638542e-01 -8.45967174e-01 -6.97559044e-02 5.25674462e-01 -8.47817183e-01 -6.97559044e-02 5.22706032e-01 -8.49646747e-01 -6.97559044e-02 5.19748092e-01 -8.51463437e-01 -6.97559044e-02 5.16777158e-01 -8.53266418e-01 -6.97559044e-02 5.13796866e-01 -8.55065942e-01 -6.97559044e-02 5.10723710e-01 -8.56904328e-01 -6.97559044e-02 5.07704914e-01 -8.58696222e-01 -6.97559044e-02 5.04808068e-01 -8.60402882e-01 -6.97559044e-02 5.01791298e-01 -8.62164438e-01 -6.97559044e-02 4.98693854e-01 -8.63961339e-01 -6.97559044e-02 4.95658904e-01 -8.65706086e-01 -6.97559044e-02 4.92727399e-01 -8.67375910e-01 -6.97559044e-02 4.89700466e-01 -8.69093180e-01 -6.97559044e-02 4.86667514e-01 -8.70791495e-01 -6.97559044e-02 4.83641565e-01 -8.72473598e-01 -6.97559044e-02 4.80579197e-01 -8.74168217e-01 -6.97559044e-02 4.77519959e-01 -8.75842929e-01 -6.97559044e-02 4.74440575e-01 -8.77512336e-01 -6.97559044e-02 4.71382648e-01 -8.79159212e-01 -6.97559044e-02 4.68307227e-01 -8.80800903e-01 -6.97559044e-02 4.65239316e-01 -8.82427871e-01 -6.97559044e-02 4.62084204e-01 -8.84081304e-01 -6.97559044e-02 4.58973825e-01 -8.85700643e-01 -6.97559044e-02 4.55969542e-01 -8.87252748e-01 -6.97559044e-02 4.52875257e-01 -8.88835430e-01 -6.97559044e-02 4.49761599e-01 -8.90414953e-01 -6.97559044e-02 4.46643591e-01 -8.91981661e-01 -6.97559044e-02 4.43532914e-01 -8.93533826e-01 -6.97559044e-02 4.40411329e-01 -8.95076632e-01 -6.97559044e-02 4.37264562e-01 -8.96618426e-01 -6.97559044e-02 4.34129328e-01 -8.98141205e-01 -6.97559044e-02 4.31006491e-01 -8.99641097e-01 -6.97559044e-02 4.27757025e-01 -9.01190281e-01 -6.97559044e-02 4.24588174e-01 -9.02689338e-01 -6.97559044e-02 4.21469182e-01 -9.04149473e-01 -6.97559044e-02 4.18280214e-01 -9.05629396e-01 -6.97559044e-02 4.15229142e-01 -9.07031417e-01 -6.97559044e-02 4.12059635e-01 -9.08477604e-01 -6.97559044e-02 4.08873200e-01 -9.09915864e-01 -6.97559044e-02 4.05616343e-01 -9.11372304e-01 -6.97559044e-02 4.02400821e-01 -9.12796080e-01 -6.97559044e-02 3.99328679e-01 -9.14145827e-01 -6.97559044e-02 3.96141380e-01 -9.15529549e-01 -6.97559044e-02 3.92930776e-01 -9.16909456e-01 -6.97559044e-02 3.89687508e-01 -9.18294966e-01 -6.97559044e-02 3.86486083e-01 -9.19648886e-01 -6.97559044e-02 3.83304119e-01 -9.20978665e-01 -6.97559044e-02 3.80064726e-01 -9.22319174e-01 -6.97559044e-02 3.76906365e-01 -9.23615873e-01 -6.97559044e-02 3.73666376e-01 -9.24930513e-01 -6.97559044e-02 3.70350152e-01 -9.26262677e-01 -6.97559044e-02 3.67083788e-01 -9.27563846e-01 -6.97559044e-02 3.63928229e-01 -9.28807318e-01 -6.97559044e-02 3.60693395e-01 -9.30060744e-01 -6.97559044e-02 3.57445806e-01 -9.31323171e-01 -6.97559044e-02 3.54175419e-01 -9.32564378e-01 -6.97559044e-02 3.50928843e-01 -9.33786809e-01 -6.97559044e-02 3.47655594e-01 -9.35009062e-01 -6.97559044e-02 3.44319135e-01 -9.36248124e-01 -6.97559044e-02 3.41044337e-01 -9.37452734e-01 -6.97559044e-02 3.37796748e-01 -9.38624799e-01 -6.97559044e-02 3.34506303e-01 -9.39804375e-01 -6.97559044e-02 3.31213325e-01 -9.40968275e-01 -6.97559044e-02 3.27920109e-01 -9.42119956e-01 -6.97559044e-02 3.24645728e-01 -9.43254530e-01 -6.97559044e-02 3.21341127e-01 -9.44383681e-01 -6.97559044e-02 3.18125784e-01 -9.45474148e-01 -6.97559044e-02 3.14811349e-01 -9.46581244e-01 -6.97559044e-02 3.11495423e-01 -9.47677314e-01 -6.97559044e-02 3.08207721e-01 -9.48751986e-01 -6.97559044e-02 3.04887235e-01 -9.49825883e-01 -6.97559044e-02 3.01596761e-01 -9.50874329e-01 -6.97559044e-02 2.98271149e-01 -9.51923668e-01 -6.97559044e-02 2.94938505e-01 -9.52961624e-01 -6.97559044e-02 2.91619539e-01 -9.53982532e-01 -6.97559044e-02 2.88225800e-01 -9.55010653e-01 -6.97559044e-02 2.84872502e-01 -9.56018031e-01 -6.97559044e-02 2.81608641e-01 -9.56985354e-01 -6.97559044e-02 2.78179556e-01 -9.57987905e-01 -6.97559044e-02 2.74757504e-01 -9.58974361e-01 -6.97559044e-02 2.71397650e-01 -9.59930956e-01 -6.97559044e-02 2.68164963e-01 -9.60840106e-01 -6.97559044e-02 2.64910996e-01 -9.61741269e-01 -6.97559044e-02 2.61539370e-01 -9.62666094e-01 -6.97559044e-02 2.58181810e-01 -9.63568509e-01 -6.97559044e-02 2.54739225e-01 -9.64484870e-01 -6.97559044e-02 2.51346231e-01 -9.65376616e-01 -6.97559044e-02 2.47979298e-01 -9.66244459e-01 -6.97559044e-02 2.44588852e-01 -9.67107892e-01 -6.97559044e-02 2.41248205e-01 -9.67946231e-01 -6.97559044e-02 2.37833276e-01 -9.68793392e-01 -6.97559044e-02 2.34542891e-01 -9.69596148e-01 -6.97559044e-02 2.31127068e-01 -9.70416725e-01 -6.97559044e-02 2.27732077e-01 -9.71218646e-01 -6.97559044e-02 2.24382475e-01 -9.71997738e-01 -6.97559044e-02 2.20866367e-01 -9.72800374e-01 -6.97559044e-02 2.17469543e-01 -9.73567307e-01 -6.97559044e-02 2.14161560e-01 -9.74298179e-01 -6.97559044e-02 2.10740954e-01 -9.75044608e-01 -6.97559044e-02 2.07359150e-01 -9.75769639e-01 -6.97559044e-02 2.03872576e-01 -9.76505160e-01 -6.97559044e-02 2.00435877e-01 -9.77216482e-01 -6.97559044e-02 1.97120607e-01 -9.77889240e-01 -6.97559044e-02 1.93702459e-01 -9.78571832e-01 -6.97559044e-02 1.90286830e-01 -9.79242384e-01 -6.97559044e-02 1.86784133e-01 -9.79914904e-01 -6.97559044e-02 1.83357060e-01 -9.80562806e-01 -6.97559044e-02 1.79945901e-01 -9.81192827e-01 -6.97559044e-02 1.76496685e-01 -9.81826007e-01 -6.97559044e-02 1.73182324e-01 -9.82414901e-01 -6.97559044e-02 1.69754162e-01 -9.83007550e-01 -6.97559044e-02 1.66330650e-01 -9.83595133e-01 -6.97559044e-02 1.62891880e-01 -9.84168589e-01 -6.97559044e-02 1.59459367e-01 -9.84731138e-01 -6.97559044e-02 1.56031534e-01 -9.85281229e-01 -6.97559044e-02 1.52599186e-01 -9.85818326e-01 -6.97559044e-02 1.49140030e-01 -9.86345172e-01 -6.97559044e-02 1.45650133e-01 -9.86867726e-01 -6.97559044e-02 1.42210856e-01 -9.87368047e-01 -6.97559044e-02 1.38806522e-01 -9.87853289e-01 -6.97559044e-02 1.35260001e-01 -9.88346338e-01 -6.97559044e-02 1.31792888e-01 -9.88813639e-01 -6.97559044e-02 1.28418818e-01 -9.89258647e-01 -6.97559044e-02 1.24979205e-01 -9.89699841e-01 -6.97559044e-02 1.21527918e-01 -9.90127742e-01 -6.97559044e-02 1.17965095e-01 -9.90559101e-01 -6.97559044e-02 1.14504099e-01 -9.90964293e-01 -6.97559044e-02 1.11154057e-01 -9.91346657e-01 -6.97559044e-02 1.07683070e-01 -9.91728663e-01 -6.97559044e-02 1.04237199e-01 -9.92097020e-01 -6.97559044e-02 1.00680679e-01 -9.92462635e-01 -6.97559044e-02 9.72065777e-02 -9.92811024e-01 -6.97559044e-02 9.37624648e-02 -9.93144155e-01 -6.97559044e-02 9.02698934e-02 -9.93466794e-01 -6.97559044e-02 8.68146792e-02 -9.93774235e-01 -6.97559044e-02 8.32576603e-02 -9.94077504e-01 -6.97559044e-02 7.98684359e-02 -9.94356811e-01 -6.97559044e-02 7.64879435e-02 -9.94621217e-01 -6.97559044e-02 7.30216131e-02 -9.94883180e-01 -6.97559044e-02 6.95374981e-02 -9.95130539e-01 -6.97559044e-02 6.60605505e-02 -9.95369077e-01 -6.97559044e-02 6.26174733e-02 -9.95591402e-01 -6.97559044e-02 5.91191314e-02 -9.95805025e-01 -6.97559044e-02 5.56254983e-02 -9.96007323e-01 -6.97559044e-02 5.21731824e-02 -9.96191561e-01 -6.97559044e-02 4.87125739e-02 -9.96369898e-01 -6.97559044e-02 4.52494733e-02 -9.96532142e-01 -6.97559044e-02 4.16580811e-02 -9.96687233e-01 -6.97559044e-02 3.81732844e-02 -9.96827543e-01 -6.97559044e-02 3.48092765e-02 -9.96950626e-01 -6.97559044e-02 3.12267821e-02 -9.97069120e-01 -6.97559044e-02 2.77312249e-02 -9.97173786e-01 -6.97559044e-02 2.42453422e-02 -9.97266352e-01 -6.97559044e-02 2.07476486e-02 -9.97341037e-01 -6.97559044e-02 1.74040236e-02 -9.97411370e-01 -6.97559044e-02 1.38225276e-02 -9.97456729e-01 -6.97559044e-02 1.03081390e-02 -9.97504950e-01 -6.97559044e-02 6.93991221e-03 -9.97540772e-01 -6.97559044e-02 3.44721694e-03 -9.97558117e-01 -6.97559044e-02 -4.20518700e-05 -9.97559190e-01 -6.97559044e-02 -3.61497491e-03 -9.97557759e-01 -6.97559044e-02 -7.08299875e-03 -9.97539997e-01 -6.97559044e-02 -1.05583770e-02 -9.97503281e-01 -6.97559044e-02 -1.40427919e-02 -9.97455657e-01 -6.97559044e-02 -1.75159778e-02 -9.97410655e-01 -6.97559044e-02 -2.10820567e-02 -9.97333944e-01 -6.97559044e-02 -2.44931001e-02 -9.97259974e-01 -6.97559044e-02 -2.78965719e-02 -9.97169197e-01 -6.97559044e-02 -3.13699730e-02 -9.97066617e-01 -6.97559044e-02 -3.48428711e-02 -9.96951342e-01 -6.97559044e-02 -3.84256952e-02 -9.96818364e-01 -6.97559044e-02 -4.19196449e-02 -9.96678233e-01 -6.97559044e-02 -4.52886596e-02 -9.96529341e-01 -6.97559044e-02 -4.87575643e-02 -9.96367872e-01 -6.97559044e-02 -5.22349551e-02 -9.96188104e-01 -6.97559044e-02 -5.57844676e-02 -9.95998919e-01 -6.97559044e-02 -5.92799149e-02 -9.95796025e-01 -6.97559044e-02 -6.27503172e-02 -9.95580196e-01 -6.97559044e-02 -6.62275776e-02 -9.95357156e-01 -6.97559044e-02 -6.96122944e-02 -9.95125830e-01 -6.97559044e-02 -7.31556639e-02 -9.94872570e-01 -6.97559044e-02 -7.66431987e-02 -9.94608998e-01 -6.97559044e-02 -8.00989494e-02 -9.94337559e-01 -6.97559044e-02 -8.35842937e-02 -9.94049907e-01 -6.97559044e-02 -8.69782045e-02 -9.93759513e-01 -6.97559044e-02 -9.05225277e-02 -9.93442237e-01 -6.97559044e-02 -9.40100327e-02 -9.93118107e-01 -6.97559044e-02 -9.74436030e-02 -9.92787361e-01 -6.97559044e-02 -1.00927457e-01 -9.92440760e-01 -6.97559044e-02 -1.04371741e-01 -9.92083848e-01 -6.97559044e-02 -1.07943416e-01 -9.91701365e-01 -6.97559044e-02 -1.11304954e-01 -9.91329908e-01 -6.97559044e-02 -1.14664197e-01 -9.90946412e-01 -6.97559044e-02 -1.18134856e-01 -9.90538120e-01 -6.97559044e-02 -1.21582486e-01 -9.90122080e-01 -6.97559044e-02 -1.25126898e-01 -9.89680648e-01 -6.97559044e-02 -1.28617406e-01 -9.89231408e-01 -6.97559044e-02 -1.31961331e-01 -9.88792777e-01 -6.97559044e-02 -1.35393634e-01 -9.88328218e-01 -6.97559044e-02 -1.38841480e-01 -9.87850308e-01 -6.97559044e-02 -1.42402336e-01 -9.87341166e-01 -6.97559044e-02 -1.45842463e-01 -9.86839354e-01 -6.97559044e-02 -1.49279520e-01 -9.86324430e-01 -6.97559044e-02 -1.52721137e-01 -9.85800683e-01 -6.97559044e-02 -1.56059340e-01 -9.85275269e-01 -6.97559044e-02 -1.59514412e-01 -9.84723210e-01 -6.97559044e-02 -1.62930489e-01 -9.84164536e-01 -6.97559044e-02 -1.66475415e-01 -9.83570755e-01 -6.97559044e-02 -1.69920310e-01 -9.82979178e-01 -6.97559044e-02 -1.73245504e-01 -9.82403100e-01 -6.97559044e-02 -1.76734030e-01 -9.81780529e-01 -6.97559044e-02 -1.80161700e-01 -9.81152952e-01 -6.97559044e-02 -1.83629036e-01 -9.80513394e-01 -6.97559044e-02 -1.87060252e-01 -9.79862809e-01 -6.97559044e-02 -1.90376475e-01 -9.79224026e-01 -6.97559044e-02 -1.93808898e-01 -9.78550851e-01 -6.97559044e-02 -1.97279438e-01 -9.77857411e-01 -6.97559044e-02 -2.00713113e-01 -9.77157295e-01 -6.97559044e-02 -2.04059973e-01 -9.76463914e-01 -6.97559044e-02 -2.07453832e-01 -9.75751519e-01 -6.97559044e-02 -2.10932329e-01 -9.75003839e-01 -6.97559044e-02 -2.14346841e-01 -9.74256039e-01 -6.97559044e-02 -2.17657238e-01 -9.73524868e-01 -6.97559044e-02 -2.21058652e-01 -9.72756982e-01 -6.97559044e-02 -2.24446163e-01 -9.71980572e-01 -6.97559044e-02 -2.27910802e-01 -9.71177936e-01 -6.97559044e-02 -2.31311023e-01 -9.70372021e-01 -6.97559044e-02 -2.34607086e-01 -9.69581068e-01 -6.97559044e-02 -2.38061339e-01 -9.68737006e-01 -6.97559044e-02 -2.41459623e-01 -9.67894554e-01 -6.97559044e-02 -2.44823113e-01 -9.67048049e-01 -6.97559044e-02 -2.48205438e-01 -9.66188192e-01 -6.97559044e-02 -2.51467347e-01 -9.65343356e-01 -6.97559044e-02 -2.54866153e-01 -9.64452803e-01 -6.97559044e-02 -2.58301437e-01 -9.63536918e-01 -6.97559044e-02 -2.61764079e-01 -9.62603390e-01 -6.97559044e-02 -2.65046597e-01 -9.61703300e-01 -6.97559044e-02 -2.68284678e-01 -9.60807025e-01 -6.97559044e-02 -2.71671891e-01 -9.59854126e-01 -6.97559044e-02 -2.75010169e-01 -9.58901346e-01 -6.97559044e-02 -2.78355867e-01 -9.57937062e-01 -6.97559044e-02 -2.81685114e-01 -9.56962347e-01 -6.97559044e-02 -2.85017043e-01 -9.55976903e-01 -6.97559044e-02 -2.88358629e-01 -9.54971373e-01 -6.97559044e-02 -2.91695118e-01 -9.53956962e-01 -6.97559044e-02 -2.95103312e-01 -9.52911735e-01 -6.97559044e-02 -2.98455894e-01 -9.51865256e-01 -6.97559044e-02 -3.01764756e-01 -9.50822115e-01 -6.97559044e-02 -3.05076540e-01 -9.49765861e-01 -6.97559044e-02 -3.08287382e-01 -9.48726892e-01 -6.97559044e-02 -3.11680228e-01 -9.47617352e-01 -6.97559044e-02 -3.15050840e-01 -9.46502328e-01 -6.97559044e-02 -3.18353206e-01 -9.45398390e-01 -6.97559044e-02 -3.21592748e-01 -9.44299757e-01 -6.97559044e-02 -3.24785650e-01 -9.43206847e-01 -6.97559044e-02 -3.28121364e-01 -9.42050099e-01 -6.97559044e-02 -3.31404626e-01 -9.40901279e-01 -6.97559044e-02 -3.34725618e-01 -9.39724445e-01 -6.97559044e-02 -3.38019311e-01 -9.38544154e-01 -6.97559044e-02 -3.41276884e-01 -9.37366545e-01 -6.97559044e-02 -3.44552785e-01 -9.36159790e-01 -6.97559044e-02 -3.47744375e-01 -9.34975445e-01 -6.97559044e-02 -3.51004153e-01 -9.33757484e-01 -6.97559044e-02 -3.54262352e-01 -9.32531953e-01 -6.97559044e-02 -3.57601434e-01 -9.31264043e-01 -6.97559044e-02 -3.60951483e-01 -9.29963291e-01 -6.97559044e-02 -3.64113361e-01 -9.28733706e-01 -6.97559044e-02 -3.67249429e-01 -9.27497745e-01 -6.97559044e-02 -3.70465159e-01 -9.26216781e-01 -6.97559044e-02 -3.73697609e-01 -9.24918354e-01 -6.97559044e-02 -3.77009332e-01 -9.23572719e-01 -6.97559044e-02 -3.80326062e-01 -9.22210097e-01 -6.97559044e-02 -3.83475393e-01 -9.20906842e-01 -6.97559044e-02 -3.86567026e-01 -9.19613898e-01 -6.97559044e-02 -3.89798462e-01 -9.18248296e-01 -6.97559044e-02 -3.93069863e-01 -9.16848421e-01 -6.97559044e-02 -3.96297336e-01 -9.15461779e-01 -6.97559044e-02 -3.99489224e-01 -9.14075732e-01 -6.97559044e-02 -4.02687430e-01 -9.12670374e-01 -6.97559044e-02 -4.05768484e-01 -9.11304593e-01 -6.97559044e-02 -4.08966333e-01 -9.09874856e-01 -6.97559044e-02 -4.12118316e-01 -9.08449829e-01 -6.97559044e-02 -4.15351987e-01 -9.06974792e-01 -6.97559044e-02 -4.18521434e-01 -9.05516565e-01 -6.97559044e-02 -4.21606958e-01 -9.04085219e-01 -6.97559044e-02 -4.24753547e-01 -9.02611256e-01 -6.97559044e-02 -4.27988559e-01 -9.01081741e-01 -6.97559044e-02 -4.31129307e-01 -8.99581552e-01 -6.97559044e-02 -4.34188038e-01 -8.98114860e-01 -6.97559044e-02 -4.37337130e-01 -8.96585166e-01 -6.97559044e-02 -4.40522075e-01 -8.95021141e-01 -6.97559044e-02 -4.43645597e-01 -8.93479288e-01 -6.97559044e-02 -4.46663827e-01 -8.91972721e-01 -6.97559044e-02 -4.49791610e-01 -8.90401483e-01 -6.97559044e-02 -4.52891856e-01 -8.88827503e-01 -6.97559044e-02 -4.56075311e-01 -8.87197733e-01 -6.97559044e-02 -4.59173471e-01 -8.85596097e-01 -6.97559044e-02 -4.62175727e-01 -8.84037256e-01 -6.97559044e-02 -4.65247869e-01 -8.82421970e-01 -6.97559044e-02 -4.68316317e-01 -8.80796909e-01 -6.97559044e-02 -4.71455634e-01 -8.79122198e-01 -6.97559044e-02 -4.74560708e-01 -8.77447903e-01 -6.97559044e-02 -4.77618039e-01 -8.75789464e-01 -6.97559044e-02 -4.80669409e-01 -8.74117851e-01 -6.97559044e-02 -4.83716309e-01 -8.72433722e-01 -6.97559044e-02 -4.86852229e-01 -8.70688021e-01 -6.97559044e-02 -4.89809483e-01 -8.69029164e-01 -6.97559044e-02 -4.92813617e-01 -8.67328763e-01 -6.97559044e-02 -4.95860130e-01 -8.65591764e-01 -6.97559044e-02 -4.98790890e-01 -8.63905370e-01 -6.97559044e-02 -5.01816273e-01 -8.62151623e-01 -6.97559044e-02 -5.04827261e-01 -8.60392094e-01 -6.97559044e-02 -5.07813036e-01 -8.58632743e-01 -6.97559044e-02 -5.10787904e-01 -8.56865883e-01 -6.97559044e-02 -5.13784885e-01 -8.55072081e-01 -6.97559044e-02 -5.16794145e-01 -8.53256524e-01 -6.97559044e-02 -5.19861341e-01 -8.51394475e-01 -6.97559044e-02 -5.22874117e-01 -8.49544108e-01 -6.97559044e-02 -5.25767446e-01 -8.47757936e-01 -6.97559044e-02 -5.28629601e-01 -8.45976651e-01 -6.97559044e-02 -5.31661153e-01 -8.44072998e-01 -6.97559044e-02 -5.34625888e-01 -8.42198670e-01 -6.97559044e-02 -5.37547410e-01 -8.40336323e-01 -6.97559044e-02 -5.40490925e-01 -8.38446856e-01 -6.97559044e-02 -5.43309450e-01 -8.36622477e-01 -6.97559044e-02 -5.46306670e-01 -8.34667325e-01 -6.97559044e-02 -5.49243748e-01 -8.32740903e-01 -6.97559044e-02 -5.52048147e-01 -8.30879986e-01 -6.97559044e-02 -5.54940879e-01 -8.28953624e-01 -6.97559044e-02 -5.57918787e-01 -8.26954007e-01 -6.97559044e-02 -5.60824215e-01 -8.24982405e-01 -6.97559044e-02 -5.63597381e-01 -8.23094249e-01 -6.97559044e-02 -5.66464186e-01 -8.21123540e-01 -6.97559044e-02 -5.69328785e-01 -8.19139063e-01 -6.97559044e-02 -5.72271466e-01 -8.17084193e-01 -6.97559044e-02 -5.75232208e-01 -8.15005720e-01 -6.97559044e-02 -5.77999353e-01 -8.13043892e-01 -6.97559044e-02 -5.80723405e-01 -8.11101794e-01 -6.97559044e-02 -5.83553016e-01 -8.09063971e-01 -6.97559044e-02 -5.86386502e-01 -8.07016492e-01 -6.97559044e-02 -5.89275181e-01 -8.04907501e-01 -6.97559044e-02 -5.92152953e-01 -8.02793324e-01 -6.97559044e-02 -5.94886601e-01 -8.00770581e-01 -6.97559044e-02 -5.97589672e-01 -7.98753560e-01 -6.97559044e-02 -6.00382745e-01 -7.96658158e-01 -6.97559044e-02 -6.03227735e-01 -7.94507980e-01 -6.97559044e-02 -6.06019676e-01 -7.92378962e-01 -6.97559044e-02 -6.08768582e-01 -7.90267229e-01 -6.97559044e-02 -6.11525893e-01 -7.88136899e-01 -6.97559044e-02 -6.14200652e-01 -7.86053658e-01 -6.97559044e-02 -6.17003143e-01 -7.83856511e-01 -6.97559044e-02 -6.19742155e-01 -7.81692326e-01 -6.97559044e-02 -6.22461379e-01 -7.79529274e-01 -6.97559044e-02 -6.25186086e-01 -7.77345836e-01 -6.97559044e-02 -6.27800226e-01 -7.75238752e-01 -6.97559044e-02 -6.30512714e-01 -7.73029387e-01 -6.97559044e-02 -6.33197427e-01 -7.70834684e-01 -6.97559044e-02 -6.35955691e-01 -7.68560529e-01 -6.97559044e-02 -6.38642490e-01 -7.66327798e-01 -6.97559044e-02 -6.41228974e-01 -7.64166713e-01 -6.97559044e-02 -6.43968463e-01 -7.61858284e-01 -6.97559044e-02 -6.46631420e-01 -7.59599566e-01 -6.97559044e-02 -6.49205506e-01 -7.57400215e-01 -6.97559044e-02 -6.51851833e-01 -7.55125761e-01 -6.97559044e-02 -6.54472113e-01 -7.52857208e-01 -6.97559044e-02 -6.57174587e-01 -7.50494599e-01 -6.97559044e-02 -6.59793019e-01 -7.48195946e-01 -6.97559044e-02 -6.62318945e-01 -7.45960951e-01 -6.97559044e-02 -6.64930642e-01 -7.43633151e-01 -6.97559044e-02 -6.67504966e-01 -7.41323650e-01 -6.97559044e-02 -6.70154929e-01 -7.38931060e-01 -6.97559044e-02 -6.72739625e-01 -7.36574113e-01 -6.97559044e-02 -6.75303459e-01 -7.34229207e-01 -6.97559044e-02 -6.77875042e-01 -7.31853485e-01 -6.97559044e-02 -6.80407465e-01 -7.29498208e-01 -6.97559044e-02 -6.83026314e-01 -7.27047503e-01 -6.97559044e-02 -6.85497761e-01 -7.24716365e-01 -6.97559044e-02 -6.87995553e-01 -7.22349763e-01 -6.97559044e-02 -6.90537393e-01 -7.19912112e-01 -6.97559044e-02 -6.92970932e-01 -7.17584312e-01 -6.97559044e-02 -6.95462525e-01 -7.15167463e-01 -6.97559044e-02 -6.97942376e-01 -7.12743998e-01 -6.97559044e-02 -7.00507998e-01 -7.10223317e-01 -6.97559044e-02 -7.03005433e-01 -7.07754791e-01 -6.97559044e-02 -7.05368340e-01 -7.05380797e-01 -6.97559044e-02 -7.07843065e-01 -7.02917457e-01 -6.97559044e-02 -7.10371494e-01 -7.00359941e-01 -6.97559044e-02 -7.12830722e-01 -6.97853863e-01 -6.97559044e-02 -7.15181589e-01 -6.95448458e-01 -6.97559044e-02 -7.17590392e-01 -6.92964554e-01 -6.97559044e-02 -7.20063984e-01 -6.90379024e-01 -6.97559044e-02 -7.22554207e-01 -6.87782407e-01 -6.97559044e-02 -7.24947274e-01 -6.85253322e-01 -6.97559044e-02 -7.27290154e-01 -6.82766616e-01 -6.97559044e-02 -7.29585588e-01 -6.80312693e-01 -6.97559044e-02 -7.32013762e-01 -6.77702308e-01 -6.97559044e-02 -7.34387517e-01 -6.75130725e-01 -6.97559044e-02 -7.36673951e-01 -6.72633231e-01 -6.97559044e-02 -7.39027917e-01 -6.70047820e-01 -6.97559044e-02 -7.41369545e-01 -6.67455196e-01 -6.97559044e-02 -7.43687868e-01 -6.64870322e-01 -6.97559044e-02 -7.46005952e-01 -6.62270427e-01 -6.97559044e-02 -7.48376191e-01 -6.59587741e-01 -6.97559044e-02 -7.50674009e-01 -6.56971753e-01 -6.97559044e-02 -7.52955377e-01 -6.54354990e-01 -6.97559044e-02 -7.55304098e-01 -6.51642442e-01 -6.97559044e-02 -7.57516801e-01 -6.49072170e-01 -6.97559044e-02 -7.59758770e-01 -6.46442950e-01 -6.97559044e-02 -7.62020886e-01 -6.43778801e-01 -6.97559044e-02 -7.64203191e-01 -6.41183734e-01 -6.97559044e-02 -7.66488969e-01 -6.38452530e-01 -6.97559044e-02 -7.68722713e-01 -6.35758460e-01 -6.97559044e-02 -7.70879209e-01 -6.33144319e-01 -6.97559044e-02 -7.73076653e-01 -6.30455554e-01 -6.97559044e-02 -7.75274575e-01 -6.27751827e-01 -6.97559044e-02 -7.77514815e-01 -6.24975741e-01 -6.97559044e-02 -7.79743731e-01 -6.22194946e-01 -6.97559044e-02 -7.81920314e-01 -6.19454861e-01 -6.97559044e-02 -7.84038067e-01 -6.16772234e-01 -6.97559044e-02 -7.86117911e-01 -6.14119709e-01 -6.97559044e-02 -7.88306415e-01 -6.11309707e-01 -6.97559044e-02 -7.90435195e-01 -6.08554423e-01 -6.97559044e-02 -7.92544603e-01 -6.05802476e-01 -6.97559044e-02 -7.94667780e-01 -6.03015602e-01 -6.97559044e-02 -7.96699345e-01 -6.00329876e-01 -6.97559044e-02 -7.98775613e-01 -5.97560465e-01 -6.97559044e-02 -8.00854445e-01 -5.94771028e-01 -6.97559044e-02 -8.02986443e-01 -5.91890454e-01 -6.97559044e-02 -8.05060923e-01 -5.89067698e-01 -6.97559044e-02 -8.07131290e-01 -5.86227059e-01 -6.97559044e-02 -8.09215546e-01 -5.83343387e-01 -6.97559044e-02 -8.11190844e-01 -5.80599487e-01 -6.97559044e-02 -8.13202918e-01 -5.77774644e-01 -6.97559044e-02 -8.15226197e-01 -5.74918926e-01 -6.97559044e-02 -8.17166448e-01 -5.72154701e-01 -6.97559044e-02 -8.19213569e-01 -5.69219589e-01 -6.97559044e-02 -8.21214378e-01 -5.66333354e-01 -6.97559044e-02 -8.23105276e-01 -5.63579202e-01 -6.97559044e-02 -8.25084686e-01 -5.60676277e-01 -6.97559044e-02 -8.27040136e-01 -5.57791233e-01 -6.97559044e-02 -8.29028785e-01 -5.54826260e-01 -6.97559044e-02 -8.30974996e-01 -5.51906466e-01 -6.97559044e-02 -8.32888663e-01 -5.49015820e-01 -6.97559044e-02 -8.34812403e-01 -5.46085954e-01 -6.97559044e-02 -8.36658955e-01 -5.43255508e-01 -6.97559044e-02 -8.38545680e-01 -5.40336788e-01 -6.97559044e-02 -8.40412796e-01 -5.37427902e-01 -6.97559044e-02 -8.42329979e-01 -5.34417629e-01 -6.97559044e-02 -8.44189286e-01 -5.31478345e-01 -6.97559044e-02 -8.45985353e-01 -5.28612435e-01 -6.97559044e-02 -8.47834885e-01 -5.25645792e-01 -6.97559044e-02 -8.49663794e-01 -5.22677600e-01 -6.97559044e-02 -8.51525486e-01 -5.19644141e-01 -6.97559044e-02 -8.53338540e-01 -5.16657948e-01 -6.97559044e-02 -8.55128050e-01 -5.13694167e-01 -6.97559044e-02 -8.56912196e-01 -5.10709524e-01 -6.97559044e-02 -8.58650208e-01 -5.07782280e-01 -6.97559044e-02 -8.60446811e-01 -5.04733503e-01 -6.97559044e-02 -8.62210929e-01 -5.01713037e-01 -6.97559044e-02 -8.63913000e-01 -4.98779118e-01 -6.97559044e-02 -8.65634680e-01 -4.95781660e-01 -6.97559044e-02 -8.67367089e-01 -4.92743462e-01 -6.97559044e-02 -8.69083583e-01 -4.89716560e-01 -6.97559044e-02 -8.70786905e-01 -4.86674130e-01 -6.97559044e-02 -8.72472525e-01 -4.83643979e-01 -6.97559044e-02 -8.74209881e-01 -4.80502248e-01 -6.97559044e-02 -8.75890017e-01 -4.77435738e-01 -6.97559044e-02 -8.77497852e-01 -4.74468797e-01 -6.97559044e-02 -8.79159987e-01 -4.71382678e-01 -6.97559044e-02 -8.80852818e-01 -4.68211859e-01 -6.97559044e-02 -8.82526100e-01 -4.65049058e-01 -6.97559044e-02 -8.84094357e-01 -4.62062329e-01 -6.97559044e-02 -8.85648608e-01 -4.59075481e-01 -6.97559044e-02 -8.87252033e-01 -4.55970198e-01 -6.97559044e-02 -8.88883829e-01 -4.52778637e-01 -6.97559044e-02 -8.90462697e-01 -4.49668378e-01 -6.97559044e-02 -8.91975462e-01 -4.46656823e-01 -6.97559044e-02 -8.93570185e-01 -4.43460852e-01 -6.97559044e-02 -8.95119309e-01 -4.40323472e-01 -6.97559044e-02 -8.96614850e-01 -4.37274516e-01 -6.97559044e-02 -8.98174822e-01 -4.34061199e-01 -6.97559044e-02 -8.99727762e-01 -4.30827200e-01 -6.97559044e-02 -9.01227295e-01 -4.27682340e-01 -6.97559044e-02 -9.02681231e-01 -4.24603730e-01 -6.97559044e-02 -9.04113770e-01 -4.21548486e-01 -6.97559044e-02 -9.05619681e-01 -4.18301970e-01 -6.97559044e-02 -9.07115996e-01 -4.15044993e-01 -6.97559044e-02 -9.08513248e-01 -4.11978871e-01 -6.97559044e-02 -9.09914553e-01 -4.08876449e-01 -6.97559044e-02 -9.11335528e-01 -4.05697584e-01 -6.97559044e-02 -9.12778318e-01 -4.02442664e-01 -6.97559044e-02 -9.14183259e-01 -3.99244905e-01 -6.97559044e-02 -9.15564656e-01 -3.96061212e-01 -6.97559044e-02 -9.16949511e-01 -3.92836511e-01 -6.97559044e-02 -9.18273687e-01 -3.89736921e-01 -6.97559044e-02 -9.19664025e-01 -3.86447787e-01 -6.97559044e-02 -9.21011567e-01 -3.83225322e-01 -6.97559044e-02 -9.22342658e-01 -3.80007774e-01 -6.97559044e-02 -9.23664153e-01 -3.76785368e-01 -6.97559044e-02 -9.24942851e-01 -3.73632699e-01 -6.97559044e-02 -9.26269889e-01 -3.70330870e-01 -6.97559044e-02 -9.27564919e-01 -3.67080718e-01 -6.97559044e-02 -9.28833842e-01 -3.63860130e-01 -6.97559044e-02 -9.30105805e-01 -3.60577643e-01 -6.97559044e-02 -9.31325853e-01 -3.57441366e-01 -6.97559044e-02 -9.32589293e-01 -3.54112953e-01 -6.97559044e-02 -9.33817148e-01 -3.50845516e-01 -6.97559044e-02 -9.34998572e-01 -3.47684026e-01 -6.97559044e-02 -9.36235547e-01 -3.44351202e-01 -6.97559044e-02 -9.37444568e-01 -3.41065645e-01 -6.97559044e-02 -9.38627779e-01 -3.37787122e-01 -6.97559044e-02 -9.39806759e-01 -3.34499210e-01 -6.97559044e-02 -9.40957487e-01 -3.31242383e-01 -6.97559044e-02 -9.42115664e-01 -3.27932715e-01 -6.97559044e-02 -9.43228424e-01 -3.24722648e-01 -6.97559044e-02 -9.44354832e-01 -3.21430296e-01 -6.97559044e-02 -9.45465326e-01 -3.18148792e-01 -6.97559044e-02 -9.46595848e-01 -3.14765036e-01 -6.97559044e-02 -9.47693467e-01 -3.11445236e-01 -6.97559044e-02 -9.48750794e-01 -3.08214456e-01 -6.97559044e-02 -9.49847579e-01 -3.04817140e-01 -6.97559044e-02 -9.50908720e-01 -3.01492423e-01 -6.97559044e-02 -9.51951385e-01 -2.98183680e-01 -6.97559044e-02 -9.52985346e-01 -2.94858754e-01 -6.97559044e-02 -9.54002917e-01 -2.91548401e-01 -6.97559044e-02 -9.55017805e-01 -2.88207471e-01 -6.97559044e-02 -9.55983043e-01 -2.84988225e-01 -6.97559044e-02 -9.57002640e-01 -2.81550497e-01 -6.97559044e-02 -9.57983732e-01 -2.78196305e-01 -6.97559044e-02 -9.58922803e-01 -2.74936110e-01 -6.97559044e-02 -9.59874034e-01 -2.71598458e-01 -6.97559044e-02 -9.60822701e-01 -2.68225819e-01 -6.97559044e-02 -9.61749256e-01 -2.64879167e-01 -6.97559044e-02 -9.62671399e-01 -2.61518806e-01 -6.97559044e-02 -9.63575661e-01 -2.58156270e-01 -6.97559044e-02 -9.64490950e-01 -2.54717797e-01 -6.97559044e-02 -9.65407252e-01 -2.51224935e-01 -6.97559044e-02 -9.66260672e-01 -2.47924104e-01 -6.97559044e-02 -9.67089474e-01 -2.44657919e-01 -6.97559044e-02 -9.67957854e-01 -2.41202965e-01 -6.97559044e-02 -9.68821526e-01 -2.37718999e-01 -6.97559044e-02 -9.69621897e-01 -2.34434575e-01 -6.97559044e-02 -9.70411181e-01 -2.31147408e-01 -6.97559044e-02 -9.71211135e-01 -2.27758825e-01 -6.97559044e-02 -9.72017229e-01 -2.24288136e-01 -6.97559044e-02 -9.72802222e-01 -2.20861182e-01 -6.97559044e-02 -9.73545194e-01 -2.17565909e-01 -6.97559044e-02 -9.74310100e-01 -2.14108005e-01 -6.97559044e-02 -9.75055873e-01 -2.10684210e-01 -6.97559044e-02 -9.75770295e-01 -2.07357734e-01 -6.97559044e-02 -9.76487756e-01 -2.03953579e-01 -6.97559044e-02 -9.77209508e-01 -2.00471953e-01 -6.97559044e-02 -9.77919757e-01 -1.96969628e-01 -6.97559044e-02 -9.78584290e-01 -1.93645492e-01 -6.97559044e-02 -9.79240119e-01 -1.90301850e-01 -6.97559044e-02 -9.79909897e-01 -1.86812356e-01 -6.97559044e-02 -9.80570614e-01 -1.83316275e-01 -6.97559044e-02 -9.81189847e-01 -1.79958954e-01 -6.97559044e-02 -9.81801867e-01 -1.76628768e-01 -6.97559044e-02 -9.82412636e-01 -1.73202753e-01 -6.97559044e-02 -9.83014762e-01 -1.69715226e-01 -6.97559044e-02 -9.83620048e-01 -1.66180313e-01 -6.97559044e-02 -9.84177589e-01 -1.62840635e-01 -6.97559044e-02 -9.84725833e-01 -1.59497365e-01 -6.97559044e-02 -9.85281885e-01 -1.56024426e-01 -6.97559044e-02 -9.85831738e-01 -1.52511194e-01 -6.97559044e-02 -9.86353397e-01 -1.49094418e-01 -6.97559044e-02 -9.86870408e-01 -1.45636559e-01 -6.97559044e-02 -9.87374067e-01 -1.42179355e-01 -6.97559044e-02 -9.87851918e-01 -1.38827711e-01 -6.97559044e-02 -9.88340914e-01 -1.35303795e-01 -6.97559044e-02 -9.88808811e-01 -1.31832764e-01 -6.97559044e-02 -9.89263654e-01 -1.28384396e-01 -6.97559044e-02 -9.89705324e-01 -1.24934755e-01 -6.97559044e-02 -9.90124464e-01 -1.21552631e-01 -6.97559044e-02 -9.90551770e-01 -1.18018232e-01 -6.97559044e-02 -9.90958929e-01 -1.14543498e-01 -6.97559044e-02 -9.91351485e-01 -1.11111455e-01 -6.97559044e-02 -9.91715312e-01 -1.07814625e-01 -6.97559863e-02 -9.92035329e-01 -1.04880832e-01 -6.97564855e-02 -9.92447317e-01 -1.00902922e-01 -6.97564706e-02 -9.92745042e-01 -9.79342610e-02 -6.97564706e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.94378626e-01 -7.96565637e-02 -6.97564632e-02 -9.94743049e-01 -7.49696046e-02 -6.97564781e-02 -9.94910538e-01 -7.27125555e-02 -6.97564706e-02 -9.95146215e-01 -6.94128722e-02 -6.97564632e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. -9.97178435e-01 3.92952971e-02 -6.39575422e-02 -9.97049272e-01 4.24423292e-02 -6.39575422e-02 -9.96905208e-01 4.56991307e-02 -6.39575571e-02 -9.96732235e-01 4.93746512e-02 -6.39574155e-02 -9.96564984e-01 5.24023324e-02 -6.39574081e-02 -9.96381581e-01 5.57231754e-02 -6.39574081e-02 -9.96175349e-01 5.92687689e-02 -6.39574081e-02 -9.95954156e-01 6.28785640e-02 -6.39574081e-02 -9.95728374e-01 6.63566515e-02 -6.39574081e-02 -9.95488048e-01 6.98475167e-02 -6.39574081e-02 -9.95242536e-01 7.32873231e-02 -6.39574081e-02 -9.94979322e-01 7.67658353e-02 -6.39574081e-02 -9.94705498e-01 8.02457258e-02 -6.39574081e-02 -9.94415820e-01 8.37429613e-02 -6.39574081e-02 -9.94127810e-01 8.71176198e-02 -6.39574081e-02 -9.93830740e-01 9.04382169e-02 -6.39574081e-02 -9.93497372e-01 9.40254256e-02 -6.39574081e-02 -9.93154824e-01 9.75844264e-02 -6.39574081e-02 -9.92809176e-01 1.01043656e-01 -6.39574081e-02 -9.92448092e-01 1.04524709e-01 -6.39574081e-02 -9.92086053e-01 1.07905477e-01 -6.39574081e-02 -9.91715372e-01 1.11264326e-01 -6.39574081e-02 -9.91308093e-01 1.14819005e-01 -6.39574081e-02 -9.90888238e-01 1.18394040e-01 -6.39574081e-02 -9.90481675e-01 1.21764652e-01 -6.39574081e-02 -9.90052283e-01 1.25206500e-01 -6.39574081e-02 -9.89593565e-01 1.28773436e-01 -6.39574081e-02 -9.89136875e-01 1.32227734e-01 -6.39574081e-02 -9.88672554e-01 1.35674715e-01 -6.39574081e-02 -9.88195837e-01 1.39102861e-01 -6.39574081e-02 -9.87720490e-01 1.42433152e-01 -6.39574081e-02 -9.87206697e-01 1.45931095e-01 -6.39574081e-02 -9.86674488e-01 1.49496168e-01 -6.39574081e-02 -9.86146450e-01 1.52949706e-01 -6.39574081e-02 -9.85621810e-01 1.56295791e-01 -6.39574081e-02 -9.85072851e-01 1.59716159e-01 -6.39574081e-02 -9.84493315e-01 1.63257524e-01 -6.39574081e-02 -9.83931184e-01 1.66608125e-01 -6.39574081e-02 -9.83348072e-01 1.70006752e-01 -6.39574081e-02 -9.82747972e-01 1.73478499e-01 -6.39574081e-02 -9.82153952e-01 1.76800936e-01 -6.39574081e-02 -9.81510162e-01 1.80309668e-01 -6.39574081e-02 -9.80859160e-01 1.83833629e-01 -6.39574081e-02 -9.80216503e-01 1.87227458e-01 -6.39574081e-02 -9.79552329e-01 1.90664515e-01 -6.39574081e-02 -9.78882313e-01 1.94085285e-01 -6.39574081e-02 -9.78217125e-01 1.97405368e-01 -6.39574081e-02 -9.77519453e-01 2.00828567e-01 -6.39574081e-02 -9.76796865e-01 2.04318583e-01 -6.39574081e-02 -9.76092756e-01 2.07665369e-01 -6.39574081e-02 -9.75364625e-01 2.11052477e-01 -6.39574081e-02 -9.74606752e-01 2.14522123e-01 -6.39574081e-02 -9.73849773e-01 2.17935637e-01 -6.39574081e-02 -9.73080218e-01 2.21340045e-01 -6.39574081e-02 -9.72320080e-01 2.24667788e-01 -6.39574081e-02 -9.71552670e-01 2.27966070e-01 -6.39574081e-02 -9.70750570e-01 2.31357530e-01 -6.39574081e-02 -9.69922066e-01 2.34804958e-01 -6.39574081e-02 -9.69069779e-01 2.38292187e-01 -6.39574081e-02 -9.68254864e-01 2.41580114e-01 -6.39574081e-02 -9.67406392e-01 2.44947419e-01 -6.39574081e-02 -9.66523051e-01 2.48423070e-01 -6.39574081e-02 -9.65655386e-01 2.51775831e-01 -6.39574081e-02 -9.64768887e-01 2.55151123e-01 -6.39574081e-02 -9.63892043e-01 2.58447438e-01 -6.39574081e-02 -9.63015258e-01 2.61692107e-01 -6.39574081e-02 -9.62069392e-01 2.65136898e-01 -6.39574081e-02 -9.61109519e-01 2.68606395e-01 -6.39574081e-02 -9.60156024e-01 2.71991521e-01 -6.39574081e-02 -9.59205806e-01 2.75322050e-01 -6.39574081e-02 -9.58240867e-01 2.78662711e-01 -6.39574081e-02 -9.57266867e-01 2.81993568e-01 -6.39574081e-02 -9.56278026e-01 2.85329223e-01 -6.39574081e-02 -9.55278516e-01 2.88653463e-01 -6.39574081e-02 -9.54284132e-01 2.91928083e-01 -6.39574081e-02 -9.53292251e-01 2.95155376e-01 -6.39574081e-02 -9.52224374e-01 2.98574865e-01 -6.39574081e-02 -9.51152623e-01 3.01969349e-01 -6.39574081e-02 -9.50115681e-01 3.05222899e-01 -6.39574081e-02 -9.49057341e-01 3.08490247e-01 -6.39574081e-02 -9.47954118e-01 3.11866581e-01 -6.39574081e-02 -9.46856201e-01 3.15184355e-01 -6.39574081e-02 -9.45751250e-01 3.18487585e-01 -6.39574081e-02 -9.44619417e-01 3.21828932e-01 -6.39574081e-02 -9.43522036e-01 3.25038493e-01 -6.39574081e-02 -9.42385256e-01 3.28307897e-01 -6.39574081e-02 -9.41203594e-01 3.31686288e-01 -6.39574081e-02 -9.40057814e-01 3.34925860e-01 -6.39574081e-02 -9.38884020e-01 3.38193178e-01 -6.39574081e-02 -9.37718272e-01 3.41419935e-01 -6.39574081e-02 -9.36539650e-01 3.44616413e-01 -6.39574081e-02 -9.35293376e-01 3.47974151e-01 -6.39574081e-02 -9.34036374e-01 3.51339012e-01 -6.39574081e-02 -9.32818413e-01 3.54573280e-01 -6.39574081e-02 -9.31581140e-01 3.57834995e-01 -6.39574081e-02 -9.30320561e-01 3.61076474e-01 -6.39574081e-02 -9.29091692e-01 3.64234835e-01 -6.39574081e-02 -9.27839398e-01 3.67411613e-01 -6.39574081e-02 -9.26525116e-01 3.70712966e-01 -6.39574081e-02 -9.25201595e-01 3.74004215e-01 -6.39574081e-02 -9.23922777e-01 3.77156466e-01 -6.39574081e-02 -9.22609210e-01 3.80352199e-01 -6.39574081e-02 -9.21239674e-01 3.83660078e-01 -6.39574081e-02 -9.19892430e-01 3.86881202e-01 -6.39574081e-02 -9.18538809e-01 3.90079737e-01 -6.39574081e-02 -9.17163014e-01 3.93300205e-01 -6.39574081e-02 -9.15824056e-01 3.96411926e-01 -6.39574081e-02 -9.14431930e-01 3.99619162e-01 -6.39574081e-02 -9.13007140e-01 4.02861208e-01 -6.39574081e-02 -9.11592185e-01 4.06051785e-01 -6.39574081e-02 -9.10163105e-01 4.09243643e-01 -6.39574081e-02 -9.08748806e-01 4.12375510e-01 -6.39574081e-02 -9.07297671e-01 4.15554732e-01 -6.39574081e-02 -9.05845344e-01 4.18711692e-01 -6.39574081e-02 -9.04372871e-01 4.21885282e-01 -6.39574081e-02 -9.02927637e-01 4.24970627e-01 -6.39574081e-02 -9.01482821e-01 4.28024888e-01 -6.39574081e-02 -8.99945557e-01 4.31245387e-01 -6.39574081e-02 -8.98404598e-01 4.34456527e-01 -6.39574081e-02 -8.96877766e-01 4.37598974e-01 -6.39574081e-02 -8.95357788e-01 4.40695375e-01 -6.39574081e-02 -8.93816411e-01 4.43814278e-01 -6.39574081e-02 -8.92270803e-01 4.46913660e-01 -6.39574081e-02 -8.90704393e-01 4.50025350e-01 -6.39574081e-02 -8.89095068e-01 4.53200340e-01 -6.39574081e-02 -8.87553453e-01 4.56212074e-01 -6.39574081e-02 -8.85960817e-01 4.59292233e-01 -6.39574081e-02 -8.84318113e-01 4.62453425e-01 -6.39574081e-02 -8.82682204e-01 4.65568841e-01 -6.39574081e-02 -8.81050944e-01 4.68645304e-01 -6.39574081e-02 -8.79412532e-01 4.71713930e-01 -6.39574081e-02 -8.77800763e-01 4.74704832e-01 -6.39574081e-02 -8.76134396e-01 4.77776647e-01 -6.39574081e-02 -8.74419510e-01 4.80905980e-01 -6.39574081e-02 -8.72740388e-01 4.83942151e-01 -6.39574081e-02 -8.71091187e-01 4.86907035e-01 -6.39574081e-02 -8.69397521e-01 4.89923090e-01 -6.39574081e-02 -8.67629230e-01 4.93048310e-01 -6.39574081e-02 -8.65915835e-01 4.96053696e-01 -6.39574081e-02 -8.64180863e-01 4.99071777e-01 -6.39574081e-02 -8.62460792e-01 5.02037704e-01 -6.39574081e-02 -8.60765100e-01 5.04937470e-01 -6.39574081e-02 -8.58933747e-01 5.08044779e-01 -6.39574081e-02 -8.57094884e-01 5.11142910e-01 -6.39574081e-02 -8.55301261e-01 5.14141023e-01 -6.39574081e-02 -8.53500366e-01 5.17120719e-01 -6.39574081e-02 -8.51733088e-01 5.20031989e-01 -6.39574081e-02 -8.49917948e-01 5.22987604e-01 -6.39574081e-02 -8.48046005e-01 5.26022434e-01 -6.39574081e-02 -8.46209228e-01 5.28968811e-01 -6.39574081e-02 -8.44401002e-01 5.31854272e-01 -6.39574081e-02 -8.42556834e-01 5.34767807e-01 -6.39574081e-02 -8.40600848e-01 5.37837863e-01 -6.39574081e-02 -8.38723600e-01 5.40758908e-01 -6.39574081e-02 -8.36822450e-01 5.43696463e-01 -6.39574081e-02 -8.34933162e-01 5.46591818e-01 -6.39574081e-02 -8.33091855e-01 5.49398959e-01 -6.39574081e-02 -8.31224620e-01 5.52212596e-01 -6.39574081e-02 -8.29232097e-01 5.55203855e-01 -6.39574081e-02 -8.27224374e-01 5.58194637e-01 -6.39574081e-02 -8.25325191e-01 5.60996175e-01 -6.39574081e-02 -8.23358297e-01 5.63878298e-01 -6.39574081e-02 -8.21329176e-01 5.66833198e-01 -6.39574081e-02 -8.19352746e-01 5.69684863e-01 -6.39574081e-02 -8.17341328e-01 5.72565317e-01 -6.39574081e-02 -8.15389335e-01 5.75346410e-01 -6.39574081e-02 -8.13430190e-01 5.78109324e-01 -6.39574081e-02 -8.11360061e-01 5.81010282e-01 -6.39574081e-02 -8.09241593e-01 5.83953559e-01 -6.39574081e-02 -8.07192087e-01 5.86788237e-01 -6.39574081e-02 -8.05142462e-01 5.89595139e-01 -6.39574081e-02 -8.03103626e-01 5.92370510e-01 -6.39574081e-02 -8.01051915e-01 5.95142066e-01 -6.39574081e-02 -7.98960805e-01 5.97945690e-01 -6.39574081e-02 -7.96853065e-01 6.00754857e-01 -6.39574081e-02 -7.94816852e-01 6.03446543e-01 -6.39574081e-02 -7.92695999e-01 6.06226921e-01 -6.39574081e-02 -7.90496707e-01 6.09091520e-01 -6.39574081e-02 -7.88367927e-01 6.11843169e-01 -6.39574081e-02 -7.86220551e-01 6.14602029e-01 -6.39574081e-02 -7.84124136e-01 6.17275894e-01 -6.39574081e-02 -7.81994581e-01 6.19969904e-01 -6.39574081e-02 -7.79806197e-01 6.22722149e-01 -6.39574081e-02 -7.77584195e-01 6.25492573e-01 -6.39574081e-02 -7.75401533e-01 6.28197908e-01 -6.39574081e-02 -7.73253322e-01 6.30839348e-01 -6.39574081e-02 -7.71051884e-01 6.33527875e-01 -6.39574081e-02 -7.68770754e-01 6.36295617e-01 -6.39574081e-02 -7.66548097e-01 6.38970435e-01 -6.39574081e-02 -7.64313459e-01 6.41641438e-01 -6.39574081e-02 -7.62118995e-01 6.44246340e-01 -6.39574081e-02 -7.59935021e-01 6.46820605e-01 -6.39574081e-02 -7.57620573e-01 6.49529397e-01 -6.39574081e-02 -7.55273521e-01 6.52260840e-01 -6.39574081e-02 -7.52995968e-01 6.54885232e-01 -6.39574081e-02 -7.50708163e-01 6.57506645e-01 -6.39574081e-02 -7.48421729e-01 6.60109341e-01 -6.39574081e-02 -7.46116757e-01 6.62713766e-01 -6.39574081e-02 -7.43767917e-01 6.65349305e-01 -6.39574081e-02 -7.41452575e-01 6.67927384e-01 -6.39574081e-02 -7.39178419e-01 6.70447767e-01 -6.39574081e-02 -7.36911416e-01 6.72934353e-01 -6.39574081e-02 -7.34498024e-01 6.75568759e-01 -6.39574081e-02 -7.32059896e-01 6.78209901e-01 -6.39574081e-02 -7.29690194e-01 6.80757344e-01 -6.39574081e-02 -7.27308571e-01 6.83301747e-01 -6.39574081e-02 -7.24922597e-01 6.85831904e-01 -6.39574081e-02 -7.22588420e-01 6.88295066e-01 -6.39574081e-02 -7.20167756e-01 6.90817237e-01 -6.39574081e-02 -7.17706382e-01 6.93388700e-01 -6.39574081e-02 -7.15329826e-01 6.95839047e-01 -6.39574081e-02 -7.12903917e-01 6.98318064e-01 -6.39574081e-02 -7.10400105e-01 7.00869560e-01 -6.39574081e-02 -7.07951605e-01 7.03345776e-01 -6.39574081e-02 -7.05469310e-01 7.05815911e-01 -6.39574081e-02 -7.03072488e-01 7.08223999e-01 -6.39574081e-02 -7.00608730e-01 7.10657001e-01 -6.39574081e-02 -6.98044300e-01 7.13173509e-01 -6.39574081e-02 -6.95631087e-01 7.15532243e-01 -6.39574081e-02 -6.93114281e-01 7.17971385e-01 -6.39574081e-02 -6.90591455e-01 7.20386207e-01 -6.39574081e-02 -6.88104153e-01 7.22768903e-01 -6.39574081e-02 -6.85489297e-01 7.25245118e-01 -6.39574081e-02 -6.82927489e-01 7.27657855e-01 -6.39574081e-02 -6.80410802e-01 7.30010986e-01 -6.39574081e-02 -6.77936435e-01 7.32313395e-01 -6.39574081e-02 -6.75376952e-01 7.34675705e-01 -6.39574081e-02 -6.72794938e-01 7.37039030e-01 -6.39574081e-02 -6.70224071e-01 7.39376903e-01 -6.39574081e-02 -6.67564273e-01 7.41780996e-01 -6.39574081e-02 -6.65039957e-01 7.44043887e-01 -6.39574081e-02 -6.62521660e-01 7.46288896e-01 -6.39574081e-02 -6.59871101e-01 7.48630404e-01 -6.39574081e-02 -6.57140434e-01 7.51027822e-01 -6.39574081e-02 -6.54520988e-01 7.53314614e-01 -6.39574081e-02 -6.51901484e-01 7.55581260e-01 -6.39574081e-02 -6.49318695e-01 7.57803559e-01 -6.39574081e-02 -6.46690428e-01 7.60043621e-01 -6.39574081e-02 -6.43951178e-01 7.62370050e-01 -6.39574081e-02 -6.41281545e-01 7.64616847e-01 -6.39574081e-02 -6.38668060e-01 7.66801953e-01 -6.39574081e-02 -6.36016726e-01 7.68999577e-01 -6.39574081e-02 -6.33231401e-01 7.71298468e-01 -6.39574081e-02 -6.30592704e-01 7.73453951e-01 -6.39574081e-02 -6.27911091e-01 7.75633633e-01 -6.39574081e-02 -6.25206590e-01 7.77816534e-01 -6.39574081e-02 -6.22506499e-01 7.79978096e-01 -6.39574081e-02 -6.19694650e-01 7.82213330e-01 -6.39574081e-02 -6.17016196e-01 7.84330189e-01 -6.39574081e-02 -6.14253223e-01 7.86493540e-01 -6.39574081e-02 -6.11453474e-01 7.88671613e-01 -6.39574081e-02 -6.08694851e-01 7.90804029e-01 -6.39574081e-02 -6.05978906e-01 7.92888224e-01 -6.39574081e-02 -6.03229344e-01 7.94980943e-01 -6.39574081e-02 -6.00379288e-01 7.97135174e-01 -6.39574081e-02 -5.97534895e-01 7.99268126e-01 -6.39574081e-02 -5.94854891e-01 8.01266730e-01 -6.39574081e-02 -5.92073739e-01 8.03320706e-01 -6.39574081e-02 -5.89147925e-01 8.05469692e-01 -6.39574081e-02 -5.86436331e-01 8.07449043e-01 -6.39574081e-02 -5.83624601e-01 8.09478343e-01 -6.39574081e-02 -5.80769360e-01 8.11535537e-01 -6.39574081e-02 -5.77950060e-01 8.13542664e-01 -6.39574081e-02 -5.75020254e-01 8.15618753e-01 -6.39574081e-02 -5.72164595e-01 8.17621589e-01 -6.39574081e-02 -5.69397032e-01 8.19553614e-01 -6.39574081e-02 -5.66568971e-01 8.21509361e-01 -6.39574081e-02 -5.63613951e-01 8.23542416e-01 -6.39574081e-02 -5.60791731e-01 8.25463176e-01 -6.39574081e-02 -5.57905436e-01 8.27417791e-01 -6.39574081e-02 -5.54993570e-01 8.29375207e-01 -6.39574081e-02 -5.52128673e-01 8.31282020e-01 -6.39574081e-02 -5.49199998e-01 8.33221793e-01 -6.39574081e-02 -5.46302140e-01 8.35122824e-01 -6.39574081e-02 -5.43318689e-01 8.37069333e-01 -6.39574081e-02 -5.40453911e-01 8.38922501e-01 -6.39574081e-02 -5.37533462e-01 8.40793729e-01 -6.39574081e-02 -5.34602582e-01 8.42660785e-01 -6.39574081e-02 -5.31657577e-01 8.44523609e-01 -6.39574081e-02 -5.28642774e-01 8.46413434e-01 -6.39574081e-02 -5.25679231e-01 8.48258913e-01 -6.39574081e-02 -5.22762775e-01 8.50057423e-01 -6.39574081e-02 -5.19806623e-01 8.51870000e-01 -6.39574081e-02 -5.16759038e-01 8.53719831e-01 -6.39574081e-02 -5.13848066e-01 8.55476856e-01 -6.39574081e-02 -5.10880828e-01 8.57250810e-01 -6.39574081e-02 -5.07863104e-01 8.59042823e-01 -6.39574081e-02 -5.04856467e-01 8.60812485e-01 -6.39574081e-02 -5.01760960e-01 8.62622738e-01 -6.39574081e-02 -4.98754978e-01 8.64362061e-01 -6.39574081e-02 -4.95838314e-01 8.66040587e-01 -6.39574081e-02 -4.92839962e-01 8.67746532e-01 -6.39574081e-02 -4.89724010e-01 8.69512379e-01 -6.39574081e-02 -4.86672431e-01 8.71221840e-01 -6.39574081e-02 -4.83640581e-01 8.72907341e-01 -6.39574081e-02 -4.80637193e-01 8.74568343e-01 -6.39574081e-02 -4.77615714e-01 8.76221240e-01 -6.39574081e-02 -4.74521250e-01 8.77900243e-01 -6.39574081e-02 -4.71483976e-01 8.79535556e-01 -6.39574081e-02 -4.68324691e-01 8.81222010e-01 -6.39574081e-02 -4.65306878e-01 8.82821202e-01 -6.39574081e-02 -4.62237418e-01 8.84429216e-01 -6.39574081e-02 -4.59104627e-01 8.86059105e-01 -6.39574081e-02 -4.56030518e-01 8.87645364e-01 -6.39574081e-02 -4.52867180e-01 8.89263809e-01 -6.39574081e-02 -4.49756920e-01 8.90841305e-01 -6.39574081e-02 -4.46734160e-01 8.92362297e-01 -6.39574081e-02 -4.43630427e-01 8.93908143e-01 -6.39574081e-02 -4.40427870e-01 8.95489335e-01 -6.39574081e-02 -4.37367201e-01 8.96991491e-01 -6.39574081e-02 -4.34332758e-01 8.98464322e-01 -6.39574081e-02 -4.31207955e-01 8.99964094e-01 -6.39574081e-02 -4.27995712e-01 9.01497483e-01 -6.39574081e-02 -4.24797624e-01 9.03010368e-01 -6.39574081e-02 -4.21725750e-01 9.04449522e-01 -6.39574081e-02 -4.18605059e-01 9.05897617e-01 -6.39574081e-02 -4.15425807e-01 9.07358527e-01 -6.39574081e-02 -4.12196308e-01 9.08830702e-01 -6.39574081e-02 -4.09011722e-01 9.10270274e-01 -6.39574081e-02 -4.05836791e-01 9.11688387e-01 -6.39574081e-02 -4.02639896e-01 9.13106203e-01 -6.39574081e-02 -3.99462134e-01 9.14500356e-01 -6.39574081e-02 -3.96206230e-01 9.15916204e-01 -6.39574081e-02 -3.93037587e-01 9.17274952e-01 -6.39574081e-02 -3.89786869e-01 9.18664098e-01 -6.39574081e-02 -3.86620522e-01 9.20003116e-01 -6.39574081e-02 -3.83426696e-01 9.21337664e-01 -6.39574081e-02 -3.80120128e-01 9.22704935e-01 -6.39574081e-02 -3.76921505e-01 9.24017549e-01 -6.39574081e-02 -3.73688757e-01 9.25330162e-01 -6.39574081e-02 -3.70462179e-01 9.26625907e-01 -6.39574081e-02 -3.67305577e-01 9.27883327e-01 -6.39574081e-02 -3.64059269e-01 9.29161251e-01 -6.39574081e-02 -3.60756427e-01 9.30442631e-01 -6.39574081e-02 -3.57586563e-01 9.31677401e-01 -6.39574081e-02 -3.54380637e-01 9.32891548e-01 -6.39574081e-02 -3.51137400e-01 9.34112132e-01 -6.39574081e-02 -3.47853154e-01 9.35338676e-01 -6.39574081e-02 -3.44541252e-01 9.36567426e-01 -6.39574081e-02 -3.41333658e-01 9.37749565e-01 -6.39574081e-02 -3.38082701e-01 9.38922942e-01 -6.39574081e-02 -3.34714502e-01 9.40131724e-01 -6.39574081e-02 -3.31319988e-01 9.41332638e-01 -6.39574081e-02 -3.28131914e-01 9.42447841e-01 -6.39574081e-02 -3.24828178e-01 9.43591774e-01 -6.39574081e-02 -3.21556479e-01 9.44712639e-01 -6.39574081e-02 -3.18263054e-01 9.45826769e-01 -6.39574081e-02 -3.14956009e-01 9.46934402e-01 -6.39574081e-02 -3.11747819e-01 9.47993457e-01 -6.39574081e-02 -3.08316976e-01 9.49114740e-01 -6.39574081e-02 -3.04911792e-01 9.50215101e-01 -6.39574081e-02 -3.01577896e-01 9.51279223e-01 -6.39574081e-02 -2.98258394e-01 9.52324331e-01 -6.39574081e-02 -2.95061946e-01 9.53318655e-01 -6.39574081e-02 -2.91703492e-01 9.54351068e-01 -6.39574081e-02 -2.88265109e-01 9.55395401e-01 -6.39574081e-02 -2.84930885e-01 9.56395447e-01 -6.39574081e-02 -2.81585246e-01 9.57387149e-01 -6.39574081e-02 -2.78347284e-01 9.58334625e-01 -6.39574081e-02 -2.75090158e-01 9.59272087e-01 -6.39574081e-02 -2.71735966e-01 9.60228741e-01 -6.39574081e-02 -2.68295139e-01 9.61194277e-01 -6.39574081e-02 -2.64837682e-01 9.62154210e-01 -6.39574081e-02 -2.61561751e-01 9.63052750e-01 -6.39574081e-02 -2.58214086e-01 9.63950813e-01 -6.39574081e-02 -2.54827529e-01 9.64854896e-01 -6.39574081e-02 -2.51476139e-01 9.65732872e-01 -6.39574081e-02 -2.48006701e-01 9.66629744e-01 -6.39574081e-02 -2.44702131e-01 9.67472136e-01 -6.39574081e-02 -2.41355181e-01 9.68309283e-01 -6.39574081e-02 -2.37940684e-01 9.69157696e-01 -6.39574081e-02 -2.34558702e-01 9.69982088e-01 -6.39574081e-02 -2.31170118e-01 9.70795572e-01 -6.39574081e-02 -2.27879211e-01 9.71571743e-01 -6.39574081e-02 -2.24397168e-01 9.72379863e-01 -6.39574081e-02 -2.20896423e-01 9.73183274e-01 -6.39574081e-02 -2.17524350e-01 9.73942518e-01 -6.39574081e-02 -2.14089349e-01 9.74700451e-01 -6.39574081e-02 -2.10779682e-01 9.75423098e-01 -6.39574081e-02 -2.07488388e-01 9.76128638e-01 -6.39574081e-02 -2.03989416e-01 9.76866305e-01 -6.39574081e-02 -2.00452700e-01 9.77598846e-01 -6.39574081e-02 -1.97018713e-01 9.78294849e-01 -6.39574081e-02 -1.93710506e-01 9.78957593e-01 -6.39574081e-02 -1.90417111e-01 9.79603291e-01 -6.39574081e-02 -1.87022150e-01 9.80255246e-01 -6.39574081e-02 -1.83495596e-01 9.80922103e-01 -6.39574081e-02 -1.79931968e-01 9.81579959e-01 -6.39574081e-02 -1.76629379e-01 9.82187390e-01 -6.39574081e-02 -1.73208266e-01 9.82794344e-01 -6.39574081e-02 -1.69779763e-01 9.83387947e-01 -6.39574081e-02 -1.66311651e-01 9.83980656e-01 -6.39574081e-02 -1.62774265e-01 9.84572172e-01 -6.39574081e-02 -1.59416810e-01 9.85122621e-01 -6.39574081e-02 -1.56006172e-01 9.85667169e-01 -6.39574081e-02 -1.52530611e-01 9.86213863e-01 -6.39574081e-02 -1.49097711e-01 9.86734629e-01 -6.39574081e-02 -1.45546198e-01 9.87265408e-01 -6.39574081e-02 -1.42206311e-01 9.87752438e-01 -6.39574081e-02 -1.38782069e-01 9.88240540e-01 -6.39574081e-02 -1.35226771e-01 9.88732576e-01 -6.39574081e-02 -1.31761074e-01 9.89201188e-01 -6.39574081e-02 -1.28393248e-01 9.89643991e-01 -6.39574081e-02 -1.25064075e-01 9.90070522e-01 -6.39574081e-02 -1.21575005e-01 9.90503848e-01 -6.39574081e-02 -1.18022904e-01 9.90932286e-01 -6.39574081e-02 -1.14446498e-01 9.91351604e-01 -6.39574081e-02 -1.11002199e-01 9.91744697e-01 -6.39574081e-02 -1.07642181e-01 9.92115259e-01 -6.39574081e-02 -1.04194060e-01 9.92480695e-01 -6.39574081e-02 -1.00695744e-01 9.92844880e-01 -6.39574081e-02 -9.72406343e-02 9.93186533e-01 -6.39574081e-02 -9.36935544e-02 9.93529439e-01 -6.39574081e-02 -9.02988985e-02 9.93844450e-01 -6.39574081e-02 -8.68361741e-02 9.94152606e-01 -6.39574081e-02 -8.33683982e-02 9.94449019e-01 -6.39574081e-02 -7.99131244e-02 9.94731128e-01 -6.39574081e-02 -7.64114633e-02 9.95007396e-01 -6.39574081e-02 -7.29571730e-02 9.95266616e-01 -6.39574081e-02 -6.94152117e-02 9.95518804e-01 -6.39574081e-02 -6.59946129e-02 9.95753169e-01 -6.39574081e-02 -6.25134259e-02 9.95973825e-01 -6.39574081e-02 -5.90516813e-02 9.96190250e-01 -6.39574081e-02 -5.56455515e-02 9.96386468e-01 -6.39574081e-02 -5.20835556e-02 9.96574402e-01 -6.39574081e-02 -4.85196896e-02 9.96758461e-01 -6.39574081e-02 -4.50529307e-02 9.96917784e-01 -6.39574081e-02 -4.15903479e-02 9.97070968e-01 -6.39574081e-02 -3.81811932e-02 9.97206628e-01 -6.39574081e-02 -3.48161124e-02 9.97328460e-01 -6.39574081e-02 -3.12423613e-02 9.97446597e-01 -6.39574081e-02 -2.76359245e-02 9.97553766e-01 -6.39574081e-02 -2.41511557e-02 9.97649431e-01 -6.39574081e-02 -2.07574610e-02 9.97720063e-01 -6.39574081e-02 -1.73892677e-02 9.97789860e-01 -6.39574081e-02 -1.38956839e-02 9.97837305e-01 -6.39574081e-02 -1.03249727e-02 9.97884512e-01 -6.39574081e-02 -6.70790719e-03 9.97921586e-01 -6.39574081e-02 -3.31954984e-03 9.97937322e-01 -6.39574081e-02 1.12009649e-04 9.97936904e-01 -6.39574081e-02 3.63776530e-03 9.97937143e-01 -6.39574081e-02 7.10589858e-03 9.97917116e-01 -6.39574081e-02 1.06922472e-02 9.97879863e-01 -6.39574081e-02 1.41647533e-02 9.97831881e-01 -6.39574081e-02 1.76542625e-02 9.97785211e-01 -6.39574081e-02 2.11319011e-02 9.97712433e-01 -6.39574081e-02 2.46054977e-02 9.97633696e-01 -6.39574081e-02 2.80992500e-02 9.97542441e-01 -6.39574081e-02 3.15015651e-02 9.97441471e-01 -6.39574081e-02 3.49860229e-02 9.97323811e-01 -6.39574081e-02 3.85431238e-02 9.97193515e-01 -6.39574081e-02 4.20359224e-02 9.97053206e-01 -6.39574081e-02 4.55191769e-02 9.96897995e-01 -6.39574081e-02 4.89324480e-02 9.96736884e-01 -6.39574081e-02 5.22977486e-02 9.96562779e-01 -6.39574081e-02 5.57590537e-02 9.96378541e-01 -6.39574081e-02 5.93419932e-02 9.96169031e-01 -6.39574081e-02 6.29108176e-02 9.95951712e-01 -6.39574081e-02 6.63023740e-02 9.95732069e-01 -6.39574081e-02 6.97571337e-02 9.95494306e-01 -6.39574081e-02 7.32404515e-02 9.95246947e-01 -6.39574081e-02 7.67125562e-02 9.94984329e-01 -6.39574081e-02 8.02786723e-02 9.94702101e-01 -6.39574081e-02 8.37548897e-02 9.94416177e-01 -6.39574081e-02 8.72291997e-02 9.94118094e-01 -6.39574081e-02 9.06467289e-02 9.93811548e-01 -6.39574081e-02 9.41662192e-02 9.93484855e-01 -6.39574081e-02 9.75397751e-02 9.93159890e-01 -6.39574081e-02 1.00989446e-01 9.92813468e-01 -6.39574081e-02 1.04559064e-01 9.92445230e-01 -6.39574081e-02 1.08025372e-01 9.92073178e-01 -6.39574081e-02 1.11480236e-01 9.91691411e-01 -6.39574081e-02 1.14947148e-01 9.91293788e-01 -6.39574081e-02 1.18331552e-01 9.90895927e-01 -6.39574081e-02 1.21759601e-01 9.90480542e-01 -6.39574081e-02 1.25315949e-01 9.90039110e-01 -6.39574081e-02 1.28780276e-01 9.89591956e-01 -6.39574081e-02 1.32244647e-01 9.89135444e-01 -6.39574081e-02 1.35600954e-01 9.88683641e-01 -6.39574081e-02 1.39035895e-01 9.88203585e-01 -6.39574081e-02 1.42509192e-01 9.87710297e-01 -6.39574081e-02 1.45920008e-01 9.87210095e-01 -6.39574081e-02 1.49448723e-01 9.86682177e-01 -6.39574081e-02 1.52833894e-01 9.86165881e-01 -6.39574081e-02 1.56265914e-01 9.85624433e-01 -6.39574081e-02 1.59802273e-01 9.85058963e-01 -6.39574081e-02 1.63228214e-01 9.84498680e-01 -6.39574081e-02 1.66661322e-01 9.83922720e-01 -6.39574081e-02 1.70121104e-01 9.83328342e-01 -6.39574081e-02 1.73555076e-01 9.82732892e-01 -6.39574081e-02 1.76884204e-01 9.82140839e-01 -6.39574081e-02 1.80308133e-01 9.81510878e-01 -6.39574081e-02 1.83829427e-01 9.80859935e-01 -6.39574081e-02 1.87163949e-01 9.80229139e-01 -6.39574081e-02 1.90571204e-01 9.79569852e-01 -6.39574081e-02 1.94099352e-01 9.78879094e-01 -6.39574081e-02 1.97488338e-01 9.78201926e-01 -6.39574081e-02 2.00866878e-01 9.77513015e-01 -6.39574081e-02 2.04233482e-01 9.76816058e-01 -6.39574081e-02 2.07554594e-01 9.76115882e-01 -6.39574081e-02 2.11068973e-01 9.75360513e-01 -6.39574081e-02 2.14567915e-01 9.74596918e-01 -6.39574081e-02 2.17945695e-01 9.73847687e-01 -6.39574081e-02 2.21267015e-01 9.73099291e-01 -6.39574081e-02 2.24557221e-01 9.72343624e-01 -6.39574081e-02 2.27953419e-01 9.71553504e-01 -6.39574081e-02 2.31415525e-01 9.70736563e-01 -6.39574081e-02 2.34898195e-01 9.69899535e-01 -6.39574081e-02 2.38306478e-01 9.69065666e-01 -6.39574081e-02 2.41681144e-01 9.68228459e-01 -6.39574081e-02 2.44984835e-01 9.67399538e-01 -6.39574081e-02 2.48312920e-01 9.66547787e-01 -6.39574081e-02 2.51816988e-01 9.65643406e-01 -6.39574081e-02 2.55120695e-01 9.64777887e-01 -6.39574081e-02 2.58470476e-01 9.63882923e-01 -6.39574081e-02 2.61875540e-01 9.62966323e-01 -6.39574081e-02 2.65231490e-01 9.62044001e-01 -6.39574081e-02 2.68534482e-01 9.61131752e-01 -6.39574081e-02 2.71789849e-01 9.60213900e-01 -6.39574081e-02 2.75219768e-01 9.59234595e-01 -6.39574081e-02 2.78703779e-01 9.58229244e-01 -6.39574081e-02 2.81982452e-01 9.57269251e-01 -6.39574081e-02 2.85246462e-01 9.56302881e-01 -6.39574081e-02 2.88516313e-01 9.55319881e-01 -6.39574081e-02 2.91827112e-01 9.54313755e-01 -6.39574081e-02 2.95248479e-01 9.53261614e-01 -6.39574081e-02 2.98654377e-01 9.52201128e-01 -6.39574081e-02 3.01908314e-01 9.51172709e-01 -6.39574081e-02 3.05162340e-01 9.50135827e-01 -6.39574081e-02 3.08533102e-01 9.49043334e-01 -6.39574081e-02 3.11837733e-01 9.47964191e-01 -6.39574081e-02 3.15131694e-01 9.46873188e-01 -6.39574081e-02 3.18515986e-01 9.45742846e-01 -6.39574081e-02 3.21802914e-01 9.44628179e-01 -6.39574081e-02 3.25104147e-01 9.43497300e-01 -6.39574081e-02 3.28356862e-01 9.42368925e-01 -6.39574081e-02 3.31638813e-01 9.41220045e-01 -6.39574081e-02 3.34872305e-01 9.40077424e-01 -6.39574081e-02 3.38157982e-01 9.38896239e-01 -6.39574081e-02 3.41495335e-01 9.37689841e-01 -6.39574081e-02 3.44763368e-01 9.36486363e-01 -6.39574081e-02 3.48026514e-01 9.35274661e-01 -6.39574081e-02 3.51235926e-01 9.34075058e-01 -6.39574081e-02 3.54397863e-01 9.32885051e-01 -6.39574081e-02 3.57730091e-01 9.31619525e-01 -6.39574081e-02 3.61040115e-01 9.30334508e-01 -6.39574081e-02 3.64289820e-01 9.29070771e-01 -6.39574081e-02 3.67547840e-01 9.27786946e-01 -6.39574081e-02 3.70699376e-01 9.26532507e-01 -6.39574081e-02 3.73927116e-01 9.25232470e-01 -6.39574081e-02 3.77227575e-01 9.23892796e-01 -6.39574081e-02 3.80439162e-01 9.22573507e-01 -6.39574081e-02 3.83657783e-01 9.21240628e-01 -6.39574081e-02 3.86809289e-01 9.19922113e-01 -6.39574081e-02 3.89987081e-01 9.18577611e-01 -6.39574081e-02 3.93207729e-01 9.17203128e-01 -6.39574081e-02 3.96406442e-01 9.15826857e-01 -6.39574081e-02 3.99684876e-01 9.14403379e-01 -6.39574081e-02 4.02880788e-01 9.12998915e-01 -6.39574081e-02 4.06014055e-01 9.11610425e-01 -6.39574081e-02 4.09168959e-01 9.10199523e-01 -6.39574081e-02 4.12305832e-01 9.08780098e-01 -6.39574081e-02 4.15505260e-01 9.07320976e-01 -6.39574081e-02 4.18654054e-01 9.05872583e-01 -6.39574081e-02 4.21858668e-01 9.04385746e-01 -6.39574081e-02 4.25001949e-01 9.02913392e-01 -6.39574081e-02 4.28116679e-01 9.01440203e-01 -6.39574081e-02 4.31341797e-01 8.99899781e-01 -6.39574081e-02 4.34378594e-01 8.98443103e-01 -6.39574081e-02 4.37532425e-01 8.96909118e-01 -6.39574081e-02 4.40773755e-01 8.95319223e-01 -6.39574081e-02 4.43899751e-01 8.93774331e-01 -6.39574081e-02 4.46999222e-01 8.92229259e-01 -6.39574081e-02 4.50061321e-01 8.90688300e-01 -6.39574081e-02 4.53150809e-01 8.89120221e-01 -6.39574081e-02 4.56200749e-01 8.87560308e-01 -6.39574081e-02 4.59322035e-01 8.85946333e-01 -6.39574081e-02 4.62470919e-01 8.84308219e-01 -6.39574081e-02 4.65544552e-01 8.82693648e-01 -6.39574081e-02 4.68658596e-01 8.81044447e-01 -6.39574081e-02 4.71688360e-01 8.79426539e-01 -6.39574081e-02 4.74751890e-01 8.77775431e-01 -6.39574081e-02 4.77834344e-01 8.76103222e-01 -6.39574081e-02 4.80865836e-01 8.74442279e-01 -6.39574081e-02 4.83930796e-01 8.72746527e-01 -6.39574081e-02 4.86920089e-01 8.71084392e-01 -6.39574081e-02 4.89952058e-01 8.69382143e-01 -6.39574081e-02 4.93066341e-01 8.67618620e-01 -6.39574081e-02 4.96096849e-01 8.65892410e-01 -6.39574081e-02 4.99113977e-01 8.64156365e-01 -6.39574081e-02 5.02138078e-01 8.62401903e-01 -6.39574081e-02 5.05137563e-01 8.60650361e-01 -6.39574081e-02 5.08122027e-01 8.58889639e-01 -6.39574081e-02 5.11034608e-01 8.57160449e-01 -6.39574081e-02 5.14050066e-01 8.55354965e-01 -6.39574081e-02 5.17100930e-01 8.53511393e-01 -6.39574081e-02 5.20078003e-01 8.51704955e-01 -6.39574081e-02 5.23073792e-01 8.49865675e-01 -6.39574081e-02 5.25934517e-01 8.48099828e-01 -6.39574081e-02 5.28895617e-01 8.46254349e-01 -6.39574081e-02 5.31839013e-01 8.44409525e-01 -6.39574081e-02 5.34763932e-01 8.42558563e-01 -6.39574081e-02 5.37810802e-01 8.40617597e-01 -6.39574081e-02 5.40665209e-01 8.38786304e-01 -6.39574081e-02 5.43478787e-01 8.36966038e-01 -6.39574081e-02 5.46416104e-01 8.35052371e-01 -6.39574081e-02 5.49340725e-01 8.33134294e-01 -6.39574081e-02 5.52305281e-01 8.31173122e-01 -6.39574081e-02 5.55230260e-01 8.29229236e-01 -6.39574081e-02 5.58104217e-01 8.27303588e-01 -6.39574155e-02 5.60811996e-01 8.25471997e-01 -6.39574602e-02 5.63589633e-01 8.23575437e-01 -6.39575645e-02 5.66441894e-01 8.21615636e-01 -6.39575571e-02 5.68567216e-01 8.20146680e-01 -6.39575422e-02 5.71545601e-01 8.18073690e-01 -6.39575422e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.08918691e-01 7.02384353e-01 -6.39575496e-02 7.10900128e-01 7.00380862e-01 -6.39574602e-02 7.13174820e-01 6.98067367e-01 -6.39574155e-02 7.15490341e-01 6.95684135e-01 -6.39574081e-02 7.17843115e-01 6.93248808e-01 -6.39574081e-02 7.20347345e-01 6.90640509e-01 -6.39574081e-02 7.22824037e-01 6.88051343e-01 -6.39574081e-02 7.25158572e-01 6.85587943e-01 -6.39574081e-02 7.27489531e-01 6.83110297e-01 -6.39574081e-02 7.29902864e-01 6.80528164e-01 -6.39574081e-02 7.32285619e-01 6.77967429e-01 -6.39574081e-02 7.34631002e-01 6.75425649e-01 -6.39574081e-02 7.37053037e-01 6.72778904e-01 -6.39574081e-02 7.39357412e-01 6.70248628e-01 -6.39574081e-02 7.41673172e-01 6.67683899e-01 -6.39574081e-02 7.43999481e-01 6.65090919e-01 -6.39574081e-02 7.46259332e-01 6.62553847e-01 -6.39574081e-02 7.48565376e-01 6.59946978e-01 -6.39574081e-02 7.50929594e-01 6.57252014e-01 -6.39574081e-02 7.53289938e-01 6.54549599e-01 -6.39574081e-02 7.55497634e-01 6.52000844e-01 -6.39574081e-02 7.57763624e-01 6.49362564e-01 -6.39574081e-02 7.60050297e-01 6.46686852e-01 -6.39574081e-02 7.62217283e-01 6.44133627e-01 -6.39574081e-02 7.64531434e-01 6.41381502e-01 -6.39574081e-02 7.66762078e-01 6.38716996e-01 -6.39574081e-02 7.68984914e-01 6.36034906e-01 -6.39574081e-02 7.71203637e-01 6.33347154e-01 -6.39574081e-02 7.73350000e-01 6.30718708e-01 -6.39574081e-02 7.75630772e-01 6.27913952e-01 -6.39574081e-02 7.77871132e-01 6.25136077e-01 -6.39574081e-02 7.80035257e-01 6.22434914e-01 -6.39574081e-02 7.82142639e-01 6.19784236e-01 -6.39574081e-02 7.84228206e-01 6.17145419e-01 -6.39574081e-02 7.86430359e-01 6.14333689e-01 -6.39574081e-02 7.88594425e-01 6.11556828e-01 -6.39574081e-02 7.90727317e-01 6.08792126e-01 -6.39574081e-02 7.92931020e-01 6.05921984e-01 -6.39574081e-02 7.95031965e-01 6.03160262e-01 -6.39574081e-02 7.97144055e-01 6.00367904e-01 -6.39574081e-02 7.99168229e-01 5.97670972e-01 -6.39574081e-02 8.01240504e-01 5.94886005e-01 -6.39574081e-02 8.03327382e-01 5.92069805e-01 -6.39574081e-02 8.05382788e-01 5.89265645e-01 -6.39574081e-02 8.07505906e-01 5.86357653e-01 -6.39574081e-02 8.09466779e-01 5.83644867e-01 -6.39574081e-02 8.11479151e-01 5.80841959e-01 -6.39574081e-02 8.13521087e-01 5.77984750e-01 -6.39574081e-02 8.15466583e-01 5.75234830e-01 -6.39574081e-02 8.17552090e-01 5.72265267e-01 -6.39574081e-02 8.19616258e-01 5.69304407e-01 -6.39574081e-02 8.21592093e-01 5.66452682e-01 -6.39574081e-02 8.23496282e-01 5.63680589e-01 -6.39574081e-02 8.25418472e-01 5.60858309e-01 -6.39574081e-02 8.27373683e-01 5.57971776e-01 -6.39574081e-02 8.29317510e-01 5.55076480e-01 -6.39574081e-02 8.31291437e-01 5.52113950e-01 -6.39574081e-02 8.33219826e-01 5.49203634e-01 -6.39574081e-02 8.35074544e-01 5.46377540e-01 -6.39574081e-02 8.37026894e-01 5.43380499e-01 -6.39574081e-02 8.38930547e-01 5.40439248e-01 -6.39574081e-02 8.40802312e-01 5.37520766e-01 -6.39574081e-02 8.42730045e-01 5.34494877e-01 -6.39574081e-02 8.44551623e-01 5.31614542e-01 -6.39574081e-02 8.46376836e-01 5.28700471e-01 -6.39574081e-02 8.48213375e-01 5.25750637e-01 -6.39574081e-02 8.50006819e-01 5.22844672e-01 -6.39574081e-02 8.51837516e-01 5.19861817e-01 -6.39574081e-02 8.53680193e-01 5.16824543e-01 -6.39574081e-02 8.55530679e-01 5.13758421e-01 -6.39574081e-02 8.57322633e-01 5.10760486e-01 -6.39574081e-02 8.59107316e-01 5.07754803e-01 -6.39574081e-02 8.60825181e-01 5.04838884e-01 -6.39574081e-02 8.62527907e-01 5.01921237e-01 -6.39574081e-02 8.64314973e-01 4.98838753e-01 -6.39574081e-02 8.66060078e-01 4.95804608e-01 -6.39574081e-02 8.67768288e-01 4.92805779e-01 -6.39574081e-02 8.69505227e-01 4.89741147e-01 -6.39574081e-02 8.71165335e-01 4.86773640e-01 -6.39574081e-02 8.72893333e-01 4.83667463e-01 -6.39574081e-02 8.74574900e-01 4.80624855e-01 -6.39574081e-02 8.76254141e-01 4.77558851e-01 -6.39574081e-02 8.77920568e-01 4.74484652e-01 -6.39574081e-02 8.79517853e-01 4.71517354e-01 -6.39574081e-02 8.81187916e-01 4.68389660e-01 -6.39574081e-02 8.82837534e-01 4.65275377e-01 -6.39574081e-02 8.84403706e-01 4.62290287e-01 -6.39574081e-02 8.86054218e-01 4.59114373e-01 -6.39574081e-02 8.87718558e-01 4.55892205e-01 -6.39574081e-02 8.89290512e-01 4.52816129e-01 -6.39574081e-02 8.90819967e-01 4.49803323e-01 -6.39574081e-02 8.92386675e-01 4.46681976e-01 -6.39574081e-02 8.93948495e-01 4.43550795e-01 -6.39574081e-02 8.95446181e-01 4.40519243e-01 -6.39574081e-02 8.97019744e-01 4.37304944e-01 -6.39574081e-02 8.98541749e-01 4.34177428e-01 -6.39574081e-02 9.00031090e-01 4.31069851e-01 -6.39574081e-02 9.01540995e-01 4.27911222e-01 -6.39574081e-02 9.02989447e-01 4.24837649e-01 -6.39574081e-02 9.04498637e-01 4.21618849e-01 -6.39574081e-02 9.06012893e-01 4.18355256e-01 -6.39574081e-02 9.07477200e-01 4.15166140e-01 -6.39574081e-02 9.08877075e-01 4.12097305e-01 -6.39574081e-02 9.10266280e-01 4.09019977e-01 -6.39574081e-02 9.11686897e-01 4.05841678e-01 -6.39574081e-02 9.13093388e-01 4.02666450e-01 -6.39574081e-02 9.14529920e-01 3.99391323e-01 -6.39574081e-02 9.15934026e-01 3.96163255e-01 -6.39574081e-02 9.17273343e-01 3.93042326e-01 -6.39574081e-02 9.18661416e-01 3.89792591e-01 -6.39574081e-02 9.20033813e-01 3.86548489e-01 -6.39574081e-02 9.21327293e-01 3.83449018e-01 -6.39574081e-02 9.22683835e-01 3.80171359e-01 -6.39574081e-02 9.24051702e-01 3.76838595e-01 -6.39574081e-02 9.25358891e-01 3.73619020e-01 -6.39574081e-02 9.26627338e-01 3.70463043e-01 -6.39574081e-02 9.27873552e-01 3.67332190e-01 -6.39574081e-02 9.29156721e-01 3.64073575e-01 -6.39574081e-02 9.30413961e-01 3.60831499e-01 -6.39574081e-02 9.31706429e-01 3.57502103e-01 -6.39574081e-02 9.32966709e-01 3.54180276e-01 -6.39574081e-02 9.34191644e-01 3.50925118e-01 -6.39574081e-02 9.35391188e-01 3.47713828e-01 -6.39574081e-02 9.36563015e-01 3.44555795e-01 -6.39574081e-02 9.37777877e-01 3.41252208e-01 -6.39574081e-02 9.38984215e-01 3.37912351e-01 -6.39574081e-02 9.40189302e-01 3.34554851e-01 -6.39574081e-02 9.41324055e-01 3.31347138e-01 -6.39574081e-02 9.42443371e-01 3.28142583e-01 -6.39574081e-02 9.43610847e-01 3.24770182e-01 -6.39574081e-02 9.44740236e-01 3.21474582e-01 -6.39574081e-02 9.45858479e-01 3.18168193e-01 -6.39574081e-02 9.46980774e-01 3.14809918e-01 -6.39574081e-02 9.48053360e-01 3.11567366e-01 -6.39574081e-02 9.49135363e-01 3.08251143e-01 -6.39574081e-02 9.50217903e-01 3.04911166e-01 -6.39574081e-02 9.51234043e-01 3.01718354e-01 -6.39574081e-02 9.52309608e-01 2.98304588e-01 -6.39574081e-02 9.53369737e-01 2.94894457e-01 -6.39574081e-02 9.54388082e-01 2.91584551e-01 -6.39574081e-02 9.55379963e-01 2.88319945e-01 -6.39574081e-02 9.56354439e-01 2.85066068e-01 -6.39574081e-02 9.57347333e-01 2.81721205e-01 -6.39574081e-02 9.58323896e-01 2.78381526e-01 -6.39574081e-02 9.59309220e-01 2.74956286e-01 -6.39574081e-02 9.60285842e-01 2.71533459e-01 -6.39574081e-02 9.61226285e-01 2.68186480e-01 -6.39574081e-02 9.62144196e-01 2.64876723e-01 -6.39574081e-02 9.63037133e-01 2.61616260e-01 -6.39574081e-02 9.63958085e-01 2.58185923e-01 -6.39574081e-02 9.64885235e-01 2.54708529e-01 -6.39574081e-02 9.65770245e-01 2.51335442e-01 -6.39574081e-02 9.66615736e-01 2.48067215e-01 -6.39574081e-02 9.67454314e-01 2.44759843e-01 -6.39574081e-02 9.68293548e-01 2.41423368e-01 -6.39574081e-02 9.69136477e-01 2.38018632e-01 -6.39574081e-02 9.69981670e-01 2.34556675e-01 -6.39574081e-02 9.70814645e-01 2.31085300e-01 -6.39574081e-02 9.71598029e-01 2.27768183e-01 -6.39574081e-02 9.72381115e-01 2.24392489e-01 -6.39574081e-02 9.73167181e-01 2.20969155e-01 -6.39574081e-02 9.73923862e-01 2.17614129e-01 -6.39574081e-02 9.74676311e-01 2.14203000e-01 -6.39574081e-02 9.75418389e-01 2.10794255e-01 -6.39574081e-02 9.76174772e-01 2.07274854e-01 -6.39574081e-02 9.76872385e-01 2.03967348e-01 -6.39574081e-02 9.77575362e-01 2.00569481e-01 -6.39574081e-02 9.78272557e-01 1.97136208e-01 -6.39574081e-02 9.78932261e-01 1.93835899e-01 -6.39574081e-02 9.79623377e-01 1.90305278e-01 -6.39574081e-02 9.80280519e-01 1.86893135e-01 -6.39574081e-02 9.80923116e-01 1.83488190e-01 -6.39574081e-02 9.81557667e-01 1.80055380e-01 -6.39574081e-02 9.82173622e-01 1.76702380e-01 -6.39574081e-02 9.82797027e-01 1.73196703e-01 -6.39574081e-02 9.83405948e-01 1.69676781e-01 -6.39574081e-02 9.83997583e-01 1.66215748e-01 -6.39574081e-02 9.84549940e-01 1.62912220e-01 -6.39574081e-02 9.85095918e-01 1.59572646e-01 -6.39574081e-02 9.85665977e-01 1.56014055e-01 -6.39574081e-02 9.86207128e-01 1.52562931e-01 -6.39574081e-02 9.86725628e-01 1.49153829e-01 -6.39574081e-02 9.87245977e-01 1.45692796e-01 -6.39574081e-02 9.87730980e-01 1.42346635e-01 -6.39574081e-02 9.88236010e-01 1.38812318e-01 -6.39574081e-02 9.88716483e-01 1.35357544e-01 -6.39574081e-02 9.89187598e-01 1.31857112e-01 -6.39574081e-02 9.89641309e-01 1.28411084e-01 -6.39574081e-02 9.90079284e-01 1.24987356e-01 -6.39574081e-02 9.90521848e-01 1.21432595e-01 -6.39574081e-02 9.90944266e-01 1.17922567e-01 -6.39574081e-02 9.91348684e-01 1.14478141e-01 -6.39574081e-02 9.91732359e-01 1.11116529e-01 -6.39574081e-02 9.92101371e-01 1.07759900e-01 -6.39574081e-02 9.92478788e-01 1.04221091e-01 -6.39574081e-02 9.92841423e-01 1.00721076e-01 -6.39574081e-02 9.93181884e-01 9.72779468e-02 -6.39574081e-02 9.93520617e-01 9.37932953e-02 -6.39574081e-02 9.93830085e-01 9.04542729e-02 -6.39574081e-02 9.94142354e-01 8.69589448e-02 -6.39574081e-02 9.94437575e-01 8.34958181e-02 -6.39574081e-02 9.94732797e-01 7.98974782e-02 -6.39574081e-02 9.95014966e-01 7.63122216e-02 -6.39574081e-02 9.95272160e-01 7.28770494e-02 -6.39574081e-02 9.95517790e-01 6.94129542e-02 -6.39574081e-02 9.95752335e-01 6.60018995e-02 -6.39574081e-02 9.95968342e-01 6.26410022e-02 -6.39574081e-02 9.96182859e-01 5.91355339e-02 -6.39574081e-02 9.96387243e-01 5.55790141e-02 -6.39574081e-02 9.96580899e-01 5.19986711e-02 -6.39574081e-02 9.96753335e-01 4.86095622e-02 -6.39574081e-02 9.96910989e-01 4.52433750e-02 -6.39574081e-02 9.97063160e-01 4.17463779e-02 -6.39574081e-02 9.97203112e-01 3.82645093e-02 -6.39574081e-02 9.97331560e-01 3.47168669e-02 -6.39574081e-02 9.97450769e-01 3.11292354e-02 -6.39574081e-02 9.97552514e-01 2.77362168e-02 -6.39574081e-02 9.97642934e-01 2.43286639e-02 -6.39574081e-02 9.97716963e-01 2.08437424e-02 -6.39574081e-02 9.97790873e-01 1.73654221e-02 -6.39574081e-02 9.97835577e-01 1.38836289e-02 -6.39574081e-02 9.97882962e-01 1.04005067e-02 -6.39574081e-02 9.97919858e-01 6.92588836e-03 -6.39574081e-02 9.97935534e-01 3.37489694e-03 -6.39574081e-02 9.97938275e-01 -1.38005576e-04 -6.39574081e-02 9.97935236e-01 -3.61040980e-03 -6.39574081e-02 9.97917295e-01 -7.12551503e-03 -6.39574081e-02 9.97882307e-01 -1.04927309e-02 -6.39574081e-02 9.97831643e-01 -1.40647246e-02 -6.39574081e-02 9.97785270e-01 -1.76534615e-02 -6.39574081e-02 9.97714520e-01 -2.10236721e-02 -6.39574081e-02 9.97637510e-01 -2.45011803e-02 -6.39574081e-02 9.97545362e-01 -2.80008148e-02 -6.39574081e-02 9.97440159e-01 -3.14793698e-02 -6.39574081e-02 9.97325599e-01 -3.49724330e-02 -6.39574081e-02 9.97199357e-01 -3.83619741e-02 -6.39574081e-02 9.97060657e-01 -4.18401361e-02 -6.39574081e-02 9.96902883e-01 -4.54013348e-02 -6.39574081e-02 9.96736288e-01 -4.89636920e-02 -6.39574081e-02 9.96554315e-01 -5.24634793e-02 -6.39574081e-02 9.96372461e-01 -5.58648929e-02 -6.39574081e-02 9.96177852e-01 -5.92178032e-02 -6.39574081e-02 9.95963693e-01 -6.26961291e-02 -6.39574081e-02 9.95736301e-01 -6.62263855e-02 -6.39574081e-02 9.95490491e-01 -6.98063076e-02 -6.39574081e-02 9.95242476e-01 -7.32784644e-02 -6.39574081e-02 9.94986176e-01 -7.66952857e-02 -6.39574081e-02 9.94719923e-01 -8.00693706e-02 -6.39574081e-02 9.94433224e-01 -8.35475400e-02 -6.39574081e-02 9.94128764e-01 -8.70951563e-02 -6.39574081e-02 9.93817151e-01 -9.05806720e-02 -6.39574081e-02 9.93504345e-01 -9.39576700e-02 -6.39574081e-02 9.93170083e-01 -9.74199548e-02 -6.39574081e-02 9.92817521e-01 -1.00947790e-01 -6.39574081e-02 9.92457449e-01 -1.04440406e-01 -6.39574081e-02 9.92085993e-01 -1.07897386e-01 -6.39574081e-02 9.91701424e-01 -1.11397982e-01 -6.39574081e-02 9.91318107e-01 -1.14732690e-01 -6.39574081e-02 9.90903258e-01 -1.18268609e-01 -6.39574081e-02 9.90482330e-01 -1.21753678e-01 -6.39574081e-02 9.90054607e-01 -1.25188172e-01 -6.39574081e-02 9.89598572e-01 -1.28723994e-01 -6.39574081e-02 9.89153206e-01 -1.32117137e-01 -6.39574081e-02 9.88686621e-01 -1.35559767e-01 -6.39574081e-02 9.88199890e-01 -1.39069021e-01 -6.39574081e-02 9.87716258e-01 -1.42463610e-01 -6.39574081e-02 9.87212121e-01 -1.45900756e-01 -6.39574081e-02 9.86696959e-01 -1.49355292e-01 -6.39574081e-02 9.86169159e-01 -1.52791470e-01 -6.39574081e-02 9.85633135e-01 -1.56222731e-01 -6.39574081e-02 9.85085607e-01 -1.59635752e-01 -6.39574081e-02 9.84523535e-01 -1.63074374e-01 -6.39574081e-02 9.83945310e-01 -1.66522399e-01 -6.39574081e-02 9.83337402e-01 -1.70066252e-01 -6.39574081e-02 9.82743084e-01 -1.73495978e-01 -6.39574081e-02 9.82149661e-01 -1.76831529e-01 -6.39574081e-02 9.81536746e-01 -1.80164784e-01 -6.39574081e-02 9.80906188e-01 -1.83587596e-01 -6.39574081e-02 9.80244100e-01 -1.87077165e-01 -6.39574081e-02 9.79566276e-01 -1.90596923e-01 -6.39574081e-02 9.78893161e-01 -1.94024175e-01 -6.39574081e-02 9.78222668e-01 -1.97385564e-01 -6.39574081e-02 9.77548182e-01 -2.00693727e-01 -6.39574081e-02 9.76843238e-01 -2.04100609e-01 -6.39574081e-02 9.76104498e-01 -2.07600251e-01 -6.39574081e-02 9.75374579e-01 -2.11014345e-01 -6.39574081e-02 9.74632800e-01 -2.14396521e-01 -6.39574081e-02 9.73880470e-01 -2.17805028e-01 -6.39574081e-02 9.73109961e-01 -2.21204549e-01 -6.39574081e-02 9.72331285e-01 -2.24617094e-01 -6.39574081e-02 9.71547127e-01 -2.27991700e-01 -6.39574081e-02 9.70745087e-01 -2.31381759e-01 -6.39574081e-02 9.69952524e-01 -2.34682620e-01 -6.39574081e-02 9.69103277e-01 -2.38150954e-01 -6.39574081e-02 9.68271613e-01 -2.41513774e-01 -6.39574081e-02 9.67419267e-01 -2.44893745e-01 -6.39574081e-02 9.66532409e-01 -2.48383731e-01 -6.39574081e-02 9.65682924e-01 -2.51674116e-01 -6.39574081e-02 9.64802682e-01 -2.55016059e-01 -6.39574081e-02 9.63904381e-01 -2.58399427e-01 -6.39574081e-02 9.63024259e-01 -2.61659384e-01 -6.39574081e-02 9.62077022e-01 -2.65113980e-01 -6.39574081e-02 9.61137295e-01 -2.68508255e-01 -6.39574081e-02 9.60201621e-01 -2.71830052e-01 -6.39574081e-02 9.59218025e-01 -2.75279403e-01 -6.39574081e-02 9.58278179e-01 -2.78537005e-01 -6.39574081e-02 9.57329273e-01 -2.81775355e-01 -6.39574081e-02 9.56316650e-01 -2.85195351e-01 -6.39574081e-02 9.55280304e-01 -2.88642853e-01 -6.39574081e-02 9.54270720e-01 -2.91974097e-01 -6.39574081e-02 9.53267932e-01 -2.95231760e-01 -6.39574081e-02 9.52266991e-01 -2.98438251e-01 -6.39574081e-02 9.51220751e-01 -3.01758707e-01 -6.39574081e-02 9.50150430e-01 -3.05113494e-01 -6.39574081e-02 9.49059546e-01 -3.08483273e-01 -6.39574081e-02 9.47949648e-01 -3.11880171e-01 -6.39574081e-02 9.46876407e-01 -3.15126300e-01 -6.39574081e-02 9.45801437e-01 -3.18339497e-01 -6.39574081e-02 9.44686413e-01 -3.21631551e-01 -6.39574081e-02 9.43535984e-01 -3.24986458e-01 -6.39574081e-02 9.42386746e-01 -3.28307718e-01 -6.39574081e-02 9.41245794e-01 -3.31561774e-01 -6.39574081e-02 9.40073431e-01 -3.34883064e-01 -6.39574081e-02 9.38902676e-01 -3.38140219e-01 -6.39574081e-02 9.37717378e-01 -3.41424167e-01 -6.39574081e-02 9.36504066e-01 -3.44716102e-01 -6.39574081e-02 9.35287356e-01 -3.47991556e-01 -6.39574081e-02 9.34112549e-01 -3.51137578e-01 -6.39574081e-02 9.32887852e-01 -3.54389340e-01 -6.39574081e-02 9.31605101e-01 -3.57768625e-01 -6.39574081e-02 9.30340409e-01 -3.61023784e-01 -6.39574081e-02 9.29090559e-01 -3.64237726e-01 -6.39574081e-02 9.27806973e-01 -3.67498457e-01 -6.39574081e-02 9.26519334e-01 -3.70727807e-01 -6.39574081e-02 9.25218046e-01 -3.73964638e-01 -6.39574081e-02 9.23952341e-01 -3.77079695e-01 -6.39574081e-02 9.22575712e-01 -3.80431563e-01 -6.39574081e-02 9.21249568e-01 -3.83638471e-01 -6.39574081e-02 9.19920146e-01 -3.86808693e-01 -6.39574081e-02 9.18513775e-01 -3.90137136e-01 -6.39574081e-02 9.17183280e-01 -3.93254638e-01 -6.39574081e-02 9.15844798e-01 -3.96365404e-01 -6.39574081e-02 9.14418578e-01 -3.99649173e-01 -6.39574081e-02 9.12981212e-01 -4.02918726e-01 -6.39574081e-02 9.11575675e-01 -4.06090170e-01 -6.39574081e-02 9.10188675e-01 -4.09193397e-01 -6.39574081e-02 9.08793330e-01 -4.12276328e-01 -6.39574081e-02 9.07349885e-01 -4.15438384e-01 -6.39574081e-02 9.05845284e-01 -4.18712407e-01 -6.39574081e-02 9.04343188e-01 -4.21948254e-01 -6.39574081e-02 9.02871609e-01 -4.25087214e-01 -6.39574081e-02 9.01414096e-01 -4.28171605e-01 -6.39574081e-02 8.99955392e-01 -4.31225568e-01 -6.39574081e-02 8.98441792e-01 -4.34378117e-01 -6.39574081e-02 8.96877706e-01 -4.37595814e-01 -6.39574081e-02 8.95338237e-01 -4.40736741e-01 -6.39574081e-02 8.93812835e-01 -4.43818539e-01 -6.39574081e-02 8.92253518e-01 -4.46950167e-01 -6.39574081e-02 8.90729785e-01 -4.49979216e-01 -6.39574081e-02 8.89161170e-01 -4.53070015e-01 -6.39574081e-02 8.87532055e-01 -4.56249535e-01 -6.39574081e-02 8.85932684e-01 -4.59350377e-01 -6.39574081e-02 8.84350717e-01 -4.62391913e-01 -6.39574081e-02 8.82740855e-01 -4.65456337e-01 -6.39574081e-02 8.81070197e-01 -4.68605340e-01 -6.39574081e-02 8.79430294e-01 -4.71682578e-01 -6.39574081e-02 8.77783775e-01 -4.74733561e-01 -6.39574081e-02 8.76110137e-01 -4.77822810e-01 -6.39574081e-02 8.74489963e-01 -4.80777591e-01 -6.39574081e-02 8.72800171e-01 -4.83834058e-01 -6.39574081e-02 8.71108592e-01 -4.86876249e-01 -6.39574081e-02 8.69406223e-01 -4.89910334e-01 -6.39574081e-02 8.67646098e-01 -4.93017554e-01 -6.39574081e-02 8.65912497e-01 -4.96061027e-01 -6.39574081e-02 8.64176691e-01 -4.99075174e-01 -6.39574081e-02 8.62432897e-01 -5.02087116e-01 -6.39574081e-02 8.60726714e-01 -5.05005002e-01 -6.39574081e-02 8.58954847e-01 -5.08009791e-01 -6.39574081e-02 8.57176960e-01 -5.11004031e-01 -6.39574081e-02 8.55332375e-01 -5.14086246e-01 -6.39574081e-02 8.53507280e-01 -5.17108858e-01 -6.39574081e-02 8.51743758e-01 -5.20014405e-01 -6.39574081e-02 8.49952996e-01 -5.22930980e-01 -6.39574081e-02 8.48133028e-01 -5.25881231e-01 -6.39574081e-02 8.46252620e-01 -5.28898537e-01 -6.39574081e-02 8.44353437e-01 -5.31926513e-01 -6.39574081e-02 8.42528284e-01 -5.34814596e-01 -6.39574081e-02 8.40696573e-01 -5.37687063e-01 -6.39574081e-02 8.38771105e-01 -5.40684819e-01 -6.39574081e-02 8.36818218e-01 -5.43704331e-01 -6.39574081e-02 8.34930420e-01 -5.46594739e-01 -6.39574081e-02 8.33022654e-01 -5.49500525e-01 -6.39574081e-02 8.31137300e-01 -5.52345812e-01 -6.39574081e-02 8.29270482e-01 -5.55146396e-01 -6.39574081e-02 8.27320337e-01 -5.58052897e-01 -6.39574081e-02 8.25309873e-01 -5.61016381e-01 -6.39574081e-02 8.23346078e-01 -5.63899517e-01 -6.39574081e-02 8.21370602e-01 -5.66769958e-01 -6.39574081e-02 8.19377720e-01 -5.69650531e-01 -6.39574081e-02 8.17395627e-01 -5.72484434e-01 -6.39574081e-02 8.15392673e-01 -5.75340986e-01 -6.39574081e-02 8.13387275e-01 -5.78167856e-01 -6.39574081e-02 8.11358631e-01 -5.81016481e-01 -6.39574081e-02 8.09363484e-01 -5.83782256e-01 -6.39574081e-02 8.07269514e-01 -5.86680651e-01 -6.39574081e-02 8.05203378e-01 -5.89512587e-01 -6.39574081e-02 8.03149760e-01 -5.92306674e-01 -6.39574081e-02 8.01042318e-01 -5.95152855e-01 -6.39574081e-02 7.99016893e-01 -5.97871602e-01 -6.39574081e-02 7.96940207e-01 -6.00636601e-01 -6.39574081e-02 7.94832230e-01 -6.03425205e-01 -6.39574081e-02 7.92774141e-01 -6.06126070e-01 -6.39574081e-02 7.90626287e-01 -6.08922184e-01 -6.39574081e-02 7.88440883e-01 -6.11748576e-01 -6.39574081e-02 7.86266029e-01 -6.14542127e-01 -6.39574081e-02 7.84115911e-01 -6.17285013e-01 -6.39574081e-02 7.82009065e-01 -6.19952023e-01 -6.39574081e-02 7.79902995e-01 -6.22598886e-01 -6.39574081e-02 7.77715623e-01 -6.25330567e-01 -6.39574081e-02 7.75485039e-01 -6.28094256e-01 -6.39574081e-02 7.73229420e-01 -6.30866408e-01 -6.39574081e-02 7.71082938e-01 -6.33489966e-01 -6.39574081e-02 7.68932164e-01 -6.36099398e-01 -6.39574081e-02 7.66724288e-01 -6.38759673e-01 -6.39574081e-02 7.64483452e-01 -6.41438782e-01 -6.39574081e-02 7.62167931e-01 -6.44185722e-01 -6.39574081e-02 7.59910405e-01 -6.46850228e-01 -6.39574081e-02 7.57640660e-01 -6.49503767e-01 -6.39574081e-02 7.55355895e-01 -6.52165174e-01 -6.39574081e-02 7.53122449e-01 -6.54740691e-01 -6.39574081e-02 7.50761151e-01 -6.57444835e-01 -6.39574081e-02 7.48458743e-01 -6.60067618e-01 -6.39574081e-02 7.46233881e-01 -6.62582219e-01 -6.39574081e-02 7.43946731e-01 -6.65149510e-01 -6.39574081e-02 7.41554976e-01 -6.67811871e-01 -6.39574081e-02 7.39199817e-01 -6.70423329e-01 -6.39574081e-02 7.36859143e-01 -6.72989547e-01 -6.39574081e-02 7.34500289e-01 -6.75567150e-01 -6.39574081e-02 7.32204080e-01 -6.78051353e-01 -6.39574081e-02 7.29840577e-01 -6.80593789e-01 -6.39574081e-02 7.27380276e-01 -6.83222830e-01 -6.39574081e-02 7.24975526e-01 -6.85775399e-01 -6.39574081e-02 7.22594321e-01 -6.88286424e-01 -6.39574081e-02 7.20200479e-01 -6.90788507e-01 -6.39574081e-02 7.17864633e-01 -6.93225682e-01 -6.39574081e-02 7.15614557e-01 -6.95562840e-01 -6.39574155e-02 7.13171005e-01 -6.98067129e-01 -6.39575645e-02 7.10568011e-01 -7.00715303e-01 -6.39575496e-02 7.08010316e-01 -7.03299344e-01 -6.39575422e-02 7.05627978e-01 -7.05689669e-01 -6.39575422e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 5.71690202e-01 -8.17973197e-01 -6.39575645e-02 5.69332004e-01 -8.19618046e-01 -6.39574155e-02 5.66574872e-01 -8.21520030e-01 -6.39574081e-02 5.63765228e-01 -8.23443592e-01 -6.39574081e-02 5.60878038e-01 -8.25410068e-01 -6.39574081e-02 5.58013856e-01 -8.27348113e-01 -6.39574081e-02 5.55149436e-01 -8.29270899e-01 -6.39574081e-02 5.52165329e-01 -8.31257999e-01 -6.39574081e-02 5.49217701e-01 -8.33211362e-01 -6.39574081e-02 5.46415150e-01 -8.35050404e-01 -6.39574081e-02 5.43428421e-01 -8.36995304e-01 -6.39574081e-02 5.40500283e-01 -8.38890553e-01 -6.39574081e-02 5.37644029e-01 -8.40723217e-01 -6.39574081e-02 5.34708142e-01 -8.42592537e-01 -6.39574081e-02 5.31765878e-01 -8.44456971e-01 -6.39574081e-02 5.28825045e-01 -8.46297204e-01 -6.39574081e-02 5.25888979e-01 -8.48129511e-01 -6.39574081e-02 5.22905052e-01 -8.49969268e-01 -6.39574081e-02 5.19953847e-01 -8.51781070e-01 -6.39574081e-02 5.16940057e-01 -8.53609741e-01 -6.39574081e-02 5.13972819e-01 -8.55401099e-01 -6.39574081e-02 5.10977566e-01 -8.57192457e-01 -6.39574081e-02 5.07979214e-01 -8.58973265e-01 -6.39574081e-02 5.04981816e-01 -8.60739827e-01 -6.39574081e-02 5.01959622e-01 -8.62504721e-01 -6.39574081e-02 4.98868227e-01 -8.64296138e-01 -6.39574081e-02 4.95850950e-01 -8.66032481e-01 -6.39574081e-02 4.92908567e-01 -8.67708147e-01 -6.39574081e-02 4.89882261e-01 -8.69423985e-01 -6.39574081e-02 4.86844242e-01 -8.71124864e-01 -6.39574081e-02 4.83779669e-01 -8.72829974e-01 -6.39574081e-02 4.80727911e-01 -8.74518037e-01 -6.39574081e-02 4.77663726e-01 -8.76195431e-01 -6.39574081e-02 4.74624991e-01 -8.77843320e-01 -6.39574081e-02 4.71544325e-01 -8.79503071e-01 -6.39574081e-02 4.68473434e-01 -8.81140709e-01 -6.39574081e-02 4.65392858e-01 -8.82773638e-01 -6.39574081e-02 4.62230206e-01 -8.84431601e-01 -6.39574081e-02 4.59109753e-01 -8.86056781e-01 -6.39574081e-02 4.56121802e-01 -8.87599289e-01 -6.39574081e-02 4.53013897e-01 -8.89188826e-01 -6.39574081e-02 4.49896753e-01 -8.90770316e-01 -6.39574081e-02 4.46779877e-01 -8.92336786e-01 -6.39574081e-02 4.43672508e-01 -8.93886209e-01 -6.39574081e-02 4.40561026e-01 -8.95424128e-01 -6.39574081e-02 4.37414944e-01 -8.96965504e-01 -6.39574081e-02 4.34289753e-01 -8.98484588e-01 -6.39574081e-02 4.31159437e-01 -8.99987161e-01 -6.39574081e-02 4.28023487e-01 -9.01483357e-01 -6.39574081e-02 4.24856484e-01 -9.02980864e-01 -6.39574081e-02 4.21640366e-01 -9.04488087e-01 -6.39574081e-02 4.18453604e-01 -9.05967593e-01 -6.39574081e-02 4.15378988e-01 -9.07379389e-01 -6.39574081e-02 4.12206739e-01 -9.08825934e-01 -6.39574081e-02 4.09041733e-01 -9.10254955e-01 -6.39574081e-02 4.05782193e-01 -9.11712706e-01 -6.39574081e-02 4.02582973e-01 -9.13130045e-01 -6.39574081e-02 3.99467766e-01 -9.14498448e-01 -6.39574081e-02 3.96270484e-01 -9.15886521e-01 -6.39574081e-02 3.93064499e-01 -9.17262971e-01 -6.39574081e-02 3.89783829e-01 -9.18663561e-01 -6.39574081e-02 3.86578828e-01 -9.20020938e-01 -6.39574081e-02 3.83376032e-01 -9.21357214e-01 -6.39574081e-02 3.80153298e-01 -9.22691286e-01 -6.39574081e-02 3.77012104e-01 -9.23981071e-01 -6.39574081e-02 3.73800576e-01 -9.25283968e-01 -6.39574081e-02 3.70469689e-01 -9.26622033e-01 -6.39574081e-02 3.67137700e-01 -9.27949190e-01 -6.39574081e-02 3.63984048e-01 -9.29191649e-01 -6.39574081e-02 3.60836118e-01 -9.30410981e-01 -6.39574081e-02 3.57571244e-01 -9.31681514e-01 -6.39574081e-02 3.54324251e-01 -9.32912469e-01 -6.39574081e-02 3.51006687e-01 -9.34160888e-01 -6.39574081e-02 3.47751468e-01 -9.35376823e-01 -6.39574081e-02 3.44537735e-01 -9.36569870e-01 -6.39574081e-02 3.41260642e-01 -9.37775493e-01 -6.39574081e-02 3.38002354e-01 -9.38950956e-01 -6.39574081e-02 3.34717780e-01 -9.40130055e-01 -6.39574081e-02 3.31422120e-01 -9.41295505e-01 -6.39574081e-02 3.28143179e-01 -9.42443252e-01 -6.39574081e-02 3.24768990e-01 -9.43611920e-01 -6.39574081e-02 3.21471840e-01 -9.44741189e-01 -6.39574081e-02 3.18257898e-01 -9.45828915e-01 -6.39574081e-02 3.14989388e-01 -9.46921170e-01 -6.39574081e-02 3.11681718e-01 -9.48014915e-01 -6.39574081e-02 3.08259636e-01 -9.49133158e-01 -6.39574081e-02 3.04933667e-01 -9.50209916e-01 -6.39574081e-02 3.01748574e-01 -9.51223433e-01 -6.39574081e-02 2.98416108e-01 -9.52273846e-01 -6.39574081e-02 2.95082539e-01 -9.53312874e-01 -6.39574081e-02 2.91755944e-01 -9.54335749e-01 -6.39574081e-02 2.88345724e-01 -9.55369115e-01 -6.39574081e-02 2.84990311e-01 -9.56379116e-01 -6.39574081e-02 2.81728417e-01 -9.57344651e-01 -6.39574081e-02 2.78298557e-01 -9.58347261e-01 -6.39574081e-02 2.74839014e-01 -9.59343076e-01 -6.39574081e-02 2.71486819e-01 -9.60298181e-01 -6.39574081e-02 2.68209070e-01 -9.61221278e-01 -6.39574081e-02 2.64981210e-01 -9.62114632e-01 -6.39574081e-02 2.61612505e-01 -9.63037729e-01 -6.39574081e-02 2.58231610e-01 -9.63946879e-01 -6.39574081e-02 2.54828930e-01 -9.64852989e-01 -6.39574081e-02 2.51466125e-01 -9.65736032e-01 -6.39574081e-02 2.48117283e-01 -9.66601610e-01 -6.39574081e-02 2.44746134e-01 -9.67457294e-01 -6.39574081e-02 2.41292819e-01 -9.68324840e-01 -6.39574081e-02 2.37898216e-01 -9.69167292e-01 -6.39574081e-02 2.34606981e-01 -9.69970882e-01 -6.39574081e-02 2.31233269e-01 -9.70779240e-01 -6.39574081e-02 2.27832913e-01 -9.71582711e-01 -6.39574081e-02 2.24364415e-01 -9.72387314e-01 -6.39574081e-02 2.20852345e-01 -9.73192811e-01 -6.39574081e-02 2.17552960e-01 -9.73936260e-01 -6.39574081e-02 2.14244917e-01 -9.74667728e-01 -6.39574081e-02 2.10850582e-01 -9.75407422e-01 -6.39574081e-02 2.07444936e-01 -9.76137459e-01 -6.39574081e-02 2.03940123e-01 -9.76876915e-01 -6.39574081e-02 2.00519428e-01 -9.77585793e-01 -6.39574081e-02 1.97216898e-01 -9.78256464e-01 -6.39574081e-02 1.93793103e-01 -9.78938282e-01 -6.39574081e-02 1.90376416e-01 -9.79610205e-01 -6.39574081e-02 1.86895221e-01 -9.80279446e-01 -6.39574081e-02 1.83429420e-01 -9.80933368e-01 -6.39574081e-02 1.80010498e-01 -9.81563985e-01 -6.39574081e-02 1.76562056e-01 -9.82200384e-01 -6.39574081e-02 1.73251852e-01 -9.82788205e-01 -6.39574081e-02 1.69814944e-01 -9.83380437e-01 -6.39574081e-02 1.66380584e-01 -9.83970821e-01 -6.39574081e-02 1.62949473e-01 -9.84543860e-01 -6.39574081e-02 1.59507811e-01 -9.85106707e-01 -6.39574081e-02 1.56056345e-01 -9.85659420e-01 -6.39574081e-02 1.52629539e-01 -9.86196458e-01 -6.39574081e-02 1.49185508e-01 -9.86722112e-01 -6.39574081e-02 1.45738855e-01 -9.87238288e-01 -6.39574081e-02 1.42311037e-01 -9.87736762e-01 -6.39574081e-02 1.38754085e-01 -9.88243461e-01 -6.39574081e-02 1.35202914e-01 -9.88736331e-01 -6.39574081e-02 1.31855771e-01 -9.89187717e-01 -6.39574081e-02 1.28482983e-01 -9.89630699e-01 -6.39574081e-02 1.25033095e-01 -9.90074992e-01 -6.39574081e-02 1.21574193e-01 -9.90502954e-01 -6.39574081e-02 1.18054606e-01 -9.90928173e-01 -6.39574081e-02 1.14572689e-01 -9.91336584e-01 -6.39574081e-02 1.11206897e-01 -9.91720200e-01 -6.39574081e-02 1.07728444e-01 -9.92104053e-01 -6.39574081e-02 1.04263738e-01 -9.92473900e-01 -6.39574081e-02 1.00712568e-01 -9.92839217e-01 -6.39574081e-02 9.72566679e-02 -9.93186355e-01 -6.39574081e-02 9.38189179e-02 -9.93518114e-01 -6.39574081e-02 9.03069526e-02 -9.93844092e-01 -6.39574081e-02 8.68629292e-02 -9.94148970e-01 -6.39574081e-02 8.32905620e-02 -9.94455576e-01 -6.39574081e-02 7.99129084e-02 -9.94734108e-01 -6.39574081e-02 7.65396133e-02 -9.94996309e-01 -6.39574081e-02 7.30665699e-02 -9.95259047e-01 -6.39574081e-02 6.95896298e-02 -9.95505869e-01 -6.39574081e-02 6.61329478e-02 -9.95743752e-01 -6.39574081e-02 6.26575351e-02 -9.95966971e-01 -6.39574081e-02 5.91596700e-02 -9.96181011e-01 -6.39574081e-02 5.56891114e-02 -9.96382177e-01 -6.39574081e-02 5.21050990e-02 -9.96573389e-01 -6.39574081e-02 4.86125797e-02 -9.96753275e-01 -6.39574081e-02 4.51487973e-02 -9.96914148e-01 -6.39574081e-02 4.15780060e-02 -9.97071326e-01 -6.39574081e-02 3.81803997e-02 -9.97207284e-01 -6.39574081e-02 3.48087102e-02 -9.97329593e-01 -6.39574081e-02 3.12461630e-02 -9.97445643e-01 -6.39574081e-02 2.77465135e-02 -9.97552693e-01 -6.39574081e-02 2.42642965e-02 -9.97644007e-01 -6.39574081e-02 2.07647663e-02 -9.97719705e-01 -6.39574081e-02 1.73725933e-02 -9.97790158e-01 -6.39574081e-02 1.38979508e-02 -9.97834444e-01 -6.39574081e-02 1.03935022e-02 -9.97883499e-01 -6.39574081e-02 6.91084238e-03 -9.97918963e-01 -6.39574081e-02 3.44333053e-03 -9.97936070e-01 -6.39574081e-02 -3.28435635e-05 -9.97937381e-01 -6.39574081e-02 -3.50766978e-03 -9.97936070e-01 -6.39574081e-02 -6.98290160e-03 -9.97919679e-01 -6.39574081e-02 -1.04748942e-02 -9.97881353e-01 -6.39574081e-02 -1.39742373e-02 -9.97835159e-01 -6.39574081e-02 -1.75343063e-02 -9.97788548e-01 -6.39574081e-02 -2.11015549e-02 -9.97711420e-01 -6.39574081e-02 -2.44969241e-02 -9.97638702e-01 -6.39574081e-02 -2.78831590e-02 -9.97548223e-01 -6.39574081e-02 -3.13657932e-02 -9.97444987e-01 -6.39574081e-02 -3.48443128e-02 -9.97329712e-01 -6.39574081e-02 -3.84159721e-02 -9.97197866e-01 -6.39574081e-02 -4.19018529e-02 -9.97058392e-01 -6.39574081e-02 -4.52941172e-02 -9.96907830e-01 -6.39574081e-02 -4.87649553e-02 -9.96745586e-01 -6.39574081e-02 -5.22390679e-02 -9.96566117e-01 -6.39574081e-02 -5.58056757e-02 -9.96375680e-01 -6.39574081e-02 -5.93032166e-02 -9.96174097e-01 -6.39574081e-02 -6.27559274e-02 -9.95958745e-01 -6.39574081e-02 -6.62425756e-02 -9.95736241e-01 -6.39574081e-02 -6.96372315e-02 -9.95503008e-01 -6.39574081e-02 -7.30960742e-02 -9.95256722e-01 -6.39574081e-02 -7.65692219e-02 -9.94995415e-01 -6.39574081e-02 -8.01324770e-02 -9.94712651e-01 -6.39574081e-02 -8.36308524e-02 -9.94426847e-01 -6.39574081e-02 -8.69920179e-02 -9.94136930e-01 -6.39574081e-02 -9.04488340e-02 -9.93829250e-01 -6.39574081e-02 -9.39410701e-02 -9.93505478e-01 -6.39574081e-02 -9.73796099e-02 -9.93174672e-01 -6.39574081e-02 -1.00854315e-01 -9.92828071e-01 -6.39574081e-02 -1.04404889e-01 -9.92460668e-01 -6.39574081e-02 -1.07973941e-01 -9.92078781e-01 -6.39574081e-02 -1.11362651e-01 -9.91705239e-01 -6.39574081e-02 -1.14708982e-01 -9.91321146e-01 -6.39574081e-02 -1.18166149e-01 -9.90914762e-01 -6.39574081e-02 -1.21630982e-01 -9.90496457e-01 -6.39574081e-02 -1.25182912e-01 -9.90054667e-01 -6.39574081e-02 -1.28670171e-01 -9.89606559e-01 -6.39574081e-02 -1.32013306e-01 -9.89166141e-01 -6.39574081e-02 -1.35472223e-01 -9.88698781e-01 -6.39574081e-02 -1.38916507e-01 -9.88221288e-01 -6.39574081e-02 -1.42446861e-01 -9.87715960e-01 -6.39574081e-02 -1.45917192e-01 -9.87210631e-01 -6.39574081e-02 -1.49329990e-01 -9.86699939e-01 -6.39574081e-02 -1.52815729e-01 -9.86167908e-01 -6.39574081e-02 -1.56161338e-01 -9.85642195e-01 -6.39574081e-02 -1.59585193e-01 -9.85095322e-01 -6.39574081e-02 -1.63035557e-01 -9.84530270e-01 -6.39574081e-02 -1.66561827e-01 -9.83938336e-01 -6.39574081e-02 -1.70012712e-01 -9.83348668e-01 -6.39574081e-02 -1.73339263e-01 -9.82771754e-01 -6.39574081e-02 -1.76760480e-01 -9.82161045e-01 -6.39574081e-02 -1.80185035e-01 -9.81533349e-01 -6.39574081e-02 -1.83700413e-01 -9.80883658e-01 -6.39574081e-02 -1.87144563e-01 -9.80232954e-01 -6.39574081e-02 -1.90438107e-01 -9.79597151e-01 -6.39574081e-02 -1.93865478e-01 -9.78926301e-01 -6.39574081e-02 -1.97397798e-01 -9.78216887e-01 -6.39574081e-02 -2.00806484e-01 -9.77525175e-01 -6.39574081e-02 -2.04102352e-01 -9.76842940e-01 -6.39574081e-02 -2.07527101e-01 -9.76122797e-01 -6.39574081e-02 -2.11009428e-01 -9.75375414e-01 -6.39574081e-02 -2.14422718e-01 -9.74629104e-01 -6.39574081e-02 -2.17743680e-01 -9.73893166e-01 -6.39574081e-02 -2.21108437e-01 -9.73132968e-01 -6.39574081e-02 -2.24549621e-01 -9.72345173e-01 -6.39574081e-02 -2.28001773e-01 -9.71543193e-01 -6.39574081e-02 -2.31394529e-01 -9.70742404e-01 -6.39574081e-02 -2.34697729e-01 -9.69947815e-01 -6.39574081e-02 -2.38137648e-01 -9.69107449e-01 -6.39574081e-02 -2.41523147e-01 -9.68269289e-01 -6.39574081e-02 -2.44835928e-01 -9.67435241e-01 -6.39574081e-02 -2.48220682e-01 -9.66573954e-01 -6.39574081e-02 -2.51668155e-01 -9.65681672e-01 -6.39574081e-02 -2.55049318e-01 -9.64796543e-01 -6.39574081e-02 -2.58393109e-01 -9.63904440e-01 -6.39574081e-02 -2.61844248e-01 -9.62974608e-01 -6.39574081e-02 -2.65135169e-01 -9.62072432e-01 -6.39574081e-02 -2.68475264e-01 -9.61144984e-01 -6.39574081e-02 -2.71817774e-01 -9.60207343e-01 -6.39574081e-02 -2.75080115e-01 -9.59275842e-01 -6.39574081e-02 -2.78439462e-01 -9.58306015e-01 -6.39574081e-02 -2.81780064e-01 -9.57328320e-01 -6.39574081e-02 -2.85124958e-01 -9.56339180e-01 -6.39574081e-02 -2.88477868e-01 -9.55330491e-01 -6.39574081e-02 -2.91813105e-01 -9.54317391e-01 -6.39574081e-02 -2.95201540e-01 -9.53275442e-01 -6.39574081e-02 -2.98523009e-01 -9.52241361e-01 -6.39574081e-02 -3.01853895e-01 -9.51188803e-01 -6.39574081e-02 -3.05172503e-01 -9.50132787e-01 -6.39574081e-02 -3.08414221e-01 -9.49081957e-01 -6.39574081e-02 -3.11809719e-01 -9.47972298e-01 -6.39574081e-02 -3.15138221e-01 -9.46873188e-01 -6.39574081e-02 -3.18423301e-01 -9.45772767e-01 -6.39574081e-02 -3.21728319e-01 -9.44654167e-01 -6.39574081e-02 -3.24908555e-01 -9.43563819e-01 -6.39574081e-02 -3.28199387e-01 -9.42423940e-01 -6.39574081e-02 -3.31483960e-01 -9.41274345e-01 -6.39574081e-02 -3.34867388e-01 -9.40074980e-01 -6.39574081e-02 -3.38157773e-01 -9.38896120e-01 -6.39574081e-02 -3.41411889e-01 -9.37718928e-01 -6.39574081e-02 -3.44714105e-01 -9.36503947e-01 -6.39574081e-02 -3.47889572e-01 -9.35325086e-01 -6.39574081e-02 -3.51152688e-01 -9.34106350e-01 -6.39574081e-02 -3.54406416e-01 -9.32882309e-01 -6.39574081e-02 -3.57687354e-01 -9.31637466e-01 -6.39574081e-02 -3.60999048e-01 -9.30350900e-01 -6.39574081e-02 -3.64233732e-01 -9.29092586e-01 -6.39574081e-02 -3.67401302e-01 -9.27844584e-01 -6.39574081e-02 -3.70628774e-01 -9.26559091e-01 -6.39574081e-02 -3.73836398e-01 -9.25269723e-01 -6.39574081e-02 -3.77147049e-01 -9.23924506e-01 -6.39574081e-02 -3.80384833e-01 -9.22594905e-01 -6.39574081e-02 -3.83538604e-01 -9.21290815e-01 -6.39574081e-02 -3.86739403e-01 -9.19950962e-01 -6.39574081e-02 -3.89945716e-01 -9.18595731e-01 -6.39574081e-02 -3.93206477e-01 -9.17202294e-01 -6.39574081e-02 -3.96413714e-01 -9.15824115e-01 -6.39574081e-02 -3.99622679e-01 -9.14429665e-01 -6.39574081e-02 -4.02792811e-01 -9.13037360e-01 -6.39574081e-02 -4.05921817e-01 -9.11650121e-01 -6.39574081e-02 -4.09087598e-01 -9.10235524e-01 -6.39574081e-02 -4.12261158e-01 -9.08800483e-01 -6.39574081e-02 -4.15516794e-01 -9.07312572e-01 -6.39574081e-02 -4.18693841e-01 -9.05853868e-01 -6.39574081e-02 -4.21741068e-01 -9.04439926e-01 -6.39574081e-02 -4.24888790e-01 -9.02965128e-01 -6.39574081e-02 -4.28127378e-01 -9.01433468e-01 -6.39574081e-02 -4.31292176e-01 -8.99923861e-01 -6.39574081e-02 -4.34338212e-01 -8.98462236e-01 -6.39574081e-02 -4.37481612e-01 -8.96934927e-01 -6.39574081e-02 -4.40700650e-01 -8.95353854e-01 -6.39574081e-02 -4.43828166e-01 -8.93809497e-01 -6.39574081e-02 -4.46872801e-01 -8.92290592e-01 -6.39574081e-02 -4.49961960e-01 -8.90738428e-01 -6.39574081e-02 -4.53052193e-01 -8.89169097e-01 -6.39574081e-02 -4.56252307e-01 -8.87530744e-01 -6.39574081e-02 -4.59357709e-01 -8.85928333e-01 -6.39574081e-02 -4.62364405e-01 -8.84364843e-01 -6.39574081e-02 -4.65445846e-01 -8.82745564e-01 -6.39574081e-02 -4.68513906e-01 -8.81119668e-01 -6.39574081e-02 -4.71645176e-01 -8.79448533e-01 -6.39574081e-02 -4.74766433e-01 -8.77766967e-01 -6.39574081e-02 -4.77835506e-01 -8.76102865e-01 -6.39574081e-02 -4.80847687e-01 -8.74451876e-01 -6.39574081e-02 -4.83896732e-01 -8.72765124e-01 -6.39574081e-02 -4.87041563e-01 -8.71015429e-01 -6.39574081e-02 -4.89996225e-01 -8.69358301e-01 -6.39574081e-02 -4.92943317e-01 -8.67688656e-01 -6.39574081e-02 -4.95977491e-01 -8.65960300e-01 -6.39574081e-02 -4.98986214e-01 -8.64229918e-01 -6.39574081e-02 -5.01985788e-01 -8.62490118e-01 -6.39574081e-02 -5.04986405e-01 -8.60737383e-01 -6.39574081e-02 -5.08002162e-01 -8.58960450e-01 -6.39574081e-02 -5.10990202e-01 -8.57185304e-01 -6.39574081e-02 -5.13984144e-01 -8.55394602e-01 -6.39574081e-02 -5.16961992e-01 -8.53595734e-01 -6.39574081e-02 -5.19986331e-01 -8.51759315e-01 -6.39574081e-02 -5.23031294e-01 -8.49891126e-01 -6.39574081e-02 -5.25965035e-01 -8.48081291e-01 -6.39574081e-02 -5.28873086e-01 -8.46269727e-01 -6.39574081e-02 -5.31933069e-01 -8.44349205e-01 -6.39574081e-02 -5.34911215e-01 -8.42465699e-01 -6.39574081e-02 -5.37846863e-01 -8.40592921e-01 -6.39574081e-02 -5.40709972e-01 -8.38755190e-01 -6.39574081e-02 -5.43545067e-01 -8.36920917e-01 -6.39574081e-02 -5.46469450e-01 -8.35012734e-01 -6.39574081e-02 -5.49377680e-01 -8.33104730e-01 -6.39574081e-02 -5.52273691e-01 -8.31183910e-01 -6.39574081e-02 -5.55186450e-01 -8.29244435e-01 -6.39574081e-02 -5.58063269e-01 -8.27312589e-01 -6.39574081e-02 -5.60956955e-01 -8.25351119e-01 -6.39574081e-02 -5.63834906e-01 -8.23389411e-01 -6.39574081e-02 -5.66728354e-01 -8.21400225e-01 -6.39574081e-02 -5.69606543e-01 -8.19406331e-01 -6.39574081e-02 -5.72478890e-01 -8.17400098e-01 -6.39574081e-02 -5.75403035e-01 -8.15347731e-01 -6.39574081e-02 -5.78208864e-01 -8.13359857e-01 -6.39574081e-02 -5.80941200e-01 -8.11410010e-01 -6.39574081e-02 -5.83790779e-01 -8.09358239e-01 -6.39574081e-02 -5.86622179e-01 -8.07312191e-01 -6.39574081e-02 -5.89488268e-01 -8.05220306e-01 -6.39574081e-02 -5.92308760e-01 -8.03149641e-01 -6.39574081e-02 -5.95021904e-01 -8.01140249e-01 -6.39574081e-02 -5.97807288e-01 -7.99061120e-01 -6.39574081e-02 -6.00598156e-01 -7.96969771e-01 -6.39574081e-02 -6.03394270e-01 -7.94856668e-01 -6.39574081e-02 -6.06150091e-01 -7.92755842e-01 -6.39574081e-02 -6.08960986e-01 -7.90595233e-01 -6.39574081e-02 -6.11745834e-01 -7.88446844e-01 -6.39574081e-02 -6.14426553e-01 -7.86356330e-01 -6.39574081e-02 -6.17155015e-01 -7.84218788e-01 -6.39574081e-02 -6.19899929e-01 -7.82049179e-01 -6.39574081e-02 -6.22677386e-01 -7.79839516e-01 -6.39574081e-02 -6.25400603e-01 -7.77658820e-01 -6.39574081e-02 -6.28041744e-01 -7.75527120e-01 -6.39574081e-02 -6.30735755e-01 -7.73334742e-01 -6.39574081e-02 -6.33443654e-01 -7.71120369e-01 -6.39574081e-02 -6.36141717e-01 -7.68896818e-01 -6.39574081e-02 -6.38846517e-01 -7.66650319e-01 -6.39574081e-02 -6.41515553e-01 -7.64419138e-01 -6.39574081e-02 -6.44225955e-01 -7.62134969e-01 -6.39574081e-02 -6.46865010e-01 -7.59896874e-01 -6.39574081e-02 -6.49514854e-01 -7.57632136e-01 -6.39574081e-02 -6.52154088e-01 -7.55365193e-01 -6.39574081e-02 -6.54713213e-01 -7.53146887e-01 -6.39574081e-02 -6.57418191e-01 -7.50784218e-01 -6.39574081e-02 -6.60037994e-01 -7.48484075e-01 -6.39574081e-02 -6.62540555e-01 -7.46270597e-01 -6.39574081e-02 -6.65140152e-01 -7.43953943e-01 -6.39574081e-02 -6.67746723e-01 -7.41614938e-01 -6.39574081e-02 -6.70338213e-01 -7.39274919e-01 -6.39574081e-02 -6.72930300e-01 -7.36911714e-01 -6.39574081e-02 -6.75568938e-01 -7.34497905e-01 -6.39574081e-02 -6.78146899e-01 -7.32118666e-01 -6.39574081e-02 -6.80670679e-01 -7.29770005e-01 -6.39574081e-02 -6.83278561e-01 -7.27329850e-01 -6.39574081e-02 -6.85753822e-01 -7.24994779e-01 -6.39574081e-02 -6.88262463e-01 -7.22616732e-01 -6.39574081e-02 -6.90810442e-01 -7.20174432e-01 -6.39574081e-02 -6.93250179e-01 -7.17840374e-01 -6.39574081e-02 -6.95743859e-01 -7.15420961e-01 -6.39574081e-02 -6.98236585e-01 -7.12985218e-01 -6.39574081e-02 -7.00722516e-01 -7.10544348e-01 -6.39574081e-02 -7.03214169e-01 -7.08080411e-01 -6.39574081e-02 -7.05688417e-01 -7.05594480e-01 -6.39574081e-02 -7.08175778e-01 -7.03119874e-01 -6.39574081e-02 -7.10594535e-01 -7.00671554e-01 -6.39574081e-02 -7.13038325e-01 -6.98181272e-01 -6.39574081e-02 -7.15464354e-01 -6.95698917e-01 -6.39574081e-02 -7.17874289e-01 -6.93213105e-01 -6.39574081e-02 -7.20356584e-01 -6.90618217e-01 -6.39574081e-02 -7.22777843e-01 -6.88096106e-01 -6.39574081e-02 -7.25158572e-01 -6.85580254e-01 -6.39574081e-02 -7.27563381e-01 -6.83028758e-01 -6.39574081e-02 -7.29867399e-01 -6.80564225e-01 -6.39574081e-02 -7.32245147e-01 -6.78007722e-01 -6.39574081e-02 -7.34606445e-01 -6.75451636e-01 -6.39574081e-02 -7.36961246e-01 -6.72878385e-01 -6.39574081e-02 -7.39336729e-01 -6.70268834e-01 -6.39574081e-02 -7.41662562e-01 -6.67694211e-01 -6.39574081e-02 -7.43966520e-01 -6.65126204e-01 -6.39574081e-02 -7.46281028e-01 -6.62528992e-01 -6.39574081e-02 -7.48638391e-01 -6.59862220e-01 -6.39574081e-02 -7.50963092e-01 -6.57216907e-01 -6.39574081e-02 -7.53196418e-01 -6.54655457e-01 -6.39574081e-02 -7.55512357e-01 -6.51978433e-01 -6.39574081e-02 -7.57795453e-01 -6.49327636e-01 -6.39574081e-02 -7.59982705e-01 -6.46763265e-01 -6.39574081e-02 -7.62246013e-01 -6.44098341e-01 -6.39574081e-02 -7.64490902e-01 -6.41429186e-01 -6.39574081e-02 -7.66773045e-01 -6.38700128e-01 -6.39574081e-02 -7.68997729e-01 -6.36020243e-01 -6.39574081e-02 -7.71181524e-01 -6.33372068e-01 -6.39574081e-02 -7.73396313e-01 -6.30663037e-01 -6.39574081e-02 -7.75558710e-01 -6.28002763e-01 -6.39574081e-02 -7.77811408e-01 -6.25210285e-01 -6.39574081e-02 -7.80010641e-01 -6.22467041e-01 -6.39574081e-02 -7.82163739e-01 -6.19753063e-01 -6.39574081e-02 -7.84319222e-01 -6.17028058e-01 -6.39574081e-02 -7.86400080e-01 -6.14371896e-01 -6.39574081e-02 -7.88548112e-01 -6.11613631e-01 -6.39574081e-02 -7.90663362e-01 -6.08874500e-01 -6.39574081e-02 -7.92842031e-01 -6.06034219e-01 -6.39574081e-02 -7.94968665e-01 -6.03245497e-01 -6.39574081e-02 -7.97011316e-01 -6.00544512e-01 -6.39574081e-02 -7.99106181e-01 -5.97751915e-01 -6.39574081e-02 -8.01189005e-01 -5.94956398e-01 -6.39574081e-02 -8.03316891e-01 -5.92078924e-01 -6.39574081e-02 -8.05387616e-01 -5.89261949e-01 -6.39574081e-02 -8.07379484e-01 -5.86529374e-01 -6.39574081e-02 -8.09465647e-01 -5.83643436e-01 -6.39574081e-02 -8.11506093e-01 -5.80808103e-01 -6.39574081e-02 -8.13465178e-01 -5.78059316e-01 -6.39574081e-02 -8.15479159e-01 -5.75216591e-01 -6.39574081e-02 -8.17481458e-01 -5.72364330e-01 -6.39574081e-02 -8.19534063e-01 -5.69421589e-01 -6.39574081e-02 -8.21508765e-01 -5.66572905e-01 -6.39574081e-02 -8.23425472e-01 -5.63781083e-01 -6.39574081e-02 -8.25393140e-01 -5.60894072e-01 -6.39574081e-02 -8.27347219e-01 -5.58010578e-01 -6.39574081e-02 -8.29328060e-01 -5.55060208e-01 -6.39574081e-02 -8.31257761e-01 -5.52166283e-01 -6.39574081e-02 -8.33190978e-01 -5.49243391e-01 -6.39574081e-02 -8.35086286e-01 -5.46359122e-01 -6.39574081e-02 -8.36934865e-01 -5.43523848e-01 -6.39574081e-02 -8.38831306e-01 -5.40590286e-01 -6.39574081e-02 -8.40711713e-01 -5.37660837e-01 -6.39574081e-02 -8.42646480e-01 -5.34623802e-01 -6.39574081e-02 -8.44502807e-01 -5.31691968e-01 -6.39574081e-02 -8.46292436e-01 -5.28833210e-01 -6.39574081e-02 -8.48124623e-01 -5.25895000e-01 -6.39574081e-02 -8.49954784e-01 -5.22929847e-01 -6.39574081e-02 -8.51786554e-01 -5.19944370e-01 -6.39574081e-02 -8.53594244e-01 -5.16966939e-01 -6.39574081e-02 -8.55402648e-01 -5.13968468e-01 -6.39574081e-02 -8.57193172e-01 -5.10977626e-01 -6.39574081e-02 -8.58966947e-01 -5.07991254e-01 -6.39574081e-02 -8.60789537e-01 -5.04895449e-01 -6.39574081e-02 -8.62555981e-01 -5.01871765e-01 -6.39574081e-02 -8.64244938e-01 -4.98960137e-01 -6.39574081e-02 -8.65973592e-01 -4.95948851e-01 -6.39574081e-02 -8.67693603e-01 -4.92934257e-01 -6.39574081e-02 -8.69430184e-01 -4.89870012e-01 -6.39574081e-02 -8.71129274e-01 -4.86836553e-01 -6.39574081e-02 -8.72819364e-01 -4.83795553e-01 -6.39574081e-02 -8.74556541e-01 -4.80657816e-01 -6.39574081e-02 -8.76241803e-01 -4.77581292e-01 -6.39574081e-02 -8.77846658e-01 -4.74618465e-01 -6.39574081e-02 -8.79509747e-01 -4.71531719e-01 -6.39574081e-02 -8.81196380e-01 -4.68370557e-01 -6.39574081e-02 -8.82827699e-01 -4.65291739e-01 -6.39574081e-02 -8.84398222e-01 -4.62296754e-01 -6.39574081e-02 -8.86009753e-01 -4.59199965e-01 -6.39574081e-02 -8.87592673e-01 -4.56133842e-01 -6.39574081e-02 -8.89194191e-01 -4.53003794e-01 -6.39574081e-02 -8.90776813e-01 -4.49882627e-01 -6.39574081e-02 -8.92341197e-01 -4.46771562e-01 -6.39574081e-02 -8.93886387e-01 -4.43671912e-01 -6.39574081e-02 -8.95425141e-01 -4.40559179e-01 -6.39574081e-02 -8.96959901e-01 -4.37427282e-01 -6.39574081e-02 -8.98523510e-01 -4.34204668e-01 -6.39574081e-02 -9.00083959e-01 -4.30957228e-01 -6.39574081e-02 -9.01537716e-01 -4.27914917e-01 -6.39574081e-02 -9.02983546e-01 -4.24849391e-01 -6.39574081e-02 -9.04454172e-01 -4.21711206e-01 -6.39574081e-02 -9.05963778e-01 -4.18458670e-01 -6.39574081e-02 -9.07420158e-01 -4.15289909e-01 -6.39574081e-02 -9.08824325e-01 -4.12210286e-01 -6.39574081e-02 -9.10255015e-01 -4.09041882e-01 -6.39574081e-02 -9.11686778e-01 -4.05839175e-01 -6.39574081e-02 -9.13098097e-01 -4.02655572e-01 -6.39574081e-02 -9.14501011e-01 -3.99458408e-01 -6.39574081e-02 -9.15920258e-01 -3.96191388e-01 -6.39574081e-02 -9.17292118e-01 -3.92999738e-01 -6.39574081e-02 -9.18617070e-01 -3.89895886e-01 -6.39574081e-02 -9.19976115e-01 -3.86679888e-01 -6.39574081e-02 -9.21323478e-01 -3.83459330e-01 -6.39574081e-02 -9.22680795e-01 -3.80179465e-01 -6.39574081e-02 -9.24016476e-01 -3.76928270e-01 -6.39574081e-02 -9.25291121e-01 -3.73779982e-01 -6.39574081e-02 -9.26616549e-01 -3.70483577e-01 -6.39574081e-02 -9.27910149e-01 -3.67239296e-01 -6.39574081e-02 -9.29146349e-01 -3.64098847e-01 -6.39574081e-02 -9.30410683e-01 -3.60839248e-01 -6.39574081e-02 -9.31675553e-01 -3.57584149e-01 -6.39574081e-02 -9.32942212e-01 -3.54247600e-01 -6.39574081e-02 -9.34172034e-01 -3.50977659e-01 -6.39574081e-02 -9.35353160e-01 -3.47815067e-01 -6.39574081e-02 -9.36598718e-01 -3.44457090e-01 -6.39574081e-02 -9.37802970e-01 -3.41189295e-01 -6.39574081e-02 -9.38978493e-01 -3.37928504e-01 -6.39574081e-02 -9.40157592e-01 -3.34643275e-01 -6.39574081e-02 -9.41315711e-01 -3.31363350e-01 -6.39574081e-02 -9.42467570e-01 -3.28073382e-01 -6.39574081e-02 -9.43574429e-01 -3.24879646e-01 -6.39574081e-02 -9.44704831e-01 -3.21575195e-01 -6.39574081e-02 -9.45821404e-01 -3.18277359e-01 -6.39574081e-02 -9.46958661e-01 -3.14875692e-01 -6.39574081e-02 -9.48054731e-01 -3.11561882e-01 -6.39574081e-02 -9.49105084e-01 -3.08349282e-01 -6.39574081e-02 -9.50177133e-01 -3.05028975e-01 -6.39574081e-02 -9.51229632e-01 -3.01727414e-01 -6.39574081e-02 -9.52312052e-01 -2.98294514e-01 -6.39574081e-02 -9.53352392e-01 -2.94957727e-01 -6.39574081e-02 -9.54348564e-01 -2.91716337e-01 -6.39574081e-02 -9.55353916e-01 -2.88397402e-01 -6.39574081e-02 -9.56356227e-01 -2.85058320e-01 -6.39574081e-02 -9.57369804e-01 -2.81641632e-01 -6.39574081e-02 -9.58351970e-01 -2.78282106e-01 -6.39574081e-02 -9.59290385e-01 -2.75025934e-01 -6.39574081e-02 -9.60244536e-01 -2.71679968e-01 -6.39574081e-02 -9.61190760e-01 -2.68315405e-01 -6.39574081e-02 -9.62116599e-01 -2.64970094e-01 -6.39574081e-02 -9.63038087e-01 -2.61612236e-01 -6.39574081e-02 -9.63944316e-01 -2.58241683e-01 -6.39574081e-02 -9.64864254e-01 -2.54779756e-01 -6.39574081e-02 -9.65749204e-01 -2.51419604e-01 -6.39574081e-02 -9.66594458e-01 -2.48141661e-01 -6.39574081e-02 -9.67450798e-01 -2.44770914e-01 -6.39574081e-02 -9.68318045e-01 -2.41323486e-01 -6.39574081e-02 -9.69158769e-01 -2.37932518e-01 -6.39574081e-02 -9.69962478e-01 -2.34639138e-01 -6.39574081e-02 -9.70775247e-01 -2.31251597e-01 -6.39574081e-02 -9.71579790e-01 -2.27847263e-01 -6.39574081e-02 -9.72381771e-01 -2.24389240e-01 -6.39574081e-02 -9.73162055e-01 -2.20987856e-01 -6.39574081e-02 -9.73907590e-01 -2.17679381e-01 -6.39574081e-02 -9.74675953e-01 -2.14202046e-01 -6.39574081e-02 -9.75420177e-01 -2.10796505e-01 -6.39574081e-02 -9.76130962e-01 -2.07477823e-01 -6.39574081e-02 -9.76855338e-01 -2.04044297e-01 -6.39574081e-02 -9.77576792e-01 -2.00560093e-01 -6.39574081e-02 -9.78268504e-01 -1.97155014e-01 -6.39574081e-02 -9.78933454e-01 -1.93823412e-01 -6.39574081e-02 -9.79598880e-01 -1.90429732e-01 -6.39574081e-02 -9.80280340e-01 -1.86886936e-01 -6.39574081e-02 -9.80928719e-01 -1.83459550e-01 -6.39574081e-02 -9.81539905e-01 -1.80148154e-01 -6.39574081e-02 -9.82170820e-01 -1.76712781e-01 -6.39574081e-02 -9.82781649e-01 -1.73279941e-01 -6.39574081e-02 -9.83394146e-01 -1.69740006e-01 -6.39574081e-02 -9.83985364e-01 -1.66298524e-01 -6.39574081e-02 -9.84536648e-01 -1.62981525e-01 -6.39574081e-02 -9.85115945e-01 -1.59446046e-01 -6.39574081e-02 -9.85671282e-01 -1.55988246e-01 -6.39574081e-02 -9.86191213e-01 -1.52665928e-01 -6.39574081e-02 -9.86713946e-01 -1.49239510e-01 -6.39574081e-02 -9.87244666e-01 -1.45689368e-01 -6.39574081e-02 -9.87752557e-01 -1.42210200e-01 -6.39574081e-02 -9.88229632e-01 -1.38859659e-01 -6.39574081e-02 -9.88718450e-01 -1.35333523e-01 -6.39574081e-02 -9.89189565e-01 -1.31851867e-01 -6.39574081e-02 -9.89626288e-01 -1.28516510e-01 -6.39574081e-02 -9.90070879e-01 -1.25066414e-01 -6.39574081e-02 -9.90498126e-01 -1.21622853e-01 -6.39574081e-02 -9.90922391e-01 -1.18109114e-01 -6.39574081e-02 -9.91332293e-01 -1.14623040e-01 -6.39574081e-02 -9.91697848e-01 -1.11511812e-01 -6.39574081e-02 -9.92062867e-01 -1.08264565e-01 -6.39575645e-02 -9.92486119e-01 -1.04307376e-01 -6.39575496e-02 -9.92767155e-01 -1.01600468e-01 -6.39575422e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.96673048e-01 5.71185537e-02 -5.81390299e-02 -9.96612728e-01 5.81624098e-02 -5.81390299e-02 -9.96322632e-01 6.29232526e-02 -5.81390262e-02 -9.96043086e-01 6.72116950e-02 -5.81389032e-02 -9.95850921e-01 6.99513927e-02 -5.81394769e-02 -9.95599389e-01 7.34063014e-02 -5.81395552e-02 -9.95347083e-01 7.67316297e-02 -5.81395738e-02 -9.95085835e-01 8.00641179e-02 -5.81395067e-02 -9.94797587e-01 8.35638791e-02 -5.81394508e-02 -9.94490564e-01 8.71251971e-02 -5.81392013e-02 -9.94173348e-01 9.06829461e-02 -5.81394508e-02 -9.93858099e-01 9.40774679e-02 -5.81395477e-02 -9.93526757e-01 9.75044295e-02 -5.81392050e-02 -9.93169665e-01 1.01090364e-01 -5.81392497e-02 -9.92816329e-01 1.04510009e-01 -5.81394136e-02 -9.92441297e-01 1.07998326e-01 -5.81392124e-02 -9.92066622e-01 1.11403733e-01 -5.81395738e-02 -9.91682112e-01 1.14747807e-01 -5.81393056e-02 -9.91260648e-01 1.18334644e-01 -5.81391566e-02 -9.90830660e-01 1.21892877e-01 -5.81393577e-02 -9.90401864e-01 1.25343189e-01 -5.81393726e-02 -9.89955068e-01 1.28804177e-01 -5.81392944e-02 -9.89499390e-01 1.32271320e-01 -5.81393577e-02 -9.89046574e-01 1.35623783e-01 -5.81395738e-02 -9.88568485e-01 1.39055461e-01 -5.81391454e-02 -9.88062024e-01 1.42602965e-01 -5.81392720e-02 -9.87572253e-01 1.45960420e-01 -5.81394695e-02 -9.87058163e-01 1.49388283e-01 -5.81391305e-02 -9.86517906e-01 1.52933300e-01 -5.81394397e-02 -9.85977054e-01 1.56371102e-01 -5.81393652e-02 -9.85425174e-01 1.59816593e-01 -5.81393242e-02 -9.84867513e-01 1.63222477e-01 -5.81393801e-02 -9.84304368e-01 1.66578025e-01 -5.81394434e-02 -9.83726084e-01 1.69959232e-01 -5.81392832e-02 -9.83119547e-01 1.73452556e-01 -5.81391528e-02 -9.82489824e-01 1.76985845e-01 -5.81392869e-02 -9.81877267e-01 1.80326641e-01 -5.81394248e-02 -9.81249034e-01 1.83722749e-01 -5.81391044e-02 -9.80583370e-01 1.87241524e-01 -5.81393465e-02 -9.79931891e-01 1.90617830e-01 -5.81393279e-02 -9.79250491e-01 1.94092169e-01 -5.81392832e-02 -9.78587866e-01 1.97408319e-01 -5.81394285e-02 -9.77908373e-01 2.00750753e-01 -5.81393503e-02 -9.77186918e-01 2.04231188e-01 -5.81390746e-02 -9.76445079e-01 2.07749560e-01 -5.81393056e-02 -9.75709736e-01 2.11176589e-01 -5.81392832e-02 -9.74964976e-01 2.14585990e-01 -5.81392720e-02 -9.74216104e-01 2.17962489e-01 -5.81393763e-02 -9.73468244e-01 2.21276999e-01 -5.81395440e-02 -9.72691596e-01 2.24660963e-01 -5.81391230e-02 -9.71868694e-01 2.28206739e-01 -5.81392534e-02 -9.71088588e-01 2.31504217e-01 -5.81395477e-02 -9.70313072e-01 2.34736159e-01 -5.81392832e-02 -9.69459116e-01 2.38228634e-01 -5.81390858e-02 -9.68593419e-01 2.41718501e-01 -5.81393167e-02 -9.67742503e-01 2.45101243e-01 -5.81392422e-02 -9.66891170e-01 2.48445690e-01 -5.81393167e-02 -9.66041267e-01 2.51728714e-01 -5.81394099e-02 -9.65173244e-01 2.55045116e-01 -5.81393093e-02 -9.64254200e-01 2.58490115e-01 -5.81391230e-02 -9.63316381e-01 2.61971563e-01 -5.81392944e-02 -9.62414443e-01 2.65256971e-01 -5.81394769e-02 -9.61488426e-01 2.68597484e-01 -5.81391044e-02 -9.60515618e-01 2.72059590e-01 -5.81392311e-02 -9.59559381e-01 2.75407523e-01 -5.81392571e-02 -9.58593905e-01 2.78747350e-01 -5.81393130e-02 -9.57636714e-01 2.82023549e-01 -5.81395440e-02 -9.56683338e-01 2.85243213e-01 -5.81393465e-02 -9.55647826e-01 2.88682073e-01 -5.81390597e-02 -9.54597533e-01 2.92143673e-01 -5.81392758e-02 -9.53568161e-01 2.95485824e-01 -5.81392869e-02 -9.52564895e-01 2.98704624e-01 -5.81395105e-02 -9.51519608e-01 3.02012831e-01 -5.81390709e-02 -9.50442612e-01 3.05395097e-01 -5.81393763e-02 -9.49399233e-01 3.08618307e-01 -5.81393801e-02 -9.48304117e-01 3.11964899e-01 -5.81391081e-02 -9.47203934e-01 3.15294594e-01 -5.81395254e-02 -9.46135581e-01 3.18486452e-01 -5.81393167e-02 -9.44983363e-01 3.21881384e-01 -5.81391528e-02 -9.43824410e-01 3.25270891e-01 -5.81393167e-02 -9.42689478e-01 3.28539997e-01 -5.81393763e-02 -9.41540301e-01 3.31819981e-01 -5.81392646e-02 -9.40386951e-01 3.35081577e-01 -5.81393763e-02 -9.39241648e-01 3.38272303e-01 -5.81394546e-02 -9.38041627e-01 3.41589600e-01 -5.81391491e-02 -9.36804831e-01 3.44948530e-01 -5.81393801e-02 -9.35618997e-01 3.48141134e-01 -5.81394471e-02 -9.34403777e-01 3.51395637e-01 -5.81391528e-02 -9.33147192e-01 3.54730695e-01 -5.81393167e-02 -9.31909323e-01 3.57995003e-01 -5.81393391e-02 -9.30644453e-01 3.61246467e-01 -5.81393018e-02 -9.29403663e-01 3.64435762e-01 -5.81394657e-02 -9.28160846e-01 3.67589682e-01 -5.81393167e-02 -9.26877201e-01 3.70811462e-01 -5.81392646e-02 -9.25546825e-01 3.74119431e-01 -5.81391118e-02 -9.24203157e-01 3.77428949e-01 -5.81392720e-02 -9.22911823e-01 3.80570889e-01 -5.81394769e-02 -9.21576858e-01 3.83792788e-01 -5.81390560e-02 -9.20192063e-01 3.87105644e-01 -5.81392832e-02 -9.18846250e-01 3.90284389e-01 -5.81392869e-02 -9.17482615e-01 3.93477857e-01 -5.81392609e-02 -9.16132629e-01 3.96617055e-01 -5.81393577e-02 -9.14784133e-01 3.99720728e-01 -5.81392609e-02 -9.13350821e-01 4.02980506e-01 -5.81391566e-02 -9.11889195e-01 4.06281233e-01 -5.81392050e-02 -9.10460830e-01 4.09468442e-01 -5.81392311e-02 -9.09028113e-01 4.12639976e-01 -5.81391975e-02 -9.07577872e-01 4.15814668e-01 -5.81392869e-02 -9.06142175e-01 4.18936640e-01 -5.81393018e-02 -9.04680908e-01 4.22082424e-01 -5.81391603e-02 -9.03183401e-01 4.25276965e-01 -5.81392460e-02 -9.01729822e-01 4.28354949e-01 -5.81394285e-02 -9.00272012e-01 4.31405008e-01 -5.81392907e-02 -8.98727000e-01 4.34621513e-01 -5.81391342e-02 -8.97165179e-01 4.37839776e-01 -5.81392534e-02 -8.95635724e-01 4.40953523e-01 -5.81393391e-02 -8.94105017e-01 4.44050223e-01 -5.81392050e-02 -8.92573118e-01 4.47121739e-01 -5.81394434e-02 -8.91046464e-01 4.50157404e-01 -5.81392869e-02 -8.89428198e-01 4.53343123e-01 -5.81390932e-02 -8.87794554e-01 4.56538737e-01 -5.81392720e-02 -8.86231124e-01 4.59561825e-01 -5.81395105e-02 -8.84632766e-01 4.62633491e-01 -5.81390634e-02 -8.82975698e-01 4.65791345e-01 -5.81393130e-02 -8.81340504e-01 4.68875349e-01 -5.81393316e-02 -8.79707932e-01 4.71932620e-01 -5.81393503e-02 -8.78100693e-01 4.74913865e-01 -5.81394434e-02 -8.76471698e-01 4.77919519e-01 -5.81393056e-02 -8.74761164e-01 4.81039733e-01 -5.81391528e-02 -8.73017371e-01 4.84190822e-01 -5.81393167e-02 -8.71341944e-01 4.87202227e-01 -5.81393056e-02 -8.69632840e-01 4.90250468e-01 -5.81392758e-02 -8.67910504e-01 4.93289530e-01 -5.81393652e-02 -8.66206884e-01 4.96279508e-01 -5.81394434e-02 -8.64521742e-01 4.99208629e-01 -5.81394173e-02 -8.62751901e-01 5.02258778e-01 -5.81391528e-02 -8.60951543e-01 5.05340219e-01 -5.81392720e-02 -8.59221756e-01 5.08274853e-01 -5.81394210e-02 -8.57457042e-01 5.11246204e-01 -5.81391342e-02 -8.55618358e-01 5.14317214e-01 -5.81392720e-02 -8.53818238e-01 5.17297983e-01 -5.81392981e-02 -8.52011502e-01 5.20273507e-01 -5.81393316e-02 -8.50176513e-01 5.23262024e-01 -5.81392795e-02 -8.48401725e-01 5.26138663e-01 -5.81394620e-02 -8.46569836e-01 5.29076159e-01 -5.81391566e-02 -8.44675541e-01 5.32097816e-01 -5.81392385e-02 -8.42804551e-01 5.35054326e-01 -5.81392720e-02 -8.40918005e-01 5.38016081e-01 -5.81393801e-02 -8.39047253e-01 5.40925860e-01 -5.81392907e-02 -8.37164223e-01 5.43837547e-01 -5.81393652e-02 -8.35264683e-01 5.46749413e-01 -5.81392832e-02 -8.33352923e-01 5.49661696e-01 -5.81393093e-02 -8.31468701e-01 5.52504003e-01 -5.81394881e-02 -8.29588473e-01 5.55325449e-01 -5.81392907e-02 -8.27605784e-01 5.58279097e-01 -5.81391156e-02 -8.25598836e-01 5.61239898e-01 -5.81392981e-02 -8.23640049e-01 5.64112186e-01 -5.81393279e-02 -8.21668029e-01 5.66981912e-01 -5.81392534e-02 -8.19669306e-01 5.69864094e-01 -5.81393056e-02 -8.17719758e-01 5.72657406e-01 -5.81394285e-02 -8.15723717e-01 5.75501263e-01 -5.81391081e-02 -8.13646376e-01 5.78428209e-01 -5.81392609e-02 -8.11679244e-01 5.81191659e-01 -5.81395291e-02 -8.09643924e-01 5.84018588e-01 -5.81391789e-02 -8.07560265e-01 5.86900532e-01 -5.81393763e-02 -8.05509925e-01 5.89709163e-01 -5.81393652e-02 -8.03449512e-01 5.92513204e-01 -5.81393391e-02 -8.01380217e-01 5.95308244e-01 -5.81393652e-02 -7.99361885e-01 5.98017633e-01 -5.81395067e-02 -7.97239900e-01 6.00843966e-01 -5.81391305e-02 -7.95071363e-01 6.03710592e-01 -5.81393763e-02 -7.92962730e-01 6.06477320e-01 -5.81393763e-02 -7.90911436e-01 6.09149992e-01 -5.81395328e-02 -7.88769841e-01 6.11916661e-01 -5.81391864e-02 -7.86580086e-01 6.14730954e-01 -5.81393205e-02 -7.84482300e-01 6.17407739e-01 -5.81394769e-02 -7.82323658e-01 6.20138049e-01 -5.81391156e-02 -7.80153573e-01 6.22868955e-01 -5.81395254e-02 -7.78025448e-01 6.25525117e-01 -5.81393465e-02 -7.75792241e-01 6.28293216e-01 -5.81391342e-02 -7.73544490e-01 6.31057143e-01 -5.81393428e-02 -7.71346927e-01 6.33740664e-01 -5.81393018e-02 -7.69089580e-01 6.36479914e-01 -5.81394061e-02 -7.66857743e-01 6.39165878e-01 -5.81394061e-02 -7.64638305e-01 6.41819179e-01 -5.81392832e-02 -7.62384713e-01 6.44495964e-01 -5.81393018e-02 -7.60130525e-01 6.47150159e-01 -5.81393056e-02 -7.57913947e-01 6.49747729e-01 -5.81395738e-02 -7.55657613e-01 6.52369797e-01 -5.81390709e-02 -7.53290474e-01 6.55102193e-01 -5.81393614e-02 -7.51008809e-01 6.57715261e-01 -5.81393093e-02 -7.48701513e-01 6.60341203e-01 -5.81393205e-02 -7.46379852e-01 6.62966013e-01 -5.81394210e-02 -7.44075477e-01 6.65551782e-01 -5.81393540e-02 -7.41823018e-01 6.68059230e-01 -5.81395738e-02 -7.39509165e-01 6.70621872e-01 -5.81391454e-02 -7.37064362e-01 6.73305690e-01 -5.81394136e-02 -7.34793782e-01 6.75786197e-01 -5.81395701e-02 -7.32427061e-01 6.78347170e-01 -5.81392571e-02 -7.30004489e-01 6.80953085e-01 -5.81394695e-02 -7.27629423e-01 6.83489799e-01 -5.81393391e-02 -7.25212693e-01 6.86053395e-01 -5.81393018e-02 -7.22849369e-01 6.88546538e-01 -5.81395738e-02 -7.20539391e-01 6.90956831e-01 -5.81393950e-02 -7.18055069e-01 6.93550944e-01 -5.81392385e-02 -7.15521693e-01 6.96161807e-01 -5.81392832e-02 -7.13085175e-01 6.98654354e-01 -5.81392944e-02 -7.10648119e-01 7.01134741e-01 -5.81393279e-02 -7.08257973e-01 7.03551948e-01 -5.81394471e-02 -7.05790997e-01 7.06007719e-01 -5.81391752e-02 -7.03284442e-01 7.08522081e-01 -5.81393279e-02 -7.00808346e-01 7.10971951e-01 -5.81392720e-02 -6.98389947e-01 7.13345766e-01 -5.81395142e-02 -6.95899367e-01 7.15776861e-01 -5.81390858e-02 -6.93307638e-01 7.18290269e-01 -5.81394061e-02 -6.90784574e-01 7.20703304e-01 -5.81394248e-02 -6.88257813e-01 7.23126054e-01 -5.81392720e-02 -6.85745716e-01 7.25503922e-01 -5.81393614e-02 -6.83253467e-01 7.27850556e-01 -5.81394285e-02 -6.80708945e-01 7.30229557e-01 -5.81392236e-02 -6.78106546e-01 7.32650280e-01 -5.81392795e-02 -6.75544739e-01 7.35016048e-01 -5.81392720e-02 -6.73026383e-01 7.37319291e-01 -5.81395216e-02 -6.70468450e-01 7.39646196e-01 -5.81391007e-02 -6.67839885e-01 7.42022038e-01 -5.81393912e-02 -6.65253162e-01 7.44339526e-01 -5.81395738e-02 -6.62686408e-01 7.46626019e-01 -5.81391789e-02 -6.60021603e-01 7.48984039e-01 -5.81393167e-02 -6.57487333e-01 7.51209855e-01 -5.81395701e-02 -6.54836833e-01 7.53520787e-01 -5.81392050e-02 -6.52132154e-01 7.55862474e-01 -5.81393167e-02 -6.49483323e-01 7.58140624e-01 -5.81393354e-02 -6.46836102e-01 7.60398507e-01 -5.81393279e-02 -6.44197524e-01 7.62635827e-01 -5.81393167e-02 -6.41520143e-01 7.64889836e-01 -5.81392944e-02 -6.38829529e-01 7.67139614e-01 -5.81392720e-02 -6.36177063e-01 7.69339621e-01 -5.81394620e-02 -6.33545220e-01 7.71511555e-01 -5.81395701e-02 -6.30926609e-01 7.73650050e-01 -5.81394844e-02 -6.28142834e-01 7.75913358e-01 -5.81392832e-02 -6.25389695e-01 7.78134704e-01 -5.81395030e-02 -6.22659087e-01 7.80320585e-01 -5.81392720e-02 -6.19917691e-01 7.82499552e-01 -5.81393167e-02 -6.17184222e-01 7.84659028e-01 -5.81393130e-02 -6.14501894e-01 7.86760986e-01 -5.81395067e-02 -6.11768544e-01 7.88887739e-01 -5.81391528e-02 -6.08929038e-01 7.91081548e-01 -5.81393279e-02 -6.06222391e-01 7.93157876e-01 -5.81395030e-02 -6.03469372e-01 7.95253813e-01 -5.81391528e-02 -6.00600302e-01 7.97423244e-01 -5.81393465e-02 -5.97826421e-01 7.99502552e-01 -5.81393279e-02 -5.95036328e-01 8.01583171e-01 -5.81393093e-02 -5.92306495e-01 8.03603292e-01 -5.81394956e-02 -5.89546144e-01 8.05628121e-01 -5.81392311e-02 -5.86665511e-01 8.07729959e-01 -5.81391454e-02 -5.83840072e-01 8.09772849e-01 -5.81394695e-02 -5.81003726e-01 8.11811328e-01 -5.81391305e-02 -5.78154862e-01 8.13845754e-01 -5.81395738e-02 -5.75353801e-01 8.15827727e-01 -5.81390336e-02 -5.72392523e-01 8.17905188e-01 -5.81393279e-02 -5.69585204e-01 8.19863915e-01 -5.81395477e-02 -5.66758037e-01 8.21820736e-01 -5.81391864e-02 -5.63885450e-01 8.23796332e-01 -5.81395738e-02 -5.61004817e-01 8.25759292e-01 -5.81391864e-02 -5.58102429e-01 8.27724397e-01 -5.81395067e-02 -5.55287898e-01 8.29613149e-01 -5.81393130e-02 -5.52292764e-01 8.31609547e-01 -5.81393391e-02 -5.49303532e-01 8.33587646e-01 -5.81393316e-02 -5.46485305e-01 8.35438490e-01 -5.81395067e-02 -5.43670118e-01 8.37274075e-01 -5.81392944e-02 -5.40650189e-01 8.39226246e-01 -5.81391640e-02 -5.37699342e-01 8.41120720e-01 -5.81394657e-02 -5.34798086e-01 8.42966557e-01 -5.81391864e-02 -5.31857550e-01 8.44828546e-01 -5.81395738e-02 -5.28899133e-01 8.46679449e-01 -5.81392013e-02 -5.25867343e-01 8.48568738e-01 -5.81393056e-02 -5.22880852e-01 8.50409567e-01 -5.81392869e-02 -5.19985378e-01 8.52186918e-01 -5.81394508e-02 -5.17051995e-01 8.53967786e-01 -5.81392087e-02 -5.13972521e-01 8.55825067e-01 -5.81392050e-02 -5.11025488e-01 8.57588351e-01 -5.81394359e-02 -5.08052349e-01 8.59352529e-01 -5.81392087e-02 -5.05032897e-01 8.61132562e-01 -5.81395179e-02 -5.02066374e-01 8.62864494e-01 -5.81392460e-02 -4.98929352e-01 8.64683032e-01 -5.81394322e-02 -4.96021748e-01 8.66353929e-01 -5.81395030e-02 -4.92977619e-01 8.68086934e-01 -5.81391566e-02 -4.89922225e-01 8.69819522e-01 -5.81395738e-02 -4.86912787e-01 8.71503770e-01 -5.81393167e-02 -4.83795226e-01 8.73236418e-01 -5.81393726e-02 -4.80765492e-01 8.74910593e-01 -5.81391975e-02 -4.77650434e-01 8.76617491e-01 -5.81392236e-02 -4.74554151e-01 8.78293991e-01 -5.81392311e-02 -4.71590638e-01 8.79889905e-01 -5.81395440e-02 -4.68633831e-01 8.81469131e-01 -5.81393279e-02 -4.65471148e-01 8.83141994e-01 -5.81391864e-02 -4.62357670e-01 8.84779453e-01 -5.81395738e-02 -4.59272683e-01 8.86381328e-01 -5.81391267e-02 -4.56120849e-01 8.88009369e-01 -5.81395105e-02 -4.53046352e-01 8.89580011e-01 -5.81393242e-02 -4.49871272e-01 8.91190171e-01 -5.81394248e-02 -4.46741521e-01 8.92763674e-01 -5.81393652e-02 -4.43722188e-01 8.94269347e-01 -5.81395738e-02 -4.40689057e-01 8.95766079e-01 -5.81393354e-02 -4.37487513e-01 8.97334576e-01 -5.81393205e-02 -4.34328407e-01 8.98871005e-01 -5.81394956e-02 -4.31197673e-01 9.00371253e-01 -5.81391938e-02 -4.28047657e-01 9.01876450e-01 -5.81395477e-02 -4.24934298e-01 9.03344810e-01 -5.81392832e-02 -4.21751589e-01 9.04838383e-01 -5.81394583e-02 -4.18604404e-01 9.06297207e-01 -5.81391677e-02 -4.15348530e-01 9.07793999e-01 -5.81395477e-02 -4.12217736e-01 9.09219682e-01 -5.81394956e-02 -4.09009308e-01 9.10670221e-01 -5.81394285e-02 -4.05894190e-01 9.12062347e-01 -5.81395440e-02 -4.02714729e-01 9.13466990e-01 -5.81392199e-02 -3.99462879e-01 9.14896905e-01 -5.81393056e-02 -3.96278977e-01 9.16279554e-01 -5.81395216e-02 -3.93128932e-01 9.17631924e-01 -5.81395738e-02 -3.89989674e-01 9.18972552e-01 -5.81392832e-02 -3.86740506e-01 9.20345366e-01 -5.81391342e-02 -3.83508205e-01 9.21697795e-01 -5.81394993e-02 -3.80296290e-01 9.23026145e-01 -5.81392683e-02 -3.77065063e-01 9.24353004e-01 -5.81394918e-02 -3.73830348e-01 9.25664425e-01 -5.81391789e-02 -3.70511919e-01 9.26997006e-01 -5.81392609e-02 -3.67279500e-01 9.28284883e-01 -5.81392795e-02 -3.64149123e-01 9.29516137e-01 -5.81395738e-02 -3.60920280e-01 9.30769682e-01 -5.81391379e-02 -3.57578635e-01 9.32067811e-01 -5.81392720e-02 -3.54383141e-01 9.33278561e-01 -5.81394322e-02 -3.51134241e-01 9.34501946e-01 -5.81391603e-02 -3.47862780e-01 9.35722888e-01 -5.81394844e-02 -3.44627589e-01 9.36923206e-01 -5.81392534e-02 -3.41314763e-01 9.38145220e-01 -5.81395738e-02 -3.38044018e-01 9.39323008e-01 -5.81392497e-02 -3.34694505e-01 9.40525115e-01 -5.81393316e-02 -3.31420958e-01 9.41682339e-01 -5.81393391e-02 -3.28108698e-01 9.42840219e-01 -5.81393056e-02 -3.24893773e-01 9.43955779e-01 -5.81395067e-02 -3.21597368e-01 9.45080638e-01 -5.81391715e-02 -3.18237484e-01 9.46220040e-01 -5.81393391e-02 -3.14910918e-01 9.47329819e-01 -5.81393428e-02 -3.11701000e-01 9.48392868e-01 -5.81395738e-02 -3.08461100e-01 9.49451447e-01 -5.81393167e-02 -3.05075765e-01 9.50544715e-01 -5.81391491e-02 -3.01750004e-01 9.51605558e-01 -5.81395403e-02 -2.98532426e-01 9.52619910e-01 -5.81394583e-02 -2.95213908e-01 9.53652203e-01 -5.81394210e-02 -2.91801274e-01 9.54701543e-01 -5.81391454e-02 -2.88432896e-01 9.55725193e-01 -5.81394546e-02 -2.85122305e-01 9.56716180e-01 -5.81391640e-02 -2.81776637e-01 9.57710505e-01 -5.81394807e-02 -2.78456926e-01 9.58678901e-01 -5.81391416e-02 -2.75037497e-01 9.59666729e-01 -5.81393763e-02 -2.71766067e-01 9.60597396e-01 -5.81394061e-02 -2.68404216e-01 9.61542487e-01 -5.81391789e-02 -2.64999747e-01 9.62486029e-01 -5.81394136e-02 -2.61635900e-01 9.63408589e-01 -5.81391938e-02 -2.58291423e-01 9.64308321e-01 -5.81394881e-02 -2.54941583e-01 9.65199947e-01 -5.81391864e-02 -2.51491427e-01 9.66104746e-01 -5.81393577e-02 -2.48109594e-01 9.66977239e-01 -5.81393093e-02 -2.44729564e-01 9.67837274e-01 -5.81393167e-02 -2.41436929e-01 9.68665302e-01 -5.81394918e-02 -2.38066658e-01 9.69498873e-01 -5.81392050e-02 -2.34596282e-01 9.70347285e-01 -5.81393316e-02 -2.31206745e-01 9.71160054e-01 -5.81393018e-02 -2.27890015e-01 9.71942008e-01 -5.81394471e-02 -2.24567905e-01 9.72715676e-01 -5.81392720e-02 -2.21106589e-01 9.73506808e-01 -5.81391901e-02 -2.17712760e-01 9.74273205e-01 -5.81394620e-02 -2.14385301e-01 9.75008249e-01 -5.81392944e-02 -2.10996196e-01 9.75748897e-01 -5.81393056e-02 -2.07522675e-01 9.76493061e-01 -5.81391752e-02 -2.04100519e-01 9.77214992e-01 -5.81395179e-02 -2.00692624e-01 9.77920890e-01 -5.81392124e-02 -1.97282478e-01 9.78613377e-01 -5.81395738e-02 -1.93844274e-01 9.79298353e-01 -5.81390895e-02 -1.90324202e-01 9.79989588e-01 -5.81393167e-02 -1.86985850e-01 9.80633378e-01 -5.81395365e-02 -1.83588088e-01 9.81273949e-01 -5.81391379e-02 -1.80145815e-01 9.81911004e-01 -5.81395589e-02 -1.76722720e-01 9.82537806e-01 -5.81391752e-02 -1.73300803e-01 9.83148515e-01 -5.81395477e-02 -1.69979885e-01 9.83721972e-01 -5.81392944e-02 -1.66420043e-01 9.84331965e-01 -5.81390858e-02 -1.62866384e-01 9.84924495e-01 -5.81393540e-02 -1.59447744e-01 9.85484779e-01 -5.81393056e-02 -1.56110540e-01 9.86019850e-01 -5.81395738e-02 -1.52785778e-01 9.86539900e-01 -5.81393614e-02 -1.49212852e-01 9.87084210e-01 -5.81390932e-02 -1.45659655e-01 9.87616539e-01 -5.81393912e-02 -1.42199740e-01 9.88120258e-01 -5.81393614e-02 -1.38855040e-01 9.88597631e-01 -5.81395738e-02 -1.35526985e-01 9.89060402e-01 -5.81393242e-02 -1.32051453e-01 9.89528596e-01 -5.81392795e-02 -1.28591835e-01 9.89983022e-01 -5.81392907e-02 -1.25045583e-01 9.90438342e-01 -5.81391230e-02 -1.21482730e-01 9.90881085e-01 -5.81393614e-02 -1.18109137e-01 9.91288126e-01 -5.81395254e-02 -1.14664115e-01 9.91690934e-01 -5.81391454e-02 -1.11194655e-01 9.92089570e-01 -5.81395663e-02 -1.07826158e-01 9.92459595e-01 -5.81392869e-02 -1.04238853e-01 9.92842495e-01 -5.81392013e-02 -1.00682646e-01 9.93209600e-01 -5.81393391e-02 -9.72265005e-02 9.93554533e-01 -5.81393354e-02 -9.37676057e-02 9.93888259e-01 -5.81393577e-02 -9.02767256e-02 9.94210601e-01 -5.81393167e-02 -8.69046673e-02 9.94513035e-01 -5.81395514e-02 -8.35359767e-02 9.94798899e-01 -5.81393242e-02 -7.99724683e-02 9.95091438e-01 -5.81391640e-02 -7.63940886e-02 9.95373607e-01 -5.81393465e-02 -7.29130134e-02 9.95635271e-01 -5.81393503e-02 -6.95556030e-02 9.95874524e-01 -5.81395254e-02 -6.61615580e-02 9.96106267e-01 -5.81393018e-02 -6.26681820e-02 9.96329665e-01 -5.81393391e-02 -5.91243319e-02 9.96546805e-01 -5.81391640e-02 -5.55502698e-02 9.96754408e-01 -5.81393093e-02 -5.20312935e-02 9.96941924e-01 -5.81393354e-02 -4.86558564e-02 9.97115195e-01 -5.81395254e-02 -4.51966673e-02 9.97274935e-01 -5.81391454e-02 -4.17196266e-02 9.97430384e-01 -5.81395142e-02 -3.82369421e-02 9.97565985e-01 -5.81390560e-02 -3.46437059e-02 9.97698545e-01 -5.81393428e-02 -3.12666520e-02 9.97810841e-01 -5.81395105e-02 -2.77939923e-02 9.97912765e-01 -5.81391416e-02 -2.43124403e-02 9.98008430e-01 -5.81395477e-02 -2.08037365e-02 9.98078167e-01 -5.81390336e-02 -1.72014888e-02 9.98156548e-01 -5.81392720e-02 -1.37178265e-02 9.98202503e-01 -5.81393503e-02 -1.02446228e-02 9.98247504e-01 -5.81393428e-02 -6.84579788e-03 9.98282194e-01 -5.81395701e-02 -3.34382150e-03 9.98299301e-01 -5.81391305e-02 1.21677193e-04 9.98301804e-01 -5.81395477e-02 3.48928152e-03 9.98299778e-01 -5.81393503e-02 7.08012376e-03 9.98280764e-01 -5.81392124e-02 1.06597580e-02 9.98242199e-01 -5.81393875e-02 1.41632147e-02 9.98196185e-01 -5.81393540e-02 1.76553801e-02 9.98148441e-01 -5.81393577e-02 2.10344605e-02 9.98079717e-01 -5.81395701e-02 2.44268905e-02 9.98002589e-01 -5.81392832e-02 2.80022603e-02 9.97907996e-01 -5.81391454e-02 3.15959640e-02 9.97800469e-01 -5.81393577e-02 3.49799134e-02 9.97688949e-01 -5.81395030e-02 3.83597724e-02 9.97564435e-01 -5.81393614e-02 4.19079177e-02 9.97419536e-01 -5.81391566e-02 4.54431660e-02 9.97265458e-01 -5.81394807e-02 4.89056893e-02 9.97103393e-01 -5.81391901e-02 5.24498858e-02 9.96919215e-01 -5.81393391e-02 5.59174940e-02 9.96734202e-01 -5.81393689e-02 5.94084784e-02 9.96530652e-01 -5.81392832e-02 6.28970116e-02 9.96314526e-01 -5.81393130e-02 6.63756505e-02 9.96090889e-01 -5.81393391e-02 6.97950423e-02 9.95855987e-01 -5.81394807e-02 7.32565671e-02 9.95608211e-01 -5.81391528e-02 7.68172964e-02 9.95339751e-01 -5.81393130e-02 8.02637041e-02 9.95069861e-01 -5.81394173e-02 8.37622508e-02 9.94779646e-01 -5.81393428e-02 8.72110873e-02 9.94483769e-01 -5.81393652e-02 9.05854329e-02 9.94182467e-01 -5.81395030e-02 9.40817520e-02 9.93858218e-01 -5.81393614e-02 9.76431966e-02 9.93514121e-01 -5.81394322e-02 1.01095043e-01 9.93169904e-01 -5.81393912e-02 1.04502574e-01 9.92817461e-01 -5.81394434e-02 1.07874930e-01 9.92454827e-01 -5.81393801e-02 1.11345701e-01 9.92072642e-01 -5.81392236e-02 1.14900947e-01 9.91664886e-01 -5.81392907e-02 1.18435793e-01 9.91249144e-01 -5.81392869e-02 1.21899754e-01 9.90829408e-01 -5.81392795e-02 1.25249311e-01 9.90414023e-01 -5.81395105e-02 1.28703833e-01 9.89967406e-01 -5.81390783e-02 1.32176757e-01 9.89513636e-01 -5.81395738e-02 1.35602906e-01 9.89047706e-01 -5.81391528e-02 1.39193237e-01 9.88549948e-01 -5.81392534e-02 1.42542064e-01 9.88072991e-01 -5.81395738e-02 1.45969495e-01 9.87568855e-01 -5.81391193e-02 1.49540693e-01 9.87036526e-01 -5.81393130e-02 1.52979836e-01 9.86510813e-01 -5.81393465e-02 1.56326652e-01 9.85984743e-01 -5.81395738e-02 1.59766287e-01 9.85432565e-01 -5.81391789e-02 1.63288429e-01 9.84856308e-01 -5.81393540e-02 1.66645691e-01 9.84294116e-01 -5.81395552e-02 1.70045853e-01 9.83710825e-01 -5.81391640e-02 1.73521638e-01 9.83108580e-01 -5.81394508e-02 1.76863313e-01 9.82511342e-01 -5.81393279e-02 1.80356935e-01 9.81871367e-01 -5.81392273e-02 1.83857605e-01 9.81223941e-01 -5.81393279e-02 1.87322006e-01 9.80568230e-01 -5.81393652e-02 1.90718219e-01 9.79913533e-01 -5.81394732e-02 1.94078371e-01 9.79256153e-01 -5.81395589e-02 1.97393611e-01 9.78590250e-01 -5.81393167e-02 2.00794682e-01 9.77897346e-01 -5.81392795e-02 2.04318777e-01 9.77168560e-01 -5.81390932e-02 2.07806274e-01 9.76433575e-01 -5.81392907e-02 2.11199239e-01 9.75706458e-01 -5.81394173e-02 2.14599922e-01 9.74961281e-01 -5.81392981e-02 2.17925325e-01 9.74224687e-01 -5.81394583e-02 2.21321970e-01 9.73456085e-01 -5.81391901e-02 2.24802494e-01 9.72661972e-01 -5.81393130e-02 2.28177756e-01 9.71875727e-01 -5.81394471e-02 2.31565922e-01 9.71074224e-01 -5.81392609e-02 2.34887958e-01 9.70276117e-01 -5.81394434e-02 2.38297507e-01 9.69442844e-01 -5.81392050e-02 2.41680965e-01 9.68604445e-01 -5.81394508e-02 2.45026529e-01 9.67760801e-01 -5.81391267e-02 2.48501301e-01 9.66878176e-01 -5.81393540e-02 2.51861244e-01 9.66006339e-01 -5.81393205e-02 2.55224198e-01 9.65124607e-01 -5.81392609e-02 2.58619457e-01 9.64220583e-01 -5.81393056e-02 2.61897862e-01 9.63337660e-01 -5.81394844e-02 2.65246272e-01 9.62416589e-01 -5.81391603e-02 2.68697679e-01 9.61461008e-01 -5.81393503e-02 2.72056222e-01 9.60517049e-01 -5.81394322e-02 2.75363088e-01 9.59573328e-01 -5.81394136e-02 2.78670698e-01 9.58617270e-01 -5.81394061e-02 2.82076448e-01 9.57619727e-01 -5.81392832e-02 2.85367697e-01 9.56646919e-01 -5.81394918e-02 2.88674772e-01 9.55650270e-01 -5.81391379e-02 2.92087406e-01 9.54615474e-01 -5.81393130e-02 2.95354813e-01 9.53609765e-01 -5.81394769e-02 2.98693538e-01 9.52567995e-01 -5.81391379e-02 3.02003264e-01 9.51523900e-01 -5.81395626e-02 3.05300653e-01 9.50471640e-01 -5.81392311e-02 3.08719128e-01 9.49365854e-01 -5.81392571e-02 3.12063873e-01 9.48271334e-01 -5.81393056e-02 3.15365821e-01 9.47179258e-01 -5.81392944e-02 3.18593383e-01 9.46100175e-01 -5.81395477e-02 3.21856081e-01 9.44992363e-01 -5.81391379e-02 3.25257957e-01 9.43830669e-01 -5.81394508e-02 3.28456640e-01 9.42719579e-01 -5.81394732e-02 3.31725210e-01 9.41572785e-01 -5.81391603e-02 3.35132301e-01 9.40370321e-01 -5.81394285e-02 3.38386118e-01 9.39200580e-01 -5.81394210e-02 3.41635197e-01 9.38025296e-01 -5.81393763e-02 3.44853163e-01 9.36839998e-01 -5.81394881e-02 3.48092347e-01 9.35637593e-01 -5.81391305e-02 3.51406664e-01 9.34397995e-01 -5.81394508e-02 3.54685158e-01 9.33165193e-01 -5.81390820e-02 3.58007282e-01 9.31904852e-01 -5.81393205e-02 3.61196131e-01 9.30663407e-01 -5.81395403e-02 3.64383787e-01 9.29423511e-01 -5.81392050e-02 3.67649019e-01 9.28137362e-01 -5.81395738e-02 3.70863289e-01 9.26856458e-01 -5.81391528e-02 3.74205261e-01 9.25512791e-01 -5.81393391e-02 3.77443194e-01 9.24198210e-01 -5.81393577e-02 3.80665988e-01 9.22872484e-01 -5.81393316e-02 3.83829236e-01 9.21564281e-01 -5.81395216e-02 3.86993110e-01 9.20237839e-01 -5.81391305e-02 3.90322238e-01 9.18830156e-01 -5.81392758e-02 3.93510371e-01 9.17469263e-01 -5.81393503e-02 3.96719635e-01 9.16087687e-01 -5.81392534e-02 3.99838239e-01 9.14734125e-01 -5.81394248e-02 4.03021097e-01 9.13333356e-01 -5.81391640e-02 4.06215221e-01 9.11919117e-01 -5.81395291e-02 4.09282595e-01 9.10546482e-01 -5.81393018e-02 4.12543744e-01 9.09070790e-01 -5.81391305e-02 4.15733695e-01 9.07615960e-01 -5.81395030e-02 4.18866694e-01 9.06174362e-01 -5.81391789e-02 4.22030479e-01 9.04707432e-01 -5.81395738e-02 4.25126195e-01 9.03256893e-01 -5.81395701e-02 4.28257585e-01 9.01773930e-01 -5.81393354e-02 4.31509227e-01 9.00222063e-01 -5.81392683e-02 4.34715241e-01 8.98683131e-01 -5.81393577e-02 4.37766880e-01 8.97201836e-01 -5.81394993e-02 4.40827429e-01 8.95698071e-01 -5.81392720e-02 4.43959653e-01 8.94150198e-01 -5.81393279e-02 4.47048366e-01 8.92610133e-01 -5.81392981e-02 4.50242043e-01 8.91003013e-01 -5.81390858e-02 4.53406870e-01 8.89397740e-01 -5.81392832e-02 4.56446975e-01 8.87842119e-01 -5.81395626e-02 4.59551185e-01 8.86237025e-01 -5.81393987e-02 4.62638199e-01 8.84634376e-01 -5.81395254e-02 4.65706050e-01 8.83019209e-01 -5.81392087e-02 4.68781263e-01 8.81390810e-01 -5.81394918e-02 4.71844941e-01 8.79754305e-01 -5.81391752e-02 4.74979639e-01 8.78064513e-01 -5.81392795e-02 4.77983207e-01 8.76437366e-01 -5.81394546e-02 4.81022656e-01 8.74769449e-01 -5.81391454e-02 4.84084159e-01 8.73077095e-01 -5.81394434e-02 4.87025976e-01 8.71441543e-01 -5.81393875e-02 4.90172893e-01 8.69676292e-01 -5.81392534e-02 4.93271053e-01 8.67920280e-01 -5.81394136e-02 4.96286273e-01 8.66201699e-01 -5.81393056e-02 4.99263912e-01 8.64491045e-01 -5.81395738e-02 5.02187908e-01 8.62793326e-01 -5.81393130e-02 5.05190849e-01 8.61038089e-01 -5.81392609e-02 5.08265257e-01 8.59225929e-01 -5.81391118e-02 5.11311352e-01 8.57417941e-01 -5.81393018e-02 5.14314950e-01 8.55618715e-01 -5.81392758e-02 5.17236054e-01 8.53856683e-01 -5.81394546e-02 5.20192981e-01 8.52059603e-01 -5.81391975e-02 5.23167193e-01 8.50234747e-01 -5.81394583e-02 5.26120961e-01 8.48412395e-01 -5.81391081e-02 5.29165328e-01 8.46513987e-01 -5.81392534e-02 5.32060385e-01 8.44699740e-01 -5.81393801e-02 5.34955680e-01 8.42867672e-01 -5.81390858e-02 5.37934124e-01 8.40970457e-01 -5.81395254e-02 5.40847659e-01 8.39098573e-01 -5.81392050e-02 5.43790877e-01 8.37195694e-01 -5.81394024e-02 5.46703637e-01 8.35293770e-01 -5.81391193e-02 5.49702048e-01 8.33326936e-01 -5.81392422e-02 5.52543640e-01 8.31442654e-01 -5.81394508e-02 5.55420160e-01 8.29524219e-01 -5.81391528e-02 5.58308959e-01 8.27587008e-01 -5.81395738e-02 5.61093926e-01 8.25698912e-01 -5.81395477e-02 5.64047694e-01 8.23686063e-01 -5.81395701e-02 5.66940486e-01 8.21700871e-01 -5.81395142e-02 5.69791675e-01 8.19722891e-01 -5.81395403e-02 5.72707951e-01 8.17690670e-01 -5.81394956e-02 5.75409293e-01 8.15794468e-01 -5.81394918e-02 5.78271985e-01 8.13766658e-01 -5.81394732e-02 5.81101835e-01 8.11749697e-01 -5.81394471e-02 5.83982825e-01 8.09681714e-01 -5.81394248e-02 5.86856306e-01 8.07606876e-01 -5.81392683e-02 5.89595735e-01 8.05600822e-01 -5.81389107e-02 5.92216492e-01 8.03676784e-01 -5.81389554e-02 5.94986737e-01 8.01629424e-01 -5.81390411e-02 5.97126067e-01 8.00037146e-01 -5.81390262e-02 5.99543750e-01 7.98227489e-01 -5.81390336e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.19211340e-01 6.92354620e-01 -5.81390299e-02 7.21623838e-01 6.89839721e-01 -5.81390299e-02 7.23448634e-01 6.87924862e-01 -5.81390299e-02 7.25646436e-01 6.85605168e-01 -5.81389442e-02 7.27972031e-01 6.83143079e-01 -5.81392497e-02 7.30291069e-01 6.80656850e-01 -5.81394248e-02 7.32573330e-01 6.78198934e-01 -5.81394471e-02 7.34954834e-01 6.75614893e-01 -5.81395105e-02 7.37321913e-01 6.73030019e-01 -5.81395142e-02 7.39641786e-01 6.70476079e-01 -5.81395291e-02 7.41971791e-01 6.67896688e-01 -5.81395589e-02 7.44225085e-01 6.65381372e-01 -5.81394695e-02 7.46608853e-01 6.62706792e-01 -5.81392236e-02 7.48919189e-01 6.60096049e-01 -5.81395663e-02 7.51213193e-01 6.57479882e-01 -5.81391975e-02 7.53486574e-01 6.54878616e-01 -5.81395738e-02 7.55713403e-01 6.52307034e-01 -5.81395365e-02 7.57982790e-01 6.49668634e-01 -5.81394956e-02 7.60251582e-01 6.47010565e-01 -5.81395142e-02 7.62559414e-01 6.44289315e-01 -5.81393167e-02 7.64879525e-01 6.41534626e-01 -5.81395291e-02 7.67055929e-01 6.38931096e-01 -5.81395701e-02 7.69222200e-01 6.36319637e-01 -5.81394956e-02 7.71433592e-01 6.33638084e-01 -5.81394993e-02 7.73695827e-01 6.30868852e-01 -5.81392385e-02 7.75958538e-01 6.28088892e-01 -5.81394583e-02 7.78082073e-01 6.25454068e-01 -5.81395738e-02 7.80182421e-01 6.22833967e-01 -5.81394583e-02 7.82357872e-01 6.20095551e-01 -5.81394210e-02 7.84600914e-01 6.17258668e-01 -5.81393093e-02 7.86794901e-01 6.14459038e-01 -5.81395105e-02 7.88929641e-01 6.11715555e-01 -5.81393912e-02 7.91064858e-01 6.08950436e-01 -5.81393652e-02 7.93136239e-01 6.06253028e-01 -5.81395738e-02 7.95233607e-01 6.03497446e-01 -5.81392199e-02 7.97336996e-01 6.00717545e-01 -5.81395067e-02 7.99377799e-01 5.97994685e-01 -5.81394061e-02 8.01517308e-01 5.95121980e-01 -5.81392050e-02 8.03592265e-01 5.92320800e-01 -5.81395738e-02 8.05641174e-01 5.89528739e-01 -5.81391975e-02 8.07748497e-01 5.86640537e-01 -5.81392981e-02 8.09745848e-01 5.83878279e-01 -5.81395105e-02 8.11706841e-01 5.81152976e-01 -5.81393912e-02 8.13800335e-01 5.78217089e-01 -5.81391603e-02 8.15872252e-01 5.75291693e-01 -5.81392832e-02 8.17865849e-01 5.72448432e-01 -5.81393205e-02 8.19802642e-01 5.69672763e-01 -5.81395477e-02 8.21746528e-01 5.66867888e-01 -5.81393316e-02 8.23719621e-01 5.63994706e-01 -5.81393130e-02 8.25731218e-01 5.61043978e-01 -5.81391677e-02 8.27737510e-01 5.58081031e-01 -5.81393279e-02 8.29634726e-01 5.55256486e-01 -5.81394956e-02 8.31545711e-01 5.52388072e-01 -5.81392646e-02 8.33475530e-01 5.49475014e-01 -5.81394807e-02 8.35403144e-01 5.46536446e-01 -5.81391864e-02 8.37305784e-01 5.43622851e-01 -5.81395254e-02 8.39142025e-01 5.40780067e-01 -5.81393093e-02 8.41059387e-01 5.37792027e-01 -5.81391975e-02 8.42948854e-01 5.34829021e-01 -5.81395738e-02 8.44803393e-01 5.31895638e-01 -5.81391118e-02 8.46713006e-01 5.28850079e-01 -5.81394620e-02 8.48498166e-01 5.25982201e-01 -5.81395105e-02 8.50324035e-01 5.23022056e-01 -5.81391864e-02 8.52165878e-01 5.20020902e-01 -5.81395738e-02 8.53968740e-01 5.17048180e-01 -5.81392311e-02 8.55778456e-01 5.14051795e-01 -5.81395738e-02 8.57491314e-01 5.11187434e-01 -5.81394099e-02 8.59280407e-01 5.08175075e-01 -5.81392832e-02 8.61053884e-01 5.05165517e-01 -5.81393465e-02 8.62858772e-01 5.02076507e-01 -5.81392087e-02 8.64661753e-01 4.98963982e-01 -5.81393652e-02 8.66341174e-01 4.96044308e-01 -5.81395738e-02 8.68015230e-01 4.93103921e-01 -5.81393912e-02 8.69734287e-01 4.90074039e-01 -5.81393912e-02 8.71490777e-01 4.86935824e-01 -5.81391901e-02 8.73259485e-01 4.83755827e-01 -5.81394695e-02 8.74879956e-01 4.80823725e-01 -5.81395701e-02 8.76512706e-01 4.77840960e-01 -5.81393912e-02 8.78167808e-01 4.74790096e-01 -5.81394844e-02 8.79866123e-01 4.71635103e-01 -5.81392013e-02 8.81510854e-01 4.68556941e-01 -5.81395738e-02 8.83146584e-01 4.65462744e-01 -5.81391640e-02 8.84812057e-01 4.62292314e-01 -5.81394620e-02 8.86365056e-01 4.59304482e-01 -5.81395738e-02 8.87943864e-01 4.56245482e-01 -5.81392720e-02 8.89550269e-01 4.53110069e-01 -5.81395589e-02 8.91067624e-01 4.50114399e-01 -5.81394173e-02 8.92709553e-01 4.46847081e-01 -5.81392571e-02 8.94270420e-01 4.43718076e-01 -5.81395738e-02 8.95797431e-01 4.40624595e-01 -5.81393577e-02 8.97374213e-01 4.37409908e-01 -5.81394844e-02 8.98858130e-01 4.34356779e-01 -5.81395738e-02 9.00330961e-01 4.31283593e-01 -5.81394508e-02 9.01830077e-01 4.28146005e-01 -5.81395738e-02 9.03357327e-01 4.24909681e-01 -5.81392497e-02 9.04884100e-01 4.21654403e-01 -5.81394918e-02 9.06306028e-01 4.18588132e-01 -5.81395663e-02 9.07716036e-01 4.15516615e-01 -5.81394285e-02 9.09154296e-01 4.12363529e-01 -5.81395738e-02 9.10640240e-01 4.09071296e-01 -5.81392422e-02 9.12099838e-01 4.05805409e-01 -5.81394695e-02 9.13477600e-01 4.02698398e-01 -5.81395701e-02 9.14873302e-01 3.99517536e-01 -5.81392832e-02 9.16254044e-01 3.96338701e-01 -5.81395738e-02 9.17625546e-01 3.93143356e-01 -5.81393428e-02 9.19005275e-01 3.89916778e-01 -5.81395589e-02 9.20327842e-01 3.86784762e-01 -5.81394508e-02 9.21698987e-01 3.83503705e-01 -5.81392311e-02 9.23029840e-01 3.80285859e-01 -5.81395477e-02 9.24345851e-01 3.77077132e-01 -5.81392460e-02 9.25699472e-01 3.73745233e-01 -5.81394695e-02 9.26970005e-01 3.70585889e-01 -5.81395663e-02 9.28251922e-01 3.67360175e-01 -5.81392422e-02 9.29531574e-01 3.64113688e-01 -5.81395067e-02 9.30781007e-01 3.60889196e-01 -5.81392534e-02 9.32085872e-01 3.57531786e-01 -5.81393540e-02 9.33305442e-01 3.54310155e-01 -5.81395701e-02 9.34487164e-01 3.51170868e-01 -5.81394285e-02 9.35711443e-01 3.47893119e-01 -5.81394956e-02 9.36947405e-01 3.44563156e-01 -5.81391975e-02 9.38193142e-01 3.41179550e-01 -5.81393763e-02 9.39337015e-01 3.38001132e-01 -5.81395254e-02 9.40499306e-01 3.34764391e-01 -5.81392460e-02 9.41681921e-01 3.31424445e-01 -5.81395179e-02 9.42822099e-01 3.28158528e-01 -5.81391044e-02 9.43994224e-01 3.24782193e-01 -5.81393652e-02 9.45094883e-01 3.21562678e-01 -5.81395738e-02 9.46200609e-01 3.18290323e-01 -5.81392124e-02 9.47318614e-01 3.14947724e-01 -5.81395738e-02 9.48406875e-01 3.11654747e-01 -5.81392236e-02 9.49494421e-01 3.08330238e-01 -5.81395477e-02 9.50533509e-01 3.05110425e-01 -5.81393912e-02 9.51622665e-01 3.01691741e-01 -5.81391640e-02 9.52673018e-01 2.98361212e-01 -5.81395738e-02 9.53695536e-01 2.95073360e-01 -5.81392199e-02 9.54752922e-01 2.91638017e-01 -5.81394024e-02 9.55738485e-01 2.88388729e-01 -5.81395738e-02 9.56737578e-01 2.85052299e-01 -5.81391826e-02 9.57737386e-01 2.81685501e-01 -5.81395328e-02 9.58707213e-01 2.78363556e-01 -5.81392646e-02 9.59697485e-01 2.74930090e-01 -5.81395105e-02 9.60626304e-01 2.71668315e-01 -5.81395626e-02 9.61539447e-01 2.68421143e-01 -5.81394322e-02 9.62472498e-01 2.65049487e-01 -5.81394248e-02 9.63412702e-01 2.61613309e-01 -5.81392646e-02 9.64352906e-01 2.58124083e-01 -5.81393875e-02 9.65226352e-01 2.54843801e-01 -5.81395738e-02 9.66107666e-01 2.51478016e-01 -5.81392311e-02 9.66979980e-01 2.48109102e-01 -5.81395738e-02 9.67832088e-01 2.44742706e-01 -5.81392422e-02 9.68705893e-01 2.41272166e-01 -5.81394359e-02 9.69541848e-01 2.37897053e-01 -5.81393987e-02 9.70364511e-01 2.34524488e-01 -5.81394061e-02 9.71157312e-01 2.31222421e-01 -5.81395738e-02 9.71946597e-01 2.27874666e-01 -5.81394173e-02 9.72752690e-01 2.24412158e-01 -5.81395589e-02 9.73506749e-01 2.21107900e-01 -5.81395179e-02 9.74291623e-01 2.17630237e-01 -5.81392944e-02 9.75040495e-01 2.14243248e-01 -5.81395663e-02 9.75782216e-01 2.10835189e-01 -5.81392236e-02 9.76516068e-01 2.07426012e-01 -5.81395701e-02 9.77215409e-01 2.04098910e-01 -5.81394061e-02 9.77924407e-01 2.00675130e-01 -5.81393354e-02 9.78635848e-01 1.97166637e-01 -5.81392422e-02 9.79327381e-01 1.93706945e-01 -5.81394322e-02 9.79997993e-01 1.90288916e-01 -5.81395738e-02 9.80644107e-01 1.86929956e-01 -5.81395477e-02 9.81271088e-01 1.83604658e-01 -5.81394695e-02 9.81901467e-01 1.80199459e-01 -5.81394769e-02 9.82556939e-01 1.76620290e-01 -5.81392311e-02 9.83172715e-01 1.73154399e-01 -5.81395105e-02 9.83754098e-01 1.69792578e-01 -5.81395738e-02 9.84329879e-01 1.66435942e-01 -5.81393763e-02 9.84903634e-01 1.62996069e-01 -5.81393540e-02 9.85463262e-01 1.59579948e-01 -5.81393130e-02 9.86029863e-01 1.56046137e-01 -5.81391081e-02 9.86581564e-01 1.52515367e-01 -5.81393167e-02 9.87107337e-01 1.49071887e-01 -5.81393279e-02 9.87610340e-01 1.45710781e-01 -5.81395030e-02 9.88112330e-01 1.42248377e-01 -5.81390932e-02 9.88616407e-01 1.38724282e-01 -5.81392422e-02 9.89083350e-01 1.35360599e-01 -5.81395738e-02 9.89545047e-01 1.31916314e-01 -5.81391975e-02 9.90002394e-01 1.28457740e-01 -5.81395067e-02 9.90440369e-01 1.25029266e-01 -5.81391193e-02 9.90876317e-01 1.21532112e-01 -5.81395291e-02 9.91283536e-01 1.18154138e-01 -5.81393279e-02 9.91686463e-01 1.14710212e-01 -5.81392497e-02 9.92090583e-01 1.11180827e-01 -5.81391007e-02 9.92482781e-01 1.07608743e-01 -5.81392385e-02 9.92850900e-01 1.04161046e-01 -5.81392311e-02 9.93203580e-01 1.00758329e-01 -5.81395179e-02 9.93544102e-01 9.73229185e-02 -5.81390783e-02 9.93880153e-01 9.38420892e-02 -5.81394285e-02 9.94201601e-01 9.03675333e-02 -5.81391230e-02 9.94518638e-01 8.68149027e-02 -5.81392609e-02 9.94807124e-01 8.34446624e-02 -5.81394210e-02 9.95087624e-01 8.00415725e-02 -5.81392981e-02 9.95358229e-01 7.65710995e-02 -5.81393391e-02 9.95623171e-01 7.30538145e-02 -5.81391156e-02 9.95874226e-01 6.95418864e-02 -5.81393801e-02 9.96106625e-01 6.61444440e-02 -5.81392348e-02 9.96333838e-01 6.25847727e-02 -5.81390634e-02 9.96550262e-01 5.90971559e-02 -5.81394434e-02 9.96748984e-01 5.56318611e-02 -5.81390671e-02 9.96941507e-01 5.20602763e-02 -5.81392422e-02 9.97114897e-01 4.86583114e-02 -5.81393763e-02 9.97276306e-01 4.51910272e-02 -5.81390858e-02 9.97430325e-01 4.17147130e-02 -5.81393987e-02 9.97566164e-01 3.82543691e-02 -5.81391305e-02 9.97697830e-01 3.46761569e-02 -5.81392236e-02 9.97812688e-01 3.12442854e-02 -5.81395030e-02 9.97912049e-01 2.78721880e-02 -5.81392646e-02 9.98004675e-01 2.43656170e-02 -5.81392609e-02 9.98078644e-01 2.08072737e-02 -5.81390560e-02 9.98154163e-01 1.73473768e-02 -5.81394508e-02 9.98198569e-01 1.39647257e-02 -5.81393205e-02 9.98246372e-01 1.04659917e-02 -5.81393428e-02 9.98282373e-01 6.96434872e-03 -5.81393018e-02 9.98299003e-01 3.40669462e-03 -5.81390597e-02 9.98300791e-01 -1.97237430e-04 -5.81392422e-02 9.98299718e-01 -3.66505655e-03 -5.81393242e-02 9.98280764e-01 -7.16607412e-03 -5.81392236e-02 9.98245120e-01 -1.05391378e-02 -5.81394061e-02 9.98196006e-01 -1.40577927e-02 -5.81391603e-02 9.98149991e-01 -1.75472107e-02 -5.81394024e-02 9.98078346e-01 -2.08916366e-02 -5.81392273e-02 9.98000145e-01 -2.44909748e-02 -5.81389777e-02 9.97908890e-01 -2.79933307e-02 -5.81394434e-02 9.97803926e-01 -3.14610824e-02 -5.81390187e-02 9.97689486e-01 -3.49546112e-02 -5.81393838e-02 9.97563958e-01 -3.83371525e-02 -5.81392311e-02 9.97420073e-01 -4.19135243e-02 -5.81390262e-02 9.97263908e-01 -4.55005057e-02 -5.81392534e-02 9.97097373e-01 -4.89864796e-02 -5.81391975e-02 9.96917605e-01 -5.24787642e-02 -5.81392720e-02 9.96737421e-01 -5.58430739e-02 -5.81394620e-02 9.96542215e-01 -5.92118353e-02 -5.81392050e-02 9.96326506e-01 -6.27093017e-02 -5.81391938e-02 9.96096492e-01 -6.62901178e-02 -5.81390336e-02 9.95849371e-01 -6.98828772e-02 -5.81393056e-02 9.95602667e-01 -7.33525082e-02 -5.81393354e-02 9.95349109e-01 -7.67064914e-02 -5.81394434e-02 9.95082855e-01 -8.00896734e-02 -5.81392050e-02 9.94795799e-01 -8.35695788e-02 -5.81392162e-02 9.94487762e-01 -8.71546939e-02 -5.81389964e-02 9.94178236e-01 -9.06287581e-02 -5.81394434e-02 9.93868649e-01 -9.39585418e-02 -5.81392422e-02 9.93534446e-01 -9.74329934e-02 -5.81392422e-02 9.93176699e-01 -1.01005003e-01 -5.81390634e-02 9.92816865e-01 -1.04499511e-01 -5.81394322e-02 9.92446721e-01 -1.07944809e-01 -5.81390485e-02 9.92066801e-01 -1.11409098e-01 -5.81394248e-02 9.91679966e-01 -1.14776015e-01 -5.81392162e-02 9.91262496e-01 -1.18318424e-01 -5.81390150e-02 9.90840375e-01 -1.21825427e-01 -5.81394546e-02 9.90414023e-01 -1.25244752e-01 -5.81390858e-02 9.89958227e-01 -1.28790721e-01 -5.81392981e-02 9.89511609e-01 -1.32175148e-01 -5.81393763e-02 9.89044607e-01 -1.35625631e-01 -5.81390411e-02 9.88551617e-01 -1.39175206e-01 -5.81392273e-02 9.88074839e-01 -1.42520711e-01 -5.81393987e-02 9.87569809e-01 -1.45966038e-01 -5.81391305e-02 9.87055242e-01 -1.49417475e-01 -5.81393875e-02 9.86525893e-01 -1.52868688e-01 -5.81390783e-02 9.85986412e-01 -1.56313360e-01 -5.81394285e-02 9.85437214e-01 -1.59738764e-01 -5.81390448e-02 9.84872162e-01 -1.63194701e-01 -5.81394508e-02 9.84303474e-01 -1.66579723e-01 -5.81391416e-02 9.83697057e-01 -1.70120597e-01 -5.81392609e-02 9.83100235e-01 -1.73567340e-01 -5.81392050e-02 9.82497752e-01 -1.76944643e-01 -5.81394285e-02 9.81887102e-01 -1.80268124e-01 -5.81392646e-02 9.81252789e-01 -1.83707461e-01 -5.81392422e-02 9.80592191e-01 -1.87194496e-01 -5.81391566e-02 9.79915440e-01 -1.90695763e-01 -5.81392087e-02 9.79244590e-01 -1.94124386e-01 -5.81391715e-02 9.78575766e-01 -1.97465688e-01 -5.81393801e-02 9.77901220e-01 -2.00784475e-01 -5.81393018e-02 9.77196753e-01 -2.04179719e-01 -5.81392050e-02 9.76459801e-01 -2.07679570e-01 -5.81390783e-02 9.75729525e-01 -2.11088628e-01 -5.81394322e-02 9.74992931e-01 -2.14454785e-01 -5.81391379e-02 9.74242985e-01 -2.17844725e-01 -5.81393279e-02 9.73460853e-01 -2.21308380e-01 -5.81391081e-02 9.72686231e-01 -2.24692911e-01 -5.81393912e-02 9.71894920e-01 -2.28096321e-01 -5.81390709e-02 9.71089900e-01 -2.31500551e-01 -5.81394248e-02 9.70297396e-01 -2.34801576e-01 -5.81391975e-02 9.69456255e-01 -2.38240212e-01 -5.81391081e-02 9.68615651e-01 -2.41632268e-01 -5.81393428e-02 9.67766345e-01 -2.45003328e-01 -5.81390746e-02 9.66888726e-01 -2.48454824e-01 -5.81393018e-02 9.66036499e-01 -2.51751184e-01 -5.81393316e-02 9.65147078e-01 -2.55143523e-01 -5.81390522e-02 9.64255393e-01 -2.58495718e-01 -5.81394248e-02 9.63369608e-01 -2.61775017e-01 -5.81391864e-02 9.62426007e-01 -2.65211403e-01 -5.81390858e-02 9.61491406e-01 -2.68593788e-01 -5.81394024e-02 9.60556030e-01 -2.71916658e-01 -5.81390820e-02 9.59565401e-01 -2.75385112e-01 -5.81391975e-02 9.58618522e-01 -2.78665274e-01 -5.81394695e-02 9.57679331e-01 -2.81874478e-01 -5.81392162e-02 9.56664383e-01 -2.85304308e-01 -5.81391007e-02 9.55633998e-01 -2.88733006e-01 -5.81392236e-02 9.54617143e-01 -2.92078346e-01 -5.81391938e-02 9.53617811e-01 -2.95327425e-01 -5.81394397e-02 9.52611983e-01 -2.98550338e-01 -5.81391864e-02 9.51562643e-01 -3.01883638e-01 -5.81392497e-02 9.50467944e-01 -3.05303097e-01 -5.81390299e-02 9.49378371e-01 -3.08680028e-01 -5.81392385e-02 9.48293388e-01 -3.11998487e-01 -5.81391975e-02 9.47222292e-01 -3.15237463e-01 -5.81394508e-02 9.46156442e-01 -3.18422914e-01 -5.81392720e-02 9.45029318e-01 -3.21751475e-01 -5.81392869e-02 9.43865538e-01 -3.25142145e-01 -5.81390522e-02 9.42720294e-01 -3.28452677e-01 -5.81394210e-02 9.41579998e-01 -3.31709981e-01 -5.81392348e-02 9.40431416e-01 -3.34961593e-01 -5.81394844e-02 9.39228952e-01 -3.38305265e-01 -5.81391044e-02 9.38048720e-01 -3.41575861e-01 -5.81394769e-02 9.36848760e-01 -3.44830930e-01 -5.81390671e-02 9.35631335e-01 -3.48108530e-01 -5.81394322e-02 9.34459925e-01 -3.51244122e-01 -5.81392683e-02 9.33221877e-01 -3.54533345e-01 -5.81392460e-02 9.31952834e-01 -3.57876599e-01 -5.81391267e-02 9.30686355e-01 -3.61135900e-01 -5.81393763e-02 9.29433405e-01 -3.64362329e-01 -5.81391379e-02 9.28152323e-01 -3.67613256e-01 -5.81393614e-02 9.26871717e-01 -3.70823950e-01 -5.81391156e-02 9.25565064e-01 -3.74078453e-01 -5.81394285e-02 9.24282789e-01 -3.77231687e-01 -5.81392832e-02 9.22945201e-01 -3.80488634e-01 -5.81391230e-02 9.21601295e-01 -3.83737504e-01 -5.81393279e-02 9.20242965e-01 -3.86980653e-01 -5.81390969e-02 9.18851495e-01 -3.90272647e-01 -5.81392944e-02 9.17532206e-01 -3.93364131e-01 -5.81394136e-02 9.16189134e-01 -3.96485001e-01 -5.81392534e-02 9.14752841e-01 -3.99789751e-01 -5.81390746e-02 9.13308442e-01 -4.03077453e-01 -5.81393205e-02 9.11900580e-01 -4.06251878e-01 -5.81392646e-02 9.10509288e-01 -4.09365028e-01 -5.81394471e-02 9.09120739e-01 -4.12435383e-01 -5.81392720e-02 9.07687902e-01 -4.15575713e-01 -5.81392869e-02 9.06191230e-01 -4.18832481e-01 -5.81390448e-02 9.04674888e-01 -4.22097892e-01 -5.81392534e-02 9.03195441e-01 -4.25251931e-01 -5.81392497e-02 9.01750088e-01 -4.28312808e-01 -5.81394471e-02 9.00289714e-01 -4.31368232e-01 -5.81392385e-02 8.98779213e-01 -4.34515625e-01 -5.81392832e-02 8.97225499e-01 -4.37712252e-01 -5.81390709e-02 8.95675600e-01 -4.40874159e-01 -5.81394173e-02 8.94136906e-01 -4.43984568e-01 -5.81390932e-02 8.92585635e-01 -4.47096795e-01 -5.81394173e-02 8.91049623e-01 -4.50153768e-01 -5.81392013e-02 8.89471352e-01 -4.53260750e-01 -5.81391975e-02 8.87842834e-01 -4.56439793e-01 -5.81390932e-02 8.86255860e-01 -4.59514081e-01 -5.81394322e-02 8.84684682e-01 -4.62536037e-01 -5.81392311e-02 8.83069277e-01 -4.65609998e-01 -5.81392124e-02 8.81413996e-01 -4.68733311e-01 -5.81391416e-02 8.79767358e-01 -4.71820652e-01 -5.81392609e-02 8.78094435e-01 -4.74923402e-01 -5.81390671e-02 8.76433671e-01 -4.77989674e-01 -5.81393875e-02 8.74796033e-01 -4.80973333e-01 -5.81391901e-02 8.73133183e-01 -4.83983159e-01 -5.81392348e-02 8.71421933e-01 -4.87058491e-01 -5.81391379e-02 8.69699836e-01 -4.90128428e-01 -5.81391715e-02 8.67947817e-01 -4.93224353e-01 -5.81390634e-02 8.66224647e-01 -4.96248186e-01 -5.81394583e-02 8.64495993e-01 -4.99249190e-01 -5.81390299e-02 8.62732172e-01 -5.02292693e-01 -5.81393614e-02 8.61039877e-01 -5.05188525e-01 -5.81391715e-02 8.59268486e-01 -5.08194625e-01 -5.81392236e-02 8.57471824e-01 -5.11219084e-01 -5.81392013e-02 8.55642200e-01 -5.14278114e-01 -5.81390187e-02 8.53791058e-01 -5.17340720e-01 -5.81392571e-02 8.52023602e-01 -5.20252764e-01 -5.81393801e-02 8.50260377e-01 -5.23124874e-01 -5.81391826e-02 8.48427653e-01 -5.26095927e-01 -5.81391789e-02 8.46532941e-01 -5.29135883e-01 -5.81390373e-02 8.44635248e-01 -5.32160699e-01 -5.81392124e-02 8.42810750e-01 -5.35044670e-01 -5.81394359e-02 8.40996146e-01 -5.37891924e-01 -5.81392124e-02 8.39073241e-01 -5.40885210e-01 -5.81390411e-02 8.37133884e-01 -5.43884099e-01 -5.81392124e-02 8.35213304e-01 -5.46826422e-01 -5.81391491e-02 8.33306909e-01 -5.49732089e-01 -5.81393167e-02 8.31435144e-01 -5.52554846e-01 -5.81393987e-02 8.29557300e-01 -5.55372417e-01 -5.81391901e-02 8.27608585e-01 -5.58274209e-01 -5.81391491e-02 8.25594604e-01 -5.61246514e-01 -5.81390820e-02 8.23624909e-01 -5.64135492e-01 -5.81393763e-02 8.21662009e-01 -5.66987753e-01 -5.81390299e-02 8.19672346e-01 -5.69862366e-01 -5.81393503e-02 8.17693472e-01 -5.72693050e-01 -5.81391118e-02 8.15695405e-01 -5.75543284e-01 -5.81393391e-02 8.13685179e-01 -5.78376174e-01 -5.81390373e-02 8.11645150e-01 -5.81239104e-01 -5.81393950e-02 8.09651136e-01 -5.84006548e-01 -5.81392087e-02 8.07595491e-01 -5.86850345e-01 -5.81391715e-02 8.05504858e-01 -5.89713752e-01 -5.81391081e-02 8.03399324e-01 -5.92579305e-01 -5.81391528e-02 8.01347733e-01 -5.95351875e-01 -5.81392795e-02 7.99319804e-01 -5.98070264e-01 -5.81392311e-02 7.97209740e-01 -6.00883663e-01 -5.81390932e-02 7.95103848e-01 -6.03668034e-01 -5.81393354e-02 7.93004692e-01 -6.06421471e-01 -5.81391044e-02 7.90875018e-01 -6.09196901e-01 -5.81393428e-02 7.88797498e-01 -6.11883700e-01 -5.81391789e-02 7.86603749e-01 -6.14700735e-01 -5.81390001e-02 7.84396648e-01 -6.17515266e-01 -5.81392311e-02 7.82286406e-01 -6.20186150e-01 -5.81393652e-02 7.80167222e-01 -6.22850239e-01 -5.81391677e-02 7.77993500e-01 -6.25563800e-01 -5.81392236e-02 7.75751889e-01 -6.28341973e-01 -5.81390187e-02 7.73540676e-01 -6.31059647e-01 -5.81393763e-02 7.71379232e-01 -6.33701444e-01 -5.81391528e-02 7.69180238e-01 -6.36369586e-01 -5.81392534e-02 7.66974866e-01 -6.39024019e-01 -5.81391342e-02 7.64716208e-01 -6.41727448e-01 -5.81392236e-02 7.62440205e-01 -6.44427955e-01 -5.81390671e-02 7.60187984e-01 -6.47083700e-01 -5.81393726e-02 7.57976711e-01 -6.49671912e-01 -5.81391864e-02 7.55685449e-01 -6.52336717e-01 -5.81392311e-02 7.53356099e-01 -6.55025959e-01 -5.81390373e-02 7.50997424e-01 -6.57727242e-01 -5.81392124e-02 7.48685777e-01 -6.60357237e-01 -5.81391715e-02 7.46441960e-01 -6.62894070e-01 -5.81394471e-02 7.44202852e-01 -6.65405452e-01 -5.81392050e-02 7.41803646e-01 -6.68079555e-01 -5.81389964e-02 7.39462852e-01 -6.70674324e-01 -5.81394173e-02 7.37123251e-01 -6.73239291e-01 -5.81390411e-02 7.34777451e-01 -6.75801814e-01 -5.81393652e-02 7.32479334e-01 -6.78290725e-01 -5.81391975e-02 7.30041564e-01 -6.80911124e-01 -5.81390448e-02 7.27592349e-01 -6.83528781e-01 -5.81391715e-02 7.25252092e-01 -6.86011374e-01 -5.81394024e-02 7.22881377e-01 -6.88512146e-01 -5.81390187e-02 7.20449686e-01 -6.91047907e-01 -5.81393391e-02 7.18061149e-01 -6.93544209e-01 -5.81390597e-02 7.15579271e-01 -6.96102083e-01 -5.81391975e-02 7.13191450e-01 -6.98545814e-01 -5.81393130e-02 7.10748732e-01 -7.01033115e-01 -5.81390746e-02 7.08291829e-01 -7.03519344e-01 -5.81395179e-02 7.05837250e-01 -7.05964506e-01 -5.81395514e-02 7.03325152e-01 -7.08482981e-01 -5.81395477e-02 7.00901866e-01 -7.10885406e-01 -5.81395142e-02 6.98491096e-01 -7.13250756e-01 -5.81395030e-02 6.95981324e-01 -7.15703309e-01 -5.81394807e-02 6.93435133e-01 -7.18164623e-01 -5.81394657e-02 6.90911412e-01 -7.20601082e-01 -5.81394024e-02 6.88431799e-01 -7.22971439e-01 -5.81393577e-02 6.85998857e-01 -7.25281000e-01 -5.81391752e-02 6.83644235e-01 -7.27493465e-01 -5.81389070e-02 6.80962563e-01 -7.30005980e-01 -5.81390299e-02 6.78323388e-01 -7.32459605e-01 -5.81390709e-02 6.75966680e-01 -7.34634697e-01 -5.81390299e-02 6.73761964e-01 -7.36657500e-01 -5.81390299e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.57018638e-01 -8.28462422e-01 -5.81390262e-02 5.54755390e-01 -8.29979539e-01 -5.81390485e-02 5.52110553e-01 -8.31747055e-01 -5.81393205e-02 5.49354970e-01 -8.33562672e-01 -5.81394322e-02 5.46543777e-01 -8.35404158e-01 -5.81394918e-02 5.43575644e-01 -8.37337554e-01 -5.81395403e-02 5.40652394e-01 -8.39228034e-01 -5.81395440e-02 5.37819564e-01 -8.41044545e-01 -5.81394881e-02 5.34882665e-01 -8.42911720e-01 -5.81393130e-02 5.31951904e-01 -8.44768584e-01 -5.81392199e-02 5.29001176e-01 -8.46615970e-01 -5.81392162e-02 5.26053309e-01 -8.48454118e-01 -5.81392497e-02 5.23079097e-01 -8.50288570e-01 -5.81392385e-02 5.20104945e-01 -8.52114022e-01 -5.81392273e-02 5.17084837e-01 -8.53945434e-01 -5.81391454e-02 5.14085889e-01 -8.55756700e-01 -5.81393465e-02 5.11145830e-01 -8.57514501e-01 -5.81392311e-02 5.08122146e-01 -8.59310448e-01 -5.81392609e-02 5.05122364e-01 -8.61078918e-01 -5.81392013e-02 5.02118170e-01 -8.62832367e-01 -5.81392720e-02 4.99041021e-01 -8.64616275e-01 -5.81391081e-02 4.96016681e-01 -8.66356492e-01 -5.81393354e-02 4.93062437e-01 -8.68038535e-01 -5.81392422e-02 4.90026295e-01 -8.69759917e-01 -5.81392199e-02 4.86980826e-01 -8.71465504e-01 -5.81391715e-02 4.83932555e-01 -8.73159528e-01 -5.81392236e-02 4.80892241e-01 -8.74842167e-01 -5.81392534e-02 4.77838457e-01 -8.76513183e-01 -5.81392348e-02 4.74795431e-01 -8.78163874e-01 -5.81392422e-02 4.71711129e-01 -8.79825652e-01 -5.81391864e-02 4.68635350e-01 -8.81466091e-01 -5.81392087e-02 4.65554237e-01 -8.83099914e-01 -5.81392124e-02 4.62486207e-01 -8.84709954e-01 -5.81392571e-02 4.59400594e-01 -8.86314273e-01 -5.81392124e-02 4.56299365e-01 -8.87916565e-01 -5.81392124e-02 4.53207523e-01 -8.89497280e-01 -5.81391938e-02 4.50103909e-01 -8.91072810e-01 -5.81391789e-02 4.46994513e-01 -8.92636716e-01 -5.81392422e-02 4.43898439e-01 -8.94179821e-01 -5.81392534e-02 4.40758348e-01 -8.95732105e-01 -5.81392422e-02 4.37631249e-01 -8.97266150e-01 -5.81392162e-02 4.34500068e-01 -8.98785651e-01 -5.81392124e-02 4.31361079e-01 -9.00293291e-01 -5.81392348e-02 4.28131282e-01 -9.01833951e-01 -5.81390113e-02 4.24957424e-01 -9.03335035e-01 -5.81393950e-02 4.21784461e-01 -9.04820383e-01 -5.81390038e-02 4.18630272e-01 -9.06285584e-01 -5.81394769e-02 4.15577054e-01 -9.07687306e-01 -5.81392385e-02 4.12401557e-01 -9.09135401e-01 -5.81392311e-02 4.09206837e-01 -9.10578489e-01 -5.81392311e-02 4.05931801e-01 -9.12042856e-01 -5.81390932e-02 4.02744353e-01 -9.13455904e-01 -5.81394657e-02 3.99668276e-01 -9.14807200e-01 -5.81392758e-02 3.96480560e-01 -9.16190684e-01 -5.81391975e-02 3.93263370e-01 -9.17573214e-01 -5.81392311e-02 3.89981836e-01 -9.18976009e-01 -5.81390448e-02 3.86738718e-01 -9.20347154e-01 -5.81393987e-02 3.83535475e-01 -9.21684563e-01 -5.81390522e-02 3.80309552e-01 -9.23020363e-01 -5.81394210e-02 3.77193511e-01 -9.24300611e-01 -5.81392385e-02 3.73954594e-01 -9.25612986e-01 -5.81391677e-02 3.70626301e-01 -9.26950693e-01 -5.81390560e-02 3.67296010e-01 -9.28277493e-01 -5.81392422e-02 3.64146560e-01 -9.29518402e-01 -5.81394359e-02 3.60992432e-01 -9.30740952e-01 -5.81391975e-02 3.57742459e-01 -9.32004690e-01 -5.81392609e-02 3.54485989e-01 -9.33240235e-01 -5.81391715e-02 3.51229876e-01 -9.34465587e-01 -5.81392050e-02 3.47940326e-01 -9.35694695e-01 -5.81392124e-02 3.44667166e-01 -9.36909139e-01 -5.81392311e-02 3.41413349e-01 -9.38106179e-01 -5.81392646e-02 3.38013053e-01 -9.39334214e-01 -5.81389777e-02 3.34716231e-01 -9.40518081e-01 -5.81394918e-02 3.31475705e-01 -9.41660821e-01 -5.81390709e-02 3.28168273e-01 -9.42820430e-01 -5.81394918e-02 3.24907422e-01 -9.43947613e-01 -5.81390187e-02 3.21589172e-01 -9.45084929e-01 -5.81394546e-02 3.18367094e-01 -9.46174622e-01 -5.81392795e-02 3.15065652e-01 -9.47277069e-01 -5.81392385e-02 3.11746746e-01 -9.48375165e-01 -5.81392087e-02 3.08440328e-01 -9.49456632e-01 -5.81392795e-02 3.05134058e-01 -9.50526655e-01 -5.81392013e-02 3.01796794e-01 -9.51588809e-01 -5.81392199e-02 2.98482776e-01 -9.52634513e-01 -5.81392832e-02 2.95163453e-01 -9.53668356e-01 -5.81392311e-02 2.91852891e-01 -9.54686582e-01 -5.81392348e-02 2.88419455e-01 -9.55726564e-01 -5.81391081e-02 2.84991264e-01 -9.56756175e-01 -5.81392199e-02 2.81722873e-01 -9.57726836e-01 -5.81393801e-02 2.78401166e-01 -9.58696544e-01 -5.81390820e-02 2.74958700e-01 -9.59687710e-01 -5.81392422e-02 2.71607429e-01 -9.60641742e-01 -5.81392534e-02 2.68337190e-01 -9.61562455e-01 -5.81394099e-02 2.65059024e-01 -9.62470055e-01 -5.81392311e-02 2.61684865e-01 -9.63395596e-01 -5.81392609e-02 2.58311093e-01 -9.64301765e-01 -5.81392050e-02 2.54937857e-01 -9.65199888e-01 -5.81392050e-02 2.51592159e-01 -9.66079593e-01 -5.81392013e-02 2.48128533e-01 -9.66971099e-01 -5.81390671e-02 2.44743019e-01 -9.67834234e-01 -5.81393838e-02 2.41371021e-01 -9.68680143e-01 -5.81391007e-02 2.37977788e-01 -9.69521582e-01 -5.81393801e-02 2.34717488e-01 -9.70317483e-01 -5.81392124e-02 2.31307864e-01 -9.71135080e-01 -5.81392162e-02 2.27913409e-01 -9.71937299e-01 -5.81392087e-02 2.24515930e-01 -9.72727597e-01 -5.81391901e-02 2.21059039e-01 -9.73516524e-01 -5.81390746e-02 2.17636675e-01 -9.74289834e-01 -5.81394061e-02 2.14322940e-01 -9.75022495e-01 -5.81392534e-02 2.10891843e-01 -9.75770175e-01 -5.81392646e-02 2.07510740e-01 -9.76494908e-01 -5.81392311e-02 2.04033554e-01 -9.77228999e-01 -5.81390783e-02 2.00531900e-01 -9.77953315e-01 -5.81392869e-02 1.97204694e-01 -9.78628874e-01 -5.81393503e-02 1.93868801e-01 -9.79293823e-01 -5.81391901e-02 1.90436050e-01 -9.79969621e-01 -5.81392199e-02 1.86938435e-01 -9.80640352e-01 -5.81390858e-02 1.83521539e-01 -9.81286943e-01 -5.81394620e-02 1.80094704e-01 -9.81918812e-01 -5.81390262e-02 1.76647156e-01 -9.82553780e-01 -5.81394024e-02 1.73342437e-01 -9.83139813e-01 -5.81392162e-02 1.69926643e-01 -9.83730555e-01 -5.81391975e-02 1.66471735e-01 -9.84322727e-01 -5.81391715e-02 1.62929162e-01 -9.84912992e-01 -5.81390299e-02 1.59481436e-01 -9.85479236e-01 -5.81394359e-02 1.56159446e-01 -9.86011684e-01 -5.81391864e-02 1.52714282e-01 -9.86551166e-01 -5.81392460e-02 1.49261773e-01 -9.87077355e-01 -5.81392199e-02 1.45833805e-01 -9.87591565e-01 -5.81392311e-02 1.42360657e-01 -9.88097250e-01 -5.81392571e-02 1.38902858e-01 -9.88591075e-01 -5.81392497e-02 1.35380924e-01 -9.89079714e-01 -5.81390187e-02 1.31910160e-01 -9.89546895e-01 -5.81393763e-02 1.28551379e-01 -9.89988387e-01 -5.81392087e-02 1.25085950e-01 -9.90433514e-01 -5.81392720e-02 1.21629983e-01 -9.90862846e-01 -5.81391864e-02 1.18066542e-01 -9.91293669e-01 -5.81390932e-02 1.14590690e-01 -9.91701186e-01 -5.81393689e-02 1.11236021e-01 -9.92083669e-01 -5.81392273e-02 1.07777849e-01 -9.92465377e-01 -5.81392758e-02 1.04320772e-01 -9.92833793e-01 -5.81392162e-02 1.00758605e-01 -9.93199825e-01 -5.81390560e-02 9.72789451e-02 -9.93548632e-01 -5.81394024e-02 9.38142240e-02 -9.93883669e-01 -5.81389964e-02 9.03351009e-02 -9.94206309e-01 -5.81394210e-02 8.68809372e-02 -9.94512975e-01 -5.81390299e-02 8.32857937e-02 -9.94819105e-01 -5.81392124e-02 7.99131021e-02 -9.95097637e-01 -5.81394061e-02 7.65366405e-02 -9.95360792e-01 -5.81392422e-02 7.30745122e-02 -9.95622098e-01 -5.81391752e-02 6.95938841e-02 -9.95870292e-01 -5.81392124e-02 6.61270395e-02 -9.96107399e-01 -5.81391864e-02 6.26656935e-02 -9.96330678e-01 -5.81392311e-02 5.91773689e-02 -9.96544838e-01 -5.81392199e-02 5.57169653e-02 -9.96744394e-01 -5.81391715e-02 5.22211455e-02 -9.96932089e-01 -5.81391975e-02 4.87238914e-02 -9.97111619e-01 -5.81391640e-02 4.51622605e-02 -9.97277915e-01 -5.81390597e-02 4.16043177e-02 -9.97433364e-01 -5.81392534e-02 3.81739400e-02 -9.97570574e-01 -5.81393242e-02 3.47864032e-02 -9.97693717e-01 -5.81392460e-02 3.12130097e-02 -9.97810602e-01 -5.81391342e-02 2.77295280e-02 -9.97915983e-01 -5.81393875e-02 2.42522173e-02 -9.98008072e-01 -5.81390522e-02 2.07463987e-02 -9.98083413e-01 -5.81394024e-02 1.73848029e-02 -9.98153090e-01 -5.81392311e-02 1.38051221e-02 -9.98198330e-01 -5.81390671e-02 1.02971420e-02 -9.98247743e-01 -5.81394210e-02 6.92479732e-03 -9.98283029e-01 -5.81392162e-02 3.44277173e-03 -9.98299420e-01 -5.81392311e-02 -4.00724566e-05 -9.98300612e-01 -5.81391975e-02 -3.51806148e-03 -9.98299420e-01 -5.81391864e-02 -7.00414926e-03 -9.98282790e-01 -5.81392124e-02 -1.04957195e-02 -9.98245716e-01 -5.81392311e-02 -1.39688691e-02 -9.98197138e-01 -5.81392050e-02 -1.75365154e-02 -9.98151422e-01 -5.81390709e-02 -2.11307108e-02 -9.98073995e-01 -5.81391603e-02 -2.45317761e-02 -9.98000741e-01 -5.81393912e-02 -2.79210750e-02 -9.97910142e-01 -5.81391938e-02 -3.14079113e-02 -9.97807026e-01 -5.81391752e-02 -3.48799266e-02 -9.97692049e-01 -5.81391677e-02 -3.84542048e-02 -9.97558296e-01 -5.81390038e-02 -4.19489145e-02 -9.97420728e-01 -5.81393391e-02 -4.53255847e-02 -9.97270525e-01 -5.81392087e-02 -4.87899520e-02 -9.97107685e-01 -5.81392013e-02 -5.22505566e-02 -9.96929944e-01 -5.81391491e-02 -5.58454767e-02 -9.96736050e-01 -5.81389964e-02 -5.93282357e-02 -9.96536791e-01 -5.81394322e-02 -6.27869591e-02 -9.96322334e-01 -5.81390262e-02 -6.62823468e-02 -9.96097147e-01 -5.81394322e-02 -6.96605071e-02 -9.95864987e-01 -5.81391864e-02 -7.32425898e-02 -9.95609581e-01 -5.81390150e-02 -7.67327622e-02 -9.95346308e-01 -5.81394248e-02 -8.01713318e-02 -9.95074987e-01 -5.81390262e-02 -8.36619511e-02 -9.94789183e-01 -5.81394248e-02 -8.70307386e-02 -9.94499147e-01 -5.81392236e-02 -9.05094519e-02 -9.94188786e-01 -5.81392236e-02 -9.39619541e-02 -9.93868828e-01 -5.81392124e-02 -9.74597484e-02 -9.93531942e-01 -5.81392013e-02 -1.00920923e-01 -9.93186116e-01 -5.81392460e-02 -1.04377091e-01 -9.92828429e-01 -5.81392273e-02 -1.07926160e-01 -9.92448688e-01 -5.81390895e-02 -1.11397669e-01 -9.92066383e-01 -5.81393838e-02 -1.14778273e-01 -9.91678298e-01 -5.81392013e-02 -1.18238300e-01 -9.91271615e-01 -5.81392311e-02 -1.21691890e-01 -9.90856826e-01 -5.81392013e-02 -1.25244051e-01 -9.90412772e-01 -5.81390522e-02 -1.28706425e-01 -9.89968121e-01 -5.81393763e-02 -1.32066160e-01 -9.89526570e-01 -5.81391379e-02 -1.35533750e-01 -9.89057243e-01 -5.81391864e-02 -1.38978913e-01 -9.88579512e-01 -5.81391975e-02 -1.42511919e-01 -9.88073885e-01 -5.81390522e-02 -1.45975828e-01 -9.87569928e-01 -5.81394210e-02 -1.49379656e-01 -9.87058580e-01 -5.81391305e-02 -1.52836546e-01 -9.86532450e-01 -5.81394061e-02 -1.56191871e-01 -9.86005127e-01 -5.81392311e-02 -1.59720838e-01 -9.85440493e-01 -5.81391118e-02 -1.63175955e-01 -9.84874666e-01 -5.81393875e-02 -1.66579425e-01 -9.84303474e-01 -5.81390783e-02 -1.70030370e-01 -9.83712971e-01 -5.81393912e-02 -1.73386201e-01 -9.83131468e-01 -5.81392683e-02 -1.76812470e-01 -9.82520819e-01 -5.81392609e-02 -1.80243403e-01 -9.81891155e-01 -5.81392385e-02 -1.83660597e-01 -9.81262386e-01 -5.81392497e-02 -1.87083945e-01 -9.80613232e-01 -5.81391975e-02 -1.90504864e-01 -9.79953289e-01 -5.81392236e-02 -1.93920866e-01 -9.79284286e-01 -5.81392050e-02 -1.97427958e-01 -9.78582203e-01 -5.81390895e-02 -2.00833604e-01 -9.77890134e-01 -5.81394322e-02 -2.04151943e-01 -9.77203012e-01 -5.81392422e-02 -2.07565963e-01 -9.76485074e-01 -5.81392236e-02 -2.11043611e-01 -9.75737929e-01 -5.81390709e-02 -2.14491114e-01 -9.74985123e-01 -5.81393689e-02 -2.17786983e-01 -9.74255562e-01 -5.81392087e-02 -2.21183464e-01 -9.73489404e-01 -5.81392087e-02 -2.24587485e-01 -9.72707868e-01 -5.81391789e-02 -2.28086576e-01 -9.71897542e-01 -5.81390448e-02 -2.31481120e-01 -9.71095502e-01 -5.81394024e-02 -2.34750137e-01 -9.70309794e-01 -5.81391752e-02 -2.38158122e-01 -9.69478309e-01 -5.81392422e-02 -2.41517678e-01 -9.68643486e-01 -5.81392348e-02 -2.44890019e-01 -9.67796445e-01 -5.81392087e-02 -2.48272702e-01 -9.66935098e-01 -5.81392124e-02 -2.51741350e-01 -9.66037512e-01 -5.81390336e-02 -2.55140930e-01 -9.65147674e-01 -5.81393503e-02 -2.58486688e-01 -9.64254797e-01 -5.81390858e-02 -2.61956781e-01 -9.63319898e-01 -5.81392013e-02 -2.65221506e-01 -9.62424338e-01 -5.81394136e-02 -2.68475741e-01 -9.61522520e-01 -5.81391789e-02 -2.71846831e-01 -9.60575104e-01 -5.81391789e-02 -2.75203913e-01 -9.59617257e-01 -5.81391677e-02 -2.78554648e-01 -9.58650291e-01 -5.81391938e-02 -2.81893969e-01 -9.57673550e-01 -5.81392050e-02 -2.85232484e-01 -9.56686616e-01 -5.81392162e-02 -2.88585603e-01 -9.55677927e-01 -5.81392162e-02 -2.91898400e-01 -9.54672515e-01 -5.81392124e-02 -2.95319885e-01 -9.53620195e-01 -5.81390224e-02 -2.98762232e-01 -9.52546418e-01 -5.81391454e-02 -3.02080721e-01 -9.51498806e-01 -5.81392050e-02 -3.05326074e-01 -9.50464785e-01 -5.81394471e-02 -3.08538496e-01 -9.49424565e-01 -5.81392199e-02 -3.11933041e-01 -9.48314130e-01 -5.81390485e-02 -3.15247774e-01 -9.47218895e-01 -5.81394210e-02 -3.18547785e-01 -9.46113229e-01 -5.81391081e-02 -3.21851104e-01 -9.44995582e-01 -5.81393838e-02 -3.25040042e-01 -9.43903089e-01 -5.81391938e-02 -3.28338057e-01 -9.42760050e-01 -5.81392571e-02 -3.31605375e-01 -9.41617548e-01 -5.81392609e-02 -3.34989369e-01 -9.40417349e-01 -5.81390150e-02 -3.38297695e-01 -9.39232290e-01 -5.81393838e-02 -3.41548622e-01 -9.38056290e-01 -5.81390075e-02 -3.44833970e-01 -9.36846793e-01 -5.81394434e-02 -3.48010421e-01 -9.35668290e-01 -5.81392162e-02 -3.51269096e-01 -9.34450567e-01 -5.81392273e-02 -3.54534388e-01 -9.33221579e-01 -5.81392758e-02 -3.57882500e-01 -9.31949914e-01 -5.81390634e-02 -3.61203909e-01 -9.30660486e-01 -5.81391491e-02 -3.64399254e-01 -9.29419160e-01 -5.81393763e-02 -3.67540628e-01 -9.28180695e-01 -5.81392236e-02 -3.70768547e-01 -9.26894486e-01 -5.81392236e-02 -3.73998642e-01 -9.25595880e-01 -5.81392124e-02 -3.77302974e-01 -9.24253881e-01 -5.81390709e-02 -3.80539387e-01 -9.22924280e-01 -5.81393726e-02 -3.83680701e-01 -9.21624005e-01 -5.81392050e-02 -3.86893660e-01 -9.20278966e-01 -5.81392087e-02 -3.90093535e-01 -9.18927908e-01 -5.81392050e-02 -3.93376082e-01 -9.17525291e-01 -5.81390299e-02 -3.96594286e-01 -9.16141987e-01 -5.81393950e-02 -3.99778426e-01 -9.14757729e-01 -5.81390895e-02 -4.02979642e-01 -9.13352191e-01 -5.81394322e-02 -4.06050563e-01 -9.11990523e-01 -5.81392236e-02 -4.09238636e-01 -9.10565197e-01 -5.81392795e-02 -4.12410796e-01 -9.09131408e-01 -5.81392311e-02 -4.15585488e-01 -9.07681942e-01 -5.81392199e-02 -4.18770701e-01 -9.06217813e-01 -5.81392311e-02 -4.21925336e-01 -9.04753804e-01 -5.81391379e-02 -4.25094068e-01 -9.03269947e-01 -5.81392273e-02 -4.28323388e-01 -9.01742697e-01 -5.81390411e-02 -4.31464314e-01 -9.00243878e-01 -5.81394061e-02 -4.34512913e-01 -8.98780584e-01 -5.81391342e-02 -4.37730491e-01 -8.97217274e-01 -5.81390075e-02 -4.40939575e-01 -8.95642698e-01 -5.81391603e-02 -4.43997800e-01 -8.94131839e-01 -5.81393205e-02 -4.47034240e-01 -8.92615736e-01 -5.81391566e-02 -4.50144917e-01 -8.91053140e-01 -5.81392050e-02 -4.53264147e-01 -8.89469862e-01 -5.81391789e-02 -4.56442475e-01 -8.87841344e-01 -5.81390858e-02 -4.59523499e-01 -8.86251092e-01 -5.81393912e-02 -4.62515742e-01 -8.84695709e-01 -5.81392087e-02 -4.65603590e-01 -8.83072615e-01 -5.81391640e-02 -4.68687236e-01 -8.81439745e-01 -5.81391975e-02 -4.71852481e-01 -8.79750609e-01 -5.81390522e-02 -4.74916071e-01 -8.78098130e-01 -5.81394359e-02 -4.77983922e-01 -8.76434147e-01 -5.81389964e-02 -4.81055081e-01 -8.74752641e-01 -5.81393503e-02 -4.84089613e-01 -8.73072743e-01 -5.81390858e-02 -4.87211466e-01 -8.71335685e-01 -5.81391379e-02 -4.90182310e-01 -8.69671285e-01 -5.81393652e-02 -4.93129492e-01 -8.68000627e-01 -5.81391528e-02 -4.96160299e-01 -8.66274357e-01 -5.81392422e-02 -4.99175131e-01 -8.64539444e-01 -5.81392199e-02 -5.02170980e-01 -8.62802386e-01 -5.81391826e-02 -5.05179822e-01 -8.61045361e-01 -5.81391789e-02 -5.08201182e-01 -8.59264016e-01 -5.81391938e-02 -5.11194468e-01 -8.57487440e-01 -5.81392273e-02 -5.14182210e-01 -8.55700433e-01 -5.81392050e-02 -5.17168343e-01 -8.53896618e-01 -5.81391938e-02 -5.20137072e-01 -8.52093339e-01 -5.81392013e-02 -5.23186326e-01 -8.50222349e-01 -5.81391230e-02 -5.26153743e-01 -8.48391712e-01 -5.81394061e-02 -5.29033720e-01 -8.46597672e-01 -5.81392311e-02 -5.32039642e-01 -8.44709456e-01 -5.81390150e-02 -5.35005808e-01 -8.42836857e-01 -5.81393912e-02 -5.37929654e-01 -8.40970814e-01 -5.81390709e-02 -5.40883124e-01 -8.39077532e-01 -5.81393801e-02 -5.43726921e-01 -8.37236106e-01 -5.81391491e-02 -5.46651721e-01 -8.35327804e-01 -5.81392311e-02 -5.49550951e-01 -8.33425760e-01 -5.81392124e-02 -5.52445829e-01 -8.31507206e-01 -5.81391528e-02 -5.55357397e-01 -8.29566121e-01 -5.81392385e-02 -5.58333218e-01 -8.27568114e-01 -5.81390522e-02 -5.61217725e-01 -8.25613379e-01 -5.81393838e-02 -5.64017832e-01 -8.23705375e-01 -5.81392348e-02 -5.66880167e-01 -8.21737170e-01 -5.81392311e-02 -5.69742501e-01 -8.19755137e-01 -5.81392236e-02 -5.72691202e-01 -8.17695260e-01 -5.81390187e-02 -5.75620711e-01 -8.15640032e-01 -5.81391975e-02 -5.78397095e-01 -8.13671112e-01 -5.81394322e-02 -5.81139982e-01 -8.11715245e-01 -5.81392199e-02 -5.83986223e-01 -8.09666097e-01 -5.81392311e-02 -5.86814463e-01 -8.07622790e-01 -5.81392422e-02 -5.89698315e-01 -8.05516958e-01 -5.81390597e-02 -5.92491150e-01 -8.03466499e-01 -5.81394210e-02 -5.95210910e-01 -8.01452279e-01 -5.81391864e-02 -5.98012447e-01 -7.99363375e-01 -5.81391789e-02 -6.00805342e-01 -7.97267914e-01 -5.81391864e-02 -6.03654623e-01 -7.95114338e-01 -5.81390150e-02 -6.06469452e-01 -7.92968690e-01 -5.81392311e-02 -6.09233797e-01 -7.90844917e-01 -5.81391267e-02 -6.11968279e-01 -7.88732588e-01 -5.81393987e-02 -6.14634216e-01 -7.86656201e-01 -5.81392087e-02 -6.17355406e-01 -7.84521282e-01 -5.81392087e-02 -6.20105922e-01 -7.82348812e-01 -5.81391975e-02 -6.22814238e-01 -7.80195832e-01 -5.81391938e-02 -6.25541985e-01 -7.78011084e-01 -5.81391752e-02 -6.28255546e-01 -7.75823653e-01 -5.81392236e-02 -6.30958498e-01 -7.73622334e-01 -5.81391975e-02 -6.33659184e-01 -7.71414101e-01 -5.81392348e-02 -6.36342287e-01 -7.69201279e-01 -5.81391752e-02 -6.39039159e-01 -7.66964555e-01 -5.81391826e-02 -6.41776383e-01 -7.64673710e-01 -5.81390932e-02 -6.44527793e-01 -7.62356579e-01 -5.81391938e-02 -6.47110701e-01 -7.60163784e-01 -5.81393279e-02 -6.49668574e-01 -7.57979989e-01 -5.81392348e-02 -6.52334273e-01 -7.55688250e-01 -5.81391528e-02 -6.54972076e-01 -7.53404200e-01 -5.81391677e-02 -6.57664418e-01 -7.51051426e-01 -5.81389926e-02 -6.60292745e-01 -7.48745501e-01 -5.81394061e-02 -6.62828982e-01 -7.46500075e-01 -5.81391491e-02 -6.65436387e-01 -7.44176805e-01 -5.81392087e-02 -6.68017983e-01 -7.41859674e-01 -5.81391826e-02 -6.70676708e-01 -7.39458203e-01 -5.81390560e-02 -6.73256636e-01 -7.37108469e-01 -5.81393391e-02 -6.75827384e-01 -7.34754443e-01 -5.81390113e-02 -6.78397536e-01 -7.32380271e-01 -5.81393540e-02 -6.80943787e-01 -7.30011582e-01 -5.81390373e-02 -6.83540940e-01 -7.27580190e-01 -5.81391305e-02 -6.86018348e-01 -7.25246072e-01 -5.81393316e-02 -6.88477457e-01 -7.22915888e-01 -5.81391454e-02 -6.91004753e-01 -7.20490813e-01 -5.81391640e-02 -6.93505108e-01 -7.18098819e-01 -5.81391640e-02 -6.96015120e-01 -7.15663433e-01 -5.81391566e-02 -6.98500156e-01 -7.13236630e-01 -5.81391938e-02 -7.00974226e-01 -7.10807562e-01 -5.81391752e-02 -7.03465164e-01 -7.08344221e-01 -5.81391528e-02 -7.05988109e-01 -7.05808222e-01 -5.81390113e-02 -7.08470404e-01 -7.03339159e-01 -5.81393950e-02 -7.10842848e-01 -7.00937808e-01 -5.81391826e-02 -7.13280201e-01 -6.98455155e-01 -5.81391752e-02 -7.15707779e-01 -6.95970118e-01 -5.81391379e-02 -7.18129635e-01 -6.93473577e-01 -5.81391826e-02 -7.20606685e-01 -6.90882683e-01 -5.81389777e-02 -7.23041773e-01 -6.88345373e-01 -5.81393577e-02 -7.25408852e-01 -6.85844362e-01 -5.81390187e-02 -7.27816761e-01 -6.83289766e-01 -5.81393056e-02 -7.30119705e-01 -6.80826366e-01 -5.81391864e-02 -7.32550800e-01 -6.78213835e-01 -5.81390709e-02 -7.34921455e-01 -6.75646245e-01 -5.81393205e-02 -7.37208784e-01 -6.73145533e-01 -5.81391826e-02 -7.39577472e-01 -6.70545995e-01 -5.81392311e-02 -7.41907775e-01 -6.67964876e-01 -5.81391864e-02 -7.44285643e-01 -6.65312707e-01 -5.81390932e-02 -7.46609449e-01 -6.62706733e-01 -5.81393763e-02 -7.48860598e-01 -6.60158813e-01 -5.81391975e-02 -7.51153171e-01 -6.57549798e-01 -5.81391938e-02 -7.53501058e-01 -6.54857278e-01 -5.81390262e-02 -7.55829871e-01 -6.52169228e-01 -5.81392460e-02 -7.58061051e-01 -6.49576247e-01 -5.81393801e-02 -7.60253251e-01 -6.47005439e-01 -5.81391528e-02 -7.62503088e-01 -6.44356728e-01 -5.81392385e-02 -7.64734745e-01 -6.41704440e-01 -5.81392236e-02 -7.67039239e-01 -6.38948143e-01 -5.81389889e-02 -7.69284010e-01 -6.36243224e-01 -5.81394508e-02 -7.71414161e-01 -6.33661926e-01 -5.81391677e-02 -7.73625135e-01 -6.30956113e-01 -5.81391864e-02 -7.75824368e-01 -6.28251791e-01 -5.81391267e-02 -7.78089881e-01 -6.25444114e-01 -5.81390075e-02 -7.80279458e-01 -6.22712076e-01 -5.81394248e-02 -7.82423615e-01 -6.20010316e-01 -5.81390113e-02 -7.84598529e-01 -6.17260218e-01 -5.81394061e-02 -7.86667526e-01 -6.14620209e-01 -5.81392199e-02 -7.88882315e-01 -6.11772537e-01 -5.81389405e-02 -7.91036546e-01 -6.08987451e-01 -5.81393987e-02 -7.93129325e-01 -6.06258512e-01 -5.81390187e-02 -7.95250773e-01 -6.03474796e-01 -5.81394359e-02 -7.97295272e-01 -6.00771725e-01 -5.81391789e-02 -7.99453020e-01 -5.97890615e-01 -5.81390150e-02 -8.01545739e-01 -5.95087349e-01 -5.81393503e-02 -8.03556919e-01 -5.92367768e-01 -5.81391528e-02 -8.05614412e-01 -5.89566052e-01 -5.81392013e-02 -8.07719350e-01 -5.86678684e-01 -5.81389777e-02 -8.09823513e-01 -5.83767891e-01 -5.81391566e-02 -8.11804235e-01 -5.81018209e-01 -5.81393391e-02 -8.13759089e-01 -5.78269899e-01 -5.81391864e-02 -8.15769911e-01 -5.75435519e-01 -5.81391752e-02 -8.17778885e-01 -5.72573662e-01 -5.81391789e-02 -8.19821537e-01 -5.69642603e-01 -5.81389666e-02 -8.21817935e-01 -5.66766083e-01 -5.81393279e-02 -8.23739529e-01 -5.63964725e-01 -5.81391416e-02 -8.25699866e-01 -5.61088979e-01 -5.81391789e-02 -8.27650309e-01 -5.58210611e-01 -5.81391789e-02 -8.29648435e-01 -5.55235207e-01 -5.81390075e-02 -8.31587315e-01 -5.52326322e-01 -5.81393465e-02 -8.33494782e-01 -5.49443603e-01 -5.81390969e-02 -8.35410953e-01 -5.46527207e-01 -5.81393093e-02 -8.37260246e-01 -5.43691456e-01 -5.81391826e-02 -8.39169085e-01 -5.40737987e-01 -5.81391826e-02 -8.41046631e-01 -5.37813962e-01 -5.81391864e-02 -8.42961192e-01 -5.34807444e-01 -5.81390448e-02 -8.44823301e-01 -5.31864822e-01 -5.81393987e-02 -8.46620262e-01 -5.28995275e-01 -5.81391901e-02 -8.48511219e-01 -5.25961518e-01 -5.81390075e-02 -8.50351036e-01 -5.22978008e-01 -5.81393838e-02 -8.52109075e-01 -5.20113587e-01 -5.81392348e-02 -8.53910446e-01 -5.17144382e-01 -5.81392683e-02 -8.55761647e-01 -5.14077783e-01 -5.81389964e-02 -8.57565105e-01 -5.11063337e-01 -5.81394434e-02 -8.59289348e-01 -5.08157969e-01 -5.81391975e-02 -8.61117721e-01 -5.05053818e-01 -5.81390671e-02 -8.62883568e-01 -5.02033234e-01 -5.81395067e-02 -8.64559472e-01 -4.99141067e-01 -5.81392273e-02 -8.66292655e-01 -4.96124327e-01 -5.81392124e-02 -8.68028283e-01 -4.93080556e-01 -5.81392087e-02 -8.69745970e-01 -4.90050405e-01 -5.81392087e-02 -8.71444643e-01 -4.87018168e-01 -5.81391975e-02 -8.73146117e-01 -4.83958334e-01 -5.81392050e-02 -8.74867737e-01 -4.80845898e-01 -5.81389666e-02 -8.76565218e-01 -4.77746665e-01 -5.81394061e-02 -8.78175080e-01 -4.74775076e-01 -5.81392050e-02 -8.79827559e-01 -4.71705437e-01 -5.81391864e-02 -8.81510675e-01 -4.68551069e-01 -5.81390373e-02 -8.83187950e-01 -4.65383589e-01 -5.81391864e-02 -8.84776592e-01 -4.62358385e-01 -5.81393503e-02 -8.86336505e-01 -4.59359884e-01 -5.81392050e-02 -8.87929916e-01 -4.56272930e-01 -5.81391640e-02 -8.89539063e-01 -4.53124613e-01 -5.81390522e-02 -8.91122401e-01 -4.50006455e-01 -5.81393763e-02 -8.92638505e-01 -4.46987718e-01 -5.81391640e-02 -8.94201815e-01 -4.43854302e-01 -5.81392087e-02 -8.95738602e-01 -4.40744996e-01 -5.81391416e-02 -8.97277653e-01 -4.37605053e-01 -5.81391715e-02 -8.98838401e-01 -4.34389681e-01 -5.81390671e-02 -9.00354624e-01 -4.31236535e-01 -5.81393428e-02 -9.01813388e-01 -4.28177565e-01 -5.81391677e-02 -9.03302670e-01 -4.25023615e-01 -5.81391938e-02 -9.04777229e-01 -4.21877742e-01 -5.81391938e-02 -9.06267822e-01 -4.18668747e-01 -5.81390709e-02 -9.07727301e-01 -4.15490031e-01 -5.81393205e-02 -9.09137249e-01 -4.12399024e-01 -5.81392087e-02 -9.10561919e-01 -4.09244508e-01 -5.81392236e-02 -9.11994219e-01 -4.06042129e-01 -5.81391416e-02 -9.13443863e-01 -4.02769387e-01 -5.81390113e-02 -9.14846718e-01 -3.99581045e-01 -5.81394322e-02 -9.16231990e-01 -3.96385133e-01 -5.81390336e-02 -9.17608500e-01 -3.93182337e-01 -5.81394359e-02 -9.18938994e-01 -3.90068650e-01 -5.81392050e-02 -9.20334637e-01 -3.86763096e-01 -5.81390113e-02 -9.21692848e-01 -3.83519202e-01 -5.81393614e-02 -9.22980785e-01 -3.80406857e-01 -5.81392422e-02 -9.24306810e-01 -3.77175927e-01 -5.81392571e-02 -9.25608039e-01 -3.73965204e-01 -5.81391156e-02 -9.26946998e-01 -3.70635986e-01 -5.81390262e-02 -9.28245246e-01 -3.67379278e-01 -5.81394322e-02 -9.29495513e-01 -3.64200324e-01 -5.81390858e-02 -9.30753708e-01 -3.60960186e-01 -5.81392609e-02 -9.32033718e-01 -3.57659221e-01 -5.81389554e-02 -9.33314085e-01 -3.54287654e-01 -5.81392534e-02 -9.34500337e-01 -3.51136297e-01 -5.81394359e-02 -9.35690105e-01 -3.47951591e-01 -5.81392050e-02 -9.36930895e-01 -3.44607919e-01 -5.81390373e-02 -9.38142478e-01 -3.41318101e-01 -5.81394061e-02 -9.39320505e-01 -3.38049114e-01 -5.81390597e-02 -9.40507591e-01 -3.34746242e-01 -5.81394434e-02 -9.41661298e-01 -3.31476808e-01 -5.81390820e-02 -9.42819476e-01 -3.28170300e-01 -5.81394173e-02 -9.43926752e-01 -3.24973196e-01 -5.81392050e-02 -9.45045114e-01 -3.21700096e-01 -5.81391789e-02 -9.46174443e-01 -3.18369746e-01 -5.81392050e-02 -9.47306454e-01 -3.14978868e-01 -5.81390224e-02 -9.48402107e-01 -3.11667860e-01 -5.81393801e-02 -9.49457169e-01 -3.08438420e-01 -5.81391901e-02 -9.50549006e-01 -3.05057138e-01 -5.81390038e-02 -9.51619804e-01 -3.01701337e-01 -5.81394210e-02 -9.52636600e-01 -2.98478067e-01 -5.81392497e-02 -9.53665912e-01 -2.95168161e-01 -5.81392385e-02 -9.54716504e-01 -2.91753322e-01 -5.81390299e-02 -9.55733955e-01 -2.88400590e-01 -5.81394546e-02 -9.56706524e-01 -2.85156965e-01 -5.81392385e-02 -9.57725167e-01 -2.81717479e-01 -5.81390634e-02 -9.58705604e-01 -2.78368831e-01 -5.81394061e-02 -9.59667027e-01 -2.75031686e-01 -5.81390671e-02 -9.60627019e-01 -2.71664560e-01 -5.81394061e-02 -9.61545587e-01 -2.68394500e-01 -5.81392124e-02 -9.62471008e-01 -2.65050560e-01 -5.81392422e-02 -9.63392556e-01 -2.61691630e-01 -5.81392050e-02 -9.64294076e-01 -2.58339167e-01 -5.81392273e-02 -9.65214670e-01 -2.54880756e-01 -5.81390671e-02 -9.66097176e-01 -2.51521051e-01 -5.81394285e-02 -9.66947973e-01 -2.48223513e-01 -5.81391938e-02 -9.67807472e-01 -2.44841725e-01 -5.81392124e-02 -9.68672872e-01 -2.41394907e-01 -5.81390522e-02 -9.69533682e-01 -2.37931147e-01 -5.81392460e-02 -9.70345438e-01 -2.34607667e-01 -5.81393950e-02 -9.71135855e-01 -2.31306866e-01 -5.81392609e-02 -9.71936524e-01 -2.27915466e-01 -5.81392162e-02 -9.72737432e-01 -2.24460542e-01 -5.81391007e-02 -9.73541498e-01 -2.20954522e-01 -5.81392683e-02 -9.74291682e-01 -2.17628971e-01 -5.81393950e-02 -9.75022614e-01 -2.14321032e-01 -5.81392422e-02 -9.75765824e-01 -2.10912213e-01 -5.81392460e-02 -9.76494133e-01 -2.07515910e-01 -5.81392609e-02 -9.77211356e-01 -2.04115719e-01 -5.81392534e-02 -9.77915227e-01 -2.00718656e-01 -5.81392497e-02 -9.78608370e-01 -1.97309971e-01 -5.81392422e-02 -9.79288816e-01 -1.93899155e-01 -5.81392199e-02 -9.79960263e-01 -1.90477848e-01 -5.81392013e-02 -9.80636835e-01 -1.86957717e-01 -5.81390224e-02 -9.81287301e-01 -1.83519468e-01 -5.81394210e-02 -9.81903672e-01 -1.80182874e-01 -5.81392199e-02 -9.82527196e-01 -1.76784441e-01 -5.81392683e-02 -9.83146608e-01 -1.73306718e-01 -5.81392795e-02 -9.83752370e-01 -1.69799104e-01 -5.81390411e-02 -9.84345675e-01 -1.66343465e-01 -5.81394695e-02 -9.84900415e-01 -1.63016140e-01 -5.81392609e-02 -9.85460103e-01 -1.59595698e-01 -5.81391864e-02 -9.86016810e-01 -1.56131059e-01 -5.81392609e-02 -9.86570358e-01 -1.52581498e-01 -5.81390671e-02 -9.87098873e-01 -1.49129421e-01 -5.81394546e-02 -9.87609804e-01 -1.45701692e-01 -5.81390522e-02 -9.88113463e-01 -1.42244503e-01 -5.81394359e-02 -9.88588631e-01 -1.38907209e-01 -5.81392758e-02 -9.89082932e-01 -1.35345623e-01 -5.81390671e-02 -9.89553154e-01 -1.31867707e-01 -5.81394061e-02 -9.89992261e-01 -1.28527939e-01 -5.81392571e-02 -9.90436077e-01 -1.25073239e-01 -5.81392124e-02 -9.90863144e-01 -1.21624865e-01 -5.81392087e-02 -9.91289794e-01 -1.18082814e-01 -5.81390709e-02 -9.91698861e-01 -1.14606619e-01 -5.81393801e-02 -9.92084980e-01 -1.11225620e-01 -5.81391677e-02 -9.92473543e-01 -1.07692935e-01 -5.81390895e-02 -9.92844939e-01 -1.04232386e-01 -5.81394471e-02 -9.93198872e-01 -1.00772150e-01 -5.81389889e-02 -9.93549228e-01 -9.72814858e-02 -5.81394657e-02 -9.93880689e-01 -9.38372612e-02 -5.81391901e-02 -9.94202137e-01 -9.03842822e-02 -5.81395738e-02 -9.94505227e-01 -8.69928077e-02 -5.81395626e-02 -9.94802237e-01 -8.35351571e-02 -5.81395291e-02 -9.95090246e-01 -8.00722465e-02 -5.81394881e-02 -9.95368242e-01 -7.65124708e-02 -5.81394807e-02 -9.95635092e-01 -7.30156004e-02 -5.81394136e-02 -9.95878339e-01 -6.96211308e-02 -5.81394024e-02 -9.96117711e-01 -6.61242604e-02 -5.81393726e-02 -9.96336460e-01 -6.27569109e-02 -5.81391305e-02 -9.96536613e-01 -5.94242886e-02 -5.81389144e-02 -9.96704042e-01 -5.65770604e-02 -5.81390485e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98288810e-01 -6.27228804e-03 -5.81390224e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.97242630e-01 5.26121706e-02 -5.23359589e-02 0. 0. 0. -9.96864617e-01 5.93410544e-02 -5.23359627e-02 -9.96587455e-01 6.38229176e-02 -5.23359738e-02 -9.96421993e-01 6.63781241e-02 -5.23357764e-02 -9.96190310e-01 6.98569939e-02 -5.23362905e-02 -9.95936751e-01 7.34322742e-02 -5.23363762e-02 -9.95675385e-01 7.68763795e-02 -5.23364954e-02 -9.95406389e-01 8.03392380e-02 -5.23365773e-02 -9.95119035e-01 8.38035420e-02 -5.23365922e-02 -9.94829178e-01 8.71765614e-02 -5.23365401e-02 -9.94522214e-01 9.06310081e-02 -5.23366854e-02 -9.94187891e-01 9.42194685e-02 -5.23366369e-02 -9.93863881e-01 9.75782499e-02 -5.23365811e-02 -9.93520439e-01 1.01028882e-01 -5.23367040e-02 -9.93146479e-01 1.04627438e-01 -5.23366034e-02 -9.92780924e-01 1.08048461e-01 -5.23366630e-02 -9.92397606e-01 1.11531489e-01 -5.23366556e-02 -9.92005587e-01 1.14941478e-01 -5.23366444e-02 -9.91606593e-01 1.18327454e-01 -5.23366295e-02 -9.91194963e-01 1.21748902e-01 -5.23366779e-02 -9.90758061e-01 1.25262931e-01 -5.23367040e-02 -9.90298390e-01 1.28829360e-01 -5.23366854e-02 -9.89854515e-01 1.32195801e-01 -5.23366407e-02 -9.89391685e-01 1.35634631e-01 -5.23367263e-02 -9.88898516e-01 1.39174730e-01 -5.23366816e-02 -9.88420844e-01 1.42521724e-01 -5.23366146e-02 -9.87914205e-01 1.45993933e-01 -5.23367114e-02 -9.87399757e-01 1.49430990e-01 -5.23366444e-02 -9.86887872e-01 1.52777612e-01 -5.23366779e-02 -9.86334383e-01 1.56314388e-01 -5.23367114e-02 -9.85764027e-01 1.59869716e-01 -5.23366854e-02 -9.85197246e-01 1.63328901e-01 -5.23366854e-02 -9.84622717e-01 1.66762188e-01 -5.23366854e-02 -9.84036386e-01 1.70174435e-01 -5.23366705e-02 -9.83438015e-01 1.73629552e-01 -5.23366928e-02 -9.82822061e-01 1.77075744e-01 -5.23366705e-02 -9.82189000e-01 1.80529222e-01 -5.23366928e-02 -9.81575608e-01 1.83840811e-01 -5.23365848e-02 -9.80954647e-01 1.87127814e-01 -5.23366854e-02 -9.80276287e-01 1.90644324e-01 -5.23367375e-02 -9.79581952e-01 1.94182277e-01 -5.23366556e-02 -9.78898942e-01 1.97601497e-01 -5.23366779e-02 -9.78201807e-01 2.01027200e-01 -5.23366854e-02 -9.77496266e-01 2.04420999e-01 -5.23366630e-02 -9.76791680e-01 2.07769066e-01 -5.23365997e-02 -9.76067543e-01 2.11152211e-01 -5.23367226e-02 -9.75297034e-01 2.14665920e-01 -5.23366705e-02 -9.74559009e-01 2.18000352e-01 -5.23366146e-02 -9.73795950e-01 2.21381456e-01 -5.23367040e-02 -9.72993195e-01 2.24889219e-01 -5.23366854e-02 -9.72201824e-01 2.28288636e-01 -5.23366854e-02 -9.71401334e-01 2.31676370e-01 -5.23366928e-02 -9.70610082e-01 2.34966427e-01 -5.23366071e-02 -9.69811022e-01 2.38236830e-01 -5.23366891e-02 -9.68941748e-01 2.41742805e-01 -5.23367338e-02 -9.68062818e-01 2.45238855e-01 -5.23366965e-02 -9.67198431e-01 2.48632848e-01 -5.23366965e-02 -9.66351271e-01 2.51901209e-01 -5.23366220e-02 -9.65481341e-01 2.55224943e-01 -5.23367114e-02 -9.64569867e-01 2.58642405e-01 -5.23366369e-02 -9.63658094e-01 2.62021989e-01 -5.23367077e-02 -9.62714791e-01 2.65457422e-01 -5.23366816e-02 -9.61805046e-01 2.68743694e-01 -5.23366369e-02 -9.60888863e-01 2.71999180e-01 -5.23366928e-02 -9.59915757e-01 2.75412440e-01 -5.23367263e-02 -9.58912432e-01 2.78884143e-01 -5.23366928e-02 -9.57941830e-01 2.82198220e-01 -5.23366816e-02 -9.56961930e-01 2.85508871e-01 -5.23366854e-02 -9.55960393e-01 2.88838357e-01 -5.23367114e-02 -9.54955339e-01 2.92144120e-01 -5.23366183e-02 -9.53932941e-01 2.95472592e-01 -5.23367263e-02 -9.52865779e-01 2.98890680e-01 -5.23366444e-02 -9.51844215e-01 3.02125543e-01 -5.23366220e-02 -9.50784087e-01 3.05451989e-01 -5.23367226e-02 -9.49684799e-01 3.08847070e-01 -5.23366854e-02 -9.48603928e-01 3.12152058e-01 -5.23366854e-02 -9.47505295e-01 3.15470248e-01 -5.23366742e-02 -9.46399868e-01 3.18779916e-01 -5.23366705e-02 -9.45305765e-01 3.21999848e-01 -5.23366146e-02 -9.44212615e-01 3.25200140e-01 -5.23366854e-02 -9.43046391e-01 3.28560561e-01 -5.23367189e-02 -9.41861570e-01 3.31942141e-01 -5.23366854e-02 -9.40725267e-01 3.35154951e-01 -5.23366183e-02 -9.39546883e-01 3.38440686e-01 -5.23367301e-02 -9.38327253e-01 3.41807783e-01 -5.23366854e-02 -9.37127411e-01 3.45064133e-01 -5.23366705e-02 -9.35917914e-01 3.48321229e-01 -5.23366854e-02 -9.34717953e-01 3.51527482e-01 -5.23365997e-02 -9.33528841e-01 3.54688525e-01 -5.23366630e-02 -9.32270467e-01 3.58009666e-01 -5.23366965e-02 -9.30966556e-01 3.61365616e-01 -5.23366928e-02 -9.29699302e-01 3.64622116e-01 -5.23366891e-02 -9.28420365e-01 3.67867887e-01 -5.23366965e-02 -9.27130878e-01 3.71102512e-01 -5.23366965e-02 -9.25826073e-01 3.74344409e-01 -5.23366854e-02 -9.24524605e-01 3.77551317e-01 -5.23366854e-02 -9.23193693e-01 3.80786955e-01 -5.23366779e-02 -9.21893358e-01 3.83925527e-01 -5.23366183e-02 -9.20585513e-01 3.87054294e-01 -5.23366705e-02 -9.19198632e-01 3.90334427e-01 -5.23367114e-02 -9.17791486e-01 3.93628836e-01 -5.23366854e-02 -9.16432202e-01 3.96784365e-01 -5.23366518e-02 -9.15061951e-01 3.99943501e-01 -5.23367152e-02 -9.13656354e-01 4.03137892e-01 -5.23366481e-02 -9.12264168e-01 4.06279951e-01 -5.23366965e-02 -9.10808623e-01 4.09534454e-01 -5.23367152e-02 -9.09347832e-01 4.12766129e-01 -5.23366965e-02 -9.07934964e-01 4.15858239e-01 -5.23366444e-02 -9.06489909e-01 4.19005305e-01 -5.23367412e-02 -9.04979646e-01 4.22254115e-01 -5.23366928e-02 -9.03511107e-01 4.25387740e-01 -5.23366854e-02 -9.02027071e-01 4.28528696e-01 -5.23366928e-02 -9.00532067e-01 4.31657374e-01 -5.23366854e-02 -8.99066746e-01 4.34710652e-01 -5.23366556e-02 -8.97522151e-01 4.37890917e-01 -5.23367412e-02 -8.95940661e-01 4.41111207e-01 -5.23366854e-02 -8.94404650e-01 4.44219023e-01 -5.23366891e-02 -8.92847657e-01 4.47337419e-01 -5.23366965e-02 -8.91277909e-01 4.50460017e-01 -5.23366854e-02 -8.89741898e-01 4.53485638e-01 -5.23366258e-02 -8.88204396e-01 4.56490308e-01 -5.23366928e-02 -8.86564612e-01 4.59666878e-01 -5.23367114e-02 -8.84920537e-01 4.62824911e-01 -5.23366854e-02 -8.83337677e-01 4.65838879e-01 -5.23366407e-02 -8.81705821e-01 4.68918920e-01 -5.23366965e-02 -8.80022287e-01 4.72070932e-01 -5.23366854e-02 -8.78371894e-01 4.75132853e-01 -5.23366854e-02 -8.76704931e-01 4.78206992e-01 -5.23366854e-02 -8.75025749e-01 4.81269926e-01 -5.23366854e-02 -8.73385429e-01 4.84232157e-01 -5.23366183e-02 -8.71697426e-01 4.87271309e-01 -5.23367003e-02 -8.69959414e-01 4.90369469e-01 -5.23366854e-02 -8.68227720e-01 4.93425488e-01 -5.23366854e-02 -8.66494238e-01 4.96466428e-01 -5.23366630e-02 -8.64777565e-01 4.99450862e-01 -5.23366556e-02 -8.63031864e-01 5.02460003e-01 -5.23366630e-02 -8.61277699e-01 5.05462348e-01 -5.23366854e-02 -8.59497488e-01 5.08482635e-01 -5.23366854e-02 -8.57760608e-01 5.11406958e-01 -5.23366295e-02 -8.56007934e-01 5.14337838e-01 -5.23366965e-02 -8.54154706e-01 5.17404258e-01 -5.23367077e-02 -8.52319956e-01 5.20425379e-01 -5.23366854e-02 -8.50492060e-01 5.23402750e-01 -5.23366854e-02 -8.48662853e-01 5.26368320e-01 -5.23366854e-02 -8.46824110e-01 5.29318213e-01 -5.23366854e-02 -8.45017731e-01 5.32198668e-01 -5.23366556e-02 -8.43149543e-01 5.35152912e-01 -5.23367263e-02 -8.41218054e-01 5.38184345e-01 -5.23366965e-02 -8.39390278e-01 5.41027069e-01 -5.23366407e-02 -8.37501824e-01 5.43948472e-01 -5.23367338e-02 -8.35573792e-01 5.46903908e-01 -5.23366854e-02 -8.33652735e-01 5.49829841e-01 -5.23366965e-02 -8.31713796e-01 5.52755713e-01 -5.23366965e-02 -8.29769611e-01 5.55671275e-01 -5.23366854e-02 -8.27890933e-01 5.58467388e-01 -5.23366258e-02 -8.25923324e-01 5.61373234e-01 -5.23367338e-02 -8.23899686e-01 5.64338803e-01 -5.23366854e-02 -8.21931660e-01 5.67202508e-01 -5.23366891e-02 -8.20003390e-01 5.69983184e-01 -5.23366109e-02 -8.18017244e-01 5.72831154e-01 -5.23367226e-02 -8.15972090e-01 5.75744092e-01 -5.23366667e-02 -8.13942730e-01 5.78606427e-01 -5.23367040e-02 -8.11895728e-01 5.81477106e-01 -5.23366556e-02 -8.09913516e-01 5.84229410e-01 -5.23366146e-02 -8.07910204e-01 5.87001681e-01 -5.23366965e-02 -8.05798531e-01 5.89894474e-01 -5.23366854e-02 -8.03694427e-01 5.92760086e-01 -5.23366854e-02 -8.01614702e-01 5.95568895e-01 -5.23366779e-02 -7.99524069e-01 5.98371625e-01 -5.23366779e-02 -7.97441363e-01 6.01145506e-01 -5.23366705e-02 -7.95339763e-01 6.03925169e-01 -5.23366816e-02 -7.93225288e-01 6.06699169e-01 -5.23366854e-02 -7.91118562e-01 6.09440804e-01 -5.23366518e-02 -7.89014637e-01 6.12161398e-01 -5.23365662e-02 -7.86892295e-01 6.14888787e-01 -5.23367375e-02 -7.84655750e-01 6.17741525e-01 -5.23366556e-02 -7.82494187e-01 6.20475948e-01 -5.23366630e-02 -7.80337453e-01 6.23190165e-01 -5.23366779e-02 -7.78142452e-01 6.25926673e-01 -5.23366854e-02 -7.75976479e-01 6.28610611e-01 -5.23366854e-02 -7.73845673e-01 6.31225765e-01 -5.23365960e-02 -7.71645904e-01 6.33920550e-01 -5.23366965e-02 -7.69358814e-01 6.36691749e-01 -5.23366295e-02 -7.67184198e-01 6.39307737e-01 -5.23365773e-02 -7.64975309e-01 6.41952157e-01 -5.23366965e-02 -7.62650013e-01 6.44712448e-01 -5.23366407e-02 -7.60415852e-01 6.47343814e-01 -5.23366742e-02 -7.58132279e-01 6.50018454e-01 -5.23366518e-02 -7.55849779e-01 6.52674198e-01 -5.23366518e-02 -7.53656447e-01 6.55204177e-01 -5.23366258e-02 -7.51315832e-01 6.57885611e-01 -5.23367152e-02 -7.48948812e-01 6.60578787e-01 -5.23366667e-02 -7.46610582e-01 6.63221300e-01 -5.23366854e-02 -7.44313776e-01 6.65798962e-01 -5.23366742e-02 -7.41985083e-01 6.68390155e-01 -5.23366705e-02 -7.39648521e-01 6.70978844e-01 -5.23366556e-02 -7.37303197e-01 6.73550725e-01 -5.23366854e-02 -7.34965086e-01 6.76104486e-01 -5.23366295e-02 -7.32636929e-01 6.78626001e-01 -5.23365960e-02 -7.30278611e-01 6.81163669e-01 -5.23367338e-02 -7.27816105e-01 6.83792412e-01 -5.23366965e-02 -7.25422382e-01 6.86331213e-01 -5.23366854e-02 -7.23014891e-01 6.88868761e-01 -5.23366667e-02 -7.20603645e-01 6.91384792e-01 -5.23366779e-02 -7.18217254e-01 6.93875253e-01 -5.23366705e-02 -7.15824962e-01 6.96340322e-01 -5.23366071e-02 -7.13406265e-01 6.98818386e-01 -5.23367152e-02 -7.10900605e-01 7.01368034e-01 -5.23366965e-02 -7.08501458e-01 7.03792214e-01 -5.23366146e-02 -7.06035793e-01 7.06248462e-01 -5.23367189e-02 -7.03513920e-01 7.08778441e-01 -5.23366854e-02 -7.01035321e-01 7.11229444e-01 -5.23366854e-02 -6.98554695e-01 7.13663459e-01 -5.23366854e-02 -6.96086347e-01 7.16073394e-01 -5.23366556e-02 -6.93648696e-01 7.18434453e-01 -5.23365960e-02 -6.91110969e-01 7.20867157e-01 -5.23366965e-02 -6.88520730e-01 7.23348975e-01 -5.23366854e-02 -6.85972154e-01 7.25761235e-01 -5.23366854e-02 -6.83437943e-01 7.28146970e-01 -5.23366407e-02 -6.80895030e-01 7.30524480e-01 -5.23366667e-02 -6.78353727e-01 7.32887089e-01 -5.23366258e-02 -6.75787568e-01 7.35258281e-01 -5.23366779e-02 -6.73212886e-01 7.37612724e-01 -5.23366928e-02 -6.70636594e-01 7.39958704e-01 -5.23366854e-02 -6.68120980e-01 7.42228627e-01 -5.23366258e-02 -6.65547848e-01 7.44537413e-01 -5.23366928e-02 -6.62841737e-01 7.46947765e-01 -5.23366444e-02 -6.60242260e-01 7.49246359e-01 -5.23366705e-02 -6.57608747e-01 7.51556635e-01 -5.23366518e-02 -6.54993832e-01 7.53838062e-01 -5.23366258e-02 -6.52416706e-01 7.56069422e-01 -5.23366034e-02 -6.49771810e-01 7.58343697e-01 -5.23366965e-02 -6.47051692e-01 7.60666072e-01 -5.23366630e-02 -6.44453108e-01 7.62869239e-01 -5.23366183e-02 -6.41810417e-01 7.65093446e-01 -5.23367152e-02 -6.39050126e-01 7.67401397e-01 -5.23366630e-02 -6.36400223e-01 7.69598782e-01 -5.23366556e-02 -6.33704305e-01 7.71822631e-01 -5.23366444e-02 -6.31054938e-01 7.73986220e-01 -5.23365922e-02 -6.28352046e-01 7.76186705e-01 -5.23367003e-02 -6.25563323e-01 7.78434575e-01 -5.23366928e-02 -6.22904301e-01 7.80562520e-01 -5.23366258e-02 -6.20189548e-01 7.82722533e-01 -5.23367301e-02 -6.17438257e-01 7.84893751e-01 -5.23366071e-02 -6.14733875e-01 7.87015855e-01 -5.23367375e-02 -6.11877561e-01 7.89237976e-01 -5.23366928e-02 -6.09191120e-01 7.91312635e-01 -5.23365997e-02 -6.06466770e-01 7.93403268e-01 -5.23367338e-02 -6.03647411e-01 7.95548260e-01 -5.23366518e-02 -6.00873470e-01 7.97649264e-01 -5.23367077e-02 -5.98080039e-01 7.99741805e-01 -5.23366369e-02 -5.95306933e-01 8.01809490e-01 -5.23367301e-02 -5.92411280e-01 8.03950250e-01 -5.23366854e-02 -5.89605451e-01 8.06011319e-01 -5.23366928e-02 -5.86847663e-01 8.08021724e-01 -5.23366183e-02 -5.84079742e-01 8.10023010e-01 -5.23366965e-02 -5.81174374e-01 8.12113523e-01 -5.23367077e-02 -5.78357041e-01 8.14121127e-01 -5.23366183e-02 -5.75544357e-01 8.16114247e-01 -5.23367189e-02 -5.72686136e-01 8.18118334e-01 -5.23366034e-02 -5.69818735e-01 8.20118845e-01 -5.23367003e-02 -5.66875339e-01 8.22157562e-01 -5.23366854e-02 -5.63990831e-01 8.24139059e-01 -5.23366854e-02 -5.61191797e-01 8.26044023e-01 -5.23366444e-02 -5.58384240e-01 8.27948511e-01 -5.23366965e-02 -5.55435419e-01 8.29927444e-01 -5.23366965e-02 -5.52505493e-01 8.31877649e-01 -5.23365885e-02 -5.49608409e-01 8.33799660e-01 -5.23367040e-02 -5.46702504e-01 8.35704923e-01 -5.23366258e-02 -5.43813884e-01 8.37588906e-01 -5.23367114e-02 -5.40805936e-01 8.39534283e-01 -5.23366965e-02 -5.37842989e-01 8.41435730e-01 -5.23366965e-02 -5.34887910e-01 8.43316674e-01 -5.23366854e-02 -5.31928480e-01 8.45187366e-01 -5.23366779e-02 -5.28986156e-01 8.47031295e-01 -5.23366556e-02 -5.26108503e-01 8.48822951e-01 -5.23366071e-02 -5.23152351e-01 8.50647449e-01 -5.23367301e-02 -5.20059705e-01 8.52542520e-01 -5.23366965e-02 -5.17064869e-01 8.54360282e-01 -5.23366854e-02 -5.14169872e-01 8.56105387e-01 -5.23366071e-02 -5.11208296e-01 8.57879460e-01 -5.23367412e-02 -5.08107483e-01 8.59718680e-01 -5.23366854e-02 -5.05177915e-01 8.61443162e-01 -5.23365960e-02 -5.02209067e-01 8.63178074e-01 -5.23366965e-02 -4.99131083e-01 8.64961326e-01 -5.23365885e-02 -4.96150881e-01 8.66673887e-01 -5.23367226e-02 -4.93040711e-01 8.68446469e-01 -5.23366369e-02 -4.90026534e-01 8.70152831e-01 -5.23366556e-02 -4.87093568e-01 8.71794224e-01 -5.23366183e-02 -4.84009773e-01 8.73511255e-01 -5.23367003e-02 -4.80873972e-01 8.75242054e-01 -5.23365922e-02 -4.77920830e-01 8.76859069e-01 -5.23365922e-02 -4.74847645e-01 8.78528118e-01 -5.23367524e-02 -4.71749723e-01 8.80192995e-01 -5.23366295e-02 -4.68718678e-01 8.81812453e-01 -5.23366854e-02 -4.65597034e-01 8.83464098e-01 -5.23365997e-02 -4.62559104e-01 8.85058939e-01 -5.23366965e-02 -4.59393740e-01 8.86704504e-01 -5.23366518e-02 -4.56277847e-01 8.88313651e-01 -5.23366407e-02 -4.53172863e-01 8.89900625e-01 -5.23366630e-02 -4.50128853e-01 8.91444385e-01 -5.23365997e-02 -4.47009295e-01 8.93012643e-01 -5.23366854e-02 -4.43848789e-01 8.94588649e-01 -5.23366705e-02 -4.40695584e-01 8.96144629e-01 -5.23366407e-02 -4.37629730e-01 8.97646248e-01 -5.23366071e-02 -4.34509605e-01 8.99162591e-01 -5.23366965e-02 -4.31286752e-01 9.00709689e-01 -5.23366518e-02 -4.28152561e-01 9.02204275e-01 -5.23366779e-02 -4.24990594e-01 9.03698325e-01 -5.23366556e-02 -4.21902001e-01 9.05144095e-01 -5.23366034e-02 -4.18758452e-01 9.06604171e-01 -5.23366965e-02 -4.15518463e-01 9.08091903e-01 -5.23366854e-02 -4.12297934e-01 9.09558773e-01 -5.23366183e-02 -4.09254193e-01 9.10932720e-01 -5.23365662e-02 -4.06082958e-01 9.12352681e-01 -5.23367003e-02 -4.02814448e-01 9.13800061e-01 -5.23366779e-02 -3.99693578e-01 9.15170789e-01 -5.23366295e-02 -3.96500111e-01 9.16557610e-01 -5.23366965e-02 -3.93262625e-01 9.17945743e-01 -5.23365624e-02 -3.90144914e-01 9.19279814e-01 -5.23366779e-02 -3.86930108e-01 9.20638204e-01 -5.23366556e-02 -3.83679003e-01 9.21997905e-01 -5.23367077e-02 -3.80345017e-01 9.23376560e-01 -5.23366444e-02 -3.77141893e-01 9.24690425e-01 -5.23366854e-02 -3.73908788e-01 9.26003277e-01 -5.23366891e-02 -3.70727092e-01 9.27280247e-01 -5.23366481e-02 -3.67483139e-01 9.28573072e-01 -5.23367114e-02 -3.64203930e-01 9.29863632e-01 -5.23366854e-02 -3.60932767e-01 9.31131661e-01 -5.23366518e-02 -3.57775718e-01 9.32360172e-01 -5.23366258e-02 -3.54532808e-01 9.33589756e-01 -5.23367040e-02 -3.51193607e-01 9.34844851e-01 -5.23366779e-02 -3.47923636e-01 9.36066091e-01 -5.23366630e-02 -3.44751894e-01 9.37240005e-01 -5.23365811e-02 -3.41552138e-01 9.38421845e-01 -5.23366183e-02 -3.38198394e-01 9.39633250e-01 -5.23367114e-02 -3.34905297e-01 9.40813720e-01 -5.23366109e-02 -3.31653476e-01 9.41964090e-01 -5.23366965e-02 -3.28347683e-01 9.43119764e-01 -5.23366146e-02 -3.25080693e-01 9.44253087e-01 -5.23366965e-02 -3.21729243e-01 9.45397794e-01 -5.23366556e-02 -3.18472117e-01 9.46501732e-01 -5.23366369e-02 -3.15160811e-01 9.47608292e-01 -5.23366965e-02 -3.11832041e-01 9.48707402e-01 -5.23366146e-02 -3.08504671e-01 9.49797273e-01 -5.23367152e-02 -3.05218756e-01 9.50858235e-01 -5.23366146e-02 -3.01905721e-01 9.51915562e-01 -5.23366854e-02 -2.98478454e-01 9.52993572e-01 -5.23366183e-02 -2.95154780e-01 9.54029143e-01 -5.23366630e-02 -2.91823387e-01 9.55053449e-01 -5.23366854e-02 -2.88498729e-01 9.56062138e-01 -5.23366593e-02 -2.85167366e-01 9.57062066e-01 -5.23366854e-02 -2.81824410e-01 9.58052933e-01 -5.23366779e-02 -2.78483361e-01 9.59029615e-01 -5.23366854e-02 -2.75213242e-01 9.59972143e-01 -5.23366295e-02 -2.71839857e-01 9.60934460e-01 -5.23367077e-02 -2.68435121e-01 9.61889267e-01 -5.23366518e-02 -2.65066087e-01 9.62823629e-01 -5.23366854e-02 -2.61766940e-01 9.63727951e-01 -5.23366258e-02 -2.58496612e-01 9.64609563e-01 -5.23366779e-02 -2.55059272e-01 9.65523362e-01 -5.23367077e-02 -2.51687586e-01 9.66407418e-01 -5.23366258e-02 -2.48301834e-01 9.67283189e-01 -5.23367077e-02 -2.44938210e-01 9.68137681e-01 -5.23366034e-02 -2.41539344e-01 9.68993425e-01 -5.23367226e-02 -2.38038719e-01 9.69860971e-01 -5.23366854e-02 -2.34758228e-01 9.70659733e-01 -5.23366220e-02 -2.31348231e-01 9.71479714e-01 -5.23367301e-02 -2.27976725e-01 9.72272754e-01 -5.23365922e-02 -2.24617258e-01 9.73056734e-01 -5.23367263e-02 -2.21177518e-01 9.73842144e-01 -5.23366183e-02 -2.17914999e-01 9.74579513e-01 -5.23366854e-02 -2.14380652e-01 9.75362420e-01 -5.23367412e-02 -2.10857555e-01 9.76129830e-01 -5.23366854e-02 -2.07461640e-01 9.76856947e-01 -5.23366854e-02 -2.04064503e-01 9.77572322e-01 -5.23366556e-02 -2.00763538e-01 9.78254199e-01 -5.23365922e-02 -1.97307959e-01 9.78957713e-01 -5.23367301e-02 -1.93778500e-01 9.79662418e-01 -5.23366854e-02 -1.90370739e-01 9.80330586e-01 -5.23366854e-02 -1.86940223e-01 9.80991244e-01 -5.23366854e-02 -1.83628500e-01 9.81613755e-01 -5.23365922e-02 -1.80212528e-01 9.82246637e-01 -5.23366854e-02 -1.76763952e-01 9.82878864e-01 -5.23365885e-02 -1.73331201e-01 9.83492017e-01 -5.23367114e-02 -1.69811502e-01 9.84099209e-01 -5.23366854e-02 -1.66464016e-01 9.84672308e-01 -5.23366183e-02 -1.63024187e-01 9.85248268e-01 -5.23367226e-02 -1.59578219e-01 9.85809565e-01 -5.23366146e-02 -1.56158522e-01 9.86359179e-01 -5.23367114e-02 -1.52595401e-01 9.86916900e-01 -5.23366854e-02 -1.49246290e-01 9.87426877e-01 -5.23366071e-02 -1.45795584e-01 9.87944067e-01 -5.23367077e-02 -1.42351255e-01 9.88444090e-01 -5.23366183e-02 -1.38904184e-01 9.88938093e-01 -5.23367152e-02 -1.35352775e-01 9.89429772e-01 -5.23366630e-02 -1.31965905e-01 9.89883721e-01 -5.23366220e-02 -1.28516182e-01 9.90340948e-01 -5.23367189e-02 -1.24972641e-01 9.90793824e-01 -5.23366779e-02 -1.21506304e-01 9.91223514e-01 -5.23366779e-02 -1.18142091e-01 9.91627514e-01 -5.23365885e-02 -1.14778340e-01 9.92024422e-01 -5.23366854e-02 -1.11229382e-01 9.92430329e-01 -5.23367077e-02 -1.07671112e-01 9.92820561e-01 -5.23366556e-02 -1.04168303e-01 9.93195534e-01 -5.23366779e-02 -1.00683033e-01 9.93553400e-01 -5.23366556e-02 -9.73310620e-02 9.93888378e-01 -5.23366034e-02 -9.39017013e-02 9.94219899e-01 -5.23367189e-02 -9.04177278e-02 9.94541824e-01 -5.23366034e-02 -8.69418159e-02 9.94853139e-01 -5.23367114e-02 -8.33466575e-02 9.95159566e-01 -5.23366556e-02 -8.00092667e-02 9.95433927e-01 -5.23365960e-02 -7.65217990e-02 9.95707095e-01 -5.23366965e-02 -7.30252787e-02 9.95968997e-01 -5.23365811e-02 -6.95707500e-02 9.96216714e-01 -5.23367152e-02 -6.59645796e-02 9.96462703e-01 -5.23366779e-02 -6.24686591e-02 9.96685266e-01 -5.23366518e-02 -5.90047687e-02 9.96898234e-01 -5.23366854e-02 -5.56364916e-02 9.97091234e-01 -5.23365848e-02 -5.21270372e-02 9.97280359e-01 -5.23367077e-02 -4.86481898e-02 9.97457206e-01 -5.23366146e-02 -4.52845022e-02 9.97615695e-01 -5.23366630e-02 -4.16999869e-02 9.97771859e-01 -5.23367114e-02 -3.81249562e-02 9.97914851e-01 -5.23366854e-02 -3.46331485e-02 9.98042047e-01 -5.23366705e-02 -3.11277509e-02 9.98158216e-01 -5.23366928e-02 -2.77463496e-02 9.98256087e-01 -5.23365960e-02 -2.43634731e-02 9.98347998e-01 -5.23366630e-02 -2.07796711e-02 9.98424649e-01 -5.23367077e-02 -1.71620566e-02 9.98500168e-01 -5.23366630e-02 -1.37208421e-02 9.98545289e-01 -5.23366556e-02 -1.03414040e-02 9.98586655e-01 -5.23365922e-02 -6.85821055e-03 9.98625576e-01 -5.23366854e-02 -3.31867905e-03 9.98641670e-01 -5.23365997e-02 1.30519678e-04 9.98644352e-01 -5.23366965e-02 3.71123618e-03 9.98642147e-01 -5.23366518e-02 7.11404905e-03 9.98620987e-01 -5.23366034e-02 1.05980346e-02 9.98586714e-01 -5.23366854e-02 1.40808513e-02 9.98540640e-01 -5.23365922e-02 1.75535418e-02 9.98493612e-01 -5.23366854e-02 2.10488569e-02 9.98420835e-01 -5.23365885e-02 2.44493261e-02 9.98345077e-01 -5.23366518e-02 2.80112457e-02 9.98251379e-01 -5.23366854e-02 3.15783508e-02 9.98143375e-01 -5.23366295e-02 3.50851007e-02 9.98027563e-01 -5.23366220e-02 3.85582708e-02 9.97899234e-01 -5.23366369e-02 4.19335030e-02 9.97762859e-01 -5.23365960e-02 4.54426929e-02 9.97608185e-01 -5.23366928e-02 4.90185283e-02 9.97439206e-01 -5.23366407e-02 5.24646752e-02 9.97261047e-01 -5.23366220e-02 5.59426583e-02 9.97075021e-01 -5.23366258e-02 5.93554787e-02 9.96877611e-01 -5.23365848e-02 6.27937987e-02 9.96665061e-01 -5.23366965e-02 6.63904995e-02 9.96432006e-01 -5.23365997e-02 6.98911026e-02 9.96192634e-01 -5.23366518e-02 7.33927935e-02 9.95943308e-01 -5.23366630e-02 7.67686367e-02 9.95686769e-01 -5.23365960e-02 8.01948532e-02 9.95417535e-01 -5.23366965e-02 8.37523490e-02 9.95124042e-01 -5.23365736e-02 8.71527940e-02 9.94832933e-01 -5.23366965e-02 9.07444358e-02 9.94511485e-01 -5.23366556e-02 9.41318199e-02 9.94193971e-01 -5.23365289e-02 9.75741372e-02 9.93865550e-01 -5.23366965e-02 1.01084277e-01 9.93514061e-01 -5.23365848e-02 1.04496241e-01 9.93160903e-01 -5.23366965e-02 1.08017579e-01 9.92782474e-01 -5.23365438e-02 1.11469142e-01 9.92403567e-01 -5.23366965e-02 1.15021445e-01 9.91995633e-01 -5.23366705e-02 1.18465133e-01 9.91589785e-01 -5.23366630e-02 1.21938162e-01 9.91170704e-01 -5.23366705e-02 1.25312492e-01 9.90751088e-01 -5.23366109e-02 1.28697202e-01 9.90314960e-01 -5.23366556e-02 1.32209823e-01 9.89853740e-01 -5.23366965e-02 1.35748699e-01 9.89374816e-01 -5.23366556e-02 1.39230072e-01 9.88890827e-01 -5.23366071e-02 1.42676935e-01 9.88397479e-01 -5.23366146e-02 1.46081522e-01 9.87899303e-01 -5.23365811e-02 1.49493352e-01 9.87390041e-01 -5.23366965e-02 1.52923569e-01 9.86864924e-01 -5.23365997e-02 1.56383291e-01 9.86323297e-01 -5.23366965e-02 1.59931213e-01 9.85753894e-01 -5.23366481e-02 1.63270146e-01 9.85205829e-01 -5.23365885e-02 1.66694671e-01 9.84633386e-01 -5.23366928e-02 1.70123801e-01 9.84044611e-01 -5.23365885e-02 1.73486546e-01 9.83461976e-01 -5.23366630e-02 1.76971868e-01 9.82841134e-01 -5.23366965e-02 1.80543333e-01 9.82186317e-01 -5.23366220e-02 1.83952227e-01 9.81554747e-01 -5.23366630e-02 1.87266618e-01 9.80927229e-01 -5.23366183e-02 1.90708116e-01 9.80264544e-01 -5.23366854e-02 1.94130361e-01 9.79593396e-01 -5.23366109e-02 1.97457373e-01 9.78926241e-01 -5.23366556e-02 2.00957626e-01 9.78216410e-01 -5.23367040e-02 2.04474211e-01 9.77485657e-01 -5.23366630e-02 2.07871869e-01 9.76770043e-01 -5.23366742e-02 2.11280316e-01 9.76038635e-01 -5.23366854e-02 2.14600757e-01 9.75310087e-01 -5.23366109e-02 2.17978597e-01 9.74565804e-01 -5.23367040e-02 2.21483171e-01 9.73770976e-01 -5.23366295e-02 2.24881902e-01 9.72994924e-01 -5.23366295e-02 2.28285879e-01 9.72202480e-01 -5.23366518e-02 2.31588438e-01 9.71419156e-01 -5.23365736e-02 2.34879330e-01 9.70632315e-01 -5.23366705e-02 2.38302350e-01 9.69794393e-01 -5.23366556e-02 2.41736665e-01 9.68943596e-01 -5.23366965e-02 2.45187148e-01 9.68075991e-01 -5.23366779e-02 2.48509213e-01 9.67229724e-01 -5.23366146e-02 2.51864791e-01 9.66361761e-01 -5.23367226e-02 2.55249470e-01 9.65473354e-01 -5.23366034e-02 2.58593112e-01 9.64583039e-01 -5.23367003e-02 2.62094617e-01 9.63637710e-01 -5.23366630e-02 2.65347838e-01 9.62744892e-01 -5.23366034e-02 2.68710196e-01 9.61814106e-01 -5.23367114e-02 2.72085577e-01 9.60862756e-01 -5.23366034e-02 2.75397003e-01 9.59920168e-01 -5.23367301e-02 2.78858006e-01 9.58918512e-01 -5.23366407e-02 2.82098293e-01 9.57971573e-01 -5.23366146e-02 2.85461813e-01 9.56976473e-01 -5.23367040e-02 2.88902193e-01 9.55939591e-01 -5.23366630e-02 2.92200863e-01 9.54939663e-01 -5.23366295e-02 2.95428008e-01 9.53945398e-01 -5.23366109e-02 2.98682570e-01 9.52932298e-01 -5.23366854e-02 3.02022129e-01 9.51878428e-01 -5.23366928e-02 3.05445254e-01 9.50784445e-01 -5.23367152e-02 3.08871239e-01 9.49677765e-01 -5.23366965e-02 3.12166095e-01 9.48599279e-01 -5.23366854e-02 3.15391988e-01 9.47531283e-01 -5.23365960e-02 3.18592757e-01 9.46462452e-01 -5.23366854e-02 3.21895808e-01 9.45341289e-01 -5.23366444e-02 3.25251430e-01 9.44194376e-01 -5.23366965e-02 3.28665286e-01 9.43008542e-01 -5.23366854e-02 3.31861913e-01 9.41890121e-01 -5.23366034e-02 3.35140198e-01 9.40730155e-01 -5.23366965e-02 3.38463247e-01 9.39535201e-01 -5.23366034e-02 3.41703504e-01 9.38366175e-01 -5.23367152e-02 3.45080048e-01 9.37122524e-01 -5.23366965e-02 3.48333538e-01 9.35912669e-01 -5.23366369e-02 3.51597220e-01 9.34693992e-01 -5.23366854e-02 3.54793161e-01 9.33488309e-01 -5.23366183e-02 3.58048439e-01 9.32255566e-01 -5.23367152e-02 3.61302733e-01 9.30988491e-01 -5.23366109e-02 3.64450336e-01 9.29764926e-01 -5.23366630e-02 3.67777854e-01 9.28454578e-01 -5.23366854e-02 3.71114075e-01 9.27126288e-01 -5.23366630e-02 3.74311596e-01 9.25837755e-01 -5.23366444e-02 3.77543896e-01 9.24527109e-01 -5.23366779e-02 3.80695701e-01 9.23230231e-01 -5.23366295e-02 3.83838534e-01 9.21930611e-01 -5.23366928e-02 3.87144893e-01 9.20547247e-01 -5.23367189e-02 3.90415728e-01 9.19163048e-01 -5.23366742e-02 3.93603802e-01 9.17802513e-01 -5.23366779e-02 3.96769583e-01 9.16438222e-01 -5.23366071e-02 3.99881959e-01 9.15088117e-01 -5.23366556e-02 4.03081119e-01 9.13680851e-01 -5.23366258e-02 4.06325728e-01 9.12243903e-01 -5.23367114e-02 4.09564912e-01 9.10794616e-01 -5.23366965e-02 4.12676007e-01 9.09387469e-01 -5.23366407e-02 4.15775776e-01 9.07973409e-01 -5.23366928e-02 4.18928921e-01 9.06522930e-01 -5.23366742e-02 4.22064871e-01 9.05068696e-01 -5.23366630e-02 4.25250500e-01 9.03575182e-01 -5.23366109e-02 4.28421110e-01 9.02076781e-01 -5.23366854e-02 4.31665093e-01 9.00527477e-01 -5.23366556e-02 4.34802771e-01 8.99021506e-01 -5.23366667e-02 4.37850118e-01 8.97540867e-01 -5.23366369e-02 4.40944582e-01 8.96022737e-01 -5.23366965e-02 4.44055051e-01 8.94485712e-01 -5.23366854e-02 4.47244257e-01 8.92895818e-01 -5.23367189e-02 4.50431436e-01 8.91292393e-01 -5.23366891e-02 4.53530401e-01 8.89718771e-01 -5.23366965e-02 4.56573337e-01 8.88160288e-01 -5.23365922e-02 4.59595263e-01 8.86598289e-01 -5.23366183e-02 4.62678760e-01 8.84998977e-01 -5.23366556e-02 4.65831131e-01 8.83341908e-01 -5.23367040e-02 4.68986303e-01 8.81670356e-01 -5.23366556e-02 4.72058266e-01 8.80029738e-01 -5.23366928e-02 4.75036293e-01 8.78422439e-01 -5.23366220e-02 4.78068650e-01 8.76780450e-01 -5.23366258e-02 4.81134832e-01 8.75099540e-01 -5.23366444e-02 4.84213769e-01 8.73397231e-01 -5.23367114e-02 4.87336338e-01 8.71660471e-01 -5.23366779e-02 4.90347415e-01 8.69970083e-01 -5.23365997e-02 4.93333966e-01 8.68281424e-01 -5.23367375e-02 4.96391267e-01 8.66536915e-01 -5.23366146e-02 4.99327093e-01 8.64848077e-01 -5.23366779e-02 5.02423465e-01 8.63054752e-01 -5.23367040e-02 5.05439460e-01 8.61289501e-01 -5.23366518e-02 5.08438289e-01 8.59524190e-01 -5.23367338e-02 5.11427045e-01 8.57746840e-01 -5.23366332e-02 5.14420509e-01 8.55957925e-01 -5.23367263e-02 5.17452955e-01 8.54124844e-01 -5.23366779e-02 5.20334542e-01 8.52375507e-01 -5.23366444e-02 5.23348272e-01 8.50527525e-01 -5.23367263e-02 5.26337087e-01 8.48681152e-01 -5.23366407e-02 5.29286504e-01 8.46845090e-01 -5.23367301e-02 5.32251179e-01 8.44984055e-01 -5.23366258e-02 5.35085082e-01 8.43192577e-01 -5.23366630e-02 5.38048565e-01 8.41304541e-01 -5.23366965e-02 5.40981472e-01 8.39420378e-01 -5.23366705e-02 5.43964863e-01 8.37491333e-01 -5.23367152e-02 5.46948314e-01 8.35546255e-01 -5.23366854e-02 5.49822927e-01 8.33657503e-01 -5.23366034e-02 5.52637339e-01 8.31790745e-01 -5.23366779e-02 5.55533826e-01 8.29862475e-01 -5.23366593e-02 5.58486283e-01 8.27879667e-01 -5.23366258e-02 5.61407447e-01 8.25897157e-01 -5.23365103e-02 5.64254820e-01 8.23952734e-01 -5.23363687e-02 5.67090869e-01 8.22001755e-01 -5.23362719e-02 5.69931030e-01 8.20032179e-01 -5.23361824e-02 5.72840273e-01 8.18002641e-01 -5.23361303e-02 5.75671315e-01 8.16009998e-01 -5.23358583e-02 5.78452229e-01 8.14040661e-01 -5.23359291e-02 5.81360757e-01 8.11965227e-01 -5.23358881e-02 5.84164202e-01 8.09943557e-01 -5.23357876e-02 5.86882293e-01 8.07976007e-01 -5.23358099e-02 5.89633405e-01 8.05971622e-01 -5.23358919e-02 5.92184246e-01 8.04100573e-01 -5.23359701e-02 5.95547497e-01 8.01613450e-01 -5.23359589e-02 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. 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. 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. 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. 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. 0. 7.21795499e-01 6.90124750e-01 -5.23359589e-02 7.23565042e-01 6.88268721e-01 -5.23359738e-02 7.25789368e-01 6.85919940e-01 -5.23358025e-02 7.28123963e-01 6.83439314e-01 -5.23357764e-02 7.30552793e-01 6.80853426e-01 -5.23359813e-02 7.32838511e-01 6.78397000e-01 -5.23360893e-02 7.35130548e-01 6.75915956e-01 -5.23362458e-02 7.37478673e-01 6.73354447e-01 -5.23363650e-02 7.39831388e-01 6.70771420e-01 -5.23364283e-02 7.42227435e-01 6.68123543e-01 -5.23366034e-02 7.44604707e-01 6.65468037e-01 -5.23365736e-02 7.46832430e-01 6.62967920e-01 -5.23364805e-02 7.49099314e-01 6.60406470e-01 -5.23365624e-02 7.51409411e-01 6.57775521e-01 -5.23365773e-02 7.53694415e-01 6.55157447e-01 -5.23365624e-02 7.56039023e-01 6.52452350e-01 -5.23366183e-02 7.58303583e-01 6.49818122e-01 -5.23365662e-02 7.60518968e-01 6.47223294e-01 -5.23366295e-02 7.62765288e-01 6.44576788e-01 -5.23366556e-02 7.65068769e-01 6.41839921e-01 -5.23366965e-02 7.67291844e-01 6.39180422e-01 -5.23365960e-02 7.69469082e-01 6.36556149e-01 -5.23366183e-02 7.71757782e-01 6.33785069e-01 -5.23367040e-02 7.74018407e-01 6.31018043e-01 -5.23366779e-02 7.76217103e-01 6.28312767e-01 -5.23366630e-02 7.78342605e-01 6.25674844e-01 -5.23366109e-02 7.80473411e-01 6.23020232e-01 -5.23366556e-02 7.82623112e-01 6.20312810e-01 -5.23366332e-02 7.84843624e-01 6.17503703e-01 -5.23367114e-02 7.87061572e-01 6.14672601e-01 -5.23366854e-02 7.89193988e-01 6.11932337e-01 -5.23366556e-02 7.91277528e-01 6.09235764e-01 -5.23365922e-02 7.93349206e-01 6.06537879e-01 -5.23366667e-02 7.95466065e-01 6.03757441e-01 -5.23366705e-02 7.97610700e-01 6.00925088e-01 -5.23367040e-02 7.99772561e-01 5.98039865e-01 -5.23366854e-02 8.01797032e-01 5.95321894e-01 -5.23366109e-02 8.03810716e-01 5.92600048e-01 -5.23366556e-02 8.05868506e-01 5.89796901e-01 -5.23366854e-02 8.07987809e-01 5.86894453e-01 -5.23367189e-02 8.10021460e-01 5.84080637e-01 -5.23366183e-02 8.11994135e-01 5.81339777e-01 -5.23366854e-02 8.14080238e-01 5.78415513e-01 -5.23367040e-02 8.16105962e-01 5.75554073e-01 -5.23366407e-02 8.18111956e-01 5.72697043e-01 -5.23367301e-02 8.20105612e-01 5.69835961e-01 -5.23365922e-02 8.22020411e-01 5.67075193e-01 -5.23366854e-02 8.24051619e-01 5.64121127e-01 -5.23367301e-02 8.26074481e-01 5.61150014e-01 -5.23366854e-02 8.28033566e-01 5.58255851e-01 -5.23366854e-02 8.29920590e-01 5.55444002e-01 -5.23366034e-02 8.31786335e-01 5.52646816e-01 -5.23366854e-02 8.33714664e-01 5.49734533e-01 -5.23366854e-02 8.35681796e-01 5.46740592e-01 -5.23366965e-02 8.37655842e-01 5.43710291e-01 -5.23366705e-02 8.39485645e-01 5.40877759e-01 -5.23365848e-02 8.41308534e-01 5.38040757e-01 -5.23366444e-02 8.43170822e-01 5.35117507e-01 -5.23366407e-02 8.45048249e-01 5.32150090e-01 -5.23366556e-02 8.46955955e-01 5.29107392e-01 -5.23367338e-02 8.48865330e-01 5.26040018e-01 -5.23366556e-02 8.50645900e-01 5.23149908e-01 -5.23365960e-02 8.52414191e-01 5.20271778e-01 -5.23366779e-02 8.54213357e-01 5.17306507e-01 -5.23366630e-02 8.56012642e-01 5.14324844e-01 -5.23366816e-02 8.57802212e-01 5.11337042e-01 -5.23366928e-02 8.59594166e-01 5.08317888e-01 -5.23366854e-02 8.61362576e-01 5.05315781e-01 -5.23366518e-02 8.63105536e-01 5.02332151e-01 -5.23366854e-02 8.64911973e-01 4.99217242e-01 -5.23367003e-02 8.66649806e-01 4.96191680e-01 -5.23365922e-02 8.68323803e-01 4.93256748e-01 -5.23366965e-02 8.70109439e-01 4.90106314e-01 -5.23367114e-02 8.71869504e-01 4.86961484e-01 -5.23366816e-02 8.73559654e-01 4.83919740e-01 -5.23366369e-02 8.75183642e-01 4.80980098e-01 -5.23366146e-02 8.76829267e-01 4.77977335e-01 -5.23366556e-02 8.78497541e-01 4.74901259e-01 -5.23366854e-02 8.80139589e-01 4.71850574e-01 -5.23366556e-02 8.81827354e-01 4.68690991e-01 -5.23367114e-02 8.83505344e-01 4.65520173e-01 -5.23366630e-02 8.85084391e-01 4.62508559e-01 -5.23365960e-02 8.86642873e-01 4.59512591e-01 -5.23366705e-02 8.88251662e-01 4.56398100e-01 -5.23366854e-02 8.89891446e-01 4.53189760e-01 -5.23366928e-02 8.91500652e-01 4.50015426e-01 -5.23366220e-02 8.93024564e-01 4.46983308e-01 -5.23365848e-02 8.94533336e-01 4.43956405e-01 -5.23366220e-02 8.96068215e-01 4.40852344e-01 -5.23366556e-02 8.97646368e-01 4.37632799e-01 -5.23366891e-02 8.99168491e-01 4.34496641e-01 -5.23365922e-02 9.00628090e-01 4.31455582e-01 -5.23366369e-02 9.02176201e-01 4.28211272e-01 -5.23366854e-02 9.03670490e-01 4.25048470e-01 -5.23366109e-02 9.05141175e-01 4.21913683e-01 -5.23367003e-02 9.06621039e-01 4.18716460e-01 -5.23365773e-02 9.08028483e-01 4.15657163e-01 -5.23366407e-02 9.09518719e-01 4.12386864e-01 -5.23366928e-02 9.10991728e-01 4.09126222e-01 -5.23366854e-02 9.12403226e-01 4.05966699e-01 -5.23366444e-02 9.13787723e-01 4.02836621e-01 -5.23366071e-02 9.15152848e-01 3.99731576e-01 -5.23366183e-02 9.16541815e-01 3.96532327e-01 -5.23366556e-02 9.17912543e-01 3.93343419e-01 -5.23366146e-02 9.19319510e-01 3.90049785e-01 -5.23366965e-02 9.20681477e-01 3.86823148e-01 -5.23365960e-02 9.21979189e-01 3.83722812e-01 -5.23366630e-02 9.23311949e-01 3.80501598e-01 -5.23366854e-02 9.24645960e-01 3.77251565e-01 -5.23366220e-02 9.25978124e-01 3.73968095e-01 -5.23366854e-02 9.27322567e-01 3.70622665e-01 -5.23366295e-02 9.28575456e-01 3.67472917e-01 -5.23365773e-02 9.29815829e-01 3.64326447e-01 -5.23366556e-02 9.31079030e-01 3.61065984e-01 -5.23366183e-02 9.32374835e-01 3.57735425e-01 -5.23366928e-02 9.33619082e-01 3.54443371e-01 -5.23365885e-02 9.34810162e-01 3.51283580e-01 -5.23366369e-02 9.36061442e-01 3.47936988e-01 -5.23366965e-02 9.37299132e-01 3.44594359e-01 -5.23366183e-02 9.38505650e-01 3.41325015e-01 -5.23366183e-02 9.39652383e-01 3.38131994e-01 -5.23365773e-02 9.40806091e-01 3.34927201e-01 -5.23366369e-02 9.41997528e-01 3.31559092e-01 -5.23366965e-02 9.43184197e-01 3.28162223e-01 -5.23366854e-02 9.44329202e-01 3.24860722e-01 -5.23366444e-02 9.45420384e-01 3.21661979e-01 -5.23365848e-02 9.46501911e-01 3.18473458e-01 -5.23366407e-02 9.47611153e-01 3.15152973e-01 -5.23366593e-02 9.48710680e-01 3.11826110e-01 -5.23366518e-02 9.49814558e-01 3.08453411e-01 -5.23366928e-02 9.50921118e-01 3.05021614e-01 -5.23366630e-02 9.51951742e-01 3.01787913e-01 -5.23365997e-02 9.52976406e-01 2.98539847e-01 -5.23366593e-02 9.54007566e-01 2.95225799e-01 -5.23366258e-02 9.55051243e-01 2.91832745e-01 -5.23367114e-02 9.56090331e-01 2.88404346e-01 -5.23366630e-02 9.57069457e-01 2.85141289e-01 -5.23366034e-02 9.58038449e-01 2.81874865e-01 -5.23366556e-02 9.59012389e-01 2.78536409e-01 -5.23366518e-02 9.59985912e-01 2.75164843e-01 -5.23366854e-02 9.60953712e-01 2.71767825e-01 -5.23366258e-02 9.61876214e-01 2.68487006e-01 -5.23366593e-02 9.62805450e-01 2.65128285e-01 -5.23366705e-02 9.63725686e-01 2.61775196e-01 -5.23366518e-02 9.64646041e-01 2.58350313e-01 -5.23366965e-02 9.65552747e-01 2.54942596e-01 -5.23365960e-02 9.66411233e-01 2.51674891e-01 -5.23366518e-02 9.67282891e-01 2.48299628e-01 -5.23366630e-02 9.68169153e-01 2.44816273e-01 -5.23366965e-02 9.69029188e-01 2.41389498e-01 -5.23366295e-02 9.69864488e-01 2.38019288e-01 -5.23366444e-02 9.70673323e-01 2.34700888e-01 -5.23366146e-02 9.71464932e-01 2.31401235e-01 -5.23366369e-02 9.72263455e-01 2.28018984e-01 -5.23366034e-02 9.73083854e-01 2.24494591e-01 -5.23366965e-02 9.73860562e-01 2.21092761e-01 -5.23365662e-02 9.74607527e-01 2.17784524e-01 -5.23366295e-02 9.75362718e-01 2.14368448e-01 -5.23366220e-02 9.76114631e-01 2.10923091e-01 -5.23366854e-02 9.76837575e-01 2.07549214e-01 -5.23365997e-02 9.77569699e-01 2.04077065e-01 -5.23366556e-02 9.78276074e-01 2.00658336e-01 -5.23365885e-02 9.78961647e-01 1.97288170e-01 -5.23366854e-02 9.79664862e-01 1.93766266e-01 -5.23366444e-02 9.80337858e-01 1.90332100e-01 -5.23366295e-02 9.80978549e-01 1.86993316e-01 -5.23365773e-02 9.81607974e-01 1.83664843e-01 -5.23366034e-02 9.82256055e-01 1.80162743e-01 -5.23366630e-02 9.82901335e-01 1.76640838e-01 -5.23366146e-02 9.83507693e-01 1.73232242e-01 -5.23366407e-02 9.84092951e-01 1.69844881e-01 -5.23366034e-02 9.84664619e-01 1.66508690e-01 -5.23366295e-02 9.85241950e-01 1.63052037e-01 -5.23366779e-02 9.85800624e-01 1.59644783e-01 -5.23366854e-02 9.86366987e-01 1.56112686e-01 -5.23367003e-02 9.86918628e-01 1.52580425e-01 -5.23366854e-02 9.87431943e-01 1.49210721e-01 -5.23366258e-02 9.87930238e-01 1.45883471e-01 -5.23366854e-02 9.88437414e-01 1.42405450e-01 -5.23366854e-02 9.88939941e-01 1.38883159e-01 -5.23367189e-02 9.89430010e-01 1.35350287e-01 -5.23366630e-02 9.89883065e-01 1.31968915e-01 -5.23365922e-02 9.90329862e-01 1.28591552e-01 -5.23366854e-02 9.90769088e-01 1.25169739e-01 -5.23366630e-02 9.91197407e-01 1.21725328e-01 -5.23366854e-02 9.91618812e-01 1.18234612e-01 -5.23366854e-02 9.92027879e-01 1.14750855e-01 -5.23366965e-02 9.92432356e-01 1.11212268e-01 -5.23367189e-02 9.92813289e-01 1.07754096e-01 -5.23366407e-02 9.93182957e-01 1.04292721e-01 -5.23367338e-02 9.93540168e-01 1.00814775e-01 -5.23366109e-02 9.93878961e-01 9.74304155e-02 -5.23366854e-02 9.94223475e-01 9.38868746e-02 -5.23367338e-02 9.94550228e-01 9.03278142e-02 -5.23366854e-02 9.94859695e-01 8.68568942e-02 -5.23366854e-02 9.95149136e-01 8.34675953e-02 -5.23366556e-02 9.95430768e-01 8.00444037e-02 -5.23366705e-02 9.95699942e-01 7.66022354e-02 -5.23366928e-02 9.95969176e-01 7.30391145e-02 -5.23367338e-02 9.96222019e-01 6.94797412e-02 -5.23366965e-02 9.96451378e-01 6.61067888e-02 -5.23366295e-02 9.96671915e-01 6.27160668e-02 -5.23366965e-02 9.96885955e-01 5.92061132e-02 -5.23366965e-02 9.97088671e-01 5.57305738e-02 -5.23366965e-02 9.97278750e-01 5.21863997e-02 -5.23367301e-02 9.97462153e-01 4.85841818e-02 -5.23366965e-02 9.97617304e-01 4.52225879e-02 -5.23366220e-02 9.97767389e-01 4.18384038e-02 -5.23366965e-02 9.97907102e-01 3.83556001e-02 -5.23366965e-02 9.98038471e-01 3.47503945e-02 -5.23367412e-02 9.98154283e-01 3.12573873e-02 -5.23366295e-02 9.98256266e-01 2.78828144e-02 -5.23366965e-02 9.98348475e-01 2.43840497e-02 -5.23367003e-02 9.98423278e-01 2.08756458e-02 -5.23366928e-02 9.98496532e-01 1.74139552e-02 -5.23366965e-02 9.98541772e-01 1.39448708e-02 -5.23366854e-02 9.98589814e-01 1.04308976e-02 -5.23366854e-02 9.98628259e-01 6.86536310e-03 -5.23367263e-02 9.98643219e-01 3.27086286e-03 -5.23366965e-02 9.98644590e-01 -2.07649195e-04 -5.23367003e-02 9.98642743e-01 -3.70242214e-03 -5.23366928e-02 9.98622417e-01 -7.10312976e-03 -5.23366146e-02 9.98590589e-01 -1.04631940e-02 -5.23367040e-02 9.98541355e-01 -1.39659019e-02 -5.23366630e-02 9.98495817e-01 -1.75628290e-02 -5.23367450e-02 9.98417377e-01 -2.11568568e-02 -5.23366965e-02 9.98341382e-01 -2.46139653e-02 -5.23366854e-02 9.98252511e-01 -2.79760174e-02 -5.23366518e-02 9.98148024e-01 -3.14783528e-02 -5.23367561e-02 9.98031616e-01 -3.49910259e-02 -5.23366556e-02 9.97905910e-01 -3.83808464e-02 -5.23367040e-02 9.97768104e-01 -4.18565534e-02 -5.23366854e-02 9.97610569e-01 -4.54246923e-02 -5.23367487e-02 9.97440934e-01 -4.90076132e-02 -5.23366965e-02 9.97261643e-01 -5.24912328e-02 -5.23366965e-02 9.97077405e-01 -5.58898039e-02 -5.23366295e-02 9.96882737e-01 -5.92712648e-02 -5.23366965e-02 9.96668994e-01 -6.27331510e-02 -5.23366965e-02 9.96438503e-01 -6.63223490e-02 -5.23367301e-02 9.96194482e-01 -6.98762015e-02 -5.23366854e-02 9.95942771e-01 -7.34079331e-02 -5.23366854e-02 9.95686471e-01 -7.67743587e-02 -5.23366146e-02 9.95422184e-01 -8.01413804e-02 -5.23366556e-02 9.95138586e-01 -8.35960731e-02 -5.23366705e-02 9.94830370e-01 -8.71936902e-02 -5.23366965e-02 9.94517922e-01 -9.06608254e-02 -5.23366183e-02 9.94209647e-01 -9.39972028e-02 -5.23366854e-02 9.93871570e-01 -9.75204632e-02 -5.23366705e-02 9.93526220e-01 -1.00972518e-01 -5.23366965e-02 9.93165195e-01 -1.04462005e-01 -5.23366854e-02 9.92790520e-01 -1.07965119e-01 -5.23367301e-02 9.92405415e-01 -1.11453407e-01 -5.23366295e-02 9.92020309e-01 -1.14821285e-01 -5.23366928e-02 9.91607130e-01 -1.18337624e-01 -5.23367152e-02 9.91184294e-01 -1.21830069e-01 -5.23366183e-02 9.90752637e-01 -1.25309840e-01 -5.23367487e-02 9.90296662e-01 -1.28837138e-01 -5.23366667e-02 9.89857852e-01 -1.32171839e-01 -5.23366444e-02 9.89388466e-01 -1.35656372e-01 -5.23367226e-02 9.88898516e-01 -1.39177114e-01 -5.23366444e-02 9.88411486e-01 -1.42581418e-01 -5.23366071e-02 9.87912297e-01 -1.46004975e-01 -5.23367226e-02 9.87391472e-01 -1.49475932e-01 -5.23366518e-02 9.86868560e-01 -1.52909011e-01 -5.23367301e-02 9.86323774e-01 -1.56370863e-01 -5.23365922e-02 9.85777855e-01 -1.59788921e-01 -5.23367226e-02 9.85214829e-01 -1.63220435e-01 -5.23366183e-02 9.84632850e-01 -1.66702569e-01 -5.23367040e-02 9.84034061e-01 -1.70186356e-01 -5.23366928e-02 9.83436108e-01 -1.73637360e-01 -5.23366854e-02 9.82839584e-01 -1.76979095e-01 -5.23366556e-02 9.82224882e-01 -1.80328354e-01 -5.23366965e-02 9.81593907e-01 -1.83746934e-01 -5.23366854e-02 9.80928659e-01 -1.87257931e-01 -5.23367226e-02 9.80256736e-01 -1.90753430e-01 -5.23366854e-02 9.79585409e-01 -1.94166943e-01 -5.23367003e-02 9.78917718e-01 -1.97505891e-01 -5.23366556e-02 9.78239954e-01 -2.00838476e-01 -5.23366854e-02 9.77524102e-01 -2.04290912e-01 -5.23366705e-02 9.76789951e-01 -2.07779735e-01 -5.23367338e-02 9.76067185e-01 -2.11151257e-01 -5.23366295e-02 9.75322366e-01 -2.14559481e-01 -5.23367263e-02 9.74564075e-01 -2.17978507e-01 -5.23366407e-02 9.73799109e-01 -2.21370980e-01 -5.23366965e-02 9.73023653e-01 -2.24757180e-01 -5.23366518e-02 9.72229719e-01 -2.28174478e-01 -5.23367338e-02 9.71423984e-01 -2.31576353e-01 -5.23366444e-02 9.70638216e-01 -2.34853581e-01 -5.23366965e-02 9.69788849e-01 -2.38328636e-01 -5.23367263e-02 9.68950927e-01 -2.41703227e-01 -5.23366369e-02 9.68097687e-01 -2.45101765e-01 -5.23367375e-02 9.67222452e-01 -2.48536706e-01 -5.23366556e-02 9.66373920e-01 -2.51813293e-01 -5.23366779e-02 9.65487301e-01 -2.55202025e-01 -5.23367301e-02 9.64580834e-01 -2.58600950e-01 -5.23366407e-02 9.63709593e-01 -2.61829883e-01 -5.23366965e-02 9.62757766e-01 -2.65299976e-01 -5.23367412e-02 9.61820483e-01 -2.68687367e-01 -5.23366332e-02 9.60884333e-01 -2.72017151e-01 -5.23367301e-02 9.59899724e-01 -2.75467575e-01 -5.23366965e-02 9.58952367e-01 -2.78742254e-01 -5.23366183e-02 9.58008885e-01 -2.81971306e-01 -5.23366965e-02 9.57000494e-01 -2.85383463e-01 -5.23367263e-02 9.55966771e-01 -2.88817078e-01 -5.23367003e-02 9.54941690e-01 -2.92196482e-01 -5.23366965e-02 9.53943074e-01 -2.95436710e-01 -5.23366295e-02 9.52939630e-01 -2.98655510e-01 -5.23366854e-02 9.51892912e-01 -3.01979899e-01 -5.23366965e-02 9.50808942e-01 -3.05376053e-01 -5.23367263e-02 9.49703693e-01 -3.08792055e-01 -5.23366965e-02 9.48627234e-01 -3.12082738e-01 -5.23366965e-02 9.47549462e-01 -3.15340161e-01 -5.23366481e-02 9.46475685e-01 -3.18550438e-01 -5.23366854e-02 9.45354760e-01 -3.21863383e-01 -5.23366965e-02 9.44204807e-01 -3.25219840e-01 -5.23367152e-02 9.43059802e-01 -3.28517437e-01 -5.23366034e-02 9.41912293e-01 -3.31800520e-01 -5.23366965e-02 9.40749109e-01 -3.35085094e-01 -5.23366071e-02 9.39575136e-01 -3.38362694e-01 -5.23367301e-02 9.38376665e-01 -3.41675580e-01 -5.23366518e-02 9.37179327e-01 -3.44927430e-01 -5.23367077e-02 9.35961723e-01 -3.48201275e-01 -5.23366518e-02 9.34775174e-01 -3.51380646e-01 -5.23366965e-02 9.33544159e-01 -3.54649603e-01 -5.23366854e-02 9.32276189e-01 -3.57997239e-01 -5.23367189e-02 9.30998683e-01 -3.61275524e-01 -5.23366332e-02 9.29748714e-01 -3.64501119e-01 -5.23367263e-02 9.28460836e-01 -3.67762238e-01 -5.23366258e-02 9.27185535e-01 -3.70968223e-01 -5.23367301e-02 9.25877094e-01 -3.74219269e-01 -5.23366407e-02 9.24610078e-01 -3.77338499e-01 -5.23366854e-02 9.23255086e-01 -3.80641341e-01 -5.23367412e-02 9.21911240e-01 -3.83884758e-01 -5.23366369e-02 9.20566320e-01 -3.87099952e-01 -5.23367412e-02 9.19160485e-01 -3.90421391e-01 -5.23366965e-02 9.17833209e-01 -3.93529117e-01 -5.23366295e-02 9.16496396e-01 -3.96638513e-01 -5.23366928e-02 9.15080249e-01 -3.99900705e-01 -5.23367226e-02 9.13640440e-01 -4.03176427e-01 -5.23366854e-02 9.12219107e-01 -4.06382084e-01 -5.23366965e-02 9.10818398e-01 -4.09512013e-01 -5.23366556e-02 9.09418762e-01 -4.12605137e-01 -5.23366779e-02 9.07997251e-01 -4.15721595e-01 -5.23366854e-02 9.06498075e-01 -4.18985754e-01 -5.23367263e-02 9.05005872e-01 -4.22199965e-01 -5.23366705e-02 9.03512359e-01 -4.25383389e-01 -5.23366742e-02 9.02052343e-01 -4.28474009e-01 -5.23366556e-02 9.00593698e-01 -4.31528509e-01 -5.23366965e-02 8.99067223e-01 -4.34709460e-01 -5.23367077e-02 8.97503734e-01 -4.37927157e-01 -5.23366965e-02 8.95963132e-01 -4.41065013e-01 -5.23366705e-02 8.94428134e-01 -4.44171876e-01 -5.23367263e-02 8.92880857e-01 -4.47271615e-01 -5.23366518e-02 8.91360164e-01 -4.50298578e-01 -5.23366854e-02 8.89797449e-01 -4.53378439e-01 -5.23366965e-02 8.88156056e-01 -4.56587851e-01 -5.23367375e-02 8.86540890e-01 -4.59706604e-01 -5.23366407e-02 8.84979665e-01 -4.62713242e-01 -5.23367040e-02 8.83368134e-01 -4.65778679e-01 -5.23366854e-02 8.81678939e-01 -4.68971521e-01 -5.23367561e-02 8.80039811e-01 -4.72038120e-01 -5.23366258e-02 8.78403604e-01 -4.75077718e-01 -5.23367487e-02 8.76719177e-01 -4.78180885e-01 -5.23366444e-02 8.75102460e-01 -4.81130868e-01 -5.23367040e-02 8.73416126e-01 -4.84180927e-01 -5.23367003e-02 8.71677935e-01 -4.87306088e-01 -5.23367338e-02 8.69971693e-01 -4.90346551e-01 -5.23366556e-02 8.68263304e-01 -4.93364006e-01 -5.23367226e-02 8.66530001e-01 -4.96405154e-01 -5.23366556e-02 8.64795983e-01 -4.99418318e-01 -5.23367375e-02 8.63013864e-01 -5.02490878e-01 -5.23366854e-02 8.61296892e-01 -5.05428851e-01 -5.23366928e-02 8.59558046e-01 -5.08379042e-01 -5.23366891e-02 8.57776105e-01 -5.11378109e-01 -5.23366965e-02 8.55944991e-01 -5.14441788e-01 -5.23367487e-02 8.54084909e-01 -5.17519534e-01 -5.23367077e-02 8.52316022e-01 -5.20431161e-01 -5.23366556e-02 8.50547373e-01 -5.23314536e-01 -5.23367040e-02 8.48712564e-01 -5.26288927e-01 -5.23366965e-02 8.46838772e-01 -5.29298365e-01 -5.23367375e-02 8.44924629e-01 -5.32346547e-01 -5.23366965e-02 8.43065143e-01 -5.35285890e-01 -5.23366965e-02 8.41251373e-01 -5.38130581e-01 -5.23366556e-02 8.39371741e-01 -5.41060805e-01 -5.23367412e-02 8.37419868e-01 -5.44074535e-01 -5.23366965e-02 8.35507870e-01 -5.47005236e-01 -5.23366965e-02 8.33591878e-01 -5.49921215e-01 -5.23366705e-02 8.31720889e-01 -5.52743077e-01 -5.23366407e-02 8.29849303e-01 -5.55553198e-01 -5.23366965e-02 8.27898920e-01 -5.58458626e-01 -5.23367077e-02 8.25898230e-01 -5.61411262e-01 -5.23367003e-02 8.23888838e-01 -5.64354599e-01 -5.23366854e-02 8.21911931e-01 -5.67232609e-01 -5.23366854e-02 8.19962204e-01 -5.70043504e-01 -5.23366444e-02 8.17978919e-01 -5.72885871e-01 -5.23367189e-02 8.15975070e-01 -5.75739741e-01 -5.23366556e-02 8.13962281e-01 -5.78581512e-01 -5.23367338e-02 8.11922848e-01 -5.81440568e-01 -5.23366556e-02 8.09929192e-01 -5.84207773e-01 -5.23366854e-02 8.07885051e-01 -5.87038875e-01 -5.23366965e-02 8.05835962e-01 -5.89844525e-01 -5.23366928e-02 8.03735554e-01 -5.92704952e-01 -5.23367375e-02 8.01591814e-01 -5.95601320e-01 -5.23366965e-02 7.99580216e-01 -5.98295152e-01 -5.23366369e-02 7.97500432e-01 -6.01069629e-01 -5.23367450e-02 7.95380414e-01 -6.03869975e-01 -5.23366444e-02 7.93292999e-01 -6.06611788e-01 -5.23367263e-02 7.91175067e-01 -6.09369040e-01 -5.23366556e-02 7.89075017e-01 -6.12086415e-01 -5.23366965e-02 7.86880076e-01 -6.14905477e-01 -5.23367040e-02 7.84683406e-01 -6.17707789e-01 -5.23367114e-02 7.82552063e-01 -6.20402634e-01 -5.23366518e-02 7.80440748e-01 -6.23058677e-01 -5.23367040e-02 7.78277040e-01 -6.25760376e-01 -5.23366965e-02 7.76025712e-01 -6.28552020e-01 -5.23367487e-02 7.73812294e-01 -6.31268084e-01 -5.23366556e-02 7.71673620e-01 -6.33884907e-01 -5.23367003e-02 7.69446671e-01 -6.36585414e-01 -5.23366854e-02 7.67242432e-01 -6.39241874e-01 -5.23367003e-02 7.65005112e-01 -6.41918123e-01 -5.23366965e-02 7.62688994e-01 -6.44667089e-01 -5.23367338e-02 7.60418236e-01 -6.47341728e-01 -5.23366407e-02 7.58234501e-01 -6.49900019e-01 -5.23367077e-02 7.55966723e-01 -6.52537346e-01 -5.23366965e-02 7.53637135e-01 -6.55227363e-01 -5.23367152e-02 7.51298726e-01 -6.57905400e-01 -5.23367226e-02 7.48969138e-01 -6.60555959e-01 -5.23366854e-02 7.46691406e-01 -6.63129151e-01 -5.23366369e-02 7.44441092e-01 -6.65655494e-01 -5.23366965e-02 7.42055953e-01 -6.68314278e-01 -5.23367189e-02 7.39724934e-01 -6.70894325e-01 -5.23366518e-02 7.37381995e-01 -6.73467636e-01 -5.23367375e-02 7.35020339e-01 -6.76043153e-01 -5.23366518e-02 7.32723176e-01 -6.78533018e-01 -5.23366965e-02 7.30358005e-01 -6.81076050e-01 -5.23366854e-02 7.27918863e-01 -6.83683693e-01 -5.23367450e-02 7.25521207e-01 -6.86225593e-01 -5.23366444e-02 7.23124802e-01 -6.88757300e-01 -5.23367375e-02 7.20712125e-01 -6.91270649e-01 -5.23366556e-02 7.18319476e-01 -6.93773091e-01 -5.23367450e-02 7.15872109e-01 -6.96292758e-01 -5.23366369e-02 7.13503838e-01 -6.98717117e-01 -5.23366779e-02 7.11005807e-01 -7.01259553e-01 -5.23366071e-02 7.08525896e-01 -7.03760982e-01 -5.23364246e-02 7.06071913e-01 -7.06212521e-01 -5.23364358e-02 7.03538895e-01 -7.08740175e-01 -5.23363054e-02 7.01141536e-01 -7.11112916e-01 -5.23360819e-02 6.98738217e-01 -7.13471532e-01 -5.23361079e-02 6.96238637e-01 -7.15910494e-01 -5.23359813e-02 6.93690002e-01 -7.18372703e-01 -5.23359030e-02 6.91141784e-01 -7.20819831e-01 -5.23357764e-02 6.88694894e-01 -7.23156452e-01 -5.23357876e-02 6.86415911e-01 -7.25320637e-01 -5.23358770e-02 6.83680892e-01 -7.27901399e-01 -5.23359738e-02 6.81597233e-01 -7.29852796e-01 -5.23359701e-02 6.79085255e-01 -7.32191026e-01 -5.23359589e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.54683805e-01 -8.30413103e-01 -5.23359738e-02 5.52288949e-01 -8.32004368e-01 -5.23357838e-02 5.49579501e-01 -8.33805919e-01 -5.23359701e-02 5.46750069e-01 -8.35668147e-01 -5.23363017e-02 5.43761015e-01 -8.37619007e-01 -5.23364246e-02 5.40828288e-01 -8.39514971e-01 -5.23363985e-02 5.37990332e-01 -8.41339886e-01 -5.23365885e-02 5.35029233e-01 -8.43225002e-01 -5.23366146e-02 5.32095134e-01 -8.45082521e-01 -5.23366295e-02 5.29145241e-01 -8.46930921e-01 -5.23366630e-02 5.26183665e-01 -8.48775864e-01 -5.23366369e-02 5.23226380e-01 -8.50599706e-01 -5.23366518e-02 5.20272672e-01 -8.52413476e-01 -5.23366481e-02 5.17306209e-01 -8.54214132e-01 -5.23366854e-02 5.14308989e-01 -8.56023908e-01 -5.23367003e-02 5.11279225e-01 -8.57836068e-01 -5.23367301e-02 5.08261025e-01 -8.59629095e-01 -5.23366965e-02 5.05323052e-01 -8.61359000e-01 -5.23366965e-02 5.02317071e-01 -8.63114893e-01 -5.23366965e-02 4.99232948e-01 -8.64903688e-01 -5.23367375e-02 4.96218771e-01 -8.66635025e-01 -5.23366630e-02 4.93251145e-01 -8.68326962e-01 -5.23366965e-02 4.90249664e-01 -8.70028496e-01 -5.23366965e-02 4.87213671e-01 -8.71729314e-01 -5.23366965e-02 4.84163672e-01 -8.73424649e-01 -5.23366965e-02 4.81110245e-01 -8.75114143e-01 -5.23366965e-02 4.78047580e-01 -8.76792073e-01 -5.23366965e-02 4.74994630e-01 -8.78448009e-01 -5.23366965e-02 4.71929312e-01 -8.80098701e-01 -5.23366965e-02 4.68847692e-01 -8.81743610e-01 -5.23367040e-02 4.65749085e-01 -8.83384883e-01 -5.23367040e-02 4.62607354e-01 -8.85033190e-01 -5.23367375e-02 4.59488004e-01 -8.86654794e-01 -5.23366295e-02 4.56479013e-01 -8.88210952e-01 -5.23366965e-02 4.53357488e-01 -8.89806628e-01 -5.23366965e-02 4.50251460e-01 -8.91383290e-01 -5.23366965e-02 4.47134346e-01 -8.92950892e-01 -5.23367040e-02 4.44031209e-01 -8.94497275e-01 -5.23366854e-02 4.40926164e-01 -8.96032333e-01 -5.23367114e-02 4.37774926e-01 -8.97576988e-01 -5.23366965e-02 4.34638143e-01 -8.99100363e-01 -5.23366965e-02 4.31480438e-01 -9.00617242e-01 -5.23366965e-02 4.28285480e-01 -9.02142763e-01 -5.23367152e-02 4.25126195e-01 -9.03634191e-01 -5.23366854e-02 4.21942383e-01 -9.05128002e-01 -5.23367561e-02 4.18751597e-01 -9.06606674e-01 -5.23366556e-02 4.15696800e-01 -9.08010066e-01 -5.23366965e-02 4.12537575e-01 -9.09452558e-01 -5.23367003e-02 4.09364253e-01 -9.10884798e-01 -5.23366928e-02 4.06058371e-01 -9.12364900e-01 -5.23367636e-02 4.02854979e-01 -9.13781524e-01 -5.23366183e-02 3.99777412e-01 -9.15134311e-01 -5.23367114e-02 3.96579146e-01 -9.16522443e-01 -5.23366965e-02 3.93375129e-01 -9.17899668e-01 -5.23367003e-02 3.90105873e-01 -9.19297099e-01 -5.23367301e-02 3.86911094e-01 -9.20646667e-01 -5.23366854e-02 3.83640826e-01 -9.22014296e-01 -5.23367673e-02 3.80396187e-01 -9.23354506e-01 -5.23366556e-02 3.77296984e-01 -9.24628675e-01 -5.23367040e-02 3.74019265e-01 -9.25958633e-01 -5.23367338e-02 3.70686352e-01 -9.27297771e-01 -5.23367301e-02 3.67412090e-01 -9.28601444e-01 -5.23366965e-02 3.64232719e-01 -9.29851830e-01 -5.23366556e-02 3.61082584e-01 -9.31074381e-01 -5.23367040e-02 3.57825041e-01 -9.32340801e-01 -5.23367077e-02 3.54580194e-01 -9.33571577e-01 -5.23366965e-02 3.51339161e-01 -9.34791803e-01 -5.23366965e-02 3.48037332e-01 -9.36024964e-01 -5.23367077e-02 3.44771534e-01 -9.37236667e-01 -5.23366965e-02 3.41519296e-01 -9.38433468e-01 -5.23367003e-02 3.38255435e-01 -9.39611912e-01 -5.23366965e-02 3.34962785e-01 -9.40793037e-01 -5.23367003e-02 3.31597507e-01 -9.41983342e-01 -5.23367450e-02 3.28282595e-01 -9.43142414e-01 -5.23366556e-02 3.25016290e-01 -9.44275498e-01 -5.23367450e-02 3.21693927e-01 -9.45410490e-01 -5.23366779e-02 3.18470240e-01 -9.46503699e-01 -5.23366965e-02 3.15086901e-01 -9.47633326e-01 -5.23367338e-02 3.11766624e-01 -9.48729157e-01 -5.23366630e-02 3.08444142e-01 -9.49816942e-01 -5.23367412e-02 3.05129975e-01 -9.50887680e-01 -5.23366630e-02 3.01891983e-01 -9.51919675e-01 -5.23367077e-02 2.98584759e-01 -9.52962637e-01 -5.23366965e-02 2.95250475e-01 -9.54001129e-01 -5.23367003e-02 2.91932046e-01 -9.55022275e-01 -5.23367003e-02 2.88504124e-01 -9.56061065e-01 -5.23367301e-02 2.85063595e-01 -9.57093298e-01 -5.23366965e-02 2.81824797e-01 -9.58053589e-01 -5.23366556e-02 2.78480291e-01 -9.59031820e-01 -5.23367450e-02 2.75032252e-01 -9.60025132e-01 -5.23366965e-02 2.71687776e-01 -9.60976124e-01 -5.23367003e-02 2.68423945e-01 -9.61894214e-01 -5.23366444e-02 2.65142202e-01 -9.62801874e-01 -5.23366854e-02 2.61774272e-01 -9.63726342e-01 -5.23366965e-02 2.58407444e-01 -9.64631855e-01 -5.23367003e-02 2.55071223e-01 -9.65519488e-01 -5.23366965e-02 2.51698881e-01 -9.66406941e-01 -5.23367114e-02 2.48241603e-01 -9.67299044e-01 -5.23367226e-02 2.44867221e-01 -9.68156576e-01 -5.23366705e-02 2.41500303e-01 -9.69003320e-01 -5.23367412e-02 2.38088503e-01 -9.69847798e-01 -5.23366742e-02 2.34778136e-01 -9.70655441e-01 -5.23366965e-02 2.31314793e-01 -9.71488893e-01 -5.23367450e-02 2.27922931e-01 -9.72286642e-01 -5.23366742e-02 2.24527270e-01 -9.73076880e-01 -5.23367450e-02 2.21045464e-01 -9.73873019e-01 -5.23366965e-02 2.17738315e-01 -9.74617898e-01 -5.23366556e-02 2.14432031e-01 -9.75349426e-01 -5.23366965e-02 2.11033121e-01 -9.76091146e-01 -5.23366965e-02 2.07623526e-01 -9.76822317e-01 -5.23367040e-02 2.04096377e-01 -9.77567673e-01 -5.23367412e-02 2.00671166e-01 -9.78274524e-01 -5.23366369e-02 1.97366998e-01 -9.78946865e-01 -5.23366965e-02 1.93956807e-01 -9.79627728e-01 -5.23366965e-02 1.90518618e-01 -9.80303049e-01 -5.23366965e-02 1.87011302e-01 -9.80977356e-01 -5.23367524e-02 1.83564961e-01 -9.81627345e-01 -5.23366407e-02 1.80146798e-01 -9.82260585e-01 -5.23367673e-02 1.76697120e-01 -9.82892573e-01 -5.23366444e-02 1.73372552e-01 -9.83484209e-01 -5.23367040e-02 1.69946477e-01 -9.84075606e-01 -5.23367114e-02 1.66493073e-01 -9.84667778e-01 -5.23366965e-02 1.62962988e-01 -9.85257506e-01 -5.23367487e-02 1.59517899e-01 -9.85821128e-01 -5.23366667e-02 1.56186491e-01 -9.86355484e-01 -5.23367003e-02 1.52732044e-01 -9.86896038e-01 -5.23366965e-02 1.49287254e-01 -9.87421215e-01 -5.23367003e-02 1.45760000e-01 -9.87950027e-01 -5.23367263e-02 1.42289117e-01 -9.88454819e-01 -5.23366630e-02 1.38851479e-01 -9.88946259e-01 -5.23367412e-02 1.35288641e-01 -9.89439189e-01 -5.23366965e-02 1.31918892e-01 -9.89890516e-01 -5.23366518e-02 1.28574312e-01 -9.90332484e-01 -5.23366965e-02 1.25119701e-01 -9.90776241e-01 -5.23366854e-02 1.21665813e-01 -9.91205156e-01 -5.23366965e-02 1.18105538e-01 -9.91635859e-01 -5.23367524e-02 1.14628814e-01 -9.92041767e-01 -5.23366444e-02 1.11292467e-01 -9.92422998e-01 -5.23366965e-02 1.07833341e-01 -9.92804170e-01 -5.23366965e-02 1.04375765e-01 -9.93173718e-01 -5.23366965e-02 1.00789331e-01 -9.93543744e-01 -5.23367375e-02 9.73087922e-02 -9.93891001e-01 -5.23366444e-02 9.38584879e-02 -9.94225323e-01 -5.23367450e-02 9.03860927e-02 -9.94543850e-01 -5.23366369e-02 8.69092047e-02 -9.94855940e-01 -5.23367338e-02 8.33352059e-02 -9.95159924e-01 -5.23367003e-02 7.99412280e-02 -9.95439470e-01 -5.23366295e-02 7.64795691e-02 -9.95712459e-01 -5.23367561e-02 7.29826242e-02 -9.95972633e-01 -5.23366630e-02 6.95978478e-02 -9.96214092e-01 -5.23367040e-02 6.61494583e-02 -9.96450484e-01 -5.23367077e-02 6.26733452e-02 -9.96674716e-01 -5.23366965e-02 5.90726808e-02 -9.96895492e-01 -5.23367412e-02 5.56021072e-02 -9.97094929e-01 -5.23366556e-02 5.21287099e-02 -9.97282267e-01 -5.23367375e-02 4.86448519e-02 -9.97458160e-01 -5.23366444e-02 4.51723039e-02 -9.97621953e-01 -5.23367487e-02 4.15895209e-02 -9.97778118e-01 -5.23366965e-02 3.81906703e-02 -9.97912109e-01 -5.23366518e-02 3.48169170e-02 -9.98035848e-01 -5.23366965e-02 3.12462114e-02 -9.98154402e-01 -5.23367263e-02 2.77411751e-02 -9.98258591e-01 -5.23366630e-02 2.42712349e-02 -9.98351812e-01 -5.23367375e-02 2.07692906e-02 -9.98425007e-01 -5.23366556e-02 1.73770208e-02 -9.98496950e-01 -5.23366965e-02 1.38248485e-02 -9.98542726e-01 -5.23367450e-02 1.03163673e-02 -9.98590529e-01 -5.23366630e-02 6.92021661e-03 -9.98626709e-01 -5.23366965e-02 3.44692543e-03 -9.98643100e-01 -5.23366965e-02 -3.31448609e-05 -9.98644412e-01 -5.23366965e-02 -3.49919195e-03 -9.98643458e-01 -5.23367226e-02 -6.98196609e-03 -9.98626590e-01 -5.23367003e-02 -1.05681671e-02 -9.98590529e-01 -5.23367599e-02 -1.40597718e-02 -9.98539746e-01 -5.23366444e-02 -1.75383557e-02 -9.98496354e-01 -5.23367450e-02 -2.11372338e-02 -9.98418093e-01 -5.23367152e-02 -2.45340802e-02 -9.98343766e-01 -5.23366630e-02 -2.79015936e-02 -9.98254776e-01 -5.23366965e-02 -3.13743167e-02 -9.98151600e-01 -5.23367114e-02 -3.49588953e-02 -9.98033226e-01 -5.23367636e-02 -3.85622904e-02 -9.97900069e-01 -5.23367077e-02 -4.19565998e-02 -9.97762740e-01 -5.23366556e-02 -4.53186855e-02 -9.97614861e-01 -5.23367003e-02 -4.88206930e-02 -9.97450471e-01 -5.23367114e-02 -5.23030497e-02 -9.97271895e-01 -5.23367040e-02 -5.58453500e-02 -9.97082472e-01 -5.23367450e-02 -5.93559109e-02 -9.96878028e-01 -5.23366630e-02 -6.28167614e-02 -9.96666074e-01 -5.23367487e-02 -6.63226843e-02 -9.96437490e-01 -5.23366556e-02 -6.97064400e-02 -9.96205747e-01 -5.23366965e-02 -7.32678100e-02 -9.95952547e-01 -5.23367412e-02 -7.67586976e-02 -9.95688677e-01 -5.23366630e-02 -8.02028403e-02 -9.95418668e-01 -5.23367375e-02 -8.36890042e-02 -9.95130062e-01 -5.23366854e-02 -8.70765299e-02 -9.94840384e-01 -5.23367003e-02 -9.05600712e-02 -9.94528234e-01 -5.23367003e-02 -9.40198898e-02 -9.94208813e-01 -5.23367152e-02 -9.75720882e-02 -9.93868172e-01 -5.23367487e-02 -1.01043522e-01 -9.93519366e-01 -5.23366444e-02 -1.04491733e-01 -9.93162870e-01 -5.23367524e-02 -1.08038515e-01 -9.92781937e-01 -5.23366965e-02 -1.11427911e-01 -9.92408276e-01 -5.23366705e-02 -1.14807174e-01 -9.92022514e-01 -5.23367003e-02 -1.18264973e-01 -9.91615236e-01 -5.23367040e-02 -1.21734492e-01 -9.91195440e-01 -5.23367077e-02 -1.25275239e-01 -9.90757704e-01 -5.23367487e-02 -1.28749236e-01 -9.90308225e-01 -5.23366518e-02 -1.32100224e-01 -9.89868701e-01 -5.23367077e-02 -1.35563955e-01 -9.89399791e-01 -5.23366965e-02 -1.39005199e-01 -9.88923311e-01 -5.23367040e-02 -1.42542496e-01 -9.88419950e-01 -5.23367487e-02 -1.45994306e-01 -9.87913191e-01 -5.23366630e-02 -1.49436459e-01 -9.87398922e-01 -5.23367263e-02 -1.52874440e-01 -9.86873031e-01 -5.23366556e-02 -1.56223744e-01 -9.86347914e-01 -5.23367003e-02 -1.59669816e-01 -9.85796511e-01 -5.23366965e-02 -1.63105577e-01 -9.85235333e-01 -5.23367003e-02 -1.66660085e-01 -9.84639823e-01 -5.23367524e-02 -1.70090571e-01 -9.84050035e-01 -5.23366444e-02 -1.73420399e-01 -9.83474672e-01 -5.23366965e-02 -1.76870570e-01 -9.82859015e-01 -5.23367114e-02 -1.80297598e-01 -9.82231021e-01 -5.23367003e-02 -1.83807552e-01 -9.81584787e-01 -5.23367375e-02 -1.87239990e-01 -9.80933189e-01 -5.23366593e-02 -1.90573767e-01 -9.80289817e-01 -5.23366965e-02 -1.93981573e-01 -9.79623258e-01 -5.23366965e-02 -1.97488159e-01 -9.78923023e-01 -5.23367338e-02 -2.00899288e-01 -9.78226185e-01 -5.23366258e-02 -2.04213902e-01 -9.77540731e-01 -5.23366928e-02 -2.07649663e-01 -9.76817846e-01 -5.23367003e-02 -2.11133987e-01 -9.76071000e-01 -5.23367450e-02 -2.14569315e-01 -9.75317538e-01 -5.23366481e-02 -2.17857897e-01 -9.74592686e-01 -5.23367003e-02 -2.21279442e-01 -9.73819852e-01 -5.23367077e-02 -2.24685982e-01 -9.73038316e-01 -5.23367040e-02 -2.28175163e-01 -9.72231030e-01 -5.23367636e-02 -2.31580377e-01 -9.71422732e-01 -5.23366444e-02 -2.34860182e-01 -9.70635712e-01 -5.23366965e-02 -2.38253549e-01 -9.69807327e-01 -5.23366965e-02 -2.41634294e-01 -9.68969047e-01 -5.23366965e-02 -2.45054275e-01 -9.68109667e-01 -5.23367338e-02 -2.48468846e-01 -9.67239857e-01 -5.23366854e-02 -2.51884311e-01 -9.66355979e-01 -5.23367412e-02 -2.55243629e-01 -9.65474963e-01 -5.23366444e-02 -2.58596539e-01 -9.64582741e-01 -5.23367375e-02 -2.62044877e-01 -9.63652253e-01 -5.23367040e-02 -2.65347332e-01 -9.62745368e-01 -5.23366630e-02 -2.68694609e-01 -9.61818933e-01 -5.23367524e-02 -2.72051185e-01 -9.60873425e-01 -5.23366556e-02 -2.75294274e-01 -9.59949493e-01 -5.23367003e-02 -2.78647840e-01 -9.58981574e-01 -5.23367077e-02 -2.81995118e-01 -9.58002031e-01 -5.23367003e-02 -2.85319954e-01 -9.57018852e-01 -5.23366965e-02 -2.88654119e-01 -9.56015766e-01 -5.23367152e-02 -2.92015344e-01 -9.54993904e-01 -5.23367077e-02 -2.95421600e-01 -9.53949690e-01 -5.23367561e-02 -2.98758447e-01 -9.52906072e-01 -5.23366481e-02 -3.02088946e-01 -9.51858342e-01 -5.23367412e-02 -3.05406004e-01 -9.50798810e-01 -5.23366556e-02 -3.08636010e-01 -9.49754477e-01 -5.23366928e-02 -3.12047690e-01 -9.48639810e-01 -5.23367524e-02 -3.15340847e-01 -9.47548926e-01 -5.23366742e-02 -3.18639278e-01 -9.46447909e-01 -5.23367375e-02 -3.21957856e-01 -9.45321023e-01 -5.23366630e-02 -3.25165659e-01 -9.44223344e-01 -5.23366965e-02 -3.28504592e-01 -9.43065703e-01 -5.23367301e-02 -3.31804514e-01 -9.41911876e-01 -5.23366854e-02 -3.35111260e-01 -9.40739930e-01 -5.23367487e-02 -3.38415086e-01 -9.39553857e-01 -5.23366556e-02 -3.41658145e-01 -9.38385010e-01 -5.23367412e-02 -3.44955176e-01 -9.37167645e-01 -5.23366630e-02 -3.48138094e-01 -9.35986876e-01 -5.23366965e-02 -3.51467997e-01 -9.34744120e-01 -5.23367375e-02 -3.54716569e-01 -9.33518171e-01 -5.23366518e-02 -3.57985348e-01 -9.32280183e-01 -5.23367450e-02 -3.61324430e-01 -9.30982232e-01 -5.23367114e-02 -3.64487350e-01 -9.29752052e-01 -5.23366556e-02 -3.67640853e-01 -9.28510308e-01 -5.23367077e-02 -3.70875418e-01 -9.27221239e-01 -5.23366965e-02 -3.74125600e-01 -9.25915360e-01 -5.23366965e-02 -3.77431363e-01 -9.24573123e-01 -5.23367599e-02 -3.80665213e-01 -9.23242629e-01 -5.23366556e-02 -3.83809507e-01 -9.21944141e-01 -5.23366965e-02 -3.87005448e-01 -9.20606017e-01 -5.23366965e-02 -3.90211850e-01 -9.19250488e-01 -5.23367040e-02 -3.93500566e-01 -9.17847395e-01 -5.23367375e-02 -3.96713585e-01 -9.16462660e-01 -5.23366369e-02 -3.99913788e-01 -9.15075421e-01 -5.23367412e-02 -4.03116345e-01 -9.13665891e-01 -5.23366779e-02 -4.06232119e-01 -9.12285984e-01 -5.23367003e-02 -4.09478575e-01 -9.10835028e-01 -5.23367487e-02 -4.12666261e-01 -9.09391701e-01 -5.23366407e-02 -4.15797949e-01 -9.07963455e-01 -5.23367450e-02 -4.18982714e-01 -9.06497955e-01 -5.23366407e-02 -4.22054738e-01 -9.05074298e-01 -5.23367077e-02 -4.25221890e-01 -9.03589666e-01 -5.23367003e-02 -4.28469330e-01 -9.02056575e-01 -5.23367487e-02 -4.31598276e-01 -9.00560141e-01 -5.23366705e-02 -4.34662223e-01 -8.99090350e-01 -5.23367189e-02 -4.37871248e-01 -8.97531629e-01 -5.23367599e-02 -4.41104800e-01 -8.95943522e-01 -5.23366965e-02 -4.44149524e-01 -8.94438624e-01 -5.23366630e-02 -4.47186202e-01 -8.92925024e-01 -5.23366965e-02 -4.50288981e-01 -8.91365469e-01 -5.23367114e-02 -4.53419119e-01 -8.89775634e-01 -5.23366965e-02 -4.56588656e-01 -8.88153434e-01 -5.23367412e-02 -4.59674329e-01 -8.86558175e-01 -5.23366444e-02 -4.62668598e-01 -8.85003448e-01 -5.23367114e-02 -4.65780854e-01 -8.83368552e-01 -5.23367040e-02 -4.68851507e-01 -8.81741464e-01 -5.23367077e-02 -4.71998811e-01 -8.80062819e-01 -5.23367412e-02 -4.75081474e-01 -8.78398895e-01 -5.23366407e-02 -4.78133649e-01 -8.76745522e-01 -5.23367375e-02 -4.81209159e-01 -8.75058830e-01 -5.23366816e-02 -4.84233290e-01 -8.73387694e-01 -5.23367375e-02 -4.87362593e-01 -8.71645510e-01 -5.23366965e-02 -4.90333438e-01 -8.69979501e-01 -5.23366854e-02 -4.93349701e-01 -8.68272185e-01 -5.23367412e-02 -4.96370226e-01 -8.66550505e-01 -5.23366854e-02 -4.99342591e-01 -8.64839613e-01 -5.23367040e-02 -5.02430081e-01 -8.63050818e-01 -5.23367673e-02 -5.05458772e-01 -8.61279845e-01 -5.23366630e-02 -5.08445203e-01 -8.59519899e-01 -5.23367561e-02 -5.11444509e-01 -8.57736290e-01 -5.23366630e-02 -5.14404476e-01 -8.55966687e-01 -5.23367561e-02 -5.17417729e-01 -8.54146600e-01 -5.23366854e-02 -5.20384490e-01 -8.52346301e-01 -5.23367450e-02 -5.23447871e-01 -8.50465953e-01 -5.23367152e-02 -5.26340127e-01 -8.48679721e-01 -5.23366630e-02 -5.29204011e-01 -8.46896529e-01 -5.23366965e-02 -5.32249510e-01 -8.44986081e-01 -5.23367710e-02 -5.35268128e-01 -8.43076706e-01 -5.23367263e-02 -5.38215458e-01 -8.41198027e-01 -5.23367003e-02 -5.41066051e-01 -8.39365959e-01 -5.23366705e-02 -5.43918371e-01 -8.37522268e-01 -5.23367189e-02 -5.46857476e-01 -8.35603893e-01 -5.23367040e-02 -5.49748719e-01 -8.33706617e-01 -5.23367040e-02 -5.52649975e-01 -8.31784248e-01 -5.23367114e-02 -5.55544019e-01 -8.29855502e-01 -5.23367077e-02 -5.58510840e-01 -8.27864349e-01 -5.23367636e-02 -5.61440825e-01 -8.25877607e-01 -5.23366891e-02 -5.64240336e-01 -8.23968947e-01 -5.23366965e-02 -5.67165017e-01 -8.21958959e-01 -5.23367636e-02 -5.70027232e-01 -8.19975436e-01 -5.23366556e-02 -5.72886705e-01 -8.17979813e-01 -5.23367673e-02 -5.75829268e-01 -8.15912008e-01 -5.23366854e-02 -5.78589797e-01 -8.13954890e-01 -5.23366332e-02 -5.81397951e-01 -8.11953008e-01 -5.23367263e-02 -5.84222615e-01 -8.09918821e-01 -5.23366854e-02 -5.87042570e-01 -8.07882011e-01 -5.23367412e-02 -5.89943588e-01 -8.05764556e-01 -5.23367189e-02 -5.92792809e-01 -8.03670585e-01 -5.23367189e-02 -5.95517576e-01 -8.01653147e-01 -5.23366556e-02 -5.98216057e-01 -7.99640536e-01 -5.23367114e-02 -6.01010025e-01 -7.97543585e-01 -5.23367040e-02 -6.03861213e-01 -7.95389175e-01 -5.23367487e-02 -6.06648803e-01 -7.93263197e-01 -5.23366556e-02 -6.09416008e-01 -7.91139126e-01 -5.23367785e-02 -6.12177134e-01 -7.89004207e-01 -5.23366556e-02 -6.14836514e-01 -7.86933661e-01 -5.23367152e-02 -6.17669404e-01 -7.84715354e-01 -5.23367524e-02 -6.20408356e-01 -7.82547534e-01 -5.23366854e-02 -6.23124838e-01 -7.80389845e-01 -5.23367561e-02 -6.25871003e-01 -7.78187037e-01 -5.23366854e-02 -6.28503501e-01 -7.76064277e-01 -5.23367040e-02 -6.31269336e-01 -7.73815334e-01 -5.23367561e-02 -6.33984685e-01 -7.71590531e-01 -5.23366556e-02 -6.36598885e-01 -7.69436777e-01 -5.23367114e-02 -6.39275432e-01 -7.67215192e-01 -5.23367189e-02 -6.41980231e-01 -7.64951110e-01 -5.23367412e-02 -6.44731820e-01 -7.62633622e-01 -5.23367226e-02 -6.47350192e-01 -7.60411084e-01 -5.23366854e-02 -6.49917066e-01 -7.58219838e-01 -5.23367040e-02 -6.52567804e-01 -7.55940855e-01 -5.23367114e-02 -6.55258596e-01 -7.53610611e-01 -5.23367561e-02 -6.57952011e-01 -7.51257598e-01 -5.23367040e-02 -6.60522997e-01 -7.48997808e-01 -5.23366518e-02 -6.63049698e-01 -7.46763587e-01 -5.23366965e-02 -6.65649652e-01 -7.44446218e-01 -5.23367003e-02 -6.68242812e-01 -7.42119372e-01 -5.23366965e-02 -6.70905769e-01 -7.39715099e-01 -5.23367561e-02 -6.73502266e-01 -7.37347424e-01 -5.23366630e-02 -6.76051497e-01 -7.35016525e-01 -5.23367301e-02 -6.78609967e-01 -7.32651532e-01 -5.23366705e-02 -6.81153357e-01 -7.30288684e-01 -5.23367748e-02 -6.83771670e-01 -7.27834880e-01 -5.23366965e-02 -6.86246693e-01 -7.25501657e-01 -5.23366854e-02 -6.88765883e-01 -7.23116338e-01 -5.23367524e-02 -6.91294372e-01 -7.20689118e-01 -5.23366630e-02 -6.93750143e-01 -7.18340993e-01 -5.23367189e-02 -6.96266115e-01 -7.15902209e-01 -5.23367375e-02 -6.98755741e-01 -7.13466406e-01 -5.23366965e-02 -7.01222479e-01 -7.11044729e-01 -5.23367040e-02 -7.03696489e-01 -7.08599210e-01 -5.23367114e-02 -7.06209898e-01 -7.06074774e-01 -5.23367301e-02 -7.08691359e-01 -7.03602612e-01 -5.23366854e-02 -7.11146235e-01 -7.01121330e-01 -5.23367599e-02 -7.13596106e-01 -6.98623598e-01 -5.23366779e-02 -7.15966761e-01 -6.96198285e-01 -5.23367040e-02 -7.18413830e-01 -6.93675399e-01 -5.23367301e-02 -7.20877945e-01 -6.91098154e-01 -5.23367450e-02 -7.23290563e-01 -6.88581347e-01 -5.23366854e-02 -7.25697756e-01 -6.86039388e-01 -5.23367412e-02 -7.28059232e-01 -6.83531523e-01 -5.23366705e-02 -7.30363846e-01 -6.81068778e-01 -5.23366965e-02 -7.32779145e-01 -6.78475082e-01 -5.23367412e-02 -7.35223055e-01 -6.75826967e-01 -5.23367338e-02 -7.37534463e-01 -6.73298120e-01 -5.23366444e-02 -7.39794910e-01 -6.70816600e-01 -5.23367189e-02 -7.42132485e-01 -6.68228805e-01 -5.23367040e-02 -7.44532406e-01 -6.65556312e-01 -5.23367785e-02 -7.46877015e-01 -6.62921369e-01 -5.23366369e-02 -7.49162138e-01 -6.60338640e-01 -5.23367450e-02 -7.51466036e-01 -6.57712281e-01 -5.23366481e-02 -7.53759146e-01 -6.55085742e-01 -5.23367450e-02 -7.56103754e-01 -6.52378619e-01 -5.23366965e-02 -7.58323908e-01 -6.49796128e-01 -5.23366854e-02 -7.60533810e-01 -6.47206187e-01 -5.23366965e-02 -7.62778699e-01 -6.44562781e-01 -5.23367040e-02 -7.65070617e-01 -6.41838133e-01 -5.23367114e-02 -7.67352521e-01 -6.39111400e-01 -5.23367189e-02 -7.69553125e-01 -6.36454344e-01 -5.23366593e-02 -7.71716356e-01 -6.33836508e-01 -5.23367189e-02 -7.73924172e-01 -6.31134927e-01 -5.23367152e-02 -7.76125669e-01 -6.28425956e-01 -5.23367003e-02 -7.78359413e-01 -6.25659704e-01 -5.23367636e-02 -7.80610502e-01 -6.22846067e-01 -5.23367040e-02 -7.82774866e-01 -6.20123446e-01 -5.23367040e-02 -7.84877419e-01 -6.17460251e-01 -5.23366593e-02 -7.86952257e-01 -6.14815056e-01 -5.23366965e-02 -7.89162576e-01 -6.11974895e-01 -5.23367599e-02 -7.91341424e-01 -6.09154522e-01 -5.23366965e-02 -7.93469548e-01 -6.06379926e-01 -5.23367301e-02 -7.95543969e-01 -6.03654087e-01 -5.23366705e-02 -7.97586977e-01 -6.00955963e-01 -5.23366965e-02 -7.99730957e-01 -5.98097444e-01 -5.23367450e-02 -8.01815033e-01 -5.95298946e-01 -5.23366816e-02 -8.03841591e-01 -5.92560172e-01 -5.23367301e-02 -8.05908799e-01 -5.89744508e-01 -5.23366854e-02 -8.07967246e-01 -5.86923420e-01 -5.23367338e-02 -8.10057223e-01 -5.84033370e-01 -5.23367263e-02 -8.12083423e-01 -5.81215322e-01 -5.23366705e-02 -8.14055562e-01 -5.78449905e-01 -5.23367152e-02 -8.16064477e-01 -5.75616598e-01 -5.23367152e-02 -8.18093896e-01 -5.72724462e-01 -5.23367226e-02 -8.20125043e-01 -5.69811821e-01 -5.23367338e-02 -8.22099268e-01 -5.66961050e-01 -5.23366854e-02 -8.24019015e-01 -5.64165890e-01 -5.23367003e-02 -8.25973630e-01 -5.61301172e-01 -5.23366965e-02 -8.27917755e-01 -5.58430493e-01 -5.23367040e-02 -8.29909384e-01 -5.55464745e-01 -5.23367710e-02 -8.31860244e-01 -5.52534699e-01 -5.23366444e-02 -8.33783150e-01 -5.49633443e-01 -5.23367561e-02 -8.35706532e-01 -5.46699584e-01 -5.23366556e-02 -8.37546110e-01 -5.43878794e-01 -5.23366854e-02 -8.39435697e-01 -5.40960014e-01 -5.23367077e-02 -8.41362536e-01 -5.37956893e-01 -5.23367375e-02 -8.43269110e-01 -5.34962833e-01 -5.23366630e-02 -8.45082581e-01 -5.32098889e-01 -5.23366965e-02 -8.46900523e-01 -5.29193699e-01 -5.23367040e-02 -8.48768890e-01 -5.26198983e-01 -5.23367152e-02 -8.50598872e-01 -5.23230016e-01 -5.23366965e-02 -8.52415264e-01 -5.20270705e-01 -5.23366965e-02 -8.54222357e-01 -5.17293632e-01 -5.23366965e-02 -8.56075227e-01 -5.14226317e-01 -5.23367561e-02 -8.57914805e-01 -5.11145592e-01 -5.23367040e-02 -8.59646261e-01 -5.08228540e-01 -5.23366667e-02 -8.61416519e-01 -5.05225778e-01 -5.23367636e-02 -8.63175392e-01 -5.02210140e-01 -5.23366854e-02 -8.64898562e-01 -4.99243140e-01 -5.23367338e-02 -8.66624475e-01 -4.96237755e-01 -5.23366854e-02 -8.68325472e-01 -4.93253857e-01 -5.23367003e-02 -8.70044410e-01 -4.90222842e-01 -5.23367040e-02 -8.71752739e-01 -4.87171263e-01 -5.23367003e-02 -8.73450458e-01 -4.84117836e-01 -5.23367189e-02 -8.75165701e-01 -4.81017083e-01 -5.23367487e-02 -8.76858234e-01 -4.77927297e-01 -5.23366965e-02 -8.78496587e-01 -4.74902987e-01 -5.23366965e-02 -8.80121052e-01 -4.71887887e-01 -5.23367040e-02 -8.81800354e-01 -4.68741000e-01 -5.23367450e-02 -8.83474410e-01 -4.65577990e-01 -5.23367152e-02 -8.85078549e-01 -4.62523520e-01 -5.23366965e-02 -8.86646748e-01 -4.59504902e-01 -5.23366854e-02 -8.88209641e-01 -4.56482053e-01 -5.23367040e-02 -8.89835477e-01 -4.53302950e-01 -5.23367487e-02 -8.91468942e-01 -4.50082600e-01 -5.23367189e-02 -8.92989814e-01 -4.47053909e-01 -5.23366705e-02 -8.94492865e-01 -4.44041193e-01 -5.23367077e-02 -8.96032691e-01 -4.40925539e-01 -5.23367003e-02 -8.97568047e-01 -4.37794030e-01 -5.23367040e-02 -8.99135411e-01 -4.34567630e-01 -5.23367636e-02 -9.00695801e-01 -4.31317985e-01 -5.23367003e-02 -9.02169466e-01 -4.28227305e-01 -5.23366667e-02 -9.03606355e-01 -4.25185770e-01 -5.23367003e-02 -9.05083895e-01 -4.22033757e-01 -5.23366965e-02 -9.06588197e-01 -4.18797731e-01 -5.23367673e-02 -9.08069313e-01 -4.15571779e-01 -5.23366854e-02 -9.09465611e-01 -4.12509620e-01 -5.23366854e-02 -9.10887480e-01 -4.09357667e-01 -5.23367077e-02 -9.12304640e-01 -4.06195253e-01 -5.23367114e-02 -9.13772881e-01 -4.02880907e-01 -5.23367785e-02 -9.15216267e-01 -3.99591029e-01 -5.23366965e-02 -9.16598856e-01 -3.96407425e-01 -5.23367003e-02 -9.17977393e-01 -3.93191367e-01 -5.23367077e-02 -9.19307411e-01 -3.90078723e-01 -5.23366556e-02 -9.20630157e-01 -3.86949480e-01 -5.23367152e-02 -9.21982527e-01 -3.83713037e-01 -5.23366928e-02 -9.23344135e-01 -3.80425870e-01 -5.23367450e-02 -9.24671769e-01 -3.77189070e-01 -5.23366518e-02 -9.25945044e-01 -3.74052733e-01 -5.23366965e-02 -9.27276790e-01 -3.70738357e-01 -5.23367450e-02 -9.28565741e-01 -3.67499352e-01 -5.23366779e-02 -9.29813504e-01 -3.64335239e-01 -5.23367077e-02 -9.31071281e-01 -3.61092150e-01 -5.23367114e-02 -9.32337880e-01 -3.57831806e-01 -5.23367189e-02 -9.33616340e-01 -3.54467124e-01 -5.23367375e-02 -9.34828639e-01 -3.51238340e-01 -5.23366779e-02 -9.36018467e-01 -3.48056883e-01 -5.23367077e-02 -9.37262416e-01 -3.44706178e-01 -5.23367450e-02 -9.38507080e-01 -3.41318339e-01 -5.23366965e-02 -9.39682662e-01 -3.38058144e-01 -5.23366965e-02 -9.40828621e-01 -3.34863007e-01 -5.23366556e-02 -9.41985607e-01 -3.31592977e-01 -5.23367450e-02 -9.43146586e-01 -3.28272790e-01 -5.23366854e-02 -9.44254279e-01 -3.25077355e-01 -5.23367040e-02 -9.45377231e-01 -3.21790934e-01 -5.23367114e-02 -9.46500242e-01 -3.18478912e-01 -5.23367152e-02 -9.47639167e-01 -3.15073371e-01 -5.23367561e-02 -9.48732972e-01 -3.11760664e-01 -5.23366630e-02 -9.49785948e-01 -3.08542103e-01 -5.23367040e-02 -9.50878978e-01 -3.05156976e-01 -5.23367561e-02 -9.51940477e-01 -3.01823467e-01 -5.23366556e-02 -9.52982426e-01 -2.98525602e-01 -5.23367263e-02 -9.54019666e-01 -2.95187354e-01 -5.23366705e-02 -9.55051363e-01 -2.91834950e-01 -5.23367338e-02 -9.56084371e-01 -2.88427651e-01 -5.23367003e-02 -9.57061112e-01 -2.85168946e-01 -5.23366593e-02 -9.58051622e-01 -2.81831115e-01 -5.23367226e-02 -9.59028363e-01 -2.78486103e-01 -5.23366556e-02 -9.59993541e-01 -2.75138557e-01 -5.23367412e-02 -9.60946679e-01 -2.71788955e-01 -5.23366518e-02 -9.61868942e-01 -2.68513769e-01 -5.23366965e-02 -9.62805033e-01 -2.65135854e-01 -5.23366965e-02 -9.63722110e-01 -2.61786997e-01 -5.23366965e-02 -9.64650393e-01 -2.58341730e-01 -5.23367412e-02 -9.65574205e-01 -2.54869878e-01 -5.23366965e-02 -9.66453910e-01 -2.51509249e-01 -5.23367040e-02 -9.67307389e-01 -2.48210907e-01 -5.23366556e-02 -9.68132496e-01 -2.44961619e-01 -5.23367003e-02 -9.69008982e-01 -2.41475314e-01 -5.23367561e-02 -9.69873130e-01 -2.37989530e-01 -5.23366965e-02 -9.70697880e-01 -2.34608814e-01 -5.23366965e-02 -9.71485734e-01 -2.31318116e-01 -5.23366556e-02 -9.72267985e-01 -2.28010222e-01 -5.23366965e-02 -9.73071516e-01 -2.24545330e-01 -5.23367375e-02 -9.73880947e-01 -2.21009776e-01 -5.23366928e-02 -9.74622250e-01 -2.17717484e-01 -5.23366295e-02 -9.75375772e-01 -2.14319602e-01 -5.23367412e-02 -9.76119578e-01 -2.10898697e-01 -5.23366369e-02 -9.76824343e-01 -2.07615077e-01 -5.23367003e-02 -9.77569222e-01 -2.04091385e-01 -5.23367487e-02 -9.78297114e-01 -2.00566471e-01 -5.23367003e-02 -9.78971839e-01 -1.97240800e-01 -5.23366518e-02 -9.79632974e-01 -1.93929881e-01 -5.23366965e-02 -9.80306983e-01 -1.90496847e-01 -5.23366928e-02 -9.80977237e-01 -1.87012926e-01 -5.23367450e-02 -9.81648982e-01 -1.83461830e-01 -5.23366965e-02 -9.82262909e-01 -1.80122018e-01 -5.23366369e-02 -9.82872188e-01 -1.76804379e-01 -5.23366928e-02 -9.83484387e-01 -1.73363358e-01 -5.23366891e-02 -9.84094560e-01 -1.69838354e-01 -5.23367524e-02 -9.84697163e-01 -1.66313931e-01 -5.23366965e-02 -9.85254467e-01 -1.62981734e-01 -5.23366407e-02 -9.85820651e-01 -1.59530088e-01 -5.23367301e-02 -9.86370623e-01 -1.56083554e-01 -5.23366258e-02 -9.86906707e-01 -1.52656868e-01 -5.23367189e-02 -9.87433195e-01 -1.49207383e-01 -5.23366556e-02 -9.87945855e-01 -1.45784900e-01 -5.23367301e-02 -9.88452017e-01 -1.42306238e-01 -5.23366630e-02 -9.88928258e-01 -1.38961270e-01 -5.23366928e-02 -9.89420176e-01 -1.35432661e-01 -5.23367152e-02 -9.89886820e-01 -1.31949067e-01 -5.23366407e-02 -9.90339518e-01 -1.28518462e-01 -5.23367077e-02 -9.90783572e-01 -1.25056416e-01 -5.23366556e-02 -9.91204381e-01 -1.21667512e-01 -5.23366854e-02 -9.91630614e-01 -1.18141241e-01 -5.23367263e-02 -9.92037475e-01 -1.14667229e-01 -5.23366556e-02 -9.92421031e-01 -1.11307234e-01 -5.23366965e-02 -9.92814660e-01 -1.07736938e-01 -5.23367375e-02 -9.93194878e-01 -1.04177535e-01 -5.23366854e-02 -9.93546426e-01 -1.00761726e-01 -5.23366854e-02 -9.93884563e-01 -9.73557159e-02 -5.23365773e-02 -9.94216383e-01 -9.39270929e-02 -5.23365922e-02 -9.94535148e-01 -9.04393941e-02 -5.23362979e-02 -9.94836688e-01 -8.70450363e-02 -5.23362085e-02 -9.95133340e-01 -8.35815966e-02 -5.23361713e-02 -9.95416999e-01 -8.01079124e-02 -5.23360707e-02 -9.95696187e-01 -7.65436068e-02 -5.23360632e-02 -9.95955050e-01 -7.30357170e-02 -5.23357764e-02 -9.96182323e-01 -6.98290989e-02 -5.23357801e-02 -9.96422589e-01 -6.63108453e-02 -5.23358025e-02 -9.96640980e-01 -6.29638359e-02 -5.23358993e-02 -9.96832073e-01 -5.98838516e-02 -5.23359589e-02 -9.97107804e-01 -5.51069081e-02 -5.23359589e-02 -9.97233152e-01 -5.27864359e-02 -5.23359627e-02 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. -9.98458624e-01 -1.84743069e-02 -5.23359589e-02 -9.98546898e-01 -1.28393741e-02 -5.23359589e-02 -9.98574734e-01 -1.04574291e-02 -5.23359627e-02 -9.98609781e-01 -6.27478119e-03 -5.23359627e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.97943163e-01 4.40945439e-02 -4.65311222e-02 -9.97740567e-01 4.84485738e-02 -4.65311185e-02 -9.97539222e-01 5.24284691e-02 -4.65311147e-02 -9.97316122e-01 5.66320978e-02 -4.65310514e-02 -9.97138917e-01 5.95142096e-02 -4.65313755e-02 -9.96926486e-01 6.29390180e-02 -4.65314239e-02 -9.96699691e-01 6.64293021e-02 -4.65314500e-02 -9.96466994e-01 6.98167235e-02 -4.65314314e-02 -9.96223986e-01 7.32079595e-02 -4.65314500e-02 -9.95956242e-01 7.67595544e-02 -4.65314500e-02 -9.95675564e-01 8.03266615e-02 -4.65314500e-02 -9.95398998e-01 8.36896971e-02 -4.65314500e-02 -9.95100319e-01 8.71601701e-02 -4.65314500e-02 -9.94782388e-01 9.07239169e-02 -4.65314500e-02 -9.94464993e-01 9.41369683e-02 -4.65314500e-02 -9.94126916e-01 9.76397917e-02 -4.65314500e-02 -9.93787050e-01 1.01058692e-01 -4.65314500e-02 -9.93439555e-01 1.04409769e-01 -4.65314500e-02 -9.93057132e-01 1.07968159e-01 -4.65314500e-02 -9.92663324e-01 1.11551762e-01 -4.65314500e-02 -9.92264390e-01 1.15030929e-01 -4.65314500e-02 -9.91855979e-01 1.18494481e-01 -4.65314500e-02 -9.91441071e-01 1.21930212e-01 -4.65314500e-02 -9.91014659e-01 1.25360981e-01 -4.65314500e-02 -9.90566492e-01 1.28841177e-01 -4.65314500e-02 -9.90103126e-01 1.32349953e-01 -4.65314500e-02 -9.89651144e-01 1.35703743e-01 -4.65314500e-02 -9.89189446e-01 1.39027983e-01 -4.65314500e-02 -9.88681495e-01 1.42578319e-01 -4.65314500e-02 -9.88162756e-01 1.46131933e-01 -4.65314500e-02 -9.87646699e-01 1.49574026e-01 -4.65314500e-02 -9.87118363e-01 1.53031021e-01 -4.65314500e-02 -9.86579895e-01 1.56469986e-01 -4.65314500e-02 -9.86043215e-01 1.59817964e-01 -4.65314500e-02 -9.85478342e-01 1.63263887e-01 -4.65314500e-02 -9.84884143e-01 1.66812420e-01 -4.65314500e-02 -9.84305918e-01 1.70192257e-01 -4.65314500e-02 -9.83710051e-01 1.73613995e-01 -4.65314500e-02 -9.83082294e-01 1.77136406e-01 -4.65314500e-02 -9.82453227e-01 1.80567712e-01 -4.65314500e-02 -9.81817961e-01 1.83999896e-01 -4.65314500e-02 -9.81185555e-01 1.87341332e-01 -4.65314500e-02 -9.80553031e-01 1.90621018e-01 -4.65314500e-02 -9.79859769e-01 1.94155410e-01 -4.65314500e-02 -9.79149938e-01 1.97708145e-01 -4.65314500e-02 -9.78447556e-01 2.01155737e-01 -4.65314500e-02 -9.77768123e-01 2.04432964e-01 -4.65314500e-02 -9.77048755e-01 2.07847998e-01 -4.65314500e-02 -9.76297736e-01 2.11349756e-01 -4.65314500e-02 -9.75570560e-01 2.14671880e-01 -4.65314388e-02 -9.74818885e-01 2.18065381e-01 -4.65314500e-02 -9.74043429e-01 2.21500874e-01 -4.65314500e-02 -9.73291814e-01 2.24776372e-01 -4.65314500e-02 -9.72485304e-01 2.28251860e-01 -4.65314500e-02 -9.71653521e-01 2.31763214e-01 -4.65314500e-02 -9.70846176e-01 2.35128447e-01 -4.65314500e-02 -9.70016837e-01 2.38517582e-01 -4.65314500e-02 -9.69173133e-01 2.41916150e-01 -4.65314500e-02 -9.68344629e-01 2.45216191e-01 -4.65314500e-02 -9.67488348e-01 2.48569578e-01 -4.65314500e-02 -9.66593385e-01 2.52035230e-01 -4.65314500e-02 -9.65729356e-01 2.55331397e-01 -4.65314500e-02 -9.64826465e-01 2.58713096e-01 -4.65314500e-02 -9.63905394e-01 2.62129664e-01 -4.65314500e-02 -9.62975979e-01 2.65513569e-01 -4.65314500e-02 -9.62045908e-01 2.68876225e-01 -4.65314500e-02 -9.61121559e-01 2.72159100e-01 -4.65314500e-02 -9.60177720e-01 2.75464773e-01 -4.65314500e-02 -9.59206223e-01 2.78829485e-01 -4.65314500e-02 -9.58225369e-01 2.82180548e-01 -4.65314500e-02 -9.57200468e-01 2.85644293e-01 -4.65314500e-02 -9.56227958e-01 2.88877726e-01 -4.65314500e-02 -9.55217898e-01 2.92197943e-01 -4.65314500e-02 -9.54159021e-01 2.95642316e-01 -4.65314500e-02 -9.53133702e-01 2.98930705e-01 -4.65314500e-02 -9.52080965e-01 3.02265018e-01 -4.65314500e-02 -9.51044023e-01 3.05518538e-01 -4.65314500e-02 -9.49998796e-01 3.08743089e-01 -4.65314500e-02 -9.48891461e-01 3.12131166e-01 -4.65314500e-02 -9.47761297e-01 3.15546632e-01 -4.65314500e-02 -9.46644902e-01 3.18883389e-01 -4.65314500e-02 -9.45528090e-01 3.22178423e-01 -4.65314500e-02 -9.44411635e-01 3.25442463e-01 -4.65314500e-02 -9.43294644e-01 3.28659952e-01 -4.65314500e-02 -9.42141593e-01 3.31949055e-01 -4.65314500e-02 -9.40949678e-01 3.35322291e-01 -4.65314500e-02 -9.39795315e-01 3.38535219e-01 -4.65314500e-02 -9.38647866e-01 3.41710746e-01 -4.65314500e-02 -9.37412977e-01 3.45063776e-01 -4.65314500e-02 -9.36168730e-01 3.48413676e-01 -4.65314500e-02 -9.34940219e-01 3.51701111e-01 -4.65314500e-02 -9.33724821e-01 3.54927719e-01 -4.65314500e-02 -9.32521164e-01 3.58105451e-01 -4.65314500e-02 -9.31269526e-01 3.61323118e-01 -4.65314500e-02 -9.29985464e-01 3.64622802e-01 -4.65314500e-02 -9.28677022e-01 3.67944002e-01 -4.65314500e-02 -9.27415967e-01 3.71110737e-01 -4.65314500e-02 -9.26127076e-01 3.74310702e-01 -4.65314500e-02 -9.24780071e-01 3.77631783e-01 -4.65314500e-02 -9.23464954e-01 3.80829960e-01 -4.65314500e-02 -9.22133803e-01 3.84045660e-01 -4.65314500e-02 -9.20812726e-01 3.87203604e-01 -4.65314500e-02 -9.19482827e-01 3.90347600e-01 -4.65314500e-02 -9.18081045e-01 3.93626034e-01 -4.65314500e-02 -9.16663170e-01 3.96926045e-01 -4.65314500e-02 -9.15278316e-01 4.00112897e-01 -4.65314500e-02 -9.13874447e-01 4.03305948e-01 -4.65314500e-02 -9.12464976e-01 4.06486541e-01 -4.65314500e-02 -9.11041319e-01 4.09666359e-01 -4.65314500e-02 -9.09637332e-01 4.12774384e-01 -4.65314500e-02 -9.08202052e-01 4.15916950e-01 -4.65314500e-02 -9.06712949e-01 4.19156283e-01 -4.65314500e-02 -9.05274332e-01 4.22258377e-01 -4.65314500e-02 -9.03808415e-01 4.25382704e-01 -4.65314500e-02 -9.02277708e-01 4.28622961e-01 -4.65314500e-02 -9.00770426e-01 4.31778789e-01 -4.65314500e-02 -8.99263203e-01 4.34916973e-01 -4.65314500e-02 -8.97763789e-01 4.38005149e-01 -4.65314500e-02 -8.96286249e-01 4.41012233e-01 -4.65314500e-02 -8.94699693e-01 4.44223166e-01 -4.65314500e-02 -8.93099129e-01 4.47430611e-01 -4.65314500e-02 -8.91534984e-01 4.50544208e-01 -4.65314500e-02 -8.89952958e-01 4.53659385e-01 -4.65314500e-02 -8.88389885e-01 4.56714183e-01 -4.65314500e-02 -8.86781096e-01 4.59825516e-01 -4.65314500e-02 -8.85177433e-01 4.62908477e-01 -4.65314500e-02 -8.83551240e-01 4.66009319e-01 -4.65314500e-02 -8.81955564e-01 4.69020277e-01 -4.65314500e-02 -8.80358517e-01 4.72010791e-01 -4.65314500e-02 -8.78664196e-01 4.75155026e-01 -4.65314500e-02 -8.76956642e-01 4.78303701e-01 -4.65314500e-02 -8.75285864e-01 4.81352240e-01 -4.65314500e-02 -8.73591363e-01 4.84412402e-01 -4.65314500e-02 -8.71906757e-01 4.87440974e-01 -4.65314500e-02 -8.70214105e-01 4.90461856e-01 -4.65314500e-02 -8.68491232e-01 4.93503422e-01 -4.65314500e-02 -8.66748691e-01 4.96559262e-01 -4.65314500e-02 -8.65043759e-01 4.99524713e-01 -4.65314388e-02 -8.63307834e-01 5.02518117e-01 -4.65314500e-02 -8.61560881e-01 5.05508065e-01 -4.65314500e-02 -8.59777689e-01 5.08531213e-01 -4.65314500e-02 -8.57944667e-01 5.11618674e-01 -4.65314500e-02 -8.56156170e-01 5.14605403e-01 -4.65314500e-02 -8.54353189e-01 5.17591953e-01 -4.65314500e-02 -8.52534592e-01 5.20587921e-01 -4.65314500e-02 -8.50709438e-01 5.23559511e-01 -4.65314500e-02 -8.48880351e-01 5.26525259e-01 -4.65314500e-02 -8.47091377e-01 5.29397666e-01 -4.65314500e-02 -8.45249414e-01 5.32330930e-01 -4.65314500e-02 -8.43350232e-01 5.35335362e-01 -4.65314500e-02 -8.41473103e-01 5.38279712e-01 -4.65314500e-02 -8.39564860e-01 5.41251719e-01 -4.65314500e-02 -8.37673664e-01 5.44173241e-01 -4.65314500e-02 -8.35833192e-01 5.46994627e-01 -4.65314500e-02 -8.33904922e-01 5.49931347e-01 -4.65314500e-02 -8.31914544e-01 5.52935183e-01 -4.65314500e-02 -8.29966664e-01 5.55857956e-01 -4.65314500e-02 -8.28065932e-01 5.58688164e-01 -4.65314500e-02 -8.26178133e-01 5.61473489e-01 -4.65314500e-02 -8.24190319e-01 5.64388275e-01 -4.65314500e-02 -8.22158992e-01 5.67344606e-01 -4.65314500e-02 -8.20149958e-01 5.70242405e-01 -4.65314500e-02 -8.18210006e-01 5.73021173e-01 -4.65314500e-02 -8.16214800e-01 5.75863361e-01 -4.65314500e-02 -8.14117968e-01 5.78820050e-01 -4.65314500e-02 -8.12089562e-01 5.81664801e-01 -4.65314500e-02 -8.10047865e-01 5.84500253e-01 -4.65314500e-02 -8.08002055e-01 5.87330103e-01 -4.65314500e-02 -8.05972695e-01 5.90110540e-01 -4.65314500e-02 -8.03979397e-01 5.92823386e-01 -4.65314388e-02 -8.01895499e-01 5.95636129e-01 -4.65314500e-02 -7.99736798e-01 5.98532259e-01 -4.65314500e-02 -7.97711730e-01 6.01231575e-01 -4.65314500e-02 -7.95616746e-01 6.04001403e-01 -4.65314500e-02 -7.93432415e-01 6.06869340e-01 -4.65314500e-02 -7.91324854e-01 6.09613180e-01 -4.65314500e-02 -7.89152503e-01 6.12420976e-01 -4.65314500e-02 -7.87053049e-01 6.15118384e-01 -4.65314500e-02 -7.84965515e-01 6.17780566e-01 -4.65314500e-02 -7.82760024e-01 6.20569825e-01 -4.65314500e-02 -7.80526757e-01 6.23379767e-01 -4.65314500e-02 -7.78325319e-01 6.26126051e-01 -4.65314500e-02 -7.76150465e-01 6.28820956e-01 -4.65314500e-02 -7.74007976e-01 6.31452739e-01 -4.65314500e-02 -7.71830976e-01 6.34114146e-01 -4.65314500e-02 -7.69544542e-01 6.36887610e-01 -4.65314500e-02 -7.67297626e-01 6.39591455e-01 -4.65314500e-02 -7.65147209e-01 6.42165363e-01 -4.65314388e-02 -7.62893736e-01 6.44837201e-01 -4.65314500e-02 -7.60536432e-01 6.47615135e-01 -4.65314500e-02 -7.58286595e-01 6.50249958e-01 -4.65314500e-02 -7.55999744e-01 6.52909279e-01 -4.65314500e-02 -7.53738523e-01 6.55515194e-01 -4.65314500e-02 -7.51491547e-01 6.58092439e-01 -4.65314388e-02 -7.49246895e-01 6.60644829e-01 -4.65314500e-02 -7.46899188e-01 6.63297474e-01 -4.65314500e-02 -7.44503975e-01 6.65987372e-01 -4.65314500e-02 -7.42212236e-01 6.68537736e-01 -4.65314500e-02 -7.39897251e-01 6.71101987e-01 -4.65314500e-02 -7.37474024e-01 6.73760176e-01 -4.65314500e-02 -7.35149324e-01 6.76300347e-01 -4.65314500e-02 -7.32766330e-01 6.78881168e-01 -4.65314500e-02 -7.30456233e-01 6.81364000e-01 -4.65314500e-02 -7.28142560e-01 6.83836579e-01 -4.65314500e-02 -7.25694835e-01 6.86429560e-01 -4.65314500e-02 -7.23224521e-01 6.89036667e-01 -4.65314500e-02 -7.20802486e-01 6.91563666e-01 -4.65314500e-02 -7.18410909e-01 6.94060445e-01 -4.65314500e-02 -7.16019332e-01 6.96525931e-01 -4.65314500e-02 -7.13604033e-01 6.98996365e-01 -4.65314500e-02 -7.11091995e-01 7.01554179e-01 -4.65314500e-02 -7.08632946e-01 7.04040587e-01 -4.65314500e-02 -7.06172585e-01 7.06489801e-01 -4.65314500e-02 -7.03775346e-01 7.08896637e-01 -4.65314500e-02 -7.01296091e-01 7.11346984e-01 -4.65314500e-02 -6.98743463e-01 7.13852286e-01 -4.65314500e-02 -6.96241915e-01 7.16295242e-01 -4.65314500e-02 -6.93741679e-01 7.18718052e-01 -4.65314500e-02 -6.91275895e-01 7.21079230e-01 -4.65314351e-02 -6.88807964e-01 7.23443508e-01 -4.65314500e-02 -6.86199844e-01 7.25912392e-01 -4.65314500e-02 -6.83638811e-01 7.28326797e-01 -4.65314500e-02 -6.81129456e-01 7.30672956e-01 -4.65314277e-02 -6.78574800e-01 7.33047247e-01 -4.65314500e-02 -6.75967336e-01 7.35454857e-01 -4.65314500e-02 -6.73446774e-01 7.37761676e-01 -4.65314500e-02 -6.70862854e-01 7.40113258e-01 -4.65314500e-02 -6.68299079e-01 7.42429376e-01 -4.65314500e-02 -6.65772974e-01 7.44695187e-01 -4.65314500e-02 -6.63106441e-01 7.47070432e-01 -4.65314500e-02 -6.60489023e-01 7.49386251e-01 -4.65314500e-02 -6.57834888e-01 7.51713395e-01 -4.65314500e-02 -6.55226827e-01 7.53993511e-01 -4.65314202e-02 -6.52617097e-01 7.56249189e-01 -4.65314500e-02 -6.49857283e-01 7.58623302e-01 -4.65314500e-02 -6.47200525e-01 7.60889530e-01 -4.65314500e-02 -6.44565403e-01 7.63124347e-01 -4.65314500e-02 -6.41982436e-01 7.65299380e-01 -4.65314500e-02 -6.39310718e-01 7.67532885e-01 -4.65314500e-02 -6.36620402e-01 7.69765437e-01 -4.65314314e-02 -6.33933544e-01 7.71980882e-01 -4.65314500e-02 -6.31139457e-01 7.74264395e-01 -4.65314500e-02 -6.28416538e-01 7.76476562e-01 -4.65314500e-02 -6.25790477e-01 7.78594255e-01 -4.65314388e-02 -6.23145163e-01 7.80714035e-01 -4.65314500e-02 -6.20352566e-01 7.82932043e-01 -4.65314500e-02 -6.17606640e-01 7.85103738e-01 -4.65314500e-02 -6.14891291e-01 7.87229955e-01 -4.65314500e-02 -6.12123728e-01 7.89386213e-01 -4.65314500e-02 -6.09426022e-01 7.91469276e-01 -4.65314500e-02 -6.06578946e-01 7.93652475e-01 -4.65314500e-02 -6.03749037e-01 7.95809209e-01 -4.65314500e-02 -6.01041436e-01 7.97856390e-01 -4.65314500e-02 -5.98267317e-01 7.99934089e-01 -4.65314500e-02 -5.95386147e-01 8.02082956e-01 -4.65314500e-02 -5.92590392e-01 8.04151058e-01 -4.65314500e-02 -5.89794934e-01 8.06203067e-01 -4.65314500e-02 -5.87037921e-01 8.08215141e-01 -4.65314500e-02 -5.84212303e-01 8.10255885e-01 -4.65314500e-02 -5.81298292e-01 8.12353492e-01 -4.65314500e-02 -5.78473747e-01 8.14366221e-01 -4.65314500e-02 -5.75599194e-01 8.16401601e-01 -4.65314500e-02 -5.72810650e-01 8.18358600e-01 -4.65314500e-02 -5.69978297e-01 8.20331573e-01 -4.65314500e-02 -5.67108214e-01 8.22323143e-01 -4.65314500e-02 -5.64240038e-01 8.24291646e-01 -4.65314500e-02 -5.61240196e-01 8.26335073e-01 -4.65314500e-02 -5.58366418e-01 8.28281045e-01 -4.65314500e-02 -5.55595458e-01 8.30143392e-01 -4.65314314e-02 -5.52656174e-01 8.32100570e-01 -4.65314500e-02 -5.49637735e-01 8.34099352e-01 -4.65314500e-02 -5.46807349e-01 8.35956633e-01 -4.65314500e-02 -5.43918192e-01 8.37838709e-01 -4.65314500e-02 -5.40962517e-01 8.39750826e-01 -4.65314500e-02 -5.38036048e-01 8.41627061e-01 -4.65314500e-02 -5.35017729e-01 8.43550801e-01 -4.65314500e-02 -5.32059431e-01 8.45419586e-01 -4.65314500e-02 -5.29187322e-01 8.47221136e-01 -4.65314500e-02 -5.26243627e-01 8.49054337e-01 -4.65314500e-02 -5.23194790e-01 8.50934207e-01 -4.65314500e-02 -5.20268440e-01 8.52727711e-01 -4.65314500e-02 -5.17285466e-01 8.54538381e-01 -4.65314500e-02 -5.14316380e-01 8.56331229e-01 -4.65314500e-02 -5.11361241e-01 8.58098328e-01 -4.65314500e-02 -5.08351743e-01 8.59883904e-01 -4.65314500e-02 -5.05414546e-01 8.61615002e-01 -4.65314500e-02 -5.02359092e-01 8.63399148e-01 -4.65314500e-02 -4.99255478e-01 8.65199327e-01 -4.65314500e-02 -4.96244580e-01 8.66927564e-01 -4.65314500e-02 -4.93234366e-01 8.68644238e-01 -4.65314500e-02 -4.90180731e-01 8.70374143e-01 -4.65314500e-02 -4.87140030e-01 8.72075975e-01 -4.65314500e-02 -4.84092057e-01 8.73770297e-01 -4.65314500e-02 -4.81071472e-01 8.75440300e-01 -4.65314500e-02 -4.78035361e-01 8.77101421e-01 -4.65314500e-02 -4.74899620e-01 8.78800154e-01 -4.65314500e-02 -4.71850336e-01 8.80443335e-01 -4.65314500e-02 -4.68772411e-01 8.82087052e-01 -4.65314500e-02 -4.65750396e-01 8.83687735e-01 -4.65314463e-02 -4.62652951e-01 8.85310292e-01 -4.65314500e-02 -4.59496021e-01 8.86952519e-01 -4.65314500e-02 -4.56376076e-01 8.88564050e-01 -4.65314500e-02 -4.53381002e-01 8.90095532e-01 -4.65314314e-02 -4.50312465e-01 8.91650259e-01 -4.65314500e-02 -4.47100013e-01 8.93266082e-01 -4.65314500e-02 -4.43973988e-01 8.94823611e-01 -4.65314500e-02 -4.40842479e-01 8.96371901e-01 -4.65314500e-02 -4.37762022e-01 8.97881925e-01 -4.65314388e-02 -4.34668750e-01 8.99382293e-01 -4.65314500e-02 -4.31483358e-01 9.00913715e-01 -4.65314500e-02 -4.28353071e-01 9.02404606e-01 -4.65314500e-02 -4.25120443e-01 9.03933465e-01 -4.65314500e-02 -4.22033638e-01 9.05380011e-01 -4.65314500e-02 -4.18887943e-01 9.06838119e-01 -4.65314500e-02 -4.15715963e-01 9.08295989e-01 -4.65314500e-02 -4.12531525e-01 9.09747541e-01 -4.65314500e-02 -4.09309179e-01 9.11203504e-01 -4.65314500e-02 -4.06095624e-01 9.12639618e-01 -4.65314500e-02 -4.03004587e-01 9.14009035e-01 -4.65314500e-02 -3.99852663e-01 9.15392280e-01 -4.65314500e-02 -3.96566212e-01 9.16820109e-01 -4.65314500e-02 -3.93301368e-01 9.18221176e-01 -4.65314500e-02 -3.90188038e-01 9.19553459e-01 -4.65314388e-02 -3.87102872e-01 9.20855343e-01 -4.65314500e-02 -3.83818865e-01 9.22228396e-01 -4.65314500e-02 -3.80507052e-01 9.23598826e-01 -4.65314500e-02 -3.77331883e-01 9.24900889e-01 -4.65314500e-02 -3.74108970e-01 9.26211417e-01 -4.65314463e-02 -3.70895952e-01 9.27500069e-01 -4.65314500e-02 -3.67599964e-01 9.28813219e-01 -4.65314500e-02 -3.64352375e-01 9.30092275e-01 -4.65314500e-02 -3.61093938e-01 9.31356132e-01 -4.65314500e-02 -3.57907951e-01 9.32596505e-01 -4.65314500e-02 -3.54649454e-01 9.33830678e-01 -4.65314500e-02 -3.51387173e-01 9.35057700e-01 -4.65314500e-02 -3.48127842e-01 9.36275244e-01 -4.65314500e-02 -3.44799191e-01 9.37509775e-01 -4.65314500e-02 -3.41569036e-01 9.38702226e-01 -4.65314388e-02 -3.38286698e-01 9.39884543e-01 -4.65314500e-02 -3.34978044e-01 9.41072643e-01 -4.65314500e-02 -3.31710011e-01 9.42227244e-01 -4.65314500e-02 -3.28368783e-01 9.43396091e-01 -4.65314500e-02 -3.25065672e-01 9.44541335e-01 -4.65314500e-02 -3.21865141e-01 9.45635140e-01 -4.65314500e-02 -3.18540275e-01 9.46760595e-01 -4.65314500e-02 -3.15191716e-01 9.47880030e-01 -4.65314500e-02 -3.11874211e-01 9.48976398e-01 -4.65314500e-02 -3.08610797e-01 9.50043499e-01 -4.65314500e-02 -3.05303216e-01 9.51111794e-01 -4.65314500e-02 -3.01946163e-01 9.52182591e-01 -4.65314500e-02 -2.98610210e-01 9.53234494e-01 -4.65314500e-02 -2.95265257e-01 9.54276562e-01 -4.65314500e-02 -2.92023391e-01 9.55273569e-01 -4.65314500e-02 -2.88677573e-01 9.56286371e-01 -4.65314500e-02 -2.85213739e-01 9.57327664e-01 -4.65314500e-02 -2.81886518e-01 9.58313882e-01 -4.65314500e-02 -2.78543711e-01 9.59289134e-01 -4.65314500e-02 -2.75278717e-01 9.60233271e-01 -4.65314388e-02 -2.71962583e-01 9.61176276e-01 -4.65314500e-02 -2.68585414e-01 9.62127209e-01 -4.65314388e-02 -2.65337616e-01 9.63025689e-01 -4.65314500e-02 -2.61847883e-01 9.63981152e-01 -4.65314500e-02 -2.58374214e-01 9.64917064e-01 -4.65314500e-02 -2.54994869e-01 9.65816140e-01 -4.65314500e-02 -2.51643509e-01 9.66695309e-01 -4.65314500e-02 -2.48375058e-01 9.67541039e-01 -4.65314500e-02 -2.44978815e-01 9.68401670e-01 -4.65314500e-02 -2.41477072e-01 9.69283462e-01 -4.65314500e-02 -2.38092303e-01 9.70121503e-01 -4.65314500e-02 -2.34698221e-01 9.70950127e-01 -4.65314500e-02 -2.31396183e-01 9.71742809e-01 -4.65314388e-02 -2.28021711e-01 9.72538233e-01 -4.65314500e-02 -2.24631280e-01 9.73327339e-01 -4.65314500e-02 -2.21229598e-01 9.74103212e-01 -4.65314500e-02 -2.17744380e-01 9.74891603e-01 -4.65314500e-02 -2.14325503e-01 9.75644946e-01 -4.65314500e-02 -2.10919708e-01 9.76388097e-01 -4.65314500e-02 -2.07594723e-01 9.77102339e-01 -4.65314500e-02 -2.04218298e-01 9.77813542e-01 -4.65314500e-02 -2.00684279e-01 9.78545606e-01 -4.65314500e-02 -1.97268918e-01 9.79237795e-01 -4.65314500e-02 -1.93847388e-01 9.79921043e-01 -4.65314500e-02 -1.90516189e-01 9.80575562e-01 -4.65314500e-02 -1.87078997e-01 9.81235027e-01 -4.65314500e-02 -1.83669150e-01 9.81880188e-01 -4.65314388e-02 -1.80299729e-01 9.82502759e-01 -4.65314500e-02 -1.76799417e-01 9.83143270e-01 -4.65314500e-02 -1.73254237e-01 9.83775079e-01 -4.65314500e-02 -1.69863626e-01 9.84362066e-01 -4.65314500e-02 -1.66400269e-01 9.84953880e-01 -4.65314500e-02 -1.63044289e-01 9.85515296e-01 -4.65314500e-02 -1.59693852e-01 9.86063063e-01 -4.65314500e-02 -1.56196564e-01 9.86623347e-01 -4.65314500e-02 -1.52618900e-01 9.87184227e-01 -4.65314500e-02 -1.49156019e-01 9.87710238e-01 -4.65314500e-02 -1.45711735e-01 9.88225937e-01 -4.65314500e-02 -1.42276332e-01 9.88725901e-01 -4.65314500e-02 -1.38943300e-01 9.89201963e-01 -4.65314351e-02 -1.35497585e-01 9.89678919e-01 -4.65314500e-02 -1.31891310e-01 9.90165174e-01 -4.65314500e-02 -1.28559589e-01 9.90603149e-01 -4.65314500e-02 -1.25118643e-01 9.91042972e-01 -4.65314500e-02 -1.21655092e-01 9.91476119e-01 -4.65314388e-02 -1.18158326e-01 9.91896689e-01 -4.65314500e-02 -1.14583574e-01 9.92316902e-01 -4.65314500e-02 -1.11132286e-01 9.92709339e-01 -4.65314500e-02 -1.07654944e-01 9.93091464e-01 -4.65314500e-02 -1.04185350e-01 9.93461430e-01 -4.65314500e-02 -1.00709237e-01 9.93820846e-01 -4.65314500e-02 -9.73341838e-02 9.94157672e-01 -4.65314500e-02 -9.39824954e-02 9.94479656e-01 -4.65314500e-02 -9.04139504e-02 9.94809687e-01 -4.65314500e-02 -8.68395939e-02 9.95129824e-01 -4.65314500e-02 -8.33469927e-02 9.95427370e-01 -4.65314500e-02 -7.98806474e-02 9.95711625e-01 -4.65314500e-02 -7.64989704e-02 9.95975673e-01 -4.65314314e-02 -7.30201900e-02 9.96238053e-01 -4.65314500e-02 -6.94459751e-02 9.96492386e-01 -4.65314500e-02 -6.59560636e-02 9.96731520e-01 -4.65314500e-02 -6.24771640e-02 9.96953428e-01 -4.65314500e-02 -5.91192059e-02 9.97160673e-01 -4.65314500e-02 -5.56575358e-02 9.97358918e-01 -4.65314500e-02 -5.21017201e-02 9.97550905e-01 -4.65314500e-02 -4.86675166e-02 9.97725725e-01 -4.65314500e-02 -4.50986102e-02 9.97891068e-01 -4.65314500e-02 -4.16041240e-02 9.98044252e-01 -4.65314500e-02 -3.81010249e-02 9.98183489e-01 -4.65314500e-02 -3.47256474e-02 9.98308241e-01 -4.65314500e-02 -3.12593728e-02 9.98420298e-01 -4.65314500e-02 -2.77500469e-02 9.98524904e-01 -4.65314388e-02 -2.42545102e-02 9.98619080e-01 -4.65314500e-02 -2.07001735e-02 9.98694181e-01 -4.65314500e-02 -1.72755439e-02 9.98764873e-01 -4.65314500e-02 -1.38210272e-02 9.98811305e-01 -4.65314500e-02 -1.03235655e-02 9.98855531e-01 -4.65314314e-02 -6.92913122e-03 9.98892009e-01 -4.65314500e-02 -3.33764032e-03 9.98909652e-01 -4.65314500e-02 2.29576981e-04 9.98911440e-01 -4.65314500e-02 3.70850018e-03 9.98910010e-01 -4.65314500e-02 7.17354007e-03 9.98889387e-01 -4.65314500e-02 1.05837816e-02 9.98854518e-01 -4.65314388e-02 1.39768487e-02 9.98809576e-01 -4.65314500e-02 1.75494310e-02 9.98760581e-01 -4.65314500e-02 2.11519636e-02 9.98686492e-01 -4.65314500e-02 2.46381667e-02 9.98606980e-01 -4.65314500e-02 2.81471275e-02 9.98515546e-01 -4.65314500e-02 3.16190273e-02 9.98410702e-01 -4.65314500e-02 3.50308605e-02 9.98298705e-01 -4.65314239e-02 3.84957418e-02 9.98169065e-01 -4.65314500e-02 4.20719460e-02 9.98025298e-01 -4.65314500e-02 4.55529280e-02 9.97871220e-01 -4.65314500e-02 4.90563512e-02 9.97706056e-01 -4.65314500e-02 5.24260253e-02 9.97532904e-01 -4.65314388e-02 5.59000671e-02 9.97345388e-01 -4.65314500e-02 5.94046973e-02 9.97144997e-01 -4.65314239e-02 6.28572181e-02 9.96928692e-01 -4.65314500e-02 6.64603934e-02 9.96697366e-01 -4.65314500e-02 6.99299052e-02 9.96458054e-01 -4.65314500e-02 7.34045208e-02 9.96211112e-01 -4.65314500e-02 7.68976808e-02 9.95945096e-01 -4.65314500e-02 8.02850351e-02 9.95681226e-01 -4.65314239e-02 8.37315097e-02 9.95395064e-01 -4.65314500e-02 8.72829407e-02 9.95091140e-01 -4.65314500e-02 9.07751918e-02 9.94777739e-01 -4.65314500e-02 9.42411944e-02 9.94455457e-01 -4.65314388e-02 9.76535454e-02 9.94127929e-01 -4.65314239e-02 1.01108029e-01 9.93780434e-01 -4.65314500e-02 1.04572192e-01 9.93422925e-01 -4.65314500e-02 1.08040206e-01 9.93050396e-01 -4.65314500e-02 1.11613691e-01 9.92654860e-01 -4.65314500e-02 1.14967726e-01 9.92272317e-01 -4.65314500e-02 1.18423380e-01 9.91864860e-01 -4.65314500e-02 1.21873014e-01 9.91449058e-01 -4.65314314e-02 1.25337183e-01 9.91016686e-01 -4.65314500e-02 1.28907904e-01 9.90556955e-01 -4.65314500e-02 1.32356808e-01 9.90103006e-01 -4.65314500e-02 1.35806650e-01 9.89637315e-01 -4.65314500e-02 1.39183357e-01 9.89169300e-01 -4.65314500e-02 1.42623097e-01 9.88675892e-01 -4.65314500e-02 1.46099627e-01 9.88169670e-01 -4.65314314e-02 1.49531022e-01 9.87653315e-01 -4.65314500e-02 1.53053388e-01 9.87117887e-01 -4.65314500e-02 1.56439945e-01 9.86584485e-01 -4.65314277e-02 1.59863278e-01 9.86036122e-01 -4.65314500e-02 1.63321495e-01 9.85470891e-01 -4.65314388e-02 1.66659459e-01 9.84909773e-01 -4.65314500e-02 1.70176968e-01 9.84307706e-01 -4.65314500e-02 1.73697755e-01 9.83697116e-01 -4.65314500e-02 1.77124262e-01 9.83087063e-01 -4.65314500e-02 1.80588409e-01 9.82451200e-01 -4.65314500e-02 1.83899865e-01 9.81838286e-01 -4.65314388e-02 1.87241197e-01 9.81204927e-01 -4.65314500e-02 1.90672621e-01 9.80543971e-01 -4.65314500e-02 1.94152728e-01 9.79859889e-01 -4.65314500e-02 1.97672561e-01 9.79156852e-01 -4.65314500e-02 2.01090962e-01 9.78460729e-01 -4.65314500e-02 2.04505846e-01 9.77751434e-01 -4.65314500e-02 2.07831621e-01 9.77054000e-01 -4.65314463e-02 2.11216226e-01 9.76324499e-01 -4.65314500e-02 2.14726061e-01 9.75558817e-01 -4.65314500e-02 2.18147591e-01 9.74800348e-01 -4.65314500e-02 2.21564204e-01 9.74027991e-01 -4.65314500e-02 2.24895597e-01 9.73267376e-01 -4.65314277e-02 2.28259087e-01 9.72483695e-01 -4.65314500e-02 2.31653780e-01 9.71680999e-01 -4.65314277e-02 2.34957889e-01 9.70887840e-01 -4.65314500e-02 2.38434225e-01 9.70036983e-01 -4.65314500e-02 2.41916999e-01 9.69173491e-01 -4.65314500e-02 2.45271593e-01 9.68329668e-01 -4.65314500e-02 2.48627976e-01 9.67476368e-01 -4.65314500e-02 2.51941085e-01 9.66618776e-01 -4.65314388e-02 2.55228102e-01 9.65755761e-01 -4.65314500e-02 2.58690983e-01 9.64831889e-01 -4.65314500e-02 2.62181103e-01 9.63891447e-01 -4.65314500e-02 2.65472084e-01 9.62988436e-01 -4.65314500e-02 2.68758804e-01 9.62079823e-01 -4.65314314e-02 2.72141695e-01 9.61124778e-01 -4.65314500e-02 2.75481433e-01 9.60175753e-01 -4.65314500e-02 2.78819233e-01 9.59209144e-01 -4.65314500e-02 2.82284886e-01 9.58194911e-01 -4.65314500e-02 2.85547674e-01 9.57230866e-01 -4.65314426e-02 2.88871527e-01 9.56227183e-01 -4.65314500e-02 2.92237043e-01 9.55207586e-01 -4.65314500e-02 2.95477480e-01 9.54211116e-01 -4.65314500e-02 2.98920631e-01 9.53137159e-01 -4.65314500e-02 3.02196383e-01 9.52102721e-01 -4.65314500e-02 3.05510253e-01 9.51045156e-01 -4.65314500e-02 3.08860779e-01 9.49962199e-01 -4.65314500e-02 3.12160224e-01 9.48882103e-01 -4.65314500e-02 3.15459341e-01 9.47791457e-01 -4.65314500e-02 3.18673998e-01 9.46716428e-01 -4.65314500e-02 3.22071254e-01 9.45565164e-01 -4.65314500e-02 3.25464040e-01 9.44403529e-01 -4.65314500e-02 3.28737438e-01 9.43267345e-01 -4.65314500e-02 3.32005978e-01 9.42123175e-01 -4.65314500e-02 3.35250378e-01 9.40976977e-01 -4.65314500e-02 3.38492453e-01 9.39810693e-01 -4.65314500e-02 3.41882050e-01 9.38584387e-01 -4.65314500e-02 3.45157653e-01 9.37376976e-01 -4.65314500e-02 3.48408520e-01 9.36170697e-01 -4.65314500e-02 3.51622194e-01 9.34969485e-01 -4.65314500e-02 3.54860574e-01 9.33750987e-01 -4.65314500e-02 3.58125120e-01 9.32515144e-01 -4.65314500e-02 3.61358285e-01 9.31256056e-01 -4.65314500e-02 3.64672244e-01 9.29965079e-01 -4.65314500e-02 3.67880255e-01 9.28702295e-01 -4.65314500e-02 3.71101469e-01 9.27417457e-01 -4.65314500e-02 3.74312401e-01 9.26127911e-01 -4.65314500e-02 3.77538055e-01 9.24816787e-01 -4.65314500e-02 3.80765826e-01 9.23491418e-01 -4.65314500e-02 3.83979768e-01 9.22160208e-01 -4.65314500e-02 3.87279809e-01 9.20780718e-01 -4.65314500e-02 3.90415639e-01 9.19454575e-01 -4.65314500e-02 3.93600047e-01 9.18092906e-01 -4.65314500e-02 3.96815151e-01 9.16710734e-01 -4.65314500e-02 3.99919242e-01 9.15363848e-01 -4.65314500e-02 4.03191596e-01 9.13925529e-01 -4.65314500e-02 4.06461060e-01 9.12476301e-01 -4.65314500e-02 4.09634233e-01 9.11055505e-01 -4.65314500e-02 4.12834764e-01 9.09610569e-01 -4.65314500e-02 4.15928125e-01 9.08197999e-01 -4.65314500e-02 4.19012994e-01 9.06778693e-01 -4.65314500e-02 4.22216564e-01 9.05293345e-01 -4.65314500e-02 4.25486565e-01 9.03759420e-01 -4.65314500e-02 4.28614646e-01 9.02281225e-01 -4.65314500e-02 4.31712002e-01 9.00802970e-01 -4.65314388e-02 4.34835851e-01 8.99301767e-01 -4.65314500e-02 4.37972784e-01 8.97780180e-01 -4.65314500e-02 4.41092819e-01 8.96246314e-01 -4.65314500e-02 4.44304943e-01 8.94659102e-01 -4.65314500e-02 4.47438717e-01 8.93095970e-01 -4.65314500e-02 4.50526297e-01 8.91544104e-01 -4.65314500e-02 4.53575045e-01 8.89997184e-01 -4.65314500e-02 4.56630051e-01 8.88432920e-01 -4.65314500e-02 4.59781766e-01 8.86803985e-01 -4.65314388e-02 4.62820590e-01 8.85226130e-01 -4.65314500e-02 4.65962589e-01 8.83573174e-01 -4.65314500e-02 4.69097137e-01 8.81914198e-01 -4.65314500e-02 4.72169787e-01 8.80271971e-01 -4.65314500e-02 4.75260258e-01 8.78607035e-01 -4.65314500e-02 4.78242874e-01 8.76990974e-01 -4.65314500e-02 4.81298387e-01 8.75313759e-01 -4.65314500e-02 4.84453678e-01 8.73569071e-01 -4.65314500e-02 4.87477779e-01 8.71886671e-01 -4.65314500e-02 4.90563631e-01 8.70156527e-01 -4.65314500e-02 4.93475288e-01 8.68507266e-01 -4.65314500e-02 4.96509820e-01 8.66775572e-01 -4.65314500e-02 4.99534756e-01 8.65037918e-01 -4.65314500e-02 5.02535224e-01 8.63296568e-01 -4.65314500e-02 5.05640447e-01 8.61481547e-01 -4.65314500e-02 5.08583367e-01 8.59748542e-01 -4.65314500e-02 5.11552393e-01 8.57984781e-01 -4.65314500e-02 5.14550567e-01 8.56190264e-01 -4.65314500e-02 5.17532825e-01 8.54388237e-01 -4.65314500e-02 5.20563960e-01 8.52548063e-01 -4.65314500e-02 5.23476362e-01 8.50760341e-01 -4.65314500e-02 5.26444256e-01 8.48930061e-01 -4.65314500e-02 5.29401898e-01 8.47087920e-01 -4.65314500e-02 5.32340586e-01 8.45242560e-01 -4.65314500e-02 5.35310924e-01 8.43365669e-01 -4.65314500e-02 5.38233399e-01 8.41501415e-01 -4.65314500e-02 5.41247487e-01 8.39566410e-01 -4.65314500e-02 5.44115722e-01 8.37712109e-01 -4.65314500e-02 5.47004998e-01 8.35824907e-01 -4.65314500e-02 5.49930394e-01 8.33907247e-01 -4.65314314e-02 5.52738905e-01 8.32046151e-01 -4.65314277e-02 5.55749595e-01 8.30040574e-01 -4.65314239e-02 5.58645427e-01 8.28097939e-01 -4.65313718e-02 5.61477363e-01 8.26179504e-01 -4.65313718e-02 5.64507306e-01 8.24115753e-01 -4.65313010e-02 5.67303240e-01 8.22199464e-01 -4.65312377e-02 5.70048809e-01 8.20297003e-01 -4.65312339e-02 5.72868466e-01 8.18332970e-01 -4.65311967e-02 5.75722694e-01 8.16324890e-01 -4.65310253e-02 5.78575790e-01 8.14299464e-01 -4.65311371e-02 5.81176400e-01 8.12445462e-01 -4.65311222e-02 5.83474994e-01 8.10796618e-01 -4.65311259e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 7.16659367e-01 6.95867896e-01 -4.65311557e-02 7.18793511e-01 6.93668008e-01 -4.65309396e-02 7.21131027e-01 6.91234589e-01 -4.65313084e-02 7.23562062e-01 6.88687205e-01 -4.65313420e-02 7.25856900e-01 6.86267793e-01 -4.65313531e-02 7.28264749e-01 6.83707178e-01 -4.65314090e-02 7.30708003e-01 6.81095064e-01 -4.65314165e-02 7.33023763e-01 6.78602874e-01 -4.65314314e-02 7.35339105e-01 6.76095665e-01 -4.65314500e-02 7.37650812e-01 6.73567116e-01 -4.65314500e-02 7.40062475e-01 6.70919418e-01 -4.65314500e-02 7.42457509e-01 6.68268263e-01 -4.65314500e-02 7.44789004e-01 6.65666461e-01 -4.65314500e-02 7.47040868e-01 6.63141191e-01 -4.65314463e-02 7.49298155e-01 6.60587728e-01 -4.65314500e-02 7.51631260e-01 6.57928169e-01 -4.65314500e-02 7.53964424e-01 6.55256331e-01 -4.65314500e-02 7.56271958e-01 6.52591407e-01 -4.65314500e-02 7.58540213e-01 6.49955869e-01 -4.65314500e-02 7.60743380e-01 6.47371888e-01 -4.65314500e-02 7.62987733e-01 6.44727647e-01 -4.65314500e-02 7.65229285e-01 6.42065465e-01 -4.65314500e-02 7.67504513e-01 6.39343798e-01 -4.65314500e-02 7.69794106e-01 6.36583149e-01 -4.65314500e-02 7.71964073e-01 6.33953512e-01 -4.65314500e-02 7.74153352e-01 6.31274343e-01 -4.65314500e-02 7.76403725e-01 6.28505647e-01 -4.65314500e-02 7.78607726e-01 6.25773430e-01 -4.65314500e-02 7.80742228e-01 6.23111129e-01 -4.65314388e-02 7.82846391e-01 6.20462835e-01 -4.65314500e-02 7.85053730e-01 6.17667615e-01 -4.65314500e-02 7.87264824e-01 6.14847839e-01 -4.65314500e-02 7.89413929e-01 6.12085700e-01 -4.65314500e-02 7.91505575e-01 6.09380960e-01 -4.65314277e-02 7.93551266e-01 6.06712103e-01 -4.65314500e-02 7.95719624e-01 6.03864789e-01 -4.65314500e-02 7.97884345e-01 6.01002395e-01 -4.65314500e-02 7.99981892e-01 5.98205388e-01 -4.65314500e-02 8.02020252e-01 5.95472872e-01 -4.65314500e-02 8.04014802e-01 5.92774808e-01 -4.65314500e-02 8.06134105e-01 5.89887917e-01 -4.65314500e-02 8.08251739e-01 5.86984277e-01 -4.65314500e-02 8.10309887e-01 5.84136486e-01 -4.65314500e-02 8.12330425e-01 5.81328988e-01 -4.65314500e-02 8.14294994e-01 5.78575730e-01 -4.65314500e-02 8.16264689e-01 5.75793207e-01 -4.65314500e-02 8.18283677e-01 5.72917461e-01 -4.65314500e-02 8.20315599e-01 5.70001483e-01 -4.65314500e-02 8.22336018e-01 5.67088068e-01 -4.65314500e-02 8.24242175e-01 5.64311564e-01 -4.65314500e-02 8.26263547e-01 5.61345160e-01 -4.65314500e-02 8.28229129e-01 5.58445334e-01 -4.65314388e-02 8.30129683e-01 5.55612803e-01 -4.65314500e-02 8.32074404e-01 5.52698493e-01 -4.65314500e-02 8.33953500e-01 5.49859107e-01 -4.65314500e-02 8.35927367e-01 5.46850264e-01 -4.65314500e-02 8.37870240e-01 5.43870986e-01 -4.65314500e-02 8.39708924e-01 5.41027784e-01 -4.65314500e-02 8.41559529e-01 5.38145423e-01 -4.65314500e-02 8.43418062e-01 5.35224795e-01 -4.65314500e-02 8.45355928e-01 5.32161415e-01 -4.65314500e-02 8.47271800e-01 5.29105604e-01 -4.65314500e-02 8.49102378e-01 5.26166081e-01 -4.65314500e-02 8.50877881e-01 5.23285151e-01 -4.65314500e-02 8.52663219e-01 5.20375490e-01 -4.65314500e-02 8.54471505e-01 5.17397642e-01 -4.65314500e-02 8.56280565e-01 5.14399171e-01 -4.65314500e-02 8.58105838e-01 5.11345804e-01 -4.65314500e-02 8.59937310e-01 5.08262396e-01 -4.65314500e-02 8.61665487e-01 5.05328953e-01 -4.65314500e-02 8.63405466e-01 5.02345562e-01 -4.65314500e-02 8.65170479e-01 4.99306321e-01 -4.65314500e-02 8.66897523e-01 4.96295720e-01 -4.65314500e-02 8.68653357e-01 4.93216276e-01 -4.65314500e-02 8.70321095e-01 4.90274757e-01 -4.65314500e-02 8.72044623e-01 4.87195194e-01 -4.65314500e-02 8.73754978e-01 4.84120548e-01 -4.65314500e-02 8.75437319e-01 4.81074989e-01 -4.65314500e-02 8.77104402e-01 4.78031695e-01 -4.65314500e-02 8.78737509e-01 4.75019246e-01 -4.65314500e-02 8.80414784e-01 4.71902937e-01 -4.65314500e-02 8.82113516e-01 4.68721598e-01 -4.65314500e-02 8.83746803e-01 4.65636641e-01 -4.65314500e-02 8.85315597e-01 4.62647885e-01 -4.65314388e-02 8.86875272e-01 4.59646493e-01 -4.65314500e-02 8.88511777e-01 4.56474602e-01 -4.65314500e-02 8.90152276e-01 4.53267246e-01 -4.65314500e-02 8.91721189e-01 4.50175524e-01 -4.65314500e-02 8.93305480e-01 4.47023392e-01 -4.65314500e-02 8.94818544e-01 4.43988055e-01 -4.65314277e-02 8.96361351e-01 4.40861851e-01 -4.65314500e-02 8.97897482e-01 4.37729120e-01 -4.65314500e-02 8.99404168e-01 4.34622049e-01 -4.65314500e-02 9.00954902e-01 4.31398600e-01 -4.65314500e-02 9.02428567e-01 4.28308576e-01 -4.65314351e-02 9.03889835e-01 4.25209045e-01 -4.65314500e-02 9.05387998e-01 4.22016650e-01 -4.65314500e-02 9.06859100e-01 4.18843269e-01 -4.65314500e-02 9.08351719e-01 4.15593565e-01 -4.65314500e-02 9.09765601e-01 4.12493587e-01 -4.65314239e-02 9.11185741e-01 4.09345269e-01 -4.65314500e-02 9.12615359e-01 4.06149477e-01 -4.65314388e-02 9.14025068e-01 4.02964950e-01 -4.65314500e-02 9.15432632e-01 3.99762809e-01 -4.65314426e-02 9.16788757e-01 3.96637380e-01 -4.65314500e-02 9.18193936e-01 3.93365711e-01 -4.65314500e-02 9.19612169e-01 3.90048563e-01 -4.65314500e-02 9.20957267e-01 3.86860251e-01 -4.65314500e-02 9.22266006e-01 3.83729070e-01 -4.65314500e-02 9.23559487e-01 3.80600244e-01 -4.65314500e-02 9.24914062e-01 3.77299070e-01 -4.65314500e-02 9.26275909e-01 3.73948365e-01 -4.65314500e-02 9.27578092e-01 3.70703489e-01 -4.65314500e-02 9.28832769e-01 3.67555708e-01 -4.65314388e-02 9.30066228e-01 3.64422232e-01 -4.65314500e-02 9.31352556e-01 3.61104429e-01 -4.65314500e-02 9.32630420e-01 3.57820898e-01 -4.65314500e-02 9.33855057e-01 3.54582161e-01 -4.65314500e-02 9.35127795e-01 3.51200283e-01 -4.65314500e-02 9.36318994e-01 3.48010153e-01 -4.65314388e-02 9.37516272e-01 3.44783664e-01 -4.65314500e-02 9.38734114e-01 3.41482520e-01 -4.65314388e-02 9.39902008e-01 3.38237762e-01 -4.65314500e-02 9.41116810e-01 3.34852636e-01 -4.65314500e-02 9.42255497e-01 3.31633747e-01 -4.65314500e-02 9.43390191e-01 3.28383654e-01 -4.65314500e-02 9.44561720e-01 3.25004458e-01 -4.65314500e-02 9.45678771e-01 3.21734875e-01 -4.65314500e-02 9.46779549e-01 3.18488389e-01 -4.65314500e-02 9.47863638e-01 3.15240294e-01 -4.65314500e-02 9.48979020e-01 3.11865568e-01 -4.65314500e-02 9.50091600e-01 3.08464259e-01 -4.65314500e-02 9.51158702e-01 3.05157840e-01 -4.65314500e-02 9.52203214e-01 3.01883638e-01 -4.65314388e-02 9.53214943e-01 2.98670560e-01 -4.65314500e-02 9.54281092e-01 2.95244128e-01 -4.65314500e-02 9.55332518e-01 2.91822821e-01 -4.65314500e-02 9.56342697e-01 2.88496137e-01 -4.65314500e-02 9.57311630e-01 2.85265446e-01 -4.65314500e-02 9.58283424e-01 2.81986922e-01 -4.65314500e-02 9.59281147e-01 2.78574347e-01 -4.65314500e-02 9.60252166e-01 2.75208175e-01 -4.65314500e-02 9.61206198e-01 2.71856189e-01 -4.65314500e-02 9.62170243e-01 2.68425345e-01 -4.65314500e-02 9.63078737e-01 2.65148640e-01 -4.65314388e-02 9.63998079e-01 2.61789501e-01 -4.65314500e-02 9.64933753e-01 2.58313179e-01 -4.65314500e-02 9.65822458e-01 2.54975080e-01 -4.65314500e-02 9.66707885e-01 2.51596302e-01 -4.65314500e-02 9.67563689e-01 2.48291463e-01 -4.65314500e-02 9.68415022e-01 2.44930580e-01 -4.65314500e-02 9.69267607e-01 2.41546869e-01 -4.65314500e-02 9.70109046e-01 2.38144562e-01 -4.65314500e-02 9.70937967e-01 2.34749362e-01 -4.65314500e-02 9.71728027e-01 2.31455684e-01 -4.65314500e-02 9.72544432e-01 2.27999255e-01 -4.65314500e-02 9.73356187e-01 2.24504501e-01 -4.65314500e-02 9.74129558e-01 2.21122012e-01 -4.65314500e-02 9.74898458e-01 2.17711106e-01 -4.65314500e-02 9.75637376e-01 2.14366168e-01 -4.65314500e-02 9.76372421e-01 2.10990459e-01 -4.65314500e-02 9.77122784e-01 2.07497388e-01 -4.65314500e-02 9.77847338e-01 2.04060763e-01 -4.65314500e-02 9.78552461e-01 2.00650081e-01 -4.65314500e-02 9.79229033e-01 1.97319448e-01 -4.65314500e-02 9.79902029e-01 1.93936557e-01 -4.65314500e-02 9.80583251e-01 1.90480739e-01 -4.65314277e-02 9.81233537e-01 1.87083796e-01 -4.65314500e-02 9.81900156e-01 1.83565110e-01 -4.65314500e-02 9.82514620e-01 1.80236086e-01 -4.65314314e-02 9.83149707e-01 1.76770002e-01 -4.65314500e-02 9.83773708e-01 1.73264101e-01 -4.65314500e-02 9.84359860e-01 1.69875816e-01 -4.65314500e-02 9.84936118e-01 1.66509151e-01 -4.65314388e-02 9.85498965e-01 1.63137555e-01 -4.65314500e-02 9.86076355e-01 1.59608155e-01 -4.65314500e-02 9.86642122e-01 1.56071886e-01 -4.65314500e-02 9.87176776e-01 1.52650610e-01 -4.65314500e-02 9.87693369e-01 1.49272576e-01 -4.65314500e-02 9.88196611e-01 1.45908967e-01 -4.65314500e-02 9.88709927e-01 1.42381981e-01 -4.65314500e-02 9.89214778e-01 1.38848156e-01 -4.65314500e-02 9.89692688e-01 1.35405362e-01 -4.65314500e-02 9.90161896e-01 1.31919622e-01 -4.65314500e-02 9.90607738e-01 1.28533170e-01 -4.65314388e-02 9.91045475e-01 1.25106022e-01 -4.65314500e-02 9.91485298e-01 1.21569164e-01 -4.65314500e-02 9.91905153e-01 1.18083350e-01 -4.65314500e-02 9.92311299e-01 1.14626609e-01 -4.65314500e-02 9.92694438e-01 1.11271150e-01 -4.65314500e-02 9.93077755e-01 1.07778654e-01 -4.65314500e-02 9.93449748e-01 1.04315884e-01 -4.65314500e-02 9.93802488e-01 1.00878276e-01 -4.65314500e-02 9.94162381e-01 9.72834006e-02 -4.65314500e-02 9.94485915e-01 9.39268172e-02 -4.65314388e-02 9.94806111e-01 9.04543921e-02 -4.65314500e-02 9.95119572e-01 8.69595185e-02 -4.65314500e-02 9.95415270e-01 8.34778473e-02 -4.65314500e-02 9.95703399e-01 7.99864754e-02 -4.65314500e-02 9.95973647e-01 7.65334964e-02 -4.65314500e-02 9.96240973e-01 7.29730651e-02 -4.65314500e-02 9.96489942e-01 6.94755912e-02 -4.65314500e-02 9.96728897e-01 6.59839287e-02 -4.65314500e-02 9.96947825e-01 6.25845790e-02 -4.65314500e-02 9.97152507e-01 5.92148788e-02 -4.65314500e-02 9.97359276e-01 5.56443781e-02 -4.65314500e-02 9.97553945e-01 5.20424657e-02 -4.65314500e-02 9.97729897e-01 4.85655777e-02 -4.65314500e-02 9.97887492e-01 4.51904759e-02 -4.65314500e-02 9.98034537e-01 4.18392308e-02 -4.65314500e-02 9.98173535e-01 3.83457690e-02 -4.65314500e-02 9.98302460e-01 3.48429233e-02 -4.65314500e-02 9.98420835e-01 3.12470514e-02 -4.65314500e-02 9.98528242e-01 2.76569426e-02 -4.65314500e-02 9.98618960e-01 2.42807530e-02 -4.65314500e-02 9.98689592e-01 2.08994579e-02 -4.65314500e-02 9.98763323e-01 1.74026061e-02 -4.65314500e-02 9.98809755e-01 1.39239877e-02 -4.65314500e-02 9.98857260e-01 1.04057388e-02 -4.65314500e-02 9.98892725e-01 6.95100566e-03 -4.65314500e-02 9.98909295e-01 3.37208156e-03 -4.65314500e-02 9.98911679e-01 -1.22644778e-04 -4.65314500e-02 9.98909235e-01 -3.59584414e-03 -4.65314500e-02 9.98890698e-01 -7.13928835e-03 -4.65314500e-02 9.98855233e-01 -1.05164507e-02 -4.65314500e-02 9.98806953e-01 -1.40368491e-02 -4.65314500e-02 9.98758852e-01 -1.76571365e-02 -4.65314500e-02 9.98687565e-01 -2.10521482e-02 -4.65314500e-02 9.98610437e-01 -2.45466661e-02 -4.65314500e-02 9.98517394e-01 -2.80458592e-02 -4.65314500e-02 9.98413682e-01 -3.14980894e-02 -4.65314500e-02 9.98298645e-01 -3.49994786e-02 -4.65314500e-02 9.98171866e-01 -3.83943543e-02 -4.65314500e-02 9.98033345e-01 -4.18758839e-02 -4.65314500e-02 9.97875869e-01 -4.54259142e-02 -4.65314500e-02 9.97708976e-01 -4.90063652e-02 -4.65314500e-02 9.97527719e-01 -5.25010452e-02 -4.65314500e-02 9.97344375e-01 -5.59056923e-02 -4.65314500e-02 9.97148931e-01 -5.92874251e-02 -4.65314500e-02 9.96934831e-01 -6.27604425e-02 -4.65314500e-02 9.96706247e-01 -6.63159937e-02 -4.65314500e-02 9.96462524e-01 -6.98714554e-02 -4.65314500e-02 9.96213138e-01 -7.33651444e-02 -4.65314500e-02 9.95956540e-01 -7.67648444e-02 -4.65314500e-02 9.95687246e-01 -8.01795796e-02 -4.65314500e-02 9.95404959e-01 -8.36155191e-02 -4.65314500e-02 9.95096147e-01 -8.72101784e-02 -4.65314500e-02 9.94789481e-01 -9.06579122e-02 -4.65314388e-02 9.94474173e-01 -9.40415114e-02 -4.65314500e-02 9.94139314e-01 -9.75207910e-02 -4.65314500e-02 9.93782818e-01 -1.01074956e-01 -4.65314500e-02 9.93424654e-01 -1.04556158e-01 -4.65314500e-02 9.93053675e-01 -1.08001098e-01 -4.65314500e-02 9.92671609e-01 -1.11483410e-01 -4.65314500e-02 9.92287755e-01 -1.14828356e-01 -4.65314500e-02 9.91869509e-01 -1.18390784e-01 -4.65314500e-02 9.91450727e-01 -1.21859878e-01 -4.65314388e-02 9.91018951e-01 -1.25325933e-01 -4.65314500e-02 9.90561187e-01 -1.28879726e-01 -4.65314500e-02 9.90117669e-01 -1.32250518e-01 -4.65314500e-02 9.89653945e-01 -1.35682747e-01 -4.65314500e-02 9.89160895e-01 -1.39233440e-01 -4.65314500e-02 9.88676667e-01 -1.42630726e-01 -4.65314351e-02 9.88175452e-01 -1.46049201e-01 -4.65314500e-02 9.87662137e-01 -1.49486765e-01 -4.65314500e-02 9.87132430e-01 -1.52931198e-01 -4.65314500e-02 9.86588359e-01 -1.56416669e-01 -4.65314388e-02 9.86042440e-01 -1.59816757e-01 -4.65314500e-02 9.85485077e-01 -1.63230553e-01 -4.65314500e-02 9.84898508e-01 -1.66729286e-01 -4.65314500e-02 9.84294772e-01 -1.70243979e-01 -4.65314500e-02 9.83705282e-01 -1.73648000e-01 -4.65314500e-02 9.83106673e-01 -1.77004933e-01 -4.65314500e-02 9.82488334e-01 -1.80375263e-01 -4.65314500e-02 9.81854975e-01 -1.83809936e-01 -4.65314500e-02 9.81197119e-01 -1.87275335e-01 -4.65314500e-02 9.80521262e-01 -1.90786570e-01 -4.65314500e-02 9.79847312e-01 -1.94221586e-01 -4.65314500e-02 9.79176760e-01 -1.97573304e-01 -4.65314500e-02 9.78503227e-01 -2.00881913e-01 -4.65314500e-02 9.77793217e-01 -2.04313815e-01 -4.65314500e-02 9.77059662e-01 -2.07794175e-01 -4.65314500e-02 9.76327479e-01 -2.11210653e-01 -4.65314500e-02 9.75597084e-01 -2.14548707e-01 -4.65314500e-02 9.74834502e-01 -2.17999905e-01 -4.65314500e-02 9.74068105e-01 -2.21384481e-01 -4.65314500e-02 9.73284781e-01 -2.24819124e-01 -4.65314388e-02 9.72487807e-01 -2.28238359e-01 -4.65314500e-02 9.71688330e-01 -2.31623739e-01 -4.65314500e-02 9.70903456e-01 -2.34890699e-01 -4.65314500e-02 9.70050931e-01 -2.38375708e-01 -4.65314500e-02 9.69216585e-01 -2.41747990e-01 -4.65314500e-02 9.68353748e-01 -2.45172605e-01 -4.65314500e-02 9.67471540e-01 -2.48639584e-01 -4.65314500e-02 9.66625750e-01 -2.51911283e-01 -4.65314500e-02 9.65749919e-01 -2.55251914e-01 -4.65314500e-02 9.64843512e-01 -2.58659631e-01 -4.65314388e-02 9.63964343e-01 -2.61912674e-01 -4.65314500e-02 9.63020861e-01 -2.65351504e-01 -4.65314500e-02 9.62078691e-01 -2.68761307e-01 -4.65314500e-02 9.61140454e-01 -2.72086978e-01 -4.65314500e-02 9.60150242e-01 -2.75558591e-01 -4.65314500e-02 9.59212184e-01 -2.78810948e-01 -4.65314500e-02 9.58261847e-01 -2.82058686e-01 -4.65314500e-02 9.57246363e-01 -2.85488307e-01 -4.65314500e-02 9.56225157e-01 -2.88880616e-01 -4.65314500e-02 9.55212891e-01 -2.92217523e-01 -4.65314500e-02 9.54205573e-01 -2.95496762e-01 -4.65314500e-02 9.53196526e-01 -2.98729777e-01 -4.65314500e-02 9.52147126e-01 -3.02056998e-01 -4.65314500e-02 9.51059937e-01 -3.05460989e-01 -4.65314500e-02 9.49949682e-01 -3.08895499e-01 -4.65314500e-02 9.48866963e-01 -3.12208116e-01 -4.65314500e-02 9.47798014e-01 -3.15442711e-01 -4.65314500e-02 9.46731448e-01 -3.18626612e-01 -4.65314500e-02 9.45608795e-01 -3.21943194e-01 -4.65314500e-02 9.44454908e-01 -3.25308979e-01 -4.65314500e-02 9.43299353e-01 -3.28645915e-01 -4.65314500e-02 9.42179441e-01 -3.31844896e-01 -4.65314500e-02 9.41023052e-01 -3.35109323e-01 -4.65314500e-02 9.39821541e-01 -3.38462919e-01 -4.65314500e-02 9.38625276e-01 -3.41776758e-01 -4.65314500e-02 9.37426209e-01 -3.45028222e-01 -4.65314500e-02 9.36198354e-01 -3.48333061e-01 -4.65314500e-02 9.35022831e-01 -3.51482153e-01 -4.65314500e-02 9.33793545e-01 -3.54745477e-01 -4.65314500e-02 9.32556748e-01 -3.58008325e-01 -4.65314500e-02 9.31287944e-01 -3.61276209e-01 -4.65314500e-02 9.29996490e-01 -3.64597797e-01 -4.65314500e-02 9.28715527e-01 -3.67845863e-01 -4.65314500e-02 9.27436352e-01 -3.71054590e-01 -4.65314500e-02 9.26122785e-01 -3.74324590e-01 -4.65314500e-02 9.24855828e-01 -3.77443880e-01 -4.65314500e-02 9.23495948e-01 -3.80756050e-01 -4.65314500e-02 9.22151566e-01 -3.84003669e-01 -4.65314500e-02 9.20812011e-01 -3.87206525e-01 -4.65314500e-02 9.19412196e-01 -3.90511930e-01 -4.65314500e-02 9.18078840e-01 -3.93637717e-01 -4.65314500e-02 9.16747689e-01 -3.96731228e-01 -4.65314500e-02 9.15325344e-01 -4.00004834e-01 -4.65314500e-02 9.13862765e-01 -4.03333396e-01 -4.65314500e-02 9.12451923e-01 -4.06514168e-01 -4.65314500e-02 9.11044419e-01 -4.09661353e-01 -4.65314500e-02 9.09645140e-01 -4.12757903e-01 -4.65314500e-02 9.08229828e-01 -4.15858269e-01 -4.65314500e-02 9.06741738e-01 -4.19091851e-01 -4.65314500e-02 9.05230343e-01 -4.22347963e-01 -4.65314500e-02 9.03736413e-01 -4.25536305e-01 -4.65314500e-02 9.02282894e-01 -4.28612053e-01 -4.65314500e-02 9.00843561e-01 -4.31624115e-01 -4.65314500e-02 8.99329543e-01 -4.34779346e-01 -4.65314500e-02 8.97766292e-01 -4.37996745e-01 -4.65314500e-02 8.96196246e-01 -4.41197246e-01 -4.65314500e-02 8.94657016e-01 -4.44308013e-01 -4.65314500e-02 8.93118620e-01 -4.47394818e-01 -4.65314500e-02 8.91599417e-01 -4.50416446e-01 -4.65314500e-02 8.90021265e-01 -4.53525692e-01 -4.65314500e-02 8.88395190e-01 -4.56701368e-01 -4.65314500e-02 8.86778116e-01 -4.59832340e-01 -4.65314500e-02 8.85165989e-01 -4.62929934e-01 -4.65314500e-02 8.83572459e-01 -4.65967655e-01 -4.65314500e-02 8.81970108e-01 -4.68988478e-01 -4.65314500e-02 8.80331337e-01 -4.72060114e-01 -4.65314500e-02 8.78626108e-01 -4.75222439e-01 -4.65314500e-02 8.76955986e-01 -4.78305459e-01 -4.65314500e-02 8.75327051e-01 -4.81274813e-01 -4.65314500e-02 8.73652995e-01 -4.84305024e-01 -4.65314500e-02 8.71916354e-01 -4.87423748e-01 -4.65314500e-02 8.70206892e-01 -4.90473688e-01 -4.65314500e-02 8.68487120e-01 -4.93508726e-01 -4.65314500e-02 8.66753876e-01 -4.96553451e-01 -4.65314500e-02 8.65025282e-01 -4.99552965e-01 -4.65314500e-02 8.63265216e-01 -5.02591670e-01 -4.65314500e-02 8.61556351e-01 -5.05514979e-01 -4.65314500e-02 8.59760582e-01 -5.08561492e-01 -4.65314500e-02 8.57959092e-01 -5.11594653e-01 -4.65314500e-02 8.56154263e-01 -5.14608562e-01 -4.65314500e-02 8.54323685e-01 -5.17638624e-01 -4.65314500e-02 8.52550209e-01 -5.20561576e-01 -4.65314500e-02 8.50777507e-01 -5.23447514e-01 -4.65314500e-02 8.48953843e-01 -5.26404858e-01 -4.65314500e-02 8.47067475e-01 -5.29428959e-01 -4.65314500e-02 8.45174730e-01 -5.32450020e-01 -4.65314500e-02 8.43353927e-01 -5.35328507e-01 -4.65314500e-02 8.41515720e-01 -5.38211644e-01 -4.65314500e-02 8.39583039e-01 -5.41221023e-01 -4.65314500e-02 8.37646723e-01 -5.44214010e-01 -4.65314500e-02 8.35743248e-01 -5.47131479e-01 -4.65314500e-02 8.33830357e-01 -5.50045490e-01 -4.65314500e-02 8.31948817e-01 -5.52884161e-01 -4.65314500e-02 8.30056429e-01 -5.55721462e-01 -4.65314500e-02 8.28132391e-01 -5.58590412e-01 -4.65314500e-02 8.26118708e-01 -5.61558664e-01 -4.65314500e-02 8.24091434e-01 -5.64533532e-01 -4.65314500e-02 8.22153151e-01 -5.67353725e-01 -4.65314500e-02 8.20205212e-01 -5.70164919e-01 -4.65314500e-02 8.18232715e-01 -5.72988510e-01 -4.65314500e-02 8.16215336e-01 -5.75864732e-01 -4.65314500e-02 8.14173222e-01 -5.78741491e-01 -4.65314500e-02 8.12143326e-01 -5.81592202e-01 -4.65314500e-02 8.10140789e-01 -5.84372044e-01 -4.65314500e-02 8.08054864e-01 -5.87256193e-01 -4.65314500e-02 8.05969715e-01 -5.90113759e-01 -4.65314500e-02 8.03890109e-01 -5.92944920e-01 -4.65314500e-02 8.01796854e-01 -5.95771492e-01 -4.65314500e-02 7.99785793e-01 -5.98469138e-01 -4.65314500e-02 7.97706902e-01 -6.01236641e-01 -4.65314500e-02 7.95599341e-01 -6.04025245e-01 -4.65314500e-02 7.93481946e-01 -6.06801569e-01 -4.65314500e-02 7.91353285e-01 -6.09576821e-01 -4.65314500e-02 7.89278150e-01 -6.12258375e-01 -4.65314500e-02 7.87085950e-01 -6.15074396e-01 -4.65314500e-02 7.84875393e-01 -6.17893934e-01 -4.65314500e-02 7.82766342e-01 -6.20563269e-01 -4.65314500e-02 7.80658603e-01 -6.23215377e-01 -4.65314500e-02 7.78426170e-01 -6.25999689e-01 -4.65314500e-02 7.76176691e-01 -6.28788590e-01 -4.65314500e-02 7.74014831e-01 -6.31443620e-01 -4.65314500e-02 7.71869242e-01 -6.34066582e-01 -4.65314500e-02 7.69662201e-01 -6.36744440e-01 -4.65314500e-02 7.67443180e-01 -6.39417171e-01 -4.65314500e-02 7.65207231e-01 -6.42090976e-01 -4.65314500e-02 7.62895942e-01 -6.44834042e-01 -4.65314500e-02 7.60641038e-01 -6.47492766e-01 -4.65314500e-02 7.58438170e-01 -6.50071323e-01 -4.65314500e-02 7.56171882e-01 -6.52708113e-01 -4.65314500e-02 7.53859520e-01 -6.55377686e-01 -4.65314500e-02 7.51510739e-01 -6.58067703e-01 -4.65314500e-02 7.49169767e-01 -6.60732925e-01 -4.65314500e-02 7.46900201e-01 -6.63298368e-01 -4.65314500e-02 7.44657338e-01 -6.65814161e-01 -4.65314500e-02 7.42274463e-01 -6.68469071e-01 -4.65314500e-02 7.39933074e-01 -6.71062231e-01 -4.65314500e-02 7.37582922e-01 -6.73640311e-01 -4.65314500e-02 7.35226810e-01 -6.76215470e-01 -4.65314500e-02 7.32941151e-01 -6.78690314e-01 -4.65314500e-02 7.30578959e-01 -6.81230366e-01 -4.65314500e-02 7.28117287e-01 -6.83860958e-01 -4.65314500e-02 7.25713611e-01 -6.86411619e-01 -4.65314500e-02 7.23315179e-01 -6.88941956e-01 -4.65314500e-02 7.20895946e-01 -6.91468418e-01 -4.65314277e-02 7.18517661e-01 -6.93950236e-01 -4.65314500e-02 7.16069520e-01 -6.96477532e-01 -4.65313755e-02 7.13745058e-01 -6.98857725e-01 -4.65313643e-02 7.11373627e-01 -7.01279461e-01 -4.65312861e-02 7.08865941e-01 -7.03811646e-01 -4.65309471e-02 7.06635714e-01 -7.06044614e-01 -4.65311632e-02 7.03793168e-01 -7.08878398e-01 -4.65311222e-02 7.01743662e-01 -7.10907340e-01 -4.65311222e-02 0. 0. 0. 6.97409213e-01 -7.15161026e-01 -4.65311185e-02 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. 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. 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. 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. 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. 0. 5.66510558e-01 -8.22738826e-01 -4.65311185e-02 5.63839972e-01 -8.24571788e-01 -4.65310216e-02 5.61306477e-01 -8.26300681e-01 -4.65312898e-02 5.58517814e-01 -8.28184783e-01 -4.65313531e-02 5.55639744e-01 -8.30116272e-01 -4.65313904e-02 5.52661121e-01 -8.32099140e-01 -4.65314277e-02 5.49754262e-01 -8.34023714e-01 -4.65314239e-02 5.46910107e-01 -8.35889399e-01 -4.65314500e-02 5.44018745e-01 -8.37774456e-01 -4.65314500e-02 5.41094422e-01 -8.39665771e-01 -4.65314500e-02 5.38180351e-01 -8.41535211e-01 -4.65314500e-02 5.35236120e-01 -8.43410432e-01 -4.65314500e-02 5.32298267e-01 -8.45271647e-01 -4.65314500e-02 5.29352188e-01 -8.47116053e-01 -4.65314500e-02 5.26390791e-01 -8.48962128e-01 -4.65314500e-02 5.23418605e-01 -8.50795984e-01 -4.65314500e-02 5.20463586e-01 -8.52610528e-01 -4.65314500e-02 5.17470121e-01 -8.54427457e-01 -4.65314500e-02 5.14483511e-01 -8.56229663e-01 -4.65314500e-02 5.11415601e-01 -8.58064711e-01 -4.65314500e-02 5.08381665e-01 -8.59866738e-01 -4.65314500e-02 5.05484521e-01 -8.61572802e-01 -4.65314500e-02 5.02474487e-01 -8.63330781e-01 -4.65314500e-02 4.99363571e-01 -8.65134656e-01 -4.65314500e-02 4.96334642e-01 -8.66877735e-01 -4.65314500e-02 4.93369520e-01 -8.68565500e-01 -4.65314500e-02 4.90358502e-01 -8.70273829e-01 -4.65314500e-02 4.87325877e-01 -8.71972322e-01 -4.65314500e-02 4.84292716e-01 -8.73658359e-01 -4.65314500e-02 4.81242925e-01 -8.75345647e-01 -4.65314500e-02 4.78174120e-01 -8.77025723e-01 -4.65314500e-02 4.75089580e-01 -8.78698230e-01 -4.65314500e-02 4.72030163e-01 -8.80346119e-01 -4.65314500e-02 4.68950808e-01 -8.81989896e-01 -4.65314500e-02 4.65871632e-01 -8.83622408e-01 -4.65314500e-02 4.62717086e-01 -8.85275781e-01 -4.65314500e-02 4.59599078e-01 -8.86899054e-01 -4.65314500e-02 4.56583083e-01 -8.88457119e-01 -4.65314500e-02 4.53493088e-01 -8.90037656e-01 -4.65314500e-02 4.50373828e-01 -8.91619802e-01 -4.65314500e-02 4.47259188e-01 -8.93185616e-01 -4.65314500e-02 4.44128722e-01 -8.94747376e-01 -4.65314500e-02 4.41008419e-01 -8.96289468e-01 -4.65314500e-02 4.37862307e-01 -8.97831380e-01 -4.65314500e-02 4.34712857e-01 -8.99360359e-01 -4.65314500e-02 4.31579739e-01 -9.00865316e-01 -4.65314500e-02 4.28323478e-01 -9.02417243e-01 -4.65314500e-02 4.25161928e-01 -9.03913856e-01 -4.65314500e-02 4.22039419e-01 -9.05375004e-01 -4.65314500e-02 4.18854833e-01 -9.06853855e-01 -4.65314500e-02 4.15790528e-01 -9.08260763e-01 -4.65314500e-02 4.12609875e-01 -9.09712493e-01 -4.65314500e-02 4.09429014e-01 -9.11148012e-01 -4.65314500e-02 4.06156719e-01 -9.12611067e-01 -4.65314500e-02 4.02951598e-01 -9.14031148e-01 -4.65314500e-02 3.99864197e-01 -9.15387154e-01 -4.65314500e-02 3.96673203e-01 -9.16771889e-01 -4.65314500e-02 3.93461674e-01 -9.18152332e-01 -4.65314500e-02 3.90219599e-01 -9.19537663e-01 -4.65314500e-02 3.87036979e-01 -9.20883715e-01 -4.65314500e-02 3.83834809e-01 -9.22221839e-01 -4.65314500e-02 3.80585670e-01 -9.23566937e-01 -4.65314500e-02 3.77411753e-01 -9.24869835e-01 -4.65314500e-02 3.74170572e-01 -9.26184654e-01 -4.65314500e-02 3.70850593e-01 -9.27517891e-01 -4.65314500e-02 3.67580742e-01 -9.28821266e-01 -4.65314500e-02 3.64425957e-01 -9.30063903e-01 -4.65314500e-02 3.61182362e-01 -9.31320906e-01 -4.65314500e-02 3.57933074e-01 -9.32583630e-01 -4.65314500e-02 3.54670733e-01 -9.33822036e-01 -4.65314500e-02 3.51409346e-01 -9.35049891e-01 -4.65314500e-02 3.48128617e-01 -9.36275363e-01 -4.65314500e-02 3.44789386e-01 -9.37514722e-01 -4.65314500e-02 3.41497511e-01 -9.38726783e-01 -4.65314500e-02 3.38270873e-01 -9.39890206e-01 -4.65314500e-02 3.34965020e-01 -9.41076159e-01 -4.65314500e-02 3.31665456e-01 -9.42241490e-01 -4.65314500e-02 3.28364611e-01 -9.43396986e-01 -4.65314500e-02 3.25077325e-01 -9.44535077e-01 -4.65314500e-02 3.21768880e-01 -9.45666671e-01 -4.65314500e-02 3.18550766e-01 -9.46756959e-01 -4.65314500e-02 3.15225095e-01 -9.47867453e-01 -4.65314500e-02 3.11902881e-01 -9.48966503e-01 -4.65314500e-02 3.08625579e-01 -9.50037301e-01 -4.65314500e-02 3.05305481e-01 -9.51111138e-01 -4.65314500e-02 3.01999539e-01 -9.52164531e-01 -4.65314500e-02 2.98688620e-01 -9.53209400e-01 -4.65314500e-02 2.95337170e-01 -9.54253256e-01 -4.65314500e-02 2.92026460e-01 -9.55271721e-01 -4.65314500e-02 2.88620204e-01 -9.56302762e-01 -4.65314500e-02 2.85260022e-01 -9.57313418e-01 -4.65314500e-02 2.81997770e-01 -9.58280146e-01 -4.65314500e-02 2.78557301e-01 -9.59284842e-01 -4.65314500e-02 2.75133133e-01 -9.60273087e-01 -4.65314500e-02 2.71763325e-01 -9.61232543e-01 -4.65314500e-02 2.68524885e-01 -9.62143719e-01 -4.65314500e-02 2.65270293e-01 -9.63044107e-01 -4.65314500e-02 2.61890620e-01 -9.63971078e-01 -4.65314500e-02 2.58527756e-01 -9.64875579e-01 -4.65314500e-02 2.55077481e-01 -9.65792656e-01 -4.65314500e-02 2.51685292e-01 -9.66685414e-01 -4.65314500e-02 2.48314843e-01 -9.67553437e-01 -4.65314500e-02 2.44926631e-01 -9.68417585e-01 -4.65314500e-02 2.41576225e-01 -9.69257057e-01 -4.65314500e-02 2.38158956e-01 -9.70105886e-01 -4.65314500e-02 2.34858200e-01 -9.70910490e-01 -4.65314500e-02 2.31438637e-01 -9.71731842e-01 -4.65314500e-02 2.28037551e-01 -9.72535431e-01 -4.65314500e-02 2.24691018e-01 -9.73313570e-01 -4.65314500e-02 2.21171796e-01 -9.74117100e-01 -4.65314500e-02 2.17761621e-01 -9.74887609e-01 -4.65314500e-02 2.14453354e-01 -9.75618184e-01 -4.65314500e-02 2.11030632e-01 -9.76364791e-01 -4.65314500e-02 2.07637161e-01 -9.77092683e-01 -4.65314500e-02 2.04148561e-01 -9.77827728e-01 -4.65314500e-02 2.00717658e-01 -9.78539109e-01 -4.65314500e-02 1.97398767e-01 -9.79211688e-01 -4.65314500e-02 1.93962082e-01 -9.79898691e-01 -4.65314500e-02 1.90537065e-01 -9.80570436e-01 -4.65314500e-02 1.87039033e-01 -9.81241822e-01 -4.65314500e-02 1.83597103e-01 -9.81893480e-01 -4.65314500e-02 1.80179954e-01 -9.82523561e-01 -4.65314500e-02 1.76743135e-01 -9.83155251e-01 -4.65314500e-02 1.73414558e-01 -9.83746827e-01 -4.65314500e-02 1.69982746e-01 -9.84339535e-01 -4.65314500e-02 1.66552067e-01 -9.84928608e-01 -4.65314500e-02 1.63105175e-01 -9.85502958e-01 -4.65314500e-02 1.59671813e-01 -9.86065984e-01 -4.65314500e-02 1.56246871e-01 -9.86615241e-01 -4.65314500e-02 1.52803943e-01 -9.87154484e-01 -4.65314500e-02 1.49340242e-01 -9.87682223e-01 -4.65314500e-02 1.45860791e-01 -9.88202631e-01 -4.65314500e-02 1.42406285e-01 -9.88706052e-01 -4.65314500e-02 1.38993606e-01 -9.89192426e-01 -4.65314500e-02 1.35436773e-01 -9.89686012e-01 -4.65314500e-02 1.31976888e-01 -9.90153134e-01 -4.65314500e-02 1.28596112e-01 -9.90598679e-01 -4.65314500e-02 1.25145718e-01 -9.91041064e-01 -4.65314500e-02 1.21686585e-01 -9.91470337e-01 -4.65314500e-02 1.18120082e-01 -9.91901278e-01 -4.65314500e-02 1.14665397e-01 -9.92307007e-01 -4.65314500e-02 1.11311257e-01 -9.92689192e-01 -4.65314500e-02 1.07824542e-01 -9.93073523e-01 -4.65314500e-02 1.04385078e-01 -9.93440628e-01 -4.65314500e-02 1.00808635e-01 -9.93807673e-01 -4.65314500e-02 9.73323658e-02 -9.94157434e-01 -4.65314500e-02 9.38932449e-02 -9.94488835e-01 -4.65314500e-02 9.03785974e-02 -9.94814992e-01 -4.65314500e-02 8.69447291e-02 -9.95119333e-01 -4.65314500e-02 8.33729431e-02 -9.95424688e-01 -4.65314500e-02 7.99700171e-02 -9.95705247e-01 -4.65314500e-02 7.66028017e-02 -9.95967984e-01 -4.65314500e-02 7.31197000e-02 -9.96231258e-01 -4.65314500e-02 6.96342662e-02 -9.96478677e-01 -4.65314500e-02 6.61680102e-02 -9.96716678e-01 -4.65314500e-02 6.26965612e-02 -9.96940911e-01 -4.65314500e-02 5.91977201e-02 -9.97154355e-01 -4.65314500e-02 5.57061099e-02 -9.97356355e-01 -4.65314500e-02 5.22408672e-02 -9.97541785e-01 -4.65314500e-02 4.87656631e-02 -9.97720540e-01 -4.65314500e-02 4.53029312e-02 -9.97882962e-01 -4.65314500e-02 4.17166948e-02 -9.98037040e-01 -4.65314500e-02 3.82243469e-02 -9.98178780e-01 -4.65314500e-02 3.48508023e-02 -9.98301804e-01 -4.65314500e-02 3.12653296e-02 -9.98419821e-01 -4.65314500e-02 2.77526025e-02 -9.98525977e-01 -4.65314500e-02 2.42814478e-02 -9.98616934e-01 -4.65314500e-02 2.07749940e-02 -9.98693168e-01 -4.65314500e-02 1.74207129e-02 -9.98763025e-01 -4.65314500e-02 1.38335228e-02 -9.98807967e-01 -4.65314500e-02 1.03138434e-02 -9.98856843e-01 -4.65314500e-02 6.95307599e-03 -9.98892307e-01 -4.65314500e-02 3.46579403e-03 -9.98909712e-01 -4.65314500e-02 -3.72573923e-05 -9.98910725e-01 -4.65314500e-02 -3.61242122e-03 -9.98908937e-01 -4.65314500e-02 -7.10398331e-03 -9.98891950e-01 -4.65314500e-02 -1.05836364e-02 -9.98854160e-01 -4.65314500e-02 -1.40616521e-02 -9.98807967e-01 -4.65314500e-02 -1.75340790e-02 -9.98762012e-01 -4.65314500e-02 -2.11078953e-02 -9.98685241e-01 -4.65314500e-02 -2.45294236e-02 -9.98611569e-01 -4.65314500e-02 -2.79359408e-02 -9.98520434e-01 -4.65314500e-02 -3.14138979e-02 -9.98417616e-01 -4.65314500e-02 -3.48955989e-02 -9.98301923e-01 -4.65314500e-02 -3.84709500e-02 -9.98168826e-01 -4.65314500e-02 -4.19745110e-02 -9.98029292e-01 -4.65314500e-02 -4.53551710e-02 -9.97879446e-01 -4.65314500e-02 -4.88268360e-02 -9.97717440e-01 -4.65314500e-02 -5.23117892e-02 -9.97537732e-01 -4.65314500e-02 -5.58600277e-02 -9.97348070e-01 -4.65314500e-02 -5.93562685e-02 -9.97146428e-01 -4.65314500e-02 -6.28461987e-02 -9.96928275e-01 -4.65314500e-02 -6.63145259e-02 -9.96706247e-01 -4.65314500e-02 -6.97024018e-02 -9.96474087e-01 -4.65314500e-02 -7.32667819e-02 -9.96219575e-01 -4.65314500e-02 -7.67506883e-02 -9.95956719e-01 -4.65314500e-02 -8.02152604e-02 -9.95683610e-01 -4.65314500e-02 -8.37011784e-02 -9.95396972e-01 -4.65314500e-02 -8.70890915e-02 -9.95106518e-01 -4.65314500e-02 -9.06389877e-02 -9.94788587e-01 -4.65314500e-02 -9.41324830e-02 -9.94464993e-01 -4.65314500e-02 -9.75786075e-02 -9.94132161e-01 -4.65314500e-02 -1.01067722e-01 -9.93785918e-01 -4.65314500e-02 -1.04514427e-01 -9.93427217e-01 -4.65314500e-02 -1.08095214e-01 -9.93044674e-01 -4.65314500e-02 -1.11449048e-01 -9.92674232e-01 -4.65314500e-02 -1.14798106e-01 -9.92291927e-01 -4.65314500e-02 -1.18309282e-01 -9.91878450e-01 -4.65314500e-02 -1.21756174e-01 -9.91462409e-01 -4.65314500e-02 -1.25299007e-01 -9.91020620e-01 -4.65314500e-02 -1.28788233e-01 -9.90572512e-01 -4.65314500e-02 -1.32130235e-01 -9.90133882e-01 -4.65314500e-02 -1.35586843e-01 -9.89665866e-01 -4.65314500e-02 -1.39030755e-01 -9.89188194e-01 -4.65314500e-02 -1.42585725e-01 -9.88680065e-01 -4.65314500e-02 -1.46032706e-01 -9.88178015e-01 -4.65314500e-02 -1.49474859e-01 -9.87661362e-01 -4.65314500e-02 -1.52929083e-01 -9.87136900e-01 -4.65314500e-02 -1.56266183e-01 -9.86611009e-01 -4.65314500e-02 -1.59723878e-01 -9.86058533e-01 -4.65314500e-02 -1.63146898e-01 -9.85498786e-01 -4.65314500e-02 -1.66698128e-01 -9.84903336e-01 -4.65314500e-02 -1.70151427e-01 -9.84311879e-01 -4.65314500e-02 -1.73482567e-01 -9.83734012e-01 -4.65314500e-02 -1.76981241e-01 -9.83109236e-01 -4.65314500e-02 -1.80404305e-01 -9.82482910e-01 -4.65314500e-02 -1.83876306e-01 -9.81841981e-01 -4.65314500e-02 -1.87316567e-01 -9.81190979e-01 -4.65314500e-02 -1.90639183e-01 -9.80550110e-01 -4.65314500e-02 -1.94061548e-01 -9.79878962e-01 -4.65314500e-02 -1.97532237e-01 -9.79184806e-01 -4.65314500e-02 -2.01000407e-01 -9.78478491e-01 -4.65314500e-02 -2.04322517e-01 -9.77790058e-01 -4.65314500e-02 -2.07728907e-01 -9.77075279e-01 -4.65314500e-02 -2.11216465e-01 -9.76325095e-01 -4.65314500e-02 -2.14638487e-01 -9.75576639e-01 -4.65314500e-02 -2.17956305e-01 -9.74843025e-01 -4.65314500e-02 -2.21357271e-01 -9.74074841e-01 -4.65314500e-02 -2.24753216e-01 -9.73296881e-01 -4.65314500e-02 -2.28225216e-01 -9.72491980e-01 -4.65314500e-02 -2.31627077e-01 -9.71686482e-01 -4.65314500e-02 -2.34922662e-01 -9.70895469e-01 -4.65314500e-02 -2.38388166e-01 -9.70048547e-01 -4.65314500e-02 -2.41777927e-01 -9.69209194e-01 -4.65314500e-02 -2.45162457e-01 -9.68355954e-01 -4.65314500e-02 -2.48536184e-01 -9.67499197e-01 -4.65314500e-02 -2.51819581e-01 -9.66648281e-01 -4.65314500e-02 -2.55205303e-01 -9.65761244e-01 -4.65314500e-02 -2.58653462e-01 -9.64841187e-01 -4.65314500e-02 -2.62113810e-01 -9.63908970e-01 -4.65314500e-02 -2.65415013e-01 -9.63004529e-01 -4.65314500e-02 -2.68654287e-01 -9.62107062e-01 -4.65314500e-02 -2.72042960e-01 -9.61153805e-01 -4.65314500e-02 -2.75391996e-01 -9.60198283e-01 -4.65314500e-02 -2.78728336e-01 -9.59236026e-01 -4.65314500e-02 -2.82071471e-01 -9.58257437e-01 -4.65314500e-02 -2.85404980e-01 -9.57271874e-01 -4.65314500e-02 -2.88742781e-01 -9.56267297e-01 -4.65314500e-02 -2.92086571e-01 -9.55250561e-01 -4.65314500e-02 -2.95500547e-01 -9.54203248e-01 -4.65314500e-02 -2.98863828e-01 -9.53154266e-01 -4.65314500e-02 -3.02167773e-01 -9.52111781e-01 -4.65314500e-02 -3.05501044e-01 -9.51049864e-01 -4.65314500e-02 -3.08705598e-01 -9.50012565e-01 -4.65314500e-02 -3.12101364e-01 -9.48901176e-01 -4.65314500e-02 -3.15481573e-01 -9.47783589e-01 -4.65314500e-02 -3.18772942e-01 -9.46683228e-01 -4.65314500e-02 -3.22038412e-01 -9.45576310e-01 -4.65314500e-02 -3.25227022e-01 -9.44484174e-01 -4.65314500e-02 -3.28566551e-01 -9.43326592e-01 -4.65314500e-02 -3.31855863e-01 -9.42175567e-01 -4.65314500e-02 -3.35181475e-01 -9.40996706e-01 -4.65314500e-02 -3.38480741e-01 -9.39814866e-01 -4.65314500e-02 -3.41748029e-01 -9.38633025e-01 -4.65314500e-02 -3.45021069e-01 -9.37427998e-01 -4.65314500e-02 -3.48219514e-01 -9.36240494e-01 -4.65314500e-02 -3.51484239e-01 -9.35021102e-01 -4.65314500e-02 -3.54738563e-01 -9.33796704e-01 -4.65314500e-02 -3.58092844e-01 -9.32522833e-01 -4.65314500e-02 -3.61441672e-01 -9.31222796e-01 -4.65314500e-02 -3.64605844e-01 -9.29992616e-01 -4.65314500e-02 -3.67751569e-01 -9.28752601e-01 -4.65314500e-02 -3.70970428e-01 -9.27470446e-01 -4.65314500e-02 -3.74205977e-01 -9.26170766e-01 -4.65314500e-02 -3.77519667e-01 -9.24823463e-01 -4.65314500e-02 -3.80846053e-01 -9.23457921e-01 -4.65314500e-02 -3.83986413e-01 -9.22158718e-01 -4.65314500e-02 -3.87100935e-01 -9.20855761e-01 -4.65314500e-02 -3.90323371e-01 -9.19493616e-01 -4.65314500e-02 -3.93611133e-01 -9.18086767e-01 -4.65314500e-02 -3.96849096e-01 -9.16696608e-01 -4.65314500e-02 -4.00020272e-01 -9.15317953e-01 -4.65314500e-02 -4.03221518e-01 -9.13912773e-01 -4.65314500e-02 -4.06316906e-01 -9.12540019e-01 -4.65314500e-02 -4.09510225e-01 -9.11112309e-01 -4.65314500e-02 -4.12675202e-01 -9.09681022e-01 -4.65314500e-02 -4.15906578e-01 -9.08207238e-01 -4.65314500e-02 -4.19082880e-01 -9.06746745e-01 -4.65314500e-02 -4.22181666e-01 -9.05308187e-01 -4.65314500e-02 -4.25331056e-01 -9.03833508e-01 -4.65314500e-02 -4.28561777e-01 -9.02305663e-01 -4.65314500e-02 -4.31717783e-01 -9.00798619e-01 -4.65314500e-02 -4.34785932e-01 -8.99326801e-01 -4.65314500e-02 -4.37927157e-01 -8.97801280e-01 -4.65314500e-02 -4.41128373e-01 -8.96228552e-01 -4.65314500e-02 -4.44240957e-01 -8.94693375e-01 -4.65314500e-02 -4.47282046e-01 -8.93174529e-01 -4.65314500e-02 -4.50407535e-01 -8.91604424e-01 -4.65314500e-02 -4.53503340e-01 -8.90033066e-01 -4.65314500e-02 -4.56696242e-01 -8.88397992e-01 -4.65314500e-02 -4.59795386e-01 -8.86797369e-01 -4.65314500e-02 -4.62801307e-01 -8.85235906e-01 -4.65314500e-02 -4.65878189e-01 -8.83618116e-01 -4.65314500e-02 -4.68941331e-01 -8.81995976e-01 -4.65314500e-02 -4.72117305e-01 -8.80301058e-01 -4.65314500e-02 -4.75197762e-01 -8.78640592e-01 -4.65314500e-02 -4.78257149e-01 -8.76980126e-01 -4.65314500e-02 -4.81317669e-01 -8.75304222e-01 -4.65314500e-02 -4.84369129e-01 -8.73615980e-01 -4.65314500e-02 -4.87516493e-01 -8.71865332e-01 -4.65314500e-02 -4.90474015e-01 -8.70206654e-01 -4.65314500e-02 -4.93484557e-01 -8.68501425e-01 -4.65314500e-02 -4.96526062e-01 -8.66768479e-01 -4.65314500e-02 -4.99464989e-01 -8.65076184e-01 -4.65314500e-02 -5.02492607e-01 -8.63321543e-01 -4.65314500e-02 -5.05511224e-01 -8.61557424e-01 -4.65314500e-02 -5.08501709e-01 -8.59795809e-01 -4.65314500e-02 -5.11488914e-01 -8.58021855e-01 -4.65314500e-02 -5.14478743e-01 -8.56232822e-01 -4.65314500e-02 -5.17488658e-01 -8.54415298e-01 -4.65314500e-02 -5.20545840e-01 -8.52559745e-01 -4.65314500e-02 -5.23579478e-01 -8.50696445e-01 -4.65314500e-02 -5.26485503e-01 -8.48902762e-01 -4.65314500e-02 -5.29344261e-01 -8.47123861e-01 -4.65314500e-02 -5.32376885e-01 -8.45218658e-01 -4.65314500e-02 -5.35347581e-01 -8.43341708e-01 -4.65314500e-02 -5.38278282e-01 -8.41471791e-01 -4.65314500e-02 -5.41227162e-01 -8.39580715e-01 -4.65314500e-02 -5.44041276e-01 -8.37758422e-01 -4.65314500e-02 -5.47050655e-01 -8.35795283e-01 -4.65314500e-02 -5.49985826e-01 -8.33871543e-01 -4.65314500e-02 -5.52798986e-01 -8.32003355e-01 -4.65314500e-02 -5.55701435e-01 -8.30070436e-01 -4.65314500e-02 -5.58676243e-01 -8.28073382e-01 -4.65314500e-02 -5.61585069e-01 -8.26099575e-01 -4.65314500e-02 -5.64363062e-01 -8.24208856e-01 -4.65314500e-02 -5.67237616e-01 -8.22232366e-01 -4.65314500e-02 -5.70100009e-01 -8.20248723e-01 -4.65314500e-02 -5.73037982e-01 -8.18197548e-01 -4.65314500e-02 -5.76009750e-01 -8.16112041e-01 -4.65314500e-02 -5.78779340e-01 -8.14148426e-01 -4.65314500e-02 -5.81511617e-01 -8.12199473e-01 -4.65314500e-02 -5.84348083e-01 -8.10156345e-01 -4.65314500e-02 -5.87182581e-01 -8.08109581e-01 -4.65314500e-02 -5.90069771e-01 -8.06000888e-01 -4.65314500e-02 -5.92966020e-01 -8.03873599e-01 -4.65314500e-02 -5.95698833e-01 -8.01851749e-01 -4.65314500e-02 -5.98395348e-01 -7.99838305e-01 -4.65314500e-02 -6.01194263e-01 -7.97738612e-01 -4.65314500e-02 -6.04041874e-01 -7.95586526e-01 -4.65314500e-02 -6.06842697e-01 -7.93451190e-01 -4.65314500e-02 -6.09588087e-01 -7.91341126e-01 -4.65314500e-02 -6.12360120e-01 -7.89201081e-01 -4.65314500e-02 -6.15023613e-01 -7.87126243e-01 -4.65314500e-02 -6.17843568e-01 -7.84914553e-01 -4.65314500e-02 -6.20580614e-01 -7.82753766e-01 -4.65314500e-02 -6.23299956e-01 -7.80588508e-01 -4.65314500e-02 -6.26030743e-01 -7.78401732e-01 -4.65314500e-02 -6.28661513e-01 -7.76279330e-01 -4.65314500e-02 -6.31359637e-01 -7.74083257e-01 -4.65314500e-02 -6.34054959e-01 -7.71878779e-01 -4.65314500e-02 -6.36819184e-01 -7.69599438e-01 -4.65314500e-02 -6.39503539e-01 -7.67370641e-01 -4.65314500e-02 -6.42102003e-01 -7.65198052e-01 -4.65314500e-02 -6.44841790e-01 -7.62888491e-01 -4.65314500e-02 -6.47508204e-01 -7.60628998e-01 -4.65314500e-02 -6.50083780e-01 -7.58427441e-01 -4.65314500e-02 -6.52733266e-01 -7.56150186e-01 -4.65314500e-02 -6.55361533e-01 -7.53874123e-01 -4.65314500e-02 -6.58071101e-01 -7.51505911e-01 -4.65314500e-02 -6.60686970e-01 -7.49210298e-01 -4.65314500e-02 -6.63221180e-01 -7.46967435e-01 -4.65314500e-02 -6.65828645e-01 -7.44642735e-01 -4.65314500e-02 -6.68409169e-01 -7.42327809e-01 -4.65314500e-02 -6.71066701e-01 -7.39928901e-01 -4.65314500e-02 -6.73647642e-01 -7.37576485e-01 -4.65314500e-02 -6.76212847e-01 -7.35228598e-01 -4.65314500e-02 -6.78779960e-01 -7.32858658e-01 -4.65314500e-02 -6.81334496e-01 -7.30481207e-01 -4.65314500e-02 -6.83955908e-01 -7.28028297e-01 -4.65314500e-02 -6.86425328e-01 -7.25700498e-01 -4.65314500e-02 -6.88931942e-01 -7.23323882e-01 -4.65314500e-02 -6.91472054e-01 -7.20889866e-01 -4.65314500e-02 -6.93909407e-01 -7.18556762e-01 -4.65314500e-02 -6.96407020e-01 -7.16134250e-01 -4.65314500e-02 -6.98891163e-01 -7.13707030e-01 -4.65314500e-02 -7.01457143e-01 -7.11185038e-01 -4.65314500e-02 -7.03959346e-01 -7.08713710e-01 -4.65314500e-02 -7.06323266e-01 -7.06337988e-01 -4.65314500e-02 -7.08797455e-01 -7.03873754e-01 -4.65314500e-02 -7.11327553e-01 -7.01314092e-01 -4.65314500e-02 -7.13800430e-01 -6.98796213e-01 -4.65314500e-02 -7.16148198e-01 -6.96392298e-01 -4.65314500e-02 -7.18566716e-01 -6.93899512e-01 -4.65314500e-02 -7.21035898e-01 -6.91317439e-01 -4.65314500e-02 -7.23526835e-01 -6.88721001e-01 -4.65314500e-02 -7.25933552e-01 -6.86177373e-01 -4.65314500e-02 -7.28270650e-01 -6.83698118e-01 -4.65314500e-02 -7.30576098e-01 -6.81233466e-01 -4.65314500e-02 -7.33008146e-01 -6.78617179e-01 -4.65314500e-02 -7.35381365e-01 -6.76047027e-01 -4.65314500e-02 -7.37673700e-01 -6.73543215e-01 -4.65314500e-02 -7.40031242e-01 -6.70952499e-01 -4.65314500e-02 -7.42373407e-01 -6.68359756e-01 -4.65314500e-02 -7.44693518e-01 -6.65773451e-01 -4.65314500e-02 -7.47010231e-01 -6.63174272e-01 -4.65314500e-02 -7.49384344e-01 -6.60486758e-01 -4.65314500e-02 -7.51685858e-01 -6.57869339e-01 -4.65314500e-02 -7.53974795e-01 -6.55242860e-01 -4.65314500e-02 -7.56321967e-01 -6.52532160e-01 -4.65314500e-02 -7.58540809e-01 -6.49954677e-01 -4.65314500e-02 -7.60786653e-01 -6.47320449e-01 -4.65314500e-02 -7.63055563e-01 -6.44648612e-01 -4.65314500e-02 -7.65236139e-01 -6.42054617e-01 -4.65314500e-02 -7.67518938e-01 -6.39326513e-01 -4.65314500e-02 -7.69759655e-01 -6.36627257e-01 -4.65314500e-02 -7.71926820e-01 -6.33997917e-01 -4.65314500e-02 -7.74126053e-01 -6.31307185e-01 -4.65314500e-02 -7.76327193e-01 -6.28601074e-01 -4.65314500e-02 -7.78567255e-01 -6.25823617e-01 -4.65314500e-02 -7.80805707e-01 -6.23030126e-01 -4.65314500e-02 -7.82989860e-01 -6.20280504e-01 -4.65314500e-02 -7.85101652e-01 -6.17607772e-01 -4.65314500e-02 -7.87180901e-01 -6.14955604e-01 -4.65314500e-02 -7.89368749e-01 -6.12143040e-01 -4.65314500e-02 -7.91505337e-01 -6.09380305e-01 -4.65314500e-02 -7.93622136e-01 -6.06619358e-01 -4.65314500e-02 -7.95757294e-01 -6.03817105e-01 -4.65314500e-02 -7.97779977e-01 -6.01142824e-01 -4.65314500e-02 -7.99864471e-01 -5.98361611e-01 -4.65314500e-02 -8.01941514e-01 -5.95573783e-01 -4.65314500e-02 -8.04072797e-01 -5.92694521e-01 -4.65314500e-02 -8.06158721e-01 -5.89856744e-01 -4.65314500e-02 -8.08221459e-01 -5.87024927e-01 -4.65314500e-02 -8.10312867e-01 -5.84133089e-01 -4.65314500e-02 -8.12285364e-01 -5.81393242e-01 -4.65314500e-02 -8.14304411e-01 -5.78558326e-01 -4.65314500e-02 -8.16329002e-01 -5.75701296e-01 -4.65314500e-02 -8.18275094e-01 -5.72928905e-01 -4.65314500e-02 -8.20324302e-01 -5.69989741e-01 -4.65314500e-02 -8.22323620e-01 -5.67107141e-01 -4.65314500e-02 -8.24221671e-01 -5.64341605e-01 -4.65314500e-02 -8.26205432e-01 -5.61432540e-01 -4.65314500e-02 -8.28160584e-01 -5.58546305e-01 -4.65314500e-02 -8.30151916e-01 -5.55577576e-01 -4.65314500e-02 -8.32101882e-01 -5.52654922e-01 -4.65314500e-02 -8.34022403e-01 -5.49750924e-01 -4.65314500e-02 -8.35940778e-01 -5.46830654e-01 -4.65314500e-02 -8.37795615e-01 -5.43985784e-01 -4.65314500e-02 -8.39681625e-01 -5.41069567e-01 -4.65314500e-02 -8.41549277e-01 -5.38159788e-01 -4.65314500e-02 -8.43475580e-01 -5.35133302e-01 -4.65314500e-02 -8.45339835e-01 -5.32189429e-01 -4.65314500e-02 -8.47133875e-01 -5.29324889e-01 -4.65314500e-02 -8.48983169e-01 -5.26358128e-01 -4.65314500e-02 -8.50811958e-01 -5.23391128e-01 -4.65314500e-02 -8.52675378e-01 -5.20354331e-01 -4.65314500e-02 -8.54495108e-01 -5.17359853e-01 -4.65314500e-02 -8.56288671e-01 -5.14385760e-01 -4.65314500e-02 -8.58070493e-01 -5.11405110e-01 -4.65314500e-02 -8.59811068e-01 -5.08475244e-01 -4.65314500e-02 -8.61608326e-01 -5.05423307e-01 -4.65314500e-02 -8.63374293e-01 -5.02401352e-01 -4.65314500e-02 -8.65085721e-01 -4.99451607e-01 -4.65314500e-02 -8.66807342e-01 -4.96454418e-01 -4.65314500e-02 -8.68543386e-01 -4.93408799e-01 -4.65314500e-02 -8.70264947e-01 -4.90373135e-01 -4.65314500e-02 -8.71963024e-01 -4.87339765e-01 -4.65314500e-02 -8.73653293e-01 -4.84301716e-01 -4.65314500e-02 -8.75392258e-01 -4.81155723e-01 -4.65314500e-02 -8.77069831e-01 -4.78096426e-01 -4.65314500e-02 -8.78688693e-01 -4.75107372e-01 -4.65314500e-02 -8.80351424e-01 -4.72020566e-01 -4.65314500e-02 -8.82055759e-01 -4.68827367e-01 -4.65314500e-02 -8.83726358e-01 -4.65671152e-01 -4.65314500e-02 -8.85292053e-01 -4.62690771e-01 -4.65314500e-02 -8.86850119e-01 -4.59694713e-01 -4.65314500e-02 -8.88454854e-01 -4.56587911e-01 -4.65314500e-02 -8.90085518e-01 -4.53395337e-01 -4.65314500e-02 -8.91668797e-01 -4.50278997e-01 -4.65314500e-02 -8.93186212e-01 -4.47257578e-01 -4.65314500e-02 -8.94783258e-01 -4.44056362e-01 -4.65314500e-02 -8.96338403e-01 -4.40909415e-01 -4.65314500e-02 -8.97829235e-01 -4.37867016e-01 -4.65314500e-02 -8.99384916e-01 -4.34662342e-01 -4.65314500e-02 -9.00943875e-01 -4.31417078e-01 -4.65314500e-02 -9.02447820e-01 -4.28262234e-01 -4.65314500e-02 -9.03900325e-01 -4.25189048e-01 -4.65314500e-02 -9.05337155e-01 -4.22124475e-01 -4.65314500e-02 -9.06846881e-01 -4.18868005e-01 -4.65314500e-02 -9.08347845e-01 -4.15601999e-01 -4.65314500e-02 -9.09743547e-01 -4.12539482e-01 -4.65314500e-02 -9.11147237e-01 -4.09429997e-01 -4.65314500e-02 -9.12569046e-01 -4.06250596e-01 -4.65314500e-02 -9.14016485e-01 -4.02983129e-01 -4.65314500e-02 -9.15425420e-01 -3.99779320e-01 -4.65314500e-02 -9.16803360e-01 -3.96600515e-01 -4.65314500e-02 -9.18194115e-01 -3.93364012e-01 -4.65314500e-02 -9.19518948e-01 -3.90263081e-01 -4.65314500e-02 -9.20909345e-01 -3.86972219e-01 -4.65314500e-02 -9.22257781e-01 -3.83748233e-01 -4.65314500e-02 -9.23584580e-01 -3.80540669e-01 -4.65314500e-02 -9.24918711e-01 -3.77290189e-01 -4.65314500e-02 -9.26196456e-01 -3.74138594e-01 -4.65314500e-02 -9.27525222e-01 -3.70830625e-01 -4.65314500e-02 -9.28823471e-01 -3.67575794e-01 -4.65314500e-02 -9.30091083e-01 -3.64354461e-01 -4.65314500e-02 -9.31362212e-01 -3.61076683e-01 -4.65314500e-02 -9.32592094e-01 -3.57914418e-01 -4.65314500e-02 -9.33853865e-01 -3.54588360e-01 -4.65314500e-02 -9.35084403e-01 -3.51317555e-01 -4.65314500e-02 -9.36262965e-01 -3.48161697e-01 -4.65314500e-02 -9.37503576e-01 -3.44817668e-01 -4.65314500e-02 -9.38715994e-01 -3.41525853e-01 -4.65314500e-02 -9.39900160e-01 -3.38241190e-01 -4.65314500e-02 -9.41080749e-01 -3.34952444e-01 -4.65314500e-02 -9.42236781e-01 -3.31678122e-01 -4.65314500e-02 -9.43391800e-01 -3.28379869e-01 -4.65314500e-02 -9.44506168e-01 -3.25164497e-01 -4.65314500e-02 -9.45632696e-01 -3.21870238e-01 -4.65314500e-02 -9.46746171e-01 -3.18582416e-01 -4.65314500e-02 -9.47879791e-01 -3.15186560e-01 -4.65314500e-02 -9.48978543e-01 -3.11866492e-01 -4.65314500e-02 -9.50038016e-01 -3.08626324e-01 -4.65314500e-02 -9.51132715e-01 -3.05235445e-01 -4.65314500e-02 -9.52195346e-01 -3.01908642e-01 -4.65314500e-02 -9.53242481e-01 -2.98581868e-01 -4.65314500e-02 -9.54275906e-01 -2.95262307e-01 -4.65314500e-02 -9.55295146e-01 -2.91943401e-01 -4.65314500e-02 -9.56311703e-01 -2.88601041e-01 -4.65314500e-02 -9.57279444e-01 -2.85371453e-01 -4.65314500e-02 -9.58297193e-01 -2.81937242e-01 -4.65314500e-02 -9.59282160e-01 -2.78574258e-01 -4.65314500e-02 -9.60222661e-01 -2.75306553e-01 -4.65314500e-02 -9.61174786e-01 -2.71966100e-01 -4.65314500e-02 -9.62127447e-01 -2.68578798e-01 -4.65314500e-02 -9.63057041e-01 -2.65221983e-01 -4.65314500e-02 -9.63974118e-01 -2.61880487e-01 -4.65314500e-02 -9.64882255e-01 -2.58501530e-01 -4.65314500e-02 -9.65799570e-01 -2.55054444e-01 -4.65314500e-02 -9.66714442e-01 -2.51568496e-01 -4.65314500e-02 -9.67568636e-01 -2.48265922e-01 -4.65314500e-02 -9.68398154e-01 -2.44995579e-01 -4.65314500e-02 -9.69267249e-01 -2.41536692e-01 -4.65314500e-02 -9.70134318e-01 -2.38041773e-01 -4.65314500e-02 -9.70937669e-01 -2.34747782e-01 -4.65314500e-02 -9.71727908e-01 -2.31452942e-01 -4.65314500e-02 -9.72526729e-01 -2.28069469e-01 -4.65314500e-02 -9.73333657e-01 -2.24593550e-01 -4.65314500e-02 -9.74120140e-01 -2.21162409e-01 -4.65314500e-02 -9.74862516e-01 -2.17868924e-01 -4.65314500e-02 -9.75633562e-01 -2.14382097e-01 -4.65314500e-02 -9.76379454e-01 -2.10960299e-01 -4.65314500e-02 -9.77092385e-01 -2.07639381e-01 -4.65314500e-02 -9.77809668e-01 -2.04236194e-01 -4.65314500e-02 -9.78531718e-01 -2.00751379e-01 -4.65314500e-02 -9.79240835e-01 -1.97258472e-01 -4.65314500e-02 -9.79912162e-01 -1.93900436e-01 -4.65314500e-02 -9.80568290e-01 -1.90552354e-01 -4.65314500e-02 -9.81233537e-01 -1.87083185e-01 -4.65314500e-02 -9.81895983e-01 -1.83583006e-01 -4.65314500e-02 -9.82520401e-01 -1.80201158e-01 -4.65314500e-02 -9.83133316e-01 -1.76861942e-01 -4.65314500e-02 -9.83742416e-01 -1.73445970e-01 -4.65314500e-02 -9.84347045e-01 -1.69942841e-01 -4.65314500e-02 -9.84951317e-01 -1.66415498e-01 -4.65314500e-02 -9.85513031e-01 -1.63057029e-01 -4.65314500e-02 -9.86059606e-01 -1.59720182e-01 -4.65314500e-02 -9.86617923e-01 -1.56232059e-01 -4.65314500e-02 -9.87168252e-01 -1.52711734e-01 -4.65314500e-02 -9.87692058e-01 -1.49285853e-01 -4.65314500e-02 -9.88208175e-01 -1.45827726e-01 -4.65314500e-02 -9.88712370e-01 -1.42372862e-01 -4.65314500e-02 -9.89190578e-01 -1.39017656e-01 -4.65314500e-02 -9.89680946e-01 -1.35478318e-01 -4.65314500e-02 -9.90148604e-01 -1.32016957e-01 -4.65314500e-02 -9.90603209e-01 -1.28563091e-01 -4.65314500e-02 -9.91046250e-01 -1.25110209e-01 -4.65314500e-02 -9.91467416e-01 -1.21709861e-01 -4.65314500e-02 -9.91894007e-01 -1.18173562e-01 -4.65314500e-02 -9.92302418e-01 -1.14695184e-01 -4.65314500e-02 -9.92696643e-01 -1.11242324e-01 -4.65314500e-02 -9.93091524e-01 -1.07667260e-01 -4.65314500e-02 -9.93449330e-01 -1.04313955e-01 -4.65314277e-02 -9.93804514e-01 -1.00887388e-01 -4.65314239e-02 -9.94143128e-01 -9.75492820e-02 -4.65312935e-02 -9.94451523e-01 -9.43392664e-02 -4.65310626e-02 -9.94778574e-01 -9.08255950e-02 -4.65311147e-02 -9.95067894e-01 -8.75997469e-02 -4.65311185e-02 -9.95376706e-01 -8.40215907e-02 -4.65311222e-02 -9.95758176e-01 -7.93735012e-02 -4.65311185e-02 -9.95995283e-01 -7.63317272e-02 -4.65311185e-02 -9.96252894e-01 -7.28980154e-02 -4.65311222e-02 -9.96464431e-01 -6.99417144e-02 -4.65311185e-02 -9.96697068e-01 -6.65500611e-02 -4.65311222e-02 -9.96952832e-01 -6.26065284e-02 -4.65311222e-02 -9.97182608e-01 -5.88360578e-02 -4.65311222e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98532236e-01 -2.77170278e-02 -4.65311222e-02 0. 0. 0. -9.98671472e-01 -2.21401043e-02 -4.65311185e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98401582e-01 3.91922407e-02 -4.07072827e-02 -9.98258173e-01 4.26995791e-02 -4.07072864e-02 -9.98100400e-01 4.62684222e-02 -4.07073535e-02 -9.97957408e-01 4.90641221e-02 -4.07070629e-02 -9.97782290e-01 5.24458252e-02 -4.07069959e-02 -9.97598588e-01 5.58117703e-02 -4.07069586e-02 -9.97392297e-01 5.93699329e-02 -4.07069176e-02 -9.97171104e-01 6.29603639e-02 -4.07069214e-02 -9.96945322e-01 6.64469972e-02 -4.07069176e-02 -9.96706784e-01 6.99134246e-02 -4.07069176e-02 -9.96460497e-01 7.33656362e-02 -4.07069176e-02 -9.96195614e-01 7.68619254e-02 -4.07069176e-02 -9.95921612e-01 8.03530887e-02 -4.07069176e-02 -9.95632410e-01 8.38424191e-02 -4.07069176e-02 -9.95342433e-01 8.72356370e-02 -4.07069437e-02 -9.95046139e-01 9.05470327e-02 -4.07069176e-02 -9.94712174e-01 9.41412076e-02 -4.07069176e-02 -9.94367719e-01 9.77185294e-02 -4.07069176e-02 -9.94022191e-01 1.01178192e-01 -4.07069176e-02 -9.93661880e-01 1.04655758e-01 -4.07069176e-02 -9.93299961e-01 1.08033210e-01 -4.07069214e-02 -9.92929280e-01 1.11393578e-01 -4.07069176e-02 -9.92518842e-01 1.14970572e-01 -4.07069176e-02 -9.92100358e-01 1.18534319e-01 -4.07069176e-02 -9.91692364e-01 1.21919662e-01 -4.07069214e-02 -9.91262674e-01 1.25361398e-01 -4.07069176e-02 -9.90805328e-01 1.28918707e-01 -4.07069176e-02 -9.90346074e-01 1.32397592e-01 -4.07069176e-02 -9.89879549e-01 1.35852590e-01 -4.07069176e-02 -9.89405453e-01 1.39265835e-01 -4.07069176e-02 -9.88930643e-01 1.42592564e-01 -4.07069214e-02 -9.88415122e-01 1.46103904e-01 -4.07069176e-02 -9.87881660e-01 1.49673820e-01 -4.07069176e-02 -9.87352610e-01 1.53137818e-01 -4.07069176e-02 -9.86828208e-01 1.56479970e-01 -4.07069325e-02 -9.86277699e-01 1.59909889e-01 -4.07069176e-02 -9.85698223e-01 1.63452446e-01 -4.07069176e-02 -9.85137284e-01 1.66797444e-01 -4.07069437e-02 -9.84547436e-01 1.70233160e-01 -4.07069176e-02 -9.83951092e-01 1.73682928e-01 -4.07069214e-02 -9.83356833e-01 1.77006111e-01 -4.07069176e-02 -9.82711196e-01 1.80527925e-01 -4.07069176e-02 -9.82057393e-01 1.84063941e-01 -4.07069176e-02 -9.81414139e-01 1.87461957e-01 -4.07069176e-02 -9.80754495e-01 1.90877765e-01 -4.07069176e-02 -9.80080903e-01 1.94316208e-01 -4.07069176e-02 -9.79412675e-01 1.97652265e-01 -4.07069214e-02 -9.78719711e-01 2.01051638e-01 -4.07069176e-02 -9.77991760e-01 2.04569146e-01 -4.07069214e-02 -9.77288842e-01 2.07911387e-01 -4.07069363e-02 -9.76560235e-01 2.11303249e-01 -4.07069176e-02 -9.75795567e-01 2.14799806e-01 -4.07069176e-02 -9.75040078e-01 2.18207836e-01 -4.07069176e-02 -9.74272668e-01 2.21604615e-01 -4.07069176e-02 -9.73507881e-01 2.24950805e-01 -4.07069400e-02 -9.72744048e-01 2.28228003e-01 -4.07069176e-02 -9.71941113e-01 2.31625974e-01 -4.07069176e-02 -9.71111655e-01 2.35079363e-01 -4.07069176e-02 -9.70252395e-01 2.38594264e-01 -4.07069176e-02 -9.69436109e-01 2.41888225e-01 -4.07069437e-02 -9.68586326e-01 2.45261401e-01 -4.07069176e-02 -9.67702389e-01 2.48739481e-01 -4.07069176e-02 -9.66835082e-01 2.52090812e-01 -4.07069176e-02 -9.65953112e-01 2.55446076e-01 -4.07069176e-02 -9.65074837e-01 2.58749217e-01 -4.07069437e-02 -9.64185059e-01 2.62041867e-01 -4.07069176e-02 -9.63241577e-01 2.65476495e-01 -4.07069176e-02 -9.62285936e-01 2.68932700e-01 -4.07069176e-02 -9.61335063e-01 2.72307396e-01 -4.07069176e-02 -9.60375130e-01 2.75671959e-01 -4.07069176e-02 -9.59412515e-01 2.79003441e-01 -4.07069176e-02 -9.58437383e-01 2.82338738e-01 -4.07069176e-02 -9.57448006e-01 2.85680503e-01 -4.07069176e-02 -9.56442177e-01 2.89020419e-01 -4.07069176e-02 -9.55455780e-01 2.92272061e-01 -4.07069325e-02 -9.54458296e-01 2.95515865e-01 -4.07069176e-02 -9.53390956e-01 2.98937142e-01 -4.07069176e-02 -9.52320814e-01 3.02323312e-01 -4.07069176e-02 -9.51282620e-01 3.05583119e-01 -4.07069474e-02 -9.50221717e-01 3.08857083e-01 -4.07069176e-02 -9.49117601e-01 3.12238246e-01 -4.07069176e-02 -9.48019087e-01 3.15557331e-01 -4.07069214e-02 -9.46910918e-01 3.18868130e-01 -4.07069176e-02 -9.45779920e-01 3.22207540e-01 -4.07069176e-02 -9.44676220e-01 3.25436056e-01 -4.07069474e-02 -9.43541110e-01 3.28699380e-01 -4.07069176e-02 -9.42349851e-01 3.32106054e-01 -4.07069176e-02 -9.41209316e-01 3.35330635e-01 -4.07069214e-02 -9.40035641e-01 3.38596702e-01 -4.07069176e-02 -9.38867152e-01 3.41833442e-01 -4.07069251e-02 -9.37689006e-01 3.45026493e-01 -4.07069176e-02 -9.36437666e-01 3.48397493e-01 -4.07069176e-02 -9.35180366e-01 3.51763994e-01 -4.07069176e-02 -9.33958769e-01 3.55006367e-01 -4.07069176e-02 -9.32722867e-01 3.58265877e-01 -4.07069176e-02 -9.31456327e-01 3.61522585e-01 -4.07069176e-02 -9.30231094e-01 3.64672601e-01 -4.07069437e-02 -9.28967535e-01 3.67877960e-01 -4.07069176e-02 -9.27660704e-01 3.71160448e-01 -4.07069176e-02 -9.26336825e-01 3.74452323e-01 -4.07069176e-02 -9.25054491e-01 3.77613813e-01 -4.07069214e-02 -9.23738182e-01 3.80815506e-01 -4.07069176e-02 -9.22368288e-01 3.84126931e-01 -4.07069176e-02 -9.21016812e-01 3.87357712e-01 -4.07069176e-02 -9.19661403e-01 3.90558064e-01 -4.07069176e-02 -9.18287456e-01 3.93775403e-01 -4.07069176e-02 -9.16944921e-01 3.96895081e-01 -4.07069176e-02 -9.15545940e-01 4.00117934e-01 -4.07069176e-02 -9.14117038e-01 4.03368920e-01 -4.07069176e-02 -9.12703097e-01 4.06557202e-01 -4.07069176e-02 -9.11277890e-01 4.09740478e-01 -4.07069176e-02 -9.09856796e-01 4.12886202e-01 -4.07069176e-02 -9.08408284e-01 4.16059673e-01 -4.07069176e-02 -9.06952322e-01 4.19227034e-01 -4.07069176e-02 -9.05479610e-01 4.22400057e-01 -4.07069176e-02 -9.04033720e-01 4.25486654e-01 -4.07069214e-02 -9.02583420e-01 4.28552598e-01 -4.07069176e-02 -9.01048124e-01 4.31768566e-01 -4.07069176e-02 -8.99495244e-01 4.35005277e-01 -4.07069176e-02 -8.97974133e-01 4.38136429e-01 -4.07069176e-02 -8.96453559e-01 4.41232830e-01 -4.07069176e-02 -8.94916594e-01 4.44343477e-01 -4.07069176e-02 -8.93363059e-01 4.47458297e-01 -4.07069176e-02 -8.91793370e-01 4.50577706e-01 -4.07069176e-02 -8.90185952e-01 4.53746974e-01 -4.07069176e-02 -8.88639688e-01 4.56768692e-01 -4.07069214e-02 -8.87039661e-01 4.59863096e-01 -4.07069176e-02 -8.85401905e-01 4.63014901e-01 -4.07069176e-02 -8.83768857e-01 4.66124386e-01 -4.07069176e-02 -8.82131875e-01 4.69213217e-01 -4.07069176e-02 -8.80489171e-01 4.72288519e-01 -4.07069176e-02 -8.78877044e-01 4.75281030e-01 -4.07069400e-02 -8.77216935e-01 4.78340238e-01 -4.07069176e-02 -8.75486434e-01 4.81497854e-01 -4.07069176e-02 -8.73808086e-01 4.84533489e-01 -4.07069176e-02 -8.72159600e-01 4.87496763e-01 -4.07069214e-02 -8.70461762e-01 4.90520656e-01 -4.07069176e-02 -8.68683934e-01 4.93661910e-01 -4.07069176e-02 -8.66975486e-01 4.96659040e-01 -4.07069176e-02 -8.65239739e-01 4.99678135e-01 -4.07069176e-02 -8.63519728e-01 5.02644956e-01 -4.07069214e-02 -8.61814618e-01 5.05561531e-01 -4.07069176e-02 -8.59980524e-01 5.08670688e-01 -4.07069176e-02 -8.58149767e-01 5.11756778e-01 -4.07069176e-02 -8.56345236e-01 5.14771044e-01 -4.07069176e-02 -8.54544818e-01 5.17751932e-01 -4.07069176e-02 -8.52786064e-01 5.20648599e-01 -4.07069214e-02 -8.50964725e-01 5.23614228e-01 -4.07069176e-02 -8.49083602e-01 5.26665449e-01 -4.07069176e-02 -8.47245157e-01 5.29614687e-01 -4.07069176e-02 -8.45433176e-01 5.32504618e-01 -4.07069176e-02 -8.43573928e-01 5.35440683e-01 -4.07069176e-02 -8.41635227e-01 5.38484037e-01 -4.07069176e-02 -8.39750946e-01 5.41418314e-01 -4.07069176e-02 -8.37840974e-01 5.44368804e-01 -4.07069176e-02 -8.35942090e-01 5.47277212e-01 -4.07069176e-02 -8.34102452e-01 5.50082922e-01 -4.07069214e-02 -8.32230449e-01 5.52903891e-01 -4.07069176e-02 -8.30241323e-01 5.55889606e-01 -4.07069176e-02 -8.28233719e-01 5.58880448e-01 -4.07069176e-02 -8.26337874e-01 5.61677277e-01 -4.07069214e-02 -8.24370801e-01 5.64560294e-01 -4.07069176e-02 -8.22338998e-01 5.67518473e-01 -4.07069176e-02 -8.20350707e-01 5.70387423e-01 -4.07069176e-02 -8.18341315e-01 5.73264062e-01 -4.07069176e-02 -8.16389203e-01 5.76044977e-01 -4.07069214e-02 -8.14424574e-01 5.78817189e-01 -4.07069176e-02 -8.12341154e-01 5.81736028e-01 -4.07069176e-02 -8.10235262e-01 5.84662259e-01 -4.07069176e-02 -8.08183670e-01 5.87500155e-01 -4.07069176e-02 -8.06136489e-01 5.90302944e-01 -4.07069176e-02 -8.04085672e-01 5.93095779e-01 -4.07069176e-02 -8.02036703e-01 5.95862448e-01 -4.07069176e-02 -7.99936712e-01 5.98678350e-01 -4.07069176e-02 -7.97830284e-01 6.01484716e-01 -4.07069176e-02 -7.95787036e-01 6.04186535e-01 -4.07069437e-02 -7.93674827e-01 6.06956124e-01 -4.07069176e-02 -7.91462243e-01 6.09837949e-01 -4.07069176e-02 -7.89332211e-01 6.12591326e-01 -4.07069176e-02 -7.87186980e-01 6.15347564e-01 -4.07069176e-02 -7.85077333e-01 6.18037641e-01 -4.07069214e-02 -7.82958984e-01 6.20717824e-01 -4.07069176e-02 -7.80742288e-01 6.23504043e-01 -4.07069176e-02 -7.78543532e-01 6.26246870e-01 -4.07069176e-02 -7.76338577e-01 6.28980219e-01 -4.07069176e-02 -7.74199128e-01 6.31611347e-01 -4.07069549e-02 -7.72002399e-01 6.34293616e-01 -4.07069176e-02 -7.69704342e-01 6.37081444e-01 -4.07069214e-02 -7.67486632e-01 6.39751792e-01 -4.07069176e-02 -7.65254140e-01 6.42420292e-01 -4.07069437e-02 -7.63042986e-01 6.45044863e-01 -4.07069474e-02 -7.60866165e-01 6.47610784e-01 -4.07069214e-02 -7.58529425e-01 6.50344133e-01 -4.07069176e-02 -7.56220341e-01 6.53031290e-01 -4.07069176e-02 -7.53922641e-01 6.55681551e-01 -4.07069214e-02 -7.51608610e-01 6.58331633e-01 -4.07069176e-02 -7.49340355e-01 6.60913169e-01 -4.07069176e-02 -7.47037530e-01 6.63515747e-01 -4.07069214e-02 -7.44678736e-01 6.66161895e-01 -4.07069176e-02 -7.42353797e-01 6.68750048e-01 -4.07069176e-02 -7.40086377e-01 6.71263576e-01 -4.07069437e-02 -7.37810075e-01 6.73758805e-01 -4.07069176e-02 -7.35392928e-01 6.76399827e-01 -4.07069176e-02 -7.32940555e-01 6.79056287e-01 -4.07069214e-02 -7.30586469e-01 6.81585968e-01 -4.07069214e-02 -7.28202701e-01 6.84132159e-01 -4.07069176e-02 -7.25803792e-01 6.86675489e-01 -4.07069176e-02 -7.23469675e-01 6.89138770e-01 -4.07069474e-02 -7.21059024e-01 6.91651106e-01 -4.07069176e-02 -7.18577921e-01 6.94243252e-01 -4.07069214e-02 -7.16197312e-01 6.96696520e-01 -4.07069437e-02 -7.13775039e-01 6.99173689e-01 -4.07069176e-02 -7.11263239e-01 7.01732635e-01 -4.07069176e-02 -7.08815992e-01 7.04207003e-01 -4.07069176e-02 -7.06338286e-01 7.06671894e-01 -4.07069176e-02 -7.03938603e-01 7.09082425e-01 -4.07069437e-02 -7.01468647e-01 7.11522818e-01 -4.07069176e-02 -6.98905110e-01 7.14037895e-01 -4.07069176e-02 -6.96482539e-01 7.16406167e-01 -4.07069474e-02 -6.93957865e-01 7.18853176e-01 -4.07069176e-02 -6.91430509e-01 7.21273005e-01 -4.07069512e-02 -6.88949168e-01 7.23650098e-01 -4.07069176e-02 -6.86318576e-01 7.26140440e-01 -4.07069176e-02 -6.83768511e-01 7.28543222e-01 -4.07069176e-02 -6.81250870e-01 7.30897367e-01 -4.07069325e-02 -6.78758204e-01 7.33216345e-01 -4.07069474e-02 -6.76218510e-01 7.35559583e-01 -4.07069176e-02 -6.73616946e-01 7.37941563e-01 -4.07069474e-02 -6.71050847e-01 7.40275323e-01 -4.07069176e-02 -6.68366194e-01 7.42701054e-01 -4.07069176e-02 -6.65837944e-01 7.44966686e-01 -4.07069214e-02 -6.63318753e-01 7.47213364e-01 -4.07069176e-02 -6.60655379e-01 7.49565363e-01 -4.07069176e-02 -6.57953918e-01 7.51937151e-01 -4.07069176e-02 -6.55330837e-01 7.54228234e-01 -4.07069214e-02 -6.52716160e-01 7.56489694e-01 -4.07069176e-02 -6.50113344e-01 7.58730292e-01 -4.07069363e-02 -6.47476196e-01 7.60977626e-01 -4.07069176e-02 -6.44741952e-01 7.63298512e-01 -4.07069176e-02 -6.42065763e-01 7.65550613e-01 -4.07069176e-02 -6.39446557e-01 7.67741680e-01 -4.07069214e-02 -6.36808753e-01 7.69927859e-01 -4.07069176e-02 -6.33999228e-01 7.72246540e-01 -4.07069176e-02 -6.31372750e-01 7.74392545e-01 -4.07069214e-02 -6.28675699e-01 7.76584864e-01 -4.07069176e-02 -6.25971437e-01 7.78766453e-01 -4.07069214e-02 -6.23252273e-01 7.80943930e-01 -4.07069176e-02 -6.20448291e-01 7.83172727e-01 -4.07069176e-02 -6.17768347e-01 7.85289168e-01 -4.07069214e-02 -6.15034699e-01 7.87431359e-01 -4.07069176e-02 -6.12203658e-01 7.89633691e-01 -4.07069176e-02 -6.09454811e-01 7.91757643e-01 -4.07069176e-02 -6.06720686e-01 7.93856621e-01 -4.07069176e-02 -6.03949130e-01 7.95966268e-01 -4.07069176e-02 -6.01096928e-01 7.98121214e-01 -4.07069176e-02 -5.98290622e-01 8.00225973e-01 -4.07069176e-02 -5.95575154e-01 8.02252352e-01 -4.07069437e-02 -5.92786372e-01 8.04310620e-01 -4.07069176e-02 -5.89873195e-01 8.06451321e-01 -4.07069176e-02 -5.87144613e-01 8.08442771e-01 -4.07069214e-02 -5.84338427e-01 8.10467184e-01 -4.07069176e-02 -5.81478417e-01 8.12529266e-01 -4.07069214e-02 -5.78656673e-01 8.14537525e-01 -4.07069176e-02 -5.75727880e-01 8.16613078e-01 -4.07069176e-02 -5.72873771e-01 8.18614364e-01 -4.07069176e-02 -5.70092261e-01 8.20555866e-01 -4.07069214e-02 -5.67252517e-01 8.22520792e-01 -4.07069176e-02 -5.64301133e-01 8.24550331e-01 -4.07069176e-02 -5.61461210e-01 8.26483905e-01 -4.07069176e-02 -5.58586657e-01 8.28429639e-01 -4.07069176e-02 -5.55668890e-01 8.30391109e-01 -4.07069474e-02 -5.52795172e-01 8.32304478e-01 -4.07069176e-02 -5.49888790e-01 8.34229410e-01 -4.07069214e-02 -5.46975195e-01 8.36140454e-01 -4.07069176e-02 -5.43993950e-01 8.38085473e-01 -4.07069176e-02 -5.41129172e-01 8.39938581e-01 -4.07069176e-02 -5.38191497e-01 8.41821849e-01 -4.07069176e-02 -5.35234988e-01 8.43704700e-01 -4.07069214e-02 -5.32309055e-01 8.45555425e-01 -4.07069176e-02 -5.29284954e-01 8.47451150e-01 -4.07069176e-02 -5.26313066e-01 8.49301457e-01 -4.07069176e-02 -5.23401797e-01 8.51096153e-01 -4.07069214e-02 -5.20441651e-01 8.52911949e-01 -4.07069176e-02 -5.17396331e-01 8.54760587e-01 -4.07069176e-02 -5.14483750e-01 8.56518388e-01 -4.07069214e-02 -5.11515319e-01 8.58293235e-01 -4.07069176e-02 -5.08494377e-01 8.60087156e-01 -4.07069214e-02 -5.05462229e-01 8.61872077e-01 -4.07069176e-02 -5.02402723e-01 8.63661170e-01 -4.07069176e-02 -4.99359727e-01 8.65422726e-01 -4.07069176e-02 -4.96453404e-01 8.67094219e-01 -4.07069214e-02 -4.93463904e-01 8.68796170e-01 -4.07069176e-02 -4.90318149e-01 8.70578647e-01 -4.07069176e-02 -4.87274975e-01 8.72282922e-01 -4.07069176e-02 -4.84239370e-01 8.73971224e-01 -4.07069176e-02 -4.81220365e-01 8.75640571e-01 -4.07069474e-02 -4.78195429e-01 8.77295792e-01 -4.07069176e-02 -4.75093663e-01 8.78977895e-01 -4.07069214e-02 -4.72047895e-01 8.80617857e-01 -4.07069176e-02 -4.68891948e-01 8.82303178e-01 -4.07069176e-02 -4.65869755e-01 8.83904457e-01 -4.07069437e-02 -4.62807029e-01 8.85510445e-01 -4.07069176e-02 -4.59705144e-01 8.87122512e-01 -4.07069437e-02 -4.56580758e-01 8.88735175e-01 -4.07069176e-02 -4.53427136e-01 8.90347719e-01 -4.07069176e-02 -4.50311899e-01 8.91927898e-01 -4.07069176e-02 -4.47284311e-01 8.93451035e-01 -4.07069437e-02 -4.44174558e-01 8.95000100e-01 -4.07069176e-02 -4.40981179e-01 8.96577537e-01 -4.07069176e-02 -4.37875867e-01 8.98101211e-01 -4.07069474e-02 -4.34850633e-01 8.99570048e-01 -4.07069214e-02 -4.31726962e-01 9.01069760e-01 -4.07069251e-02 -4.28502440e-01 9.02608216e-01 -4.07069176e-02 -4.25325841e-01 9.04110730e-01 -4.07069474e-02 -4.22251552e-01 9.05550122e-01 -4.07069176e-02 -4.19107467e-01 9.07009423e-01 -4.07069176e-02 -4.15934265e-01 9.08466816e-01 -4.07069176e-02 -4.12707627e-01 9.09938455e-01 -4.07069176e-02 -4.09520864e-01 9.11379397e-01 -4.07069214e-02 -4.06314492e-01 9.12811220e-01 -4.07069176e-02 -4.03117776e-01 9.14228976e-01 -4.07069176e-02 -3.99927378e-01 9.15628552e-01 -4.07069176e-02 -3.96741837e-01 9.17013645e-01 -4.07069437e-02 -3.93525541e-01 9.18393075e-01 -4.07069176e-02 -3.90252978e-01 9.19792235e-01 -4.07069176e-02 -3.87094080e-01 9.21128392e-01 -4.07069437e-02 -3.83869886e-01 9.22475219e-01 -4.07069176e-02 -3.80578697e-01 9.23836052e-01 -4.07069176e-02 -3.77382636e-01 9.25148010e-01 -4.07069176e-02 -3.74165475e-01 9.26453471e-01 -4.07069176e-02 -3.70928466e-01 9.27754223e-01 -4.07069176e-02 -3.67755413e-01 9.29017842e-01 -4.07069214e-02 -3.64515007e-01 9.30293024e-01 -4.07069176e-02 -3.61201435e-01 9.31579292e-01 -4.07069176e-02 -3.58013481e-01 9.32821453e-01 -4.07069214e-02 -3.54822636e-01 9.34028864e-01 -4.07069176e-02 -3.51564139e-01 9.35255110e-01 -4.07069176e-02 -3.48265916e-01 9.36487138e-01 -4.07069176e-02 -3.44974458e-01 9.37708735e-01 -4.07069474e-02 -3.41751158e-01 9.38896179e-01 -4.07069214e-02 -3.38496923e-01 9.40071106e-01 -4.07069176e-02 -3.35108578e-01 9.41286564e-01 -4.07069176e-02 -3.31718296e-01 9.42486107e-01 -4.07069176e-02 -3.28527451e-01 9.43602264e-01 -4.07069214e-02 -3.25228125e-01 9.44745600e-01 -4.07069176e-02 -3.21952343e-01 9.45866764e-01 -4.07069474e-02 -3.18655938e-01 9.46981728e-01 -4.07069176e-02 -3.15334290e-01 9.48094904e-01 -4.07069549e-02 -3.12139779e-01 9.49149251e-01 -4.07069176e-02 -3.08694869e-01 9.50275362e-01 -4.07069176e-02 -3.05274397e-01 9.51380432e-01 -4.07069176e-02 -3.01950604e-01 9.52441692e-01 -4.07069214e-02 -2.98618525e-01 9.53489900e-01 -4.07069214e-02 -2.95428067e-01 9.54482913e-01 -4.07069474e-02 -2.92067379e-01 9.55516338e-01 -4.07069176e-02 -2.88631052e-01 9.56559658e-01 -4.07069176e-02 -2.85271853e-01 9.57566857e-01 -4.07069176e-02 -2.81931192e-01 9.58557189e-01 -4.07069176e-02 -2.78683096e-01 9.59507942e-01 -4.07069437e-02 -2.75423825e-01 9.60446000e-01 -4.07069176e-02 -2.72072434e-01 9.61402118e-01 -4.07069176e-02 -2.68623471e-01 9.62369919e-01 -4.07069176e-02 -2.65154362e-01 9.63332951e-01 -4.07069176e-02 -2.61892915e-01 9.64227378e-01 -4.07069437e-02 -2.58525312e-01 9.65131223e-01 -4.07069176e-02 -2.55144745e-01 9.66033638e-01 -4.07069437e-02 -2.51805037e-01 9.66908276e-01 -4.07069176e-02 -2.48298019e-01 9.67815042e-01 -4.07069176e-02 -2.45020062e-01 9.68650520e-01 -4.07069474e-02 -2.41627321e-01 9.69499409e-01 -4.07069176e-02 -2.38233164e-01 9.70342159e-01 -4.07069214e-02 -2.34857872e-01 9.71165478e-01 -4.07069176e-02 -2.31459454e-01 9.71981049e-01 -4.07069437e-02 -2.28170022e-01 9.72757041e-01 -4.07069176e-02 -2.24663541e-01 9.73570764e-01 -4.07069176e-02 -2.21160442e-01 9.74374712e-01 -4.07069176e-02 -2.17787832e-01 9.75134313e-01 -4.07069176e-02 -2.14369178e-01 9.75889027e-01 -4.07069176e-02 -2.11038977e-01 9.76615667e-01 -4.07069214e-02 -2.07735091e-01 9.77323592e-01 -4.07069176e-02 -2.04254225e-01 9.78057563e-01 -4.07069176e-02 -2.00708479e-01 9.78791952e-01 -4.07069176e-02 -1.97273657e-01 9.79488313e-01 -4.07069176e-02 -1.93946257e-01 9.80154634e-01 -4.07069214e-02 -1.90668926e-01 9.80797529e-01 -4.07069176e-02 -1.87241107e-01 9.81455564e-01 -4.07069176e-02 -1.83713153e-01 9.82122898e-01 -4.07069176e-02 -1.80141836e-01 9.82782185e-01 -4.07069176e-02 -1.76839575e-01 9.83389616e-01 -4.07069214e-02 -1.73443556e-01 9.83992338e-01 -4.07069176e-02 -1.69953376e-01 9.84597206e-01 -4.07069437e-02 -1.66518629e-01 9.85183239e-01 -4.07069176e-02 -1.62986189e-01 9.85774994e-01 -4.07069176e-02 -1.59612477e-01 9.86327469e-01 -4.07069474e-02 -1.56187028e-01 9.86874104e-01 -4.07069176e-02 -1.52710095e-01 9.87421274e-01 -4.07069474e-02 -1.49279952e-01 9.87941265e-01 -4.07069176e-02 -1.45708591e-01 9.88474607e-01 -4.07069176e-02 -1.42378896e-01 9.88960862e-01 -4.07069437e-02 -1.38959244e-01 9.89447951e-01 -4.07069176e-02 -1.35397270e-01 9.89940941e-01 -4.07069176e-02 -1.31929517e-01 9.90410089e-01 -4.07069176e-02 -1.28541619e-01 9.90855098e-01 -4.07069214e-02 -1.25220925e-01 9.91281211e-01 -4.07069176e-02 -1.21718124e-01 9.91716564e-01 -4.07069176e-02 -1.18170954e-01 9.92143750e-01 -4.07069176e-02 -1.14579767e-01 9.92564857e-01 -4.07069176e-02 -1.11136563e-01 9.92958188e-01 -4.07069214e-02 -1.07764944e-01 9.93329883e-01 -4.07069474e-02 -1.04325764e-01 9.93694723e-01 -4.07069176e-02 -1.00798905e-01 9.94061530e-01 -4.07069437e-02 -9.73617658e-02 9.94400680e-01 -4.07069176e-02 -9.38052684e-02 9.94744539e-01 -4.07069176e-02 -9.04204845e-02 9.95058835e-01 -4.07069437e-02 -8.69513676e-02 9.95368063e-01 -4.07069176e-02 -8.34489241e-02 9.95668173e-01 -4.07069474e-02 -8.00077617e-02 9.95948374e-01 -4.07069176e-02 -7.65078813e-02 9.96224105e-01 -4.07069474e-02 -7.30651915e-02 9.96482432e-01 -4.07069176e-02 -6.94695711e-02 9.96738017e-01 -4.07069176e-02 -6.60792142e-02 9.96970236e-01 -4.07069474e-02 -6.25922009e-02 9.97192085e-01 -4.07069176e-02 -5.91288246e-02 9.97408926e-01 -4.07069474e-02 -5.57202622e-02 9.97604609e-01 -4.07069176e-02 -5.21442778e-02 9.97793257e-01 -4.07069176e-02 -4.85783927e-02 9.97977912e-01 -4.07069176e-02 -4.50965092e-02 9.98137891e-01 -4.07069176e-02 -4.16330919e-02 9.98290300e-01 -4.07069176e-02 -3.82248014e-02 9.98426318e-01 -4.07069214e-02 -3.48363891e-02 9.98549819e-01 -4.07069176e-02 -3.12693492e-02 9.98667240e-01 -4.07069176e-02 -2.76669171e-02 9.98773396e-01 -4.07069176e-02 -2.41604764e-02 9.98869479e-01 -4.07069176e-02 -2.07777098e-02 9.98942077e-01 -4.07069437e-02 -1.74074359e-02 9.99009490e-01 -4.07069176e-02 -1.39066773e-02 9.99058843e-01 -4.07069176e-02 -1.03297485e-02 9.99104321e-01 -4.07069176e-02 -6.70089154e-03 9.99141574e-01 -4.07069176e-02 -3.32843768e-03 9.99157965e-01 -4.07069474e-02 1.24876911e-04 9.99157488e-01 -4.07069176e-02 3.64549528e-03 9.99157727e-01 -4.07069474e-02 7.12699257e-03 9.99136746e-01 -4.07069176e-02 1.07040955e-02 9.99100268e-01 -4.07069214e-02 1.42001566e-02 9.99053299e-01 -4.07069176e-02 1.76669229e-02 9.99005139e-01 -4.07069176e-02 2.11674385e-02 9.98932838e-01 -4.07069176e-02 2.46370416e-02 9.98854339e-01 -4.07069176e-02 2.81307455e-02 9.98762488e-01 -4.07069176e-02 3.15358751e-02 9.98661637e-01 -4.07069474e-02 3.49928327e-02 9.98544693e-01 -4.07069176e-02 3.85820270e-02 9.98413324e-01 -4.07069176e-02 4.20841314e-02 9.98272896e-01 -4.07069176e-02 4.55599129e-02 9.98117924e-01 -4.07069176e-02 4.89861779e-02 9.97955918e-01 -4.07069214e-02 5.23350462e-02 9.97783899e-01 -4.07069214e-02 5.58392256e-02 9.97596443e-01 -4.07069176e-02 5.94277568e-02 9.97386873e-01 -4.07069176e-02 6.29810691e-02 9.97170031e-01 -4.07069176e-02 6.63909987e-02 9.96948898e-01 -4.07069512e-02 6.98388889e-02 9.96712387e-01 -4.07069176e-02 7.33423755e-02 9.96463001e-01 -4.07069474e-02 7.68076256e-02 9.96200919e-01 -4.07069176e-02 8.03682581e-02 9.95920300e-01 -4.07069214e-02 8.38418752e-02 9.95634377e-01 -4.07069214e-02 8.73418897e-02 9.95333374e-01 -4.07069176e-02 9.07581672e-02 9.95027244e-01 -4.07069176e-02 9.42780450e-02 9.94700432e-01 -4.07069437e-02 9.76604745e-02 9.94374931e-01 -4.07069474e-02 1.01111963e-01 9.94028389e-01 -4.07069176e-02 1.04663171e-01 9.93661642e-01 -4.07069176e-02 1.08186081e-01 9.93283212e-01 -4.07069176e-02 1.11635283e-01 9.92902339e-01 -4.07069176e-02 1.15100458e-01 9.92504358e-01 -4.07069176e-02 1.18477814e-01 9.92107213e-01 -4.07069214e-02 1.21921465e-01 9.91690457e-01 -4.07069176e-02 1.25457436e-01 9.91251945e-01 -4.07069214e-02 1.28927097e-01 9.90804076e-01 -4.07069214e-02 1.32406175e-01 9.90345299e-01 -4.07069176e-02 1.35762334e-01 9.89892960e-01 -4.07069400e-02 1.39191732e-01 9.89414990e-01 -4.07069176e-02 1.42696723e-01 9.88916934e-01 -4.07069586e-02 1.46118134e-01 9.88414586e-01 -4.07069176e-02 1.49639681e-01 9.87887800e-01 -4.07069176e-02 1.53003246e-01 9.87374663e-01 -4.07069549e-02 1.56455606e-01 9.86830950e-01 -4.07069176e-02 1.60007551e-01 9.86262560e-01 -4.07069176e-02 1.63434014e-01 9.85701442e-01 -4.07069176e-02 1.66881949e-01 9.85123515e-01 -4.07069176e-02 1.70342714e-01 9.84528661e-01 -4.07069176e-02 1.73772916e-01 9.83933687e-01 -4.07069176e-02 1.77110508e-01 9.83340323e-01 -4.07069474e-02 1.80519536e-01 9.82712865e-01 -4.07069176e-02 1.84051722e-01 9.82060373e-01 -4.07069176e-02 1.87379256e-01 9.81430769e-01 -4.07069214e-02 1.90795153e-01 9.80770171e-01 -4.07069176e-02 1.94343090e-01 9.80074883e-01 -4.07069176e-02 1.97732523e-01 9.79397357e-01 -4.07069176e-02 2.01115713e-01 9.78707492e-01 -4.07069176e-02 2.04479903e-01 9.78010774e-01 -4.07069214e-02 2.07805857e-01 9.77310240e-01 -4.07069176e-02 2.11325720e-01 9.76553798e-01 -4.07069176e-02 2.14832276e-01 9.75788832e-01 -4.07069176e-02 2.18224525e-01 9.75035548e-01 -4.07069176e-02 2.21543252e-01 9.74287808e-01 -4.07069549e-02 2.24838972e-01 9.73531485e-01 -4.07069176e-02 2.28237137e-01 9.72740591e-01 -4.07069176e-02 2.31695950e-01 9.71924126e-01 -4.07069176e-02 2.35188529e-01 9.71085012e-01 -4.07069176e-02 2.38603815e-01 9.70248997e-01 -4.07069176e-02 2.41969436e-01 9.69414473e-01 -4.07069176e-02 2.45277181e-01 9.68584895e-01 -4.07069214e-02 2.48623610e-01 9.67728794e-01 -4.07069176e-02 2.52123177e-01 9.66824532e-01 -4.07069176e-02 2.55452007e-01 9.65952933e-01 -4.07069214e-02 2.58793294e-01 9.65059578e-01 -4.07069176e-02 2.62203634e-01 9.64142263e-01 -4.07069176e-02 2.65550673e-01 9.63221788e-01 -4.07069176e-02 2.68866211e-01 9.62305725e-01 -4.07069437e-02 2.72110254e-01 9.61391568e-01 -4.07069176e-02 2.75553435e-01 9.60407853e-01 -4.07069176e-02 2.79030085e-01 9.59405065e-01 -4.07069176e-02 2.82331049e-01 9.58438516e-01 -4.07069176e-02 2.85589427e-01 9.57473934e-01 -4.07069214e-02 2.88869470e-01 9.56487834e-01 -4.07069176e-02 2.92185903e-01 9.55479980e-01 -4.07069176e-02 2.95623064e-01 9.54423010e-01 -4.07069176e-02 2.99016595e-01 9.53366160e-01 -4.07069176e-02 3.02288711e-01 9.52332318e-01 -4.07069176e-02 3.05533737e-01 9.51297820e-01 -4.07069176e-02 3.08900207e-01 9.50207055e-01 -4.07069176e-02 3.12206507e-01 9.49127376e-01 -4.07069176e-02 3.15508962e-01 9.48033929e-01 -4.07069176e-02 3.18896532e-01 9.46901917e-01 -4.07069176e-02 3.22188824e-01 9.45785463e-01 -4.07069176e-02 3.25495362e-01 9.44653451e-01 -4.07069176e-02 3.28750521e-01 9.43523943e-01 -4.07069176e-02 3.32043260e-01 9.42371726e-01 -4.07069176e-02 3.35286766e-01 9.41225469e-01 -4.07069214e-02 3.38567346e-01 9.40045834e-01 -4.07069176e-02 3.41918319e-01 9.38834429e-01 -4.07069176e-02 3.45188320e-01 9.37629938e-01 -4.07069176e-02 3.48452568e-01 9.36418235e-01 -4.07069176e-02 3.51671755e-01 9.35214996e-01 -4.07069214e-02 3.54823470e-01 9.34028625e-01 -4.07069176e-02 3.58158141e-01 9.32762980e-01 -4.07069176e-02 3.61481637e-01 9.31472182e-01 -4.07069176e-02 3.64733547e-01 9.30207253e-01 -4.07069176e-02 3.67999583e-01 9.28920686e-01 -4.07069176e-02 3.71151298e-01 9.27665830e-01 -4.07069214e-02 3.74384850e-01 9.26363289e-01 -4.07069176e-02 3.77692163e-01 9.25020635e-01 -4.07069176e-02 3.80892903e-01 9.23706174e-01 -4.07069176e-02 3.84126365e-01 9.22367036e-01 -4.07069176e-02 3.87275755e-01 9.21049714e-01 -4.07069176e-02 3.90469462e-01 9.19698596e-01 -4.07069176e-02 3.93676221e-01 9.18329835e-01 -4.07069176e-02 3.96880507e-01 9.16950941e-01 -4.07069176e-02 4.00158972e-01 9.15527523e-01 -4.07069176e-02 4.03373539e-01 9.14115429e-01 -4.07069176e-02 4.06538159e-01 9.12712455e-01 -4.07069176e-02 4.09673393e-01 9.11310256e-01 -4.07069214e-02 4.12809074e-01 9.09892082e-01 -4.07069176e-02 4.16009754e-01 9.08432782e-01 -4.07069176e-02 4.19160098e-01 9.06982958e-01 -4.07069176e-02 4.22387481e-01 9.05485213e-01 -4.07069176e-02 4.25517321e-01 9.04019654e-01 -4.07069474e-02 4.28626508e-01 9.02548254e-01 -4.07069176e-02 4.31875139e-01 9.00997519e-01 -4.07069176e-02 4.34915215e-01 8.99538934e-01 -4.07069176e-02 4.38074648e-01 8.98002267e-01 -4.07069176e-02 4.41313714e-01 8.96413207e-01 -4.07069176e-02 4.44431633e-01 8.94872606e-01 -4.07069176e-02 4.47553962e-01 8.93316209e-01 -4.07069176e-02 4.50624943e-01 8.91770899e-01 -4.07069176e-02 4.53692853e-01 8.90213668e-01 -4.07069176e-02 4.56748188e-01 8.88650835e-01 -4.07069437e-02 4.59892273e-01 8.87025833e-01 -4.07069176e-02 4.63035405e-01 8.85390759e-01 -4.07069176e-02 4.66108561e-01 8.83775651e-01 -4.07069176e-02 4.69230503e-01 8.82122934e-01 -4.07069176e-02 4.72268224e-01 8.80499721e-01 -4.07069176e-02 4.75331277e-01 8.78848612e-01 -4.07069176e-02 4.78417575e-01 8.77175033e-01 -4.07069176e-02 4.81459737e-01 8.75508308e-01 -4.07069176e-02 4.84511882e-01 8.73819411e-01 -4.07069176e-02 4.87525672e-01 8.72143507e-01 -4.07069437e-02 4.90552336e-01 8.70444417e-01 -4.07069176e-02 4.93672282e-01 8.68677497e-01 -4.07069176e-02 4.96687233e-01 8.66960108e-01 -4.07069176e-02 4.99725431e-01 8.65211725e-01 -4.07069176e-02 5.02749562e-01 8.63457561e-01 -4.07069176e-02 5.05749941e-01 8.61705899e-01 -4.07069176e-02 5.08752704e-01 8.59933794e-01 -4.07069176e-02 5.11659920e-01 8.58207464e-01 -4.07069176e-02 5.14671147e-01 8.56404603e-01 -4.07069176e-02 5.17730713e-01 8.54555726e-01 -4.07069176e-02 5.20708919e-01 8.52749407e-01 -4.07069176e-02 5.23704410e-01 8.50910842e-01 -4.07069176e-02 5.26565671e-01 8.49144697e-01 -4.07069214e-02 5.29522598e-01 8.47301602e-01 -4.07069176e-02 5.32484174e-01 8.45445395e-01 -4.07069214e-02 5.35415411e-01 8.43590498e-01 -4.07069176e-02 5.38453400e-01 8.41654539e-01 -4.07069176e-02 5.41324615e-01 8.39813113e-01 -4.07069735e-02 5.44139504e-01 8.37991774e-01 -4.07069586e-02 5.47066450e-01 8.36082995e-01 -4.07069698e-02 5.50029159e-01 8.34140360e-01 -4.07070071e-02 5.52985787e-01 8.32181573e-01 -4.07069996e-02 5.55958092e-01 8.30202579e-01 -4.07070294e-02 5.58872759e-01 8.28246772e-01 -4.07070629e-02 5.61651707e-01 8.26368272e-01 -4.07071076e-02 5.64484417e-01 8.24439645e-01 -4.07071412e-02 5.67331553e-01 8.22486758e-01 -4.07073498e-02 5.70051253e-01 8.20600390e-01 -4.07072194e-02 5.72923839e-01 8.18596423e-01 -4.07072939e-02 5.75909793e-01 8.16498816e-01 -4.07072864e-02 5.78658879e-01 8.14553082e-01 -4.07072827e-02 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. 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. 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. 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. 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. 7.04709530e-01 7.08326936e-01 -4.07072864e-02 7.07251191e-01 7.05789447e-01 -4.07072902e-02 7.09310114e-01 7.03724205e-01 -4.07073759e-02 7.11623788e-01 7.01382101e-01 -4.07071151e-02 7.13976324e-01 6.98982179e-01 -4.07070704e-02 7.16338933e-01 6.96557939e-01 -4.07070629e-02 7.18762040e-01 6.94053710e-01 -4.07070480e-02 7.21233964e-01 6.91476822e-01 -4.07069996e-02 7.23722875e-01 6.88874900e-01 -4.07069698e-02 7.26037264e-01 6.86430991e-01 -4.07069661e-02 7.28355110e-01 6.83969319e-01 -4.07069214e-02 7.30785489e-01 6.81370199e-01 -4.07069176e-02 7.33179092e-01 6.78798437e-01 -4.07069214e-02 7.35546410e-01 6.76232338e-01 -4.07069176e-02 7.37961173e-01 6.73592925e-01 -4.07069176e-02 7.40255713e-01 6.71074271e-01 -4.07069400e-02 7.42576778e-01 6.68503404e-01 -4.07069176e-02 7.44901836e-01 6.65912509e-01 -4.07069214e-02 7.47172296e-01 6.63364291e-01 -4.07069176e-02 7.49480784e-01 6.60753191e-01 -4.07069176e-02 7.51848221e-01 6.58055484e-01 -4.07069176e-02 7.54215240e-01 6.55344963e-01 -4.07069176e-02 7.56420791e-01 6.52798533e-01 -4.07069214e-02 7.58695126e-01 6.50150001e-01 -4.07069176e-02 7.60988951e-01 6.47466719e-01 -4.07069474e-02 7.63148308e-01 6.44921184e-01 -4.07069176e-02 7.65452862e-01 6.42180204e-01 -4.07069176e-02 7.67703533e-01 6.39492333e-01 -4.07069437e-02 7.69935429e-01 6.36800528e-01 -4.07069176e-02 7.72159755e-01 6.34103954e-01 -4.07069214e-02 7.74297893e-01 6.31487310e-01 -4.07069176e-02 7.76573002e-01 6.28688633e-01 -4.07069176e-02 7.78832495e-01 6.25887096e-01 -4.07069176e-02 7.80997097e-01 6.23184860e-01 -4.07069176e-02 7.83106387e-01 6.20533466e-01 -4.07069474e-02 7.85193026e-01 6.17892027e-01 -4.07069176e-02 7.87400305e-01 6.15073502e-01 -4.07069176e-02 7.89562881e-01 6.12298310e-01 -4.07069214e-02 7.91695118e-01 6.09534204e-01 -4.07069176e-02 7.93905079e-01 6.06656492e-01 -4.07069176e-02 7.96007454e-01 6.03893816e-01 -4.07069176e-02 7.98124671e-01 6.01093650e-01 -4.07069176e-02 8.00149798e-01 5.98396480e-01 -4.07069474e-02 8.02210391e-01 5.95625997e-01 -4.07069176e-02 8.04306209e-01 5.92797041e-01 -4.07069214e-02 8.06366384e-01 5.89988649e-01 -4.07069176e-02 8.08492661e-01 5.87076247e-01 -4.07069176e-02 8.10453594e-01 5.84363222e-01 -4.07069214e-02 8.12470019e-01 5.81554830e-01 -4.07069176e-02 8.14528227e-01 5.78673780e-01 -4.07069437e-02 8.16466510e-01 5.75934291e-01 -4.07069176e-02 8.18552732e-01 5.72961628e-01 -4.07069176e-02 8.20619702e-01 5.69999516e-01 -4.07069176e-02 8.22591603e-01 5.67150831e-01 -4.07069176e-02 8.24503958e-01 5.64368069e-01 -4.07069214e-02 8.26417744e-01 5.61558545e-01 -4.07069176e-02 8.28386962e-01 5.58651626e-01 -4.07069176e-02 8.30332041e-01 5.55753231e-01 -4.07069176e-02 8.32305729e-01 5.52792549e-01 -4.07069176e-02 8.34240675e-01 5.49872339e-01 -4.07069214e-02 8.36099207e-01 5.47039688e-01 -4.07069176e-02 8.38047802e-01 5.44049203e-01 -4.07069176e-02 8.39957476e-01 5.41098595e-01 -4.07069214e-02 8.41828227e-01 5.38181424e-01 -4.07069176e-02 8.43756139e-01 5.35155535e-01 -4.07069176e-02 8.45581710e-01 5.32268643e-01 -4.07069214e-02 8.47416997e-01 5.29337704e-01 -4.07069176e-02 8.49251032e-01 5.26392817e-01 -4.07069214e-02 8.51038456e-01 5.23495972e-01 -4.07069176e-02 8.52871239e-01 5.20509064e-01 -4.07069176e-02 8.54721129e-01 5.17460406e-01 -4.07069176e-02 8.56566548e-01 5.14402986e-01 -4.07069176e-02 8.58369112e-01 5.11387229e-01 -4.07069176e-02 8.60148609e-01 5.08391082e-01 -4.07069176e-02 8.61872077e-01 5.05465567e-01 -4.07069214e-02 8.63587320e-01 5.02524316e-01 -4.07069176e-02 8.65372181e-01 4.99446303e-01 -4.07069176e-02 8.67116868e-01 4.96412903e-01 -4.07069214e-02 8.68827701e-01 4.93409008e-01 -4.07069176e-02 8.70567977e-01 4.90339279e-01 -4.07069214e-02 8.72228265e-01 4.87370551e-01 -4.07069176e-02 8.73962045e-01 4.84253943e-01 -4.07069176e-02 8.75648975e-01 4.81203049e-01 -4.07069214e-02 8.77321422e-01 4.78147537e-01 -4.07069176e-02 8.78992081e-01 4.75066155e-01 -4.07069214e-02 8.80597472e-01 4.72084284e-01 -4.07069176e-02 8.82271409e-01 4.68946993e-01 -4.07069176e-02 8.83908987e-01 4.65859056e-01 -4.07069214e-02 8.85487497e-01 4.62850809e-01 -4.07069176e-02 8.87134016e-01 4.59680915e-01 -4.07069176e-02 8.88791144e-01 4.56472605e-01 -4.07069176e-02 8.90369356e-01 4.53385532e-01 -4.07069176e-02 8.91914725e-01 4.50340480e-01 -4.07069437e-02 8.93467665e-01 4.47248012e-01 -4.07069176e-02 8.95036995e-01 4.44100708e-01 -4.07069214e-02 8.96540403e-01 4.41058636e-01 -4.07069214e-02 8.98115218e-01 4.37843323e-01 -4.07069176e-02 8.99637580e-01 4.34712946e-01 -4.07069437e-02 9.01132107e-01 4.31594282e-01 -4.07069176e-02 9.02643323e-01 4.28431749e-01 -4.07069214e-02 9.04086769e-01 4.25369620e-01 -4.07069176e-02 9.05604243e-01 4.22137588e-01 -4.07069176e-02 9.07126606e-01 4.18852299e-01 -4.07069176e-02 9.08577681e-01 4.15694952e-01 -4.07069176e-02 9.09993649e-01 4.12588537e-01 -4.07069363e-02 9.11374569e-01 4.09529865e-01 -4.07069176e-02 9.12799120e-01 4.06341285e-01 -4.07069176e-02 9.14223015e-01 4.03130144e-01 -4.07069176e-02 9.15644109e-01 3.99890304e-01 -4.07069176e-02 9.17044044e-01 3.96671087e-01 -4.07069437e-02 9.18397129e-01 3.93518895e-01 -4.07069176e-02 9.19789433e-01 3.90257359e-01 -4.07069176e-02 9.21155632e-01 3.87028366e-01 -4.07069325e-02 9.22451138e-01 3.83924007e-01 -4.07069176e-02 9.23819602e-01 3.80617321e-01 -4.07069176e-02 9.25182164e-01 3.77298832e-01 -4.07069176e-02 9.26488161e-01 3.74079436e-01 -4.07069176e-02 9.27758873e-01 3.70918691e-01 -4.07069214e-02 9.29006755e-01 3.67784142e-01 -4.07069176e-02 9.30295348e-01 3.64512622e-01 -4.07069176e-02 9.31559145e-01 3.61253262e-01 -4.07069176e-02 9.32844341e-01 3.57940525e-01 -4.07069176e-02 9.34107065e-01 3.54615301e-01 -4.07069176e-02 9.35333431e-01 3.51354986e-01 -4.07069176e-02 9.36533749e-01 3.48141581e-01 -4.07069251e-02 9.37709630e-01 3.44972789e-01 -4.07069176e-02 9.38923895e-01 3.41672421e-01 -4.07069176e-02 9.40141857e-01 3.38299096e-01 -4.07069176e-02 9.41333115e-01 3.34978193e-01 -4.07069176e-02 9.42471921e-01 3.31761211e-01 -4.07069214e-02 9.43597853e-01 3.28538686e-01 -4.07069176e-02 9.44762588e-01 3.25174451e-01 -4.07069176e-02 9.45894063e-01 3.21872473e-01 -4.07069214e-02 9.47012126e-01 3.18567127e-01 -4.07069176e-02 9.48138237e-01 3.15195620e-01 -4.07069176e-02 9.49213147e-01 3.11946273e-01 -4.07069214e-02 9.50291753e-01 3.08640152e-01 -4.07069176e-02 9.51380908e-01 3.05281520e-01 -4.07069474e-02 9.52400744e-01 3.02076340e-01 -4.07069176e-02 9.53472316e-01 2.98675895e-01 -4.07069176e-02 9.54533160e-01 2.95263380e-01 -4.07069176e-02 9.55556512e-01 2.91934609e-01 -4.07069176e-02 9.56549048e-01 2.88669050e-01 -4.07069176e-02 9.57525969e-01 2.85406619e-01 -4.07069176e-02 9.58517730e-01 2.82067180e-01 -4.07069176e-02 9.59494114e-01 2.78728127e-01 -4.07069176e-02 9.60483193e-01 2.75290787e-01 -4.07069176e-02 9.61459458e-01 2.71869093e-01 -4.07069176e-02 9.62400734e-01 2.68519372e-01 -4.07069176e-02 9.63319004e-01 2.65206754e-01 -4.07069214e-02 9.64213490e-01 2.61942655e-01 -4.07069176e-02 9.65137362e-01 2.58500308e-01 -4.07069176e-02 9.66063738e-01 2.55026966e-01 -4.07069176e-02 9.66952085e-01 2.51640052e-01 -4.07069176e-02 9.67797697e-01 2.48373449e-01 -4.07069474e-02 9.68640327e-01 2.45051473e-01 -4.07069214e-02 9.69475925e-01 2.41722912e-01 -4.07069176e-02 9.70320642e-01 2.38313198e-01 -4.07069176e-02 9.71170723e-01 2.34832317e-01 -4.07069176e-02 9.72003162e-01 2.31363609e-01 -4.07069176e-02 9.72782910e-01 2.28058919e-01 -4.07069474e-02 9.73573565e-01 2.24653229e-01 -4.07069176e-02 9.74354863e-01 2.21251070e-01 -4.07069474e-02 9.75110888e-01 2.17896312e-01 -4.07069176e-02 9.75870430e-01 2.14458436e-01 -4.07069474e-02 9.76611376e-01 2.11052671e-01 -4.07069176e-02 9.77366924e-01 2.07535818e-01 -4.07069214e-02 9.78066146e-01 2.04224512e-01 -4.07069437e-02 9.78771031e-01 2.00814754e-01 -4.07069176e-02 9.79468584e-01 1.97377682e-01 -4.07069214e-02 9.80128944e-01 1.94074735e-01 -4.07069176e-02 9.80819762e-01 1.90551847e-01 -4.07069176e-02 9.81478691e-01 1.87130660e-01 -4.07069474e-02 9.82124448e-01 1.83706641e-01 -4.07069176e-02 9.82759714e-01 1.80268705e-01 -4.07069474e-02 9.83375490e-01 1.76916510e-01 -4.07069214e-02 9.83998418e-01 1.73409373e-01 -4.07069176e-02 9.84609187e-01 1.69881403e-01 -4.07069176e-02 9.85198498e-01 1.66434780e-01 -4.07069176e-02 9.85753775e-01 1.63114056e-01 -4.07069325e-02 9.86303926e-01 1.59750283e-01 -4.07069176e-02 9.86872196e-01 1.56199977e-01 -4.07069176e-02 9.87412930e-01 1.52755424e-01 -4.07069214e-02 9.87933934e-01 1.49329677e-01 -4.07069176e-02 9.88454103e-01 1.45867914e-01 -4.07069214e-02 9.88939762e-01 1.42516121e-01 -4.07069176e-02 9.89446461e-01 1.38971552e-01 -4.07069176e-02 9.89928246e-01 1.35506973e-01 -4.07069474e-02 9.90396798e-01 1.32022619e-01 -4.07069176e-02 9.90849972e-01 1.28578693e-01 -4.07069437e-02 9.91288841e-01 1.25153214e-01 -4.07069176e-02 9.91735160e-01 1.21571817e-01 -4.07069176e-02 9.92155015e-01 1.18071765e-01 -4.07069176e-02 9.92559671e-01 1.14633530e-01 -4.07069176e-02 9.92945075e-01 1.11252591e-01 -4.07069437e-02 9.93314266e-01 1.07894853e-01 -4.07069176e-02 9.93693292e-01 1.04344010e-01 -4.07069176e-02 9.94056165e-01 1.00843497e-01 -4.07069474e-02 9.94397759e-01 9.73876417e-02 -4.07069176e-02 9.94735599e-01 9.39071849e-02 -4.07069325e-02 9.95045066e-01 9.05683935e-02 -4.07069176e-02 9.95358229e-01 8.70662704e-02 -4.07069176e-02 9.95656431e-01 8.35676342e-02 -4.07069176e-02 9.95949924e-01 7.99823403e-02 -4.07069176e-02 9.96231914e-01 7.64018297e-02 -4.07069176e-02 9.96490359e-01 7.29550496e-02 -4.07069176e-02 9.96734738e-01 6.95024282e-02 -4.07069176e-02 9.96969283e-01 6.60953969e-02 -4.07069214e-02 9.97187078e-01 6.27081469e-02 -4.07069176e-02 9.97401774e-01 5.91980852e-02 -4.07069176e-02 9.97606099e-01 5.56462370e-02 -4.07069176e-02 9.97800589e-01 5.20454310e-02 -4.07069176e-02 9.97971654e-01 4.86767553e-02 -4.07069214e-02 9.98130262e-01 4.52961363e-02 -4.07069176e-02 9.98282373e-01 4.18061391e-02 -4.07069176e-02 9.98423040e-01 3.83168608e-02 -4.07069176e-02 9.98551428e-01 3.47556137e-02 -4.07069176e-02 9.98671055e-01 3.11638210e-02 -4.07069176e-02 9.98772085e-01 2.77675260e-02 -4.07069214e-02 9.98862565e-01 2.43650433e-02 -4.07069176e-02 9.98937428e-01 2.08728742e-02 -4.07069176e-02 9.99010324e-01 1.73983742e-02 -4.07069176e-02 9.99057949e-01 1.38914771e-02 -4.07069176e-02 9.99102414e-01 1.04172016e-02 -4.07069176e-02 9.99139667e-01 6.93064509e-03 -4.07069176e-02 9.99156117e-01 3.37926275e-03 -4.07069176e-02 9.99158919e-01 -1.45981539e-04 -4.07069437e-02 9.99156296e-01 -3.60920350e-03 -4.07069176e-02 9.99136686e-01 -7.11822277e-03 -4.07069251e-02 9.99102592e-01 -1.04997978e-02 -4.07069176e-02 9.99053836e-01 -1.40961083e-02 -4.07069176e-02 9.99005020e-01 -1.76746398e-02 -4.07069176e-02 9.98934984e-01 -2.10602563e-02 -4.07069214e-02 9.98857856e-01 -2.45251115e-02 -4.07069176e-02 9.98765349e-01 -2.80328505e-02 -4.07069176e-02 9.98660207e-01 -3.15199941e-02 -4.07069176e-02 9.98545647e-01 -3.50198820e-02 -4.07069214e-02 9.98419642e-01 -3.84040065e-02 -4.07069176e-02 9.98280823e-01 -4.18800898e-02 -4.07069176e-02 9.98123288e-01 -4.54405397e-02 -4.07069176e-02 9.97955501e-01 -4.90185991e-02 -4.07069176e-02 9.97773290e-01 -5.25250584e-02 -4.07069176e-02 9.97591496e-01 -5.59266433e-02 -4.07069214e-02 9.97396946e-01 -5.92912249e-02 -4.07069176e-02 9.97181714e-01 -6.27727881e-02 -4.07069176e-02 9.96954143e-01 -6.63069785e-02 -4.07069176e-02 9.96709108e-01 -6.98847249e-02 -4.07069214e-02 9.96459961e-01 -7.33674169e-02 -4.07069176e-02 9.96201634e-01 -7.68051893e-02 -4.07069214e-02 9.95935619e-01 -8.01805332e-02 -4.07069176e-02 9.95652497e-01 -8.36189315e-02 -4.07069176e-02 9.95344043e-01 -8.72067586e-02 -4.07069176e-02 9.95032310e-01 -9.07056108e-02 -4.07069214e-02 9.94717896e-01 -9.40853357e-02 -4.07069176e-02 9.94384527e-01 -9.75475013e-02 -4.07069176e-02 9.94031906e-01 -1.01069361e-01 -4.07069176e-02 9.93670106e-01 -1.04581140e-01 -4.07069214e-02 9.93299067e-01 -1.08031586e-01 -4.07069176e-02 9.92915988e-01 -1.11521296e-01 -4.07069214e-02 9.92530823e-01 -1.14871569e-01 -4.07069176e-02 9.92115557e-01 -1.18408360e-01 -4.07069176e-02 9.91694629e-01 -1.21900022e-01 -4.07069437e-02 9.91265476e-01 -1.25340626e-01 -4.07069176e-02 9.90811169e-01 -1.28867507e-01 -4.07069176e-02 9.90364432e-01 -1.32264286e-01 -4.07069214e-02 9.89897966e-01 -1.35710984e-01 -4.07069176e-02 9.89412785e-01 -1.39219165e-01 -4.07069214e-02 9.88922596e-01 -1.42653883e-01 -4.07069474e-02 9.88418937e-01 -1.46082222e-01 -4.07069176e-02 9.87904251e-01 -1.49536073e-01 -4.07069176e-02 9.87376273e-01 -1.52971447e-01 -4.07069176e-02 9.86840546e-01 -1.56404525e-01 -4.07069214e-02 9.86288786e-01 -1.59846351e-01 -4.07069176e-02 9.85730410e-01 -1.63254723e-01 -4.07069214e-02 9.85147059e-01 -1.66733891e-01 -4.07069176e-02 9.84540343e-01 -1.70273691e-01 -4.07069176e-02 9.83945549e-01 -1.73704326e-01 -4.07069176e-02 9.83350396e-01 -1.77050874e-01 -4.07069214e-02 9.82736170e-01 -1.80389613e-01 -4.07069176e-02 9.82105792e-01 -1.83812723e-01 -4.07069176e-02 9.81441259e-01 -1.87315047e-01 -4.07069176e-02 9.80761826e-01 -1.90839216e-01 -4.07069176e-02 9.80092704e-01 -1.94250867e-01 -4.07069176e-02 9.79419410e-01 -1.97624385e-01 -4.07069214e-02 9.78746414e-01 -2.00926036e-01 -4.07069176e-02 9.78033066e-01 -2.04372734e-01 -4.07069176e-02 9.77301657e-01 -2.07840651e-01 -4.07069176e-02 9.76567864e-01 -2.11273223e-01 -4.07069437e-02 9.75828648e-01 -2.14645475e-01 -4.07069176e-02 9.75074649e-01 -2.18056083e-01 -4.07069214e-02 9.74297047e-01 -2.21490145e-01 -4.07069176e-02 9.73518431e-01 -2.24903286e-01 -4.07069474e-02 9.72735941e-01 -2.28264689e-01 -4.07069176e-02 9.71932411e-01 -2.31664225e-01 -4.07069325e-02 9.71138537e-01 -2.34970063e-01 -4.07069176e-02 9.70287919e-01 -2.38445133e-01 -4.07069176e-02 9.69456553e-01 -2.41805404e-01 -4.07069214e-02 9.68603909e-01 -2.45189056e-01 -4.07069176e-02 9.67715740e-01 -2.48683780e-01 -4.07069176e-02 9.66862679e-01 -2.51988292e-01 -4.07069474e-02 9.65983629e-01 -2.55327225e-01 -4.07069176e-02 9.65078354e-01 -2.58732855e-01 -4.07069214e-02 9.64196205e-01 -2.62000114e-01 -4.07069176e-02 9.63257909e-01 -2.65421897e-01 -4.07069176e-02 9.62311387e-01 -2.68843830e-01 -4.07069251e-02 9.61377263e-01 -2.72157639e-01 -4.07069176e-02 9.60391402e-01 -2.75616437e-01 -4.07069176e-02 9.59445596e-01 -2.78892666e-01 -4.07069437e-02 9.58497107e-01 -2.82131374e-01 -4.07069176e-02 9.57483292e-01 -2.85553873e-01 -4.07069176e-02 9.56449628e-01 -2.88993329e-01 -4.07069176e-02 9.55436468e-01 -2.92336017e-01 -4.07069176e-02 9.54436898e-01 -2.95582771e-01 -4.07069214e-02 9.53428805e-01 -2.98813790e-01 -4.07069176e-02 9.52375829e-01 -3.02154332e-01 -4.07069176e-02 9.51315641e-01 -3.05477858e-01 -4.07069176e-02 9.50219452e-01 -3.08862150e-01 -4.07069176e-02 9.49116945e-01 -3.12237144e-01 -4.07069176e-02 9.48033094e-01 -3.15516889e-01 -4.07069214e-02 9.46955621e-01 -3.18735182e-01 -4.07069176e-02 9.45841134e-01 -3.22026402e-01 -4.07069176e-02 9.44688141e-01 -3.25391769e-01 -4.07069176e-02 9.43541706e-01 -3.28702599e-01 -4.07069474e-02 9.42395151e-01 -3.31971586e-01 -4.07069176e-02 9.41223204e-01 -3.35293502e-01 -4.07069437e-02 9.40046847e-01 -3.38563621e-01 -4.07069176e-02 9.38864052e-01 -3.41842532e-01 -4.07069176e-02 9.37648416e-01 -3.45139503e-01 -4.07069176e-02 9.36428666e-01 -3.48422855e-01 -4.07069214e-02 9.35252190e-01 -3.51573050e-01 -4.07069176e-02 9.34031367e-01 -3.54815036e-01 -4.07069176e-02 9.32747304e-01 -3.58198971e-01 -4.07069176e-02 9.31476235e-01 -3.61470431e-01 -4.07069214e-02 9.30225790e-01 -3.64684850e-01 -4.07069176e-02 9.28941488e-01 -3.67947876e-01 -4.07069214e-02 9.27656829e-01 -3.71168286e-01 -4.07069176e-02 9.26352978e-01 -3.74413699e-01 -4.07069214e-02 9.25081968e-01 -3.77541810e-01 -4.07069176e-02 9.23706293e-01 -3.80891711e-01 -4.07069176e-02 9.22374606e-01 -3.84111553e-01 -4.07069214e-02 9.21042621e-01 -3.87287736e-01 -4.07069176e-02 9.19634998e-01 -3.90619665e-01 -4.07069176e-02 9.18309331e-01 -3.93725097e-01 -4.07069214e-02 9.16967094e-01 -3.96844476e-01 -4.07069176e-02 9.15535569e-01 -4.00140584e-01 -4.07069176e-02 9.14097428e-01 -4.03411508e-01 -4.07069176e-02 9.12689984e-01 -4.06587511e-01 -4.07069176e-02 9.11306858e-01 -4.09681678e-01 -4.07069176e-02 9.09905672e-01 -4.12778199e-01 -4.07069176e-02 9.08461094e-01 -4.15942132e-01 -4.07069176e-02 9.06957865e-01 -4.19214100e-01 -4.07069176e-02 9.05449033e-01 -4.22464699e-01 -4.07069176e-02 9.03974712e-01 -4.25609112e-01 -4.07069176e-02 9.02516544e-01 -4.28695261e-01 -4.07069176e-02 9.01054323e-01 -4.31755930e-01 -4.07069176e-02 8.99544120e-01 -4.34902281e-01 -4.07069176e-02 8.97981763e-01 -4.38115835e-01 -4.07069176e-02 8.96439850e-01 -4.41262245e-01 -4.07069214e-02 8.94905210e-01 -4.44361925e-01 -4.07069176e-02 8.93356562e-01 -4.47472870e-01 -4.07069214e-02 8.91824603e-01 -4.50517893e-01 -4.07069176e-02 8.90247226e-01 -4.53626156e-01 -4.07069176e-02 8.88615251e-01 -4.56810951e-01 -4.07069176e-02 8.87007833e-01 -4.59926099e-01 -4.07069176e-02 8.85435045e-01 -4.62950647e-01 -4.07069176e-02 8.83818507e-01 -4.66028541e-01 -4.07069176e-02 8.82146180e-01 -4.69179869e-01 -4.07069176e-02 8.80509138e-01 -4.72253352e-01 -4.07069214e-02 8.78852308e-01 -4.75322634e-01 -4.07069176e-02 8.77182066e-01 -4.78406459e-01 -4.07069176e-02 8.75550270e-01 -4.81380731e-01 -4.07069176e-02 8.73868823e-01 -4.84422147e-01 -4.07069176e-02 8.72171819e-01 -4.87473875e-01 -4.07069176e-02 8.70466053e-01 -4.90516245e-01 -4.07069176e-02 8.68705809e-01 -4.93622452e-01 -4.07069176e-02 8.66964042e-01 -4.96680975e-01 -4.07069214e-02 8.65242660e-01 -4.99671996e-01 -4.07069176e-02 8.63480270e-01 -5.02714217e-01 -4.07069176e-02 8.61782730e-01 -5.05617976e-01 -4.07069176e-02 8.60008180e-01 -5.08627653e-01 -4.07069176e-02 8.58224869e-01 -5.11629045e-01 -4.07069176e-02 8.56381118e-01 -5.14711440e-01 -4.07069176e-02 8.54548216e-01 -5.17744958e-01 -4.07069176e-02 8.52782130e-01 -5.20654857e-01 -4.07069176e-02 8.50995064e-01 -5.23565888e-01 -4.07069176e-02 8.49171937e-01 -5.26521504e-01 -4.07069176e-02 8.47289801e-01 -5.29541910e-01 -4.07069176e-02 8.45389128e-01 -5.32571971e-01 -4.07069176e-02 8.43561411e-01 -5.35463691e-01 -4.07069176e-02 8.41732740e-01 -5.38332164e-01 -4.07069176e-02 8.39796901e-01 -5.41345656e-01 -4.07069176e-02 8.37839842e-01 -5.44371486e-01 -4.07069176e-02 8.35956216e-01 -5.47257781e-01 -4.07069176e-02 8.34045649e-01 -5.50165296e-01 -4.07069176e-02 8.32148731e-01 -5.53028464e-01 -4.07069214e-02 8.30280125e-01 -5.55833936e-01 -4.07069176e-02 8.28332722e-01 -5.58734536e-01 -4.07069176e-02 8.26311052e-01 -5.61715305e-01 -4.07069176e-02 8.24345052e-01 -5.64600706e-01 -4.07069437e-02 8.22379172e-01 -5.67457139e-01 -4.07069176e-02 8.20387304e-01 -5.70335984e-01 -4.07069251e-02 8.18386436e-01 -5.73197305e-01 -4.07069176e-02 8.16384673e-01 -5.76052606e-01 -4.07069214e-02 8.14382017e-01 -5.78874111e-01 -4.07069176e-02 8.12350333e-01 -5.81728518e-01 -4.07069176e-02 8.10350955e-01 -5.84501207e-01 -4.07069176e-02 8.08257520e-01 -5.87397337e-01 -4.07069176e-02 8.06184351e-01 -5.90239286e-01 -4.07069176e-02 8.04130793e-01 -5.93033254e-01 -4.07069176e-02 8.02026808e-01 -5.95873892e-01 -4.07069176e-02 7.99992204e-01 -5.98605335e-01 -4.07069176e-02 7.97913492e-01 -6.01372361e-01 -4.07069176e-02 7.95800924e-01 -6.04167163e-01 -4.07069176e-02 7.93742061e-01 -6.06870234e-01 -4.07069176e-02 7.91597247e-01 -6.09661758e-01 -4.07069176e-02 7.89419770e-01 -6.12477779e-01 -4.07069176e-02 7.87225425e-01 -6.15296781e-01 -4.07069176e-02 7.85076678e-01 -6.18037999e-01 -4.07069176e-02 7.82968879e-01 -6.20705009e-01 -4.07069176e-02 7.80857921e-01 -6.23359263e-01 -4.07069176e-02 7.78670490e-01 -6.26090527e-01 -4.07069176e-02 7.76435614e-01 -6.28859401e-01 -4.07069176e-02 7.74182737e-01 -6.31628394e-01 -4.07069176e-02 7.72028923e-01 -6.34261191e-01 -4.07069176e-02 7.69874394e-01 -6.36875153e-01 -4.07069176e-02 7.67655015e-01 -6.39548779e-01 -4.07069176e-02 7.65419006e-01 -6.42222583e-01 -4.07069176e-02 7.63104260e-01 -6.44969165e-01 -4.07069176e-02 7.60834813e-01 -6.47647202e-01 -4.07069214e-02 7.58564115e-01 -6.50302172e-01 -4.07069176e-02 7.56276011e-01 -6.52966261e-01 -4.07069214e-02 7.54041314e-01 -6.55543983e-01 -4.07069176e-02 7.51681268e-01 -6.58247292e-01 -4.07069176e-02 7.49343753e-01 -6.60909235e-01 -4.07069176e-02 7.47113109e-01 -6.63430750e-01 -4.07069176e-02 7.44854808e-01 -6.65963888e-01 -4.07069176e-02 7.42459357e-01 -6.68631673e-01 -4.07069176e-02 7.40102947e-01 -6.71243787e-01 -4.07069214e-02 7.37748325e-01 -6.73826277e-01 -4.07069176e-02 7.35396385e-01 -6.76396132e-01 -4.07069214e-02 7.33099461e-01 -6.78881645e-01 -4.07069176e-02 7.30731487e-01 -6.81428015e-01 -4.07069176e-02 7.28273034e-01 -6.84055150e-01 -4.07069176e-02 7.25875437e-01 -6.86600983e-01 -4.07069474e-02 7.23480821e-01 -6.89126790e-01 -4.07069437e-02 7.21069336e-01 -6.91650152e-01 -4.07070071e-02 7.18659699e-01 -6.94158435e-01 -4.07070182e-02 7.16413498e-01 -6.96493328e-01 -4.07072566e-02 7.13650405e-01 -6.99322641e-01 -4.07073684e-02 7.11928248e-01 -7.01069653e-01 -4.07072417e-02 7.09334075e-01 -7.03695059e-01 -4.07072678e-02 7.06828833e-01 -7.06212223e-01 -4.07072827e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.90116143e-01 -8.06291401e-01 -4.07072827e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.75053871e-01 -8.17102015e-01 -4.07072641e-02 5.72930336e-01 -8.18593204e-01 -4.07071486e-02 5.70123851e-01 -8.20542037e-01 -4.07070629e-02 5.67253590e-01 -8.22528780e-01 -4.07070518e-02 5.64459562e-01 -8.24444771e-01 -4.07070071e-02 5.61586261e-01 -8.26401353e-01 -4.07069623e-02 5.58721185e-01 -8.28341901e-01 -4.07069586e-02 5.55814385e-01 -8.30293894e-01 -4.07069437e-02 5.52840173e-01 -8.32274497e-01 -4.07069176e-02 5.49891174e-01 -8.34229171e-01 -4.07069176e-02 5.47076762e-01 -8.36074650e-01 -4.07069176e-02 5.44104934e-01 -8.38011324e-01 -4.07069176e-02 5.41168988e-01 -8.39911997e-01 -4.07069176e-02 5.38306653e-01 -8.41748416e-01 -4.07069176e-02 5.35359502e-01 -8.43624473e-01 -4.07069176e-02 5.32406211e-01 -8.45495045e-01 -4.07069176e-02 5.29473305e-01 -8.47330868e-01 -4.07069176e-02 5.26534975e-01 -8.49164963e-01 -4.07069176e-02 5.23544073e-01 -8.51008534e-01 -4.07069176e-02 5.20580530e-01 -8.52827549e-01 -4.07069176e-02 5.17581046e-01 -8.54648411e-01 -4.07069176e-02 5.14589906e-01 -8.56454015e-01 -4.07069176e-02 5.11597395e-01 -8.58243704e-01 -4.07069176e-02 5.08602977e-01 -8.60021770e-01 -4.07069176e-02 5.05594254e-01 -8.61795723e-01 -4.07069176e-02 5.02575696e-01 -8.63557458e-01 -4.07069176e-02 4.99476016e-01 -8.65354896e-01 -4.07069176e-02 4.96465147e-01 -8.67087483e-01 -4.07069214e-02 4.93493289e-01 -8.68779242e-01 -4.07069176e-02 4.90468323e-01 -8.70494664e-01 -4.07069176e-02 4.87431407e-01 -8.72194648e-01 -4.07069176e-02 4.84382272e-01 -8.73891175e-01 -4.07069176e-02 4.81316954e-01 -8.75586450e-01 -4.07069176e-02 4.78246778e-01 -8.77268076e-01 -4.07069176e-02 4.75201905e-01 -8.78918886e-01 -4.07069176e-02 4.72125679e-01 -8.80575716e-01 -4.07069176e-02 4.69047219e-01 -8.82217884e-01 -4.07069176e-02 4.65976268e-01 -8.83845627e-01 -4.07069176e-02 4.62786227e-01 -8.85517836e-01 -4.07069176e-02 4.59682822e-01 -8.87133718e-01 -4.07069176e-02 4.56686407e-01 -8.88681352e-01 -4.07069176e-02 4.53573793e-01 -8.90272796e-01 -4.07069176e-02 4.50447470e-01 -8.91859233e-01 -4.07069176e-02 4.47319895e-01 -8.93431067e-01 -4.07069176e-02 4.44209933e-01 -8.94981742e-01 -4.07069176e-02 4.41102117e-01 -8.96518171e-01 -4.07069176e-02 4.37951565e-01 -8.98061693e-01 -4.07069176e-02 4.34823602e-01 -8.99581611e-01 -4.07069176e-02 4.31679726e-01 -9.01090801e-01 -4.07069176e-02 4.28551316e-01 -9.02584493e-01 -4.07069176e-02 4.25388217e-01 -9.04078364e-01 -4.07069176e-02 4.22153682e-01 -9.05595064e-01 -4.07069176e-02 4.18967843e-01 -9.07074451e-01 -4.07069176e-02 4.15896624e-01 -9.08483744e-01 -4.07069176e-02 4.12712097e-01 -9.09936488e-01 -4.07069176e-02 4.09539908e-01 -9.11368549e-01 -4.07069176e-02 4.06275809e-01 -9.12828863e-01 -4.07069176e-02 4.03077215e-01 -9.14246142e-01 -4.07069176e-02 3.99951935e-01 -9.15618181e-01 -4.07069176e-02 3.96756172e-01 -9.17005956e-01 -4.07069176e-02 3.93546939e-01 -9.18383658e-01 -4.07069176e-02 3.90272349e-01 -9.19782102e-01 -4.07069176e-02 3.87052357e-01 -9.21145439e-01 -4.07069176e-02 3.83846730e-01 -9.22483206e-01 -4.07069176e-02 3.80620539e-01 -9.23818350e-01 -4.07069214e-02 3.77474278e-01 -9.25110459e-01 -4.07069176e-02 3.74255121e-01 -9.26416755e-01 -4.07069176e-02 3.70917916e-01 -9.27757084e-01 -4.07069176e-02 3.67595643e-01 -9.29080367e-01 -4.07069176e-02 3.64423513e-01 -9.30330157e-01 -4.07069176e-02 3.61277848e-01 -9.31548476e-01 -4.07069176e-02 3.58014673e-01 -9.32817519e-01 -4.07069176e-02 3.54764372e-01 -9.34050560e-01 -4.07069176e-02 3.51447284e-01 -9.35298681e-01 -4.07069176e-02 3.48189920e-01 -9.36515689e-01 -4.07069176e-02 3.44960868e-01 -9.37714398e-01 -4.07069176e-02 3.41682673e-01 -9.38920498e-01 -4.07069176e-02 3.38412762e-01 -9.40100491e-01 -4.07069176e-02 3.35126489e-01 -9.41279948e-01 -4.07069176e-02 3.31827611e-01 -9.42446232e-01 -4.07069176e-02 3.28546941e-01 -9.43594277e-01 -4.07069176e-02 3.25168371e-01 -9.44765151e-01 -4.07069176e-02 3.21874321e-01 -9.45893228e-01 -4.07069176e-02 3.18661392e-01 -9.46980596e-01 -4.07069176e-02 3.15372586e-01 -9.48079646e-01 -4.07069176e-02 3.12059253e-01 -9.49174821e-01 -4.07069176e-02 3.08642149e-01 -9.50291753e-01 -4.07069176e-02 3.05312067e-01 -9.51370060e-01 -4.07069176e-02 3.02111357e-01 -9.52388227e-01 -4.07069176e-02 2.98783422e-01 -9.53437448e-01 -4.07069176e-02 2.95440882e-01 -9.54479158e-01 -4.07069176e-02 2.92101026e-01 -9.55506325e-01 -4.07069176e-02 2.88704216e-01 -9.56535459e-01 -4.07069176e-02 2.85338879e-01 -9.57548380e-01 -4.07069176e-02 2.82079816e-01 -9.58513021e-01 -4.07069176e-02 2.78641999e-01 -9.59518492e-01 -4.07069176e-02 2.75184602e-01 -9.60513473e-01 -4.07069176e-02 2.71822721e-01 -9.61471081e-01 -4.07069176e-02 2.68547028e-01 -9.62393880e-01 -4.07069214e-02 2.65308201e-01 -9.63290274e-01 -4.07069176e-02 2.61928886e-01 -9.64216411e-01 -4.07069176e-02 2.58560658e-01 -9.65121925e-01 -4.07069176e-02 2.55144805e-01 -9.66031373e-01 -4.07069176e-02 2.51769990e-01 -9.66917992e-01 -4.07069176e-02 2.48431087e-01 -9.67780709e-01 -4.07069176e-02 2.45038465e-01 -9.68642056e-01 -4.07069176e-02 2.41583556e-01 -9.69510019e-01 -4.07069176e-02 2.38190219e-01 -9.70351815e-01 -4.07069176e-02 2.34892413e-01 -9.71157312e-01 -4.07069176e-02 2.31508493e-01 -9.71968293e-01 -4.07069176e-02 2.28108153e-01 -9.72771168e-01 -4.07069176e-02 2.24628776e-01 -9.73578811e-01 -4.07069176e-02 2.21121818e-01 -9.74382937e-01 -4.07069176e-02 2.17814699e-01 -9.75128114e-01 -4.07069176e-02 2.14516178e-01 -9.75857317e-01 -4.07069176e-02 2.11105675e-01 -9.76600647e-01 -4.07069176e-02 2.07710922e-01 -9.77328479e-01 -4.07069176e-02 2.04190835e-01 -9.78071272e-01 -4.07069176e-02 2.00765878e-01 -9.78780866e-01 -4.07069176e-02 1.97454780e-01 -9.79453206e-01 -4.07069176e-02 1.94042966e-01 -9.80133057e-01 -4.07069176e-02 1.90623105e-01 -9.80805159e-01 -4.07069176e-02 1.87117502e-01 -9.81479168e-01 -4.07069176e-02 1.83666065e-01 -9.82130289e-01 -4.07069176e-02 1.80231348e-01 -9.82763827e-01 -4.07069176e-02 1.76779240e-01 -9.83401000e-01 -4.07069214e-02 1.73461795e-01 -9.83990073e-01 -4.07069176e-02 1.70028284e-01 -9.84581888e-01 -4.07069176e-02 1.66574836e-01 -9.85175550e-01 -4.07069176e-02 1.63137957e-01 -9.85749722e-01 -4.07069176e-02 1.59693152e-01 -9.86312747e-01 -4.07069176e-02 1.56258762e-01 -9.86862898e-01 -4.07069176e-02 1.52821034e-01 -9.87401843e-01 -4.07069176e-02 1.49370328e-01 -9.87928212e-01 -4.07069176e-02 1.45932585e-01 -9.88443077e-01 -4.07069176e-02 1.42479971e-01 -9.88945246e-01 -4.07069176e-02 1.38930365e-01 -9.89451289e-01 -4.07069176e-02 1.35371581e-01 -9.89944875e-01 -4.07069176e-02 1.32027447e-01 -9.90395844e-01 -4.07069176e-02 1.28645435e-01 -9.90840137e-01 -4.07069176e-02 1.25175342e-01 -9.91287172e-01 -4.07069176e-02 1.21717125e-01 -9.91715133e-01 -4.07069176e-02 1.18185796e-01 -9.92141485e-01 -4.07069176e-02 1.14707299e-01 -9.92549121e-01 -4.07069176e-02 1.11343101e-01 -9.92932737e-01 -4.07069176e-02 1.07869029e-01 -9.93315995e-01 -4.07069176e-02 1.04389161e-01 -9.93687749e-01 -4.07069176e-02 1.00832105e-01 -9.94053781e-01 -4.07069176e-02 9.73745510e-02 -9.94401038e-01 -4.07069176e-02 9.39299166e-02 -9.94733334e-01 -4.07069176e-02 9.04264897e-02 -9.95058596e-01 -4.07069176e-02 8.69840831e-02 -9.95363474e-01 -4.07069176e-02 8.33926722e-02 -9.95671332e-01 -4.07069176e-02 8.00105780e-02 -9.95950460e-01 -4.07069176e-02 7.66466260e-02 -9.96212065e-01 -4.07069176e-02 7.31564686e-02 -9.96475935e-01 -4.07069176e-02 6.96721822e-02 -9.96723056e-01 -4.07069176e-02 6.62194937e-02 -9.96960759e-01 -4.07069176e-02 6.27247468e-02 -9.97185588e-01 -4.07069176e-02 5.92223257e-02 -9.97399926e-01 -4.07069176e-02 5.57539389e-02 -9.97600615e-01 -4.07069176e-02 5.21740690e-02 -9.97791886e-01 -4.07069176e-02 4.86707911e-02 -9.97972310e-01 -4.07069176e-02 4.52171527e-02 -9.98132646e-01 -4.07069176e-02 4.16372605e-02 -9.98290300e-01 -4.07069176e-02 3.82223055e-02 -9.98426855e-01 -4.07069176e-02 3.48581597e-02 -9.98548865e-01 -4.07069176e-02 3.12849581e-02 -9.98665273e-01 -4.07069176e-02 2.77819708e-02 -9.98772383e-01 -4.07069176e-02 2.42987648e-02 -9.98863995e-01 -4.07069176e-02 2.07910296e-02 -9.98940051e-01 -4.07069214e-02 1.73954275e-02 -9.99010146e-01 -4.07069176e-02 1.39121991e-02 -9.99054909e-01 -4.07069176e-02 1.03969863e-02 -9.99103606e-01 -4.07069176e-02 6.92230789e-03 -9.99138832e-01 -4.07069176e-02 3.44786048e-03 -9.99156415e-01 -4.07069176e-02 -3.10089854e-05 -9.99157786e-01 -4.07069176e-02 -3.50813940e-03 -9.99156296e-01 -4.07069176e-02 -6.99454965e-03 -9.99139607e-01 -4.07069176e-02 -1.04938364e-02 -9.99101043e-01 -4.07069176e-02 -1.39899207e-02 -9.99055326e-01 -4.07069176e-02 -1.75478030e-02 -9.99008536e-01 -4.07069176e-02 -2.11169291e-02 -9.98931944e-01 -4.07069176e-02 -2.45360788e-02 -9.98858273e-01 -4.07069176e-02 -2.79258061e-02 -9.98767793e-01 -4.07069176e-02 -3.14027742e-02 -9.98664618e-01 -4.07069176e-02 -3.48910652e-02 -9.98548985e-01 -4.07069176e-02 -3.84542271e-02 -9.98417795e-01 -4.07069176e-02 -4.19615582e-02 -9.98277545e-01 -4.07069176e-02 -4.53574918e-02 -9.98126507e-01 -4.07069176e-02 -4.88177948e-02 -9.97964859e-01 -4.07069176e-02 -5.22962511e-02 -9.97785032e-01 -4.07069176e-02 -5.58683388e-02 -9.97594357e-01 -4.07069176e-02 -5.93795665e-02 -9.97392118e-01 -4.07069214e-02 -6.28274009e-02 -9.97176468e-01 -4.07069176e-02 -6.63164705e-02 -9.96954203e-01 -4.07069176e-02 -6.97281510e-02 -9.96719897e-01 -4.07069176e-02 -7.31786117e-02 -9.96474206e-01 -4.07069176e-02 -7.66591430e-02 -9.96212244e-01 -4.07069176e-02 -8.02332163e-02 -9.95928705e-01 -4.07069176e-02 -8.37186947e-02 -9.95643914e-01 -4.07069176e-02 -8.70892853e-02 -9.95353639e-01 -4.07069176e-02 -9.05529857e-02 -9.95045245e-01 -4.07069176e-02 -9.40491557e-02 -9.94720995e-01 -4.07069176e-02 -9.75078493e-02 -9.94388044e-01 -4.07069176e-02 -1.00977279e-01 -9.94042099e-01 -4.07069176e-02 -1.04544133e-01 -9.93672788e-01 -4.07069176e-02 -1.08112395e-01 -9.93291199e-01 -4.07069176e-02 -1.11489393e-01 -9.92918909e-01 -4.07069176e-02 -1.14847809e-01 -9.92533803e-01 -4.07069176e-02 -1.18318900e-01 -9.92125332e-01 -4.07069176e-02 -1.21776156e-01 -9.91708219e-01 -4.07069176e-02 -1.25346735e-01 -9.91263747e-01 -4.07069176e-02 -1.28832236e-01 -9.90816116e-01 -4.07069176e-02 -1.32174417e-01 -9.90375638e-01 -4.07069176e-02 -1.35648444e-01 -9.89906490e-01 -4.07069176e-02 -1.39073804e-01 -9.89431560e-01 -4.07069176e-02 -1.42611161e-01 -9.88924563e-01 -4.07069176e-02 -1.46089152e-01 -9.88418996e-01 -4.07069176e-02 -1.49506077e-01 -9.87907231e-01 -4.07069176e-02 -1.52998254e-01 -9.87374127e-01 -4.07069176e-02 -1.56351954e-01 -9.86847043e-01 -4.07069176e-02 -1.59786612e-01 -9.86298800e-01 -4.07069176e-02 -1.63238227e-01 -9.85733509e-01 -4.07069176e-02 -1.66760474e-01 -9.85142171e-01 -4.07069176e-02 -1.70209333e-01 -9.84553039e-01 -4.07069176e-02 -1.73551798e-01 -9.83973384e-01 -4.07069176e-02 -1.76979154e-01 -9.83361423e-01 -4.07069176e-02 -1.80402502e-01 -9.82733727e-01 -4.07069176e-02 -1.83929726e-01 -9.82082307e-01 -4.07069176e-02 -1.87376738e-01 -9.81430769e-01 -4.07069176e-02 -1.90658152e-01 -9.80797529e-01 -4.07069176e-02 -1.94096819e-01 -9.80124176e-01 -4.07069176e-02 -1.97633564e-01 -9.79413807e-01 -4.07069176e-02 -2.01040208e-01 -9.78722990e-01 -4.07069214e-02 -2.04339921e-01 -9.78040338e-01 -4.07069176e-02 -2.07779989e-01 -9.77316499e-01 -4.07069176e-02 -2.11255908e-01 -9.76570547e-01 -4.07069176e-02 -2.14684159e-01 -9.75820899e-01 -4.07069176e-02 -2.18001455e-01 -9.75086153e-01 -4.07069176e-02 -2.21379951e-01 -9.74322736e-01 -4.07069176e-02 -2.24810511e-01 -9.73537445e-01 -4.07069176e-02 -2.28277460e-01 -9.72731888e-01 -4.07069176e-02 -2.31680632e-01 -9.71928477e-01 -4.07069176e-02 -2.34990716e-01 -9.71132517e-01 -4.07069176e-02 -2.38427803e-01 -9.70292866e-01 -4.07069176e-02 -2.41827309e-01 -9.69451368e-01 -4.07069176e-02 -2.45141461e-01 -9.68616724e-01 -4.07069176e-02 -2.48519242e-01 -9.67756927e-01 -4.07069176e-02 -2.51980841e-01 -9.66861308e-01 -4.07069176e-02 -2.55368829e-01 -9.65974212e-01 -4.07069176e-02 -2.58712918e-01 -9.65082347e-01 -4.07069176e-02 -2.62170255e-01 -9.64150608e-01 -4.07069176e-02 -2.65452296e-01 -9.63250458e-01 -4.07069176e-02 -2.68800467e-01 -9.62320924e-01 -4.07069176e-02 -2.72156090e-01 -9.61379707e-01 -4.07069214e-02 -2.75417745e-01 -9.60448146e-01 -4.07069176e-02 -2.78775305e-01 -9.59478855e-01 -4.07069176e-02 -2.82125264e-01 -9.58498716e-01 -4.07069176e-02 -2.85485506e-01 -9.57504928e-01 -4.07069176e-02 -2.88823396e-01 -9.56500888e-01 -4.07069176e-02 -2.92169303e-01 -9.55484450e-01 -4.07069176e-02 -2.95560271e-01 -9.54441845e-01 -4.07069176e-02 -2.98893183e-01 -9.53404129e-01 -4.07069176e-02 -3.02215070e-01 -9.52354014e-01 -4.07069176e-02 -3.05553943e-01 -9.51291978e-01 -4.07069176e-02 -3.08801413e-01 -9.50239062e-01 -4.07069176e-02 -3.12199205e-01 -9.49128866e-01 -4.07069176e-02 -3.15517604e-01 -9.48032260e-01 -4.07069176e-02 -3.18815351e-01 -9.46928263e-01 -4.07069176e-02 -3.22119832e-01 -9.45809722e-01 -4.07069214e-02 -3.25310916e-01 -9.44716334e-01 -4.07069176e-02 -3.28601778e-01 -9.43575799e-01 -4.07069176e-02 -3.31891000e-01 -9.42424834e-01 -4.07069176e-02 -3.35253477e-01 -9.41232383e-01 -4.07069176e-02 -3.38573068e-01 -9.40043569e-01 -4.07069176e-02 -3.41827959e-01 -9.38866377e-01 -4.07069176e-02 -3.45137537e-01 -9.37648058e-01 -4.07069176e-02 -3.48301977e-01 -9.36473787e-01 -4.07069176e-02 -3.51592034e-01 -9.35244799e-01 -4.07069176e-02 -3.54833335e-01 -9.34024870e-01 -4.07069176e-02 -3.58115941e-01 -9.32779849e-01 -4.07069176e-02 -3.61428618e-01 -9.31493104e-01 -4.07069176e-02 -3.64674836e-01 -9.30230141e-01 -4.07069176e-02 -3.67837250e-01 -9.28984225e-01 -4.07069176e-02 -3.71067643e-01 -9.27697718e-01 -4.07069176e-02 -3.74299020e-01 -9.26398993e-01 -4.07069176e-02 -3.77618968e-01 -9.25049841e-01 -4.07069176e-02 -3.80862683e-01 -9.23717916e-01 -4.07069176e-02 -3.84019256e-01 -9.22412694e-01 -4.07069176e-02 -3.87211382e-01 -9.21076357e-01 -4.07069176e-02 -3.90430778e-01 -9.19715405e-01 -4.07069176e-02 -3.93694460e-01 -9.18320894e-01 -4.07069176e-02 -3.96900415e-01 -9.16943192e-01 -4.07069176e-02 -4.00097370e-01 -9.15554106e-01 -4.07069176e-02 -4.03291732e-01 -9.14151251e-01 -4.07069176e-02 -4.06419903e-01 -9.12764251e-01 -4.07069176e-02 -4.09591019e-01 -9.11346853e-01 -4.07069176e-02 -4.12775069e-01 -9.09907222e-01 -4.07069176e-02 -4.16019171e-01 -9.08424616e-01 -4.07069176e-02 -4.19208288e-01 -9.06960368e-01 -4.07069176e-02 -4.22256589e-01 -9.05545413e-01 -4.07069176e-02 -4.25403416e-01 -9.04071450e-01 -4.07069176e-02 -4.28648561e-01 -9.02537167e-01 -4.07069176e-02 -4.31822300e-01 -9.01023149e-01 -4.07069176e-02 -4.34875876e-01 -8.99557471e-01 -4.07069176e-02 -4.38009650e-01 -8.98034811e-01 -4.07069176e-02 -4.41228211e-01 -8.96454573e-01 -4.07069176e-02 -4.44370449e-01 -8.94902527e-01 -4.07069176e-02 -4.47420180e-01 -8.93381298e-01 -4.07069176e-02 -4.50514704e-01 -8.91826212e-01 -4.07069176e-02 -4.53610063e-01 -8.90254438e-01 -4.07069176e-02 -4.56803560e-01 -8.88619363e-01 -4.07069176e-02 -4.59921449e-01 -8.87010694e-01 -4.07069176e-02 -4.62917268e-01 -8.85453045e-01 -4.07069176e-02 -4.66012418e-01 -8.83826554e-01 -4.07069176e-02 -4.69086468e-01 -8.82197380e-01 -4.07069176e-02 -4.72236067e-01 -8.80515814e-01 -4.07069176e-02 -4.75353628e-01 -8.78836930e-01 -4.07069176e-02 -4.78431255e-01 -8.77168119e-01 -4.07069176e-02 -4.81451780e-01 -8.75512064e-01 -4.07069176e-02 -4.84494448e-01 -8.73828650e-01 -4.07069176e-02 -4.87634361e-01 -8.72081637e-01 -4.07069176e-02 -4.90593463e-01 -8.70422184e-01 -4.07069176e-02 -4.93558973e-01 -8.68742108e-01 -4.07069176e-02 -4.96576220e-01 -8.67024302e-01 -4.07069176e-02 -4.99577492e-01 -8.65296900e-01 -4.07069176e-02 -5.02612054e-01 -8.63537848e-01 -4.07069176e-02 -5.05606592e-01 -8.61788273e-01 -4.07069176e-02 -5.08619010e-01 -8.60013306e-01 -4.07069176e-02 -5.11619270e-01 -8.58231306e-01 -4.07069176e-02 -5.14610648e-01 -8.56442332e-01 -4.07069176e-02 -5.17605543e-01 -8.54633570e-01 -4.07069176e-02 -5.20614147e-01 -8.52805674e-01 -4.07069176e-02 -5.23661017e-01 -8.50936711e-01 -4.07069176e-02 -5.26614487e-01 -8.49114597e-01 -4.07069176e-02 -5.29544890e-01 -8.47288251e-01 -4.07069176e-02 -5.32593191e-01 -8.45375240e-01 -4.07069176e-02 -5.35576284e-01 -8.43487859e-01 -4.07069176e-02 -5.38509488e-01 -8.41617525e-01 -4.07069176e-02 -5.41378438e-01 -8.39775920e-01 -4.07069176e-02 -5.44210613e-01 -8.37943316e-01 -4.07069176e-02 -5.47149181e-01 -8.36025655e-01 -4.07069176e-02 -5.50047159e-01 -8.34124863e-01 -4.07069176e-02 -5.52954257e-01 -8.32196355e-01 -4.07069176e-02 -5.55861413e-01 -8.30260873e-01 -4.07069176e-02 -5.58756828e-01 -8.28316152e-01 -4.07069176e-02 -5.61646044e-01 -8.26358318e-01 -4.07069176e-02 -5.64528584e-01 -8.24393272e-01 -4.07069176e-02 -5.67435980e-01 -8.22393835e-01 -4.07069176e-02 -5.70305288e-01 -8.20406437e-01 -4.07069176e-02 -5.73193252e-01 -8.18389893e-01 -4.07069176e-02 -5.76118290e-01 -8.16337287e-01 -4.07069176e-02 -5.78915179e-01 -8.14354539e-01 -4.07069176e-02 -5.81655562e-01 -8.12399507e-01 -4.07069176e-02 -5.84497869e-01 -8.10353398e-01 -4.07069176e-02 -5.87337732e-01 -8.08300495e-01 -4.07069176e-02 -5.90212584e-01 -8.06201041e-01 -4.07069176e-02 -5.93031108e-01 -8.04133058e-01 -4.07069176e-02 -5.95743835e-01 -8.02123785e-01 -4.07069176e-02 -5.98537683e-01 -8.00039232e-01 -4.07069176e-02 -6.01329744e-01 -7.97945797e-01 -4.07069176e-02 -6.04125917e-01 -7.95833290e-01 -4.07069176e-02 -6.06884539e-01 -7.93730140e-01 -4.07069176e-02 -6.09715283e-01 -7.91553974e-01 -4.07069176e-02 -6.12488329e-01 -7.89414644e-01 -4.07069176e-02 -6.15167439e-01 -7.87325442e-01 -4.07069176e-02 -6.17906928e-01 -7.85180032e-01 -4.07069176e-02 -6.20653272e-01 -7.83009291e-01 -4.07069176e-02 -6.23433888e-01 -7.80797005e-01 -4.07069176e-02 -6.26160920e-01 -7.78613508e-01 -4.07069176e-02 -6.28810585e-01 -7.76475310e-01 -4.07069176e-02 -6.31504297e-01 -7.74283171e-01 -4.07069176e-02 -6.34206593e-01 -7.72073269e-01 -4.07069176e-02 -6.36923134e-01 -7.69833863e-01 -4.07069176e-02 -6.39612794e-01 -7.67599940e-01 -4.07069176e-02 -6.42286420e-01 -7.65365660e-01 -4.07069176e-02 -6.44997180e-01 -7.63080478e-01 -4.07069176e-02 -6.47652864e-01 -7.60829031e-01 -4.07069176e-02 -6.50299847e-01 -7.58566141e-01 -4.07069176e-02 -6.52944922e-01 -7.56295025e-01 -4.07069176e-02 -6.55517340e-01 -7.54064381e-01 -4.07069176e-02 -6.58218622e-01 -7.51705110e-01 -4.07069176e-02 -6.60839021e-01 -7.49405444e-01 -4.07069176e-02 -6.63347065e-01 -7.47186661e-01 -4.07069176e-02 -6.65956616e-01 -7.44860411e-01 -4.07069176e-02 -6.68563724e-01 -7.42520809e-01 -4.07069176e-02 -6.71145558e-01 -7.40190983e-01 -4.07069176e-02 -6.73748791e-01 -7.37817287e-01 -4.07069176e-02 -6.76390588e-01 -7.35400796e-01 -4.07069176e-02 -6.78977191e-01 -7.33012199e-01 -4.07069176e-02 -6.81492329e-01 -7.30672002e-01 -4.07069176e-02 -6.84114933e-01 -7.28218496e-01 -4.07069176e-02 -6.86590433e-01 -7.25882888e-01 -4.07069176e-02 -6.89104140e-01 -7.23499775e-01 -4.07069176e-02 -6.91653907e-01 -7.21056998e-01 -4.07069176e-02 -6.94106698e-01 -7.18709826e-01 -4.07069176e-02 -6.96605742e-01 -7.16285706e-01 -4.07069176e-02 -6.99091911e-01 -7.13855743e-01 -4.07069176e-02 -7.01575637e-01 -7.11417437e-01 -4.07069176e-02 -7.04075754e-01 -7.08945394e-01 -4.07069176e-02 -7.06554890e-01 -7.06453562e-01 -4.07069176e-02 -7.09035933e-01 -7.03984559e-01 -4.07069176e-02 -7.11459696e-01 -7.01532781e-01 -4.07069176e-02 -7.13911176e-01 -6.99034393e-01 -4.07069176e-02 -7.16337442e-01 -6.96551383e-01 -4.07069176e-02 -7.18753994e-01 -6.94060445e-01 -4.07069176e-02 -7.21239984e-01 -6.91460252e-01 -4.07069176e-02 -7.23664284e-01 -6.88935220e-01 -4.07069176e-02 -7.26050138e-01 -6.86413825e-01 -4.07069176e-02 -7.28449941e-01 -6.83867574e-01 -4.07069176e-02 -7.30761051e-01 -6.81395233e-01 -4.07069176e-02 -7.33129323e-01 -6.78849578e-01 -4.07069176e-02 -7.35505998e-01 -6.76276803e-01 -4.07069176e-02 -7.37856269e-01 -6.73708320e-01 -4.07069176e-02 -7.40239084e-01 -6.71090186e-01 -4.07069176e-02 -7.42570698e-01 -6.68509603e-01 -4.07069176e-02 -7.44870126e-01 -6.65945888e-01 -4.07069176e-02 -7.47190297e-01 -6.63343728e-01 -4.07069176e-02 -7.49552488e-01 -6.60670340e-01 -4.07069176e-02 -7.51887977e-01 -6.58013940e-01 -4.07069176e-02 -7.54125893e-01 -6.55445874e-01 -4.07069176e-02 -7.56447971e-01 -6.52762651e-01 -4.07069176e-02 -7.58708656e-01 -6.50138259e-01 -4.07069214e-02 -7.60912538e-01 -6.47553027e-01 -4.07069176e-02 -7.63179898e-01 -6.44883990e-01 -4.07069176e-02 -7.65428543e-01 -6.42210543e-01 -4.07069176e-02 -7.67713785e-01 -6.39477611e-01 -4.07069176e-02 -7.69944191e-01 -6.36790156e-01 -4.07069176e-02 -7.72118866e-01 -6.34152174e-01 -4.07069176e-02 -7.74336934e-01 -6.31439865e-01 -4.07069176e-02 -7.76506960e-01 -6.28770828e-01 -4.07069176e-02 -7.78763056e-01 -6.25975311e-01 -4.07069176e-02 -7.80964553e-01 -6.23227835e-01 -4.07069214e-02 -7.83119023e-01 -6.20512009e-01 -4.07069176e-02 -7.85278022e-01 -6.17783964e-01 -4.07069176e-02 -7.87370980e-01 -6.15111530e-01 -4.07069176e-02 -7.89510965e-01 -6.12363160e-01 -4.07069176e-02 -7.91636586e-01 -6.09610736e-01 -4.07069176e-02 -7.93819189e-01 -6.06764555e-01 -4.07069176e-02 -7.95943797e-01 -6.03978753e-01 -4.07069176e-02 -7.97988653e-01 -6.01275563e-01 -4.07069176e-02 -8.00082803e-01 -5.98482609e-01 -4.07069176e-02 -8.02166760e-01 -5.95686436e-01 -4.07069176e-02 -8.04297149e-01 -5.92806220e-01 -4.07069176e-02 -8.06377351e-01 -5.89976609e-01 -4.07069176e-02 -8.08373928e-01 -5.87237000e-01 -4.07069176e-02 -8.10457110e-01 -5.84354460e-01 -4.07069176e-02 -8.12499702e-01 -5.81516266e-01 -4.07069176e-02 -8.14463139e-01 -5.78761280e-01 -4.07069176e-02 -8.16473365e-01 -5.75924098e-01 -4.07069176e-02 -8.18478346e-01 -5.73067248e-01 -4.07069176e-02 -8.20532143e-01 -5.70122778e-01 -4.07069176e-02 -8.22516799e-01 -5.67260802e-01 -4.07069176e-02 -8.24432492e-01 -5.64470649e-01 -4.07069176e-02 -8.26401591e-01 -5.61580300e-01 -4.07069176e-02 -8.28363299e-01 -5.58686614e-01 -4.07069176e-02 -8.30339432e-01 -5.55744112e-01 -4.07069176e-02 -8.32283318e-01 -5.52828312e-01 -4.07069176e-02 -8.34204137e-01 -5.49922824e-01 -4.07069176e-02 -8.36106062e-01 -5.47029734e-01 -4.07069176e-02 -8.37956190e-01 -5.44191182e-01 -4.07069176e-02 -8.39857757e-01 -5.41250229e-01 -4.07069176e-02 -8.41741204e-01 -5.38315713e-01 -4.07069176e-02 -8.43675137e-01 -5.35279214e-01 -4.07069176e-02 -8.45533431e-01 -5.32345235e-01 -4.07069176e-02 -8.47324133e-01 -5.29484093e-01 -4.07069176e-02 -8.49168181e-01 -5.26527584e-01 -4.07069176e-02 -8.50994766e-01 -5.23567379e-01 -4.07069176e-02 -8.52830291e-01 -5.20576537e-01 -4.07069176e-02 -8.54640186e-01 -5.17594337e-01 -4.07069176e-02 -8.56448233e-01 -5.14597356e-01 -4.07069176e-02 -8.58248353e-01 -5.11590481e-01 -4.07069176e-02 -8.60025287e-01 -5.08596897e-01 -4.07069176e-02 -8.61840785e-01 -5.05515754e-01 -4.07069176e-02 -8.63609254e-01 -5.02487779e-01 -4.07069176e-02 -8.65302742e-01 -4.99568492e-01 -4.07069176e-02 -8.67032230e-01 -4.96556848e-01 -4.07069176e-02 -8.68753850e-01 -4.93538350e-01 -4.07069176e-02 -8.70496154e-01 -4.90464538e-01 -4.07069176e-02 -8.72198105e-01 -4.87425148e-01 -4.07069176e-02 -8.73892248e-01 -4.84377384e-01 -4.07069176e-02 -8.75624776e-01 -4.81246740e-01 -4.07069176e-02 -8.77317309e-01 -4.78158265e-01 -4.07069176e-02 -8.78921449e-01 -4.75195915e-01 -4.07069176e-02 -8.80587518e-01 -4.72104132e-01 -4.07069176e-02 -8.82275522e-01 -4.68941092e-01 -4.07069176e-02 -8.83906126e-01 -4.65863973e-01 -4.07069176e-02 -8.85478318e-01 -4.62865233e-01 -4.07069176e-02 -8.87088656e-01 -4.59770262e-01 -4.07069176e-02 -8.88684034e-01 -4.56680834e-01 -4.07069176e-02 -8.90277982e-01 -4.53566492e-01 -4.07069176e-02 -8.91860723e-01 -4.50443596e-01 -4.07069176e-02 -8.93425226e-01 -4.47332263e-01 -4.07069176e-02 -8.94982040e-01 -4.44209218e-01 -4.07069176e-02 -8.96522999e-01 -4.41092074e-01 -4.07069176e-02 -8.98063719e-01 -4.37948704e-01 -4.07069176e-02 -8.99618983e-01 -4.34742153e-01 -4.07069176e-02 -9.01180029e-01 -4.31494147e-01 -4.07069176e-02 -9.02639747e-01 -4.28438932e-01 -4.07069176e-02 -9.04090166e-01 -4.25364375e-01 -4.07069176e-02 -9.05565143e-01 -4.22217548e-01 -4.07069176e-02 -9.07071531e-01 -4.18970704e-01 -4.07069176e-02 -9.08528984e-01 -4.15799171e-01 -4.07069176e-02 -9.09936607e-01 -4.12711799e-01 -4.07069176e-02 -9.11367595e-01 -4.09543574e-01 -4.07069176e-02 -9.12800312e-01 -4.06338096e-01 -4.07069176e-02 -9.14214373e-01 -4.03148741e-01 -4.07069176e-02 -9.15620387e-01 -3.99944454e-01 -4.07069176e-02 -9.17041183e-01 -3.96674126e-01 -4.07069176e-02 -9.18416977e-01 -3.93473119e-01 -4.07069176e-02 -9.19737279e-01 -3.90379727e-01 -4.07069176e-02 -9.21100855e-01 -3.87153774e-01 -4.07069176e-02 -9.22451794e-01 -3.83925468e-01 -4.07069176e-02 -9.23812628e-01 -3.80635381e-01 -4.07069176e-02 -9.25145090e-01 -3.77391636e-01 -4.07069176e-02 -9.26422954e-01 -3.74235600e-01 -4.07069176e-02 -9.27745223e-01 -3.70948046e-01 -4.07069176e-02 -9.29045320e-01 -3.67686987e-01 -4.07069176e-02 -9.30282414e-01 -3.64544213e-01 -4.07069176e-02 -9.31550443e-01 -3.61275166e-01 -4.07069176e-02 -9.32816088e-01 -3.58018279e-01 -4.07069176e-02 -9.34083879e-01 -3.54677826e-01 -4.07069176e-02 -9.35316205e-01 -3.51401299e-01 -4.07069176e-02 -9.36496496e-01 -3.48240703e-01 -4.07069176e-02 -9.37740266e-01 -3.44887614e-01 -4.07069176e-02 -9.38947976e-01 -3.41610789e-01 -4.07069176e-02 -9.40127015e-01 -3.38341236e-01 -4.07069176e-02 -9.41308260e-01 -3.35049897e-01 -4.07069176e-02 -9.42466378e-01 -3.31769824e-01 -4.07069176e-02 -9.43621099e-01 -3.28471988e-01 -4.07069176e-02 -9.44726884e-01 -3.25281084e-01 -4.07069176e-02 -9.45858955e-01 -3.21971923e-01 -4.07069176e-02 -9.46976125e-01 -3.18672687e-01 -4.07069176e-02 -9.48117852e-01 -3.15257788e-01 -4.07069176e-02 -9.49214697e-01 -3.11941087e-01 -4.07069176e-02 -9.50266421e-01 -3.08723539e-01 -4.07069176e-02 -9.51339483e-01 -3.05400491e-01 -4.07069176e-02 -9.52394783e-01 -3.02088737e-01 -4.07069176e-02 -9.53474224e-01 -2.98667014e-01 -4.07069176e-02 -9.54518259e-01 -2.95317978e-01 -4.07069176e-02 -9.55513835e-01 -2.92078614e-01 -4.07069176e-02 -9.56522584e-01 -2.88747013e-01 -4.07069176e-02 -9.57525194e-01 -2.85408378e-01 -4.07069176e-02 -9.58541274e-01 -2.81983048e-01 -4.07069176e-02 -9.59523022e-01 -2.78626144e-01 -4.07069176e-02 -9.60463822e-01 -2.75360495e-01 -4.07069176e-02 -9.61415172e-01 -2.72024810e-01 -4.07069176e-02 -9.62365448e-01 -2.68646508e-01 -4.07069176e-02 -9.63292837e-01 -2.65293956e-01 -4.07069176e-02 -9.64215279e-01 -2.61934966e-01 -4.07069176e-02 -9.65121925e-01 -2.58562237e-01 -4.07069176e-02 -9.66040671e-01 -2.55104989e-01 -4.07069176e-02 -9.66931403e-01 -2.51720458e-01 -4.07069176e-02 -9.67773497e-01 -2.48454407e-01 -4.07069176e-02 -9.68633473e-01 -2.45071337e-01 -4.07069176e-02 -9.69501495e-01 -2.41620854e-01 -4.07069176e-02 -9.70344305e-01 -2.38220647e-01 -4.07069176e-02 -9.71152544e-01 -2.34909073e-01 -4.07069176e-02 -9.71966147e-01 -2.31518209e-01 -4.07069176e-02 -9.72774029e-01 -2.28098571e-01 -4.07069176e-02 -9.73569989e-01 -2.24667698e-01 -4.07069176e-02 -9.74354684e-01 -2.21245617e-01 -4.07069176e-02 -9.75096703e-01 -2.17953011e-01 -4.07069176e-02 -9.75867867e-01 -2.14464352e-01 -4.07069176e-02 -9.76612985e-01 -2.11054251e-01 -4.07069176e-02 -9.77323711e-01 -2.07736552e-01 -4.07069176e-02 -9.78047073e-01 -2.04306290e-01 -4.07069176e-02 -9.78769839e-01 -2.00817138e-01 -4.07069176e-02 -9.79464054e-01 -1.97399661e-01 -4.07069176e-02 -9.80130494e-01 -1.94061473e-01 -4.07069176e-02 -9.80797112e-01 -1.90660477e-01 -4.07069176e-02 -9.81476128e-01 -1.87130451e-01 -4.07069176e-02 -9.82127190e-01 -1.83690324e-01 -4.07069214e-02 -9.82738972e-01 -1.80374414e-01 -4.07069176e-02 -9.83370721e-01 -1.76935449e-01 -4.07069176e-02 -9.83981431e-01 -1.73504993e-01 -4.07069176e-02 -9.84598398e-01 -1.69939414e-01 -4.07069176e-02 -9.85187531e-01 -1.66507497e-01 -4.07069437e-02 -9.85740066e-01 -1.63185537e-01 -4.07069176e-02 -9.86322224e-01 -1.59632578e-01 -4.07069176e-02 -9.86875772e-01 -1.56185001e-01 -4.07069214e-02 -9.87396359e-01 -1.52857020e-01 -4.07069176e-02 -9.87921178e-01 -1.49417818e-01 -4.07069176e-02 -9.88452971e-01 -1.45860612e-01 -4.07069176e-02 -9.88960624e-01 -1.42386883e-01 -4.07069214e-02 -9.89437342e-01 -1.39032871e-01 -4.07069176e-02 -9.89929557e-01 -1.35487124e-01 -4.07069176e-02 -9.90399599e-01 -1.32010102e-01 -4.07069214e-02 -9.90837276e-01 -1.28671408e-01 -4.07069176e-02 -9.91282642e-01 -1.25211611e-01 -4.07069176e-02 -9.91707981e-01 -1.21785551e-01 -4.07069176e-02 -9.92136180e-01 -1.18234046e-01 -4.07069176e-02 -9.92547154e-01 -1.14729285e-01 -4.07069214e-02 -9.92932618e-01 -1.11377642e-01 -4.07069474e-02 -9.93321776e-01 -1.07840315e-01 -4.07069698e-02 -9.93704557e-01 -1.04307868e-01 -4.07070518e-02 -9.94055629e-01 -1.00921281e-01 -4.07070629e-02 -9.94376183e-01 -9.77842659e-02 -4.07073423e-02 -9.94707406e-01 -9.43316370e-02 -4.07072715e-02 -9.95074213e-01 -9.03838873e-02 -4.07072864e-02 -9.95313704e-01 -8.77090469e-02 -4.07072827e-02 -9.95593548e-01 -8.44774991e-02 -4.07072827e-02 -9.95910406e-01 -8.06540325e-02 -4.07072864e-02 -9.96172369e-01 -7.73511454e-02 -4.07072827e-02 -9.96506870e-01 -7.29168728e-02 -4.07072790e-02 -9.96712804e-01 -7.00467899e-02 -4.07072864e-02 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. 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. 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. 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. -9.97374773e-01 6.34484813e-02 -3.48994993e-02 -9.97100353e-01 6.76003844e-02 -3.48994881e-02 -9.96926963e-01 7.00951442e-02 -3.48993279e-02 -9.96684849e-01 7.34660625e-02 -3.48993577e-02 -9.96430278e-01 7.68338144e-02 -3.48994434e-02 -9.96168375e-01 8.01782459e-02 -3.48995812e-02 -9.95882869e-01 8.36460516e-02 -3.48995999e-02 -9.95574951e-01 8.72277170e-02 -3.48996781e-02 -9.95256722e-01 9.07884166e-02 -3.48995887e-02 -9.94944096e-01 9.41513181e-02 -3.48995328e-02 -9.94610369e-01 9.76120010e-02 -3.48996781e-02 -9.94253516e-01 1.01195894e-01 -3.48996520e-02 -9.93897915e-01 1.04630008e-01 -3.48995924e-02 -9.93524253e-01 1.08112566e-01 -3.48996669e-02 -9.93148565e-01 1.11515380e-01 -3.48995291e-02 -9.92762208e-01 1.14883438e-01 -3.48996297e-02 -9.92342174e-01 1.18459620e-01 -3.48996669e-02 -9.91911530e-01 1.22023463e-01 -3.48996110e-02 -9.91481006e-01 1.25485376e-01 -3.48996110e-02 -9.91036296e-01 1.28932357e-01 -3.48996297e-02 -9.90581036e-01 1.32395729e-01 -3.48996185e-02 -9.90125358e-01 1.35764733e-01 -3.48995030e-02 -9.89649236e-01 1.39192656e-01 -3.48996781e-02 -9.89139616e-01 1.42757744e-01 -3.48995961e-02 -9.88648295e-01 1.46123588e-01 -3.48995663e-02 -9.88134325e-01 1.49558857e-01 -3.48996930e-02 -9.87592697e-01 1.53103888e-01 -3.48995887e-02 -9.87052500e-01 1.56538188e-01 -3.48996148e-02 -9.86499786e-01 1.59989938e-01 -3.48996222e-02 -9.85942423e-01 1.63393617e-01 -3.48995961e-02 -9.85380232e-01 1.66743338e-01 -3.48995849e-02 -9.84802306e-01 1.70128182e-01 -3.48996110e-02 -9.84190822e-01 1.73647448e-01 -3.48996595e-02 -9.83562589e-01 1.77171990e-01 -3.48996036e-02 -9.82946515e-01 1.80530697e-01 -3.48995477e-02 -9.82318103e-01 1.83931082e-01 -3.48996930e-02 -9.81652081e-01 1.87449485e-01 -3.48996185e-02 -9.80998576e-01 1.90838188e-01 -3.48995961e-02 -9.80320752e-01 1.94294140e-01 -3.48995999e-02 -9.79651034e-01 1.97641194e-01 -3.48995477e-02 -9.78980482e-01 2.00941414e-01 -3.48995849e-02 -9.78249729e-01 2.04470068e-01 -3.48996595e-02 -9.77507353e-01 2.07989976e-01 -3.48995961e-02 -9.76777911e-01 2.11390153e-01 -3.48995738e-02 -9.76025879e-01 2.14831173e-01 -3.48995961e-02 -9.75280643e-01 2.18189001e-01 -3.48995887e-02 -9.74533617e-01 2.21498206e-01 -3.48995402e-02 -9.73751664e-01 2.24910840e-01 -3.48996781e-02 -9.72932100e-01 2.28441954e-01 -3.48996297e-02 -9.72148597e-01 2.31749669e-01 -3.48995030e-02 -9.71371472e-01 2.34989792e-01 -3.48995849e-02 -9.70513463e-01 2.38502532e-01 -3.48996744e-02 -9.69653189e-01 2.41968274e-01 -3.48995812e-02 -9.68802333e-01 2.45352775e-01 -3.48996148e-02 -9.67946529e-01 2.48714447e-01 -3.48995849e-02 -9.67092872e-01 2.52010942e-01 -3.48995477e-02 -9.66222942e-01 2.55334914e-01 -3.48995999e-02 -9.65302825e-01 2.58783728e-01 -3.48996706e-02 -9.64373052e-01 2.62235314e-01 -3.48996110e-02 -9.63465512e-01 2.65538931e-01 -3.48995589e-02 -9.62537169e-01 2.68892378e-01 -3.48996930e-02 -9.61565137e-01 2.72348076e-01 -3.48995999e-02 -9.60611701e-01 2.75688469e-01 -3.48995700e-02 -9.59634840e-01 2.79065907e-01 -3.48995924e-02 -9.58675325e-01 2.82346725e-01 -3.48995030e-02 -9.57721233e-01 2.85571963e-01 -3.48995775e-02 -9.56691325e-01 2.88994342e-01 -3.48996930e-02 -9.55641866e-01 2.92451560e-01 -3.48995812e-02 -9.54615593e-01 2.95785666e-01 -3.48995849e-02 -9.53608215e-01 2.99014568e-01 -3.48995067e-02 -9.52561915e-01 3.02330166e-01 -3.48996669e-02 -9.51481819e-01 3.05719674e-01 -3.48995663e-02 -9.50432718e-01 3.08958858e-01 -3.48995142e-02 -9.49344993e-01 3.12286705e-01 -3.48996669e-02 -9.48233962e-01 3.15644205e-01 -3.48995142e-02 -9.47167158e-01 3.18834871e-01 -3.48995663e-02 -9.46012676e-01 3.22239727e-01 -3.48996520e-02 -9.44858849e-01 3.25613141e-01 -3.48995477e-02 -9.43717122e-01 3.28898340e-01 -3.48995700e-02 -9.42566335e-01 3.32183570e-01 -3.48995775e-02 -9.41412389e-01 3.35448235e-01 -3.48995775e-02 -9.40261602e-01 3.38650733e-01 -3.48995440e-02 -9.39072430e-01 3.41942966e-01 -3.48996446e-02 -9.37825024e-01 3.45326483e-01 -3.48995775e-02 -9.36632991e-01 3.48536402e-01 -3.48995663e-02 -9.35422778e-01 3.51778358e-01 -3.48996669e-02 -9.34166074e-01 3.55112433e-01 -3.48995887e-02 -9.32927847e-01 3.58379543e-01 -3.48996148e-02 -9.31656480e-01 3.61647546e-01 -3.48995999e-02 -9.30417180e-01 3.64831895e-01 -3.48995700e-02 -9.29169834e-01 3.67998362e-01 -3.48995775e-02 -9.27888751e-01 3.71215641e-01 -3.48995999e-02 -9.26559865e-01 3.74519736e-01 -3.48996781e-02 -9.25208092e-01 3.77848536e-01 -3.48995961e-02 -9.23916757e-01 3.80986989e-01 -3.48995402e-02 -9.22584116e-01 3.84208053e-01 -3.48996930e-02 -9.21198487e-01 3.87520880e-01 -3.48995924e-02 -9.19851780e-01 3.90701622e-01 -3.48995924e-02 -9.18483615e-01 3.93906444e-01 -3.48995924e-02 -9.17125583e-01 3.97063524e-01 -3.48995700e-02 -9.15773094e-01 4.00177330e-01 -3.48995812e-02 -9.14348900e-01 4.03415918e-01 -3.48996781e-02 -9.12888348e-01 4.06714886e-01 -3.48996259e-02 -9.11454618e-01 4.09913391e-01 -3.48996222e-02 -9.10010874e-01 4.13110048e-01 -3.48996297e-02 -9.08572674e-01 4.16256636e-01 -3.48996036e-02 -9.07133877e-01 4.19384271e-01 -3.48995738e-02 -9.05674219e-01 4.22529608e-01 -3.48996781e-02 -9.04165030e-01 4.25748050e-01 -3.48996371e-02 -9.02711034e-01 4.28825557e-01 -3.48995738e-02 -9.01257575e-01 4.31867808e-01 -3.48996036e-02 -8.99709165e-01 4.35092956e-01 -3.48996781e-02 -8.98146152e-01 4.38311726e-01 -3.48996110e-02 -8.96621406e-01 4.41415906e-01 -3.48995775e-02 -8.95087719e-01 4.44519907e-01 -3.48996446e-02 -8.93545985e-01 4.47609514e-01 -3.48995663e-02 -8.92018318e-01 4.50649261e-01 -3.48996259e-02 -8.90403509e-01 4.53829050e-01 -3.48996967e-02 -8.88758659e-01 4.57044512e-01 -3.48996036e-02 -8.87195528e-01 4.60065573e-01 -3.48995291e-02 -8.85606408e-01 4.63123232e-01 -3.48997116e-02 -8.83939385e-01 4.66297626e-01 -3.48996148e-02 -8.82309675e-01 4.69371438e-01 -3.48996036e-02 -8.80670905e-01 4.72440451e-01 -3.48995812e-02 -8.79054785e-01 4.75436658e-01 -3.48995477e-02 -8.77431273e-01 4.78434294e-01 -3.48996185e-02 -8.75703812e-01 4.81586188e-01 -3.48996930e-02 -8.73976648e-01 4.84706044e-01 -3.48996036e-02 -8.72290969e-01 4.87735152e-01 -3.48996148e-02 -8.70575368e-01 4.90795761e-01 -3.48996371e-02 -8.68854105e-01 4.93832201e-01 -3.48996185e-02 -8.67167175e-01 4.96792883e-01 -3.48995663e-02 -8.65463495e-01 4.99753684e-01 -3.48995775e-02 -8.63697946e-01 5.02797365e-01 -3.48996930e-02 -8.61898124e-01 5.05878329e-01 -3.48996408e-02 -8.60163093e-01 5.08820415e-01 -3.48995849e-02 -8.58397603e-01 5.11793852e-01 -3.48996930e-02 -8.56549203e-01 5.14882267e-01 -3.48996334e-02 -8.54742229e-01 5.17872989e-01 -3.48996483e-02 -8.52940440e-01 5.20840287e-01 -3.48996520e-02 -8.51100743e-01 5.23836970e-01 -3.48996185e-02 -8.49327922e-01 5.26709318e-01 -3.48995663e-02 -8.47487450e-01 5.29662669e-01 -3.48996930e-02 -8.45581651e-01 5.32701969e-01 -3.48996595e-02 -8.43720138e-01 5.35644233e-01 -3.48996371e-02 -8.41840506e-01 5.38594127e-01 -3.48996297e-02 -8.39973688e-01 5.41498244e-01 -3.48996297e-02 -8.38076293e-01 5.44432402e-01 -3.48995961e-02 -8.36171508e-01 5.47352612e-01 -3.48996259e-02 -8.34258318e-01 5.50266147e-01 -3.48996259e-02 -8.32361758e-01 5.53126633e-01 -3.48995142e-02 -8.30502391e-01 5.55917442e-01 -3.48996110e-02 -8.28506649e-01 5.58891356e-01 -3.48996930e-02 -8.26510608e-01 5.61835825e-01 -3.48995738e-02 -8.24548244e-01 5.64712942e-01 -3.48995961e-02 -8.22561562e-01 5.67604542e-01 -3.48996110e-02 -8.20566535e-01 5.70480287e-01 -3.48995961e-02 -8.18615079e-01 5.73275626e-01 -3.48995849e-02 -8.16601932e-01 5.76146364e-01 -3.48996967e-02 -8.14537883e-01 5.79053640e-01 -3.48996110e-02 -8.12565029e-01 5.81824064e-01 -3.48995142e-02 -8.10526311e-01 5.84657252e-01 -3.48996446e-02 -8.08441222e-01 5.87540269e-01 -3.48996259e-02 -8.06397557e-01 5.90339065e-01 -3.48995775e-02 -8.04321766e-01 5.93165457e-01 -3.48995775e-02 -8.02240312e-01 5.95975518e-01 -3.48995887e-02 -8.00228596e-01 5.98675787e-01 -3.48995589e-02 -7.98107743e-01 6.01501286e-01 -3.48997153e-02 -7.95938075e-01 6.04370475e-01 -3.48995961e-02 -7.93837130e-01 6.07125282e-01 -3.48995999e-02 -7.91768610e-01 6.09820306e-01 -3.48994918e-02 -7.89639413e-01 6.12572432e-01 -3.48996595e-02 -7.87432551e-01 6.15408063e-01 -3.48996185e-02 -7.85332978e-01 6.18087232e-01 -3.48995514e-02 -7.83177674e-01 6.20814323e-01 -3.48996781e-02 -7.81000853e-01 6.23551846e-01 -3.48995291e-02 -7.78884530e-01 6.26193404e-01 -3.48996148e-02 -7.76642919e-01 6.28974259e-01 -3.48996595e-02 -7.74382234e-01 6.31752431e-01 -3.48995775e-02 -7.72191823e-01 6.34426594e-01 -3.48995738e-02 -7.69916952e-01 6.37187362e-01 -3.48995477e-02 -7.67695904e-01 6.39860034e-01 -3.48995812e-02 -7.65471160e-01 6.42520130e-01 -3.48995849e-02 -7.63223410e-01 6.45190120e-01 -3.48995924e-02 -7.60957181e-01 6.47858918e-01 -3.48995887e-02 -7.58740723e-01 6.50454402e-01 -3.48995179e-02 -7.56482482e-01 6.53081298e-01 -3.48996930e-02 -7.54138529e-01 6.55784965e-01 -3.48995738e-02 -7.51823068e-01 6.58437192e-01 -3.48995663e-02 -7.49505758e-01 6.61074877e-01 -3.48995775e-02 -7.47195303e-01 6.63687527e-01 -3.48995514e-02 -7.44891047e-01 6.66272581e-01 -3.48995253e-02 -7.42628694e-01 6.68790102e-01 -3.48994732e-02 -7.40306616e-01 6.71364069e-01 -3.48996781e-02 -7.37869143e-01 6.74038529e-01 -3.48995589e-02 -7.35593379e-01 6.76523268e-01 -3.48994769e-02 -7.33236372e-01 6.79076314e-01 -3.48996110e-02 -7.30796993e-01 6.81698799e-01 -3.48995253e-02 -7.28452802e-01 6.84203148e-01 -3.48995440e-02 -7.26008713e-01 6.86796010e-01 -3.48995849e-02 -7.23647535e-01 6.89286649e-01 -3.48995030e-02 -7.21315384e-01 6.91719532e-01 -3.48995589e-02 -7.18816102e-01 6.94330931e-01 -3.48996632e-02 -7.16320395e-01 6.96902454e-01 -3.48995849e-02 -7.13858962e-01 6.99420333e-01 -3.48995924e-02 -7.11427629e-01 7.01894701e-01 -3.48995738e-02 -7.09029317e-01 7.04319537e-01 -3.48995142e-02 -7.06573665e-01 7.06765413e-01 -3.48996148e-02 -7.04049349e-01 7.09296465e-01 -3.48995700e-02 -7.01572537e-01 7.11746991e-01 -3.48995775e-02 -6.99151695e-01 7.14121819e-01 -3.48995514e-02 -6.96659386e-01 7.16558397e-01 -3.48996930e-02 -6.94066346e-01 7.19070315e-01 -3.48995887e-02 -6.91533029e-01 7.21493602e-01 -3.48995775e-02 -6.89014137e-01 7.23909318e-01 -3.48996222e-02 -6.86496198e-01 7.26292968e-01 -3.48996110e-02 -6.83997929e-01 7.28645146e-01 -3.48995589e-02 -6.81444407e-01 7.31032431e-01 -3.48996446e-02 -6.78853512e-01 7.33442128e-01 -3.48996334e-02 -6.76277339e-01 7.35821545e-01 -3.48996371e-02 -6.73765063e-01 7.38118172e-01 -3.48994844e-02 -6.71196699e-01 7.40456522e-01 -3.48996595e-02 -6.68547273e-01 7.42849588e-01 -3.48996148e-02 -6.66006386e-01 7.45125115e-01 -3.48995738e-02 -6.63416088e-01 7.47434437e-01 -3.48996706e-02 -6.60753489e-01 7.49790490e-01 -3.48996036e-02 -6.58197522e-01 7.52034426e-01 -3.48995738e-02 -6.55570567e-01 7.54325867e-01 -3.48997004e-02 -6.52855277e-01 7.56676316e-01 -3.48995663e-02 -6.50205553e-01 7.58954823e-01 -3.48996073e-02 -6.47535086e-01 7.61233211e-01 -3.48996036e-02 -6.44889355e-01 7.63476610e-01 -3.48996110e-02 -6.42224193e-01 7.65719831e-01 -3.48996148e-02 -6.39540672e-01 7.67963827e-01 -3.48996297e-02 -6.36862576e-01 7.70184457e-01 -3.48996036e-02 -6.34229064e-01 7.72356153e-01 -3.48995440e-02 -6.31613433e-01 7.74494350e-01 -3.48996185e-02 -6.28826737e-01 7.76761115e-01 -3.48996930e-02 -6.26051843e-01 7.78998017e-01 -3.48995849e-02 -6.23333097e-01 7.81174958e-01 -3.48996185e-02 -6.20591223e-01 7.83354104e-01 -3.48995961e-02 -6.17861927e-01 7.85511315e-01 -3.48996185e-02 -6.15199447e-01 7.87597060e-01 -3.48995477e-02 -6.12428010e-01 7.89754629e-01 -3.48996930e-02 -6.09590530e-01 7.91945994e-01 -3.48995999e-02 -6.06867135e-01 7.94034600e-01 -3.48995477e-02 -6.04115963e-01 7.96130121e-01 -3.48996930e-02 -6.01269484e-01 7.98281491e-01 -3.48996036e-02 -5.98478794e-01 8.00374150e-01 -3.48996036e-02 -5.95691621e-01 8.02452028e-01 -3.48996185e-02 -5.92957973e-01 8.04474413e-01 -3.48995626e-02 -5.90190589e-01 8.06506336e-01 -3.48996259e-02 -5.87298632e-01 8.08615565e-01 -3.48996930e-02 -5.84471881e-01 8.10658634e-01 -3.48995626e-02 -5.81625342e-01 8.12706172e-01 -3.48996967e-02 -5.78786790e-01 8.14731121e-01 -3.48995253e-02 -5.75965583e-01 8.16728175e-01 -3.48997489e-02 -5.73000610e-01 8.18808377e-01 -3.48996371e-02 -5.70195377e-01 8.20765138e-01 -3.48995663e-02 -5.67369699e-01 8.22722256e-01 -3.48996781e-02 -5.64495683e-01 8.24696898e-01 -3.48995477e-02 -5.61625719e-01 8.26653719e-01 -3.48997116e-02 -5.58716953e-01 8.28622520e-01 -3.48995477e-02 -5.55901349e-01 8.30512047e-01 -3.48995999e-02 -5.52901864e-01 8.32511246e-01 -3.48996148e-02 -5.49905777e-01 8.34494114e-01 -3.48996297e-02 -5.47086000e-01 8.36345494e-01 -3.48995253e-02 -5.44264257e-01 8.38186204e-01 -3.48996446e-02 -5.41246295e-01 8.40137005e-01 -3.48996781e-02 -5.38293779e-01 8.42032552e-01 -3.48995291e-02 -5.35396695e-01 8.43875885e-01 -3.48996706e-02 -5.32424927e-01 8.45756829e-01 -3.48995440e-02 -5.29483020e-01 8.47599387e-01 -3.48996930e-02 -5.26443720e-01 8.49492550e-01 -3.48996371e-02 -5.23448586e-01 8.51338625e-01 -3.48996185e-02 -5.20568788e-01 8.53106320e-01 -3.48995775e-02 -5.17611384e-01 8.54901552e-01 -3.48996781e-02 -5.14534056e-01 8.56757939e-01 -3.48996744e-02 -5.11581898e-01 8.58524442e-01 -3.48995812e-02 -5.08597732e-01 8.60294998e-01 -3.48996930e-02 -5.05583227e-01 8.62070620e-01 -3.48995477e-02 -5.02612114e-01 8.63806784e-01 -3.48996855e-02 -4.99475569e-01 8.65624428e-01 -3.48995477e-02 -4.96563494e-01 8.67297649e-01 -3.48995402e-02 -4.93532896e-01 8.69023681e-01 -3.48996930e-02 -4.90463704e-01 8.70762646e-01 -3.48995104e-02 -4.87435162e-01 8.72458696e-01 -3.48996371e-02 -4.84331191e-01 8.74183416e-01 -3.48995551e-02 -4.81296182e-01 8.75861526e-01 -3.48996520e-02 -4.78167236e-01 8.77576113e-01 -3.48996259e-02 -4.75065202e-01 8.79255354e-01 -3.48995961e-02 -4.72099662e-01 8.80851328e-01 -3.48994918e-02 -4.69130814e-01 8.82437766e-01 -3.48995924e-02 -4.65956300e-01 8.84117365e-01 -3.48996781e-02 -4.62859422e-01 8.85744452e-01 -3.48994732e-02 -4.59773093e-01 8.87349069e-01 -3.48996781e-02 -4.56632167e-01 8.88969600e-01 -3.48995328e-02 -4.53520209e-01 8.90559912e-01 -3.48995961e-02 -4.50367987e-01 8.92158329e-01 -3.48995738e-02 -4.47233498e-01 8.93734872e-01 -3.48995999e-02 -4.44207013e-01 8.95243049e-01 -3.48995365e-02 -4.41172808e-01 8.96741629e-01 -3.48996185e-02 -4.37963486e-01 8.98313642e-01 -3.48995924e-02 -4.34800923e-01 8.99851263e-01 -3.48994620e-02 -4.31644559e-01 9.01364744e-01 -3.48996557e-02 -4.28511381e-01 9.02860761e-01 -3.48995253e-02 -4.25400317e-01 9.04328465e-01 -3.48996185e-02 -4.22209084e-01 9.05825496e-01 -3.48995589e-02 -4.19058472e-01 9.07287240e-01 -3.48996706e-02 -4.15813655e-01 9.08776879e-01 -3.48995924e-02 -4.12642896e-01 9.10221815e-01 -3.48995887e-02 -4.09445047e-01 9.11667526e-01 -3.48995775e-02 -4.06349242e-01 9.13050592e-01 -3.48994844e-02 -4.03162926e-01 9.14459467e-01 -3.48996669e-02 -3.99900883e-01 9.15893734e-01 -3.48996259e-02 -3.96693200e-01 9.17285621e-01 -3.48995849e-02 -3.93536478e-01 9.18640256e-01 -3.48995477e-02 -3.90408546e-01 9.19977307e-01 -3.48996446e-02 -3.87155354e-01 9.21352804e-01 -3.48996744e-02 -3.83943707e-01 9.22695100e-01 -3.48995663e-02 -3.80717933e-01 9.24030006e-01 -3.48996185e-02 -3.77491951e-01 9.25354064e-01 -3.48995514e-02 -3.74230057e-01 9.26677167e-01 -3.48996669e-02 -3.70922446e-01 9.28005695e-01 -3.48996148e-02 -3.67669761e-01 9.29300785e-01 -3.48996185e-02 -3.64532828e-01 9.30534422e-01 -3.48995291e-02 -3.61338735e-01 9.31775451e-01 -3.48996520e-02 -3.57963145e-01 9.33086812e-01 -3.48996110e-02 -3.54760408e-01 9.34298754e-01 -3.48995663e-02 -3.51509780e-01 9.35524046e-01 -3.48996781e-02 -3.48234057e-01 9.36745822e-01 -3.48995663e-02 -3.45010191e-01 9.37941611e-01 -3.48995812e-02 -3.41668725e-01 9.39173996e-01 -3.48994844e-02 -3.38417709e-01 9.40344930e-01 -3.48996185e-02 -3.35062087e-01 9.41550076e-01 -3.48995663e-02 -3.31771135e-01 9.42713439e-01 -3.48995738e-02 -3.28474641e-01 9.43865955e-01 -3.48996110e-02 -3.25237125e-01 9.44988430e-01 -3.48995477e-02 -3.21941584e-01 9.46114182e-01 -3.48996930e-02 -3.18570703e-01 9.47256207e-01 -3.48995999e-02 -3.15261811e-01 9.48360264e-01 -3.48995849e-02 -3.12014371e-01 9.49434340e-01 -3.48995142e-02 -3.08798462e-01 9.50486183e-01 -3.48995924e-02 -3.05417657e-01 9.51578617e-01 -3.48996781e-02 -3.02092612e-01 9.52637851e-01 -3.48995104e-02 -2.98844397e-01 9.53661859e-01 -3.48995477e-02 -2.95516670e-01 9.54698205e-01 -3.48995663e-02 -2.92111576e-01 9.55746174e-01 -3.48996669e-02 -2.88751274e-01 9.56766188e-01 -3.48995440e-02 -2.85439491e-01 9.57758188e-01 -3.48996520e-02 -2.82079011e-01 9.58756089e-01 -3.48995402e-02 -2.78744489e-01 9.59729612e-01 -3.48996781e-02 -2.75342375e-01 9.60711420e-01 -3.48995775e-02 -2.72070140e-01 9.61642623e-01 -3.48995775e-02 -2.68697947e-01 9.62590873e-01 -3.48996371e-02 -2.65290201e-01 9.63534951e-01 -3.48995775e-02 -2.61921197e-01 9.64459538e-01 -3.48996818e-02 -2.58574992e-01 9.65359151e-01 -3.48995440e-02 -2.55209506e-01 9.66255367e-01 -3.48996781e-02 -2.51766920e-01 9.67158258e-01 -3.48995999e-02 -2.48398617e-01 9.68027532e-01 -3.48996036e-02 -2.44988590e-01 9.68895018e-01 -3.48995961e-02 -2.41692871e-01 9.69722748e-01 -3.48995179e-02 -2.38328651e-01 9.70556259e-01 -3.48996110e-02 -2.34846517e-01 9.71406519e-01 -3.48995961e-02 -2.31462345e-01 9.72218275e-01 -3.48996222e-02 -2.28135437e-01 9.73002076e-01 -3.48995514e-02 -2.24803254e-01 9.73778188e-01 -3.48995961e-02 -2.21349552e-01 9.74568367e-01 -3.48996595e-02 -2.17960984e-01 9.75332856e-01 -3.48995663e-02 -2.14616001e-01 9.76072252e-01 -3.48996036e-02 -2.11207837e-01 9.76816833e-01 -3.48996259e-02 -2.07740515e-01 9.77559805e-01 -3.48996706e-02 -2.04324558e-01 9.78279352e-01 -3.48995663e-02 -2.00921133e-01 9.78985250e-01 -3.48996557e-02 -1.97484374e-01 9.79682803e-01 -3.48995477e-02 -1.94055170e-01 9.80367184e-01 -3.48996930e-02 -1.90522268e-01 9.81060386e-01 -3.48996222e-02 -1.87200338e-01 9.81699824e-01 -3.48995440e-02 -1.83796108e-01 9.82343078e-01 -3.48996930e-02 -1.80337951e-01 9.82981145e-01 -3.48994620e-02 -1.76925614e-01 9.83608007e-01 -3.48996669e-02 -1.73483774e-01 9.84221101e-01 -3.48995402e-02 -1.70178860e-01 9.84792411e-01 -3.48996297e-02 -1.66615874e-01 9.85404015e-01 -3.48997153e-02 -1.63054183e-01 9.85996783e-01 -3.48995775e-02 -1.59612745e-01 9.86560881e-01 -3.48995924e-02 -1.56276062e-01 9.87094879e-01 -3.48994918e-02 -1.52936116e-01 9.87618089e-01 -3.48996036e-02 -1.49378791e-01 9.88160849e-01 -3.48997153e-02 -1.45815119e-01 9.88693953e-01 -3.48996185e-02 -1.42360702e-01 9.89196837e-01 -3.48996036e-02 -1.39006570e-01 9.89675283e-01 -3.48995589e-02 -1.35670945e-01 9.90139246e-01 -3.48995999e-02 -1.32183447e-01 9.90609348e-01 -3.48996185e-02 -1.28718466e-01 9.91064489e-01 -3.48996259e-02 -1.25182405e-01 9.91518736e-01 -3.48996967e-02 -1.21627197e-01 9.91959989e-01 -3.48996110e-02 -1.18248001e-01 9.92367029e-01 -3.48995514e-02 -1.14794165e-01 9.92772102e-01 -3.48996818e-02 -1.11319557e-01 9.93170440e-01 -3.48995477e-02 -1.07952058e-01 9.93540764e-01 -3.48996185e-02 -1.04377031e-01 9.93922889e-01 -3.48996818e-02 -1.00809149e-01 9.94291067e-01 -3.48995849e-02 -9.73260403e-02 9.94638264e-01 -3.48995924e-02 -9.38682556e-02 9.94972467e-01 -3.48996185e-02 -9.03742164e-02 9.95294929e-01 -3.48995961e-02 -8.70080665e-02 9.95595872e-01 -3.48995179e-02 -8.36350098e-02 9.95882928e-01 -3.48995887e-02 -8.00488964e-02 9.96177614e-01 -3.48996781e-02 -7.64644295e-02 9.96459663e-01 -3.48995961e-02 -7.30005354e-02 9.96720195e-01 -3.48995999e-02 -6.96249232e-02 9.96960223e-01 -3.48995291e-02 -6.62261248e-02 9.97192919e-01 -3.48995961e-02 -6.27254471e-02 9.97417688e-01 -3.48995700e-02 -5.91860451e-02 9.97633994e-01 -3.48996595e-02 -5.56024089e-02 9.97841716e-01 -3.48995999e-02 -5.20863049e-02 9.98029470e-01 -3.48995999e-02 -4.87086438e-02 9.98201847e-01 -3.48995440e-02 -4.52457033e-02 9.98362780e-01 -3.48996818e-02 -4.17624041e-02 9.98517215e-01 -3.48995142e-02 -3.82775068e-02 9.98655736e-01 -3.48996855e-02 -3.46831717e-02 9.98786628e-01 -3.48995961e-02 -3.13133299e-02 9.98898745e-01 -3.48995142e-02 -2.78154369e-02 9.99001801e-01 -3.48996706e-02 -2.43323147e-02 9.99095798e-01 -3.48995104e-02 -2.08303705e-02 9.99168098e-01 -3.48997042e-02 -1.72270928e-02 9.99244452e-01 -3.48995961e-02 -1.37089845e-02 9.99292195e-01 -3.48995849e-02 -1.02502322e-02 9.99335408e-01 -3.48995775e-02 -6.85350969e-03 9.99369085e-01 -3.48994583e-02 -3.36340698e-03 9.99388456e-01 -3.48996669e-02 1.12017195e-04 9.99389768e-01 -3.48995142e-02 3.50840646e-03 9.99388278e-01 -3.48995775e-02 7.09074456e-03 9.99369502e-01 -3.48996446e-02 1.06845014e-02 9.99330521e-01 -3.48995887e-02 1.41958008e-02 9.99284923e-01 -3.48995812e-02 1.76604316e-02 9.99236763e-01 -3.48995961e-02 2.10603140e-02 9.99167740e-01 -3.48995142e-02 2.44607050e-02 9.99090731e-01 -3.48996185e-02 2.80472152e-02 9.98996019e-01 -3.48996930e-02 3.16444114e-02 9.98888135e-01 -3.48995999e-02 3.50426659e-02 9.98775065e-01 -3.48995291e-02 3.83946076e-02 9.98652399e-01 -3.48996036e-02 4.19537574e-02 9.98508155e-01 -3.48996744e-02 4.55044024e-02 9.98351932e-01 -3.48995291e-02 4.89567518e-02 9.98190999e-01 -3.48996483e-02 5.25191985e-02 9.98005986e-01 -3.48995887e-02 5.59647530e-02 9.97821510e-01 -3.48995291e-02 5.94619811e-02 9.97618556e-01 -3.48995887e-02 6.29608929e-02 9.97401774e-01 -3.48995999e-02 6.64067417e-02 9.97180104e-01 -3.48995775e-02 6.98681921e-02 9.96941507e-01 -3.48994769e-02 7.33599514e-02 9.96692538e-01 -3.48996185e-02 7.69089833e-02 9.96424258e-01 -3.48995887e-02 8.03503394e-02 9.96155024e-01 -3.48995589e-02 8.38680342e-02 9.95863140e-01 -3.48995775e-02 8.72921869e-02 9.95569050e-01 -3.48995700e-02 9.07004625e-02 9.95264351e-01 -3.48995104e-02 9.41804200e-02 9.94942129e-01 -3.48995663e-02 9.77539569e-02 9.94596362e-01 -3.48995328e-02 1.01200506e-01 9.94253397e-01 -3.48995775e-02 1.04621947e-01 9.93898273e-01 -3.48995291e-02 1.07996099e-01 9.93536234e-01 -3.48995663e-02 1.11463822e-01 9.93154883e-01 -3.48996222e-02 1.15021281e-01 9.92746532e-01 -3.48995924e-02 1.18571721e-01 9.92328942e-01 -3.48995999e-02 1.22041158e-01 9.91909027e-01 -3.48996259e-02 1.25385031e-01 9.91493285e-01 -3.48995328e-02 1.28829092e-01 9.91049945e-01 -3.48996595e-02 1.32329568e-01 9.90590870e-01 -3.48994620e-02 1.35765985e-01 9.90124762e-01 -3.48996557e-02 1.39344767e-01 9.89628255e-01 -3.48996446e-02 1.42682135e-01 9.89151716e-01 -3.48994695e-02 1.46146387e-01 9.88643944e-01 -3.48996669e-02 1.49691030e-01 9.88115013e-01 -3.48996185e-02 1.53126553e-01 9.87589598e-01 -3.48995924e-02 1.56495228e-01 9.87059832e-01 -3.48994620e-02 1.59929901e-01 9.86509621e-01 -3.48996371e-02 1.63466915e-01 9.85930204e-01 -3.48996148e-02 1.66804448e-01 9.85370517e-01 -3.48995589e-02 1.70213759e-01 9.84786928e-01 -3.48997153e-02 1.73702031e-01 9.84181821e-01 -3.48995738e-02 1.77022904e-01 9.83589113e-01 -3.48995924e-02 1.80562839e-01 9.82940853e-01 -3.48996520e-02 1.84063479e-01 9.82292831e-01 -3.48996185e-02 1.87512249e-01 9.81640160e-01 -3.48996371e-02 1.90928906e-01 9.80981112e-01 -3.48996036e-02 1.94285408e-01 9.80323851e-01 -3.48995663e-02 1.97611779e-01 9.79656637e-01 -3.48996595e-02 2.01020196e-01 9.78962719e-01 -3.48996595e-02 2.04529136e-01 9.78237391e-01 -3.48997153e-02 2.08030894e-01 9.77498472e-01 -3.48996595e-02 2.11424500e-01 9.76771593e-01 -3.48996185e-02 2.14810610e-01 9.76029634e-01 -3.48996557e-02 2.18149126e-01 9.75289822e-01 -3.48995402e-02 2.21551925e-01 9.74520683e-01 -3.48996408e-02 2.25051537e-01 9.73721266e-01 -3.48996110e-02 2.28430390e-01 9.72934008e-01 -3.48995775e-02 2.31837332e-01 9.72128928e-01 -3.48995999e-02 2.35149339e-01 9.71332312e-01 -3.48995626e-02 2.38553390e-01 9.70501482e-01 -3.48996930e-02 2.41938874e-01 9.69661713e-01 -3.48995663e-02 2.45287240e-01 9.68818486e-01 -3.48996781e-02 2.48766646e-01 9.67933834e-01 -3.48996110e-02 2.52158076e-01 9.67054009e-01 -3.48996297e-02 2.55510330e-01 9.66175079e-01 -3.48996297e-02 2.58896530e-01 9.65273261e-01 -3.48996259e-02 2.62180805e-01 9.64388311e-01 -3.48995738e-02 2.65519172e-01 9.63471174e-01 -3.48996930e-02 2.68986583e-01 9.62510407e-01 -3.48995812e-02 2.72359908e-01 9.61562634e-01 -3.48996185e-02 2.75657177e-01 9.60621536e-01 -3.48995775e-02 2.78985888e-01 9.59659159e-01 -3.48996110e-02 2.82387853e-01 9.58663106e-01 -3.48996595e-02 2.85675347e-01 9.57690835e-01 -3.48995663e-02 2.88999587e-01 9.56690431e-01 -3.48996930e-02 2.92400539e-01 9.55657840e-01 -3.48996483e-02 2.95678407e-01 9.54648733e-01 -3.48995887e-02 2.98988521e-01 9.53616738e-01 -3.48997042e-02 3.02349329e-01 9.52555537e-01 -3.48995589e-02 3.05624127e-01 9.51510727e-01 -3.48996855e-02 3.09045017e-01 9.50404882e-01 -3.48996669e-02 3.12400311e-01 9.49306905e-01 -3.48996557e-02 3.15720469e-01 9.48208749e-01 -3.48996595e-02 3.18927169e-01 9.47135985e-01 -3.48995663e-02 3.22225004e-01 9.46017742e-01 -3.48997153e-02 3.25598091e-01 9.44864511e-01 -3.48995961e-02 3.28799039e-01 9.43752527e-01 -3.48995999e-02 3.32088798e-01 9.42599535e-01 -3.48996967e-02 3.35494578e-01 9.41396534e-01 -3.48995961e-02 3.38758826e-01 9.40223277e-01 -3.48995887e-02 3.42008173e-01 9.39047456e-01 -3.48996259e-02 3.45208734e-01 9.37868714e-01 -3.48995812e-02 3.48447502e-01 9.36667442e-01 -3.48996781e-02 3.51776779e-01 9.35421765e-01 -3.48995775e-02 3.55063945e-01 9.34186578e-01 -3.48997153e-02 3.58407587e-01 9.32917297e-01 -3.48996185e-02 3.61570507e-01 9.31685328e-01 -3.48995477e-02 3.64784151e-01 9.30435717e-01 -3.48996595e-02 3.68052602e-01 9.29147303e-01 -3.48995291e-02 3.71286303e-01 9.27860141e-01 -3.48996855e-02 3.74620408e-01 9.26518857e-01 -3.48996520e-02 3.77872556e-01 9.25198615e-01 -3.48996446e-02 3.81083250e-01 9.23878312e-01 -3.48996595e-02 3.84233505e-01 9.22574043e-01 -3.48995849e-02 3.87411922e-01 9.21243072e-01 -3.48997153e-02 3.90740454e-01 9.19835508e-01 -3.48996595e-02 3.93931001e-01 9.18473721e-01 -3.48996297e-02 3.97148460e-01 9.17088449e-01 -3.48996595e-02 4.00277585e-01 9.15730357e-01 -3.48995849e-02 4.03462797e-01 9.14328694e-01 -3.48997079e-02 4.06660438e-01 9.12911654e-01 -3.48995775e-02 4.09729928e-01 9.11538899e-01 -3.48996371e-02 4.12991583e-01 9.10063744e-01 -3.48997153e-02 4.16187227e-01 9.08605099e-01 -3.48995477e-02 4.19314712e-01 9.07166898e-01 -3.48996781e-02 4.22496051e-01 9.05690491e-01 -3.48995104e-02 4.25596178e-01 9.04238462e-01 -3.48995887e-02 4.28711385e-01 9.02763724e-01 -3.48996185e-02 4.31994200e-01 9.01197433e-01 -3.48996930e-02 4.35183972e-01 8.99665415e-01 -3.48996408e-02 4.38246161e-01 8.98178697e-01 -3.48995775e-02 4.41316903e-01 8.96670997e-01 -3.48996595e-02 4.44442511e-01 8.95125747e-01 -3.48996408e-02 4.47541088e-01 8.93580794e-01 -3.48996520e-02 4.50729191e-01 8.91977966e-01 -3.48997489e-02 4.53908443e-01 8.90363753e-01 -3.48996706e-02 4.56953466e-01 8.88804853e-01 -3.48995738e-02 4.60044622e-01 8.87207568e-01 -3.48997153e-02 4.63126510e-01 8.85607004e-01 -3.48995887e-02 4.66209769e-01 8.83984387e-01 -3.48997153e-02 4.69294876e-01 8.82349551e-01 -3.48995924e-02 4.72360343e-01 8.80713820e-01 -3.48997153e-02 4.75496083e-01 8.79023075e-01 -3.48996669e-02 4.78501648e-01 8.77394259e-01 -3.48995775e-02 4.81547445e-01 8.75724137e-01 -3.48997153e-02 4.84613538e-01 8.74027967e-01 -3.48995887e-02 4.87562001e-01 8.72388959e-01 -3.48996520e-02 4.90698129e-01 8.70630205e-01 -3.48996781e-02 4.93787557e-01 8.68878484e-01 -3.48996148e-02 4.96844202e-01 8.67136419e-01 -3.48996222e-02 4.99803126e-01 8.65436256e-01 -3.48995775e-02 5.02738237e-01 8.63732755e-01 -3.48996595e-02 5.05739391e-01 8.61979723e-01 -3.48996595e-02 5.08816838e-01 8.60165179e-01 -3.48997153e-02 5.11869609e-01 8.58352661e-01 -3.48996595e-02 5.14871061e-01 8.56555283e-01 -3.48996669e-02 5.17787397e-01 8.54795158e-01 -3.48995887e-02 5.20755053e-01 8.52993011e-01 -3.48996930e-02 5.23737311e-01 8.51161420e-01 -3.48995999e-02 5.26695132e-01 8.49337578e-01 -3.48997153e-02 5.29740512e-01 8.47437978e-01 -3.48996706e-02 5.32639742e-01 8.45620692e-01 -3.48995999e-02 5.35538733e-01 8.43788028e-01 -3.48997153e-02 5.38516939e-01 8.41889203e-01 -3.48995700e-02 5.41434646e-01 8.40016305e-01 -3.48996930e-02 5.44380367e-01 8.38110209e-01 -3.48995999e-02 5.47308981e-01 8.36200237e-01 -3.48997079e-02 5.50297379e-01 8.34237754e-01 -3.48996446e-02 5.53140104e-01 8.32352400e-01 -3.48995291e-02 5.56020856e-01 8.30433011e-01 -3.48996371e-02 5.58907568e-01 8.28495026e-01 -3.48994620e-02 5.61698377e-01 8.26602936e-01 -3.48994806e-02 5.64647734e-01 8.24593186e-01 -3.48994359e-02 5.67557156e-01 8.22593510e-01 -3.48993056e-02 5.70420802e-01 8.20608616e-01 -3.48993056e-02 5.73318362e-01 8.18586767e-01 -3.48993093e-02 5.76059937e-01 8.16661894e-01 -3.48993167e-02 5.78884184e-01 8.14661324e-01 -3.48993391e-02 5.81719577e-01 8.12637866e-01 -3.48993875e-02 5.84596634e-01 8.10571194e-01 -3.48994322e-02 5.87427378e-01 8.08522344e-01 -3.48996110e-02 5.90208769e-01 8.06493700e-01 -3.48995849e-02 5.92777550e-01 8.04608345e-01 -3.48994844e-02 5.95662951e-01 8.02475393e-01 -3.48994993e-02 5.97261250e-01 8.01287115e-01 -3.48994955e-02 6.00193799e-01 7.99092829e-01 -3.48994955e-02 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. 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. 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. 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. 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. 7.24397182e-01 6.88498080e-01 -3.48994844e-02 7.26397574e-01 6.86385632e-01 -3.48996110e-02 7.28690207e-01 6.83950722e-01 -3.48993912e-02 7.31061757e-01 6.81413949e-01 -3.48993056e-02 7.33397126e-01 6.78902090e-01 -3.48993056e-02 7.35741794e-01 6.76362276e-01 -3.48993950e-02 7.38114238e-01 6.73770666e-01 -3.48993540e-02 7.40438819e-01 6.71217024e-01 -3.48996110e-02 7.42790401e-01 6.68612659e-01 -3.48994806e-02 7.45023608e-01 6.66121423e-01 -3.48995924e-02 7.47426629e-01 6.63425982e-01 -3.48996781e-02 7.49736309e-01 6.60813630e-01 -3.48995440e-02 7.52029479e-01 6.58201635e-01 -3.48997153e-02 7.54316032e-01 6.55582964e-01 -3.48995663e-02 7.56536961e-01 6.53016031e-01 -3.48996036e-02 7.58812487e-01 6.50371969e-01 -3.48996297e-02 7.61083543e-01 6.47711635e-01 -3.48996185e-02 7.63392508e-01 6.44990265e-01 -3.48996930e-02 7.65709639e-01 6.42237186e-01 -3.48996110e-02 7.67888248e-01 6.39631569e-01 -3.48995477e-02 7.70064652e-01 6.37007296e-01 -3.48996148e-02 7.72274077e-01 6.34329319e-01 -3.48996185e-02 7.74541140e-01 6.31555676e-01 -3.48996930e-02 7.76797175e-01 6.28782809e-01 -3.48996148e-02 7.78928697e-01 6.26136243e-01 -3.48995440e-02 7.81043291e-01 6.23499870e-01 -3.48996148e-02 7.83211350e-01 6.20771229e-01 -3.48996520e-02 7.85446644e-01 6.17943943e-01 -3.48996930e-02 7.87661552e-01 6.15116358e-01 -3.48996036e-02 7.89788961e-01 6.12384200e-01 -3.48996148e-02 7.91928113e-01 6.09613359e-01 -3.48996297e-02 7.93999135e-01 6.06914878e-01 -3.48995514e-02 7.96101868e-01 6.04153574e-01 -3.48996706e-02 7.98211873e-01 6.01364732e-01 -3.48995700e-02 8.00246000e-01 5.98651052e-01 -3.48995999e-02 8.02388549e-01 5.95776439e-01 -3.48996781e-02 8.04458916e-01 5.92978418e-01 -3.48995589e-02 8.06508422e-01 5.90188086e-01 -3.48996930e-02 8.08628678e-01 5.87280154e-01 -3.48996297e-02 8.10632229e-01 5.84509730e-01 -3.48995700e-02 8.12598765e-01 5.81776917e-01 -3.48995999e-02 8.14685941e-01 5.78849792e-01 -3.48997153e-02 8.16765130e-01 5.75914562e-01 -3.48996595e-02 8.18752646e-01 5.73080063e-01 -3.48996148e-02 8.20698798e-01 5.70290029e-01 -3.48995663e-02 8.22639048e-01 5.67490935e-01 -3.48996297e-02 8.24615002e-01 5.64612925e-01 -3.48996371e-02 8.26630771e-01 5.61658382e-01 -3.48996930e-02 8.28646064e-01 5.58680117e-01 -3.48996334e-02 8.30540657e-01 5.55859268e-01 -3.48995775e-02 8.32455456e-01 5.52986205e-01 -3.48996781e-02 8.34388971e-01 5.50066411e-01 -3.48995812e-02 8.36314738e-01 5.47132909e-01 -3.48996855e-02 8.38218093e-01 5.44215918e-01 -3.48995700e-02 8.40056419e-01 5.41371584e-01 -3.48996446e-02 8.41987371e-01 5.38362205e-01 -3.48997079e-02 8.43857527e-01 5.35426199e-01 -3.48995589e-02 8.45727086e-01 5.32472968e-01 -3.48997153e-02 8.47635448e-01 5.29426992e-01 -3.48995999e-02 8.49419057e-01 5.26561439e-01 -3.48995663e-02 8.51257980e-01 5.23582101e-01 -3.48996930e-02 8.53090405e-01 5.20593762e-01 -3.48995440e-02 8.54887903e-01 5.17633736e-01 -3.48996930e-02 8.56706142e-01 5.14618933e-01 -3.48995477e-02 8.58434379e-01 5.11731744e-01 -3.48996110e-02 8.60218167e-01 5.08726895e-01 -3.48996595e-02 8.61989081e-01 5.05722344e-01 -3.48996222e-02 8.63805413e-01 5.02614439e-01 -3.48997153e-02 8.65601897e-01 4.99512583e-01 -3.48996148e-02 8.67280841e-01 4.96592492e-01 -3.48995253e-02 8.68959963e-01 4.93644774e-01 -3.48996148e-02 8.70688975e-01 4.90596801e-01 -3.48996222e-02 8.72443378e-01 4.87464160e-01 -3.48997153e-02 8.74204576e-01 4.84295666e-01 -3.48996036e-02 8.75836313e-01 4.81343180e-01 -3.48995700e-02 8.77468348e-01 4.78362024e-01 -3.48996185e-02 8.79125059e-01 4.75307971e-01 -3.48995999e-02 8.80825162e-01 4.72152144e-01 -3.48996930e-02 8.82473886e-01 4.69063282e-01 -3.48995589e-02 8.84101629e-01 4.65985417e-01 -3.48997153e-02 8.85783136e-01 4.62783277e-01 -3.48995849e-02 8.87329936e-01 4.59806770e-01 -3.48995589e-02 8.88918638e-01 4.56731409e-01 -3.48996781e-02 8.90515924e-01 4.53609437e-01 -3.48995291e-02 8.92046750e-01 4.50589329e-01 -3.48996520e-02 8.93677354e-01 4.47345942e-01 -3.48996930e-02 8.95232320e-01 4.44227606e-01 -3.48995067e-02 8.96769166e-01 4.41115260e-01 -3.48996595e-02 8.98351133e-01 4.37888205e-01 -3.48995775e-02 8.99835765e-01 4.34834152e-01 -3.48995589e-02 9.01308119e-01 4.31762964e-01 -3.48995775e-02 9.02819395e-01 4.28598911e-01 -3.48995887e-02 9.04341698e-01 4.25373703e-01 -3.48996930e-02 9.05860126e-01 4.22134787e-01 -3.48995887e-02 9.07308996e-01 4.19010133e-01 -3.48995253e-02 9.08697963e-01 4.15987462e-01 -3.48995924e-02 9.10161555e-01 4.12778437e-01 -3.48996036e-02 9.11634088e-01 4.09516186e-01 -3.48996818e-02 9.13092852e-01 4.06251073e-01 -3.48996036e-02 9.14475799e-01 4.03130263e-01 -3.48995440e-02 9.15866852e-01 3.99962634e-01 -3.48996930e-02 9.17248964e-01 3.96778017e-01 -3.48995328e-02 9.18628633e-01 3.93565953e-01 -3.48996669e-02 9.20009136e-01 3.90333742e-01 -3.48995402e-02 9.21330452e-01 3.87207508e-01 -3.48996334e-02 9.22709227e-01 3.83911490e-01 -3.48996781e-02 9.24034417e-01 3.80703032e-01 -3.48995589e-02 9.25354719e-01 3.77486467e-01 -3.48997153e-02 9.26712155e-01 3.74144316e-01 -3.48996185e-02 9.27982986e-01 3.70982170e-01 -3.48995253e-02 9.29259717e-01 3.67771983e-01 -3.48996930e-02 9.30550516e-01 3.64495844e-01 -3.48995700e-02 9.31795895e-01 3.61283362e-01 -3.48996930e-02 9.33105886e-01 3.57910246e-01 -3.48996520e-02 9.34319556e-01 3.54702920e-01 -3.48995440e-02 9.35502410e-01 3.51563364e-01 -3.48996148e-02 9.36723530e-01 3.48294973e-01 -3.48996110e-02 9.37965810e-01 3.44951153e-01 -3.48997153e-02 9.39211428e-01 3.41564447e-01 -3.48996446e-02 9.40360188e-01 3.38370442e-01 -3.48995663e-02 9.41524982e-01 3.35130274e-01 -3.48996930e-02 9.42703307e-01 3.31798494e-01 -3.48995663e-02 9.43849206e-01 3.28522384e-01 -3.48997153e-02 9.45024073e-01 3.25133473e-01 -3.48996297e-02 9.46124256e-01 3.21912169e-01 -3.48995402e-02 9.47228491e-01 3.18651021e-01 -3.48996669e-02 9.48350132e-01 3.15294415e-01 -3.48995700e-02 9.49444413e-01 3.11984897e-01 -3.48997153e-02 9.50531006e-01 3.08661431e-01 -3.48995663e-02 9.51573551e-01 3.05432439e-01 -3.48996371e-02 9.52659607e-01 3.02024782e-01 -3.48997153e-02 9.53710616e-01 2.98688084e-01 -3.48995514e-02 9.54735935e-01 2.95394957e-01 -3.48996930e-02 9.55793977e-01 2.91955560e-01 -3.48996371e-02 9.56781745e-01 2.88696229e-01 -3.48995775e-02 9.57779109e-01 2.85371274e-01 -3.48997153e-02 9.58783627e-01 2.81985521e-01 -3.48995738e-02 9.59756970e-01 2.78653115e-01 -3.48996930e-02 9.60744560e-01 2.75222123e-01 -3.48996185e-02 9.61669385e-01 2.71976978e-01 -3.48995700e-02 9.62586284e-01 2.68719941e-01 -3.48996036e-02 9.63523805e-01 2.65330315e-01 -3.48996185e-02 9.64466333e-01 2.61888087e-01 -3.48996930e-02 9.65400875e-01 2.58418560e-01 -3.48996036e-02 9.66280162e-01 2.55111039e-01 -3.48995663e-02 9.67163384e-01 2.51747012e-01 -3.48996781e-02 9.68032956e-01 2.48380274e-01 -3.48995477e-02 9.68889296e-01 2.45002568e-01 -3.48996930e-02 9.69755769e-01 2.41559684e-01 -3.48995961e-02 9.70600605e-01 2.38150358e-01 -3.48996148e-02 9.71423984e-01 2.34771341e-01 -3.48996148e-02 9.72221136e-01 2.31450409e-01 -3.48995440e-02 9.73011971e-01 2.28097647e-01 -3.48996334e-02 9.73806858e-01 2.24680424e-01 -3.48995477e-02 9.74573731e-01 2.21322492e-01 -3.48995738e-02 9.75357294e-01 2.17854187e-01 -3.48996446e-02 9.76105630e-01 2.14462921e-01 -3.48995104e-02 9.76844609e-01 2.11073086e-01 -3.48996595e-02 9.77578044e-01 2.07657531e-01 -3.48994881e-02 9.78283703e-01 2.04305142e-01 -3.48995812e-02 9.78992343e-01 2.00886831e-01 -3.48995999e-02 9.79706705e-01 1.97367325e-01 -3.48996930e-02 9.80395675e-01 1.93913788e-01 -3.48996036e-02 9.81068552e-01 1.90484613e-01 -3.48995812e-02 9.81711149e-01 1.87141120e-01 -3.48995663e-02 9.82341707e-01 1.83801204e-01 -3.48995775e-02 9.82974529e-01 1.80380628e-01 -3.48995477e-02 9.83623207e-01 1.76840991e-01 -3.48996520e-02 9.84246254e-01 1.73331410e-01 -3.48995738e-02 9.84825313e-01 1.69983834e-01 -3.48995328e-02 9.85404730e-01 1.66607529e-01 -3.48996073e-02 9.85975921e-01 1.63183242e-01 -3.48996110e-02 9.86538529e-01 1.59751311e-01 -3.48996259e-02 9.87104714e-01 1.56223282e-01 -3.48997153e-02 9.87655401e-01 1.52693883e-01 -3.48996073e-02 9.88181233e-01 1.49246469e-01 -3.48996036e-02 9.88685966e-01 1.45873785e-01 -3.48995775e-02 9.89188850e-01 1.42417088e-01 -3.48997153e-02 9.89693522e-01 1.38882250e-01 -3.48996259e-02 9.90159154e-01 1.35520577e-01 -3.48994881e-02 9.90623236e-01 1.32070377e-01 -3.48996669e-02 9.91081595e-01 1.28597200e-01 -3.48995589e-02 9.91520345e-01 1.25169426e-01 -3.48996930e-02 9.91956234e-01 1.21665642e-01 -3.48995589e-02 9.92362440e-01 1.18296631e-01 -3.48996110e-02 9.92766261e-01 1.14849277e-01 -3.48996595e-02 9.93173420e-01 1.11297727e-01 -3.48996818e-02 9.93564785e-01 1.07728958e-01 -3.48996185e-02 9.93933737e-01 1.04275279e-01 -3.48996148e-02 9.94284987e-01 1.00878790e-01 -3.48995365e-02 9.94629502e-01 9.74186659e-02 -3.48996930e-02 9.94964421e-01 9.39370617e-02 -3.48995589e-02 9.95285332e-01 9.04784724e-02 -3.48996706e-02 9.95603740e-01 8.69052559e-02 -3.48996148e-02 9.95893002e-01 8.35197493e-02 -3.48995589e-02 9.96173143e-01 8.01251605e-02 -3.48996148e-02 9.96442258e-01 7.66714513e-02 -3.48996148e-02 9.96709466e-01 7.31283352e-02 -3.48996930e-02 9.96959507e-01 6.96270391e-02 -3.48995775e-02 9.97192681e-01 6.62244931e-02 -3.48996446e-02 9.97421145e-01 6.26554042e-02 -3.48997153e-02 9.97637749e-01 5.91447651e-02 -3.48995514e-02 9.97837245e-01 5.56850210e-02 -3.48996930e-02 9.98028755e-01 5.21177016e-02 -3.48996297e-02 9.98201728e-01 4.87182811e-02 -3.48995700e-02 9.98363972e-01 4.52508889e-02 -3.48996855e-02 9.98518169e-01 4.17548344e-02 -3.48995700e-02 9.98654962e-01 3.82933915e-02 -3.48996781e-02 9.98786211e-01 3.47017013e-02 -3.48996632e-02 9.98900294e-01 3.12741697e-02 -3.48995663e-02 9.99000311e-01 2.79003605e-02 -3.48996259e-02 9.99092817e-01 2.43951995e-02 -3.48996259e-02 9.99168336e-01 2.08443329e-02 -3.48997153e-02 9.99241889e-01 1.73678249e-02 -3.48995477e-02 9.99287486e-01 1.39731178e-02 -3.48995887e-02 9.99334455e-01 1.04727410e-02 -3.48995999e-02 9.99371052e-01 6.96361763e-03 -3.48996185e-02 9.99388516e-01 3.42317321e-03 -3.48996930e-02 9.99389648e-01 -1.87420097e-04 -3.48996185e-02 9.99388218e-01 -3.67544219e-03 -3.48995663e-02 9.99369085e-01 -7.13851675e-03 -3.48996110e-02 9.99333382e-01 -1.05563253e-02 -3.48995663e-02 9.99285579e-01 -1.40782818e-02 -3.48996446e-02 9.99237299e-01 -1.75677761e-02 -3.48995663e-02 9.99167442e-01 -2.09235903e-02 -3.48996222e-02 9.99089658e-01 -2.45125610e-02 -3.48997153e-02 9.98996198e-01 -2.80344170e-02 -3.48995477e-02 9.98893499e-01 -3.14898975e-02 -3.48997153e-02 9.98776853e-01 -3.49961668e-02 -3.48995663e-02 9.98652458e-01 -3.83742228e-02 -3.48996185e-02 9.98508871e-01 -4.19522338e-02 -3.48997153e-02 9.98351634e-01 -4.55405116e-02 -3.48996259e-02 9.98184741e-01 -4.90440056e-02 -3.48996446e-02 9.98005033e-01 -5.25351949e-02 -3.48996259e-02 9.97823238e-01 -5.59076555e-02 -3.48995179e-02 9.97628987e-01 -5.92779964e-02 -3.48996259e-02 9.97413874e-01 -6.27691746e-02 -3.48996297e-02 9.97183025e-01 -6.63653165e-02 -3.48997079e-02 9.96935725e-01 -6.99618310e-02 -3.48996036e-02 9.96689200e-01 -7.34183118e-02 -3.48996110e-02 9.96434510e-01 -7.67835751e-02 -3.48995551e-02 9.96168435e-01 -8.01756531e-02 -3.48996520e-02 9.95883107e-01 -8.36413354e-02 -3.48995924e-02 9.95571017e-01 -8.72726589e-02 -3.48996595e-02 9.95260954e-01 -9.07350630e-02 -3.48995067e-02 9.94950771e-01 -9.40790027e-02 -3.48995775e-02 9.94617522e-01 -9.75469053e-02 -3.48996036e-02 9.94261444e-01 -1.01105928e-01 -3.48997153e-02 9.93899405e-01 -1.04607224e-01 -3.48995589e-02 9.93528664e-01 -1.08069867e-01 -3.48996930e-02 9.93146420e-01 -1.11543268e-01 -3.48995440e-02 9.92760897e-01 -1.14904881e-01 -3.48996148e-02 9.92342651e-01 -1.18462235e-01 -3.48997004e-02 9.91919398e-01 -1.21969886e-01 -3.48995253e-02 9.91494834e-01 -1.25380591e-01 -3.48996893e-02 9.91036475e-01 -1.28940344e-01 -3.48996185e-02 9.90591407e-01 -1.32310510e-01 -3.48995738e-02 9.90123451e-01 -1.35777310e-01 -3.48996930e-02 9.89630520e-01 -1.39327258e-01 -3.48995812e-02 9.89150047e-01 -1.42691359e-01 -3.48995291e-02 9.88647878e-01 -1.46122813e-01 -3.48996595e-02 9.88129973e-01 -1.49590820e-01 -3.48995477e-02 9.87602532e-01 -1.53036579e-01 -3.48996930e-02 9.87058640e-01 -1.56501174e-01 -3.48995253e-02 9.86510098e-01 -1.59927651e-01 -3.48996669e-02 9.85947251e-01 -1.63363785e-01 -3.48995104e-02 9.85372245e-01 -1.66793078e-01 -3.48996371e-02 9.84771788e-01 -1.70296475e-01 -3.48995924e-02 9.84170973e-01 -1.73763469e-01 -3.48996520e-02 9.83569026e-01 -1.77135944e-01 -3.48995365e-02 9.82958794e-01 -1.80460960e-01 -3.48995999e-02 9.82323587e-01 -1.83905736e-01 -3.48995887e-02 9.81661737e-01 -1.87399685e-01 -3.48996595e-02 9.80984032e-01 -1.90908030e-01 -3.48996185e-02 9.80311811e-01 -1.94341376e-01 -3.48996185e-02 9.79641378e-01 -1.97688267e-01 -3.48995738e-02 9.78968441e-01 -2.00999469e-01 -3.48995887e-02 9.78257656e-01 -2.04424545e-01 -3.48996148e-02 9.77526486e-01 -2.07901895e-01 -3.48996930e-02 9.76792037e-01 -2.11325094e-01 -3.48995700e-02 9.76056457e-01 -2.14689463e-01 -3.48996371e-02 9.75298822e-01 -2.18109578e-01 -3.48995626e-02 9.74520147e-01 -2.21561566e-01 -3.48996595e-02 9.73743498e-01 -2.24953771e-01 -3.48995402e-02 9.72954690e-01 -2.28347063e-01 -3.48996781e-02 9.72149193e-01 -2.31749639e-01 -3.48995700e-02 9.71355736e-01 -2.35057771e-01 -3.48996520e-02 9.70514894e-01 -2.38496810e-01 -3.48996930e-02 9.69674945e-01 -2.41884917e-01 -3.48995849e-02 9.68824923e-01 -2.45261461e-01 -3.48996930e-02 9.67944741e-01 -2.48719797e-01 -3.48995999e-02 9.67087150e-01 -2.52036154e-01 -3.48995887e-02 9.66204703e-01 -2.55405068e-01 -3.48996669e-02 9.65301394e-01 -2.58797050e-01 -3.48995328e-02 9.64418650e-01 -2.62067884e-01 -3.48996520e-02 9.63476539e-01 -2.65499353e-01 -3.48996893e-02 9.62540746e-01 -2.68882006e-01 -3.48995663e-02 9.61604774e-01 -2.72211254e-01 -3.48996781e-02 9.60613191e-01 -2.75681466e-01 -3.48996259e-02 9.59660530e-01 -2.78977633e-01 -3.48995402e-02 9.58721578e-01 -2.82190353e-01 -3.48996520e-02 9.57703054e-01 -2.85633713e-01 -3.48996930e-02 9.56676006e-01 -2.89049089e-01 -3.48996446e-02 9.55661297e-01 -2.92387962e-01 -3.48996520e-02 9.54659283e-01 -2.95643955e-01 -3.48995589e-02 9.53649759e-01 -2.98880011e-01 -3.48996669e-02 9.52598393e-01 -3.02215993e-01 -3.48995775e-02 9.51506376e-01 -3.05633634e-01 -3.48996930e-02 9.50411737e-01 -3.09023321e-01 -3.48996334e-02 9.49335039e-01 -3.12315911e-01 -3.48996371e-02 9.48260844e-01 -3.15564603e-01 -3.48995440e-02 9.47182834e-01 -3.18788111e-01 -3.48996185e-02 9.46067095e-01 -3.22081238e-01 -3.48996148e-02 9.44898486e-01 -3.25488657e-01 -3.48997153e-02 9.43744659e-01 -3.28820139e-01 -3.48995700e-02 9.42602336e-01 -3.32084358e-01 -3.48996483e-02 9.41458344e-01 -3.35320711e-01 -3.48995589e-02 9.40253496e-01 -3.38674814e-01 -3.48997153e-02 9.39069092e-01 -3.41953486e-01 -3.48995626e-02 9.37870920e-01 -3.45207125e-01 -3.48997153e-02 9.36652482e-01 -3.48484755e-01 -3.48995775e-02 9.35478091e-01 -3.51629615e-01 -3.48996259e-02 9.34234142e-01 -3.54934782e-01 -3.48996669e-02 9.32966530e-01 -3.58275861e-01 -3.48996781e-02 9.31702018e-01 -3.61527741e-01 -3.48995999e-02 9.30447161e-01 -3.64760727e-01 -3.48996781e-02 9.29164112e-01 -3.68014902e-01 -3.48995887e-02 9.27887261e-01 -3.71217042e-01 -3.48997004e-02 9.26578283e-01 -3.74474704e-01 -3.48995775e-02 9.25293148e-01 -3.77636999e-01 -3.48996259e-02 9.23949778e-01 -3.80909592e-01 -3.48996930e-02 9.22610462e-01 -3.84145975e-01 -3.48996036e-02 9.21250105e-01 -3.87395799e-01 -3.48997153e-02 9.19855297e-01 -3.90694141e-01 -3.48996110e-02 9.18527424e-01 -3.93804818e-01 -3.48995738e-02 9.17190373e-01 -3.96912426e-01 -3.48996334e-02 9.15751994e-01 -4.00223970e-01 -3.48997153e-02 9.14304256e-01 -4.03517008e-01 -3.48996185e-02 9.12905037e-01 -4.06673580e-01 -3.48996259e-02 9.11489248e-01 -4.09837842e-01 -3.48995663e-02 9.10105169e-01 -4.12900299e-01 -3.48996036e-02 9.08678412e-01 -4.16027576e-01 -3.48996110e-02 9.07180011e-01 -4.19289857e-01 -3.48997153e-02 9.05666053e-01 -4.22547728e-01 -3.48995887e-02 9.04187620e-01 -4.25700366e-01 -3.48995887e-02 9.02726889e-01 -4.28792357e-01 -3.48995663e-02 9.01269913e-01 -4.31842744e-01 -3.48996595e-02 8.99760365e-01 -4.34987664e-01 -3.48996297e-02 8.98195744e-01 -4.38207537e-01 -3.48997153e-02 8.96652281e-01 -4.41353351e-01 -3.48995775e-02 8.95118475e-01 -4.44457203e-01 -3.48997042e-02 8.93558145e-01 -4.47585821e-01 -3.48995775e-02 8.92015636e-01 -4.50657040e-01 -3.48996446e-02 8.90443683e-01 -4.53751981e-01 -3.48996595e-02 8.88807833e-01 -4.56945211e-01 -3.48996930e-02 8.87220263e-01 -4.60018367e-01 -3.48995775e-02 8.85654449e-01 -4.63032544e-01 -3.48996371e-02 8.84033263e-01 -4.66117382e-01 -3.48996520e-02 8.82373571e-01 -4.69248861e-01 -3.48996781e-02 8.80724967e-01 -4.72338110e-01 -3.48996110e-02 8.79048884e-01 -4.75449204e-01 -3.48996967e-02 8.77384901e-01 -4.78519022e-01 -3.48995812e-02 8.75756979e-01 -4.81486052e-01 -3.48996446e-02 8.74084711e-01 -4.84512150e-01 -3.48996297e-02 8.72373402e-01 -4.87588286e-01 -3.48996781e-02 8.70646060e-01 -4.90668088e-01 -3.48996595e-02 8.68901134e-01 -4.93749887e-01 -3.48996930e-02 8.67169261e-01 -4.96788830e-01 -3.48995514e-02 8.65436614e-01 -4.99798775e-01 -3.48997153e-02 8.63678455e-01 -5.02830744e-01 -3.48995589e-02 8.61980557e-01 -5.05737662e-01 -3.48996371e-02 8.60207140e-01 -5.08747101e-01 -3.48996259e-02 8.58411193e-01 -5.11769831e-01 -3.48996185e-02 8.56574178e-01 -5.14841795e-01 -3.48996930e-02 8.54725003e-01 -5.17901897e-01 -3.48996148e-02 8.52950990e-01 -5.20821989e-01 -3.48995477e-02 8.51180375e-01 -5.23707151e-01 -3.48996371e-02 8.49352598e-01 -5.26670873e-01 -3.48996297e-02 8.47461641e-01 -5.29704928e-01 -3.48996930e-02 8.45553160e-01 -5.32746971e-01 -3.48996259e-02 8.43733251e-01 -5.35622656e-01 -3.48995663e-02 8.41915071e-01 -5.38477242e-01 -3.48996185e-02 8.39989305e-01 -5.41474283e-01 -3.48997116e-02 8.38044822e-01 -5.44480324e-01 -3.48996446e-02 8.36125076e-01 -5.47421813e-01 -3.48996595e-02 8.34215701e-01 -5.50331891e-01 -3.48996110e-02 8.32341194e-01 -5.53157747e-01 -3.48995738e-02 8.30458283e-01 -5.55983305e-01 -3.48996073e-02 8.28520954e-01 -5.58869541e-01 -3.48996185e-02 8.26492667e-01 -5.61862648e-01 -3.48996930e-02 8.24526727e-01 -5.64744353e-01 -3.48995402e-02 8.22557211e-01 -5.67607820e-01 -3.48996781e-02 8.20570648e-01 -5.70476413e-01 -3.48995738e-02 8.18582356e-01 -5.73322475e-01 -3.48996669e-02 8.16586554e-01 -5.76168120e-01 -3.48995700e-02 8.14568400e-01 -5.79012990e-01 -3.48996930e-02 8.12535107e-01 -5.81865370e-01 -3.48995700e-02 8.10528994e-01 -5.84651172e-01 -3.48996297e-02 8.08474779e-01 -5.87494016e-01 -3.48996520e-02 8.06386173e-01 -5.90354621e-01 -3.48996781e-02 8.04279983e-01 -5.93222320e-01 -3.48996669e-02 8.02237391e-01 -5.95981002e-01 -3.48996110e-02 8.00191462e-01 -5.98723948e-01 -3.48996371e-02 7.98073292e-01 -6.01546943e-01 -3.48996967e-02 7.95971096e-01 -6.04326248e-01 -3.48995961e-02 7.93869197e-01 -6.07084036e-01 -3.48996930e-02 7.91740417e-01 -6.09857678e-01 -3.48995961e-02 7.89659977e-01 -6.12548709e-01 -3.48996595e-02 7.87459910e-01 -6.15373671e-01 -3.48997153e-02 7.85246730e-01 -6.18196130e-01 -3.48996408e-02 7.83142090e-01 -6.20859325e-01 -3.48995849e-02 7.81031311e-01 -6.23515129e-01 -3.48996557e-02 7.78841615e-01 -6.26246929e-01 -3.48996483e-02 7.76602387e-01 -6.29023015e-01 -3.48997153e-02 7.74390936e-01 -6.31739438e-01 -3.48995812e-02 7.72230983e-01 -6.34380877e-01 -3.48996595e-02 7.70031035e-01 -6.37049317e-01 -3.48996446e-02 7.67803431e-01 -6.39732361e-01 -3.48996781e-02 7.65551686e-01 -6.42425358e-01 -3.48996520e-02 7.63274252e-01 -6.45129025e-01 -3.48996930e-02 7.61011362e-01 -6.47795200e-01 -3.48995887e-02 7.58798897e-01 -6.50387228e-01 -3.48996669e-02 7.56519854e-01 -6.53037369e-01 -3.48996446e-02 7.54175901e-01 -6.55742943e-01 -3.48997153e-02 7.51811922e-01 -6.58450663e-01 -3.48996595e-02 7.49502838e-01 -6.61078036e-01 -3.48996371e-02 7.47252882e-01 -6.63620591e-01 -3.48995700e-02 7.45015323e-01 -6.66131258e-01 -3.48996520e-02 7.42613912e-01 -6.68808520e-01 -3.48997489e-02 7.40266383e-01 -6.71408772e-01 -3.48995663e-02 7.37933338e-01 -6.73968434e-01 -3.48997153e-02 7.35567927e-01 -6.76550746e-01 -3.48995849e-02 7.33282328e-01 -6.79026186e-01 -3.48996520e-02 7.30843902e-01 -6.81648076e-01 -3.48996669e-02 7.28387117e-01 -6.84272230e-01 -3.48996781e-02 7.26041675e-01 -6.86760604e-01 -3.48995775e-02 7.23670065e-01 -6.89264476e-01 -3.48997153e-02 7.21238554e-01 -6.91799164e-01 -3.48995924e-02 7.18848169e-01 -6.94297612e-01 -3.48997153e-02 7.16364324e-01 -6.96857154e-01 -3.48996520e-02 7.13975728e-01 -6.99300349e-01 -3.48995961e-02 7.11511433e-01 -7.01810956e-01 -3.48996595e-02 7.09056139e-01 -7.04292417e-01 -3.48994508e-02 7.06614554e-01 -7.06727207e-01 -3.48994657e-02 7.04087615e-01 -7.09255278e-01 -3.48993056e-02 7.01665342e-01 -7.11656034e-01 -3.48993056e-02 6.99249148e-01 -7.14026988e-01 -3.48993056e-02 6.96737170e-01 -7.16478288e-01 -3.48993167e-02 6.94179535e-01 -7.18950450e-01 -3.48993801e-02 6.91660643e-01 -7.21377790e-01 -3.48994918e-02 6.89243853e-01 -7.23686874e-01 -3.48996110e-02 6.86973095e-01 -7.25842297e-01 -3.48995104e-02 6.84206605e-01 -7.28451371e-01 -3.48994844e-02 6.81695640e-01 -7.30802476e-01 -3.48994918e-02 6.79487646e-01 -7.32855558e-01 -3.48994955e-02 6.77361906e-01 -7.34821737e-01 -3.48994993e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.55088997e-01 -8.31057727e-01 -3.48994844e-02 5.52706957e-01 -8.32641602e-01 -3.48993875e-02 5.49967647e-01 -8.34454596e-01 -3.48993056e-02 5.47137260e-01 -8.36311579e-01 -3.48993354e-02 5.44194877e-01 -8.38230908e-01 -3.48995440e-02 5.41231871e-01 -8.40147316e-01 -3.48994732e-02 5.38419485e-01 -8.41953337e-01 -3.48995961e-02 5.35471439e-01 -8.43827069e-01 -3.48996148e-02 5.32514989e-01 -8.45701039e-01 -3.48996595e-02 5.29575109e-01 -8.47541153e-01 -3.48996595e-02 5.26622534e-01 -8.49382281e-01 -3.48996595e-02 5.23643315e-01 -8.51219535e-01 -3.48996669e-02 5.20677149e-01 -8.53040040e-01 -3.48996669e-02 5.17645299e-01 -8.54880214e-01 -3.48997153e-02 5.14636397e-01 -8.56695712e-01 -3.48996036e-02 5.11699677e-01 -8.58452499e-01 -3.48996781e-02 5.08684158e-01 -8.60243320e-01 -3.48996520e-02 5.05677700e-01 -8.62015843e-01 -3.48996781e-02 5.02662301e-01 -8.63776147e-01 -3.48996371e-02 4.99585599e-01 -8.65559578e-01 -3.48997153e-02 4.96564746e-01 -8.67296994e-01 -3.48996036e-02 4.93593127e-01 -8.68988454e-01 -3.48996297e-02 4.90546942e-01 -8.70717287e-01 -3.48996297e-02 4.87516493e-01 -8.72413218e-01 -3.48996669e-02 4.84462410e-01 -8.74111056e-01 -3.48996520e-02 4.81418461e-01 -8.75794947e-01 -3.48996595e-02 4.78376567e-01 -8.77460003e-01 -3.48996483e-02 4.75307286e-01 -8.79125357e-01 -3.48996595e-02 4.72229302e-01 -8.80783975e-01 -3.48996781e-02 4.69145447e-01 -8.82428050e-01 -3.48996595e-02 4.66050208e-01 -8.84069324e-01 -3.48996557e-02 4.62993860e-01 -8.85673285e-01 -3.48996408e-02 4.59893465e-01 -8.87285829e-01 -3.48996595e-02 4.56794262e-01 -8.88886452e-01 -3.48996595e-02 4.53705698e-01 -8.90465736e-01 -3.48996446e-02 4.50599074e-01 -8.92042756e-01 -3.48996669e-02 4.47471470e-01 -8.93615603e-01 -3.48996595e-02 4.44371194e-01 -8.95160556e-01 -3.48996371e-02 4.41239297e-01 -8.96708786e-01 -3.48996446e-02 4.38112170e-01 -8.98243070e-01 -3.48996669e-02 4.34978008e-01 -8.99764001e-01 -3.48996669e-02 4.31829512e-01 -9.01276648e-01 -3.48996595e-02 4.28598821e-01 -9.02818203e-01 -3.48997489e-02 4.25420582e-01 -9.04320061e-01 -3.48995775e-02 4.22241807e-01 -9.05809462e-01 -3.48997489e-02 4.19074386e-01 -9.07279372e-01 -3.48995663e-02 4.16027337e-01 -9.08678412e-01 -3.48996669e-02 4.12845939e-01 -9.10129547e-01 -3.48996595e-02 4.09656048e-01 -9.11570013e-01 -3.48996669e-02 4.06378150e-01 -9.13036346e-01 -3.48997153e-02 4.03176308e-01 -9.14454758e-01 -3.48995738e-02 4.00086999e-01 -9.15812016e-01 -3.48996408e-02 3.96916151e-01 -9.17188764e-01 -3.48996781e-02 3.93700868e-01 -9.18570697e-01 -3.48996669e-02 3.90414059e-01 -9.19976234e-01 -3.48997153e-02 3.87160540e-01 -9.21350658e-01 -3.48995999e-02 3.83954585e-01 -9.22690153e-01 -3.48997153e-02 3.80717188e-01 -9.24029529e-01 -3.48995812e-02 3.77613634e-01 -9.25305128e-01 -3.48996595e-02 3.74366581e-01 -9.26621377e-01 -3.48996781e-02 3.71027321e-01 -9.27963734e-01 -3.48997302e-02 3.67702216e-01 -9.29287672e-01 -3.48996557e-02 3.64545733e-01 -9.30530846e-01 -3.48995812e-02 3.61386687e-01 -9.31756258e-01 -3.48996744e-02 3.58131707e-01 -9.33021426e-01 -3.48996595e-02 3.54871601e-01 -9.34258640e-01 -3.48996781e-02 3.51606876e-01 -9.35487151e-01 -3.48996669e-02 3.48324299e-01 -9.36713398e-01 -3.48996595e-02 3.45035285e-01 -9.37934041e-01 -3.48996595e-02 3.41797620e-01 -9.39124823e-01 -3.48996595e-02 3.38386685e-01 -9.40358043e-01 -3.48997563e-02 3.35080445e-01 -9.41544235e-01 -3.48995812e-02 3.31830412e-01 -9.42690969e-01 -3.48997489e-02 3.28522623e-01 -9.43849742e-01 -3.48995775e-02 3.25260013e-01 -9.44978476e-01 -3.48997489e-02 3.21928591e-01 -9.46118951e-01 -3.48995775e-02 3.18710387e-01 -9.47207630e-01 -3.48996595e-02 3.15409184e-01 -9.48310852e-01 -3.48996781e-02 3.12089533e-01 -9.49408710e-01 -3.48996706e-02 3.08775395e-01 -9.50492322e-01 -3.48996446e-02 3.05462986e-01 -9.51564729e-01 -3.48996669e-02 3.02136242e-01 -9.52623785e-01 -3.48996669e-02 2.98812300e-01 -9.53671813e-01 -3.48996371e-02 2.95495719e-01 -9.54705298e-01 -3.48996520e-02 2.92174697e-01 -9.55726981e-01 -3.48996520e-02 2.88730860e-01 -9.56770122e-01 -3.48997153e-02 2.85318404e-01 -9.57794905e-01 -3.48996446e-02 2.82034934e-01 -9.58769441e-01 -3.48996036e-02 2.78712720e-01 -9.59740758e-01 -3.48997153e-02 2.75256425e-01 -9.60734785e-01 -3.48996669e-02 2.71897227e-01 -9.61691320e-01 -3.48996520e-02 2.68622369e-01 -9.62612450e-01 -3.48995775e-02 2.65350938e-01 -9.63519335e-01 -3.48996520e-02 2.61975318e-01 -9.64444816e-01 -3.48996520e-02 2.58593291e-01 -9.65353429e-01 -3.48996818e-02 2.55221218e-01 -9.66251433e-01 -3.48996669e-02 2.51859248e-01 -9.67135608e-01 -3.48996595e-02 2.48404726e-01 -9.68024671e-01 -3.48997153e-02 2.45011270e-01 -9.68889296e-01 -3.48995849e-02 2.41634548e-01 -9.69737113e-01 -3.48996930e-02 2.38242701e-01 -9.70577300e-01 -3.48995775e-02 2.34960258e-01 -9.71379161e-01 -3.48996632e-02 2.31560677e-01 -9.72194135e-01 -3.48996632e-02 2.28163570e-01 -9.72997189e-01 -3.48996595e-02 2.24768400e-01 -9.73787010e-01 -3.48996632e-02 2.21292943e-01 -9.74580586e-01 -3.48997153e-02 2.17867076e-01 -9.75353777e-01 -3.48995812e-02 2.14548111e-01 -9.76087868e-01 -3.48996259e-02 2.11129680e-01 -9.76832449e-01 -3.48996595e-02 2.07744226e-01 -9.77558613e-01 -3.48996595e-02 2.04258621e-01 -9.78294969e-01 -3.48997153e-02 2.00752810e-01 -9.79019582e-01 -3.48996148e-02 1.97417170e-01 -9.79696453e-01 -3.48996110e-02 1.94083273e-01 -9.80361640e-01 -3.48996669e-02 1.90647975e-01 -9.81036901e-01 -3.48996297e-02 1.87143564e-01 -9.81710136e-01 -3.48997153e-02 1.83716461e-01 -9.82357800e-01 -3.48995775e-02 1.80292517e-01 -9.82990026e-01 -3.48997489e-02 1.76838741e-01 -9.83625054e-01 -3.48995849e-02 1.73528776e-01 -9.84212816e-01 -3.48996595e-02 1.70103580e-01 -9.84805286e-01 -3.48996669e-02 1.66653275e-01 -9.85396326e-01 -3.48996669e-02 1.63106740e-01 -9.85987544e-01 -3.48997489e-02 1.59653410e-01 -9.86554086e-01 -3.48995663e-02 1.56328917e-01 -9.87087488e-01 -3.48996706e-02 1.52883500e-01 -9.87626612e-01 -3.48996520e-02 1.49434328e-01 -9.88152266e-01 -3.48996520e-02 1.45981178e-01 -9.88670349e-01 -3.48996595e-02 1.42512649e-01 -9.89175439e-01 -3.48996446e-02 1.39059097e-01 -9.89668667e-01 -3.48996595e-02 1.35523677e-01 -9.90159988e-01 -3.48997153e-02 1.32053301e-01 -9.90626037e-01 -3.48995924e-02 1.28693387e-01 -9.91068304e-01 -3.48996669e-02 1.25211000e-01 -9.91515219e-01 -3.48996446e-02 1.21765547e-01 -9.91943479e-01 -3.48996595e-02 1.18203230e-01 -9.92374420e-01 -3.48997153e-02 1.14722513e-01 -9.92781639e-01 -3.48995887e-02 1.11359961e-01 -9.93165493e-01 -3.48996595e-02 1.07884236e-01 -9.93548989e-01 -3.48996520e-02 1.04426384e-01 -9.93918002e-01 -3.48996520e-02 1.00868918e-01 -9.94283617e-01 -3.48997377e-02 9.73831564e-02 -9.94632244e-01 -3.48995887e-02 9.39144045e-02 -9.94968534e-01 -3.48997489e-02 9.04304087e-02 -9.95290458e-01 -3.48995775e-02 8.69812965e-02 -9.95597839e-01 -3.48997153e-02 8.33954886e-02 -9.95903075e-01 -3.48996520e-02 7.99974278e-02 -9.96182621e-01 -3.48995775e-02 7.66146258e-02 -9.96446848e-01 -3.48996520e-02 7.31540695e-02 -9.96708095e-01 -3.48996781e-02 6.96671307e-02 -9.96956766e-01 -3.48996632e-02 6.61963597e-02 -9.97194231e-01 -3.48996781e-02 6.27251789e-02 -9.97417986e-01 -3.48996520e-02 5.92575856e-02 -9.97630715e-01 -3.48996520e-02 5.57696223e-02 -9.97832358e-01 -3.48996669e-02 5.22748046e-02 -9.98020053e-01 -3.48996520e-02 4.87906151e-02 -9.98198330e-01 -3.48996595e-02 4.52161543e-02 -9.98365998e-01 -3.48997153e-02 4.16454673e-02 -9.98521507e-01 -3.48996446e-02 3.82304117e-02 -9.98658001e-01 -3.48995812e-02 3.48270014e-02 -9.98781919e-01 -3.48996185e-02 3.12575176e-02 -9.98899102e-01 -3.48996893e-02 2.77658440e-02 -9.99003410e-01 -3.48995812e-02 2.42860746e-02 -9.99096990e-01 -3.48997153e-02 2.07824390e-02 -9.99171197e-01 -3.48995887e-02 1.74017604e-02 -9.99242008e-01 -3.48996595e-02 1.38226002e-02 -9.99287724e-01 -3.48997153e-02 1.03133051e-02 -9.99335825e-01 -3.48995812e-02 6.94143539e-03 -9.99371588e-01 -3.48996595e-02 3.44591308e-03 -9.99388397e-01 -3.48996669e-02 -3.55278426e-05 -9.99389648e-01 -3.48996595e-02 -3.50816641e-03 -9.99388456e-01 -3.48996781e-02 -7.00703450e-03 -9.99371707e-01 -3.48996706e-02 -1.05060684e-02 -9.99334335e-01 -3.48996520e-02 -1.39824850e-02 -9.99286354e-01 -3.48996595e-02 -1.75541192e-02 -9.99240458e-01 -3.48997116e-02 -2.11470947e-02 -9.99162972e-01 -3.48996930e-02 -2.45646276e-02 -9.99088585e-01 -3.48995999e-02 -2.79433895e-02 -9.98998940e-01 -3.48996669e-02 -3.14354189e-02 -9.98895645e-01 -3.48996855e-02 -3.49051021e-02 -9.98780727e-01 -3.48996930e-02 -3.85029130e-02 -9.98646915e-01 -3.48997489e-02 -4.19955403e-02 -9.98508215e-01 -3.48996110e-02 -4.53763381e-02 -9.98358488e-01 -3.48996595e-02 -4.88461778e-02 -9.98195291e-01 -3.48996930e-02 -5.23020849e-02 -9.98017967e-01 -3.48996930e-02 -5.59078529e-02 -9.97823834e-01 -3.48997489e-02 -5.94030172e-02 -9.97622550e-01 -3.48995849e-02 -6.28482327e-02 -9.97410119e-01 -3.48997563e-02 -6.63552582e-02 -9.97183204e-01 -3.48995924e-02 -6.97268620e-02 -9.96952116e-01 -3.48996930e-02 -7.33186007e-02 -9.96696591e-01 -3.48997489e-02 -7.68115595e-02 -9.96432006e-01 -3.48995775e-02 -8.02728161e-02 -9.96159732e-01 -3.48997489e-02 -8.37621316e-02 -9.95872796e-01 -3.48995961e-02 -8.71240124e-02 -9.95584011e-01 -3.48996669e-02 -9.05978233e-02 -9.95274067e-01 -3.48996706e-02 -9.40757841e-02 -9.94951725e-01 -3.48996595e-02 -9.75599885e-02 -9.94616091e-01 -3.48996781e-02 -1.01024784e-01 -9.94270027e-01 -3.48996669e-02 -1.04480892e-01 -9.93912518e-01 -3.48996706e-02 -1.08053587e-01 -9.93530869e-01 -3.48997153e-02 -1.11504450e-01 -9.93149638e-01 -3.48995887e-02 -1.14910714e-01 -9.92758691e-01 -3.48996297e-02 -1.18385807e-01 -9.92350638e-01 -3.48996483e-02 -1.21837534e-01 -9.91935968e-01 -3.48996744e-02 -1.25382721e-01 -9.91493404e-01 -3.48997302e-02 -1.28845602e-01 -9.91047561e-01 -3.48996036e-02 -1.32208824e-01 -9.90606248e-01 -3.48996930e-02 -1.35678276e-01 -9.90136564e-01 -3.48996781e-02 -1.39125168e-01 -9.89658713e-01 -3.48996595e-02 -1.42665818e-01 -9.89152610e-01 -3.48997153e-02 -1.46128342e-01 -9.88647401e-01 -3.48995961e-02 -1.49552971e-01 -9.88133907e-01 -3.48997153e-02 -1.53007850e-01 -9.87607121e-01 -3.48995887e-02 -1.56360403e-01 -9.87080932e-01 -3.48996595e-02 -1.59902826e-01 -9.86514330e-01 -3.48997153e-02 -1.63349465e-01 -9.85949159e-01 -3.48996036e-02 -1.66772783e-01 -9.85375702e-01 -3.48997414e-02 -1.70232102e-01 -9.84782875e-01 -3.48995849e-02 -1.73576266e-01 -9.84203696e-01 -3.48996669e-02 -1.77011639e-01 -9.83591199e-01 -3.48996446e-02 -1.80445492e-01 -9.82960999e-01 -3.48996781e-02 -1.83860853e-01 -9.82332468e-01 -3.48996632e-02 -1.87288627e-01 -9.81683135e-01 -3.48996781e-02 -1.90716580e-01 -9.81021404e-01 -3.48996669e-02 -1.94135502e-01 -9.80351925e-01 -3.48996669e-02 -1.97641462e-01 -9.79650557e-01 -3.48997153e-02 -2.01045021e-01 -9.78957534e-01 -3.48995924e-02 -2.04379201e-01 -9.78267670e-01 -3.48996595e-02 -2.07783222e-01 -9.77552235e-01 -3.48996446e-02 -2.11277753e-01 -9.76801813e-01 -3.48997153e-02 -2.14724362e-01 -9.76048231e-01 -3.48995961e-02 -2.18014076e-01 -9.75320756e-01 -3.48996669e-02 -2.21417710e-01 -9.74552691e-01 -3.48996669e-02 -2.24840611e-01 -9.73767459e-01 -3.48996930e-02 -2.28335053e-01 -9.72958207e-01 -3.48997153e-02 -2.31728226e-01 -9.72155273e-01 -3.48995775e-02 -2.35009775e-01 -9.71367657e-01 -3.48996781e-02 -2.38414705e-01 -9.70536590e-01 -3.48996595e-02 -2.41777524e-01 -9.69701111e-01 -3.48996595e-02 -2.45163783e-01 -9.68850434e-01 -3.48996781e-02 -2.48541191e-01 -9.67990458e-01 -3.48996781e-02 -2.51998276e-01 -9.67096448e-01 -3.48997153e-02 -2.55416930e-01 -9.66200709e-01 -3.48996036e-02 -2.58762151e-01 -9.65308666e-01 -3.48997153e-02 -2.62250096e-01 -9.64368820e-01 -3.48996595e-02 -2.65513271e-01 -9.63472784e-01 -3.48995775e-02 -2.68766493e-01 -9.62571740e-01 -3.48996706e-02 -2.72143990e-01 -9.61622834e-01 -3.48996669e-02 -2.75505424e-01 -9.60663795e-01 -3.48996781e-02 -2.78859437e-01 -9.59695339e-01 -3.48996595e-02 -2.82199025e-01 -9.58718538e-01 -3.48996520e-02 -2.85543054e-01 -9.57730055e-01 -3.48996371e-02 -2.88871318e-01 -9.56728995e-01 -3.48996520e-02 -2.92205304e-01 -9.55717564e-01 -3.48996595e-02 -2.95642763e-01 -9.54660773e-01 -3.48997489e-02 -2.99085557e-01 -9.53586459e-01 -3.48996669e-02 -3.02411199e-01 -9.52536285e-01 -3.48996781e-02 -3.05659324e-01 -9.51501191e-01 -3.48995738e-02 -3.08878034e-01 -9.50459003e-01 -3.48996669e-02 -3.12271118e-01 -9.49349821e-01 -3.48997153e-02 -3.15589488e-01 -9.48252559e-01 -3.48995887e-02 -3.18881303e-01 -9.47150409e-01 -3.48997153e-02 -3.22190970e-01 -9.46029902e-01 -3.48995887e-02 -3.25392097e-01 -9.44933712e-01 -3.48996669e-02 -3.28689426e-01 -9.43790793e-01 -3.48996297e-02 -3.31976205e-01 -9.42641079e-01 -3.48996446e-02 -3.35361600e-01 -9.41441476e-01 -3.48997191e-02 -3.38675320e-01 -9.40252841e-01 -3.48995849e-02 -3.41920078e-01 -9.39080894e-01 -3.48997302e-02 -3.45208347e-01 -9.37868059e-01 -3.48995700e-02 -3.48400950e-01 -9.36684310e-01 -3.48996520e-02 -3.51652026e-01 -9.35469508e-01 -3.48996595e-02 -3.54909301e-01 -9.34243858e-01 -3.48996595e-02 -3.58277321e-01 -9.32965279e-01 -3.48997340e-02 -3.61591756e-01 -9.31678176e-01 -3.48996855e-02 -3.64788741e-01 -9.30435419e-01 -3.48995887e-02 -3.67945045e-01 -9.29191291e-01 -3.48996669e-02 -3.71176183e-01 -9.27903891e-01 -3.48996371e-02 -3.74419928e-01 -9.26600218e-01 -3.48996669e-02 -3.77720088e-01 -9.25260484e-01 -3.48997153e-02 -3.80971819e-01 -9.23922896e-01 -3.48995849e-02 -3.84090275e-01 -9.22632813e-01 -3.48996595e-02 -3.87296468e-01 -9.21291113e-01 -3.48996371e-02 -3.90531927e-01 -9.19924974e-01 -3.48996446e-02 -3.93817395e-01 -9.18521643e-01 -3.48997153e-02 -3.97018135e-01 -9.17144537e-01 -3.48995812e-02 -4.00209188e-01 -9.15758491e-01 -3.48997153e-02 -4.03416067e-01 -9.14349318e-01 -3.48995812e-02 -4.06504452e-01 -9.12980378e-01 -3.48996744e-02 -4.09700960e-01 -9.11551476e-01 -3.48996520e-02 -4.12860572e-01 -9.10123110e-01 -3.48996781e-02 -4.16052759e-01 -9.08665717e-01 -3.48996595e-02 -4.19229120e-01 -9.07205343e-01 -3.48996446e-02 -4.22379017e-01 -9.05743957e-01 -3.48996781e-02 -4.25556391e-01 -9.04256225e-01 -3.48996557e-02 -4.28787261e-01 -9.02728736e-01 -3.48997377e-02 -4.31927204e-01 -9.01229262e-01 -3.48995849e-02 -4.34973598e-01 -8.99767518e-01 -3.48996930e-02 -4.38203096e-01 -8.98198605e-01 -3.48997489e-02 -4.41422343e-01 -8.96619618e-01 -3.48996781e-02 -4.44478244e-01 -8.95108879e-01 -3.48996148e-02 -4.47520018e-01 -8.93590569e-01 -3.48996930e-02 -4.50637192e-01 -8.92024219e-01 -3.48996930e-02 -4.53751594e-01 -8.90443802e-01 -3.48996706e-02 -4.56934571e-01 -8.88812780e-01 -3.48997153e-02 -4.60029125e-01 -8.87215316e-01 -3.48995812e-02 -4.63021398e-01 -8.85660470e-01 -3.48996520e-02 -4.66123372e-01 -8.84030223e-01 -3.48996520e-02 -4.69204903e-01 -8.82398069e-01 -3.48996632e-02 -4.72376496e-01 -8.80705714e-01 -3.48997377e-02 -4.75431204e-01 -8.79056513e-01 -3.48995887e-02 -4.78506029e-01 -8.77390862e-01 -3.48997489e-02 -4.81578559e-01 -8.75707209e-01 -3.48995999e-02 -4.84618753e-01 -8.74025106e-01 -3.48997116e-02 -4.87743109e-01 -8.72286499e-01 -3.48996781e-02 -4.90709335e-01 -8.70623291e-01 -3.48995924e-02 -4.93677467e-01 -8.68941486e-01 -3.48996781e-02 -4.96710986e-01 -8.67213964e-01 -3.48996669e-02 -4.99717593e-01 -8.65483642e-01 -3.48996595e-02 -5.02729356e-01 -8.63738835e-01 -3.48996520e-02 -5.05744100e-01 -8.61977816e-01 -3.48996669e-02 -5.08760214e-01 -8.60198259e-01 -3.48996669e-02 -5.11753142e-01 -8.58421683e-01 -3.48996744e-02 -5.14746428e-01 -8.56631160e-01 -3.48996781e-02 -5.17737567e-01 -8.54825020e-01 -3.48996669e-02 -5.20711184e-01 -8.53018403e-01 -3.48996781e-02 -5.23753524e-01 -8.51151705e-01 -3.48997153e-02 -5.26714981e-01 -8.49324644e-01 -3.48995961e-02 -5.29600799e-01 -8.47528100e-01 -3.48996669e-02 -5.32633483e-01 -8.45623493e-01 -3.48997563e-02 -5.35596371e-01 -8.43750954e-01 -3.48996073e-02 -5.38517118e-01 -8.41888726e-01 -3.48997489e-02 -5.41474223e-01 -8.39991093e-01 -3.48996036e-02 -5.44312179e-01 -8.38155568e-01 -3.48996930e-02 -5.47244549e-01 -8.36241663e-01 -3.48996781e-02 -5.50130427e-01 -8.34347963e-01 -3.48996669e-02 -5.53048790e-01 -8.32413733e-01 -3.48996669e-02 -5.55962920e-01 -8.30472231e-01 -3.48996520e-02 -5.58947265e-01 -8.28467965e-01 -3.48997489e-02 -5.61833978e-01 -8.26511025e-01 -3.48995999e-02 -5.64630568e-01 -8.24606061e-01 -3.48996781e-02 -5.67493200e-01 -8.22636604e-01 -3.48996930e-02 -5.70367396e-01 -8.20646524e-01 -3.48996781e-02 -5.73313594e-01 -8.18588972e-01 -3.48997563e-02 -5.76248348e-01 -8.16529751e-01 -3.48996930e-02 -5.79013944e-01 -8.14568222e-01 -3.48995961e-02 -5.81775546e-01 -8.12599778e-01 -3.48996669e-02 -5.84607840e-01 -8.10560346e-01 -3.48996930e-02 -5.87455332e-01 -8.08503330e-01 -3.48996781e-02 -5.90325058e-01 -8.06408286e-01 -3.48997489e-02 -5.93141556e-01 -8.04338932e-01 -3.48995999e-02 -5.95864892e-01 -8.02323341e-01 -3.48996781e-02 -5.98661423e-01 -8.00238907e-01 -3.48996930e-02 -6.01459503e-01 -7.98138857e-01 -3.48996930e-02 -6.04312003e-01 -7.95982480e-01 -3.48997489e-02 -6.07123792e-01 -7.93838859e-01 -3.48996446e-02 -6.09882653e-01 -7.91719854e-01 -3.48997153e-02 -6.12624466e-01 -7.89601564e-01 -3.48995999e-02 -6.15298033e-01 -7.87519515e-01 -3.48996781e-02 -6.18035913e-01 -7.85372496e-01 -3.48996855e-02 -6.20783925e-01 -7.83202291e-01 -3.48996781e-02 -6.23501658e-01 -7.81040549e-01 -3.48996930e-02 -6.26228690e-01 -7.78856218e-01 -3.48996818e-02 -6.28950000e-01 -7.76662409e-01 -3.48996781e-02 -6.31649077e-01 -7.74463594e-01 -3.48996930e-02 -6.34351730e-01 -7.72254109e-01 -3.48996595e-02 -6.37042880e-01 -7.70035982e-01 -3.48996706e-02 -6.39728129e-01 -7.67807484e-01 -3.48996930e-02 -6.42478824e-01 -7.65506923e-01 -3.48997153e-02 -6.45232379e-01 -7.63187826e-01 -3.48996781e-02 -6.47819161e-01 -7.60989964e-01 -3.48996110e-02 -6.50386751e-01 -7.58798420e-01 -3.48996930e-02 -6.53036535e-01 -7.56521285e-01 -3.48996818e-02 -6.55689776e-01 -7.54223049e-01 -3.48996781e-02 -6.58374786e-01 -7.51877785e-01 -3.48997563e-02 -6.61012650e-01 -7.49561667e-01 -3.48995887e-02 -6.63555741e-01 -7.47311234e-01 -3.48996930e-02 -6.66161478e-01 -7.44989216e-01 -3.48996669e-02 -6.68750763e-01 -7.42664993e-01 -3.48996669e-02 -6.71410084e-01 -7.40263641e-01 -3.48997489e-02 -6.73996091e-01 -7.37907112e-01 -3.48996148e-02 -6.76569104e-01 -7.35552728e-01 -3.48997563e-02 -6.79132998e-01 -7.33182132e-01 -3.48996185e-02 -6.81678891e-01 -7.30814457e-01 -3.48997563e-02 -6.84304059e-01 -7.28357434e-01 -3.48996930e-02 -6.86769307e-01 -7.26033747e-01 -3.48996110e-02 -6.89232588e-01 -7.23700762e-01 -3.48996930e-02 -6.91756070e-01 -7.21279860e-01 -3.48996930e-02 -6.94263875e-01 -7.18880415e-01 -3.48996930e-02 -6.96774065e-01 -7.16445744e-01 -3.48996930e-02 -6.99260712e-01 -7.14015067e-01 -3.48996669e-02 -7.01746702e-01 -7.11575210e-01 -3.48996930e-02 -7.04238296e-01 -7.09110856e-01 -3.48996930e-02 -7.06764162e-01 -7.06573069e-01 -3.48997563e-02 -7.09240019e-01 -7.04109311e-01 -3.48995999e-02 -7.11613834e-01 -7.01706231e-01 -3.48996855e-02 -7.14061737e-01 -6.99212193e-01 -3.48996930e-02 -7.16489255e-01 -6.96729541e-01 -3.48997153e-02 -7.18918324e-01 -6.94224000e-01 -3.48996781e-02 -7.21389294e-01 -6.91641569e-01 -3.48997563e-02 -7.23829031e-01 -6.89097583e-01 -3.48996036e-02 -7.26201117e-01 -6.86592102e-01 -3.48997191e-02 -7.28612363e-01 -6.84033513e-01 -3.48996185e-02 -7.30915785e-01 -6.81569815e-01 -3.48996781e-02 -7.33351171e-01 -6.78952813e-01 -3.48997153e-02 -7.35720575e-01 -6.76385522e-01 -3.48996334e-02 -7.38012135e-01 -6.73882067e-01 -3.48996781e-02 -7.40381420e-01 -6.71280146e-01 -3.48996855e-02 -7.42714226e-01 -6.68695748e-01 -3.48996893e-02 -7.45097518e-01 -6.66038990e-01 -3.48997489e-02 -7.47424722e-01 -6.63428545e-01 -3.48995999e-02 -7.49674797e-01 -6.60882831e-01 -3.48996930e-02 -7.51973748e-01 -6.58265352e-01 -3.48996706e-02 -7.54319251e-01 -6.55577302e-01 -3.48997451e-02 -7.56664932e-01 -6.52868450e-01 -3.48996371e-02 -7.58881569e-01 -6.50291920e-01 -3.48995924e-02 -7.61084020e-01 -6.47709548e-01 -3.48996781e-02 -7.63340175e-01 -6.45052969e-01 -3.48996297e-02 -7.65568376e-01 -6.42405689e-01 -3.48996595e-02 -7.67872512e-01 -6.39650106e-01 -3.48997489e-02 -7.70119905e-01 -6.36940956e-01 -3.48995775e-02 -7.72254825e-01 -6.34354115e-01 -3.48996930e-02 -7.74472594e-01 -6.31640017e-01 -3.48996595e-02 -7.76670456e-01 -6.28937244e-01 -3.48996930e-02 -7.78932393e-01 -6.26135170e-01 -3.48997489e-02 -7.81125307e-01 -6.23397231e-01 -3.48995849e-02 -7.83273041e-01 -6.20695233e-01 -3.48997489e-02 -7.85447717e-01 -6.17941439e-01 -3.48995775e-02 -7.87524462e-01 -6.15292788e-01 -3.48996669e-02 -7.89743483e-01 -6.12440288e-01 -3.48997638e-02 -7.91904032e-01 -6.09643638e-01 -3.48995775e-02 -7.93995440e-01 -6.06919169e-01 -3.48997153e-02 -7.96118081e-01 -6.04132950e-01 -3.48995924e-02 -7.98159778e-01 -6.01433039e-01 -3.48996781e-02 -8.00319433e-01 -5.98552346e-01 -3.48997489e-02 -8.02422345e-01 -5.95733285e-01 -3.48996185e-02 -8.04434240e-01 -5.93012929e-01 -3.48996781e-02 -8.06497335e-01 -5.90203285e-01 -3.48996446e-02 -8.08593392e-01 -5.87329090e-01 -3.48997489e-02 -8.10700893e-01 -5.84413409e-01 -3.48996781e-02 -8.12688887e-01 -5.81652045e-01 -3.48995961e-02 -8.14644337e-01 -5.78903377e-01 -3.48996669e-02 -8.16651642e-01 -5.76075137e-01 -3.48996781e-02 -8.18672001e-01 -5.73197603e-01 -3.48996781e-02 -8.20712566e-01 -5.70269763e-01 -3.48997563e-02 -8.22716892e-01 -5.67378283e-01 -3.48996110e-02 -8.24633002e-01 -5.64588368e-01 -3.48996893e-02 -8.26597512e-01 -5.61706722e-01 -3.48996446e-02 -8.28556478e-01 -5.58814049e-01 -3.48996781e-02 -8.30563903e-01 -5.55825472e-01 -3.48997153e-02 -8.32493663e-01 -5.52930355e-01 -3.48996036e-02 -8.34399998e-01 -5.50048769e-01 -3.48997153e-02 -8.36317837e-01 -5.47129154e-01 -3.48996110e-02 -8.38176608e-01 -5.44278979e-01 -3.48996669e-02 -8.40084553e-01 -5.41329145e-01 -3.48996669e-02 -8.41967821e-01 -5.38395464e-01 -3.48996669e-02 -8.43876541e-01 -5.35397112e-01 -3.48997042e-02 -8.45746696e-01 -5.32441080e-01 -3.48995775e-02 -8.47544849e-01 -5.29569626e-01 -3.48996446e-02 -8.49442840e-01 -5.26526690e-01 -3.48997191e-02 -8.51279676e-01 -5.23544371e-01 -3.48995775e-02 -8.53037179e-01 -5.20682573e-01 -3.48996483e-02 -8.54843974e-01 -5.17704010e-01 -3.48996446e-02 -8.56692076e-01 -5.14645159e-01 -3.48997563e-02 -8.58499050e-01 -5.11621118e-01 -3.48995775e-02 -8.60230625e-01 -5.08706033e-01 -3.48996446e-02 -8.62056673e-01 -5.05606532e-01 -3.48997153e-02 -8.63813758e-01 -5.02598464e-01 -3.48995626e-02 -8.65505397e-01 -4.99681264e-01 -3.48996595e-02 -8.67240667e-01 -4.96659905e-01 -3.48996595e-02 -8.68975937e-01 -4.93616790e-01 -3.48996595e-02 -8.70695770e-01 -4.90584016e-01 -3.48996669e-02 -8.72393012e-01 -4.87554401e-01 -3.48996669e-02 -8.74090672e-01 -4.84499961e-01 -3.48996520e-02 -8.75824571e-01 -4.81367797e-01 -3.48997563e-02 -8.77522051e-01 -4.78265733e-01 -3.48995700e-02 -8.79133224e-01 -4.75292981e-01 -3.48996781e-02 -8.80784154e-01 -4.72226501e-01 -3.48996781e-02 -8.82472873e-01 -4.69062865e-01 -3.48997153e-02 -8.84155214e-01 -4.65884358e-01 -3.48996669e-02 -8.85742426e-01 -4.62862015e-01 -3.48995924e-02 -8.87298942e-01 -4.59869981e-01 -3.48996595e-02 -8.88901532e-01 -4.56765592e-01 -3.48996669e-02 -8.90513182e-01 -4.53612030e-01 -3.48997153e-02 -8.92096043e-01 -4.50494170e-01 -3.48996110e-02 -8.93618047e-01 -4.47464377e-01 -3.48996818e-02 -8.95175636e-01 -4.44341272e-01 -3.48996446e-02 -8.96723926e-01 -4.41209286e-01 -3.48996669e-02 -8.98255944e-01 -4.38083202e-01 -3.48996744e-02 -8.99816394e-01 -4.34869647e-01 -3.48997153e-02 -9.01335597e-01 -4.31707859e-01 -3.48995887e-02 -9.02803004e-01 -4.28632379e-01 -3.48996669e-02 -9.04284179e-01 -4.25495118e-01 -3.48996632e-02 -9.05759037e-01 -4.22349185e-01 -3.48996595e-02 -9.07255888e-01 -4.19126898e-01 -3.48997153e-02 -9.08721507e-01 -4.15932983e-01 -3.48995887e-02 -9.10125017e-01 -4.12856489e-01 -3.48996483e-02 -9.11559582e-01 -4.09682542e-01 -3.48996557e-02 -9.12991107e-01 -4.06480998e-01 -3.48996930e-02 -9.14433122e-01 -4.03226376e-01 -3.48997489e-02 -9.15843606e-01 -4.00018036e-01 -3.48995775e-02 -9.17225599e-01 -3.96831691e-01 -3.48997489e-02 -9.18612003e-01 -3.93603206e-01 -3.48995849e-02 -9.19939578e-01 -3.90498161e-01 -3.48996781e-02 -9.21335578e-01 -3.87193292e-01 -3.48997489e-02 -9.22702074e-01 -3.83927077e-01 -3.48995961e-02 -9.23993111e-01 -3.80807430e-01 -3.48996595e-02 -9.25313413e-01 -3.77590925e-01 -3.48996520e-02 -9.26617742e-01 -3.74374479e-01 -3.48996930e-02 -9.27958846e-01 -3.71039093e-01 -3.48997563e-02 -9.29259419e-01 -3.67773652e-01 -3.48995775e-02 -9.30513322e-01 -3.64588410e-01 -3.48997153e-02 -9.31773067e-01 -3.61343473e-01 -3.48996520e-02 -9.33057785e-01 -3.58032048e-01 -3.48997600e-02 -9.34331715e-01 -3.54675651e-01 -3.48996595e-02 -9.35521483e-01 -3.51512522e-01 -3.48995775e-02 -9.36715841e-01 -3.48317683e-01 -3.48996669e-02 -9.37952161e-01 -3.44986677e-01 -3.48997489e-02 -9.39168334e-01 -3.41681302e-01 -3.48995999e-02 -9.40349281e-01 -3.38408262e-01 -3.48997489e-02 -9.41532671e-01 -3.35110962e-01 -3.48995887e-02 -9.42688167e-01 -3.31839353e-01 -3.48997153e-02 -9.43847835e-01 -3.28525960e-01 -3.48995887e-02 -9.44959700e-01 -3.25318873e-01 -3.48996595e-02 -9.46079135e-01 -3.22042614e-01 -3.48996930e-02 -9.47209418e-01 -3.18708152e-01 -3.48996781e-02 -9.48340595e-01 -3.15321535e-01 -3.48997489e-02 -9.49437737e-01 -3.12003374e-01 -3.48996073e-02 -9.50492859e-01 -3.08774680e-01 -3.48996595e-02 -9.51585889e-01 -3.05391788e-01 -3.48997563e-02 -9.52655196e-01 -3.02037358e-01 -3.48995961e-02 -9.53676105e-01 -2.98801631e-01 -3.48996669e-02 -9.54705715e-01 -2.95490354e-01 -3.48996669e-02 -9.55758572e-01 -2.92071223e-01 -3.48997228e-02 -9.56778646e-01 -2.88705826e-01 -3.48995924e-02 -9.57749724e-01 -2.85468340e-01 -3.48996781e-02 -9.58770275e-01 -2.82025933e-01 -3.48997451e-02 -9.59748924e-01 -2.78679907e-01 -3.48995812e-02 -9.60713089e-01 -2.75334716e-01 -3.48997153e-02 -9.61673200e-01 -2.71964669e-01 -3.48995924e-02 -9.62593138e-01 -2.68692344e-01 -3.48996781e-02 -9.63521242e-01 -2.65337557e-01 -3.48996595e-02 -9.64445829e-01 -2.61968136e-01 -3.48996669e-02 -9.65349913e-01 -2.58605808e-01 -3.48996520e-02 -9.66268241e-01 -2.55157441e-01 -3.48997489e-02 -9.67153609e-01 -2.51783162e-01 -3.48995887e-02 -9.68001485e-01 -2.48499632e-01 -3.48996781e-02 -9.68862414e-01 -2.45111063e-01 -3.48996557e-02 -9.69730437e-01 -2.41657510e-01 -3.48997153e-02 -9.70591545e-01 -2.38188848e-01 -3.48996520e-02 -9.71403778e-01 -2.34860390e-01 -3.48995887e-02 -9.72197354e-01 -2.31550425e-01 -3.48996669e-02 -9.72994864e-01 -2.28172377e-01 -3.48996669e-02 -9.73799288e-01 -2.24703148e-01 -3.48997302e-02 -9.74603117e-01 -2.21196890e-01 -3.48996334e-02 -9.75353003e-01 -2.17869624e-01 -3.48995961e-02 -9.76086855e-01 -2.14551136e-01 -3.48996520e-02 -9.76829946e-01 -2.11143389e-01 -3.48996557e-02 -9.77559388e-01 -2.07741186e-01 -3.48996371e-02 -9.78276551e-01 -2.04341814e-01 -3.48996408e-02 -9.78983462e-01 -2.00929955e-01 -3.48996408e-02 -9.79675710e-01 -1.97524741e-01 -3.48996520e-02 -9.80357707e-01 -1.94108069e-01 -3.48996483e-02 -9.81029928e-01 -1.90682426e-01 -3.48996483e-02 -9.81707454e-01 -1.87158704e-01 -3.48997153e-02 -9.82355714e-01 -1.83725595e-01 -3.48995775e-02 -9.82972562e-01 -1.80389985e-01 -3.48996446e-02 -9.83601451e-01 -1.76962435e-01 -3.48996408e-02 -9.84216392e-01 -1.73505425e-01 -3.48996073e-02 -9.84828830e-01 -1.69970900e-01 -3.48996930e-02 -9.85418022e-01 -1.66529655e-01 -3.48995216e-02 -9.85973835e-01 -1.63197234e-01 -3.48996073e-02 -9.86538649e-01 -1.59752339e-01 -3.48996185e-02 -9.87093031e-01 -1.56297103e-01 -3.48996036e-02 -9.87644196e-01 -1.52766243e-01 -3.48997153e-02 -9.88175690e-01 -1.49288088e-01 -3.48995663e-02 -9.88687336e-01 -1.45862415e-01 -3.48997079e-02 -9.89191949e-01 -1.42390475e-01 -3.48995440e-02 -9.89667535e-01 -1.39058515e-01 -3.48995849e-02 -9.90162432e-01 -1.35493368e-01 -3.48996930e-02 -9.90632057e-01 -1.32010818e-01 -3.48995514e-02 -9.91071582e-01 -1.28672644e-01 -3.48995887e-02 -9.91517425e-01 -1.25201479e-01 -3.48995924e-02 -9.91944671e-01 -1.21754259e-01 -3.48995961e-02 -9.92369890e-01 -1.18228465e-01 -3.48996669e-02 -9.92778778e-01 -1.14739612e-01 -3.48995477e-02 -9.93166625e-01 -1.11351252e-01 -3.48996148e-02 -9.93555129e-01 -1.07819580e-01 -3.48996446e-02 -9.93926883e-01 -1.04348436e-01 -3.48995253e-02 -9.94282544e-01 -1.00889631e-01 -3.48996706e-02 -9.94629741e-01 -9.74186957e-02 -3.48994732e-02 -9.94962037e-01 -9.39644277e-02 -3.48995253e-02 -9.95284796e-01 -9.04878750e-02 -3.48993056e-02 -9.95588303e-01 -8.70926231e-02 -3.48993056e-02 -9.95886326e-01 -8.35970417e-02 -3.48993093e-02 -9.96168196e-01 -8.01832005e-02 -3.48993875e-02 -9.96434867e-01 -7.67835900e-02 -3.48995812e-02 -9.96688545e-01 -7.34262541e-02 -3.48995849e-02 -9.96934175e-01 -7.00112581e-02 -3.48994844e-02 -9.97149825e-01 -6.68767467e-02 -3.48994844e-02 -9.97413456e-01 -6.28248379e-02 -3.48994993e-02 -9.97653961e-01 -5.88832535e-02 -3.48994993e-02 -9.97832119e-01 -5.57873584e-02 -3.48994918e-02 -9.97980773e-01 -5.30588143e-02 -3.48994955e-02 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. 0. 0. -9.99290943e-01 -1.41280983e-02 -3.48994955e-02 -9.99337912e-01 -1.02909952e-02 -3.48994955e-02 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. 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. -9.97929394e-01 5.73655218e-02 -2.90905349e-02 -9.97761607e-01 6.02100678e-02 -2.90905330e-02 0. 0. 0. -9.97315586e-01 6.72070831e-02 -2.90905628e-02 -9.97119427e-01 6.99826702e-02 -2.90907193e-02 -9.96868968e-01 7.34859630e-02 -2.90907361e-02 -9.96605515e-01 7.69406781e-02 -2.90907528e-02 -9.96334255e-01 8.04158971e-02 -2.90907677e-02 -9.96044338e-01 8.39053169e-02 -2.90907733e-02 -9.95755851e-01 8.72674733e-02 -2.90907715e-02 -9.95455205e-01 9.07035396e-02 -2.90907770e-02 -9.95119750e-01 9.42914337e-02 -2.90907733e-02 -9.94792044e-01 9.76805761e-02 -2.90907752e-02 -9.94454384e-01 1.01118304e-01 -2.90907845e-02 -9.94078696e-01 1.04711019e-01 -2.90907770e-02 -9.93709207e-01 1.08170256e-01 -2.90907789e-02 -9.93328691e-01 1.11630194e-01 -2.90907789e-02 -9.92937326e-01 1.15026094e-01 -2.90907770e-02 -9.92536485e-01 1.18436843e-01 -2.90907789e-02 -9.92126048e-01 1.21856675e-01 -2.90907808e-02 -9.91689742e-01 1.25384107e-01 -2.90907864e-02 -9.91228640e-01 1.28947452e-01 -2.90907826e-02 -9.90782082e-01 1.32314235e-01 -2.90907770e-02 -9.90323126e-01 1.35752887e-01 -2.90907864e-02 -9.89827514e-01 1.39295995e-01 -2.90907808e-02 -9.89345729e-01 1.42661974e-01 -2.90907752e-02 -9.88842726e-01 1.46133631e-01 -2.90907845e-02 -9.88322556e-01 1.49579555e-01 -2.90907752e-02 -9.87814546e-01 1.52914375e-01 -2.90907808e-02 -9.87260997e-01 1.56469405e-01 -2.90907864e-02 -9.86691952e-01 1.60005450e-01 -2.90907808e-02 -9.86125469e-01 1.63466230e-01 -2.90907826e-02 -9.85546112e-01 1.66921914e-01 -2.90907808e-02 -9.84957576e-01 1.70342252e-01 -2.90907789e-02 -9.84361410e-01 1.73788652e-01 -2.90907808e-02 -9.83744681e-01 1.77240327e-01 -2.90907808e-02 -9.83115494e-01 1.80681452e-01 -2.90907845e-02 -9.82493043e-01 1.84015438e-01 -2.90907752e-02 -9.81876135e-01 1.87300384e-01 -2.90907808e-02 -9.81197715e-01 1.90828815e-01 -2.90907882e-02 -9.80500817e-01 1.94361597e-01 -2.90907789e-02 -9.79818165e-01 1.97784945e-01 -2.90907808e-02 -9.79121923e-01 2.01210096e-01 -2.90907826e-02 -9.78413224e-01 2.04614311e-01 -2.90907808e-02 -9.77704108e-01 2.07966402e-01 -2.90907752e-02 -9.76985276e-01 2.11348146e-01 -2.90907845e-02 -9.76212680e-01 2.14865312e-01 -2.90907808e-02 -9.75473642e-01 2.18193352e-01 -2.90907752e-02 -9.74711835e-01 2.21586123e-01 -2.90907845e-02 -9.73906279e-01 2.25098506e-01 -2.90907808e-02 -9.73110378e-01 2.28515774e-01 -2.90907789e-02 -9.72309887e-01 2.31903151e-01 -2.90907808e-02 -9.71515834e-01 2.35190183e-01 -2.90907752e-02 -9.70718265e-01 2.38470361e-01 -2.90907808e-02 -9.69856560e-01 2.41956189e-01 -2.90907864e-02 -9.68972564e-01 2.45459899e-01 -2.90907789e-02 -9.68107224e-01 2.48856202e-01 -2.90907770e-02 -9.67254400e-01 2.52133429e-01 -2.90907752e-02 -9.66382205e-01 2.55483538e-01 -2.90907808e-02 -9.65472639e-01 2.58881569e-01 -2.90907752e-02 -9.64561701e-01 2.62266457e-01 -2.90907808e-02 -9.63618279e-01 2.65699774e-01 -2.90907770e-02 -9.62701857e-01 2.69004703e-01 -2.90907752e-02 -9.61792529e-01 2.72240698e-01 -2.90907770e-02 -9.60813880e-01 2.75684178e-01 -2.90907845e-02 -9.59808290e-01 2.79150277e-01 -2.90907770e-02 -9.58839953e-01 2.82458156e-01 -2.90907752e-02 -9.57859874e-01 2.85771757e-01 -2.90907770e-02 -9.56858397e-01 2.89103687e-01 -2.90907808e-02 -9.55854833e-01 2.92396367e-01 -2.90907752e-02 -9.54836369e-01 2.95730442e-01 -2.90907864e-02 -9.53759134e-01 2.99165428e-01 -2.90907752e-02 -9.52731967e-01 3.02414000e-01 -2.90907752e-02 -9.51681912e-01 3.05726171e-01 -2.90907845e-02 -9.50584114e-01 3.09106857e-01 -2.90907770e-02 -9.49490130e-01 3.12451184e-01 -2.90907770e-02 -9.48400259e-01 3.15747142e-01 -2.90907789e-02 -9.47293937e-01 3.19053769e-01 -2.90907770e-02 -9.46193099e-01 3.22287410e-01 -2.90907752e-02 -9.45101082e-01 3.25493842e-01 -2.90907770e-02 -9.43927944e-01 3.28880817e-01 -2.90907826e-02 -9.42745626e-01 3.32250714e-01 -2.90907789e-02 -9.41607893e-01 3.35458487e-01 -2.90907752e-02 -9.40432906e-01 3.38746995e-01 -2.90907826e-02 -9.39207613e-01 3.42125267e-01 -2.90907770e-02 -9.38005269e-01 3.45386744e-01 -2.90907789e-02 -9.36796486e-01 3.48646015e-01 -2.90907789e-02 -9.35596347e-01 3.51845235e-01 -2.90907752e-02 -9.34414506e-01 3.54995281e-01 -2.90907808e-02 -9.33147311e-01 3.58345836e-01 -2.90907845e-02 -9.31835353e-01 3.61715555e-01 -2.90907808e-02 -9.30572510e-01 3.64957064e-01 -2.90907789e-02 -9.29290056e-01 3.68212402e-01 -2.90907789e-02 -9.28000450e-01 3.71449471e-01 -2.90907789e-02 -9.26697373e-01 3.74688208e-01 -2.90907789e-02 -9.25391734e-01 3.77905130e-01 -2.90907789e-02 -9.24068451e-01 3.81119668e-01 -2.90907789e-02 -9.22758639e-01 3.84280652e-01 -2.90907752e-02 -9.21456814e-01 3.87396961e-01 -2.90907789e-02 -9.20064628e-01 3.90696377e-01 -2.90907845e-02 -9.18655992e-01 3.93991530e-01 -2.90907808e-02 -9.17293310e-01 3.97147894e-01 -2.90907752e-02 -9.15922642e-01 4.00316566e-01 -2.90907845e-02 -9.14515615e-01 4.03506309e-01 -2.90907770e-02 -9.13119137e-01 4.06664044e-01 -2.90907826e-02 -9.11665142e-01 4.09918219e-01 -2.90907845e-02 -9.10203218e-01 4.13149178e-01 -2.90907808e-02 -9.08781886e-01 4.16252345e-01 -2.90907752e-02 -9.07342255e-01 4.19399023e-01 -2.90907864e-02 -9.05833244e-01 4.22640800e-01 -2.90907808e-02 -9.04362440e-01 4.25775796e-01 -2.90907789e-02 -9.02878463e-01 4.28921044e-01 -2.90907826e-02 -9.01381254e-01 4.32049364e-01 -2.90907770e-02 -8.99904907e-01 4.35124904e-01 -2.90907770e-02 -8.98363709e-01 4.38307762e-01 -2.90907864e-02 -8.96784544e-01 4.41520542e-01 -2.90907826e-02 -8.95247519e-01 4.44629818e-01 -2.90907808e-02 -8.93684864e-01 4.47760850e-01 -2.90907826e-02 -8.92115772e-01 4.50880170e-01 -2.90907808e-02 -8.90577078e-01 4.53905344e-01 -2.90907752e-02 -8.89036357e-01 4.56920236e-01 -2.90907789e-02 -8.87396336e-01 4.60100710e-01 -2.90907845e-02 -8.85745704e-01 4.63270932e-01 -2.90907808e-02 -8.84158552e-01 4.66284811e-01 -2.90907752e-02 -8.82536292e-01 4.69356507e-01 -2.90907845e-02 -8.80846620e-01 4.72516268e-01 -2.90907808e-02 -8.79194200e-01 4.75582838e-01 -2.90907808e-02 -8.77531290e-01 4.78652060e-01 -2.90907826e-02 -8.75842512e-01 4.81730431e-01 -2.90907826e-02 -8.74201119e-01 4.84690160e-01 -2.90907770e-02 -8.72520685e-01 4.87721980e-01 -2.90907845e-02 -8.70774686e-01 4.90832657e-01 -2.90907826e-02 -8.69038582e-01 4.93896216e-01 -2.90907808e-02 -8.67316306e-01 4.96916264e-01 -2.90907808e-02 -8.65591705e-01 4.99916136e-01 -2.90907808e-02 -8.63835990e-01 5.02939224e-01 -2.90907789e-02 -8.62081528e-01 5.05945086e-01 -2.90907826e-02 -8.60308349e-01 5.08950412e-01 -2.90907808e-02 -8.58567655e-01 5.11876762e-01 -2.90907752e-02 -8.56803715e-01 5.14833391e-01 -2.90907826e-02 -8.54959965e-01 5.17886221e-01 -2.90907826e-02 -8.53120089e-01 5.20910263e-01 -2.90907770e-02 -8.51288080e-01 5.23896098e-01 -2.90907808e-02 -8.49449694e-01 5.26875734e-01 -2.90907789e-02 -8.47612619e-01 5.29824078e-01 -2.90907789e-02 -8.45795810e-01 5.32716095e-01 -2.90907752e-02 -8.43941212e-01 5.35660565e-01 -2.90907882e-02 -8.42014909e-01 5.38678527e-01 -2.90907826e-02 -8.40176702e-01 5.41533172e-01 -2.90907752e-02 -8.38290215e-01 5.44458568e-01 -2.90907864e-02 -8.36350203e-01 5.47426939e-01 -2.90907789e-02 -8.34436059e-01 5.50345719e-01 -2.90907826e-02 -8.32483172e-01 5.53290188e-01 -2.90907808e-02 -8.30551028e-01 5.56191504e-01 -2.90907826e-02 -8.28659415e-01 5.59000254e-01 -2.90907752e-02 -8.26707423e-01 5.61891794e-01 -2.90907864e-02 -8.24677706e-01 5.64860284e-01 -2.90907789e-02 -8.22698295e-01 5.67741334e-01 -2.90907808e-02 -8.20764601e-01 5.70526123e-01 -2.90907752e-02 -8.18785429e-01 5.73369682e-01 -2.90907845e-02 -8.16735923e-01 5.76283574e-01 -2.90907770e-02 -8.14707398e-01 5.79150259e-01 -2.90907845e-02 -8.12651753e-01 5.82026601e-01 -2.90907752e-02 -8.10677528e-01 5.84764183e-01 -2.90907752e-02 -8.08688462e-01 5.87525845e-01 -2.90907808e-02 -8.06562185e-01 5.90439498e-01 -2.90907826e-02 -8.04445684e-01 5.93321443e-01 -2.90907808e-02 -8.02355647e-01 5.96141100e-01 -2.90907789e-02 -8.00268650e-01 5.98940432e-01 -2.90907808e-02 -7.98186064e-01 6.01713777e-01 -2.90907789e-02 -7.96088934e-01 6.04487717e-01 -2.90907808e-02 -7.93977857e-01 6.07254624e-01 -2.90907789e-02 -7.91860282e-01 6.10010564e-01 -2.90907752e-02 -7.89754748e-01 6.12727761e-01 -2.90907752e-02 -7.87633359e-01 6.15465999e-01 -2.90907864e-02 -7.85392046e-01 6.18319511e-01 -2.90907789e-02 -7.83240438e-01 6.21042788e-01 -2.90907789e-02 -7.81068027e-01 6.23776734e-01 -2.90907808e-02 -7.78869569e-01 6.26515985e-01 -2.90907789e-02 -7.76691437e-01 6.29212558e-01 -2.90907770e-02 -7.74559259e-01 6.31824493e-01 -2.90907752e-02 -7.72376001e-01 6.34508491e-01 -2.90907826e-02 -7.70064533e-01 6.37305498e-01 -2.90907770e-02 -7.67907619e-01 6.39896214e-01 -2.90907752e-02 -7.65674472e-01 6.42580330e-01 -2.90907864e-02 -7.63364315e-01 6.45316362e-01 -2.90907752e-02 -7.61124969e-01 6.47955596e-01 -2.90907789e-02 -7.58822143e-01 6.50654018e-01 -2.90907808e-02 -7.56551385e-01 6.53290629e-01 -2.90907752e-02 -7.54338801e-01 6.55844152e-01 -2.90907770e-02 -7.52027094e-01 6.58499300e-01 -2.90907864e-02 -7.49645531e-01 6.61205769e-01 -2.90907808e-02 -7.47318685e-01 6.63835108e-01 -2.90907808e-02 -7.45013893e-01 6.66417241e-01 -2.90907752e-02 -7.42655933e-01 6.69043362e-01 -2.90907770e-02 -7.40339041e-01 6.71612322e-01 -2.90907789e-02 -7.37995505e-01 6.74181879e-01 -2.90907789e-02 -7.35643208e-01 6.76751137e-01 -2.90907789e-02 -7.33348429e-01 6.79229498e-01 -2.90907752e-02 -7.30941296e-01 6.81829810e-01 -2.90907845e-02 -7.28497028e-01 6.84437335e-01 -2.90907808e-02 -7.26103306e-01 6.86974049e-01 -2.90907808e-02 -7.23697424e-01 6.89510286e-01 -2.90907808e-02 -7.21290529e-01 6.92019641e-01 -2.90907770e-02 -7.18883038e-01 6.94535136e-01 -2.90907789e-02 -7.16493309e-01 6.96994364e-01 -2.90907733e-02 -7.14078844e-01 6.99472666e-01 -2.90907845e-02 -7.11559355e-01 7.02034295e-01 -2.90907808e-02 -7.09156215e-01 7.04456389e-01 -2.90907752e-02 -7.06712186e-01 7.06901133e-01 -2.90907864e-02 -7.04165518e-01 7.09453046e-01 -2.90907808e-02 -7.01692343e-01 7.11898565e-01 -2.90907808e-02 -6.99198306e-01 7.14343369e-01 -2.90907789e-02 -6.96723223e-01 7.16761529e-01 -2.90907789e-02 -6.94295287e-01 7.19111025e-01 -2.90907770e-02 -6.91761911e-01 7.21544266e-01 -2.90907864e-02 -6.89160466e-01 7.24032938e-01 -2.90907789e-02 -6.86627269e-01 7.26432204e-01 -2.90907826e-02 -6.84086680e-01 7.28824019e-01 -2.90907808e-02 -6.81545556e-01 7.31200635e-01 -2.90907826e-02 -6.78990483e-01 7.33575046e-01 -2.90907808e-02 -6.76412642e-01 7.35958517e-01 -2.90907826e-02 -6.73834801e-01 7.38314509e-01 -2.90907826e-02 -6.71263337e-01 7.40655780e-01 -2.90907808e-02 -6.68736160e-01 7.42932081e-01 -2.90907752e-02 -6.66164935e-01 7.45246470e-01 -2.90907864e-02 -6.63486600e-01 7.47627079e-01 -2.90907770e-02 -6.60854816e-01 7.49955416e-01 -2.90907808e-02 -6.58233941e-01 7.52254426e-01 -2.90907789e-02 -6.55598044e-01 7.54554689e-01 -2.90907808e-02 -6.53026581e-01 7.56778240e-01 -2.90907752e-02 -6.50369346e-01 7.59067416e-01 -2.90907826e-02 -6.47668898e-01 7.61372030e-01 -2.90907808e-02 -6.45063579e-01 7.63577998e-01 -2.90907770e-02 -6.42421663e-01 7.65806854e-01 -2.90907864e-02 -6.39657676e-01 7.68113911e-01 -2.90907789e-02 -6.36962056e-01 7.70348668e-01 -2.90907789e-02 -6.34287179e-01 7.72558689e-01 -2.90907826e-02 -6.31656587e-01 7.74701595e-01 -2.90907752e-02 -6.28955185e-01 7.76907325e-01 -2.90907864e-02 -6.26148999e-01 7.79164016e-01 -2.90907789e-02 -6.23490989e-01 7.81289220e-01 -2.90907752e-02 -6.20755374e-01 7.83472776e-01 -2.90907864e-02 -6.18006468e-01 7.85634518e-01 -2.90907752e-02 -6.15297139e-01 7.87767410e-01 -2.90907864e-02 -6.12456262e-01 7.89974689e-01 -2.90907808e-02 -6.09756231e-01 7.92055607e-01 -2.90907752e-02 -6.07036710e-01 7.94149876e-01 -2.90907864e-02 -6.04207695e-01 7.96296537e-01 -2.90907752e-02 -6.01453245e-01 7.98387825e-01 -2.90907864e-02 -5.98642468e-01 8.00489247e-01 -2.90907752e-02 -5.95855415e-01 8.02572906e-01 -2.90907864e-02 -5.92958093e-01 8.04711461e-01 -2.90907808e-02 -5.90151489e-01 8.06773543e-01 -2.90907808e-02 -5.87411940e-01 8.08765531e-01 -2.90907752e-02 -5.84645927e-01 8.10772717e-01 -2.90907845e-02 -5.81720769e-01 8.12875628e-01 -2.90907826e-02 -5.78901649e-01 8.14881325e-01 -2.90907752e-02 -5.76078355e-01 8.16884875e-01 -2.90907826e-02 -5.73214710e-01 8.18888664e-01 -2.90907752e-02 -5.70371866e-01 8.20878327e-01 -2.90907864e-02 -5.67421734e-01 8.22919369e-01 -2.90907808e-02 -5.64540982e-01 8.24896932e-01 -2.90907789e-02 -5.61725736e-01 8.26811016e-01 -2.90907752e-02 -5.58917463e-01 8.28717291e-01 -2.90907789e-02 -5.55940330e-01 8.30718815e-01 -2.90907826e-02 -5.53040326e-01 8.32640707e-01 -2.90907752e-02 -5.50135076e-01 8.34573805e-01 -2.90907808e-02 -5.47209263e-01 8.36489618e-01 -2.90907752e-02 -5.44327259e-01 8.38372469e-01 -2.90907808e-02 -5.41321635e-01 8.40313315e-01 -2.90907752e-02 -5.38350821e-01 8.42220426e-01 -2.90907770e-02 -5.35408139e-01 8.44093800e-01 -2.90907770e-02 -5.32436788e-01 8.45973372e-01 -2.90907789e-02 -5.29480100e-01 8.47825050e-01 -2.90907770e-02 -5.26604295e-01 8.49611938e-01 -2.90907752e-02 -5.23642600e-01 8.51447165e-01 -2.90907826e-02 -5.20555258e-01 8.53338063e-01 -2.90907808e-02 -5.17553270e-01 8.55159223e-01 -2.90907789e-02 -5.14653206e-01 8.56903553e-01 -2.90907752e-02 -5.11668682e-01 8.58697653e-01 -2.90907845e-02 -5.08585572e-01 8.60522807e-01 -2.90907975e-02 -5.05655229e-01 8.62244189e-01 -2.90907752e-02 -5.02670050e-01 8.63994122e-01 -2.90907808e-02 -4.99612749e-01 8.65759254e-01 -2.90907752e-02 -4.96631145e-01 8.67479563e-01 -2.90907826e-02 -4.93489772e-01 8.69266808e-01 -2.90907752e-02 -4.90498632e-01 8.70958567e-01 -2.90907752e-02 -4.87547100e-01 8.72609019e-01 -2.90907752e-02 -4.84465986e-01 8.74331594e-01 -2.90907845e-02 -4.81321037e-01 8.76063943e-01 -2.90907752e-02 -4.78364557e-01 8.77681077e-01 -2.90907752e-02 -4.75287884e-01 8.79358470e-01 -2.90907882e-02 -4.72204149e-01 8.81009996e-01 -2.90907752e-02 -4.69155461e-01 8.82641971e-01 -2.90907808e-02 -4.66056108e-01 8.84279490e-01 -2.90907752e-02 -4.62977916e-01 8.85898292e-01 -2.90907826e-02 -4.59830314e-01 8.87533605e-01 -2.90907789e-02 -4.56710577e-01 8.89143407e-01 -2.90907770e-02 -4.53605294e-01 8.90730441e-01 -2.90907770e-02 -4.50549573e-01 8.92278075e-01 -2.90907752e-02 -4.47458595e-01 8.93836319e-01 -2.90907808e-02 -4.44256514e-01 8.95430028e-01 -2.90907770e-02 -4.41126078e-01 8.96974742e-01 -2.90907752e-02 -4.38042134e-01 8.98483634e-01 -2.90907752e-02 -4.34928596e-01 9.00001705e-01 -2.90907826e-02 -4.31699663e-01 9.01549518e-01 -2.90907770e-02 -4.28546101e-01 9.03053701e-01 -2.90907770e-02 -4.25413489e-01 9.04532731e-01 -2.90907752e-02 -4.22297120e-01 9.05989945e-01 -2.90907752e-02 -4.19137329e-01 9.07460988e-01 -2.90907826e-02 -4.15898442e-01 9.08947706e-01 -2.90907789e-02 -4.12708730e-01 9.10400569e-01 -2.90907770e-02 -4.09634143e-01 9.11785305e-01 -2.90907752e-02 -4.06490356e-01 9.13198054e-01 -2.90907826e-02 -4.03193980e-01 9.14654970e-01 -2.90907789e-02 -4.00062680e-01 9.16028440e-01 -2.90907752e-02 -3.96849543e-01 9.17427361e-01 -2.90907826e-02 -3.93622428e-01 9.18807030e-01 -2.90907752e-02 -3.90513897e-01 9.20140088e-01 -2.90907789e-02 -3.87290776e-01 9.21501875e-01 -2.90907770e-02 -3.84041041e-01 9.22863245e-01 -2.90907826e-02 -3.80715340e-01 9.24233019e-01 -2.90907752e-02 -3.77498388e-01 9.25556123e-01 -2.90907789e-02 -3.74239534e-01 9.26878512e-01 -2.90907770e-02 -3.71073544e-01 9.28147554e-01 -2.90907752e-02 -3.67829204e-01 9.29443955e-01 -2.90907808e-02 -3.64534885e-01 9.30739939e-01 -2.90907789e-02 -3.61271918e-01 9.32001889e-01 -2.90907733e-02 -3.58109117e-01 9.33231950e-01 -2.90907752e-02 -3.54857951e-01 9.34468746e-01 -2.90907826e-02 -3.51525158e-01 9.35720325e-01 -2.90907789e-02 -3.48249882e-01 9.36942101e-01 -2.90907770e-02 -3.45061600e-01 9.38118815e-01 -2.90907752e-02 -3.41866314e-01 9.39300597e-01 -2.90907752e-02 -3.38509142e-01 9.40515518e-01 -2.90907808e-02 -3.35213542e-01 9.41693962e-01 -2.90907752e-02 -3.31968904e-01 9.42845225e-01 -2.90907789e-02 -3.28654379e-01 9.43999767e-01 -2.90907752e-02 -3.25369388e-01 9.45145071e-01 -2.90907826e-02 -3.22031796e-01 9.46281672e-01 -2.90907752e-02 -3.18768352e-01 9.47388709e-01 -2.90907752e-02 -3.15456092e-01 9.48498070e-01 -2.90907826e-02 -3.12110662e-01 9.49599266e-01 -2.90907752e-02 -3.08799177e-01 9.50688422e-01 -2.90907845e-02 -3.05486321e-01 9.51753199e-01 -2.90907752e-02 -3.02169234e-01 9.52816546e-01 -2.90907826e-02 -2.98773885e-01 9.53880191e-01 -2.90907752e-02 -2.95437455e-01 9.54921246e-01 -2.90907975e-02 -2.92092115e-01 9.55950022e-01 -2.90907770e-02 -2.88774252e-01 9.56956327e-01 -2.90907770e-02 -2.85426766e-01 9.57961619e-01 -2.90907770e-02 -2.82093197e-01 9.58949447e-01 -2.90907770e-02 -2.78763235e-01 9.59922791e-01 -2.90907789e-02 -2.75460273e-01 9.60873485e-01 -2.90907752e-02 -2.72095740e-01 9.61835742e-01 -2.90907808e-02 -2.68669516e-01 9.62795317e-01 -2.90907770e-02 -2.65323848e-01 9.63722110e-01 -2.90907770e-02 -2.62006134e-01 9.64630127e-01 -2.90907752e-02 -2.58718431e-01 9.65518475e-01 -2.90907770e-02 -2.55292952e-01 9.66431201e-01 -2.90907826e-02 -2.51914263e-01 9.67313647e-01 -2.90907733e-02 -2.48552874e-01 9.68186557e-01 -2.90907808e-02 -2.45169252e-01 9.69042301e-01 -2.90907752e-02 -2.41770133e-01 9.69902635e-01 -2.90907845e-02 -2.38270000e-01 9.70767677e-01 -2.90907789e-02 -2.34973565e-01 9.71567988e-01 -2.90907752e-02 -2.31565565e-01 9.72392559e-01 -2.90907845e-02 -2.28180662e-01 9.73183513e-01 -2.90907752e-02 -2.24826887e-01 9.73972082e-01 -2.90907864e-02 -2.21406668e-01 9.74748254e-01 -2.90907733e-02 -2.18114868e-01 9.75493073e-01 -2.90907770e-02 -2.14582846e-01 9.76279795e-01 -2.90907864e-02 -2.11052239e-01 9.77046072e-01 -2.90907808e-02 -2.07649782e-01 9.77775037e-01 -2.90907808e-02 -2.04248771e-01 9.78491008e-01 -2.90907789e-02 -2.00946063e-01 9.79169846e-01 -2.90907752e-02 -1.97517678e-01 9.79872882e-01 -2.90907845e-02 -1.93961874e-01 9.80581164e-01 -2.90907789e-02 -1.90554813e-01 9.81248140e-01 -2.90907789e-02 -1.87110931e-01 9.81912494e-01 -2.90907808e-02 -1.83799937e-01 9.82530177e-01 -2.90907752e-02 -1.80377156e-01 9.83169198e-01 -2.90907808e-02 -1.76911116e-01 9.83800948e-01 -2.90907752e-02 -1.73496723e-01 9.84416485e-01 -2.90907864e-02 -1.69965610e-01 9.85023022e-01 -2.90907789e-02 -1.66617900e-01 9.85593557e-01 -2.90907752e-02 -1.63176343e-01 9.86173153e-01 -2.90907826e-02 -1.59717083e-01 9.86732483e-01 -2.90907752e-02 -1.56305403e-01 9.87286389e-01 -2.90907845e-02 -1.52737111e-01 9.87842202e-01 -2.90907789e-02 -1.49393678e-01 9.88348126e-01 -2.90907752e-02 -1.45924017e-01 9.88873184e-01 -2.90907845e-02 -1.42494231e-01 9.89366353e-01 -2.90907752e-02 -1.39038444e-01 9.89865005e-01 -2.90907826e-02 -1.35486573e-01 9.90355074e-01 -2.90907770e-02 -1.32078424e-01 9.90810990e-01 -2.90907752e-02 -1.28641531e-01 9.91270244e-01 -2.90907845e-02 -1.25085071e-01 9.91722643e-01 -2.90907789e-02 -1.21639490e-01 9.92149830e-01 -2.90907770e-02 -1.18268207e-01 9.92552102e-01 -2.90907752e-02 -1.14883274e-01 9.92953181e-01 -2.90907770e-02 -1.11324020e-01 9.93363798e-01 -2.90907826e-02 -1.07765056e-01 9.93751884e-01 -2.90907770e-02 -1.04279034e-01 9.94126022e-01 -2.90907789e-02 -1.00789465e-01 9.94483113e-01 -2.90907770e-02 -9.73975584e-02 9.94817972e-01 -2.90907752e-02 -9.39623788e-02 9.95155811e-01 -2.90907845e-02 -9.04895440e-02 9.95472312e-01 -2.90907752e-02 -8.70331973e-02 9.95787561e-01 -2.90907845e-02 -8.34295228e-02 9.96092141e-01 -2.90907789e-02 -8.00722688e-02 9.96365428e-01 -2.90907752e-02 -7.66190216e-02 9.96640086e-01 -2.90907826e-02 -7.30875880e-02 9.96900260e-01 -2.90907752e-02 -6.96186274e-02 9.97154653e-01 -2.90907845e-02 -6.60282373e-02 9.97395992e-01 -2.90907770e-02 -6.25409111e-02 9.97617960e-01 -2.90907752e-02 -5.90517595e-02 9.97834206e-01 -2.90907789e-02 -5.56716695e-02 9.98020887e-01 -2.90907752e-02 -5.21552302e-02 9.98218417e-01 -2.90907845e-02 -4.86877002e-02 9.98389363e-01 -2.90907752e-02 -4.53343615e-02 9.98549819e-01 -2.90907770e-02 -4.17210832e-02 9.98710275e-01 -2.90907826e-02 -3.81606184e-02 9.98850286e-01 -2.90907789e-02 -3.46621871e-02 9.98978257e-01 -2.90907789e-02 -3.11557055e-02 9.99094665e-01 -2.90907789e-02 -2.77526285e-02 9.99189138e-01 -2.90907752e-02 -2.43869107e-02 9.99284029e-01 -2.90907789e-02 -2.07902286e-02 9.99362648e-01 -2.90907826e-02 -1.71785206e-02 9.99434769e-01 -2.90907770e-02 -1.37197729e-02 9.99482095e-01 -2.90907789e-02 -1.03501473e-02 9.99519110e-01 -2.90907752e-02 -6.85018860e-03 9.99562502e-01 -2.90907808e-02 -3.31990817e-03 9.99574125e-01 -2.90907752e-02 1.27404390e-04 9.99582171e-01 -2.90907826e-02 3.70415137e-03 9.99577403e-01 -2.90907770e-02 7.11824419e-03 9.99552846e-01 -2.90907752e-02 1.05869230e-02 9.99523520e-01 -2.90907808e-02 1.40983518e-02 9.99474645e-01 -2.90907752e-02 1.75724961e-02 9.99431372e-01 -2.90907826e-02 2.10690387e-02 9.99353230e-01 -2.90907752e-02 2.44858824e-02 9.99280035e-01 -2.90907770e-02 2.80359369e-02 9.99189913e-01 -2.90907826e-02 3.16209868e-02 9.99079227e-01 -2.90907789e-02 3.51144858e-02 9.98962462e-01 -2.90907770e-02 3.85960676e-02 9.98833060e-01 -2.90907752e-02 4.19910550e-02 9.98696327e-01 -2.90907752e-02 4.54897471e-02 9.98544931e-01 -2.90907826e-02 4.90674861e-02 9.98374581e-01 -2.90907789e-02 5.25349788e-02 9.98195171e-01 -2.90907770e-02 5.59973083e-02 9.98009026e-01 -2.90907770e-02 5.93968853e-02 9.97810960e-01 -2.90907752e-02 6.28770813e-02 9.97600853e-01 -2.90907845e-02 6.64537102e-02 9.97366905e-01 -2.90907789e-02 6.99494258e-02 9.97128129e-01 -2.90907808e-02 7.34646693e-02 9.96877372e-01 -2.90907808e-02 7.68251270e-02 9.96619225e-01 -2.90907752e-02 8.02744851e-02 9.96352315e-01 -2.90907826e-02 8.38130713e-02 9.96054471e-01 -2.90907752e-02 8.72381777e-02 9.95767832e-01 -2.90907845e-02 9.08424035e-02 9.95443404e-01 -2.90907808e-02 9.42176059e-02 9.95121717e-01 -2.90907752e-02 9.76608098e-02 9.94798899e-01 -2.90907808e-02 1.01184264e-01 9.94441748e-01 -2.90907752e-02 1.04601532e-01 9.94093418e-01 -2.90907826e-02 1.08111255e-01 9.93711948e-01 -2.90907752e-02 1.11557350e-01 9.93338645e-01 -2.90907845e-02 1.15142532e-01 9.92923141e-01 -2.90907770e-02 1.18595138e-01 9.92516220e-01 -2.90907770e-02 1.22054450e-01 9.92099166e-01 -2.90907789e-02 1.25433102e-01 9.91678417e-01 -2.90907752e-02 1.28816053e-01 9.91243839e-01 -2.90907789e-02 1.32332042e-01 9.90783095e-01 -2.90907826e-02 1.35878220e-01 9.90300477e-01 -2.90907752e-02 1.39368147e-01 9.89814699e-01 -2.90907752e-02 1.42830610e-01 9.89320397e-01 -2.90907770e-02 1.46174505e-01 9.88828182e-01 -2.90907752e-02 1.49634674e-01 9.88317788e-01 -2.90907845e-02 1.53076828e-01 9.87786531e-01 -2.90907752e-02 1.56489179e-01 9.87255991e-01 -2.90907826e-02 1.60056010e-01 9.86680269e-01 -2.90907752e-02 1.63452819e-01 9.86122072e-01 -2.90907752e-02 1.66854888e-01 9.85557199e-01 -2.90907826e-02 1.70280710e-01 9.84964848e-01 -2.90907752e-02 1.73649818e-01 9.84382570e-01 -2.90907770e-02 1.77151054e-01 9.83761847e-01 -2.90907826e-02 1.80695146e-01 9.83109295e-01 -2.90907752e-02 1.84126362e-01 9.82475221e-01 -2.90907789e-02 1.87443987e-01 9.81845379e-01 -2.90907752e-02 1.90885231e-01 9.81185436e-01 -2.90907826e-02 1.94315687e-01 9.80509162e-01 -2.90907752e-02 1.97638348e-01 9.79846179e-01 -2.90907808e-02 2.01126799e-01 9.79139328e-01 -2.90907845e-02 2.04664141e-01 9.78402674e-01 -2.90907789e-02 2.08054051e-01 9.77688730e-01 -2.90907789e-02 2.11476803e-01 9.76955712e-01 -2.90907826e-02 2.14803740e-01 9.76223052e-01 -2.90907752e-02 2.18176141e-01 9.75483179e-01 -2.90907845e-02 2.21700072e-01 9.74680364e-01 -2.90907752e-02 2.25097284e-01 9.73905563e-01 -2.90907770e-02 2.28513464e-01 9.73110616e-01 -2.90907789e-02 2.31798485e-01 9.72329557e-01 -2.90907752e-02 2.35103831e-01 9.71542716e-01 -2.90907808e-02 2.38523722e-01 9.70703840e-01 -2.90907789e-02 2.41972566e-01 9.69852626e-01 -2.90907845e-02 2.45424971e-01 9.68981802e-01 -2.90907789e-02 2.48741329e-01 9.68135178e-01 -2.90907752e-02 2.52116024e-01 9.67267334e-01 -2.90907864e-02 2.55496085e-01 9.66375530e-01 -2.90907752e-02 2.58854866e-01 9.65485573e-01 -2.90907864e-02 2.62318373e-01 9.64548528e-01 -2.90907808e-02 2.65617907e-01 9.63639140e-01 -2.90907752e-02 2.68940687e-01 9.62723911e-01 -2.90907845e-02 2.72347569e-01 9.61758375e-01 -2.90907752e-02 2.75670111e-01 9.60819066e-01 -2.90907864e-02 2.79102713e-01 9.59821701e-01 -2.90907752e-02 2.82400966e-01 9.58856821e-01 -2.90907752e-02 2.85733938e-01 9.57875669e-01 -2.90907864e-02 2.89159477e-01 9.56840396e-01 -2.90907789e-02 2.92487592e-01 9.55831051e-01 -2.90907770e-02 2.95706183e-01 9.54838216e-01 -2.90907752e-02 2.98958451e-01 9.53828990e-01 -2.90907826e-02 3.02297324e-01 9.52775955e-01 -2.90907845e-02 3.05723399e-01 9.51681554e-01 -2.90907864e-02 3.09176058e-01 9.50565577e-01 -2.90907845e-02 3.12459320e-01 9.49490011e-01 -2.90907826e-02 3.15688133e-01 9.48417485e-01 -2.90907752e-02 3.18904728e-01 9.47347164e-01 -2.90907826e-02 3.22205395e-01 9.46226358e-01 -2.90907808e-02 3.25568080e-01 9.45078135e-01 -2.90907845e-02 3.28969061e-01 9.43896234e-01 -2.90907826e-02 3.32188964e-01 9.42765951e-01 -2.90907752e-02 3.35469455e-01 9.41610873e-01 -2.90907882e-02 3.38764727e-01 9.40421164e-01 -2.90907752e-02 3.42027456e-01 9.39247668e-01 -2.90907864e-02 3.45402569e-01 9.38003778e-01 -2.90907826e-02 3.48644912e-01 9.36796308e-01 -2.90907789e-02 3.51933271e-01 9.35569763e-01 -2.90907826e-02 3.55119675e-01 9.34364140e-01 -2.90907752e-02 3.58378351e-01 9.33135211e-01 -2.90907864e-02 3.61634195e-01 9.31863785e-01 -2.90907770e-02 3.64775300e-01 9.30644691e-01 -2.90907808e-02 3.68137360e-01 9.29321170e-01 -2.90907826e-02 3.71467084e-01 9.27993774e-01 -2.90907789e-02 3.74671489e-01 9.26702619e-01 -2.90907789e-02 3.77898067e-01 9.25394535e-01 -2.90907808e-02 3.81066918e-01 9.24089551e-01 -2.90907770e-02 3.84190559e-01 9.22801197e-01 -2.90907845e-02 3.87504488e-01 9.21416163e-01 -2.90907882e-02 3.90786588e-01 9.20024693e-01 -2.90907826e-02 3.93991172e-01 9.18656111e-01 -2.90907808e-02 3.97132546e-01 9.17301774e-01 -2.90907770e-02 4.00268584e-01 9.15943027e-01 -2.90907826e-02 4.03456360e-01 9.14540768e-01 -2.90907808e-02 4.06691819e-01 9.13109243e-01 -2.90907864e-02 4.09961909e-01 9.11644816e-01 -2.90907845e-02 4.13071573e-01 9.10235524e-01 -2.90907770e-02 4.16164815e-01 9.08825994e-01 -2.90907808e-02 4.19322908e-01 9.07374084e-01 -2.90907826e-02 4.22468901e-01 9.05914426e-01 -2.90907808e-02 4.25653428e-01 9.04419005e-01 -2.90907752e-02 4.28822607e-01 9.02923226e-01 -2.90907808e-02 4.32045162e-01 9.01383460e-01 -2.90907789e-02 4.35220450e-01 8.99860620e-01 -2.90907808e-02 4.38294291e-01 8.98366153e-01 -2.90907770e-02 4.41370130e-01 8.96858692e-01 -2.90907826e-02 4.44469810e-01 8.95325899e-01 -2.90907808e-02 4.47650850e-01 8.93743396e-01 -2.90907864e-02 4.50849861e-01 8.92132044e-01 -2.90907826e-02 4.53960836e-01 8.90552223e-01 -2.90907826e-02 4.56989974e-01 8.88997257e-01 -2.90907733e-02 4.60022569e-01 8.87429953e-01 -2.90907752e-02 4.63126749e-01 8.85821164e-01 -2.90907789e-02 4.66277122e-01 8.84168148e-01 -2.90907864e-02 4.69426274e-01 8.82498145e-01 -2.90907808e-02 4.72509295e-01 8.80852759e-01 -2.90907845e-02 4.75486249e-01 8.79243493e-01 -2.90907770e-02 4.78513032e-01 8.77607405e-01 -2.90907826e-02 4.81569499e-01 8.75930905e-01 -2.90907808e-02 4.84666109e-01 8.74221683e-01 -2.90907882e-02 4.87778187e-01 8.72488141e-01 -2.90907826e-02 4.90807176e-01 8.70783925e-01 -2.90907752e-02 4.93795186e-01 8.69100213e-01 -2.90907882e-02 4.96844828e-01 8.67355168e-01 -2.90907752e-02 4.99793500e-01 8.65661204e-01 -2.90907808e-02 5.02901733e-01 8.63863289e-01 -2.90907864e-02 5.05910099e-01 8.62099409e-01 -2.90907789e-02 5.08920789e-01 8.60330343e-01 -2.90907882e-02 5.11903048e-01 8.58552814e-01 -2.90907770e-02 5.14898121e-01 8.56767654e-01 -2.90907864e-02 5.17938972e-01 8.54926765e-01 -2.90907808e-02 5.20819128e-01 8.53177190e-01 -2.90907789e-02 5.23840547e-01 8.51328850e-01 -2.90907882e-02 5.26838243e-01 8.49473238e-01 -2.90907808e-02 5.29789090e-01 8.47639263e-01 -2.90907882e-02 5.32753587e-01 8.45773995e-01 -2.90907789e-02 5.35599530e-01 8.43975484e-01 -2.90907808e-02 5.38569689e-01 8.42085838e-01 -2.90907845e-02 5.41508079e-01 8.40195417e-01 -2.90907789e-02 5.44468105e-01 8.38285089e-01 -2.90907864e-02 5.47482193e-01 8.36319268e-01 -2.90907826e-02 5.50329745e-01 8.34442317e-01 -2.90907752e-02 5.53158224e-01 8.32568049e-01 -2.90907770e-02 5.56052804e-01 8.30640078e-01 -2.90907770e-02 5.58987260e-01 8.28666210e-01 -2.90907752e-02 5.61929822e-01 8.26668084e-01 -2.90907696e-02 5.64778984e-01 8.24725032e-01 -2.90907547e-02 5.67602575e-01 8.22785616e-01 -2.90907342e-02 5.70440233e-01 8.20818663e-01 -2.90907249e-02 5.73354483e-01 8.18786800e-01 -2.90907249e-02 5.76223254e-01 8.16771328e-01 -2.90907025e-02 5.79005241e-01 8.14801097e-01 -2.90906969e-02 5.81901133e-01 8.12734842e-01 -2.90906914e-02 5.84634542e-01 8.10772538e-01 -2.90905572e-02 5.87397873e-01 8.08773756e-01 -2.90905163e-02 5.90200782e-01 8.06732595e-01 -2.90905423e-02 5.92797637e-01 8.04825366e-01 -2.90905293e-02 5.96181810e-01 8.02321196e-01 -2.90905349e-02 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. 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. 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. 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. 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. 0. 7.22480178e-01 6.90779388e-01 -2.90905349e-02 7.24302411e-01 6.88867450e-01 -2.90905256e-02 7.26464868e-01 6.86584473e-01 -2.90905647e-02 7.28802562e-01 6.84100330e-01 -2.90906988e-02 7.31228948e-01 6.81505978e-01 -2.90907342e-02 7.33521879e-01 6.79038167e-01 -2.90907416e-02 7.35829711e-01 6.76538587e-01 -2.90907584e-02 7.38179147e-01 6.73972309e-01 -2.90907696e-02 7.40523219e-01 6.71397269e-01 -2.90907752e-02 7.42926717e-01 6.68746591e-01 -2.90907770e-02 7.45294333e-01 6.66101277e-01 -2.90907770e-02 7.47550845e-01 6.63565457e-01 -2.90907752e-02 7.49799550e-01 6.61028981e-01 -2.90907770e-02 7.52110958e-01 6.58398509e-01 -2.90907808e-02 7.54402697e-01 6.55772328e-01 -2.90907789e-02 7.56746233e-01 6.53070271e-01 -2.90907826e-02 7.59012759e-01 6.50428474e-01 -2.90907752e-02 7.61226296e-01 6.47839785e-01 -2.90907826e-02 7.63489306e-01 6.45172477e-01 -2.90907808e-02 7.65786827e-01 6.42445683e-01 -2.90907864e-02 7.68022597e-01 6.39765799e-01 -2.90907752e-02 7.70187378e-01 6.37159705e-01 -2.90907808e-02 7.72483587e-01 6.34383917e-01 -2.90907864e-02 7.74742484e-01 6.31614447e-01 -2.90907826e-02 7.76942909e-01 6.28906548e-01 -2.90907826e-02 7.79071152e-01 6.26263499e-01 -2.90907789e-02 7.81199276e-01 6.23612940e-01 -2.90907826e-02 7.83358395e-01 6.20893896e-01 -2.90907808e-02 7.85582960e-01 6.18087947e-01 -2.90907901e-02 7.87803113e-01 6.15249634e-01 -2.90907845e-02 7.89936364e-01 6.12506151e-01 -2.90907826e-02 7.92014003e-01 6.09812856e-01 -2.90907770e-02 7.94097543e-01 6.07103527e-01 -2.90907826e-02 7.96216071e-01 6.04321301e-01 -2.90907826e-02 7.98370361e-01 6.01476729e-01 -2.90907864e-02 8.00519705e-01 5.98606050e-01 -2.90907826e-02 8.02546322e-01 5.95883071e-01 -2.90907770e-02 8.04561853e-01 5.93161941e-01 -2.90907808e-02 8.06621432e-01 5.90357244e-01 -2.90907826e-02 8.08743656e-01 5.87453306e-01 -2.90907864e-02 8.10785830e-01 5.84619880e-01 -2.90907770e-02 8.12762320e-01 5.81880510e-01 -2.90907845e-02 8.14839184e-01 5.78970015e-01 -2.90907864e-02 8.16874981e-01 5.76089740e-01 -2.90907789e-02 8.18885982e-01 5.73231816e-01 -2.90907901e-02 8.20873201e-01 5.70368469e-01 -2.90907733e-02 8.22800636e-01 5.67596376e-01 -2.90907826e-02 8.24824572e-01 5.64655066e-01 -2.90907882e-02 8.26846182e-01 5.61683118e-01 -2.90907826e-02 8.28805029e-01 5.58790445e-01 -2.90907826e-02 8.30696881e-01 5.55966556e-01 -2.90907752e-02 8.32570791e-01 5.53161740e-01 -2.90907826e-02 8.34502757e-01 5.50244749e-01 -2.90907826e-02 8.36479068e-01 5.47239780e-01 -2.90907882e-02 8.38437319e-01 5.44228971e-01 -2.90907826e-02 8.40275168e-01 5.41379869e-01 -2.90907752e-02 8.42093945e-01 5.38551152e-01 -2.90907808e-02 8.43961596e-01 5.35621881e-01 -2.90907826e-02 8.45843613e-01 5.32649398e-01 -2.90907826e-02 8.47754359e-01 5.29605269e-01 -2.90907901e-02 8.49669695e-01 5.26523054e-01 -2.90908013e-02 8.51442099e-01 5.23642361e-01 -2.90907770e-02 8.53213906e-01 5.20763099e-01 -2.90907845e-02 8.55019927e-01 5.17786264e-01 -2.90907808e-02 8.56812716e-01 5.14813960e-01 -2.90907808e-02 8.58609557e-01 5.11815906e-01 -2.90907845e-02 8.60406816e-01 5.08787870e-01 -2.90907845e-02 8.62179577e-01 5.05773902e-01 -2.90907789e-02 8.63918483e-01 5.02800524e-01 -2.90907826e-02 8.65712285e-01 4.99710977e-01 -2.90907864e-02 8.67465079e-01 4.96649116e-01 -2.90907752e-02 8.69142413e-01 4.93718535e-01 -2.90907864e-02 8.70933414e-01 4.90558177e-01 -2.90907882e-02 8.72690558e-01 4.87416416e-01 -2.90907845e-02 8.74377191e-01 4.84378368e-01 -2.90907808e-02 8.76006424e-01 4.81427014e-01 -2.90907770e-02 8.77646148e-01 4.78437483e-01 -2.90907808e-02 8.79318297e-01 4.75355029e-01 -2.90907826e-02 8.80969703e-01 4.72286224e-01 -2.90907808e-02 8.82655501e-01 4.69136655e-01 -2.90907882e-02 8.84337962e-01 4.65952277e-01 -2.90907826e-02 8.85907292e-01 4.62953836e-01 -2.90907752e-02 8.87468994e-01 4.59956527e-01 -2.90907808e-02 8.89077723e-01 4.56844360e-01 -2.90907845e-02 8.90718639e-01 4.53636110e-01 -2.90907864e-02 8.92336726e-01 4.50441539e-01 -2.90907808e-02 8.93860519e-01 4.47401941e-01 -2.90907752e-02 8.95374417e-01 4.44371521e-01 -2.90907808e-02 8.96900177e-01 4.41286117e-01 -2.90907808e-02 8.98489296e-01 4.38044250e-01 -2.90907826e-02 9.00012910e-01 4.34899122e-01 -2.90907752e-02 9.01481450e-01 4.31846142e-01 -2.90907808e-02 9.03019607e-01 4.28625524e-01 -2.90907864e-02 9.04512227e-01 4.25457984e-01 -2.90907770e-02 9.05986190e-01 4.22324389e-01 -2.90907864e-02 9.07469571e-01 4.19111878e-01 -2.90907752e-02 9.08879697e-01 4.16049480e-01 -2.90907808e-02 9.10362780e-01 4.12801057e-01 -2.90907864e-02 9.11847055e-01 4.09509897e-01 -2.90907808e-02 9.13256586e-01 4.06352401e-01 -2.90907789e-02 9.14640665e-01 4.03220624e-01 -2.90907770e-02 9.16007400e-01 4.00114626e-01 -2.90907770e-02 9.17401612e-01 3.96901637e-01 -2.90907789e-02 9.18775022e-01 3.93711030e-01 -2.90907808e-02 9.20180798e-01 3.90425175e-01 -2.90907864e-02 9.21543956e-01 3.87183249e-01 -2.90907733e-02 9.22849298e-01 3.84072602e-01 -2.90907808e-02 9.24182832e-01 3.80850673e-01 -2.90907826e-02 9.25511122e-01 3.77612174e-01 -2.90907789e-02 9.26854014e-01 3.74308944e-01 -2.90907845e-02 9.28190887e-01 3.70977759e-01 -2.90907808e-02 9.29446280e-01 3.67812216e-01 -2.90907752e-02 9.30695534e-01 3.64655286e-01 -2.90907826e-02 9.31956112e-01 3.61397803e-01 -2.90907808e-02 9.33249950e-01 3.58076155e-01 -2.90907864e-02 9.34494019e-01 3.54781508e-01 -2.90907789e-02 9.35688496e-01 3.51610363e-01 -2.90907789e-02 9.36942577e-01 3.48266035e-01 -2.90907864e-02 9.38183844e-01 3.44908059e-01 -2.90907808e-02 9.39384460e-01 3.41651112e-01 -2.90907808e-02 9.40535486e-01 3.38442147e-01 -2.90907752e-02 9.41681623e-01 3.35264772e-01 -2.90907826e-02 9.42881048e-01 3.31879824e-01 -2.90907882e-02 9.44070399e-01 3.28470200e-01 -2.90907826e-02 9.45220530e-01 3.25153470e-01 -2.90907826e-02 9.46308911e-01 3.21952879e-01 -2.90907752e-02 9.47385848e-01 3.18781465e-01 -2.90907770e-02 9.48510528e-01 3.15422118e-01 -2.90907826e-02 9.49607372e-01 3.12101036e-01 -2.90907808e-02 9.50710475e-01 3.08738321e-01 -2.90907864e-02 9.51817691e-01 3.05299699e-01 -2.90907845e-02 9.52843487e-01 3.02072793e-01 -2.90907770e-02 9.53869879e-01 2.98825800e-01 -2.90907826e-02 9.54900026e-01 2.95510471e-01 -2.90907808e-02 9.55953479e-01 2.92097032e-01 -2.90907882e-02 9.56988811e-01 2.88674712e-01 -2.90907826e-02 9.57964838e-01 2.85415351e-01 -2.90907770e-02 9.58930731e-01 2.82164335e-01 -2.90907826e-02 9.59910929e-01 2.78805822e-01 -2.90907808e-02 9.60894167e-01 2.75404394e-01 -2.90907845e-02 9.61854279e-01 2.72026837e-01 -2.90907789e-02 9.62776899e-01 2.68745154e-01 -2.90907808e-02 9.63708878e-01 2.65382290e-01 -2.90907826e-02 9.64630365e-01 2.62018859e-01 -2.90907808e-02 9.65553343e-01 2.58595973e-01 -2.90907864e-02 9.66461062e-01 2.55170375e-01 -2.90907770e-02 9.67318714e-01 2.51903445e-01 -2.90907789e-02 9.68191028e-01 2.48534024e-01 -2.90907826e-02 9.69074547e-01 2.45060921e-01 -2.90907826e-02 9.69941735e-01 2.41603196e-01 -2.90907789e-02 9.70772266e-01 2.38250539e-01 -2.90907789e-02 9.71580088e-01 2.34934449e-01 -2.90907770e-02 9.72378969e-01 2.31611326e-01 -2.90907808e-02 9.73176777e-01 2.28229269e-01 -2.90907789e-02 9.74001706e-01 2.24691078e-01 -2.90907845e-02 9.74767447e-01 2.21313983e-01 -2.90907752e-02 9.75522637e-01 2.17989326e-01 -2.90907808e-02 9.76272523e-01 2.14582220e-01 -2.90907752e-02 9.77030873e-01 2.11120069e-01 -2.90907808e-02 9.77748752e-01 2.07758114e-01 -2.90907752e-02 9.78487849e-01 2.04275399e-01 -2.90907845e-02 9.79193091e-01 2.00845987e-01 -2.90907752e-02 9.79885876e-01 1.97461888e-01 -2.90907864e-02 9.80580986e-01 1.93966225e-01 -2.90907808e-02 9.81258810e-01 1.90506116e-01 -2.90907789e-02 9.81898069e-01 1.87168047e-01 -2.90907770e-02 9.82527137e-01 1.83852404e-01 -2.90907808e-02 9.83177066e-01 1.80344701e-01 -2.90907845e-02 9.83822882e-01 1.76811129e-01 -2.90907789e-02 9.84430611e-01 1.73399508e-01 -2.90907808e-02 9.85012412e-01 1.70006141e-01 -2.90907752e-02 9.85590398e-01 1.66664526e-01 -2.90907808e-02 9.86163735e-01 1.63226157e-01 -2.90907826e-02 9.86729860e-01 1.59774587e-01 -2.90907826e-02 9.87294793e-01 1.56263351e-01 -2.90907882e-02 9.87843037e-01 1.52737349e-01 -2.90907826e-02 9.88356173e-01 1.49356633e-01 -2.90907770e-02 9.88857687e-01 1.46025538e-01 -2.90907826e-02 9.89364207e-01 1.42551050e-01 -2.90907826e-02 9.89872932e-01 1.39002457e-01 -2.90907882e-02 9.90356624e-01 1.35490566e-01 -2.90907808e-02 9.90808964e-01 1.32090256e-01 -2.90907752e-02 9.91258144e-01 1.28717944e-01 -2.90907808e-02 9.91701543e-01 1.25262991e-01 -2.90907808e-02 9.92129028e-01 1.21827081e-01 -2.90907808e-02 9.92550671e-01 1.18338041e-01 -2.90907808e-02 9.92962062e-01 1.14848763e-01 -2.90907845e-02 9.93368328e-01 1.11298054e-01 -2.90907864e-02 9.93743777e-01 1.07851684e-01 -2.90907770e-02 9.94115829e-01 1.04401760e-01 -2.90907864e-02 9.94469523e-01 1.00912400e-01 -2.90907733e-02 9.94811416e-01 9.75254774e-02 -2.90907808e-02 9.95158792e-01 9.39750373e-02 -2.90907864e-02 9.95484173e-01 9.04126316e-02 -2.90907826e-02 9.95791733e-01 8.69551525e-02 -2.90907808e-02 9.96082425e-01 8.35388154e-02 -2.90907770e-02 9.96363759e-01 8.01343098e-02 -2.90907808e-02 9.96634424e-01 7.66784996e-02 -2.90907826e-02 9.96906698e-01 7.31081590e-02 -2.90907864e-02 9.97157753e-01 6.95400462e-02 -2.90907826e-02 9.97383475e-01 6.61731809e-02 -2.90907752e-02 9.97607768e-01 6.27810061e-02 -2.90907826e-02 9.97821867e-01 5.92671335e-02 -2.90907826e-02 9.98024046e-01 5.57958484e-02 -2.90907808e-02 9.98217285e-01 5.22319525e-02 -2.90907864e-02 9.98398244e-01 4.86437716e-02 -2.90907826e-02 9.98551011e-01 4.52588052e-02 -2.90907752e-02 9.98704493e-01 4.18787003e-02 -2.90907826e-02 9.98844504e-01 3.83949876e-02 -2.90907826e-02 9.98977542e-01 3.47785167e-02 -2.90907864e-02 9.99090135e-01 3.12838480e-02 -2.90907789e-02 9.99192655e-01 2.79218871e-02 -2.90907808e-02 9.99285817e-01 2.44026780e-02 -2.90907826e-02 9.99360859e-01 2.08995137e-02 -2.90907826e-02 9.99432564e-01 1.74406264e-02 -2.90907808e-02 9.99478698e-01 1.39551414e-02 -2.90907808e-02 9.99525964e-01 1.04411934e-02 -2.90907789e-02 9.99567330e-01 6.87309168e-03 -2.90907864e-02 9.99580681e-01 3.26668215e-03 -2.90907826e-02 9.99581337e-01 -1.98829439e-04 -2.90907808e-02 9.99579430e-01 -3.72107886e-03 -2.90907808e-02 9.99554276e-01 -7.11928401e-03 -2.90907752e-02 9.99526441e-01 -1.04888259e-02 -2.90907808e-02 9.99477923e-01 -1.39551796e-02 -2.90907789e-02 9.99433041e-01 -1.75805110e-02 -2.90907845e-02 9.99354839e-01 -2.11775433e-02 -2.90907808e-02 9.99277592e-01 -2.46457104e-02 -2.90907789e-02 9.99186695e-01 -2.80090403e-02 -2.90907770e-02 9.99087930e-01 -3.15062143e-02 -2.90907882e-02 9.98966336e-01 -3.50095518e-02 -2.90907752e-02 9.98843491e-01 -3.84214260e-02 -2.90907845e-02 9.98704135e-01 -4.19014208e-02 -2.90907808e-02 9.98548925e-01 -4.54630479e-02 -2.90907882e-02 9.98376966e-01 -4.90474142e-02 -2.90907808e-02 9.98198211e-01 -5.25384657e-02 -2.90907826e-02 9.98010516e-01 -5.59471324e-02 -2.90907752e-02 9.97819185e-01 -5.93277514e-02 -2.90907826e-02 9.97605324e-01 -6.27924427e-02 -2.90907826e-02 9.97377574e-01 -6.63660914e-02 -2.90907882e-02 9.97128367e-01 -6.99428692e-02 -2.90907808e-02 9.96876061e-01 -7.34885931e-02 -2.90907808e-02 9.96618688e-01 -7.68434405e-02 -2.90907752e-02 9.96357024e-01 -8.02149251e-02 -2.90907808e-02 9.96073544e-01 -8.36685151e-02 -2.90907808e-02 9.95765090e-01 -8.72784108e-02 -2.90907845e-02 9.95446801e-01 -9.07681063e-02 -2.90907752e-02 9.95142996e-01 -9.40872729e-02 -2.90907808e-02 9.94801879e-01 -9.76188332e-02 -2.90907770e-02 9.94460404e-01 -1.01054981e-01 -2.90907826e-02 9.94099975e-01 -1.04538731e-01 -2.90907826e-02 9.93722916e-01 -1.08072475e-01 -2.90907864e-02 9.93334949e-01 -1.11550219e-01 -2.90907752e-02 9.92950797e-01 -1.14929311e-01 -2.90907808e-02 9.92538333e-01 -1.18449993e-01 -2.90907845e-02 9.92112339e-01 -1.21936209e-01 -2.90907733e-02 9.91687298e-01 -1.25404105e-01 -2.90907864e-02 9.91225243e-01 -1.28955647e-01 -2.90907770e-02 9.90783513e-01 -1.32304475e-01 -2.90907770e-02 9.90317345e-01 -1.35789469e-01 -2.90907845e-02 9.89824295e-01 -1.39317796e-01 -2.90907770e-02 9.89337265e-01 -1.42703369e-01 -2.90907752e-02 9.88841414e-01 -1.46138310e-01 -2.90907845e-02 9.88316238e-01 -1.49615645e-01 -2.90907752e-02 9.87795055e-01 -1.53056353e-01 -2.90907845e-02 9.87245023e-01 -1.56515524e-01 -2.90907752e-02 9.86709476e-01 -1.59903601e-01 -2.90907845e-02 9.86132324e-01 -1.63393542e-01 -2.90907752e-02 9.85557437e-01 -1.66848958e-01 -2.90907808e-02 9.84955549e-01 -1.70351714e-01 -2.90907808e-02 9.84359980e-01 -1.73798785e-01 -2.90907826e-02 9.83761430e-01 -1.77136257e-01 -2.90907752e-02 9.83149350e-01 -1.80482060e-01 -2.90907808e-02 9.82516408e-01 -1.83913037e-01 -2.90907808e-02 9.81850803e-01 -1.87437296e-01 -2.90907864e-02 9.81175542e-01 -1.90934107e-01 -2.90907789e-02 9.80507076e-01 -1.94340080e-01 -2.90907826e-02 9.79834318e-01 -1.97687641e-01 -2.90907752e-02 9.79153991e-01 -2.01036811e-01 -2.90907789e-02 9.78446543e-01 -2.04447687e-01 -2.90907770e-02 9.77705359e-01 -2.07987353e-01 -2.90907845e-02 9.76979673e-01 -2.11357087e-01 -2.90907752e-02 9.76237774e-01 -2.14769408e-01 -2.90907864e-02 9.75475490e-01 -2.18183696e-01 -2.90907752e-02 9.74720597e-01 -2.21544847e-01 -2.90907826e-02 9.73934174e-01 -2.24963233e-01 -2.90907752e-02 9.73137975e-01 -2.28413209e-01 -2.90907845e-02 9.72335875e-01 -2.31781289e-01 -2.90907752e-02 9.71551716e-01 -2.35061273e-01 -2.90907808e-02 9.70699608e-01 -2.38557115e-01 -2.90907864e-02 9.69860554e-01 -2.41917372e-01 -2.90907752e-02 9.69007850e-01 -2.45333418e-01 -2.90907864e-02 9.68127489e-01 -2.48775110e-01 -2.90907770e-02 9.67279732e-01 -2.52042681e-01 -2.90907752e-02 9.66401160e-01 -2.55416244e-01 -2.90907845e-02 9.65484202e-01 -2.58838564e-01 -2.90907733e-02 9.64612305e-01 -2.62081832e-01 -2.90907808e-02 9.63663220e-01 -2.65551388e-01 -2.90907864e-02 9.62718546e-01 -2.68934995e-01 -2.90907752e-02 9.61787760e-01 -2.72269756e-01 -2.90907845e-02 9.60795045e-01 -2.75741607e-01 -2.90907789e-02 9.59847987e-01 -2.79001683e-01 -2.90907752e-02 9.58906531e-01 -2.82240361e-01 -2.90907808e-02 9.57897842e-01 -2.85656780e-01 -2.90907845e-02 9.56863403e-01 -2.89088726e-01 -2.90907826e-02 9.55835462e-01 -2.92477489e-01 -2.90907826e-02 9.54832911e-01 -2.95720488e-01 -2.90907752e-02 9.53830540e-01 -2.98943728e-01 -2.90907789e-02 9.52789009e-01 -3.02248806e-01 -2.90907789e-02 9.51697707e-01 -3.05674523e-01 -2.90907826e-02 9.50597584e-01 -3.09072673e-01 -2.90907808e-02 9.49519336e-01 -3.12367320e-01 -2.90907808e-02 9.48428810e-01 -3.15655917e-01 -2.90907752e-02 9.47368920e-01 -3.18830311e-01 -2.90907770e-02 9.46239531e-01 -3.22163492e-01 -2.90907770e-02 9.45090711e-01 -3.25525671e-01 -2.90907808e-02 9.43935215e-01 -3.28841597e-01 -2.90907752e-02 9.42786753e-01 -3.32142472e-01 -2.90907845e-02 9.41637993e-01 -3.35374236e-01 -2.90907752e-02 9.40451384e-01 -3.38699311e-01 -2.90907864e-02 9.39258218e-01 -3.41989458e-01 -2.90907770e-02 9.38055634e-01 -3.45262319e-01 -2.90907845e-02 9.36839044e-01 -3.48524004e-01 -2.90907752e-02 9.35651362e-01 -3.51712376e-01 -2.90907808e-02 9.34419394e-01 -3.54982555e-01 -2.90907808e-02 9.33156371e-01 -3.58324319e-01 -2.90907864e-02 9.31869745e-01 -3.61616194e-01 -2.90907752e-02 9.30619180e-01 -3.64854217e-01 -2.90907864e-02 9.29333746e-01 -3.68094712e-01 -2.90907752e-02 9.28063571e-01 -3.71303827e-01 -2.90907882e-02 9.26741838e-01 -3.74575377e-01 -2.90907770e-02 9.25481379e-01 -3.77684087e-01 -2.90907808e-02 9.24125016e-01 -3.80997151e-01 -2.90907882e-02 9.22774553e-01 -3.84241253e-01 -2.90907752e-02 9.21436787e-01 -3.87454033e-01 -2.90907882e-02 9.20028269e-01 -3.90773684e-01 -2.90907808e-02 9.18694675e-01 -3.93892169e-01 -2.90907752e-02 9.17357147e-01 -3.97008628e-01 -2.90907808e-02 9.15938437e-01 -4.00282115e-01 -2.90907864e-02 9.14497375e-01 -4.03555632e-01 -2.90907808e-02 9.13070917e-01 -4.06773835e-01 -2.90907826e-02 9.11673307e-01 -4.09885466e-01 -2.90907752e-02 9.10268962e-01 -4.12996560e-01 -2.90907789e-02 9.08848405e-01 -4.16113317e-01 -2.90907808e-02 9.07349646e-01 -4.19380218e-01 -2.90907845e-02 9.05858874e-01 -4.22586262e-01 -2.90907789e-02 9.04358447e-01 -4.25783455e-01 -2.90907770e-02 9.02893186e-01 -4.28881526e-01 -2.90907752e-02 9.01436031e-01 -4.31937665e-01 -2.90907808e-02 8.99919093e-01 -4.35102433e-01 -2.90907826e-02 8.98344159e-01 -4.38342839e-01 -2.90907826e-02 8.96804273e-01 -4.41476077e-01 -2.90907770e-02 8.95274282e-01 -4.44573671e-01 -2.90907808e-02 8.93717170e-01 -4.47688878e-01 -2.90907752e-02 8.92194688e-01 -4.50719893e-01 -2.90907770e-02 8.90628397e-01 -4.53805655e-01 -2.90907770e-02 8.88990760e-01 -4.57017809e-01 -2.90907864e-02 8.87381017e-01 -4.60114658e-01 -2.90907752e-02 8.85806799e-01 -4.63153720e-01 -2.90907808e-02 8.84196579e-01 -4.66216624e-01 -2.90907808e-02 8.82513225e-01 -4.69403267e-01 -2.90907864e-02 8.80876541e-01 -4.72452193e-01 -2.90907752e-02 8.79232049e-01 -4.75517273e-01 -2.90907826e-02 8.77537370e-01 -4.78632480e-01 -2.90907752e-02 8.75932217e-01 -4.81563032e-01 -2.90907789e-02 8.74226093e-01 -4.84652340e-01 -2.90907808e-02 8.72504592e-01 -4.87747163e-01 -2.90907826e-02 8.70781243e-01 -4.90812063e-01 -2.90907752e-02 8.69084656e-01 -4.93814647e-01 -2.90907808e-02 8.67343605e-01 -4.96862888e-01 -2.90907752e-02 8.65610600e-01 -4.99886096e-01 -2.90907864e-02 8.63824069e-01 -5.02958357e-01 -2.90907770e-02 8.62110138e-01 -5.05894244e-01 -2.90907808e-02 8.60362053e-01 -5.08857250e-01 -2.90907770e-02 8.58589172e-01 -5.11841655e-01 -2.90907770e-02 8.56752574e-01 -5.14921904e-01 -2.90907864e-02 8.54890883e-01 -5.18000901e-01 -2.90907845e-02 8.53111863e-01 -5.20920634e-01 -2.90907752e-02 8.51343989e-01 -5.23809373e-01 -2.90907826e-02 8.49511325e-01 -5.26778281e-01 -2.90907826e-02 8.47632766e-01 -5.29801071e-01 -2.90907882e-02 8.45722795e-01 -5.32837510e-01 -2.90907808e-02 8.43856573e-01 -5.35785854e-01 -2.90907808e-02 8.42046261e-01 -5.38624704e-01 -2.90907789e-02 8.40160728e-01 -5.41569829e-01 -2.90907864e-02 8.38199019e-01 -5.44594705e-01 -2.90907808e-02 8.36297154e-01 -5.47510684e-01 -2.90907826e-02 8.34378064e-01 -5.50431192e-01 -2.90907808e-02 8.32489908e-01 -5.53274333e-01 -2.90907752e-02 8.30629468e-01 -5.56072176e-01 -2.90907808e-02 8.28678071e-01 -5.58979213e-01 -2.90907826e-02 8.26669097e-01 -5.61945260e-01 -2.90907845e-02 8.24664831e-01 -5.64881206e-01 -2.90907808e-02 8.22677910e-01 -5.67771554e-01 -2.90907789e-02 8.20739090e-01 -5.70563734e-01 -2.90907752e-02 8.18746269e-01 -5.73425949e-01 -2.90907845e-02 8.16740811e-01 -5.76276481e-01 -2.90907770e-02 8.14733386e-01 -5.79115987e-01 -2.90907845e-02 8.12680602e-01 -5.81986785e-01 -2.90907733e-02 8.10690820e-01 -5.84753990e-01 -2.90907808e-02 8.08642149e-01 -5.87590694e-01 -2.90907826e-02 8.06596398e-01 -5.90388894e-01 -2.90907770e-02 8.04495513e-01 -5.93253911e-01 -2.90907826e-02 8.02343965e-01 -5.96160352e-01 -2.90907826e-02 8.00324380e-01 -5.98861039e-01 -2.90907752e-02 7.98257649e-01 -6.01626873e-01 -2.90907882e-02 7.96120644e-01 -6.04441941e-01 -2.90907752e-02 7.94023693e-01 -6.07201219e-01 -2.90907864e-02 7.91913092e-01 -6.09943867e-01 -2.90907770e-02 7.89822817e-01 -6.12651050e-01 -2.90907826e-02 7.87625670e-01 -6.15474880e-01 -2.90907845e-02 7.85424173e-01 -6.18281066e-01 -2.90907826e-02 7.83280313e-01 -6.20989025e-01 -2.90907752e-02 7.81166613e-01 -6.23652041e-01 -2.90907826e-02 7.78996110e-01 -6.26362026e-01 -2.90907826e-02 7.76757300e-01 -6.29141986e-01 -2.90907882e-02 7.74545193e-01 -6.31848574e-01 -2.90907752e-02 7.72383153e-01 -6.34496510e-01 -2.90907808e-02 7.70168543e-01 -6.37183905e-01 -2.90907808e-02 7.67961144e-01 -6.39844596e-01 -2.90907845e-02 7.65724242e-01 -6.42519355e-01 -2.90907826e-02 7.63400674e-01 -6.45280123e-01 -2.90907864e-02 7.61137843e-01 -6.47938430e-01 -2.90907752e-02 7.58944213e-01 -6.50511920e-01 -2.90907826e-02 7.56676078e-01 -6.53150797e-01 -2.90907826e-02 7.54356027e-01 -6.55829191e-01 -2.90907826e-02 7.52003789e-01 -6.58525109e-01 -2.90907845e-02 7.49664366e-01 -6.61186635e-01 -2.90907826e-02 7.47393131e-01 -6.63747847e-01 -2.90907770e-02 7.45132804e-01 -6.66289270e-01 -2.90907826e-02 7.42760599e-01 -6.68936253e-01 -2.90907864e-02 7.40427911e-01 -6.71510577e-01 -2.90907770e-02 7.38072515e-01 -6.74104691e-01 -2.90907864e-02 7.35706866e-01 -6.76680028e-01 -2.90907770e-02 7.33415961e-01 -6.79165423e-01 -2.90907826e-02 7.31049716e-01 -6.81710541e-01 -2.90907826e-02 7.28607059e-01 -6.84323013e-01 -2.90907864e-02 7.26197004e-01 -6.86871588e-01 -2.90907770e-02 7.23802149e-01 -6.89406276e-01 -2.90907845e-02 7.21389830e-01 -6.91912591e-01 -2.90907752e-02 7.18990028e-01 -6.94428205e-01 -2.90907845e-02 7.16537476e-01 -6.96946800e-01 -2.90907752e-02 7.14172304e-01 -6.99368596e-01 -2.90907733e-02 7.11662531e-01 -7.01920450e-01 -2.90907752e-02 7.09194958e-01 -7.04409301e-01 -2.90907566e-02 7.06740737e-01 -7.06863821e-01 -2.90907603e-02 7.04175770e-01 -7.09424734e-01 -2.90907491e-02 7.01783776e-01 -7.11796165e-01 -2.90907267e-02 6.99399292e-01 -7.14136779e-01 -2.90907230e-02 6.96895897e-01 -7.16581166e-01 -2.90906895e-02 6.94412827e-01 -7.18983114e-01 -2.90906336e-02 6.92030370e-01 -7.21281648e-01 -2.90905330e-02 6.89327419e-01 -7.23864794e-01 -2.90905256e-02 6.86919093e-01 -7.26150632e-01 -2.90905274e-02 6.84774041e-01 -7.28173852e-01 -2.90905293e-02 6.82251632e-01 -7.30538130e-01 -2.90905330e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.54948151e-01 -8.31376016e-01 -2.90905368e-02 5.52626014e-01 -8.32918286e-01 -2.90905982e-02 5.50063372e-01 -8.34611416e-01 -2.90907361e-02 5.47246873e-01 -8.36459696e-01 -2.90907640e-02 5.44277549e-01 -8.38397443e-01 -2.90907752e-02 5.41353583e-01 -8.40286613e-01 -2.90907733e-02 5.38488448e-01 -8.42130184e-01 -2.90907752e-02 5.35531759e-01 -8.44013274e-01 -2.90907752e-02 5.32591879e-01 -8.45874846e-01 -2.90907770e-02 5.29641330e-01 -8.47725153e-01 -2.90907789e-02 5.26674747e-01 -8.49573135e-01 -2.90907789e-02 5.23713231e-01 -8.51399541e-01 -2.90907789e-02 5.20747960e-01 -8.53222132e-01 -2.90907808e-02 5.17787158e-01 -8.55017424e-01 -2.90907808e-02 5.14774323e-01 -8.56839061e-01 -2.90907845e-02 5.11754870e-01 -8.58646154e-01 -2.90907864e-02 5.08732855e-01 -8.60436976e-01 -2.90907808e-02 5.05797446e-01 -8.62168491e-01 -2.90907826e-02 5.02788305e-01 -8.63927007e-01 -2.90907826e-02 4.99687374e-01 -8.65725696e-01 -2.90907864e-02 4.96670574e-01 -8.67455661e-01 -2.90907789e-02 4.93716985e-01 -8.69140625e-01 -2.90907826e-02 4.90709901e-01 -8.70846331e-01 -2.90907826e-02 4.87672567e-01 -8.72546256e-01 -2.90907808e-02 4.84608054e-01 -8.74250472e-01 -2.90907826e-02 4.81579840e-01 -8.75926495e-01 -2.90907845e-02 4.78513092e-01 -8.77605557e-01 -2.90907826e-02 4.75427419e-01 -8.79280090e-01 -2.90907826e-02 4.72375005e-01 -8.80924404e-01 -2.90907845e-02 4.69283789e-01 -8.82574797e-01 -2.90907845e-02 4.66180056e-01 -8.84218574e-01 -2.90907845e-02 4.63060379e-01 -8.85857701e-01 -2.90907882e-02 4.59944934e-01 -8.87472987e-01 -2.90907789e-02 4.56913322e-01 -8.89042556e-01 -2.90907845e-02 4.53784585e-01 -8.90642047e-01 -2.90907826e-02 4.50676501e-01 -8.92218828e-01 -2.90907826e-02 4.47554141e-01 -8.93789530e-01 -2.90907826e-02 4.44453597e-01 -8.95335078e-01 -2.90907826e-02 4.41339016e-01 -8.96875799e-01 -2.90907845e-02 4.38185364e-01 -8.98420095e-01 -2.90907826e-02 4.35055226e-01 -8.99940431e-01 -2.90907826e-02 4.31894392e-01 -9.01459694e-01 -2.90907845e-02 4.28695858e-01 -9.02987242e-01 -2.90907864e-02 4.25541252e-01 -9.04474735e-01 -2.90907808e-02 4.22333270e-01 -9.05984223e-01 -2.90907901e-02 4.19140488e-01 -9.07457471e-01 -2.90907770e-02 4.16083843e-01 -9.08864498e-01 -2.90907826e-02 4.12910074e-01 -9.10313070e-01 -2.90907826e-02 4.09738034e-01 -9.11745608e-01 -2.90907826e-02 4.06452388e-01 -9.13219154e-01 -2.90907901e-02 4.03229475e-01 -9.14638519e-01 -2.90907752e-02 4.00149822e-01 -9.15995717e-01 -2.90907845e-02 3.96953642e-01 -9.17382717e-01 -2.90907826e-02 3.93743634e-01 -9.18762386e-01 -2.90907826e-02 3.90476435e-01 -9.20160294e-01 -2.90907864e-02 3.87287408e-01 -9.21504855e-01 -2.90907808e-02 3.83997440e-01 -9.22885001e-01 -2.90907901e-02 3.80748570e-01 -9.24221337e-01 -2.90907770e-02 3.77659529e-01 -9.25494373e-01 -2.90907845e-02 3.74358952e-01 -9.26834702e-01 -2.90907864e-02 3.71040583e-01 -9.28167224e-01 -2.90907864e-02 3.67752552e-01 -9.29475129e-01 -2.90907826e-02 3.64565730e-01 -9.30727065e-01 -2.90907789e-02 3.61424357e-01 -9.31949258e-01 -2.90907864e-02 3.58164042e-01 -9.33216214e-01 -2.90907845e-02 3.54916364e-01 -9.34447110e-01 -2.90907826e-02 3.51658434e-01 -9.35673356e-01 -2.90907826e-02 3.48381668e-01 -9.36898768e-01 -2.90907845e-02 3.45094651e-01 -9.38116431e-01 -2.90907826e-02 3.41845840e-01 -9.39312816e-01 -2.90907826e-02 3.38572234e-01 -9.40494955e-01 -2.90907845e-02 3.35274756e-01 -9.41677928e-01 -2.90907826e-02 3.31913918e-01 -9.42869544e-01 -2.90907901e-02 3.28595310e-01 -9.44025397e-01 -2.90907789e-02 3.25314790e-01 -9.45167363e-01 -2.90907901e-02 3.21993709e-01 -9.46297169e-01 -2.90907789e-02 3.18769783e-01 -9.47392106e-01 -2.90907826e-02 3.15389723e-01 -9.48523581e-01 -2.90907882e-02 3.12054485e-01 -9.49620128e-01 -2.90907789e-02 3.08743954e-01 -9.50707793e-01 -2.90907882e-02 3.05415183e-01 -9.51778769e-01 -2.90907770e-02 3.02172244e-01 -9.52814758e-01 -2.90907845e-02 2.98873037e-01 -9.53855515e-01 -2.90907845e-02 2.95520872e-01 -9.54899728e-01 -2.90907845e-02 2.92202264e-01 -9.55921054e-01 -2.90907845e-02 2.88769186e-01 -9.56962407e-01 -2.90907864e-02 2.85331935e-01 -9.57992196e-01 -2.90907826e-02 2.82083333e-01 -9.58953619e-01 -2.90907789e-02 2.78726518e-01 -9.59939003e-01 -2.90907882e-02 2.75291771e-01 -9.60926294e-01 -2.90907826e-02 2.71940440e-01 -9.61879790e-01 -2.90907845e-02 2.68685967e-01 -9.62792754e-01 -2.90907770e-02 2.65385598e-01 -9.63707566e-01 -2.90907826e-02 2.62035728e-01 -9.64627445e-01 -2.90907826e-02 2.58653313e-01 -9.65537190e-01 -2.90907845e-02 2.55293965e-01 -9.66431201e-01 -2.90907826e-02 2.51933366e-01 -9.67315853e-01 -2.90907845e-02 2.48467058e-01 -9.68210876e-01 -2.90907864e-02 2.45084003e-01 -9.69067812e-01 -2.90907789e-02 2.41723269e-01 -9.69916403e-01 -2.90907882e-02 2.38316149e-01 -9.70756412e-01 -2.90907789e-02 2.34994859e-01 -9.71568406e-01 -2.90907845e-02 2.31526896e-01 -9.72404838e-01 -2.90907882e-02 2.28145838e-01 -9.73196030e-01 -2.90907789e-02 2.24748135e-01 -9.73990917e-01 -2.90907882e-02 2.21251026e-01 -9.74788010e-01 -2.90907826e-02 2.17938378e-01 -9.75532711e-01 -2.90907789e-02 2.14643329e-01 -9.76264119e-01 -2.90907845e-02 2.11231127e-01 -9.77007747e-01 -2.90907826e-02 2.07811534e-01 -9.77742016e-01 -2.90907845e-02 2.04291955e-01 -9.78487492e-01 -2.90907882e-02 2.00861067e-01 -9.79190469e-01 -2.90907752e-02 1.97557062e-01 -9.79865193e-01 -2.90907826e-02 1.94141850e-01 -9.80547965e-01 -2.90907845e-02 1.90701246e-01 -9.81223226e-01 -2.90907826e-02 1.87188745e-01 -9.81901407e-01 -2.90907901e-02 1.83740303e-01 -9.82546270e-01 -2.90907770e-02 1.80306539e-01 -9.83187497e-01 -2.90907901e-02 1.76859587e-01 -9.83814418e-01 -2.90907789e-02 1.73526838e-01 -9.84409392e-01 -2.90907845e-02 1.70101613e-01 -9.85001266e-01 -2.90907845e-02 1.66643038e-01 -9.85593796e-01 -2.90907826e-02 1.63107634e-01 -9.86187220e-01 -2.90907901e-02 1.59669757e-01 -9.86744046e-01 -2.90907770e-02 1.56322852e-01 -9.87284005e-01 -2.90907845e-02 1.52882189e-01 -9.87822235e-01 -2.90907845e-02 1.49430797e-01 -9.88348305e-01 -2.90907845e-02 1.45895243e-01 -9.88879561e-01 -2.90907864e-02 1.42430514e-01 -9.89379823e-01 -2.90907789e-02 1.38980836e-01 -9.89876449e-01 -2.90907882e-02 1.35411382e-01 -9.90369201e-01 -2.90907826e-02 1.32047921e-01 -9.90817726e-01 -2.90907770e-02 1.28698215e-01 -9.91262734e-01 -2.90907845e-02 1.25238925e-01 -9.91706431e-01 -2.90907826e-02 1.21792294e-01 -9.92134571e-01 -2.90907826e-02 1.18218310e-01 -9.92569983e-01 -2.90907901e-02 1.14732057e-01 -9.92972136e-01 -2.90907770e-02 1.11393400e-01 -9.93355989e-01 -2.90907845e-02 1.07923634e-01 -9.93737996e-01 -2.90907826e-02 1.04464136e-01 -9.94108260e-01 -2.90907845e-02 1.00886539e-01 -9.94479120e-01 -2.90907882e-02 9.74044502e-02 -9.94822502e-01 -2.90907789e-02 9.39534530e-02 -9.95161533e-01 -2.90907901e-02 9.04607996e-02 -9.95477021e-01 -2.90907770e-02 8.69935378e-02 -9.95792687e-01 -2.90907882e-02 8.34235400e-02 -9.96094286e-01 -2.90907826e-02 8.00062791e-02 -9.96372342e-01 -2.90907752e-02 7.65506104e-02 -9.96649742e-01 -2.90907901e-02 7.30534941e-02 -9.96905923e-01 -2.90907789e-02 6.96619153e-02 -9.97149944e-01 -2.90907845e-02 6.62117451e-02 -9.97387111e-01 -2.90907845e-02 6.27240166e-02 -9.97611582e-01 -2.90907826e-02 5.91344535e-02 -9.97833788e-01 -2.90907882e-02 5.56537546e-02 -9.98029768e-01 -2.90907789e-02 5.21875508e-02 -9.98220921e-01 -2.90907882e-02 4.86924425e-02 -9.98393118e-01 -2.90907789e-02 4.52216975e-02 -9.98561561e-01 -2.90907901e-02 4.16307785e-02 -9.98716056e-01 -2.90907845e-02 3.82268727e-02 -9.98847902e-01 -2.90907789e-02 3.48513313e-02 -9.98973370e-01 -2.90907826e-02 3.12725566e-02 -9.99093771e-01 -2.90907882e-02 2.77678147e-02 -9.99195099e-01 -2.90907789e-02 2.42771674e-02 -9.99292493e-01 -2.90907901e-02 2.07832456e-02 -9.99361336e-01 -2.90907770e-02 1.73888523e-02 -9.99435425e-01 -2.90907845e-02 1.38407554e-02 -9.99483228e-01 -2.90907901e-02 1.03193698e-02 -9.99526918e-01 -2.90907789e-02 6.93280529e-03 -9.99564588e-01 -2.90907826e-02 3.43665760e-03 -9.99581277e-01 -2.90907826e-02 -3.21903608e-05 -9.99583125e-01 -2.90907845e-02 -3.49652185e-03 -9.99582946e-01 -2.90907864e-02 -7.00198906e-03 -9.99565363e-01 -2.90907845e-02 -1.05765536e-02 -9.99531388e-01 -2.90907901e-02 -1.40825910e-02 -9.99475598e-01 -2.90907789e-02 -1.75592229e-02 -9.99436796e-01 -2.90907901e-02 -2.11564153e-02 -9.99356985e-01 -2.90907845e-02 -2.45588180e-02 -9.99279976e-01 -2.90907789e-02 -2.79331617e-02 -9.99192715e-01 -2.90907845e-02 -3.14019918e-02 -9.99089837e-01 -2.90907845e-02 -3.49902585e-02 -9.98973787e-01 -2.90907919e-02 -3.86037603e-02 -9.98838186e-01 -2.90907845e-02 -4.19876017e-02 -9.98698175e-01 -2.90907770e-02 -4.53652702e-02 -9.98552740e-01 -2.90907845e-02 -4.88744266e-02 -9.98388112e-01 -2.90907845e-02 -5.23518175e-02 -9.98209000e-01 -2.90907845e-02 -5.59029467e-02 -9.98020947e-01 -2.90907882e-02 -5.94203845e-02 -9.97811675e-01 -2.90907770e-02 -6.28790781e-02 -9.97604132e-01 -2.90907901e-02 -6.63916245e-02 -9.97372150e-01 -2.90907808e-02 -6.97789043e-02 -9.97141480e-01 -2.90907845e-02 -7.33272210e-02 -9.96891141e-01 -2.90907882e-02 -7.68209547e-02 -9.96623576e-01 -2.90907789e-02 -8.02874938e-02 -9.96355534e-01 -2.90907901e-02 -8.37742537e-02 -9.96063471e-01 -2.90907808e-02 -8.71556848e-02 -9.95775819e-01 -2.90907845e-02 -9.06446502e-02 -9.95463610e-01 -2.90907845e-02 -9.41110998e-02 -9.95143414e-01 -2.90907864e-02 -9.76657420e-02 -9.94803488e-01 -2.90907882e-02 -1.01132616e-01 -9.94451344e-01 -2.90907789e-02 -1.04586102e-01 -9.94098306e-01 -2.90907882e-02 -1.08140394e-01 -9.93714273e-01 -2.90907826e-02 -1.11534432e-01 -9.93337870e-01 -2.90907789e-02 -1.14912748e-01 -9.92954910e-01 -2.90907845e-02 -1.18371390e-01 -9.92547631e-01 -2.90907845e-02 -1.21846028e-01 -9.92127955e-01 -2.90907864e-02 -1.25386983e-01 -9.91691649e-01 -2.90907901e-02 -1.28867283e-01 -9.91236866e-01 -2.90907770e-02 -1.32230356e-01 -9.90798593e-01 -2.90907845e-02 -1.35689110e-01 -9.90330279e-01 -2.90907845e-02 -1.39135167e-01 -9.89853323e-01 -2.90907845e-02 -1.42683759e-01 -9.89350021e-01 -2.90907901e-02 -1.46129772e-01 -9.88840163e-01 -2.90907789e-02 -1.49576530e-01 -9.88328755e-01 -2.90907882e-02 -1.53016552e-01 -9.87798750e-01 -2.90907789e-02 -1.56373605e-01 -9.87274349e-01 -2.90907845e-02 -1.59823701e-01 -9.86722052e-01 -2.90907826e-02 -1.63257509e-01 -9.86161649e-01 -2.90907845e-02 -1.66817740e-01 -9.85566854e-01 -2.90907901e-02 -1.70252860e-01 -9.84972477e-01 -2.90907789e-02 -1.73586860e-01 -9.84398425e-01 -2.90907845e-02 -1.77037522e-01 -9.83783424e-01 -2.90907864e-02 -1.80451125e-01 -9.83157039e-01 -2.90907845e-02 -1.83977515e-01 -9.82509851e-01 -2.90907901e-02 -1.87417403e-01 -9.81853366e-01 -2.90907994e-02 -1.90748975e-01 -9.81211662e-01 -2.90907845e-02 -1.94164395e-01 -9.80543673e-01 -2.90907845e-02 -1.97675511e-01 -9.79844868e-01 -2.90907901e-02 -2.01088250e-01 -9.79143739e-01 -2.90907789e-02 -2.04420105e-01 -9.78456616e-01 -2.90907845e-02 -2.07847655e-01 -9.77735579e-01 -2.90907845e-02 -2.11330935e-01 -9.76990342e-01 -2.90907882e-02 -2.14765489e-01 -9.76233304e-01 -2.90907789e-02 -2.18064159e-01 -9.75508571e-01 -2.90907864e-02 -2.21481487e-01 -9.74736989e-01 -2.90907864e-02 -2.24895179e-01 -9.73953485e-01 -2.90907845e-02 -2.28398517e-01 -9.73144233e-01 -2.90908068e-02 -2.31790856e-01 -9.72334921e-01 -2.90907789e-02 -2.35075146e-01 -9.71549392e-01 -2.90907845e-02 -2.38472432e-01 -9.70719635e-01 -2.90907845e-02 -2.41849586e-01 -9.69882369e-01 -2.90907845e-02 -2.45300829e-01 -9.69016910e-01 -2.90907882e-02 -2.48725414e-01 -9.68141437e-01 -2.90907808e-02 -2.52120852e-01 -9.67267096e-01 -2.90907901e-02 -2.55488127e-01 -9.66379046e-01 -2.90907789e-02 -2.58832783e-01 -9.65493023e-01 -2.90907882e-02 -2.62308180e-01 -9.64553714e-01 -2.90907845e-02 -2.65588224e-01 -9.63649511e-01 -2.90907770e-02 -2.68934131e-01 -9.62728024e-01 -2.90907882e-02 -2.72298634e-01 -9.61776614e-01 -2.90907789e-02 -2.75559187e-01 -9.60849583e-01 -2.90907845e-02 -2.78906614e-01 -9.59883928e-01 -2.90907845e-02 -2.82256216e-01 -9.58902836e-01 -2.90907826e-02 -2.85578877e-01 -9.57920194e-01 -2.90907826e-02 -2.88924724e-01 -9.56914961e-01 -2.90907864e-02 -2.92276621e-01 -9.55895901e-01 -2.90907845e-02 -2.95696735e-01 -9.54849720e-01 -2.90907901e-02 -2.99032092e-01 -9.53801811e-01 -2.90907789e-02 -3.02372009e-01 -9.52754855e-01 -2.90907882e-02 -3.05699527e-01 -9.51688588e-01 -2.90907789e-02 -3.08913678e-01 -9.50650692e-01 -2.90907845e-02 -3.12335819e-01 -9.49534833e-01 -2.90907901e-02 -3.15635264e-01 -9.48438406e-01 -2.90907808e-02 -3.18941295e-01 -9.47338402e-01 -2.90907882e-02 -3.22250068e-01 -9.46211100e-01 -2.90907808e-02 -3.25467497e-01 -9.45111632e-01 -2.90907826e-02 -3.28819335e-01 -9.43950891e-01 -2.90907864e-02 -3.32112759e-01 -9.42797363e-01 -2.90907808e-02 -3.35424721e-01 -9.41626728e-01 -2.90907882e-02 -3.38718712e-01 -9.40439165e-01 -2.90907770e-02 -3.41992319e-01 -9.39262807e-01 -2.90907882e-02 -3.45278084e-01 -9.38046575e-01 -2.90907789e-02 -3.48460764e-01 -9.36868191e-01 -2.90907845e-02 -3.51785302e-01 -9.35629189e-01 -2.90908068e-02 -3.55044901e-01 -9.34395671e-01 -2.90907789e-02 -3.58317435e-01 -9.33160007e-01 -2.90907882e-02 -3.61658335e-01 -9.31860209e-01 -2.90907864e-02 -3.64826858e-01 -9.30623233e-01 -2.90907770e-02 -3.67983729e-01 -9.29384351e-01 -2.90907845e-02 -3.71222824e-01 -9.28093553e-01 -2.90907845e-02 -3.74479532e-01 -9.26784933e-01 -2.90907845e-02 -3.77787054e-01 -9.25444603e-01 -2.90907919e-02 -3.81039530e-01 -9.24101114e-01 -2.90907789e-02 -3.84169340e-01 -9.22809720e-01 -2.90907826e-02 -3.87362927e-01 -9.21473503e-01 -2.90907826e-02 -3.90583754e-01 -9.20112133e-01 -2.90907845e-02 -3.93884152e-01 -9.18705702e-01 -2.90907882e-02 -3.97091120e-01 -9.17319834e-01 -2.90907789e-02 -4.00282353e-01 -9.15941119e-01 -2.90907901e-02 -4.03494805e-01 -9.14523184e-01 -2.90907808e-02 -4.06603187e-01 -9.13148701e-01 -2.90907845e-02 -4.09860551e-01 -9.11694288e-01 -2.90907882e-02 -4.13055062e-01 -9.10243213e-01 -2.90907789e-02 -4.16191727e-01 -9.08818245e-01 -2.90907901e-02 -4.19365942e-01 -9.07351673e-01 -2.90907770e-02 -4.22455609e-01 -9.05922592e-01 -2.90907845e-02 -4.25613642e-01 -9.04443443e-01 -2.90907864e-02 -4.28873986e-01 -9.02906179e-01 -2.90907901e-02 -4.32007283e-01 -9.01402593e-01 -2.90907789e-02 -4.35069472e-01 -8.99936616e-01 -2.90907864e-02 -4.38290834e-01 -8.98373842e-01 -2.90907901e-02 -4.41510886e-01 -8.96789551e-01 -2.90907845e-02 -4.44559306e-01 -8.95282209e-01 -2.90907808e-02 -4.47601885e-01 -8.93767178e-01 -2.90907845e-02 -4.50711429e-01 -8.92204463e-01 -2.90907864e-02 -4.53836828e-01 -8.90616119e-01 -2.90907845e-02 -4.57025439e-01 -8.88986170e-01 -2.90907882e-02 -4.60103333e-01 -8.87390077e-01 -2.90907789e-02 -4.63117301e-01 -8.85827661e-01 -2.90907845e-02 -4.66219246e-01 -8.84198725e-01 -2.90907845e-02 -4.69291449e-01 -8.82570386e-01 -2.90907845e-02 -4.72456664e-01 -8.80885124e-01 -2.90907901e-02 -4.75525588e-01 -8.79223824e-01 -2.90907789e-02 -4.78572339e-01 -8.77577722e-01 -2.90907882e-02 -4.81656879e-01 -8.75881791e-01 -2.90907808e-02 -4.84690040e-01 -8.74209940e-01 -2.90907901e-02 -4.87824082e-01 -8.72463465e-01 -2.90907845e-02 -4.90796804e-01 -8.70794117e-01 -2.90907808e-02 -4.93822902e-01 -8.69085252e-01 -2.90907901e-02 -4.96846586e-01 -8.67357194e-01 -2.90907808e-02 -4.99806166e-01 -8.65655720e-01 -2.90907864e-02 -5.02902150e-01 -8.63865197e-01 -2.90907919e-02 -5.05920112e-01 -8.62094641e-01 -2.90907789e-02 -5.08928239e-01 -8.60327601e-01 -2.90907901e-02 -5.11921167e-01 -8.58542502e-01 -2.90907789e-02 -5.14896989e-01 -8.56767535e-01 -2.90907882e-02 -5.17899573e-01 -8.54950011e-01 -2.90907808e-02 -5.20879447e-01 -8.53146791e-01 -2.90907901e-02 -5.23942590e-01 -8.51264298e-01 -2.90907864e-02 -5.26829541e-01 -8.49478066e-01 -2.90907789e-02 -5.29699564e-01 -8.47694278e-01 -2.90907845e-02 -5.32753289e-01 -8.45781207e-01 -2.90907919e-02 -5.35770655e-01 -8.43870401e-01 -2.90907864e-02 -5.38714826e-01 -8.41993332e-01 -2.90907864e-02 -5.41576564e-01 -8.40152621e-01 -2.90907808e-02 -5.44433057e-01 -8.38308930e-01 -2.90907864e-02 -5.47364771e-01 -8.36394668e-01 -2.90907864e-02 -5.50273120e-01 -8.34485710e-01 -2.90907845e-02 -5.53166449e-01 -8.32568228e-01 -2.90907845e-02 -5.56065977e-01 -8.30636024e-01 -2.90907845e-02 -5.59043288e-01 -8.28640103e-01 -2.90907901e-02 -5.61970413e-01 -8.26650739e-01 -2.90907826e-02 -5.64764559e-01 -8.24747682e-01 -2.90907845e-02 -5.67703009e-01 -8.22731197e-01 -2.90907901e-02 -5.70573270e-01 -8.20737660e-01 -2.90907808e-02 -5.73422432e-01 -8.18753660e-01 -2.90907919e-02 -5.76375842e-01 -8.16676080e-01 -2.90907864e-02 -5.79131424e-01 -8.14718246e-01 -2.90907789e-02 -5.81937432e-01 -8.12722325e-01 -2.90907882e-02 -5.84767997e-01 -8.10680985e-01 -2.90907808e-02 -5.87592244e-01 -8.08645427e-01 -2.90907882e-02 -5.90511560e-01 -8.06511581e-01 -2.90907864e-02 -5.93352079e-01 -8.04424822e-01 -2.90907845e-02 -5.96073389e-01 -8.02405298e-01 -2.90907770e-02 -5.98775923e-01 -8.00394475e-01 -2.90907845e-02 -6.01575613e-01 -7.98293769e-01 -2.90907864e-02 -6.04427576e-01 -7.96140492e-01 -2.90907901e-02 -6.07216358e-01 -7.94007897e-01 -2.90907789e-02 -6.09980524e-01 -7.91893184e-01 -2.90907919e-02 -6.12752676e-01 -7.89743066e-01 -2.90907789e-02 -6.15422845e-01 -7.87668288e-01 -2.90907864e-02 -6.18249953e-01 -7.85455883e-01 -2.90907901e-02 -6.20992482e-01 -7.83279181e-01 -2.90907789e-02 -6.23708427e-01 -7.81126857e-01 -2.90907882e-02 -6.26449585e-01 -7.78925598e-01 -2.90907826e-02 -6.29097998e-01 -7.76790679e-01 -2.90907845e-02 -6.31862044e-01 -7.74545193e-01 -2.90907901e-02 -6.34578824e-01 -7.72315681e-01 -2.90907789e-02 -6.37194216e-01 -7.70162582e-01 -2.90907845e-02 -6.39874578e-01 -7.67937899e-01 -2.90907864e-02 -6.42580748e-01 -7.65675426e-01 -2.90907882e-02 -6.45335972e-01 -7.63353765e-01 -2.90907864e-02 -6.47960782e-01 -7.61122048e-01 -2.90907808e-02 -6.50528491e-01 -7.58931339e-01 -2.90907845e-02 -6.53183281e-01 -7.56650448e-01 -2.90907845e-02 -6.55872285e-01 -7.54322529e-01 -2.90907901e-02 -6.58566236e-01 -7.51967967e-01 -2.90907864e-02 -6.61138594e-01 -7.49704123e-01 -2.90907808e-02 -6.63676441e-01 -7.47462749e-01 -2.90907845e-02 -6.66269481e-01 -7.45151937e-01 -2.90907864e-02 -6.68880343e-01 -7.42808402e-01 -2.90907845e-02 -6.71534598e-01 -7.40416110e-01 -2.90907901e-02 -6.74133360e-01 -7.38040626e-01 -2.90907808e-02 -6.76691771e-01 -7.35706091e-01 -2.90907901e-02 -6.79247200e-01 -7.33337343e-01 -2.90907789e-02 -6.81795955e-01 -7.30976701e-01 -2.90907919e-02 -6.84408545e-01 -7.28524327e-01 -2.90907845e-02 -6.86894715e-01 -7.26177812e-01 -2.90907808e-02 -6.89426363e-01 -7.23786235e-01 -2.90907901e-02 -6.91942215e-01 -7.21366167e-01 -2.90907789e-02 -6.94399118e-01 -7.19020605e-01 -2.90907864e-02 -6.96924746e-01 -7.16573715e-01 -2.90907882e-02 -6.99427843e-01 -7.14119792e-01 -2.90907826e-02 -7.01881111e-01 -7.11714923e-01 -2.90907864e-02 -7.04353511e-01 -7.09270835e-01 -2.90907864e-02 -7.06877112e-01 -7.06737757e-01 -2.90907901e-02 -7.09353387e-01 -7.04266965e-01 -2.90907826e-02 -7.11820006e-01 -7.01777458e-01 -2.90907901e-02 -7.14265347e-01 -6.99279726e-01 -2.90907808e-02 -7.16638982e-01 -6.96853518e-01 -2.90907864e-02 -7.19093382e-01 -6.94324493e-01 -2.90907882e-02 -7.21557260e-01 -6.91748738e-01 -2.90907901e-02 -7.23969996e-01 -6.89227045e-01 -2.90907808e-02 -7.26372421e-01 -6.86696231e-01 -2.90907901e-02 -7.28737533e-01 -6.84178114e-01 -2.90907808e-02 -7.31044471e-01 -6.81716263e-01 -2.90907845e-02 -7.33467698e-01 -6.79113984e-01 -2.90907882e-02 -7.35921919e-01 -6.76455915e-01 -2.90907882e-02 -7.38217831e-01 -6.73935771e-01 -2.90907752e-02 -7.40492225e-01 -6.71444595e-01 -2.90907864e-02 -7.42834747e-01 -6.68852031e-01 -2.90907845e-02 -7.45234549e-01 -6.66181862e-01 -2.90907919e-02 -7.47571349e-01 -6.63549304e-01 -2.90907770e-02 -7.49874890e-01 -6.60952210e-01 -2.90907901e-02 -7.52170026e-01 -6.58329010e-01 -2.90907789e-02 -7.54467428e-01 -6.55705810e-01 -2.90907901e-02 -7.56812394e-01 -6.52993083e-01 -2.90907826e-02 -7.59037673e-01 -6.50402963e-01 -2.90907808e-02 -7.61244118e-01 -6.47820354e-01 -2.90907845e-02 -7.63495862e-01 -6.45167291e-01 -2.90907845e-02 -7.65781105e-01 -6.42452896e-01 -2.90907864e-02 -7.68067956e-01 -6.39720023e-01 -2.90907864e-02 -7.70281553e-01 -6.37043655e-01 -2.90907808e-02 -7.72442639e-01 -6.34432375e-01 -2.90907864e-02 -7.74643064e-01 -6.31737649e-01 -2.90907845e-02 -7.76850402e-01 -6.29022002e-01 -2.90907826e-02 -7.79094458e-01 -6.26246631e-01 -2.90907901e-02 -7.81335950e-01 -6.23441637e-01 -2.90907845e-02 -7.83511281e-01 -6.20704174e-01 -2.90907845e-02 -7.85604954e-01 -6.18049383e-01 -2.90907789e-02 -7.87686884e-01 -6.15397990e-01 -2.90907845e-02 -7.89904058e-01 -6.12554014e-01 -2.90907901e-02 -7.92082191e-01 -6.09730244e-01 -2.90907826e-02 -7.94215381e-01 -6.06953681e-01 -2.90907882e-02 -7.96291709e-01 -6.04219496e-01 -2.90907808e-02 -7.98330069e-01 -6.01530492e-01 -2.90907845e-02 -8.00474048e-01 -5.98673522e-01 -2.90907901e-02 -8.02567244e-01 -5.95857441e-01 -2.90907789e-02 -8.04600239e-01 -5.93115866e-01 -2.90907882e-02 -8.06668401e-01 -5.90294540e-01 -2.90907826e-02 -8.08742106e-01 -5.87457120e-01 -2.90907882e-02 -8.10836315e-01 -5.84557831e-01 -2.90907864e-02 -8.12840462e-01 -5.81765592e-01 -2.90907789e-02 -8.14819813e-01 -5.78993976e-01 -2.90907845e-02 -8.16828668e-01 -5.76159477e-01 -2.90907845e-02 -8.18868577e-01 -5.73255956e-01 -2.90907864e-02 -8.20907176e-01 -5.70332170e-01 -2.90907864e-02 -8.22876930e-01 -5.67483485e-01 -2.90907808e-02 -8.24792981e-01 -5.64696074e-01 -2.90907845e-02 -8.26753199e-01 -5.61821699e-01 -2.90907826e-02 -8.28697324e-01 -5.58952272e-01 -2.90907826e-02 -8.30693424e-01 -5.55985987e-01 -2.90907919e-02 -8.32638323e-01 -5.53054452e-01 -2.90907789e-02 -8.34569395e-01 -5.50149322e-01 -2.90907901e-02 -8.36497784e-01 -5.47200263e-01 -2.90907770e-02 -8.38338733e-01 -5.44379950e-01 -2.90907826e-02 -8.40231001e-01 -5.41458964e-01 -2.90907845e-02 -8.42156887e-01 -5.38461089e-01 -2.90907882e-02 -8.44072521e-01 -5.35447121e-01 -2.90907808e-02 -8.45882058e-01 -5.32585979e-01 -2.90907808e-02 -8.47702444e-01 -5.29679477e-01 -2.90907826e-02 -8.49560976e-01 -5.26701927e-01 -2.90907845e-02 -8.51391554e-01 -5.23731947e-01 -2.90907845e-02 -8.53216827e-01 -5.20757496e-01 -2.90907826e-02 -8.55027199e-01 -5.17776966e-01 -2.90907845e-02 -8.56878877e-01 -5.14715374e-01 -2.90907901e-02 -8.58719349e-01 -5.11628032e-01 -2.90907845e-02 -8.60459268e-01 -5.08692443e-01 -2.90907789e-02 -8.62225950e-01 -5.05705178e-01 -2.90907901e-02 -8.63986671e-01 -5.02679408e-01 -2.90907789e-02 -8.65711272e-01 -4.99714941e-01 -2.90907882e-02 -8.67442787e-01 -4.96696353e-01 -2.90907826e-02 -8.69144559e-01 -4.93711114e-01 -2.90907845e-02 -8.70860755e-01 -4.90686476e-01 -2.90907845e-02 -8.72571766e-01 -4.87627387e-01 -2.90907826e-02 -8.74266505e-01 -4.84582841e-01 -2.90907845e-02 -8.75990868e-01 -4.81468588e-01 -2.90907882e-02 -8.77692580e-01 -4.78356034e-01 -2.90907826e-02 -8.79330754e-01 -4.75328267e-01 -2.90907808e-02 -8.80947709e-01 -4.72329319e-01 -2.90907826e-02 -8.82628322e-01 -4.69187170e-01 -2.90907882e-02 -8.84307861e-01 -4.66009587e-01 -2.90907845e-02 -8.85915875e-01 -4.62946355e-01 -2.90907808e-02 -8.87483120e-01 -4.59926158e-01 -2.90907789e-02 -8.89048874e-01 -4.56900746e-01 -2.90907845e-02 -8.90674591e-01 -4.53726918e-01 -2.90907882e-02 -8.92305434e-01 -4.50508922e-01 -2.90907845e-02 -8.93826723e-01 -4.47473407e-01 -2.90907789e-02 -8.95333707e-01 -4.44458067e-01 -2.90907845e-02 -8.96872878e-01 -4.41343665e-01 -2.90907845e-02 -8.98408413e-01 -4.38210338e-01 -2.90907826e-02 -8.99987161e-01 -4.34967250e-01 -2.90907901e-02 -9.01537657e-01 -4.31733191e-01 -2.90907845e-02 -9.03013587e-01 -4.28632766e-01 -2.90907789e-02 -9.04456913e-01 -4.25580531e-01 -2.90907826e-02 -9.05930042e-01 -4.22437817e-01 -2.90907826e-02 -9.07448053e-01 -4.19180155e-01 -2.90907901e-02 -9.08922911e-01 -4.15956825e-01 -2.90907808e-02 -9.10321593e-01 -4.12890226e-01 -2.90907808e-02 -9.11737919e-01 -4.09752339e-01 -2.90907826e-02 -9.13164198e-01 -4.06570822e-01 -2.90907845e-02 -9.14630711e-01 -4.03269500e-01 -2.90907919e-02 -9.16074872e-01 -3.99968922e-01 -2.90907845e-02 -9.17458653e-01 -3.96782011e-01 -2.90907845e-02 -9.18832660e-01 -3.93576771e-01 -2.90907826e-02 -9.20174003e-01 -3.90432209e-01 -2.90907770e-02 -9.21489060e-01 -3.87329489e-01 -2.90907845e-02 -9.22845304e-01 -3.84082377e-01 -2.90907826e-02 -9.24218237e-01 -3.80771369e-01 -2.90907882e-02 -9.25538063e-01 -3.77542198e-01 -2.90907770e-02 -9.26813245e-01 -3.74408215e-01 -2.90907845e-02 -9.28148150e-01 -3.71091336e-01 -2.90907882e-02 -9.29432869e-01 -3.67854565e-01 -2.90907808e-02 -9.30685937e-01 -3.64680856e-01 -2.90907845e-02 -9.31948245e-01 -3.61426771e-01 -2.90907845e-02 -9.33219194e-01 -3.58155817e-01 -2.90907864e-02 -9.34493780e-01 -3.54805410e-01 -2.90907882e-02 -9.35704887e-01 -3.51567209e-01 -2.90907789e-02 -9.36897457e-01 -3.48381639e-01 -2.90907826e-02 -9.38148618e-01 -3.45020145e-01 -2.90907882e-02 -9.39384580e-01 -3.41650486e-01 -2.90907826e-02 -9.40565050e-01 -3.38376582e-01 -2.90907826e-02 -9.41714048e-01 -3.35166812e-01 -2.90907770e-02 -9.42872763e-01 -3.31903815e-01 -2.90907882e-02 -9.44027841e-01 -3.28586251e-01 -2.90907789e-02 -9.45139468e-01 -3.25388581e-01 -2.90907826e-02 -9.46266770e-01 -3.22090656e-01 -2.90907845e-02 -9.47388768e-01 -3.18782002e-01 -2.90907845e-02 -9.48528707e-01 -3.15379113e-01 -2.90907901e-02 -9.49616313e-01 -3.12068045e-01 -2.90907770e-02 -9.50680733e-01 -3.08825821e-01 -2.90907845e-02 -9.51774061e-01 -3.05444032e-01 -2.90907882e-02 -9.52832639e-01 -3.02108079e-01 -2.90907789e-02 -9.53880668e-01 -2.98803985e-01 -2.90907882e-02 -9.54916954e-01 -2.95457035e-01 -2.90907789e-02 -9.55945194e-01 -2.92127520e-01 -2.90907882e-02 -9.56980944e-01 -2.88705766e-01 -2.90907845e-02 -9.57960546e-01 -2.85431892e-01 -2.90907808e-02 -9.58952129e-01 -2.82099128e-01 -2.90907864e-02 -9.59928215e-01 -2.78746068e-01 -2.90907789e-02 -9.60900187e-01 -2.75385231e-01 -2.90907882e-02 -9.61850703e-01 -2.72031248e-01 -2.90907770e-02 -9.62769330e-01 -2.68778354e-01 -2.90907845e-02 -9.63707566e-01 -2.65393943e-01 -2.90907845e-02 -9.64628518e-01 -2.62028396e-01 -2.90907826e-02 -9.65558469e-01 -2.58584440e-01 -2.90907882e-02 -9.66482460e-01 -2.55106419e-01 -2.90907845e-02 -9.67366040e-01 -2.51729310e-01 -2.90907845e-02 -9.68212783e-01 -2.48449013e-01 -2.90907789e-02 -9.69041586e-01 -2.45194525e-01 -2.90907845e-02 -9.69920576e-01 -2.41707563e-01 -2.90907901e-02 -9.70783889e-01 -2.38215685e-01 -2.90907845e-02 -9.71610963e-01 -2.34826490e-01 -2.90907845e-02 -9.72395658e-01 -2.31537879e-01 -2.90907770e-02 -9.73179340e-01 -2.28234336e-01 -2.90907845e-02 -9.73989308e-01 -2.24754617e-01 -2.90907901e-02 -9.74791527e-01 -2.21234709e-01 -2.90907826e-02 -9.75536764e-01 -2.17915058e-01 -2.90907770e-02 -9.76291716e-01 -2.14528322e-01 -2.90907864e-02 -9.77033198e-01 -2.11101413e-01 -2.90907770e-02 -9.77742076e-01 -2.07810432e-01 -2.90907826e-02 -9.78487194e-01 -2.04289243e-01 -2.90907864e-02 -9.79216993e-01 -2.00750321e-01 -2.90907826e-02 -9.79885340e-01 -1.97438031e-01 -2.90907752e-02 -9.80552793e-01 -1.94110841e-01 -2.90907826e-02 -9.81225967e-01 -1.90680563e-01 -2.90907808e-02 -9.81900692e-01 -1.87179714e-01 -2.90907845e-02 -9.82567966e-01 -1.83641940e-01 -2.90907808e-02 -9.83180642e-01 -1.80299640e-01 -2.90907752e-02 -9.83792603e-01 -1.76976621e-01 -2.90907789e-02 -9.84406769e-01 -1.73522919e-01 -2.90907789e-02 -9.85018432e-01 -1.70009553e-01 -2.90907864e-02 -9.85616803e-01 -1.66492030e-01 -2.90907789e-02 -9.86176610e-01 -1.63132966e-01 -2.90907752e-02 -9.86746252e-01 -1.59684479e-01 -2.90907845e-02 -9.87292826e-01 -1.56235725e-01 -2.90907733e-02 -9.87832665e-01 -1.52810842e-01 -2.90907845e-02 -9.88356888e-01 -1.49357691e-01 -2.90907789e-02 -9.88873541e-01 -1.45926058e-01 -2.90907845e-02 -9.89377499e-01 -1.42442748e-01 -2.90907752e-02 -9.89857078e-01 -1.39083490e-01 -2.90907789e-02 -9.90347445e-01 -1.35568693e-01 -2.90907826e-02 -9.90810633e-01 -1.32082835e-01 -2.90907752e-02 -9.91268158e-01 -1.28648013e-01 -2.90907826e-02 -9.91709411e-01 -1.25180677e-01 -2.90907752e-02 -9.92130160e-01 -1.21795975e-01 -2.90907752e-02 -9.92560446e-01 -1.18249491e-01 -2.90907808e-02 -9.92960632e-01 -1.14787742e-01 -2.90907752e-02 -9.93351102e-01 -1.11418508e-01 -2.90907789e-02 -9.93744791e-01 -1.07842758e-01 -2.90907826e-02 -9.94122803e-01 -1.04284801e-01 -2.90907752e-02 -9.94472861e-01 -1.00858949e-01 -2.90907752e-02 -9.94811058e-01 -9.74503979e-02 -2.90907640e-02 -9.95143592e-01 -9.39986482e-02 -2.90907659e-02 -9.95467365e-01 -9.05077979e-02 -2.90907379e-02 -9.95766044e-01 -8.71584788e-02 -2.90907230e-02 -9.96056259e-01 -8.37818682e-02 -2.90906802e-02 -9.96327162e-01 -8.05256367e-02 -2.90905349e-02 -9.96610522e-01 -7.69382194e-02 -2.90905256e-02 -9.96879995e-01 -7.33703598e-02 -2.90905256e-02 -9.97097611e-01 -7.03469887e-02 -2.90905293e-02 -9.97376621e-01 -6.62808046e-02 -2.90905349e-02 -9.97631073e-01 -6.23287633e-02 -2.90905330e-02 -9.97895777e-01 -5.79461306e-02 -2.90905330e-02 -9.98071313e-01 -5.48397675e-02 -2.90905312e-02 -9.98243153e-01 -5.16169295e-02 -2.90905330e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.99331295e-01 -2.21544933e-02 -2.90905312e-02 0. 0. 0. -9.99471962e-01 -1.44798271e-02 -2.90905349e-02 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. 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. 0. -9.98092234e-01 5.71849011e-02 -2.32631415e-02 -9.97938395e-01 5.98087348e-02 -2.32630353e-02 -9.97749448e-01 6.30044863e-02 -2.32631937e-02 -9.97524977e-01 6.64979964e-02 -2.32632793e-02 -9.97289002e-01 6.99191913e-02 -2.32632942e-02 -9.97051239e-01 7.32778683e-02 -2.32633520e-02 -9.96785998e-01 7.68048093e-02 -2.32633818e-02 -9.96505380e-01 8.03742856e-02 -2.32633501e-02 -9.96223509e-01 8.37843642e-02 -2.32633222e-02 -9.95926678e-01 8.72519389e-02 -2.32633818e-02 -9.95609522e-01 9.08070207e-02 -2.32633669e-02 -9.95291412e-01 9.42236707e-02 -2.32633688e-02 -9.94954050e-01 9.77284759e-02 -2.32634079e-02 -9.94613707e-01 1.01140387e-01 -2.32633688e-02 -9.94264901e-01 1.04508080e-01 -2.32633874e-02 -9.93882060e-01 1.08084679e-01 -2.32634321e-02 -9.93491530e-01 1.11632213e-01 -2.32634041e-02 -9.93091047e-01 1.15120836e-01 -2.32634041e-02 -9.92682219e-01 1.18590437e-01 -2.32634079e-02 -9.92266119e-01 1.22034371e-01 -2.32634041e-02 -9.91838157e-01 1.25476465e-01 -2.32633986e-02 -9.91391063e-01 1.28955305e-01 -2.32634284e-02 -9.90928471e-01 1.32457212e-01 -2.32634209e-02 -9.90472972e-01 1.35823831e-01 -2.32633688e-02 -9.90016043e-01 1.39125124e-01 -2.32634135e-02 -9.89505351e-01 1.42705321e-01 -2.32634451e-02 -9.88984883e-01 1.46258697e-01 -2.32633948e-02 -9.88466918e-01 1.49715573e-01 -2.32634004e-02 -9.87940669e-01 1.53161347e-01 -2.32634135e-02 -9.87402558e-01 1.56593964e-01 -2.32634004e-02 -9.86860514e-01 1.59966499e-01 -2.32633706e-02 -9.86302078e-01 1.63391739e-01 -2.32634563e-02 -9.85703766e-01 1.66954160e-01 -2.32634004e-02 -9.85128582e-01 1.70310348e-01 -2.32633706e-02 -9.84534085e-01 1.73739284e-01 -2.32634451e-02 -9.83902931e-01 1.77275524e-01 -2.32634135e-02 -9.83271599e-01 1.80717930e-01 -2.32634135e-02 -9.82636988e-01 1.84148267e-01 -2.32634135e-02 -9.82006252e-01 1.87471613e-01 -2.32633688e-02 -9.81369197e-01 1.90783426e-01 -2.32634172e-02 -9.80674148e-01 1.94332570e-01 -2.32634451e-02 -9.79964674e-01 1.97876215e-01 -2.32634135e-02 -9.79269624e-01 2.01287165e-01 -2.32634097e-02 -9.78580832e-01 2.04603821e-01 -2.32633688e-02 -9.77862239e-01 2.08028808e-01 -2.32634526e-02 -9.77107525e-01 2.11539462e-01 -2.32634023e-02 -9.76380169e-01 2.14854315e-01 -2.32633576e-02 -9.75631535e-01 2.18245685e-01 -2.32634321e-02 -9.74859178e-01 2.21658483e-01 -2.32633688e-02 -9.74101782e-01 2.24967465e-01 -2.32634004e-02 -9.73291218e-01 2.28462607e-01 -2.32634321e-02 -9.72462833e-01 2.31956735e-01 -2.32634004e-02 -9.71656442e-01 2.35316277e-01 -2.32633911e-02 -9.70828474e-01 2.38701120e-01 -2.32633986e-02 -9.69979286e-01 2.42122352e-01 -2.32633986e-02 -9.69152331e-01 2.45408937e-01 -2.32633613e-02 -9.68298197e-01 2.48767808e-01 -2.32634451e-02 -9.67398524e-01 2.52242416e-01 -2.32633818e-02 -9.66528654e-01 2.55555212e-01 -2.32633576e-02 -9.65631723e-01 2.58925796e-01 -2.32634135e-02 -9.64708030e-01 2.62347400e-01 -2.32633818e-02 -9.63783562e-01 2.65714049e-01 -2.32633837e-02 -9.62850332e-01 2.69086182e-01 -2.32633874e-02 -9.61920083e-01 2.72387564e-01 -2.32633632e-02 -9.60973620e-01 2.75708109e-01 -2.32634135e-02 -9.59999144e-01 2.79076368e-01 -2.32633688e-02 -9.59024310e-01 2.82415420e-01 -2.32634246e-02 -9.58001554e-01 2.85866320e-01 -2.32633874e-02 -9.57023263e-01 2.89115548e-01 -2.32633520e-02 -9.56013143e-01 2.92448103e-01 -2.32634284e-02 -9.54955757e-01 2.95879811e-01 -2.32633892e-02 -9.53915656e-01 2.99214929e-01 -2.32633855e-02 -9.52873886e-01 3.02515179e-01 -2.32633930e-02 -9.51836586e-01 3.05768073e-01 -2.32633706e-02 -9.50792789e-01 3.08991760e-01 -2.32633874e-02 -9.49677825e-01 3.12404960e-01 -2.32634209e-02 -9.48553622e-01 3.15800488e-01 -2.32633948e-02 -9.47441399e-01 3.19123268e-01 -2.32633892e-02 -9.46320832e-01 3.22431058e-01 -2.32633911e-02 -9.45197284e-01 3.25715125e-01 -2.32633837e-02 -9.44072306e-01 3.28952730e-01 -2.32633818e-02 -9.42920089e-01 3.32245082e-01 -2.32634060e-02 -9.41736519e-01 3.35591882e-01 -2.32633799e-02 -9.40582037e-01 3.38800102e-01 -2.32633669e-02 -9.39432919e-01 3.41986835e-01 -2.32633874e-02 -9.38190937e-01 3.45360279e-01 -2.32634209e-02 -9.36944187e-01 3.48714679e-01 -2.32634004e-02 -9.35718179e-01 3.51994336e-01 -2.32633930e-02 -9.34500158e-01 3.55226368e-01 -2.32633874e-02 -9.33296502e-01 3.58407319e-01 -2.32633725e-02 -9.32045162e-01 3.61623108e-01 -2.32633967e-02 -9.30765271e-01 3.64912212e-01 -2.32634209e-02 -9.29450214e-01 3.68249983e-01 -2.32633911e-02 -9.28190470e-01 3.71410668e-01 -2.32633650e-02 -9.26897168e-01 3.74627769e-01 -2.32634321e-02 -9.25556064e-01 3.77931297e-01 -2.32633948e-02 -9.24234509e-01 3.81143838e-01 -2.32633892e-02 -9.22901154e-01 3.84366900e-01 -2.32633892e-02 -9.21580613e-01 3.87519777e-01 -2.32633688e-02 -9.20255542e-01 3.90657008e-01 -2.32634060e-02 -9.18851197e-01 3.93944055e-01 -2.32634414e-02 -9.17427659e-01 3.97253036e-01 -2.32633967e-02 -9.16046202e-01 4.00432765e-01 -2.32633948e-02 -9.14641500e-01 4.03629631e-01 -2.32634004e-02 -9.13216829e-01 4.06842709e-01 -2.32633948e-02 -9.11799312e-01 4.10008699e-01 -2.32634004e-02 -9.10395145e-01 4.13115114e-01 -2.32633818e-02 -9.08955216e-01 4.16273117e-01 -2.32634284e-02 -9.07462656e-01 4.19515908e-01 -2.32634004e-02 -9.06028152e-01 4.22607273e-01 -2.32633818e-02 -9.04558599e-01 4.25745547e-01 -2.32634395e-02 -9.03028131e-01 4.28982496e-01 -2.32634041e-02 -9.01523292e-01 4.32131797e-01 -2.32633948e-02 -9.00013685e-01 4.35276657e-01 -2.32634060e-02 -8.98506582e-01 4.38378394e-01 -2.32633874e-02 -8.97024810e-01 4.41395849e-01 -2.32634041e-02 -8.95446897e-01 4.44592267e-01 -2.32634339e-02 -8.93851399e-01 4.47787434e-01 -2.32634060e-02 -8.92280996e-01 4.50913012e-01 -2.32634079e-02 -8.90700758e-01 4.54024255e-01 -2.32633948e-02 -8.89118850e-01 4.57114428e-01 -2.32633874e-02 -8.87520492e-01 4.60207403e-01 -2.32633986e-02 -8.85906816e-01 4.63309348e-01 -2.32634060e-02 -8.84292305e-01 4.66387302e-01 -2.32633948e-02 -8.82682383e-01 4.69422191e-01 -2.32633706e-02 -8.81087542e-01 4.72411335e-01 -2.32633967e-02 -8.79392624e-01 4.75558996e-01 -2.32634451e-02 -8.77688169e-01 4.78699803e-01 -2.32634023e-02 -8.76003802e-01 4.81772214e-01 -2.32634116e-02 -8.74314725e-01 4.84823555e-01 -2.32633967e-02 -8.72628391e-01 4.87854391e-01 -2.32633986e-02 -8.70938599e-01 4.90869850e-01 -2.32633986e-02 -8.69200706e-01 4.93940592e-01 -2.32634284e-02 -8.67469490e-01 4.96974945e-01 -2.32634004e-02 -8.65763307e-01 4.99939263e-01 -2.32633669e-02 -8.64026487e-01 5.02938449e-01 -2.32634358e-02 -8.62272918e-01 5.05935550e-01 -2.32633725e-02 -8.60493541e-01 5.08956671e-01 -2.32634284e-02 -8.58667254e-01 5.12031019e-01 -2.32633986e-02 -8.56864452e-01 5.15041828e-01 -2.32633986e-02 -8.55067968e-01 5.18018126e-01 -2.32633948e-02 -8.53249788e-01 5.21013260e-01 -2.32634135e-02 -8.51415396e-01 5.24000347e-01 -2.32633967e-02 -8.49587560e-01 5.26962519e-01 -2.32633986e-02 -8.47794652e-01 5.29839694e-01 -2.32633706e-02 -8.45949471e-01 5.32782853e-01 -2.32634451e-02 -8.44044566e-01 5.35792351e-01 -2.32633967e-02 -8.42164457e-01 5.38744152e-01 -2.32634321e-02 -8.40255082e-01 5.41715920e-01 -2.32633930e-02 -8.38373721e-01 5.44622898e-01 -2.32633986e-02 -8.36519122e-01 5.47464371e-01 -2.32633781e-02 -8.34601998e-01 5.50388396e-01 -2.32634395e-02 -8.32609177e-01 5.53393006e-01 -2.32634265e-02 -8.30664277e-01 5.56311667e-01 -2.32634172e-02 -8.28755260e-01 5.59154093e-01 -2.32633874e-02 -8.26866448e-01 5.61939955e-01 -2.32633892e-02 -8.24882090e-01 5.64851701e-01 -2.32634321e-02 -8.22847307e-01 5.67812085e-01 -2.32634135e-02 -8.20836365e-01 5.70713878e-01 -2.32633986e-02 -8.18887889e-01 5.73500633e-01 -2.32633613e-02 -8.16893280e-01 5.76347709e-01 -2.32634358e-02 -8.14797342e-01 5.79298735e-01 -2.32633948e-02 -8.12770247e-01 5.82143128e-01 -2.32633930e-02 -8.10720325e-01 5.84990382e-01 -2.32633948e-02 -8.08675706e-01 5.87817430e-01 -2.32633892e-02 -8.06638658e-01 5.90608597e-01 -2.32634004e-02 -8.04648340e-01 5.93315005e-01 -2.32633669e-02 -8.02571058e-01 5.96123338e-01 -2.32634451e-02 -8.00408840e-01 5.99023044e-01 -2.32633986e-02 -7.98393726e-01 6.01706862e-01 -2.32633594e-02 -7.96278238e-01 6.04507804e-01 -2.32634395e-02 -7.94106841e-01 6.07355177e-01 -2.32633837e-02 -7.91978300e-01 6.10126138e-01 -2.32633725e-02 -7.89817274e-01 6.12920523e-01 -2.32633930e-02 -7.87716866e-01 6.15618467e-01 -2.32633837e-02 -7.85624206e-01 6.18286490e-01 -2.32633855e-02 -7.83421695e-01 6.21078074e-01 -2.32634563e-02 -7.81171083e-01 6.23906612e-01 -2.32633986e-02 -7.78976142e-01 6.26643896e-01 -2.32634079e-02 -7.76794136e-01 6.29346132e-01 -2.32633818e-02 -7.74650455e-01 6.31979167e-01 -2.32633632e-02 -7.72461891e-01 6.34656787e-01 -2.32634302e-02 -7.70192564e-01 6.37407899e-01 -2.32633874e-02 -7.67937601e-01 6.40121818e-01 -2.32633911e-02 -7.65779853e-01 6.42702878e-01 -2.32633743e-02 -7.63521373e-01 6.45385146e-01 -2.32634433e-02 -7.61181056e-01 6.48141146e-01 -2.32634116e-02 -7.58916974e-01 6.50791705e-01 -2.32634004e-02 -7.56624103e-01 6.53459549e-01 -2.32634079e-02 -7.54361153e-01 6.56067371e-01 -2.32633986e-02 -7.52123892e-01 6.58630311e-01 -2.32633743e-02 -7.49878168e-01 6.61186337e-01 -2.32634079e-02 -7.47514904e-01 6.63858533e-01 -2.32634377e-02 -7.45126426e-01 6.66539729e-01 -2.32634116e-02 -7.42833972e-01 6.69088960e-01 -2.32633706e-02 -7.40508735e-01 6.71667576e-01 -2.32634377e-02 -7.38110006e-01 6.74297035e-01 -2.32634060e-02 -7.35747933e-01 6.76878154e-01 -2.32634004e-02 -7.33376741e-01 6.79445148e-01 -2.32633911e-02 -7.31064022e-01 6.81930244e-01 -2.32633799e-02 -7.28749156e-01 6.84405923e-01 -2.32634041e-02 -7.26304531e-01 6.86998069e-01 -2.32634451e-02 -7.23827839e-01 6.89609230e-01 -2.32634004e-02 -7.21416175e-01 6.92125082e-01 -2.32633986e-02 -7.18986511e-01 6.94661617e-01 -2.32633892e-02 -7.16628730e-01 6.97089732e-01 -2.32633688e-02 -7.14197278e-01 6.99581146e-01 -2.32634321e-02 -7.11673617e-01 7.02149093e-01 -2.32634060e-02 -7.09222376e-01 7.04627275e-01 -2.32633986e-02 -7.06773877e-01 7.07065105e-01 -2.32633948e-02 -7.04355061e-01 7.09491849e-01 -2.32633818e-02 -7.01885641e-01 7.11934865e-01 -2.32634321e-02 -6.99316680e-01 7.14455247e-01 -2.32633986e-02 -6.96819484e-01 7.16893673e-01 -2.32634135e-02 -6.94311380e-01 7.19325066e-01 -2.32634060e-02 -6.91832721e-01 7.21695423e-01 -2.32633781e-02 -6.89372420e-01 7.24053860e-01 -2.32633911e-02 -6.86786711e-01 7.26503968e-01 -2.32634284e-02 -6.84187829e-01 7.28951395e-01 -2.32634004e-02 -6.81686163e-01 7.31288254e-01 -2.32633743e-02 -6.79150701e-01 7.33649433e-01 -2.32634321e-02 -6.76523268e-01 7.36073852e-01 -2.32634116e-02 -6.74009025e-01 7.38373041e-01 -2.32633818e-02 -6.71438575e-01 7.40714848e-01 -2.32634451e-02 -6.68848276e-01 7.43052542e-01 -2.32633706e-02 -6.66332006e-01 7.45309651e-01 -2.32633911e-02 -6.63647830e-01 7.47703493e-01 -2.32634284e-02 -6.61019623e-01 7.50025451e-01 -2.32633781e-02 -6.58400536e-01 7.52324700e-01 -2.32634451e-02 -6.55754387e-01 7.54633069e-01 -2.32633539e-02 -6.53170109e-01 7.56872475e-01 -2.32634451e-02 -6.50409222e-01 7.59246111e-01 -2.32634041e-02 -6.47739887e-01 7.61523068e-01 -2.32634004e-02 -6.45114064e-01 7.63750315e-01 -2.32633986e-02 -6.42513692e-01 7.65937626e-01 -2.32633650e-02 -6.39836907e-01 7.68177748e-01 -2.32634284e-02 -6.37127995e-01 7.70422101e-01 -2.32633688e-02 -6.34465873e-01 7.72621155e-01 -2.32634451e-02 -6.31668508e-01 7.74905741e-01 -2.32634041e-02 -6.28963172e-01 7.77103841e-01 -2.32634060e-02 -6.26300693e-01 7.79248953e-01 -2.32633632e-02 -6.23675883e-01 7.81355619e-01 -2.32634135e-02 -6.20855808e-01 7.83596039e-01 -2.32634284e-02 -6.18122518e-01 7.85754144e-01 -2.32633688e-02 -6.15399718e-01 7.87889659e-01 -2.32634321e-02 -6.12645924e-01 7.90031970e-01 -2.32633613e-02 -6.09923720e-01 7.92135894e-01 -2.32634004e-02 -6.07070625e-01 7.94324636e-01 -2.32634209e-02 -6.04244709e-01 7.96476960e-01 -2.32634079e-02 -6.01541400e-01 7.98520148e-01 -2.32633837e-02 -5.98773658e-01 8.00595403e-01 -2.32634377e-02 -5.95883369e-01 8.02750647e-01 -2.32634135e-02 -5.93079627e-01 8.04823101e-01 -2.32633967e-02 -5.90279281e-01 8.06879699e-01 -2.32633930e-02 -5.87531805e-01 8.08882654e-01 -2.32633688e-02 -5.84700525e-01 8.10930967e-01 -2.32634339e-02 -5.81785917e-01 8.13026667e-01 -2.32633967e-02 -5.78958511e-01 8.15042257e-01 -2.32634060e-02 -5.76083779e-01 8.17077518e-01 -2.32633874e-02 -5.73301017e-01 8.19029391e-01 -2.32633706e-02 -5.70452273e-01 8.21015775e-01 -2.32634209e-02 -5.67581713e-01 8.23005497e-01 -2.32633688e-02 -5.64712584e-01 8.24978113e-01 -2.32634321e-02 -5.61722815e-01 8.27013850e-01 -2.32633986e-02 -5.58840513e-01 8.28964412e-01 -2.32633874e-02 -5.56044817e-01 8.30840111e-01 -2.32633464e-02 -5.53130567e-01 8.32784772e-01 -2.32634246e-02 -5.50119042e-01 8.34777832e-01 -2.32633892e-02 -5.47272563e-01 8.36644769e-01 -2.32633594e-02 -5.44370353e-01 8.38537037e-01 -2.32634190e-02 -5.41400313e-01 8.40455830e-01 -2.32633408e-02 -5.38495302e-01 8.42322171e-01 -2.32634228e-02 -5.35456300e-01 8.44256997e-01 -2.32633781e-02 -5.32501340e-01 8.46124053e-01 -2.32633911e-02 -5.29628813e-01 8.47924292e-01 -2.32633669e-02 -5.26694655e-01 8.49754274e-01 -2.32634135e-02 -5.23629189e-01 8.51641059e-01 -2.32633427e-02 -5.20699084e-01 8.53438973e-01 -2.32633725e-02 -5.17712772e-01 8.55253100e-01 -2.32634246e-02 -5.14742255e-01 8.57043564e-01 -2.32633613e-02 -5.11785567e-01 8.58813882e-01 -2.32634060e-02 -5.08780062e-01 8.60595703e-01 -2.32633688e-02 -5.05851507e-01 8.62322986e-01 -2.32633855e-02 -5.02773583e-01 8.64120364e-01 -2.32633967e-02 -4.99679983e-01 8.65912557e-01 -2.32633706e-02 -4.96657103e-01 8.67649615e-01 -2.32633892e-02 -4.93623078e-01 8.69379163e-01 -2.32633818e-02 -4.90575671e-01 8.71105015e-01 -2.32633818e-02 -4.87541914e-01 8.72803867e-01 -2.32633948e-02 -4.84480977e-01 8.74505281e-01 -2.32633930e-02 -4.81486470e-01 8.76159430e-01 -2.32633706e-02 -4.78435278e-01 8.77831757e-01 -2.32634321e-02 -4.75289702e-01 8.79535317e-01 -2.32633967e-02 -4.72243011e-01 8.81176293e-01 -2.32633948e-02 -4.69164759e-01 8.82819712e-01 -2.32633837e-02 -4.66130912e-01 8.84425402e-01 -2.32633594e-02 -4.63037312e-01 8.86049271e-01 -2.32634079e-02 -4.59875524e-01 8.87692153e-01 -2.32633948e-02 -4.56753224e-01 8.89304459e-01 -2.32633855e-02 -4.53753948e-01 8.90836775e-01 -2.32633520e-02 -4.50678796e-01 8.92398059e-01 -2.32634209e-02 -4.47472543e-01 8.94009650e-01 -2.32633874e-02 -4.44338799e-01 8.95570755e-01 -2.32633874e-02 -4.41221446e-01 8.97111535e-01 -2.32633837e-02 -4.38144416e-01 8.98618698e-01 -2.32633594e-02 -4.35029715e-01 9.00131464e-01 -2.32633986e-02 -4.31845695e-01 9.01660264e-01 -2.32633576e-02 -4.28720176e-01 9.03151929e-01 -2.32634116e-02 -4.25495356e-01 9.04675126e-01 -2.32633781e-02 -4.22390670e-01 9.06129777e-01 -2.32633576e-02 -4.19227749e-01 9.07597244e-01 -2.32633948e-02 -4.16058958e-01 9.09052312e-01 -2.32633539e-02 -4.12880033e-01 9.10503447e-01 -2.32634079e-02 -4.09647256e-01 9.11962390e-01 -2.32633743e-02 -4.06433225e-01 9.13398981e-01 -2.32633818e-02 -4.03337300e-01 9.14769590e-01 -2.32633650e-02 -4.00200456e-01 9.16148245e-01 -2.32633911e-02 -3.96910608e-01 9.17577565e-01 -2.32634116e-02 -3.93616110e-01 9.18990612e-01 -2.32633874e-02 -3.90540570e-01 9.20305431e-01 -2.32633632e-02 -3.87413740e-01 9.21626210e-01 -2.32633874e-02 -3.84104878e-01 9.23011363e-01 -2.32634321e-02 -3.80839795e-01 9.24359739e-01 -2.32633706e-02 -3.77613455e-01 9.25684333e-01 -2.32633930e-02 -3.74414384e-01 9.26983237e-01 -2.32633576e-02 -3.71208072e-01 9.28272307e-01 -2.32634284e-02 -3.67884576e-01 9.29594934e-01 -2.32633911e-02 -3.64656419e-01 9.30866718e-01 -2.32633986e-02 -3.61393809e-01 9.32131767e-01 -2.32633874e-02 -3.58208150e-01 9.33371902e-01 -2.32633706e-02 -3.54939014e-01 9.34610307e-01 -2.32634209e-02 -3.51674318e-01 9.35836554e-01 -2.32633576e-02 -3.48411441e-01 9.37057078e-01 -2.32634079e-02 -3.45073760e-01 9.38293397e-01 -2.32633799e-02 -3.41870278e-01 9.39475715e-01 -2.32633576e-02 -3.38589370e-01 9.40659583e-01 -2.32634041e-02 -3.35263580e-01 9.41852868e-01 -2.32633539e-02 -3.31997842e-01 9.43007231e-01 -2.32633855e-02 -3.28639030e-01 9.44181204e-01 -2.32633762e-02 -3.25338304e-01 9.45327163e-01 -2.32633874e-02 -3.22124600e-01 9.46423829e-01 -2.32633501e-02 -3.18804711e-01 9.47549820e-01 -2.32634209e-02 -3.15434933e-01 9.48674858e-01 -2.32633781e-02 -3.12136143e-01 9.49764907e-01 -2.32633874e-02 -3.08869183e-01 9.50832546e-01 -2.32633688e-02 -3.05553108e-01 9.51906145e-01 -2.32634246e-02 -3.02184016e-01 9.52978730e-01 -2.32633706e-02 -2.98842162e-01 9.54032242e-01 -2.32633725e-02 -2.95520663e-01 9.55067813e-01 -2.32633837e-02 -2.92259544e-01 9.56069112e-01 -2.32633613e-02 -2.88926721e-01 9.57080960e-01 -2.32634190e-02 -2.85459429e-01 9.58121359e-01 -2.32633911e-02 -2.82129884e-01 9.59109247e-01 -2.32633948e-02 -2.78778821e-01 9.60087597e-01 -2.32634060e-02 -2.75525659e-01 9.61025715e-01 -2.32633390e-02 -2.72175938e-01 9.61980879e-01 -2.32634135e-02 -2.68793404e-01 9.62930322e-01 -2.32633539e-02 -2.65555710e-01 9.63827312e-01 -2.32633781e-02 -2.62068540e-01 9.64784205e-01 -2.32634284e-02 -2.58588076e-01 9.65720475e-01 -2.32633855e-02 -2.55206943e-01 9.66620684e-01 -2.32633948e-02 -2.51848340e-01 9.67500567e-01 -2.32633818e-02 -2.48579010e-01 9.68346059e-01 -2.32633445e-02 -2.45163918e-01 9.69214141e-01 -2.32634321e-02 -2.41685510e-01 9.70088005e-01 -2.32633818e-02 -2.38267645e-01 9.70934093e-01 -2.32633837e-02 -2.34891787e-01 9.71758723e-01 -2.32633892e-02 -2.31585637e-01 9.72550333e-01 -2.32633408e-02 -2.28218481e-01 9.73346949e-01 -2.32634265e-02 -2.24816591e-01 9.74137127e-01 -2.32633650e-02 -2.21408501e-01 9.74916756e-01 -2.32634284e-02 -2.17913538e-01 9.75705028e-01 -2.32633706e-02 -2.14511245e-01 9.76455569e-01 -2.32633818e-02 -2.11093038e-01 9.77201700e-01 -2.32633930e-02 -2.07770228e-01 9.77913558e-01 -2.32633594e-02 -2.04377726e-01 9.78630662e-01 -2.32634284e-02 -2.00840533e-01 9.79362488e-01 -2.32633892e-02 -1.97421014e-01 9.80054438e-01 -2.32633818e-02 -1.94000676e-01 9.80738759e-01 -2.32633930e-02 -1.90674752e-01 9.81390297e-01 -2.32633576e-02 -1.87231556e-01 9.82054293e-01 -2.32634321e-02 -1.83815479e-01 9.82697487e-01 -2.32633464e-02 -1.80435732e-01 9.83322799e-01 -2.32633837e-02 -1.76946282e-01 9.83962417e-01 -2.32634246e-02 -1.73400730e-01 9.84593213e-01 -2.32633837e-02 -1.69987977e-01 9.85184491e-01 -2.32633892e-02 -1.66555405e-01 9.85770941e-01 -2.32633874e-02 -1.63171768e-01 9.86335337e-01 -2.32633557e-02 -1.59824923e-01 9.86883819e-01 -2.32633818e-02 -1.56325743e-01 9.87445831e-01 -2.32634097e-02 -1.52742341e-01 9.88006949e-01 -2.32633930e-02 -1.49275690e-01 9.88532841e-01 -2.32633781e-02 -1.45827174e-01 9.89049137e-01 -2.32633874e-02 -1.42392486e-01 9.89548922e-01 -2.32633892e-02 -1.39051110e-01 9.90024924e-01 -2.32633408e-02 -1.35592297e-01 9.90506828e-01 -2.32634209e-02 -1.32017851e-01 9.90986466e-01 -2.32633837e-02 -1.28675908e-01 9.91425514e-01 -2.32633520e-02 -1.25226036e-01 9.91867959e-01 -2.32634116e-02 -1.21752575e-01 9.92300272e-01 -2.32633594e-02 -1.18257426e-01 9.92722750e-01 -2.32634284e-02 -1.14676394e-01 9.93142962e-01 -2.32633911e-02 -1.11224510e-01 9.93535340e-01 -2.32633855e-02 -1.07729219e-01 9.93919790e-01 -2.32633892e-02 -1.04279578e-01 9.94287133e-01 -2.32633762e-02 -1.00806177e-01 9.94646609e-01 -2.32633874e-02 -9.74031165e-02 9.94984388e-01 -2.32633520e-02 -9.40701887e-02 9.95306909e-01 -2.32633911e-02 -9.04801115e-02 9.95639384e-01 -2.32634079e-02 -8.69078934e-02 9.95958388e-01 -2.32633855e-02 -8.34388286e-02 9.96254206e-01 -2.32633911e-02 -7.99419358e-02 9.96541023e-01 -2.32633967e-02 -7.65457749e-02 9.96804476e-01 -2.32633408e-02 -7.30666593e-02 9.97069597e-01 -2.32634321e-02 -6.95096850e-02 9.97321069e-01 -2.32633743e-02 -6.60036728e-02 9.97561336e-01 -2.32633725e-02 -6.25203997e-02 9.97783720e-01 -2.32633837e-02 -5.91729768e-02 9.97989595e-01 -2.32633632e-02 -5.57062551e-02 9.98190105e-01 -2.32634172e-02 -5.21421991e-02 9.98379886e-01 -2.32633594e-02 -4.87074703e-02 9.98556852e-01 -2.32634284e-02 -4.51264121e-02 9.98721778e-01 -2.32633930e-02 -4.16574106e-02 9.98874664e-01 -2.32634004e-02 -3.81548442e-02 9.99013662e-01 -2.32633930e-02 -3.47426832e-02 9.99138296e-01 -2.32633650e-02 -3.12815495e-02 9.99252558e-01 -2.32634228e-02 -2.77523138e-02 9.99355197e-01 -2.32633594e-02 -2.42820196e-02 9.99451399e-01 -2.32634284e-02 -2.07093973e-02 9.99526024e-01 -2.32633911e-02 -1.72977615e-02 9.99594748e-01 -2.32633688e-02 -1.38280820e-02 9.99643505e-01 -2.32634284e-02 -1.03406170e-02 9.99684691e-01 -2.32633483e-02 -6.93677645e-03 9.99722362e-01 -2.32633688e-02 -3.33290873e-03 9.99741971e-01 -2.32634116e-02 2.11894614e-04 9.99742687e-01 -2.32633892e-02 3.71826370e-03 9.99740958e-01 -2.32633818e-02 7.17183808e-03 9.99720216e-01 -2.32633837e-02 1.05824340e-02 9.99684274e-01 -2.32633539e-02 1.39885359e-02 9.99640942e-01 -2.32633892e-02 1.75560657e-02 9.99592662e-01 -2.32634153e-02 2.11451426e-02 9.99518216e-01 -2.32633930e-02 2.46677138e-02 9.99438286e-01 -2.32633911e-02 2.81618275e-02 9.99347270e-01 -2.32633986e-02 3.16625684e-02 9.99241173e-01 -2.32633911e-02 3.50602679e-02 9.99127209e-01 -2.32633352e-02 3.85075025e-02 9.99001563e-01 -2.32634135e-02 4.21015024e-02 9.98856604e-01 -2.32633967e-02 4.56070155e-02 9.98700619e-01 -2.32633837e-02 4.90874499e-02 9.98536408e-01 -2.32633855e-02 5.24744727e-02 9.98361230e-01 -2.32633650e-02 5.59598282e-02 9.98175442e-01 -2.32634116e-02 5.94628900e-02 9.97971892e-01 -2.32633483e-02 6.29226267e-02 9.97758985e-01 -2.32634377e-02 6.65050969e-02 9.97527361e-01 -2.32633930e-02 6.99763075e-02 9.97288167e-01 -2.32633911e-02 7.34543651e-02 9.97040987e-01 -2.32633930e-02 7.69546777e-02 9.96775031e-01 -2.32634041e-02 8.03319663e-02 9.96508539e-01 -2.32633427e-02 8.38079676e-02 9.96224046e-01 -2.32634190e-02 8.73411968e-02 9.95920181e-01 -2.32633948e-02 9.08413231e-02 9.95606422e-01 -2.32633911e-02 9.43041593e-02 9.95283604e-01 -2.32633688e-02 9.77261961e-02 9.94953275e-01 -2.32633352e-02 1.01183757e-01 9.94609773e-01 -2.32634246e-02 1.04655743e-01 9.94249225e-01 -2.32633706e-02 1.08123742e-01 9.93879855e-01 -2.32634470e-02 1.11685492e-01 9.93483543e-01 -2.32633911e-02 1.15086727e-01 9.93093312e-01 -2.32633520e-02 1.18543543e-01 9.92688835e-01 -2.32634209e-02 1.21997081e-01 9.92270052e-01 -2.32633688e-02 1.25442341e-01 9.91842151e-01 -2.32634265e-02 1.29001081e-01 9.91383612e-01 -2.32633986e-02 1.32469520e-01 9.90926683e-01 -2.32633874e-02 1.35930821e-01 9.90458965e-01 -2.32633874e-02 1.39295444e-01 9.89992082e-01 -2.32633501e-02 1.42762765e-01 9.89496469e-01 -2.32633967e-02 1.46203235e-01 9.88992870e-01 -2.32633539e-02 1.49652988e-01 9.88476753e-01 -2.32634284e-02 1.53194010e-01 9.87937033e-01 -2.32633930e-02 1.56532124e-01 9.87409472e-01 -2.32633520e-02 1.59981743e-01 9.86859620e-01 -2.32633930e-02 1.63467690e-01 9.86288190e-01 -2.32633594e-02 1.66796952e-01 9.85729992e-01 -2.32633986e-02 1.70311287e-01 9.85129654e-01 -2.32634209e-02 1.73842475e-01 9.84514952e-01 -2.32633706e-02 1.77268356e-01 9.83905911e-01 -2.32633874e-02 1.80738717e-01 9.83268499e-01 -2.32633855e-02 1.84065819e-01 9.82651412e-01 -2.32633632e-02 1.87387988e-01 9.82023776e-01 -2.32633986e-02 1.90833509e-01 9.81359422e-01 -2.32633911e-02 1.94339558e-01 9.80672002e-01 -2.32634302e-02 1.97824687e-01 9.79974210e-01 -2.32633911e-02 2.01261178e-01 9.79275048e-01 -2.32634041e-02 2.04676270e-01 9.78565753e-01 -2.32633986e-02 2.08011210e-01 9.77864802e-01 -2.32633743e-02 2.11403415e-01 9.77136374e-01 -2.32634414e-02 2.14899972e-01 9.76372302e-01 -2.32634079e-02 2.18321815e-01 9.75613058e-01 -2.32633948e-02 2.21773848e-01 9.74832416e-01 -2.32633855e-02 2.25073680e-01 9.74077046e-01 -2.32633557e-02 2.28439465e-01 9.73296762e-01 -2.32634321e-02 2.31860042e-01 9.72484648e-01 -2.32633557e-02 2.35144183e-01 9.71698940e-01 -2.32634116e-02 2.38637120e-01 9.70844924e-01 -2.32634414e-02 2.42131874e-01 9.69976962e-01 -2.32633967e-02 2.45474681e-01 9.69136000e-01 -2.32633948e-02 2.48833165e-01 9.68282342e-01 -2.32634004e-02 2.52155393e-01 9.67420638e-01 -2.32633837e-02 2.55443811e-01 9.66559589e-01 -2.32634246e-02 2.58930922e-01 9.65630114e-01 -2.32634451e-02 2.62396455e-01 9.64695156e-01 -2.32634116e-02 2.65732467e-01 9.63778436e-01 -2.32633948e-02 2.68977195e-01 9.62880135e-01 -2.32633557e-02 2.72349089e-01 9.61931407e-01 -2.32634284e-02 2.75720567e-01 9.60970879e-01 -2.32633743e-02 2.79048979e-01 9.60009396e-01 -2.32634321e-02 2.82533824e-01 9.58989084e-01 -2.32634060e-02 2.85790980e-01 9.58024919e-01 -2.32633706e-02 2.89110214e-01 9.57025290e-01 -2.32634451e-02 2.92485654e-01 9.56000090e-01 -2.32633743e-02 2.95740873e-01 9.55001116e-01 -2.32634284e-02 2.99182177e-01 9.53928053e-01 -2.32634377e-02 3.02449733e-01 9.52894211e-01 -2.32633781e-02 3.05763066e-01 9.51838672e-01 -2.32634451e-02 3.09119105e-01 9.50751960e-01 -2.32633837e-02 3.12425166e-01 9.49672282e-01 -2.32634451e-02 3.15718681e-01 9.48580801e-01 -2.32633837e-02 3.18931043e-01 9.47507739e-01 -2.32634190e-02 3.22333932e-01 9.46355522e-01 -2.32634451e-02 3.25731754e-01 9.45190609e-01 -2.32634023e-02 3.29007506e-01 9.44054306e-01 -2.32634060e-02 3.32286924e-01 9.42906201e-01 -2.32634060e-02 3.35523754e-01 9.41760898e-01 -2.32633837e-02 3.38780046e-01 9.40592587e-01 -2.32634451e-02 3.42167825e-01 9.39366400e-01 -2.32634246e-02 3.45445871e-01 9.38157499e-01 -2.32634060e-02 3.48685324e-01 9.36955154e-01 -2.32634004e-02 3.51921231e-01 9.35744464e-01 -2.32633818e-02 3.55147362e-01 9.34532762e-01 -2.32634321e-02 3.58419269e-01 9.33291674e-01 -2.32633855e-02 3.61667037e-01 9.32030022e-01 -2.32634451e-02 3.64970505e-01 9.30741549e-01 -2.32634041e-02 3.68179709e-01 9.29476857e-01 -2.32633706e-02 3.71405721e-01 9.28193331e-01 -2.32634433e-02 3.74634296e-01 9.26894248e-01 -2.32633818e-02 3.77858102e-01 9.25585985e-01 -2.32634451e-02 3.81086737e-01 9.24258709e-01 -2.32633948e-02 3.84302735e-01 9.22928751e-01 -2.32634451e-02 3.87602895e-01 9.21547413e-01 -2.32634246e-02 3.90722036e-01 9.20226991e-01 -2.32633837e-02 3.93935204e-01 9.18855786e-01 -2.32634451e-02 3.97150069e-01 9.17471647e-01 -2.32633855e-02 4.00257468e-01 9.16124225e-01 -2.32634060e-02 4.03527260e-01 9.14687514e-01 -2.32634451e-02 4.06779170e-01 9.13244784e-01 -2.32633967e-02 4.09985214e-01 9.11810100e-01 -2.32634246e-02 4.13163811e-01 9.10374463e-01 -2.32634041e-02 4.16272879e-01 9.08953965e-01 -2.32633818e-02 4.19360936e-01 9.07534719e-01 -2.32634172e-02 4.22570974e-01 9.06046450e-01 -2.32634209e-02 4.25836742e-01 9.04513299e-01 -2.32633855e-02 4.28974837e-01 9.03030753e-01 -2.32633948e-02 4.32073742e-01 9.01550353e-01 -2.32633688e-02 4.35192227e-01 9.00054395e-01 -2.32634284e-02 4.38333392e-01 8.98529172e-01 -2.32633874e-02 4.41464871e-01 8.96991372e-01 -2.32634451e-02 4.44667697e-01 8.95408511e-01 -2.32634135e-02 4.47805464e-01 8.93843770e-01 -2.32634284e-02 4.50909615e-01 8.92283678e-01 -2.32634284e-02 4.53956157e-01 8.90735865e-01 -2.32633818e-02 4.57004488e-01 8.89176190e-01 -2.32634172e-02 4.60164785e-01 8.87540042e-01 -2.32633501e-02 4.63203639e-01 8.85964096e-01 -2.32633930e-02 4.66348678e-01 8.84311795e-01 -2.32634451e-02 4.69486624e-01 8.82649183e-01 -2.32633986e-02 4.72572356e-01 8.81001234e-01 -2.32634377e-02 4.75651145e-01 8.79342139e-01 -2.32634209e-02 4.78638470e-01 8.77722025e-01 -2.32633874e-02 4.81697977e-01 8.76045287e-01 -2.32634563e-02 4.84843850e-01 8.74304831e-01 -2.32634321e-02 4.87887502e-01 8.72610569e-01 -2.32634060e-02 4.90971714e-01 8.70880961e-01 -2.32633892e-02 4.93882477e-01 8.69231403e-01 -2.32633837e-02 4.96919215e-01 8.67501795e-01 -2.32634451e-02 4.99939650e-01 8.65762949e-01 -2.32633650e-02 5.02967536e-01 8.64008963e-01 -2.32634451e-02 5.06070197e-01 8.62195671e-01 -2.32634339e-02 5.09013951e-01 8.60458910e-01 -2.32633874e-02 5.11971653e-01 8.58705044e-01 -2.32634507e-02 5.14977396e-01 8.56903732e-01 -2.32633874e-02 5.17962456e-01 8.55102003e-01 -2.32634414e-02 5.21000743e-01 8.53256643e-01 -2.32634172e-02 5.23920655e-01 8.51463079e-01 -2.32633911e-02 5.26884317e-01 8.49637747e-01 -2.32634563e-02 5.29848516e-01 8.47789466e-01 -2.32633892e-02 5.32787621e-01 8.45946074e-01 -2.32634414e-02 5.35759628e-01 8.44064653e-01 -2.32633818e-02 5.38684189e-01 8.42201829e-01 -2.32634321e-02 5.41712046e-01 8.40257525e-01 -2.32634284e-02 5.44578195e-01 8.38401496e-01 -2.32633650e-02 5.47467172e-01 8.36518109e-01 -2.32634116e-02 5.50372899e-01 8.34607661e-01 -2.32633036e-02 5.53213418e-01 8.32726419e-01 -2.32632942e-02 5.56202054e-01 8.30733299e-01 -2.32632924e-02 5.59087515e-01 8.28790128e-01 -2.32631452e-02 5.61958969e-01 8.26846838e-01 -2.32631657e-02 5.64908147e-01 8.24829996e-01 -2.32630335e-02 5.67732513e-01 8.22881997e-01 -2.32630391e-02 5.70469499e-01 8.20984900e-01 -2.32630484e-02 5.73236525e-01 8.19057047e-01 -2.32630912e-02 5.76088250e-01 8.17056060e-01 -2.32631750e-02 5.78997433e-01 8.14996541e-01 -2.32631471e-02 5.82075000e-01 8.12801719e-01 -2.32631452e-02 5.84755182e-01 8.10875058e-01 -2.32631378e-02 5.87731540e-01 8.08720887e-01 -2.32631378e-02 5.90656996e-01 8.06587279e-01 -2.32631415e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.10852504e-01 7.02956319e-01 -2.32631397e-02 7.14217603e-01 6.99535787e-01 -2.32631397e-02 7.17737436e-01 6.95924997e-01 -2.32631415e-02 7.19628036e-01 6.93969965e-01 -2.32631210e-02 7.21792281e-01 6.91715658e-01 -2.32630670e-02 7.24164367e-01 6.89229369e-01 -2.32630409e-02 7.26486206e-01 6.86791241e-01 -2.32630335e-02 7.28901625e-01 6.84233010e-01 -2.32631750e-02 7.31316805e-01 6.81652546e-01 -2.32631993e-02 7.33652115e-01 6.79141521e-01 -2.32632589e-02 7.35978425e-01 6.76623285e-01 -2.32632998e-02 7.38274455e-01 6.74117804e-01 -2.32633725e-02 7.40675509e-01 6.71482801e-01 -2.32634060e-02 7.43086457e-01 6.68811381e-01 -2.32633874e-02 7.45401800e-01 6.66227579e-01 -2.32633874e-02 7.47658491e-01 6.63696110e-01 -2.32633576e-02 7.49927819e-01 6.61130309e-01 -2.32633948e-02 7.52249062e-01 6.58485770e-01 -2.32634172e-02 7.54573822e-01 6.55822814e-01 -2.32634004e-02 7.56891608e-01 6.53147757e-01 -2.32634284e-02 7.59179473e-01 6.50486171e-01 -2.32633874e-02 7.61379600e-01 6.47905946e-01 -2.32633762e-02 7.63627827e-01 6.45259976e-01 -2.32634209e-02 7.65877724e-01 6.42585933e-01 -2.32633986e-02 7.68147171e-01 6.39873326e-01 -2.32634451e-02 7.70440102e-01 6.37107611e-01 -2.32634060e-02 7.72602797e-01 6.34485841e-01 -2.32633855e-02 7.74803996e-01 6.31794095e-01 -2.32634377e-02 7.77054012e-01 6.29025280e-01 -2.32634135e-02 7.79256821e-01 6.26295149e-01 -2.32634284e-02 7.81388819e-01 6.23633325e-01 -2.32633855e-02 7.83493936e-01 6.20986164e-01 -2.32634284e-02 7.85702646e-01 6.18191063e-01 -2.32634563e-02 7.87913918e-01 6.15368843e-01 -2.32634209e-02 7.90069520e-01 6.12599254e-01 -2.32634451e-02 7.92161703e-01 6.09888971e-01 -2.32633725e-02 7.94216335e-01 6.07212126e-01 -2.32634135e-02 7.96385229e-01 6.04366302e-01 -2.32634563e-02 7.98548639e-01 6.01502836e-01 -2.32634135e-02 8.00647378e-01 5.98704994e-01 -2.32633986e-02 8.02683890e-01 5.95972955e-01 -2.32633725e-02 8.04684699e-01 5.93267322e-01 -2.32634060e-02 8.06794703e-01 5.90396285e-01 -2.32634451e-02 8.08920145e-01 5.87481558e-01 -2.32634284e-02 8.10981452e-01 5.84629118e-01 -2.32634041e-02 8.13002229e-01 5.81818938e-01 -2.32634079e-02 8.14966023e-01 5.79064846e-01 -2.32633725e-02 8.16948235e-01 5.76268911e-01 -2.32634339e-02 8.18961501e-01 5.73401093e-01 -2.32634172e-02 8.21001530e-01 5.70475757e-01 -2.32634731e-02 8.23021770e-01 5.67557514e-01 -2.32633818e-02 8.24923515e-01 5.64789116e-01 -2.32634209e-02 8.26953173e-01 5.61815083e-01 -2.32634731e-02 8.28915536e-01 5.58912635e-01 -2.32633706e-02 8.30808461e-01 5.56095839e-01 -2.32634339e-02 8.32753241e-01 5.53179562e-01 -2.32634172e-02 8.34647357e-01 5.50317526e-01 -2.32634209e-02 8.36620927e-01 5.47311664e-01 -2.32634451e-02 8.38579893e-01 5.44306457e-01 -2.32634377e-02 8.40424955e-01 5.41451216e-01 -2.32633799e-02 8.42256188e-01 5.38600266e-01 -2.32634097e-02 8.44121993e-01 5.35668135e-01 -2.32634377e-02 8.46060753e-01 5.32607257e-01 -2.32634563e-02 8.47980678e-01 5.29541552e-01 -2.32634321e-02 8.49814355e-01 5.26595473e-01 -2.32634004e-02 8.51582825e-01 5.23726106e-01 -2.32633892e-02 8.53370965e-01 5.20813704e-01 -2.32634172e-02 8.55179489e-01 5.17835081e-01 -2.32634246e-02 8.56989503e-01 5.14834642e-01 -2.32634097e-02 8.58824134e-01 5.11768043e-01 -2.32634563e-02 8.60652387e-01 5.08686900e-01 -2.32634116e-02 8.62381637e-01 5.05750597e-01 -2.32633837e-02 8.64131868e-01 5.02754986e-01 -2.32634451e-02 8.65888953e-01 4.99723613e-01 -2.32633855e-02 8.67622077e-01 4.96708304e-01 -2.32634544e-02 8.69367421e-01 4.93641764e-01 -2.32633911e-02 8.71037185e-01 4.90696341e-01 -2.32633911e-02 8.72774422e-01 4.87596095e-01 -2.32634451e-02 8.74481022e-01 4.84524727e-01 -2.32633967e-02 8.76163125e-01 4.81482178e-01 -2.32634284e-02 8.77831638e-01 4.78433460e-01 -2.32633874e-02 8.79461288e-01 4.75430369e-01 -2.32634116e-02 8.81149530e-01 4.72294241e-01 -2.32634377e-02 8.82840753e-01 4.69126552e-01 -2.32634246e-02 8.84482384e-01 4.66023117e-01 -2.32634097e-02 8.86055708e-01 4.63025063e-01 -2.32633818e-02 8.87610257e-01 4.60034698e-01 -2.32633967e-02 8.89254808e-01 4.56851631e-01 -2.32634544e-02 8.90889645e-01 4.53653842e-01 -2.32634228e-02 8.92467618e-01 4.50542003e-01 -2.32634004e-02 8.94039273e-01 4.47415739e-01 -2.32634172e-02 8.95562887e-01 4.44354296e-01 -2.32633706e-02 8.97093296e-01 4.41259861e-01 -2.32634414e-02 8.98632526e-01 4.38115239e-01 -2.32633576e-02 9.00158882e-01 4.34974551e-01 -2.32634377e-02 9.01711583e-01 4.31742370e-01 -2.32634060e-02 9.03176844e-01 4.28668529e-01 -2.32633818e-02 9.04651284e-01 4.25547659e-01 -2.32634451e-02 9.06138480e-01 4.22372341e-01 -2.32633818e-02 9.07608569e-01 4.19207573e-01 -2.32634451e-02 9.09109592e-01 4.15936649e-01 -2.32634172e-02 9.10522938e-01 4.12833124e-01 -2.32633613e-02 9.11943913e-01 4.09690291e-01 -2.32634451e-02 9.13374662e-01 4.06485319e-01 -2.32633743e-02 9.14783597e-01 4.03308123e-01 -2.32634377e-02 9.16187942e-01 4.00108486e-01 -2.32633650e-02 9.17552888e-01 3.96964937e-01 -2.32634041e-02 9.18963552e-01 3.93683553e-01 -2.32634395e-02 9.20366347e-01 3.90398264e-01 -2.32633967e-02 9.21723068e-01 3.87185007e-01 -2.32633967e-02 9.23031390e-01 3.84051859e-01 -2.32633781e-02 9.24328864e-01 3.80917788e-01 -2.32634209e-02 9.25687313e-01 3.77609044e-01 -2.32634451e-02 9.27050412e-01 3.74250770e-01 -2.32634079e-02 9.28350627e-01 3.71011466e-01 -2.32634004e-02 9.29604411e-01 3.67863089e-01 -2.32633743e-02 9.30841208e-01 3.64724249e-01 -2.32634060e-02 9.32128251e-01 3.61407906e-01 -2.32634451e-02 9.33406830e-01 3.58117074e-01 -2.32633818e-02 9.34634149e-01 3.54878545e-01 -2.32634451e-02 9.35907483e-01 3.51490557e-01 -2.32634172e-02 9.37092662e-01 3.48313332e-01 -2.32633818e-02 9.38302577e-01 3.45058858e-01 -2.32634451e-02 9.39510524e-01 3.41776252e-01 -2.32633818e-02 9.40690458e-01 3.38509321e-01 -2.32634563e-02 9.41896021e-01 3.35143000e-01 -2.32634135e-02 9.43039536e-01 3.31908464e-01 -2.32633855e-02 9.44178641e-01 3.28652173e-01 -2.32634451e-02 9.45350170e-01 3.25269938e-01 -2.32634190e-02 9.46468711e-01 3.21995288e-01 -2.32634041e-02 9.47563648e-01 3.18762928e-01 -2.32633725e-02 9.48654056e-01 3.15499663e-01 -2.32634041e-02 9.49774742e-01 3.12113941e-01 -2.32634563e-02 9.50882554e-01 3.08722466e-01 -2.32634135e-02 9.51954663e-01 3.05401444e-01 -2.32634172e-02 9.52990234e-01 3.02151322e-01 -2.32633837e-02 9.54010308e-01 2.98915297e-01 -2.32634135e-02 9.55078423e-01 2.95484543e-01 -2.32634451e-02 9.56130981e-01 2.92056948e-01 -2.32634135e-02 9.57138002e-01 2.88741946e-01 -2.32634079e-02 9.58110571e-01 2.85493970e-01 -2.32633892e-02 9.59082305e-01 2.82219231e-01 -2.32634097e-02 9.60084975e-01 2.78793126e-01 -2.32634451e-02 9.61051226e-01 2.75435925e-01 -2.32633818e-02 9.62009847e-01 2.72078127e-01 -2.32634563e-02 9.62971330e-01 2.68648714e-01 -2.32633967e-02 9.63879108e-01 2.65369892e-01 -2.32633688e-02 9.64803576e-01 2.62000978e-01 -2.32634451e-02 9.65737164e-01 2.58529216e-01 -2.32634041e-02 9.66627240e-01 2.55184740e-01 -2.32634116e-02 9.67510402e-01 2.51814157e-01 -2.32633892e-02 9.68368948e-01 2.48494402e-01 -2.32633706e-02 9.69222724e-01 2.45131895e-01 -2.32634079e-02 9.70079005e-01 2.41725177e-01 -2.32633725e-02 9.70915258e-01 2.38354102e-01 -2.32634451e-02 9.71744061e-01 2.34950617e-01 -2.32633837e-02 9.72537041e-01 2.31648088e-01 -2.32633948e-02 9.73351002e-01 2.28206545e-01 -2.32634284e-02 9.74165022e-01 2.24692702e-01 -2.32633892e-02 9.74944413e-01 2.21287906e-01 -2.32633892e-02 9.75710750e-01 2.17889726e-01 -2.32634041e-02 9.76444960e-01 2.14558885e-01 -2.32633501e-02 9.77188468e-01 2.11158171e-01 -2.32634377e-02 9.77936327e-01 2.07666278e-01 -2.32633855e-02 9.78660345e-01 2.04234764e-01 -2.32633986e-02 9.79366541e-01 2.00821117e-01 -2.32634060e-02 9.80044067e-01 1.97479591e-01 -2.32633818e-02 9.80717480e-01 1.94106400e-01 -2.32634377e-02 9.81401443e-01 1.90618619e-01 -2.32633501e-02 9.82054532e-01 1.87222689e-01 -2.32634451e-02 9.82715070e-01 1.83727816e-01 -2.32634041e-02 9.83332932e-01 1.80375636e-01 -2.32633706e-02 9.83969450e-01 1.76917568e-01 -2.32634451e-02 9.84585881e-01 1.73444659e-01 -2.32633855e-02 9.85182285e-01 1.69998705e-01 -2.32633874e-02 9.85757589e-01 1.66638374e-01 -2.32633930e-02 9.86319602e-01 1.63275391e-01 -2.32634153e-02 9.86899853e-01 1.59735799e-01 -2.32634563e-02 9.87463713e-01 1.56204239e-01 -2.32634209e-02 9.88000453e-01 1.52770326e-01 -2.32634228e-02 9.88515019e-01 1.49397582e-01 -2.32633874e-02 9.89018857e-01 1.46038249e-01 -2.32634190e-02 9.89534140e-01 1.42506033e-01 -2.32634563e-02 9.90040123e-01 1.38952434e-01 -2.32634190e-02 9.90515172e-01 1.35528892e-01 -2.32633948e-02 9.90984678e-01 1.32040873e-01 -2.32633948e-02 9.91429746e-01 1.28648445e-01 -2.32633688e-02 9.91872549e-01 1.25203669e-01 -2.32634451e-02 9.92312133e-01 1.21660389e-01 -2.32634097e-02 9.92732227e-01 1.18173756e-01 -2.32634023e-02 9.93136644e-01 1.14732705e-01 -2.32634209e-02 9.93521392e-01 1.11354865e-01 -2.32633892e-02 9.93905365e-01 1.07877359e-01 -2.32634563e-02 9.94276345e-01 1.04399428e-01 -2.32633837e-02 9.94632304e-01 1.00943111e-01 -2.32634284e-02 9.94990528e-01 9.73614827e-02 -2.32634209e-02 9.95313525e-01 9.39955041e-02 -2.32633706e-02 9.95636046e-01 9.05300677e-02 -2.32634563e-02 9.95945394e-01 8.70550722e-02 -2.32633725e-02 9.96245384e-01 8.35484192e-02 -2.32634451e-02 9.96531844e-01 8.00479427e-02 -2.32633837e-02 9.96803880e-01 7.66081437e-02 -2.32634488e-02 9.97071862e-01 7.30251521e-02 -2.32634321e-02 9.97320771e-01 6.95196316e-02 -2.32634135e-02 9.97558713e-01 6.60467148e-02 -2.32634209e-02 9.97775674e-01 6.26584962e-02 -2.32633837e-02 9.97982502e-01 5.92731796e-02 -2.32634079e-02 9.98191297e-01 5.56931980e-02 -2.32634563e-02 9.98383939e-01 5.21002784e-02 -2.32634079e-02 9.98561502e-01 4.86061573e-02 -2.32634284e-02 9.98716593e-01 4.52390909e-02 -2.32633706e-02 9.98865962e-01 4.18784358e-02 -2.32634172e-02 9.99005616e-01 3.83769237e-02 -2.32634284e-02 9.99134123e-01 3.48807238e-02 -2.32634135e-02 9.99254107e-01 3.12851258e-02 -2.32634563e-02 9.99359846e-01 2.76820138e-02 -2.32634079e-02 9.99448717e-01 2.42894720e-02 -2.32633669e-02 9.99522150e-01 2.09090393e-02 -2.32634116e-02 9.99595225e-01 1.74276903e-02 -2.32634153e-02 9.99641716e-01 1.39370058e-02 -2.32633948e-02 9.99688506e-01 1.04307448e-02 -2.32634060e-02 9.99724030e-01 6.94946293e-03 -2.32633967e-02 9.99742985e-01 3.36485333e-03 -2.32634563e-02 9.99742448e-01 -1.28134139e-04 -2.32633781e-02 9.99742150e-01 -3.60272522e-03 -2.32634284e-02 9.99720395e-01 -7.14164926e-03 -2.32633706e-02 9.99686360e-01 -1.05348015e-02 -2.32633967e-02 9.99639511e-01 -1.40464799e-02 -2.32634284e-02 9.99590337e-01 -1.76748354e-02 -2.32634116e-02 9.99518514e-01 -2.10766774e-02 -2.32633874e-02 9.99443233e-01 -2.45784111e-02 -2.32634563e-02 9.99347985e-01 -2.80720200e-02 -2.32633781e-02 9.99246001e-01 -3.15277278e-02 -2.32634414e-02 9.99130011e-01 -3.50262858e-02 -2.32633967e-02 9.99003708e-01 -3.84248719e-02 -2.32634172e-02 9.98864591e-01 -4.19138707e-02 -2.32634116e-02 9.98709321e-01 -4.54500094e-02 -2.32634563e-02 9.98539209e-01 -4.90604825e-02 -2.32634060e-02 9.98360038e-01 -5.25317155e-02 -2.32634135e-02 9.98174191e-01 -5.59494570e-02 -2.32633874e-02 9.97979820e-01 -5.93390316e-02 -2.32634284e-02 9.97765541e-01 -6.28155768e-02 -2.32634302e-02 9.97536838e-01 -6.63805678e-02 -2.32634451e-02 9.97291803e-01 -6.99308142e-02 -2.32633948e-02 9.97042060e-01 -7.34388903e-02 -2.32633986e-02 9.96785700e-01 -7.68244192e-02 -2.32633930e-02 9.96517301e-01 -8.02387372e-02 -2.32634116e-02 9.96233582e-01 -8.36859122e-02 -2.32634041e-02 9.95925963e-01 -8.72752368e-02 -2.32634284e-02 9.95613515e-01 -9.07605290e-02 -2.32633706e-02 9.95302141e-01 -9.41228718e-02 -2.32634060e-02 9.94964242e-01 -9.76312310e-02 -2.32633986e-02 9.94610608e-01 -1.01168789e-01 -2.32634451e-02 9.94250119e-01 -1.04651675e-01 -2.32633781e-02 9.93881464e-01 -1.08094484e-01 -2.32634451e-02 9.93497014e-01 -1.11569658e-01 -2.32633669e-02 9.93113995e-01 -1.14924207e-01 -2.32634079e-02 9.92696881e-01 -1.18489318e-01 -2.32634377e-02 9.92272913e-01 -1.21976137e-01 -2.32633725e-02 9.91844893e-01 -1.25433758e-01 -2.32634358e-02 9.91385639e-01 -1.28990442e-01 -2.32634172e-02 9.90940332e-01 -1.32366523e-01 -2.32633837e-02 9.90478277e-01 -1.35800064e-01 -2.32634284e-02 9.89982128e-01 -1.39366403e-01 -2.32634041e-02 9.89500940e-01 -1.42733142e-01 -2.32633725e-02 9.89001036e-01 -1.46160230e-01 -2.32634321e-02 9.88484204e-01 -1.49605125e-01 -2.32633725e-02 9.87957895e-01 -1.53045222e-01 -2.32634284e-02 9.87407267e-01 -1.56551778e-01 -2.32633520e-02 9.86868560e-01 -1.59924179e-01 -2.32634079e-02 9.86304760e-01 -1.63368180e-01 -2.32633706e-02 9.85719800e-01 -1.66861907e-01 -2.32634079e-02 9.85114753e-01 -1.70381069e-01 -2.32633818e-02 9.84524012e-01 -1.73795715e-01 -2.32634041e-02 9.83925343e-01 -1.77147225e-01 -2.32633818e-02 9.83307660e-01 -1.80515975e-01 -2.32633930e-02 9.82672632e-01 -1.83965072e-01 -2.32634041e-02 9.82015669e-01 -1.87429681e-01 -2.32634377e-02 9.81338143e-01 -1.90944448e-01 -2.32634041e-02 9.80664909e-01 -1.94376484e-01 -2.32634060e-02 9.79992688e-01 -1.97731361e-01 -2.32633837e-02 9.79319036e-01 -2.01041639e-01 -2.32633837e-02 9.78604496e-01 -2.04495475e-01 -2.32633986e-02 9.77875412e-01 -2.07965896e-01 -2.32634563e-02 9.77139354e-01 -2.11386994e-01 -2.32633818e-02 9.76409912e-01 -2.14727595e-01 -2.32634172e-02 9.75646138e-01 -2.18175188e-01 -2.32633688e-02 9.74877954e-01 -2.21580237e-01 -2.32634321e-02 9.74096715e-01 -2.24991426e-01 -2.32633539e-02 9.73295629e-01 -2.28442580e-01 -2.32634377e-02 9.72495615e-01 -2.31817931e-01 -2.32633706e-02 9.71712053e-01 -2.35087559e-01 -2.32633986e-02 9.70862925e-01 -2.38563344e-01 -2.32634451e-02 9.70023036e-01 -2.41947994e-01 -2.32633855e-02 9.69162405e-01 -2.45373935e-01 -2.32634507e-02 9.68276203e-01 -2.48850778e-01 -2.32633986e-02 9.67426479e-01 -2.52129942e-01 -2.32633594e-02 9.66555297e-01 -2.55465239e-01 -2.32634377e-02 9.65642035e-01 -2.58885413e-01 -2.32633557e-02 9.64766383e-01 -2.62134820e-01 -2.32633948e-02 9.63822126e-01 -2.65578330e-01 -2.32634414e-02 9.62874532e-01 -2.68999875e-01 -2.32633781e-02 9.61943805e-01 -2.72305548e-01 -2.32634153e-02 9.60952997e-01 -2.75776803e-01 -2.32633986e-02 9.60007787e-01 -2.79042542e-01 -2.32633408e-02 9.59060907e-01 -2.82290131e-01 -2.32634041e-02 9.58044708e-01 -2.85725325e-01 -2.32634284e-02 9.57019925e-01 -2.89125979e-01 -2.32633892e-02 9.56009686e-01 -2.92454541e-01 -2.32633967e-02 9.54998851e-01 -2.95743972e-01 -2.32633781e-02 9.53990161e-01 -2.98978269e-01 -2.32633967e-02 9.52945828e-01 -3.02288681e-01 -2.32633911e-02 9.51843500e-01 -3.05746645e-01 -2.32634321e-02 9.50742900e-01 -3.09147418e-01 -2.32634116e-02 9.49666202e-01 -3.12439114e-01 -2.32633837e-02 9.48581278e-01 -3.15718949e-01 -2.32633688e-02 9.47522104e-01 -3.18885893e-01 -2.32633855e-02 9.46396530e-01 -3.22206110e-01 -2.32633706e-02 9.45239067e-01 -3.25592488e-01 -2.32634321e-02 9.44089413e-01 -3.28901142e-01 -2.32633632e-02 9.42967474e-01 -3.32111537e-01 -2.32633892e-02 9.41816568e-01 -3.35362017e-01 -2.32633911e-02 9.40597236e-01 -3.38766843e-01 -2.32634284e-02 9.39404845e-01 -3.42063308e-01 -2.32633725e-02 9.38202798e-01 -3.45328629e-01 -2.32634321e-02 9.36982453e-01 -3.48607510e-01 -2.32633762e-02 9.35795665e-01 -3.51789653e-01 -2.32634023e-02 9.34564590e-01 -3.55056673e-01 -2.32633948e-02 9.33331609e-01 -3.58311594e-01 -2.32633986e-02 9.32059526e-01 -3.61585945e-01 -2.32633967e-02 9.30767477e-01 -3.64913553e-01 -2.32634321e-02 9.29488063e-01 -3.68151903e-01 -2.32633706e-02 9.28210318e-01 -3.71363312e-01 -2.32634377e-02 9.26891387e-01 -3.74639660e-01 -2.32633706e-02 9.25626516e-01 -3.77757490e-01 -2.32634116e-02 9.24265742e-01 -3.81073326e-01 -2.32634451e-02 9.22922313e-01 -3.84315491e-01 -2.32633837e-02 9.21575129e-01 -3.87540609e-01 -2.32634377e-02 9.20181513e-01 -3.90829653e-01 -2.32634116e-02 9.18840885e-01 -3.93968225e-01 -2.32633725e-02 9.17512178e-01 -3.97057652e-01 -2.32633892e-02 9.16091323e-01 -4.00333881e-01 -2.32634451e-02 9.14627612e-01 -4.03661042e-01 -2.32634172e-02 9.13210034e-01 -4.06856775e-01 -2.32633967e-02 9.11807656e-01 -4.09989715e-01 -2.32633688e-02 9.10395145e-01 -4.13116515e-01 -2.32633818e-02 9.08992946e-01 -4.16189164e-01 -2.32633930e-02 9.07494783e-01 -4.19448286e-01 -2.32634246e-02 9.05995965e-01 -4.22675759e-01 -2.32633874e-02 9.04492974e-01 -4.25881028e-01 -2.32633911e-02 9.03032660e-01 -4.28969771e-01 -2.32633669e-02 9.01595771e-01 -4.31979746e-01 -2.32633948e-02 9.00080800e-01 -4.35137540e-01 -2.32633948e-02 8.98508251e-01 -4.38376397e-01 -2.32634377e-02 8.96938443e-01 -4.41571385e-01 -2.32633874e-02 8.95399034e-01 -4.44685698e-01 -2.32633948e-02 8.93864095e-01 -4.47761148e-01 -2.32633688e-02 8.92345488e-01 -4.50784594e-01 -2.32633874e-02 8.90759289e-01 -4.53908980e-01 -2.32633874e-02 8.89129519e-01 -4.57095265e-01 -2.32634433e-02 8.87526929e-01 -4.60193723e-01 -2.32633818e-02 8.85905445e-01 -4.63313967e-01 -2.32634097e-02 8.84309649e-01 -4.66351360e-01 -2.32633743e-02 8.82704318e-01 -4.69379872e-01 -2.32634116e-02 8.81068110e-01 -4.72446382e-01 -2.32633892e-02 8.79360139e-01 -4.75618005e-01 -2.32634284e-02 8.77686143e-01 -4.78703141e-01 -2.32633725e-02 8.76072526e-01 -4.81646210e-01 -2.32634041e-02 8.74368668e-01 -4.84728634e-01 -2.32634041e-02 8.72645080e-01 -4.87827390e-01 -2.32634358e-02 8.70917261e-01 -4.90905941e-01 -2.32633706e-02 8.69209290e-01 -4.93923396e-01 -2.32634284e-02 8.67474973e-01 -4.96964425e-01 -2.32633501e-02 8.65752637e-01 -4.99959826e-01 -2.32634451e-02 8.63977015e-01 -5.03019810e-01 -2.32633706e-02 8.62280428e-01 -5.05925000e-01 -2.32634023e-02 8.60482872e-01 -5.08975208e-01 -2.32634116e-02 8.58692825e-01 -5.11986971e-01 -2.32633874e-02 8.56882095e-01 -5.15014708e-01 -2.32634246e-02 8.55041206e-01 -5.18063128e-01 -2.32634246e-02 8.53257358e-01 -5.20999670e-01 -2.32633930e-02 8.51494670e-01 -5.23871064e-01 -2.32634172e-02 8.49659920e-01 -5.26845753e-01 -2.32634060e-02 8.47768307e-01 -5.29881716e-01 -2.32634563e-02 8.45878065e-01 -5.32894015e-01 -2.32634023e-02 8.44050407e-01 -5.35781801e-01 -2.32633855e-02 8.42218041e-01 -5.38658321e-01 -2.32634097e-02 8.40288281e-01 -5.41665673e-01 -2.32634451e-02 8.38331282e-01 -5.44688225e-01 -2.32634135e-02 8.36443067e-01 -5.47581494e-01 -2.32633986e-02 8.34525108e-01 -5.50502658e-01 -2.32634116e-02 8.32630694e-01 -5.53358495e-01 -2.32633706e-02 8.30755413e-01 -5.56173265e-01 -2.32633948e-02 8.28826904e-01 -5.59048772e-01 -2.32633930e-02 8.26806962e-01 -5.62029064e-01 -2.32634414e-02 8.24775338e-01 -5.65005481e-01 -2.32633874e-02 8.22823048e-01 -5.67847252e-01 -2.32633930e-02 8.20884466e-01 -5.70642591e-01 -2.32633818e-02 8.18893373e-01 -5.73497534e-01 -2.32634246e-02 8.16888571e-01 -5.76351285e-01 -2.32633781e-02 8.14850450e-01 -5.79228222e-01 -2.32634321e-02 8.12823832e-01 -5.82068264e-01 -2.32633669e-02 8.10814679e-01 -5.84860384e-01 -2.32634172e-02 8.08730066e-01 -5.87744057e-01 -2.32634284e-02 8.06643367e-01 -5.90601623e-01 -2.32633967e-02 8.04560959e-01 -5.93437672e-01 -2.32634041e-02 8.02471220e-01 -5.96258819e-01 -2.32634060e-02 8.00448060e-01 -5.98970115e-01 -2.32633706e-02 7.98365831e-01 -6.01747572e-01 -2.32634451e-02 7.96259761e-01 -6.04529440e-01 -2.32633706e-02 7.94140518e-01 -6.07312202e-01 -2.32634451e-02 7.92011321e-01 -6.10083461e-01 -2.32633725e-02 7.89941788e-01 -6.12760127e-01 -2.32634172e-02 7.87735403e-01 -6.15596414e-01 -2.32634451e-02 7.85526097e-01 -6.18413150e-01 -2.32634135e-02 7.83414841e-01 -6.21083260e-01 -2.32633874e-02 7.81302452e-01 -6.23742521e-01 -2.32634172e-02 7.79065251e-01 -6.26533210e-01 -2.32634451e-02 7.76822627e-01 -6.29312277e-01 -2.32634265e-02 7.74658918e-01 -6.31969810e-01 -2.32633930e-02 7.72508562e-01 -6.34599924e-01 -2.32634172e-02 7.70297766e-01 -6.37282252e-01 -2.32634209e-02 7.68081725e-01 -6.39950633e-01 -2.32634284e-02 7.65838981e-01 -6.42632365e-01 -2.32634135e-02 7.63538897e-01 -6.45364225e-01 -2.32634451e-02 7.61282921e-01 -6.48021460e-01 -2.32633874e-02 7.59071052e-01 -6.50611758e-01 -2.32634284e-02 7.56791651e-01 -6.53263211e-01 -2.32634004e-02 7.54479766e-01 -6.55932844e-01 -2.32634339e-02 7.52135575e-01 -6.58618093e-01 -2.32634321e-02 7.49790192e-01 -6.61286414e-01 -2.32634060e-02 7.47524798e-01 -6.63844824e-01 -2.32633706e-02 7.45276928e-01 -6.66369557e-01 -2.32634079e-02 7.42893994e-01 -6.69026852e-01 -2.32634451e-02 7.40556121e-01 -6.71612263e-01 -2.32633781e-02 7.38198817e-01 -6.74201667e-01 -2.32634563e-02 7.35832810e-01 -6.76783681e-01 -2.32633706e-02 7.33555138e-01 -6.79252505e-01 -2.32634172e-02 7.31180489e-01 -6.81804597e-01 -2.32634079e-02 7.28740335e-01 -6.84413850e-01 -2.32634321e-02 7.26324499e-01 -6.86974704e-01 -2.32633688e-02 7.23911047e-01 -6.89523458e-01 -2.32634172e-02 7.21494317e-01 -6.92042589e-01 -2.32633278e-02 7.19115436e-01 -6.94525898e-01 -2.32633576e-02 7.16656566e-01 -6.97054923e-01 -2.32631844e-02 7.14314938e-01 -6.99449658e-01 -2.32631322e-02 7.12039590e-01 -7.01751411e-01 -2.32630502e-02 7.09763706e-01 -7.04054594e-01 -2.32631452e-02 7.07490861e-01 -7.06339180e-01 -2.32631415e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.63697815e-01 -8.25653434e-01 -2.32631378e-02 5.61308980e-01 -8.27279985e-01 -2.32631750e-02 5.58858395e-01 -8.28934312e-01 -2.32630335e-02 5.56036651e-01 -8.30840170e-01 -2.32631303e-02 5.53116083e-01 -8.32790732e-01 -2.32632961e-02 5.50195932e-01 -8.34723353e-01 -2.32632793e-02 5.47354043e-01 -8.36590111e-01 -2.32633129e-02 5.44457912e-01 -8.38479638e-01 -2.32633539e-02 5.41528702e-01 -8.40375304e-01 -2.32633650e-02 5.38612247e-01 -8.42246056e-01 -2.32633818e-02 5.35662115e-01 -8.44126463e-01 -2.32633911e-02 5.32729447e-01 -8.45982969e-01 -2.32633930e-02 5.29790163e-01 -8.47823262e-01 -2.32633967e-02 5.26827931e-01 -8.49670947e-01 -2.32633930e-02 5.23855329e-01 -8.51503611e-01 -2.32633967e-02 5.20888984e-01 -8.53325665e-01 -2.32633986e-02 5.17898560e-01 -8.55140388e-01 -2.32634023e-02 5.14905393e-01 -8.56947601e-01 -2.32634004e-02 5.11844277e-01 -8.58779430e-01 -2.32634433e-02 5.08804619e-01 -8.60582054e-01 -2.32633743e-02 5.05909860e-01 -8.62289131e-01 -2.32634041e-02 5.02889991e-01 -8.64051819e-01 -2.32634041e-02 4.99787420e-01 -8.65852892e-01 -2.32634563e-02 4.96738583e-01 -8.67603481e-01 -2.32633818e-02 4.93805051e-01 -8.69274616e-01 -2.32634060e-02 4.90763366e-01 -8.71001244e-01 -2.32634190e-02 4.87733215e-01 -8.72697651e-01 -2.32634135e-02 4.84688342e-01 -8.74390662e-01 -2.32634284e-02 4.81639951e-01 -8.76077056e-01 -2.32634209e-02 4.78568375e-01 -8.77758384e-01 -2.32634079e-02 4.75481421e-01 -8.79433572e-01 -2.32634284e-02 4.72426176e-01 -8.81078362e-01 -2.32634172e-02 4.69340205e-01 -8.82726014e-01 -2.32634284e-02 4.66248482e-01 -8.84364605e-01 -2.32634172e-02 4.63108063e-01 -8.86012077e-01 -2.32634507e-02 4.59990561e-01 -8.87632549e-01 -2.32633874e-02 4.56975311e-01 -8.89191210e-01 -2.32634209e-02 4.53872114e-01 -8.90778244e-01 -2.32634228e-02 4.50745583e-01 -8.92364800e-01 -2.32634135e-02 4.47627068e-01 -8.93931925e-01 -2.32634116e-02 4.44498062e-01 -8.95493925e-01 -2.32634284e-02 4.41376299e-01 -8.97036254e-01 -2.32634172e-02 4.38227862e-01 -8.98579001e-01 -2.32634265e-02 4.35073048e-01 -9.00111198e-01 -2.32634153e-02 4.31948841e-01 -9.01611269e-01 -2.32634079e-02 4.28693384e-01 -9.03164685e-01 -2.32634563e-02 4.25514638e-01 -9.04665887e-01 -2.32633818e-02 4.22381729e-01 -9.06135380e-01 -2.32634563e-02 4.19194192e-01 -9.07612562e-01 -2.32633818e-02 4.16147053e-01 -9.09013331e-01 -2.32634209e-02 4.12965566e-01 -9.10464585e-01 -2.32634190e-02 4.09764707e-01 -9.11909699e-01 -2.32634209e-02 4.06498700e-01 -9.13371027e-01 -2.32634563e-02 4.03288096e-01 -9.14790809e-01 -2.32633855e-02 4.00199294e-01 -9.16149020e-01 -2.32634172e-02 3.97003651e-01 -9.17536139e-01 -2.32634302e-02 3.93786460e-01 -9.18918908e-01 -2.32634265e-02 3.90547246e-01 -9.20303345e-01 -2.32634321e-02 3.87336642e-01 -9.21660423e-01 -2.32634135e-02 3.84150892e-01 -9.22992110e-01 -2.32634284e-02 3.80906790e-01 -9.24334109e-01 -2.32634079e-02 3.77731144e-01 -9.25638735e-01 -2.32634209e-02 3.74488294e-01 -9.26954687e-01 -2.32634321e-02 3.71162593e-01 -9.28291082e-01 -2.32634563e-02 3.67892295e-01 -9.29592311e-01 -2.32633911e-02 3.64723682e-01 -9.30841327e-01 -2.32634284e-02 3.61484408e-01 -9.32096601e-01 -2.32634284e-02 3.58223170e-01 -9.33364749e-01 -2.32634284e-02 3.54960293e-01 -9.34602141e-01 -2.32634209e-02 3.51699531e-01 -9.35829520e-01 -2.32634172e-02 3.48413408e-01 -9.37057436e-01 -2.32634284e-02 3.45070928e-01 -9.38298821e-01 -2.32634488e-02 3.41784179e-01 -9.39507127e-01 -2.32633874e-02 3.38538200e-01 -9.40679789e-01 -2.32634563e-02 3.35242599e-01 -9.41860199e-01 -2.32633892e-02 3.31936061e-01 -9.43030059e-01 -2.32634563e-02 3.28651428e-01 -9.44177628e-01 -2.32633930e-02 3.25351924e-01 -9.45322156e-01 -2.32634544e-02 3.22035879e-01 -9.46453631e-01 -2.32633874e-02 3.18809688e-01 -9.47548807e-01 -2.32634358e-02 3.15511793e-01 -9.48650301e-01 -2.32634321e-02 3.12177420e-01 -9.49751854e-01 -2.32634116e-02 3.08897942e-01 -9.50823963e-01 -2.32634209e-02 3.05564582e-01 -9.51902568e-01 -2.32634284e-02 3.02250117e-01 -9.52958226e-01 -2.32634172e-02 2.98942626e-01 -9.54002023e-01 -2.32634284e-02 2.95585245e-01 -9.55047667e-01 -2.32634209e-02 2.92263418e-01 -9.56070006e-01 -2.32634284e-02 2.88862646e-01 -9.57100213e-01 -2.32634526e-02 2.85497695e-01 -9.58110273e-01 -2.32633911e-02 2.82225788e-01 -9.59080219e-01 -2.32634153e-02 2.78779626e-01 -9.60088313e-01 -2.32634563e-02 2.75364906e-01 -9.61072981e-01 -2.32634321e-02 2.71989107e-01 -9.62033153e-01 -2.32634135e-02 2.68742830e-01 -9.62945759e-01 -2.32633818e-02 2.65484810e-01 -9.63848770e-01 -2.32634209e-02 2.62117147e-01 -9.64772344e-01 -2.32634284e-02 2.58760810e-01 -9.65674937e-01 -2.32634321e-02 2.55284160e-01 -9.66600895e-01 -2.32634731e-02 2.51887560e-01 -9.67491329e-01 -2.32633874e-02 2.48520970e-01 -9.68361318e-01 -2.32634563e-02 2.45126694e-01 -9.69224215e-01 -2.32633855e-02 2.41774365e-01 -9.70066547e-01 -2.32634563e-02 2.38357916e-01 -9.70913172e-01 -2.32633892e-02 2.35060975e-01 -9.71718311e-01 -2.32634209e-02 2.31634870e-01 -9.72541153e-01 -2.32634451e-02 2.28236854e-01 -9.73343670e-01 -2.32634172e-02 2.24868059e-01 -9.74126935e-01 -2.32634284e-02 2.21353620e-01 -9.74930823e-01 -2.32634563e-02 2.17942625e-01 -9.75699008e-01 -2.32633874e-02 2.14627683e-01 -9.76432085e-01 -2.32634116e-02 2.11209923e-01 -9.77177382e-01 -2.32634172e-02 2.07810149e-01 -9.77906823e-01 -2.32634172e-02 2.04317912e-01 -9.78644013e-01 -2.32634563e-02 2.00891808e-01 -9.79351759e-01 -2.32633911e-02 1.97548717e-01 -9.80030894e-01 -2.32634321e-02 1.94134027e-01 -9.80713010e-01 -2.32634079e-02 1.90711319e-01 -9.81384873e-01 -2.32634302e-02 1.87198892e-01 -9.82060015e-01 -2.32634563e-02 1.83760852e-01 -9.82708395e-01 -2.32633892e-02 1.80320576e-01 -9.83345270e-01 -2.32634563e-02 1.76892102e-01 -9.83973145e-01 -2.32633892e-02 1.73553765e-01 -9.84567523e-01 -2.32634284e-02 1.70131534e-01 -9.85158741e-01 -2.32634209e-02 1.66694269e-01 -9.85749245e-01 -2.32634321e-02 1.63239762e-01 -9.86325145e-01 -2.32634321e-02 1.59784392e-01 -9.86890972e-01 -2.32634172e-02 1.56370044e-01 -9.87439096e-01 -2.32634321e-02 1.52928799e-01 -9.87977684e-01 -2.32634284e-02 1.49477169e-01 -9.88503039e-01 -2.32634190e-02 1.45960689e-01 -9.89030361e-01 -2.32634414e-02 1.42516524e-01 -9.89530444e-01 -2.32634023e-02 1.39102101e-01 -9.90017891e-01 -2.32634116e-02 1.35542333e-01 -9.90512729e-01 -2.32634563e-02 1.32085040e-01 -9.90977287e-01 -2.32633874e-02 1.28703475e-01 -9.91424263e-01 -2.32634135e-02 1.25273496e-01 -9.91863847e-01 -2.32634172e-02 1.21808916e-01 -9.92293894e-01 -2.32634172e-02 1.18211828e-01 -9.92729604e-01 -2.32634563e-02 1.14751957e-01 -9.93133783e-01 -2.32633874e-02 1.11403503e-01 -9.93516386e-01 -2.32634284e-02 1.07916355e-01 -9.93900657e-01 -2.32634116e-02 1.04459047e-01 -9.94270086e-01 -2.32634135e-02 1.00901276e-01 -9.94635999e-01 -2.32634563e-02 9.74125564e-02 -9.94985104e-01 -2.32633892e-02 9.39661413e-02 -9.95319366e-01 -2.32634731e-02 9.04544070e-02 -9.95642900e-01 -2.32633892e-02 8.70104060e-02 -9.95950282e-01 -2.32634563e-02 8.34461600e-02 -9.96253550e-01 -2.32634004e-02 8.00388977e-02 -9.96533334e-01 -2.32633818e-02 7.66538754e-02 -9.96799350e-01 -2.32634302e-02 7.31816143e-02 -9.97061670e-01 -2.32634284e-02 6.96827173e-02 -9.97309864e-01 -2.32634321e-02 6.62153885e-02 -9.97547805e-01 -2.32634246e-02 6.27424344e-02 -9.97772276e-01 -2.32634321e-02 5.92485294e-02 -9.97985065e-01 -2.32634209e-02 5.57601675e-02 -9.98187065e-01 -2.32634246e-02 5.22816256e-02 -9.98373091e-01 -2.32634246e-02 4.88029793e-02 -9.98552084e-01 -2.32634246e-02 4.53416854e-02 -9.98714745e-01 -2.32634321e-02 4.17466648e-02 -9.98870909e-01 -2.32634731e-02 3.82466279e-02 -9.99009967e-01 -2.32633892e-02 3.48858275e-02 -9.99133706e-01 -2.32634209e-02 3.12905423e-02 -9.99252856e-01 -2.32634563e-02 2.77770292e-02 -9.99356747e-01 -2.32633911e-02 2.42870580e-02 -9.99450624e-01 -2.32634563e-02 2.07852498e-02 -9.99524593e-01 -2.32633781e-02 1.74225457e-02 -9.99595344e-01 -2.32634228e-02 1.38422186e-02 -9.99642074e-01 -2.32634563e-02 1.03240097e-02 -9.99688327e-01 -2.32633911e-02 6.95881620e-03 -9.99724925e-01 -2.32634246e-02 3.44907166e-03 -9.99742389e-01 -2.32634284e-02 -5.36814950e-05 -9.99743581e-01 -2.32634321e-02 -3.61751975e-03 -9.99742806e-01 -2.32634582e-02 -7.10824179e-03 -9.99723256e-01 -2.32633967e-02 -1.05878292e-02 -9.99688148e-01 -2.32634600e-02 -1.40741160e-02 -9.99639094e-01 -2.32633930e-02 -1.75435506e-02 -9.99595523e-01 -2.32634563e-02 -2.11304165e-02 -9.99517798e-01 -2.32634321e-02 -2.45509651e-02 -9.99443173e-01 -2.32634079e-02 -2.79700980e-02 -9.99352455e-01 -2.32634321e-02 -3.14390920e-02 -9.99249876e-01 -2.32634321e-02 -3.49212252e-02 -9.99134481e-01 -2.32634451e-02 -3.85111421e-02 -9.99001920e-01 -2.32634712e-02 -4.20236439e-02 -9.98859227e-01 -2.32633930e-02 -4.53971103e-02 -9.98711228e-01 -2.32634377e-02 -4.88715954e-02 -9.98548746e-01 -2.32634246e-02 -5.23471162e-02 -9.98369873e-01 -2.32634284e-02 -5.59067503e-02 -9.98180628e-01 -2.32634563e-02 -5.94161823e-02 -9.97976065e-01 -2.32633892e-02 -6.29021227e-02 -9.97759700e-01 -2.32634563e-02 -6.63806349e-02 -9.97535527e-01 -2.32633986e-02 -6.97607249e-02 -9.97304559e-01 -2.32634284e-02 -7.33146220e-02 -9.97052133e-01 -2.32634563e-02 -7.68076256e-02 -9.96786714e-01 -2.32634097e-02 -8.02847743e-02 -9.96514261e-01 -2.32634451e-02 -8.37688670e-02 -9.96225774e-01 -2.32633930e-02 -8.71617198e-02 -9.95935678e-01 -2.32634209e-02 -9.07115564e-02 -9.95619059e-01 -2.32634563e-02 -9.42089781e-02 -9.95292425e-01 -2.32633892e-02 -9.76570621e-02 -9.94962335e-01 -2.32634563e-02 -1.01148106e-01 -9.94613230e-01 -2.32633874e-02 -1.04597464e-01 -9.94256973e-01 -2.32634731e-02 -1.08187526e-01 -9.93871868e-01 -2.32634246e-02 -1.11543454e-01 -9.93500173e-01 -2.32633874e-02 -1.14904411e-01 -9.93117571e-01 -2.32634284e-02 -1.18387967e-01 -9.92707670e-01 -2.32634321e-02 -1.21849634e-01 -9.92290080e-01 -2.32634321e-02 -1.25401422e-01 -9.91847873e-01 -2.32634563e-02 -1.28899485e-01 -9.91396904e-01 -2.32633986e-02 -1.32236287e-01 -9.90959883e-01 -2.32634284e-02 -1.35693893e-01 -9.90491569e-01 -2.32634284e-02 -1.39143005e-01 -9.90013659e-01 -2.32634451e-02 -1.42699182e-01 -9.89506185e-01 -2.32634638e-02 -1.46157160e-01 -9.89000082e-01 -2.32633874e-02 -1.49605945e-01 -9.88484919e-01 -2.32634563e-02 -1.53044030e-01 -9.87960458e-01 -2.32633948e-02 -1.56388402e-01 -9.87435162e-01 -2.32634284e-02 -1.59869641e-01 -9.86878574e-01 -2.32634284e-02 -1.63289234e-01 -9.86319125e-01 -2.32634172e-02 -1.66833207e-01 -9.85726058e-01 -2.32634693e-02 -1.70283526e-01 -9.85132515e-01 -2.32633874e-02 -1.73618183e-01 -9.84555602e-01 -2.32634284e-02 -1.77120209e-01 -9.83931005e-01 -2.32634451e-02 -1.80554807e-01 -9.83301461e-01 -2.32634079e-02 -1.84017703e-01 -9.82663751e-01 -2.32634731e-02 -1.87474862e-01 -9.82006490e-01 -2.32633837e-02 -1.90784708e-01 -9.81369793e-01 -2.32634246e-02 -1.94225341e-01 -9.80695307e-01 -2.32634284e-02 -1.97704047e-01 -9.80000615e-01 -2.32634563e-02 -2.01161265e-01 -9.79294360e-01 -2.32633967e-02 -2.04500258e-01 -9.78603482e-01 -2.32634284e-02 -2.07907349e-01 -9.77888048e-01 -2.32634321e-02 -2.11398184e-01 -9.77138937e-01 -2.32634563e-02 -2.14820489e-01 -9.76388037e-01 -2.32634004e-02 -2.18134239e-01 -9.75656092e-01 -2.32634321e-02 -2.21546635e-01 -9.74885881e-01 -2.32634358e-02 -2.24938735e-01 -9.74108458e-01 -2.32634228e-02 -2.28418902e-01 -9.73302782e-01 -2.32634563e-02 -2.31821403e-01 -9.72495019e-01 -2.32633948e-02 -2.35113069e-01 -9.71706092e-01 -2.32634228e-02 -2.38584176e-01 -9.70858514e-01 -2.32634563e-02 -2.41977587e-01 -9.70016360e-01 -2.32633930e-02 -2.45366246e-01 -9.69164371e-01 -2.32634563e-02 -2.48748764e-01 -9.68303204e-01 -2.32633948e-02 -2.52026528e-01 -9.67454791e-01 -2.32634321e-02 -2.55426794e-01 -9.66563880e-01 -2.32634284e-02 -2.58870631e-01 -9.65646029e-01 -2.32634563e-02 -2.62338161e-01 -9.64710832e-01 -2.32634246e-02 -2.65634477e-01 -9.63806212e-01 -2.32633911e-02 -2.68871397e-01 -9.62911069e-01 -2.32634321e-02 -2.72269875e-01 -9.61954892e-01 -2.32634321e-02 -2.75613844e-01 -9.61000860e-01 -2.32634321e-02 -2.78963059e-01 -9.60034430e-01 -2.32634172e-02 -2.82300413e-01 -9.59058285e-01 -2.32634377e-02 -2.85644412e-01 -9.58069623e-01 -2.32634321e-02 -2.88986981e-01 -9.57063198e-01 -2.32634284e-02 -2.92337120e-01 -9.56045151e-01 -2.32634321e-02 -2.95747250e-01 -9.54999745e-01 -2.32634563e-02 -2.99107969e-01 -9.53949392e-01 -2.32633986e-02 -3.02428931e-01 -9.52903211e-01 -2.32634563e-02 -3.05750579e-01 -9.51842844e-01 -2.32633892e-02 -3.08960795e-01 -9.50805008e-01 -2.32634377e-02 -3.12359691e-01 -9.49693859e-01 -2.32634563e-02 -3.15735996e-01 -9.48575854e-01 -2.32634116e-02 -3.19036990e-01 -9.47473407e-01 -2.32634377e-02 -3.22293669e-01 -9.46367800e-01 -2.32633948e-02 -3.25498253e-01 -9.45271730e-01 -2.32634246e-02 -3.28836113e-01 -9.44114029e-01 -2.32634321e-02 -3.32130820e-01 -9.42961454e-01 -2.32634284e-02 -3.35482925e-01 -9.41773891e-01 -2.32634470e-02 -3.38767201e-01 -9.40595210e-01 -2.32633874e-02 -3.42032492e-01 -9.39416409e-01 -2.32634544e-02 -3.45309019e-01 -9.38208520e-01 -2.32634041e-02 -3.48512352e-01 -9.37019944e-01 -2.32634284e-02 -3.51781726e-01 -9.35798287e-01 -2.32634190e-02 -3.55038136e-01 -9.34573591e-01 -2.32634377e-02 -3.58379930e-01 -9.33305740e-01 -2.32634563e-02 -3.61742795e-01 -9.31999326e-01 -2.32634451e-02 -3.64915729e-01 -9.30764079e-01 -2.32633874e-02 -3.68049145e-01 -9.29530263e-01 -2.32634284e-02 -3.71281117e-01 -9.28242981e-01 -2.32634358e-02 -3.74517500e-01 -9.26942945e-01 -2.32634246e-02 -3.77834529e-01 -9.25595999e-01 -2.32634731e-02 -3.81162792e-01 -9.24227774e-01 -2.32634284e-02 -3.84315073e-01 -9.22922194e-01 -2.32633874e-02 -3.87418747e-01 -9.21624959e-01 -2.32634321e-02 -3.90650153e-01 -9.20259893e-01 -2.32634358e-02 -3.93942595e-01 -9.18852270e-01 -2.32634619e-02 -3.97171497e-01 -9.17462885e-01 -2.32633911e-02 -4.00354683e-01 -9.16081965e-01 -2.32634731e-02 -4.03548360e-01 -9.14676726e-01 -2.32633855e-02 -4.06644851e-01 -9.13305700e-01 -2.32634321e-02 -4.09850240e-01 -9.11872327e-01 -2.32634228e-02 -4.13024664e-01 -9.10436869e-01 -2.32634284e-02 -4.16255683e-01 -9.08964634e-01 -2.32634563e-02 -4.19432431e-01 -9.07501638e-01 -2.32633948e-02 -4.22532111e-01 -9.06063914e-01 -2.32634358e-02 -4.25677389e-01 -9.04590905e-01 -2.32634321e-02 -4.28919226e-01 -9.03058946e-01 -2.32634600e-02 -4.32078153e-01 -9.01548147e-01 -2.32633986e-02 -4.35139358e-01 -9.00080979e-01 -2.32634377e-02 -4.38291013e-01 -8.98550332e-01 -2.32634284e-02 -4.41483229e-01 -8.96983624e-01 -2.32634563e-02 -4.44618583e-01 -8.95434439e-01 -2.32633967e-02 -4.47648942e-01 -8.93922269e-01 -2.32634451e-02 -4.50780123e-01 -8.92349243e-01 -2.32634377e-02 -4.53883320e-01 -8.90774190e-01 -2.32634377e-02 -4.57075804e-01 -8.89139950e-01 -2.32634731e-02 -4.60172564e-01 -8.87537897e-01 -2.32633874e-02 -4.63195115e-01 -8.85969758e-01 -2.32634284e-02 -4.66263115e-01 -8.84356141e-01 -2.32634284e-02 -4.69346106e-01 -8.82723570e-01 -2.32634377e-02 -4.72507507e-01 -8.81037712e-01 -2.32634582e-02 -4.75597948e-01 -8.79369438e-01 -2.32633986e-02 -4.78652596e-01 -8.77713978e-01 -2.32634563e-02 -4.81719643e-01 -8.76032472e-01 -2.32633930e-02 -4.84775007e-01 -8.74345422e-01 -2.32634768e-02 -4.87919927e-01 -8.72593939e-01 -2.32634321e-02 -4.90882516e-01 -8.70930731e-01 -2.32634023e-02 -4.93896455e-01 -8.69227111e-01 -2.32634805e-02 -4.96944368e-01 -8.67487371e-01 -2.32633967e-02 -4.99882549e-01 -8.65797222e-01 -2.32634451e-02 -5.02911329e-01 -8.64041448e-01 -2.32634451e-02 -5.05934000e-01 -8.62275302e-01 -2.32634377e-02 -5.08932889e-01 -8.60508323e-01 -2.32634321e-02 -5.11914432e-01 -8.58737826e-01 -2.32634358e-02 -5.14908969e-01 -8.56946230e-01 -2.32634284e-02 -5.17917514e-01 -8.55130255e-01 -2.32634563e-02 -5.20987093e-01 -8.53266537e-01 -2.32634656e-02 -5.24016142e-01 -8.51406693e-01 -2.32634451e-02 -5.26906967e-01 -8.49620700e-01 -2.32634023e-02 -5.29792607e-01 -8.47826123e-01 -2.32634321e-02 -5.32834291e-01 -8.45916569e-01 -2.32634768e-02 -5.35797536e-01 -8.44041765e-01 -2.32634041e-02 -5.38722754e-01 -8.42178047e-01 -2.32634731e-02 -5.41679382e-01 -8.40278625e-01 -2.32633986e-02 -5.44500172e-01 -8.38454008e-01 -2.32634451e-02 -5.47504306e-01 -8.36494863e-01 -2.32634749e-02 -5.50447226e-01 -8.34562421e-01 -2.32633892e-02 -5.53253174e-01 -8.32701981e-01 -2.32634377e-02 -5.56158245e-01 -8.30766857e-01 -2.32634209e-02 -5.59151590e-01 -8.28758478e-01 -2.32634731e-02 -5.62050760e-01 -8.26788843e-01 -2.32633911e-02 -5.64827025e-01 -8.24899971e-01 -2.32634451e-02 -5.67708790e-01 -8.22918713e-01 -2.32634321e-02 -5.70576727e-01 -8.20932627e-01 -2.32634563e-02 -5.73526919e-01 -8.18872631e-01 -2.32634768e-02 -5.76491416e-01 -8.16791296e-01 -2.32634433e-02 -5.79261303e-01 -8.14825892e-01 -2.32633948e-02 -5.81994474e-01 -8.12877595e-01 -2.32634377e-02 -5.84828436e-01 -8.10837090e-01 -2.32634377e-02 -5.87674558e-01 -8.08780789e-01 -2.32634377e-02 -5.90562999e-01 -8.06672812e-01 -2.32634563e-02 -5.93454659e-01 -8.04547668e-01 -2.32634451e-02 -5.96195877e-01 -8.02518606e-01 -2.32633911e-02 -5.98899245e-01 -8.00502360e-01 -2.32634321e-02 -6.01691484e-01 -7.98406959e-01 -2.32634377e-02 -6.04546607e-01 -7.96250284e-01 -2.32634731e-02 -6.07345760e-01 -7.94114053e-01 -2.32634041e-02 -6.10100269e-01 -7.92000175e-01 -2.32634768e-02 -6.12860680e-01 -7.89865375e-01 -2.32633930e-02 -6.15535855e-01 -7.87782609e-01 -2.32634377e-02 -6.18359387e-01 -7.85570264e-01 -2.32634731e-02 -6.21092975e-01 -7.83408582e-01 -2.32633930e-02 -6.23830736e-01 -7.81232357e-01 -2.32634693e-02 -6.26561344e-01 -7.79041946e-01 -2.32633911e-02 -6.29176140e-01 -7.76935339e-01 -2.32634433e-02 -6.31891906e-01 -7.74723351e-01 -2.32634451e-02 -6.34585738e-01 -7.72520542e-01 -2.32634321e-02 -6.37343407e-01 -7.70248890e-01 -2.32634768e-02 -6.40037417e-01 -7.68008292e-01 -2.32633986e-02 -6.42637491e-01 -7.65835106e-01 -2.32634321e-02 -6.45375371e-01 -7.63529420e-01 -2.32634731e-02 -6.48040950e-01 -7.61267841e-01 -2.32633986e-02 -6.50627315e-01 -7.59058952e-01 -2.32634470e-02 -6.53282404e-01 -7.56777167e-01 -2.32634321e-02 -6.55906558e-01 -7.54504323e-01 -2.32634321e-02 -6.58619344e-01 -7.52134740e-01 -2.32634768e-02 -6.61240876e-01 -7.49830365e-01 -2.32633986e-02 -6.63773060e-01 -7.47591317e-01 -2.32634451e-02 -6.66379631e-01 -7.45267689e-01 -2.32634377e-02 -6.68960750e-01 -7.42951870e-01 -2.32634339e-02 -6.71619415e-01 -7.40552664e-01 -2.32634563e-02 -6.74210966e-01 -7.38188744e-01 -2.32634116e-02 -6.76791728e-01 -7.35829175e-01 -2.32634656e-02 -6.79356337e-01 -7.33458281e-01 -2.32634079e-02 -6.81904435e-01 -7.31090307e-01 -2.32634731e-02 -6.84521437e-01 -7.28640318e-01 -2.32634395e-02 -6.87002599e-01 -7.26299405e-01 -2.32633967e-02 -6.89501882e-01 -7.23932862e-01 -2.32634731e-02 -6.92054749e-01 -7.21482396e-01 -2.32634004e-02 -6.94480538e-01 -7.19164193e-01 -2.32634377e-02 -6.96993113e-01 -7.16726303e-01 -2.32634377e-02 -6.99478388e-01 -7.14297354e-01 -2.32634321e-02 -7.02042639e-01 -7.11780846e-01 -2.32634805e-02 -7.04541385e-01 -7.09307373e-01 -2.32633986e-02 -7.06912756e-01 -7.06926346e-01 -2.32634563e-02 -7.09389031e-01 -7.04460621e-01 -2.32634451e-02 -7.11925983e-01 -7.01895416e-01 -2.32634824e-02 -7.14389861e-01 -6.99383736e-01 -2.32633986e-02 -7.16746211e-01 -6.96972072e-01 -2.32634321e-02 -7.19166636e-01 -6.94477320e-01 -2.32634321e-02 -7.21641660e-01 -6.91891193e-01 -2.32634731e-02 -7.24133432e-01 -6.89292073e-01 -2.32634451e-02 -7.26540804e-01 -6.86747253e-01 -2.32634470e-02 -7.28875041e-01 -6.84268475e-01 -2.32633948e-02 -7.31186390e-01 -6.81799471e-01 -2.32634414e-02 -7.33622074e-01 -6.79180741e-01 -2.32634731e-02 -7.35996842e-01 -6.76606238e-01 -2.32633986e-02 -7.38288581e-01 -6.74105108e-01 -2.32634433e-02 -7.40640998e-01 -6.71519995e-01 -2.32634284e-02 -7.42991328e-01 -6.68917656e-01 -2.32634284e-02 -7.45315969e-01 -6.66326046e-01 -2.32634284e-02 -7.47641861e-01 -6.63718224e-01 -2.32634395e-02 -7.50024498e-01 -6.61022246e-01 -2.32634600e-02 -7.52313733e-01 -6.58413708e-01 -2.32633967e-02 -7.54607141e-01 -6.55785739e-01 -2.32634731e-02 -7.56959498e-01 -6.53067708e-01 -2.32634209e-02 -7.59171426e-01 -6.50496721e-01 -2.32633874e-02 -7.61422515e-01 -6.47859037e-01 -2.32634731e-02 -7.63688385e-01 -6.45188451e-01 -2.32633948e-02 -7.65874982e-01 -6.42589331e-01 -2.32634321e-02 -7.68158615e-01 -6.39861882e-01 -2.32634582e-02 -7.70401835e-01 -6.37154520e-01 -2.32633948e-02 -7.72569299e-01 -6.34528220e-01 -2.32634284e-02 -7.74767816e-01 -6.31838024e-01 -2.32634414e-02 -7.76971281e-01 -6.29128098e-01 -2.32634284e-02 -7.79217601e-01 -6.26344979e-01 -2.32634619e-02 -7.81457067e-01 -6.23548627e-01 -2.32634135e-02 -7.83630311e-01 -6.20813549e-01 -2.32634377e-02 -7.85746157e-01 -6.18134022e-01 -2.32633986e-02 -7.87839055e-01 -6.15465283e-01 -2.32634284e-02 -7.90036440e-01 -6.12644017e-01 -2.32634563e-02 -7.92159200e-01 -6.09894335e-01 -2.32633967e-02 -7.94293344e-01 -6.07114136e-01 -2.32634731e-02 -7.96411455e-01 -6.04329586e-01 -2.32633911e-02 -7.98448324e-01 -6.01638854e-01 -2.32634302e-02 -8.00525784e-01 -5.98867774e-01 -2.32634284e-02 -8.02617848e-01 -5.96060574e-01 -2.32634377e-02 -8.04739416e-01 -5.93194962e-01 -2.32634563e-02 -8.06823492e-01 -5.90356827e-01 -2.32634060e-02 -8.08890998e-01 -5.87522388e-01 -2.32634638e-02 -8.10986161e-01 -5.84621727e-01 -2.32634153e-02 -8.12969387e-01 -5.81865132e-01 -2.32633892e-02 -8.14981759e-01 -5.79044759e-01 -2.32634563e-02 -8.17006350e-01 -5.76182723e-01 -2.32633874e-02 -8.18959653e-01 -5.73403537e-01 -2.32634377e-02 -8.21006358e-01 -5.70469856e-01 -2.32634731e-02 -8.23012531e-01 -5.67572236e-01 -2.32633874e-02 -8.24909866e-01 -5.64810634e-01 -2.32634451e-02 -8.26891959e-01 -5.61903536e-01 -2.32634209e-02 -8.28851700e-01 -5.59010029e-01 -2.32634284e-02 -8.30847800e-01 -5.56037903e-01 -2.32634638e-02 -8.32790852e-01 -5.53119719e-01 -2.32634004e-02 -8.34717751e-01 -5.50210953e-01 -2.32634563e-02 -8.36645484e-01 -5.47272682e-01 -2.32633930e-02 -8.38491142e-01 -5.44444203e-01 -2.32634228e-02 -8.40386391e-01 -5.41513264e-01 -2.32634284e-02 -8.42257142e-01 -5.38597405e-01 -2.32634190e-02 -8.44173014e-01 -5.35589337e-01 -2.32634563e-02 -8.46036077e-01 -5.32643497e-01 -2.32633911e-02 -8.47843051e-01 -5.29760361e-01 -2.32634209e-02 -8.49686146e-01 -5.26804686e-01 -2.32634284e-02 -8.51516426e-01 -5.23836076e-01 -2.32634284e-02 -8.53385746e-01 -5.20789981e-01 -2.32634563e-02 -8.55210006e-01 -5.17783284e-01 -2.32633930e-02 -8.56998801e-01 -5.14821947e-01 -2.32634563e-02 -8.58788133e-01 -5.11826396e-01 -2.32634023e-02 -8.60527337e-01 -5.08900106e-01 -2.32634284e-02 -8.62331152e-01 -5.05838990e-01 -2.32634563e-02 -8.64091635e-01 -5.02823591e-01 -2.32634060e-02 -8.65803421e-01 -4.99872208e-01 -2.32634284e-02 -8.67528856e-01 -4.96869415e-01 -2.32634321e-02 -8.69268119e-01 -4.93819118e-01 -2.32634414e-02 -8.70988667e-01 -4.90785003e-01 -2.32634321e-02 -8.72692168e-01 -4.87742722e-01 -2.32634321e-02 -8.74382436e-01 -4.84704703e-01 -2.32634358e-02 -8.76124561e-01 -4.81554717e-01 -2.32634731e-02 -8.77802610e-01 -4.78489280e-01 -2.32633911e-02 -8.79424691e-01 -4.75497276e-01 -2.32634209e-02 -8.81084204e-01 -4.72416133e-01 -2.32634321e-02 -8.82785559e-01 -4.69230831e-01 -2.32634563e-02 -8.84454191e-01 -4.66076314e-01 -2.32634209e-02 -8.86027753e-01 -4.63078201e-01 -2.32633892e-02 -8.87589693e-01 -4.60077703e-01 -2.32634246e-02 -8.89192104e-01 -4.56973523e-01 -2.32634209e-02 -8.90829802e-01 -4.53772187e-01 -2.32634731e-02 -8.92415822e-01 -4.50643867e-01 -2.32633818e-02 -8.93929183e-01 -4.47633386e-01 -2.32634377e-02 -8.95533800e-01 -4.44419593e-01 -2.32634563e-02 -8.97083402e-01 -4.41277325e-01 -2.32633818e-02 -8.98581028e-01 -4.38225031e-01 -2.32634246e-02 -9.00139749e-01 -4.35016483e-01 -2.32634563e-02 -9.01698291e-01 -4.31770533e-01 -2.32634321e-02 -9.03202415e-01 -4.28615123e-01 -2.32634321e-02 -9.04651046e-01 -4.25545990e-01 -2.32633874e-02 -9.06090617e-01 -4.22477752e-01 -2.32634190e-02 -9.07602787e-01 -4.19220179e-01 -2.32634563e-02 -9.09101963e-01 -4.15955693e-01 -2.32634321e-02 -9.10502732e-01 -4.12880272e-01 -2.32633967e-02 -9.11904335e-01 -4.09776360e-01 -2.32634284e-02 -9.13328707e-01 -4.06591654e-01 -2.32634339e-02 -9.14777279e-01 -4.03324932e-01 -2.32634731e-02 -9.16185975e-01 -4.00115103e-01 -2.32633930e-02 -9.17569458e-01 -3.96930486e-01 -2.32634638e-02 -9.18958187e-01 -3.93692434e-01 -2.32633874e-02 -9.20287132e-01 -3.90583724e-01 -2.32634284e-02 -9.21677411e-01 -3.87296945e-01 -2.32634638e-02 -9.23029840e-01 -3.84057403e-01 -2.32633874e-02 -9.24359739e-01 -3.80847633e-01 -2.32634600e-02 -9.25687611e-01 -3.77605528e-01 -2.32633911e-02 -9.26971018e-01 -3.74444574e-01 -2.32634321e-02 -9.28298891e-01 -3.71142447e-01 -2.32634563e-02 -9.29594815e-01 -3.67884755e-01 -2.32633855e-02 -9.30868030e-01 -3.64657432e-01 -2.32634731e-02 -9.32138443e-01 -3.61374438e-01 -2.32633930e-02 -9.33366120e-01 -3.58221829e-01 -2.32634284e-02 -9.34636593e-01 -3.54875267e-01 -2.32634563e-02 -9.35859442e-01 -3.51617604e-01 -2.32633874e-02 -9.37046587e-01 -3.48442018e-01 -2.32634135e-02 -9.38284814e-01 -3.45107466e-01 -2.32634451e-02 -9.39494371e-01 -3.41819525e-01 -2.32633948e-02 -9.40685213e-01 -3.38521123e-01 -2.32634563e-02 -9.41867113e-01 -3.35222840e-01 -2.32633986e-02 -9.43022847e-01 -3.31955075e-01 -2.32634563e-02 -9.44177389e-01 -3.28650922e-01 -2.32633911e-02 -9.45294917e-01 -3.25431138e-01 -2.32634284e-02 -9.46422040e-01 -3.22136283e-01 -2.32634321e-02 -9.47536409e-01 -3.18845242e-01 -2.32634321e-02 -9.48670506e-01 -3.15449834e-01 -2.32634563e-02 -9.49764073e-01 -3.12140167e-01 -2.32633986e-02 -9.50830102e-01 -3.08882833e-01 -2.32634284e-02 -9.51929867e-01 -3.05478811e-01 -2.32634563e-02 -9.52991128e-01 -3.02149504e-01 -2.32633948e-02 -9.54035401e-01 -2.98840553e-01 -2.32634619e-02 -9.55070734e-01 -2.95505762e-01 -2.32633874e-02 -9.56091344e-01 -2.92191267e-01 -2.32634731e-02 -9.57106948e-01 -2.88842797e-01 -2.32633911e-02 -9.58079696e-01 -2.85601109e-01 -2.32634284e-02 -9.59095657e-01 -2.82176733e-01 -2.32634582e-02 -9.60081935e-01 -2.78800637e-01 -2.32633911e-02 -9.61026013e-01 -2.75525630e-01 -2.32634209e-02 -9.61976767e-01 -2.72189289e-01 -2.32634265e-02 -9.62926090e-01 -2.68814683e-01 -2.32634284e-02 -9.63855743e-01 -2.65457869e-01 -2.32634321e-02 -9.64775920e-01 -2.62103885e-01 -2.32634246e-02 -9.65684474e-01 -2.58725554e-01 -2.32634265e-02 -9.66604471e-01 -2.55273283e-01 -2.32634731e-02 -9.67523098e-01 -2.51767665e-01 -2.32634246e-02 -9.68372524e-01 -2.48480335e-01 -2.32633930e-02 -9.69204664e-01 -2.45203108e-01 -2.32634321e-02 -9.70078647e-01 -2.41729274e-01 -2.32634712e-02 -9.70945537e-01 -2.38230839e-01 -2.32634377e-02 -9.71746683e-01 -2.34938189e-01 -2.32633818e-02 -9.72537220e-01 -2.31647924e-01 -2.32634116e-02 -9.73335564e-01 -2.28267297e-01 -2.32634246e-02 -9.74147379e-01 -2.24773422e-01 -2.32634451e-02 -9.74926412e-01 -2.21364617e-01 -2.32633818e-02 -9.75675046e-01 -2.18051553e-01 -2.32634246e-02 -9.76445258e-01 -2.14570940e-01 -2.32634451e-02 -9.77187693e-01 -2.11155742e-01 -2.32633837e-02 -9.77907181e-01 -2.07810253e-01 -2.32634153e-02 -9.78625178e-01 -2.04401642e-01 -2.32634060e-02 -9.79347944e-01 -2.00917199e-01 -2.32634358e-02 -9.80058432e-01 -1.97411880e-01 -2.32634153e-02 -9.80725467e-01 -1.94069847e-01 -2.32633688e-02 -9.81383324e-01 -1.90721661e-01 -2.32634079e-02 -9.82052445e-01 -1.87232912e-01 -2.32634284e-02 -9.82713342e-01 -1.83738947e-01 -2.32634004e-02 -9.83336806e-01 -1.80357352e-01 -2.32633818e-02 -9.83948648e-01 -1.77025795e-01 -2.32633892e-02 -9.84562814e-01 -1.73583239e-01 -2.32634060e-02 -9.85169649e-01 -1.70074776e-01 -2.32634302e-02 -9.85770464e-01 -1.66560993e-01 -2.32634060e-02 -9.86331940e-01 -1.63195848e-01 -2.32633688e-02 -9.86881793e-01 -1.59845650e-01 -2.32634060e-02 -9.87438142e-01 -1.56370476e-01 -2.32633948e-02 -9.87989962e-01 -1.52850658e-01 -2.32634451e-02 -9.88512695e-01 -1.49415568e-01 -2.32633818e-02 -9.89032924e-01 -1.45949453e-01 -2.32634507e-02 -9.89534497e-01 -1.42490372e-01 -2.32633706e-02 -9.90014553e-01 -1.39133647e-01 -2.32634060e-02 -9.90506053e-01 -1.35592863e-01 -2.32634377e-02 -9.90972698e-01 -1.32119820e-01 -2.32633706e-02 -9.91430402e-01 -1.28659070e-01 -2.32634265e-02 -9.91869271e-01 -1.25217170e-01 -2.32633501e-02 -9.92292464e-01 -1.21816449e-01 -2.32633855e-02 -9.92718279e-01 -1.18287489e-01 -2.32634004e-02 -9.93123114e-01 -1.14816040e-01 -2.32633259e-02 -9.93520260e-01 -1.11355722e-01 -2.32633296e-02 -9.93909895e-01 -1.07794970e-01 -2.32632514e-02 -9.94263411e-01 -1.04460932e-01 -2.32631229e-02 -9.94574487e-01 -1.01366527e-01 -2.32630540e-02 -9.94935751e-01 -9.77783501e-02 -2.32631341e-02 -9.95275497e-01 -9.42564681e-02 -2.32631415e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.96973872e-01 -7.41755143e-02 -2.32631415e-02 -9.97220516e-01 -7.07818568e-02 -2.32631397e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98754144e-01 4.67503667e-02 -1.74524058e-02 -9.98606384e-01 4.98007014e-02 -1.74524058e-02 -9.98441935e-01 5.29866703e-02 -1.74523611e-02 -9.98292267e-01 5.58886342e-02 -1.74523313e-02 -9.98093724e-01 5.94178662e-02 -1.74523294e-02 -9.97874200e-01 6.30032048e-02 -1.74523238e-02 -9.97648537e-01 6.64930865e-02 -1.74523201e-02 -9.97410119e-01 6.99762553e-02 -1.74523201e-02 -9.97164011e-01 7.34202489e-02 -1.74523201e-02 -9.96900141e-01 7.69140720e-02 -1.74523201e-02 -9.96625185e-01 8.04124326e-02 -1.74523201e-02 -9.96335983e-01 8.39137957e-02 -1.74523201e-02 -9.96045232e-01 8.72867182e-02 -1.74523201e-02 -9.95749474e-01 9.06143859e-02 -1.74523201e-02 -9.95418608e-01 9.41943005e-02 -1.74523201e-02 -9.95071828e-01 9.77760553e-02 -1.74523201e-02 -9.94724751e-01 1.01255350e-01 -1.74523201e-02 -9.94365335e-01 1.04720674e-01 -1.74523201e-02 -9.94001210e-01 1.08108774e-01 -1.74523201e-02 -9.93629515e-01 1.11489847e-01 -1.74523201e-02 -9.93221104e-01 1.15057796e-01 -1.74523201e-02 -9.92801905e-01 1.18618436e-01 -1.74523201e-02 -9.92392123e-01 1.22006424e-01 -1.74523201e-02 -9.91963327e-01 1.25459179e-01 -1.74523201e-02 -9.91506159e-01 1.29007816e-01 -1.74523201e-02 -9.91045892e-01 1.32488698e-01 -1.74523201e-02 -9.90582108e-01 1.35927901e-01 -1.74523201e-02 -9.90103245e-01 1.39373839e-01 -1.74523201e-02 -9.89625156e-01 1.42718762e-01 -1.74523201e-02 -9.89115417e-01 1.46207839e-01 -1.74523201e-02 -9.88581181e-01 1.49771884e-01 -1.74523201e-02 -9.88052309e-01 1.53236002e-01 -1.74523201e-02 -9.87524748e-01 1.56589434e-01 -1.74523201e-02 -9.86975849e-01 1.60030365e-01 -1.74523201e-02 -9.86394405e-01 1.63573459e-01 -1.74523201e-02 -9.85831618e-01 1.66917965e-01 -1.74523201e-02 -9.85247612e-01 1.70339882e-01 -1.74523201e-02 -9.84645367e-01 1.73806354e-01 -1.74523201e-02 -9.84053075e-01 1.77125767e-01 -1.74523201e-02 -9.83408809e-01 1.80647850e-01 -1.74523201e-02 -9.82751667e-01 1.84192955e-01 -1.74523201e-02 -9.82107818e-01 1.87591493e-01 -1.74523201e-02 -9.81450260e-01 1.91001981e-01 -1.74523201e-02 -9.80772913e-01 1.94456533e-01 -1.74523201e-02 -9.80103493e-01 1.97792247e-01 -1.74523201e-02 -9.79413092e-01 2.01192215e-01 -1.74523201e-02 -9.78679121e-01 2.04728335e-01 -1.74523201e-02 -9.77979720e-01 2.08051860e-01 -1.74523201e-02 -9.77250636e-01 2.11454049e-01 -1.74523201e-02 -9.76487875e-01 2.14939460e-01 -1.74523201e-02 -9.75735843e-01 2.18331128e-01 -1.74523201e-02 -9.74960327e-01 2.21764073e-01 -1.74523201e-02 -9.74193931e-01 2.25110918e-01 -1.74523201e-02 -9.73428369e-01 2.28400275e-01 -1.74523201e-02 -9.72626150e-01 2.31795624e-01 -1.74523201e-02 -9.71795797e-01 2.35257834e-01 -1.74523201e-02 -9.70942616e-01 2.38743171e-01 -1.74523201e-02 -9.70121920e-01 2.42047414e-01 -1.74523201e-02 -9.69271958e-01 2.45434985e-01 -1.74523201e-02 -9.68385398e-01 2.48916835e-01 -1.74523201e-02 -9.67517674e-01 2.52268374e-01 -1.74523201e-02 -9.66635466e-01 2.55626172e-01 -1.74523201e-02 -9.65752542e-01 2.58942157e-01 -1.74523201e-02 -9.64869320e-01 2.62216210e-01 -1.74523201e-02 -9.63926971e-01 2.65650213e-01 -1.74523201e-02 -9.62969959e-01 2.69106239e-01 -1.74523201e-02 -9.62013304e-01 2.72502422e-01 -1.74523201e-02 -9.61061001e-01 2.75842518e-01 -1.74523201e-02 -9.60088730e-01 2.79202133e-01 -1.74523201e-02 -9.59117353e-01 2.82528698e-01 -1.74523201e-02 -9.58125472e-01 2.85878778e-01 -1.74523201e-02 -9.57115471e-01 2.89232522e-01 -1.74523201e-02 -9.56132114e-01 2.92471319e-01 -1.74523201e-02 -9.55133617e-01 2.95722276e-01 -1.74523201e-02 -9.54073548e-01 2.99122900e-01 -1.74523201e-02 -9.52992260e-01 3.02541435e-01 -1.74523201e-02 -9.51947510e-01 3.05817336e-01 -1.74523201e-02 -9.50897574e-01 3.09063494e-01 -1.74523201e-02 -9.49784398e-01 3.12470227e-01 -1.74523201e-02 -9.48685229e-01 3.15789104e-01 -1.74523201e-02 -9.47581589e-01 3.19090039e-01 -1.74523201e-02 -9.46444929e-01 3.22443575e-01 -1.74523201e-02 -9.45341527e-01 3.25666249e-01 -1.74523201e-02 -9.44203079e-01 3.28949571e-01 -1.74523201e-02 -9.43020940e-01 3.32324326e-01 -1.74523201e-02 -9.41878200e-01 3.35553885e-01 -1.74523201e-02 -9.40702379e-01 3.38826895e-01 -1.74523201e-02 -9.39523280e-01 3.42090756e-01 -1.74523201e-02 -9.38342988e-01 3.45293075e-01 -1.74523201e-02 -9.37093973e-01 3.48661184e-01 -1.74523201e-02 -9.35840070e-01 3.52011919e-01 -1.74523201e-02 -9.34617102e-01 3.55258465e-01 -1.74523201e-02 -9.33384538e-01 3.58516067e-01 -1.74523201e-02 -9.32114303e-01 3.61777157e-01 -1.74523201e-02 -9.30883169e-01 3.64939213e-01 -1.74523201e-02 -9.29631710e-01 3.68119687e-01 -1.74523201e-02 -9.28318560e-01 3.71418059e-01 -1.74523201e-02 -9.26986694e-01 3.74728322e-01 -1.74523201e-02 -9.25705075e-01 3.77885818e-01 -1.74523201e-02 -9.24395084e-01 3.81077170e-01 -1.74523201e-02 -9.23019707e-01 3.84398907e-01 -1.74523201e-02 -9.21675861e-01 3.87611836e-01 -1.74523201e-02 -9.20309722e-01 3.90837282e-01 -1.74523201e-02 -9.18941379e-01 3.94043088e-01 -1.74523201e-02 -9.17585433e-01 3.97191316e-01 -1.74523201e-02 -9.16202009e-01 4.00383174e-01 -1.74523201e-02 -9.14775610e-01 4.03626770e-01 -1.74523201e-02 -9.13343132e-01 4.06857163e-01 -1.74523201e-02 -9.11926687e-01 4.10020351e-01 -1.74523201e-02 -9.10496891e-01 4.13185835e-01 -1.74523201e-02 -9.09051538e-01 4.16350037e-01 -1.74523201e-02 -9.07594800e-01 4.19520795e-01 -1.74523201e-02 -9.06119227e-01 4.22700584e-01 -1.74523201e-02 -9.04672265e-01 4.25785631e-01 -1.74523201e-02 -9.03230190e-01 4.28837478e-01 -1.74523201e-02 -9.01687145e-01 4.32071507e-01 -1.74523201e-02 -9.00138974e-01 4.35296416e-01 -1.74523201e-02 -8.98609877e-01 4.38444257e-01 -1.74523201e-02 -8.97085845e-01 4.41546619e-01 -1.74523201e-02 -8.95551503e-01 4.44653720e-01 -1.74523201e-02 -8.93991292e-01 4.47780997e-01 -1.74523201e-02 -8.92419338e-01 4.50907558e-01 -1.74523201e-02 -8.90814066e-01 4.54071373e-01 -1.74523201e-02 -8.89267802e-01 4.57089126e-01 -1.74523201e-02 -8.87671709e-01 4.60182458e-01 -1.74523201e-02 -8.86018872e-01 4.63361144e-01 -1.74523201e-02 -8.84389460e-01 4.66461867e-01 -1.74523201e-02 -8.82749975e-01 4.69554365e-01 -1.74523201e-02 -8.81110549e-01 4.72624987e-01 -1.74523201e-02 -8.79492283e-01 4.75625247e-01 -1.74523201e-02 -8.77818942e-01 4.78715420e-01 -1.74523201e-02 -8.76106679e-01 4.81835365e-01 -1.74523201e-02 -8.74423385e-01 4.84880179e-01 -1.74523201e-02 -8.72765362e-01 4.87855256e-01 -1.74523201e-02 -8.71076882e-01 4.90871131e-01 -1.74523201e-02 -8.69301140e-01 4.94005054e-01 -1.74523201e-02 -8.67586315e-01 4.97012824e-01 -1.74523201e-02 -8.65859926e-01 5.00018060e-01 -1.74523201e-02 -8.64119887e-01 5.03013313e-01 -1.74523201e-02 -8.62424374e-01 5.05917907e-01 -1.74523201e-02 -8.60598981e-01 5.09015083e-01 -1.74523201e-02 -8.58751774e-01 5.12128413e-01 -1.74523201e-02 -8.56953382e-01 5.15130281e-01 -1.74523201e-02 -8.55144739e-01 5.18125415e-01 -1.74523201e-02 -8.53380144e-01 5.21028399e-01 -1.74523201e-02 -8.51571858e-01 5.23977757e-01 -1.74523201e-02 -8.49692941e-01 5.27022719e-01 -1.74523201e-02 -8.47842097e-01 5.29992342e-01 -1.74523201e-02 -8.46034765e-01 5.32871842e-01 -1.74523201e-02 -8.44175279e-01 5.35816789e-01 -1.74523201e-02 -8.42230022e-01 5.38866401e-01 -1.74523201e-02 -8.40345562e-01 5.41798592e-01 -1.74523201e-02 -8.38440776e-01 5.44741750e-01 -1.74523201e-02 -8.36550832e-01 5.47636807e-01 -1.74523201e-02 -8.34716141e-01 5.50433218e-01 -1.74523201e-02 -8.32823813e-01 5.53288102e-01 -1.74523201e-02 -8.30829442e-01 5.56285024e-01 -1.74523201e-02 -8.28822672e-01 5.59271634e-01 -1.74523201e-02 -8.26916337e-01 5.62079668e-01 -1.74523201e-02 -8.24960172e-01 5.64952910e-01 -1.74523201e-02 -8.22914898e-01 5.67927718e-01 -1.74523201e-02 -8.20927203e-01 5.70796430e-01 -1.74523201e-02 -8.18922460e-01 5.73666453e-01 -1.74523201e-02 -8.16957116e-01 5.76463342e-01 -1.74523201e-02 -8.15014303e-01 5.79206288e-01 -1.74523201e-02 -8.12931061e-01 5.82127929e-01 -1.74523201e-02 -8.10798585e-01 5.85089862e-01 -1.74523201e-02 -8.08748186e-01 5.87925076e-01 -1.74523201e-02 -8.06697309e-01 5.90732396e-01 -1.74523201e-02 -8.04661930e-01 5.93502581e-01 -1.74523201e-02 -8.02605331e-01 5.96281767e-01 -1.74523201e-02 -8.00506175e-01 5.99096298e-01 -1.74523201e-02 -7.98398376e-01 6.01904869e-01 -1.74523201e-02 -7.96348155e-01 6.04613364e-01 -1.74523201e-02 -7.94246733e-01 6.07372284e-01 -1.74523201e-02 -7.92032957e-01 6.10253632e-01 -1.74523201e-02 -7.89893866e-01 6.13020599e-01 -1.74523201e-02 -7.87733734e-01 6.15796089e-01 -1.74523201e-02 -7.85636306e-01 6.18466735e-01 -1.74523201e-02 -7.83504665e-01 6.21167898e-01 -1.74523201e-02 -7.81308234e-01 6.23928428e-01 -1.74523201e-02 -7.79080629e-01 6.26706064e-01 -1.74523201e-02 -7.76890397e-01 6.29421651e-01 -1.74523201e-02 -7.74734557e-01 6.32068455e-01 -1.74523201e-02 -7.72559106e-01 6.34729862e-01 -1.74523201e-02 -7.70253181e-01 6.37524843e-01 -1.74523201e-02 -7.68031240e-01 6.40200615e-01 -1.74523201e-02 -7.65779793e-01 6.42891765e-01 -1.74523201e-02 -7.63587236e-01 6.45492971e-01 -1.74523201e-02 -7.61407018e-01 6.48063958e-01 -1.74523201e-02 -7.59087861e-01 6.50779366e-01 -1.74523201e-02 -7.56741285e-01 6.53508127e-01 -1.74523201e-02 -7.54443049e-01 6.56157970e-01 -1.74523201e-02 -7.52148509e-01 6.58787370e-01 -1.74523201e-02 -7.49855578e-01 6.61396027e-01 -1.74523201e-02 -7.47539937e-01 6.64012372e-01 -1.74523201e-02 -7.45220959e-01 6.66614413e-01 -1.74523201e-02 -7.42878735e-01 6.69221759e-01 -1.74523201e-02 -7.40591109e-01 6.71754777e-01 -1.74523201e-02 -7.38327861e-01 6.74238324e-01 -1.74523201e-02 -7.35930800e-01 6.76859796e-01 -1.74523201e-02 -7.33466744e-01 6.79525673e-01 -1.74523201e-02 -7.31082976e-01 6.82088494e-01 -1.74523201e-02 -7.28702903e-01 6.84631169e-01 -1.74523201e-02 -7.26319611e-01 6.87156677e-01 -1.74523201e-02 -7.23972023e-01 6.89633369e-01 -1.74523201e-02 -7.21558273e-01 6.92151308e-01 -1.74523201e-02 -7.19066918e-01 6.94753528e-01 -1.74523201e-02 -7.16711938e-01 6.97177768e-01 -1.74523201e-02 -7.14286745e-01 6.99661970e-01 -1.74523201e-02 -7.11759090e-01 7.02234626e-01 -1.74523201e-02 -7.09322274e-01 7.04698980e-01 -1.74523201e-02 -7.06843257e-01 7.07167625e-01 -1.74523201e-02 -7.04435050e-01 7.09582329e-01 -1.74523201e-02 -7.01968014e-01 7.12024212e-01 -1.74523201e-02 -6.99397326e-01 7.14546263e-01 -1.74523201e-02 -6.96958542e-01 7.16926038e-01 -1.74523201e-02 -6.94463551e-01 7.19347775e-01 -1.74523201e-02 -6.91935658e-01 7.21763313e-01 -1.74523219e-02 -6.89438522e-01 7.24161029e-01 -1.74523201e-02 -6.86808288e-01 7.26649821e-01 -1.74523201e-02 -6.84242785e-01 7.29065657e-01 -1.74523201e-02 -6.81718588e-01 7.31425583e-01 -1.74523201e-02 -6.79243743e-01 7.33726919e-01 -1.74523201e-02 -6.76675916e-01 7.36100435e-01 -1.74523201e-02 -6.74090207e-01 7.38464177e-01 -1.74523201e-02 -6.71522975e-01 7.40802288e-01 -1.74523201e-02 -6.68838859e-01 7.43227065e-01 -1.74523201e-02 -6.66310668e-01 7.45490789e-01 -1.74523201e-02 -6.63776934e-01 7.47750223e-01 -1.74523201e-02 -6.61131740e-01 7.50089645e-01 -1.74523201e-02 -6.58418417e-01 7.52470136e-01 -1.74523201e-02 -6.55787110e-01 7.54766643e-01 -1.74523201e-02 -6.53164566e-01 7.57035911e-01 -1.74523201e-02 -6.50576890e-01 7.59260714e-01 -1.74523201e-02 -6.47941530e-01 7.61511266e-01 -1.74523201e-02 -6.45188630e-01 7.63846874e-01 -1.74523201e-02 -6.42515600e-01 7.66095638e-01 -1.74523201e-02 -6.39902174e-01 7.68279791e-01 -1.74523201e-02 -6.37242973e-01 7.70487726e-01 -1.74523201e-02 -6.34471595e-01 7.72772968e-01 -1.74523201e-02 -6.31812871e-01 7.74942756e-01 -1.74523201e-02 -6.29129529e-01 7.77126312e-01 -1.74523201e-02 -6.26406729e-01 7.79320598e-01 -1.74523201e-02 -6.23706460e-01 7.81486690e-01 -1.74523201e-02 -6.20883763e-01 7.83728659e-01 -1.74523201e-02 -6.18212879e-01 7.85837114e-01 -1.74523201e-02 -6.15462780e-01 7.87994802e-01 -1.74523201e-02 -6.12628102e-01 7.90198505e-01 -1.74523201e-02 -6.09872699e-01 7.92326689e-01 -1.74523201e-02 -6.07155383e-01 7.94411838e-01 -1.74523201e-02 -6.04378223e-01 7.96528697e-01 -1.74523201e-02 -6.01524591e-01 7.98684537e-01 -1.74523201e-02 -5.98709881e-01 8.00794542e-01 -1.74523201e-02 -5.96002400e-01 8.02811742e-01 -1.74523201e-02 -5.93218803e-01 8.04871559e-01 -1.74523201e-02 -5.90287387e-01 8.07024181e-01 -1.74523201e-02 -5.87562025e-01 8.09010565e-01 -1.74523201e-02 -5.84756136e-01 8.11039031e-01 -1.74523201e-02 -5.81888139e-01 8.13102603e-01 -1.74523201e-02 -5.79069614e-01 8.15112710e-01 -1.74523201e-02 -5.76150715e-01 8.17179203e-01 -1.74523201e-02 -5.73267698e-01 8.19199979e-01 -1.74523201e-02 -5.70493996e-01 8.21134806e-01 -1.74523201e-02 -5.67661941e-01 8.23097169e-01 -1.74523201e-02 -5.64713359e-01 8.25122058e-01 -1.74523201e-02 -5.61855793e-01 8.27067375e-01 -1.74523201e-02 -5.58981776e-01 8.29017580e-01 -1.74523201e-02 -5.56095004e-01 8.30952883e-01 -1.74523219e-02 -5.53214788e-01 8.32873404e-01 -1.74523201e-02 -5.50287724e-01 8.34810734e-01 -1.74523201e-02 -5.47355533e-01 8.36736441e-01 -1.74523201e-02 -5.44357955e-01 8.38690162e-01 -1.74523201e-02 -5.41508138e-01 8.40531886e-01 -1.74523201e-02 -5.38587809e-01 8.42408061e-01 -1.74523201e-02 -5.35620809e-01 8.44294608e-01 -1.74523201e-02 -5.32688320e-01 8.46151531e-01 -1.74523201e-02 -5.29662967e-01 8.48047614e-01 -1.74523201e-02 -5.26687562e-01 8.49899769e-01 -1.74523201e-02 -5.23781478e-01 8.51690114e-01 -1.74523201e-02 -5.20813346e-01 8.53513777e-01 -1.74523201e-02 -5.17759860e-01 8.55366290e-01 -1.74523201e-02 -5.14841855e-01 8.57125342e-01 -1.74523201e-02 -5.11859834e-01 8.58911872e-01 -1.74523201e-02 -5.08860290e-01 8.60689282e-01 -1.74523201e-02 -5.05846441e-01 8.62466991e-01 -1.74523201e-02 -5.02741933e-01 8.64279807e-01 -1.74523201e-02 -4.99714792e-01 8.66032600e-01 -1.74523201e-02 -4.96801496e-01 8.67706954e-01 -1.74523201e-02 -4.93801922e-01 8.69417489e-01 -1.74523201e-02 -4.90669012e-01 8.71191144e-01 -1.74523201e-02 -4.87616003e-01 8.72901201e-01 -1.74523201e-02 -4.84572262e-01 8.74593496e-01 -1.74523201e-02 -4.81571853e-01 8.76250923e-01 -1.74523201e-02 -4.78531182e-01 8.77918065e-01 -1.74523201e-02 -4.75420505e-01 8.79601955e-01 -1.74523201e-02 -4.72380877e-01 8.81241322e-01 -1.74523201e-02 -4.69222277e-01 8.82926822e-01 -1.74523201e-02 -4.66209203e-01 8.84521842e-01 -1.74523201e-02 -4.63114321e-01 8.86146486e-01 -1.74523201e-02 -4.60014760e-01 8.87755394e-01 -1.74523201e-02 -4.56920594e-01 8.89354944e-01 -1.74523201e-02 -4.53750581e-01 8.90975356e-01 -1.74523201e-02 -4.50614333e-01 8.92565489e-01 -1.74523201e-02 -4.47601199e-01 8.94080341e-01 -1.74523201e-02 -4.44507241e-01 8.95623684e-01 -1.74523201e-02 -4.41284329e-01 8.97215247e-01 -1.74523201e-02 -4.38210368e-01 8.98721218e-01 -1.74523201e-02 -4.35162425e-01 9.00202334e-01 -1.74523201e-02 -4.32043344e-01 9.01699424e-01 -1.74523201e-02 -4.28816438e-01 9.03240681e-01 -1.74523201e-02 -4.25630510e-01 9.04744506e-01 -1.74523201e-02 -4.22550350e-01 9.06189203e-01 -1.74523201e-02 -4.19399291e-01 9.07651484e-01 -1.74523201e-02 -4.16232526e-01 9.09107447e-01 -1.74523201e-02 -4.13004249e-01 9.10579085e-01 -1.74523201e-02 -4.09797698e-01 9.12026763e-01 -1.74523201e-02 -4.06606555e-01 9.13454533e-01 -1.74523201e-02 -4.03406441e-01 9.14872289e-01 -1.74523201e-02 -4.00206923e-01 9.16277707e-01 -1.74523201e-02 -3.97021443e-01 9.17659998e-01 -1.74523201e-02 -3.93790334e-01 9.19048667e-01 -1.74523201e-02 -3.90518188e-01 9.20446455e-01 -1.74523201e-02 -3.87360781e-01 9.21780586e-01 -1.74523201e-02 -3.84155363e-01 9.23121214e-01 -1.74523201e-02 -3.80872101e-01 9.24477816e-01 -1.74523201e-02 -3.77640933e-01 9.25804257e-01 -1.74523201e-02 -3.74411702e-01 9.27115798e-01 -1.74523201e-02 -3.71173710e-01 9.28416729e-01 -1.74523201e-02 -3.68001252e-01 9.29678380e-01 -1.74523201e-02 -3.64759624e-01 9.30957496e-01 -1.74523201e-02 -3.61449182e-01 9.32240248e-01 -1.74523201e-02 -3.58254910e-01 9.33484077e-01 -1.74523201e-02 -3.55077922e-01 9.34685946e-01 -1.74523201e-02 -3.51811439e-01 9.35915470e-01 -1.74523201e-02 -3.48495036e-01 9.37155664e-01 -1.74523201e-02 -3.45217615e-01 9.38369155e-01 -1.74523201e-02 -3.42006981e-01 9.39554214e-01 -1.74523201e-02 -3.38745892e-01 9.40731108e-01 -1.74523201e-02 -3.35344046e-01 9.41953301e-01 -1.74523201e-02 -3.31947476e-01 9.43152666e-01 -1.74523201e-02 -3.28741938e-01 9.44272816e-01 -1.74523201e-02 -3.25441658e-01 9.45420325e-01 -1.74523201e-02 -3.22169393e-01 9.46535528e-01 -1.74523219e-02 -3.18883181e-01 9.47652042e-01 -1.74523201e-02 -3.15550804e-01 9.48763967e-01 -1.74523201e-02 -3.12353015e-01 9.49821651e-01 -1.74523201e-02 -3.08910698e-01 9.50949490e-01 -1.74523201e-02 -3.05482209e-01 9.52055395e-01 -1.74523201e-02 -3.02165419e-01 9.53113675e-01 -1.74523201e-02 -2.98827499e-01 9.54162300e-01 -1.74523201e-02 -2.95632213e-01 9.55155969e-01 -1.74523219e-02 -2.92255461e-01 9.56198633e-01 -1.74523201e-02 -2.88820326e-01 9.57240045e-01 -1.74523201e-02 -2.85473496e-01 9.58243668e-01 -1.74523201e-02 -2.82136887e-01 9.59233403e-01 -1.74523201e-02 -2.78887749e-01 9.60181653e-01 -1.74523201e-02 -2.75648475e-01 9.61115897e-01 -1.74523201e-02 -2.72256911e-01 9.62082684e-01 -1.74523201e-02 -2.68808365e-01 9.63052988e-01 -1.74523201e-02 -2.65360504e-01 9.64007616e-01 -1.74523201e-02 -2.62079209e-01 9.64907229e-01 -1.74523201e-02 -2.58719593e-01 9.65811610e-01 -1.74523201e-02 -2.55340934e-01 9.66710627e-01 -1.74523201e-02 -2.51986712e-01 9.67591584e-01 -1.74523201e-02 -2.48471081e-01 9.68499064e-01 -1.74523201e-02 -2.45173290e-01 9.69337404e-01 -1.74523201e-02 -2.41809964e-01 9.70182776e-01 -1.74523201e-02 -2.38423526e-01 9.71020043e-01 -1.74523201e-02 -2.35011816e-01 9.71855402e-01 -1.74523201e-02 -2.31617093e-01 9.72667396e-01 -1.74523201e-02 -2.28316426e-01 9.73447680e-01 -1.74523201e-02 -2.24820301e-01 9.74260330e-01 -1.74523201e-02 -2.21303999e-01 9.75065827e-01 -1.74523201e-02 -2.17937380e-01 9.75824296e-01 -1.74523201e-02 -2.14527965e-01 9.76577342e-01 -1.74523201e-02 -2.11196899e-01 9.77302551e-01 -1.74523201e-02 -2.07881689e-01 9.78014469e-01 -1.74523201e-02 -2.04368860e-01 9.78755653e-01 -1.74523201e-02 -2.00845286e-01 9.79484677e-01 -1.74523201e-02 -1.97405517e-01 9.80181634e-01 -1.74523201e-02 -1.94075674e-01 9.80847478e-01 -1.74523201e-02 -1.90794602e-01 9.81492281e-01 -1.74523201e-02 -1.87367424e-01 9.82150435e-01 -1.74523201e-02 -1.83823839e-01 9.82822895e-01 -1.74523201e-02 -1.80284649e-01 9.83473122e-01 -1.74523201e-02 -1.76973179e-01 9.84081328e-01 -1.74523201e-02 -1.73533812e-01 9.84694362e-01 -1.74523201e-02 -1.70087293e-01 9.85288680e-01 -1.74523201e-02 -1.66632250e-01 9.85881925e-01 -1.74523201e-02 -1.63091227e-01 9.86472547e-01 -1.74523201e-02 -1.59729347e-01 9.87021089e-01 -1.74523201e-02 -1.56286880e-01 9.87574160e-01 -1.74523201e-02 -1.52831674e-01 9.88114834e-01 -1.74523201e-02 -1.49394259e-01 9.88638878e-01 -1.74523201e-02 -1.45827159e-01 9.89171267e-01 -1.74523201e-02 -1.42458305e-01 9.89660740e-01 -1.74523201e-02 -1.39054120e-01 9.90149021e-01 -1.74523201e-02 -1.35488093e-01 9.90640998e-01 -1.74523201e-02 -1.31999120e-01 9.91113126e-01 -1.74523201e-02 -1.28622100e-01 9.91554558e-01 -1.74523201e-02 -1.25286683e-01 9.91984427e-01 -1.74523201e-02 -1.21814191e-01 9.92415845e-01 -1.74523201e-02 -1.18232362e-01 9.92847860e-01 -1.74523201e-02 -1.14678048e-01 9.93263900e-01 -1.74523201e-02 -1.11220591e-01 9.93659198e-01 -1.74523201e-02 -1.07841864e-01 9.94029939e-01 -1.74523201e-02 -1.04403496e-01 9.94397342e-01 -1.74523201e-02 -1.00867882e-01 9.94762659e-01 -1.74523201e-02 -9.74103957e-02 9.95106518e-01 -1.74523201e-02 -9.38555151e-02 9.95448589e-01 -1.74523201e-02 -9.04504955e-02 9.95763540e-01 -1.74523201e-02 -8.70033130e-02 9.96072650e-01 -1.74523201e-02 -8.35323408e-02 9.96367812e-01 -1.74523201e-02 -8.00634325e-02 9.96653318e-01 -1.74523201e-02 -7.65589625e-02 9.96926546e-01 -1.74523201e-02 -7.30819553e-02 9.97190118e-01 -1.74523201e-02 -6.95273876e-02 9.97441947e-01 -1.74523201e-02 -6.61285892e-02 9.97672975e-01 -1.74523201e-02 -6.26433715e-02 9.97897446e-01 -1.74523201e-02 -5.91537952e-02 9.98113215e-01 -1.74523201e-02 -5.57539240e-02 9.98309731e-01 -1.74523201e-02 -5.22057042e-02 9.98498678e-01 -1.74523201e-02 -4.86117303e-02 9.98683035e-01 -1.74523201e-02 -4.51502502e-02 9.98842239e-01 -1.74523201e-02 -4.16599587e-02 9.98996556e-01 -1.74523201e-02 -3.82683128e-02 9.99130189e-01 -1.74523201e-02 -3.48625109e-02 9.99255538e-01 -1.74523201e-02 -3.12837660e-02 9.99374688e-01 -1.74523201e-02 -2.76914239e-02 9.99479771e-01 -1.74523201e-02 -2.41721775e-02 9.99576211e-01 -1.74523201e-02 -2.07918733e-02 9.99646723e-01 -1.74523201e-02 -1.74175594e-02 9.99715805e-01 -1.74523201e-02 -1.39186997e-02 9.99764264e-01 -1.74523201e-02 -1.03368005e-02 9.99812424e-01 -1.74523201e-02 -6.72272546e-03 9.99848425e-01 -1.74523201e-02 -3.32912360e-03 9.99862015e-01 -1.74523201e-02 1.19374476e-04 9.99865115e-01 -1.74523201e-02 3.64957587e-03 9.99861658e-01 -1.74523201e-02 7.11028092e-03 9.99844134e-01 -1.74523201e-02 1.07102459e-02 9.99805748e-01 -1.74523201e-02 1.42078707e-02 9.99758780e-01 -1.74523201e-02 1.76963862e-02 9.99711037e-01 -1.74523201e-02 2.11756099e-02 9.99638736e-01 -1.74523201e-02 2.46732272e-02 9.99559820e-01 -1.74523201e-02 2.81633791e-02 9.99468207e-01 -1.74523201e-02 3.15626599e-02 9.99365628e-01 -1.74523201e-02 3.50329354e-02 9.99250650e-01 -1.74523201e-02 3.86080518e-02 9.99119341e-01 -1.74523201e-02 4.21232767e-02 9.98977602e-01 -1.74523201e-02 4.55943458e-02 9.98822927e-01 -1.74523201e-02 4.90289293e-02 9.98659194e-01 -1.74523201e-02 5.24088405e-02 9.98487055e-01 -1.74523201e-02 5.58857732e-02 9.98300493e-01 -1.74523201e-02 5.94582818e-02 9.98093784e-01 -1.74523201e-02 6.30453974e-02 9.97873962e-01 -1.74523201e-02 6.64173514e-02 9.97652650e-01 -1.74523201e-02 6.98939189e-02 9.97416973e-01 -1.74523201e-02 7.33926594e-02 9.97166395e-01 -1.74523201e-02 7.68655092e-02 9.96905982e-01 -1.74523201e-02 8.04300159e-02 9.96623039e-01 -1.74523201e-02 8.39112177e-02 9.96335924e-01 -1.74523201e-02 8.74036103e-02 9.96037424e-01 -1.74523201e-02 9.08330530e-02 9.95729506e-01 -1.74523201e-02 9.43202302e-02 9.95404243e-01 -1.74523201e-02 9.77419689e-02 9.95074570e-01 -1.74523201e-02 1.01188287e-01 9.94731486e-01 -1.74523201e-02 1.04758762e-01 9.94361579e-01 -1.74523201e-02 1.08249076e-01 9.93987262e-01 -1.74523201e-02 1.11693025e-01 9.93606210e-01 -1.74523201e-02 1.15175478e-01 9.93207037e-01 -1.74523201e-02 1.18556179e-01 9.92808342e-01 -1.74523201e-02 1.22004062e-01 9.92393792e-01 -1.74523201e-02 1.25550479e-01 9.91951764e-01 -1.74523201e-02 1.29019067e-01 9.91504192e-01 -1.74523201e-02 1.32482916e-01 9.91047561e-01 -1.74523201e-02 1.35860711e-01 9.90590930e-01 -1.74523201e-02 1.39303282e-01 9.90113437e-01 -1.74523201e-02 1.42791748e-01 9.89614487e-01 -1.74523201e-02 1.46219105e-01 9.89114642e-01 -1.74523201e-02 1.49741516e-01 9.88586605e-01 -1.74523201e-02 1.53129891e-01 9.88067985e-01 -1.74523201e-02 1.56557620e-01 9.87530768e-01 -1.74523201e-02 1.60104766e-01 9.86961961e-01 -1.74523201e-02 1.63543373e-01 9.86399531e-01 -1.74523201e-02 1.66992679e-01 9.85820651e-01 -1.74523201e-02 1.70455694e-01 9.85225797e-01 -1.74523201e-02 1.73896983e-01 9.84628856e-01 -1.74523201e-02 1.77235618e-01 9.84032929e-01 -1.74523201e-02 1.80629864e-01 9.83412504e-01 -1.74523201e-02 1.84191301e-01 9.82751667e-01 -1.74523201e-02 1.87516659e-01 9.82122600e-01 -1.74523201e-02 1.90943792e-01 9.81462359e-01 -1.74523201e-02 1.94481760e-01 9.80767369e-01 -1.74523201e-02 1.97862133e-01 9.80091333e-01 -1.74523201e-02 2.01262236e-01 9.79399264e-01 -1.74523201e-02 2.04598472e-01 9.78706837e-01 -1.74523201e-02 2.07954213e-01 9.78002131e-01 -1.74523201e-02 2.11467832e-01 9.77247417e-01 -1.74523201e-02 2.14983463e-01 9.76479292e-01 -1.74523201e-02 2.18379125e-01 9.75724518e-01 -1.74523201e-02 2.21715778e-01 9.74969745e-01 -1.74523201e-02 2.25005358e-01 9.74217653e-01 -1.74523201e-02 2.28389069e-01 9.73429859e-01 -1.74523201e-02 2.31853157e-01 9.72614229e-01 -1.74523201e-02 2.35345289e-01 9.71774399e-01 -1.74523201e-02 2.38770604e-01 9.70935643e-01 -1.74523201e-02 2.42165476e-01 9.70093906e-01 -1.74523201e-02 2.45455831e-01 9.69266415e-01 -1.74523201e-02 2.48804152e-01 9.68412757e-01 -1.74523201e-02 2.52299309e-01 9.67508972e-01 -1.74523201e-02 2.55622119e-01 9.66637313e-01 -1.74523201e-02 2.58989096e-01 9.65739965e-01 -1.74523201e-02 2.62393862e-01 9.64821875e-01 -1.74523201e-02 2.65750110e-01 9.63899970e-01 -1.74523201e-02 2.69040048e-01 9.62989092e-01 -1.74523201e-02 2.72328943e-01 9.62063611e-01 -1.74523201e-02 2.75770098e-01 9.61082041e-01 -1.74523201e-02 2.79200315e-01 9.60090101e-01 -1.74523201e-02 2.82555550e-01 9.59108651e-01 -1.74523201e-02 2.85782307e-01 9.58152115e-01 -1.74523201e-02 2.89063841e-01 9.57167208e-01 -1.74523201e-02 2.92399675e-01 9.56153393e-01 -1.74523201e-02 2.95811296e-01 9.55106020e-01 -1.74523201e-02 2.99239337e-01 9.54035997e-01 -1.74523201e-02 3.02487195e-01 9.53009963e-01 -1.74523201e-02 3.05765301e-01 9.51965749e-01 -1.74523201e-02 3.09130967e-01 9.50876474e-01 -1.74523201e-02 3.12430829e-01 9.49795842e-01 -1.74523201e-02 3.15728933e-01 9.48707283e-01 -1.74523201e-02 3.19119245e-01 9.47573006e-01 -1.74523201e-02 3.22421372e-01 9.46453571e-01 -1.74523201e-02 3.25722516e-01 9.45322394e-01 -1.74523201e-02 3.28992486e-01 9.44187939e-01 -1.74523201e-02 3.32285196e-01 9.43035841e-01 -1.74523201e-02 3.35522711e-01 9.41890121e-01 -1.74523201e-02 3.38801891e-01 9.40713465e-01 -1.74523201e-02 3.42162251e-01 9.39497948e-01 -1.74523201e-02 3.45433205e-01 9.38292801e-01 -1.74523201e-02 3.48677605e-01 9.37087238e-01 -1.74523201e-02 3.51909071e-01 9.35879350e-01 -1.74523201e-02 3.55073631e-01 9.34689462e-01 -1.74523201e-02 3.58416378e-01 9.33421612e-01 -1.74523201e-02 3.61737192e-01 9.32130754e-01 -1.74523201e-02 3.64983708e-01 9.30868149e-01 -1.74523201e-02 3.68263423e-01 9.29574847e-01 -1.74523201e-02 3.71431261e-01 9.28313255e-01 -1.74523201e-02 3.74643296e-01 9.27023053e-01 -1.74523201e-02 3.77955645e-01 9.25677240e-01 -1.74523201e-02 3.81181031e-01 9.24352050e-01 -1.74523201e-02 3.84392858e-01 9.23022091e-01 -1.74523201e-02 3.87551367e-01 9.21699762e-01 -1.74523201e-02 3.90751451e-01 9.20347393e-01 -1.74523201e-02 3.93958509e-01 9.18976545e-01 -1.74523201e-02 3.97160202e-01 9.17601466e-01 -1.74523201e-02 4.00446534e-01 9.16173875e-01 -1.74523201e-02 4.03662473e-01 9.14760649e-01 -1.74523201e-02 4.06833649e-01 9.13355410e-01 -1.74523201e-02 4.09956157e-01 9.11956489e-01 -1.74523201e-02 4.13102001e-01 9.10535395e-01 -1.74523201e-02 4.16300118e-01 9.09075916e-01 -1.74523201e-02 4.19465065e-01 9.07621801e-01 -1.74523201e-02 4.22654748e-01 9.06140327e-01 -1.74523201e-02 4.25809205e-01 9.04660225e-01 -1.74523201e-02 4.28954214e-01 9.03175831e-01 -1.74523201e-02 4.32166398e-01 9.01639938e-01 -1.74523201e-02 4.35206741e-01 9.00181949e-01 -1.74523201e-02 4.38388795e-01 8.98637176e-01 -1.74523201e-02 4.41619903e-01 8.97051215e-01 -1.74523201e-02 4.44760859e-01 8.95498276e-01 -1.74523201e-02 4.47855800e-01 8.93955529e-01 -1.74523201e-02 4.50934023e-01 8.92406523e-01 -1.74523201e-02 4.54019964e-01 8.90840054e-01 -1.74523201e-02 4.57040459e-01 8.89293611e-01 -1.74523201e-02 4.60220754e-01 8.87651980e-01 -1.74523201e-02 4.63375181e-01 8.86009812e-01 -1.74523201e-02 4.66437638e-01 8.84402215e-01 -1.74523201e-02 4.69560981e-01 8.82747531e-01 -1.74523201e-02 4.72594827e-01 8.81126344e-01 -1.74523201e-02 4.75665092e-01 8.79472494e-01 -1.74523201e-02 4.78773177e-01 8.77785921e-01 -1.74523201e-02 4.81799543e-01 8.76128137e-01 -1.74523201e-02 4.84853953e-01 8.74439299e-01 -1.74523201e-02 4.87852246e-01 8.72768879e-01 -1.74523201e-02 4.90909427e-01 8.71055841e-01 -1.74523201e-02 4.94018972e-01 8.69293928e-01 -1.74523201e-02 4.97065783e-01 8.67557406e-01 -1.74523201e-02 5.00061393e-01 8.65835071e-01 -1.74523201e-02 5.03106713e-01 8.64067614e-01 -1.74523201e-02 5.06111503e-01 8.62312078e-01 -1.74523201e-02 5.09115040e-01 8.60540748e-01 -1.74523201e-02 5.12016118e-01 8.58817875e-01 -1.74523201e-02 5.15036166e-01 8.57011676e-01 -1.74523201e-02 5.18092394e-01 8.55163991e-01 -1.74523201e-02 5.21085441e-01 8.53347301e-01 -1.74523201e-02 5.24080276e-01 8.51509333e-01 -1.74523201e-02 5.26949942e-01 8.49736094e-01 -1.74523201e-02 5.29906332e-01 8.47897112e-01 -1.74523201e-02 5.32859564e-01 8.46042454e-01 -1.74523201e-02 5.35816133e-01 8.44174445e-01 -1.74523201e-02 5.38842142e-01 8.42245281e-01 -1.74523201e-02 5.41714787e-01 8.40398729e-01 -1.74523201e-02 5.44525981e-01 8.38580787e-01 -1.74523201e-02 5.47451496e-01 8.36671531e-01 -1.74523201e-02 5.50380468e-01 8.34748805e-01 -1.74523238e-02 5.53377926e-01 8.32762718e-01 -1.74523257e-02 5.56379676e-01 8.30759525e-01 -1.74523313e-02 5.59255183e-01 8.28824878e-01 -1.74523313e-02 5.62039912e-01 8.26932549e-01 -1.74523313e-02 5.64900100e-01 8.24984729e-01 -1.74523313e-02 5.67775905e-01 8.22998822e-01 -1.74523499e-02 5.70544899e-01 8.21079731e-01 -1.74523611e-02 5.73440671e-01 8.19060326e-01 -1.74523983e-02 5.76272905e-01 8.17070007e-01 -1.74524002e-02 5.79292059e-01 8.14932406e-01 -1.74524095e-02 5.81628442e-01 8.13266754e-01 -1.74524058e-02 5.84443867e-01 8.11246455e-01 -1.74524058e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.08231628e-01 7.05764353e-01 -1.74524058e-02 7.09892273e-01 7.04093277e-01 -1.74524058e-02 7.12474227e-01 7.01480627e-01 -1.74524039e-02 7.14581907e-01 6.99335337e-01 -1.74523611e-02 7.16859698e-01 6.97013557e-01 -1.74523313e-02 7.19276786e-01 6.94518149e-01 -1.74523313e-02 7.21727073e-01 6.91973984e-01 -1.74523313e-02 7.24239171e-01 6.89347625e-01 -1.74523313e-02 7.26543248e-01 6.86915815e-01 -1.74523313e-02 7.28881419e-01 6.84437275e-01 -1.74523201e-02 7.31319487e-01 6.81834280e-01 -1.74523201e-02 7.33698666e-01 6.79275393e-01 -1.74523201e-02 7.36064672e-01 6.76712453e-01 -1.74523201e-02 7.38484085e-01 6.74067736e-01 -1.74523201e-02 7.40776122e-01 6.71550095e-01 -1.74523201e-02 7.43116975e-01 6.68960094e-01 -1.74523201e-02 7.45440781e-01 6.66368246e-01 -1.74523201e-02 7.47713208e-01 6.63819015e-01 -1.74523201e-02 7.50011802e-01 6.61219597e-01 -1.74523201e-02 7.52382100e-01 6.58522069e-01 -1.74523201e-02 7.54749477e-01 6.55806720e-01 -1.74523201e-02 7.56955922e-01 6.53257728e-01 -1.74523201e-02 7.59230494e-01 6.50614023e-01 -1.74523201e-02 7.61512041e-01 6.47938430e-01 -1.74523201e-02 7.63698459e-01 6.45365000e-01 -1.74523201e-02 7.66003966e-01 6.42626166e-01 -1.74523201e-02 7.68247843e-01 6.39940679e-01 -1.74523201e-02 7.70465910e-01 6.37269974e-01 -1.74523201e-02 7.72700250e-01 6.34557545e-01 -1.74523201e-02 7.74847448e-01 6.31931841e-01 -1.74523201e-02 7.77129471e-01 6.29127800e-01 -1.74523201e-02 7.79379129e-01 6.26335621e-01 -1.74523201e-02 7.81540930e-01 6.23637259e-01 -1.74523201e-02 7.83665597e-01 6.20961845e-01 -1.74523201e-02 7.85747290e-01 6.18329585e-01 -1.74523201e-02 7.87958622e-01 6.15510821e-01 -1.74523201e-02 7.90116370e-01 6.12735212e-01 -1.74523201e-02 7.92256415e-01 6.09967470e-01 -1.74523201e-02 7.94457436e-01 6.07096553e-01 -1.74523201e-02 7.96569645e-01 6.04322195e-01 -1.74523201e-02 7.98692346e-01 6.01514816e-01 -1.74523201e-02 8.00714195e-01 5.98816991e-01 -1.74523201e-02 8.02783906e-01 5.96041977e-01 -1.74523201e-02 8.04873884e-01 5.93215704e-01 -1.74523201e-02 8.06934416e-01 5.90411067e-01 -1.74523201e-02 8.09069335e-01 5.87482870e-01 -1.74523201e-02 8.11028183e-01 5.84771395e-01 -1.74523201e-02 8.13053966e-01 5.81954122e-01 -1.74523201e-02 8.15091610e-01 5.79096913e-01 -1.74523201e-02 8.17044377e-01 5.76342523e-01 -1.74523201e-02 8.19135189e-01 5.73364794e-01 -1.74523201e-02 8.21193576e-01 5.70412099e-01 -1.74523201e-02 8.23174298e-01 5.67549109e-01 -1.74523201e-02 8.25083137e-01 5.64770997e-01 -1.74523201e-02 8.27005029e-01 5.61952770e-01 -1.74523201e-02 8.28972876e-01 5.59047818e-01 -1.74523201e-02 8.30922127e-01 5.56142986e-01 -1.74523201e-02 8.32901895e-01 5.53174913e-01 -1.74523201e-02 8.34828794e-01 5.50261259e-01 -1.74523201e-02 8.36691916e-01 5.47425330e-01 -1.74523201e-02 8.38644445e-01 5.44431269e-01 -1.74523201e-02 8.40545356e-01 5.41487336e-01 -1.74523201e-02 8.42422605e-01 5.38566887e-01 -1.74523201e-02 8.44350159e-01 5.35538077e-01 -1.74523201e-02 8.46173406e-01 5.32651305e-01 -1.74523201e-02 8.48014355e-01 5.29719114e-01 -1.74523201e-02 8.49854708e-01 5.26758492e-01 -1.74523201e-02 8.51643205e-01 5.23861647e-01 -1.74523201e-02 8.53472888e-01 5.20879090e-01 -1.74523201e-02 8.55319619e-01 5.17839074e-01 -1.74523201e-02 8.57179403e-01 5.14755845e-01 -1.74523201e-02 8.58977199e-01 5.11748493e-01 -1.74523201e-02 8.60760510e-01 5.08743107e-01 -1.74523201e-02 8.62482071e-01 5.05819976e-01 -1.74523201e-02 8.64187837e-01 5.02897263e-01 -1.74523201e-02 8.65982294e-01 4.99806613e-01 -1.74523201e-02 8.67727935e-01 4.96765018e-01 -1.74523201e-02 8.69443476e-01 4.93758947e-01 -1.74523201e-02 8.71181011e-01 4.90688384e-01 -1.74523201e-02 8.72843087e-01 4.87718880e-01 -1.74523201e-02 8.74577463e-01 4.84603852e-01 -1.74523201e-02 8.76276255e-01 4.81526613e-01 -1.74523201e-02 8.77941310e-01 4.78489488e-01 -1.74523201e-02 8.79615366e-01 4.75396127e-01 -1.74523201e-02 8.81213188e-01 4.72431570e-01 -1.74523201e-02 8.82888138e-01 4.69295382e-01 -1.74523201e-02 8.84543002e-01 4.66167897e-01 -1.74523201e-02 8.86110544e-01 4.63183045e-01 -1.74523201e-02 8.87756228e-01 4.60018754e-01 -1.74523201e-02 8.89413834e-01 4.56806034e-01 -1.74523201e-02 8.90996516e-01 4.53710318e-01 -1.74523201e-02 8.92541468e-01 4.50662404e-01 -1.74523201e-02 8.94102395e-01 4.47560638e-01 -1.74523201e-02 8.95666659e-01 4.44417894e-01 -1.74523201e-02 8.97169650e-01 4.41377997e-01 -1.74523201e-02 8.98749590e-01 4.38156873e-01 -1.74523201e-02 9.00273085e-01 4.35016274e-01 -1.74523201e-02 9.01774883e-01 4.31889415e-01 -1.74523201e-02 9.03276980e-01 4.28741187e-01 -1.74523201e-02 9.04724061e-01 4.25675154e-01 -1.74523201e-02 9.06247556e-01 4.22430366e-01 -1.74523201e-02 9.07768846e-01 4.19148386e-01 -1.74523201e-02 9.09227490e-01 4.15971637e-01 -1.74523201e-02 9.10631657e-01 4.12888139e-01 -1.74523201e-02 9.12025154e-01 4.09804463e-01 -1.74523201e-02 9.13447261e-01 4.06623244e-01 -1.74523201e-02 9.14861083e-01 4.03433859e-01 -1.74523201e-02 9.16294098e-01 4.00168717e-01 -1.74523201e-02 9.17704344e-01 3.96918923e-01 -1.74523201e-02 9.19038177e-01 3.93815488e-01 -1.74523201e-02 9.20440435e-01 3.90534759e-01 -1.74523201e-02 9.21805739e-01 3.87299776e-01 -1.74523201e-02 9.23105359e-01 3.84191722e-01 -1.74523201e-02 9.24467623e-01 3.80901426e-01 -1.74523201e-02 9.25834417e-01 3.77570897e-01 -1.74523201e-02 9.27148223e-01 3.74331176e-01 -1.74523201e-02 9.28414166e-01 3.71178597e-01 -1.74523201e-02 9.29665983e-01 3.68036062e-01 -1.74523201e-02 9.30958450e-01 3.64757031e-01 -1.74523201e-02 9.32218015e-01 3.61507654e-01 -1.74523201e-02 9.33504164e-01 3.58197957e-01 -1.74523201e-02 9.34773326e-01 3.54850888e-01 -1.74523201e-02 9.35994446e-01 3.51605058e-01 -1.74523201e-02 9.37196612e-01 3.48382711e-01 -1.74523201e-02 9.38377380e-01 3.45204949e-01 -1.74523201e-02 9.39588547e-01 3.41912508e-01 -1.74523201e-02 9.40804482e-01 3.38547856e-01 -1.74523201e-02 9.42002594e-01 3.35205197e-01 -1.74523201e-02 9.43141282e-01 3.31985027e-01 -1.74523201e-02 9.44265127e-01 3.28770667e-01 -1.74523201e-02 9.45437312e-01 3.25389653e-01 -1.74523201e-02 9.46562529e-01 3.22096795e-01 -1.74523201e-02 9.47677076e-01 3.18809271e-01 -1.74523201e-02 9.48813260e-01 3.15403193e-01 -1.74523201e-02 9.49877262e-01 3.12184066e-01 -1.74523201e-02 9.50964749e-01 3.08860123e-01 -1.74523201e-02 9.52049017e-01 3.05505484e-01 -1.74523201e-02 9.53069568e-01 3.02305162e-01 -1.74523201e-02 9.54151154e-01 2.98877269e-01 -1.74523201e-02 9.55210805e-01 2.95462459e-01 -1.74523201e-02 9.56234932e-01 2.92133659e-01 -1.74523201e-02 9.57224905e-01 2.88871229e-01 -1.74523201e-02 9.58202958e-01 2.85610944e-01 -1.74523201e-02 9.59194064e-01 2.82272816e-01 -1.74523201e-02 9.60171938e-01 2.78925449e-01 -1.74523201e-02 9.61160898e-01 2.75495291e-01 -1.74523201e-02 9.62141037e-01 2.72054076e-01 -1.74523201e-02 9.63085532e-01 2.68693238e-01 -1.74523201e-02 9.63999450e-01 2.65391022e-01 -1.74523201e-02 9.64897871e-01 2.62118220e-01 -1.74523201e-02 9.65821862e-01 2.58679688e-01 -1.74523201e-02 9.66750503e-01 2.55189657e-01 -1.74523201e-02 9.67632592e-01 2.51828730e-01 -1.74523201e-02 9.68481004e-01 2.48543784e-01 -1.74523201e-02 9.69316423e-01 2.45256513e-01 -1.74523201e-02 9.70169127e-01 2.41860047e-01 -1.74523201e-02 9.71005917e-01 2.38483608e-01 -1.74523201e-02 9.71858442e-01 2.34997392e-01 -1.74523201e-02 9.72690046e-01 2.31527045e-01 -1.74523201e-02 9.73467231e-01 2.28229612e-01 -1.74523201e-02 9.74265397e-01 2.24801689e-01 -1.74523201e-02 9.75039124e-01 2.21416831e-01 -1.74523201e-02 9.75799084e-01 2.18059942e-01 -1.74523201e-02 9.76562858e-01 2.14588985e-01 -1.74523201e-02 9.77303386e-01 2.11200297e-01 -1.74523201e-02 9.78054702e-01 2.07693398e-01 -1.74523201e-02 9.78759170e-01 2.04352140e-01 -1.74523201e-02 9.79465067e-01 2.00951651e-01 -1.74523201e-02 9.80160952e-01 1.97511822e-01 -1.74523201e-02 9.80824530e-01 1.94196135e-01 -1.74523201e-02 9.81513560e-01 1.90684706e-01 -1.74523201e-02 9.82173026e-01 1.87250808e-01 -1.74523201e-02 9.82815981e-01 1.83853328e-01 -1.74523201e-02 9.83449876e-01 1.80409983e-01 -1.74523201e-02 9.84073818e-01 1.77021876e-01 -1.74523201e-02 9.84691679e-01 1.73550501e-01 -1.74523201e-02 9.85305309e-01 1.69998959e-01 -1.74523201e-02 9.85893250e-01 1.66564077e-01 -1.74523201e-02 9.86448526e-01 1.63234472e-01 -1.74523201e-02 9.87001002e-01 1.59868106e-01 -1.74523201e-02 9.87573504e-01 1.56300277e-01 -1.74523201e-02 9.88110721e-01 1.52856991e-01 -1.74523201e-02 9.88632321e-01 1.49442002e-01 -1.74523201e-02 9.89151418e-01 1.45970330e-01 -1.74523201e-02 9.89638984e-01 1.42618045e-01 -1.74523201e-02 9.90149617e-01 1.39055014e-01 -1.74523201e-02 9.90624249e-01 1.35617554e-01 -1.74523201e-02 9.91096199e-01 1.32125974e-01 -1.74523201e-02 9.91549194e-01 1.28668591e-01 -1.74523201e-02 9.91993606e-01 1.25218883e-01 -1.74523201e-02 9.92435515e-01 1.21666536e-01 -1.74523201e-02 9.92854714e-01 1.18166327e-01 -1.74523201e-02 9.93263066e-01 1.14699736e-01 -1.74523201e-02 9.93646681e-01 1.11324318e-01 -1.74523201e-02 9.94017303e-01 1.07969299e-01 -1.74523201e-02 9.94397700e-01 1.04415275e-01 -1.74523201e-02 9.94753659e-01 1.00941218e-01 -1.74523201e-02 9.95102346e-01 9.74625796e-02 -1.74523201e-02 9.95436370e-01 9.39783081e-02 -1.74523201e-02 9.95749652e-01 9.06221494e-02 -1.74523201e-02 9.96062994e-01 8.71224776e-02 -1.74523201e-02 9.96358752e-01 8.36440399e-02 -1.74523201e-02 9.96654868e-01 8.00451115e-02 -1.74523201e-02 9.96936381e-01 7.64621496e-02 -1.74523201e-02 9.97194409e-01 7.30093494e-02 -1.74523201e-02 9.97439802e-01 6.95515722e-02 -1.74523201e-02 9.97673035e-01 6.61404505e-02 -1.74523201e-02 9.97891366e-01 6.27636015e-02 -1.74523201e-02 9.98107076e-01 5.92507198e-02 -1.74523201e-02 9.98313725e-01 5.56731187e-02 -1.74523201e-02 9.98505116e-01 5.20988367e-02 -1.74523201e-02 9.98676062e-01 4.87052873e-02 -1.74523201e-02 9.98836637e-01 4.53227237e-02 -1.74523201e-02 9.98988211e-01 4.18321267e-02 -1.74523201e-02 9.99128461e-01 3.83472331e-02 -1.74523201e-02 9.99258518e-01 3.47849764e-02 -1.74523201e-02 9.99377191e-01 3.11850104e-02 -1.74523201e-02 9.99476790e-01 2.78010257e-02 -1.74523201e-02 9.99569178e-01 2.43913680e-02 -1.74523201e-02 9.99644279e-01 2.08900236e-02 -1.74523201e-02 9.99715984e-01 1.74132008e-02 -1.74523201e-02 9.99763250e-01 1.39364135e-02 -1.74523201e-02 9.99809682e-01 1.03951478e-02 -1.74523201e-02 9.99845326e-01 6.93757692e-03 -1.74523201e-02 9.99864280e-01 3.38670867e-03 -1.74523201e-02 9.99863863e-01 -1.31864144e-04 -1.74523201e-02 9.99863982e-01 -3.60967848e-03 -1.74523201e-02 9.99841928e-01 -7.13506900e-03 -1.74523201e-02 9.99806702e-01 -1.05274813e-02 -1.74523201e-02 9.99760509e-01 -1.40718007e-02 -1.74523201e-02 9.99710262e-01 -1.77001767e-02 -1.74523201e-02 9.99640048e-01 -2.10843179e-02 -1.74523201e-02 9.99565423e-01 -2.45492514e-02 -1.74523201e-02 9.99470532e-01 -2.80498769e-02 -1.74523201e-02 9.99366701e-01 -3.15681361e-02 -1.74523201e-02 9.99250650e-01 -3.50401960e-02 -1.74523201e-02 9.99125302e-01 -3.84380519e-02 -1.74523201e-02 9.98985946e-01 -4.19228934e-02 -1.74523201e-02 9.98829961e-01 -4.54829969e-02 -1.74523201e-02 9.98661399e-01 -4.90539894e-02 -1.74523201e-02 9.98480439e-01 -5.25472537e-02 -1.74523201e-02 9.98295546e-01 -5.59665896e-02 -1.74523201e-02 9.98101711e-01 -5.93390092e-02 -1.74523201e-02 9.97886896e-01 -6.28161430e-02 -1.74523201e-02 9.97660637e-01 -6.63507134e-02 -1.74523201e-02 9.97414231e-01 -6.99257031e-02 -1.74523201e-02 9.97163415e-01 -7.34252781e-02 -1.74523201e-02 9.96905982e-01 -7.68500492e-02 -1.74523201e-02 9.96640027e-01 -8.02379549e-02 -1.74523201e-02 9.96355057e-01 -8.36963803e-02 -1.74523201e-02 9.96047556e-01 -8.72784406e-02 -1.74523201e-02 9.95735347e-01 -9.07552913e-02 -1.74523201e-02 9.95424747e-01 -9.41191167e-02 -1.74523201e-02 9.95084524e-01 -9.76395905e-02 -1.74523201e-02 9.94734645e-01 -1.01152800e-01 -1.74523201e-02 9.94372249e-01 -1.04647316e-01 -1.74523201e-02 9.94002044e-01 -1.08112253e-01 -1.74523201e-02 9.93616343e-01 -1.11605689e-01 -1.74523201e-02 9.93233621e-01 -1.14943169e-01 -1.74523201e-02 9.92817998e-01 -1.18494600e-01 -1.74523201e-02 9.92393374e-01 -1.21993259e-01 -1.74523201e-02 9.91966963e-01 -1.25429153e-01 -1.74523201e-02 9.91511285e-01 -1.28960580e-01 -1.74523201e-02 9.91062045e-01 -1.32370085e-01 -1.74523201e-02 9.90596890e-01 -1.35822386e-01 -1.74523201e-02 9.90109086e-01 -1.39330298e-01 -1.74523201e-02 9.89624619e-01 -1.42720267e-01 -1.74523201e-02 9.89118874e-01 -1.46185070e-01 -1.74523201e-02 9.88604128e-01 -1.49628565e-01 -1.74523201e-02 9.88077462e-01 -1.53069749e-01 -1.74523201e-02 9.87534702e-01 -1.56524420e-01 -1.74523201e-02 9.86991644e-01 -1.59922406e-01 -1.74523201e-02 9.86420989e-01 -1.63403869e-01 -1.74523201e-02 9.85844135e-01 -1.66852891e-01 -1.74523201e-02 9.85234678e-01 -1.70404941e-01 -1.74523201e-02 9.84639287e-01 -1.73837796e-01 -1.74523201e-02 9.84042883e-01 -1.77181795e-01 -1.74523201e-02 9.83431399e-01 -1.80514023e-01 -1.74523201e-02 9.82797861e-01 -1.83953568e-01 -1.74523201e-02 9.82137203e-01 -1.87443256e-01 -1.74523201e-02 9.81457770e-01 -1.90965697e-01 -1.74523201e-02 9.80784118e-01 -1.94397300e-01 -1.74523201e-02 9.80109155e-01 -1.97771162e-01 -1.74523201e-02 9.79439437e-01 -2.01061651e-01 -1.74523201e-02 9.78723586e-01 -2.04518124e-01 -1.74523201e-02 9.77985740e-01 -2.08029002e-01 -1.74523201e-02 9.77256358e-01 -2.11422712e-01 -1.74523201e-02 9.76521194e-01 -2.14789331e-01 -1.74523201e-02 9.75755990e-01 -2.18237251e-01 -1.74523201e-02 9.74993646e-01 -2.21617579e-01 -1.74523201e-02 9.74208176e-01 -2.25045070e-01 -1.74523201e-02 9.73419726e-01 -2.28450343e-01 -1.74523201e-02 9.72615004e-01 -2.31839687e-01 -1.74523201e-02 9.71825004e-01 -2.35138446e-01 -1.74523201e-02 9.70973134e-01 -2.38621846e-01 -1.74523201e-02 9.70139623e-01 -2.41981059e-01 -1.74523201e-02 9.69289482e-01 -2.45363727e-01 -1.74523201e-02 9.68401492e-01 -2.48856887e-01 -1.74523201e-02 9.67546225e-01 -2.52157688e-01 -1.74523201e-02 9.66668487e-01 -2.55503982e-01 -1.74523201e-02 9.65757012e-01 -2.58924276e-01 -1.74523201e-02 9.64872181e-01 -2.62207031e-01 -1.74523201e-02 9.63934124e-01 -2.65631437e-01 -1.74523201e-02 9.62996244e-01 -2.69008726e-01 -1.74523201e-02 9.62050796e-01 -2.72376150e-01 -1.74523201e-02 9.61059213e-01 -2.75846779e-01 -1.74523201e-02 9.60128188e-01 -2.79063910e-01 -1.74523201e-02 9.59173024e-01 -2.82335013e-01 -1.74523201e-02 9.58159626e-01 -2.85763770e-01 -1.74523201e-02 9.57123458e-01 -2.89206326e-01 -1.74523201e-02 9.56112266e-01 -2.92540461e-01 -1.74523201e-02 9.55106497e-01 -2.95803696e-01 -1.74523201e-02 9.54102039e-01 -2.99027741e-01 -1.74523201e-02 9.53056395e-01 -3.02346140e-01 -1.74523201e-02 9.51988876e-01 -3.05690885e-01 -1.74523201e-02 9.50891554e-01 -3.09083492e-01 -1.74523201e-02 9.49785829e-01 -3.12462807e-01 -1.74523201e-02 9.48702216e-01 -3.15738887e-01 -1.74523201e-02 9.47636783e-01 -3.18926066e-01 -1.74523201e-02 9.46503818e-01 -3.22267830e-01 -1.74523201e-02 9.45365906e-01 -3.25595438e-01 -1.74523201e-02 9.44210052e-01 -3.28924984e-01 -1.74523201e-02 9.43061173e-01 -3.32210898e-01 -1.74523201e-02 9.41896498e-01 -3.35503131e-01 -1.74523201e-02 9.40714598e-01 -3.38796377e-01 -1.74523201e-02 9.39529002e-01 -3.42076898e-01 -1.74523201e-02 9.38310564e-01 -3.45389724e-01 -1.74523201e-02 9.37085330e-01 -3.48678827e-01 -1.74523201e-02 9.35917020e-01 -3.51811588e-01 -1.74523201e-02 9.34696555e-01 -3.55051547e-01 -1.74523201e-02 9.33405876e-01 -3.58460039e-01 -1.74523201e-02 9.32129443e-01 -3.61735463e-01 -1.74523201e-02 9.30889010e-01 -3.64932448e-01 -1.74523201e-02 9.29595232e-01 -3.68209958e-01 -1.74523201e-02 9.28310931e-01 -3.71441036e-01 -1.74523201e-02 9.27002966e-01 -3.74686867e-01 -1.74523201e-02 9.25734639e-01 -3.77812445e-01 -1.74523201e-02 9.24369276e-01 -3.81142378e-01 -1.74523201e-02 9.23023880e-01 -3.84384900e-01 -1.74523201e-02 9.21697497e-01 -3.87559056e-01 -1.74523201e-02 9.20282245e-01 -3.90902907e-01 -1.74523201e-02 9.18955088e-01 -3.94008279e-01 -1.74523201e-02 9.17616844e-01 -3.97122115e-01 -1.74523201e-02 9.16185498e-01 -4.00421798e-01 -1.74523201e-02 9.14737999e-01 -4.03708249e-01 -1.74523201e-02 9.13337469e-01 -4.06868488e-01 -1.74523201e-02 9.11946535e-01 -4.09977168e-01 -1.74523201e-02 9.10550237e-01 -4.13066626e-01 -1.74523201e-02 9.09099519e-01 -4.16246712e-01 -1.74523201e-02 9.07593727e-01 -4.19525445e-01 -1.74523201e-02 9.06102538e-01 -4.22734261e-01 -1.74523201e-02 9.04611588e-01 -4.25914705e-01 -1.74523201e-02 9.03157473e-01 -4.28989172e-01 -1.74523201e-02 9.01690245e-01 -4.32064295e-01 -1.74523201e-02 9.00179148e-01 -4.35212463e-01 -1.74523201e-02 8.98616314e-01 -4.38428909e-01 -1.74523201e-02 8.97071898e-01 -4.41575348e-01 -1.74523201e-02 8.95546615e-01 -4.44662482e-01 -1.74523201e-02 8.93966258e-01 -4.47829723e-01 -1.74523201e-02 8.92458677e-01 -4.50828820e-01 -1.74523201e-02 8.90885532e-01 -4.53929216e-01 -1.74523201e-02 8.89246047e-01 -4.57133114e-01 -1.74523201e-02 8.87634933e-01 -4.60248142e-01 -1.74523201e-02 8.86053443e-01 -4.63294923e-01 -1.74523201e-02 8.84443462e-01 -4.66359168e-01 -1.74523201e-02 8.82777095e-01 -4.69503254e-01 -1.74523201e-02 8.81135225e-01 -4.72577184e-01 -1.74523201e-02 8.79478455e-01 -4.75653589e-01 -1.74523201e-02 8.77793074e-01 -4.78758365e-01 -1.74523201e-02 8.76178086e-01 -4.81705934e-01 -1.74523201e-02 8.74483645e-01 -4.84769553e-01 -1.74523201e-02 8.72788608e-01 -4.87819284e-01 -1.74523201e-02 8.71084034e-01 -4.90858734e-01 -1.74523201e-02 8.69324803e-01 -4.93965119e-01 -1.74523201e-02 8.67579758e-01 -4.97024775e-01 -1.74523201e-02 8.65837991e-01 -5.00056326e-01 -1.74523201e-02 8.64095211e-01 -5.03059506e-01 -1.74523201e-02 8.62386823e-01 -5.05985141e-01 -1.74523201e-02 8.60621274e-01 -5.08978426e-01 -1.74523201e-02 8.58831108e-01 -5.11992395e-01 -1.74523201e-02 8.56986463e-01 -5.15077531e-01 -1.74523201e-02 8.55148911e-01 -5.18117487e-01 -1.74523201e-02 8.53387773e-01 -5.21017492e-01 -1.74523201e-02 8.51604879e-01 -5.23924112e-01 -1.74523201e-02 8.49773765e-01 -5.26892006e-01 -1.74523201e-02 8.47884953e-01 -5.29925823e-01 -1.74523201e-02 8.45995605e-01 -5.32935560e-01 -1.74523201e-02 8.44151795e-01 -5.35849512e-01 -1.74523201e-02 8.42318773e-01 -5.38728118e-01 -1.74523201e-02 8.40392709e-01 -5.41728258e-01 -1.74523201e-02 8.38430166e-01 -5.44760227e-01 -1.74523201e-02 8.36545408e-01 -5.47646582e-01 -1.74523201e-02 8.34639668e-01 -5.50549686e-01 -1.74523201e-02 8.32734704e-01 -5.53422570e-01 -1.74523201e-02 8.30874026e-01 -5.56215465e-01 -1.74523201e-02 8.28907132e-01 -5.59145808e-01 -1.74523201e-02 8.26899350e-01 -5.62109113e-01 -1.74523201e-02 8.24931979e-01 -5.64990461e-01 -1.74523201e-02 8.22953701e-01 -5.67870855e-01 -1.74523201e-02 8.20956707e-01 -5.70750356e-01 -1.74523201e-02 8.18979144e-01 -5.73585331e-01 -1.74523201e-02 8.16956043e-01 -5.76465070e-01 -1.74523201e-02 8.14955711e-01 -5.79289079e-01 -1.74523201e-02 8.12920392e-01 -5.82143486e-01 -1.74523201e-02 8.10922265e-01 -5.84917724e-01 -1.74523201e-02 8.08823943e-01 -5.87820709e-01 -1.74523201e-02 8.06764543e-01 -5.90641260e-01 -1.74523201e-02 8.04692149e-01 -5.93463480e-01 -1.74523201e-02 8.02586019e-01 -5.96306145e-01 -1.74523201e-02 8.00565422e-01 -5.99017143e-01 -1.74523201e-02 7.98477709e-01 -6.01800680e-01 -1.74523201e-02 7.96364307e-01 -6.04591310e-01 -1.74523201e-02 7.94295609e-01 -6.07308567e-01 -1.74523201e-02 7.92152464e-01 -6.10099614e-01 -1.74523201e-02 7.89967775e-01 -6.12926126e-01 -1.74523201e-02 7.87772000e-01 -6.15745723e-01 -1.74523201e-02 7.85643101e-01 -6.18460894e-01 -1.74523201e-02 7.83520579e-01 -6.21146381e-01 -1.74523201e-02 7.81395674e-01 -6.23817801e-01 -1.74523201e-02 7.79220462e-01 -6.26534402e-01 -1.74523201e-02 7.76973903e-01 -6.29320085e-01 -1.74523201e-02 7.74722517e-01 -6.32084608e-01 -1.74523201e-02 7.72571504e-01 -6.34712577e-01 -1.74523201e-02 7.70409524e-01 -6.37337267e-01 -1.74523201e-02 7.68194973e-01 -6.40004516e-01 -1.74523201e-02 7.65953958e-01 -6.42685294e-01 -1.74523201e-02 7.63641477e-01 -6.45430982e-01 -1.74523201e-02 7.61385560e-01 -6.48087621e-01 -1.74523201e-02 7.59104431e-01 -6.50759339e-01 -1.74523201e-02 7.56815612e-01 -6.53420210e-01 -1.74523201e-02 7.54578114e-01 -6.56005263e-01 -1.74523201e-02 7.52224326e-01 -6.58700585e-01 -1.74523201e-02 7.49881327e-01 -6.61366284e-01 -1.74523201e-02 7.47650146e-01 -6.63888693e-01 -1.74523201e-02 7.45370686e-01 -6.66448057e-01 -1.74523201e-02 7.42982626e-01 -6.69109523e-01 -1.74523201e-02 7.40624547e-01 -6.71717405e-01 -1.74523201e-02 7.38282323e-01 -6.74291611e-01 -1.74523201e-02 7.35914648e-01 -6.76873624e-01 -1.74523201e-02 7.33608723e-01 -6.79373324e-01 -1.74523201e-02 7.31242001e-01 -6.81916416e-01 -1.74523201e-02 7.28791535e-01 -6.84537709e-01 -1.74523201e-02 7.26376832e-01 -6.87095881e-01 -1.74523201e-02 7.24001110e-01 -6.89604580e-01 -1.74523201e-02 7.21580505e-01 -6.92128301e-01 -1.74523257e-02 7.19164193e-01 -6.94646597e-01 -1.74523257e-02 7.16709852e-01 -6.97173536e-01 -1.74523313e-02 7.14347839e-01 -6.99589789e-01 -1.74523313e-02 7.11877406e-01 -7.02103555e-01 -1.74523313e-02 7.09401608e-01 -7.04587221e-01 -1.74523443e-02 7.07142174e-01 -7.06855297e-01 -1.74524002e-02 7.04504251e-01 -7.09483802e-01 -1.74524095e-02 7.01842904e-01 -7.12117016e-01 -1.74524076e-02 6.99631274e-01 -7.14290321e-01 -1.74524076e-02 6.96808398e-01 -7.17044473e-01 -1.74524076e-02 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. 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. 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. 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. 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. 5.69636106e-01 -8.21711361e-01 -1.74523983e-02 5.67546189e-01 -8.23161125e-01 -1.74523313e-02 5.64833164e-01 -8.25033247e-01 -1.74523313e-02 5.61967611e-01 -8.26990485e-01 -1.74523313e-02 5.59105098e-01 -8.28931034e-01 -1.74523219e-02 5.56216896e-01 -8.30871522e-01 -1.74523201e-02 5.53234160e-01 -8.32861423e-01 -1.74523201e-02 5.50287127e-01 -8.34811866e-01 -1.74523201e-02 5.47459006e-01 -8.36668670e-01 -1.74523201e-02 5.44489264e-01 -8.38605881e-01 -1.74523201e-02 5.41533470e-01 -8.40515792e-01 -1.74523201e-02 5.38682044e-01 -8.42347205e-01 -1.74523201e-02 5.35735071e-01 -8.44224274e-01 -1.74523201e-02 5.32796621e-01 -8.46084535e-01 -1.74523201e-02 5.29847264e-01 -8.47931147e-01 -1.74523201e-02 5.26900947e-01 -8.49769294e-01 -1.74523201e-02 5.23911059e-01 -8.51612449e-01 -1.74523201e-02 5.20939827e-01 -8.53437603e-01 -1.74523201e-02 5.17939806e-01 -8.55257452e-01 -1.74523201e-02 5.14948964e-01 -8.57062697e-01 -1.74523201e-02 5.11963487e-01 -8.58848691e-01 -1.74523201e-02 5.08959293e-01 -8.60632837e-01 -1.74523201e-02 5.05951524e-01 -8.62406135e-01 -1.74523201e-02 5.02933502e-01 -8.64167154e-01 -1.74523201e-02 4.99822527e-01 -8.65972579e-01 -1.74523201e-02 4.96810287e-01 -8.67702663e-01 -1.74523201e-02 4.93848234e-01 -8.69390249e-01 -1.74523201e-02 4.90827501e-01 -8.71103168e-01 -1.74523201e-02 4.87768412e-01 -8.72816682e-01 -1.74523201e-02 4.84715372e-01 -8.74515057e-01 -1.74523201e-02 4.81681168e-01 -8.76193285e-01 -1.74523201e-02 4.78583634e-01 -8.77889156e-01 -1.74523201e-02 4.75537539e-01 -8.79540384e-01 -1.74523201e-02 4.72466379e-01 -8.81195962e-01 -1.74523201e-02 4.69379246e-01 -8.82842600e-01 -1.74523201e-02 4.66290236e-01 -8.84479463e-01 -1.74523201e-02 4.63113159e-01 -8.86146545e-01 -1.74523201e-02 4.60012794e-01 -8.87757421e-01 -1.74523201e-02 4.57016796e-01 -8.89306605e-01 -1.74523201e-02 4.53896850e-01 -8.90901804e-01 -1.74523201e-02 4.50769424e-01 -8.92488539e-01 -1.74523201e-02 4.47652638e-01 -8.94054830e-01 -1.74523201e-02 4.44528013e-01 -8.95612836e-01 -1.74523201e-02 4.41413343e-01 -8.97153437e-01 -1.74523201e-02 4.38247353e-01 -8.98704231e-01 -1.74523201e-02 4.35119063e-01 -9.00224030e-01 -1.74523201e-02 4.31984693e-01 -9.01728868e-01 -1.74523201e-02 4.28862065e-01 -9.03219163e-01 -1.74523201e-02 4.25688118e-01 -9.04718757e-01 -1.74523201e-02 4.22463924e-01 -9.06232238e-01 -1.74523201e-02 4.19265419e-01 -9.07713830e-01 -1.74523201e-02 4.16190475e-01 -9.09127295e-01 -1.74523201e-02 4.13009286e-01 -9.10578430e-01 -1.74523201e-02 4.09820288e-01 -9.12018299e-01 -1.74523201e-02 4.06554341e-01 -9.13479686e-01 -1.74523201e-02 4.03355181e-01 -9.14894700e-01 -1.74523201e-02 4.00250822e-01 -9.16259289e-01 -1.74523201e-02 3.97047937e-01 -9.17650640e-01 -1.74523201e-02 3.93824786e-01 -9.19034183e-01 -1.74523201e-02 3.90557706e-01 -9.20430779e-01 -1.74523201e-02 3.87331188e-01 -9.21793759e-01 -1.74523201e-02 3.84122282e-01 -9.23136055e-01 -1.74523201e-02 3.80870670e-01 -9.24478352e-01 -1.74523201e-02 3.77741873e-01 -9.25764740e-01 -1.74523201e-02 3.74522477e-01 -9.27071571e-01 -1.74523201e-02 3.71186644e-01 -9.28412616e-01 -1.74523201e-02 3.67858082e-01 -9.29736495e-01 -1.74523201e-02 3.64680976e-01 -9.30988133e-01 -1.74523201e-02 3.61534417e-01 -9.32207644e-01 -1.74523201e-02 3.58273476e-01 -9.33476269e-01 -1.74523201e-02 3.55004311e-01 -9.34715211e-01 -1.74523201e-02 3.51698756e-01 -9.35960352e-01 -1.74523201e-02 3.48445892e-01 -9.37174141e-01 -1.74523201e-02 3.45209450e-01 -9.38376188e-01 -1.74523201e-02 3.41931313e-01 -9.39582348e-01 -1.74523201e-02 3.38642389e-01 -9.40769613e-01 -1.74523201e-02 3.35366338e-01 -9.41945195e-01 -1.74523201e-02 3.32056612e-01 -9.43115652e-01 -1.74523201e-02 3.28768820e-01 -9.44265842e-01 -1.74523201e-02 3.25389951e-01 -9.45438087e-01 -1.74523201e-02 3.22098225e-01 -9.46562052e-01 -1.74523201e-02 3.18887830e-01 -9.47650433e-01 -1.74523201e-02 3.15590888e-01 -9.48752105e-01 -1.74523201e-02 3.12277198e-01 -9.49847758e-01 -1.74523201e-02 3.08854491e-01 -9.50968504e-01 -1.74523201e-02 3.05545211e-01 -9.52035904e-01 -1.74523201e-02 3.02331418e-01 -9.53060389e-01 -1.74523201e-02 2.98994154e-01 -9.54112709e-01 -1.74523201e-02 2.95659453e-01 -9.55151796e-01 -1.74523201e-02 2.92308211e-01 -9.56182241e-01 -1.74523201e-02 2.88913399e-01 -9.57212389e-01 -1.74523201e-02 2.85525024e-01 -9.58229005e-01 -1.74523201e-02 2.82279879e-01 -9.59191382e-01 -1.74523201e-02 2.78841615e-01 -9.60197866e-01 -1.74523201e-02 2.75385708e-01 -9.61191952e-01 -1.74523201e-02 2.72009343e-01 -9.62153196e-01 -1.74523201e-02 2.68741757e-01 -9.63071823e-01 -1.74523201e-02 2.65479594e-01 -9.63976800e-01 -1.74523201e-02 2.62111604e-01 -9.64899540e-01 -1.74523201e-02 2.58736193e-01 -9.65806901e-01 -1.74523201e-02 2.55334020e-01 -9.66713727e-01 -1.74523201e-02 2.51949251e-01 -9.67601061e-01 -1.74523201e-02 2.48605028e-01 -9.68466520e-01 -1.74523201e-02 2.45216548e-01 -9.69326377e-01 -1.74523201e-02 2.41763264e-01 -9.70195293e-01 -1.74523201e-02 2.38351345e-01 -9.71039772e-01 -1.74523201e-02 2.35063165e-01 -9.71844077e-01 -1.74523201e-02 2.31679589e-01 -9.72654760e-01 -1.74523201e-02 2.28266686e-01 -9.73460615e-01 -1.74523201e-02 2.24784479e-01 -9.74270046e-01 -1.74523201e-02 2.21271887e-01 -9.75073814e-01 -1.74523201e-02 2.17975557e-01 -9.75815058e-01 -1.74523201e-02 2.14676440e-01 -9.76546228e-01 -1.74523201e-02 2.11245224e-01 -9.77294207e-01 -1.74523201e-02 2.07847863e-01 -9.78022397e-01 -1.74523201e-02 2.04338849e-01 -9.78764355e-01 -1.74523201e-02 2.00917423e-01 -9.79469836e-01 -1.74523201e-02 1.97589979e-01 -9.80147541e-01 -1.74523201e-02 1.94166780e-01 -9.80829716e-01 -1.74523201e-02 1.90747455e-01 -9.81501222e-01 -1.74523201e-02 1.87251315e-01 -9.82174754e-01 -1.74523201e-02 1.83786988e-01 -9.82825994e-01 -1.74523201e-02 1.80351585e-01 -9.83462095e-01 -1.74523201e-02 1.76908210e-01 -9.84094262e-01 -1.74523201e-02 1.73582777e-01 -9.84687269e-01 -1.74523201e-02 1.70148477e-01 -9.85279202e-01 -1.74523201e-02 1.66694045e-01 -9.85873044e-01 -1.74523201e-02 1.63259059e-01 -9.86446500e-01 -1.74523201e-02 1.59811467e-01 -9.87009943e-01 -1.74523201e-02 1.56354472e-01 -9.87563729e-01 -1.74523201e-02 1.52932510e-01 -9.88100111e-01 -1.74523201e-02 1.49477333e-01 -9.88626719e-01 -1.74523201e-02 1.46027535e-01 -9.89143670e-01 -1.74523201e-02 1.42584488e-01 -9.89644825e-01 -1.74523201e-02 1.39034092e-01 -9.90152717e-01 -1.74523201e-02 1.35460824e-01 -9.90646064e-01 -1.74523201e-02 1.32110298e-01 -9.91096914e-01 -1.74523201e-02 1.28733128e-01 -9.91541982e-01 -1.74523201e-02 1.25267997e-01 -9.91988003e-01 -1.74523201e-02 1.21803097e-01 -9.92417097e-01 -1.74523201e-02 1.18273385e-01 -9.92843986e-01 -1.74523201e-02 1.14776187e-01 -9.93251741e-01 -1.74523201e-02 1.11423969e-01 -9.93636012e-01 -1.74523201e-02 1.07933827e-01 -9.94020641e-01 -1.74523201e-02 1.04461633e-01 -9.94391084e-01 -1.74523201e-02 1.00913249e-01 -9.94757354e-01 -1.74523201e-02 9.74512473e-02 -9.95102823e-01 -1.74523201e-02 9.39908922e-02 -9.95439589e-01 -1.74523201e-02 9.04818922e-02 -9.95761991e-01 -1.74523201e-02 8.70322362e-02 -9.96070564e-01 -1.74523201e-02 8.34525153e-02 -9.96376097e-01 -1.74523201e-02 8.00601393e-02 -9.96654272e-01 -1.74523201e-02 7.66930729e-02 -9.96918023e-01 -1.74523201e-02 7.32014850e-02 -9.97181952e-01 -1.74523201e-02 6.97190166e-02 -9.97429192e-01 -1.74523201e-02 6.62601888e-02 -9.97666895e-01 -1.74523201e-02 6.27774745e-02 -9.97891068e-01 -1.74523201e-02 5.92712685e-02 -9.98105228e-01 -1.74523201e-02 5.57949245e-02 -9.98306990e-01 -1.74523201e-02 5.22134639e-02 -9.98499632e-01 -1.74523201e-02 4.86956313e-02 -9.98677850e-01 -1.74523201e-02 4.52332422e-02 -9.98841107e-01 -1.74523201e-02 4.16533090e-02 -9.98997390e-01 -1.74523201e-02 3.82565856e-02 -9.99131739e-01 -1.74523201e-02 3.48767377e-02 -9.99255657e-01 -1.74523201e-02 3.13038789e-02 -9.99373615e-01 -1.74523201e-02 2.77917255e-02 -9.99478400e-01 -1.74523201e-02 2.43053697e-02 -9.99572575e-01 -1.74523201e-02 2.07959544e-02 -9.99645531e-01 -1.74523201e-02 1.74091887e-02 -9.99717414e-01 -1.74523201e-02 1.39178773e-02 -9.99762595e-01 -1.74523201e-02 1.04108211e-02 -9.99810934e-01 -1.74523201e-02 6.92255190e-03 -9.99846160e-01 -1.74523201e-02 3.44362785e-03 -9.99863863e-01 -1.74523201e-02 -3.74583797e-05 -9.99864876e-01 -1.74523201e-02 -3.51822935e-03 -9.99863625e-01 -1.74523201e-02 -7.00075738e-03 -9.99847114e-01 -1.74523201e-02 -1.04915891e-02 -9.99808908e-01 -1.74523201e-02 -1.40021425e-02 -9.99762177e-01 -1.74523201e-02 -1.75688080e-02 -9.99716640e-01 -1.74523201e-02 -2.11346410e-02 -9.99639213e-01 -1.74523201e-02 -2.45430321e-02 -9.99564648e-01 -1.74523201e-02 -2.79460866e-02 -9.99475121e-01 -1.74523201e-02 -3.14294212e-02 -9.99371231e-01 -1.74523201e-02 -3.49119231e-02 -9.99256313e-01 -1.74523201e-02 -3.84921730e-02 -9.99125302e-01 -1.74523201e-02 -4.19889204e-02 -9.98982906e-01 -1.74523201e-02 -4.53832373e-02 -9.98833418e-01 -1.74523201e-02 -4.88528088e-02 -9.98671353e-01 -1.74523201e-02 -5.23363762e-02 -9.98491108e-01 -1.74523201e-02 -5.59100322e-02 -9.98302281e-01 -1.74523201e-02 -5.94257601e-02 -9.98096287e-01 -1.74523201e-02 -6.28876761e-02 -9.97882664e-01 -1.74523201e-02 -6.63724691e-02 -9.97658134e-01 -1.74523201e-02 -6.97777420e-02 -9.97425616e-01 -1.74523201e-02 -7.32441321e-02 -9.97178912e-01 -1.74523201e-02 -7.67173022e-02 -9.96917069e-01 -1.74523201e-02 -8.02870393e-02 -9.96635437e-01 -1.74523201e-02 -8.37901980e-02 -9.96346295e-01 -1.74523201e-02 -8.71489868e-02 -9.96058404e-01 -1.74523201e-02 -9.06219184e-02 -9.95749474e-01 -1.74523201e-02 -9.41162631e-02 -9.95425224e-01 -1.74523201e-02 -9.75777507e-02 -9.95091856e-01 -1.74523201e-02 -1.01049684e-01 -9.94745612e-01 -1.74523201e-02 -1.04609191e-01 -9.94378865e-01 -1.74523201e-02 -1.08182646e-01 -9.93995190e-01 -1.74523201e-02 -1.11568041e-01 -9.93620753e-01 -1.74523201e-02 -1.14922374e-01 -9.93236601e-01 -1.74523201e-02 -1.18401229e-01 -9.92827713e-01 -1.74523201e-02 -1.21859744e-01 -9.92410839e-01 -1.74523201e-02 -1.25430286e-01 -9.91967916e-01 -1.74523201e-02 -1.28924593e-01 -9.91516173e-01 -1.74523201e-02 -1.32268265e-01 -9.91077006e-01 -1.74523201e-02 -1.35729134e-01 -9.90609586e-01 -1.74523201e-02 -1.39188066e-01 -9.90129411e-01 -1.74523201e-02 -1.42723620e-01 -9.89624560e-01 -1.74523201e-02 -1.46190837e-01 -9.89117503e-01 -1.74523201e-02 -1.49626926e-01 -9.88605499e-01 -1.74523201e-02 -1.53105170e-01 -9.88072634e-01 -1.74523201e-02 -1.56474963e-01 -9.87544179e-01 -1.74523201e-02 -1.59897059e-01 -9.86997962e-01 -1.74523201e-02 -1.63354084e-01 -9.86431241e-01 -1.74523201e-02 -1.66882873e-01 -9.85840261e-01 -1.74523201e-02 -1.70335099e-01 -9.85247493e-01 -1.74523201e-02 -1.73680291e-01 -9.84669030e-01 -1.74523201e-02 -1.77100897e-01 -9.84058022e-01 -1.74523201e-02 -1.80531755e-01 -9.83429313e-01 -1.74523201e-02 -1.84059322e-01 -9.82779384e-01 -1.74523201e-02 -1.87511429e-01 -9.82123494e-01 -1.74523201e-02 -1.90791115e-01 -9.81491923e-01 -1.74523201e-02 -1.94225997e-01 -9.80820060e-01 -1.74523201e-02 -1.97772592e-01 -9.80109155e-01 -1.74523201e-02 -2.01193511e-01 -9.79411721e-01 -1.74523201e-02 -2.04483926e-01 -9.78732109e-01 -1.74523201e-02 -2.07931072e-01 -9.78007317e-01 -1.74523201e-02 -2.11415231e-01 -9.77261007e-01 -1.74523201e-02 -2.14836448e-01 -9.76509690e-01 -1.74523201e-02 -2.18161508e-01 -9.75775182e-01 -1.74523201e-02 -2.21536964e-01 -9.75012958e-01 -1.74523201e-02 -2.24982947e-01 -9.74223495e-01 -1.74523201e-02 -2.28436515e-01 -9.73422348e-01 -1.74523201e-02 -2.31835544e-01 -9.72617447e-01 -1.74523201e-02 -2.35144362e-01 -9.71823454e-01 -1.74523201e-02 -2.38599569e-01 -9.70979869e-01 -1.74523201e-02 -2.42001861e-01 -9.70135927e-01 -1.74523201e-02 -2.45313630e-01 -9.69302952e-01 -1.74523201e-02 -2.48692602e-01 -9.68442619e-01 -1.74523201e-02 -2.52156198e-01 -9.67547953e-01 -1.74523201e-02 -2.55545676e-01 -9.66658056e-01 -1.74523201e-02 -2.58880585e-01 -9.65771019e-01 -1.74523201e-02 -2.62369066e-01 -9.64829445e-01 -1.74523201e-02 -2.65645623e-01 -9.63929355e-01 -1.74523201e-02 -2.68996000e-01 -9.63002324e-01 -1.74523201e-02 -2.72356808e-01 -9.62056279e-01 -1.74523201e-02 -2.75615096e-01 -9.61127996e-01 -1.74523201e-02 -2.78966278e-01 -9.60160673e-01 -1.74523201e-02 -2.82329649e-01 -9.59175944e-01 -1.74523201e-02 -2.85679549e-01 -9.58186090e-01 -1.74523201e-02 -2.89026946e-01 -9.57178175e-01 -1.74523201e-02 -2.92370498e-01 -9.56162274e-01 -1.74523201e-02 -2.95769274e-01 -9.55118537e-01 -1.74523201e-02 -2.99102306e-01 -9.54079092e-01 -1.74523201e-02 -3.02430689e-01 -9.53029215e-01 -1.74523201e-02 -3.05771083e-01 -9.51963723e-01 -1.74523201e-02 -3.09005231e-01 -9.50917065e-01 -1.74523201e-02 -3.12411577e-01 -9.49805677e-01 -1.74523201e-02 -3.15740645e-01 -9.48702633e-01 -1.74523201e-02 -3.19042355e-01 -9.47599232e-01 -1.74523201e-02 -3.22360665e-01 -9.46473122e-01 -1.74523201e-02 -3.25534433e-01 -9.45387244e-01 -1.74523201e-02 -3.28831404e-01 -9.44244564e-01 -1.74523201e-02 -3.32122475e-01 -9.43093181e-01 -1.74523201e-02 -3.35513681e-01 -9.41892385e-01 -1.74523201e-02 -3.38805854e-01 -9.40709889e-01 -1.74523201e-02 -3.42091858e-01 -9.39524233e-01 -1.74523201e-02 -3.45383644e-01 -9.38310206e-01 -1.74523201e-02 -3.48553717e-01 -9.37135100e-01 -1.74523201e-02 -3.51841837e-01 -9.35906470e-01 -1.74523201e-02 -3.55091661e-01 -9.34683621e-01 -1.74523201e-02 -3.58375251e-01 -9.33437705e-01 -1.74523201e-02 -3.61690700e-01 -9.32151020e-01 -1.74523201e-02 -3.64944756e-01 -9.30882692e-01 -1.74523201e-02 -3.68111730e-01 -9.29636598e-01 -1.74523201e-02 -3.71333003e-01 -9.28353012e-01 -1.74523201e-02 -3.74563187e-01 -9.27054882e-01 -1.74523201e-02 -3.77882212e-01 -9.25708175e-01 -1.74523201e-02 -3.81126493e-01 -9.24373269e-01 -1.74523201e-02 -3.84295642e-01 -9.23063397e-01 -1.74523201e-02 -3.87477010e-01 -9.21731889e-01 -1.74523201e-02 -3.90702397e-01 -9.20368552e-01 -1.74523201e-02 -3.93974572e-01 -9.18970764e-01 -1.74523201e-02 -3.97169858e-01 -9.17596221e-01 -1.74523201e-02 -4.00379747e-01 -9.16204274e-01 -1.74523201e-02 -4.03576076e-01 -9.14797664e-01 -1.74523201e-02 -4.06695306e-01 -9.13416207e-01 -1.74523201e-02 -4.09870327e-01 -9.11996782e-01 -1.74523201e-02 -4.13069576e-01 -9.10550416e-01 -1.74523201e-02 -4.16307479e-01 -9.09072101e-01 -1.74523201e-02 -4.19494390e-01 -9.07605529e-01 -1.74523201e-02 -4.22557116e-01 -9.06185925e-01 -1.74523201e-02 -4.25714284e-01 -9.04707491e-01 -1.74523201e-02 -4.28954720e-01 -9.03176069e-01 -1.74523201e-02 -4.32126760e-01 -9.01660323e-01 -1.74523201e-02 -4.35175568e-01 -9.00197983e-01 -1.74523201e-02 -4.38322842e-01 -8.98669481e-01 -1.74523201e-02 -4.41539705e-01 -8.97091508e-01 -1.74523201e-02 -4.44681734e-01 -8.95536125e-01 -1.74523201e-02 -4.47745532e-01 -8.94010127e-01 -1.74523201e-02 -4.50838506e-01 -8.92454982e-01 -1.74523201e-02 -4.53913599e-01 -8.90894175e-01 -1.74523201e-02 -4.57111955e-01 -8.89257610e-01 -1.74523201e-02 -4.60252404e-01 -8.87634635e-01 -1.74523201e-02 -4.63257134e-01 -8.86072874e-01 -1.74523201e-02 -4.66334581e-01 -8.84456336e-01 -1.74523201e-02 -4.69413459e-01 -8.82824659e-01 -1.74523201e-02 -4.72561151e-01 -8.81145597e-01 -1.74523201e-02 -4.75681663e-01 -8.79462957e-01 -1.74523201e-02 -4.78766829e-01 -8.77791226e-01 -1.74523201e-02 -4.81780738e-01 -8.76137555e-01 -1.74523201e-02 -4.84833747e-01 -8.74451339e-01 -1.74523201e-02 -4.87981349e-01 -8.72698188e-01 -1.74523201e-02 -4.90951806e-01 -8.71030927e-01 -1.74523201e-02 -4.93904293e-01 -8.69359791e-01 -1.74523201e-02 -4.96926874e-01 -8.67638528e-01 -1.74523201e-02 -4.99943525e-01 -8.65902305e-01 -1.74523201e-02 -5.02958894e-01 -8.64154994e-01 -1.74523201e-02 -5.05959392e-01 -8.62401128e-01 -1.74523201e-02 -5.08990169e-01 -8.60615134e-01 -1.74523201e-02 -5.11987031e-01 -8.58835161e-01 -1.74523201e-02 -5.14971972e-01 -8.57050300e-01 -1.74523201e-02 -5.17958879e-01 -8.55246007e-01 -1.74523201e-02 -5.20986080e-01 -8.53408515e-01 -1.74523201e-02 -5.24032474e-01 -8.51539969e-01 -1.74523201e-02 -5.26979148e-01 -8.49719405e-01 -1.74523201e-02 -5.29896557e-01 -8.47904742e-01 -1.74523201e-02 -5.32957375e-01 -8.45983326e-01 -1.74523201e-02 -5.35950601e-01 -8.44088137e-01 -1.74523201e-02 -5.38883984e-01 -8.42218995e-01 -1.74523201e-02 -5.41756749e-01 -8.40372920e-01 -1.74523201e-02 -5.44594526e-01 -8.38538229e-01 -1.74523201e-02 -5.47524989e-01 -8.36625993e-01 -1.74523201e-02 -5.50449669e-01 -8.34706843e-01 -1.74523201e-02 -5.53351760e-01 -8.32782686e-01 -1.74523201e-02 -5.56247413e-01 -8.30853939e-01 -1.74523201e-02 -5.59152544e-01 -8.28902662e-01 -1.74523201e-02 -5.62048614e-01 -8.26940775e-01 -1.74523201e-02 -5.64917147e-01 -8.24984729e-01 -1.74523201e-02 -5.67825794e-01 -8.22984815e-01 -1.74523201e-02 -5.70707023e-01 -8.20989668e-01 -1.74523201e-02 -5.73596835e-01 -8.18971992e-01 -1.74523201e-02 -5.76517284e-01 -8.16921234e-01 -1.74523201e-02 -5.79326749e-01 -8.14928353e-01 -1.74523201e-02 -5.82084954e-01 -8.12962651e-01 -1.74523201e-02 -5.84910572e-01 -8.10927451e-01 -1.74523201e-02 -5.87743104e-01 -8.08880627e-01 -1.74523201e-02 -5.90618610e-01 -8.06781888e-01 -1.74523201e-02 -5.93450069e-01 -8.04701447e-01 -1.74523201e-02 -5.96167207e-01 -8.02690923e-01 -1.74523201e-02 -5.98961294e-01 -8.00606430e-01 -1.74523201e-02 -6.01752937e-01 -7.98513532e-01 -1.74523201e-02 -6.04555786e-01 -7.96395361e-01 -1.74523201e-02 -6.07316613e-01 -7.94290543e-01 -1.74523201e-02 -6.10142708e-01 -7.92120218e-01 -1.74523201e-02 -6.12921059e-01 -7.89973259e-01 -1.74523201e-02 -6.15609229e-01 -7.87878633e-01 -1.74523201e-02 -6.18346632e-01 -7.85733998e-01 -1.74523201e-02 -6.21087193e-01 -7.83567846e-01 -1.74523201e-02 -6.23871565e-01 -7.81355202e-01 -1.74523201e-02 -6.26612544e-01 -7.79156208e-01 -1.74523201e-02 -6.29261553e-01 -7.77019978e-01 -1.74523201e-02 -6.31953955e-01 -7.74828613e-01 -1.74523201e-02 -6.34663045e-01 -7.72614539e-01 -1.74523201e-02 -6.37381792e-01 -7.70373523e-01 -1.74523201e-02 -6.40082479e-01 -7.68130422e-01 -1.74523201e-02 -6.42748594e-01 -7.65901923e-01 -1.74523201e-02 -6.45465970e-01 -7.63613760e-01 -1.74523201e-02 -6.48118615e-01 -7.61359930e-01 -1.74523201e-02 -6.50767386e-01 -7.59099483e-01 -1.74523201e-02 -6.53407395e-01 -7.56828368e-01 -1.74523201e-02 -6.55983210e-01 -7.54598439e-01 -1.74523201e-02 -6.58680439e-01 -7.52243221e-01 -1.74523201e-02 -6.61311686e-01 -7.49929726e-01 -1.74523201e-02 -6.63829684e-01 -7.47703910e-01 -1.74523201e-02 -6.66423261e-01 -7.45393455e-01 -1.74523201e-02 -6.69024169e-01 -7.43057847e-01 -1.74523201e-02 -6.71631098e-01 -7.40705252e-01 -1.74523201e-02 -6.74238145e-01 -7.38328993e-01 -1.74523201e-02 -6.76877320e-01 -7.35916674e-01 -1.74523201e-02 -6.79454565e-01 -7.33532667e-01 -1.74523201e-02 -6.81987226e-01 -7.31179297e-01 -1.74523201e-02 -6.84597552e-01 -7.28735447e-01 -1.74523201e-02 -6.87077880e-01 -7.26392984e-01 -1.74523201e-02 -6.89604700e-01 -7.24002898e-01 -1.74523201e-02 -6.92143679e-01 -7.21566856e-01 -1.74523201e-02 -6.94592595e-01 -7.19223619e-01 -1.74523201e-02 -6.97089672e-01 -7.16802299e-01 -1.74523201e-02 -6.99587524e-01 -7.14360893e-01 -1.74523201e-02 -7.02078223e-01 -7.11915851e-01 -1.74523201e-02 -7.04568744e-01 -7.09452629e-01 -1.74523201e-02 -7.07052767e-01 -7.06958652e-01 -1.74523201e-02 -7.09534347e-01 -7.04486787e-01 -1.74523201e-02 -7.11962461e-01 -7.02030897e-01 -1.74523201e-02 -7.14411259e-01 -6.99535787e-01 -1.74523201e-02 -7.16848969e-01 -6.97040439e-01 -1.74523201e-02 -7.19268024e-01 -6.94546461e-01 -1.74523201e-02 -7.21755624e-01 -6.91948116e-01 -1.74523201e-02 -7.24168062e-01 -6.89429224e-01 -1.74523201e-02 -7.26560414e-01 -6.86905384e-01 -1.74523201e-02 -7.28959501e-01 -6.84355736e-01 -1.74523201e-02 -7.31282413e-01 -6.81873500e-01 -1.74523201e-02 -7.33658612e-01 -6.79320097e-01 -1.74523201e-02 -7.36031115e-01 -6.76750481e-01 -1.74523201e-02 -7.38388240e-01 -6.74174607e-01 -1.74523201e-02 -7.40769804e-01 -6.71559036e-01 -1.74523201e-02 -7.43099868e-01 -6.68978095e-01 -1.74523201e-02 -7.45403886e-01 -6.66409850e-01 -1.74523201e-02 -7.47725964e-01 -6.63804650e-01 -1.74523201e-02 -7.50089228e-01 -6.61133587e-01 -1.74523201e-02 -7.52416015e-01 -6.58480883e-01 -1.74523201e-02 -7.54655719e-01 -6.55915499e-01 -1.74523201e-02 -7.56979644e-01 -6.53230190e-01 -1.74523201e-02 -7.59259045e-01 -6.50579751e-01 -1.74523201e-02 -7.61449099e-01 -6.48014605e-01 -1.74523201e-02 -7.63725042e-01 -6.45335972e-01 -1.74523201e-02 -7.65972316e-01 -6.42662525e-01 -1.74523201e-02 -7.68260837e-01 -6.39929771e-01 -1.74523201e-02 -7.70487905e-01 -6.37240350e-01 -1.74523201e-02 -7.72667825e-01 -6.34600043e-01 -1.74523201e-02 -7.74894714e-01 -6.31874204e-01 -1.74523201e-02 -7.77055264e-01 -6.29217565e-01 -1.74523201e-02 -7.79324412e-01 -6.26407802e-01 -1.74523201e-02 -7.81515419e-01 -6.23668671e-01 -1.74523201e-02 -7.83671975e-01 -6.20955348e-01 -1.74523201e-02 -7.85836518e-01 -6.18215680e-01 -1.74523201e-02 -7.87929416e-01 -6.15545750e-01 -1.74523201e-02 -7.90070713e-01 -6.12795889e-01 -1.74523201e-02 -7.92195976e-01 -6.10043705e-01 -1.74523201e-02 -7.94380784e-01 -6.07197404e-01 -1.74523201e-02 -7.96505988e-01 -6.04406774e-01 -1.74523201e-02 -7.98557401e-01 -6.01696312e-01 -1.74523201e-02 -8.00651431e-01 -5.98903716e-01 -1.74523201e-02 -8.02738070e-01 -5.96104443e-01 -1.74523201e-02 -8.04870665e-01 -5.93221664e-01 -1.74523201e-02 -8.06941152e-01 -5.90400696e-01 -1.74523201e-02 -8.08947265e-01 -5.87652564e-01 -1.74523201e-02 -8.11029673e-01 -5.84771037e-01 -1.74523201e-02 -8.13069284e-01 -5.81934571e-01 -1.74523201e-02 -8.15041900e-01 -5.79167128e-01 -1.74523201e-02 -8.17055047e-01 -5.76327264e-01 -1.74523201e-02 -8.19060206e-01 -5.73473096e-01 -1.74523201e-02 -8.21108818e-01 -5.70534110e-01 -1.74523201e-02 -8.23099554e-01 -5.67660034e-01 -1.74523201e-02 -8.25015128e-01 -5.64872384e-01 -1.74523201e-02 -8.26985240e-01 -5.61980784e-01 -1.74523201e-02 -8.28948796e-01 -5.59082985e-01 -1.74523201e-02 -8.30932856e-01 -5.56130648e-01 -1.74523201e-02 -8.32858980e-01 -5.53237736e-01 -1.74523201e-02 -8.34797144e-01 -5.50310969e-01 -1.74523201e-02 -8.36710513e-01 -5.47393501e-01 -1.74523201e-02 -8.38553011e-01 -5.44571400e-01 -1.74523201e-02 -8.40454936e-01 -5.41629076e-01 -1.74523201e-02 -8.42331529e-01 -5.38706720e-01 -1.74523201e-02 -8.44275594e-01 -5.35656631e-01 -1.74523201e-02 -8.46138775e-01 -5.32707453e-01 -1.74523201e-02 -8.47920716e-01 -5.29864311e-01 -1.74523201e-02 -8.49763572e-01 -5.26908755e-01 -1.74523201e-02 -8.51605117e-01 -5.23923635e-01 -1.74523201e-02 -8.53433311e-01 -5.20946205e-01 -1.74523201e-02 -8.55241060e-01 -5.17968774e-01 -1.74523201e-02 -8.57064486e-01 -5.14945388e-01 -1.74523201e-02 -8.58850181e-01 -5.11960447e-01 -1.74523201e-02 -8.60628068e-01 -5.08967936e-01 -1.74523201e-02 -8.62453640e-01 -5.05871356e-01 -1.74523201e-02 -8.64221215e-01 -5.02839386e-01 -1.74523201e-02 -8.65913570e-01 -4.99926269e-01 -1.74523201e-02 -8.67648602e-01 -4.96902883e-01 -1.74523201e-02 -8.69367123e-01 -4.93891716e-01 -1.74523201e-02 -8.71105611e-01 -4.90824491e-01 -1.74523201e-02 -8.72812629e-01 -4.87775862e-01 -1.74523201e-02 -8.74508142e-01 -4.84725177e-01 -1.74523201e-02 -8.76252294e-01 -4.81577456e-01 -1.74523201e-02 -8.77929032e-01 -4.78510410e-01 -1.74523201e-02 -8.79549026e-01 -4.75522369e-01 -1.74523201e-02 -8.81213486e-01 -4.72433478e-01 -1.74523201e-02 -8.82892668e-01 -4.69289064e-01 -1.74523201e-02 -8.84531379e-01 -4.66191053e-01 -1.74523201e-02 -8.86108577e-01 -4.63185817e-01 -1.74523201e-02 -8.87719631e-01 -4.60090011e-01 -1.74523201e-02 -8.89304757e-01 -4.57020491e-01 -1.74523201e-02 -8.90915334e-01 -4.53872681e-01 -1.74523201e-02 -8.92502487e-01 -4.50742722e-01 -1.74523201e-02 -8.94064069e-01 -4.47635621e-01 -1.74523201e-02 -8.95617008e-01 -4.44520742e-01 -1.74523201e-02 -8.97155821e-01 -4.41409320e-01 -1.74523201e-02 -8.98701966e-01 -4.38254029e-01 -1.74523201e-02 -9.00260806e-01 -4.35042888e-01 -1.74523201e-02 -9.01818871e-01 -4.31798488e-01 -1.74523201e-02 -9.03283596e-01 -4.28728729e-01 -1.74523201e-02 -9.04715180e-01 -4.25696105e-01 -1.74523201e-02 -9.06202734e-01 -4.22524005e-01 -1.74523201e-02 -9.07712638e-01 -4.19272929e-01 -1.74523201e-02 -9.09172237e-01 -4.16090578e-01 -1.74523201e-02 -9.10581112e-01 -4.13003385e-01 -1.74523201e-02 -9.12013412e-01 -4.09833163e-01 -1.74523201e-02 -9.13444400e-01 -4.06631798e-01 -1.74523201e-02 -9.14861500e-01 -4.03434426e-01 -1.74523201e-02 -9.16273117e-01 -4.00218248e-01 -1.74523201e-02 -9.17692184e-01 -3.96952689e-01 -1.74523201e-02 -9.19064760e-01 -3.93752992e-01 -1.74523201e-02 -9.20390606e-01 -3.90650541e-01 -1.74523201e-02 -9.21755314e-01 -3.87423158e-01 -1.74523201e-02 -9.23103213e-01 -3.84200305e-01 -1.74523201e-02 -9.24466014e-01 -3.80910218e-01 -1.74523201e-02 -9.25798178e-01 -3.77660304e-01 -1.74523201e-02 -9.27080691e-01 -3.74496192e-01 -1.74523201e-02 -9.28410709e-01 -3.71191233e-01 -1.74523201e-02 -9.29699361e-01 -3.67954075e-01 -1.74523201e-02 -9.30941701e-01 -3.64801556e-01 -1.74523201e-02 -9.32203591e-01 -3.61547053e-01 -1.74523201e-02 -9.33475912e-01 -3.58275145e-01 -1.74523201e-02 -9.34750736e-01 -3.54916930e-01 -1.74523201e-02 -9.35972333e-01 -3.51661265e-01 -1.74523201e-02 -9.37161803e-01 -3.48480135e-01 -1.74523201e-02 -9.38409448e-01 -3.45120072e-01 -1.74523201e-02 -9.39611673e-01 -3.41851830e-01 -1.74523201e-02 -9.40791547e-01 -3.38588148e-01 -1.74523201e-02 -9.41974163e-01 -3.35283488e-01 -1.74523201e-02 -9.43128526e-01 -3.32022011e-01 -1.74523201e-02 -9.44287598e-01 -3.28704268e-01 -1.74523201e-02 -9.45397317e-01 -3.25506777e-01 -1.74523201e-02 -9.46529150e-01 -3.22198510e-01 -1.74523201e-02 -9.47644591e-01 -3.18904102e-01 -1.74523201e-02 -9.48795676e-01 -3.15465659e-01 -1.74523201e-02 -9.49883282e-01 -3.12166542e-01 -1.74523201e-02 -9.50934112e-01 -3.08954597e-01 -1.74523201e-02 -9.52011764e-01 -3.05620551e-01 -1.74523201e-02 -9.53069508e-01 -3.02302271e-01 -1.74523201e-02 -9.54151988e-01 -2.98873007e-01 -1.74523201e-02 -9.55192685e-01 -2.95527458e-01 -1.74523201e-02 -9.56188083e-01 -2.92292923e-01 -1.74523201e-02 -9.57200527e-01 -2.88951457e-01 -1.74523201e-02 -9.58204031e-01 -2.85606205e-01 -1.74523201e-02 -9.59217548e-01 -2.82193691e-01 -1.74523201e-02 -9.60202515e-01 -2.78815806e-01 -1.74523201e-02 -9.61141169e-01 -2.75564939e-01 -1.74523201e-02 -9.62101817e-01 -2.72194684e-01 -1.74523201e-02 -9.63043928e-01 -2.68845916e-01 -1.74523201e-02 -9.63973641e-01 -2.65486270e-01 -1.74523201e-02 -9.64898169e-01 -2.62118250e-01 -1.74523201e-02 -9.65803504e-01 -2.58751392e-01 -1.74523201e-02 -9.66728687e-01 -2.55274475e-01 -1.74523201e-02 -9.67615604e-01 -2.51895249e-01 -1.74523201e-02 -9.68457282e-01 -2.48634428e-01 -1.74523201e-02 -9.69320297e-01 -2.45242596e-01 -1.74523201e-02 -9.70190167e-01 -2.41786450e-01 -1.74523201e-02 -9.71029818e-01 -2.38390863e-01 -1.74523201e-02 -9.71838295e-01 -2.35082194e-01 -1.74523201e-02 -9.72652018e-01 -2.31690079e-01 -1.74523201e-02 -9.73458052e-01 -2.28279069e-01 -1.74523201e-02 -9.74258244e-01 -2.24835232e-01 -1.74523201e-02 -9.75040972e-01 -2.21412882e-01 -1.74523201e-02 -9.75788116e-01 -2.18098909e-01 -1.74523201e-02 -9.76559758e-01 -2.14615479e-01 -1.74523201e-02 -9.77302432e-01 -2.11203709e-01 -1.74523201e-02 -9.78012383e-01 -2.07897574e-01 -1.74523201e-02 -9.78741050e-01 -2.04439625e-01 -1.74523201e-02 -9.79465723e-01 -2.00947642e-01 -1.74523201e-02 -9.80156124e-01 -1.97535262e-01 -1.74523201e-02 -9.80823457e-01 -1.94198370e-01 -1.74523201e-02 -9.81490672e-01 -1.90797150e-01 -1.74523201e-02 -9.82172370e-01 -1.87260777e-01 -1.74523201e-02 -9.82820630e-01 -1.83816329e-01 -1.74523201e-02 -9.83435750e-01 -1.80497020e-01 -1.74523201e-02 -9.84068453e-01 -1.77049756e-01 -1.74523201e-02 -9.84678328e-01 -1.73622787e-01 -1.74523201e-02 -9.85295236e-01 -1.70064777e-01 -1.74523201e-02 -9.85882163e-01 -1.66626632e-01 -1.74523201e-02 -9.86438394e-01 -1.63294777e-01 -1.74523201e-02 -9.87022281e-01 -1.59739748e-01 -1.74523201e-02 -9.87573266e-01 -1.56289652e-01 -1.74523201e-02 -9.88095224e-01 -1.52964041e-01 -1.74523201e-02 -9.88619030e-01 -1.49532035e-01 -1.74523201e-02 -9.89152670e-01 -1.45970181e-01 -1.74523201e-02 -9.89659011e-01 -1.42483845e-01 -1.74523201e-02 -9.90138292e-01 -1.39124259e-01 -1.74523201e-02 -9.90628541e-01 -1.35596707e-01 -1.74523201e-02 -9.91096556e-01 -1.32113516e-01 -1.74523201e-02 -9.91538167e-01 -1.28761321e-01 -1.74523201e-02 -9.91982043e-01 -1.25309512e-01 -1.74523201e-02 -9.92408276e-01 -1.21876121e-01 -1.74523201e-02 -9.92837191e-01 -1.18318737e-01 -1.74523201e-02 -9.93246198e-01 -1.14807606e-01 -1.74523238e-02 -9.93631303e-01 -1.11437239e-01 -1.74523275e-02 -9.94021595e-01 -1.07899353e-01 -1.74523257e-02 -9.94396269e-01 -1.04376711e-01 -1.74523313e-02 -9.94750261e-01 -1.00937754e-01 -1.74523313e-02 -9.95085955e-01 -9.75006968e-02 -1.74523313e-02 -9.95364189e-01 -9.45730805e-02 -1.74524020e-02 -9.95697796e-01 -9.09964517e-02 -1.74524076e-02 -9.96034920e-01 -8.72295126e-02 -1.74524058e-02 -9.96340454e-01 -8.36651996e-02 -1.74524058e-02 -9.96606946e-01 -8.04303437e-02 -1.74524076e-02 -9.96840298e-01 -7.74904042e-02 -1.74524076e-02 -9.97149765e-01 -7.34013245e-02 -1.74524058e-02 -9.97350872e-01 -7.06164092e-02 -1.74524039e-02 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. 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. 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. 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. 0. 0. -9.97628570e-01 6.78364336e-02 -1.16410842e-02 -9.97422636e-01 7.07961321e-02 -1.16410842e-02 -9.97195482e-01 7.39841834e-02 -1.16410404e-02 -9.96974766e-01 7.68993795e-02 -1.16410414e-02 -9.96712506e-01 8.02361220e-02 -1.16411271e-02 -9.96427000e-01 8.37188736e-02 -1.16411792e-02 -9.96113181e-01 8.73032212e-02 -1.16412146e-02 -9.95798588e-01 9.08373445e-02 -1.16412118e-02 -9.95484293e-01 9.42182168e-02 -1.16412090e-02 -9.95145559e-01 9.76704732e-02 -1.16412453e-02 -9.94791031e-01 1.01249442e-01 -1.16412314e-02 -9.94437158e-01 1.04686446e-01 -1.16412258e-02 -9.94058967e-01 1.08180597e-01 -1.16412388e-02 -9.93691146e-01 1.11569650e-01 -1.16412034e-02 -9.93299961e-01 1.14936434e-01 -1.16412286e-02 -9.92876172e-01 1.18526734e-01 -1.16412453e-02 -9.92446601e-01 1.22107364e-01 -1.16412239e-02 -9.92017269e-01 1.25556201e-01 -1.16412304e-02 -9.91571605e-01 1.29008934e-01 -1.16412276e-02 -9.91114855e-01 1.32486403e-01 -1.16412239e-02 -9.90664840e-01 1.35845587e-01 -1.16412016e-02 -9.90185261e-01 1.39248163e-01 -1.16412416e-02 -9.89676237e-01 1.42826959e-01 -1.16412239e-02 -9.89188790e-01 1.46187335e-01 -1.16412081e-02 -9.88666892e-01 1.49630174e-01 -1.16412491e-02 -9.88129973e-01 1.53182581e-01 -1.16412183e-02 -9.87587392e-01 1.56616256e-01 -1.16412276e-02 -9.87034857e-01 1.60071909e-01 -1.16412248e-02 -9.86476004e-01 1.63479924e-01 -1.16412276e-02 -9.85911667e-01 1.66850075e-01 -1.16412221e-02 -9.85332727e-01 1.70234293e-01 -1.16412267e-02 -9.84721184e-01 1.73738167e-01 -1.16412463e-02 -9.84093130e-01 1.77271381e-01 -1.16412323e-02 -9.83481348e-01 1.80624738e-01 -1.16412146e-02 -9.82845247e-01 1.84038445e-01 -1.16412453e-02 -9.82180476e-01 1.87570930e-01 -1.16412239e-02 -9.81529713e-01 1.90942973e-01 -1.16412230e-02 -9.80851710e-01 1.94391087e-01 -1.16412304e-02 -9.80185747e-01 1.97734952e-01 -1.16412239e-02 -9.79508519e-01 2.01058567e-01 -1.16412258e-02 -9.78778601e-01 2.04565108e-01 -1.16412519e-02 -9.78036940e-01 2.08096087e-01 -1.16412342e-02 -9.77303743e-01 2.11514786e-01 -1.16412276e-02 -9.76553500e-01 2.14947209e-01 -1.16412286e-02 -9.75803554e-01 2.18328878e-01 -1.16412267e-02 -9.75062907e-01 2.21624285e-01 -1.16412090e-02 -9.74273026e-01 2.25037634e-01 -1.16412565e-02 -9.73459959e-01 2.28556111e-01 -1.16412304e-02 -9.72680151e-01 2.31872916e-01 -1.16412016e-02 -9.71897781e-01 2.35113159e-01 -1.16412276e-02 -9.71042037e-01 2.38605782e-01 -1.16412453e-02 -9.70175803e-01 2.42115885e-01 -1.16412165e-02 -9.69324946e-01 2.45494038e-01 -1.16412230e-02 -9.68467116e-01 2.48866513e-01 -1.16412221e-02 -9.67618227e-01 2.52146631e-01 -1.16412174e-02 -9.66744721e-01 2.55478829e-01 -1.16412230e-02 -9.65826809e-01 2.58908153e-01 -1.16412453e-02 -9.64890420e-01 2.62396634e-01 -1.16412230e-02 -9.63987291e-01 2.65691251e-01 -1.16412127e-02 -9.63058949e-01 2.69024700e-01 -1.16412453e-02 -9.62081909e-01 2.72504717e-01 -1.16412332e-02 -9.61125076e-01 2.75857896e-01 -1.16412276e-02 -9.60151434e-01 2.79224247e-01 -1.16412304e-02 -9.59203005e-01 2.82483280e-01 -1.16412099e-02 -9.58240390e-01 2.85725504e-01 -1.16412230e-02 -9.57201838e-01 2.89163321e-01 -1.16412491e-02 -9.56157386e-01 2.92610794e-01 -1.16412342e-02 -9.55123007e-01 2.95972407e-01 -1.16412295e-02 -9.54123378e-01 2.99194604e-01 -1.16412025e-02 -9.53069866e-01 3.02507669e-01 -1.16412472e-02 -9.51995611e-01 3.05889457e-01 -1.16412230e-02 -9.50949013e-01 3.09124380e-01 -1.16412211e-02 -9.49849904e-01 3.12472045e-01 -1.16412481e-02 -9.48751211e-01 3.15811455e-01 -1.16412118e-02 -9.47681308e-01 3.19005907e-01 -1.16412230e-02 -9.46529865e-01 3.22391093e-01 -1.16412379e-02 -9.45365667e-01 3.25800180e-01 -1.16412276e-02 -9.44229007e-01 3.29074681e-01 -1.16412230e-02 -9.43077385e-01 3.32362533e-01 -1.16412239e-02 -9.41922903e-01 3.35632384e-01 -1.16412183e-02 -9.40776527e-01 3.38823318e-01 -1.16412202e-02 -9.39574599e-01 3.42134595e-01 -1.16412472e-02 -9.38330531e-01 3.45523298e-01 -1.16412202e-02 -9.37144935e-01 3.48718077e-01 -1.16412127e-02 -9.35923159e-01 3.51978362e-01 -1.16412435e-02 -9.34670746e-01 3.55307877e-01 -1.16412248e-02 -9.33431864e-01 3.58575851e-01 -1.16412267e-02 -9.32165146e-01 3.61833960e-01 -1.16412239e-02 -9.30923522e-01 3.65030795e-01 -1.16412062e-02 -9.29677308e-01 3.68184477e-01 -1.16412286e-02 -9.28387761e-01 3.71426016e-01 -1.16412230e-02 -9.27053750e-01 3.74733478e-01 -1.16412453e-02 -9.25712109e-01 3.78042430e-01 -1.16412304e-02 -9.24415886e-01 3.81204724e-01 -1.16412081e-02 -9.23074543e-01 3.84427905e-01 -1.16412491e-02 -9.21699643e-01 3.87726009e-01 -1.16412230e-02 -9.20345664e-01 3.90922457e-01 -1.16412248e-02 -9.18979406e-01 3.94121230e-01 -1.16412295e-02 -9.17616308e-01 3.97296220e-01 -1.16412165e-02 -9.16273892e-01 4.00380760e-01 -1.16412276e-02 -9.14839685e-01 4.03639853e-01 -1.16412370e-02 -9.13378000e-01 4.06944096e-01 -1.16412248e-02 -9.11942780e-01 4.10145700e-01 -1.16412276e-02 -9.10508335e-01 4.13320690e-01 -1.16412304e-02 -9.09053802e-01 4.16505069e-01 -1.16412248e-02 -9.07622457e-01 4.19621319e-01 -1.16412202e-02 -9.06157672e-01 4.22768712e-01 -1.16412360e-02 -9.04655337e-01 4.25976217e-01 -1.16412276e-02 -9.03205216e-01 4.29052353e-01 -1.16412099e-02 -9.01743829e-01 4.32107896e-01 -1.16412202e-02 -9.00188804e-01 4.35338348e-01 -1.16412397e-02 -8.98624837e-01 4.38563168e-01 -1.16412286e-02 -8.97096634e-01 4.41677392e-01 -1.16412211e-02 -8.95561874e-01 4.44779128e-01 -1.16412304e-02 -8.94026577e-01 4.47863460e-01 -1.16412127e-02 -8.92500281e-01 4.50896978e-01 -1.16412230e-02 -8.90886962e-01 4.54066545e-01 -1.16412435e-02 -8.89249027e-01 4.57273185e-01 -1.16412267e-02 -8.87681901e-01 4.60308611e-01 -1.16412109e-02 -8.86077166e-01 4.63383168e-01 -1.16412472e-02 -8.84416640e-01 4.66550678e-01 -1.16412286e-02 -8.82782459e-01 4.69635069e-01 -1.16412258e-02 -8.81140471e-01 4.72709417e-01 -1.16412258e-02 -8.79522324e-01 4.75714207e-01 -1.16412146e-02 -8.77903044e-01 4.78697658e-01 -1.16412295e-02 -8.76185477e-01 4.81825769e-01 -1.16412453e-02 -8.74441922e-01 4.84981596e-01 -1.16412276e-02 -8.72753859e-01 4.88015532e-01 -1.16412239e-02 -8.71052623e-01 4.91050571e-01 -1.16412276e-02 -8.69321167e-01 4.94106084e-01 -1.16412267e-02 -8.67632389e-01 4.97071534e-01 -1.16412202e-02 -8.65938067e-01 5.00018716e-01 -1.16412127e-02 -8.64170730e-01 5.03057897e-01 -1.16412342e-02 -8.62358332e-01 5.06163359e-01 -1.16412258e-02 -8.60626161e-01 5.09106398e-01 -1.16412090e-02 -8.58862698e-01 5.12067318e-01 -1.16412397e-02 -8.57018352e-01 5.15150785e-01 -1.16412267e-02 -8.55207801e-01 5.18149257e-01 -1.16412248e-02 -8.53401780e-01 5.21121681e-01 -1.16412286e-02 -8.51563990e-01 5.24115980e-01 -1.16412276e-02 -8.49784791e-01 5.27004778e-01 -1.16412118e-02 -8.47943544e-01 5.29949725e-01 -1.16412388e-02 -8.46046031e-01 5.32979608e-01 -1.16412267e-02 -8.44175458e-01 5.35936058e-01 -1.16412267e-02 -8.42287958e-01 5.38897395e-01 -1.16412276e-02 -8.40421677e-01 5.41798830e-01 -1.16412332e-02 -8.38532269e-01 5.44721544e-01 -1.16412267e-02 -8.36619675e-01 5.47653556e-01 -1.16412304e-02 -8.34701300e-01 5.50576925e-01 -1.16412276e-02 -8.32820058e-01 5.53419352e-01 -1.16412118e-02 -8.30946088e-01 5.56226432e-01 -1.16412276e-02 -8.28951359e-01 5.59194982e-01 -1.16412472e-02 -8.26945961e-01 5.62156975e-01 -1.16412258e-02 -8.24989319e-01 5.65025568e-01 -1.16412276e-02 -8.23008895e-01 5.67906439e-01 -1.16412304e-02 -8.21013927e-01 5.70782602e-01 -1.16412304e-02 -8.19062233e-01 5.73582292e-01 -1.16412211e-02 -8.17042291e-01 5.76454043e-01 -1.16412491e-02 -8.14973891e-01 5.79371333e-01 -1.16412332e-02 -8.13018978e-01 5.82123816e-01 -1.16412099e-02 -8.10970962e-01 5.84961295e-01 -1.16412453e-02 -8.08880925e-01 5.87853074e-01 -1.16412314e-02 -8.06830704e-01 5.90662956e-01 -1.16412276e-02 -8.04754674e-01 5.93486369e-01 -1.16412332e-02 -8.02683890e-01 5.96284509e-01 -1.16412276e-02 -8.00656140e-01 5.99009395e-01 -1.16412165e-02 -7.98535466e-01 6.01825118e-01 -1.16412630e-02 -7.96365976e-01 6.04699552e-01 -1.16412342e-02 -7.94265211e-01 6.07454836e-01 -1.16412286e-02 -7.92193949e-01 6.10160112e-01 -1.16412081e-02 -7.90076256e-01 6.12888336e-01 -1.16412388e-02 -7.87857592e-01 6.15742803e-01 -1.16412267e-02 -7.85762370e-01 6.18418574e-01 -1.16412165e-02 -7.83598006e-01 6.21150255e-01 -1.16412453e-02 -7.81420410e-01 6.23900592e-01 -1.16412025e-02 -7.79316247e-01 6.26520991e-01 -1.16412230e-02 -7.77061403e-01 6.29312694e-01 -1.16412416e-02 -7.74798989e-01 6.32097423e-01 -1.16412258e-02 -7.72582948e-01 6.34800792e-01 -1.16412342e-02 -7.70346344e-01 6.37518883e-01 -1.16412221e-02 -7.68123686e-01 6.40196025e-01 -1.16412118e-02 -7.65874565e-01 6.42883062e-01 -1.16412211e-02 -7.63633072e-01 6.45545542e-01 -1.16412211e-02 -7.61381686e-01 6.48194134e-01 -1.16412286e-02 -7.59166479e-01 6.50794685e-01 -1.16412081e-02 -7.56909370e-01 6.53411686e-01 -1.16412332e-02 -7.54552722e-01 6.56138539e-01 -1.16412090e-02 -7.52220273e-01 6.58805847e-01 -1.16412230e-02 -7.49913275e-01 6.61428988e-01 -1.16412276e-02 -7.47620165e-01 6.64025068e-01 -1.16412202e-02 -7.45309711e-01 6.66617870e-01 -1.16412202e-02 -7.43035555e-01 6.69156075e-01 -1.16411960e-02 -7.40703523e-01 6.71726465e-01 -1.16412453e-02 -7.38271952e-01 6.74399376e-01 -1.16412267e-02 -7.35991061e-01 6.76898122e-01 -1.16411988e-02 -7.33624101e-01 6.79449320e-01 -1.16412453e-02 -7.31206894e-01 6.82055295e-01 -1.16412239e-02 -7.28812575e-01 6.84613943e-01 -1.16412127e-02 -7.26390064e-01 6.87179446e-01 -1.16412286e-02 -7.24041760e-01 6.89661741e-01 -1.16412072e-02 -7.21716523e-01 6.92084074e-01 -1.16412211e-02 -7.19204903e-01 6.94703817e-01 -1.16412360e-02 -7.16696143e-01 6.97291553e-01 -1.16412304e-02 -7.14246750e-01 6.99798048e-01 -1.16412248e-02 -7.11807907e-01 7.02280521e-01 -1.16412239e-02 -7.09405780e-01 7.04711258e-01 -1.16412146e-02 -7.06952155e-01 7.07147539e-01 -1.16412435e-02 -7.04428792e-01 7.09681332e-01 -1.16412286e-02 -7.01951146e-01 7.12132990e-01 -1.16412258e-02 -6.99531794e-01 7.14510560e-01 -1.16412099e-02 -6.97025955e-01 7.16951191e-01 -1.16412472e-02 -6.94425404e-01 7.19474792e-01 -1.16412286e-02 -6.91929221e-01 7.21864283e-01 -1.16412230e-02 -6.89392030e-01 7.24298298e-01 -1.16412174e-02 -6.86863959e-01 7.26690888e-01 -1.16412183e-02 -6.84361279e-01 7.29047954e-01 -1.16412239e-02 -6.81825936e-01 7.31413722e-01 -1.16412379e-02 -6.79224670e-01 7.33834684e-01 -1.16412304e-02 -6.76641285e-01 7.36220419e-01 -1.16412351e-02 -6.74127460e-01 7.38521576e-01 -1.16412202e-02 -6.71553195e-01 7.40859330e-01 -1.16412491e-02 -6.68906629e-01 7.43252516e-01 -1.16412304e-02 -6.66357815e-01 7.45539904e-01 -1.16412174e-02 -6.63757086e-01 7.47851670e-01 -1.16412407e-02 -6.61105335e-01 7.50199974e-01 -1.16412314e-02 -6.58534467e-01 7.52461314e-01 -1.16412118e-02 -6.55911684e-01 7.54741549e-01 -1.16412472e-02 -6.53202891e-01 7.57091522e-01 -1.16412230e-02 -6.50549650e-01 7.59371281e-01 -1.16412258e-02 -6.47894740e-01 7.61637509e-01 -1.16412239e-02 -6.45235896e-01 7.63892114e-01 -1.16412276e-02 -6.42570972e-01 7.66132891e-01 -1.16412360e-02 -6.39878273e-01 7.68385351e-01 -1.16412286e-02 -6.37202621e-01 7.70606756e-01 -1.16412211e-02 -6.34579420e-01 7.72773266e-01 -1.16412072e-02 -6.31954670e-01 7.74913251e-01 -1.16412276e-02 -6.29173815e-01 7.77171135e-01 -1.16412509e-02 -6.26405537e-01 7.79410124e-01 -1.16412146e-02 -6.23666823e-01 7.81600177e-01 -1.16412304e-02 -6.20926321e-01 7.83779263e-01 -1.16412248e-02 -6.18184209e-01 7.85946190e-01 -1.16412248e-02 -6.15518689e-01 7.88037300e-01 -1.16412109e-02 -6.12761259e-01 7.90176511e-01 -1.16412472e-02 -6.09918535e-01 7.92376101e-01 -1.16412276e-02 -6.07211888e-01 7.94457138e-01 -1.16412062e-02 -6.04439557e-01 7.96560109e-01 -1.16412407e-02 -6.01591229e-01 7.98718095e-01 -1.16412230e-02 -5.98812997e-01 8.00801992e-01 -1.16412202e-02 -5.96004963e-01 8.02894235e-01 -1.16412239e-02 -5.93290567e-01 8.04906368e-01 -1.16412072e-02 -5.90512335e-01 8.06939781e-01 -1.16412286e-02 -5.87624490e-01 8.09046328e-01 -1.16412323e-02 -5.84792435e-01 8.11099827e-01 -1.16412062e-02 -5.81943691e-01 8.13141048e-01 -1.16412425e-02 -5.79125047e-01 8.15160215e-01 -1.16412006e-02 -5.76293230e-01 8.17156315e-01 -1.16412453e-02 -5.73330402e-01 8.19238365e-01 -1.16412230e-02 -5.70516825e-01 8.21204722e-01 -1.16412053e-02 -5.67674339e-01 8.23167920e-01 -1.16412276e-02 -5.64802587e-01 8.25147688e-01 -1.16412025e-02 -5.61925471e-01 8.27102721e-01 -1.16412314e-02 -5.59021711e-01 8.29074144e-01 -1.16412062e-02 -5.56164145e-01 8.30985546e-01 -1.16412314e-02 -5.53182602e-01 8.32975388e-01 -1.16412221e-02 -5.50222576e-01 8.34935904e-01 -1.16412127e-02 -5.47385931e-01 8.36801171e-01 -1.16412016e-02 -5.44566572e-01 8.38634670e-01 -1.16412258e-02 -5.41545928e-01 8.40585113e-01 -1.16412360e-02 -5.38605988e-01 8.42479765e-01 -1.16412016e-02 -5.35677969e-01 8.44336033e-01 -1.16412370e-02 -5.32724857e-01 8.46213877e-01 -1.16411978e-02 -5.29778779e-01 8.48051727e-01 -1.16412314e-02 -5.26718855e-01 8.49959433e-01 -1.16412211e-02 -5.23727477e-01 8.51802826e-01 -1.16412230e-02 -5.20847976e-01 8.53572607e-01 -1.16412081e-02 -5.17923892e-01 8.55343163e-01 -1.16412342e-02 -5.14848828e-01 8.57199550e-01 -1.16412276e-02 -5.11848211e-01 8.58999789e-01 -1.16412025e-02 -5.08872092e-01 8.60759199e-01 -1.16412342e-02 -5.05867004e-01 8.62535715e-01 -1.16412062e-02 -5.02874494e-01 8.64278197e-01 -1.16412323e-02 -4.99779671e-01 8.66075456e-01 -1.16412193e-02 -4.96821642e-01 8.67777765e-01 -1.16412034e-02 -4.93792415e-01 8.69496465e-01 -1.16412342e-02 -4.90744501e-01 8.71231139e-01 -1.16411997e-02 -4.87691641e-01 8.72935295e-01 -1.16412248e-02 -4.84604537e-01 8.74653518e-01 -1.16412118e-02 -4.81563538e-01 8.76330793e-01 -1.16412276e-02 -4.78440553e-01 8.78045738e-01 -1.16412183e-02 -4.75323021e-01 8.79731178e-01 -1.16412239e-02 -4.72367823e-01 8.81326318e-01 -1.16412062e-02 -4.69384849e-01 8.82917285e-01 -1.16412183e-02 -4.66202706e-01 8.84597003e-01 -1.16412397e-02 -4.63115513e-01 8.86226952e-01 -1.16411988e-02 -4.60036635e-01 8.87818813e-01 -1.16412370e-02 -4.56858903e-01 8.89464080e-01 -1.16412127e-02 -4.53772396e-01 8.91038597e-01 -1.16412248e-02 -4.50601667e-01 8.92647624e-01 -1.16412221e-02 -4.47481453e-01 8.94214749e-01 -1.16412276e-02 -4.44474280e-01 8.95717978e-01 -1.16412109e-02 -4.41419244e-01 8.97224009e-01 -1.16412230e-02 -4.38214451e-01 8.98794055e-01 -1.16412202e-02 -4.35065269e-01 9.00328636e-01 -1.16412025e-02 -4.31881964e-01 9.01848793e-01 -1.16412360e-02 -4.28731769e-01 9.03360844e-01 -1.16411997e-02 -4.25624162e-01 9.04820502e-01 -1.16412286e-02 -4.22442228e-01 9.06318486e-01 -1.16412081e-02 -4.19297040e-01 9.07772720e-01 -1.16412239e-02 -4.16051030e-01 9.09267068e-01 -1.16412109e-02 -4.12869602e-01 9.10715163e-01 -1.16412174e-02 -4.09689128e-01 9.12152529e-01 -1.16412202e-02 -4.06548589e-01 9.13559854e-01 -1.16411988e-02 -4.03381705e-01 9.14956272e-01 -1.16412183e-02 -4.00142133e-01 9.16380525e-01 -1.16412202e-02 -3.96901608e-01 9.17786479e-01 -1.16412211e-02 -3.93764675e-01 9.19134974e-01 -1.16412081e-02 -3.90633494e-01 9.20471728e-01 -1.16412165e-02 -3.87357175e-01 9.21854496e-01 -1.16412267e-02 -3.84149730e-01 9.23199296e-01 -1.16412053e-02 -3.80944520e-01 9.24520969e-01 -1.16412258e-02 -3.77665758e-01 9.25871789e-01 -1.16412034e-02 -3.74443412e-01 9.27172720e-01 -1.16412342e-02 -3.71126115e-01 9.28508580e-01 -1.16412202e-02 -3.67871910e-01 9.29803669e-01 -1.16412230e-02 -3.64740252e-01 9.31038737e-01 -1.16412016e-02 -3.61496806e-01 9.32292163e-01 -1.16412397e-02 -3.58176559e-01 9.33586240e-01 -1.16412211e-02 -3.54970008e-01 9.34801161e-01 -1.16412062e-02 -3.51707637e-01 9.36025918e-01 -1.16412332e-02 -3.48421276e-01 9.37258840e-01 -1.16411988e-02 -3.45203668e-01 9.38448131e-01 -1.16412211e-02 -3.41868162e-01 9.39684868e-01 -1.16411904e-02 -3.38570535e-01 9.40865755e-01 -1.16412211e-02 -3.35229397e-01 9.42067444e-01 -1.16412109e-02 -3.31940502e-01 9.43230689e-01 -1.16412081e-02 -3.28648239e-01 9.44379210e-01 -1.16412193e-02 -3.25415492e-01 9.45504427e-01 -1.16412006e-02 -3.22131038e-01 9.46620405e-01 -1.16412276e-02 -3.18755537e-01 9.47767317e-01 -1.16412174e-02 -3.15424263e-01 9.48880792e-01 -1.16412044e-02 -3.12184781e-01 9.49953973e-01 -1.16411988e-02 -3.08972001e-01 9.50999916e-01 -1.16412211e-02 -3.05578887e-01 9.52092707e-01 -1.16412379e-02 -3.02234203e-01 9.53165174e-01 -1.16412025e-02 -2.99025804e-01 9.54175472e-01 -1.16412090e-02 -2.95685142e-01 9.55215991e-01 -1.16412081e-02 -2.92260289e-01 9.56264555e-01 -1.16412332e-02 -2.88907915e-01 9.57287848e-01 -1.16412062e-02 -2.85588652e-01 9.58277285e-01 -1.16412314e-02 -2.82245666e-01 9.59272861e-01 -1.16412127e-02 -2.78897434e-01 9.60246265e-01 -1.16412379e-02 -2.75485873e-01 9.61233914e-01 -1.16412211e-02 -2.72210240e-01 9.62168217e-01 -1.16412099e-02 -2.68849045e-01 9.63108718e-01 -1.16412360e-02 -2.65433669e-01 9.64058161e-01 -1.16412202e-02 -2.62069672e-01 9.64978278e-01 -1.16412332e-02 -2.58731484e-01 9.65880871e-01 -1.16412072e-02 -2.55360723e-01 9.66773629e-01 -1.16412332e-02 -2.51908660e-01 9.67681408e-01 -1.16412202e-02 -2.48514190e-01 9.68557477e-01 -1.16412211e-02 -2.45130330e-01 9.69418764e-01 -1.16412202e-02 -2.41827399e-01 9.70251560e-01 -1.16412016e-02 -2.38452882e-01 9.71082389e-01 -1.16412276e-02 -2.34979630e-01 9.71932411e-01 -1.16412202e-02 -2.31576845e-01 9.72747445e-01 -1.16412230e-02 -2.28262112e-01 9.73530948e-01 -1.16412099e-02 -2.24933907e-01 9.74303722e-01 -1.16412239e-02 -2.21483842e-01 9.75090861e-01 -1.16412360e-02 -2.18075573e-01 9.75864291e-01 -1.16412099e-02 -2.14725867e-01 9.76602197e-01 -1.16412248e-02 -2.11323619e-01 9.77344692e-01 -1.16412276e-02 -2.07864299e-01 9.78085160e-01 -1.16412360e-02 -2.04420790e-01 9.78813827e-01 -1.16412183e-02 -2.01019958e-01 9.79515553e-01 -1.16412342e-02 -1.97603479e-01 9.80213344e-01 -1.16412081e-02 -1.94164962e-01 9.80893970e-01 -1.16412453e-02 -1.90637901e-01 9.81588721e-01 -1.16412267e-02 -1.87295914e-01 9.82236862e-01 -1.16412034e-02 -1.83868945e-01 9.82876956e-01 -1.16412453e-02 -1.80457070e-01 9.83515322e-01 -1.16411960e-02 -1.77011341e-01 9.84140813e-01 -1.16412342e-02 -1.73590168e-01 9.84755278e-01 -1.16412062e-02 -1.70261294e-01 9.85326350e-01 -1.16412286e-02 -1.66695029e-01 9.85935390e-01 -1.16412519e-02 -1.63146272e-01 9.86530185e-01 -1.16412239e-02 -1.59686908e-01 9.87096310e-01 -1.16412276e-02 -1.56360537e-01 9.87633348e-01 -1.16412062e-02 -1.53038904e-01 9.88149047e-01 -1.16412267e-02 -1.49473608e-01 9.88690436e-01 -1.16412453e-02 -1.45894498e-01 9.89229143e-01 -1.16412239e-02 -1.42432138e-01 9.89732623e-01 -1.16412276e-02 -1.39081359e-01 9.90213335e-01 -1.16412118e-02 -1.35745779e-01 9.90674317e-01 -1.16412286e-02 -1.32261053e-01 9.91143823e-01 -1.16412276e-02 -1.28801748e-01 9.91598666e-01 -1.16412286e-02 -1.25247180e-01 9.92052734e-01 -1.16412435e-02 -1.21688083e-01 9.92497027e-01 -1.16412276e-02 -1.18317232e-01 9.92906630e-01 -1.16412081e-02 -1.14848152e-01 9.93306875e-01 -1.16412472e-02 -1.11376591e-01 9.93710995e-01 -1.16412118e-02 -1.08008578e-01 9.94079351e-01 -1.16412248e-02 -1.04431912e-01 9.94458139e-01 -1.16412453e-02 -1.00866005e-01 9.94828105e-01 -1.16412276e-02 -9.73784253e-02 9.95177031e-01 -1.16412267e-02 -9.39214826e-02 9.95510876e-01 -1.16412239e-02 -9.04333889e-02 9.95832205e-01 -1.16412323e-02 -8.70625749e-02 9.96137500e-01 -1.16412072e-02 -8.36762115e-02 9.96421278e-01 -1.16412314e-02 -8.00902098e-02 9.96713758e-01 -1.16412453e-02 -7.65148923e-02 9.96998191e-01 -1.16412267e-02 -7.30372444e-02 9.97259498e-01 -1.16412304e-02 -6.96694404e-02 9.97502446e-01 -1.16412090e-02 -6.62833452e-02 9.97730911e-01 -1.16412332e-02 -6.27545863e-02 9.97956991e-01 -1.16412323e-02 -5.92066981e-02 9.98171747e-01 -1.16412453e-02 -5.56161925e-02 9.98381555e-01 -1.16412342e-02 -5.21193035e-02 9.98568296e-01 -1.16412351e-02 -4.87289988e-02 9.98745143e-01 -1.16412109e-02 -4.52607535e-02 9.98901010e-01 -1.16412453e-02 -4.17696312e-02 9.99062598e-01 -1.16412044e-02 -3.83186787e-02 9.99190688e-01 -1.16412528e-02 -3.46918106e-02 9.99326587e-01 -1.16412286e-02 -3.13216001e-02 9.99441028e-01 -1.16412165e-02 -2.78515629e-02 9.99538720e-01 -1.16412453e-02 -2.43433509e-02 9.99639273e-01 -1.16412146e-02 -2.08380055e-02 9.99703825e-01 -1.16412593e-02 -1.72346234e-02 9.99784589e-01 -1.16412342e-02 -1.37373675e-02 9.99831438e-01 -1.16412276e-02 -1.02505162e-02 9.99876201e-01 -1.16412304e-02 -6.84337784e-03 9.99914825e-01 -1.16412044e-02 -3.37112788e-03 9.99925673e-01 -1.16412565e-02 1.26064158e-04 9.99933243e-01 -1.16412109e-02 3.49960243e-03 9.99929011e-01 -1.16412267e-02 7.10876426e-03 9.99908566e-01 -1.16412379e-02 1.06873512e-02 9.99871433e-01 -1.16412258e-02 1.41894501e-02 9.99825180e-01 -1.16412267e-02 1.76782515e-02 9.99776721e-01 -1.16412314e-02 2.10669897e-02 9.99711156e-01 -1.16412090e-02 2.44656838e-02 9.99630392e-01 -1.16412332e-02 2.80535463e-02 9.99533236e-01 -1.16412500e-02 3.16568017e-02 9.99428630e-01 -1.16412304e-02 3.50424536e-02 9.99319613e-01 -1.16412127e-02 3.83986272e-02 9.99193311e-01 -1.16412267e-02 4.19882052e-02 9.99044001e-01 -1.16412519e-02 4.55138534e-02 9.98895705e-01 -1.16412109e-02 4.89769988e-02 9.98728752e-01 -1.16412453e-02 5.25613278e-02 9.98544991e-01 -1.16412276e-02 5.60077094e-02 9.98361588e-01 -1.16412221e-02 5.95076643e-02 9.98156786e-01 -1.16412295e-02 6.30048215e-02 9.97940719e-01 -1.16412276e-02 6.64766580e-02 9.97716427e-01 -1.16412304e-02 6.98992759e-02 9.97484386e-01 -1.16412165e-02 7.33914524e-02 9.97230351e-01 -1.16412435e-02 7.69413710e-02 9.96963561e-01 -1.16412286e-02 8.04186016e-02 9.96691465e-01 -1.16412276e-02 8.39049667e-02 9.96401906e-01 -1.16412314e-02 8.73433128e-02 9.96108353e-01 -1.16412221e-02 9.07539949e-02 9.95804250e-01 -1.16412202e-02 9.42127705e-02 9.95480835e-01 -1.16412360e-02 9.78080407e-02 9.95136678e-01 -1.16412183e-02 1.01278871e-01 9.94789779e-01 -1.16412230e-02 1.04654223e-01 9.94440973e-01 -1.16412211e-02 1.08043671e-01 9.94074345e-01 -1.16412304e-02 1.11524038e-01 9.93689775e-01 -1.16412453e-02 1.15088671e-01 9.93282616e-01 -1.16412323e-02 1.18633464e-01 9.92866099e-01 -1.16412276e-02 1.22104570e-01 9.92445052e-01 -1.16412314e-02 1.25463903e-01 9.92030263e-01 -1.16412211e-02 1.28920943e-01 9.91578937e-01 -1.16412546e-02 1.32400826e-01 9.91128802e-01 -1.16412127e-02 1.35819480e-01 9.90660608e-01 -1.16412509e-02 1.39404565e-01 9.90164459e-01 -1.16412332e-02 1.42780736e-01 9.89686012e-01 -1.16412174e-02 1.46208704e-01 9.89177644e-01 -1.16412491e-02 1.49784982e-01 9.88646924e-01 -1.16412286e-02 1.53232381e-01 9.88120854e-01 -1.16412239e-02 1.56575501e-01 9.87597585e-01 -1.16412081e-02 1.60004333e-01 9.87041652e-01 -1.16412491e-02 1.63551211e-01 9.86463130e-01 -1.16412323e-02 1.66909039e-01 9.85903025e-01 -1.16412183e-02 1.70310676e-01 9.85316992e-01 -1.16412444e-02 1.73787355e-01 9.84717846e-01 -1.16412174e-02 1.77141085e-01 9.84116733e-01 -1.16412276e-02 1.80633321e-01 9.83477056e-01 -1.16412314e-02 1.84151322e-01 9.82825160e-01 -1.16412323e-02 1.87605232e-01 9.82172608e-01 -1.16412248e-02 1.91044152e-01 9.81509149e-01 -1.16412286e-02 1.94398537e-01 9.80854690e-01 -1.16412202e-02 1.97707951e-01 9.80187178e-01 -1.16412360e-02 2.01128110e-01 9.79490936e-01 -1.16412323e-02 2.04632401e-01 9.78763402e-01 -1.16412630e-02 2.08137780e-01 9.78027403e-01 -1.16412332e-02 2.11549714e-01 9.77297962e-01 -1.16412258e-02 2.14934677e-01 9.76553917e-01 -1.16412407e-02 2.18283162e-01 9.75815058e-01 -1.16412221e-02 2.21690729e-01 9.75041270e-01 -1.16412425e-02 2.25167990e-01 9.74248052e-01 -1.16412342e-02 2.28559092e-01 9.73460078e-01 -1.16412230e-02 2.31961191e-01 9.72654462e-01 -1.16412332e-02 2.35269919e-01 9.71860826e-01 -1.16412211e-02 2.38673106e-01 9.71025944e-01 -1.16412453e-02 2.42065221e-01 9.70189393e-01 -1.16412202e-02 2.45429337e-01 9.69336748e-01 -1.16412491e-02 2.48909622e-01 9.68454421e-01 -1.16412314e-02 2.52274483e-01 9.67581213e-01 -1.16412323e-02 2.55645782e-01 9.66697395e-01 -1.16412332e-02 2.59037733e-01 9.65793848e-01 -1.16412342e-02 2.62330145e-01 9.64909196e-01 -1.16412211e-02 2.65670329e-01 9.63986874e-01 -1.16412472e-02 2.69139439e-01 9.63029683e-01 -1.16412239e-02 2.72501677e-01 9.62082803e-01 -1.16412342e-02 2.75821030e-01 9.61136639e-01 -1.16412276e-02 2.79131919e-01 9.60179627e-01 -1.16412286e-02 2.82539070e-01 9.59181011e-01 -1.16412351e-02 2.85830647e-01 9.58210647e-01 -1.16412183e-02 2.89145827e-01 9.57208037e-01 -1.16412453e-02 2.92588353e-01 9.56166267e-01 -1.16412258e-02 2.95840591e-01 9.55166101e-01 -1.16412202e-02 2.99150735e-01 9.54128981e-01 -1.16412528e-02 3.02507669e-01 9.53074753e-01 -1.16412155e-02 3.05789232e-01 9.52022314e-01 -1.16412491e-02 3.09207708e-01 9.50918019e-01 -1.16412407e-02 3.12579602e-01 9.49815512e-01 -1.16412351e-02 3.15884471e-01 9.48722064e-01 -1.16412379e-02 3.19114387e-01 9.47645128e-01 -1.16412202e-02 3.22395176e-01 9.46526051e-01 -1.16412602e-02 3.25788915e-01 9.45371091e-01 -1.16412248e-02 3.29004139e-01 9.44254935e-01 -1.16412211e-02 3.32281262e-01 9.43101168e-01 -1.16412528e-02 3.35690677e-01 9.41900253e-01 -1.16412276e-02 3.38945478e-01 9.40730751e-01 -1.16412267e-02 3.42195302e-01 9.39553440e-01 -1.16412323e-02 3.45400989e-01 9.38375413e-01 -1.16412230e-02 3.48650187e-01 9.37165082e-01 -1.16412491e-02 3.51963371e-01 9.35929894e-01 -1.16412258e-02 3.55251104e-01 9.34689105e-01 -1.16412630e-02 3.58594358e-01 9.33422267e-01 -1.16412360e-02 3.61782461e-01 9.32186186e-01 -1.16412109e-02 3.64999354e-01 9.30928886e-01 -1.16412528e-02 3.68249655e-01 9.29654837e-01 -1.16412072e-02 3.71473372e-01 9.28365350e-01 -1.16412416e-02 3.74815166e-01 9.27021325e-01 -1.16412360e-02 3.78071249e-01 9.25700128e-01 -1.16412323e-02 3.81291837e-01 9.24374819e-01 -1.16412379e-02 3.84437621e-01 9.23075676e-01 -1.16412230e-02 3.87624919e-01 9.21735704e-01 -1.16412528e-02 3.90925765e-01 9.20343041e-01 -1.16412323e-02 3.94158810e-01 9.18963850e-01 -1.16412267e-02 3.97362500e-01 9.17582810e-01 -1.16412379e-02 4.00492877e-01 9.16227341e-01 -1.16412211e-02 4.03672129e-01 9.14823830e-01 -1.16412491e-02 4.06881183e-01 9.13406849e-01 -1.16412202e-02 4.09967333e-01 9.12023842e-01 -1.16412342e-02 4.13215071e-01 9.10552382e-01 -1.16412565e-02 4.16424423e-01 9.09092605e-01 -1.16412202e-02 4.19543892e-01 9.07651961e-01 -1.16412528e-02 4.22720999e-01 9.06186759e-01 -1.16412062e-02 4.25813854e-01 9.04735565e-01 -1.16412221e-02 4.28982288e-01 9.03234005e-01 -1.16412248e-02 4.32206720e-01 9.01693821e-01 -1.16412342e-02 4.35429454e-01 9.00147736e-01 -1.16412267e-02 4.38483119e-01 8.98666561e-01 -1.16412202e-02 4.41551000e-01 8.97155881e-01 -1.16412379e-02 4.44683105e-01 8.95609379e-01 -1.16412314e-02 4.47777182e-01 8.94066036e-01 -1.16412342e-02 4.50979412e-01 8.92452002e-01 -1.16412630e-02 4.54150230e-01 8.90845776e-01 -1.16412388e-02 4.57184345e-01 8.89295399e-01 -1.16412230e-02 4.60302621e-01 8.87680829e-01 -1.16412342e-02 4.63387907e-01 8.86083364e-01 -1.16412118e-02 4.66459394e-01 8.84460688e-01 -1.16412491e-02 4.69550580e-01 8.82827520e-01 -1.16412221e-02 4.72614527e-01 8.81187499e-01 -1.16412491e-02 4.75759298e-01 8.79493892e-01 -1.16412332e-02 4.78760570e-01 8.77870440e-01 -1.16412211e-02 4.81801122e-01 8.76197159e-01 -1.16412528e-02 4.84862030e-01 8.74510825e-01 -1.16412202e-02 4.87830073e-01 8.72857690e-01 -1.16412314e-02 4.90957052e-01 8.71102929e-01 -1.16412379e-02 4.94070321e-01 8.69338036e-01 -1.16412323e-02 4.97095287e-01 8.67615402e-01 -1.16412286e-02 5.00055552e-01 8.65916491e-01 -1.16412211e-02 5.03011763e-01 8.64198923e-01 -1.16412314e-02 5.06011128e-01 8.62444818e-01 -1.16412360e-02 5.09085476e-01 8.60629737e-01 -1.16412537e-02 5.12151122e-01 8.58812213e-01 -1.16412370e-02 5.15154719e-01 8.57012749e-01 -1.16412388e-02 5.18081665e-01 8.55249286e-01 -1.16412248e-02 5.21030426e-01 8.53455484e-01 -1.16412453e-02 5.24027169e-01 8.51619840e-01 -1.16412221e-02 5.26979387e-01 8.49792659e-01 -1.16412574e-02 5.30028999e-01 8.47894013e-01 -1.16412379e-02 5.32919645e-01 8.46084952e-01 -1.16412230e-02 5.35837948e-01 8.44232619e-01 -1.16412630e-02 5.38808763e-01 8.42347860e-01 -1.16412127e-02 5.41722238e-01 8.40470374e-01 -1.16412472e-02 5.44674337e-01 8.38564754e-01 -1.16412239e-02 5.47599196e-01 8.36650908e-01 -1.16412546e-02 5.50575018e-01 8.34702194e-01 -1.16412286e-02 5.53450465e-01 8.32797587e-01 -1.16412239e-02 5.56320965e-01 8.30879629e-01 -1.16412472e-02 5.59206784e-01 8.28951895e-01 -1.16412016e-02 5.61996877e-01 8.27058852e-01 -1.16412053e-02 5.64949691e-01 8.25050354e-01 -1.16411913e-02 5.67860723e-01 8.23050380e-01 -1.16411205e-02 5.70716798e-01 8.21069777e-01 -1.16411448e-02 5.73599815e-01 8.19058239e-01 -1.16410702e-02 5.76350033e-01 8.17127407e-01 -1.16410777e-02 5.79215705e-01 8.15097928e-01 -1.16410423e-02 5.82019329e-01 8.13096762e-01 -1.16410367e-02 5.84890783e-01 8.11033726e-01 -1.16410386e-02 5.87786376e-01 8.08935344e-01 -1.16410470e-02 5.90521455e-01 8.06936920e-01 -1.16410619e-02 5.93257844e-01 8.04926574e-01 -1.16410851e-02 5.95943093e-01 8.02941203e-01 -1.16410851e-02 5.98591149e-01 8.00969303e-01 -1.16410833e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 7.26884782e-01 6.86660349e-01 -1.16410833e-02 7.29261756e-01 6.84134066e-01 -1.16410842e-02 7.31663942e-01 6.81570351e-01 -1.16410414e-02 7.33902872e-01 6.79161787e-01 -1.16410367e-02 7.36155629e-01 6.76721215e-01 -1.16411336e-02 7.38516927e-01 6.74143255e-01 -1.16411038e-02 7.40852714e-01 6.71575308e-01 -1.16411839e-02 7.43199587e-01 6.68977737e-01 -1.16411680e-02 7.45449901e-01 6.66460991e-01 -1.16412081e-02 7.47823954e-01 6.63791537e-01 -1.16412314e-02 7.50145137e-01 6.61173940e-01 -1.16412062e-02 7.52441466e-01 6.58547699e-01 -1.16412444e-02 7.54727364e-01 6.55939817e-01 -1.16412081e-02 7.56943822e-01 6.53374851e-01 -1.16412221e-02 7.59230793e-01 6.50716543e-01 -1.16412221e-02 7.61490762e-01 6.48067117e-01 -1.16412258e-02 7.63815463e-01 6.45324647e-01 -1.16412388e-02 7.66122282e-01 6.42587185e-01 -1.16412267e-02 7.68303335e-01 6.39984250e-01 -1.16412062e-02 7.70468414e-01 6.37368798e-01 -1.16412258e-02 7.72697628e-01 6.34665430e-01 -1.16412258e-02 7.74955869e-01 6.31897211e-01 -1.16412491e-02 7.77223229e-01 6.29115224e-01 -1.16412258e-02 7.79348671e-01 6.26483619e-01 -1.16412034e-02 7.81450033e-01 6.23859763e-01 -1.16412211e-02 7.83641100e-01 6.21098042e-01 -1.16412276e-02 7.85869420e-01 6.18275940e-01 -1.16412491e-02 7.88095236e-01 6.15439355e-01 -1.16412276e-02 7.90220678e-01 6.12706661e-01 -1.16412332e-02 7.92358696e-01 6.09938979e-01 -1.16412314e-02 7.94439673e-01 6.07234538e-01 -1.16412146e-02 7.96534777e-01 6.04473352e-01 -1.16412472e-02 7.98640192e-01 6.01696730e-01 -1.16412202e-02 8.00673068e-01 5.98982871e-01 -1.16412276e-02 8.02824020e-01 5.96092939e-01 -1.16412472e-02 8.04902017e-01 5.93292296e-01 -1.16412165e-02 8.06948960e-01 5.90495229e-01 -1.16412472e-02 8.09060454e-01 5.87605238e-01 -1.16412323e-02 8.11069667e-01 5.84831774e-01 -1.16412127e-02 8.13038588e-01 5.82091570e-01 -1.16412276e-02 8.15125883e-01 5.79158127e-01 -1.16412528e-02 8.17204118e-01 5.76226532e-01 -1.16412407e-02 8.19199443e-01 5.73382437e-01 -1.16412360e-02 8.21144283e-01 5.70600748e-01 -1.16412127e-02 8.23086798e-01 5.67791760e-01 -1.16412332e-02 8.25060129e-01 5.64917684e-01 -1.16412360e-02 8.27071607e-01 5.61965823e-01 -1.16412491e-02 8.29087973e-01 5.58990061e-01 -1.16412332e-02 8.30991566e-01 5.56162894e-01 -1.16412155e-02 8.32907379e-01 5.53277493e-01 -1.16412491e-02 8.34834754e-01 5.50374448e-01 -1.16412221e-02 8.36760581e-01 5.47432125e-01 -1.16412491e-02 8.38673711e-01 5.44509530e-01 -1.16412193e-02 8.40506911e-01 5.41666985e-01 -1.16412360e-02 8.42440844e-01 5.38648963e-01 -1.16412509e-02 8.44314396e-01 5.35720348e-01 -1.16412165e-02 8.46183062e-01 5.32754719e-01 -1.16412630e-02 8.48095834e-01 5.29713035e-01 -1.16412230e-02 8.49877536e-01 5.26850581e-01 -1.16412221e-02 8.51718545e-01 5.23858607e-01 -1.16412491e-02 8.53549123e-01 5.20885289e-01 -1.16412127e-02 8.55355442e-01 5.17896771e-01 -1.16412528e-02 8.57169986e-01 5.14901698e-01 -1.16412165e-02 8.58896792e-01 5.12009144e-01 -1.16412304e-02 8.60683680e-01 5.08999467e-01 -1.16412370e-02 8.62457454e-01 5.05991876e-01 -1.16412295e-02 8.64273310e-01 5.02877772e-01 -1.16412491e-02 8.66069615e-01 4.99783039e-01 -1.16412276e-02 8.67755651e-01 4.96857464e-01 -1.16412099e-02 8.69429529e-01 4.93911237e-01 -1.16412314e-02 8.71158361e-01 4.90863442e-01 -1.16412323e-02 8.72912526e-01 4.87723470e-01 -1.16412574e-02 8.74679446e-01 4.84553903e-01 -1.16412267e-02 8.76317680e-01 4.81594861e-01 -1.16412118e-02 8.77937138e-01 4.78629947e-01 -1.16412314e-02 8.79600763e-01 4.75565612e-01 -1.16412248e-02 8.81297231e-01 4.72408086e-01 -1.16412491e-02 8.82956505e-01 4.69311833e-01 -1.16412146e-02 8.84577036e-01 4.66234148e-01 -1.16412574e-02 8.86255205e-01 4.63048279e-01 -1.16412248e-02 8.87806416e-01 4.60066378e-01 -1.16412165e-02 8.89397085e-01 4.56977069e-01 -1.16412472e-02 8.91007543e-01 4.53841090e-01 -1.16412127e-02 8.92525136e-01 4.50838864e-01 -1.16412360e-02 8.94158304e-01 4.47584599e-01 -1.16412528e-02 8.95723522e-01 4.44456279e-01 -1.16412211e-02 8.97251964e-01 4.41355377e-01 -1.16412379e-02 8.98835480e-01 4.38128293e-01 -1.16412304e-02 9.00327981e-01 4.35067624e-01 -1.16412062e-02 9.01802540e-01 4.31978643e-01 -1.16412360e-02 9.03310776e-01 4.28825438e-01 -1.16412267e-02 9.04829621e-01 4.25598204e-01 -1.16412528e-02 9.06355977e-01 4.22350526e-01 -1.16412304e-02 9.07795608e-01 4.19251978e-01 -1.16412183e-02 9.09202635e-01 4.16180998e-01 -1.16412304e-02 9.10649300e-01 4.13009614e-01 -1.16412379e-02 9.12123740e-01 4.09737587e-01 -1.16412491e-02 9.13590789e-01 4.06461030e-01 -1.16412304e-02 9.14967120e-01 4.03364390e-01 -1.16412081e-02 9.16366339e-01 4.00164992e-01 -1.16412444e-02 9.17752981e-01 3.96978199e-01 -1.16412221e-02 9.19119298e-01 3.93787086e-01 -1.16412453e-02 9.20500159e-01 3.90567303e-01 -1.16412137e-02 9.21831489e-01 3.87408257e-01 -1.16412342e-02 9.23202455e-01 3.84124398e-01 -1.16412472e-02 9.24537361e-01 3.80906880e-01 -1.16412211e-02 9.25850153e-01 3.77693743e-01 -1.16412528e-02 9.27215159e-01 3.74341786e-01 -1.16412304e-02 9.28484499e-01 3.71194005e-01 -1.16412081e-02 9.29759145e-01 3.67969155e-01 -1.16412528e-02 9.31051016e-01 3.64703715e-01 -1.16412211e-02 9.32296634e-01 3.61478895e-01 -1.16412491e-02 9.33609843e-01 3.58103812e-01 -1.16412342e-02 9.34826076e-01 3.54901433e-01 -1.16412090e-02 9.36004460e-01 3.51763070e-01 -1.16412286e-02 9.37232137e-01 3.48479033e-01 -1.16412267e-02 9.38475788e-01 3.45119923e-01 -1.16412509e-02 9.39717293e-01 3.41752976e-01 -1.16412314e-02 9.40871239e-01 3.38555187e-01 -1.16412155e-02 9.42030907e-01 3.35310429e-01 -1.16412481e-02 9.43214238e-01 3.31980765e-01 -1.16412202e-02 9.44351494e-01 3.28714162e-01 -1.16412491e-02 9.45535719e-01 3.25306505e-01 -1.16412314e-02 9.46640551e-01 3.22084516e-01 -1.16412090e-02 9.47738349e-01 3.18824977e-01 -1.16412481e-02 9.48868513e-01 3.15456450e-01 -1.16412202e-02 9.49953735e-01 3.12153906e-01 -1.16412528e-02 9.51048315e-01 3.08824688e-01 -1.16412202e-02 9.52082932e-01 3.05609435e-01 -1.16412342e-02 9.53171372e-01 3.02187532e-01 -1.16412528e-02 9.54229832e-01 2.98847020e-01 -1.16412137e-02 9.55252230e-01 2.95544386e-01 -1.16412472e-02 9.56310332e-01 2.92111218e-01 -1.16412351e-02 9.57304478e-01 2.88843066e-01 -1.16412202e-02 9.58292127e-01 2.85527736e-01 -1.16412621e-02 9.59305167e-01 2.82138705e-01 -1.16412099e-02 9.60275054e-01 2.78796911e-01 -1.16412491e-02 9.61268723e-01 2.75357842e-01 -1.16412248e-02 9.62194145e-01 2.72118390e-01 -1.16412118e-02 9.63109851e-01 2.68854022e-01 -1.16412276e-02 9.64045703e-01 2.65475303e-01 -1.16412276e-02 9.64986444e-01 2.62024432e-01 -1.16412453e-02 9.65926826e-01 2.58545309e-01 -1.16412267e-02 9.66808856e-01 2.55239934e-01 -1.16412090e-02 9.67675924e-01 2.51915187e-01 -1.16412379e-02 9.68562841e-01 2.48505190e-01 -1.16412090e-02 9.69405711e-01 2.45157868e-01 -1.16412407e-02 9.70291793e-01 2.41647765e-01 -1.16412221e-02 9.71123695e-01 2.38288671e-01 -1.16412267e-02 9.71949637e-01 2.34898835e-01 -1.16412304e-02 9.72747505e-01 2.31584653e-01 -1.16412127e-02 9.73533213e-01 2.28239492e-01 -1.16412342e-02 9.74342227e-01 2.24781096e-01 -1.16412109e-02 9.75095987e-01 2.21467480e-01 -1.16412239e-02 9.75880325e-01 2.17979863e-01 -1.16412453e-02 9.76637959e-01 2.14582130e-01 -1.16411997e-02 9.77373600e-01 2.11173028e-01 -1.16412435e-02 9.78115618e-01 2.07747132e-01 -1.16412081e-02 9.78810430e-01 2.04433531e-01 -1.16412230e-02 9.79520917e-01 2.00998440e-01 -1.16412304e-02 9.80231702e-01 1.97483048e-01 -1.16412472e-02 9.80929732e-01 1.94001511e-01 -1.16412239e-02 9.81599927e-01 1.90597832e-01 -1.16412109e-02 9.82246578e-01 1.87233195e-01 -1.16412118e-02 9.82873857e-01 1.83896244e-01 -1.16412286e-02 9.83508110e-01 1.80473268e-01 -1.16412211e-02 9.84155536e-01 1.76927909e-01 -1.16412388e-02 9.84777510e-01 1.73443183e-01 -1.16412230e-02 9.85363662e-01 1.70079872e-01 -1.16411960e-02 9.85935211e-01 1.66714177e-01 -1.16412286e-02 9.86509860e-01 1.63268670e-01 -1.16412258e-02 9.87072110e-01 1.59833521e-01 -1.16412304e-02 9.87635314e-01 1.56306922e-01 -1.16412528e-02 9.88190114e-01 1.52768478e-01 -1.16412304e-02 9.88715708e-01 1.49331957e-01 -1.16412248e-02 9.89222169e-01 1.45958722e-01 -1.16412127e-02 9.89719510e-01 1.42496005e-01 -1.16412584e-02 9.90229607e-01 1.38950467e-01 -1.16412276e-02 9.90698576e-01 1.35597795e-01 -1.16412062e-02 9.91156936e-01 1.32144123e-01 -1.16412360e-02 9.91619408e-01 1.28681362e-01 -1.16412072e-02 9.92058098e-01 1.25206187e-01 -1.16412453e-02 9.92493451e-01 1.21749520e-01 -1.16412137e-02 9.92898703e-01 1.18377201e-01 -1.16412211e-02 9.93305922e-01 1.14883199e-01 -1.16412286e-02 9.93710518e-01 1.11333795e-01 -1.16412472e-02 9.94100511e-01 1.07800804e-01 -1.16412286e-02 9.94470954e-01 1.04335628e-01 -1.16412276e-02 9.94828165e-01 1.00924104e-01 -1.16412062e-02 9.95163798e-01 9.74806622e-02 -1.16412463e-02 9.95504558e-01 9.39970389e-02 -1.16412118e-02 9.95822430e-01 9.05170664e-02 -1.16412453e-02 9.96140480e-01 8.69704559e-02 -1.16412286e-02 9.96434093e-01 8.35794881e-02 -1.16412090e-02 9.96712804e-01 8.01643357e-02 -1.16412239e-02 9.96982396e-01 7.66967013e-02 -1.16412276e-02 9.97247994e-01 7.31539577e-02 -1.16412435e-02 9.97501016e-01 6.96599260e-02 -1.16412202e-02 9.97730792e-01 6.62659705e-02 -1.16412332e-02 9.97957170e-01 6.26973510e-02 -1.16412472e-02 9.98178363e-01 5.92008829e-02 -1.16412183e-02 9.98373210e-01 5.57313040e-02 -1.16412472e-02 9.98569310e-01 5.21462262e-02 -1.16412248e-02 9.98746276e-01 4.87350523e-02 -1.16412072e-02 9.98902798e-01 4.52554002e-02 -1.16412407e-02 9.99060571e-01 4.17912528e-02 -1.16412127e-02 9.99193966e-01 3.82964462e-02 -1.16412407e-02 9.99326289e-01 3.47096696e-02 -1.16412314e-02 9.99443650e-01 3.12958732e-02 -1.16412109e-02 9.99540210e-01 2.79195476e-02 -1.16412304e-02 9.99633312e-01 2.44075935e-02 -1.16412267e-02 9.99706805e-01 2.08453946e-02 -1.16412500e-02 9.99785066e-01 1.73785966e-02 -1.16412118e-02 9.99828100e-01 1.39830234e-02 -1.16412248e-02 9.99876678e-01 1.04633011e-02 -1.16412221e-02 9.99911547e-01 6.95979083e-03 -1.16412267e-02 9.99925733e-01 3.41973198e-03 -1.16412491e-02 9.99930561e-01 -1.89777013e-04 -1.16412258e-02 9.99929368e-01 -3.66123300e-03 -1.16412248e-02 9.99909639e-01 -7.17462180e-03 -1.16412258e-02 9.99876142e-01 -1.05737904e-02 -1.16412099e-02 9.99823093e-01 -1.40510211e-02 -1.16412463e-02 9.99781013e-01 -1.75680462e-02 -1.16412053e-02 9.99707341e-01 -2.09407862e-02 -1.16412276e-02 9.99625385e-01 -2.45347936e-02 -1.16412630e-02 9.99539375e-01 -2.80433744e-02 -1.16412127e-02 9.99429941e-01 -3.15127708e-02 -1.16412491e-02 9.99318957e-01 -3.50251235e-02 -1.16412183e-02 9.99191940e-01 -3.83947752e-02 -1.16412304e-02 9.99045551e-01 -4.19757478e-02 -1.16412528e-02 9.98890996e-01 -4.55689877e-02 -1.16412304e-02 9.98723447e-01 -4.90591116e-02 -1.16412388e-02 9.98544872e-01 -5.25560491e-02 -1.16412304e-02 9.98367488e-01 -5.59234954e-02 -1.16412090e-02 9.98167157e-01 -5.93125336e-02 -1.16412360e-02 9.97951746e-01 -6.27995059e-02 -1.16412388e-02 9.97720182e-01 -6.63852990e-02 -1.16412519e-02 9.97474670e-01 -6.99968114e-02 -1.16412304e-02 9.97228503e-01 -7.34708980e-02 -1.16412239e-02 9.96976256e-01 -7.68195987e-02 -1.16412221e-02 9.96705770e-01 -8.02247226e-02 -1.16412314e-02 9.96421039e-01 -8.36873204e-02 -1.16412314e-02 9.96107876e-01 -8.73127803e-02 -1.16412463e-02 9.95802701e-01 -9.07947049e-02 -1.16412053e-02 9.95489478e-01 -9.41221118e-02 -1.16412286e-02 9.95155752e-01 -9.76024419e-02 -1.16412248e-02 9.94794846e-01 -1.01176910e-01 -1.16412453e-02 9.94440556e-01 -1.04658976e-01 -1.16412118e-02 9.94065046e-01 -1.08112946e-01 -1.16412472e-02 9.93689120e-01 -1.11580290e-01 -1.16412127e-02 9.93298352e-01 -1.14957199e-01 -1.16412323e-02 9.92878318e-01 -1.18506797e-01 -1.16412509e-02 9.92459893e-01 -1.22028686e-01 -1.16412099e-02 9.92026687e-01 -1.25455573e-01 -1.16412491e-02 9.91572618e-01 -1.29012838e-01 -1.16412267e-02 9.91128623e-01 -1.32385895e-01 -1.16412211e-02 9.90657389e-01 -1.35851845e-01 -1.16412379e-02 9.90166545e-01 -1.39400125e-01 -1.16412248e-02 9.89687860e-01 -1.42777056e-01 -1.16412072e-02 9.89181697e-01 -1.46192938e-01 -1.16412407e-02 9.88668084e-01 -1.49654999e-01 -1.16412202e-02 9.88132715e-01 -1.53125510e-01 -1.16412491e-02 9.87598956e-01 -1.56577185e-01 -1.16412016e-02 9.87047017e-01 -1.59977317e-01 -1.16412472e-02 9.86479580e-01 -1.63484439e-01 -1.16412044e-02 9.85907853e-01 -1.66873187e-01 -1.16412258e-02 9.85302031e-01 -1.70403987e-01 -1.16412276e-02 9.84703362e-01 -1.73850343e-01 -1.16412388e-02 9.84100819e-01 -1.77245542e-01 -1.16412165e-02 9.83493447e-01 -1.80540964e-01 -1.16412276e-02 9.82854307e-01 -1.84007168e-01 -1.16412286e-02 9.82191145e-01 -1.87496513e-01 -1.16412416e-02 9.81517315e-01 -1.90994650e-01 -1.16412304e-02 9.80840564e-01 -1.94445044e-01 -1.16412360e-02 9.80171561e-01 -1.97798163e-01 -1.16412267e-02 9.79498446e-01 -2.01111078e-01 -1.16412230e-02 9.78785753e-01 -2.04547375e-01 -1.16412230e-02 9.78050292e-01 -2.08020136e-01 -1.16412509e-02 9.77324903e-01 -2.11430147e-01 -1.16412165e-02 9.76584077e-01 -2.14798748e-01 -1.16412379e-02 9.75830197e-01 -2.18224436e-01 -1.16412109e-02 9.75054562e-01 -2.21638143e-01 -1.16412425e-02 9.74274874e-01 -2.25065440e-01 -1.16412146e-02 9.73472118e-01 -2.28495285e-01 -1.16412472e-02 9.72675622e-01 -2.31883287e-01 -1.16412127e-02 9.71881449e-01 -2.35178486e-01 -1.16412342e-02 9.71036375e-01 -2.38626495e-01 -1.16412491e-02 9.70201015e-01 -2.42016122e-01 -1.16412202e-02 9.69343483e-01 -2.45402455e-01 -1.16412481e-02 9.68470514e-01 -2.48849288e-01 -1.16412239e-02 9.67615485e-01 -2.52159864e-01 -1.16412202e-02 9.66727376e-01 -2.55536467e-01 -1.16412360e-02 9.65827465e-01 -2.58942634e-01 -1.16411997e-02 9.64937210e-01 -2.62221873e-01 -1.16412258e-02 9.63998377e-01 -2.65630215e-01 -1.16412472e-02 9.63064671e-01 -2.69027442e-01 -1.16412118e-02 9.62122440e-01 -2.72361755e-01 -1.16412342e-02 9.61126387e-01 -2.75855780e-01 -1.16412248e-02 9.60187614e-01 -2.79119253e-01 -1.16412016e-02 9.59240198e-01 -2.82344580e-01 -1.16412239e-02 9.58221674e-01 -2.85775542e-01 -1.16412463e-02 9.57193732e-01 -2.89203972e-01 -1.16412276e-02 9.56175864e-01 -2.92550474e-01 -1.16412323e-02 9.55177724e-01 -2.95808285e-01 -1.16412090e-02 9.54167306e-01 -2.99034446e-01 -1.16412314e-02 9.53117549e-01 -3.02370101e-01 -1.16412314e-02 9.52014327e-01 -3.05815160e-01 -1.16412407e-02 9.50926363e-01 -3.09188157e-01 -1.16412276e-02 9.49840784e-01 -3.12506318e-01 -1.16412332e-02 9.48770881e-01 -3.15752596e-01 -1.16412127e-02 9.47709084e-01 -3.18920553e-01 -1.16412248e-02 9.46573436e-01 -3.22274029e-01 -1.16412221e-02 9.45402861e-01 -3.25682461e-01 -1.16412360e-02 9.44256127e-01 -3.29008698e-01 -1.16412044e-02 9.43114161e-01 -3.32257420e-01 -1.16412323e-02 9.41961229e-01 -3.35525453e-01 -1.16412202e-02 9.40766037e-01 -3.38837504e-01 -1.16412500e-02 9.39584136e-01 -3.42128545e-01 -1.16412109e-02 9.38369036e-01 -3.45411539e-01 -1.16412379e-02 9.37159300e-01 -3.48678589e-01 -1.16412165e-02 9.35981154e-01 -3.51828814e-01 -1.16412239e-02 9.34746563e-01 -3.55104983e-01 -1.16412286e-02 9.33472037e-01 -3.58464628e-01 -1.16412370e-02 9.32206154e-01 -3.61725301e-01 -1.16412211e-02 9.30948138e-01 -3.64956796e-01 -1.16412435e-02 9.29668903e-01 -3.68214160e-01 -1.16412127e-02 9.28378224e-01 -3.71438265e-01 -1.16412453e-02 9.27075326e-01 -3.74695778e-01 -1.16412127e-02 9.25796628e-01 -3.77833694e-01 -1.16412286e-02 9.24447596e-01 -3.81113857e-01 -1.16412453e-02 9.23105419e-01 -3.84364277e-01 -1.16412248e-02 9.21742797e-01 -3.87612432e-01 -1.16412453e-02 9.20350373e-01 -3.90912890e-01 -1.16412230e-02 9.19032812e-01 -3.94005835e-01 -1.16412118e-02 9.17683601e-01 -3.97135288e-01 -1.16412248e-02 9.16242182e-01 -4.00443316e-01 -1.16412528e-02 9.14799929e-01 -4.03735548e-01 -1.16412211e-02 9.13387299e-01 -4.06918436e-01 -1.16412286e-02 9.12003219e-01 -4.10026968e-01 -1.16411988e-02 9.10605192e-01 -4.13107961e-01 -1.16412239e-02 9.09172356e-01 -4.16250974e-01 -1.16412221e-02 9.07668650e-01 -4.19515789e-01 -1.16412379e-02 9.06165719e-01 -4.22758907e-01 -1.16412230e-02 9.04675782e-01 -4.25937682e-01 -1.16412202e-02 9.03223455e-01 -4.29018795e-01 -1.16412025e-02 9.01757240e-01 -4.32077020e-01 -1.16412276e-02 9.00259733e-01 -4.35199916e-01 -1.16412202e-02 8.98679137e-01 -4.38446403e-01 -1.16412342e-02 8.97144616e-01 -4.41583872e-01 -1.16412127e-02 8.95608962e-01 -4.44681793e-01 -1.16412342e-02 8.94038737e-01 -4.47838008e-01 -1.16412146e-02 8.92504692e-01 -4.50888306e-01 -1.16412230e-02 8.90933037e-01 -4.53986645e-01 -1.16412183e-02 8.89285147e-01 -4.57194567e-01 -1.16412407e-02 8.87708783e-01 -4.60259348e-01 -1.16412072e-02 8.86124611e-01 -4.63303208e-01 -1.16412221e-02 8.84509444e-01 -4.66371983e-01 -1.16412314e-02 8.82852912e-01 -4.69500214e-01 -1.16412351e-02 8.81212294e-01 -4.72577542e-01 -1.16412165e-02 8.79531205e-01 -4.75692958e-01 -1.16412314e-02 8.77861381e-01 -4.78782833e-01 -1.16412081e-02 8.76242161e-01 -4.81725246e-01 -1.16412248e-02 8.74550402e-01 -4.84788060e-01 -1.16412258e-02 8.72854471e-01 -4.87834543e-01 -1.16412304e-02 8.71118784e-01 -4.90930766e-01 -1.16412276e-02 8.69374394e-01 -4.94010568e-01 -1.16412304e-02 8.67657423e-01 -4.97035801e-01 -1.16411978e-02 8.65896761e-01 -5.00075281e-01 -1.16412491e-02 8.64140332e-01 -5.03119051e-01 -1.16412081e-02 8.62449169e-01 -5.06005824e-01 -1.16412295e-02 8.60670686e-01 -5.09025455e-01 -1.16412248e-02 8.58875930e-01 -5.12048304e-01 -1.16412230e-02 8.57048213e-01 -5.15099406e-01 -1.16412388e-02 8.55184615e-01 -5.18184662e-01 -1.16412323e-02 8.53414834e-01 -5.21105170e-01 -1.16412118e-02 8.51647317e-01 -5.23978710e-01 -1.16412323e-02 8.49812150e-01 -5.26953101e-01 -1.16412351e-02 8.47913384e-01 -5.29994786e-01 -1.16412528e-02 8.46018493e-01 -5.33021748e-01 -1.16412304e-02 8.44192445e-01 -5.35914540e-01 -1.16412090e-02 8.42377841e-01 -5.38754463e-01 -1.16412332e-02 8.40441465e-01 -5.41766286e-01 -1.16412453e-02 8.38492274e-01 -5.44782341e-01 -1.16412286e-02 8.36579978e-01 -5.47711432e-01 -1.16412360e-02 8.34669888e-01 -5.50627232e-01 -1.16412230e-02 8.32803309e-01 -5.53446829e-01 -1.16412044e-02 8.30915689e-01 -5.56272686e-01 -1.16412258e-02 8.28955472e-01 -5.59190333e-01 -1.16412276e-02 8.26947629e-01 -5.62151313e-01 -1.16412453e-02 8.24982345e-01 -5.65043449e-01 -1.16412062e-02 8.22994471e-01 -5.67922831e-01 -1.16412407e-02 8.21011961e-01 -5.70795894e-01 -1.16412099e-02 8.19026649e-01 -5.73628426e-01 -1.16412323e-02 8.17027867e-01 -5.76486170e-01 -1.16412090e-02 8.15011322e-01 -5.79318762e-01 -1.16412472e-02 8.12970817e-01 -5.82192481e-01 -1.16412081e-02 8.10969234e-01 -5.84965408e-01 -1.16412267e-02 8.08906198e-01 -5.87820590e-01 -1.16412258e-02 8.06823313e-01 -5.90672016e-01 -1.16412276e-02 8.04703772e-01 -5.93555212e-01 -1.16412323e-02 8.02659810e-01 -5.96321940e-01 -1.16412230e-02 8.00622046e-01 -5.99050879e-01 -1.16412276e-02 7.98512101e-01 -6.01860702e-01 -1.16412379e-02 7.96408117e-01 -6.04648352e-01 -1.16412127e-02 7.94292867e-01 -6.07417941e-01 -1.16412379e-02 7.92176366e-01 -6.10179842e-01 -1.16412211e-02 7.90085435e-01 -6.12882137e-01 -1.16412286e-02 7.87880123e-01 -6.15708828e-01 -1.16412472e-02 7.85673976e-01 -6.18527293e-01 -1.16412267e-02 7.83558369e-01 -6.21208429e-01 -1.16412146e-02 7.81440616e-01 -6.23869777e-01 -1.16412230e-02 7.79268026e-01 -6.26578748e-01 -1.16412286e-02 7.77013958e-01 -6.29368901e-01 -1.16412491e-02 7.74820626e-01 -6.32073343e-01 -1.16412099e-02 7.72638977e-01 -6.34732723e-01 -1.16412360e-02 7.70443797e-01 -6.37398541e-01 -1.16412276e-02 7.68214941e-01 -6.40078485e-01 -1.16412425e-02 7.65962303e-01 -6.42776430e-01 -1.16412323e-02 7.63678968e-01 -6.45483613e-01 -1.16412453e-02 7.61427283e-01 -6.48144245e-01 -1.16412183e-02 7.59207845e-01 -6.50738955e-01 -1.16412314e-02 7.56921351e-01 -6.53398693e-01 -1.16412295e-02 7.54574835e-01 -6.56102419e-01 -1.16412491e-02 7.52221763e-01 -6.58803165e-01 -1.16412304e-02 7.49911547e-01 -6.61431432e-01 -1.16412304e-02 7.47655571e-01 -6.63987279e-01 -1.16412062e-02 7.45412052e-01 -6.66497111e-01 -1.16412332e-02 7.43010283e-01 -6.69170439e-01 -1.16412528e-02 7.40669489e-01 -6.71772957e-01 -1.16412118e-02 7.38325953e-01 -6.74335182e-01 -1.16412491e-02 7.35972166e-01 -6.76912248e-01 -1.16412174e-02 7.33676791e-01 -6.79394662e-01 -1.16412295e-02 7.31231570e-01 -6.82021320e-01 -1.16412491e-02 7.28790283e-01 -6.84633076e-01 -1.16412304e-02 7.26437449e-01 -6.87131464e-01 -1.16412165e-02 7.24054396e-01 -6.89639449e-01 -1.16412491e-02 7.21628129e-01 -6.92177415e-01 -1.16412165e-02 7.19225287e-01 -6.94679737e-01 -1.16412491e-02 7.16756761e-01 -6.97228193e-01 -1.16412304e-02 7.14361191e-01 -6.99680865e-01 -1.16412221e-02 7.11913526e-01 -7.02172816e-01 -1.16412276e-02 7.09437430e-01 -7.04686701e-01 -1.16411885e-02 7.06994236e-01 -7.07121789e-01 -1.16411932e-02 7.04472959e-01 -7.09645450e-01 -1.16411569e-02 7.02044249e-01 -7.12051690e-01 -1.16411038e-02 6.99621379e-01 -7.14428604e-01 -1.16410814e-02 6.97158217e-01 -7.16833174e-01 -1.16410367e-02 6.94611788e-01 -7.19295025e-01 -1.16410367e-02 6.92134798e-01 -7.21679389e-01 -1.16410414e-02 6.89693868e-01 -7.24005818e-01 -1.16410702e-02 6.87073171e-01 -7.26493478e-01 -1.16410842e-02 6.84576988e-01 -7.28846133e-01 -1.16410851e-02 6.81918323e-01 -7.31334507e-01 -1.16410842e-02 6.80053294e-01 -7.33069777e-01 -1.16410842e-02 6.77728832e-01 -7.35219717e-01 -1.16410833e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.52626967e-01 -8.33347380e-01 -1.16410824e-02 5.49695015e-01 -8.35283160e-01 -1.16410730e-02 5.47303200e-01 -8.36857557e-01 -1.16410367e-02 5.44441104e-01 -8.38724196e-01 -1.16411541e-02 5.41523755e-01 -8.40610862e-01 -1.16411578e-02 5.38692176e-01 -8.42426479e-01 -1.16411997e-02 5.35758495e-01 -8.44288766e-01 -1.16412109e-02 5.32819211e-01 -8.46149921e-01 -1.16412193e-02 5.29851496e-01 -8.48005474e-01 -1.16412304e-02 5.26903689e-01 -8.49843383e-01 -1.16412276e-02 5.23925722e-01 -8.51679504e-01 -1.16412332e-02 5.20940781e-01 -8.53512108e-01 -1.16412304e-02 5.17921627e-01 -8.55342329e-01 -1.16412444e-02 5.14910996e-01 -8.57163191e-01 -1.16412211e-02 5.11971176e-01 -8.58918846e-01 -1.16412304e-02 5.08951485e-01 -8.60712528e-01 -1.16412314e-02 5.05935788e-01 -8.62489462e-01 -1.16412342e-02 5.02934873e-01 -8.64242196e-01 -1.16412286e-02 4.99840558e-01 -8.66033435e-01 -1.16412453e-02 4.96812701e-01 -8.67779315e-01 -1.16412230e-02 4.93865907e-01 -8.69456112e-01 -1.16412258e-02 4.90827590e-01 -8.71179581e-01 -1.16412267e-02 4.87771481e-01 -8.72888744e-01 -1.16412323e-02 4.84714627e-01 -8.74588966e-01 -1.16412286e-02 4.81687129e-01 -8.76262784e-01 -1.16412360e-02 4.78624403e-01 -8.77940178e-01 -1.16412295e-02 4.75569904e-01 -8.79596353e-01 -1.16412332e-02 4.72478330e-01 -8.81260991e-01 -1.16412425e-02 4.69411075e-01 -8.82897615e-01 -1.16412360e-02 4.66323346e-01 -8.84535968e-01 -1.16412323e-02 4.63246644e-01 -8.86150002e-01 -1.16412332e-02 4.60146874e-01 -8.87761474e-01 -1.16412360e-02 4.57047820e-01 -8.89362872e-01 -1.16412342e-02 4.53953952e-01 -8.90944362e-01 -1.16412342e-02 4.50844824e-01 -8.92522871e-01 -1.16412332e-02 4.47723091e-01 -8.94092977e-01 -1.16412332e-02 4.44615543e-01 -8.95642519e-01 -1.16412286e-02 4.41485912e-01 -8.97189081e-01 -1.16412360e-02 4.38343376e-01 -8.98730040e-01 -1.16412360e-02 4.35209811e-01 -9.00250137e-01 -1.16412379e-02 4.32062894e-01 -9.01762605e-01 -1.16412342e-02 4.28834707e-01 -9.03300166e-01 -1.16412565e-02 4.25649703e-01 -9.04811859e-01 -1.16412202e-02 4.22472119e-01 -9.06293094e-01 -1.16412630e-02 4.19310302e-01 -9.07768548e-01 -1.16412127e-02 4.16254163e-01 -9.09167826e-01 -1.16412360e-02 4.13070142e-01 -9.10619557e-01 -1.16412379e-02 4.09874678e-01 -9.12063479e-01 -1.16412342e-02 4.06607568e-01 -9.13521886e-01 -1.16412528e-02 4.03398484e-01 -9.14949059e-01 -1.16412221e-02 4.00311440e-01 -9.16304171e-01 -1.16412276e-02 3.97130340e-01 -9.17682528e-01 -1.16412453e-02 3.93915296e-01 -9.19065714e-01 -1.16412379e-02 3.90621036e-01 -9.20470536e-01 -1.16412630e-02 3.87371659e-01 -9.21849191e-01 -1.16412230e-02 3.84153187e-01 -9.23188746e-01 -1.16412528e-02 3.80924463e-01 -9.24530149e-01 -1.16412211e-02 3.77797544e-01 -9.25812125e-01 -1.16412379e-02 3.74555022e-01 -9.27125990e-01 -1.16412407e-02 3.71234447e-01 -9.28459108e-01 -1.16412528e-02 3.67906123e-01 -9.29786384e-01 -1.16412388e-02 3.64738435e-01 -9.31037128e-01 -1.16412267e-02 3.61578017e-01 -9.32259798e-01 -1.16412407e-02 3.58333945e-01 -9.33520973e-01 -1.16412379e-02 3.55061173e-01 -9.34762418e-01 -1.16412435e-02 3.51799995e-01 -9.35990691e-01 -1.16412360e-02 3.48508567e-01 -9.37219858e-01 -1.16412379e-02 3.45218241e-01 -9.38441157e-01 -1.16412342e-02 3.41971457e-01 -9.39635515e-01 -1.16412360e-02 3.38563323e-01 -9.40862656e-01 -1.16412630e-02 3.35264206e-01 -9.42054212e-01 -1.16412258e-02 3.32007319e-01 -9.43197370e-01 -1.16412630e-02 3.28694433e-01 -9.44364190e-01 -1.16412193e-02 3.25433463e-01 -9.45485532e-01 -1.16412630e-02 3.22106540e-01 -9.46630895e-01 -1.16412211e-02 3.18888247e-01 -9.47716177e-01 -1.16412407e-02 3.15578878e-01 -9.48821843e-01 -1.16412407e-02 3.12256426e-01 -9.49920654e-01 -1.16412435e-02 3.08942616e-01 -9.51004624e-01 -1.16412360e-02 3.05626988e-01 -9.52077627e-01 -1.16412416e-02 3.02277148e-01 -9.53144133e-01 -1.16412397e-02 2.98969805e-01 -9.54188287e-01 -1.16412332e-02 2.95640230e-01 -9.55225050e-01 -1.16412342e-02 2.92323053e-01 -9.56245422e-01 -1.16412379e-02 2.88888067e-01 -9.57283139e-01 -1.16412565e-02 2.85458326e-01 -9.58315492e-01 -1.16412407e-02 2.82192379e-01 -9.59287286e-01 -1.16412248e-02 2.78848261e-01 -9.60260034e-01 -1.16412528e-02 2.75399327e-01 -9.61254835e-01 -1.16412379e-02 2.72048026e-01 -9.62209642e-01 -1.16412314e-02 2.68770933e-01 -9.63133872e-01 -1.16412211e-02 2.65478104e-01 -9.64043081e-01 -1.16412379e-02 2.62106866e-01 -9.64968383e-01 -1.16412342e-02 2.58742243e-01 -9.65871036e-01 -1.16412407e-02 2.55360305e-01 -9.66771424e-01 -1.16412407e-02 2.51998216e-01 -9.67656195e-01 -1.16412379e-02 2.48528168e-01 -9.68546689e-01 -1.16412602e-02 2.45149300e-01 -9.69412506e-01 -1.16412239e-02 2.41767675e-01 -9.70257044e-01 -1.16412528e-02 2.38371447e-01 -9.71103370e-01 -1.16412230e-02 2.35096812e-01 -9.71900702e-01 -1.16412388e-02 2.31682405e-01 -9.72718954e-01 -1.16412425e-02 2.28285357e-01 -9.73522365e-01 -1.16412379e-02 2.24873602e-01 -9.74315703e-01 -1.16412388e-02 2.21411869e-01 -9.75103915e-01 -1.16412565e-02 2.17983454e-01 -9.75883007e-01 -1.16412221e-02 2.14669853e-01 -9.76613820e-01 -1.16412332e-02 2.11238787e-01 -9.77360606e-01 -1.16412351e-02 2.07847103e-01 -9.78088558e-01 -1.16412332e-02 2.04356983e-01 -9.78821993e-01 -1.16412630e-02 2.00863227e-01 -9.79548573e-01 -1.16412286e-02 1.97514623e-01 -9.80229378e-01 -1.16412248e-02 1.94174901e-01 -9.80892539e-01 -1.16412472e-02 1.90747336e-01 -9.81567085e-01 -1.16412407e-02 1.87262058e-01 -9.82234538e-01 -1.16412491e-02 1.83820575e-01 -9.82889533e-01 -1.16412211e-02 1.80390432e-01 -9.83516455e-01 -1.16412630e-02 1.76934332e-01 -9.84158576e-01 -1.16412211e-02 1.73626766e-01 -9.84742403e-01 -1.16412407e-02 1.70200050e-01 -9.85334516e-01 -1.16412453e-02 1.66749120e-01 -9.85925674e-01 -1.16412472e-02 1.63204163e-01 -9.86514091e-01 -1.16412630e-02 1.59740090e-01 -9.87088442e-01 -1.16412230e-02 1.56403556e-01 -9.87620056e-01 -1.16412472e-02 1.52963594e-01 -9.88159001e-01 -1.16412435e-02 1.49504051e-01 -9.88686740e-01 -1.16412388e-02 1.46067873e-01 -9.89202797e-01 -1.16412342e-02 1.42596409e-01 -9.89708185e-01 -1.16412351e-02 1.39148369e-01 -9.90200400e-01 -1.16412351e-02 1.35584563e-01 -9.90693152e-01 -1.16412528e-02 1.32126004e-01 -9.91162300e-01 -1.16412248e-02 1.28768310e-01 -9.91602063e-01 -1.16412379e-02 1.25277519e-01 -9.92050171e-01 -1.16412360e-02 1.21817745e-01 -9.92480159e-01 -1.16412379e-02 1.18270487e-01 -9.92907047e-01 -1.16412528e-02 1.14783794e-01 -9.93319452e-01 -1.16412239e-02 1.11415707e-01 -9.93701041e-01 -1.16412397e-02 1.07958511e-01 -9.94083345e-01 -1.16412360e-02 1.04478203e-01 -9.94454205e-01 -1.16412379e-02 1.00923948e-01 -9.94817317e-01 -1.16412621e-02 9.74386036e-02 -9.95171249e-01 -1.16412211e-02 9.39614847e-02 -9.95501995e-01 -1.16412630e-02 9.04693753e-02 -9.95830536e-01 -1.16412230e-02 8.70212913e-02 -9.96131837e-01 -1.16412630e-02 8.34251195e-02 -9.96441424e-01 -1.16412370e-02 8.00523758e-02 -9.96721804e-01 -1.16412211e-02 7.66679123e-02 -9.96984422e-01 -1.16412314e-02 7.31914192e-02 -9.97245550e-01 -1.16412407e-02 6.97219148e-02 -9.97492611e-01 -1.16412435e-02 6.62385076e-02 -9.97730553e-01 -1.16412453e-02 6.27457127e-02 -9.97956514e-01 -1.16412407e-02 5.92792928e-02 -9.98169065e-01 -1.16412407e-02 5.58025837e-02 -9.98369277e-01 -1.16412472e-02 5.23097403e-02 -9.98556912e-01 -1.16412453e-02 4.88082878e-02 -9.98735964e-01 -1.16412491e-02 4.52431366e-02 -9.98901129e-01 -1.16412630e-02 4.16681617e-02 -9.99059737e-01 -1.16412388e-02 3.82393263e-02 -9.99197423e-01 -1.16412332e-02 3.48403864e-02 -9.99320030e-01 -1.16412435e-02 3.12639065e-02 -9.99435365e-01 -1.16412593e-02 2.77829636e-02 -9.99544621e-01 -1.16412248e-02 2.42895260e-02 -9.99631941e-01 -1.16412630e-02 2.07799803e-02 -9.99711990e-01 -1.16412258e-02 1.74059793e-02 -9.99780536e-01 -1.16412453e-02 1.38367731e-02 -9.99823689e-01 -1.16412612e-02 1.03204977e-02 -9.99877334e-01 -1.16412286e-02 6.94486080e-03 -9.99910414e-01 -1.16412379e-02 3.43627273e-03 -9.99927580e-01 -1.16412360e-02 -3.91726171e-05 -9.99927521e-01 -1.16412453e-02 -3.51674762e-03 -9.99926448e-01 -1.16412453e-02 -7.02602603e-03 -9.99909461e-01 -1.16412453e-02 -1.05140908e-02 -9.99873102e-01 -1.16412388e-02 -1.39916847e-02 -9.99824643e-01 -1.16412416e-02 -1.75757259e-02 -9.99776721e-01 -1.16412537e-02 -2.11622715e-02 -9.99700606e-01 -1.16412472e-02 -2.45793778e-02 -9.99629676e-01 -1.16412248e-02 -2.79706232e-02 -9.99536335e-01 -1.16412453e-02 -3.14534307e-02 -9.99433637e-01 -1.16412444e-02 -3.49223949e-02 -9.99318242e-01 -1.16412472e-02 -3.85177545e-02 -9.99182582e-01 -1.16412630e-02 -4.20216508e-02 -9.99048769e-01 -1.16412248e-02 -4.54164930e-02 -9.98896062e-01 -1.16412360e-02 -4.88731377e-02 -9.98733699e-01 -1.16412379e-02 -5.23343012e-02 -9.98554587e-01 -1.16412472e-02 -5.59323244e-02 -9.98358905e-01 -1.16412630e-02 -5.94319515e-02 -9.98163700e-01 -1.16412221e-02 -6.28914461e-02 -9.97944236e-01 -1.16412630e-02 -6.63919821e-02 -9.97724116e-01 -1.16412202e-02 -6.97800964e-02 -9.97487545e-01 -1.16412453e-02 -7.33669400e-02 -9.97229815e-01 -1.16412630e-02 -7.68502280e-02 -9.96972501e-01 -1.16412211e-02 -8.03048313e-02 -9.96694088e-01 -1.16412630e-02 -8.38085115e-02 -9.96412039e-01 -1.16412248e-02 -8.71785879e-02 -9.96119857e-01 -1.16412425e-02 -9.06532854e-02 -9.95809317e-01 -1.16412453e-02 -9.41231772e-02 -9.95488167e-01 -1.16412407e-02 -9.76213217e-02 -9.95151043e-01 -1.16412435e-02 -1.01089977e-01 -9.94804680e-01 -1.16412388e-02 -1.04544565e-01 -9.94447410e-01 -1.16412407e-02 -1.08114302e-01 -9.94064093e-01 -1.16412528e-02 -1.11577965e-01 -9.93686080e-01 -1.16412239e-02 -1.14972107e-01 -9.93294060e-01 -1.16412425e-02 -1.18434094e-01 -9.92887557e-01 -1.16412407e-02 -1.21894561e-01 -9.92471039e-01 -1.16412453e-02 -1.25450999e-01 -9.92024958e-01 -1.16412630e-02 -1.28916740e-01 -9.91583765e-01 -1.16412276e-02 -1.32277533e-01 -9.91139293e-01 -1.16412472e-02 -1.35752454e-01 -9.90669429e-01 -1.16412453e-02 -1.39204666e-01 -9.90190506e-01 -1.16412453e-02 -1.42732099e-01 -9.89683926e-01 -1.16412630e-02 -1.46203086e-01 -9.89183545e-01 -1.16412239e-02 -1.49631500e-01 -9.88664865e-01 -1.16412528e-02 -1.53084636e-01 -9.88142967e-01 -1.16412276e-02 -1.56452984e-01 -9.87611651e-01 -1.16412397e-02 -1.59979224e-01 -9.87045348e-01 -1.16412574e-02 -1.63431689e-01 -9.86483932e-01 -1.16412258e-02 -1.66858733e-01 -9.85904515e-01 -1.16412733e-02 -1.70322642e-01 -9.85315621e-01 -1.16412276e-02 -1.73664227e-01 -9.84734714e-01 -1.16412453e-02 -1.77095309e-01 -9.84123468e-01 -1.16412407e-02 -1.80538014e-01 -9.83491421e-01 -1.16412435e-02 -1.83968604e-01 -9.82860744e-01 -1.16412379e-02 -1.87387004e-01 -9.82212484e-01 -1.16412407e-02 -1.90815151e-01 -9.81551111e-01 -1.16412397e-02 -1.94232941e-01 -9.80881751e-01 -1.16412379e-02 -1.97752565e-01 -9.80175257e-01 -1.16412612e-02 -2.01157436e-01 -9.79486346e-01 -1.16412276e-02 -2.04483673e-01 -9.78796482e-01 -1.16412388e-02 -2.07918182e-01 -9.78074491e-01 -1.16412379e-02 -2.11397097e-01 -9.77324009e-01 -1.16412630e-02 -2.14845404e-01 -9.76575375e-01 -1.16412258e-02 -2.18132421e-01 -9.75845635e-01 -1.16412453e-02 -2.21540719e-01 -9.75076795e-01 -1.16412453e-02 -2.24960923e-01 -9.74291563e-01 -1.16412472e-02 -2.28453711e-01 -9.73480761e-01 -1.16412630e-02 -2.31860265e-01 -9.72681463e-01 -1.16412183e-02 -2.35138759e-01 -9.71889615e-01 -1.16412472e-02 -2.38549024e-01 -9.71057773e-01 -1.16412453e-02 -2.41907150e-01 -9.70223784e-01 -1.16412388e-02 -2.45301291e-01 -9.69370425e-01 -1.16412453e-02 -2.48668298e-01 -9.68513370e-01 -1.16412453e-02 -2.52133995e-01 -9.67614412e-01 -1.16412630e-02 -2.55550206e-01 -9.66724873e-01 -1.16412267e-02 -2.58905023e-01 -9.65825260e-01 -1.16412630e-02 -2.62392610e-01 -9.64888215e-01 -1.16412407e-02 -2.65654713e-01 -9.63995278e-01 -1.16412239e-02 -2.68919557e-01 -9.63087559e-01 -1.16412453e-02 -2.72289634e-01 -9.62140322e-01 -1.16412472e-02 -2.75667101e-01 -9.61177051e-01 -1.16412453e-02 -2.79011220e-01 -9.60211754e-01 -1.16412472e-02 -2.82354236e-01 -9.59234476e-01 -1.16412388e-02 -2.85700738e-01 -9.58245158e-01 -1.16412435e-02 -2.89048970e-01 -9.57238019e-01 -1.16412407e-02 -2.92369127e-01 -9.56230700e-01 -1.16412407e-02 -2.95804113e-01 -9.55171645e-01 -1.16412630e-02 -2.99260199e-01 -9.54095423e-01 -1.16412472e-02 -3.02575916e-01 -9.53048587e-01 -1.16412472e-02 -3.05821210e-01 -9.52017426e-01 -1.16412239e-02 -3.09038043e-01 -9.50972736e-01 -1.16412453e-02 -3.12443167e-01 -9.49857056e-01 -1.16412733e-02 -3.15769285e-01 -9.48762357e-01 -1.16412323e-02 -3.19064617e-01 -9.47653651e-01 -1.16412630e-02 -3.22366208e-01 -9.46541607e-01 -1.16412248e-02 -3.25561851e-01 -9.45444405e-01 -1.16412453e-02 -3.28871459e-01 -9.44298267e-01 -1.16412342e-02 -3.32151711e-01 -9.43150818e-01 -1.16412360e-02 -3.35528851e-01 -9.41949725e-01 -1.16412630e-02 -3.38852912e-01 -9.40765560e-01 -1.16412211e-02 -3.42118144e-01 -9.39578295e-01 -1.16412630e-02 -3.45389485e-01 -9.38379109e-01 -1.16412221e-02 -3.48592937e-01 -9.37188148e-01 -1.16412379e-02 -3.51857603e-01 -9.35967922e-01 -1.16412407e-02 -3.55107754e-01 -9.34745312e-01 -1.16412444e-02 -3.58462483e-01 -9.33468103e-01 -1.16412630e-02 -3.61798137e-01 -9.32175219e-01 -1.16412453e-02 -3.64994377e-01 -9.30936158e-01 -1.16412258e-02 -3.68151486e-01 -9.29688692e-01 -1.16412407e-02 -3.71379018e-01 -9.28402901e-01 -1.16412407e-02 -3.74614716e-01 -9.27101731e-01 -1.16412453e-02 -3.77920449e-01 -9.25757229e-01 -1.16412630e-02 -3.81167173e-01 -9.24427807e-01 -1.16412258e-02 -3.84292006e-01 -9.23132300e-01 -1.16412407e-02 -3.87526512e-01 -9.21778202e-01 -1.16412444e-02 -3.90738875e-01 -9.20421720e-01 -1.16412435e-02 -3.94020200e-01 -9.19016838e-01 -1.16412630e-02 -3.97236764e-01 -9.17639315e-01 -1.16412258e-02 -4.00427252e-01 -9.16247606e-01 -1.16412630e-02 -4.03637022e-01 -9.14843857e-01 -1.16412230e-02 -4.06720459e-01 -9.13472533e-01 -1.16412472e-02 -4.09906387e-01 -9.12048995e-01 -1.16412416e-02 -4.13088679e-01 -9.10610855e-01 -1.16412407e-02 -4.16260123e-01 -9.09162521e-01 -1.16412435e-02 -4.19446439e-01 -9.07697976e-01 -1.16412435e-02 -4.22609121e-01 -9.06230390e-01 -1.16412453e-02 -4.25793141e-01 -9.04740751e-01 -1.16412342e-02 -4.29026812e-01 -9.03207898e-01 -1.16412630e-02 -4.32161570e-01 -9.01718080e-01 -1.16412211e-02 -4.35226411e-01 -9.00242984e-01 -1.16412453e-02 -4.38440472e-01 -8.98678601e-01 -1.16412733e-02 -4.41662431e-01 -8.97100747e-01 -1.16412453e-02 -4.44714934e-01 -8.95594895e-01 -1.16412267e-02 -4.47763443e-01 -8.94070089e-01 -1.16412453e-02 -4.50886726e-01 -8.92500520e-01 -1.16412453e-02 -4.53999102e-01 -8.90921712e-01 -1.16412444e-02 -4.57185537e-01 -8.89287293e-01 -1.16412593e-02 -4.60277140e-01 -8.87696803e-01 -1.16412221e-02 -4.63281840e-01 -8.86132598e-01 -1.16412370e-02 -4.66366291e-01 -8.84509206e-01 -1.16412472e-02 -4.69456047e-01 -8.82873774e-01 -1.16412453e-02 -4.72620726e-01 -8.81182194e-01 -1.16412630e-02 -4.75692809e-01 -8.79530549e-01 -1.16412258e-02 -4.78752464e-01 -8.77865136e-01 -1.16412630e-02 -4.81840938e-01 -8.76179218e-01 -1.16412286e-02 -4.84874815e-01 -8.74496281e-01 -1.16412584e-02 -4.88012046e-01 -8.72753143e-01 -1.16412444e-02 -4.90986764e-01 -8.71088922e-01 -1.16412230e-02 -4.93930578e-01 -8.69415700e-01 -1.16412491e-02 -4.96971071e-01 -8.67685616e-01 -1.16412388e-02 -4.99991387e-01 -8.65947485e-01 -1.16412435e-02 -5.02995849e-01 -8.64204705e-01 -1.16412453e-02 -5.06006479e-01 -8.62446606e-01 -1.16412453e-02 -5.09023964e-01 -8.60666037e-01 -1.16412491e-02 -5.12021661e-01 -8.58888209e-01 -1.16412407e-02 -5.15034378e-01 -8.57087016e-01 -1.16412388e-02 -5.18016636e-01 -8.55284810e-01 -1.16412444e-02 -5.20991921e-01 -8.53477240e-01 -1.16412453e-02 -5.24042368e-01 -8.51604044e-01 -1.16412574e-02 -5.27007699e-01 -8.49779844e-01 -1.16412248e-02 -5.29888451e-01 -8.47983181e-01 -1.16412407e-02 -5.32914639e-01 -8.46079230e-01 -1.16412630e-02 -5.35889030e-01 -8.44205797e-01 -1.16412258e-02 -5.38816273e-01 -8.42333138e-01 -1.16412630e-02 -5.41767240e-01 -8.40444565e-01 -1.16412286e-02 -5.44600785e-01 -8.38607788e-01 -1.16412491e-02 -5.47536969e-01 -8.36692929e-01 -1.16412453e-02 -5.50439239e-01 -8.34789276e-01 -1.16412397e-02 -5.53346395e-01 -8.32861781e-01 -1.16412472e-02 -5.56255817e-01 -8.30923557e-01 -1.16412435e-02 -5.59244454e-01 -8.28915000e-01 -1.16412528e-02 -5.62133193e-01 -8.26962948e-01 -1.16412230e-02 -5.64931810e-01 -8.25051665e-01 -1.16412453e-02 -5.67805588e-01 -8.23076189e-01 -1.16412435e-02 -5.70676804e-01 -8.21087718e-01 -1.16412388e-02 -5.73622942e-01 -8.19026649e-01 -1.16412630e-02 -5.76561391e-01 -8.16966951e-01 -1.16412472e-02 -5.79334259e-01 -8.15005481e-01 -1.16412248e-02 -5.82087815e-01 -8.13037634e-01 -1.16412407e-02 -5.84931135e-01 -8.10989916e-01 -1.16412463e-02 -5.87763786e-01 -8.08944345e-01 -1.16412397e-02 -5.90656042e-01 -8.06829810e-01 -1.16412630e-02 -5.93468189e-01 -8.04771423e-01 -1.16412221e-02 -5.96188545e-01 -8.02753091e-01 -1.16412472e-02 -5.98987997e-01 -8.00666928e-01 -1.16412407e-02 -6.01787269e-01 -7.98565209e-01 -1.16412472e-02 -6.04639828e-01 -7.96406507e-01 -1.16412630e-02 -6.07459307e-01 -7.94260919e-01 -1.16412323e-02 -6.10213816e-01 -7.92141199e-01 -1.16412621e-02 -6.12959146e-01 -7.90026605e-01 -1.16412239e-02 -6.15633667e-01 -7.87939608e-01 -1.16412472e-02 -6.18371487e-01 -7.85792947e-01 -1.16412472e-02 -6.21111035e-01 -7.83629894e-01 -1.16412453e-02 -6.23837590e-01 -7.81461060e-01 -1.16412453e-02 -6.26559675e-01 -7.79281020e-01 -1.16412453e-02 -6.29295886e-01 -7.77076066e-01 -1.16412388e-02 -6.31987154e-01 -7.74882734e-01 -1.16412453e-02 -6.34690344e-01 -7.72672832e-01 -1.16412416e-02 -6.37386918e-01 -7.70449400e-01 -1.16412472e-02 -6.40080810e-01 -7.68213749e-01 -1.16412453e-02 -6.42811000e-01 -7.65927315e-01 -1.16412630e-02 -6.45578027e-01 -7.63598979e-01 -1.16412453e-02 -6.48171842e-01 -7.61398971e-01 -1.16412304e-02 -6.50733590e-01 -7.59209633e-01 -1.16412472e-02 -6.53393388e-01 -7.56921530e-01 -1.16412509e-02 -6.56041563e-01 -7.54629910e-01 -1.16412453e-02 -6.58729732e-01 -7.52279043e-01 -1.16412630e-02 -6.61375940e-01 -7.49962807e-01 -1.16412239e-02 -6.63910568e-01 -7.47715116e-01 -1.16412491e-02 -6.66513681e-01 -7.45396674e-01 -1.16412453e-02 -6.69106543e-01 -7.43068337e-01 -1.16412463e-02 -6.71772480e-01 -7.40659118e-01 -1.16412630e-02 -6.74359560e-01 -7.38308012e-01 -1.16412258e-02 -6.76923275e-01 -7.35952914e-01 -1.16412630e-02 -6.79506421e-01 -7.33574271e-01 -1.16412276e-02 -6.82042301e-01 -7.31208563e-01 -1.16412630e-02 -6.84660792e-01 -7.28759527e-01 -1.16412491e-02 -6.87145829e-01 -7.26421773e-01 -1.16412258e-02 -6.89608574e-01 -7.24085093e-01 -1.16412472e-02 -6.92126155e-01 -7.21669436e-01 -1.16412472e-02 -6.94634616e-01 -7.19270229e-01 -1.16412435e-02 -6.97151780e-01 -7.16828823e-01 -1.16412472e-02 -6.99637175e-01 -7.14400828e-01 -1.16412407e-02 -7.02121973e-01 -7.11961329e-01 -1.16412435e-02 -7.04613328e-01 -7.09496558e-01 -1.16412472e-02 -7.07134843e-01 -7.06958711e-01 -1.16412630e-02 -7.09631503e-01 -7.04484224e-01 -1.16412202e-02 -7.12001622e-01 -7.02081144e-01 -1.16412388e-02 -7.14443386e-01 -6.99591815e-01 -1.16412463e-02 -7.16867983e-01 -6.97110355e-01 -1.16412491e-02 -7.19303012e-01 -6.94600463e-01 -1.16412453e-02 -7.21773028e-01 -6.92015588e-01 -1.16412630e-02 -7.24214852e-01 -6.89478338e-01 -1.16412211e-02 -7.26593912e-01 -6.86957777e-01 -1.16412574e-02 -7.29006290e-01 -6.84402943e-01 -1.16412304e-02 -7.31308043e-01 -6.81938112e-01 -1.16412453e-02 -7.33740151e-01 -6.79321945e-01 -1.16412630e-02 -7.36121953e-01 -6.76746488e-01 -1.16412314e-02 -7.38403618e-01 -6.74251020e-01 -1.16412453e-02 -7.40786433e-01 -6.71636403e-01 -1.16412360e-02 -7.43115067e-01 -6.69054151e-01 -1.16412472e-02 -7.45493293e-01 -6.66400373e-01 -1.16412546e-02 -7.47828543e-01 -6.63788438e-01 -1.16412230e-02 -7.50070989e-01 -6.61247373e-01 -1.16412435e-02 -7.52374232e-01 -6.58626020e-01 -1.16412388e-02 -7.54720211e-01 -6.55932248e-01 -1.16412630e-02 -7.57066727e-01 -6.53227687e-01 -1.16412332e-02 -7.59296477e-01 -6.50640488e-01 -1.16412202e-02 -7.61489928e-01 -6.48062587e-01 -1.16412453e-02 -7.63758838e-01 -6.45394027e-01 -1.16412332e-02 -7.65976548e-01 -6.42757058e-01 -1.16412360e-02 -7.68284857e-01 -6.39991224e-01 -1.16412630e-02 -7.70542324e-01 -6.37283325e-01 -1.16412099e-02 -7.72679269e-01 -6.34685695e-01 -1.16412407e-02 -7.74887443e-01 -6.31984055e-01 -1.16412360e-02 -7.77086377e-01 -6.29278362e-01 -1.16412472e-02 -7.79348135e-01 -6.26473010e-01 -1.16412630e-02 -7.81546533e-01 -6.23739541e-01 -1.16412146e-02 -7.83693016e-01 -6.21028662e-01 -1.16412491e-02 -7.85874605e-01 -6.18275821e-01 -1.16412202e-02 -7.87950993e-01 -6.15622520e-01 -1.16412379e-02 -7.90163517e-01 -6.12772286e-01 -1.16412630e-02 -7.92327166e-01 -6.09984040e-01 -1.16412202e-02 -7.94426322e-01 -6.07238889e-01 -1.16412528e-02 -7.96548903e-01 -6.04461670e-01 -1.16412202e-02 -7.98594534e-01 -6.01749599e-01 -1.16412453e-02 -8.00757110e-01 -5.98860562e-01 -1.16412630e-02 -8.02857935e-01 -5.96054554e-01 -1.16412286e-02 -8.04869294e-01 -5.93331099e-01 -1.16412407e-02 -8.06929886e-01 -5.90524495e-01 -1.16412388e-02 -8.09028685e-01 -5.87642372e-01 -1.16412630e-02 -8.11145544e-01 -5.84717572e-01 -1.16412435e-02 -8.13128769e-01 -5.81968784e-01 -1.16412221e-02 -8.15082610e-01 -5.79219043e-01 -1.16412332e-02 -8.17091644e-01 -5.76386333e-01 -1.16412379e-02 -8.19112480e-01 -5.73506117e-01 -1.16412453e-02 -8.21150899e-01 -5.70576668e-01 -1.16412630e-02 -8.23164999e-01 -5.67682564e-01 -1.16412248e-02 -8.25076580e-01 -5.64892471e-01 -1.16412453e-02 -8.27044308e-01 -5.62007606e-01 -1.16412379e-02 -8.29001844e-01 -5.59119105e-01 -1.16412360e-02 -8.30998003e-01 -5.56139588e-01 -1.16412630e-02 -8.32946599e-01 -5.53226531e-01 -1.16412248e-02 -8.34853172e-01 -5.50337315e-01 -1.16412528e-02 -8.36774349e-01 -5.47420502e-01 -1.16412248e-02 -8.38631928e-01 -5.44567347e-01 -1.16412388e-02 -8.40537071e-01 -5.41622281e-01 -1.16412351e-02 -8.42422009e-01 -5.38685858e-01 -1.16412425e-02 -8.44331384e-01 -5.35682857e-01 -1.16412491e-02 -8.46213639e-01 -5.32718360e-01 -1.16412193e-02 -8.47998977e-01 -5.29862046e-01 -1.16412332e-02 -8.49892795e-01 -5.26818991e-01 -1.16412602e-02 -8.51739407e-01 -5.23833811e-01 -1.16412155e-02 -8.53500009e-01 -5.20961523e-01 -1.16412286e-02 -8.55301201e-01 -5.17990768e-01 -1.16412332e-02 -8.57153416e-01 -5.14919341e-01 -1.16412556e-02 -8.58964264e-01 -5.11901855e-01 -1.16412165e-02 -8.60696137e-01 -5.08978665e-01 -1.16412342e-02 -8.62521946e-01 -5.05873680e-01 -1.16412584e-02 -8.64289045e-01 -5.02861798e-01 -1.16412118e-02 -8.65974426e-01 -4.99947101e-01 -1.16412360e-02 -8.67715180e-01 -4.96915281e-01 -1.16412379e-02 -8.69443953e-01 -4.93883640e-01 -1.16412388e-02 -8.71165931e-01 -4.90846753e-01 -1.16412379e-02 -8.72865379e-01 -4.87812817e-01 -1.16412388e-02 -8.74564409e-01 -4.84757274e-01 -1.16412342e-02 -8.76295626e-01 -4.81621116e-01 -1.16412630e-02 -8.77993941e-01 -4.78531420e-01 -1.16412230e-02 -8.79608452e-01 -4.75544006e-01 -1.16412453e-02 -8.81262481e-01 -4.72473145e-01 -1.16412407e-02 -8.82945120e-01 -4.69316423e-01 -1.16412630e-02 -8.84626985e-01 -4.66144741e-01 -1.16412388e-02 -8.86216879e-01 -4.63122010e-01 -1.16412239e-02 -8.87781143e-01 -4.60112125e-01 -1.16412360e-02 -8.89372766e-01 -4.57025677e-01 -1.16412435e-02 -8.90989661e-01 -4.53859687e-01 -1.16412500e-02 -8.92576694e-01 -4.50743258e-01 -1.16412211e-02 -8.94099712e-01 -4.47703779e-01 -1.16412453e-02 -8.95659089e-01 -4.44579840e-01 -1.16412444e-02 -8.97202134e-01 -4.41457927e-01 -1.16412407e-02 -8.98744643e-01 -4.38309938e-01 -1.16412388e-02 -9.00295615e-01 -4.35111523e-01 -1.16412528e-02 -9.01831269e-01 -4.31927621e-01 -1.16412221e-02 -9.03284848e-01 -4.28874910e-01 -1.16412342e-02 -9.04769957e-01 -4.25729483e-01 -1.16412370e-02 -9.06257570e-01 -4.22555864e-01 -1.16412351e-02 -9.07746494e-01 -4.19344485e-01 -1.16412528e-02 -9.09205616e-01 -4.16174024e-01 -1.16412267e-02 -9.10620630e-01 -4.13068265e-01 -1.16412388e-02 -9.12048936e-01 -4.09906626e-01 -1.16412388e-02 -9.13479388e-01 -4.06707287e-01 -1.16412453e-02 -9.14931417e-01 -4.03423429e-01 -1.16412630e-02 -9.16338265e-01 -4.00237799e-01 -1.16412258e-02 -9.17719007e-01 -3.97039920e-01 -1.16412630e-02 -9.19106662e-01 -3.93825263e-01 -1.16412211e-02 -9.20433402e-01 -3.90712768e-01 -1.16412435e-02 -9.21830237e-01 -3.87399077e-01 -1.16412630e-02 -9.23196077e-01 -3.84146333e-01 -1.16412276e-02 -9.24491048e-01 -3.81012917e-01 -1.16412425e-02 -9.25804853e-01 -3.77814382e-01 -1.16412332e-02 -9.27115083e-01 -3.74581337e-01 -1.16412407e-02 -9.28453624e-01 -3.71245176e-01 -1.16412630e-02 -9.29759979e-01 -3.67982894e-01 -1.16412202e-02 -9.31009769e-01 -3.64795178e-01 -1.16412472e-02 -9.32271719e-01 -3.61549556e-01 -1.16412332e-02 -9.33556259e-01 -3.58228266e-01 -1.16412630e-02 -9.34838533e-01 -3.54859143e-01 -1.16412360e-02 -9.36027348e-01 -3.51707399e-01 -1.16412211e-02 -9.37217295e-01 -3.48516554e-01 -1.16412342e-02 -9.38464522e-01 -3.45147222e-01 -1.16412593e-02 -9.39677894e-01 -3.41865152e-01 -1.16412230e-02 -9.40852702e-01 -3.38592559e-01 -1.16412528e-02 -9.42046821e-01 -3.35285336e-01 -1.16412183e-02 -9.43195105e-01 -3.32016289e-01 -1.16412528e-02 -9.44357634e-01 -3.28712136e-01 -1.16412202e-02 -9.45467710e-01 -3.25499266e-01 -1.16412360e-02 -9.46585357e-01 -3.22225600e-01 -1.16412407e-02 -9.47719336e-01 -3.18882078e-01 -1.16412342e-02 -9.48848844e-01 -3.15493047e-01 -1.16412556e-02 -9.49950218e-01 -3.12179267e-01 -1.16412221e-02 -9.51006293e-01 -3.08939755e-01 -1.16412342e-02 -9.52099502e-01 -3.05544287e-01 -1.16412630e-02 -9.53174889e-01 -3.02188635e-01 -1.16412258e-02 -9.54185069e-01 -2.98980296e-01 -1.16412388e-02 -9.55226958e-01 -2.95630008e-01 -1.16412435e-02 -9.56271112e-01 -2.92229027e-01 -1.16412621e-02 -9.57295418e-01 -2.88867742e-01 -1.16412221e-02 -9.58266437e-01 -2.85620302e-01 -1.16412407e-02 -9.59282517e-01 -2.82185107e-01 -1.16412556e-02 -9.60269570e-01 -2.78831214e-01 -1.16412211e-02 -9.61228967e-01 -2.75482118e-01 -1.16412584e-02 -9.62196350e-01 -2.72108883e-01 -1.16412183e-02 -9.63113785e-01 -2.68830001e-01 -1.16412388e-02 -9.64044094e-01 -2.65470654e-01 -1.16412360e-02 -9.64965880e-01 -2.62110263e-01 -1.16412360e-02 -9.65868413e-01 -2.58753628e-01 -1.16412370e-02 -9.66786087e-01 -2.55298525e-01 -1.16412556e-02 -9.67678607e-01 -2.51917809e-01 -1.16412211e-02 -9.68521655e-01 -2.48637646e-01 -1.16412453e-02 -9.69384134e-01 -2.45247230e-01 -1.16412379e-02 -9.70250785e-01 -2.41788536e-01 -1.16412556e-02 -9.71118629e-01 -2.38304466e-01 -1.16412332e-02 -9.71930563e-01 -2.34986588e-01 -1.16412230e-02 -9.72720981e-01 -2.31678098e-01 -1.16412351e-02 -9.73518789e-01 -2.28298351e-01 -1.16412379e-02 -9.74317968e-01 -2.24841923e-01 -1.16412640e-02 -9.75125611e-01 -2.21334621e-01 -1.16412314e-02 -9.75881040e-01 -2.17992440e-01 -1.16412211e-02 -9.76614118e-01 -2.14667484e-01 -1.16412304e-02 -9.77357447e-01 -2.11256638e-01 -1.16412332e-02 -9.78086531e-01 -2.07856253e-01 -1.16412323e-02 -9.78805661e-01 -2.04447746e-01 -1.16412332e-02 -9.79512453e-01 -2.01033041e-01 -1.16412388e-02 -9.80203211e-01 -1.97639391e-01 -1.16412332e-02 -9.80886638e-01 -1.94213912e-01 -1.16412332e-02 -9.81557667e-01 -1.90794647e-01 -1.16412332e-02 -9.82234657e-01 -1.87257320e-01 -1.16412630e-02 -9.82888281e-01 -1.83826745e-01 -1.16412211e-02 -9.83501613e-01 -1.80491924e-01 -1.16412388e-02 -9.84131277e-01 -1.77060127e-01 -1.16412388e-02 -9.84749615e-01 -1.73594326e-01 -1.16412286e-02 -9.85356510e-01 -1.70064509e-01 -1.16412630e-02 -9.85953808e-01 -1.66618496e-01 -1.16412127e-02 -9.86505270e-01 -1.63291365e-01 -1.16412332e-02 -9.87066984e-01 -1.59857079e-01 -1.16412444e-02 -9.87625599e-01 -1.56381175e-01 -1.16412342e-02 -9.88174736e-01 -1.52839437e-01 -1.16412630e-02 -9.88710105e-01 -1.49371162e-01 -1.16412258e-02 -9.89219308e-01 -1.45928770e-01 -1.16412630e-02 -9.89727378e-01 -1.42475188e-01 -1.16412211e-02 -9.90202725e-01 -1.39123723e-01 -1.16412332e-02 -9.90692556e-01 -1.35576323e-01 -1.16412528e-02 -9.91170406e-01 -1.32081017e-01 -1.16412155e-02 -9.91605580e-01 -1.28748059e-01 -1.16412342e-02 -9.92051721e-01 -1.25275820e-01 -1.16412332e-02 -9.92478907e-01 -1.21829480e-01 -1.16412332e-02 -9.92904246e-01 -1.18286476e-01 -1.16412481e-02 -9.93318498e-01 -1.14801101e-01 -1.16412165e-02 -9.93707120e-01 -1.11384302e-01 -1.16412276e-02 -9.94090736e-01 -1.07878596e-01 -1.16412407e-02 -9.94469881e-01 -1.04406774e-01 -1.16411997e-02 -9.94820118e-01 -1.00963935e-01 -1.16412202e-02 -9.95175660e-01 -9.74687338e-02 -1.16411643e-02 -9.95509744e-01 -9.39889476e-02 -1.16411820e-02 -9.95831132e-01 -9.05376151e-02 -1.16411150e-02 -9.96131718e-01 -8.71674344e-02 -1.16410935e-02 -9.96428370e-01 -8.36954117e-02 -1.16410367e-02 -9.96691644e-01 -8.04685876e-02 -1.16410432e-02 -9.96953070e-01 -7.71145150e-02 -1.16410842e-02 -9.97213542e-01 -7.36807212e-02 -1.16410842e-02 -9.97552574e-01 -6.89393729e-02 -1.16410824e-02 -9.97825384e-01 -6.48762956e-02 -1.16410833e-02 0. 0. 0. 0. 0. 0. -9.98304188e-01 -5.70372306e-02 -1.16410842e-02 -9.98483121e-01 -5.38137481e-02 -1.16410833e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.97812986e-01 6.58372566e-02 -5.81191387e-03 -9.97522712e-01 7.01034665e-02 -5.81191387e-03 -9.97297645e-01 7.32369795e-02 -5.81191387e-03 -9.96968508e-01 7.75876492e-02 -5.81191387e-03 -9.96700943e-01 8.09514299e-02 -5.81191340e-03 -9.96358216e-01 8.50677118e-02 -5.81191340e-03 -9.96147037e-01 8.75018388e-02 -5.81191340e-03 -9.95883346e-01 9.04572234e-02 -5.81191340e-03 -9.95485485e-01 9.47322026e-02 -5.81191340e-03 -9.95184600e-01 9.78417173e-02 -5.81191387e-03 -9.94836569e-01 1.01314954e-01 -5.81191387e-03 -9.94409382e-01 1.05429195e-01 -5.81191387e-03 -9.94049311e-01 1.08778983e-01 -5.81191620e-03 -9.93712127e-01 1.11770578e-01 -5.81192458e-03 -9.93322074e-01 1.15191422e-01 -5.81192551e-03 -9.92930114e-01 1.18544407e-01 -5.81192132e-03 -9.92521644e-01 1.21947750e-01 -5.81187382e-03 -9.92085159e-01 1.25481546e-01 -5.81183843e-03 -9.91633713e-01 1.28995866e-01 -5.81183145e-03 -9.91187751e-01 1.32374316e-01 -5.81184030e-03 -9.90725756e-01 1.35811165e-01 -5.81182214e-03 -9.90231812e-01 1.39359951e-01 -5.81183238e-03 -9.89751756e-01 1.42722860e-01 -5.81183936e-03 -9.89245772e-01 1.46187887e-01 -5.81182074e-03 -9.88730967e-01 1.49626493e-01 -5.81183797e-03 -9.88219202e-01 1.52973056e-01 -5.81183098e-03 -9.87663507e-01 1.56525239e-01 -5.81181608e-03 -9.87092435e-01 1.60086557e-01 -5.81182772e-03 -9.86524701e-01 1.63551435e-01 -5.81182679e-03 -9.85949099e-01 1.66989923e-01 -5.81182633e-03 -9.85363543e-01 1.70397833e-01 -5.81182959e-03 -9.84764576e-01 1.73856571e-01 -5.81182446e-03 -9.84147191e-01 1.77311465e-01 -5.81182679e-03 -9.83515501e-01 1.80757701e-01 -5.81182539e-03 -9.82900083e-01 1.84080988e-01 -5.81183983e-03 -9.82279539e-01 1.87365294e-01 -5.81182726e-03 -9.81595099e-01 1.90910429e-01 -5.81181608e-03 -9.80903745e-01 1.94435880e-01 -5.81183052e-03 -9.80221033e-01 1.97854474e-01 -5.81182912e-03 -9.79521811e-01 2.01288953e-01 -5.81183005e-03 -9.78814840e-01 2.04689249e-01 -5.81183238e-03 -9.78108287e-01 2.08048671e-01 -5.81183890e-03 -9.77384746e-01 2.11428255e-01 -5.81181981e-03 -9.76607859e-01 2.14972183e-01 -5.81182959e-03 -9.75872815e-01 2.18292832e-01 -5.81183750e-03 -9.75104988e-01 2.21693590e-01 -5.81182074e-03 -9.74305809e-01 2.25186273e-01 -5.81182679e-03 -9.73512292e-01 2.28594691e-01 -5.81182959e-03 -9.72708941e-01 2.31990054e-01 -5.81183052e-03 -9.71914589e-01 2.35297918e-01 -5.81183843e-03 -9.71117914e-01 2.38558650e-01 -5.81183098e-03 -9.70251620e-01 2.42051035e-01 -5.81182214e-03 -9.69370902e-01 2.45555699e-01 -5.81182819e-03 -9.68505025e-01 2.48954937e-01 -5.81182819e-03 -9.67653692e-01 2.52239823e-01 -5.81183657e-03 -9.66779709e-01 2.55577743e-01 -5.81182307e-03 -9.65873897e-01 2.58977115e-01 -5.81183238e-03 -9.64956582e-01 2.62374163e-01 -5.81181981e-03 -9.64012444e-01 2.65814841e-01 -5.81182726e-03 -9.63103592e-01 2.69098014e-01 -5.81183517e-03 -9.62187946e-01 2.72349417e-01 -5.81182726e-03 -9.61205065e-01 2.75797218e-01 -5.81181608e-03 -9.60205793e-01 2.79255301e-01 -5.81182726e-03 -9.59234715e-01 2.82573134e-01 -5.81182912e-03 -9.58257020e-01 2.85875559e-01 -5.81183005e-03 -9.57249105e-01 2.89224923e-01 -5.81181888e-03 -9.56241488e-01 2.92541057e-01 -5.81183424e-03 -9.55221295e-01 2.95860797e-01 -5.81181608e-03 -9.54155445e-01 2.99277097e-01 -5.81183052e-03 -9.53126729e-01 3.02535385e-01 -5.81183098e-03 -9.52066898e-01 3.05858016e-01 -5.81181608e-03 -9.50970173e-01 3.09246749e-01 -5.81182586e-03 -9.49883223e-01 3.12568784e-01 -5.81182865e-03 -9.48789835e-01 3.15871626e-01 -5.81182959e-03 -9.47678149e-01 3.19200844e-01 -5.81183098e-03 -9.46579278e-01 3.22435796e-01 -5.81183424e-03 -9.45486605e-01 3.25633943e-01 -5.81182819e-03 -9.44316864e-01 3.29003602e-01 -5.81181794e-03 -9.43130851e-01 3.32388610e-01 -5.81183005e-03 -9.41991627e-01 3.35611373e-01 -5.81183517e-03 -9.40813780e-01 3.38894308e-01 -5.81181981e-03 -9.39595699e-01 3.42257828e-01 -5.81182819e-03 -9.38391447e-01 3.45527709e-01 -5.81182726e-03 -9.37180102e-01 3.48788589e-01 -5.81182865e-03 -9.35982466e-01 3.51988673e-01 -5.81183657e-03 -9.34792757e-01 3.55152309e-01 -5.81182865e-03 -9.33527589e-01 3.58489931e-01 -5.81182307e-03 -9.32222545e-01 3.61848086e-01 -5.81182726e-03 -9.30952191e-01 3.65111947e-01 -5.81182912e-03 -9.29666579e-01 3.68373394e-01 -5.81182819e-03 -9.28381920e-01 3.71599048e-01 -5.81182865e-03 -9.27078247e-01 3.74837697e-01 -5.81183145e-03 -9.25769627e-01 3.78061682e-01 -5.81183005e-03 -9.24440682e-01 3.81293356e-01 -5.81182865e-03 -9.23141599e-01 3.84429425e-01 -5.81183471e-03 -9.21833754e-01 3.87557358e-01 -5.81182865e-03 -9.20436502e-01 3.90862674e-01 -5.81181981e-03 -9.19031441e-01 3.94152850e-01 -5.81182726e-03 -9.17670965e-01 3.97310108e-01 -5.81183238e-03 -9.16296899e-01 4.00476933e-01 -5.81182307e-03 -9.14889574e-01 4.03675586e-01 -5.81183750e-03 -9.13502395e-01 4.06806916e-01 -5.81182586e-03 -9.12038267e-01 4.10080880e-01 -5.81182353e-03 -9.10574377e-01 4.13318634e-01 -5.81182912e-03 -9.09160137e-01 4.16414648e-01 -5.81183750e-03 -9.07716393e-01 4.19557959e-01 -5.81181981e-03 -9.06204939e-01 4.22809303e-01 -5.81182679e-03 -9.04729724e-01 4.25957441e-01 -5.81183191e-03 -9.03250039e-01 4.29089248e-01 -5.81183191e-03 -9.01747525e-01 4.32233393e-01 -5.81183191e-03 -9.00271833e-01 4.35309201e-01 -5.81183238e-03 -8.98728549e-01 4.38485891e-01 -5.81181981e-03 -8.97148252e-01 4.41706061e-01 -5.81182959e-03 -8.95607948e-01 4.44822371e-01 -5.81183005e-03 -8.94047558e-01 4.47947085e-01 -5.81182586e-03 -8.92481625e-01 4.51060832e-01 -5.81182959e-03 -8.90939891e-01 4.54098374e-01 -5.81183843e-03 -8.89394879e-01 4.57117558e-01 -5.81183052e-03 -8.87757719e-01 4.60288465e-01 -5.81182120e-03 -8.86105657e-01 4.63463515e-01 -5.81182865e-03 -8.84515584e-01 4.66489345e-01 -5.81183517e-03 -8.82896066e-01 4.69547570e-01 -5.81181934e-03 -8.81215453e-01 4.72693712e-01 -5.81182865e-03 -8.79551172e-01 4.75780517e-01 -5.81183005e-03 -8.77882719e-01 4.78858352e-01 -5.81182679e-03 -8.76204789e-01 4.81918603e-01 -5.81182726e-03 -8.74564707e-01 4.84881908e-01 -5.81183517e-03 -8.72880161e-01 4.87912774e-01 -5.81181981e-03 -8.71119082e-01 4.91053134e-01 -5.81182726e-03 -8.69396508e-01 4.94092435e-01 -5.81182865e-03 -8.67675543e-01 4.97111291e-01 -5.81183191e-03 -8.65945935e-01 5.00120521e-01 -5.81182865e-03 -8.64198625e-01 5.03130317e-01 -5.81183005e-03 -8.62430930e-01 5.06154895e-01 -5.81182912e-03 -8.60659301e-01 5.09161115e-01 -5.81183098e-03 -8.58919382e-01 5.12090027e-01 -5.81183936e-03 -8.57153833e-01 5.15042901e-01 -5.81182912e-03 -8.55305552e-01 5.18103480e-01 -5.81182633e-03 -8.53463590e-01 5.21133482e-01 -5.81183704e-03 -8.51645589e-01 5.24095058e-01 -5.81183005e-03 -8.49802375e-01 5.27083814e-01 -5.81183191e-03 -8.47959757e-01 5.30040562e-01 -5.81183424e-03 -8.46150041e-01 5.32925427e-01 -5.81183797e-03 -8.44275296e-01 5.35890937e-01 -5.81182307e-03 -8.42351973e-01 5.38909674e-01 -5.81182679e-03 -8.40519667e-01 5.41759133e-01 -5.81183843e-03 -8.38619709e-01 5.44696689e-01 -5.81182539e-03 -8.36694956e-01 5.47648132e-01 -5.81183238e-03 -8.34764004e-01 5.50588489e-01 -5.81182959e-03 -8.32820952e-01 5.53520203e-01 -5.81182726e-03 -8.30891967e-01 5.56415558e-01 -5.81182726e-03 -8.29000652e-01 5.59229076e-01 -5.81183843e-03 -8.27035904e-01 5.62131941e-01 -5.81181888e-03 -8.25009823e-01 5.65100431e-01 -5.81182912e-03 -8.23038101e-01 5.67969382e-01 -5.81182959e-03 -8.21101964e-01 5.70761144e-01 -5.81183843e-03 -8.19115520e-01 5.73608458e-01 -5.81181888e-03 -8.17064583e-01 5.76529980e-01 -5.81183098e-03 -8.15036476e-01 5.79390645e-01 -5.81181981e-03 -8.12987685e-01 5.82263947e-01 -5.81183052e-03 -8.11007440e-01 5.85014403e-01 -5.81183331e-03 -8.09006631e-01 5.87783217e-01 -5.81182074e-03 -8.06887746e-01 5.90685189e-01 -5.81182074e-03 -8.04774344e-01 5.93563318e-01 -5.81182772e-03 -8.02694857e-01 5.96371233e-01 -5.81182819e-03 -8.00598621e-01 5.99181533e-01 -5.81182819e-03 -7.98518240e-01 6.01953924e-01 -5.81182819e-03 -7.96406925e-01 6.04746163e-01 -5.81182772e-03 -7.94304013e-01 6.07503831e-01 -5.81183098e-03 -7.92190969e-01 6.10254526e-01 -5.81183191e-03 -7.90075958e-01 6.12989485e-01 -5.81184030e-03 -7.87946403e-01 6.15725040e-01 -5.81181608e-03 -7.85717607e-01 6.18569136e-01 -5.81183052e-03 -7.83558905e-01 6.21300042e-01 -5.81182865e-03 -7.81371117e-01 6.24052167e-01 -5.81183238e-03 -7.79193163e-01 6.26767874e-01 -5.81182912e-03 -7.77011156e-01 6.29471123e-01 -5.81182959e-03 -7.74888992e-01 6.32075906e-01 -5.81184030e-03 -7.72699296e-01 6.34756804e-01 -5.81182539e-03 -7.70388782e-01 6.37557328e-01 -5.81183843e-03 -7.68211961e-01 6.40176058e-01 -5.81184821e-03 -7.66000688e-01 6.42824292e-01 -5.81181981e-03 -7.63670623e-01 6.45590425e-01 -5.81183471e-03 -7.61441410e-01 6.48214877e-01 -5.81182912e-03 -7.59139538e-01 6.50911450e-01 -5.81182865e-03 -7.56886125e-01 6.53531611e-01 -5.81183797e-03 -7.54650235e-01 6.56111300e-01 -5.81183890e-03 -7.52325237e-01 6.58775389e-01 -5.81182307e-03 -7.49940753e-01 6.61488593e-01 -5.81182865e-03 -7.47620881e-01 6.64108872e-01 -5.81183098e-03 -7.45321929e-01 6.66689217e-01 -5.81183843e-03 -7.42974102e-01 6.69302762e-01 -5.81183517e-03 -7.40631938e-01 6.71897411e-01 -5.81183843e-03 -7.38293231e-01 6.74462080e-01 -5.81183238e-03 -7.35946298e-01 6.77026033e-01 -5.81183191e-03 -7.33635128e-01 6.79528117e-01 -5.81184309e-03 -7.31279731e-01 6.82061493e-01 -5.81182726e-03 -7.28778303e-01 6.84734344e-01 -5.81183424e-03 -7.26396501e-01 6.87259138e-01 -5.81183238e-03 -7.23982096e-01 6.89803720e-01 -5.81183238e-03 -7.21597314e-01 6.92292333e-01 -5.81184030e-03 -7.19158709e-01 6.94837451e-01 -5.81183238e-03 -7.16788948e-01 6.97281003e-01 -5.81183983e-03 -7.14364946e-01 6.99761689e-01 -5.81182679e-03 -7.11860597e-01 7.02310503e-01 -5.81183098e-03 -7.09454000e-01 7.04743028e-01 -5.81184030e-03 -7.06991374e-01 7.07196832e-01 -5.81182353e-03 -7.04463303e-01 7.09731877e-01 -5.81183005e-03 -7.01983333e-01 7.12185025e-01 -5.81183005e-03 -6.99484825e-01 7.14635730e-01 -5.81183052e-03 -6.96999967e-01 7.17062235e-01 -5.81183052e-03 -6.94559753e-01 7.19426453e-01 -5.81183424e-03 -6.92052782e-01 7.21828938e-01 -5.81182586e-03 -6.89457178e-01 7.24314034e-01 -5.81183657e-03 -6.86902225e-01 7.26733208e-01 -5.81183424e-03 -6.84362352e-01 7.29126155e-01 -5.81183145e-03 -6.81814492e-01 7.31506228e-01 -5.81183098e-03 -6.79258943e-01 7.33883679e-01 -5.81183238e-03 -6.76681578e-01 7.36263454e-01 -5.81182865e-03 -6.74112201e-01 7.38614202e-01 -5.81182819e-03 -6.71542764e-01 7.40953684e-01 -5.81182865e-03 -6.69020712e-01 7.43229151e-01 -5.81183843e-03 -6.66428685e-01 7.45555699e-01 -5.81181748e-03 -6.63744748e-01 7.47946918e-01 -5.81183052e-03 -6.61129415e-01 7.50258505e-01 -5.81182865e-03 -6.58504307e-01 7.52562344e-01 -5.81182819e-03 -6.55877411e-01 7.54853547e-01 -5.81182819e-03 -6.53289318e-01 7.57094145e-01 -5.81183424e-03 -6.50637984e-01 7.59373665e-01 -5.81182446e-03 -6.47923350e-01 7.61692286e-01 -5.81182912e-03 -6.45326376e-01 7.63893366e-01 -5.81183797e-03 -6.42672420e-01 7.66127288e-01 -5.81181888e-03 -6.39928997e-01 7.68421531e-01 -5.81182912e-03 -6.37251377e-01 7.70641506e-01 -5.81183191e-03 -6.34538293e-01 7.72879839e-01 -5.81182726e-03 -6.31900072e-01 7.75034070e-01 -5.81183797e-03 -6.29200995e-01 7.77231753e-01 -5.81181888e-03 -6.26403451e-01 7.79484808e-01 -5.81183098e-03 -6.23754501e-01 7.81605721e-01 -5.81183983e-03 -6.21028960e-01 7.83773720e-01 -5.81181981e-03 -6.18275881e-01 7.85946548e-01 -5.81184169e-03 -6.15561545e-01 7.88076460e-01 -5.81181981e-03 -6.12690389e-01 7.90310383e-01 -5.81183052e-03 -6.10003352e-01 7.92385697e-01 -5.81184123e-03 -6.07283115e-01 7.94472396e-01 -5.81181981e-03 -6.04467690e-01 7.96616018e-01 -5.81183843e-03 -6.01702094e-01 7.98709631e-01 -5.81182353e-03 -5.98895550e-01 8.00812781e-01 -5.81183936e-03 -5.96108258e-01 8.02890480e-01 -5.81182214e-03 -5.93196034e-01 8.05043519e-01 -5.81183098e-03 -5.90393066e-01 8.07102442e-01 -5.81182959e-03 -5.87658644e-01 8.09095323e-01 -5.81184169e-03 -5.84878743e-01 8.11106622e-01 -5.81182726e-03 -5.81954658e-01 8.13208520e-01 -5.81183052e-03 -5.79140663e-01 8.15215230e-01 -5.81184076e-03 -5.76314867e-01 8.17218125e-01 -5.81182214e-03 -5.73441565e-01 8.19232881e-01 -5.81183983e-03 -5.70594192e-01 8.21217775e-01 -5.81182539e-03 -5.67642629e-01 8.23263168e-01 -5.81183191e-03 -5.64751208e-01 8.25248480e-01 -5.81183191e-03 -5.61939120e-01 8.27162921e-01 -5.81183843e-03 -5.59133947e-01 8.29065800e-01 -5.81183191e-03 -5.56160748e-01 8.31060767e-01 -5.81182819e-03 -5.53261638e-01 8.32992077e-01 -5.81184775e-03 -5.50366998e-01 8.34910214e-01 -5.81182819e-03 -5.47438860e-01 8.36831510e-01 -5.81183983e-03 -5.44556499e-01 8.38711083e-01 -5.81182726e-03 -5.41547298e-01 8.40656281e-01 -5.81183424e-03 -5.38575172e-01 8.42563927e-01 -5.81183098e-03 -5.35624385e-01 8.44442248e-01 -5.81183191e-03 -5.32664418e-01 8.46313894e-01 -5.81183191e-03 -5.29712379e-01 8.48163664e-01 -5.81183564e-03 -5.26834607e-01 8.49954844e-01 -5.81184076e-03 -5.23862541e-01 8.51790428e-01 -5.81181981e-03 -5.20767272e-01 8.53687644e-01 -5.81182679e-03 -5.17775118e-01 8.55503321e-01 -5.81183424e-03 -5.14881015e-01 8.57247889e-01 -5.81184402e-03 -5.11891305e-01 8.59039485e-01 -5.81181888e-03 -5.08777142e-01 8.60885561e-01 -5.81183238e-03 -5.05868196e-01 8.62598062e-01 -5.81184169e-03 -5.02875030e-01 8.64347875e-01 -5.81182446e-03 -4.99822229e-01 8.66116107e-01 -5.81184123e-03 -4.96827066e-01 8.67837429e-01 -5.81182120e-03 -4.93713051e-01 8.69612217e-01 -5.81183657e-03 -4.90679562e-01 8.71329129e-01 -5.81184169e-03 -4.87744778e-01 8.72972608e-01 -5.81183331e-03 -4.84664947e-01 8.74686778e-01 -5.81182074e-03 -4.81540769e-01 8.76411319e-01 -5.81184030e-03 -4.78566945e-01 8.78039598e-01 -5.81184123e-03 -4.75486815e-01 8.79712164e-01 -5.81181236e-03 -4.72394854e-01 8.81374121e-01 -5.81183890e-03 -4.69350636e-01 8.83000970e-01 -5.81182726e-03 -4.66272354e-01 8.84630382e-01 -5.81183657e-03 -4.63169485e-01 8.86259079e-01 -5.81182586e-03 -4.60016400e-01 8.87897551e-01 -5.81183191e-03 -4.56902951e-01 8.89505148e-01 -5.81183750e-03 -4.53778297e-01 8.91103268e-01 -5.81183191e-03 -4.50729847e-01 8.92648637e-01 -5.81183890e-03 -4.47633773e-01 8.94205332e-01 -5.81182912e-03 -4.44460869e-01 8.95787060e-01 -5.81183191e-03 -4.41300869e-01 8.97346258e-01 -5.81183657e-03 -4.38229024e-01 8.98851633e-01 -5.81184169e-03 -4.35091674e-01 9.00375903e-01 -5.81182679e-03 -4.31876957e-01 9.01919305e-01 -5.81183331e-03 -4.28714991e-01 9.03426111e-01 -5.81183936e-03 -4.25569713e-01 9.04912949e-01 -5.81183797e-03 -4.22468066e-01 9.06365037e-01 -5.81184076e-03 -4.19314623e-01 9.07828987e-01 -5.81182679e-03 -4.16060954e-01 9.09323335e-01 -5.81183704e-03 -4.12888646e-01 9.10768569e-01 -5.81183936e-03 -4.09804314e-01 9.12161231e-01 -5.81184402e-03 -4.06644225e-01 9.13574994e-01 -5.81182726e-03 -4.03375268e-01 9.15022433e-01 -5.81183704e-03 -4.00229841e-01 9.16405201e-01 -5.81183936e-03 -3.97009760e-01 9.17802513e-01 -5.81183005e-03 -3.93809259e-01 9.19175684e-01 -5.81184868e-03 -3.90675902e-01 9.20515478e-01 -5.81183843e-03 -3.87454957e-01 9.21877444e-01 -5.81183424e-03 -3.84189755e-01 9.23242986e-01 -5.81182912e-03 -3.80862683e-01 9.24617589e-01 -5.81184216e-03 -3.77658814e-01 9.25932944e-01 -5.81183843e-03 -3.74424845e-01 9.27245677e-01 -5.81183238e-03 -3.71214896e-01 9.28534389e-01 -5.81183936e-03 -3.67972761e-01 9.29826438e-01 -5.81183052e-03 -3.64699781e-01 9.31113482e-01 -5.81183471e-03 -3.61420691e-01 9.32385981e-01 -5.81183704e-03 -3.58258516e-01 9.33616638e-01 -5.81184402e-03 -3.55010122e-01 9.34847057e-01 -5.81182865e-03 -3.51674974e-01 9.36100960e-01 -5.81183517e-03 -3.48397523e-01 9.37324166e-01 -5.81183797e-03 -3.45208198e-01 9.38506484e-01 -5.81184961e-03 -3.42013717e-01 9.39685285e-01 -5.81184542e-03 -3.38657975e-01 9.40896690e-01 -5.81182772e-03 -3.35339308e-01 9.42087770e-01 -5.81184635e-03 -3.32111686e-01 9.43229020e-01 -5.81183098e-03 -3.28800082e-01 9.44386542e-01 -5.81184449e-03 -3.25520217e-01 9.45524216e-01 -5.81183191e-03 -3.22170973e-01 9.46668744e-01 -5.81183890e-03 -3.18913847e-01 9.47773874e-01 -5.81184216e-03 -3.15566927e-01 9.48889911e-01 -5.81183843e-03 -3.12255830e-01 9.49984729e-01 -5.81184216e-03 -3.08923304e-01 9.51075971e-01 -5.81182679e-03 -3.05603057e-01 9.52147782e-01 -5.81184495e-03 -3.02285850e-01 9.53206718e-01 -5.81183005e-03 -2.98900992e-01 9.54271495e-01 -5.81184076e-03 -2.95542896e-01 9.55317020e-01 -5.81183936e-03 -2.92221934e-01 9.56338584e-01 -5.81183424e-03 -2.88898855e-01 9.57346916e-01 -5.81183843e-03 -2.85537422e-01 9.58355606e-01 -5.81183704e-03 -2.82205820e-01 9.59343910e-01 -5.81183145e-03 -2.78851986e-01 9.60323215e-01 -5.81183191e-03 -2.75565177e-01 9.61271644e-01 -5.81183843e-03 -2.72203803e-01 9.62229550e-01 -5.81182446e-03 -2.68792331e-01 9.63187099e-01 -5.81183424e-03 -2.65424013e-01 9.64119971e-01 -5.81183191e-03 -2.62133658e-01 9.65022624e-01 -5.81183843e-03 -2.58845270e-01 9.65908885e-01 -5.81183191e-03 -2.55404502e-01 9.66823697e-01 -5.81182586e-03 -2.52022058e-01 9.67710912e-01 -5.81183704e-03 -2.48639628e-01 9.68585730e-01 -5.81182633e-03 -2.45264515e-01 9.69443560e-01 -5.81184216e-03 -2.41872087e-01 9.70296800e-01 -5.81182539e-03 -2.38357723e-01 9.71167862e-01 -5.81183145e-03 -2.35071182e-01 9.71968293e-01 -5.81184123e-03 -2.31667757e-01 9.72786486e-01 -5.81182167e-03 -2.28284359e-01 9.73582745e-01 -5.81184495e-03 -2.24910885e-01 9.74369645e-01 -5.81182074e-03 -2.21479431e-01 9.75153565e-01 -5.81184030e-03 -2.18212843e-01 9.75891113e-01 -5.81183145e-03 -2.14670077e-01 9.76676464e-01 -5.81181888e-03 -2.11152524e-01 9.77442980e-01 -5.81183005e-03 -2.07747564e-01 9.78172123e-01 -5.81182959e-03 -2.04319999e-01 9.78893399e-01 -5.81183424e-03 -2.01037183e-01 9.79572237e-01 -5.81184588e-03 -1.97592035e-01 9.80273306e-01 -5.81181981e-03 -1.94059983e-01 9.80978787e-01 -5.81183005e-03 -1.90627068e-01 9.81651247e-01 -5.81183238e-03 -1.87188908e-01 9.82313573e-01 -5.81183052e-03 -1.83884934e-01 9.82934713e-01 -5.81184588e-03 -1.80460170e-01 9.83569682e-01 -5.81182912e-03 -1.77003503e-01 9.84203637e-01 -5.81184262e-03 -1.73572317e-01 9.84815836e-01 -5.81182633e-03 -1.70044661e-01 9.85424340e-01 -5.81183471e-03 -1.66692644e-01 9.85997856e-01 -5.81184402e-03 -1.63247988e-01 9.86574531e-01 -5.81182633e-03 -1.59801975e-01 9.87136722e-01 -5.81184216e-03 -1.56354904e-01 9.87690389e-01 -5.81182214e-03 -1.52791515e-01 9.88247812e-01 -5.81183238e-03 -1.49444446e-01 9.88758147e-01 -5.81183936e-03 -1.45987093e-01 9.89275813e-01 -5.81182353e-03 -1.42536819e-01 9.89776969e-01 -5.81183890e-03 -1.39087185e-01 9.90271091e-01 -5.81182074e-03 -1.35526597e-01 9.90764201e-01 -5.81183191e-03 -1.32125050e-01 9.91219878e-01 -5.81184123e-03 -1.28679007e-01 9.91675973e-01 -5.81182446e-03 -1.25140190e-01 9.92128491e-01 -5.81183191e-03 -1.21675521e-01 9.92558718e-01 -5.81183098e-03 -1.18308321e-01 9.92963612e-01 -5.81183890e-03 -1.14943415e-01 9.93359625e-01 -5.81183052e-03 -1.11364171e-01 9.93769109e-01 -5.81182446e-03 -1.07813574e-01 9.94158804e-01 -5.81183331e-03 -1.04320101e-01 9.94532704e-01 -5.81182912e-03 -1.00846499e-01 9.94889796e-01 -5.81183145e-03 -9.74408463e-02 9.95229423e-01 -5.81184123e-03 -9.39934701e-02 9.95562673e-01 -5.81182214e-03 -9.05332565e-02 9.95882988e-01 -5.81184123e-03 -8.70683491e-02 9.96193111e-01 -5.81181934e-03 -8.34767967e-02 9.96499181e-01 -5.81183191e-03 -8.01269785e-02 9.96774495e-01 -5.81184030e-03 -7.66404346e-02 9.97047484e-01 -5.81182493e-03 -7.31252283e-02 9.97311413e-01 -5.81183890e-03 -6.96430653e-02 9.97560441e-01 -5.81182074e-03 -6.60757422e-02 9.97804523e-01 -5.81183052e-03 -6.25561625e-02 9.98028457e-01 -5.81183238e-03 -5.90807796e-02 9.98242080e-01 -5.81182865e-03 -5.57058081e-02 9.98435974e-01 -5.81184030e-03 -5.22061139e-02 9.98624027e-01 -5.81182120e-03 -4.87172343e-02 9.98801112e-01 -5.81183750e-03 -4.53438908e-02 9.98960376e-01 -5.81182959e-03 -4.17608544e-02 9.99116123e-01 -5.81181888e-03 -3.81755792e-02 9.99259651e-01 -5.81182959e-03 -3.46731581e-02 9.99387383e-01 -5.81182865e-03 -3.11697181e-02 9.99503434e-01 -5.81182819e-03 -2.77791042e-02 9.99601901e-01 -5.81183843e-03 -2.44152304e-02 9.99693155e-01 -5.81182959e-03 -2.08068229e-02 9.99770164e-01 -5.81181981e-03 -1.71937626e-02 9.99845505e-01 -5.81183052e-03 -1.37208421e-02 9.99891400e-01 -5.81182912e-03 -1.03461295e-02 9.99931872e-01 -5.81184402e-03 -6.85838284e-03 9.99971211e-01 -5.81182726e-03 -3.33283376e-03 9.99987721e-01 -5.81183936e-03 1.19608914e-04 9.99990165e-01 -5.81182307e-03 3.71365249e-03 9.99988079e-01 -5.81183145e-03 7.12664193e-03 9.99966621e-01 -5.81183843e-03 1.06094303e-02 9.99932826e-01 -5.81182539e-03 1.41038075e-02 9.99886394e-01 -5.81183704e-03 1.75645780e-02 9.99840081e-01 -5.81182446e-03 2.10799556e-02 9.99766827e-01 -5.81184030e-03 2.44967025e-02 9.99690056e-01 -5.81182959e-03 2.80648656e-02 9.99596775e-01 -5.81181981e-03 3.16295214e-02 9.99488533e-01 -5.81183191e-03 3.51253413e-02 9.99372780e-01 -5.81183424e-03 3.85994241e-02 9.99244750e-01 -5.81183052e-03 4.19894531e-02 9.99108195e-01 -5.81183704e-03 4.55002114e-02 9.98952925e-01 -5.81182167e-03 4.90781479e-02 9.98784363e-01 -5.81183052e-03 5.25625758e-02 9.98604000e-01 -5.81183098e-03 5.60193174e-02 9.98419225e-01 -5.81183052e-03 5.94353490e-02 9.98221219e-01 -5.81183843e-03 6.29187450e-02 9.98005450e-01 -5.81182307e-03 6.64769486e-02 9.97775853e-01 -5.81182959e-03 6.99770749e-02 9.97535765e-01 -5.81182865e-03 7.34797865e-02 9.97285962e-01 -5.81183052e-03 7.68675804e-02 9.97029006e-01 -5.81183890e-03 8.03310797e-02 9.96756554e-01 -5.81182633e-03 8.38258043e-02 9.96468186e-01 -5.81184076e-03 8.72757360e-02 9.96173441e-01 -5.81182074e-03 9.08761099e-02 9.95851338e-01 -5.81182865e-03 9.42518488e-02 9.95535195e-01 -5.81184542e-03 9.77027416e-02 9.95205164e-01 -5.81182633e-03 1.01217665e-01 9.94853795e-01 -5.81184030e-03 1.04643248e-01 9.94499147e-01 -5.81181888e-03 1.08159497e-01 9.94121969e-01 -5.81183936e-03 1.11597285e-01 9.93743837e-01 -5.81181841e-03 1.15182742e-01 9.93331432e-01 -5.81183005e-03 1.18649274e-01 9.92923737e-01 -5.81182819e-03 1.22088566e-01 9.92507935e-01 -5.81182912e-03 1.25469640e-01 9.92087781e-01 -5.81183843e-03 1.28847018e-01 9.91652489e-01 -5.81183191e-03 1.32392585e-01 9.91186857e-01 -5.81182539e-03 1.35932982e-01 9.90707934e-01 -5.81182865e-03 1.39428630e-01 9.90221977e-01 -5.81183005e-03 1.42869696e-01 9.89729941e-01 -5.81182912e-03 1.46263406e-01 9.89233494e-01 -5.81184076e-03 1.49674505e-01 9.88723874e-01 -5.81182214e-03 1.53146327e-01 9.88193095e-01 -5.81183843e-03 1.56574041e-01 9.87655461e-01 -5.81181608e-03 1.60134628e-01 9.87084627e-01 -5.81182726e-03 1.63501367e-01 9.86532748e-01 -5.81183517e-03 1.66899294e-01 9.85964298e-01 -5.81181794e-03 1.70342758e-01 9.85372961e-01 -5.81183657e-03 1.73712030e-01 9.84788895e-01 -5.81183052e-03 1.77211836e-01 9.84165490e-01 -5.81182167e-03 1.80752859e-01 9.83516335e-01 -5.81183285e-03 1.84204355e-01 9.82877016e-01 -5.81182865e-03 1.87519640e-01 9.82249022e-01 -5.81183238e-03 1.90972000e-01 9.81584311e-01 -5.81181981e-03 1.94395885e-01 9.80912924e-01 -5.81183424e-03 1.97720438e-01 9.80246842e-01 -5.81182539e-03 2.01220632e-01 9.79536295e-01 -5.81181794e-03 2.04727426e-01 9.78807569e-01 -5.81182586e-03 2.08135203e-01 9.78090048e-01 -5.81182912e-03 2.11574584e-01 9.77351844e-01 -5.81182679e-03 2.14887157e-01 9.76625443e-01 -5.81183238e-03 2.18263164e-01 9.75881457e-01 -5.81181888e-03 2.21794128e-01 9.75080311e-01 -5.81183610e-03 2.25204855e-01 9.74301815e-01 -5.81183052e-03 2.28601560e-01 9.73511338e-01 -5.81182865e-03 2.31895596e-01 9.72730398e-01 -5.81183890e-03 2.35193700e-01 9.71941233e-01 -5.81182819e-03 2.38618687e-01 9.71102834e-01 -5.81182959e-03 2.42061257e-01 9.70249474e-01 -5.81181981e-03 2.45527968e-01 9.69378054e-01 -5.81182865e-03 2.48855144e-01 9.68530715e-01 -5.81183285e-03 2.52219498e-01 9.67660069e-01 -5.81181608e-03 2.55598515e-01 9.66773450e-01 -5.81183285e-03 2.58955330e-01 9.65879500e-01 -5.81181888e-03 2.62440741e-01 9.64938641e-01 -5.81182679e-03 2.65725106e-01 9.64037478e-01 -5.81183331e-03 2.69071788e-01 9.63109493e-01 -5.81182120e-03 2.72445858e-01 9.62159395e-01 -5.81183797e-03 2.75787145e-01 9.61207628e-01 -5.81181794e-03 2.79222786e-01 9.60214794e-01 -5.81183238e-03 2.82503098e-01 9.59255576e-01 -5.81183191e-03 2.85838932e-01 9.58268583e-01 -5.81181701e-03 2.89270043e-01 9.57234979e-01 -5.81182865e-03 2.92599052e-01 9.56225574e-01 -5.81183005e-03 2.95822889e-01 9.55232501e-01 -5.81183238e-03 2.99084574e-01 9.54216599e-01 -5.81182446e-03 3.02421540e-01 9.53164160e-01 -5.81182400e-03 3.05857271e-01 9.52065647e-01 -5.81181515e-03 3.09290320e-01 9.50956762e-01 -5.81182214e-03 3.12590003e-01 9.49877143e-01 -5.81182493e-03 3.15822214e-01 9.48807120e-01 -5.81183517e-03 3.19032907e-01 9.47734475e-01 -5.81182586e-03 3.22332919e-01 9.46614504e-01 -5.81182865e-03 3.25702250e-01 9.45462406e-01 -5.81181748e-03 3.29098552e-01 9.44283187e-01 -5.81182586e-03 3.32321733e-01 9.43155587e-01 -5.81183517e-03 3.35610986e-01 9.41991389e-01 -5.81181608e-03 3.38926256e-01 9.40799773e-01 -5.81183517e-03 3.42162162e-01 9.39631224e-01 -5.81181794e-03 3.45538497e-01 9.38387215e-01 -5.81182633e-03 3.48802000e-01 9.37175333e-01 -5.81182912e-03 3.52081448e-01 9.35949981e-01 -5.81182446e-03 3.55266362e-01 9.34748948e-01 -5.81183191e-03 3.58524948e-01 9.33514059e-01 -5.81181794e-03 3.61791044e-01 9.32243526e-01 -5.81183238e-03 3.64929646e-01 9.31023121e-01 -5.81182865e-03 3.68293405e-01 9.29699123e-01 -5.81181794e-03 3.71606231e-01 9.28378761e-01 -5.81182679e-03 3.74824077e-01 9.27082956e-01 -5.81182633e-03 3.78057122e-01 9.25770998e-01 -5.81182633e-03 3.81215513e-01 9.24472094e-01 -5.81183191e-03 3.84359211e-01 9.23171818e-01 -5.81182167e-03 3.87657255e-01 9.21791732e-01 -5.81181468e-03 3.90940130e-01 9.20402706e-01 -5.81183005e-03 3.94135118e-01 9.19038951e-01 -5.81182679e-03 3.97293925e-01 9.17678416e-01 -5.81183238e-03 4.00433123e-01 9.16316330e-01 -5.81182633e-03 4.03609991e-01 9.14919674e-01 -5.81182959e-03 4.06866968e-01 9.13475752e-01 -5.81182167e-03 4.10141379e-01 9.12010193e-01 -5.81183005e-03 4.13240105e-01 9.10609365e-01 -5.81183424e-03 4.16335970e-01 9.09197330e-01 -5.81182586e-03 4.19479936e-01 9.07750785e-01 -5.81182865e-03 4.22656357e-01 9.06277955e-01 -5.81183238e-03 4.25828606e-01 9.04790759e-01 -5.81183471e-03 4.28997368e-01 9.03293014e-01 -5.81182586e-03 4.32225227e-01 9.01752234e-01 -5.81182539e-03 4.35373843e-01 9.00240242e-01 -5.81182865e-03 4.38463807e-01 8.98739457e-01 -5.81183145e-03 4.41550404e-01 8.97224903e-01 -5.81182307e-03 4.44658577e-01 8.95689130e-01 -5.81182679e-03 4.47838664e-01 8.94103289e-01 -5.81181608e-03 4.51037139e-01 8.92494559e-01 -5.81182493e-03 4.54136550e-01 8.90920460e-01 -5.81182214e-03 4.57190007e-01 8.89356434e-01 -5.81183936e-03 4.60216790e-01 8.87792230e-01 -5.81183331e-03 4.63311285e-01 8.86186779e-01 -5.81182586e-03 4.66467530e-01 8.84527028e-01 -5.81181888e-03 4.69602078e-01 8.82867813e-01 -5.81182726e-03 4.72683311e-01 8.81221712e-01 -5.81182446e-03 4.75702167e-01 8.79593015e-01 -5.81183191e-03 4.78715539e-01 8.77961695e-01 -5.81182679e-03 4.81763989e-01 8.76289725e-01 -5.81182912e-03 4.84858841e-01 8.74578774e-01 -5.81181608e-03 4.87987548e-01 8.72838259e-01 -5.81182865e-03 4.91001159e-01 8.71147215e-01 -5.81183238e-03 4.93982643e-01 8.69459867e-01 -5.81181189e-03 4.97067869e-01 8.67700994e-01 -5.81183657e-03 5.00002861e-01 8.66011620e-01 -5.81182865e-03 5.03107250e-01 8.64213526e-01 -5.81181794e-03 5.06122887e-01 8.62449765e-01 -5.81183005e-03 5.09118795e-01 8.60684991e-01 -5.81181329e-03 5.12120485e-01 8.58900487e-01 -5.81183145e-03 5.15111685e-01 8.57112646e-01 -5.81181608e-03 5.18130720e-01 8.55288088e-01 -5.81182959e-03 5.21024883e-01 8.53530645e-01 -5.81182633e-03 5.24056077e-01 8.51671636e-01 -5.81181189e-03 5.27059019e-01 8.49817038e-01 -5.81182865e-03 5.30000091e-01 8.47986102e-01 -5.81181608e-03 5.32963872e-01 8.46125364e-01 -5.81183191e-03 5.35812080e-01 8.44325423e-01 -5.81182679e-03 5.38785636e-01 8.42431009e-01 -5.81181934e-03 5.41725516e-01 8.40542257e-01 -5.81182865e-03 5.44696271e-01 8.38621199e-01 -5.81181422e-03 5.47698140e-01 8.36664498e-01 -5.81182307e-03 5.50559342e-01 8.34784329e-01 -5.81183285e-03 5.53366065e-01 8.32922518e-01 -5.81183145e-03 5.56258380e-01 8.30995321e-01 -5.81184262e-03 5.59216917e-01 8.29008400e-01 -5.81185194e-03 5.62159300e-01 8.27012479e-01 -5.81186963e-03 5.64989746e-01 8.25079203e-01 -5.81189664e-03 5.67828774e-01 8.23126972e-01 -5.81191247e-03 5.70691526e-01 8.21142554e-01 -5.81192411e-03 5.73563397e-01 8.19139302e-01 -5.81192551e-03 5.76446176e-01 8.17107797e-01 -5.81192551e-03 5.79188406e-01 8.15168202e-01 -5.81192411e-03 5.82049370e-01 8.13131988e-01 -5.81192365e-03 5.84894180e-01 8.11089635e-01 -5.81191061e-03 5.87647557e-01 8.09096456e-01 -5.81190968e-03 5.90380669e-01 8.07103395e-01 -5.81191434e-03 5.93002677e-01 8.05179000e-01 -5.81191387e-03 5.96635044e-01 8.02491724e-01 -5.81191387e-03 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.29553342e-01 6.83899224e-01 -5.81191387e-03 7.31757700e-01 6.81540072e-01 -5.81191387e-03 7.33954549e-01 6.79173768e-01 -5.81191387e-03 7.36438751e-01 6.76479280e-01 -5.81191387e-03 0. 0. 0. 7.40674257e-01 6.71838224e-01 -5.81191340e-03 7.42874980e-01 6.69404507e-01 -5.81191387e-03 7.45676279e-01 6.66282475e-01 -5.81191340e-03 7.48063207e-01 6.63601577e-01 -5.81191434e-03 7.50234842e-01 6.61144853e-01 -5.81191434e-03 7.52638817e-01 6.58407927e-01 -5.81191201e-03 7.54927278e-01 6.55783415e-01 -5.81192039e-03 7.57188797e-01 6.53163314e-01 -5.81192458e-03 7.59363294e-01 6.50636494e-01 -5.81192551e-03 7.61553228e-01 6.48078203e-01 -5.81189245e-03 7.63817489e-01 6.45413280e-01 -5.81185939e-03 7.66131043e-01 6.42667711e-01 -5.81182865e-03 7.68338561e-01 6.40028358e-01 -5.81183238e-03 7.70507455e-01 6.37413800e-01 -5.81182586e-03 7.72811055e-01 6.34622991e-01 -5.81181888e-03 7.75063038e-01 6.31866634e-01 -5.81182446e-03 7.77263641e-01 6.29159212e-01 -5.81182493e-03 7.79386103e-01 6.26525223e-01 -5.81183191e-03 7.81519771e-01 6.23866260e-01 -5.81182679e-03 7.83672512e-01 6.21155262e-01 -5.81182819e-03 7.85903752e-01 6.18333459e-01 -5.81181096e-03 7.88128018e-01 6.15494370e-01 -5.81182214e-03 7.90258765e-01 6.12755358e-01 -5.81182633e-03 7.92335927e-01 6.10067129e-01 -5.81183238e-03 7.94418216e-01 6.07354343e-01 -5.81182539e-03 7.96535254e-01 6.04575932e-01 -5.81182633e-03 7.98690557e-01 6.01728141e-01 -5.81181608e-03 8.00845325e-01 5.98851085e-01 -5.81182633e-03 8.02880943e-01 5.96120596e-01 -5.81183238e-03 8.04893553e-01 5.93399704e-01 -5.81182679e-03 8.06953728e-01 5.90593874e-01 -5.81182446e-03 8.09073746e-01 5.87690353e-01 -5.81181562e-03 8.11121166e-01 5.84857345e-01 -5.81183098e-03 8.13097358e-01 5.82110345e-01 -5.81182353e-03 8.15180779e-01 5.79190075e-01 -5.81181515e-03 8.17210734e-01 5.76322973e-01 -5.81183005e-03 8.19220662e-01 5.73461056e-01 -5.81181096e-03 8.21209311e-01 5.70606887e-01 -5.81183657e-03 8.23137879e-01 5.67825198e-01 -5.81182214e-03 8.25157821e-01 5.64885914e-01 -5.81181608e-03 8.27181637e-01 5.61916292e-01 -5.81182307e-03 8.29145193e-01 5.59015334e-01 -5.81182353e-03 8.31040800e-01 5.56191325e-01 -5.81183191e-03 8.32911193e-01 5.53386331e-01 -5.81182679e-03 8.34848940e-01 5.50459683e-01 -5.81182586e-03 8.36822569e-01 5.47455728e-01 -5.81181608e-03 8.38780642e-01 5.44449985e-01 -5.81182726e-03 8.40617299e-01 5.41607320e-01 -5.81183610e-03 8.42427433e-01 5.38788795e-01 -5.81182959e-03 8.44317734e-01 5.35821497e-01 -5.81183052e-03 8.46196651e-01 5.32854557e-01 -5.81182493e-03 8.48106444e-01 5.29807091e-01 -5.81181096e-03 8.50011468e-01 5.26746094e-01 -5.81182539e-03 8.51793051e-01 5.23854673e-01 -5.81183191e-03 8.53564084e-01 5.20972371e-01 -5.81181981e-03 8.55365396e-01 5.18003881e-01 -5.81182633e-03 8.57173383e-01 5.15007496e-01 -5.81182446e-03 8.58965695e-01 5.12012541e-01 -5.81182074e-03 8.60757172e-01 5.08994758e-01 -5.81181981e-03 8.62528145e-01 5.05989850e-01 -5.81182912e-03 8.64280820e-01 5.02989471e-01 -5.81182214e-03 8.66065681e-01 4.99910355e-01 -5.81181096e-03 8.67819786e-01 4.96856779e-01 -5.81183517e-03 8.69497478e-01 4.93917048e-01 -5.81181701e-03 8.71290803e-01 4.90750611e-01 -5.81181189e-03 8.73044312e-01 4.87618655e-01 -5.81182027e-03 8.74737501e-01 4.84572172e-01 -5.81182819e-03 8.76369417e-01 4.81619149e-01 -5.81183005e-03 8.78010988e-01 4.78621989e-01 -5.81182446e-03 8.79675984e-01 4.75551605e-01 -5.81182167e-03 8.81338537e-01 4.72464889e-01 -5.81182633e-03 8.83016407e-01 4.69320327e-01 -5.81181096e-03 8.84695828e-01 4.66148347e-01 -5.81182167e-03 8.86275709e-01 4.63136792e-01 -5.81183098e-03 8.87835503e-01 4.60138381e-01 -5.81182353e-03 8.89449298e-01 4.57013071e-01 -5.81182214e-03 8.91084969e-01 4.53812391e-01 -5.81181608e-03 8.92693579e-01 4.50640947e-01 -5.81182446e-03 8.94225538e-01 4.47591841e-01 -5.81183238e-03 8.95734549e-01 4.44566607e-01 -5.81182446e-03 8.97273302e-01 4.41452563e-01 -5.81182539e-03 8.98851454e-01 4.38233167e-01 -5.81181608e-03 9.00383949e-01 4.35075879e-01 -5.81183750e-03 9.01851952e-01 4.32017982e-01 -5.81182307e-03 9.03384924e-01 4.28804308e-01 -5.81181655e-03 9.04885590e-01 4.25627977e-01 -5.81183145e-03 9.06357825e-01 4.22489166e-01 -5.81181655e-03 9.07837749e-01 4.19294149e-01 -5.81183191e-03 9.09253120e-01 4.16216135e-01 -5.81182772e-03 9.10730660e-01 4.12974924e-01 -5.81181562e-03 9.12218571e-01 4.09680307e-01 -5.81182307e-03 9.13627028e-01 4.06527072e-01 -5.81183052e-03 9.15025890e-01 4.03364182e-01 -5.81183610e-03 9.16388690e-01 4.00267094e-01 -5.81182819e-03 9.17773664e-01 3.97076994e-01 -5.81182539e-03 9.19149756e-01 3.93875271e-01 -5.81182633e-03 9.20556128e-01 3.90581459e-01 -5.81181888e-03 9.21921253e-01 3.87347549e-01 -5.81183331e-03 9.23224330e-01 3.84234965e-01 -5.81182400e-03 9.24559712e-01 3.81006747e-01 -5.81182353e-03 9.25885856e-01 3.77776980e-01 -5.81182679e-03 9.27229643e-01 3.74466091e-01 -5.81181701e-03 9.28573668e-01 3.71121436e-01 -5.81182633e-03 9.29830849e-01 3.67960781e-01 -5.81183797e-03 9.31068957e-01 3.64819527e-01 -5.81182446e-03 9.32331800e-01 3.61559480e-01 -5.81182586e-03 9.33626592e-01 3.58228415e-01 -5.81181608e-03 9.34880733e-01 3.54918540e-01 -5.81183052e-03 9.36077297e-01 3.51741076e-01 -5.81182726e-03 9.37325060e-01 3.48402232e-01 -5.81181888e-03 9.38567698e-01 3.45050365e-01 -5.81182726e-03 9.39768016e-01 3.41791660e-01 -5.81182586e-03 9.40918565e-01 3.38593483e-01 -5.81183191e-03 9.42067981e-01 3.35395724e-01 -5.81182586e-03 9.43259478e-01 3.32027525e-01 -5.81181608e-03 9.44455385e-01 3.28605980e-01 -5.81182353e-03 9.45606172e-01 3.25287044e-01 -5.81182633e-03 9.46696460e-01 3.22090298e-01 -5.81183378e-03 9.47773218e-01 3.18915874e-01 -5.81183145e-03 9.48889196e-01 3.15576047e-01 -5.81182400e-03 9.49991524e-01 3.12241882e-01 -5.81182586e-03 9.51091290e-01 3.08881938e-01 -5.81181608e-03 9.52201962e-01 3.05436432e-01 -5.81181981e-03 9.53233778e-01 3.02198857e-01 -5.81183191e-03 9.54258382e-01 2.98954189e-01 -5.81182400e-03 9.55291808e-01 2.95628011e-01 -5.81182865e-03 9.56340432e-01 2.92220980e-01 -5.81181282e-03 9.57379639e-01 2.88791746e-01 -5.81182446e-03 9.58360910e-01 2.85523355e-01 -5.81183052e-03 9.59327281e-01 2.82262623e-01 -5.81182493e-03 9.60307062e-01 2.78907478e-01 -5.81182726e-03 9.61282492e-01 2.75525987e-01 -5.81181934e-03 9.62247193e-01 2.72142529e-01 -5.81183005e-03 9.63174284e-01 2.68842548e-01 -5.81182726e-03 9.64105666e-01 2.65478253e-01 -5.81182633e-03 9.65024590e-01 2.62129158e-01 -5.81182912e-03 9.65945721e-01 2.58703679e-01 -5.81182214e-03 9.66860175e-01 2.55266070e-01 -5.81183238e-03 9.67716157e-01 2.52003700e-01 -5.81183005e-03 9.68586028e-01 2.48637721e-01 -5.81182679e-03 9.69473481e-01 2.45146483e-01 -5.81182633e-03 9.70335484e-01 2.41715208e-01 -5.81182959e-03 9.71170902e-01 2.38345802e-01 -5.81183052e-03 9.71983194e-01 2.35011637e-01 -5.81183191e-03 9.72777367e-01 2.31701717e-01 -5.81182865e-03 9.73574758e-01 2.28324920e-01 -5.81183145e-03 9.74393189e-01 2.24805385e-01 -5.81181794e-03 9.75173354e-01 2.21390322e-01 -5.81183843e-03 9.75919127e-01 2.18089476e-01 -5.81183052e-03 9.76678014e-01 2.14651972e-01 -5.81183331e-03 9.77430046e-01 2.11207628e-01 -5.81182539e-03 9.78152275e-01 2.07837716e-01 -5.81183750e-03 9.78884935e-01 2.04365849e-01 -5.81181981e-03 9.79591310e-01 2.00948685e-01 -5.81183564e-03 9.80283797e-01 1.97544038e-01 -5.81182074e-03 9.80983675e-01 1.94034994e-01 -5.81182819e-03 9.81664777e-01 1.90565065e-01 -5.81182539e-03 9.82301831e-01 1.87241837e-01 -5.81183238e-03 9.82932687e-01 1.83909610e-01 -5.81182912e-03 9.83580172e-01 1.80403963e-01 -5.81182586e-03 9.84224141e-01 1.76890910e-01 -5.81183098e-03 9.84835505e-01 1.73454821e-01 -5.81183098e-03 9.85422194e-01 1.70053601e-01 -5.81184262e-03 9.85991895e-01 1.66739434e-01 -5.81183005e-03 9.86566126e-01 1.63293123e-01 -5.81182819e-03 9.87134457e-01 1.59826145e-01 -5.81183052e-03 9.87695754e-01 1.56326458e-01 -5.81182260e-03 9.88246441e-01 1.52798742e-01 -5.81183098e-03 9.88761544e-01 1.49420783e-01 -5.81183843e-03 9.89264429e-01 1.46059617e-01 -5.81183191e-03 9.89765584e-01 1.42623663e-01 -5.81182865e-03 9.90272582e-01 1.39073744e-01 -5.81182819e-03 9.90762293e-01 1.35538429e-01 -5.81183238e-03 9.91216779e-01 1.32155612e-01 -5.81183750e-03 9.91664350e-01 1.28765687e-01 -5.81183191e-03 9.92105007e-01 1.25330806e-01 -5.81183191e-03 9.92532909e-01 1.21886745e-01 -5.81183564e-03 9.92956340e-01 1.18377469e-01 -5.81183238e-03 9.93364513e-01 1.14907034e-01 -5.81182586e-03 9.93771076e-01 1.11347377e-01 -5.81182539e-03 9.94151056e-01 1.07894927e-01 -5.81183983e-03 9.94518876e-01 1.04453370e-01 -5.81182493e-03 9.94880915e-01 1.00937068e-01 -5.81184262e-03 9.95217204e-01 9.75710526e-02 -5.81183098e-03 9.95562136e-01 9.40157324e-02 -5.81182446e-03 9.95888889e-01 9.04592127e-02 -5.81183238e-03 9.96198595e-01 8.69868472e-02 -5.81183238e-03 9.96490598e-01 8.35676566e-02 -5.81184169e-03 9.96771395e-01 8.01605433e-02 -5.81183424e-03 9.97041941e-01 7.66985267e-02 -5.81183098e-03 9.97311354e-01 7.31318444e-02 -5.81182307e-03 9.97564554e-01 6.95676878e-02 -5.81182959e-03 9.97794271e-01 6.61955401e-02 -5.81183936e-03 9.98014331e-01 6.28052577e-02 -5.81182679e-03 9.98228729e-01 5.92914782e-02 -5.81182865e-03 9.98431683e-01 5.58129475e-02 -5.81182865e-03 9.98622358e-01 5.22548184e-02 -5.81182307e-03 9.98805642e-01 4.86611277e-02 -5.81183005e-03 9.98961151e-01 4.52852771e-02 -5.81184076e-03 9.99112308e-01 4.18860056e-02 -5.81183005e-03 9.99252081e-01 3.83999199e-02 -5.81182726e-03 9.99383450e-01 3.47933769e-02 -5.81181888e-03 9.99499381e-01 3.13003585e-02 -5.81183704e-03 9.99600887e-01 2.79146228e-02 -5.81183005e-03 9.99692917e-01 2.44235676e-02 -5.81183005e-03 9.99769032e-01 2.09129546e-02 -5.81182959e-03 9.99840558e-01 1.74434334e-02 -5.81183238e-03 9.99887884e-01 1.39643680e-02 -5.81183424e-03 9.99933600e-01 1.04447231e-02 -5.81183238e-03 9.99973297e-01 6.87463256e-03 -5.81182214e-03 9.99988496e-01 3.27372761e-03 -5.81183098e-03 9.99989748e-01 -2.16409404e-04 -5.81183052e-03 9.99987602e-01 -3.71119194e-03 -5.81183750e-03 9.99966919e-01 -7.08871754e-03 -5.81184309e-03 9.99933839e-01 -1.04847755e-02 -5.81183098e-03 9.99887586e-01 -1.39751192e-02 -5.81183657e-03 9.99837995e-01 -1.75943077e-02 -5.81182772e-03 9.99763131e-01 -2.11890079e-02 -5.81182865e-03 9.99686539e-01 -2.46525072e-02 -5.81183005e-03 9.99595761e-01 -2.80209966e-02 -5.81183983e-03 9.99492407e-01 -3.15178633e-02 -5.81181794e-03 9.99375522e-01 -3.50461453e-02 -5.81183517e-03 9.99250412e-01 -3.84346172e-02 -5.81182539e-03 9.99112725e-01 -4.19151857e-02 -5.81182726e-03 9.98954952e-01 -4.54798266e-02 -5.81181608e-03 9.98784482e-01 -4.90801223e-02 -5.81182633e-03 9.98606503e-01 -5.25446534e-02 -5.81182726e-03 9.98420715e-01 -5.59627041e-02 -5.81183750e-03 9.98226702e-01 -5.93390986e-02 -5.81182959e-03 9.98012066e-01 -6.28197566e-02 -5.81182912e-03 9.97782290e-01 -6.63966089e-02 -5.81181888e-03 9.97535706e-01 -6.99777380e-02 -5.81183098e-03 9.97285903e-01 -7.34928325e-02 -5.81182959e-03 9.97028410e-01 -7.68748373e-02 -5.81183843e-03 9.96763527e-01 -8.02508444e-02 -5.81182912e-03 9.96480167e-01 -8.37029591e-02 -5.81183098e-03 9.96170402e-01 -8.73152614e-02 -5.81182539e-03 9.95856047e-01 -9.08061042e-02 -5.81184030e-03 9.95550215e-01 -9.41182226e-02 -5.81182959e-03 9.95211065e-01 -9.76470336e-02 -5.81183517e-03 9.94864583e-01 -1.01113953e-01 -5.81182865e-03 9.94505882e-01 -1.04579762e-01 -5.81182819e-03 9.94125962e-01 -1.08126201e-01 -5.81182074e-03 9.93743658e-01 -1.11591905e-01 -5.81183750e-03 9.93357122e-01 -1.14973508e-01 -5.81182865e-03 9.92942691e-01 -1.18501507e-01 -5.81182167e-03 9.92519498e-01 -1.21996246e-01 -5.81183843e-03 9.92089391e-01 -1.25461772e-01 -5.81181515e-03 9.91629899e-01 -1.29021689e-01 -5.81183098e-03 9.91189063e-01 -1.32368609e-01 -5.81183657e-03 9.90720630e-01 -1.35840565e-01 -5.81182446e-03 9.90230083e-01 -1.39375389e-01 -5.81183517e-03 9.89743531e-01 -1.42773271e-01 -5.81183843e-03 9.89243269e-01 -1.46200553e-01 -5.81181888e-03 9.88723695e-01 -1.49668992e-01 -5.81183750e-03 9.88198221e-01 -1.53111070e-01 -5.81182353e-03 9.87653732e-01 -1.56575397e-01 -5.81184030e-03 9.87105787e-01 -1.60001308e-01 -5.81183005e-03 9.86541927e-01 -1.63441777e-01 -5.81183936e-03 9.85961020e-01 -1.66914538e-01 -5.81182679e-03 9.85354722e-01 -1.70443639e-01 -5.81183098e-03 9.84762311e-01 -1.73864603e-01 -5.81182865e-03 9.84165490e-01 -1.77208096e-01 -5.81183517e-03 9.83550727e-01 -1.80559292e-01 -5.81182772e-03 9.82918680e-01 -1.83985665e-01 -5.81182912e-03 9.82249618e-01 -1.87516898e-01 -5.81181608e-03 9.81577218e-01 -1.91010565e-01 -5.81183098e-03 9.80906844e-01 -1.94422901e-01 -5.81182726e-03 9.80235457e-01 -1.97776049e-01 -5.81183424e-03 9.79555964e-01 -2.01117173e-01 -5.81183238e-03 9.78840113e-01 -2.04569921e-01 -5.81183098e-03 9.78107870e-01 -2.08050698e-01 -5.81181608e-03 9.77381587e-01 -2.11441427e-01 -5.81183704e-03 9.76640880e-01 -2.14826837e-01 -5.81182353e-03 9.75874484e-01 -2.18284920e-01 -5.81183983e-03 9.75108445e-01 -2.21678913e-01 -5.81182772e-03 9.74338830e-01 -2.25043520e-01 -5.81183797e-03 9.73536074e-01 -2.28496596e-01 -5.81182539e-03 9.72726703e-01 -2.31913447e-01 -5.81183704e-03 9.71948326e-01 -2.35158607e-01 -5.81182679e-03 9.71099973e-01 -2.38631472e-01 -5.81181888e-03 9.70254600e-01 -2.42036089e-01 -5.81183610e-03 9.69401360e-01 -2.45434210e-01 -5.81181981e-03 9.68525231e-01 -2.48873845e-01 -5.81183238e-03 9.67677653e-01 -2.52145678e-01 -5.81183145e-03 9.66794252e-01 -2.55522370e-01 -5.81182353e-03 9.65881824e-01 -2.58945823e-01 -5.81183704e-03 9.65006232e-01 -2.62189239e-01 -5.81183098e-03 9.64062035e-01 -2.65632242e-01 -5.81181981e-03 9.63113666e-01 -2.69056678e-01 -5.81184262e-03 9.62187052e-01 -2.72352248e-01 -5.81182400e-03 9.61195767e-01 -2.75830150e-01 -5.81182912e-03 9.60247993e-01 -2.79105544e-01 -5.81184030e-03 9.59293067e-01 -2.82372922e-01 -5.81183098e-03 9.58288252e-01 -2.85772443e-01 -5.81181888e-03 9.57248867e-01 -2.89223820e-01 -5.81182726e-03 9.56222713e-01 -2.92604983e-01 -5.81182865e-03 9.55223620e-01 -2.95850486e-01 -5.81183843e-03 9.54222560e-01 -2.99062192e-01 -5.81182865e-03 9.53173101e-01 -3.02391142e-01 -5.81183005e-03 9.52087522e-01 -3.05793881e-01 -5.81182120e-03 9.50984716e-01 -3.09203953e-01 -5.81182726e-03 9.49906051e-01 -3.12500030e-01 -5.81183052e-03 9.48821187e-01 -3.15781206e-01 -5.81183657e-03 9.47749913e-01 -3.18983048e-01 -5.81183285e-03 9.46633279e-01 -3.22280735e-01 -5.81183191e-03 9.45476770e-01 -3.25660288e-01 -5.81182633e-03 9.44323897e-01 -3.28980476e-01 -5.81184076e-03 9.43174899e-01 -3.32265913e-01 -5.81182539e-03 9.42018092e-01 -3.35533798e-01 -5.81183657e-03 9.40837562e-01 -3.38826716e-01 -5.81181934e-03 9.39651608e-01 -3.42106611e-01 -5.81183890e-03 9.38438892e-01 -3.45398784e-01 -5.81182539e-03 9.37226415e-01 -3.48660737e-01 -5.81183657e-03 9.36035156e-01 -3.51850450e-01 -5.81183098e-03 9.34803009e-01 -3.55121970e-01 -5.81183191e-03 9.33531165e-01 -3.58482540e-01 -5.81181981e-03 9.32253361e-01 -3.61763149e-01 -5.81183517e-03 9.31000650e-01 -3.64992440e-01 -5.81181981e-03 9.29716349e-01 -3.68245870e-01 -5.81183983e-03 9.28434610e-01 -3.71467978e-01 -5.81181981e-03 9.27128434e-01 -3.74713153e-01 -5.81183750e-03 9.25856769e-01 -3.77845675e-01 -5.81182912e-03 9.24501240e-01 -3.81148577e-01 -5.81181794e-03 9.23150182e-01 -3.84409100e-01 -5.81183704e-03 9.21804249e-01 -3.87628198e-01 -5.81181888e-03 9.20398414e-01 -3.90948743e-01 -5.81182959e-03 9.19064879e-01 -3.94071370e-01 -5.81183843e-03 9.17732656e-01 -3.97168666e-01 -5.81183098e-03 9.16309416e-01 -4.00447369e-01 -5.81182446e-03 9.14866209e-01 -4.03731257e-01 -5.81183098e-03 9.13457572e-01 -4.06906843e-01 -5.81183052e-03 9.12042618e-01 -4.10069853e-01 -5.81183936e-03 9.10656273e-01 -4.13134605e-01 -5.81183145e-03 9.09226358e-01 -4.16269422e-01 -5.81183657e-03 9.07716453e-01 -4.19555753e-01 -5.81182633e-03 9.06217158e-01 -4.22785968e-01 -5.81183843e-03 9.04736698e-01 -4.25942183e-01 -5.81183424e-03 9.03257906e-01 -4.29071993e-01 -5.81183843e-03 9.01803792e-01 -4.32116568e-01 -5.81183052e-03 9.00302708e-01 -4.35244501e-01 -5.81183238e-03 8.98717463e-01 -4.38508332e-01 -5.81182260e-03 8.97172153e-01 -4.41656798e-01 -5.81183378e-03 8.95627677e-01 -4.44780141e-01 -5.81183191e-03 8.94088626e-01 -4.47864771e-01 -5.81183843e-03 8.92558157e-01 -4.50910568e-01 -5.81183750e-03 8.90993893e-01 -4.53992039e-01 -5.81183564e-03 8.89346421e-01 -4.57212508e-01 -5.81181981e-03 8.87737751e-01 -4.60320860e-01 -5.81184356e-03 8.86175454e-01 -4.63331908e-01 -5.81182865e-03 8.84568214e-01 -4.66388226e-01 -5.81183238e-03 8.82865191e-01 -4.69606668e-01 -5.81182074e-03 8.81224275e-01 -4.72675979e-01 -5.81184262e-03 8.79594445e-01 -4.75703537e-01 -5.81182865e-03 8.77909303e-01 -4.78810340e-01 -5.81183843e-03 8.76283288e-01 -4.81772810e-01 -5.81183098e-03 8.74591649e-01 -4.84835297e-01 -5.81182819e-03 8.72860789e-01 -4.87946033e-01 -5.81182726e-03 8.71136606e-01 -4.91019845e-01 -5.81183843e-03 8.69434595e-01 -4.94024664e-01 -5.81182912e-03 8.67698371e-01 -4.97072190e-01 -5.81184309e-03 8.65961373e-01 -5.00092506e-01 -5.81182353e-03 8.64173532e-01 -5.03174007e-01 -5.81183052e-03 8.62453461e-01 -5.06117344e-01 -5.81183238e-03 8.60713422e-01 -5.09069264e-01 -5.81183145e-03 8.58940542e-01 -5.12052178e-01 -5.81183238e-03 8.57101500e-01 -5.15129685e-01 -5.81182586e-03 8.55242908e-01 -5.18206120e-01 -5.81182633e-03 8.53459001e-01 -5.21140754e-01 -5.81183843e-03 8.51695657e-01 -5.24014413e-01 -5.81182865e-03 8.49858344e-01 -5.26993394e-01 -5.81182865e-03 8.47969592e-01 -5.30026853e-01 -5.81181794e-03 8.46066773e-01 -5.33057153e-01 -5.81182865e-03 8.44205439e-01 -5.35999298e-01 -5.81182959e-03 8.42393875e-01 -5.38840413e-01 -5.81183564e-03 8.40501666e-01 -5.41791081e-01 -5.81181794e-03 8.38543832e-01 -5.44813931e-01 -5.81183145e-03 8.36635947e-01 -5.47737241e-01 -5.81182726e-03 8.34717393e-01 -5.50659239e-01 -5.81183145e-03 8.32837403e-01 -5.53493679e-01 -5.81183890e-03 8.30987811e-01 -5.56271374e-01 -5.81183424e-03 8.29010189e-01 -5.59217632e-01 -5.81182865e-03 8.27000558e-01 -5.62183022e-01 -5.81182493e-03 8.24990034e-01 -5.65128148e-01 -5.81183191e-03 8.23017240e-01 -5.67999899e-01 -5.81183238e-03 8.21061432e-01 -5.70819438e-01 -5.81183843e-03 8.19077432e-01 -5.73662996e-01 -5.81182446e-03 8.17076385e-01 -5.76512814e-01 -5.81183843e-03 8.15065682e-01 -5.79350471e-01 -5.81182539e-03 8.13012123e-01 -5.82229972e-01 -5.81183936e-03 8.11033428e-01 -5.84977031e-01 -5.81182959e-03 8.08964550e-01 -5.87841034e-01 -5.81183052e-03 8.06921244e-01 -5.90639353e-01 -5.81183610e-03 8.04814875e-01 -5.93507826e-01 -5.81182307e-03 8.02681863e-01 -5.96389949e-01 -5.81182912e-03 8.00660014e-01 -5.99097490e-01 -5.81183936e-03 7.98565507e-01 -6.01891696e-01 -5.81182307e-03 7.96443701e-01 -6.04695082e-01 -5.81184123e-03 7.94360638e-01 -6.07430398e-01 -5.81182353e-03 7.92239189e-01 -6.10191464e-01 -5.81183657e-03 7.90144801e-01 -6.12901449e-01 -5.81182865e-03 7.87941337e-01 -6.15732789e-01 -5.81182772e-03 7.85732269e-01 -6.18550122e-01 -5.81182633e-03 7.83615172e-01 -6.21227682e-01 -5.81184030e-03 7.81486094e-01 -6.23906076e-01 -5.81182865e-03 7.79316604e-01 -6.26614630e-01 -5.81182865e-03 7.77070761e-01 -6.29399121e-01 -5.81181794e-03 7.74859846e-01 -6.32113397e-01 -5.81183610e-03 7.72715211e-01 -6.34735525e-01 -5.81182865e-03 7.70495057e-01 -6.37430310e-01 -5.81182865e-03 7.68268049e-01 -6.40111983e-01 -5.81182726e-03 7.66029596e-01 -6.42789304e-01 -5.81182865e-03 7.63712585e-01 -6.45539761e-01 -5.81182074e-03 7.61441112e-01 -6.48216367e-01 -5.81183657e-03 7.59257376e-01 -6.50773346e-01 -5.81182726e-03 7.56971955e-01 -6.53431892e-01 -5.81182865e-03 7.54659057e-01 -6.56102717e-01 -5.81182586e-03 7.52310753e-01 -6.58792257e-01 -5.81182120e-03 7.49964118e-01 -6.61461413e-01 -5.81183052e-03 7.47691214e-01 -6.64028883e-01 -5.81183843e-03 7.45434105e-01 -6.66564405e-01 -5.81182772e-03 7.43045926e-01 -6.69225633e-01 -5.81182353e-03 7.40726590e-01 -6.71792626e-01 -5.81183424e-03 7.38375962e-01 -6.74374759e-01 -5.81181981e-03 7.36012340e-01 -6.76953197e-01 -5.81183378e-03 7.33714521e-01 -6.79442942e-01 -5.81182912e-03 7.31339157e-01 -6.81997895e-01 -5.81182726e-03 7.28899240e-01 -6.84605062e-01 -5.81182446e-03 7.26482987e-01 -6.87166631e-01 -5.81183750e-03 7.24094927e-01 -6.89688444e-01 -5.81182586e-03 7.21683383e-01 -6.92201912e-01 -5.81184076e-03 7.19288230e-01 -6.94705188e-01 -5.81182633e-03 7.16833532e-01 -6.97233140e-01 -5.81184635e-03 7.14462876e-01 -6.99659288e-01 -5.81184356e-03 7.11959183e-01 -7.02207863e-01 -5.81185333e-03 7.09475458e-01 -7.04708457e-01 -5.81189524e-03 7.07027256e-01 -7.07162142e-01 -5.81188826e-03 7.04485357e-01 -7.09691286e-01 -5.81192225e-03 7.02086210e-01 -7.12062061e-01 -5.81192551e-03 6.99707389e-01 -7.14400947e-01 -5.81192505e-03 6.97371244e-01 -7.16687799e-01 -5.81192179e-03 6.94772422e-01 -7.19206274e-01 -5.81190828e-03 6.91991985e-01 -7.21880853e-01 -5.81191434e-03 6.89595401e-01 -7.24170506e-01 -5.81191434e-03 6.87709689e-01 -7.25962400e-01 -5.81191434e-03 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. 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 5.22908986e-01 -8.52368653e-01 -5.81191434e-03 5.20624936e-01 -8.53767037e-01 -5.81191108e-03 5.17760336e-01 -8.55501533e-01 -5.81192411e-03 5.14907241e-01 -8.57223690e-01 -5.81192551e-03 5.11885762e-01 -8.59035432e-01 -5.81190130e-03 5.08874834e-01 -8.60823631e-01 -5.81188081e-03 5.05966127e-01 -8.62539351e-01 -5.81185380e-03 5.02944946e-01 -8.64305854e-01 -5.81183517e-03 4.99897003e-01 -8.66073787e-01 -5.81181981e-03 4.96877462e-01 -8.67808759e-01 -5.81183238e-03 4.93921965e-01 -8.69493842e-01 -5.81182865e-03 4.90902334e-01 -8.71205628e-01 -5.81182586e-03 4.87873584e-01 -8.72901559e-01 -5.81182865e-03 4.84788924e-01 -8.74616861e-01 -5.81182772e-03 4.81762469e-01 -8.76290560e-01 -5.81182679e-03 4.78704661e-01 -8.77965569e-01 -5.81182633e-03 4.75629747e-01 -8.79633844e-01 -5.81182633e-03 4.72568035e-01 -8.81281912e-01 -5.81182586e-03 4.69476759e-01 -8.82933557e-01 -5.81182586e-03 4.66376364e-01 -8.84575665e-01 -5.81182353e-03 4.63236004e-01 -8.86223316e-01 -5.81181608e-03 4.60119963e-01 -8.87843192e-01 -5.81183238e-03 4.57108080e-01 -8.89400542e-01 -5.81182586e-03 4.53977227e-01 -8.91000926e-01 -5.81182679e-03 4.50853407e-01 -8.92586112e-01 -5.81182679e-03 4.47731882e-01 -8.94156396e-01 -5.81182539e-03 4.44634348e-01 -8.95700157e-01 -5.81182819e-03 4.41515267e-01 -8.97242188e-01 -5.81182446e-03 4.38358665e-01 -8.98789644e-01 -5.81182633e-03 4.35230762e-01 -9.00308311e-01 -5.81182679e-03 4.32055175e-01 -9.01834190e-01 -5.81182539e-03 4.28858697e-01 -9.03359830e-01 -5.81182074e-03 4.25707787e-01 -9.04847860e-01 -5.81183005e-03 4.22516316e-01 -9.06345546e-01 -5.81181608e-03 4.19316649e-01 -9.07827497e-01 -5.81183191e-03 4.16251540e-01 -9.09236193e-01 -5.81182586e-03 4.13082570e-01 -9.10682499e-01 -5.81182633e-03 4.09907341e-01 -9.12116170e-01 -5.81182586e-03 4.06609565e-01 -9.13591981e-01 -5.81181096e-03 4.03402418e-01 -9.15010870e-01 -5.81183704e-03 4.00319487e-01 -9.16366100e-01 -5.81181981e-03 3.97114187e-01 -9.17757392e-01 -5.81182446e-03 3.93901914e-01 -9.19137537e-01 -5.81182586e-03 3.90636206e-01 -9.20533478e-01 -5.81181981e-03 3.87459189e-01 -9.21876013e-01 -5.81182865e-03 3.84148836e-01 -9.23260152e-01 -5.81181096e-03 3.80900323e-01 -9.24602211e-01 -5.81183238e-03 3.77813637e-01 -9.25871193e-01 -5.81182446e-03 3.74508798e-01 -9.27212119e-01 -5.81181981e-03 3.71184468e-01 -9.28547859e-01 -5.81181981e-03 3.67909670e-01 -9.29851651e-01 -5.81182353e-03 3.64722520e-01 -9.31105733e-01 -5.81183191e-03 3.61568153e-01 -9.32329416e-01 -5.81182353e-03 3.58313501e-01 -9.33595002e-01 -5.81182400e-03 3.55069995e-01 -9.34824467e-01 -5.81182679e-03 3.51804525e-01 -9.36054230e-01 -5.81182539e-03 3.48513037e-01 -9.37283695e-01 -5.81182214e-03 3.45248491e-01 -9.38494563e-01 -5.81182633e-03 3.41977000e-01 -9.39699054e-01 -5.81182307e-03 3.38710934e-01 -9.40878093e-01 -5.81182493e-03 3.35410058e-01 -9.42062318e-01 -5.81182633e-03 3.32043737e-01 -9.43252742e-01 -5.81181562e-03 3.28732491e-01 -9.44411039e-01 -5.81183098e-03 3.25439215e-01 -9.45552826e-01 -5.81181608e-03 3.22122157e-01 -9.46685731e-01 -5.81183145e-03 3.18907827e-01 -9.47776139e-01 -5.81182446e-03 3.15508813e-01 -9.48911309e-01 -5.81181608e-03 3.12180877e-01 -9.50009644e-01 -5.81183098e-03 3.08871031e-01 -9.51093078e-01 -5.81181794e-03 3.05543125e-01 -9.52168703e-01 -5.81183098e-03 3.02293688e-01 -9.53204036e-01 -5.81182446e-03 2.98984319e-01 -9.54247475e-01 -5.81182446e-03 2.95638978e-01 -9.55289483e-01 -5.81182539e-03 2.92305678e-01 -9.56315160e-01 -5.81182260e-03 2.88888812e-01 -9.57350552e-01 -5.81181934e-03 2.85448968e-01 -9.58382666e-01 -5.81182633e-03 2.82207161e-01 -9.59344208e-01 -5.81183145e-03 2.78855860e-01 -9.60323870e-01 -5.81181329e-03 2.75412440e-01 -9.61315691e-01 -5.81182633e-03 2.72056520e-01 -9.62270558e-01 -5.81182446e-03 2.68791229e-01 -9.63189185e-01 -5.81183238e-03 2.65504628e-01 -9.64098215e-01 -5.81182586e-03 2.62129903e-01 -9.65024471e-01 -5.81182586e-03 2.58744627e-01 -9.65934217e-01 -5.81182446e-03 2.55399853e-01 -9.66824770e-01 -5.81182353e-03 2.52037555e-01 -9.67709363e-01 -5.81182214e-03 2.48567536e-01 -9.68604565e-01 -5.81181794e-03 2.45187789e-01 -9.69463408e-01 -5.81183052e-03 2.41816789e-01 -9.70311105e-01 -5.81181562e-03 2.38408804e-01 -9.71154988e-01 -5.81183005e-03 2.35097677e-01 -9.71962750e-01 -5.81182446e-03 2.31613219e-01 -9.72800970e-01 -5.81181608e-03 2.28228465e-01 -9.73597288e-01 -5.81183005e-03 2.24829733e-01 -9.74388182e-01 -5.81181422e-03 2.21343845e-01 -9.75185037e-01 -5.81182446e-03 2.18047693e-01 -9.75927591e-01 -5.81183191e-03 2.14721441e-01 -9.76663828e-01 -5.81182446e-03 2.11317554e-01 -9.77406621e-01 -5.81182400e-03 2.07903981e-01 -9.78138447e-01 -5.81182214e-03 2.04380020e-01 -9.78882968e-01 -5.81181096e-03 2.00943589e-01 -9.79592860e-01 -5.81183331e-03 1.97633788e-01 -9.80266035e-01 -5.81182446e-03 1.94224536e-01 -9.80946422e-01 -5.81182586e-03 1.90778822e-01 -9.81623530e-01 -5.81182353e-03 1.87257364e-01 -9.82300520e-01 -5.81181096e-03 1.83807805e-01 -9.82951105e-01 -5.81183191e-03 1.80384502e-01 -9.83584404e-01 -5.81181096e-03 1.76922709e-01 -9.84219372e-01 -5.81183238e-03 1.73607215e-01 -9.84809220e-01 -5.81182074e-03 1.70170292e-01 -9.85402524e-01 -5.81181981e-03 1.66712984e-01 -9.85995650e-01 -5.81182539e-03 1.63180947e-01 -9.86585319e-01 -5.81181096e-03 1.59722939e-01 -9.87151027e-01 -5.81183191e-03 1.56387955e-01 -9.87686157e-01 -5.81182307e-03 1.52948663e-01 -9.88224149e-01 -5.81182260e-03 1.49498209e-01 -9.88750100e-01 -5.81182353e-03 1.45949081e-01 -9.89282131e-01 -5.81181701e-03 1.42500967e-01 -9.89783466e-01 -5.81183238e-03 1.39039859e-01 -9.90278125e-01 -5.81181794e-03 1.35466829e-01 -9.90772843e-01 -5.81182446e-03 1.32100016e-01 -9.91223872e-01 -5.81183424e-03 1.28754795e-01 -9.91666257e-01 -5.81182679e-03 1.25289038e-01 -9.92111444e-01 -5.81182633e-03 1.21836782e-01 -9.92540300e-01 -5.81182307e-03 1.18266284e-01 -9.92971897e-01 -5.81181096e-03 1.14783868e-01 -9.93378818e-01 -5.81183098e-03 1.11440912e-01 -9.93760705e-01 -5.81182586e-03 1.07975021e-01 -9.94142413e-01 -5.81182493e-03 1.04507588e-01 -9.94513035e-01 -5.81182074e-03 1.00919008e-01 -9.94883180e-01 -5.81181096e-03 9.74328369e-02 -9.95231509e-01 -5.81183191e-03 9.39989388e-02 -9.95563447e-01 -5.81181468e-03 9.05011371e-02 -9.95884955e-01 -5.81183145e-03 8.70299414e-02 -9.96196270e-01 -5.81181608e-03 8.34448636e-02 -9.96501327e-01 -5.81182307e-03 8.00301656e-02 -9.96782660e-01 -5.81183564e-03 7.65795186e-02 -9.97053862e-01 -5.81181096e-03 7.30670020e-02 -9.97315705e-01 -5.81183052e-03 6.96922094e-02 -9.97556627e-01 -5.81182167e-03 6.62399754e-02 -9.97793078e-01 -5.81182307e-03 6.27543107e-02 -9.98017848e-01 -5.81182539e-03 5.91427162e-02 -9.98239160e-01 -5.81181608e-03 5.56727983e-02 -9.98439014e-01 -5.81183145e-03 5.22090308e-02 -9.98625517e-01 -5.81181096e-03 4.87170145e-02 -9.98802364e-01 -5.81183098e-03 4.52371351e-02 -9.98966098e-01 -5.81181096e-03 4.16294038e-02 -9.99123335e-01 -5.81182074e-03 3.82358991e-02 -9.99257326e-01 -5.81183098e-03 3.48653495e-02 -9.99381006e-01 -5.81182214e-03 3.12868468e-02 -9.99499381e-01 -5.81181608e-03 2.77716443e-02 -9.99604106e-01 -5.81183052e-03 2.42942907e-02 -9.99697328e-01 -5.81181096e-03 2.08023116e-02 -9.99770701e-01 -5.81183098e-03 1.73931569e-02 -9.99843001e-01 -5.81182307e-03 1.38385277e-02 -9.99888182e-01 -5.81181096e-03 1.03287697e-02 -9.99936402e-01 -5.81182959e-03 6.92668324e-03 -9.99972403e-01 -5.81182214e-03 3.44125764e-03 -9.99988914e-01 -5.81182353e-03 -3.56052551e-05 -9.99990284e-01 -5.81182260e-03 -3.49850790e-03 -9.99989152e-01 -5.81181794e-03 -7.00718584e-03 -9.99972045e-01 -5.81181981e-03 -1.05862254e-02 -9.99935746e-01 -5.81181096e-03 -1.40714813e-02 -9.99885738e-01 -5.81183191e-03 -1.75635125e-02 -9.99842107e-01 -5.81181096e-03 -2.11636573e-02 -9.99763548e-01 -5.81181888e-03 -2.45681833e-02 -9.99689281e-01 -5.81183005e-03 -2.79429369e-02 -9.99600053e-01 -5.81182167e-03 -3.14161964e-02 -9.99496698e-01 -5.81181888e-03 -3.50035690e-02 -9.99377847e-01 -5.81181096e-03 -3.86160612e-02 -9.99244869e-01 -5.81181888e-03 -4.20093648e-02 -9.99107659e-01 -5.81182959e-03 -4.53878045e-02 -9.98958945e-01 -5.81182027e-03 -4.88930754e-02 -9.98794675e-01 -5.81181888e-03 -5.23697287e-02 -9.98615921e-01 -5.81182074e-03 -5.59277013e-02 -9.98425603e-01 -5.81181096e-03 -5.94375841e-02 -9.98221576e-01 -5.81183098e-03 -6.28991947e-02 -9.98008966e-01 -5.81181096e-03 -6.64087534e-02 -9.97780800e-01 -5.81182959e-03 -6.97995648e-02 -9.97548401e-01 -5.81182214e-03 -7.33668134e-02 -9.97294426e-01 -5.81181096e-03 -7.68538713e-02 -9.97031271e-01 -5.81182912e-03 -8.03100467e-02 -9.96760368e-01 -5.81181189e-03 -8.38002264e-02 -9.96471345e-01 -5.81182679e-03 -8.71976316e-02 -9.96180654e-01 -5.81181981e-03 -9.06813368e-02 -9.95868742e-01 -5.81181981e-03 -9.41516906e-02 -9.95548069e-01 -5.81181981e-03 -9.77069139e-02 -9.95206773e-01 -5.81181096e-03 -1.01185486e-01 -9.94857669e-01 -5.81183052e-03 -1.04629867e-01 -9.94501233e-01 -5.81181096e-03 -1.08185686e-01 -9.94119823e-01 -5.81182307e-03 -1.11583464e-01 -9.93744969e-01 -5.81182959e-03 -1.14965461e-01 -9.93359029e-01 -5.81181981e-03 -1.18419454e-01 -9.92951989e-01 -5.81181981e-03 -1.21894367e-01 -9.92531836e-01 -5.81181888e-03 -1.25439927e-01 -9.92093384e-01 -5.81181096e-03 -1.28914088e-01 -9.91643906e-01 -5.81183098e-03 -1.32287934e-01 -9.91201818e-01 -5.81181794e-03 -1.35739863e-01 -9.90733981e-01 -5.81182074e-03 -1.39193267e-01 -9.90256131e-01 -5.81181981e-03 -1.42740041e-01 -9.89751339e-01 -5.81181096e-03 -1.46196768e-01 -9.89243746e-01 -5.81182959e-03 -1.49641454e-01 -9.88729000e-01 -5.81181282e-03 -1.53063342e-01 -9.88205433e-01 -5.81183052e-03 -1.56425804e-01 -9.87678528e-01 -5.81182167e-03 -1.59883454e-01 -9.87124979e-01 -5.81182400e-03 -1.63319707e-01 -9.86563981e-01 -5.81181981e-03 -1.66889504e-01 -9.85965848e-01 -5.81181096e-03 -1.70329392e-01 -9.85374928e-01 -5.81182959e-03 -1.73659831e-01 -9.84799206e-01 -5.81182214e-03 -1.77104279e-01 -9.84184384e-01 -5.81181794e-03 -1.80536121e-01 -9.83555555e-01 -5.81181981e-03 -1.84056193e-01 -9.82907832e-01 -5.81181096e-03 -1.87493175e-01 -9.82255340e-01 -5.81182819e-03 -1.90821916e-01 -9.81612206e-01 -5.81182214e-03 -1.94244400e-01 -9.80943143e-01 -5.81181981e-03 -1.97752759e-01 -9.80242789e-01 -5.81181096e-03 -2.01176554e-01 -9.79543924e-01 -5.81183052e-03 -2.04495996e-01 -9.78856564e-01 -5.81181981e-03 -2.07928196e-01 -9.78134632e-01 -5.81182074e-03 -2.11419463e-01 -9.77385998e-01 -5.81181096e-03 -2.14849100e-01 -9.76634324e-01 -5.81183005e-03 -2.18159899e-01 -9.75903869e-01 -5.81181981e-03 -2.21572280e-01 -9.75133657e-01 -5.81181794e-03 -2.24989206e-01 -9.74349439e-01 -5.81181981e-03 -2.28483468e-01 -9.73540843e-01 -5.81181096e-03 -2.31895328e-01 -9.72731292e-01 -5.81183052e-03 -2.35166535e-01 -9.71946299e-01 -5.81182074e-03 -2.38568082e-01 -9.71115887e-01 -5.81181888e-03 -2.41961747e-01 -9.70274389e-01 -5.81182214e-03 -2.45389849e-01 -9.69412863e-01 -5.81181096e-03 -2.48818740e-01 -9.68539655e-01 -5.81182679e-03 -2.52215087e-01 -9.67660487e-01 -5.81181096e-03 -2.55597770e-01 -9.66773808e-01 -5.81182912e-03 -2.58937627e-01 -9.65884686e-01 -5.81181142e-03 -2.62400597e-01 -9.64949965e-01 -5.81181888e-03 -2.65700758e-01 -9.64044154e-01 -5.81183005e-03 -2.69050479e-01 -9.63116765e-01 -5.81181096e-03 -2.72419602e-01 -9.62168157e-01 -5.81183052e-03 -2.75671005e-01 -9.61241364e-01 -5.81182027e-03 -2.79017836e-01 -9.60275233e-01 -5.81181981e-03 -2.82376885e-01 -9.59292769e-01 -5.81181981e-03 -2.85708815e-01 -9.58307028e-01 -5.81182214e-03 -2.89047331e-01 -9.57303107e-01 -5.81181608e-03 -2.92401373e-01 -9.56283212e-01 -5.81181981e-03 -2.95824766e-01 -9.55233395e-01 -5.81181096e-03 -2.99158365e-01 -9.54191625e-01 -5.81183052e-03 -3.02489847e-01 -9.53143179e-01 -5.81181096e-03 -3.05823028e-01 -9.52078521e-01 -5.81182819e-03 -3.09049875e-01 -9.51034844e-01 -5.81181934e-03 -3.12466472e-01 -9.49918628e-01 -5.81181096e-03 -3.15762788e-01 -9.48827326e-01 -5.81182586e-03 -3.19076747e-01 -9.47720528e-01 -5.81181096e-03 -3.22396427e-01 -9.46593285e-01 -5.81182912e-03 -3.25598240e-01 -9.45498168e-01 -5.81181981e-03 -3.28952193e-01 -9.44334865e-01 -5.81181096e-03 -3.32255185e-01 -9.43180442e-01 -5.81182679e-03 -3.35567892e-01 -9.42005694e-01 -5.81181096e-03 -3.38869661e-01 -9.40821052e-01 -5.81183052e-03 -3.42126876e-01 -9.39646363e-01 -5.81181096e-03 -3.45425874e-01 -9.38428760e-01 -5.81182912e-03 -3.48599404e-01 -9.37251210e-01 -5.81181981e-03 -3.51947278e-01 -9.36001718e-01 -5.81181096e-03 -3.55196863e-01 -9.34776068e-01 -5.81182819e-03 -3.58459353e-01 -9.33539510e-01 -5.81181096e-03 -3.61816794e-01 -9.32234943e-01 -5.81181888e-03 -3.64981711e-01 -9.31003809e-01 -5.81182959e-03 -3.68139356e-01 -9.29760277e-01 -5.81181981e-03 -3.71382296e-01 -9.28468227e-01 -5.81182167e-03 -3.74626547e-01 -9.27164257e-01 -5.81182214e-03 -3.77934128e-01 -9.25821304e-01 -5.81181096e-03 -3.81189883e-01 -9.24481869e-01 -5.81183098e-03 -3.84336352e-01 -9.23182309e-01 -5.81182214e-03 -3.87521952e-01 -9.21848834e-01 -5.81181981e-03 -3.90744328e-01 -9.20486748e-01 -5.81181888e-03 -3.94042253e-01 -9.19078946e-01 -5.81181096e-03 -3.97254348e-01 -9.17695582e-01 -5.81182959e-03 -4.00445908e-01 -9.16311204e-01 -5.81181096e-03 -4.03661549e-01 -9.14896488e-01 -5.81182726e-03 -4.06768948e-01 -9.13520098e-01 -5.81181981e-03 -4.10026163e-01 -9.12064195e-01 -5.81181096e-03 -4.13214803e-01 -9.10621345e-01 -5.81183005e-03 -4.16359544e-01 -9.09186423e-01 -5.81181096e-03 -4.19544458e-01 -9.07721400e-01 -5.81183052e-03 -4.22627300e-01 -9.06291783e-01 -5.81181981e-03 -4.25799251e-01 -9.04805481e-01 -5.81182027e-03 -4.29038227e-01 -9.03276265e-01 -5.81181096e-03 -4.32186782e-01 -9.01770651e-01 -5.81182865e-03 -4.35248971e-01 -9.00301814e-01 -5.81181608e-03 -4.38466072e-01 -8.98738861e-01 -5.81181096e-03 -4.41694111e-01 -8.97153735e-01 -5.81182074e-03 -4.44746315e-01 -8.95645499e-01 -5.81182819e-03 -4.47783083e-01 -8.94131482e-01 -5.81181981e-03 -4.50892359e-01 -8.92568171e-01 -5.81181748e-03 -4.54016715e-01 -8.90981972e-01 -5.81181981e-03 -4.57193315e-01 -8.89355838e-01 -5.81181096e-03 -4.60302830e-01 -8.87748957e-01 -5.81183005e-03 -4.63299811e-01 -8.86191785e-01 -5.81181794e-03 -4.66403931e-01 -8.84561419e-01 -5.81181794e-03 -4.69482392e-01 -8.82929921e-01 -5.81181888e-03 -4.72650647e-01 -8.81240249e-01 -5.81181096e-03 -4.75724012e-01 -8.79581809e-01 -5.81182726e-03 -4.78778124e-01 -8.77927363e-01 -5.81181096e-03 -4.81851578e-01 -8.76241267e-01 -5.81182679e-03 -4.84891266e-01 -8.74561429e-01 -5.81181096e-03 -4.88018006e-01 -8.72820914e-01 -5.81181934e-03 -4.90988582e-01 -8.71154726e-01 -5.81182726e-03 -4.94020283e-01 -8.69439125e-01 -5.81181096e-03 -4.97046143e-01 -8.67714286e-01 -5.81182633e-03 -5.00004470e-01 -8.66010785e-01 -5.81181981e-03 -5.03105640e-01 -8.64214778e-01 -5.81181096e-03 -5.06133497e-01 -8.62444758e-01 -5.81182912e-03 -5.09125531e-01 -8.60680878e-01 -5.81181096e-03 -5.12126923e-01 -8.58897090e-01 -5.81182912e-03 -5.15104413e-01 -8.57116222e-01 -5.81181096e-03 -5.18108249e-01 -8.55301976e-01 -5.81182912e-03 -5.21089137e-01 -8.53493571e-01 -5.81181096e-03 -5.24153173e-01 -8.51612210e-01 -5.81181794e-03 -5.27042389e-01 -8.49827766e-01 -5.81182959e-03 -5.29913366e-01 -8.48040342e-01 -5.81182074e-03 -5.32966733e-01 -8.46124470e-01 -5.81181096e-03 -5.35988092e-01 -8.44213009e-01 -5.81181655e-03 -5.38936555e-01 -8.42334151e-01 -5.81181981e-03 -5.41797638e-01 -8.40496659e-01 -5.81182865e-03 -5.44654012e-01 -8.38649154e-01 -5.81181655e-03 -5.47590196e-01 -8.36732566e-01 -5.81181888e-03 -5.50491333e-01 -8.34829986e-01 -5.81182260e-03 -5.53393781e-01 -8.32905471e-01 -5.81181981e-03 -5.56292236e-01 -8.30973923e-01 -5.81182074e-03 -5.59262872e-01 -8.28980923e-01 -5.81181096e-03 -5.62201619e-01 -8.26986790e-01 -5.81182679e-03 -5.64999938e-01 -8.25079620e-01 -5.81182307e-03 -5.67919552e-01 -8.23073566e-01 -5.81181096e-03 -5.70790768e-01 -8.21084619e-01 -5.81182865e-03 -5.73650897e-01 -8.19086790e-01 -5.81181096e-03 -5.76607764e-01 -8.17009985e-01 -5.81181888e-03 -5.79367876e-01 -8.15052927e-01 -5.81183052e-03 -5.82178891e-01 -8.13049495e-01 -5.81181096e-03 -5.85000336e-01 -8.11016798e-01 -5.81182633e-03 -5.87830544e-01 -8.08972895e-01 -5.81181096e-03 -5.90743184e-01 -8.06846917e-01 -5.81181608e-03 -5.93590260e-01 -8.04754138e-01 -5.81181934e-03 -5.96315503e-01 -8.02736640e-01 -5.81183098e-03 -5.99025488e-01 -8.00716519e-01 -5.81181888e-03 -6.01824939e-01 -7.98615038e-01 -5.81181888e-03 -6.04668736e-01 -7.96465516e-01 -5.81181096e-03 -6.07466102e-01 -7.94332147e-01 -5.81183052e-03 -6.10237062e-01 -7.92204082e-01 -5.81181096e-03 -6.13005579e-01 -7.90064871e-01 -5.81182912e-03 -6.15670919e-01 -7.87990689e-01 -5.81181794e-03 -6.18502855e-01 -7.85771787e-01 -5.81181096e-03 -6.21243954e-01 -7.83602536e-01 -5.81182819e-03 -6.23970151e-01 -7.81437337e-01 -5.81181096e-03 -6.26713574e-01 -7.79236794e-01 -5.81182633e-03 -6.29354596e-01 -7.77106822e-01 -5.81181981e-03 -6.32122815e-01 -7.74855077e-01 -5.81181096e-03 -6.34836614e-01 -7.72632778e-01 -5.81182959e-03 -6.37450457e-01 -7.70477831e-01 -5.81181794e-03 -6.40135109e-01 -7.68250287e-01 -5.81181888e-03 -6.42855108e-01 -7.65974641e-01 -5.81181096e-03 -6.45606816e-01 -7.63656378e-01 -5.81181608e-03 -6.48221672e-01 -7.61436403e-01 -5.81182586e-03 -6.50792062e-01 -7.59242535e-01 -5.81181888e-03 -6.53454781e-01 -7.56953359e-01 -5.81181981e-03 -6.56143427e-01 -7.54624486e-01 -5.81181096e-03 -6.58848047e-01 -7.52261639e-01 -5.81182027e-03 -6.61413729e-01 -7.50007391e-01 -5.81182959e-03 -6.63944900e-01 -7.47768044e-01 -5.81182074e-03 -6.66540444e-01 -7.45454967e-01 -5.81181981e-03 -6.69144511e-01 -7.43118644e-01 -5.81181888e-03 -6.71810210e-01 -7.40711927e-01 -5.81181096e-03 -6.74414515e-01 -7.38336682e-01 -5.81182912e-03 -6.76959693e-01 -7.36010253e-01 -5.81181096e-03 -6.79529667e-01 -7.33634055e-01 -5.81182865e-03 -6.82071149e-01 -7.31273234e-01 -5.81181096e-03 -6.84688926e-01 -7.28820145e-01 -5.81182120e-03 -6.87174201e-01 -7.26476967e-01 -5.81182679e-03 -6.89702272e-01 -7.24081755e-01 -5.81181096e-03 -6.92224741e-01 -7.21662045e-01 -5.81182865e-03 -6.94688678e-01 -7.19306052e-01 -5.81181841e-03 -6.97209656e-01 -7.16861069e-01 -5.81181096e-03 -6.99717462e-01 -7.14407921e-01 -5.81182726e-03 -7.02180207e-01 -7.11991906e-01 -5.81181888e-03 -7.04640687e-01 -7.09558845e-01 -5.81181794e-03 -7.07166433e-01 -7.07021117e-01 -5.81181096e-03 -7.09644854e-01 -7.04552591e-01 -5.81182586e-03 -7.12110996e-01 -7.02058136e-01 -5.81181096e-03 -7.14553356e-01 -6.99568987e-01 -5.81182726e-03 -7.16924131e-01 -6.97143972e-01 -5.81181888e-03 -7.19384611e-01 -6.94607079e-01 -5.81181608e-03 -7.21847475e-01 -6.92031562e-01 -5.81181096e-03 -7.24257827e-01 -6.89517617e-01 -5.81182865e-03 -7.26662934e-01 -6.86978459e-01 -5.81181096e-03 -7.29040682e-01 -6.84452713e-01 -5.81183191e-03 -7.31346607e-01 -6.81988895e-01 -5.81182027e-03 -7.33769953e-01 -6.79384708e-01 -5.81181096e-03 -7.36216128e-01 -6.76735580e-01 -5.81181608e-03 -7.38533080e-01 -6.74200833e-01 -5.81183191e-03 -7.40790009e-01 -6.71721697e-01 -5.81181888e-03 -7.43136525e-01 -6.69124424e-01 -5.81182307e-03 -7.45538354e-01 -6.66447878e-01 -5.81181096e-03 -7.47885108e-01 -6.63812816e-01 -5.81183145e-03 -7.50174224e-01 -6.61224902e-01 -5.81181096e-03 -7.52471149e-01 -6.58607662e-01 -5.81183098e-03 -7.54770637e-01 -6.55972421e-01 -5.81181096e-03 -7.57124424e-01 -6.53255999e-01 -5.81182307e-03 -7.59344041e-01 -6.50673747e-01 -5.81182865e-03 -7.61549950e-01 -6.48088813e-01 -5.81182167e-03 -7.63811350e-01 -6.45425856e-01 -5.81182214e-03 -7.66086996e-01 -6.42720103e-01 -5.81181794e-03 -7.68389523e-01 -6.39968395e-01 -5.81181841e-03 -7.70592809e-01 -6.37308836e-01 -5.81182959e-03 -7.72754550e-01 -6.34693265e-01 -5.81181794e-03 -7.74969876e-01 -6.31981134e-01 -5.81181981e-03 -7.77165771e-01 -6.29280329e-01 -5.81182307e-03 -7.79410005e-01 -6.26500309e-01 -5.81181096e-03 -7.81655669e-01 -6.23694122e-01 -5.81181981e-03 -7.83828020e-01 -6.20961249e-01 -5.81182260e-03 -7.85931528e-01 -6.18296325e-01 -5.81183145e-03 -7.88002729e-01 -6.15656614e-01 -5.81182307e-03 -7.90227950e-01 -6.12797141e-01 -5.81181096e-03 -7.92413831e-01 -6.09967768e-01 -5.81182353e-03 -7.94535458e-01 -6.07200801e-01 -5.81181794e-03 -7.96626806e-01 -6.04453564e-01 -5.81183238e-03 -7.98653364e-01 -6.01777196e-01 -5.81182539e-03 -8.00803185e-01 -5.98911047e-01 -5.81181608e-03 -8.02896261e-01 -5.96100390e-01 -5.81182912e-03 -8.04928780e-01 -5.93352795e-01 -5.81181841e-03 -8.06989491e-01 -5.90546012e-01 -5.81182819e-03 -8.09073687e-01 -5.87689877e-01 -5.81181794e-03 -8.11157286e-01 -5.84807754e-01 -5.81181888e-03 -8.13184619e-01 -5.81989050e-01 -5.81183191e-03 -8.15152764e-01 -5.79228163e-01 -5.81181888e-03 -8.17165136e-01 -5.76389730e-01 -5.81182353e-03 -8.19197416e-01 -5.73494911e-01 -5.81181981e-03 -8.21234465e-01 -5.70572436e-01 -5.81181608e-03 -8.23203743e-01 -5.67730188e-01 -5.81182865e-03 -8.25137019e-01 -5.64915419e-01 -5.81182539e-03 -8.27078104e-01 -5.62070191e-01 -5.81182446e-03 -8.29029799e-01 -5.59186995e-01 -5.81182493e-03 -8.31033111e-01 -5.56204200e-01 -5.81181096e-03 -8.32984805e-01 -5.53273857e-01 -5.81183238e-03 -8.34902644e-01 -5.50380051e-01 -5.81181096e-03 -8.36838782e-01 -5.47427118e-01 -5.81183517e-03 -8.38679671e-01 -5.44604182e-01 -5.81182679e-03 -8.40575337e-01 -5.41677058e-01 -5.81182214e-03 -8.42498362e-01 -5.38678467e-01 -5.81181608e-03 -8.44405115e-01 -5.35683274e-01 -5.81183005e-03 -8.46224427e-01 -5.32810211e-01 -5.81182726e-03 -8.48043501e-01 -5.29904485e-01 -5.81182307e-03 -8.49910021e-01 -5.26911378e-01 -5.81182307e-03 -8.51743639e-01 -5.23937047e-01 -5.81182865e-03 -8.53559315e-01 -5.20979404e-01 -5.81182679e-03 -8.55384290e-01 -5.17973959e-01 -5.81182493e-03 -8.57225180e-01 -5.14926434e-01 -5.81181096e-03 -8.59069824e-01 -5.11835098e-01 -5.81182353e-03 -8.60809147e-01 -5.08906186e-01 -5.81183098e-03 -8.62572849e-01 -5.05912721e-01 -5.81181655e-03 -8.64339113e-01 -5.02885222e-01 -5.81183424e-03 -8.66061211e-01 -4.99920696e-01 -5.81182353e-03 -8.67786586e-01 -4.96916384e-01 -5.81182865e-03 -8.69500577e-01 -4.93909359e-01 -5.81182586e-03 -8.71215761e-01 -4.90884781e-01 -5.81182353e-03 -8.72930765e-01 -4.87821102e-01 -5.81182726e-03 -8.74619544e-01 -4.84784991e-01 -5.81181981e-03 -8.76342654e-01 -4.81668979e-01 -5.81181608e-03 -8.78046870e-01 -4.78558987e-01 -5.81182446e-03 -8.79681468e-01 -4.75540668e-01 -5.81182539e-03 -8.81308198e-01 -4.72521007e-01 -5.81182493e-03 -8.82978678e-01 -4.69391108e-01 -5.81181608e-03 -8.84664237e-01 -4.66206074e-01 -5.81182214e-03 -8.86274219e-01 -4.63141292e-01 -5.81183098e-03 -8.87835026e-01 -4.60137129e-01 -5.81183098e-03 -8.89410317e-01 -4.57089067e-01 -5.81182353e-03 -8.91039491e-01 -4.53903973e-01 -5.81181096e-03 -8.92672241e-01 -4.50684965e-01 -5.81182074e-03 -8.94193470e-01 -4.47655380e-01 -5.81183238e-03 -8.95697713e-01 -4.44641143e-01 -5.81182307e-03 -8.97240877e-01 -4.41519231e-01 -5.81182074e-03 -8.98778737e-01 -4.38380837e-01 -5.81182353e-03 -9.00343120e-01 -4.35160577e-01 -5.81181096e-03 -9.01906550e-01 -4.31905329e-01 -5.81182214e-03 -9.03386712e-01 -4.28801775e-01 -5.81183005e-03 -9.04826462e-01 -4.25753176e-01 -5.81182353e-03 -9.06304479e-01 -4.22600091e-01 -5.81182633e-03 -9.07808006e-01 -4.19364899e-01 -5.81181096e-03 -9.09293890e-01 -4.16129678e-01 -5.81182912e-03 -9.10699368e-01 -4.13046449e-01 -5.81182726e-03 -9.12111104e-01 -4.09917861e-01 -5.81182214e-03 -9.13535535e-01 -4.06737715e-01 -5.81182074e-03 -9.15001392e-01 -4.03429657e-01 -5.81181096e-03 -9.16446984e-01 -4.00135040e-01 -5.81182307e-03 -9.17828381e-01 -3.96953404e-01 -5.81182353e-03 -9.19208407e-01 -3.93735468e-01 -5.81182027e-03 -9.20548797e-01 -3.90598446e-01 -5.81183191e-03 -9.21868265e-01 -3.87477309e-01 -5.81181981e-03 -9.23219681e-01 -3.84244472e-01 -5.81182074e-03 -9.24589515e-01 -3.80935460e-01 -5.81181608e-03 -9.25910950e-01 -3.77714485e-01 -5.81183191e-03 -9.27193046e-01 -3.74555320e-01 -5.81182586e-03 -9.28529143e-01 -3.71231049e-01 -5.81181189e-03 -9.29813206e-01 -3.68004620e-01 -5.81183005e-03 -9.31065559e-01 -3.64827514e-01 -5.81182027e-03 -9.32326734e-01 -3.61575872e-01 -5.81182120e-03 -9.33597863e-01 -3.58305067e-01 -5.81181981e-03 -9.34870303e-01 -3.54954392e-01 -5.81181608e-03 -9.36083257e-01 -3.51722896e-01 -5.81183191e-03 -9.37278152e-01 -3.48527580e-01 -5.81182493e-03 -9.38528597e-01 -3.45161706e-01 -5.81181096e-03 -9.39769506e-01 -3.41784477e-01 -5.81182446e-03 -9.40949142e-01 -3.38512480e-01 -5.81182539e-03 -9.42098737e-01 -3.35307688e-01 -5.81183191e-03 -9.43252683e-01 -3.32044899e-01 -5.81181422e-03 -9.44414377e-01 -3.28722179e-01 -5.81183052e-03 -9.45525169e-01 -3.25519830e-01 -5.81182353e-03 -9.46651638e-01 -3.22223812e-01 -5.81182167e-03 -9.47775245e-01 -3.18909943e-01 -5.81182074e-03 -9.48912144e-01 -3.15509081e-01 -5.81181096e-03 -9.50012088e-01 -3.12178999e-01 -5.81183145e-03 -9.51066792e-01 -3.08955699e-01 -5.81182074e-03 -9.52160597e-01 -3.05565685e-01 -5.81181142e-03 -9.53222573e-01 -3.02232593e-01 -5.81182912e-03 -9.54268634e-01 -2.98922420e-01 -5.81181375e-03 -9.55307603e-01 -2.95578927e-01 -5.81183005e-03 -9.56330895e-01 -2.92252153e-01 -5.81181096e-03 -9.57369864e-01 -2.88826466e-01 -5.81182214e-03 -9.58350539e-01 -2.85555631e-01 -5.81183098e-03 -9.59340930e-01 -2.82216728e-01 -5.81181608e-03 -9.60321903e-01 -2.78858811e-01 -5.81182912e-03 -9.61287022e-01 -2.75510252e-01 -5.81181422e-03 -9.62241948e-01 -2.72156835e-01 -5.81183005e-03 -9.63165402e-01 -2.68875897e-01 -5.81182167e-03 -9.64100361e-01 -2.65501529e-01 -5.81182074e-03 -9.65020299e-01 -2.62142509e-01 -5.81182027e-03 -9.65951145e-01 -2.58686483e-01 -5.81181096e-03 -9.66872513e-01 -2.55224317e-01 -5.81182214e-03 -9.67757225e-01 -2.51843870e-01 -5.81182074e-03 -9.68609214e-01 -2.48552576e-01 -5.81183098e-03 -9.69436288e-01 -2.45295361e-01 -5.81182307e-03 -9.70313430e-01 -2.41805464e-01 -5.81181096e-03 -9.71180618e-01 -2.38308206e-01 -5.81182353e-03 -9.72004890e-01 -2.34930143e-01 -5.81182167e-03 -9.72797155e-01 -2.31621429e-01 -5.81183145e-03 -9.73575532e-01 -2.28328273e-01 -5.81182120e-03 -9.74380612e-01 -2.24857926e-01 -5.81181422e-03 -9.75191772e-01 -2.21314520e-01 -5.81182493e-03 -9.75936949e-01 -2.18006745e-01 -5.81183098e-03 -9.76689637e-01 -2.14610130e-01 -5.81181562e-03 -9.77437615e-01 -2.11173147e-01 -5.81183191e-03 -9.78140056e-01 -2.07897946e-01 -5.81181981e-03 -9.78883743e-01 -2.04378307e-01 -5.81181096e-03 -9.79613304e-01 -2.00847313e-01 -5.81182214e-03 -9.80291009e-01 -1.97505549e-01 -5.81183238e-03 -9.80951667e-01 -1.94197491e-01 -5.81182446e-03 -9.81626213e-01 -1.90763265e-01 -5.81182446e-03 -9.82298911e-01 -1.87265083e-01 -5.81181608e-03 -9.82971370e-01 -1.83711246e-01 -5.81182539e-03 -9.83586967e-01 -1.80364892e-01 -5.81183191e-03 -9.84197021e-01 -1.77041352e-01 -5.81182726e-03 -9.84810174e-01 -1.73594147e-01 -5.81182819e-03 -9.85417783e-01 -1.70082688e-01 -5.81181096e-03 -9.86022234e-01 -1.66550085e-01 -5.81182539e-03 -9.86582875e-01 -1.63197711e-01 -5.81183331e-03 -9.87148762e-01 -1.59745365e-01 -5.81181794e-03 -9.87699866e-01 -1.56295732e-01 -5.81183191e-03 -9.88234282e-01 -1.52880207e-01 -5.81181608e-03 -9.88762975e-01 -1.49413973e-01 -5.81183145e-03 -9.89278316e-01 -1.45973057e-01 -5.81182074e-03 -9.89783883e-01 -1.42500415e-01 -5.81183238e-03 -9.90261912e-01 -1.39146596e-01 -5.81182726e-03 -9.90749836e-01 -1.35637164e-01 -5.81181981e-03 -9.91219640e-01 -1.32131696e-01 -5.81183704e-03 -9.91673529e-01 -1.28694162e-01 -5.81182446e-03 -9.92120147e-01 -1.25218004e-01 -5.81183704e-03 -9.92537737e-01 -1.21849418e-01 -5.81183191e-03 -9.92966056e-01 -1.18297182e-01 -5.81182819e-03 -9.93371665e-01 -1.14831761e-01 -5.81184030e-03 -9.93758619e-01 -1.11457653e-01 -5.81183471e-03 -9.94150996e-01 -1.07881255e-01 -5.81183610e-03 -9.94528413e-01 -1.04343452e-01 -5.81185520e-03 -9.94882703e-01 -1.00910559e-01 -5.81186544e-03 -9.95217979e-01 -9.75138322e-02 -5.81190595e-03 -9.95544255e-01 -9.41089541e-02 -5.81191387e-03 -9.95862186e-01 -9.06224698e-02 -5.81192551e-03 -9.96156752e-01 -8.73804763e-02 -5.81192365e-03 -9.96445000e-01 -8.40553343e-02 -5.81191480e-03 -9.96739209e-01 -8.04709792e-02 -5.81191434e-03 -9.97014165e-01 -7.69912899e-02 -5.81191434e-03 -9.97272015e-01 -7.35851899e-02 -5.81191387e-03 -9.97510076e-01 -7.02776909e-02 -5.81191434e-03 -9.97667491e-01 -6.80142418e-02 -5.81191434e-03 0. 0. 0. -9.98202264e-01 -5.96539415e-02 -5.81191340e-03 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98564720e-01 5.35559878e-02 0. -9.98396575e-01 5.66077530e-02 0. -9.98223960e-01 5.95621020e-02 0. -9.98010278e-01 6.30298704e-02 0. -9.97783601e-01 6.65206537e-02 0. -9.97549117e-01 6.99178129e-02 0. -9.97308910e-01 7.32922256e-02 0. -9.97042656e-01 7.68294632e-02 0. -9.96759713e-01 8.04287568e-02 0. -9.96480048e-01 8.38153213e-02 0. -9.96185243e-01 8.72543678e-02 0. -9.95865524e-01 9.08357725e-02 0. -9.95547235e-01 9.42616314e-02 0. -9.95210826e-01 9.77409035e-02 0. -9.94872034e-01 1.01147771e-01 0. -9.94522393e-01 1.04521319e-01 0. -9.94138658e-01 1.08096838e-01 0. -9.93745267e-01 1.11672267e-01 0. -9.93347406e-01 1.15139708e-01 0. -9.92935896e-01 1.18631527e-01 0. -9.92519915e-01 1.22076891e-01 0. -9.92091775e-01 1.25520423e-01 0. -9.91644681e-01 1.28993466e-01 0. -9.91181910e-01 1.32497847e-01 0. -9.90727365e-01 1.35865018e-01 0. -9.90268528e-01 1.39169961e-01 0. -9.89760458e-01 1.42729446e-01 0. -9.89239454e-01 1.46293581e-01 0. -9.88724113e-01 1.49733409e-01 0. -9.88195300e-01 1.53192967e-01 0. -9.87653792e-01 1.56650782e-01 0. -9.87114549e-01 1.60010308e-01 0. -9.86552835e-01 1.63443610e-01 0. -9.85956311e-01 1.67002350e-01 0. -9.85381007e-01 1.70360267e-01 0. -9.84784126e-01 1.73795879e-01 0. -9.84152675e-01 1.77337497e-01 0. -9.83523190e-01 1.80768058e-01 0. -9.82886076e-01 1.84212327e-01 0. -9.82257903e-01 1.87526882e-01 0. -9.81624365e-01 1.90815896e-01 0. -9.80928242e-01 1.94367737e-01 0. -9.80218887e-01 1.97914124e-01 0. -9.79520380e-01 2.01341987e-01 0. -9.78832543e-01 2.04658151e-01 0. -9.78112340e-01 2.08082035e-01 0. -9.77362275e-01 2.11578161e-01 0. -9.76631641e-01 2.14912117e-01 0. -9.75883305e-01 2.18296394e-01 0. -9.75104570e-01 2.21741393e-01 0. -9.74352598e-01 2.25021139e-01 0. -9.73540306e-01 2.28524759e-01 0. -9.72711325e-01 2.32021689e-01 0. -9.71903682e-01 2.35386685e-01 0. -9.71076906e-01 2.38766804e-01 0. -9.70228732e-01 2.42183119e-01 0. -9.69401062e-01 2.45476618e-01 0. -9.68545914e-01 2.48832509e-01 0. -9.67642307e-01 2.52327532e-01 0. -9.66776252e-01 2.55629271e-01 0. -9.65879679e-01 2.58991003e-01 0. -9.64954317e-01 2.62422144e-01 0. -9.64028895e-01 2.65792251e-01 0. -9.63096619e-01 2.69161433e-01 0. -9.62164223e-01 2.72470921e-01 0. -9.61219609e-01 2.75781453e-01 0. -9.60246027e-01 2.79151499e-01 0. -9.59270239e-01 2.82487541e-01 0. -9.58251417e-01 2.85928965e-01 0. -9.57268834e-01 2.89195955e-01 0. -9.56252694e-01 2.92540312e-01 0. -9.55201328e-01 2.95955807e-01 0. -9.54169095e-01 2.99267054e-01 0. -9.53120649e-01 3.02588612e-01 0. -9.52077031e-01 3.05861145e-01 0. -9.51034069e-01 3.09080034e-01 0. -9.49927032e-01 3.12467903e-01 0. -9.48795974e-01 3.15886647e-01 0. -9.47679460e-01 3.19222599e-01 0. -9.46563065e-01 3.22517514e-01 0. -9.45436478e-01 3.25810552e-01 0. -9.44318533e-01 3.29029769e-01 0. -9.43164766e-01 3.32322896e-01 0. -9.41977561e-01 3.35679978e-01 0. -9.40822482e-01 3.38895023e-01 0. -9.39671814e-01 3.42079222e-01 0. -9.38435078e-01 3.45440418e-01 0. -9.37185943e-01 3.48803103e-01 0. -9.35956478e-01 3.52091998e-01 0. -9.34740722e-01 3.55318338e-01 0. -9.33536351e-01 3.58498335e-01 0. -9.32281554e-01 3.61724883e-01 0. -9.30998027e-01 3.65023911e-01 0. -9.29688334e-01 3.68346155e-01 0. -9.28425491e-01 3.71516138e-01 0. -9.27137911e-01 3.74716818e-01 0. -9.25786316e-01 3.78047436e-01 0. -9.24461603e-01 3.81268412e-01 0. -9.23135400e-01 3.84472728e-01 0. -9.21817839e-01 3.87620360e-01 0. -9.20490682e-01 3.90760332e-01 0. -9.19084549e-01 3.94049317e-01 0. -9.17661726e-01 3.97360444e-01 0. -9.16283548e-01 4.00531441e-01 0. -9.14869606e-01 4.03748333e-01 0. -9.13458347e-01 4.06932294e-01 0. -9.12037194e-01 4.10107017e-01 0. -9.10631418e-01 4.13217425e-01 0. -9.09195602e-01 4.16363657e-01 0. -9.07696307e-01 4.19623375e-01 0. -9.06260848e-01 4.22717750e-01 0. -9.04789805e-01 4.25855279e-01 0. -9.03261721e-01 4.29089963e-01 0. -9.01751637e-01 4.32249725e-01 0. -9.00242448e-01 4.35393453e-01 0. -8.98734689e-01 4.38497961e-01 0. -8.97245944e-01 4.41529244e-01 0. -8.95678341e-01 4.44701612e-01 0. -8.94076347e-01 4.47912425e-01 0. -8.92506421e-01 4.51034963e-01 0. -8.90923977e-01 4.54151392e-01 0. -8.89349043e-01 4.57229763e-01 0. -8.87748182e-01 4.60326731e-01 0. -8.86139333e-01 4.63418305e-01 0. -8.84511948e-01 4.66521084e-01 0. -8.82910550e-01 4.69541430e-01 0. -8.81315351e-01 4.72530335e-01 0. -8.79624426e-01 4.75668848e-01 0. -8.77913892e-01 4.78821844e-01 0. -8.76236081e-01 4.81883913e-01 0. -8.74542236e-01 4.84943092e-01 0. -8.72849822e-01 4.87984806e-01 0. -8.71159256e-01 4.91001487e-01 0. -8.69435906e-01 4.94045287e-01 0. -8.67687762e-01 4.97110456e-01 0. -8.65992129e-01 5.00058651e-01 0. -8.64247561e-01 5.03068209e-01 0. -8.62493634e-01 5.06068289e-01 0. -8.60715032e-01 5.09086728e-01 0. -8.58880460e-01 5.12175739e-01 0. -8.57087672e-01 5.15169024e-01 0. -8.55285645e-01 5.18154502e-01 0. -8.53456318e-01 5.21167040e-01 0. -8.51635993e-01 5.24132371e-01 0. -8.49810123e-01 5.27090549e-01 0. -8.48014534e-01 5.29974759e-01 0. -8.46159756e-01 5.32929540e-01 0. -8.44260156e-01 5.35932183e-01 0. -8.42379332e-01 5.38883448e-01 0. -8.40471208e-01 5.41854858e-01 0. -8.38580012e-01 5.44776499e-01 0. -8.36737156e-01 5.47601283e-01 0. -8.34814727e-01 5.50530434e-01 0. -8.32819104e-01 5.53541541e-01 0. -8.30874443e-01 5.56458771e-01 0. -8.28976870e-01 5.59285223e-01 0. -8.27079833e-01 5.62083542e-01 0. -8.25089514e-01 5.65003395e-01 0. -8.23041320e-01 5.67983508e-01 0. -8.21046174e-01 5.70861042e-01 0. -8.19101632e-01 5.73644340e-01 0. -8.17102432e-01 5.76495230e-01 0. -8.15003335e-01 5.79452574e-01 0. -8.12987030e-01 5.82282722e-01 0. -8.10943127e-01 5.85121691e-01 0. -8.08890641e-01 5.87958872e-01 0. -8.06853473e-01 5.90750217e-01 0. -8.04846168e-01 5.93480468e-01 0. -8.02775383e-01 5.96278608e-01 0. -8.00614119e-01 5.99177659e-01 0. -7.98581243e-01 6.01886272e-01 0. -7.96477258e-01 6.04669273e-01 0. -7.94300497e-01 6.07525647e-01 0. -7.92189777e-01 6.10273242e-01 0. -7.90016055e-01 6.13083839e-01 0. -7.87914872e-01 6.15783155e-01 0. -7.85831511e-01 6.18439734e-01 0. -7.83634841e-01 6.21221185e-01 0. -7.81372011e-01 6.24066114e-01 0. -7.79175997e-01 6.26804769e-01 0. -7.76993871e-01 6.29508495e-01 0. -7.74845719e-01 6.32147968e-01 0. -7.72668898e-01 6.34809852e-01 0. -7.70375252e-01 6.37590587e-01 0. -7.68149972e-01 6.40267909e-01 0. -7.65974939e-01 6.42870963e-01 0. -7.63716161e-01 6.45551443e-01 0. -7.61371613e-01 6.48313463e-01 0. -7.59106398e-01 6.50966048e-01 0. -7.56825507e-01 6.53619468e-01 0. -7.54539192e-01 6.56254411e-01 0. -7.52316892e-01 6.58801317e-01 0. -7.50069618e-01 6.61356509e-01 0. -7.47697055e-01 6.64038777e-01 0. -7.45323896e-01 6.66703045e-01 0. -7.43031621e-01 6.69254601e-01 0. -7.40706503e-01 6.71830595e-01 0. -7.38294125e-01 6.74476624e-01 0. -7.35932827e-01 6.77056372e-01 0. -7.33567834e-01 6.79616928e-01 0. -7.31251895e-01 6.82105184e-01 0. -7.28944123e-01 6.84572935e-01 0. -7.26466537e-01 6.87199056e-01 0. -7.24020481e-01 6.89779580e-01 0. -7.21596420e-01 6.92308426e-01 0. -7.19178319e-01 6.94832623e-01 0. -7.16809034e-01 6.97273850e-01 0. -7.14373648e-01 6.99767470e-01 0. -7.11855829e-01 7.02329993e-01 0. -7.09400535e-01 7.04813361e-01 0. -7.06950009e-01 7.07251906e-01 0. -7.04541504e-01 7.09669769e-01 0. -7.02051699e-01 7.12131381e-01 0. -6.99504614e-01 7.14630842e-01 0. -6.97008967e-01 7.17068315e-01 0. -6.94497705e-01 7.19501555e-01 0. -6.92034125e-01 7.21859694e-01 0. -6.89549208e-01 7.24241614e-01 0. -6.86965048e-01 7.26687133e-01 0. -6.84366107e-01 7.29136169e-01 0. -6.81856692e-01 7.31480896e-01 0. -6.79325998e-01 7.33836651e-01 0. -6.76710069e-01 7.36251056e-01 0. -6.74181223e-01 7.38564432e-01 0. -6.71592593e-01 7.40920961e-01 0. -6.69012487e-01 7.43251085e-01 0. -6.66490316e-01 7.45512962e-01 0. -6.63819671e-01 7.47893810e-01 0. -6.61200881e-01 7.50208974e-01 0. -6.58560693e-01 7.52525091e-01 0. -6.55936778e-01 7.54816175e-01 0. -6.53330386e-01 7.57072330e-01 0. -6.50579751e-01 7.59437799e-01 0. -6.47905588e-01 7.61719227e-01 0. -6.45271778e-01 7.63953507e-01 0. -6.42674208e-01 7.66139805e-01 0. -6.40006125e-01 7.68370152e-01 0. -6.37301207e-01 7.70613849e-01 0. -6.34633482e-01 7.72815347e-01 0. -6.31833911e-01 7.75102258e-01 0. -6.29123092e-01 7.77305007e-01 0. -6.26476228e-01 7.79438972e-01 0. -6.23840511e-01 7.81553149e-01 0. -6.21020138e-01 7.83793449e-01 0. -6.18275464e-01 7.85961568e-01 0. -6.15554035e-01 7.88094819e-01 0. -6.12801075e-01 7.90238440e-01 0. -6.10082924e-01 7.92337418e-01 0. -6.07236743e-01 7.94520199e-01 0. -6.04397714e-01 7.96682894e-01 0. -6.01689041e-01 7.98730731e-01 0. -5.98922908e-01 8.00804198e-01 0. -5.96033454e-01 8.02958548e-01 0. -5.93243420e-01 8.05022180e-01 0. -5.90429783e-01 8.07087183e-01 0. -5.87676525e-01 8.09096813e-01 0. -5.84860861e-01 8.11131120e-01 0. -5.81933975e-01 8.13237011e-01 0. -5.79101324e-01 8.15256119e-01 0. -5.76217890e-01 8.17297697e-01 0. -5.73443651e-01 8.19244146e-01 0. -5.70602596e-01 8.21224928e-01 0. -5.67720234e-01 8.23223412e-01 0. -5.64861536e-01 8.25186193e-01 0. -5.61855793e-01 8.27234089e-01 0. -5.58980167e-01 8.29180002e-01 0. -5.56185126e-01 8.31057131e-01 0. -5.53273916e-01 8.32997620e-01 0. -5.50235391e-01 8.35009575e-01 0. -5.47413349e-01 8.36860597e-01 0. -5.44510901e-01 8.38751733e-01 0. -5.41553617e-01 8.40664744e-01 0. -5.38632274e-01 8.42538595e-01 0. -5.35611629e-01 8.44463289e-01 0. -5.32640457e-01 8.46340537e-01 0. -5.29764116e-01 8.48144174e-01 0. -5.26828527e-01 8.49973559e-01 0. -5.23767769e-01 8.51858735e-01 0. -5.20839632e-01 8.53654504e-01 0. -5.17854154e-01 8.55468571e-01 0. -5.14882922e-01 8.57259691e-01 0. -5.11923373e-01 8.59030247e-01 0. -5.08910298e-01 8.60817850e-01 0. -5.05974710e-01 8.62548947e-01 0. -5.02910972e-01 8.64337623e-01 0. -4.99823719e-01 8.66127431e-01 0. -4.96774942e-01 8.67879152e-01 0. -4.93748188e-01 8.69604051e-01 0. -4.90720719e-01 8.71318638e-01 0. -4.87674952e-01 8.73024285e-01 0. -4.84607458e-01 8.74729395e-01 0. -4.81617451e-01 8.76381516e-01 0. -4.78578687e-01 8.78045678e-01 0. -4.75420833e-01 8.79756629e-01 0. -4.72356290e-01 8.81407440e-01 0. -4.69299465e-01 8.83039296e-01 0. -4.66252446e-01 8.84652793e-01 0. -4.63151842e-01 8.86278033e-01 0. -4.59977806e-01 8.87929320e-01 0. -4.56882477e-01 8.89527202e-01 0. -4.53882188e-01 8.91061068e-01 0. -4.50794637e-01 8.92627239e-01 0. -4.47584063e-01 8.94241810e-01 0. -4.44453835e-01 8.95800531e-01 0. -4.41335797e-01 8.97341847e-01 0. -4.38254356e-01 8.98851752e-01 0. -4.35136795e-01 9.00365472e-01 0. -4.31954533e-01 9.01894152e-01 0. -4.28826094e-01 9.03385282e-01 0. -4.25594151e-01 9.04913604e-01 0. -4.22497600e-01 9.06364441e-01 0. -4.19338763e-01 9.07829583e-01 0. -4.16163534e-01 9.09288168e-01 0. -4.13001508e-01 9.10730481e-01 0. -4.09739226e-01 9.12203491e-01 0. -4.06535804e-01 9.13635731e-01 0. -4.03432399e-01 9.15009737e-01 0. -4.00285751e-01 9.16391015e-01 0. -3.97015840e-01 9.17811930e-01 0. -3.93741429e-01 9.19217169e-01 0. -3.90625089e-01 9.20549810e-01 0. -3.87510210e-01 9.21864092e-01 0. -3.84237826e-01 9.23233271e-01 0. -3.80950034e-01 9.24593031e-01 0. -3.77735168e-01 9.25912440e-01 0. -3.74537706e-01 9.27211463e-01 0. -3.71301264e-01 9.28511143e-01 0. -3.67995024e-01 9.29827750e-01 0. -3.64729822e-01 9.31113839e-01 0. -3.61495584e-01 9.32367742e-01 0. -3.58287632e-01 9.33616579e-01 0. -3.55035454e-01 9.34849322e-01 0. -3.51764977e-01 9.36078250e-01 0. -3.48502994e-01 9.37297642e-01 0. -3.45177412e-01 9.38530147e-01 0. -3.41940820e-01 9.39724445e-01 0. -3.38658959e-01 9.40907538e-01 0. -3.35338145e-01 9.42099512e-01 0. -3.32077175e-01 9.43252206e-01 0. -3.28734368e-01 9.44421172e-01 0. -3.25438917e-01 9.45564151e-01 0. -3.22219759e-01 9.46663976e-01 0. -3.18914801e-01 9.47783470e-01 0. -3.15536112e-01 9.48912621e-01 0. -3.12204331e-01 9.50013876e-01 0. -3.08950722e-01 9.51077223e-01 0. -3.05637985e-01 9.52148020e-01 0. -3.02257389e-01 9.53225613e-01 0. -2.98957109e-01 9.54266012e-01 0. -2.95596182e-01 9.55313206e-01 0. -2.92331576e-01 9.56317008e-01 0. -2.89003670e-01 9.57325637e-01 0. -2.85529703e-01 9.58369255e-01 0. -2.82192439e-01 9.59358811e-01 0. -2.78833270e-01 9.60339189e-01 0. -2.75590837e-01 9.61275160e-01 0. -2.72254169e-01 9.62225497e-01 0. -2.68859684e-01 9.63180602e-01 0. -2.65619814e-01 9.64076877e-01 0. -2.62127727e-01 9.65033829e-01 0. -2.58657396e-01 9.65968251e-01 0. -2.55283177e-01 9.66866195e-01 0. -2.51916885e-01 9.67749000e-01 0. -2.48642817e-01 9.68595564e-01 0. -2.45225683e-01 9.69462931e-01 0. -2.41746068e-01 9.70338285e-01 0. -2.38342419e-01 9.71181214e-01 0. -2.34949052e-01 9.72009897e-01 0. -2.31652513e-01 9.72800076e-01 0. -2.28272200e-01 9.73598123e-01 0. -2.24872947e-01 9.74388301e-01 0. -2.21468359e-01 9.75166023e-01 0. -2.17963159e-01 9.75958288e-01 0. -2.14557186e-01 9.76708889e-01 0. -2.11142108e-01 9.77453947e-01 0. -2.07818091e-01 9.78167236e-01 0. -2.04432398e-01 9.78881538e-01 0. -2.00892910e-01 9.79614139e-01 0. -1.97476923e-01 9.80306208e-01 0. -1.94068283e-01 9.80987132e-01 0. -1.90714180e-01 9.81645226e-01 0. -1.87286615e-01 9.82304811e-01 0. -1.83863863e-01 9.82950628e-01 0. -1.80498406e-01 9.83572721e-01 0. -1.76980063e-01 9.84218001e-01 0. -1.73442975e-01 9.84847069e-01 0. -1.70019940e-01 9.85439956e-01 0. -1.66586816e-01 9.86026585e-01 0. -1.63234040e-01 9.86586750e-01 0. -1.59870610e-01 9.87137079e-01 0. -1.56355888e-01 9.87700641e-01 0. -1.52788028e-01 9.88259971e-01 0. -1.49333298e-01 9.88784254e-01 0. -1.45861998e-01 9.89304364e-01 0. -1.42421603e-01 9.89804626e-01 0. -1.39081717e-01 9.90280747e-01 0. -1.35637552e-01 9.90759194e-01 0. -1.32056817e-01 9.91241097e-01 0. -1.28700063e-01 9.91682291e-01 0. -1.25251040e-01 9.92124200e-01 0. -1.21766783e-01 9.92557943e-01 0. -1.18297935e-01 9.92977381e-01 0. -1.14713140e-01 9.93397772e-01 0. -1.11246668e-01 9.93792117e-01 0. -1.07762538e-01 9.94174659e-01 0. -1.04291819e-01 9.94544804e-01 0. -1.00820988e-01 9.94903505e-01 0. -9.74332839e-02 9.95241344e-01 0. -9.40674469e-02 9.95565414e-01 0. -9.04994980e-02 9.95895505e-01 0. -8.69398713e-02 9.96213675e-01 0. -8.34494531e-02 9.96511340e-01 0. -7.99563155e-02 9.96797681e-01 0. -7.65768811e-02 9.97061193e-01 0. -7.30984360e-02 9.97324586e-01 0. -6.95100576e-02 9.97579038e-01 0. -6.60291463e-02 9.97817159e-01 0. -6.25485852e-02 9.98039424e-01 0. -5.91884218e-02 9.98246670e-01 0. -5.57255670e-02 9.98445630e-01 0. -5.21648824e-02 9.98636425e-01 0. -4.87147421e-02 9.98813748e-01 0. -4.51504663e-02 9.98978257e-01 0. -4.16494980e-02 9.99131978e-01 0. -3.81545797e-02 9.99270678e-01 0. -3.47588919e-02 9.99395728e-01 0. -3.12899351e-02 9.99508500e-01 0. -2.77813096e-02 9.99612629e-01 0. -2.42880601e-02 9.99708056e-01 0. -2.07177829e-02 9.99781966e-01 0. -1.73012689e-02 9.99853015e-01 0. -1.38293579e-02 9.99899268e-01 0. -1.03503838e-02 9.99944210e-01 0. -6.93674432e-03 9.99980569e-01 0. -3.34371184e-03 9.99998629e-01 0. 2.32413076e-04 9.99999881e-01 0. 3.72070097e-03 9.99998450e-01 0. 7.18242256e-03 9.99978244e-01 0. 1.06063206e-02 9.99942124e-01 0. 1.39939068e-02 9.99897122e-01 0. 1.75721236e-02 9.99850214e-01 0. 2.11675763e-02 9.99773920e-01 0. 2.46743746e-02 9.99695182e-01 0. 2.81732921e-02 9.99604762e-01 0. 3.16680558e-02 9.99498248e-01 0. 3.50616798e-02 9.99386013e-01 0. 3.85123901e-02 9.99258101e-01 0. 4.21284474e-02 9.99112964e-01 0. 4.56301346e-02 9.98957276e-01 0. 4.90978509e-02 9.98793840e-01 0. 5.24846129e-02 9.98618782e-01 0. 5.59455082e-02 9.98433232e-01 0. 5.94736859e-02 9.98229623e-01 0. 6.29390925e-02 9.98014271e-01 0. 6.65288270e-02 9.97783780e-01 0. 6.99900538e-02 9.97545123e-01 0. 7.34678954e-02 9.97298062e-01 0. 7.69739151e-02 9.97031391e-01 0. 8.03597942e-02 9.96765256e-01 0. 8.38263258e-02 9.96479869e-01 0. 8.73817429e-02 9.96174693e-01 0. 9.08661634e-02 9.95862007e-01 0. 9.43334326e-02 9.95539844e-01 0. 9.77504477e-02 9.95211065e-01 0. 1.01205252e-01 9.94865596e-01 0. 1.04685716e-01 9.94505346e-01 0. 1.08151577e-01 9.94134367e-01 0. 1.11735739e-01 9.93736565e-01 0. 1.15107939e-01 9.93351400e-01 0. 1.18557245e-01 9.92945969e-01 0. 1.22034319e-01 9.92524981e-01 0. 1.25480250e-01 9.92095768e-01 0. 1.29055977e-01 9.91635382e-01 0. 1.32507831e-01 9.91181016e-01 0. 1.35971010e-01 9.90713179e-01 0. 1.39330551e-01 9.90247428e-01 0. 1.42801046e-01 9.89750504e-01 0. 1.46246180e-01 9.89247441e-01 0. 1.49676964e-01 9.88732338e-01 0. 1.53227851e-01 9.88191545e-01 0. 1.56599313e-01 9.87660050e-01 0. 1.60020992e-01 9.87113059e-01 0. 1.63494870e-01 9.86544907e-01 0. 1.66828305e-01 9.85985160e-01 0. 1.70341298e-01 9.85384464e-01 0. 1.73875779e-01 9.84771073e-01 0. 1.77308917e-01 9.84159768e-01 0. 1.80781588e-01 9.83522475e-01 0. 1.84100792e-01 9.82907116e-01 0. 1.87434912e-01 9.82276261e-01 0. 1.90894902e-01 9.81610060e-01 0. 1.94379881e-01 9.80925262e-01 0. 1.97888166e-01 9.80224013e-01 0. 2.01320320e-01 9.79525030e-01 0. 2.04732418e-01 9.78816569e-01 0. 2.08067745e-01 9.78115737e-01 0. 2.11430028e-01 9.77392435e-01 0. 2.14972332e-01 9.76619244e-01 0. 2.18400672e-01 9.75859523e-01 0. 2.21802592e-01 9.75089967e-01 0. 2.25124076e-01 9.74330544e-01 0. 2.28505105e-01 9.73545074e-01 0. 2.31929421e-01 9.72733617e-01 0. 2.35207528e-01 9.71947610e-01 0. 2.38689020e-01 9.71096098e-01 0. 2.42170751e-01 9.70232248e-01 0. 2.45539814e-01 9.69384372e-01 0. 2.48903856e-01 9.68528986e-01 0. 2.52216160e-01 9.67670977e-01 0. 2.55502135e-01 9.66809571e-01 0. 2.58984476e-01 9.65880930e-01 0. 2.62463152e-01 9.64943409e-01 0. 2.65797377e-01 9.64027345e-01 0. 2.69063413e-01 9.63123977e-01 0. 2.72431254e-01 9.62175071e-01 0. 2.75799125e-01 9.61216450e-01 0. 2.79135913e-01 9.60251331e-01 0. 2.82588422e-01 9.59240675e-01 0. 2.85871297e-01 9.58270133e-01 0. 2.89181411e-01 9.57271159e-01 0. 2.92545587e-01 9.56251144e-01 0. 2.95823246e-01 9.55244005e-01 0. 2.99263924e-01 9.54170644e-01 0. 3.02535236e-01 9.53137040e-01 0. 3.05854827e-01 9.52078164e-01 0. 3.09193432e-01 9.50998366e-01 0. 3.12499315e-01 9.49917793e-01 0. 3.15811157e-01 9.48821545e-01 0. 3.19018424e-01 9.47749376e-01 0. 3.22417319e-01 9.46597159e-01 0. 3.25816482e-01 9.45433021e-01 0. 3.29106301e-01 9.44291651e-01 0. 3.32373768e-01 9.43147838e-01 0. 3.35611433e-01 9.42002833e-01 0. 3.38872939e-01 9.40831423e-01 0. 3.42258841e-01 9.39606071e-01 0. 3.45523804e-01 9.38402414e-01 0. 3.48777086e-01 9.37195361e-01 0. 3.52005869e-01 9.35988128e-01 0. 3.55259866e-01 9.34764802e-01 0. 3.58511955e-01 9.33531702e-01 0. 3.61764848e-01 9.32266772e-01 0. 3.65070015e-01 9.30978477e-01 0. 3.68275911e-01 9.29715812e-01 0. 3.71528804e-01 9.28419828e-01 0. 3.74730110e-01 9.27132547e-01 0. 3.77957702e-01 9.25822079e-01 0. 3.81180376e-01 9.24497843e-01 0. 3.84402931e-01 9.23163652e-01 0. 3.87695819e-01 9.21786547e-01 0. 3.90828222e-01 9.20461893e-01 0. 3.94043863e-01 9.19087648e-01 0. 3.97254080e-01 9.17706728e-01 0. 4.00356442e-01 9.16361570e-01 0. 4.03628469e-01 9.14922655e-01 0. 4.06895399e-01 9.13474560e-01 0. 4.10086155e-01 9.12046254e-01 0. 4.13267821e-01 9.10609305e-01 0. 4.16375458e-01 9.09190357e-01 0. 4.19468492e-01 9.07767773e-01 0. 4.22682077e-01 9.06277776e-01 0. 4.25918877e-01 9.04759169e-01 0. 4.29097563e-01 9.03256834e-01 0. 4.32167500e-01 9.01790857e-01 0. 4.35313314e-01 9.00280714e-01 0. 4.38434780e-01 8.98765743e-01 0. 4.41572547e-01 8.97223890e-01 0. 4.44785684e-01 8.95636618e-01 0. 4.47923005e-01 8.94071162e-01 0. 4.51018423e-01 8.92515659e-01 0. 4.54080194e-01 8.90961587e-01 0. 4.57120478e-01 8.89404893e-01 0. 4.60283369e-01 8.87769461e-01 0. 4.63333100e-01 8.86185944e-01 0. 4.66463774e-01 8.84540439e-01 0. 4.69605625e-01 8.82876456e-01 0. 4.72676784e-01 8.81236017e-01 0. 4.75776345e-01 8.79565835e-01 0. 4.78757232e-01 8.77950072e-01 0. 4.81824309e-01 8.76268208e-01 0. 4.84967917e-01 8.74528825e-01 0. 4.88035977e-01 8.72821569e-01 0. 4.91082847e-01 8.71113360e-01 0. 4.94007260e-01 8.69457006e-01 0. 4.97048914e-01 8.67722988e-01 0. 5.00057876e-01 8.65992546e-01 0. 5.03109515e-01 8.64223421e-01 0. 5.06195962e-01 8.62419248e-01 0. 5.09137452e-01 8.60684812e-01 0. 5.12107730e-01 8.58921945e-01 0. 5.15103102e-01 8.57128203e-01 0. 5.18093109e-01 8.55322361e-01 0. 5.21130443e-01 8.53478074e-01 0. 5.24052501e-01 8.51684690e-01 0. 5.27033806e-01 8.49846900e-01 0. 5.29992461e-01 8.48002970e-01 0. 5.32916784e-01 8.46167207e-01 0. 5.35907865e-01 8.44275296e-01 0. 5.38813651e-01 8.42423379e-01 0. 5.41841030e-01 8.40479553e-01 0. 5.44702590e-01 8.38628411e-01 0. 5.47573328e-01 8.36754262e-01 0. 5.50513804e-01 8.34825575e-01 0. 5.53339481e-01 8.32953215e-01 0. 5.56357145e-01 8.30942094e-01 0. 5.59224784e-01 8.29015553e-01 0. 5.62089562e-01 8.27075779e-01 0. 5.65019369e-01 8.25077057e-01 0. 5.67849100e-01 8.23133111e-01 0. 5.70592582e-01 8.21232438e-01 0. 5.73447168e-01 8.19242418e-01 0. 5.76309800e-01 8.17230523e-01 0. 5.79272926e-01 8.15132976e-01 0. 5.82022250e-01 8.13172162e-01 0. 5.84362626e-01 8.11492145e-01 0. 5.87784767e-01 8.09016705e-01 0. 5.90887070e-01 8.06754231e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.12944508e-01 7.01220393e-01 0. 7.14702904e-01 6.99427605e-01 0. 7.17331767e-01 6.96730912e-01 0. 7.19504476e-01 6.94484830e-01 0. 7.21900403e-01 6.91994488e-01 0. 7.24352777e-01 6.89429283e-01 0. 7.26654947e-01 6.87001705e-01 0. 7.29045212e-01 6.84463203e-01 0. 7.31488883e-01 6.81851506e-01 0. 7.33828902e-01 6.79333925e-01 0. 7.36151338e-01 6.76818848e-01 0. 7.38457561e-01 6.74298704e-01 0. 7.40878403e-01 6.71640635e-01 0. 7.43272781e-01 6.68988526e-01 0. 7.45594859e-01 6.66397393e-01 0. 7.47856200e-01 6.63861573e-01 0. 7.50120223e-01 6.61300302e-01 0. 7.52443552e-01 6.58653378e-01 0. 7.54781783e-01 6.55975401e-01 0. 7.57096529e-01 6.53302133e-01 0. 7.59375691e-01 6.50653243e-01 0. 7.61571229e-01 6.48078203e-01 0. 7.63820589e-01 6.45428777e-01 0. 7.66072869e-01 6.42752826e-01 0. 7.68343091e-01 6.40037954e-01 0. 7.70638227e-01 6.37270570e-01 0. 7.72798777e-01 6.34651899e-01 0. 7.75011301e-01 6.31945312e-01 0. 7.77259648e-01 6.29179180e-01 0. 7.79456496e-01 6.26455665e-01 0. 7.81582177e-01 6.23803556e-01 0. 7.83698022e-01 6.21140957e-01 0. 7.85912395e-01 6.18337452e-01 0. 7.88120151e-01 6.15521431e-01 0. 7.90273428e-01 6.12755537e-01 0. 7.92374790e-01 6.10034764e-01 0. 7.94415355e-01 6.07374370e-01 0. 7.96596229e-01 6.04511976e-01 0. 7.98743427e-01 6.01671696e-01 0. 8.00842702e-01 5.98872125e-01 0. 8.02887201e-01 5.96130311e-01 0. 8.04893374e-01 5.93417406e-01 0. 8.07007313e-01 5.90539455e-01 0. 8.09130013e-01 5.87628126e-01 0. 8.11189771e-01 5.84776938e-01 0. 8.13223779e-01 5.81951976e-01 0. 8.15180063e-01 5.79208314e-01 0. 8.17150116e-01 5.76427519e-01 0. 8.19166243e-01 5.73555708e-01 0. 8.21217954e-01 5.70612788e-01 0. 8.23237956e-01 5.67697406e-01 0. 8.25138867e-01 5.64928830e-01 0. 8.27159524e-01 5.61966181e-01 0. 8.29123437e-01 5.59064746e-01 0. 8.31028998e-01 5.56225955e-01 0. 8.32977951e-01 5.53305447e-01 0. 8.34849298e-01 5.50477684e-01 0. 8.36833954e-01 5.47453344e-01 0. 8.38788986e-01 5.44455588e-01 0. 8.40649486e-01 5.41578233e-01 0. 8.42465103e-01 5.38750291e-01 0. 8.44328642e-01 5.35822272e-01 0. 8.46277297e-01 5.32743931e-01 0. 8.48198116e-01 5.29677033e-01 0. 8.50030839e-01 5.26734412e-01 0. 8.51804614e-01 5.23856699e-01 0. 8.53586495e-01 5.20952225e-01 0. 8.55403900e-01 5.17959952e-01 0. 8.57207179e-01 5.14971018e-01 0. 8.59044731e-01 5.11898816e-01 0. 8.60880911e-01 5.08805275e-01 0. 8.62604856e-01 5.05878627e-01 0. 8.64356041e-01 5.02879322e-01 0. 8.66113126e-01 4.99850094e-01 0. 8.67844343e-01 4.96834278e-01 0. 8.69593143e-01 4.93764549e-01 0. 8.71265173e-01 4.90816176e-01 0. 8.72999012e-01 4.87718910e-01 0. 8.74706030e-01 4.84649688e-01 0. 8.76392841e-01 4.81596172e-01 0. 8.78057003e-01 4.78557527e-01 0. 8.79689038e-01 4.75547671e-01 0. 8.81375909e-01 4.72415328e-01 0. 8.83068204e-01 4.69245106e-01 0. 8.84704411e-01 4.66152668e-01 0. 8.86283815e-01 4.63144481e-01 0. 8.87839794e-01 4.60150450e-01 0. 8.89483094e-01 4.56967562e-01 0. 8.91124427e-01 4.53758061e-01 0. 8.92699063e-01 4.50653732e-01 0. 8.94264638e-01 4.47539032e-01 0. 8.95792067e-01 4.44471836e-01 0. 8.97322059e-01 4.41375554e-01 0. 8.98869157e-01 4.38218862e-01 0. 9.00381446e-01 4.35102701e-01 0. 9.01952088e-01 4.31835502e-01 0. 9.03406918e-01 4.28783983e-01 0. 9.04883504e-01 4.25654650e-01 0. 9.06377196e-01 4.22470361e-01 0. 9.07842815e-01 4.19310421e-01 0. 9.09343064e-01 4.16042477e-01 0. 9.10754681e-01 4.12945777e-01 0. 9.12175119e-01 4.09800828e-01 0. 9.13611054e-01 4.06588137e-01 0. 9.15023685e-01 4.03400242e-01 0. 9.16431129e-01 4.00194466e-01 0. 9.17786181e-01 3.97073328e-01 0. 9.19197977e-01 3.93786043e-01 0. 9.20602918e-01 3.90498817e-01 0. 9.21962023e-01 3.87278110e-01 0. 9.23271000e-01 3.84146333e-01 0. 9.24567580e-01 3.81012022e-01 0. 9.25925791e-01 3.77701610e-01 0. 9.27283049e-01 3.74361008e-01 0. 9.28583801e-01 3.71119767e-01 0. 9.29840803e-01 3.67965728e-01 0. 9.31077600e-01 3.64824563e-01 0. 9.32371795e-01 3.61489743e-01 0. 9.33644295e-01 3.58214438e-01 0. 9.34869766e-01 3.54980171e-01 0. 9.36140001e-01 3.51601660e-01 0. 9.37335670e-01 3.48398000e-01 0. 9.38543618e-01 3.45147401e-01 0. 9.39756215e-01 3.41853827e-01 0. 9.40929711e-01 3.38601202e-01 0. 9.42137957e-01 3.35227787e-01 0. 9.43277061e-01 3.32008123e-01 0. 9.44420993e-01 3.28735381e-01 0. 9.45591867e-01 3.25356364e-01 0. 9.46708083e-01 3.22089583e-01 0. 9.47811306e-01 3.18834990e-01 0. 9.48896646e-01 3.15584898e-01 0. 9.50020254e-01 3.12186718e-01 0. 9.51127350e-01 3.08799386e-01 0. 9.52198505e-01 3.05480689e-01 0. 9.53237951e-01 3.02221656e-01 0. 9.54256713e-01 2.98987269e-01 0. 9.55319226e-01 2.95572788e-01 0. 9.56377745e-01 2.92128235e-01 0. 9.57381129e-01 2.88824439e-01 0. 9.58362222e-01 2.85549790e-01 0. 9.59330857e-01 2.82284856e-01 0. 9.60330427e-01 2.78867364e-01 0. 9.61295962e-01 2.75513500e-01 0. 9.62256610e-01 2.72144228e-01 0. 9.63215232e-01 2.68730283e-01 0. 9.64124322e-01 2.65449673e-01 0. 9.65047121e-01 2.62079865e-01 0. 9.65980530e-01 2.58612961e-01 0. 9.66877759e-01 2.55240202e-01 0. 9.67758358e-01 2.51882851e-01 0. 9.68617380e-01 2.48562843e-01 0. 9.69466507e-01 2.45213553e-01 0. 9.70330119e-01 2.41782919e-01 0. 9.71162140e-01 2.38423049e-01 0. 9.71992254e-01 2.35017642e-01 0. 9.72784221e-01 2.31721267e-01 0. 9.73603725e-01 2.28253603e-01 0. 9.74414527e-01 2.24755034e-01 0. 9.75189567e-01 2.21370354e-01 0. 9.75964427e-01 2.17932850e-01 0. 9.76700425e-01 2.14596942e-01 0. 9.77438092e-01 2.11214766e-01 0. 9.78191435e-01 2.07702652e-01 0. 9.78912711e-01 2.04284355e-01 0. 9.79615092e-01 2.00886443e-01 0. 9.80296850e-01 1.97530508e-01 0. 9.80971336e-01 1.94142431e-01 0. 9.81648982e-01 1.90697297e-01 0. 9.82308388e-01 1.87258109e-01 0. 9.82969940e-01 1.83762506e-01 0. 9.83585894e-01 1.80423304e-01 0. 9.84220982e-01 1.76967204e-01 0. 9.84840393e-01 1.73483148e-01 0. 9.85431850e-01 1.70063540e-01 0. 9.86012936e-01 1.66669354e-01 0. 9.86572385e-01 1.63319096e-01 0. 9.87149656e-01 1.59793541e-01 0. 9.87718701e-01 1.56234995e-01 0. 9.88255501e-01 1.52802601e-01 0. 9.88768995e-01 1.49438798e-01 0. 9.89273310e-01 1.46072820e-01 0. 9.89790201e-01 1.42524138e-01 0. 9.90294755e-01 1.38983577e-01 0. 9.90770757e-01 1.35557741e-01 0. 9.91237521e-01 1.32083371e-01 0. 9.91686583e-01 1.28674790e-01 0. 9.92125392e-01 1.25246167e-01 0. 9.92566884e-01 1.21693321e-01 0. 9.92985129e-01 1.18217543e-01 0. 9.93393004e-01 1.14750102e-01 0. 9.93777275e-01 1.11380301e-01 0. 9.94160950e-01 1.07894331e-01 0. 9.94532526e-01 1.04426287e-01 0. 9.94887769e-01 1.00971200e-01 0. 9.95246887e-01 9.73851755e-02 0. 9.95569348e-01 9.40189660e-02 0. 9.95892763e-01 9.05335397e-02 0. 9.96203959e-01 8.70606974e-02 0. 9.96500254e-01 8.35787654e-02 0. 9.96790767e-01 8.00434053e-02 0. 9.97059464e-01 7.66136497e-02 0. 9.97327447e-01 7.30444416e-02 0. 9.97576892e-01 6.95353672e-02 0. 9.97814000e-01 6.60722181e-02 0. 9.98033106e-01 6.26700893e-02 0. 9.98239815e-01 5.92777915e-02 0. 9.98446226e-01 5.57246022e-02 0. 9.98640180e-01 5.21276221e-02 0. 9.98817503e-01 4.86231036e-02 0. 9.98974681e-01 4.52311523e-02 0. 9.99122441e-01 4.18950431e-02 0. 9.99261916e-01 3.83921899e-02 0. 9.99390483e-01 3.48867364e-02 0. 9.99510229e-01 3.12851258e-02 0. 9.99616086e-01 2.76894122e-02 0. 9.99706030e-01 2.43118946e-02 0. 9.99780118e-01 2.09306758e-02 0. 9.99851406e-01 1.74297933e-02 0. 9.99899685e-01 1.39286071e-02 0. 9.99945164e-01 1.04029635e-02 0. 9.99980211e-01 6.94888830e-03 0. 9.99998689e-01 3.36152362e-03 0. 9.99999881e-01 -1.27273219e-04 0. 9.99998450e-01 -3.60056199e-03 0. 9.99977708e-01 -7.15485448e-03 0. 9.99942601e-01 -1.05323810e-02 0. 9.99896169e-01 -1.40469810e-02 0. 9.99845624e-01 -1.76733974e-02 0. 9.99777377e-01 -2.10940428e-02 0. 9.99699295e-01 -2.45844703e-02 0. 9.99605000e-01 -2.80772336e-02 0. 9.99501705e-01 -3.15394104e-02 0. 9.99386966e-01 -3.50325592e-02 0. 9.99260247e-01 -3.84366252e-02 0. 9.99121249e-01 -4.19219546e-02 0. 9.98964131e-01 -4.54769656e-02 0. 9.98795748e-01 -4.90670353e-02 0. 9.98616099e-01 -5.25493398e-02 0. 9.98430729e-01 -5.59674203e-02 0. 9.98237073e-01 -5.93354180e-02 0. 9.98022079e-01 -6.28238842e-02 0. 9.97792304e-01 -6.64030313e-02 0. 9.97548342e-01 -6.99445009e-02 0. 9.97297108e-01 -7.34693632e-02 0. 9.97041523e-01 -7.68514276e-02 0. 9.96771514e-01 -8.02804902e-02 0. 9.96488690e-01 -8.37164298e-02 0. 9.96181965e-01 -8.72927159e-02 0. 9.95871365e-01 -9.07673389e-02 0. 9.95556772e-01 -9.41571742e-02 0. 9.95222092e-01 -9.76370722e-02 0. 9.94865596e-01 -1.01198487e-01 0. 9.94507253e-01 -1.04665235e-01 0. 9.94137883e-01 -1.08106263e-01 0. 9.93753374e-01 -1.11597590e-01 0. 9.93369102e-01 -1.14955515e-01 0. 9.92950678e-01 -1.18522182e-01 0. 9.92529750e-01 -1.21999808e-01 0. 9.92098331e-01 -1.25474244e-01 0. 9.91640449e-01 -1.29019812e-01 0. 9.91193891e-01 -1.32412478e-01 0. 9.90733027e-01 -1.35828033e-01 0. 9.90240693e-01 -1.39372766e-01 0. 9.89753485e-01 -1.42787844e-01 0. 9.89255309e-01 -1.46192595e-01 0. 9.88737881e-01 -1.49648890e-01 0. 9.88209844e-01 -1.53094426e-01 0. 9.87669230e-01 -1.56547457e-01 0. 9.87119436e-01 -1.59983680e-01 0. 9.86554742e-01 -1.63436010e-01 0. 9.85981345e-01 -1.66856259e-01 0. 9.85368073e-01 -1.70427173e-01 0. 9.84773397e-01 -1.73860386e-01 0. 9.84176517e-01 -1.77205801e-01 0. 9.83561039e-01 -1.80560648e-01 0. 9.82926428e-01 -1.84005871e-01 0. 9.82267916e-01 -1.87473893e-01 0. 9.81590807e-01 -1.90991506e-01 0. 9.80916500e-01 -1.94429263e-01 0. 9.80243921e-01 -1.97786421e-01 0. 9.79568899e-01 -2.01105043e-01 0. 9.78857994e-01 -2.04540342e-01 0. 9.78121638e-01 -2.08036810e-01 0. 9.77392495e-01 -2.11434752e-01 0. 9.76661921e-01 -2.14777291e-01 0. 9.75898921e-01 -2.18225524e-01 0. 9.75131035e-01 -2.21622735e-01 0. 9.74345624e-01 -2.25058794e-01 0. 9.73556042e-01 -2.28454798e-01 0. 9.72741842e-01 -2.31895342e-01 0. 9.71959889e-01 -2.35155538e-01 0. 9.71114099e-01 -2.38615170e-01 0. 9.70269620e-01 -2.42022142e-01 0. 9.69409764e-01 -2.45440066e-01 0. 9.68523860e-01 -2.48919919e-01 0. 9.67676878e-01 -2.52192408e-01 0. 9.66801167e-01 -2.55537242e-01 0. 9.65889335e-01 -2.58958846e-01 0. 9.65009451e-01 -2.62218297e-01 0. 9.64063108e-01 -2.65666991e-01 0. 9.63131726e-01 -2.69036293e-01 0. 9.62185502e-01 -2.72394866e-01 0. 9.61194336e-01 -2.75866389e-01 0. 9.60263133e-01 -2.79090375e-01 0. 9.59305942e-01 -2.82366186e-01 0. 9.58284438e-01 -2.85818100e-01 0. 9.57263708e-01 -2.89208978e-01 0. 9.56250250e-01 -2.92547673e-01 0. 9.55239117e-01 -2.95838594e-01 0. 9.54232097e-01 -2.99066454e-01 0. 9.53191161e-01 -3.02366555e-01 0. 9.52096462e-01 -3.05797279e-01 0. 9.50982153e-01 -3.09242576e-01 0. 9.49901283e-01 -3.12547326e-01 0. 9.48829412e-01 -3.15789551e-01 0. 9.47769046e-01 -3.18958372e-01 0. 9.46630299e-01 -3.22318912e-01 0. 9.45488155e-01 -3.25655162e-01 0. 9.44335759e-01 -3.28977793e-01 0. 9.43204165e-01 -3.32212418e-01 0. 9.42046881e-01 -3.35480005e-01 0. 9.40841615e-01 -3.38845015e-01 0. 9.39645886e-01 -3.42153788e-01 0. 9.38444614e-01 -3.45412970e-01 0. 9.37221766e-01 -3.48702639e-01 0. 9.36043501e-01 -3.51857960e-01 0. 9.34810758e-01 -3.55132163e-01 0. 9.33566332e-01 -3.58417720e-01 0. 9.32300329e-01 -3.61675262e-01 0. 9.31008160e-01 -3.65001500e-01 0. 9.29726958e-01 -3.68248433e-01 0. 9.28447008e-01 -3.71461391e-01 0. 9.27134156e-01 -3.74726325e-01 0. 9.25865114e-01 -3.77852321e-01 0. 9.24505532e-01 -3.81164372e-01 0. 9.23160017e-01 -3.84414017e-01 0. 9.21815395e-01 -3.87630403e-01 0. 9.20408905e-01 -3.90950292e-01 0. 9.19078708e-01 -3.94067019e-01 0. 9.17749524e-01 -3.97157043e-01 0. 9.16324914e-01 -4.00437802e-01 0. 9.14860785e-01 -4.03768539e-01 0. 9.13437843e-01 -4.06977266e-01 0. 9.12038028e-01 -4.10105556e-01 0. 9.10629034e-01 -4.13222671e-01 0. 9.09219503e-01 -4.16311800e-01 0. 9.07725275e-01 -4.19560820e-01 0. 9.06229436e-01 -4.22783971e-01 0. 9.04713869e-01 -4.26016629e-01 0. 9.03267503e-01 -4.29076195e-01 0. 9.01821136e-01 -4.32103604e-01 0. 9.00302947e-01 -4.35267746e-01 0. 8.98740649e-01 -4.38483983e-01 0. 8.97174537e-01 -4.41674262e-01 0. 8.95637453e-01 -4.44783539e-01 0. 8.94088507e-01 -4.47888017e-01 0. 8.92585933e-01 -4.50879395e-01 0. 8.90994132e-01 -4.54014987e-01 0. 8.89358044e-01 -4.57210749e-01 0. 8.87746811e-01 -4.60328400e-01 0. 8.86136591e-01 -4.63425905e-01 0. 8.84534299e-01 -4.66477245e-01 0. 8.82929385e-01 -4.69504356e-01 0. 8.81296992e-01 -4.72562999e-01 0. 8.79579365e-01 -4.75750774e-01 0. 8.77918839e-01 -4.78813708e-01 0. 8.76287103e-01 -4.81788874e-01 0. 8.74593794e-01 -4.84851539e-01 0. 8.72865200e-01 -4.87958819e-01 0. 8.71143520e-01 -4.91029918e-01 0. 8.69433701e-01 -4.94048655e-01 0. 8.67705405e-01 -4.97082919e-01 0. 8.65960181e-01 -5.00112891e-01 0. 8.64215493e-01 -5.03122330e-01 0. 8.62490535e-01 -5.06074369e-01 0. 8.60702336e-01 -5.09108961e-01 0. 8.58910859e-01 -5.12124360e-01 0. 8.57086957e-01 -5.15171885e-01 0. 8.55255187e-01 -5.18204629e-01 0. 8.53478551e-01 -5.21129727e-01 0. 8.51706684e-01 -5.24016261e-01 0. 8.49879086e-01 -5.26980877e-01 0. 8.47991168e-01 -5.30007660e-01 0. 8.46091568e-01 -5.33037305e-01 0. 8.44258547e-01 -5.35934865e-01 0. 8.42436671e-01 -5.38793087e-01 0. 8.40502024e-01 -5.41806161e-01 0. 8.38547349e-01 -5.44826865e-01 0. 8.36655140e-01 -5.47726214e-01 0. 8.34733665e-01 -5.50652981e-01 0. 8.32852006e-01 -5.53490758e-01 0. 8.30963612e-01 -5.56323767e-01 0. 8.29034686e-01 -5.59199572e-01 0. 8.27024341e-01 -5.62164843e-01 0. 8.24998260e-01 -5.65135300e-01 0. 8.23039889e-01 -5.67986131e-01 0. 8.21096897e-01 -5.70788145e-01 0. 8.19117188e-01 -5.73624671e-01 0. 8.17095101e-01 -5.76505303e-01 0. 8.15059602e-01 -5.79376817e-01 0. 8.13026011e-01 -5.82228839e-01 0. 8.11029077e-01 -5.85001230e-01 0. 8.08941782e-01 -5.87888837e-01 0. 8.06842685e-01 -5.90764582e-01 0. 8.04759860e-01 -5.93599379e-01 0. 8.02672386e-01 -5.96417904e-01 0. 8.00659478e-01 -5.99117696e-01 0. 7.98573911e-01 -6.01896107e-01 0. 7.96463490e-01 -6.04686618e-01 0. 7.94335663e-01 -6.07479751e-01 0. 7.92211533e-01 -6.10244930e-01 0. 7.90149152e-01 -6.12911522e-01 0. 7.87936270e-01 -6.15754843e-01 0. 7.85735130e-01 -6.18562222e-01 0. 7.83624709e-01 -6.21232092e-01 0. 7.81501472e-01 -6.23904228e-01 0. 7.79261470e-01 -6.26698554e-01 0. 7.77016282e-01 -6.29480839e-01 0. 7.74853706e-01 -6.32137120e-01 0. 7.72716582e-01 -6.34750903e-01 0. 7.70482779e-01 -6.37460828e-01 0. 7.68275678e-01 -6.40118182e-01 0. 7.66039670e-01 -6.42793417e-01 0. 7.63733089e-01 -6.45530999e-01 0. 7.61486948e-01 -6.48178875e-01 0. 7.59260654e-01 -6.50784969e-01 0. 7.56998956e-01 -6.53416395e-01 0. 7.54683256e-01 -6.56090140e-01 0. 7.52329051e-01 -6.58786297e-01 0. 7.49982834e-01 -6.61457479e-01 0. 7.47720242e-01 -6.64014220e-01 0. 7.45460987e-01 -6.66548610e-01 0. 7.43085563e-01 -6.69196129e-01 0. 7.40745187e-01 -6.71788037e-01 0. 7.38394678e-01 -6.74367666e-01 0. 7.36036539e-01 -6.76942229e-01 0. 7.33734608e-01 -6.79436207e-01 0. 7.31368363e-01 -6.81980848e-01 0. 7.28935063e-01 -6.84580922e-01 0. 7.26491690e-01 -6.87173128e-01 0. 7.24098682e-01 -6.89698458e-01 0. 7.21665561e-01 -6.92237914e-01 0. 7.19274461e-01 -6.94732666e-01 0. 7.16863275e-01 -6.97218180e-01 0. 7.14501321e-01 -6.99636817e-01 0. 7.12200224e-01 -7.01978624e-01 0. 7.10181296e-01 -7.04018116e-01 0. 7.07571447e-01 -7.06641138e-01 0. 7.04980850e-01 -7.09226251e-01 0. 7.03022361e-01 -7.11167753e-01 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 5.66909552e-01 -8.23780060e-01 0. 5.64270079e-01 -8.25589895e-01 0. 5.61944962e-01 -8.27173591e-01 0. 5.59117675e-01 -8.29089344e-01 0. 5.56238115e-01 -8.31021965e-01 0. 5.53269982e-01 -8.33000302e-01 0. 5.50338864e-01 -8.34940970e-01 0. 5.47505260e-01 -8.36800456e-01 0. 5.44600785e-01 -8.38694692e-01 0. 5.41687191e-01 -8.40579271e-01 0. 5.38757682e-01 -8.42458844e-01 0. 5.35810351e-01 -8.44336212e-01 0. 5.32867789e-01 -8.46199870e-01 0. 5.29928327e-01 -8.48040164e-01 0. 5.26957452e-01 -8.49892974e-01 0. 5.23985028e-01 -8.51726055e-01 0. 5.21021307e-01 -8.53545964e-01 0. 5.18035293e-01 -8.55357468e-01 0. 5.15047193e-01 -8.57161283e-01 0. 5.11975110e-01 -8.58999848e-01 0. 5.08947909e-01 -8.60796750e-01 0. 5.06053388e-01 -8.62502813e-01 0. 5.03025234e-01 -8.64270508e-01 0. 4.99923974e-01 -8.66069496e-01 0. 4.96871084e-01 -8.67824554e-01 0. 4.93921936e-01 -8.69503736e-01 0. 4.90901887e-01 -8.71217549e-01 0. 4.87853587e-01 -8.72924626e-01 0. 4.84813660e-01 -8.74614477e-01 0. 4.81757492e-01 -8.76304984e-01 0. 4.78692204e-01 -8.77983987e-01 0. 4.75620180e-01 -8.79649758e-01 0. 4.72549736e-01 -8.81302893e-01 0. 4.69458967e-01 -8.82953644e-01 0. 4.66370195e-01 -8.84590864e-01 0. 4.63225394e-01 -8.86239350e-01 0. 4.60110307e-01 -8.87860596e-01 0. 4.57093090e-01 -8.89418960e-01 0. 4.53992903e-01 -8.91004443e-01 0. 4.50860620e-01 -8.92594397e-01 0. 4.47750509e-01 -8.94157350e-01 0. 4.44603115e-01 -8.95727396e-01 0. 4.41482693e-01 -8.97270143e-01 0. 4.38335001e-01 -8.98812175e-01 0. 4.35184687e-01 -9.00341749e-01 0. 4.32065040e-01 -9.01840150e-01 0. 4.28797841e-01 -9.03398275e-01 0. 4.25619215e-01 -9.04901087e-01 0. 4.22495216e-01 -9.06364977e-01 0. 4.19299215e-01 -9.07847226e-01 0. 4.16251838e-01 -9.09247935e-01 0. 4.13077503e-01 -9.10695493e-01 0. 4.09873843e-01 -9.12142217e-01 0. 4.06609982e-01 -9.13601816e-01 0. 4.03392673e-01 -9.15026128e-01 0. 4.00309861e-01 -9.16380703e-01 0. 3.97098392e-01 -9.17774737e-01 0. 3.93887609e-01 -9.19154882e-01 0. 3.90643388e-01 -9.20540810e-01 0. 3.87445867e-01 -9.21893179e-01 0. 3.84254843e-01 -9.23226655e-01 0. 3.80995780e-01 -9.24574912e-01 0. 3.77822816e-01 -9.25878227e-01 0. 3.74585807e-01 -9.27191257e-01 0. 3.71259183e-01 -9.28528488e-01 0. 3.67979944e-01 -9.29833889e-01 0. 3.64826649e-01 -9.31076646e-01 0. 3.61578196e-01 -9.32335436e-01 0. 3.58321756e-01 -9.33601677e-01 0. 3.55048984e-01 -9.34842765e-01 0. 3.51798356e-01 -9.36066508e-01 0. 3.48504007e-01 -9.37297285e-01 0. 3.45168203e-01 -9.38535929e-01 0. 3.41867536e-01 -9.39750433e-01 0. 3.38629633e-01 -9.40919101e-01 0. 3.35334450e-01 -9.42100465e-01 0. 3.32030416e-01 -9.43268359e-01 0. 3.28731865e-01 -9.44421530e-01 0. 3.25436682e-01 -9.45563734e-01 0. 3.22122157e-01 -9.46696162e-01 0. 3.18896502e-01 -9.47789788e-01 0. 3.15562427e-01 -9.48903561e-01 0. 3.12247038e-01 -9.49999452e-01 0. 3.08976918e-01 -9.51068163e-01 0. 3.05648863e-01 -9.52144802e-01 0. 3.02331358e-01 -9.53201890e-01 0. 2.99015909e-01 -9.54247892e-01 0. 2.95662165e-01 -9.55292583e-01 0. 2.92328894e-01 -9.56318259e-01 0. 2.88941532e-01 -9.57343876e-01 0. 2.85565227e-01 -9.58358169e-01 0. 2.82295257e-01 -9.59327221e-01 0. 2.78870463e-01 -9.60328400e-01 0. 2.75426954e-01 -9.61321712e-01 0. 2.72067219e-01 -9.62278247e-01 0. 2.68817008e-01 -9.63192284e-01 0. 2.65552431e-01 -9.64096189e-01 0. 2.62185752e-01 -9.65019345e-01 0. 2.58821100e-01 -9.65924442e-01 0. 2.55357802e-01 -9.66846108e-01 0. 2.51949847e-01 -9.67741191e-01 0. 2.48594403e-01 -9.68606532e-01 0. 2.45175958e-01 -9.69476998e-01 0. 2.41834223e-01 -9.70315576e-01 0. 2.38402739e-01 -9.71166790e-01 0. 2.35113755e-01 -9.71969247e-01 0. 2.31683448e-01 -9.72793043e-01 0. 2.28287458e-01 -9.73595262e-01 0. 2.24916458e-01 -9.74378943e-01 0. 2.21413389e-01 -9.75179613e-01 0. 2.17996269e-01 -9.75950599e-01 0. 2.14683935e-01 -9.76682544e-01 0. 2.11265281e-01 -9.77428198e-01 0. 2.07860351e-01 -9.78158772e-01 0. 2.04370886e-01 -9.78894293e-01 0. 2.00937629e-01 -9.79605138e-01 0. 1.97608948e-01 -9.80280340e-01 0. 1.94186777e-01 -9.80964184e-01 0. 1.90746114e-01 -9.81639326e-01 0. 1.87240988e-01 -9.82312500e-01 0. 1.83802158e-01 -9.82962012e-01 0. 1.80372074e-01 -9.83595908e-01 0. 1.76938713e-01 -9.84226048e-01 0. 1.73594534e-01 -9.84820962e-01 0. 1.70159146e-01 -9.85414207e-01 0. 1.66732207e-01 -9.86002684e-01 0. 1.63283870e-01 -9.86577630e-01 0. 1.59856766e-01 -9.87139285e-01 0. 1.56415820e-01 -9.87691164e-01 0. 1.52974382e-01 -9.88230050e-01 0. 1.49504572e-01 -9.88758445e-01 0. 1.46020383e-01 -9.89280403e-01 0. 1.42561167e-01 -9.89783347e-01 0. 1.39144883e-01 -9.90271032e-01 0. 1.35588855e-01 -9.90764558e-01 0. 1.32115573e-01 -9.91232753e-01 0. 1.28741071e-01 -9.91677940e-01 0. 1.25301421e-01 -9.92119133e-01 0. 1.21811852e-01 -9.92552280e-01 0. 1.18258238e-01 -9.92981970e-01 0. 1.14788026e-01 -9.93388534e-01 0. 1.11425623e-01 -9.93772209e-01 0. 1.07950203e-01 -9.94155288e-01 0. 1.04508027e-01 -9.94522631e-01 0. 1.00927286e-01 -9.94890869e-01 0. 9.74393040e-02 -9.95240867e-01 0. 9.39832404e-02 -9.95574832e-01 0. 9.04843360e-02 -9.95898545e-01 0. 8.70286450e-02 -9.96205747e-01 0. 8.34588632e-02 -9.96510148e-01 0. 8.00611451e-02 -9.96789873e-01 0. 7.66712949e-02 -9.97054935e-01 0. 7.31881782e-02 -9.97318149e-01 0. 6.97156116e-02 -9.97564793e-01 0. 6.62232041e-02 -9.97804463e-01 0. 6.27597719e-02 -9.98027980e-01 0. 5.92570864e-02 -9.98241663e-01 0. 5.57744019e-02 -9.98443127e-01 0. 5.22968136e-02 -9.98629093e-01 0. 4.88270000e-02 -9.98807907e-01 0. 4.53621224e-02 -9.98970389e-01 0. 4.17509638e-02 -9.99126554e-01 0. 3.82681303e-02 -9.99266386e-01 0. 3.48940939e-02 -9.99389946e-01 0. 3.12955305e-02 -9.99508977e-01 0. 2.77922302e-02 -9.99613702e-01 0. 2.43002158e-02 -9.99706447e-01 0. 2.07874179e-02 -9.99781311e-01 0. 1.74482688e-02 -9.99851763e-01 0. 1.38455508e-02 -9.99897718e-01 0. 1.03374021e-02 -9.99945045e-01 0. 6.95124781e-03 -9.99981463e-01 0. 3.45419860e-03 -9.99998808e-01 0. -4.53507673e-05 -9.99999881e-01 0. -3.63037968e-03 -9.99998510e-01 0. -7.11531006e-03 -9.99980569e-01 0. -1.05883274e-02 -9.99943793e-01 0. -1.40723791e-02 -9.99896228e-01 0. -1.75498929e-02 -9.99851346e-01 0. -2.11335570e-02 -9.99773979e-01 0. -2.45488472e-02 -9.99700069e-01 0. -2.79755928e-02 -9.99608874e-01 0. -3.14475186e-02 -9.99506354e-01 0. -3.49387340e-02 -9.99390423e-01 0. -3.85159962e-02 -9.99257505e-01 0. -4.20272313e-02 -9.99116600e-01 0. -4.54046205e-02 -9.98967350e-01 0. -4.88883108e-02 -9.98804927e-01 0. -5.23481965e-02 -9.98626590e-01 0. -5.59182540e-02 -9.98436153e-01 0. -5.94235174e-02 -9.98232961e-01 0. -6.29094914e-02 -9.98015821e-01 0. -6.63906857e-02 -9.97792304e-01 0. -6.97796345e-02 -9.97560501e-01 0. -7.33469874e-02 -9.97305810e-01 0. -7.68307149e-02 -9.97042477e-01 0. -8.02994594e-02 -9.96770024e-01 0. -8.37935060e-02 -9.96481538e-01 0. -8.71771425e-02 -9.96191919e-01 0. -9.07447413e-02 -9.95872915e-01 0. -9.42233354e-02 -9.95549858e-01 0. -9.76910740e-02 -9.95215774e-01 0. -1.01176880e-01 -9.94868517e-01 0. -1.04627252e-01 -9.94511068e-01 0. -1.08205162e-01 -9.94128168e-01 0. -1.11578606e-01 -9.93755102e-01 0. -1.14935204e-01 -9.93372083e-01 0. -1.18415453e-01 -9.92962599e-01 0. -1.21871814e-01 -9.92545366e-01 0. -1.25439331e-01 -9.92101610e-01 0. -1.28935963e-01 -9.91651058e-01 0. -1.32268727e-01 -9.91214216e-01 0. -1.35718763e-01 -9.90746856e-01 0. -1.39177173e-01 -9.90267694e-01 0. -1.42746925e-01 -9.89757776e-01 0. -1.46192595e-01 -9.89254653e-01 0. -1.49640411e-01 -9.88738358e-01 0. -1.53091878e-01 -9.88213360e-01 0. -1.56430006e-01 -9.87687886e-01 0. -1.59904569e-01 -9.87132728e-01 0. -1.63328364e-01 -9.86572564e-01 0. -1.66879267e-01 -9.85977948e-01 0. -1.70330554e-01 -9.85385299e-01 0. -1.73675880e-01 -9.84805703e-01 0. -1.77154288e-01 -9.84185040e-01 0. -1.80594459e-01 -9.83554780e-01 0. -1.84075490e-01 -9.82912779e-01 0. -1.87517151e-01 -9.82260525e-01 0. -1.90843865e-01 -9.81619656e-01 0. -1.94268033e-01 -9.80947793e-01 0. -1.97768062e-01 -9.80248928e-01 0. -2.01227143e-01 -9.79543209e-01 0. -2.04547048e-01 -9.78855550e-01 0. -2.07949802e-01 -9.78141308e-01 0. -2.11449295e-01 -9.77389395e-01 0. -2.14876249e-01 -9.76638496e-01 0. -2.18190819e-01 -9.75906312e-01 0. -2.21604437e-01 -9.75135744e-01 0. -2.24999517e-01 -9.74357724e-01 0. -2.28480741e-01 -9.73551214e-01 0. -2.31876895e-01 -9.72746015e-01 0. -2.35179886e-01 -9.71953690e-01 0. -2.38640040e-01 -9.71108496e-01 0. -2.42042094e-01 -9.70264554e-01 0. -2.45431066e-01 -9.69411910e-01 0. -2.48809427e-01 -9.68552828e-01 0. -2.52084225e-01 -9.67704594e-01 0. -2.55494803e-01 -9.66811180e-01 0. -2.58932441e-01 -9.65894341e-01 0. -2.62404680e-01 -9.64958608e-01 0. -2.65698373e-01 -9.64055359e-01 0. -2.68936664e-01 -9.63158906e-01 0. -2.72345394e-01 -9.62199926e-01 0. -2.75680304e-01 -9.61248159e-01 0. -2.79022217e-01 -9.60285008e-01 0. -2.82376528e-01 -9.59303021e-01 0. -2.85709143e-01 -9.58317459e-01 0. -2.89065868e-01 -9.57307398e-01 0. -2.92398244e-01 -9.56294239e-01 0. -2.95821220e-01 -9.55244899e-01 0. -2.99186110e-01 -9.54193830e-01 0. -3.02501678e-01 -9.53149021e-01 0. -3.05813104e-01 -9.52092528e-01 0. -3.09043765e-01 -9.51047421e-01 0. -3.12439382e-01 -9.49936926e-01 0. -3.15828323e-01 -9.48816121e-01 0. -3.19132864e-01 -9.47711587e-01 0. -3.22383553e-01 -9.46608663e-01 0. -3.25573206e-01 -9.45516884e-01 0. -3.28922570e-01 -9.44355369e-01 0. -3.32209259e-01 -9.43205476e-01 0. -3.35547924e-01 -9.42022800e-01 0. -3.38850141e-01 -9.40838873e-01 0. -3.42119694e-01 -9.39657271e-01 0. -3.45398277e-01 -9.38449442e-01 0. -3.48594308e-01 -9.37263608e-01 0. -3.51863354e-01 -9.36042428e-01 0. -3.55137080e-01 -9.34811175e-01 0. -3.58477175e-01 -9.33541954e-01 0. -3.61834139e-01 -9.32238936e-01 0. -3.65000278e-01 -9.31007683e-01 0. -3.68148237e-01 -9.29766893e-01 0. -3.71377766e-01 -9.28480387e-01 0. -3.74615669e-01 -9.27179694e-01 0. -3.77934992e-01 -9.25831020e-01 0. -3.81263137e-01 -9.24463749e-01 0. -3.84408742e-01 -9.23162222e-01 0. -3.87519419e-01 -9.21860874e-01 0. -3.90752256e-01 -9.20494974e-01 0. -3.94035339e-01 -9.19090152e-01 0. -3.97277355e-01 -9.17696655e-01 0. -4.00463283e-01 -9.16313648e-01 0. -4.03668344e-01 -9.14905131e-01 0. -4.06761229e-01 -9.13534403e-01 0. -4.09966230e-01 -9.12101269e-01 0. -4.13127959e-01 -9.10671771e-01 0. -4.16364789e-01 -9.09195125e-01 0. -4.19544399e-01 -9.07732964e-01 0. -4.22638565e-01 -9.06296909e-01 0. -4.25798237e-01 -9.04816985e-01 0. -4.29033458e-01 -9.03287590e-01 0. -4.32192922e-01 -9.01778758e-01 0. -4.35252994e-01 -9.00310636e-01 0. -4.38405812e-01 -8.98779333e-01 0. -4.41597193e-01 -8.97212446e-01 0. -4.44729090e-01 -8.95666063e-01 0. -4.47765976e-01 -8.94150078e-01 0. -4.50894445e-01 -8.92578542e-01 0. -4.53999162e-01 -8.91002953e-01 0. -4.57186759e-01 -8.89370739e-01 0. -4.60295022e-01 -8.87764156e-01 0. -4.63302076e-01 -8.86202395e-01 0. -4.66386884e-01 -8.84580314e-01 0. -4.69460607e-01 -8.82952631e-01 0. -4.72625464e-01 -8.81264329e-01 0. -4.75722641e-01 -8.79593849e-01 0. -4.78776723e-01 -8.77937496e-01 0. -4.81836379e-01 -8.76261652e-01 0. -4.84890074e-01 -8.74573767e-01 0. -4.88036752e-01 -8.72822165e-01 0. -4.91006434e-01 -8.71156216e-01 0. -4.94020164e-01 -8.69450629e-01 0. -4.97072369e-01 -8.67710233e-01 0. -5.00002146e-01 -8.66023779e-01 0. -5.03038764e-01 -8.64264131e-01 0. -5.06059706e-01 -8.62498403e-01 0. -5.09055197e-01 -8.60733807e-01 0. -5.12043953e-01 -8.58959019e-01 0. -5.15039504e-01 -8.57165873e-01 0. -5.18050671e-01 -8.55348706e-01 0. -5.21117806e-01 -8.53486359e-01 0. -5.24150431e-01 -8.51623833e-01 0. -5.27048409e-01 -8.49835634e-01 0. -5.29921591e-01 -8.48047793e-01 0. -5.32964408e-01 -8.46136451e-01 0. -5.35936117e-01 -8.44257712e-01 0. -5.38864732e-01 -8.42390418e-01 0. -5.41812837e-01 -8.40498090e-01 0. -5.44640839e-01 -8.38667929e-01 0. -5.47641933e-01 -8.36709738e-01 0. -5.50584614e-01 -8.34779918e-01 0. -5.53388596e-01 -8.32919836e-01 0. -5.56296289e-01 -8.30983520e-01 0. -5.59271812e-01 -8.28986228e-01 0. -5.62189400e-01 -8.27005625e-01 0. -5.64977765e-01 -8.25107932e-01 0. -5.67854822e-01 -8.23129594e-01 0. -5.70715785e-01 -8.21147382e-01 0. -5.73671460e-01 -8.19084108e-01 0. -5.76634705e-01 -8.17003727e-01 0. -5.79402447e-01 -8.15040529e-01 0. -5.82145452e-01 -8.13085318e-01 0. -5.84984899e-01 -8.11040938e-01 0. -5.87822795e-01 -8.08989704e-01 0. -5.90713859e-01 -8.06879282e-01 0. -5.93606532e-01 -8.04754019e-01 0. -5.96346915e-01 -8.02725911e-01 0. -5.99056661e-01 -8.00704181e-01 0. -6.01853311e-01 -7.98606217e-01 0. -6.04694128e-01 -7.96458960e-01 0. -6.07500136e-01 -7.94319928e-01 0. -6.10261023e-01 -7.92199254e-01 0. -6.13021553e-01 -7.90065944e-01 0. -6.15704000e-01 -7.87976623e-01 0. -6.18517935e-01 -7.85771012e-01 0. -6.21250629e-01 -7.83611596e-01 0. -6.23979390e-01 -7.81440794e-01 0. -6.26714289e-01 -7.79249191e-01 0. -6.29341483e-01 -7.77129829e-01 0. -6.32058024e-01 -7.74918199e-01 0. -6.34740829e-01 -7.72724807e-01 0. -6.37504756e-01 -7.70446241e-01 0. -6.40205204e-01 -7.68203318e-01 0. -6.42799258e-01 -7.66034782e-01 0. -6.45540595e-01 -7.63724923e-01 0. -6.48215413e-01 -7.61456549e-01 0. -6.50791228e-01 -7.59255767e-01 0. -6.53442681e-01 -7.56976545e-01 0. -6.56076074e-01 -7.54696488e-01 0. -6.58787608e-01 -7.52327025e-01 0. -6.61406696e-01 -7.50026882e-01 0. -6.63941801e-01 -7.47784674e-01 0. -6.66556716e-01 -7.45453417e-01 0. -6.69136643e-01 -7.43138075e-01 0. -6.71797931e-01 -7.40736127e-01 0. -6.74387038e-01 -7.38375306e-01 0. -6.76964819e-01 -7.36017168e-01 0. -6.79532588e-01 -7.33645320e-01 0. -6.82077646e-01 -7.31278181e-01 0. -6.84693694e-01 -7.28830099e-01 0. -6.87180519e-01 -7.26484418e-01 0. -6.89685822e-01 -7.24109828e-01 0. -6.92223370e-01 -7.21677125e-01 0. -6.94666445e-01 -7.19340265e-01 0. -6.97169900e-01 -7.16911018e-01 0. -6.99652076e-01 -7.14486063e-01 0. -7.02217281e-01 -7.11966932e-01 0. -7.04727709e-01 -7.09483981e-01 0. -7.07096636e-01 -7.07104385e-01 0. -7.09573269e-01 -7.04638422e-01 0. -7.12100506e-01 -7.02081859e-01 0. -7.14575768e-01 -6.99559748e-01 0. -7.16932178e-01 -6.97148800e-01 0. -7.19355941e-01 -6.94649220e-01 0. -7.21824348e-01 -6.92070067e-01 0. -7.24322200e-01 -6.89465284e-01 0. -7.26727009e-01 -6.86924338e-01 0. -7.29064405e-01 -6.84442520e-01 0. -7.31375039e-01 -6.81972206e-01 0. -7.33813345e-01 -6.79351211e-01 0. -7.36183524e-01 -6.76783085e-01 0. -7.38479018e-01 -6.74275637e-01 0. -7.40833342e-01 -6.71689689e-01 0. -7.43178129e-01 -6.69093490e-01 0. -7.45508254e-01 -6.66496217e-01 0. -7.47830927e-01 -6.63890660e-01 0. -7.50211596e-01 -6.61196530e-01 0. -7.52505481e-01 -6.58584058e-01 0. -7.54797578e-01 -6.55955851e-01 0. -7.57157862e-01 -6.53230965e-01 0. -7.59370148e-01 -6.50659919e-01 0. -7.61606097e-01 -6.48038328e-01 0. -7.63890207e-01 -6.45347714e-01 0. -7.66069770e-01 -6.42756581e-01 0. -7.68366158e-01 -6.40011787e-01 0. -7.70601332e-01 -6.37317181e-01 0. -7.72765398e-01 -6.34692967e-01 0. -7.74967790e-01 -6.31998718e-01 0. -7.77175367e-01 -6.29283547e-01 0. -7.79415131e-01 -6.26506984e-01 0. -7.81655490e-01 -6.23711467e-01 0. -7.83828259e-01 -6.20976627e-01 0. -7.85953283e-01 -6.18285060e-01 0. -7.88043082e-01 -6.15620375e-01 0. -7.90232539e-01 -6.12807751e-01 0. -7.92364717e-01 -6.10049248e-01 0. -7.94487953e-01 -6.07281208e-01 0. -7.96615958e-01 -6.04486644e-01 0. -7.98652828e-01 -6.01792991e-01 0. -8.00731480e-01 -5.99020958e-01 0. -8.02818775e-01 -5.96219003e-01 0. -8.04947734e-01 -5.93343616e-01 0. -8.07030439e-01 -5.90508163e-01 0. -8.09094369e-01 -5.87678015e-01 0. -8.11203301e-01 -5.84759355e-01 0. -8.13175261e-01 -5.82019806e-01 0. -8.15192342e-01 -5.79190314e-01 0. -8.17219853e-01 -5.76327324e-01 0. -8.19170296e-01 -5.73549092e-01 0. -8.21220040e-01 -5.70609510e-01 0. -8.23219180e-01 -5.67724466e-01 0. -8.25122952e-01 -5.64953685e-01 0. -8.27113211e-01 -5.62034369e-01 0. -8.29065740e-01 -5.59153378e-01 0. -8.31058264e-01 -5.56182325e-01 0. -8.33005667e-01 -5.53261697e-01 0. -8.34934652e-01 -5.50347090e-01 0. -8.36856067e-01 -5.47420084e-01 0. -8.38708818e-01 -5.44579923e-01 0. -8.40596735e-01 -5.41659772e-01 0. -8.42477977e-01 -5.38729072e-01 0. -8.44395041e-01 -5.35719454e-01 0. -8.46259117e-01 -5.32771587e-01 0. -8.48059356e-01 -5.29898226e-01 0. -8.49904716e-01 -5.26939392e-01 0. -8.51738334e-01 -5.23964882e-01 0. -8.53604078e-01 -5.20923674e-01 0. -8.55431020e-01 -5.17915785e-01 0. -8.57217193e-01 -5.14955223e-01 0. -8.59010816e-01 -5.11954188e-01 0. -8.60749543e-01 -5.09028077e-01 0. -8.62544477e-01 -5.05981624e-01 0. -8.64313424e-01 -5.02951682e-01 0. -8.66032600e-01 -4.99989867e-01 0. -8.67750883e-01 -4.96997774e-01 0. -8.69493544e-01 -4.93941784e-01 0. -8.71217251e-01 -4.90901947e-01 0. -8.72918904e-01 -4.87862229e-01 0. -8.74606311e-01 -4.84829068e-01 0. -8.76344085e-01 -4.81686443e-01 0. -8.78030598e-01 -4.78608221e-01 0. -8.79640818e-01 -4.75637078e-01 0. -8.81309152e-01 -4.72539574e-01 0. -8.83011103e-01 -4.69351530e-01 0. -8.84689152e-01 -4.66181427e-01 0. -8.86256576e-01 -4.63195264e-01 0. -8.87814581e-01 -4.60200816e-01 0. -8.89418304e-01 -4.57095325e-01 0. -8.91061485e-01 -4.53881025e-01 0. -8.92638087e-01 -4.50774461e-01 0. -8.94163668e-01 -4.47737724e-01 0. -8.95753264e-01 -4.44552690e-01 0. -8.97317410e-01 -4.41384763e-01 0. -8.98810565e-01 -4.38339442e-01 0. -9.00370419e-01 -4.35127348e-01 0. -9.01929975e-01 -4.31879848e-01 0. -9.03429627e-01 -4.28733766e-01 0. -9.04888928e-01 -4.25643921e-01 0. -9.06324863e-01 -4.22582388e-01 0. -9.07831490e-01 -4.19335246e-01 0. -9.09333885e-01 -4.16065454e-01 0. -9.10738289e-01 -4.12983000e-01 0. -9.12142336e-01 -4.09872472e-01 0. -9.13563907e-01 -4.06692773e-01 0. -9.15010333e-01 -4.03430343e-01 0. -9.16420698e-01 -4.00219679e-01 0. -9.17805314e-01 -3.97029132e-01 0. -9.19193149e-01 -3.93796921e-01 0. -9.20522869e-01 -3.90684158e-01 0. -9.21916306e-01 -3.87388319e-01 0. -9.23266768e-01 -3.84157896e-01 0. -9.24595833e-01 -3.80946845e-01 0. -9.25927639e-01 -3.77698064e-01 0. -9.27203059e-01 -3.74554247e-01 0. -9.28539157e-01 -3.71229231e-01 0. -9.29832935e-01 -3.67981941e-01 0. -9.31104183e-01 -3.64756584e-01 0. -9.32382405e-01 -3.61457080e-01 0. -9.33606863e-01 -3.58309925e-01 0. -9.34876978e-01 -3.54963422e-01 0. -9.36099231e-01 -3.51710558e-01 0. -9.37287271e-01 -3.48531187e-01 0. -9.38526511e-01 -3.45192432e-01 0. -9.39739883e-01 -3.41896147e-01 0. -9.40925777e-01 -3.38608712e-01 0. -9.42106068e-01 -3.35318834e-01 0. -9.43263531e-01 -3.32042217e-01 0. -9.44418252e-01 -3.28740984e-01 0. -9.45535302e-01 -3.25520664e-01 0. -9.46660399e-01 -3.22231978e-01 0. -9.47778225e-01 -3.18930179e-01 0. -9.48910177e-01 -3.15539926e-01 0. -9.50012624e-01 -3.12207282e-01 0. -9.51069951e-01 -3.08973581e-01 0. -9.52173054e-01 -3.05559188e-01 0. -9.53236580e-01 -3.02226454e-01 0. -9.54279304e-01 -2.98917621e-01 0. -9.55317914e-01 -2.95577019e-01 0. -9.56336081e-01 -2.92265445e-01 0. -9.57352519e-01 -2.88918853e-01 0. -9.58324671e-01 -2.85676837e-01 0. -9.59342718e-01 -2.82243431e-01 0. -9.60328519e-01 -2.78874099e-01 0. -9.61269796e-01 -2.75604784e-01 0. -9.62223232e-01 -2.72260576e-01 0. -9.63173151e-01 -2.68883198e-01 0. -9.64101434e-01 -2.65530050e-01 0. -9.65023756e-01 -2.62170941e-01 0. -9.65933621e-01 -2.58785993e-01 0. -9.66851890e-01 -2.55337745e-01 0. -9.67769444e-01 -2.51839310e-01 0. -9.68622386e-01 -2.48541012e-01 0. -9.69455957e-01 -2.45254993e-01 0. -9.70328391e-01 -2.41784573e-01 0. -9.71193373e-01 -2.38295674e-01 0. -9.71995234e-01 -2.35003799e-01 0. -9.72787678e-01 -2.31704220e-01 0. -9.73589063e-01 -2.28309110e-01 0. -9.74397123e-01 -2.24829569e-01 0. -9.75178957e-01 -2.21415430e-01 0. -9.75924253e-01 -2.18111232e-01 0. -9.76696491e-01 -2.14621097e-01 0. -9.77440238e-01 -2.11205676e-01 0. -9.78156686e-01 -2.07869783e-01 0. -9.78874028e-01 -2.04465523e-01 0. -9.79598522e-01 -2.00971693e-01 0. -9.80310202e-01 -1.97464049e-01 0. -9.80979383e-01 -1.94114104e-01 0. -9.81634319e-01 -1.90776110e-01 0. -9.82306123e-01 -1.87274039e-01 0. -9.82966304e-01 -1.83783621e-01 0. -9.83588934e-01 -1.80407658e-01 0. -9.84205067e-01 -1.77053764e-01 0. -9.84818637e-01 -1.73612237e-01 0. -9.85421360e-01 -1.70123369e-01 0. -9.86026049e-01 -1.66589618e-01 0. -9.86587286e-01 -1.63229585e-01 0. -9.87137437e-01 -1.59873337e-01 0. -9.87694621e-01 -1.56393468e-01 0. -9.88244534e-01 -1.52880400e-01 0. -9.88768339e-01 -1.49448529e-01 0. -9.89287317e-01 -1.45978853e-01 0. -9.89790976e-01 -1.42516881e-01 0. -9.90270972e-01 -1.39155388e-01 0. -9.90759790e-01 -1.35628641e-01 0. -9.91228342e-01 -1.32151917e-01 0. -9.91684377e-01 -1.28693119e-01 0. -9.92127001e-01 -1.25236958e-01 0. -9.92548287e-01 -1.21845357e-01 0. -9.92974937e-01 -1.18306592e-01 0. -9.93380725e-01 -1.14840843e-01 0. -9.93777931e-01 -1.11378349e-01 0. -9.94169950e-01 -1.07812241e-01 0. -9.94522870e-01 -1.04513653e-01 0. -9.94849622e-01 -1.01360321e-01 0. -9.95213807e-01 -9.77149084e-02 0. -9.95516479e-01 -9.45861414e-02 0. -9.95860577e-01 -9.08932537e-02 0. 0. 0. 0. 0. 0. 0. -9.96806264e-01 -7.98510313e-02 0. -9.96971846e-01 -7.77630806e-02 0. 0. 0. 0. -9.97490466e-01 -7.08010122e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98741686e-01 4.98075709e-02 5.81191340e-03 -9.98561382e-01 5.33278808e-02 5.81192179e-03 -9.98418510e-01 5.59069552e-02 5.81191247e-03 -9.98219013e-01 5.94334044e-02 5.81186730e-03 -9.97997880e-01 6.30362108e-02 5.81185566e-03 -9.97773290e-01 6.64999485e-02 5.81184123e-03 -9.97534573e-01 6.99870661e-02 5.81183843e-03 -9.97287631e-01 7.34446198e-02 5.81183843e-03 -9.97024953e-01 7.69193918e-02 5.81183331e-03 -9.96748626e-01 8.04368332e-02 5.81183424e-03 -9.96461511e-01 8.39144513e-02 5.81183238e-03 -9.96169806e-01 8.73032287e-02 5.81184635e-03 -9.95873451e-01 9.06275436e-02 5.81183424e-03 -9.95542824e-01 9.42025259e-02 5.81182865e-03 -9.95194554e-01 9.78001356e-02 5.81183936e-03 -9.94849563e-01 1.01263948e-01 5.81183285e-03 -9.94488716e-01 1.04737416e-01 5.81183238e-03 -9.94126379e-01 1.08119294e-01 5.81183983e-03 -9.93752778e-01 1.11514226e-01 5.81183098e-03 -9.93345618e-01 1.15071282e-01 5.81181981e-03 -9.92924631e-01 1.18651897e-01 5.81182819e-03 -9.92514789e-01 1.22037008e-01 5.81183238e-03 -9.92088199e-01 1.25472426e-01 5.81181888e-03 -9.91628051e-01 1.29044279e-01 5.81182586e-03 -9.91170526e-01 1.32507026e-01 5.81182679e-03 -9.90702331e-01 1.35977030e-01 5.81182679e-03 -9.90226984e-01 1.39394626e-01 5.81183098e-03 -9.89750504e-01 1.42729566e-01 5.81182959e-03 -9.89239752e-01 1.46220207e-01 5.81181701e-03 -9.88704622e-01 1.49799824e-01 5.81182307e-03 -9.88173783e-01 1.53271839e-01 5.81182307e-03 -9.87649739e-01 1.56603888e-01 5.81183145e-03 -9.87100899e-01 1.60039857e-01 5.81181608e-03 -9.86517251e-01 1.63598642e-01 5.81182865e-03 -9.85952795e-01 1.66954249e-01 5.81183238e-03 -9.85367835e-01 1.70379341e-01 5.81181888e-03 -9.84768212e-01 1.73832953e-01 5.81183331e-03 -9.84174669e-01 1.77159935e-01 5.81182539e-03 -9.83530939e-01 1.80676669e-01 5.81181608e-03 -9.82874691e-01 1.84221148e-01 5.81182260e-03 -9.82228935e-01 1.87627867e-01 5.81182726e-03 -9.81570065e-01 1.91042855e-01 5.81181981e-03 -9.80895519e-01 1.94486484e-01 5.81182400e-03 -9.80226934e-01 1.97816461e-01 5.81183098e-03 -9.79532897e-01 2.01233134e-01 5.81181422e-03 -9.78803813e-01 2.04747513e-01 5.81182819e-03 -9.78100538e-01 2.08088025e-01 5.81182959e-03 -9.77370322e-01 2.11495325e-01 5.81181794e-03 -9.76611614e-01 2.14960143e-01 5.81182586e-03 -9.75852907e-01 2.18382269e-01 5.81182726e-03 -9.75081801e-01 2.21795112e-01 5.81182679e-03 -9.74315047e-01 2.25145429e-01 5.81183191e-03 -9.73547935e-01 2.28445217e-01 5.81182633e-03 -9.72751200e-01 2.31816560e-01 5.81182586e-03 -9.71917570e-01 2.35290051e-01 5.81181096e-03 -9.71062362e-01 2.38784954e-01 5.81182539e-03 -9.70242739e-01 2.42086738e-01 5.81183191e-03 -9.69394803e-01 2.45463863e-01 5.81181096e-03 -9.68507230e-01 2.48947024e-01 5.81182353e-03 -9.67640758e-01 2.52296329e-01 5.81182400e-03 -9.66753900e-01 2.55672008e-01 5.81182633e-03 -9.65873063e-01 2.58980274e-01 5.81182959e-03 -9.64993238e-01 2.62239993e-01 5.81182865e-03 -9.64045167e-01 2.65696555e-01 5.81181608e-03 -9.63086188e-01 2.69160211e-01 5.81181888e-03 -9.62133408e-01 2.72543639e-01 5.81182214e-03 -9.61179137e-01 2.75888324e-01 5.81181888e-03 -9.60211635e-01 2.79237449e-01 5.81182214e-03 -9.59234059e-01 2.82580435e-01 5.81182167e-03 -9.58243906e-01 2.85921812e-01 5.81182353e-03 -9.57235157e-01 2.89273471e-01 5.81182353e-03 -9.56244707e-01 2.92533338e-01 5.81183052e-03 -9.55252290e-01 2.95763582e-01 5.81182446e-03 -9.54184830e-01 2.99185961e-01 5.81181468e-03 -9.53108370e-01 3.02593529e-01 5.81182307e-03 -9.52067971e-01 3.05852711e-01 5.81183191e-03 -9.51011181e-01 3.09123486e-01 5.81181794e-03 -9.49906886e-01 3.12500060e-01 5.81182074e-03 -9.48806465e-01 3.15823644e-01 5.81182679e-03 -9.47699785e-01 3.19135040e-01 5.81181608e-03 -9.46560860e-01 3.22495222e-01 5.81182353e-03 -9.45460141e-01 3.25709730e-01 5.81183238e-03 -9.44324434e-01 3.28984648e-01 5.81181096e-03 -9.43139911e-01 3.32367033e-01 5.81182353e-03 -9.41990256e-01 3.35615009e-01 5.81182772e-03 -9.40821588e-01 3.38872164e-01 5.81182074e-03 -9.39645886e-01 3.42121124e-01 5.81183098e-03 -9.38468695e-01 3.45319331e-01 5.81182120e-03 -9.37219322e-01 3.48687232e-01 5.81181608e-03 -9.35958207e-01 3.52060825e-01 5.81182167e-03 -9.34737861e-01 3.55299354e-01 5.81182633e-03 -9.33502734e-01 3.58556300e-01 5.81182446e-03 -9.32235599e-01 3.61813992e-01 5.81182819e-03 -9.31000412e-01 3.64986569e-01 5.81183238e-03 -9.29747760e-01 3.68167698e-01 5.81181981e-03 -9.28431928e-01 3.71474713e-01 5.81181888e-03 -9.27100062e-01 3.74783605e-01 5.81182260e-03 -9.25820291e-01 3.77936512e-01 5.81182912e-03 -9.24502552e-01 3.81148040e-01 5.81181608e-03 -9.23134387e-01 3.84449780e-01 5.81182586e-03 -9.21784222e-01 3.87677312e-01 5.81182353e-03 -9.20424044e-01 3.90892506e-01 5.81182074e-03 -9.19053614e-01 3.94099057e-01 5.81182074e-03 -9.17704225e-01 3.97234708e-01 5.81182633e-03 -9.16314423e-01 4.00438577e-01 5.81182214e-03 -9.14881110e-01 4.03699040e-01 5.81182307e-03 -9.13467646e-01 4.06885862e-01 5.81182353e-03 -9.12037075e-01 4.10081118e-01 5.81182633e-03 -9.10613477e-01 4.13231939e-01 5.81182865e-03 -9.09166336e-01 4.16402072e-01 5.81182819e-03 -9.07701731e-01 4.19589370e-01 5.81182307e-03 -9.06235099e-01 4.22749221e-01 5.81182446e-03 -9.04793262e-01 4.25823301e-01 5.81183238e-03 -9.03341413e-01 4.28895712e-01 5.81182865e-03 -9.01796460e-01 4.32134718e-01 5.81181608e-03 -9.00249720e-01 4.35355693e-01 5.81182586e-03 -8.98726046e-01 4.38492566e-01 5.81182446e-03 -8.97197545e-01 4.41604793e-01 5.81182865e-03 -8.95650625e-01 4.44736123e-01 5.81182214e-03 -8.94111931e-01 4.47819740e-01 5.81182865e-03 -8.92533243e-01 4.50959593e-01 5.81181608e-03 -8.90928328e-01 4.54123020e-01 5.81182446e-03 -8.89377415e-01 4.57150817e-01 5.81183191e-03 -8.87781739e-01 4.60242510e-01 5.81181608e-03 -8.86129320e-01 4.63419020e-01 5.81182353e-03 -8.84503841e-01 4.66514111e-01 5.81182539e-03 -8.82863402e-01 4.69608665e-01 5.81182633e-03 -8.81223142e-01 4.72680569e-01 5.81182446e-03 -8.79605711e-01 4.75679576e-01 5.81183145e-03 -8.77940893e-01 4.78753239e-01 5.81181096e-03 -8.76210928e-01 4.81906444e-01 5.81182539e-03 -8.74535024e-01 4.84937936e-01 5.81182539e-03 -8.72883260e-01 4.87904131e-01 5.81183238e-03 -8.71189058e-01 4.90928441e-01 5.81181236e-03 -8.69407654e-01 4.94072676e-01 5.81182772e-03 -8.67696285e-01 4.97074395e-01 5.81183052e-03 -8.65961909e-01 5.00092149e-01 5.81182539e-03 -8.64238977e-01 5.03058732e-01 5.81183843e-03 -8.62534404e-01 5.05979180e-01 5.81182679e-03 -8.60698938e-01 5.09093642e-01 5.81182074e-03 -8.58864725e-01 5.12183011e-01 5.81182586e-03 -8.57060909e-01 5.15195966e-01 5.81182912e-03 -8.55252087e-01 5.18191218e-01 5.81182726e-03 -8.53487611e-01 5.21092772e-01 5.81183797e-03 -8.51668775e-01 5.24060965e-01 5.81181888e-03 -8.49796474e-01 5.27094185e-01 5.81182865e-03 -8.47944498e-01 5.30064881e-01 5.81182679e-03 -8.46133828e-01 5.32951236e-01 5.81183424e-03 -8.44280362e-01 5.35884380e-01 5.81181096e-03 -8.42331409e-01 5.38940728e-01 5.81182586e-03 -8.40447843e-01 5.41872799e-01 5.81182446e-03 -8.38548124e-01 5.44807196e-01 5.81182586e-03 -8.36641133e-01 5.47729313e-01 5.81182865e-03 -8.34791124e-01 5.50547004e-01 5.81183471e-03 -8.32928896e-01 5.53355992e-01 5.81182633e-03 -8.30936551e-01 5.56349456e-01 5.81181096e-03 -8.28926086e-01 5.59342146e-01 5.81182353e-03 -8.27024519e-01 5.62145054e-01 5.81183471e-03 -8.25057089e-01 5.65032721e-01 5.81181608e-03 -8.23026180e-01 5.67987502e-01 5.81182772e-03 -8.21037531e-01 5.70856512e-01 5.81182400e-03 -8.19020927e-01 5.73744357e-01 5.81182307e-03 -8.17070246e-01 5.76520920e-01 5.81183098e-03 -8.15106094e-01 5.79294264e-01 5.81182214e-03 -8.13027382e-01 5.82208097e-01 5.81181096e-03 -8.10906172e-01 5.85154772e-01 5.81182120e-03 -8.08852792e-01 5.87994516e-01 5.81182353e-03 -8.06806982e-01 5.90795755e-01 5.81182446e-03 -8.04754972e-01 5.93588054e-01 5.81182819e-03 -8.02697957e-01 5.96368074e-01 5.81182633e-03 -8.00598621e-01 5.99182546e-01 5.81182446e-03 -7.98491240e-01 6.01989329e-01 5.81182633e-03 -7.96450973e-01 6.04685962e-01 5.81183331e-03 -7.94334233e-01 6.07465565e-01 5.81181096e-03 -7.92125463e-01 6.10340595e-01 5.81181981e-03 -7.89989591e-01 6.13101721e-01 5.81182307e-03 -7.87833750e-01 6.15871370e-01 5.81182307e-03 -7.85735905e-01 6.18544817e-01 5.81182959e-03 -7.83612370e-01 6.21233702e-01 5.81181981e-03 -7.81403005e-01 6.24010742e-01 5.81181981e-03 -7.79189289e-01 6.26772344e-01 5.81182214e-03 -7.76985466e-01 6.29503012e-01 5.81182074e-03 -7.74825513e-01 6.32155836e-01 5.81183797e-03 -7.72644758e-01 6.34823203e-01 5.81182074e-03 -7.70346105e-01 6.37609780e-01 5.81182726e-03 -7.68124044e-01 6.40285850e-01 5.81182679e-03 -7.65880525e-01 6.42966807e-01 5.81182679e-03 -7.63681650e-01 6.45575643e-01 5.81183191e-03 -7.61502981e-01 6.48145437e-01 5.81182679e-03 -7.59176433e-01 6.50869012e-01 5.81181608e-03 -7.56840885e-01 6.53584957e-01 5.81182633e-03 -7.54548132e-01 6.56228483e-01 5.81182539e-03 -7.52241433e-01 6.58871055e-01 5.81182726e-03 -7.49960721e-01 6.61467433e-01 5.81182865e-03 -7.47641087e-01 6.64087534e-01 5.81182633e-03 -7.45301723e-01 6.66713059e-01 5.81182493e-03 -7.42972016e-01 6.69306457e-01 5.81182633e-03 -7.40704536e-01 6.71817899e-01 5.81183331e-03 -7.38412678e-01 6.74331605e-01 5.81182353e-03 -7.36007392e-01 6.76961899e-01 5.81181096e-03 -7.33569801e-01 6.79600120e-01 5.81182865e-03 -7.31171191e-01 6.82178020e-01 5.81182633e-03 -7.28799582e-01 6.84711456e-01 5.81182446e-03 -7.26395607e-01 6.87260151e-01 5.81182633e-03 -7.24066496e-01 6.89716458e-01 5.81183704e-03 -7.21642554e-01 6.92245841e-01 5.81181841e-03 -7.19158232e-01 6.94838822e-01 5.81182959e-03 -7.16797888e-01 6.97270572e-01 5.81183657e-03 -7.14362621e-01 6.99765146e-01 5.81181608e-03 -7.11854637e-01 7.02317297e-01 5.81182865e-03 -7.09401011e-01 7.04798579e-01 5.81182865e-03 -7.06919909e-01 7.07268059e-01 5.81182353e-03 -7.04514980e-01 7.09680974e-01 5.81183471e-03 -7.02051401e-01 7.12118804e-01 5.81181422e-03 -6.99491441e-01 7.14629710e-01 5.81182027e-03 -6.97038829e-01 7.17023671e-01 5.81183145e-03 -6.94531083e-01 7.19458401e-01 5.81181096e-03 -6.92011476e-01 7.21865416e-01 5.81183424e-03 -6.89514399e-01 7.24261880e-01 5.81181096e-03 -6.86888099e-01 7.26747096e-01 5.81182307e-03 -6.84337258e-01 7.29149878e-01 5.81182307e-03 -6.81817889e-01 7.31504619e-01 5.81182539e-03 -6.79328144e-01 7.33820081e-01 5.81183610e-03 -6.76768541e-01 7.36186743e-01 5.81181329e-03 -6.74169421e-01 7.38562465e-01 5.81183052e-03 -6.71612680e-01 7.40889966e-01 5.81181096e-03 -6.68929994e-01 7.43313849e-01 5.81182307e-03 -6.66387200e-01 7.45590687e-01 5.81183005e-03 -6.63871527e-01 7.47834444e-01 5.81182446e-03 -6.61213934e-01 7.50185311e-01 5.81181096e-03 -6.58494651e-01 7.52569795e-01 5.81182074e-03 -6.55883551e-01 7.54848957e-01 5.81182586e-03 -6.53256059e-01 7.57122874e-01 5.81181981e-03 -6.50659084e-01 7.59355783e-01 5.81183238e-03 -6.48010135e-01 7.61617422e-01 5.81181096e-03 -6.45283163e-01 7.63930678e-01 5.81182214e-03 -6.42590821e-01 7.66197085e-01 5.81182307e-03 -6.39984310e-01 7.68375516e-01 5.81182865e-03 -6.37330711e-01 7.70577431e-01 5.81181096e-03 -6.34543002e-01 7.72877097e-01 5.81181981e-03 -6.31899059e-01 7.75035262e-01 5.81183005e-03 -6.29204929e-01 7.77227461e-01 5.81181888e-03 -6.26484752e-01 7.79418886e-01 5.81183098e-03 -6.23781204e-01 7.81587780e-01 5.81181096e-03 -6.20968878e-01 7.83821821e-01 5.81182446e-03 -6.18287921e-01 7.85938501e-01 5.81182819e-03 -6.15530729e-01 7.88100898e-01 5.81181375e-03 -6.12697303e-01 7.90303648e-01 5.81182120e-03 -6.09951019e-01 7.92425931e-01 5.81182633e-03 -6.07237399e-01 7.94508278e-01 5.81183005e-03 -6.04480565e-01 7.96609879e-01 5.81181096e-03 -6.01597905e-01 7.98786938e-01 5.81181841e-03 -5.98783076e-01 8.00897181e-01 5.81181888e-03 -5.96069813e-01 8.02919328e-01 5.81183145e-03 -5.93273461e-01 8.04987490e-01 5.81181096e-03 -5.90359330e-01 8.07126939e-01 5.81182446e-03 -5.87633669e-01 8.09114456e-01 5.81183191e-03 -5.84823728e-01 8.11144471e-01 5.81181096e-03 -5.81963956e-01 8.13203335e-01 5.81183145e-03 -5.79141378e-01 8.15216184e-01 5.81181096e-03 -5.76207280e-01 8.17293763e-01 5.81182167e-03 -5.73343575e-01 8.19301248e-01 5.81181981e-03 -5.70554793e-01 8.21247160e-01 5.81182865e-03 -5.67726672e-01 8.23205471e-01 5.81181096e-03 -5.64780653e-01 8.25230002e-01 5.81182726e-03 -5.61941504e-01 8.27161849e-01 5.81183098e-03 -5.59055984e-01 8.29119205e-01 5.81181096e-03 -5.56144834e-01 8.31071556e-01 5.81183098e-03 -5.53267777e-01 8.32991183e-01 5.81181794e-03 -5.50346076e-01 8.34924102e-01 5.81182865e-03 -5.47435164e-01 8.36835980e-01 5.81181096e-03 -5.44436276e-01 8.38790298e-01 5.81182446e-03 -5.41573524e-01 8.40641677e-01 5.81182865e-03 -5.38639843e-01 8.42523932e-01 5.81181096e-03 -5.35684288e-01 8.44404280e-01 5.81183005e-03 -5.32751262e-01 8.46261501e-01 5.81181562e-03 -5.29731393e-01 8.48153174e-01 5.81181981e-03 -5.26749551e-01 8.50009918e-01 5.81181981e-03 -5.23835003e-01 8.51806104e-01 5.81182865e-03 -5.20881236e-01 8.53620172e-01 5.81181096e-03 -5.17820895e-01 8.55477512e-01 5.81181981e-03 -5.14907002e-01 8.57233524e-01 5.81182865e-03 -5.11931181e-01 8.59016299e-01 5.81181096e-03 -5.08904576e-01 8.60810459e-01 5.81182865e-03 -5.05900502e-01 8.62580597e-01 5.81181794e-03 -5.02805948e-01 8.64387870e-01 5.81181981e-03 -4.99778926e-01 8.66140723e-01 5.81182586e-03 -4.96866941e-01 8.67814660e-01 5.81183238e-03 -4.93850172e-01 8.69534791e-01 5.81181096e-03 -4.90722358e-01 8.71305346e-01 5.81182307e-03 -4.87675160e-01 8.73012900e-01 5.81182214e-03 -4.84619498e-01 8.74711514e-01 5.81182214e-03 -4.81631100e-01 8.76362860e-01 5.81182959e-03 -4.78603244e-01 8.78021836e-01 5.81181608e-03 -4.75491077e-01 8.79707694e-01 5.81182959e-03 -4.72445369e-01 8.81350338e-01 5.81181608e-03 -4.69283670e-01 8.83036673e-01 5.81182307e-03 -4.66248959e-01 8.84643674e-01 5.81183005e-03 -4.63184714e-01 8.86250734e-01 5.81181468e-03 -4.60072964e-01 8.87867451e-01 5.81183005e-03 -4.56983268e-01 8.89465153e-01 5.81181096e-03 -4.53807682e-01 8.91087830e-01 5.81181981e-03 -4.50665534e-01 8.92681599e-01 5.81182586e-03 -4.47646737e-01 8.94199133e-01 5.81182959e-03 -4.44554746e-01 8.95741403e-01 5.81181096e-03 -4.41340387e-01 8.97327960e-01 5.81182353e-03 -4.38264728e-01 8.98835242e-01 5.81183191e-03 -4.35230404e-01 9.00309622e-01 5.81182120e-03 -4.32084531e-01 9.01820183e-01 5.81182446e-03 -4.28850472e-01 9.03364956e-01 5.81181096e-03 -4.25684661e-01 9.04859364e-01 5.81183098e-03 -4.22623128e-01 9.06295061e-01 5.81182307e-03 -4.19453770e-01 9.07766879e-01 5.81182307e-03 -4.16283756e-01 9.09222066e-01 5.81182214e-03 -4.13051933e-01 9.10696864e-01 5.81181608e-03 -4.09856468e-01 9.12140071e-01 5.81182819e-03 -4.06660616e-01 9.13568676e-01 5.81181422e-03 -4.03457999e-01 9.14988220e-01 5.81182726e-03 -4.00249571e-01 9.16397214e-01 5.81181096e-03 -3.97065490e-01 9.17778313e-01 5.81182959e-03 -3.93865317e-01 9.19153988e-01 5.81181189e-03 -3.90589714e-01 9.20552671e-01 5.81182167e-03 -3.87428999e-01 9.21888471e-01 5.81182865e-03 -3.84202063e-01 9.23237681e-01 5.81181608e-03 -3.80927503e-01 9.24592555e-01 5.81182214e-03 -3.77707988e-01 9.25913036e-01 5.81182214e-03 -3.74469429e-01 9.27228153e-01 5.81182307e-03 -3.71227920e-01 9.28530276e-01 5.81182307e-03 -3.68076175e-01 9.29784834e-01 5.81183052e-03 -3.64799589e-01 9.31076765e-01 5.81181608e-03 -3.61499876e-01 9.32355762e-01 5.81182819e-03 -3.58318418e-01 9.33593631e-01 5.81182959e-03 -3.55119795e-01 9.34806645e-01 5.81182353e-03 -3.51869255e-01 9.36029196e-01 5.81182819e-03 -3.48533094e-01 9.37276602e-01 5.81181888e-03 -3.45252454e-01 9.38492835e-01 5.81183005e-03 -3.42056215e-01 9.39669669e-01 5.81182307e-03 -3.38779390e-01 9.40853655e-01 5.81182586e-03 -3.35403293e-01 9.42065954e-01 5.81181096e-03 -3.31993639e-01 9.43271279e-01 5.81182353e-03 -3.28799486e-01 9.44386959e-01 5.81183424e-03 -3.25495571e-01 9.45534468e-01 5.81181096e-03 -3.22216362e-01 9.46653903e-01 5.81183704e-03 -3.18935871e-01 9.47767198e-01 5.81181096e-03 -3.15605491e-01 9.48879123e-01 5.81183191e-03 -3.12405735e-01 9.49937642e-01 5.81182307e-03 -3.08961630e-01 9.51065063e-01 5.81181096e-03 -3.05530787e-01 9.52171504e-01 5.81182307e-03 -3.02203745e-01 9.53233719e-01 5.81182446e-03 -2.98882306e-01 9.54278171e-01 5.81183098e-03 -2.95665294e-01 9.55278337e-01 5.81183517e-03 -2.92297304e-01 9.56317902e-01 5.81181096e-03 -2.88862526e-01 9.57358718e-01 5.81182586e-03 -2.85506040e-01 9.58365202e-01 5.81182446e-03 -2.82155931e-01 9.59358275e-01 5.81181981e-03 -2.78912097e-01 9.60306942e-01 5.81183098e-03 -2.75660545e-01 9.61243153e-01 5.81181981e-03 -2.72299528e-01 9.62202609e-01 5.81181981e-03 -2.68836766e-01 9.63175416e-01 5.81181096e-03 -2.65385240e-01 9.64132488e-01 5.81182214e-03 -2.62104005e-01 9.65030730e-01 5.81183098e-03 -2.58736998e-01 9.65937018e-01 5.81181096e-03 -2.55357683e-01 9.66836095e-01 5.81182959e-03 -2.51993656e-01 9.67720389e-01 5.81181096e-03 -2.48498783e-01 9.68621910e-01 5.81181888e-03 -2.45212749e-01 9.69458222e-01 5.81183098e-03 -2.41841882e-01 9.70304549e-01 5.81181096e-03 -2.38432422e-01 9.71149027e-01 5.81183052e-03 -2.35038802e-01 9.71978962e-01 5.81181096e-03 -2.31650904e-01 9.72789526e-01 5.81183098e-03 -2.28344694e-01 9.73570764e-01 5.81182214e-03 -2.24848032e-01 9.74383056e-01 5.81181096e-03 -2.21353099e-01 9.75183725e-01 5.81182679e-03 -2.17946857e-01 9.75951135e-01 5.81182307e-03 -2.14553475e-01 9.76700068e-01 5.81182120e-03 -2.11221740e-01 9.77426469e-01 5.81183005e-03 -2.07898527e-01 9.78139579e-01 5.81182353e-03 -2.04414323e-01 9.78875101e-01 5.81181608e-03 -2.00874120e-01 9.79608059e-01 5.81181981e-03 -1.97441623e-01 9.80303049e-01 5.81182446e-03 -1.94113180e-01 9.80968833e-01 5.81183145e-03 -1.90816551e-01 9.81616199e-01 5.81182214e-03 -1.87381983e-01 9.82275844e-01 5.81182493e-03 -1.83856964e-01 9.82944250e-01 5.81181096e-03 -1.80319205e-01 9.83595312e-01 5.81182307e-03 -1.76988006e-01 9.84207332e-01 5.81183098e-03 -1.73567429e-01 9.84816372e-01 5.81181515e-03 -1.70115113e-01 9.85411584e-01 5.81183098e-03 -1.66660577e-01 9.86004770e-01 5.81181096e-03 -1.63102344e-01 9.86598372e-01 5.81181981e-03 -1.59747973e-01 9.87147033e-01 5.81183098e-03 -1.56303108e-01 9.87698793e-01 5.81181096e-03 -1.52855650e-01 9.88238633e-01 5.81183191e-03 -1.49411604e-01 9.88764584e-01 5.81181096e-03 -1.45835161e-01 9.89297926e-01 5.81182027e-03 -1.42488554e-01 9.89783764e-01 5.81183238e-03 -1.39052093e-01 9.90276337e-01 5.81181096e-03 -1.35498777e-01 9.90767300e-01 5.81181981e-03 -1.32027417e-01 9.91236329e-01 5.81181981e-03 -1.28650054e-01 9.91678774e-01 5.81183052e-03 -1.25309348e-01 9.92108345e-01 5.81182307e-03 -1.21835761e-01 9.92539525e-01 5.81181981e-03 -1.18253969e-01 9.92973030e-01 5.81181142e-03 -1.14684716e-01 9.93390441e-01 5.81182214e-03 -1.11222886e-01 9.93785203e-01 5.81182353e-03 -1.07865475e-01 9.94154215e-01 5.81183052e-03 -1.04404137e-01 9.94523525e-01 5.81181096e-03 -1.00889981e-01 9.94886994e-01 5.81183052e-03 -9.74415317e-02 9.95230496e-01 5.81181096e-03 -9.38789994e-02 9.95573938e-01 5.81182307e-03 -9.04825479e-02 9.95887339e-01 5.81182959e-03 -8.70111883e-02 9.96198654e-01 5.81181375e-03 -8.35354626e-02 9.96493816e-01 5.81183005e-03 -8.00703466e-02 9.96778965e-01 5.81181096e-03 -7.65633062e-02 9.97052729e-01 5.81183098e-03 -7.30981529e-02 9.97315407e-01 5.81181096e-03 -6.95418343e-02 9.97567415e-01 5.81182214e-03 -6.61348775e-02 9.97798681e-01 5.81183145e-03 -6.26516789e-02 9.98022974e-01 5.81181096e-03 -5.91735765e-02 9.98237371e-01 5.81183005e-03 -5.57714812e-02 9.98435020e-01 5.81181934e-03 -5.22013493e-02 9.98624265e-01 5.81181096e-03 -4.86230254e-02 9.98808861e-01 5.81181981e-03 -4.51390184e-02 9.98968840e-01 5.81182214e-03 -4.16648611e-02 9.99121904e-01 5.81182074e-03 -3.82729992e-02 9.99255776e-01 5.81183238e-03 -3.48851532e-02 9.99380112e-01 5.81181981e-03 -3.13019939e-02 9.99499738e-01 5.81181096e-03 -2.76931450e-02 9.99606311e-01 5.81181841e-03 -2.41882578e-02 9.99701738e-01 5.81181934e-03 -2.08019316e-02 9.99771237e-01 5.81183145e-03 -1.74268261e-02 9.99842763e-01 5.81181888e-03 -1.39296474e-02 9.99888659e-01 5.81182260e-03 -1.03453100e-02 9.99938786e-01 5.81181096e-03 -6.73437770e-03 9.99974608e-01 5.81181888e-03 -3.31366877e-03 9.99988139e-01 5.81183424e-03 1.24982660e-04 9.99990761e-01 5.81181096e-03 3.65762482e-03 9.99988258e-01 5.81182959e-03 7.12090358e-03 9.99970496e-01 5.81181608e-03 1.07180877e-02 9.99931991e-01 5.81182539e-03 1.41970646e-02 9.99884069e-01 5.81181981e-03 1.76996607e-02 9.99837756e-01 5.81182074e-03 2.11837441e-02 9.99763489e-01 5.81182307e-03 2.46716458e-02 9.99685705e-01 5.81182167e-03 2.81655192e-02 9.99594688e-01 5.81181981e-03 3.15810144e-02 9.99491215e-01 5.81183098e-03 3.50346528e-02 9.99376774e-01 5.81181562e-03 3.86105739e-02 9.99245167e-01 5.81182074e-03 4.21301872e-02 9.99103785e-01 5.81182214e-03 4.56026569e-02 9.98948872e-01 5.81182353e-03 4.90261018e-02 9.98785794e-01 5.81183191e-03 5.24066985e-02 9.98613179e-01 5.81181888e-03 5.58885783e-02 9.98426974e-01 5.81182120e-03 5.94601892e-02 9.98219609e-01 5.81181096e-03 6.30407184e-02 9.98000324e-01 5.81182214e-03 6.64508045e-02 9.97777879e-01 5.81183098e-03 6.99017495e-02 9.97542977e-01 5.81181096e-03 7.33892918e-02 9.97293234e-01 5.81182819e-03 7.68727958e-02 9.97031868e-01 5.81181096e-03 8.04480165e-02 9.96747613e-01 5.81182074e-03 8.39202031e-02 9.96461749e-01 5.81182260e-03 8.74102637e-02 9.96163070e-01 5.81181981e-03 9.08434540e-02 9.95854378e-01 5.81181794e-03 9.43541974e-02 9.95529175e-01 5.81182446e-03 9.77461413e-02 9.95201111e-01 5.81182865e-03 1.01202570e-01 9.94856358e-01 5.81181096e-03 1.04771882e-01 9.94486570e-01 5.81181981e-03 1.08250692e-01 9.94113445e-01 5.81181888e-03 1.11714967e-01 9.93730366e-01 5.81182214e-03 1.15183376e-01 9.93333459e-01 5.81181888e-03 1.18569128e-01 9.92934048e-01 5.81182865e-03 1.22001559e-01 9.92520094e-01 5.81181096e-03 1.25582039e-01 9.92074370e-01 5.81182214e-03 1.29035398e-01 9.91628766e-01 5.81181981e-03 1.32511199e-01 9.91170764e-01 5.81181981e-03 1.35867566e-01 9.90716994e-01 5.81183191e-03 1.39311150e-01 9.90238905e-01 5.81181096e-03 1.42792672e-01 9.89741802e-01 5.81183005e-03 1.46220371e-01 9.89241540e-01 5.81181096e-03 1.49774075e-01 9.88708973e-01 5.81182214e-03 1.53152078e-01 9.88192201e-01 5.81182912e-03 1.56585082e-01 9.87653375e-01 5.81181096e-03 1.60132036e-01 9.87084508e-01 5.81181981e-03 1.63557649e-01 9.86524701e-01 5.81182074e-03 1.67010784e-01 9.85945404e-01 5.81181888e-03 1.70468882e-01 9.85351145e-01 5.81181981e-03 1.73913240e-01 9.84754443e-01 5.81181981e-03 1.77259222e-01 9.84157145e-01 5.81183005e-03 1.80666253e-01 9.83533323e-01 5.81181096e-03 1.84201270e-01 9.82878506e-01 5.81182353e-03 1.87536582e-01 9.82246995e-01 5.81182819e-03 1.90957472e-01 9.81587410e-01 5.81181096e-03 1.94496229e-01 9.80892301e-01 5.81182027e-03 1.97891951e-01 9.80214119e-01 5.81182353e-03 2.01294318e-01 9.79520917e-01 5.81181888e-03 2.04643399e-01 9.78825688e-01 5.81182912e-03 2.07982242e-01 9.78123784e-01 5.81181282e-03 2.11495548e-01 9.77369308e-01 5.81181282e-03 2.15017200e-01 9.76600170e-01 5.81181794e-03 2.18403459e-01 9.75848138e-01 5.81181981e-03 2.21715480e-01 9.75099683e-01 5.81183238e-03 2.25013494e-01 9.74344909e-01 5.81182307e-03 2.28415132e-01 9.73553717e-01 5.81181981e-03 2.31888801e-01 9.72735047e-01 5.81181096e-03 2.35375971e-01 9.71896172e-01 5.81181794e-03 2.38788530e-01 9.71060932e-01 5.81181981e-03 2.42183030e-01 9.70218599e-01 5.81181981e-03 2.45484889e-01 9.69388664e-01 5.81182819e-03 2.48840094e-01 9.68533039e-01 5.81181096e-03 2.52327740e-01 9.67631638e-01 5.81181794e-03 2.55643427e-01 9.66761827e-01 5.81182819e-03 2.59013206e-01 9.65862632e-01 5.81181096e-03 2.62427866e-01 9.64943588e-01 5.81181981e-03 2.65791953e-01 9.64018464e-01 5.81181794e-03 2.69087642e-01 9.63106632e-01 5.81182912e-03 2.72340775e-01 9.62190688e-01 5.81182214e-03 2.75793552e-01 9.61206019e-01 5.81181096e-03 2.79242247e-01 9.60210681e-01 5.81182167e-03 2.82569140e-01 9.59236085e-01 5.81181888e-03 2.85829037e-01 9.58269894e-01 5.81182912e-03 2.89095223e-01 9.57288980e-01 5.81182027e-03 2.92432368e-01 9.56274986e-01 5.81181981e-03 2.95850873e-01 9.55225110e-01 5.81181096e-03 2.99267471e-01 9.54159737e-01 5.81182493e-03 3.02537113e-01 9.53126729e-01 5.81182539e-03 3.05797875e-01 9.52086926e-01 5.81182214e-03 3.09155256e-01 9.51000571e-01 5.81181096e-03 3.12474608e-01 9.49914396e-01 5.81182865e-03 3.15777451e-01 9.48823571e-01 5.81181096e-03 3.19165707e-01 9.47689533e-01 5.81181888e-03 3.22468013e-01 9.46570039e-01 5.81181981e-03 3.25772077e-01 9.45437968e-01 5.81181888e-03 3.29031616e-01 9.44307387e-01 5.81182307e-03 3.32318693e-01 9.43157434e-01 5.81181701e-03 3.35561723e-01 9.42009270e-01 5.81182819e-03 3.38847160e-01 9.40830767e-01 5.81181096e-03 3.42198223e-01 9.39618230e-01 5.81182167e-03 3.45479727e-01 9.38409984e-01 5.81182307e-03 3.48737329e-01 9.37200189e-01 5.81182539e-03 3.51954341e-01 9.35997128e-01 5.81182912e-03 3.55122894e-01 9.34805930e-01 5.81182074e-03 3.58465225e-01 9.33536828e-01 5.81181096e-03 3.61785024e-01 9.32246745e-01 5.81182074e-03 3.65036815e-01 9.30983305e-01 5.81181888e-03 3.68299156e-01 9.29695249e-01 5.81182260e-03 3.71467471e-01 9.28434372e-01 5.81182865e-03 3.74693274e-01 9.27137673e-01 5.81181096e-03 3.78005445e-01 9.25791979e-01 5.81181981e-03 3.81213188e-01 9.24474537e-01 5.81181934e-03 3.84440124e-01 9.23138559e-01 5.81181888e-03 3.87598455e-01 9.21816587e-01 5.81182819e-03 3.90790641e-01 9.20466483e-01 5.81182074e-03 3.94000798e-01 9.19095457e-01 5.81182819e-03 3.97208393e-01 9.17717278e-01 5.81181096e-03 4.00509566e-01 9.16283429e-01 5.81181981e-03 4.03713107e-01 9.14875388e-01 5.81181981e-03 4.06876802e-01 9.13473845e-01 5.81181888e-03 4.10015702e-01 9.12067652e-01 5.81183052e-03 4.13155377e-01 9.10649538e-01 5.81181608e-03 4.16357547e-01 9.09187138e-01 5.81182633e-03 4.19497669e-01 9.07744706e-01 5.81181422e-03 4.22732234e-01 9.06242311e-01 5.81181236e-03 4.25867945e-01 9.04772103e-01 5.81183238e-03 4.28997755e-01 9.03294265e-01 5.81181096e-03 4.32223231e-01 9.01753128e-01 5.81182353e-03 4.35277134e-01 9.00287330e-01 5.81182772e-03 4.38437074e-01 8.98753166e-01 5.81181096e-03 4.41670597e-01 8.97165716e-01 5.81181794e-03 4.44815040e-01 8.95611107e-01 5.81182214e-03 4.47924107e-01 8.94061029e-01 5.81182120e-03 4.50995207e-01 8.92516136e-01 5.81182446e-03 4.54088420e-01 8.90946031e-01 5.81182307e-03 4.57131028e-01 8.89388263e-01 5.81182679e-03 4.60266322e-01 8.87770295e-01 5.81181096e-03 4.63411152e-01 8.86132360e-01 5.81182074e-03 4.66509372e-01 8.84505212e-01 5.81181189e-03 4.69621420e-01 8.82857025e-01 5.81182074e-03 4.72660542e-01 8.81234288e-01 5.81182307e-03 4.75722134e-01 8.79584134e-01 5.81181888e-03 4.78813827e-01 8.77906978e-01 5.81181981e-03 4.81856078e-01 8.76240015e-01 5.81182167e-03 4.84915704e-01 8.74547899e-01 5.81181608e-03 4.87923086e-01 8.72873902e-01 5.81182819e-03 4.90952581e-01 8.71175647e-01 5.81181096e-03 4.94066358e-01 8.69411111e-01 5.81182353e-03 4.97115046e-01 8.67673695e-01 5.81182633e-03 5.00134110e-01 8.65937471e-01 5.81181794e-03 5.03172100e-01 8.64175498e-01 5.81181794e-03 5.06167293e-01 8.62425268e-01 5.81182307e-03 5.09171247e-01 8.60653996e-01 5.81181981e-03 5.12084007e-01 8.58923256e-01 5.81183005e-03 5.15102506e-01 8.57118070e-01 5.81181096e-03 5.18163085e-01 8.55268896e-01 5.81181794e-03 5.21148264e-01 8.53455603e-01 5.81181794e-03 5.24150908e-01 8.51613522e-01 5.81181888e-03 5.27011871e-01 8.49845409e-01 5.81183424e-03 5.29984415e-01 8.47995698e-01 5.81181096e-03 5.32937527e-01 8.46142292e-01 5.81183238e-03 5.35875618e-01 8.44283998e-01 5.81181794e-03 5.38921118e-01 8.42343807e-01 5.81182027e-03 5.41772544e-01 8.40510786e-01 5.81183843e-03 5.44599712e-01 8.38682652e-01 5.81183052e-03 5.47512054e-01 8.36782157e-01 5.81183704e-03 5.50479352e-01 8.34834456e-01 5.81185287e-03 5.53432822e-01 8.32877815e-01 5.81184495e-03 5.56441486e-01 8.30871344e-01 5.81186265e-03 5.59318721e-01 8.28937173e-01 5.81188034e-03 5.62078178e-01 8.27062607e-01 5.81191387e-03 5.64913929e-01 8.25127244e-01 5.81192551e-03 5.67824066e-01 8.23125184e-01 5.81192411e-03 5.70516467e-01 8.21266294e-01 5.81192225e-03 5.73284745e-01 8.19336355e-01 5.81191154e-03 5.76606333e-01 8.17000926e-01 5.81191434e-03 5.79854190e-01 8.14699113e-01 5.81191434e-03 5.81716239e-01 8.13370705e-01 5.81191434e-03 5.84239781e-01 8.11560273e-01 5.81191387e-03 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.07834721e-01 7.06354201e-01 5.81191340e-03 7.10050046e-01 7.04126596e-01 5.81191387e-03 7.12352335e-01 7.01797366e-01 5.81191434e-03 7.14974165e-01 6.99127793e-01 5.81190921e-03 7.17084229e-01 6.96958661e-01 5.81192365e-03 7.19392836e-01 6.94569945e-01 5.81192551e-03 7.21883237e-01 6.91991866e-01 5.81189105e-03 7.24326491e-01 6.89439237e-01 5.81186870e-03 7.26653695e-01 6.86982751e-01 5.81187056e-03 7.28971660e-01 6.84523284e-01 5.81185706e-03 7.31399894e-01 6.81930542e-01 5.81184076e-03 7.33799100e-01 6.79349065e-01 5.81184961e-03 7.36168027e-01 6.76785290e-01 5.81183145e-03 7.38589346e-01 6.74138844e-01 5.81182959e-03 7.40873158e-01 6.71630204e-01 5.81183517e-03 7.43199587e-01 6.69056416e-01 5.81182167e-03 7.45537996e-01 6.66447341e-01 5.81183052e-03 7.47803867e-01 6.63906157e-01 5.81182493e-03 7.50099421e-01 6.61309719e-01 5.81182307e-03 7.52478600e-01 6.58600986e-01 5.81181096e-03 7.54841924e-01 6.55892372e-01 5.81182446e-03 7.57051349e-01 6.53339565e-01 5.81183191e-03 7.59324014e-01 6.50696516e-01 5.81181096e-03 7.61608303e-01 6.48019910e-01 5.81183657e-03 7.63787210e-01 6.45453930e-01 5.81182446e-03 7.66096115e-01 6.42710090e-01 5.81181096e-03 7.68340349e-01 6.40026331e-01 5.81183145e-03 7.70568252e-01 6.37343526e-01 5.81181096e-03 7.72812188e-01 6.34619594e-01 5.81183191e-03 7.74938822e-01 6.32018328e-01 5.81182446e-03 7.77215183e-01 6.29220366e-01 5.81181096e-03 7.79483080e-01 6.26406431e-01 5.81182074e-03 7.81646252e-01 6.23705685e-01 5.81182353e-03 7.83753812e-01 6.21053338e-01 5.81183191e-03 7.85848618e-01 6.18404448e-01 5.81182214e-03 7.88059175e-01 6.15585327e-01 5.81181096e-03 7.90219247e-01 6.12808645e-01 5.81183005e-03 7.92357206e-01 6.10041201e-01 5.81181096e-03 7.94555306e-01 6.07175827e-01 5.81182353e-03 7.96668649e-01 6.04400218e-01 5.81181981e-03 7.98781514e-01 6.01604998e-01 5.81181981e-03 8.00812721e-01 5.98895371e-01 5.81183331e-03 8.02884758e-01 5.96117020e-01 5.81181096e-03 8.04971576e-01 5.93295097e-01 5.81182959e-03 8.07040751e-01 5.90477943e-01 5.81181096e-03 8.09158683e-01 5.87574363e-01 5.81182586e-03 8.11124325e-01 5.84853768e-01 5.81182959e-03 8.13151062e-01 5.82035840e-01 5.81181096e-03 8.15198183e-01 5.79164207e-01 5.81183238e-03 8.17144871e-01 5.76418996e-01 5.81181375e-03 8.19238126e-01 5.73436975e-01 5.81181096e-03 8.21302712e-01 5.70475101e-01 5.81181608e-03 8.23275685e-01 5.67624688e-01 5.81182726e-03 8.25185239e-01 5.64844489e-01 5.81182959e-03 8.27107608e-01 5.62024355e-01 5.81182074e-03 8.29073250e-01 5.59122384e-01 5.81181981e-03 8.31019104e-01 5.56223810e-01 5.81182446e-03 8.33005011e-01 5.53246140e-01 5.81181096e-03 8.34936440e-01 5.50325751e-01 5.81183238e-03 8.36795866e-01 5.47495306e-01 5.81181981e-03 8.38753164e-01 5.44494152e-01 5.81181096e-03 8.40648711e-01 5.41561842e-01 5.81182959e-03 8.42526972e-01 5.38634539e-01 5.81181794e-03 8.44463170e-01 5.35593867e-01 5.81182586e-03 8.46281469e-01 5.32717764e-01 5.81183191e-03 8.48118365e-01 5.29788256e-01 5.81181096e-03 8.49961460e-01 5.26824296e-01 5.81182959e-03 8.51751566e-01 5.23925662e-01 5.81182260e-03 8.53585064e-01 5.20937085e-01 5.81182353e-03 8.55429769e-01 5.17900109e-01 5.81181096e-03 8.57285619e-01 5.14822423e-01 5.81182120e-03 8.59086752e-01 5.11809707e-01 5.81181888e-03 8.60869229e-01 5.08805931e-01 5.81182446e-03 8.62593293e-01 5.05878568e-01 5.81183052e-03 8.64295006e-01 5.02962470e-01 5.81182493e-03 8.66092026e-01 4.99865860e-01 5.81181096e-03 8.67839992e-01 4.96822387e-01 5.81182959e-03 8.69553924e-01 4.93818879e-01 5.81181096e-03 8.71296465e-01 4.90740150e-01 5.81182959e-03 8.72957230e-01 4.87772405e-01 5.81182586e-03 8.74686420e-01 4.84666348e-01 5.81181142e-03 8.76381934e-01 4.81595457e-01 5.81183052e-03 8.78053427e-01 4.78544623e-01 5.81181096e-03 8.79726171e-01 4.75455135e-01 5.81183145e-03 8.81324530e-01 4.72489923e-01 5.81182214e-03 8.82999420e-01 4.69352394e-01 5.81181468e-03 8.84649038e-01 4.66236472e-01 5.81183005e-03 8.86219859e-01 4.63244617e-01 5.81182260e-03 8.87872398e-01 4.60067570e-01 5.81181096e-03 8.89529884e-01 4.56856102e-01 5.81182400e-03 8.91109407e-01 4.53765839e-01 5.81182539e-03 8.92652333e-01 4.50722963e-01 5.81183098e-03 8.94214034e-01 4.47617292e-01 5.81181096e-03 8.95773530e-01 4.44485962e-01 5.81183005e-03 8.97268355e-01 4.41462040e-01 5.81182633e-03 8.98863733e-01 4.38210696e-01 5.81181236e-03 9.00386333e-01 4.35072541e-01 5.81183098e-03 9.01885211e-01 4.31949794e-01 5.81181468e-03 9.03390467e-01 4.28796440e-01 5.81182912e-03 9.04842794e-01 4.25718248e-01 5.81181981e-03 9.06357944e-01 4.22490060e-01 5.81181096e-03 9.07880604e-01 4.19206381e-01 5.81181981e-03 9.09342051e-01 4.16022360e-01 5.81182074e-03 9.10746455e-01 4.12939340e-01 5.81183145e-03 9.12135541e-01 4.09864664e-01 5.81182400e-03 9.13558662e-01 4.06681687e-01 5.81182307e-03 9.14976954e-01 4.03482646e-01 5.81182586e-03 9.16412234e-01 4.00212348e-01 5.81181096e-03 9.17818248e-01 3.96974474e-01 5.81182819e-03 9.19147611e-01 3.93879890e-01 5.81182214e-03 9.20554519e-01 3.90587062e-01 5.81181096e-03 9.21924770e-01 3.87342125e-01 5.81183145e-03 9.23221946e-01 3.84237915e-01 5.81181888e-03 9.24589157e-01 3.80937696e-01 5.81181096e-03 9.25956070e-01 3.77605170e-01 5.81182307e-03 9.27262366e-01 3.74382943e-01 5.81182120e-03 9.28533196e-01 3.71222049e-01 5.81182865e-03 9.29784060e-01 3.68080705e-01 5.81182307e-03 9.31071460e-01 3.64813030e-01 5.81182027e-03 9.32335675e-01 3.61552238e-01 5.81182307e-03 9.33623135e-01 3.58236015e-01 5.81181236e-03 9.34888840e-01 3.54901850e-01 5.81182353e-03 9.36117828e-01 3.51635158e-01 5.81181981e-03 9.37312722e-01 3.48430991e-01 5.81183331e-03 9.38496292e-01 3.45245987e-01 5.81182074e-03 9.39704955e-01 3.41958970e-01 5.81181888e-03 9.40921485e-01 3.38595331e-01 5.81181096e-03 9.42121267e-01 3.35246265e-01 5.81182400e-03 9.43260372e-01 3.32025588e-01 5.81183052e-03 9.44382489e-01 3.28815281e-01 5.81182353e-03 9.45552289e-01 3.25440228e-01 5.81181096e-03 9.46681857e-01 3.22136343e-01 5.81183098e-03 9.47800457e-01 3.18834931e-01 5.81181794e-03 9.48929310e-01 3.15452874e-01 5.81182307e-03 9.49998975e-01 3.12215358e-01 5.81183005e-03 9.51084495e-01 3.08899462e-01 5.81181096e-03 9.52166736e-01 3.05550188e-01 5.81183052e-03 9.53187346e-01 3.02348882e-01 5.81182307e-03 9.54269886e-01 2.98917025e-01 5.81181096e-03 9.55329895e-01 2.95502543e-01 5.81182260e-03 9.56354439e-01 2.92171925e-01 5.81182074e-03 9.57344174e-01 2.88911730e-01 5.81182912e-03 9.58321512e-01 2.85653412e-01 5.81181981e-03 9.59316492e-01 2.82302529e-01 5.81181934e-03 9.60293353e-01 2.78958648e-01 5.81182214e-03 9.61280525e-01 2.75532842e-01 5.81181096e-03 9.62259352e-01 2.72097051e-01 5.81182586e-03 9.63205993e-01 2.68727928e-01 5.81182027e-03 9.64122295e-01 2.65420794e-01 5.81182959e-03 9.65015411e-01 2.62163788e-01 5.81182353e-03 9.65942323e-01 2.58715183e-01 5.81181142e-03 9.66867208e-01 2.55243242e-01 5.81182539e-03 9.67757404e-01 2.51847237e-01 5.81182819e-03 9.68603849e-01 2.48570487e-01 5.81183145e-03 9.69441891e-01 2.45272890e-01 5.81182726e-03 9.70284343e-01 2.41921186e-01 5.81182167e-03 9.71126735e-01 2.38520935e-01 5.81182214e-03 9.71978426e-01 2.35036656e-01 5.81181375e-03 9.72810328e-01 2.31565148e-01 5.81182446e-03 9.73594964e-01 2.28238940e-01 5.81182912e-03 9.74382818e-01 2.24849805e-01 5.81181096e-03 9.75164711e-01 2.21434578e-01 5.81183191e-03 9.75924551e-01 2.18074664e-01 5.81181608e-03 9.76683021e-01 2.14630052e-01 5.81183145e-03 9.77428138e-01 2.11217001e-01 5.81181096e-03 9.78180349e-01 2.07707092e-01 5.81182260e-03 9.78878200e-01 2.04396546e-01 5.81183191e-03 9.79585707e-01 2.00988367e-01 5.81181422e-03 9.80283260e-01 1.97541162e-01 5.81183098e-03 9.80946362e-01 1.94226027e-01 5.81182539e-03 9.81637359e-01 1.90707609e-01 5.81181468e-03 9.82295811e-01 1.87275499e-01 5.81183145e-03 9.82939780e-01 1.83873951e-01 5.81181608e-03 9.83573020e-01 1.80437341e-01 5.81182959e-03 9.84193981e-01 1.77063465e-01 5.81182353e-03 9.84815001e-01 1.73575789e-01 5.81181655e-03 9.85432267e-01 1.70003146e-01 5.81182400e-03 9.86016154e-01 1.66589797e-01 5.81182307e-03 9.86572742e-01 1.63250744e-01 5.81183471e-03 9.87123489e-01 1.59894511e-01 5.81182353e-03 9.87697959e-01 1.56313658e-01 5.81181096e-03 9.88234818e-01 1.52874738e-01 5.81183145e-03 9.88756299e-01 1.49462312e-01 5.81181608e-03 9.89279032e-01 1.45962015e-01 5.81183704e-03 9.89761531e-01 1.42645791e-01 5.81182539e-03 9.90270793e-01 1.39089584e-01 5.81181608e-03 9.90749955e-01 1.35626882e-01 5.81183238e-03 9.91219640e-01 1.32150650e-01 5.81181888e-03 9.91675854e-01 1.28665507e-01 5.81183843e-03 9.92116809e-01 1.25241697e-01 5.81181934e-03 9.92560327e-01 1.21676140e-01 5.81182726e-03 9.92981374e-01 1.18161611e-01 5.81183005e-03 9.93386924e-01 1.14718489e-01 5.81182586e-03 9.93770897e-01 1.11341611e-01 5.81183517e-03 9.94141102e-01 1.07989386e-01 5.81183052e-03 9.94522631e-01 1.04425885e-01 5.81181655e-03 9.94880974e-01 1.00938104e-01 5.81183936e-03 9.95226026e-01 9.74782184e-02 5.81181794e-03 9.95561719e-01 9.39878523e-02 5.81183843e-03 9.95875239e-01 9.06209350e-02 5.81183238e-03 9.96188283e-01 8.71194825e-02 5.81183098e-03 9.96482790e-01 8.36568847e-02 5.81183285e-03 9.96779978e-01 8.00512582e-02 5.81182446e-03 9.97060418e-01 7.64828697e-02 5.81182726e-03 9.97319818e-01 7.30130374e-02 5.81183052e-03 9.97565210e-01 6.95542470e-02 5.81182772e-03 9.97797668e-01 6.61553964e-02 5.81183331e-03 9.98018205e-01 6.27511665e-02 5.81182726e-03 9.98231530e-01 5.92600070e-02 5.81182586e-03 9.98436451e-01 5.57105951e-02 5.81181981e-03 9.98630285e-01 5.21002412e-02 5.81182772e-03 9.98800635e-01 4.87240106e-02 5.81183890e-03 9.98960793e-01 4.53470908e-02 5.81182819e-03 9.99113142e-01 4.18484360e-02 5.81182912e-03 9.99253631e-01 3.83553244e-02 5.81182865e-03 9.99383450e-01 3.47972512e-02 5.81181981e-03 9.99501467e-01 3.12078986e-02 5.81182959e-03 9.99602258e-01 2.77946237e-02 5.81183657e-03 9.99693930e-01 2.43920609e-02 5.81183005e-03 9.99769866e-01 2.09080558e-02 5.81183191e-03 9.99840379e-01 1.74201913e-02 5.81183331e-03 9.99888480e-01 1.39233219e-02 5.81182912e-03 9.99934316e-01 1.04306648e-02 5.81183005e-03 9.99971271e-01 6.95307693e-03 5.81182959e-03 9.99989152e-01 3.39659350e-03 5.81182074e-03 9.99989092e-01 -1.24641112e-04 5.81183843e-03 9.99988735e-01 -3.62631702e-03 5.81182400e-03 9.99966741e-01 -7.13717518e-03 5.81183936e-03 9.99933839e-01 -1.05030788e-02 5.81183005e-03 9.99885559e-01 -1.40833911e-02 5.81182074e-03 9.99836147e-01 -1.76695604e-02 5.81183052e-03 9.99765992e-01 -2.10781451e-02 5.81183797e-03 9.99690473e-01 -2.45520454e-02 5.81181888e-03 9.99595523e-01 -2.80541405e-02 5.81183238e-03 9.99492407e-01 -3.15481946e-02 5.81182214e-03 9.99376118e-01 -3.50411199e-02 5.81183704e-03 9.99250352e-01 -3.84457484e-02 5.81182865e-03 9.99111295e-01 -4.19265404e-02 5.81182912e-03 9.98955309e-01 -4.54791076e-02 5.81181794e-03 9.98786330e-01 -4.90593575e-02 5.81182307e-03 9.98605728e-01 -5.25449365e-02 5.81182633e-03 9.98421431e-01 -5.59640005e-02 5.81183704e-03 9.98226881e-01 -5.93451075e-02 5.81182633e-03 9.98011887e-01 -6.28239065e-02 5.81182772e-03 9.97784913e-01 -6.63679838e-02 5.81181981e-03 9.97538030e-01 -6.99533448e-02 5.81182726e-03 9.97288406e-01 -7.34407604e-02 5.81182679e-03 9.97030914e-01 -7.68580735e-02 5.81183331e-03 9.96765733e-01 -8.02412853e-02 5.81182214e-03 9.96479452e-01 -8.37095380e-02 5.81182586e-03 9.96175706e-01 -8.72568712e-02 5.81181888e-03 9.95860875e-01 -9.07659903e-02 5.81183098e-03 9.95548308e-01 -9.41392034e-02 5.81183005e-03 9.95210230e-01 -9.76498127e-02 5.81182679e-03 9.94858921e-01 -1.01172760e-01 5.81181748e-03 9.94498134e-01 -1.04651518e-01 5.81183191e-03 9.94128704e-01 -1.08104721e-01 5.81181981e-03 9.93741751e-01 -1.11613147e-01 5.81183471e-03 9.93357360e-01 -1.14962049e-01 5.81182819e-03 9.92942393e-01 -1.18513569e-01 5.81181794e-03 9.92517650e-01 -1.22009777e-01 5.81183285e-03 9.92090821e-01 -1.25452772e-01 5.81181794e-03 9.91634905e-01 -1.28978789e-01 5.81182586e-03 9.91188049e-01 -1.32375702e-01 5.81183191e-03 9.90720093e-01 -1.35843590e-01 5.81181888e-03 9.90229964e-01 -1.39370501e-01 5.81183052e-03 9.89748359e-01 -1.42741412e-01 5.81183238e-03 9.89243388e-01 -1.46199107e-01 5.81181888e-03 9.88728225e-01 -1.49646804e-01 5.81183191e-03 9.88198221e-01 -1.53104216e-01 5.81181794e-03 9.87659752e-01 -1.56541213e-01 5.81183191e-03 9.87110794e-01 -1.59974992e-01 5.81181888e-03 9.86549497e-01 -1.63399220e-01 5.81183191e-03 9.85971451e-01 -1.66855261e-01 5.81181934e-03 9.85360324e-01 -1.70415446e-01 5.81182353e-03 9.84761357e-01 -1.73869625e-01 5.81182679e-03 9.84166086e-01 -1.77207828e-01 5.81183424e-03 9.83555615e-01 -1.80532634e-01 5.81182679e-03 9.82923269e-01 -1.83966026e-01 5.81182865e-03 9.82261181e-01 -1.87459871e-01 5.81181794e-03 9.81579483e-01 -1.90994918e-01 5.81182679e-03 9.80907202e-01 -1.94421113e-01 5.81182353e-03 9.80233848e-01 -1.97788492e-01 5.81183238e-03 9.79553282e-01 -2.01131329e-01 5.81183052e-03 9.78851318e-01 -2.04521492e-01 5.81182726e-03 9.78115022e-01 -2.08023071e-01 5.81181096e-03 9.77376401e-01 -2.11461335e-01 5.81183517e-03 9.76636350e-01 -2.14847609e-01 5.81181748e-03 9.75880325e-01 -2.18261078e-01 5.81183285e-03 9.75110292e-01 -2.21671894e-01 5.81181189e-03 9.74328041e-01 -2.25085765e-01 5.81183843e-03 9.73542929e-01 -2.28476897e-01 5.81181096e-03 9.72737074e-01 -2.31868535e-01 5.81183610e-03 9.71947789e-01 -2.35164985e-01 5.81182539e-03 9.71096754e-01 -2.38644227e-01 5.81181888e-03 9.70259547e-01 -2.42018491e-01 5.81183657e-03 9.69411254e-01 -2.45393470e-01 5.81181096e-03 9.68520999e-01 -2.48892173e-01 5.81182446e-03 9.67669129e-01 -2.52185434e-01 5.81183517e-03 9.66784298e-01 -2.55555063e-01 5.81181608e-03 9.65882301e-01 -2.58943021e-01 5.81183238e-03 9.65000272e-01 -2.62214184e-01 5.81182539e-03 9.64054525e-01 -2.65666485e-01 5.81181794e-03 9.63114381e-01 -2.69055635e-01 5.81183238e-03 9.62177753e-01 -2.72389054e-01 5.81181794e-03 9.61186528e-01 -2.75858641e-01 5.81182819e-03 9.60246384e-01 -2.79111564e-01 5.81183704e-03 9.59297001e-01 -2.82360554e-01 5.81182260e-03 9.58280146e-01 -2.85796553e-01 5.81181794e-03 9.57239032e-01 -2.89256871e-01 5.81182493e-03 9.56230700e-01 -2.92583346e-01 5.81182539e-03 9.55224097e-01 -2.95850545e-01 5.81183191e-03 9.54223633e-01 -2.99060643e-01 5.81182633e-03 9.53175008e-01 -3.02387327e-01 5.81182353e-03 9.52109754e-01 -3.05725724e-01 5.81182446e-03 9.51010704e-01 -3.09123367e-01 5.81181794e-03 9.49899077e-01 -3.12520653e-01 5.81182633e-03 9.48821068e-01 -3.15780491e-01 5.81182959e-03 9.47750390e-01 -3.18982571e-01 5.81182959e-03 9.46626246e-01 -3.22298288e-01 5.81183098e-03 9.45476770e-01 -3.25657248e-01 5.81181981e-03 9.44327295e-01 -3.28970611e-01 5.81183517e-03 9.43178654e-01 -3.32255453e-01 5.81181794e-03 9.42006230e-01 -3.35569382e-01 5.81183610e-03 9.40834224e-01 -3.38836193e-01 5.81181981e-03 9.39648747e-01 -3.42116773e-01 5.81183145e-03 9.38431561e-01 -3.45424145e-01 5.81181562e-03 9.37208176e-01 -3.48710626e-01 5.81183238e-03 9.36033189e-01 -3.51858675e-01 5.81182912e-03 9.34812307e-01 -3.55100602e-01 5.81182865e-03 9.33520257e-01 -3.58510107e-01 5.81181282e-03 9.32253122e-01 -3.61764580e-01 5.81183657e-03 9.31005657e-01 -3.64979714e-01 5.81181794e-03 9.29714203e-01 -3.68252456e-01 5.81183610e-03 9.28428054e-01 -3.71485323e-01 5.81181794e-03 9.27119374e-01 -3.74735266e-01 5.81183424e-03 9.25853252e-01 -3.77853870e-01 5.81182539e-03 9.24480021e-01 -3.81201148e-01 5.81181096e-03 9.23140466e-01 -3.84433091e-01 5.81183517e-03 9.21811402e-01 -3.87611002e-01 5.81181189e-03 9.20398772e-01 -3.90950024e-01 5.81182586e-03 9.19074893e-01 -3.94048125e-01 5.81183285e-03 9.17734146e-01 -3.97167474e-01 5.81182353e-03 9.16302741e-01 -4.00466681e-01 5.81181189e-03 9.14853513e-01 -4.03758347e-01 5.81182865e-03 9.13450658e-01 -4.06923741e-01 5.81182865e-03 9.12060440e-01 -4.10032123e-01 5.81183191e-03 9.10659373e-01 -4.13130522e-01 5.81182679e-03 9.09214318e-01 -4.16296959e-01 5.81182586e-03 9.07709777e-01 -4.19572890e-01 5.81181608e-03 9.06210601e-01 -4.22799736e-01 5.81183145e-03 9.04737115e-01 -4.25942063e-01 5.81182865e-03 9.03264761e-01 -4.29057002e-01 5.81183238e-03 9.01809633e-01 -4.32105988e-01 5.81182633e-03 9.00292039e-01 -4.35267061e-01 5.81182633e-03 8.98727596e-01 -4.38487381e-01 5.81181794e-03 8.97184432e-01 -4.41630930e-01 5.81183424e-03 8.95651817e-01 -4.44732726e-01 5.81181375e-03 8.94091904e-01 -4.47860777e-01 5.81183238e-03 8.92561436e-01 -4.50903982e-01 5.81182912e-03 8.90991509e-01 -4.53997821e-01 5.81183098e-03 8.89353216e-01 -4.57198977e-01 5.81181608e-03 8.87743652e-01 -4.60311562e-01 5.81183471e-03 8.86174858e-01 -4.63333130e-01 5.81182726e-03 8.84555578e-01 -4.66415524e-01 5.81182539e-03 8.82883012e-01 -4.69569951e-01 5.81181468e-03 8.81240666e-01 -4.72646534e-01 5.81183890e-03 8.79596114e-01 -4.75699097e-01 5.81181888e-03 8.77911210e-01 -4.78804588e-01 5.81183517e-03 8.76279473e-01 -4.81781393e-01 5.81182446e-03 8.74598265e-01 -4.84822184e-01 5.81182819e-03 8.72902393e-01 -4.87874091e-01 5.81182353e-03 8.71188283e-01 -4.90929663e-01 5.81182493e-03 8.69429231e-01 -4.94035602e-01 5.81182307e-03 8.67695332e-01 -4.97075766e-01 5.81183843e-03 8.65955532e-01 -5.00103056e-01 5.81181841e-03 8.64206672e-01 -5.03118575e-01 5.81183238e-03 8.62491608e-01 -5.06053269e-01 5.81182726e-03 8.60723019e-01 -5.09054840e-01 5.81182633e-03 8.58942688e-01 -5.12049198e-01 5.81183191e-03 8.57099295e-01 -5.15133739e-01 5.81181981e-03 8.55260551e-01 -5.18174291e-01 5.81182819e-03 8.53494465e-01 -5.21082103e-01 5.81183285e-03 8.51710975e-01 -5.23990512e-01 5.81182912e-03 8.49879026e-01 -5.26961148e-01 5.81182539e-03 8.47994089e-01 -5.29987872e-01 5.81181608e-03 8.46096992e-01 -5.33009768e-01 5.81182679e-03 8.44250917e-01 -5.35927415e-01 5.81183424e-03 8.42423677e-01 -5.38796723e-01 5.81182446e-03 8.40502203e-01 -5.41790128e-01 5.81181841e-03 8.38542342e-01 -5.44818223e-01 5.81182307e-03 8.36646974e-01 -5.47721446e-01 5.81182865e-03 8.34743619e-01 -5.50619960e-01 5.81182307e-03 8.32848787e-01 -5.53476691e-01 5.81183843e-03 8.30978274e-01 -5.56284010e-01 5.81182865e-03 8.29012573e-01 -5.59214056e-01 5.81182865e-03 8.27008307e-01 -5.62171161e-01 5.81181608e-03 8.25043857e-01 -5.65049529e-01 5.81183890e-03 8.23065341e-01 -5.67930222e-01 5.81181981e-03 8.21066856e-01 -5.70812643e-01 5.81183983e-03 8.19079280e-01 -5.73660612e-01 5.81181608e-03 8.17069471e-01 -5.76522291e-01 5.81183610e-03 8.15069973e-01 -5.79345226e-01 5.81181981e-03 8.13033462e-01 -5.82201242e-01 5.81183704e-03 8.11020017e-01 -5.84997058e-01 5.81182307e-03 8.08923244e-01 -5.87897480e-01 5.81182586e-03 8.06866348e-01 -5.90714037e-01 5.81183843e-03 8.04807961e-01 -5.93517244e-01 5.81181888e-03 8.02695572e-01 -5.96369505e-01 5.81182865e-03 8.00664425e-01 -5.99094510e-01 5.81183238e-03 7.98568726e-01 -6.01886928e-01 5.81182027e-03 7.96463370e-01 -6.04668677e-01 5.81183378e-03 7.94406593e-01 -6.07370198e-01 5.81182586e-03 7.92263269e-01 -6.10161781e-01 5.81182353e-03 7.90073156e-01 -6.12993956e-01 5.81181981e-03 7.87880242e-01 -6.15810454e-01 5.81182633e-03 7.85737395e-01 -6.18543506e-01 5.81182865e-03 7.83631921e-01 -6.21205986e-01 5.81183750e-03 7.81498790e-01 -6.23889327e-01 5.81183191e-03 7.79311955e-01 -6.26620770e-01 5.81182633e-03 7.77076066e-01 -6.29392564e-01 5.81181608e-03 7.74819970e-01 -6.32162809e-01 5.81182865e-03 7.72675633e-01 -6.34782732e-01 5.81183704e-03 7.70516753e-01 -6.37405217e-01 5.81182912e-03 7.68282533e-01 -6.40095651e-01 5.81182959e-03 7.66056657e-01 -6.42757654e-01 5.81182679e-03 7.63734639e-01 -6.45514846e-01 5.81181608e-03 7.61474013e-01 -6.48177445e-01 5.81183517e-03 7.59204566e-01 -6.50837243e-01 5.81181329e-03 7.56901741e-01 -6.53512836e-01 5.81183564e-03 7.54669130e-01 -6.56091809e-01 5.81181888e-03 7.52310991e-01 -6.58791602e-01 5.81182214e-03 7.49984264e-01 -6.61439836e-01 5.81183191e-03 7.47761667e-01 -6.63952112e-01 5.81183191e-03 7.45473325e-01 -6.66521549e-01 5.81182679e-03 7.43082583e-01 -6.69185758e-01 5.81181608e-03 7.40726829e-01 -6.71791673e-01 5.81183797e-03 7.38375127e-01 -6.74375772e-01 5.81181608e-03 7.36015022e-01 -6.76950336e-01 5.81183610e-03 7.33712375e-01 -6.79445446e-01 5.81182214e-03 7.31338263e-01 -6.81997716e-01 5.81182865e-03 7.28878856e-01 -6.84626639e-01 5.81182586e-03 7.26474285e-01 -6.87175632e-01 5.81184123e-03 7.24098504e-01 -6.89684331e-01 5.81182586e-03 7.21665978e-01 -6.92220271e-01 5.81185007e-03 7.19295263e-01 -6.94690704e-01 5.81186172e-03 7.16929257e-01 -6.97119892e-01 5.81192551e-03 7.14692771e-01 -6.99414909e-01 5.81191666e-03 7.12218940e-01 -7.01932728e-01 5.81191434e-03 7.09572136e-01 -7.04608202e-01 5.81191434e-03 7.07248807e-01 -7.06940174e-01 5.81191434e-03 7.04699457e-01 -7.09481597e-01 5.81191387e-03 7.02538550e-01 -7.11621642e-01 5.81191387e-03 6.99453652e-01 -7.14653611e-01 5.81191434e-03 6.97222650e-01 -7.16830730e-01 5.81191434e-03 6.94233954e-01 -7.19725788e-01 5.81191434e-03 0. 0. 0. 6.90492153e-01 -7.23316550e-01 5.81191387e-03 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.75709283e-01 -8.17633688e-01 5.81191434e-03 0. 0. 0. 5.70431352e-01 -8.21324229e-01 5.81191387e-03 5.67075312e-01 -8.23646426e-01 5.81191480e-03 5.64812124e-01 -8.25196803e-01 5.81192551e-03 5.62042177e-01 -8.27091396e-01 5.81187103e-03 5.59162855e-01 -8.29043508e-01 5.81184914e-03 5.56287706e-01 -8.30975413e-01 5.81184076e-03 5.53304911e-01 -8.32964957e-01 5.81182959e-03 5.50360501e-01 -8.34914148e-01 5.81183936e-03 5.47546804e-01 -8.36761594e-01 5.81183191e-03 5.44554174e-01 -8.38712513e-01 5.81182353e-03 5.41615784e-01 -8.40611756e-01 5.81183657e-03 5.38749695e-01 -8.42453122e-01 5.81182959e-03 5.35807908e-01 -8.44326138e-01 5.81182865e-03 5.32853484e-01 -8.46196651e-01 5.81182772e-03 5.29904485e-01 -8.48042846e-01 5.81182865e-03 5.26961684e-01 -8.49879265e-01 5.81182633e-03 5.23982406e-01 -8.51715863e-01 5.81182726e-03 5.21009326e-01 -8.53541434e-01 5.81182865e-03 5.18009424e-01 -8.55362117e-01 5.81182493e-03 5.15026152e-01 -8.57162476e-01 5.81182959e-03 5.12028217e-01 -8.58956099e-01 5.81182586e-03 5.09027004e-01 -8.60738277e-01 5.81182679e-03 5.06012619e-01 -8.62514675e-01 5.81182539e-03 5.02999485e-01 -8.64273965e-01 5.81182633e-03 4.99890864e-01 -8.66077662e-01 5.81181468e-03 4.96886104e-01 -8.67803037e-01 5.81183843e-03 4.93921310e-01 -8.69493127e-01 5.81182539e-03 4.90896612e-01 -8.71208727e-01 5.81182633e-03 4.87835020e-01 -8.72922957e-01 5.81182260e-03 4.84780014e-01 -8.74621749e-01 5.81182772e-03 4.81720418e-01 -8.76314580e-01 5.81182446e-03 4.78650779e-01 -8.77994716e-01 5.81182586e-03 4.75611180e-01 -8.79643142e-01 5.81182586e-03 4.72518742e-01 -8.81309927e-01 5.81182120e-03 4.69441950e-01 -8.82951021e-01 5.81182074e-03 4.66351062e-01 -8.84589076e-01 5.81182539e-03 4.63171512e-01 -8.86257291e-01 5.81181096e-03 4.60053295e-01 -8.87878120e-01 5.81183378e-03 4.57057536e-01 -8.89426529e-01 5.81182586e-03 4.53944266e-01 -8.91018450e-01 5.81182539e-03 4.50831413e-01 -8.92597735e-01 5.81182353e-03 4.47702646e-01 -8.94170046e-01 5.81182353e-03 4.44593400e-01 -8.95720601e-01 5.81182633e-03 4.41465229e-01 -8.97267103e-01 5.81182074e-03 4.38310713e-01 -8.98812830e-01 5.81182307e-03 4.35166895e-01 -9.00340319e-01 5.81182679e-03 4.32028711e-01 -9.01847124e-01 5.81182307e-03 4.28907216e-01 -9.03336287e-01 5.81182539e-03 4.25747246e-01 -9.04829919e-01 5.81182633e-03 4.22501296e-01 -9.06353235e-01 5.81181282e-03 4.19319451e-01 -9.07827199e-01 5.81183098e-03 4.16248411e-01 -9.09238636e-01 5.81182586e-03 4.13056433e-01 -9.10694242e-01 5.81182353e-03 4.09868747e-01 -9.12133873e-01 5.81182539e-03 4.06602800e-01 -9.13595378e-01 5.81181608e-03 4.03402478e-01 -9.15010571e-01 5.81183098e-03 4.00296569e-01 -9.16376233e-01 5.81182539e-03 3.97090077e-01 -9.17768657e-01 5.81182446e-03 3.93875808e-01 -9.19148624e-01 5.81182260e-03 3.90597641e-01 -9.20549810e-01 5.81181096e-03 3.87373060e-01 -9.21912193e-01 5.81183098e-03 3.84178072e-01 -9.23248291e-01 5.81181608e-03 3.80915940e-01 -9.24595356e-01 5.81183238e-03 3.77785772e-01 -9.25882220e-01 5.81182539e-03 3.74563098e-01 -9.27190244e-01 5.81182353e-03 3.71234208e-01 -9.28528130e-01 5.81181701e-03 3.67905289e-01 -9.29852962e-01 5.81182307e-03 3.64729494e-01 -9.31103706e-01 5.81183052e-03 3.61581415e-01 -9.32323694e-01 5.81182260e-03 3.58305335e-01 -9.33598042e-01 5.81182539e-03 3.55046272e-01 -9.34833586e-01 5.81182446e-03 3.51731390e-01 -9.36082065e-01 5.81181888e-03 3.48474681e-01 -9.37296987e-01 5.81182959e-03 3.45251352e-01 -9.38494623e-01 5.81182260e-03 3.41975302e-01 -9.39699829e-01 5.81182679e-03 3.38698924e-01 -9.40882385e-01 5.81182167e-03 3.35414469e-01 -9.42061067e-01 5.81182307e-03 3.32117528e-01 -9.43226814e-01 5.81182539e-03 3.28816205e-01 -9.44382250e-01 5.81182307e-03 3.25434685e-01 -9.45554912e-01 5.81181562e-03 3.22144806e-01 -9.46678996e-01 5.81183098e-03 3.18930537e-01 -9.47768509e-01 5.81182400e-03 3.15634280e-01 -9.48869884e-01 5.81182400e-03 3.12316447e-01 -9.49966609e-01 5.81182446e-03 3.08889419e-01 -9.51087892e-01 5.81181096e-03 3.05574059e-01 -9.52158570e-01 5.81183424e-03 3.02358866e-01 -9.53183115e-01 5.81182074e-03 2.99024999e-01 -9.54234362e-01 5.81182539e-03 2.95688540e-01 -9.55273986e-01 5.81182586e-03 2.92346746e-01 -9.56301451e-01 5.81182539e-03 2.88941801e-01 -9.57334459e-01 5.81181608e-03 2.85563618e-01 -9.58348334e-01 5.81183191e-03 2.82310188e-01 -9.59313214e-01 5.81182307e-03 2.78880715e-01 -9.60317135e-01 5.81181189e-03 2.75407493e-01 -9.61315989e-01 5.81182074e-03 2.72043526e-01 -9.62273777e-01 5.81182353e-03 2.68766314e-01 -9.63194966e-01 5.81183285e-03 2.65527219e-01 -9.64093745e-01 5.81182074e-03 2.62143910e-01 -9.65020359e-01 5.81182446e-03 2.58762807e-01 -9.65929508e-01 5.81182027e-03 2.55354196e-01 -9.66837645e-01 5.81181888e-03 2.51969397e-01 -9.67725456e-01 5.81182912e-03 2.48629227e-01 -9.68589306e-01 5.81182074e-03 2.45245859e-01 -9.69448209e-01 5.81182307e-03 2.41786376e-01 -9.70317960e-01 5.81181794e-03 2.38384604e-01 -9.71160531e-01 5.81182959e-03 2.35092819e-01 -9.71965373e-01 5.81182493e-03 2.31707931e-01 -9.72776234e-01 5.81182400e-03 2.28296518e-01 -9.73582208e-01 5.81182446e-03 2.24819422e-01 -9.74390388e-01 5.81181142e-03 2.21299574e-01 -9.75195587e-01 5.81182633e-03 2.17990085e-01 -9.75940287e-01 5.81183191e-03 2.14695260e-01 -9.76670325e-01 5.81182353e-03 2.11290792e-01 -9.77412343e-01 5.81182539e-03 2.07880259e-01 -9.78143454e-01 5.81182446e-03 2.04370514e-01 -9.78885531e-01 5.81181096e-03 2.00942799e-01 -9.79593098e-01 5.81183145e-03 1.97625712e-01 -9.80267942e-01 5.81182307e-03 1.94195628e-01 -9.80951607e-01 5.81182214e-03 1.90779537e-01 -9.81622696e-01 5.81182539e-03 1.87282652e-01 -9.82296169e-01 5.81181608e-03 1.83815554e-01 -9.82948184e-01 5.81182959e-03 1.80364370e-01 -9.83586967e-01 5.81181422e-03 1.76922008e-01 -9.84219551e-01 5.81183424e-03 1.73604667e-01 -9.84810591e-01 5.81182120e-03 1.70159116e-01 -9.85404253e-01 5.81182214e-03 1.66716233e-01 -9.85996127e-01 5.81181981e-03 1.63289100e-01 -9.86568391e-01 5.81182074e-03 1.59824088e-01 -9.87134755e-01 5.81182679e-03 1.56374082e-01 -9.87687409e-01 5.81182307e-03 1.52946815e-01 -9.88224387e-01 5.81182446e-03 1.49496958e-01 -9.88750458e-01 5.81182679e-03 1.46047488e-01 -9.89267468e-01 5.81182539e-03 1.42605111e-01 -9.89768445e-01 5.81182214e-03 1.39049158e-01 -9.90276396e-01 5.81181096e-03 1.35482982e-01 -9.90769684e-01 5.81182679e-03 1.32121056e-01 -9.91221905e-01 5.81183191e-03 1.28755942e-01 -9.91665125e-01 5.81182586e-03 1.25294611e-01 -9.92110848e-01 5.81182539e-03 1.21819034e-01 -9.92541373e-01 5.81182353e-03 1.18295349e-01 -9.92967606e-01 5.81181608e-03 1.14799701e-01 -9.93375599e-01 5.81183005e-03 1.11431889e-01 -9.93760526e-01 5.81182307e-03 1.07954018e-01 -9.94144380e-01 5.81182539e-03 1.04479745e-01 -9.94515061e-01 5.81182539e-03 1.00927189e-01 -9.94881690e-01 5.81181608e-03 9.74481776e-02 -9.95228827e-01 5.81183191e-03 9.40015540e-02 -9.95564342e-01 5.81181096e-03 9.05025750e-02 -9.95886266e-01 5.81183238e-03 8.70407224e-02 -9.96195197e-01 5.81181608e-03 8.34599510e-02 -9.96500790e-01 5.81182586e-03 8.00755322e-02 -9.96778607e-01 5.81183238e-03 7.66863078e-02 -9.97044206e-01 5.81182120e-03 7.32055530e-02 -9.97306883e-01 5.81182120e-03 6.97333142e-02 -9.97553527e-01 5.81182446e-03 6.62639663e-02 -9.97792304e-01 5.81182167e-03 6.27699718e-02 -9.98016894e-01 5.81182214e-03 5.92754371e-02 -9.98230457e-01 5.81182726e-03 5.58001436e-02 -9.98432040e-01 5.81182307e-03 5.22269309e-02 -9.98624086e-01 5.81181096e-03 4.86972928e-02 -9.98802960e-01 5.81183191e-03 4.52406034e-02 -9.98965859e-01 5.81181608e-03 4.16684113e-02 -9.99122262e-01 5.81182539e-03 3.82572524e-02 -9.99257326e-01 5.81183052e-03 3.48898433e-02 -9.99380648e-01 5.81182586e-03 3.13084312e-02 -9.99498546e-01 5.81181096e-03 2.77936216e-02 -9.99603808e-01 5.81183005e-03 2.43115276e-02 -9.99697208e-01 5.81181515e-03 2.07940806e-02 -9.99771118e-01 5.81183145e-03 1.74089428e-02 -9.99842763e-01 5.81182307e-03 1.39150126e-02 -9.99887526e-01 5.81181981e-03 1.04232607e-02 -9.99936402e-01 5.81182027e-03 6.93015754e-03 -9.99971628e-01 5.81182307e-03 3.44604976e-03 -9.99988973e-01 5.81182214e-03 -3.17006197e-05 -9.99990225e-01 5.81182074e-03 -3.51746194e-03 -9.99988794e-01 5.81182214e-03 -6.99861441e-03 -9.99972582e-01 5.81181981e-03 -1.04995836e-02 -9.99933660e-01 5.81182307e-03 -1.40014859e-02 -9.99887407e-01 5.81182307e-03 -1.75644830e-02 -9.99842286e-01 5.81181096e-03 -2.11400259e-02 -9.99764264e-01 5.81182074e-03 -2.45457105e-02 -9.99689817e-01 5.81182865e-03 -2.79412344e-02 -9.99600708e-01 5.81181888e-03 -3.14312875e-02 -9.99496698e-01 5.81182353e-03 -3.49270850e-02 -9.99381185e-01 5.81181888e-03 -3.84950638e-02 -9.99250233e-01 5.81181096e-03 -4.19822559e-02 -9.99108732e-01 5.81182865e-03 -4.53894883e-02 -9.98958528e-01 5.81182027e-03 -4.88741957e-02 -9.98795748e-01 5.81181981e-03 -5.23533635e-02 -9.98615384e-01 5.81182214e-03 -5.59177883e-02 -9.98427093e-01 5.81181096e-03 -5.94270192e-02 -9.98221755e-01 5.81183145e-03 -6.28887117e-02 -9.98008311e-01 5.81181096e-03 -6.63720369e-02 -9.97784019e-01 5.81182912e-03 -6.97823614e-02 -9.97551084e-01 5.81181981e-03 -7.32380748e-02 -9.97304976e-01 5.81181981e-03 -7.67194331e-02 -9.97042477e-01 5.81182214e-03 -8.03065225e-02 -9.96759593e-01 5.81181096e-03 -8.37904140e-02 -9.96472299e-01 5.81182959e-03 -8.71620625e-02 -9.96183097e-01 5.81182074e-03 -9.06329229e-02 -9.95874166e-01 5.81181888e-03 -9.41395313e-02 -9.95548666e-01 5.81182074e-03 -9.75859389e-02 -9.95217025e-01 5.81182074e-03 -1.01059958e-01 -9.94870603e-01 5.81182214e-03 -1.04631759e-01 -9.94502127e-01 5.81181096e-03 -1.08198270e-01 -9.94119406e-01 5.81182214e-03 -1.11589842e-01 -9.93744195e-01 5.81182912e-03 -1.14931092e-01 -9.93361890e-01 5.81182214e-03 -1.18401967e-01 -9.92954016e-01 5.81181981e-03 -1.21879600e-01 -9.92534518e-01 5.81181981e-03 -1.25439897e-01 -9.92093086e-01 5.81181096e-03 -1.28936812e-01 -9.91640925e-01 5.81183098e-03 -1.32287547e-01 -9.91201103e-01 5.81181794e-03 -1.35745898e-01 -9.90733564e-01 5.81181888e-03 -1.39200389e-01 -9.90253925e-01 5.81182027e-03 -1.42730519e-01 -9.89749908e-01 5.81181096e-03 -1.46215007e-01 -9.89240706e-01 5.81182912e-03 -1.49642617e-01 -9.88729537e-01 5.81181096e-03 -1.53126463e-01 -9.88196313e-01 5.81182819e-03 -1.56480834e-01 -9.87669826e-01 5.81182074e-03 -1.59916192e-01 -9.87121403e-01 5.81181981e-03 -1.63368642e-01 -9.86556172e-01 5.81181981e-03 -1.66905433e-01 -9.85963166e-01 5.81181096e-03 -1.70349285e-01 -9.85372305e-01 5.81183052e-03 -1.73700050e-01 -9.84792829e-01 5.81181888e-03 -1.77127376e-01 -9.84180570e-01 5.81182260e-03 -1.80557579e-01 -9.83551979e-01 5.81182074e-03 -1.84078887e-01 -9.82902944e-01 5.81181096e-03 -1.87540114e-01 -9.82245922e-01 5.81183145e-03 -1.90823838e-01 -9.81613219e-01 5.81182353e-03 -1.94252163e-01 -9.80942726e-01 5.81181794e-03 -1.97802559e-01 -9.80230629e-01 5.81181096e-03 -2.01227650e-01 -9.79532897e-01 5.81183145e-03 -2.04509422e-01 -9.78854895e-01 5.81182120e-03 -2.07950458e-01 -9.78131115e-01 5.81182214e-03 -2.11439595e-01 -9.77383912e-01 5.81181096e-03 -2.14861333e-01 -9.76633310e-01 5.81183052e-03 -2.18191564e-01 -9.75896657e-01 5.81181981e-03 -2.21561551e-01 -9.75135744e-01 5.81181701e-03 -2.25000933e-01 -9.74348068e-01 5.81181934e-03 -2.28470877e-01 -9.73542869e-01 5.81181096e-03 -2.31881753e-01 -9.72735286e-01 5.81183005e-03 -2.35179260e-01 -9.71943796e-01 5.81181888e-03 -2.38618404e-01 -9.71104264e-01 5.81181608e-03 -2.42026716e-01 -9.70258653e-01 5.81182819e-03 -2.45340675e-01 -9.69425440e-01 5.81181888e-03 -2.48728320e-01 -9.68562722e-01 5.81181981e-03 -2.52190173e-01 -9.67668355e-01 5.81181096e-03 -2.55581111e-01 -9.66778219e-01 5.81182865e-03 -2.58920103e-01 -9.65889394e-01 5.81181096e-03 -2.62396425e-01 -9.64951932e-01 5.81181888e-03 -2.65672117e-01 -9.64052439e-01 5.81183052e-03 -2.69025207e-01 -9.63124037e-01 5.81181096e-03 -2.72382140e-01 -9.62180018e-01 5.81182959e-03 -2.75638312e-01 -9.61251616e-01 5.81181794e-03 -2.79009402e-01 -9.60278451e-01 5.81181981e-03 -2.82358557e-01 -9.59298313e-01 5.81181981e-03 -2.85708755e-01 -9.58307862e-01 5.81181608e-03 -2.89065897e-01 -9.57297742e-01 5.81181934e-03 -2.92404562e-01 -9.56283391e-01 5.81181888e-03 -2.95802593e-01 -9.55239475e-01 5.81181096e-03 -2.99141705e-01 -9.54198062e-01 5.81182633e-03 -3.02475244e-01 -9.53146517e-01 5.81181096e-03 -3.05807889e-01 -9.52083528e-01 5.81182865e-03 -3.09042871e-01 -9.51036274e-01 5.81181748e-03 -3.12444955e-01 -9.49926138e-01 5.81181096e-03 -3.15773606e-01 -9.48823810e-01 5.81182726e-03 -3.19071263e-01 -9.47722077e-01 5.81181096e-03 -3.22392285e-01 -9.46594775e-01 5.81182959e-03 -3.25576633e-01 -9.45505023e-01 5.81181888e-03 -3.28870296e-01 -9.44364011e-01 5.81182074e-03 -3.32158983e-01 -9.43213105e-01 5.81181981e-03 -3.35541040e-01 -9.42015290e-01 5.81181096e-03 -3.38845551e-01 -9.40829217e-01 5.81182959e-03 -3.42118979e-01 -9.39647794e-01 5.81181096e-03 -3.45425606e-01 -9.38428998e-01 5.81182819e-03 -3.48592103e-01 -9.37254846e-01 5.81181608e-03 -3.51882428e-01 -9.36025262e-01 5.81181981e-03 -3.55140835e-01 -9.34799612e-01 5.81181794e-03 -3.58421415e-01 -9.33553934e-01 5.81181748e-03 -3.61740083e-01 -9.32266474e-01 5.81181096e-03 -3.64990473e-01 -9.30999756e-01 5.81182865e-03 -3.68157059e-01 -9.29753244e-01 5.81181934e-03 -3.71378511e-01 -9.28469718e-01 5.81181981e-03 -3.74611914e-01 -9.27170575e-01 5.81181888e-03 -3.77923369e-01 -9.25826609e-01 5.81181096e-03 -3.81180346e-01 -9.24486637e-01 5.81182726e-03 -3.84340048e-01 -9.23180938e-01 5.81181934e-03 -3.87537271e-01 -9.21842217e-01 5.81181794e-03 -3.90747845e-01 -9.20485616e-01 5.81181888e-03 -3.94021422e-01 -9.19086814e-01 5.81181608e-03 -3.97211552e-01 -9.17714655e-01 5.81182586e-03 -4.00423467e-01 -9.16321814e-01 5.81181096e-03 -4.03635859e-01 -9.14907992e-01 5.81182633e-03 -4.06743109e-01 -9.13531601e-01 5.81181981e-03 -4.09930050e-01 -9.12107468e-01 5.81181888e-03 -4.13114160e-01 -9.10668433e-01 5.81181888e-03 -4.16368723e-01 -9.09181535e-01 5.81181096e-03 -4.19545829e-01 -9.07720268e-01 5.81183098e-03 -4.22606885e-01 -9.06301022e-01 5.81182307e-03 -4.25755620e-01 -9.04826343e-01 5.81181888e-03 -4.29005384e-01 -9.03290451e-01 5.81181096e-03 -4.32177037e-01 -9.01775539e-01 5.81182865e-03 -4.35227782e-01 -9.00311708e-01 5.81181981e-03 -4.38376606e-01 -8.98782194e-01 5.81181981e-03 -4.41597462e-01 -8.97202373e-01 5.81181096e-03 -4.44739461e-01 -8.95647109e-01 5.81183052e-03 -4.47806805e-01 -8.94119263e-01 5.81181608e-03 -4.50900376e-01 -8.92564416e-01 5.81182074e-03 -4.53988642e-01 -8.90996337e-01 5.81181794e-03 -4.57169801e-01 -8.89368474e-01 5.81181096e-03 -4.60305154e-01 -8.87748420e-01 5.81182819e-03 -4.63318378e-01 -8.86182368e-01 5.81181981e-03 -4.66396093e-01 -8.84565175e-01 5.81181981e-03 -4.69474256e-01 -8.82934153e-01 5.81181981e-03 -4.72624272e-01 -8.81253779e-01 5.81181096e-03 -4.75745380e-01 -8.79571557e-01 5.81182307e-03 -4.78816181e-01 -8.77907038e-01 5.81181468e-03 -4.81840998e-01 -8.76247525e-01 5.81182679e-03 -4.84900117e-01 -8.74557734e-01 5.81181096e-03 -4.88040656e-01 -8.72808456e-01 5.81181981e-03 -4.91005242e-01 -8.71144891e-01 5.81182865e-03 -4.93956566e-01 -8.69474173e-01 5.81181794e-03 -4.96985912e-01 -8.67748618e-01 5.81182074e-03 -5.00013053e-01 -8.66007090e-01 5.81181981e-03 -5.03020585e-01 -8.64263177e-01 5.81181934e-03 -5.06023705e-01 -8.62508655e-01 5.81181981e-03 -5.09053469e-01 -8.60723555e-01 5.81182260e-03 -5.12038231e-01 -8.58950078e-01 5.81182074e-03 -5.15043378e-01 -8.57153237e-01 5.81182353e-03 -5.18026531e-01 -8.55351865e-01 5.81181888e-03 -5.21054924e-01 -8.53513122e-01 5.81181608e-03 -5.24097800e-01 -8.51646423e-01 5.81181608e-03 -5.27046800e-01 -8.49825263e-01 5.81183052e-03 -5.29959321e-01 -8.48012924e-01 5.81181096e-03 -5.33009171e-01 -8.46098363e-01 5.81181096e-03 -5.36020041e-01 -8.44192922e-01 5.81182074e-03 -5.38944662e-01 -8.42328370e-01 5.81181608e-03 -5.41819215e-01 -8.40481460e-01 5.81182912e-03 -5.44662297e-01 -8.38643432e-01 5.81181981e-03 -5.47600210e-01 -8.36725831e-01 5.81181794e-03 -5.50509334e-01 -8.34817171e-01 5.81182214e-03 -5.53413570e-01 -8.32891107e-01 5.81181981e-03 -5.56314349e-01 -8.30960572e-01 5.81182214e-03 -5.59210598e-01 -8.29014659e-01 5.81182353e-03 -5.62111318e-01 -8.27048898e-01 5.81182400e-03 -5.64987481e-01 -8.25087905e-01 5.81182214e-03 -5.67902505e-01 -8.23084772e-01 5.81181888e-03 -5.70773125e-01 -8.21095765e-01 5.81181981e-03 -5.73662281e-01 -8.19078207e-01 5.81181608e-03 -5.76602399e-01 -8.17014694e-01 5.81181794e-03 -5.79388261e-01 -8.15038860e-01 5.81182819e-03 -5.82148969e-01 -8.13070476e-01 5.81182214e-03 -5.84989250e-01 -8.11025321e-01 5.81182214e-03 -5.87819159e-01 -8.08980346e-01 5.81182307e-03 -5.90700865e-01 -8.06877971e-01 5.81181096e-03 -5.93523085e-01 -8.04803193e-01 5.81182865e-03 -5.96239448e-01 -8.02793562e-01 5.81181934e-03 -5.99035561e-01 -8.00706983e-01 5.81181888e-03 -6.01830959e-01 -7.98610866e-01 5.81181981e-03 -6.04617834e-01 -7.96505153e-01 5.81182074e-03 -6.07387722e-01 -7.94393301e-01 5.81181794e-03 -6.10219896e-01 -7.92218506e-01 5.81181096e-03 -6.12997651e-01 -7.90072501e-01 5.81182633e-03 -6.15685940e-01 -7.87977636e-01 5.81181888e-03 -6.18420303e-01 -7.85836220e-01 5.81182074e-03 -6.21165872e-01 -7.83666193e-01 5.81181888e-03 -6.23946726e-01 -7.81455100e-01 5.81181096e-03 -6.26688182e-01 -7.79256582e-01 5.81182819e-03 -6.29336953e-01 -7.77120173e-01 5.81181841e-03 -6.32029414e-01 -7.74929166e-01 5.81181934e-03 -6.34749115e-01 -7.72705078e-01 5.81182353e-03 -6.37459815e-01 -7.70471334e-01 5.81181841e-03 -6.40157342e-01 -7.68230498e-01 5.81182353e-03 -6.42837524e-01 -7.65989840e-01 5.81182586e-03 -6.45546854e-01 -7.63708532e-01 5.81181608e-03 -6.48205698e-01 -7.61450052e-01 5.81183098e-03 -6.50846243e-01 -7.59196222e-01 5.81181282e-03 -6.53487086e-01 -7.56924748e-01 5.81183238e-03 -6.56057715e-01 -7.54697859e-01 5.81182633e-03 -6.58763051e-01 -7.52335727e-01 5.81181329e-03 -6.61395609e-01 -7.50022411e-01 5.81183657e-03 -6.63913012e-01 -7.47796893e-01 5.81182679e-03 -6.66510820e-01 -7.45481730e-01 5.81182307e-03 -6.69111967e-01 -7.43147373e-01 5.81182446e-03 -6.71709239e-01 -7.40803540e-01 5.81181981e-03 -6.74310625e-01 -7.38431573e-01 5.81181981e-03 -6.76954865e-01 -7.36014664e-01 5.81181096e-03 -6.79543614e-01 -7.33620405e-01 5.81183285e-03 -6.82066977e-01 -7.31276214e-01 5.81181608e-03 -6.84690118e-01 -7.28820086e-01 5.81182074e-03 -6.87165499e-01 -7.26483107e-01 5.81183238e-03 -6.89682782e-01 -7.24100232e-01 5.81181096e-03 -6.92226231e-01 -7.21660376e-01 5.81183005e-03 -6.94676399e-01 -7.19316840e-01 5.81182307e-03 -6.97179437e-01 -7.16888666e-01 5.81182353e-03 -6.99675143e-01 -7.14450181e-01 5.81182586e-03 -7.02160299e-01 -7.12009788e-01 5.81182633e-03 -7.04661489e-01 -7.09536076e-01 5.81182586e-03 -7.07152188e-01 -7.07035899e-01 5.81182027e-03 -7.09643304e-01 -7.04553306e-01 5.81183005e-03 -7.12056875e-01 -7.02112734e-01 5.81182307e-03 -7.14507699e-01 -6.99615717e-01 5.81181981e-03 -7.16937661e-01 -6.97127879e-01 5.81182586e-03 -7.19359517e-01 -6.94631040e-01 5.81182260e-03 -7.21845567e-01 -6.92034006e-01 5.81181608e-03 -7.24262595e-01 -6.89511657e-01 5.81183238e-03 -7.26652801e-01 -6.86990499e-01 5.81181096e-03 -7.29065776e-01 -6.84426367e-01 5.81183191e-03 -7.31371701e-01 -6.81961000e-01 5.81181981e-03 -7.33749151e-01 -6.79405868e-01 5.81181981e-03 -7.36118436e-01 -6.76840544e-01 5.81182214e-03 -7.38472402e-01 -6.74268246e-01 5.81182353e-03 -7.40867019e-01 -6.71638310e-01 5.81182074e-03 -7.43200243e-01 -6.69053674e-01 5.81182633e-03 -7.45495677e-01 -6.66494370e-01 5.81182586e-03 -7.47818828e-01 -6.63889825e-01 5.81182167e-03 -7.50182509e-01 -6.61216497e-01 5.81181096e-03 -7.52505898e-01 -6.58569336e-01 5.81183098e-03 -7.54741013e-01 -6.56007767e-01 5.81182074e-03 -7.57077157e-01 -6.53308868e-01 5.81181562e-03 -7.59349167e-01 -6.50668323e-01 5.81183098e-03 -7.61541605e-01 -6.48099661e-01 5.81182307e-03 -7.63814986e-01 -6.45423234e-01 5.81182214e-03 -7.66063273e-01 -6.42749071e-01 5.81182819e-03 -7.68356144e-01 -6.40009344e-01 5.81181608e-03 -7.70577312e-01 -6.37329221e-01 5.81183191e-03 -7.72757590e-01 -6.34687603e-01 5.81181375e-03 -7.74975240e-01 -6.31973445e-01 5.81182819e-03 -7.77150452e-01 -6.29299641e-01 5.81182260e-03 -7.79413402e-01 -6.26496017e-01 5.81181096e-03 -7.81613648e-01 -6.23746514e-01 5.81183191e-03 -7.83772767e-01 -6.21030092e-01 5.81181096e-03 -7.85933197e-01 -6.18295729e-01 5.81183238e-03 -7.88019300e-01 -6.15635335e-01 5.81182074e-03 -7.90176153e-01 -6.12864494e-01 5.81182353e-03 -7.92284429e-01 -6.10134244e-01 5.81182307e-03 -7.94476509e-01 -6.07277393e-01 5.81181096e-03 -7.96605110e-01 -6.04482591e-01 5.81182959e-03 -7.98652351e-01 -6.01777852e-01 5.81182214e-03 -8.00753236e-01 -5.98977149e-01 5.81182074e-03 -8.02838266e-01 -5.96180022e-01 5.81181981e-03 -8.04969072e-01 -5.93300402e-01 5.81181096e-03 -8.07040989e-01 -5.90476692e-01 5.81183098e-03 -8.09044421e-01 -5.87730646e-01 5.81182074e-03 -8.11133623e-01 -5.84841609e-01 5.81181515e-03 -8.13177407e-01 -5.81999838e-01 5.81183005e-03 -8.15142393e-01 -5.79242885e-01 5.81182446e-03 -8.17163706e-01 -5.76390207e-01 5.81182586e-03 -8.19157302e-01 -5.73551178e-01 5.81181888e-03 -8.21207225e-01 -5.70612788e-01 5.81181096e-03 -8.23200405e-01 -5.67734897e-01 5.81183005e-03 -8.25121522e-01 -5.64938784e-01 5.81181981e-03 -8.27091813e-01 -5.62047660e-01 5.81182027e-03 -8.29054236e-01 -5.59151292e-01 5.81182214e-03 -8.31032634e-01 -5.56205750e-01 5.81181096e-03 -8.32972944e-01 -5.53292811e-01 5.81183098e-03 -8.34904552e-01 -5.50376475e-01 5.81181096e-03 -8.36807013e-01 -5.47476470e-01 5.81183238e-03 -8.38656843e-01 -5.44641614e-01 5.81182074e-03 -8.40554595e-01 -5.41706681e-01 5.81182307e-03 -8.42440367e-01 -5.38769186e-01 5.81182074e-03 -8.44380975e-01 -5.35723269e-01 5.81181096e-03 -8.46242845e-01 -5.32778740e-01 5.81183098e-03 -8.48035872e-01 -5.29917419e-01 5.81182446e-03 -8.49875271e-01 -5.26967406e-01 5.81182214e-03 -8.51710677e-01 -5.23991346e-01 5.81182679e-03 -8.53536367e-01 -5.21015882e-01 5.81182586e-03 -8.55357826e-01 -5.18016875e-01 5.81182586e-03 -8.57167780e-01 -5.15016973e-01 5.81182167e-03 -8.58963311e-01 -5.12017071e-01 5.81182633e-03 -8.60738158e-01 -5.09027660e-01 5.81182539e-03 -8.62555802e-01 -5.05945146e-01 5.81181096e-03 -8.64326119e-01 -5.02908051e-01 5.81183238e-03 -8.66022170e-01 -4.99987781e-01 5.81182400e-03 -8.67752731e-01 -4.96973515e-01 5.81182493e-03 -8.69480908e-01 -4.93944705e-01 5.81182074e-03 -8.71211767e-01 -4.90891278e-01 5.81181888e-03 -8.72924149e-01 -4.87832665e-01 5.81182307e-03 -8.74615490e-01 -4.84790176e-01 5.81182307e-03 -8.76357913e-01 -4.81644452e-01 5.81181096e-03 -8.78038287e-01 -4.78572965e-01 5.81183098e-03 -8.79654765e-01 -4.75590020e-01 5.81182446e-03 -8.81316721e-01 -4.72505808e-01 5.81182353e-03 -8.83012295e-01 -4.69330281e-01 5.81181608e-03 -8.84645164e-01 -4.66244310e-01 5.81183145e-03 -8.86218131e-01 -4.63246524e-01 5.81182679e-03 -8.87832224e-01 -4.60144550e-01 5.81182539e-03 -8.89419317e-01 -4.57071841e-01 5.81182307e-03 -8.91018093e-01 -4.53945935e-01 5.81182446e-03 -8.92608941e-01 -4.50809866e-01 5.81181888e-03 -8.94167364e-01 -4.47709024e-01 5.81182074e-03 -8.95726919e-01 -4.44581062e-01 5.81182214e-03 -8.97265375e-01 -4.41469908e-01 5.81182167e-03 -8.98810625e-01 -4.38316524e-01 5.81181981e-03 -9.00369763e-01 -4.35105294e-01 5.81181096e-03 -9.01928663e-01 -4.31858987e-01 5.81182074e-03 -9.03394997e-01 -4.28786248e-01 5.81183005e-03 -9.04842079e-01 -4.25721258e-01 5.81182493e-03 -9.06316698e-01 -4.22575653e-01 5.81182214e-03 -9.07825708e-01 -4.19326067e-01 5.81181096e-03 -9.09284532e-01 -4.16145921e-01 5.81183145e-03 -9.10688758e-01 -4.13068980e-01 5.81182214e-03 -9.12133098e-01 -4.09872264e-01 5.81182074e-03 -9.13563967e-01 -4.06670570e-01 5.81181888e-03 -9.14974868e-01 -4.03487653e-01 5.81182260e-03 -9.16377544e-01 -4.00291681e-01 5.81181981e-03 -9.17808592e-01 -3.96999806e-01 5.81181096e-03 -9.19175267e-01 -3.93814087e-01 5.81183005e-03 -9.20507491e-01 -3.90696496e-01 5.81182353e-03 -9.21871066e-01 -3.87471318e-01 5.81182027e-03 -9.23219919e-01 -3.84245306e-01 5.81181981e-03 -9.24582481e-01 -3.80956054e-01 5.81181096e-03 -9.25920665e-01 -3.77692133e-01 5.81183145e-03 -9.27198112e-01 -3.74540120e-01 5.81182446e-03 -9.28523123e-01 -3.71248186e-01 5.81181422e-03 -9.29817080e-01 -3.67996514e-01 5.81182959e-03 -9.31059957e-01 -3.64843607e-01 5.81182074e-03 -9.32323635e-01 -3.61584544e-01 5.81182307e-03 -9.33593094e-01 -3.58318686e-01 5.81182214e-03 -9.34863567e-01 -3.54973733e-01 5.81181096e-03 -9.36090887e-01 -3.51702511e-01 5.81183191e-03 -9.37277794e-01 -3.48527759e-01 5.81182679e-03 -9.38520432e-01 -3.45181525e-01 5.81181096e-03 -9.39730883e-01 -3.41890782e-01 5.81183145e-03 -9.40911472e-01 -3.38623852e-01 5.81181096e-03 -9.42091942e-01 -3.35327297e-01 5.81183285e-03 -9.43249941e-01 -3.32053691e-01 5.81181468e-03 -9.44405496e-01 -3.28745514e-01 5.81183238e-03 -9.45516348e-01 -3.25545818e-01 5.81182539e-03 -9.46648657e-01 -3.22236985e-01 5.81182400e-03 -9.47764695e-01 -3.18939358e-01 5.81182353e-03 -9.48913574e-01 -3.15506309e-01 5.81181608e-03 -9.50002193e-01 -3.12206060e-01 5.81183098e-03 -9.51055050e-01 -3.08989346e-01 5.81182539e-03 -9.52132523e-01 -3.05654317e-01 5.81182307e-03 -9.53188121e-01 -3.02342325e-01 5.81182074e-03 -9.54267085e-01 -2.98924863e-01 5.81181096e-03 -9.55312550e-01 -2.95563877e-01 5.81183145e-03 -9.56308663e-01 -2.92326748e-01 5.81182400e-03 -9.57316875e-01 -2.88998038e-01 5.81182214e-03 -9.58320916e-01 -2.85652548e-01 5.81182446e-03 -9.59337592e-01 -2.82229573e-01 5.81181562e-03 -9.60323036e-01 -2.78850734e-01 5.81183331e-03 -9.61263716e-01 -2.75591075e-01 5.81182307e-03 -9.62219298e-01 -2.72239953e-01 5.81182586e-03 -9.63168442e-01 -2.68864989e-01 5.81182586e-03 -9.64099169e-01 -2.65502721e-01 5.81182400e-03 -9.65019822e-01 -2.62149245e-01 5.81182214e-03 -9.65926647e-01 -2.58774638e-01 5.81182353e-03 -9.66848969e-01 -2.55308360e-01 5.81181096e-03 -9.67734396e-01 -2.51935601e-01 5.81183145e-03 -9.68579710e-01 -2.48660699e-01 5.81182586e-03 -9.69437420e-01 -2.45289385e-01 5.81181981e-03 -9.70314801e-01 -2.41804048e-01 5.81181701e-03 -9.71152365e-01 -2.38416970e-01 5.81183098e-03 -9.71958280e-01 -2.35117793e-01 5.81182539e-03 -9.72775757e-01 -2.31711358e-01 5.81182260e-03 -9.73580420e-01 -2.28305593e-01 5.81182307e-03 -9.74381745e-01 -2.24855676e-01 5.81181794e-03 -9.75166380e-01 -2.21427828e-01 5.81182959e-03 -9.75910068e-01 -2.18129441e-01 5.81182446e-03 -9.76679027e-01 -2.14655712e-01 5.81181608e-03 -9.77426887e-01 -2.11223438e-01 5.81183005e-03 -9.78135943e-01 -2.07919613e-01 5.81182214e-03 -9.78864193e-01 -2.04465717e-01 5.81182353e-03 -9.79589701e-01 -2.00968176e-01 5.81181608e-03 -9.80279326e-01 -1.97559595e-01 5.81183238e-03 -9.80947614e-01 -1.94217488e-01 5.81182772e-03 -9.81613636e-01 -1.90821826e-01 5.81182586e-03 -9.82295275e-01 -1.87285721e-01 5.81181422e-03 -9.82944846e-01 -1.83836073e-01 5.81183517e-03 -9.83558238e-01 -1.80522755e-01 5.81182446e-03 -9.84194160e-01 -1.77058414e-01 5.81182539e-03 -9.84801590e-01 -1.73645407e-01 5.81182819e-03 -9.85419035e-01 -1.70084149e-01 5.81181096e-03 -9.86005843e-01 -1.66647479e-01 5.81183750e-03 -9.86561120e-01 -1.63319975e-01 5.81182819e-03 -9.87143397e-01 -1.59776181e-01 5.81181608e-03 -9.87695992e-01 -1.56317264e-01 5.81183517e-03 -9.88220215e-01 -1.52977288e-01 5.81182307e-03 -9.88745630e-01 -1.49533302e-01 5.81182446e-03 -9.89276826e-01 -1.45988151e-01 5.81181608e-03 -9.89783168e-01 -1.42503306e-01 5.81183238e-03 -9.90261436e-01 -1.39151305e-01 5.81182493e-03 -9.90753233e-01 -1.35612771e-01 5.81181608e-03 -9.91222382e-01 -1.32118419e-01 5.81183936e-03 -9.91661489e-01 -1.28780633e-01 5.81183098e-03 -9.92106378e-01 -1.25319615e-01 5.81183471e-03 -9.92533207e-01 -1.21886268e-01 5.81183517e-03 -9.92961943e-01 -1.18328899e-01 5.81183191e-03 -9.93369579e-01 -1.14836015e-01 5.81185753e-03 -9.93756294e-01 -1.11452170e-01 5.81186404e-03 -9.94146526e-01 -1.07912563e-01 5.81186265e-03 -9.94508862e-01 -1.04486607e-01 5.81192551e-03 -9.94826734e-01 -1.01410143e-01 5.81192365e-03 -9.95167315e-01 -9.80183855e-02 5.81191434e-03 -9.95499253e-01 -9.45879817e-02 5.81191434e-03 -9.95845973e-01 -9.08628926e-02 5.81191340e-03 0. 0. 0. 0. 0. 0. -9.96845484e-01 -7.91541040e-02 5.81191387e-03 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.97652173e-01 6.74882159e-02 1.16410833e-02 -9.97422040e-01 7.08374754e-02 1.16410470e-02 -9.97228742e-01 7.35410452e-02 1.16410721e-02 -9.96977806e-01 7.68627524e-02 1.16411196e-02 -9.96712863e-01 8.02370906e-02 1.16411746e-02 -9.96426404e-01 8.36972818e-02 1.16412006e-02 -9.96113002e-01 8.72753263e-02 1.16412304e-02 -9.95796859e-01 9.08432901e-02 1.16412165e-02 -9.95485723e-01 9.42103788e-02 1.16412044e-02 -9.95145440e-01 9.76792350e-02 1.16412342e-02 -9.94790614e-01 1.01256289e-01 1.16412276e-02 -9.94435072e-01 1.04693517e-01 1.16412258e-02 -9.94059563e-01 1.08173877e-01 1.16412388e-02 -9.93688941e-01 1.11577310e-01 1.16412109e-02 -9.93300915e-01 1.14919886e-01 1.16412342e-02 -9.92874801e-01 1.18531942e-01 1.16412528e-02 -9.92445648e-01 1.22099690e-01 1.16412332e-02 -9.92018700e-01 1.25539958e-01 1.16412286e-02 -9.91570830e-01 1.29006937e-01 1.16412332e-02 -9.91116881e-01 1.32465139e-01 1.16412276e-02 -9.90666091e-01 1.35833025e-01 1.16412034e-02 -9.90185440e-01 1.39253616e-01 1.16412379e-02 -9.89677012e-01 1.42819256e-01 1.16412267e-02 -9.89187598e-01 1.46188989e-01 1.16412127e-02 -9.88665879e-01 1.49639860e-01 1.16412463e-02 -9.88125443e-01 1.53202161e-01 1.16412230e-02 -9.87586319e-01 1.56619966e-01 1.16412314e-02 -9.87031519e-01 1.60080895e-01 1.16412332e-02 -9.86471534e-01 1.63495436e-01 1.16412379e-02 -9.85909522e-01 1.66855454e-01 1.16412286e-02 -9.85329211e-01 1.70233905e-01 1.16412472e-02 -9.84719098e-01 1.73741281e-01 1.16412630e-02 -9.84088421e-01 1.77285433e-01 1.16412500e-02 -9.83478427e-01 1.80625185e-01 1.16412286e-02 -9.82843399e-01 1.84038281e-01 1.16412630e-02 -9.82179880e-01 1.87554628e-01 1.16412407e-02 -9.81525958e-01 1.90948620e-01 1.16412379e-02 -9.80847478e-01 1.94398433e-01 1.16412453e-02 -9.80180562e-01 1.97752297e-01 1.16412295e-02 -9.79508698e-01 2.01049089e-01 1.16412360e-02 -9.78775859e-01 2.04569042e-01 1.16412630e-02 -9.78035748e-01 2.08090603e-01 1.16412435e-02 -9.77300525e-01 2.11519167e-01 1.16412407e-02 -9.76556540e-01 2.14927346e-01 1.16412388e-02 -9.75805163e-01 2.18316138e-01 1.16412332e-02 -9.75060046e-01 2.21628979e-01 1.16412221e-02 -9.74272072e-01 2.25034654e-01 1.16412630e-02 -9.73456085e-01 2.28561491e-01 1.16412472e-02 -9.72677827e-01 2.31871143e-01 1.16412165e-02 -9.71896887e-01 2.35111266e-01 1.16412388e-02 -9.71034646e-01 2.38625333e-01 1.16412630e-02 -9.70172942e-01 2.42114708e-01 1.16412323e-02 -9.69320595e-01 2.45499387e-01 1.16412388e-02 -9.68465209e-01 2.48861358e-01 1.16412342e-02 -9.67617929e-01 2.52139360e-01 1.16412267e-02 -9.66745615e-01 2.55463153e-01 1.16412388e-02 -9.65819120e-01 2.58927971e-01 1.16412630e-02 -9.64885414e-01 2.62402713e-01 1.16412444e-02 -9.63989556e-01 2.65673906e-01 1.16412258e-02 -9.63054001e-01 2.69032180e-01 1.16412630e-02 -9.62080777e-01 2.72502631e-01 1.16412453e-02 -9.61123824e-01 2.75856823e-01 1.16412388e-02 -9.60151911e-01 2.79217064e-01 1.16412453e-02 -9.59195316e-01 2.82497823e-01 1.16412230e-02 -9.58239138e-01 2.85722315e-01 1.16412360e-02 -9.57200527e-01 2.89160281e-01 1.16412630e-02 -9.56154108e-01 2.92614937e-01 1.16412472e-02 -9.55122888e-01 2.95963556e-01 1.16412453e-02 -9.54124153e-01 2.99180955e-01 1.16412211e-02 -9.53069031e-01 3.02505463e-01 1.16412630e-02 -9.51989114e-01 3.05904359e-01 1.16412314e-02 -9.50945258e-01 3.09131742e-01 1.16412276e-02 -9.49848533e-01 3.12469482e-01 1.16412630e-02 -9.48748589e-01 3.15814346e-01 1.16412248e-02 -9.47674692e-01 3.19015861e-01 1.16412379e-02 -9.46524203e-01 3.22398067e-01 1.16412630e-02 -9.45360303e-01 3.25808465e-01 1.16412379e-02 -9.44225907e-01 3.29076111e-01 1.16412388e-02 -9.43075061e-01 3.32359850e-01 1.16412407e-02 -9.41914797e-01 3.35643530e-01 1.16412323e-02 -9.40768778e-01 3.38838398e-01 1.16412304e-02 -9.39567029e-01 3.42147470e-01 1.16412630e-02 -9.38332677e-01 3.45512867e-01 1.16412342e-02 -9.37145293e-01 3.48712683e-01 1.16412239e-02 -9.35922325e-01 3.51975054e-01 1.16412630e-02 -9.34667706e-01 3.55312079e-01 1.16412407e-02 -9.33428228e-01 3.58575284e-01 1.16412453e-02 -9.32162166e-01 3.61834913e-01 1.16412463e-02 -9.30916786e-01 3.65039498e-01 1.16412276e-02 -9.29676414e-01 3.68184179e-01 1.16412360e-02 -9.28384066e-01 3.71425629e-01 1.16412407e-02 -9.27055359e-01 3.74723345e-01 1.16412630e-02 -9.25705075e-01 3.78054112e-01 1.16412472e-02 -9.24416065e-01 3.81198436e-01 1.16412230e-02 -9.23073709e-01 3.84423107e-01 1.16412630e-02 -9.21693802e-01 3.87732476e-01 1.16412407e-02 -9.20345604e-01 3.90917093e-01 1.16412397e-02 -9.18975353e-01 3.94124389e-01 1.16412453e-02 -9.17623401e-01 3.97275269e-01 1.16412248e-02 -9.16274607e-01 4.00375903e-01 1.16412342e-02 -9.14831519e-01 4.03650820e-01 1.16412565e-02 -9.13381636e-01 4.06928658e-01 1.16412472e-02 -9.11942601e-01 4.10140336e-01 1.16412453e-02 -9.10504520e-01 4.13323045e-01 1.16412472e-02 -9.09060121e-01 4.16485459e-01 1.16412435e-02 -9.07616258e-01 4.19628263e-01 1.16412360e-02 -9.06151175e-01 4.22776222e-01 1.16412528e-02 -9.04656053e-01 4.25969571e-01 1.16412407e-02 -9.03206050e-01 4.29047644e-01 1.16412202e-02 -9.01734710e-01 4.32120442e-01 1.16412360e-02 -9.00189817e-01 4.35329825e-01 1.16412630e-02 -8.98631692e-01 4.38545913e-01 1.16412388e-02 -8.97102356e-01 4.41661775e-01 1.16412314e-02 -8.95561278e-01 4.44774747e-01 1.16412453e-02 -8.94024253e-01 4.47862566e-01 1.16412267e-02 -8.92497361e-01 4.50894982e-01 1.16412388e-02 -8.90876472e-01 4.54080582e-01 1.16412630e-02 -8.89241695e-01 4.57282484e-01 1.16412435e-02 -8.87677431e-01 4.60312486e-01 1.16412230e-02 -8.86076212e-01 4.63379920e-01 1.16412630e-02 -8.84412110e-01 4.66554850e-01 1.16412388e-02 -8.82777691e-01 4.69640315e-01 1.16412323e-02 -8.81142557e-01 4.72702652e-01 1.16412314e-02 -8.79528701e-01 4.75697845e-01 1.16412258e-02 -8.77898693e-01 4.78704751e-01 1.16412323e-02 -8.76186371e-01 4.81821477e-01 1.16412584e-02 -8.74446929e-01 4.84970152e-01 1.16412342e-02 -8.72752607e-01 4.88015264e-01 1.16412342e-02 -8.71044576e-01 4.91058230e-01 1.16412453e-02 -8.69321525e-01 4.94100839e-01 1.16412342e-02 -8.67633939e-01 4.97066587e-01 1.16412248e-02 -8.65937173e-01 5.00013053e-01 1.16412323e-02 -8.64158869e-01 5.03073931e-01 1.16412528e-02 -8.62357676e-01 5.06159842e-01 1.16412425e-02 -8.60623837e-01 5.09106278e-01 1.16412211e-02 -8.58849287e-01 5.12085557e-01 1.16412528e-02 -8.57018232e-01 5.15148222e-01 1.16412342e-02 -8.55209708e-01 5.18141866e-01 1.16412342e-02 -8.53398263e-01 5.21123052e-01 1.16412435e-02 -8.51564944e-01 5.24111390e-01 1.16412379e-02 -8.49788308e-01 5.26995182e-01 1.16412230e-02 -8.47941935e-01 5.29948592e-01 1.16412528e-02 -8.46048057e-01 5.32971382e-01 1.16412444e-02 -8.44172895e-01 5.35936713e-01 1.16412388e-02 -8.42295825e-01 5.38882911e-01 1.16412342e-02 -8.40427339e-01 5.41788697e-01 1.16412388e-02 -8.38532746e-01 5.44718981e-01 1.16412323e-02 -8.36623192e-01 5.47644138e-01 1.16412453e-02 -8.34712148e-01 5.50557554e-01 1.16412360e-02 -8.32817435e-01 5.53418934e-01 1.16412221e-02 -8.30943942e-01 5.56226432e-01 1.16412379e-02 -8.28951180e-01 5.59189498e-01 1.16412630e-02 -8.26946974e-01 5.62153876e-01 1.16412314e-02 -8.24979484e-01 5.65037608e-01 1.16412323e-02 -8.23004961e-01 5.67912340e-01 1.16412342e-02 -8.21010709e-01 5.70786715e-01 1.16412360e-02 -8.19061339e-01 5.73583007e-01 1.16412230e-02 -8.17043424e-01 5.76449573e-01 1.16412630e-02 -8.14967632e-01 5.79376340e-01 1.16412453e-02 -8.13007653e-01 5.82136333e-01 1.16412239e-02 -8.10968339e-01 5.84961593e-01 1.16412630e-02 -8.08889627e-01 5.87838292e-01 1.16412397e-02 -8.06822419e-01 5.90670586e-01 1.16412379e-02 -8.04752171e-01 5.93487263e-01 1.16412463e-02 -8.02688420e-01 5.96275330e-01 1.16412388e-02 -8.00663948e-01 5.98996401e-01 1.16412276e-02 -7.98537433e-01 6.01820350e-01 1.16412630e-02 -7.96368957e-01 6.04693234e-01 1.16412407e-02 -7.94259906e-01 6.07459545e-01 1.16412388e-02 -7.92193532e-01 6.10155880e-01 1.16412239e-02 -7.90067792e-01 6.12893522e-01 1.16412630e-02 -7.87862897e-01 6.15732193e-01 1.16412397e-02 -7.85761178e-01 6.18417025e-01 1.16412276e-02 -7.83596516e-01 6.21148407e-01 1.16412630e-02 -7.81423390e-01 6.23889446e-01 1.16412258e-02 -7.79308975e-01 6.26524687e-01 1.16412453e-02 -7.77055621e-01 6.29316032e-01 1.16412630e-02 -7.74804592e-01 6.32087111e-01 1.16412407e-02 -7.72583842e-01 6.34797454e-01 1.16412453e-02 -7.70335376e-01 6.37528241e-01 1.16412332e-02 -7.68112302e-01 6.40202343e-01 1.16412388e-02 -7.65879571e-01 6.42871201e-01 1.16412388e-02 -7.63630748e-01 6.45542443e-01 1.16412453e-02 -7.61367321e-01 6.48208141e-01 1.16412397e-02 -7.59148061e-01 6.50811434e-01 1.16412239e-02 -7.56883919e-01 6.53433442e-01 1.16412630e-02 -7.54511595e-01 6.56177342e-01 1.16412351e-02 -7.52227187e-01 6.58793628e-01 1.16412407e-02 -7.49908507e-01 6.61432087e-01 1.16412407e-02 -7.47598946e-01 6.64044261e-01 1.16412379e-02 -7.45284617e-01 6.66639745e-01 1.16412453e-02 -7.43034899e-01 6.69149637e-01 1.16412202e-02 -7.40697742e-01 6.71729565e-01 1.16412630e-02 -7.38269925e-01 6.74397647e-01 1.16412444e-02 -7.35993028e-01 6.76890671e-01 1.16412183e-02 -7.33626544e-01 6.79442346e-01 1.16412630e-02 -7.31179893e-01 6.82078838e-01 1.16412360e-02 -7.28826582e-01 6.84592187e-01 1.16412407e-02 -7.26399779e-01 6.87163591e-01 1.16412584e-02 -7.24042594e-01 6.89656317e-01 1.16412258e-02 -7.21695244e-01 6.92101181e-01 1.16412388e-02 -7.19220102e-01 6.94684029e-01 1.16412630e-02 -7.16699421e-01 6.97284400e-01 1.16412472e-02 -7.14245498e-01 6.99794471e-01 1.16412444e-02 -7.11802304e-01 7.02283025e-01 1.16412323e-02 -7.09412277e-01 7.04704344e-01 1.16412202e-02 -7.06940413e-01 7.07158685e-01 1.16412453e-02 -7.04427898e-01 7.09681809e-01 1.16412388e-02 -7.01944828e-01 7.12136626e-01 1.16412379e-02 -6.99528217e-01 7.14512348e-01 1.16412221e-02 -6.97027683e-01 7.16946661e-01 1.16412630e-02 -6.94431424e-01 7.19467521e-01 1.16412397e-02 -6.91920340e-01 7.21868336e-01 1.16412379e-02 -6.89381003e-01 7.24304199e-01 1.16412407e-02 -6.86871052e-01 7.26679564e-01 1.16412388e-02 -6.84354424e-01 7.29049265e-01 1.16412332e-02 -6.81806326e-01 7.31430352e-01 1.16412453e-02 -6.79225028e-01 7.33832598e-01 1.16412435e-02 -6.76645994e-01 7.36214578e-01 1.16412453e-02 -6.74143612e-01 7.38505304e-01 1.16412230e-02 -6.71556711e-01 7.40853667e-01 1.16412630e-02 -6.68906569e-01 7.43251801e-01 1.16412342e-02 -6.66352153e-01 7.45541096e-01 1.16412286e-02 -6.63762152e-01 7.47844756e-01 1.16412630e-02 -6.61101818e-01 7.50200689e-01 1.16412388e-02 -6.58544481e-01 7.52448261e-01 1.16412276e-02 -6.55905724e-01 7.54743874e-01 1.16412630e-02 -6.53197050e-01 7.57092237e-01 1.16412388e-02 -6.50554955e-01 7.59364784e-01 1.16412388e-02 -6.47875190e-01 7.61651516e-01 1.16412379e-02 -6.45239532e-01 7.63886034e-01 1.16412388e-02 -6.42562628e-01 7.66138673e-01 1.16412472e-02 -6.39887094e-01 7.68376112e-01 1.16412472e-02 -6.37204826e-01 7.70600855e-01 1.16412407e-02 -6.34576738e-01 7.72771895e-01 1.16412230e-02 -6.31944954e-01 7.74918675e-01 1.16412435e-02 -6.29152596e-01 7.77187169e-01 1.16412621e-02 -6.26399517e-01 7.79410362e-01 1.16412332e-02 -6.23676002e-01 7.81589687e-01 1.16412472e-02 -6.20914221e-01 7.83784688e-01 1.16412453e-02 -6.18185937e-01 7.85941660e-01 1.16412407e-02 -6.15509689e-01 7.88042188e-01 1.16412239e-02 -6.12752140e-01 7.90180862e-01 1.16412630e-02 -6.09911144e-01 7.92379379e-01 1.16412453e-02 -6.07202351e-01 7.94459522e-01 1.16412239e-02 -6.04442954e-01 7.96553254e-01 1.16412630e-02 -6.01580322e-01 7.98721552e-01 1.16412453e-02 -5.98788917e-01 8.00816000e-01 1.16412360e-02 -5.96010149e-01 8.02887082e-01 1.16412407e-02 -5.93280852e-01 8.04908395e-01 1.16412267e-02 -5.90509832e-01 8.06938529e-01 1.16412453e-02 -5.87607563e-01 8.09053957e-01 1.16412612e-02 -5.84781229e-01 8.11102509e-01 1.16412258e-02 -5.81943631e-01 8.13136697e-01 1.16412630e-02 -5.79102874e-01 8.15171421e-01 1.16412202e-02 -5.76287568e-01 8.17157149e-01 1.16412630e-02 -5.73318481e-01 8.19242477e-01 1.16412453e-02 -5.70513070e-01 8.21202993e-01 1.16412230e-02 -5.67685127e-01 8.23154807e-01 1.16412630e-02 -5.64806104e-01 8.25140297e-01 1.16412230e-02 -5.61933696e-01 8.27091277e-01 1.16412630e-02 -5.59019566e-01 8.29070687e-01 1.16412248e-02 -5.56181073e-01 8.30971301e-01 1.16412565e-02 -5.53201318e-01 8.32957327e-01 1.16412528e-02 -5.50214708e-01 8.34933937e-01 1.16412491e-02 -5.47378600e-01 8.36802363e-01 1.16412221e-02 -5.44558227e-01 8.38637590e-01 1.16412453e-02 -5.41537881e-01 8.40585947e-01 1.16412630e-02 -5.38592458e-01 8.42483044e-01 1.16412267e-02 -5.35664856e-01 8.44341338e-01 1.16412612e-02 -5.32713652e-01 8.46214831e-01 1.16412230e-02 -5.29773653e-01 8.48049104e-01 1.16412630e-02 -5.26717782e-01 8.49955320e-01 1.16412453e-02 -5.23732483e-01 8.51796150e-01 1.16412453e-02 -5.20832181e-01 8.53578746e-01 1.16412276e-02 -5.17892897e-01 8.55358601e-01 1.16412593e-02 -5.14819682e-01 8.57212245e-01 1.16412556e-02 -5.11857986e-01 8.58988822e-01 1.16412276e-02 -5.08876681e-01 8.60753596e-01 1.16412630e-02 -5.05871892e-01 8.62528682e-01 1.16412276e-02 -5.02878547e-01 8.64271045e-01 1.16412630e-02 -4.99767959e-01 8.66077065e-01 1.16412435e-02 -4.96827155e-01 8.67769361e-01 1.16412276e-02 -4.93776113e-01 8.69501650e-01 1.16412630e-02 -4.90716845e-01 8.71240437e-01 1.16412276e-02 -4.87690300e-01 8.72931123e-01 1.16412602e-02 -4.84590590e-01 8.74655962e-01 1.16412379e-02 -4.81545150e-01 8.76336694e-01 1.16412630e-02 -4.78423625e-01 8.78048003e-01 1.16412491e-02 -4.75327641e-01 8.79724503e-01 1.16412472e-02 -4.72356141e-01 8.81328285e-01 1.16412230e-02 -4.69392300e-01 8.82906854e-01 1.16412472e-02 -4.66204405e-01 8.84590805e-01 1.16412630e-02 -4.63102043e-01 8.86228979e-01 1.16412211e-02 -4.60021347e-01 8.87823582e-01 1.16412630e-02 -4.56859946e-01 8.89459729e-01 1.16412314e-02 -4.53760147e-01 8.91040146e-01 1.16412528e-02 -4.50603008e-01 8.92643273e-01 1.16412435e-02 -4.47464526e-01 8.94220531e-01 1.16412472e-02 -4.44436073e-01 8.95732939e-01 1.16412267e-02 -4.41413432e-01 8.97222579e-01 1.16412444e-02 -4.38196421e-01 8.98800373e-01 1.16412342e-02 -4.35030609e-01 9.00340378e-01 1.16412276e-02 -4.31885123e-01 9.01843250e-01 1.16412630e-02 -4.28732395e-01 9.03354645e-01 1.16412276e-02 -4.25617367e-01 9.04819489e-01 1.16412565e-02 -4.22444135e-01 9.06312227e-01 1.16412276e-02 -4.19282675e-01 9.07774568e-01 1.16412630e-02 -4.16043878e-01 9.09263730e-01 1.16412407e-02 -4.12872493e-01 9.10708785e-01 1.16412453e-02 -4.09691870e-01 9.12146330e-01 1.16412472e-02 -4.06559289e-01 9.13549006e-01 1.16412276e-02 -4.03379589e-01 9.14951444e-01 1.16412528e-02 -4.00117636e-01 9.16385651e-01 1.16412472e-02 -3.96896988e-01 9.17783797e-01 1.16412435e-02 -3.93760681e-01 9.19133484e-01 1.16412230e-02 -3.90635341e-01 9.20464993e-01 1.16412453e-02 -3.87355179e-01 9.21849608e-01 1.16412630e-02 -3.84142339e-01 9.23198223e-01 1.16412267e-02 -3.80928725e-01 9.24523354e-01 1.16412630e-02 -3.77680033e-01 9.25861239e-01 1.16412258e-02 -3.74435842e-01 9.27172661e-01 1.16412528e-02 -3.71128052e-01 9.28502262e-01 1.16412463e-02 -3.67866278e-01 9.29802537e-01 1.16412397e-02 -3.64729851e-01 9.31040108e-01 1.16412202e-02 -3.61502349e-01 9.32286263e-01 1.16412630e-02 -3.58168691e-01 9.33585703e-01 1.16412323e-02 -3.54967028e-01 9.34800029e-01 1.16412258e-02 -3.51693332e-01 9.36028004e-01 1.16412630e-02 -3.48420709e-01 9.37254071e-01 1.16412267e-02 -3.45173478e-01 9.38455462e-01 1.16412528e-02 -3.41865361e-01 9.39676166e-01 1.16412276e-02 -3.38598073e-01 9.40851510e-01 1.16412537e-02 -3.35227042e-01 9.42062020e-01 1.16412397e-02 -3.31946313e-01 9.43222165e-01 1.16412388e-02 -3.28657597e-01 9.44372058e-01 1.16412453e-02 -3.25420141e-01 9.45496976e-01 1.16412258e-02 -3.22118938e-01 9.46619213e-01 1.16412630e-02 -3.18758786e-01 9.47760522e-01 1.16412453e-02 -3.15429598e-01 9.48873162e-01 1.16412332e-02 -3.12204748e-01 9.49941993e-01 1.16412230e-02 -3.08976144e-01 9.50995088e-01 1.16412388e-02 -3.05578917e-01 9.52089489e-01 1.16412630e-02 -3.02236974e-01 9.53160763e-01 1.16412221e-02 -2.99022675e-01 9.54171658e-01 1.16412379e-02 -2.95678079e-01 9.55214202e-01 1.16412295e-02 -2.92272568e-01 9.56257463e-01 1.16412630e-02 -2.88917959e-01 9.57280934e-01 1.16412239e-02 -2.85587788e-01 9.58274186e-01 1.16412528e-02 -2.82234788e-01 9.59273458e-01 1.16412248e-02 -2.78900206e-01 9.60243046e-01 1.16412630e-02 -2.75482744e-01 9.61231470e-01 1.16412360e-02 -2.72203356e-01 9.62166548e-01 1.16412267e-02 -2.68832684e-01 9.63110447e-01 1.16412556e-02 -2.65418410e-01 9.64059293e-01 1.16412323e-02 -2.62046605e-01 9.64981139e-01 1.16412574e-02 -2.58718818e-01 9.65880692e-01 1.16412230e-02 -2.55346119e-01 9.66773212e-01 1.16412630e-02 -2.51904011e-01 9.67678845e-01 1.16412435e-02 -2.48512566e-01 9.68553782e-01 1.16412425e-02 -2.45134309e-01 9.69412565e-01 1.16412453e-02 -2.41829693e-01 9.70247030e-01 1.16412230e-02 -2.38450184e-01 9.71079588e-01 1.16412500e-02 -2.34991580e-01 9.71926689e-01 1.16412342e-02 -2.31584147e-01 9.72743154e-01 1.16412388e-02 -2.28264391e-01 9.73528206e-01 1.16412258e-02 -2.24936366e-01 9.74300504e-01 1.16412435e-02 -2.21480772e-01 9.75089788e-01 1.16412491e-02 -2.18068764e-01 9.75863099e-01 1.16412258e-02 -2.14724958e-01 9.76599813e-01 1.16412407e-02 -2.11337388e-01 9.77339685e-01 1.16412388e-02 -2.07854196e-01 9.78084981e-01 1.16412509e-02 -2.04435617e-01 9.78809059e-01 1.16412258e-02 -2.01029539e-01 9.79511440e-01 1.16412519e-02 -1.97606117e-01 9.80212033e-01 1.16412202e-02 -1.94170937e-01 9.80890453e-01 1.16412630e-02 -1.90632105e-01 9.81587172e-01 1.16412435e-02 -1.87299326e-01 9.82232749e-01 1.16412221e-02 -1.83876544e-01 9.82872665e-01 1.16412630e-02 -1.80452093e-01 9.83511865e-01 1.16412193e-02 -1.77042097e-01 9.84131694e-01 1.16412630e-02 -1.73586160e-01 9.84753668e-01 1.16412211e-02 -1.70262679e-01 9.85324502e-01 1.16412425e-02 -1.66692093e-01 9.85933602e-01 1.16412630e-02 -1.63128868e-01 9.86531138e-01 1.16412370e-02 -1.59682706e-01 9.87094522e-01 1.16412453e-02 -1.56367853e-01 9.87629354e-01 1.16412202e-02 -1.53037161e-01 9.88146782e-01 1.16412435e-02 -1.49449155e-01 9.88691449e-01 1.16412630e-02 -1.45890862e-01 9.89226580e-01 1.16412472e-02 -1.42429322e-01 9.89731550e-01 1.16412388e-02 -1.39073834e-01 9.90212321e-01 1.16412239e-02 -1.35732472e-01 9.90674675e-01 1.16412397e-02 -1.32271931e-01 9.91139948e-01 1.16412472e-02 -1.28801256e-01 9.91596758e-01 1.16412481e-02 -1.25239164e-01 9.92051601e-01 1.16412630e-02 -1.21682167e-01 9.92496133e-01 1.16412360e-02 -1.18294336e-01 9.92908537e-01 1.16412202e-02 -1.14844374e-01 9.93305266e-01 1.16412630e-02 -1.11375488e-01 9.93709862e-01 1.16412202e-02 -1.08017214e-01 9.94075835e-01 1.16412360e-02 -1.04423039e-01 9.94457543e-01 1.16412630e-02 -1.00868605e-01 9.94824886e-01 1.16412453e-02 -9.73794162e-02 9.95174289e-01 1.16412425e-02 -9.39164236e-02 9.95509505e-01 1.16412397e-02 -9.04274285e-02 9.95830715e-01 1.16412425e-02 -8.70580226e-02 9.96135712e-01 1.16412211e-02 -8.36679563e-02 9.96420860e-01 1.16412397e-02 -8.00926834e-02 9.96712208e-01 1.16412630e-02 -7.65123442e-02 9.96997118e-01 1.16412388e-02 -7.30328262e-02 9.97258067e-01 1.16412453e-02 -6.96671829e-02 9.97500479e-01 1.16412258e-02 -6.62711635e-02 9.97730255e-01 1.16412397e-02 -6.27748296e-02 9.97953534e-01 1.16412379e-02 -5.92222549e-02 9.98169243e-01 1.16412565e-02 -5.56182638e-02 9.98379648e-01 1.16412491e-02 -5.21233827e-02 9.98565674e-01 1.16412453e-02 -4.87339906e-02 9.98743176e-01 1.16412239e-02 -4.52736728e-02 9.98898029e-01 1.16412630e-02 -4.17791158e-02 9.99059141e-01 1.16412211e-02 -3.83087471e-02 9.99189198e-01 1.16412630e-02 -3.46936397e-02 9.99325514e-01 1.16412351e-02 -3.13104130e-02 9.99440730e-01 1.16412221e-02 -2.78397594e-02 9.99538302e-01 1.16412528e-02 -2.43488140e-02 9.99637187e-01 1.16412286e-02 -2.08361149e-02 9.99702036e-01 1.16412630e-02 -1.72292758e-02 9.99783635e-01 1.16412472e-02 -1.37503417e-02 9.99828398e-01 1.16412407e-02 -1.02449413e-02 9.99875546e-01 1.16412435e-02 -6.85653929e-03 9.99913156e-01 1.16412239e-02 -3.37039423e-03 9.99924481e-01 1.16412630e-02 1.31729015e-04 9.99931395e-01 1.16412230e-02 3.51853762e-03 9.99928236e-01 1.16412314e-02 7.10201450e-03 9.99906957e-01 1.16412537e-02 1.06882276e-02 9.99869466e-01 1.16412388e-02 1.41921435e-02 9.99822497e-01 1.16412435e-02 1.76849347e-02 9.99775887e-01 1.16412453e-02 2.10778918e-02 9.99708712e-01 1.16412202e-02 2.44697891e-02 9.99628901e-01 1.16412435e-02 2.80630086e-02 9.99532402e-01 1.16412630e-02 3.16665210e-02 9.99426782e-01 1.16412397e-02 3.50443460e-02 9.99317408e-01 1.16412230e-02 3.84064615e-02 9.99191523e-01 1.16412379e-02 4.19859774e-02 9.99042928e-01 1.16412630e-02 4.55271155e-02 9.98892367e-01 1.16412239e-02 4.89827022e-02 9.98727322e-01 1.16412574e-02 5.25537096e-02 9.98543143e-01 1.16412407e-02 5.60001135e-02 9.98360515e-01 1.16412323e-02 5.94922677e-02 9.98154640e-01 1.16412491e-02 6.30034283e-02 9.97937679e-01 1.16412472e-02 6.64905757e-02 9.97713149e-01 1.16412453e-02 6.98966458e-02 9.97483134e-01 1.16412230e-02 7.33817443e-02 9.97228801e-01 1.16412546e-02 7.69373700e-02 9.96961892e-01 1.16412453e-02 8.04185569e-02 9.96688843e-01 1.16412416e-02 8.39020163e-02 9.96400118e-01 1.16412453e-02 8.73535052e-02 9.96105194e-01 1.16412379e-02 9.07450318e-02 9.95802343e-01 1.16412304e-02 9.42073539e-02 9.95478809e-01 1.16412630e-02 9.78048369e-02 9.95132804e-01 1.16412453e-02 1.01263903e-01 9.94787216e-01 1.16412407e-02 1.04664013e-01 9.94437039e-01 1.16412342e-02 1.08058162e-01 9.94071782e-01 1.16412360e-02 1.11528188e-01 9.93687749e-01 1.16412612e-02 1.15098543e-01 9.93279338e-01 1.16412509e-02 1.18622027e-01 9.92865145e-01 1.16412453e-02 1.22104779e-01 9.92443442e-01 1.16412453e-02 1.25458255e-01 9.92029905e-01 1.16412295e-02 1.28915623e-01 9.91578221e-01 1.16412630e-02 1.32407814e-01 9.91127074e-01 1.16412202e-02 1.35828108e-01 9.90656972e-01 1.16412630e-02 1.39416665e-01 9.90160286e-01 1.16412491e-02 1.42788231e-01 9.89684582e-01 1.16412202e-02 1.46205112e-01 9.89176452e-01 1.16412630e-02 1.49779201e-01 9.88645554e-01 1.16412453e-02 1.53225437e-01 9.88118887e-01 1.16412407e-02 1.56572223e-01 9.87596333e-01 1.16412183e-02 1.60013884e-01 9.87037957e-01 1.16412630e-02 1.63556680e-01 9.86461163e-01 1.16412407e-02 1.66904464e-01 9.85902488e-01 1.16412248e-02 1.70332938e-01 9.85310137e-01 1.16412630e-02 1.73793688e-01 9.84715164e-01 1.16412267e-02 1.77149221e-01 9.84113514e-01 1.16412388e-02 1.80638239e-01 9.83472407e-01 1.16412574e-02 1.84157699e-01 9.82822835e-01 1.16412407e-02 1.87613636e-01 9.82169032e-01 1.16412416e-02 1.91035554e-01 9.81508970e-01 1.16412407e-02 1.94393516e-01 9.80854988e-01 1.16412221e-02 1.97702989e-01 9.80186820e-01 1.16412472e-02 2.01132640e-01 9.79488909e-01 1.16412500e-02 2.04635456e-01 9.78760898e-01 1.16412630e-02 2.08144233e-01 9.78024542e-01 1.16412435e-02 2.11527094e-01 9.77301002e-01 1.16412342e-02 2.14929521e-01 9.76554155e-01 1.16412472e-02 2.18284890e-01 9.75814104e-01 1.16412239e-02 2.21682116e-01 9.75040674e-01 1.16412584e-02 2.25164816e-01 9.74248290e-01 1.16412379e-02 2.28539646e-01 9.73464429e-01 1.16412248e-02 2.31930301e-01 9.72658575e-01 1.16412528e-02 2.35266447e-01 9.71859455e-01 1.16412323e-02 2.38680214e-01 9.71023798e-01 1.16412491e-02 2.42060050e-01 9.70189035e-01 1.16412267e-02 2.45435670e-01 9.69333053e-01 1.16412630e-02 2.48921394e-01 9.68449712e-01 1.16412407e-02 2.52276152e-01 9.67578888e-01 1.16412453e-02 2.55639374e-01 9.66697395e-01 1.16412463e-02 2.59038419e-01 9.65791762e-01 1.16412472e-02 2.62331516e-01 9.64907050e-01 1.16412276e-02 2.65677571e-01 9.63982522e-01 1.16412733e-02 2.69145638e-01 9.63025749e-01 1.16412407e-02 2.72495955e-01 9.62083101e-01 1.16412444e-02 2.75811315e-01 9.61138189e-01 1.16412323e-02 2.79110879e-01 9.60184038e-01 1.16412453e-02 2.82530844e-01 9.59181666e-01 1.16412491e-02 2.85825491e-01 9.58210051e-01 1.16412248e-02 2.89134115e-01 9.57209289e-01 1.16412621e-02 2.92579591e-01 9.56166327e-01 1.16412388e-02 2.95844525e-01 9.55162644e-01 1.16412304e-02 2.99149215e-01 9.54127729e-01 1.16412630e-02 3.02505016e-01 9.53074217e-01 1.16412295e-02 3.05782765e-01 9.52022612e-01 1.16412630e-02 3.09207767e-01 9.50916290e-01 1.16412528e-02 3.12569439e-01 9.49817002e-01 1.16412472e-02 3.15885246e-01 9.48720038e-01 1.16412491e-02 3.19111645e-01 9.47644472e-01 1.16412267e-02 3.22379231e-01 9.46529865e-01 1.16412630e-02 3.25771838e-01 9.45375144e-01 1.16412332e-02 3.28981757e-01 9.44260478e-01 1.16412304e-02 3.32279772e-01 9.43099737e-01 1.16412630e-02 3.35678279e-01 9.41902757e-01 1.16412388e-02 3.38938296e-01 9.40731466e-01 1.16412388e-02 3.42187196e-01 9.39555585e-01 1.16412379e-02 3.45402658e-01 9.38374639e-01 1.16412248e-02 3.48652273e-01 9.37163174e-01 1.16412630e-02 3.51973832e-01 9.35925066e-01 1.16412332e-02 3.55263144e-01 9.34684098e-01 1.16412630e-02 3.58590186e-01 9.33421671e-01 1.16412528e-02 3.61787915e-01 9.32182610e-01 1.16412211e-02 3.64988416e-01 9.30931866e-01 1.16412630e-02 3.68244141e-01 9.29652870e-01 1.16412276e-02 3.71469557e-01 9.28363860e-01 1.16412630e-02 3.74809116e-01 9.27022099e-01 1.16412491e-02 3.78065139e-01 9.25701380e-01 1.16412500e-02 3.81289303e-01 9.24374819e-01 1.16412528e-02 3.84439558e-01 9.23073292e-01 1.16412286e-02 3.87623280e-01 9.21734631e-01 1.16412630e-02 3.90944570e-01 9.20332730e-01 1.16412453e-02 3.94130737e-01 9.18974400e-01 1.16412425e-02 3.97356302e-01 9.17584181e-01 1.16412491e-02 4.00488704e-01 9.16227520e-01 1.16412267e-02 4.03672874e-01 9.14821684e-01 1.16412630e-02 4.06872451e-01 9.13408399e-01 1.16412276e-02 4.09955025e-01 9.12027836e-01 1.16412472e-02 4.13223416e-01 9.10546005e-01 1.16412630e-02 4.16414112e-01 9.09095466e-01 1.16412267e-02 4.19541925e-01 9.07652080e-01 1.16412630e-02 4.22732472e-01 9.06177104e-01 1.16412258e-02 4.25804943e-01 9.04734850e-01 1.16412435e-02 4.28964347e-01 9.03239191e-01 1.16412491e-02 4.32196379e-01 9.01694238e-01 1.16412630e-02 4.35420126e-01 9.00149405e-01 1.16412425e-02 4.38476503e-01 8.98667216e-01 1.16412286e-02 4.41546232e-01 8.97157133e-01 1.16412472e-02 4.44678485e-01 8.95609081e-01 1.16412453e-02 4.47786778e-01 8.94059300e-01 1.16412453e-02 4.50974107e-01 8.92453432e-01 1.16412630e-02 4.54158902e-01 8.90840292e-01 1.16412453e-02 4.57200825e-01 8.89284670e-01 1.16412323e-02 4.60296065e-01 8.87680411e-01 1.16412630e-02 4.63379294e-01 8.86084020e-01 1.16412304e-02 4.66459543e-01 8.84457588e-01 1.16412630e-02 4.69546854e-01 8.82827282e-01 1.16412314e-02 4.72619772e-01 8.81182909e-01 1.16412630e-02 4.75759864e-01 8.79491746e-01 1.16412472e-02 4.78758574e-01 8.77869666e-01 1.16412267e-02 4.81807977e-01 8.76192331e-01 1.16412630e-02 4.84880477e-01 8.74498129e-01 1.16412276e-02 4.87842113e-01 8.72848153e-01 1.16412472e-02 4.90965515e-01 8.71093810e-01 1.16412630e-02 4.94063109e-01 8.69341731e-01 1.16412435e-02 4.97095764e-01 8.67613137e-01 1.16412407e-02 5.00055313e-01 8.65916133e-01 1.16412230e-02 5.03016472e-01 8.64193499e-01 1.16412407e-02 5.06007731e-01 8.62444997e-01 1.16412481e-02 5.09086072e-01 8.60627055e-01 1.16412630e-02 5.12142718e-01 8.58816206e-01 1.16412435e-02 5.15146017e-01 8.57017577e-01 1.16412500e-02 5.18068016e-01 8.55256081e-01 1.16412286e-02 5.21041334e-01 8.53447199e-01 1.16412556e-02 5.24017274e-01 8.51623118e-01 1.16412314e-02 5.26976347e-01 8.49793196e-01 1.16412630e-02 5.30033231e-01 8.47888708e-01 1.16412528e-02 5.32925069e-01 8.46078753e-01 1.16412314e-02 5.35828888e-01 8.44236195e-01 1.16412630e-02 5.38806200e-01 8.42346668e-01 1.16412239e-02 5.41721582e-01 8.40468705e-01 1.16412565e-02 5.44675231e-01 8.38562667e-01 1.16412332e-02 5.47594428e-01 8.36652994e-01 1.16412630e-02 5.50575733e-01 8.34701300e-01 1.16412360e-02 5.53433597e-01 8.32807899e-01 1.16412221e-02 5.56321681e-01 8.30878317e-01 1.16412472e-02 5.59207141e-01 8.28949749e-01 1.16412099e-02 5.61999440e-01 8.27054620e-01 1.16412183e-02 5.64962387e-01 8.25036108e-01 1.16412099e-02 5.67886710e-01 8.23032856e-01 1.16411597e-02 5.70716381e-01 8.21069658e-01 1.16411941e-02 5.73582828e-01 8.19069743e-01 1.16411215e-02 5.76328874e-01 8.17143142e-01 1.16411187e-02 5.79172671e-01 8.15128982e-01 1.16410656e-02 5.82009971e-01 8.13103497e-01 1.16410367e-02 5.84888637e-01 8.11034620e-01 1.16410404e-02 5.87771773e-01 8.08944762e-01 1.16410470e-02 5.90496123e-01 8.06955397e-01 1.16410842e-02 5.92990637e-01 8.05124104e-01 1.16410842e-02 5.96569598e-01 8.02476883e-01 1.16410833e-02 5.98702967e-01 8.00885260e-01 1.16410833e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 7.26764739e-01 6.86787069e-01 1.16410842e-02 7.29351640e-01 6.84037566e-01 1.16410740e-02 7.31625557e-01 6.81613624e-01 1.16410386e-02 7.33847141e-01 6.79222584e-01 1.16410367e-02 7.36158133e-01 6.76719069e-01 1.16411662e-02 7.38518596e-01 6.74141228e-01 1.16411485e-02 7.40855038e-01 6.71567142e-01 1.16412090e-02 7.43211329e-01 6.68963909e-01 1.16411913e-02 7.45438099e-01 6.66468084e-01 1.16412314e-02 7.47822821e-01 6.63787901e-01 1.16412574e-02 7.50140727e-01 6.61174417e-01 1.16412221e-02 7.52439559e-01 6.58546031e-01 1.16412630e-02 7.54726052e-01 6.55935705e-01 1.16412248e-02 7.56944358e-01 6.53369009e-01 1.16412407e-02 7.59224892e-01 6.50718629e-01 1.16412407e-02 7.61488378e-01 6.48067474e-01 1.16412342e-02 7.63806760e-01 6.45331621e-01 1.16412528e-02 7.66123712e-01 6.42581344e-01 1.16412435e-02 7.68309176e-01 6.39973938e-01 1.16412183e-02 7.70469010e-01 6.37364566e-01 1.16412360e-02 7.72693932e-01 6.34667814e-01 1.16412342e-02 7.74951637e-01 6.31900668e-01 1.16412630e-02 7.77228057e-01 6.29105866e-01 1.16412435e-02 7.79357135e-01 6.26468837e-01 1.16412202e-02 7.81457484e-01 6.23846173e-01 1.16412360e-02 7.83639371e-01 6.21096730e-01 1.16412472e-02 7.85871148e-01 6.18269861e-01 1.16412630e-02 7.88087487e-01 6.15447640e-01 1.16412360e-02 7.90213525e-01 6.12714171e-01 1.16412435e-02 7.92353034e-01 6.09943926e-01 1.16412435e-02 7.94433773e-01 6.07237875e-01 1.16412248e-02 7.96537280e-01 6.04468405e-01 1.16412556e-02 7.98643112e-01 6.01689935e-01 1.16412267e-02 8.00675452e-01 5.98977268e-01 1.16412388e-02 8.02827895e-01 5.96083760e-01 1.16412630e-02 8.04896832e-01 5.93295872e-01 1.16412248e-02 8.06947947e-01 5.90495110e-01 1.16412630e-02 8.09062719e-01 5.87598681e-01 1.16412425e-02 8.11072350e-01 5.84824383e-01 1.16412230e-02 8.13038409e-01 5.82088292e-01 1.16412388e-02 8.15119803e-01 5.79164088e-01 1.16412630e-02 8.17207694e-01 5.76220572e-01 1.16412472e-02 8.19194853e-01 5.73387504e-01 1.16412425e-02 8.21142852e-01 5.70599794e-01 1.16412239e-02 8.23084354e-01 5.67794383e-01 1.16412407e-02 8.25068355e-01 5.64903915e-01 1.16412472e-02 8.27074349e-01 5.61959028e-01 1.16412630e-02 8.29090416e-01 5.58983028e-01 1.16412453e-02 8.30991447e-01 5.56159079e-01 1.16412258e-02 8.32904160e-01 5.53278923e-01 1.16412574e-02 8.34837377e-01 5.50366819e-01 1.16412304e-02 8.36765170e-01 5.47424197e-01 1.16412602e-02 8.38672757e-01 5.44508815e-01 1.16412248e-02 8.40501964e-01 5.41672647e-01 1.16412463e-02 8.42441201e-01 5.38646519e-01 1.16412630e-02 8.44316483e-01 5.35714030e-01 1.16412248e-02 8.46182287e-01 5.32752752e-01 1.16412630e-02 8.48093450e-01 5.29714048e-01 1.16412286e-02 8.49877119e-01 5.26849747e-01 1.16412258e-02 8.51713359e-01 5.23863435e-01 1.16412630e-02 8.53550494e-01 5.20880818e-01 1.16412211e-02 8.55347633e-01 5.17907798e-01 1.16412630e-02 8.57173204e-01 5.14893889e-01 1.16412230e-02 8.58900607e-01 5.12002230e-01 1.16412388e-02 8.60685408e-01 5.08995116e-01 1.16412444e-02 8.62457931e-01 5.05987227e-01 1.16412416e-02 8.64264488e-01 5.02890289e-01 1.16412630e-02 8.66072416e-01 4.99777347e-01 1.16412332e-02 8.67760897e-01 4.96844411e-01 1.16412248e-02 8.69426429e-01 4.93912429e-01 1.16412453e-02 8.71151328e-01 4.90872025e-01 1.16412435e-02 8.72912228e-01 4.87721354e-01 1.16412630e-02 8.74678493e-01 4.84552622e-01 1.16412360e-02 8.76317441e-01 4.81591105e-01 1.16412258e-02 8.77939522e-01 4.78620380e-01 1.16412463e-02 8.79599214e-01 4.75564152e-01 1.16412379e-02 8.81297171e-01 4.72404152e-01 1.16412630e-02 8.82952988e-01 4.69314337e-01 1.16412258e-02 8.84577692e-01 4.66227174e-01 1.16412630e-02 8.86259556e-01 4.63034809e-01 1.16412342e-02 8.87806594e-01 4.60061282e-01 1.16412267e-02 8.89395654e-01 4.56975251e-01 1.16412630e-02 8.91009331e-01 4.53836262e-01 1.16412202e-02 8.92525613e-01 4.50834185e-01 1.16412491e-02 8.94154727e-01 4.47587311e-01 1.16412630e-02 8.95722091e-01 4.44456935e-01 1.16412258e-02 8.97257030e-01 4.41340208e-01 1.16412472e-02 8.98822844e-01 4.38150674e-01 1.16412407e-02 9.00329769e-01 4.35055435e-01 1.16412248e-02 9.01800632e-01 4.31978345e-01 1.16412463e-02 9.03305352e-01 4.28830981e-01 1.16412388e-02 9.04825389e-01 4.25602853e-01 1.16412630e-02 9.06357706e-01 4.22340244e-01 1.16412463e-02 9.07793283e-01 4.19252634e-01 1.16412267e-02 9.09198105e-01 4.16185886e-01 1.16412453e-02 9.10646021e-01 4.13012981e-01 1.16412453e-02 9.12122726e-01 4.09735560e-01 1.16412630e-02 9.13584471e-01 4.06470209e-01 1.16412453e-02 9.14967597e-01 4.03357327e-01 1.16412230e-02 9.16363358e-01 4.00164127e-01 1.16412630e-02 9.17751133e-01 3.96979719e-01 1.16412286e-02 9.19121206e-01 3.93776774e-01 1.16412630e-02 9.20500815e-01 3.90558660e-01 1.16412276e-02 9.21830118e-01 3.87407690e-01 1.16412463e-02 9.23199415e-01 3.84128064e-01 1.16412630e-02 9.24538970e-01 3.80899608e-01 1.16412286e-02 9.25852358e-01 3.77684891e-01 1.16412630e-02 9.27216172e-01 3.74333590e-01 1.16412453e-02 9.28484321e-01 3.71185631e-01 1.16412239e-02 9.29758370e-01 3.67966652e-01 1.16412630e-02 9.31050777e-01 3.64699900e-01 1.16412286e-02 9.32299495e-01 3.61468554e-01 1.16412630e-02 9.33605075e-01 3.58107299e-01 1.16412491e-02 9.34824049e-01 3.54901969e-01 1.16412248e-02 9.36005116e-01 3.51757199e-01 1.16412453e-02 9.37230110e-01 3.48479599e-01 1.16412397e-02 9.38473582e-01 3.45122933e-01 1.16412630e-02 9.39716041e-01 3.41750681e-01 1.16412435e-02 9.40872848e-01 3.38545531e-01 1.16412258e-02 9.42027509e-01 3.35313767e-01 1.16412630e-02 9.43210959e-01 3.31985742e-01 1.16412248e-02 9.44355428e-01 3.28696877e-01 1.16412630e-02 9.45534348e-01 3.25301111e-01 1.16412472e-02 9.46638048e-01 3.22084486e-01 1.16412211e-02 9.47734535e-01 3.18827778e-01 1.16412528e-02 9.48867381e-01 3.15455943e-01 1.16412258e-02 9.49949205e-01 3.12164247e-01 1.16412630e-02 9.51041996e-01 3.08838665e-01 1.16412258e-02 9.52085078e-01 3.05600226e-01 1.16412407e-02 9.53175008e-01 3.02171469e-01 1.16412630e-02 9.54229116e-01 2.98845381e-01 1.16412221e-02 9.55246210e-01 2.95559227e-01 1.16412612e-02 9.56308186e-01 2.92111665e-01 1.16412472e-02 9.57300961e-01 2.88848996e-01 1.16412258e-02 9.58290458e-01 2.85529524e-01 1.16412630e-02 9.59301054e-01 2.82144248e-01 1.16412248e-02 9.60270166e-01 2.78807670e-01 1.16412630e-02 9.61260080e-01 2.75379300e-01 1.16412342e-02 9.62192774e-01 2.72116095e-01 1.16412230e-02 9.63107765e-01 2.68852800e-01 1.16412453e-02 9.64041293e-01 2.65477329e-01 1.16412453e-02 9.64983284e-01 2.62032002e-01 1.16412556e-02 9.65926111e-01 2.58536696e-01 1.16412463e-02 9.66801822e-01 2.55250186e-01 1.16412276e-02 9.67681527e-01 2.51886010e-01 1.16412546e-02 9.68558669e-01 2.48510569e-01 1.16412230e-02 9.69403267e-01 2.45159164e-01 1.16412528e-02 9.70284402e-01 2.41663978e-01 1.16412425e-02 9.71121073e-01 2.38291577e-01 1.16412388e-02 9.71945405e-01 2.34907672e-01 1.16412425e-02 9.72743750e-01 2.31591225e-01 1.16412248e-02 9.73534644e-01 2.28225604e-01 1.16412491e-02 9.74337459e-01 2.24787727e-01 1.16412267e-02 9.75095749e-01 2.21465424e-01 1.16412276e-02 9.75878239e-01 2.17987478e-01 1.16412491e-02 9.76638317e-01 2.14573905e-01 1.16412062e-02 9.77372766e-01 2.11172983e-01 1.16412491e-02 9.78113174e-01 2.07747176e-01 1.16412202e-02 9.78808880e-01 2.04434440e-01 1.16412286e-02 9.79518652e-01 2.01001063e-01 1.16412453e-02 9.80230570e-01 1.97485521e-01 1.16412556e-02 9.80926275e-01 1.94014370e-01 1.16412286e-02 9.81595874e-01 1.90607131e-01 1.16412248e-02 9.82241750e-01 1.87248453e-01 1.16412230e-02 9.82871294e-01 1.83904976e-01 1.16412351e-02 9.83503163e-01 1.80490986e-01 1.16412286e-02 9.84154761e-01 1.76926509e-01 1.16412472e-02 9.84778285e-01 1.73434377e-01 1.16412230e-02 9.85359192e-01 1.70083135e-01 1.16412146e-02 9.85931814e-01 1.66731045e-01 1.16412304e-02 9.86508489e-01 1.63267747e-01 1.16412323e-02 9.87069428e-01 1.59837633e-01 1.16412416e-02 9.87634301e-01 1.56308264e-01 1.16412556e-02 9.88192022e-01 1.52755708e-01 1.16412323e-02 9.88715291e-01 1.49328262e-01 1.16412314e-02 9.89225745e-01 1.45936966e-01 1.16412137e-02 9.89719212e-01 1.42494023e-01 1.16412630e-02 9.90232110e-01 1.38935640e-01 1.16412276e-02 9.90698099e-01 1.35591730e-01 1.16412127e-02 9.91155684e-01 1.32138461e-01 1.16412593e-02 9.91619766e-01 1.28675982e-01 1.16412081e-02 9.92055297e-01 1.25224993e-01 1.16412472e-02 9.92495894e-01 1.21728763e-01 1.16412137e-02 9.92902279e-01 1.18344605e-01 1.16412230e-02 9.93304133e-01 1.14892460e-01 1.16412360e-02 9.93708313e-01 1.11344755e-01 1.16412528e-02 9.94101822e-01 1.07790932e-01 1.16412276e-02 9.94472325e-01 1.04321584e-01 1.16412276e-02 9.94825959e-01 1.00918248e-01 1.16412202e-02 9.95164096e-01 9.74783897e-02 1.16412453e-02 9.95505810e-01 9.39790234e-02 1.16412155e-02 9.95823562e-01 9.05071944e-02 1.16412407e-02 9.96142089e-01 8.69644880e-02 1.16412239e-02 9.96434569e-01 8.35762769e-02 1.16412081e-02 9.96713221e-01 8.01573023e-02 1.16412267e-02 9.96982157e-01 7.66982958e-02 1.16412286e-02 9.97247577e-01 7.31512383e-02 1.16412453e-02 9.97500360e-01 6.96593970e-02 1.16412221e-02 9.97730792e-01 6.62604123e-02 1.16412360e-02 9.97957349e-01 6.26862943e-02 1.16412528e-02 9.98178720e-01 5.91976456e-02 1.16412165e-02 9.98373091e-01 5.57231344e-02 1.16412509e-02 9.98568356e-01 5.21405712e-02 1.16412314e-02 9.98743236e-01 4.87343371e-02 1.16412211e-02 9.98902500e-01 4.52553034e-02 1.16412453e-02 9.99059975e-01 4.17742431e-02 1.16412211e-02 9.99192417e-01 3.83159183e-02 1.16412453e-02 9.99325633e-01 3.47042307e-02 1.16412379e-02 9.99443650e-01 3.12846527e-02 1.16412118e-02 9.99540448e-01 2.79038027e-02 1.16412304e-02 9.99633133e-01 2.44199876e-02 1.16412258e-02 9.99706149e-01 2.08503772e-02 1.16412472e-02 9.99785364e-01 1.73789244e-02 1.16412099e-02 9.99827504e-01 1.39790932e-02 1.16412276e-02 9.99875665e-01 1.04538305e-02 1.16412276e-02 9.99911070e-01 6.97054341e-03 1.16412304e-02 9.99926269e-01 3.40784737e-03 1.16412472e-02 9.99930620e-01 -1.94998342e-04 1.16412258e-02 9.99929547e-01 -3.68757523e-03 1.16412239e-02 9.99909520e-01 -7.15353386e-03 1.16412295e-02 9.99876201e-01 -1.05865235e-02 1.16412090e-02 9.99823332e-01 -1.40426299e-02 1.16412453e-02 9.99780834e-01 -1.75854620e-02 1.16412072e-02 9.99707580e-01 -2.09482163e-02 1.16412276e-02 9.99625683e-01 -2.45343484e-02 1.16412612e-02 9.99539196e-01 -2.80455947e-02 1.16412137e-02 9.99430537e-01 -3.15128677e-02 1.16412491e-02 9.99318957e-01 -3.50246131e-02 1.16412174e-02 9.99191284e-01 -3.84128615e-02 1.16412314e-02 9.99044299e-01 -4.19797562e-02 1.16412668e-02 9.98889685e-01 -4.55854274e-02 1.16412342e-02 9.98722196e-01 -4.90754172e-02 1.16412435e-02 9.98543262e-01 -5.25586270e-02 1.16412397e-02 9.98364925e-01 -5.59399538e-02 1.16412211e-02 9.98165488e-01 -5.93181327e-02 1.16412453e-02 9.97950852e-01 -6.28031567e-02 1.16412453e-02 9.97718990e-01 -6.63906038e-02 1.16412630e-02 9.97473240e-01 -6.99958727e-02 1.16412379e-02 9.97228563e-01 -7.34540299e-02 1.16412286e-02 9.96974409e-01 -7.68292621e-02 1.16412230e-02 9.96705651e-01 -8.02168474e-02 1.16412379e-02 9.96419191e-01 -8.36910084e-02 1.16412407e-02 9.96106803e-01 -8.72966498e-02 1.16412630e-02 9.95802164e-01 -9.07921940e-02 1.16412127e-02 9.95490313e-01 -9.41146612e-02 1.16412286e-02 9.95155334e-01 -9.76013616e-02 1.16412267e-02 9.94793236e-01 -1.01182960e-01 1.16412528e-02 9.94438827e-01 -1.04660086e-01 1.16412230e-02 9.94063258e-01 -1.08117655e-01 1.16412574e-02 9.93688285e-01 -1.11581407e-01 1.16412202e-02 9.93296087e-01 -1.14969812e-01 1.16412370e-02 9.92876172e-01 -1.18515402e-01 1.16412630e-02 9.92459714e-01 -1.22015737e-01 1.16412211e-02 9.92026627e-01 -1.25451773e-01 1.16412602e-02 9.91572559e-01 -1.29002437e-01 1.16412323e-02 9.91127670e-01 -1.32380992e-01 1.16412258e-02 9.90655065e-01 -1.35855511e-01 1.16412491e-02 9.90166306e-01 -1.39397904e-01 1.16412267e-02 9.89686668e-01 -1.42783225e-01 1.16412090e-02 9.89179552e-01 -1.46198422e-01 1.16412509e-02 9.88666117e-01 -1.49661139e-01 1.16412230e-02 9.88132894e-01 -1.53117299e-01 1.16412537e-02 9.87599015e-01 -1.56557426e-01 1.16412202e-02 9.87044752e-01 -1.59985259e-01 1.16412528e-02 9.86479402e-01 -1.63467914e-01 1.16412211e-02 9.85908806e-01 -1.66854426e-01 1.16412397e-02 9.85300660e-01 -1.70412898e-01 1.16412276e-02 9.84700203e-01 -1.73861638e-01 1.16412453e-02 9.84102547e-01 -1.77232906e-01 1.16412211e-02 9.83491361e-01 -1.80550843e-01 1.16412304e-02 9.82852995e-01 -1.84003517e-01 1.16412379e-02 9.82190549e-01 -1.87493533e-01 1.16412528e-02 9.81516123e-01 -1.90995738e-01 1.16412379e-02 9.80841458e-01 -1.94442376e-01 1.16412351e-02 9.80172634e-01 -1.97792128e-01 1.16412230e-02 9.79495585e-01 -2.01120168e-01 1.16412276e-02 9.78788316e-01 -2.04528645e-01 1.16412267e-02 9.78050649e-01 -2.08015367e-01 1.16412537e-02 9.77322578e-01 -2.11436749e-01 1.16412211e-02 9.76581156e-01 -2.14808092e-01 1.16412491e-02 9.75830555e-01 -2.18210965e-01 1.16412258e-02 9.75051403e-01 -2.21647963e-01 1.16412472e-02 9.74273980e-01 -2.25058943e-01 1.16412258e-02 9.73477125e-01 -2.28476852e-01 1.16412425e-02 9.72672701e-01 -2.31896281e-01 1.16412183e-02 9.71880257e-01 -2.35179961e-01 1.16412435e-02 9.71035182e-01 -2.38630146e-01 1.16412500e-02 9.70196486e-01 -2.42027104e-01 1.16412267e-02 9.69346225e-01 -2.45386258e-01 1.16412593e-02 9.68473434e-01 -2.48831600e-01 1.16412304e-02 9.67618823e-01 -2.52141923e-01 1.16412230e-02 9.66725886e-01 -2.55538434e-01 1.16412444e-02 9.65828061e-01 -2.58930534e-01 1.16412118e-02 9.64938760e-01 -2.62208432e-01 1.16412370e-02 9.63994682e-01 -2.65639514e-01 1.16412528e-02 9.63063836e-01 -2.69023210e-01 1.16412230e-02 9.62126017e-01 -2.72341758e-01 1.16412491e-02 9.61128354e-01 -2.75842011e-01 1.16412342e-02 9.60188091e-01 -2.79114485e-01 1.16412062e-02 9.59237218e-01 -2.82348424e-01 1.16412323e-02 9.58219469e-01 -2.85779506e-01 1.16412528e-02 9.57192421e-01 -2.89204031e-01 1.16412360e-02 9.56173718e-01 -2.92550325e-01 1.16412472e-02 9.55176055e-01 -2.95807898e-01 1.16412202e-02 9.54164624e-01 -2.99036801e-01 1.16412435e-02 9.53121066e-01 -3.02358121e-01 1.16412267e-02 9.52012599e-01 -3.05811048e-01 1.16412574e-02 9.50921476e-01 -3.09199095e-01 1.16412370e-02 9.49840844e-01 -3.12500924e-01 1.16412453e-02 9.48769808e-01 -3.15749675e-01 1.16412211e-02 9.47704792e-01 -3.18928242e-01 1.16412323e-02 9.46572185e-01 -3.22272658e-01 1.16412276e-02 9.45400357e-01 -3.25679839e-01 1.16412528e-02 9.44249094e-01 -3.29017550e-01 1.16412239e-02 9.43106830e-01 -3.32271039e-01 1.16412453e-02 9.41958487e-01 -3.35528105e-01 1.16412239e-02 9.40763474e-01 -3.38840485e-01 1.16412630e-02 9.39586043e-01 -3.42123300e-01 1.16412109e-02 9.38373744e-01 -3.45396847e-01 1.16412453e-02 9.37158465e-01 -3.48680407e-01 1.16412202e-02 9.35980022e-01 -3.51828009e-01 1.16412304e-02 9.34749007e-01 -3.55096549e-01 1.16412379e-02 9.33473229e-01 -3.58450651e-01 1.16412593e-02 9.32205319e-01 -3.61726105e-01 1.16412276e-02 9.30945218e-01 -3.64960343e-01 1.16412528e-02 9.29670990e-01 -3.68203670e-01 1.16412267e-02 9.28381503e-01 -3.71424854e-01 1.16412630e-02 9.27077234e-01 -3.74684811e-01 1.16412230e-02 9.25793290e-01 -3.77838075e-01 1.16412388e-02 9.24451053e-01 -3.81102443e-01 1.16412574e-02 9.23102319e-01 -3.84369880e-01 1.16412304e-02 9.21742022e-01 -3.87610495e-01 1.16412528e-02 9.20357883e-01 -3.90892476e-01 1.16412314e-02 9.19026136e-01 -3.94015759e-01 1.16412230e-02 9.17686701e-01 -3.97124499e-01 1.16412332e-02 9.16252375e-01 -4.00418669e-01 1.16412537e-02 9.14798021e-01 -4.03736293e-01 1.16412295e-02 9.13390160e-01 -4.06909883e-01 1.16412360e-02 9.11986828e-01 -4.10053790e-01 1.16412202e-02 9.10598457e-01 -4.13120598e-01 1.16412304e-02 9.09174979e-01 -4.16242480e-01 1.16412276e-02 9.07670200e-01 -4.19510782e-01 1.16412453e-02 9.06168878e-01 -4.22751635e-01 1.16412239e-02 9.04678345e-01 -4.25927222e-01 1.16412276e-02 9.03217793e-01 -4.29025263e-01 1.16412118e-02 9.01753962e-01 -4.32079703e-01 1.16412379e-02 9.00254667e-01 -4.35208559e-01 1.16412248e-02 8.98674130e-01 -4.38452035e-01 1.16412472e-02 8.97137582e-01 -4.41597700e-01 1.16412174e-02 8.95608246e-01 -4.44682211e-01 1.16412435e-02 8.94043684e-01 -4.47827041e-01 1.16412183e-02 8.92503977e-01 -4.50886875e-01 1.16412304e-02 8.90931845e-01 -4.53985691e-01 1.16412221e-02 8.89290929e-01 -4.57181782e-01 1.16412463e-02 8.87712657e-01 -4.60249662e-01 1.16412109e-02 8.86120260e-01 -4.63308930e-01 1.16412258e-02 8.84508550e-01 -4.66371328e-01 1.16412370e-02 8.82850885e-01 -4.69500512e-01 1.16412360e-02 8.81214917e-01 -4.72570598e-01 1.16412230e-02 8.79528761e-01 -4.75693375e-01 1.16412407e-02 8.77856970e-01 -4.78787720e-01 1.16412137e-02 8.76236558e-01 -4.81734097e-01 1.16412304e-02 8.74545813e-01 -4.84793186e-01 1.16412323e-02 8.72854233e-01 -4.87832904e-01 1.16412397e-02 8.71117651e-01 -4.90931392e-01 1.16412304e-02 8.69367003e-01 -4.94021714e-01 1.16412370e-02 8.67656708e-01 -4.97033745e-01 1.16412034e-02 8.65895867e-01 -5.00077724e-01 1.16412519e-02 8.64138901e-01 -5.03118217e-01 1.16412202e-02 8.62441957e-01 -5.06014824e-01 1.16412416e-02 8.60669911e-01 -5.09026587e-01 1.16412267e-02 8.58877659e-01 -5.12043238e-01 1.16412258e-02 8.57047796e-01 -5.15099645e-01 1.16412435e-02 8.55182827e-01 -5.18186271e-01 1.16412360e-02 8.53417575e-01 -5.21097481e-01 1.16412221e-02 8.51654530e-01 -5.23964942e-01 1.16412435e-02 8.49808931e-01 -5.26957214e-01 1.16412435e-02 8.47912729e-01 -5.29995382e-01 1.16412630e-02 8.46017659e-01 -5.33023119e-01 1.16412314e-02 8.44190240e-01 -5.35916448e-01 1.16412155e-02 8.42366517e-01 -5.38772762e-01 1.16412323e-02 8.40438247e-01 -5.41770160e-01 1.16412528e-02 8.38495433e-01 -5.44775367e-01 1.16412351e-02 8.36578310e-01 -5.47712922e-01 1.16412388e-02 8.34674597e-01 -5.50619483e-01 1.16412258e-02 8.32804859e-01 -5.53443432e-01 1.16412072e-02 8.30914140e-01 -5.56274831e-01 1.16412276e-02 8.28955889e-01 -5.59189677e-01 1.16412314e-02 8.26945722e-01 -5.62151849e-01 1.16412528e-02 8.24981987e-01 -5.65043747e-01 1.16412081e-02 8.22992563e-01 -5.67924798e-01 1.16412453e-02 8.21011782e-01 -5.70795417e-01 1.16412072e-02 8.19015086e-01 -5.73641717e-01 1.16412472e-02 8.17023873e-01 -5.76489747e-01 1.16412165e-02 8.15010786e-01 -5.79319000e-01 1.16412472e-02 8.12969744e-01 -5.82192421e-01 1.16412118e-02 8.10954034e-01 -5.84982097e-01 1.16412388e-02 8.08905840e-01 -5.87821722e-01 1.16412230e-02 8.06838751e-01 -5.90650976e-01 1.16412304e-02 8.04718912e-01 -5.93533158e-01 1.16412435e-02 8.02656531e-01 -5.96324027e-01 1.16412267e-02 8.00625741e-01 -5.99045873e-01 1.16412304e-02 7.98504770e-01 -6.01868391e-01 1.16412453e-02 7.96410799e-01 -6.04642928e-01 1.16412221e-02 7.94296741e-01 -6.07411444e-01 1.16412444e-02 7.92172849e-01 -6.10184550e-01 1.16412221e-02 7.90085196e-01 -6.12880111e-01 1.16412342e-02 7.87885964e-01 -6.15701199e-01 1.16412528e-02 7.85674214e-01 -6.18526340e-01 1.16412314e-02 7.83569932e-01 -6.21192455e-01 1.16412183e-02 7.81438470e-01 -6.23870134e-01 1.16412304e-02 7.79266894e-01 -6.26579046e-01 1.16412314e-02 7.77017772e-01 -6.29364014e-01 1.16412528e-02 7.74814785e-01 -6.32079303e-01 1.16412127e-02 7.72655308e-01 -6.34714961e-01 1.16412286e-02 7.70441234e-01 -6.37400806e-01 1.16412286e-02 7.68218577e-01 -6.40075147e-01 1.16412379e-02 7.65972614e-01 -6.42763674e-01 1.16412342e-02 7.63691068e-01 -6.45470619e-01 1.16412379e-02 7.61422753e-01 -6.48147881e-01 1.16412211e-02 7.59223759e-01 -6.50723934e-01 1.16412230e-02 7.56917894e-01 -6.53406084e-01 1.16412221e-02 7.54581988e-01 -6.56093299e-01 1.16412565e-02 7.52226591e-01 -6.58795834e-01 1.16412332e-02 7.49909937e-01 -6.61430836e-01 1.16412342e-02 7.47664094e-01 -6.63973749e-01 1.16412165e-02 7.45406270e-01 -6.66503668e-01 1.16412342e-02 7.43002117e-01 -6.69177532e-01 1.16412630e-02 7.40671992e-01 -6.71770215e-01 1.16412146e-02 7.38324881e-01 -6.74335837e-01 1.16412574e-02 7.35969663e-01 -6.76913381e-01 1.16412211e-02 7.33676016e-01 -6.79394484e-01 1.16412342e-02 7.31232464e-01 -6.82019055e-01 1.16412528e-02 7.28782892e-01 -6.84641004e-01 1.16412276e-02 7.26433158e-01 -6.87137961e-01 1.16412099e-02 7.24055707e-01 -6.89636946e-01 1.16412565e-02 7.21626222e-01 -6.92177653e-01 1.16412221e-02 7.19224274e-01 -6.94680214e-01 1.16412574e-02 7.16753542e-01 -6.97229862e-01 1.16412332e-02 7.14350641e-01 -6.99690104e-01 1.16412248e-02 7.11899996e-01 -7.02183843e-01 1.16412425e-02 7.09432602e-01 -7.04688132e-01 1.16412034e-02 7.06988215e-01 -7.07120061e-01 1.16412165e-02 7.04478621e-01 -7.09641218e-01 1.16411764e-02 7.02065587e-01 -7.12031066e-01 1.16411000e-02 6.99633896e-01 -7.14416325e-01 1.16410637e-02 6.97125077e-01 -7.16865242e-01 1.16410367e-02 6.94614708e-01 -7.19292521e-01 1.16410367e-02 6.92083478e-01 -7.21728683e-01 1.16410414e-02 6.89857721e-01 -7.23850369e-01 1.16410619e-02 6.87012672e-01 -7.26550579e-01 1.16410842e-02 6.84487700e-01 -7.28930712e-01 1.16410851e-02 6.81971431e-01 -7.31285393e-01 1.16410851e-02 6.79932594e-01 -7.33181715e-01 1.16410833e-02 6.77728832e-01 -7.35219717e-01 1.16410833e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.58431387e-01 -8.29469025e-01 1.16410833e-02 5.55605114e-01 -8.31364810e-01 1.16410842e-02 5.52427769e-01 -8.33478868e-01 1.16410842e-02 5.49962461e-01 -8.35112274e-01 1.16410404e-02 5.47437072e-01 -8.36770535e-01 1.16410870e-02 5.44480741e-01 -8.38695884e-01 1.16411997e-02 5.41549385e-01 -8.40593934e-01 1.16411950e-02 5.38703263e-01 -8.42413545e-01 1.16412239e-02 5.35771549e-01 -8.44277620e-01 1.16412276e-02 5.32813191e-01 -8.46150875e-01 1.16412314e-02 5.29860914e-01 -8.47998381e-01 1.16412342e-02 5.26913702e-01 -8.49835455e-01 1.16412360e-02 5.23929477e-01 -8.51677060e-01 1.16412342e-02 5.20955563e-01 -8.53502631e-01 1.16412332e-02 5.17920375e-01 -8.55342269e-01 1.16412453e-02 5.14929235e-01 -8.57151568e-01 1.16412258e-02 5.11972964e-01 -8.58918190e-01 1.16412304e-02 5.08955479e-01 -8.60710621e-01 1.16412286e-02 5.05951822e-01 -8.62480819e-01 1.16412388e-02 5.02952278e-01 -8.64233494e-01 1.16412267e-02 4.99869972e-01 -8.66018176e-01 1.16412379e-02 4.96821523e-01 -8.67774665e-01 1.16412211e-02 4.93859112e-01 -8.69459331e-01 1.16412276e-02 4.90824729e-01 -8.71180296e-01 1.16412304e-02 4.87774998e-01 -8.72886539e-01 1.16412360e-02 4.84728634e-01 -8.74579966e-01 1.16412332e-02 4.81678069e-01 -8.76267791e-01 1.16412332e-02 4.78619039e-01 -8.77943873e-01 1.16412258e-02 4.75569397e-01 -8.79596889e-01 1.16412342e-02 4.72477436e-01 -8.81261647e-01 1.16412407e-02 4.69410002e-01 -8.82897019e-01 1.16412435e-02 4.66315985e-01 -8.84539366e-01 1.16412351e-02 4.63247299e-01 -8.86148989e-01 1.16412379e-02 4.60139751e-01 -8.87765169e-01 1.16412360e-02 4.57052290e-01 -8.89360666e-01 1.16412332e-02 4.53956783e-01 -8.90942454e-01 1.16412379e-02 4.50844318e-01 -8.92522752e-01 1.16412463e-02 4.47726607e-01 -8.94090652e-01 1.16412342e-02 4.44614291e-01 -8.95642340e-01 1.16412407e-02 4.41475689e-01 -8.97193491e-01 1.16412360e-02 4.38354552e-01 -8.98724318e-01 1.16412388e-02 4.35212106e-01 -9.00249302e-01 1.16412370e-02 4.32074904e-01 -9.01757121e-01 1.16412342e-02 4.28835064e-01 -9.03299034e-01 1.16412630e-02 4.25661772e-01 -9.04805005e-01 1.16412230e-02 4.22472179e-01 -9.06292379e-01 1.16412630e-02 4.19304311e-01 -9.07770753e-01 1.16412193e-02 4.16259259e-01 -9.09165561e-01 1.16412360e-02 4.13068116e-01 -9.10620213e-01 1.16412463e-02 4.09875393e-01 -9.12063301e-01 1.16412332e-02 4.06603813e-01 -9.13522899e-01 1.16412621e-02 4.03402448e-01 -9.14947033e-01 1.16412230e-02 4.00317490e-01 -9.16300356e-01 1.16412332e-02 3.97130191e-01 -9.17683065e-01 1.16412379e-02 3.93913716e-01 -9.19065833e-01 1.16412379e-02 3.90611887e-01 -9.20474887e-01 1.16412621e-02 3.87368590e-01 -9.21850085e-01 1.16412239e-02 3.84162515e-01 -9.23184574e-01 1.16412584e-02 3.80919695e-01 -9.24532294e-01 1.16412211e-02 3.77812475e-01 -9.25806880e-01 1.16412332e-02 3.74562472e-01 -9.27122772e-01 1.16412388e-02 3.71230811e-01 -9.28459883e-01 1.16412556e-02 3.67896408e-01 -9.29790020e-01 1.16412407e-02 3.64745796e-01 -9.31034446e-01 1.16412258e-02 3.61589760e-01 -9.32255328e-01 1.16412388e-02 3.58332455e-01 -9.33522224e-01 1.16412360e-02 3.55057806e-01 -9.34763491e-01 1.16412453e-02 3.51806194e-01 -9.35988188e-01 1.16412360e-02 3.48504543e-01 -9.37221766e-01 1.16412360e-02 3.45232368e-01 -9.38435733e-01 1.16412342e-02 3.41976345e-01 -9.39634740e-01 1.16412323e-02 3.38566840e-01 -9.40862000e-01 1.16412630e-02 3.35269094e-01 -9.42052901e-01 1.16412174e-02 3.32007140e-01 -9.43197489e-01 1.16412602e-02 3.28693628e-01 -9.44364667e-01 1.16412183e-02 3.25429142e-01 -9.45487857e-01 1.16412602e-02 3.22100461e-01 -9.46632862e-01 1.16412221e-02 3.18884373e-01 -9.47717965e-01 1.16412370e-02 3.15572500e-01 -9.48824525e-01 1.16412360e-02 3.12259614e-01 -9.49919701e-01 1.16412407e-02 3.08947057e-01 -9.51004088e-01 1.16412332e-02 3.05632621e-01 -9.52075899e-01 1.16412388e-02 3.02284956e-01 -9.53141689e-01 1.16412407e-02 2.98968226e-01 -9.54188645e-01 1.16412332e-02 2.95646220e-01 -9.55222726e-01 1.16412388e-02 2.92337567e-01 -9.56241071e-01 1.16412360e-02 2.88887799e-01 -9.57283676e-01 1.16412519e-02 2.85464615e-01 -9.58313704e-01 1.16412351e-02 2.82184243e-01 -9.59290147e-01 1.16412239e-02 2.78850347e-01 -9.60259318e-01 1.16412574e-02 2.75401264e-01 -9.61254239e-01 1.16412379e-02 2.72055358e-01 -9.62207377e-01 1.16412388e-02 2.68772006e-01 -9.63133574e-01 1.16412211e-02 2.65478671e-01 -9.64042664e-01 1.16412407e-02 2.62111634e-01 -9.64967430e-01 1.16412314e-02 2.58744240e-01 -9.65870440e-01 1.16412416e-02 2.55361110e-01 -9.66771185e-01 1.16412435e-02 2.51997828e-01 -9.67655659e-01 1.16412425e-02 2.48534888e-01 -9.68545079e-01 1.16412602e-02 2.45144278e-01 -9.69413579e-01 1.16412248e-02 2.41765097e-01 -9.70257938e-01 1.16412528e-02 2.38369688e-01 -9.71104264e-01 1.16412211e-02 2.35091463e-01 -9.71902132e-01 1.16412388e-02 2.31682017e-01 -9.72719729e-01 1.16412360e-02 2.28274226e-01 -9.73524570e-01 1.16412397e-02 2.24883750e-01 -9.74313080e-01 1.16412407e-02 2.21399397e-01 -9.75106597e-01 1.16412556e-02 2.17987031e-01 -9.75882351e-01 1.16412221e-02 2.14662179e-01 -9.76615012e-01 1.16412342e-02 2.11245254e-01 -9.77358460e-01 1.16412407e-02 2.07851887e-01 -9.78087068e-01 1.16412360e-02 2.04367742e-01 -9.78819251e-01 1.16412630e-02 2.00855955e-01 -9.79549050e-01 1.16412323e-02 1.97511971e-01 -9.80230391e-01 1.16412230e-02 1.94172382e-01 -9.80893373e-01 1.16412379e-02 1.90747455e-01 -9.81566966e-01 1.16412379e-02 1.87242731e-01 -9.82237399e-01 1.16412528e-02 1.83818221e-01 -9.82889414e-01 1.16412230e-02 1.80388942e-01 -9.83517528e-01 1.16412612e-02 1.76937744e-01 -9.84157681e-01 1.16412221e-02 1.73628092e-01 -9.84742880e-01 1.16412370e-02 1.70190439e-01 -9.85335886e-01 1.16412463e-02 1.66748300e-01 -9.85926628e-01 1.16412407e-02 1.63200229e-01 -9.86514986e-01 1.16412630e-02 1.59742445e-01 -9.87088740e-01 1.16412202e-02 1.56406537e-01 -9.87620294e-01 1.16412435e-02 1.52962193e-01 -9.88160193e-01 1.16412379e-02 1.49504066e-01 -9.88686740e-01 1.16412388e-02 1.46065071e-01 -9.89202380e-01 1.16412435e-02 1.42587841e-01 -9.89709437e-01 1.16412360e-02 1.39130831e-01 -9.90202844e-01 1.16412360e-02 1.35588884e-01 -9.90692437e-01 1.16412584e-02 1.32122278e-01 -9.91162539e-01 1.16412248e-02 1.28755867e-01 -9.91602957e-01 1.16412435e-02 1.25278771e-01 -9.92050052e-01 1.16412351e-02 1.21817753e-01 -9.92480278e-01 1.16412360e-02 1.18266091e-01 -9.92907405e-01 1.16412556e-02 1.14781767e-01 -9.93319631e-01 1.16412230e-02 1.11415148e-01 -9.93701518e-01 1.16412370e-02 1.07951485e-01 -9.94084895e-01 1.16412314e-02 1.04475863e-01 -9.94455159e-01 1.16412332e-02 1.00928701e-01 -9.94817615e-01 1.16412593e-02 9.74365696e-02 -9.95172560e-01 1.16412165e-02 9.39599648e-02 -9.95502412e-01 1.16412630e-02 9.04828310e-02 -9.95829701e-01 1.16412211e-02 8.70266557e-02 -9.96131897e-01 1.16412630e-02 8.34215060e-02 -9.96441782e-01 1.16412342e-02 8.00443441e-02 -9.96722400e-01 1.16412221e-02 7.66701475e-02 -9.96983528e-01 1.16412351e-02 7.31971860e-02 -9.97245133e-01 1.16412388e-02 6.97147772e-02 -9.97493446e-01 1.16412407e-02 6.62356615e-02 -9.97730911e-01 1.16412453e-02 6.27543107e-02 -9.97956395e-01 1.16412360e-02 5.92758879e-02 -9.98169959e-01 1.16412360e-02 5.58027774e-02 -9.98369455e-01 1.16412453e-02 5.22950366e-02 -9.98558342e-01 1.16412388e-02 4.88093719e-02 -9.98736382e-01 1.16412453e-02 4.52367812e-02 -9.98901904e-01 1.16412621e-02 4.16646004e-02 -9.99060273e-01 1.16412360e-02 3.82411256e-02 -9.99198854e-01 1.16412267e-02 3.48319560e-02 -9.99321043e-01 1.16412379e-02 3.12542431e-02 -9.99436080e-01 1.16412528e-02 2.77774725e-02 -9.99544919e-01 1.16412248e-02 2.42972355e-02 -9.99632895e-01 1.16412630e-02 2.07728315e-02 -9.99712586e-01 1.16412248e-02 1.74108129e-02 -9.99780595e-01 1.16412463e-02 1.38347428e-02 -9.99823749e-01 1.16412574e-02 1.03181377e-02 -9.99877393e-01 1.16412248e-02 6.94328966e-03 -9.99910355e-01 1.16412463e-02 3.44864372e-03 -9.99927282e-01 1.16412379e-02 -3.70620983e-05 -9.99928415e-01 1.16412397e-02 -3.51656741e-03 -9.99927104e-01 1.16412407e-02 -7.02334614e-03 -9.99909818e-01 1.16412453e-02 -1.05164712e-02 -9.99873161e-01 1.16412379e-02 -1.39925713e-02 -9.99824584e-01 1.16412407e-02 -1.75688043e-02 -9.99777198e-01 1.16412528e-02 -2.11587735e-02 -9.99701202e-01 1.16412453e-02 -2.45791581e-02 -9.99629617e-01 1.16412258e-02 -2.79646795e-02 -9.99536455e-01 1.16412472e-02 -3.14620920e-02 -9.99432981e-01 1.16412453e-02 -3.49237360e-02 -9.99318182e-01 1.16412472e-02 -3.85172106e-02 -9.99182045e-01 1.16412630e-02 -4.20227535e-02 -9.99048769e-01 1.16412258e-02 -4.54100519e-02 -9.98895645e-01 1.16412416e-02 -4.88735475e-02 -9.98732686e-01 1.16412453e-02 -5.23393676e-02 -9.98553932e-01 1.16412500e-02 -5.59408814e-02 -9.98358130e-01 1.16412630e-02 -5.94301373e-02 -9.98163819e-01 1.16412221e-02 -6.28773570e-02 -9.97944772e-01 1.16412630e-02 -6.63865358e-02 -9.97723997e-01 1.16412221e-02 -6.97731823e-02 -9.97488558e-01 1.16412407e-02 -7.33550861e-02 -9.97230589e-01 1.16412630e-02 -7.68544450e-02 -9.96971607e-01 1.16412248e-02 -8.03052783e-02 -9.96694207e-01 1.16412630e-02 -8.38019624e-02 -9.96412516e-01 1.16412258e-02 -8.71688873e-02 -9.96120274e-01 1.16412453e-02 -9.06452760e-02 -9.95810211e-01 1.16412444e-02 -9.41330492e-02 -9.95487571e-01 1.16412407e-02 -9.76173580e-02 -9.95150983e-01 1.16412453e-02 -1.01089843e-01 -9.94804323e-01 1.16412435e-02 -1.04544155e-01 -9.94447231e-01 1.16412435e-02 -1.08114786e-01 -9.94063258e-01 1.16412630e-02 -1.11577198e-01 -9.93685842e-01 1.16412304e-02 -1.14972696e-01 -9.93292809e-01 1.16412481e-02 -1.18436359e-01 -9.92887139e-01 1.16412416e-02 -1.21901073e-01 -9.92470682e-01 1.16412435e-02 -1.25453100e-01 -9.92024660e-01 1.16412630e-02 -1.28915802e-01 -9.91583884e-01 1.16412267e-02 -1.32279664e-01 -9.91139233e-01 1.16412472e-02 -1.35746107e-01 -9.90670085e-01 1.16412472e-02 -1.39210269e-01 -9.90189135e-01 1.16412491e-02 -1.42745942e-01 -9.89681244e-01 1.16412630e-02 -1.46213055e-01 -9.89181876e-01 1.16412248e-02 -1.49635106e-01 -9.88663137e-01 1.16412630e-02 -1.53081879e-01 -9.88143086e-01 1.16412286e-02 -1.56451136e-01 -9.87611592e-01 1.16412435e-02 -1.59985259e-01 -9.87044513e-01 1.16412574e-02 -1.63425744e-01 -9.86484408e-01 1.16412332e-02 -1.66864097e-01 -9.85903740e-01 1.16412630e-02 -1.70319468e-01 -9.85315621e-01 1.16412304e-02 -1.73669562e-01 -9.84733820e-01 1.16412472e-02 -1.77090019e-01 -9.84124541e-01 1.16412388e-02 -1.80531889e-01 -9.83491957e-01 1.16412463e-02 -1.83965728e-01 -9.82860446e-01 1.16412444e-02 -1.87391937e-01 -9.82211411e-01 1.16412453e-02 -1.90824896e-01 -9.81549025e-01 1.16412416e-02 -1.94237188e-01 -9.80880380e-01 1.16412453e-02 -1.97752446e-01 -9.80174601e-01 1.16412695e-02 -2.01154292e-01 -9.79486942e-01 1.16412276e-02 -2.04482526e-01 -9.78796065e-01 1.16412453e-02 -2.07904994e-01 -9.78077233e-01 1.16412388e-02 -2.11393103e-01 -9.77325320e-01 1.16412630e-02 -2.14830354e-01 -9.76578057e-01 1.16412286e-02 -2.18135804e-01 -9.75844502e-01 1.16412472e-02 -2.21534759e-01 -9.75078225e-01 1.16412453e-02 -2.24954158e-01 -9.74292338e-01 1.16412528e-02 -2.28450686e-01 -9.73481178e-01 1.16412630e-02 -2.31850937e-01 -9.72682953e-01 1.16412230e-02 -2.35134542e-01 -9.71889913e-01 1.16412491e-02 -2.38537118e-01 -9.71060693e-01 1.16412453e-02 -2.41918206e-01 -9.70220625e-01 1.16412453e-02 -2.45295554e-01 -9.69371796e-01 1.16412528e-02 -2.48678818e-01 -9.68510568e-01 1.16412453e-02 -2.52146810e-01 -9.67611134e-01 1.16412630e-02 -2.55551964e-01 -9.66724575e-01 1.16412258e-02 -2.58900166e-01 -9.65826035e-01 1.16412630e-02 -2.62391180e-01 -9.64888096e-01 1.16412435e-02 -2.65654773e-01 -9.63995159e-01 1.16412239e-02 -2.68920332e-01 -9.63087261e-01 1.16412472e-02 -2.72295207e-01 -9.62139189e-01 1.16412453e-02 -2.75659025e-01 -9.61178362e-01 1.16412491e-02 -2.79013067e-01 -9.60211277e-01 1.16412472e-02 -2.82347620e-01 -9.59236085e-01 1.16412425e-02 -2.85698831e-01 -9.58245337e-01 1.16412453e-02 -2.89049655e-01 -9.57236707e-01 1.16412472e-02 -2.92366862e-01 -9.56230164e-01 1.16412453e-02 -2.95799851e-01 -9.55172420e-01 1.16412630e-02 -2.99255848e-01 -9.54096377e-01 1.16412491e-02 -3.02573174e-01 -9.53049004e-01 1.16412472e-02 -3.05823237e-01 -9.52016056e-01 1.16412258e-02 -3.09047192e-01 -9.50968921e-01 1.16412491e-02 -3.12434494e-01 -9.49859440e-01 1.16412630e-02 -3.15773070e-01 -9.48761046e-01 1.16412286e-02 -3.19059283e-01 -9.47655141e-01 1.16412630e-02 -3.22369725e-01 -9.46540236e-01 1.16412258e-02 -3.25570613e-01 -9.45440352e-01 1.16412491e-02 -3.28873932e-01 -9.44296181e-01 1.16412453e-02 -3.32149297e-01 -9.43150222e-01 1.16412453e-02 -3.35535645e-01 -9.41946566e-01 1.16412630e-02 -3.38851213e-01 -9.40765142e-01 1.16412230e-02 -3.42104495e-01 -9.39583600e-01 1.16412630e-02 -3.45391661e-01 -9.38377857e-01 1.16412248e-02 -3.48583937e-01 -9.37190831e-01 1.16412453e-02 -3.51843745e-01 -9.35971975e-01 1.16412491e-02 -3.55112284e-01 -9.34743106e-01 1.16412453e-02 -3.58465970e-01 -9.33464944e-01 1.16412630e-02 -3.61798108e-01 -9.32174444e-01 1.16412509e-02 -3.64993453e-01 -9.30935681e-01 1.16412286e-02 -3.68140250e-01 -9.29692507e-01 1.16412472e-02 -3.71378630e-01 -9.28402305e-01 1.16412444e-02 -3.74612987e-01 -9.27101910e-01 1.16412472e-02 -3.77914250e-01 -9.25759077e-01 1.16412630e-02 -3.81164223e-01 -9.24428940e-01 1.16412258e-02 -3.84303480e-01 -9.23127115e-01 1.16412453e-02 -3.87523115e-01 -9.21779454e-01 1.16412472e-02 -3.90735447e-01 -9.20422971e-01 1.16412453e-02 -3.94016266e-01 -9.19018626e-01 1.16412630e-02 -3.97237629e-01 -9.17638421e-01 1.16412286e-02 -4.00420278e-01 -9.16250288e-01 1.16412630e-02 -4.03632492e-01 -9.14844453e-01 1.16412267e-02 -4.06722724e-01 -9.13471460e-01 1.16412472e-02 -4.09905195e-01 -9.12050009e-01 1.16412416e-02 -4.13079977e-01 -9.10613954e-01 1.16412481e-02 -4.16262150e-01 -9.09161150e-01 1.16412472e-02 -4.19450700e-01 -9.07695711e-01 1.16412453e-02 -4.22600061e-01 -9.06234026e-01 1.16412491e-02 -4.25793856e-01 -9.04739499e-01 1.16412379e-02 -4.29019660e-01 -9.03211176e-01 1.16412630e-02 -4.32169378e-01 -9.01713252e-01 1.16412239e-02 -4.35214460e-01 -9.00247872e-01 1.16412491e-02 -4.38439161e-01 -8.98679256e-01 1.16412630e-02 -4.41655785e-01 -8.97103727e-01 1.16412453e-02 -4.44721758e-01 -8.95590961e-01 1.16412304e-02 -4.47764188e-01 -8.94069791e-01 1.16412453e-02 -4.50874686e-01 -8.92506540e-01 1.16412472e-02 -4.53986913e-01 -8.90927553e-01 1.16412453e-02 -4.57177937e-01 -8.89290333e-01 1.16412630e-02 -4.60277170e-01 -8.87696505e-01 1.16412230e-02 -4.63280588e-01 -8.86132896e-01 1.16412379e-02 -4.66366112e-01 -8.84509265e-01 1.16412491e-02 -4.69461769e-01 -8.82870615e-01 1.16412472e-02 -4.72629339e-01 -8.81177127e-01 1.16412630e-02 -4.75694686e-01 -8.79528940e-01 1.16412267e-02 -4.78760719e-01 -8.77859712e-01 1.16412630e-02 -4.81838614e-01 -8.76180112e-01 1.16412314e-02 -4.84875590e-01 -8.74495864e-01 1.16412630e-02 -4.88004267e-01 -8.72755647e-01 1.16412491e-02 -4.90985066e-01 -8.71089339e-01 1.16412248e-02 -4.93933409e-01 -8.69414449e-01 1.16412481e-02 -4.96970534e-01 -8.67685378e-01 1.16412435e-02 -4.99989420e-01 -8.65948617e-01 1.16412435e-02 -5.02992451e-01 -8.64207089e-01 1.16412453e-02 -5.06002784e-01 -8.62449288e-01 1.16412472e-02 -5.09025455e-01 -8.60666037e-01 1.16412500e-02 -5.12015998e-01 -8.58891189e-01 1.16412453e-02 -5.15028059e-01 -8.57090414e-01 1.16412453e-02 -5.18004894e-01 -8.55290592e-01 1.16412472e-02 -5.20993650e-01 -8.53476405e-01 1.16412472e-02 -5.24043560e-01 -8.51602852e-01 1.16412630e-02 -5.27015030e-01 -8.49774182e-01 1.16412286e-02 -5.29892325e-01 -8.47979546e-01 1.16412500e-02 -5.32915175e-01 -8.46079171e-01 1.16412630e-02 -5.35883427e-01 -8.44208896e-01 1.16412276e-02 -5.38807213e-01 -8.42338979e-01 1.16412630e-02 -5.41760087e-01 -8.40449512e-01 1.16412286e-02 -5.44605970e-01 -8.38605106e-01 1.16412491e-02 -5.47526836e-01 -8.36698890e-01 1.16412472e-02 -5.50439239e-01 -8.34789097e-01 1.16412453e-02 -5.53334832e-01 -8.32868338e-01 1.16412509e-02 -5.56254804e-01 -8.30923796e-01 1.16412472e-02 -5.59241474e-01 -8.28915894e-01 1.16412630e-02 -5.62131941e-01 -8.26964140e-01 1.16412202e-02 -5.64930320e-01 -8.25052679e-01 1.16412388e-02 -5.67804217e-01 -8.23075891e-01 1.16412453e-02 -5.70675313e-01 -8.21087718e-01 1.16412407e-02 -5.73629081e-01 -8.19022357e-01 1.16412630e-02 -5.76557040e-01 -8.16970587e-01 1.16412453e-02 -5.79339504e-01 -8.15001786e-01 1.16412230e-02 -5.82089961e-01 -8.13036680e-01 1.16412388e-02 -5.84929287e-01 -8.10992062e-01 1.16412388e-02 -5.87774575e-01 -8.08937490e-01 1.16412360e-02 -5.90638280e-01 -8.06844115e-01 1.16412528e-02 -5.93460917e-01 -8.04776609e-01 1.16412230e-02 -5.96186578e-01 -8.02755415e-01 1.16412397e-02 -5.98984599e-01 -8.00668478e-01 1.16412453e-02 -6.01785302e-01 -7.98568249e-01 1.16412407e-02 -6.04631603e-01 -7.96414018e-01 1.16412630e-02 -6.07452452e-01 -7.94266999e-01 1.16412323e-02 -6.10211909e-01 -7.92143583e-01 1.16412630e-02 -6.12958431e-01 -7.90027201e-01 1.16412230e-02 -6.15631223e-01 -7.87941337e-01 1.16412453e-02 -6.18374527e-01 -7.85790682e-01 1.16412463e-02 -6.21111035e-01 -7.83629239e-01 1.16412444e-02 -6.23832464e-01 -7.81464934e-01 1.16412453e-02 -6.26558542e-01 -7.79282033e-01 1.16412444e-02 -6.29279613e-01 -7.77089655e-01 1.16412342e-02 -6.31980062e-01 -7.74889827e-01 1.16412360e-02 -6.34687781e-01 -7.72676051e-01 1.16412342e-02 -6.37387872e-01 -7.70449162e-01 1.16412360e-02 -6.40074193e-01 -7.68220782e-01 1.16412342e-02 -6.42802596e-01 -7.65935242e-01 1.16412519e-02 -6.45573974e-01 -7.63604164e-01 1.16412370e-02 -6.48169219e-01 -7.61402965e-01 1.16412230e-02 -6.50728941e-01 -7.59215176e-01 1.16412379e-02 -6.53383315e-01 -7.56932080e-01 1.16412453e-02 -6.56033397e-01 -7.54638791e-01 1.16412332e-02 -6.58729613e-01 -7.52279401e-01 1.16412602e-02 -6.61372900e-01 -7.49967337e-01 1.16412202e-02 -6.63907111e-01 -7.47720242e-01 1.16412379e-02 -6.66528046e-01 -7.45387077e-01 1.16412267e-02 -6.69107318e-01 -7.43069887e-01 1.16412332e-02 -6.71764374e-01 -7.40667164e-01 1.16412528e-02 -6.74351037e-01 -7.38317192e-01 1.16412202e-02 -6.76922143e-01 -7.35956311e-01 1.16412630e-02 -6.79505646e-01 -7.33576238e-01 1.16412239e-02 -6.82056248e-01 -7.31196463e-01 1.16412630e-02 -6.84664309e-01 -7.28756189e-01 1.16412472e-02 -6.87136948e-01 -7.26430595e-01 1.16412258e-02 -6.89602137e-01 -7.24091649e-01 1.16412407e-02 -6.92129195e-01 -7.21667230e-01 1.16412453e-02 -6.94639266e-01 -7.19267607e-01 1.16412323e-02 -6.97147191e-01 -7.16835320e-01 1.16412360e-02 -6.99633539e-01 -7.14406073e-01 1.16412323e-02 -7.02116489e-01 -7.11968243e-01 1.16412332e-02 -7.04612911e-01 -7.09498525e-01 1.16412360e-02 -7.07147598e-01 -7.06948817e-01 1.16412556e-02 -7.09626675e-01 -7.04488814e-01 1.16412258e-02 -7.12002397e-01 -7.02081084e-01 1.16412360e-02 -7.14437664e-01 -6.99599624e-01 1.16412407e-02 -7.16874540e-01 -6.97105229e-01 1.16412453e-02 -7.19304025e-01 -6.94599986e-01 1.16412379e-02 -7.21773326e-01 -6.92015529e-01 1.16412630e-02 -7.24219441e-01 -6.89474106e-01 1.16412165e-02 -7.26590097e-01 -6.86963260e-01 1.16412472e-02 -7.29006767e-01 -6.84403181e-01 1.16412258e-02 -7.31313705e-01 -6.81933463e-01 1.16412388e-02 -7.33743310e-01 -6.79320991e-01 1.16412491e-02 -7.36116827e-01 -6.76753044e-01 1.16412286e-02 -7.38410413e-01 -6.74243748e-01 1.16412407e-02 -7.40785956e-01 -6.71637416e-01 1.16412323e-02 -7.43115127e-01 -6.69055700e-01 1.16412435e-02 -7.45495021e-01 -6.66398406e-01 1.16412630e-02 -7.47832537e-01 -6.63785279e-01 1.16412211e-02 -7.50075817e-01 -6.61242127e-01 1.16412435e-02 -7.52375901e-01 -6.58624351e-01 1.16412388e-02 -7.54727006e-01 -6.55924082e-01 1.16412630e-02 -7.57065713e-01 -6.53227925e-01 1.16412407e-02 -7.59290934e-01 -6.50645316e-01 1.16412248e-02 -7.61492014e-01 -6.48059070e-01 1.16412472e-02 -7.63752282e-01 -6.45401478e-01 1.16412342e-02 -7.65979707e-01 -6.42753184e-01 1.16412370e-02 -7.68291473e-01 -6.39982581e-01 1.16412630e-02 -7.70541430e-01 -6.37281179e-01 1.16412202e-02 -7.72675574e-01 -6.34688854e-01 1.16412472e-02 -7.74883568e-01 -6.31988645e-01 1.16412360e-02 -7.77086020e-01 -6.29278243e-01 1.16412472e-02 -7.79356241e-01 -6.26462162e-01 1.16412630e-02 -7.81546891e-01 -6.23738050e-01 1.16412202e-02 -7.83693552e-01 -6.21025860e-01 1.16412630e-02 -7.85872579e-01 -6.18277550e-01 1.16412202e-02 -7.87944078e-01 -6.15631461e-01 1.16412360e-02 -7.90165186e-01 -6.12769663e-01 1.16412630e-02 -7.92324245e-01 -6.09986126e-01 1.16412230e-02 -7.94427633e-01 -6.07236326e-01 1.16412630e-02 -7.96557188e-01 -6.04450643e-01 1.16412211e-02 -7.98598528e-01 -6.01745307e-01 1.16412435e-02 -8.00749898e-01 -5.98869920e-01 1.16412630e-02 -8.02854478e-01 -5.96058965e-01 1.16412248e-02 -8.04869890e-01 -5.93329549e-01 1.16412472e-02 -8.06925714e-01 -5.90530157e-01 1.16412388e-02 -8.09029996e-01 -5.87638795e-01 1.16412630e-02 -8.11140001e-01 -5.84723949e-01 1.16412453e-02 -8.13124597e-01 -5.81973016e-01 1.16412248e-02 -8.15078676e-01 -5.79222739e-01 1.16412435e-02 -8.17096949e-01 -5.76378345e-01 1.16412435e-02 -8.19110632e-01 -5.73508859e-01 1.16412453e-02 -8.21152270e-01 -5.70574522e-01 1.16412630e-02 -8.23154747e-01 -5.67695379e-01 1.16412276e-02 -8.25075030e-01 -5.64893484e-01 1.16412491e-02 -8.27041149e-01 -5.62011898e-01 1.16412453e-02 -8.29006135e-01 -5.59111953e-01 1.16412360e-02 -8.30995202e-01 -5.56144536e-01 1.16412630e-02 -8.32947493e-01 -5.53225636e-01 1.16412239e-02 -8.34853292e-01 -5.50337493e-01 1.16412528e-02 -8.36774409e-01 -5.47417939e-01 1.16412304e-02 -8.38630676e-01 -5.44567764e-01 1.16412453e-02 -8.40535164e-01 -5.41622877e-01 1.16412444e-02 -8.42420936e-01 -5.38684666e-01 1.16412453e-02 -8.44328761e-01 -5.35685003e-01 1.16412630e-02 -8.46207917e-01 -5.32724321e-01 1.16412248e-02 -8.47996950e-01 -5.29862642e-01 1.16412435e-02 -8.49895358e-01 -5.26812375e-01 1.16412630e-02 -8.51739943e-01 -5.23829520e-01 1.16412239e-02 -8.53499591e-01 -5.20960093e-01 1.16412332e-02 -8.55301857e-01 -5.17988741e-01 1.16412388e-02 -8.57149363e-01 -5.14921010e-01 1.16412630e-02 -8.58964980e-01 -5.11898279e-01 1.16412221e-02 -8.60696852e-01 -5.08974314e-01 1.16412453e-02 -8.62517059e-01 -5.05879521e-01 1.16412630e-02 -8.64284515e-01 -5.02867699e-01 1.16412193e-02 -8.65973651e-01 -4.99945849e-01 1.16412500e-02 -8.67708504e-01 -4.96925771e-01 1.16412453e-02 -8.69448483e-01 -4.93875593e-01 1.16412379e-02 -8.71164799e-01 -4.90846366e-01 1.16412472e-02 -8.72858465e-01 -4.87823606e-01 1.16412453e-02 -8.74568701e-01 -4.84749824e-01 1.16412388e-02 -8.76294255e-01 -4.81622905e-01 1.16412630e-02 -8.77991498e-01 -4.78534818e-01 1.16412248e-02 -8.79609585e-01 -4.75542277e-01 1.16412453e-02 -8.81263256e-01 -4.72471982e-01 1.16412453e-02 -8.82948339e-01 -4.69310105e-01 1.16412630e-02 -8.84628177e-01 -4.66140449e-01 1.16412463e-02 -8.86216760e-01 -4.63123113e-01 1.16412239e-02 -8.87779117e-01 -4.60114181e-01 1.16412407e-02 -8.89376700e-01 -4.57017601e-01 1.16412453e-02 -8.90988410e-01 -4.53860581e-01 1.16412556e-02 -8.92579734e-01 -4.50735480e-01 1.16412267e-02 -8.94093752e-01 -4.47714806e-01 1.16412472e-02 -8.95657599e-01 -4.44581270e-01 1.16412407e-02 -8.97206604e-01 -4.41445172e-01 1.16412491e-02 -8.98739994e-01 -4.38318253e-01 1.16412463e-02 -9.00296271e-01 -4.35108483e-01 1.16412630e-02 -9.01826262e-01 -4.31934565e-01 1.16412351e-02 -9.03280735e-01 -4.28880662e-01 1.16412463e-02 -9.04770970e-01 -4.25724119e-01 1.16412472e-02 -9.06246722e-01 -4.22574908e-01 1.16412472e-02 -9.07739520e-01 -4.19358104e-01 1.16412630e-02 -9.09206331e-01 -4.16170210e-01 1.16412323e-02 -9.10617769e-01 -4.13072437e-01 1.16412453e-02 -9.12044287e-01 -4.09914643e-01 1.16412472e-02 -9.13475096e-01 -4.06714737e-01 1.16412528e-02 -9.14924443e-01 -4.03437942e-01 1.16412630e-02 -9.16342020e-01 -4.00227785e-01 1.16412276e-02 -9.17716861e-01 -3.97043765e-01 1.16412630e-02 -9.19107616e-01 -3.93820465e-01 1.16412248e-02 -9.20434117e-01 -3.90707523e-01 1.16412491e-02 -9.21830773e-01 -3.87397707e-01 1.16412630e-02 -9.23198342e-01 -3.84140044e-01 1.16412286e-02 -9.24488127e-01 -3.81019443e-01 1.16412463e-02 -9.25806701e-01 -3.77807021e-01 1.16412407e-02 -9.27116811e-01 -3.74573916e-01 1.16412491e-02 -9.28454697e-01 -3.71237785e-01 1.16412630e-02 -9.29759800e-01 -3.67979437e-01 1.16412258e-02 -9.31014895e-01 -3.64777058e-01 1.16412733e-02 -9.32276964e-01 -3.61535728e-01 1.16412342e-02 -9.33550000e-01 -3.58240008e-01 1.16412630e-02 -9.34834123e-01 -3.54869574e-01 1.16412435e-02 -9.36025023e-01 -3.51710767e-01 1.16412239e-02 -9.37215567e-01 -3.48518670e-01 1.16412425e-02 -9.38461244e-01 -3.45154226e-01 1.16412630e-02 -9.39676940e-01 -3.41864675e-01 1.16412267e-02 -9.40851927e-01 -3.38592678e-01 1.16412630e-02 -9.42043185e-01 -3.35289747e-01 1.16412239e-02 -9.43192244e-01 -3.32022667e-01 1.16412630e-02 -9.44355547e-01 -3.28714162e-01 1.16412239e-02 -9.45467472e-01 -3.25495929e-01 1.16412453e-02 -9.46587324e-01 -3.22217703e-01 1.16412472e-02 -9.47718382e-01 -3.18882674e-01 1.16412453e-02 -9.48849976e-01 -3.15487385e-01 1.16412630e-02 -9.49952900e-01 -3.12168300e-01 1.16412248e-02 -9.51006055e-01 -3.08937430e-01 1.16412481e-02 -9.52098191e-01 -3.05546343e-01 1.16412630e-02 -9.53174412e-01 -3.02189440e-01 1.16412267e-02 -9.54186022e-01 -2.98973650e-01 1.16412453e-02 -9.55220938e-01 -2.95646101e-01 1.16412435e-02 -9.56271768e-01 -2.92226404e-01 1.16412630e-02 -9.57293928e-01 -2.88873196e-01 1.16412230e-02 -9.58268106e-01 -2.85614461e-01 1.16412425e-02 -9.59284782e-01 -2.82175273e-01 1.16412630e-02 -9.60266769e-01 -2.78836817e-01 1.16412239e-02 -9.61227715e-01 -2.75482953e-01 1.16412630e-02 -9.62195277e-01 -2.72109896e-01 1.16412221e-02 -9.63113010e-01 -2.68831968e-01 1.16412453e-02 -9.64041054e-01 -2.65477479e-01 1.16412435e-02 -9.64961112e-01 -2.62122631e-01 1.16412453e-02 -9.65865254e-01 -2.58763850e-01 1.16412435e-02 -9.66786623e-01 -2.55293518e-01 1.16412630e-02 -9.67676342e-01 -2.51924455e-01 1.16412230e-02 -9.68522608e-01 -2.48633385e-01 1.16412453e-02 -9.69385147e-01 -2.45244354e-01 1.16412342e-02 -9.70251203e-01 -2.41782561e-01 1.16412630e-02 -9.71116543e-01 -2.38312200e-01 1.16412342e-02 -9.71928060e-01 -2.34996960e-01 1.16412211e-02 -9.72719550e-01 -2.31683865e-01 1.16412425e-02 -9.73518968e-01 -2.28296205e-01 1.16412388e-02 -9.74319637e-01 -2.24830359e-01 1.16412630e-02 -9.75126266e-01 -2.21330732e-01 1.16412323e-02 -9.75877881e-01 -2.17998862e-01 1.16412286e-02 -9.76610661e-01 -2.14675799e-01 1.16412453e-02 -9.77354348e-01 -2.11264014e-01 1.16412463e-02 -9.78087246e-01 -2.07847863e-01 1.16412500e-02 -9.78803873e-01 -2.04452217e-01 1.16412407e-02 -9.79510963e-01 -2.01038152e-01 1.16412435e-02 -9.80201781e-01 -1.97642237e-01 1.16412397e-02 -9.80884910e-01 -1.94216833e-01 1.16412425e-02 -9.81558144e-01 -1.90789357e-01 1.16412360e-02 -9.82231855e-01 -1.87272489e-01 1.16412584e-02 -9.82888997e-01 -1.83823839e-01 1.16412202e-02 -9.83503222e-01 -1.80485696e-01 1.16412342e-02 -9.84133780e-01 -1.77045614e-01 1.16412388e-02 -9.84750748e-01 -1.73585266e-01 1.16412342e-02 -9.85355079e-01 -1.70068309e-01 1.16412630e-02 -9.85953689e-01 -1.66613609e-01 1.16412202e-02 -9.86505628e-01 -1.63286254e-01 1.16412360e-02 -9.87067878e-01 -1.59849077e-01 1.16412425e-02 -9.87623692e-01 -1.56389922e-01 1.16412379e-02 -9.88172293e-01 -1.52854994e-01 1.16412630e-02 -9.88708913e-01 -1.49381906e-01 1.16412239e-02 -9.89217401e-01 -1.45940438e-01 1.16412630e-02 -9.89726305e-01 -1.42484218e-01 1.16412211e-02 -9.90199745e-01 -1.39141381e-01 1.16412360e-02 -9.90692794e-01 -1.35575458e-01 1.16412546e-02 -9.91168857e-01 -1.32088766e-01 1.16412221e-02 -9.91606534e-01 -1.28744900e-01 1.16412323e-02 -9.92051065e-01 -1.25280008e-01 1.16412351e-02 -9.92478669e-01 -1.21826582e-01 1.16412388e-02 -9.92906392e-01 -1.18265055e-01 1.16412509e-02 -9.93317366e-01 -1.14806838e-01 1.16412202e-02 -9.93704140e-01 -1.11398995e-01 1.16412360e-02 -9.94088590e-01 -1.07886560e-01 1.16412491e-02 -9.94466126e-01 -1.04410172e-01 1.16412165e-02 -9.94816005e-01 -1.00963227e-01 1.16412435e-02 -9.95176733e-01 -9.74604487e-02 1.16411746e-02 -9.95505750e-01 -9.40321237e-02 1.16411690e-02 -9.95832622e-01 -9.05206129e-02 1.16410954e-02 -9.96135175e-01 -8.71297419e-02 1.16410917e-02 -9.96427894e-01 -8.37021396e-02 1.16410367e-02 -9.96714473e-01 -8.02160501e-02 1.16410377e-02 -9.96969402e-01 -7.69585520e-02 1.16410414e-02 -9.97207522e-01 -7.37522766e-02 1.16410851e-02 -9.97426689e-01 -7.07383007e-02 1.16410842e-02 -9.97698784e-01 -6.67920858e-02 1.16410851e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.97786105e-01 6.41742796e-02 1.74524039e-02 -9.97600079e-01 6.69986829e-02 1.74524244e-02 -9.97392535e-01 7.00547323e-02 1.74523313e-02 -9.97150362e-01 7.35136643e-02 1.74523313e-02 -9.96890903e-01 7.69539401e-02 1.74523313e-02 -9.96621907e-01 8.04155841e-02 1.74523313e-02 -9.96333122e-01 8.39049295e-02 1.74523294e-02 -9.96043146e-01 8.72750059e-02 1.74523313e-02 -9.95736182e-01 9.07312706e-02 1.74523238e-02 -9.95403409e-01 9.43096131e-02 1.74523257e-02 -9.95077193e-01 9.76906791e-02 1.74523294e-02 -9.94735301e-01 1.01139121e-01 1.74523219e-02 -9.94360566e-01 1.04722366e-01 1.74523294e-02 -9.93993282e-01 1.08156614e-01 1.74523294e-02 -9.93610561e-01 1.11631438e-01 1.74523313e-02 -9.93234217e-01 1.14873044e-01 1.74523313e-02 -9.92816091e-01 1.18364945e-01 1.74523555e-02 -9.92401004e-01 1.21798992e-01 1.74523611e-02 -9.91972208e-01 1.25242710e-01 1.74523611e-02 -9.91509438e-01 1.28854573e-01 1.74524244e-02 -9.91020620e-01 1.32562935e-01 1.74524244e-02 -9.90568519e-01 1.35894537e-01 1.74523611e-02 -9.90094244e-01 1.39314726e-01 1.74523480e-02 -9.89619792e-01 1.42644837e-01 1.74523517e-02 -9.89109099e-01 1.46184027e-01 1.74523313e-02 -9.88594830e-01 1.49637356e-01 1.74523313e-02 -9.88087654e-01 1.52968392e-01 1.74523313e-02 -9.87534642e-01 1.56523630e-01 1.74523219e-02 -9.86966908e-01 1.60074279e-01 1.74523201e-02 -9.86402631e-01 1.63519040e-01 1.74523201e-02 -9.85826433e-01 1.66963860e-01 1.74523201e-02 -9.85235989e-01 1.70401320e-01 1.74523201e-02 -9.84640121e-01 1.73841685e-01 1.74523201e-02 -9.84024107e-01 1.77290887e-01 1.74523201e-02 -9.83392477e-01 1.80734336e-01 1.74523201e-02 -9.82776403e-01 1.84060290e-01 1.74523201e-02 -9.82154250e-01 1.87355205e-01 1.74523201e-02 -9.81471479e-01 1.90893337e-01 1.74523201e-02 -9.80778098e-01 1.94426134e-01 1.74523201e-02 -9.80098605e-01 1.97830573e-01 1.74523201e-02 -9.79399383e-01 2.01265216e-01 1.74523201e-02 -9.78689790e-01 2.04677701e-01 1.74523201e-02 -9.77985501e-01 2.08023518e-01 1.74523201e-02 -9.77261066e-01 2.11407855e-01 1.74523201e-02 -9.76486921e-01 2.14940712e-01 1.74523201e-02 -9.75750148e-01 2.18265980e-01 1.74523201e-02 -9.74985719e-01 2.21652851e-01 1.74523201e-02 -9.74183083e-01 2.25162938e-01 1.74523201e-02 -9.73392665e-01 2.28557155e-01 1.74523201e-02 -9.72583055e-01 2.31981844e-01 1.74523201e-02 -9.71794426e-01 2.35260814e-01 1.74523201e-02 -9.70995247e-01 2.38532260e-01 1.74523201e-02 -9.70129251e-01 2.42026150e-01 1.74523201e-02 -9.69247401e-01 2.45533705e-01 1.74523201e-02 -9.68383491e-01 2.48925701e-01 1.74523201e-02 -9.67532218e-01 2.52209514e-01 1.74523201e-02 -9.66655195e-01 2.55560666e-01 1.74523201e-02 -9.65750992e-01 2.58952260e-01 1.74523201e-02 -9.64840055e-01 2.62327373e-01 1.74523201e-02 -9.63893294e-01 2.65775919e-01 1.74523201e-02 -9.62982655e-01 2.69064635e-01 1.74523201e-02 -9.62066710e-01 2.72319555e-01 1.74523201e-02 -9.61081207e-01 2.75776237e-01 1.74523201e-02 -9.60085332e-01 2.79222012e-01 1.74523201e-02 -9.59111571e-01 2.82546937e-01 1.74523201e-02 -9.58137512e-01 2.85839260e-01 1.74523201e-02 -9.57130134e-01 2.89187193e-01 1.74523201e-02 -9.56120968e-01 2.92507261e-01 1.74523201e-02 -9.55100179e-01 2.95830309e-01 1.74523201e-02 -9.54032063e-01 2.99253374e-01 1.74523201e-02 -9.53004479e-01 3.02507222e-01 1.74523201e-02 -9.51948106e-01 3.05818528e-01 1.74523201e-02 -9.50847983e-01 3.09217513e-01 1.74523201e-02 -9.49762464e-01 3.12537074e-01 1.74523201e-02 -9.48668063e-01 3.15843076e-01 1.74523201e-02 -9.47555900e-01 3.19173783e-01 1.74523201e-02 -9.46465790e-01 3.22379559e-01 1.74523201e-02 -9.45367932e-01 3.25593859e-01 1.74523201e-02 -9.44195092e-01 3.28973383e-01 1.74523201e-02 -9.43011403e-01 3.32351089e-01 1.74523201e-02 -9.41871107e-01 3.35574836e-01 1.74523201e-02 -9.40700352e-01 3.38840723e-01 1.74523201e-02 -9.39478278e-01 3.42215836e-01 1.74523201e-02 -9.38276708e-01 3.45478326e-01 1.74523201e-02 -9.37062085e-01 3.48748207e-01 1.74523201e-02 -9.35866058e-01 3.51945758e-01 1.74523201e-02 -9.34668899e-01 3.55125666e-01 1.74523201e-02 -9.33408618e-01 3.58451426e-01 1.74523201e-02 -9.32103693e-01 3.61810148e-01 1.74523201e-02 -9.30832386e-01 3.65074515e-01 1.74523201e-02 -9.29552555e-01 3.68323863e-01 1.74523201e-02 -9.28260386e-01 3.71565104e-01 1.74523201e-02 -9.26963508e-01 3.74787420e-01 1.74523201e-02 -9.25650299e-01 3.78023893e-01 1.74523201e-02 -9.24324811e-01 3.81247312e-01 1.74523201e-02 -9.23013389e-01 3.84412050e-01 1.74523201e-02 -9.21719372e-01 3.87507886e-01 1.74523201e-02 -9.20326650e-01 3.90801638e-01 1.74523201e-02 -9.18914080e-01 3.94108236e-01 1.74523201e-02 -9.17548537e-01 3.97277027e-01 1.74523201e-02 -9.16167438e-01 4.00460243e-01 1.74523201e-02 -9.14771974e-01 4.03632522e-01 1.74523201e-02 -9.13378239e-01 4.06778485e-01 1.74523201e-02 -9.11918759e-01 4.10042137e-01 1.74523201e-02 -9.10458028e-01 4.13272738e-01 1.74523201e-02 -9.09045100e-01 4.16364938e-01 1.74523201e-02 -9.07595158e-01 4.19523388e-01 1.74523201e-02 -9.06087995e-01 4.22765225e-01 1.74523201e-02 -9.04614449e-01 4.25908536e-01 1.74523201e-02 -9.03129458e-01 4.29052025e-01 1.74523201e-02 -9.01633620e-01 4.32182968e-01 1.74523201e-02 -9.00158346e-01 4.35257465e-01 1.74523201e-02 -8.98621321e-01 4.38420951e-01 1.74523201e-02 -8.97034347e-01 4.41653132e-01 1.74523201e-02 -8.95499229e-01 4.44759011e-01 1.74523201e-02 -8.93940091e-01 4.47882205e-01 1.74523201e-02 -8.92368734e-01 4.51007664e-01 1.74523201e-02 -8.90832365e-01 4.54034448e-01 1.74523201e-02 -8.89285684e-01 4.57056135e-01 1.74523201e-02 -8.87648582e-01 4.60227489e-01 1.74523201e-02 -8.85999680e-01 4.63396132e-01 1.74523201e-02 -8.84406805e-01 4.66427237e-01 1.74523201e-02 -8.82787526e-01 4.69484389e-01 1.74523201e-02 -8.81097615e-01 4.72648352e-01 1.74523201e-02 -8.79444063e-01 4.75715876e-01 1.74523201e-02 -8.77775490e-01 4.78793532e-01 1.74523201e-02 -8.76092613e-01 4.81863320e-01 1.74523201e-02 -8.74459147e-01 4.84813511e-01 1.74523201e-02 -8.72766435e-01 4.87859815e-01 1.74523201e-02 -8.71015668e-01 4.90981311e-01 1.74523201e-02 -8.69286597e-01 4.94033098e-01 1.74523201e-02 -8.67559552e-01 4.97062445e-01 1.74523201e-02 -8.65830481e-01 5.00070274e-01 1.74523201e-02 -8.64086568e-01 5.03074825e-01 1.74523201e-02 -8.62327039e-01 5.06085992e-01 1.74523201e-02 -8.60545695e-01 5.09107471e-01 1.74523201e-02 -8.58809471e-01 5.12030482e-01 1.74523201e-02 -8.57048392e-01 5.14975965e-01 1.74523201e-02 -8.55195403e-01 5.18044114e-01 1.74523201e-02 -8.53361309e-01 5.21063149e-01 1.74523201e-02 -8.51541281e-01 5.24027407e-01 1.74523201e-02 -8.49699795e-01 5.27012348e-01 1.74523201e-02 -8.47859681e-01 5.29964805e-01 1.74523201e-02 -8.46058965e-01 5.32835245e-01 1.74523201e-02 -8.44179988e-01 5.35807788e-01 1.74523201e-02 -8.42253983e-01 5.38829803e-01 1.74523201e-02 -8.40405047e-01 5.41705906e-01 1.74523201e-02 -8.38526785e-01 5.44610858e-01 1.74523201e-02 -8.36596549e-01 5.47570348e-01 1.74523201e-02 -8.34673703e-01 5.50499856e-01 1.74523201e-02 -8.32720757e-01 5.53445399e-01 1.74523201e-02 -8.30786109e-01 5.56347787e-01 1.74523201e-02 -8.28890026e-01 5.59170008e-01 1.74523201e-02 -8.26936424e-01 5.62055588e-01 1.74523201e-02 -8.24905872e-01 5.65030515e-01 1.74523201e-02 -8.22933972e-01 5.67899585e-01 1.74523201e-02 -8.20998967e-01 5.70689917e-01 1.74523201e-02 -8.19017351e-01 5.73531449e-01 1.74523201e-02 -8.16965520e-01 5.76453090e-01 1.74523201e-02 -8.14945817e-01 5.79302847e-01 1.74523201e-02 -8.12888265e-01 5.82188129e-01 1.74523201e-02 -8.10912549e-01 5.84931374e-01 1.74523201e-02 -8.08916211e-01 5.87693393e-01 1.74523201e-02 -8.06791127e-01 5.90605855e-01 1.74523201e-02 -8.04676116e-01 5.93486309e-01 1.74523201e-02 -8.02590430e-01 5.96303046e-01 1.74523201e-02 -8.00506115e-01 5.99098206e-01 1.74523201e-02 -7.98405468e-01 6.01895273e-01 1.74523201e-02 -7.96310484e-01 6.04666471e-01 1.74523201e-02 -7.94197500e-01 6.07437611e-01 1.74523201e-02 -7.92077661e-01 6.10196769e-01 1.74523201e-02 -7.89989591e-01 6.12897038e-01 1.74523201e-02 -7.87857592e-01 6.15636706e-01 1.74523201e-02 -7.85621107e-01 6.18489087e-01 1.74523201e-02 -7.83460557e-01 6.21222019e-01 1.74523201e-02 -7.81284392e-01 6.23961091e-01 1.74523201e-02 -7.79093385e-01 6.26692057e-01 1.74523201e-02 -7.76919425e-01 6.29386187e-01 1.74523201e-02 -7.74781704e-01 6.32009387e-01 1.74523201e-02 -7.72596478e-01 6.34685218e-01 1.74523201e-02 -7.70278275e-01 6.37496054e-01 1.74523201e-02 -7.68116117e-01 6.40096366e-01 1.74523201e-02 -7.65896261e-01 6.42753482e-01 1.74523201e-02 -7.63585627e-01 6.45496964e-01 1.74523201e-02 -7.61324883e-01 6.48159742e-01 1.74523201e-02 -7.59042263e-01 6.50833368e-01 1.74523201e-02 -7.56794989e-01 6.53447211e-01 1.74523201e-02 -7.54569411e-01 6.56015337e-01 1.74523201e-02 -7.52241313e-01 6.58682227e-01 1.74523201e-02 -7.49848604e-01 6.61405206e-01 1.74523201e-02 -7.47528434e-01 6.64025426e-01 1.74523201e-02 -7.45208442e-01 6.66629374e-01 1.74523201e-02 -7.42881119e-01 6.69219792e-01 1.74523201e-02 -7.40555823e-01 6.71796501e-01 1.74523201e-02 -7.38207161e-01 6.74371541e-01 1.74523201e-02 -7.35859632e-01 6.76936150e-01 1.74523201e-02 -7.33547151e-01 6.79439962e-01 1.74523201e-02 -7.31171727e-01 6.81996107e-01 1.74523201e-02 -7.28708029e-01 6.84627354e-01 1.74523201e-02 -7.26304829e-01 6.87175333e-01 1.74523201e-02 -7.23890960e-01 6.89718127e-01 1.74523201e-02 -7.21496820e-01 6.92217410e-01 1.74523201e-02 -7.19087422e-01 6.94733322e-01 1.74523201e-02 -7.16705263e-01 6.97187901e-01 1.74523201e-02 -7.14281797e-01 6.99668825e-01 1.74523201e-02 -7.11770475e-01 7.02224553e-01 1.74523201e-02 -7.09370017e-01 7.04651237e-01 1.74523201e-02 -7.06898570e-01 7.07111657e-01 1.74523201e-02 -7.04374015e-01 7.09645391e-01 1.74523201e-02 -7.01890230e-01 7.12102115e-01 1.74523201e-02 -6.99404716e-01 7.14539766e-01 1.74523201e-02 -6.96925759e-01 7.16961622e-01 1.74523201e-02 -6.94475472e-01 7.19334602e-01 1.74523201e-02 -6.91961646e-01 7.21743286e-01 1.74523201e-02 -6.89365268e-01 7.24231362e-01 1.74523201e-02 -6.86821997e-01 7.26637125e-01 1.74523201e-02 -6.84278786e-01 7.29032218e-01 1.74523201e-02 -6.81731820e-01 7.31413424e-01 1.74523201e-02 -6.79184020e-01 7.33782411e-01 1.74523201e-02 -6.76608682e-01 7.36161709e-01 1.74523201e-02 -6.74029410e-01 7.38519847e-01 1.74523201e-02 -6.71457946e-01 7.40861595e-01 1.74523201e-02 -6.68933511e-01 7.43139148e-01 1.74523201e-02 -6.66349173e-01 7.45459616e-01 1.74523201e-02 -6.63665652e-01 7.47849882e-01 1.74523201e-02 -6.61045134e-01 7.50165761e-01 1.74523201e-02 -6.58410311e-01 7.52478063e-01 1.74523201e-02 -6.55801058e-01 7.54755199e-01 1.74523201e-02 -6.53212190e-01 7.56995916e-01 1.74523201e-02 -6.50563896e-01 7.59273887e-01 1.74523201e-02 -6.47855282e-01 7.61586189e-01 1.74523201e-02 -6.45235896e-01 7.63806283e-01 1.74523201e-02 -6.42605841e-01 7.66020298e-01 1.74523201e-02 -6.39832795e-01 7.68339515e-01 1.74523201e-02 -6.37168467e-01 7.70547688e-01 1.74523201e-02 -6.34454906e-01 7.72787154e-01 1.74523201e-02 -6.31827295e-01 7.74932146e-01 1.74523201e-02 -6.29112124e-01 7.77143180e-01 1.74523201e-02 -6.26326621e-01 7.79386878e-01 1.74523201e-02 -6.23669684e-01 7.81513810e-01 1.74523201e-02 -6.20936453e-01 7.83688366e-01 1.74523201e-02 -6.18187308e-01 7.85857618e-01 1.74523201e-02 -6.15470052e-01 7.87989855e-01 1.74523201e-02 -6.12626374e-01 7.90202796e-01 1.74523201e-02 -6.09934688e-01 7.92280376e-01 1.74523201e-02 -6.07199609e-01 7.94380367e-01 1.74523201e-02 -6.04387283e-01 7.96520233e-01 1.74523201e-02 -6.01611614e-01 7.98621893e-01 1.74523201e-02 -5.98814309e-01 8.00717592e-01 1.74523201e-02 -5.96030116e-01 8.02793384e-01 1.74523201e-02 -5.93126476e-01 8.04939151e-01 1.74523201e-02 -5.90312064e-01 8.07006955e-01 1.74523201e-02 -5.87565064e-01 8.09009552e-01 1.74523201e-02 -5.84813118e-01 8.11000288e-01 1.74523201e-02 -5.81886172e-01 8.13104987e-01 1.74523201e-02 -5.79061568e-01 8.15118313e-01 1.74523201e-02 -5.76241195e-01 8.17117751e-01 1.74523201e-02 -5.73371649e-01 8.19128633e-01 1.74523201e-02 -5.70526361e-01 8.21114063e-01 1.74523201e-02 -5.67564607e-01 8.23164523e-01 1.74523201e-02 -5.64695597e-01 8.25135827e-01 1.74523201e-02 -5.61876595e-01 8.27054620e-01 1.74523201e-02 -5.59069335e-01 8.28957856e-01 1.74523201e-02 -5.56093752e-01 8.30957413e-01 1.74523201e-02 -5.53168356e-01 8.32903743e-01 1.74523201e-02 -5.50291836e-01 8.34811449e-01 1.74523201e-02 -5.47364950e-01 8.36730659e-01 1.74523201e-02 -5.44481516e-01 8.38610649e-01 1.74523201e-02 -5.41469276e-01 8.40558171e-01 1.74523201e-02 -5.38507462e-01 8.42459261e-01 1.74523201e-02 -5.35546780e-01 8.44343960e-01 1.74523201e-02 -5.32584727e-01 8.46217036e-01 1.74523201e-02 -5.29635310e-01 8.48065197e-01 1.74523201e-02 -5.26759148e-01 8.49855423e-01 1.74523201e-02 -5.23790359e-01 8.51688981e-01 1.74523201e-02 -5.20702362e-01 8.53580594e-01 1.74523201e-02 -5.17704308e-01 8.55401278e-01 1.74523201e-02 -5.14803767e-01 8.57149243e-01 1.74523201e-02 -5.11839449e-01 8.58925045e-01 1.74523201e-02 -5.08712411e-01 8.60778928e-01 1.74523201e-02 -5.05801022e-01 8.62492740e-01 1.74523201e-02 -5.02811849e-01 8.64240170e-01 1.74523201e-02 -4.99774158e-01 8.65999758e-01 1.74523201e-02 -4.96771216e-01 8.67725670e-01 1.74523201e-02 -4.93639648e-01 8.69511187e-01 1.74523201e-02 -4.90622461e-01 8.71218860e-01 1.74523201e-02 -4.87686217e-01 8.72862220e-01 1.74523201e-02 -4.84604120e-01 8.74578178e-01 1.74523201e-02 -4.81466740e-01 8.76310289e-01 1.74523201e-02 -4.78498071e-01 8.77934754e-01 1.74523201e-02 -4.75421637e-01 8.79605174e-01 1.74523201e-02 -4.72327083e-01 8.81268680e-01 1.74523201e-02 -4.69288468e-01 8.82892013e-01 1.74523201e-02 -4.66186792e-01 8.84533942e-01 1.74523201e-02 -4.63113248e-01 8.86146665e-01 1.74523201e-02 -4.59953278e-01 8.87790620e-01 1.74523201e-02 -4.56834882e-01 8.89399588e-01 1.74523201e-02 -4.53718841e-01 8.90992939e-01 1.74523201e-02 -4.50672746e-01 8.92537832e-01 1.74523201e-02 -4.47565347e-01 8.94100428e-01 1.74523201e-02 -4.44390088e-01 8.95683169e-01 1.74523201e-02 -4.41248745e-01 8.97233009e-01 1.74523201e-02 -4.38166589e-01 8.98742557e-01 1.74523201e-02 -4.35027242e-01 9.00269151e-01 1.74523201e-02 -4.31819022e-01 9.01809633e-01 1.74523201e-02 -4.28666502e-01 9.03312027e-01 1.74523201e-02 -4.25517231e-01 9.04800534e-01 1.74523201e-02 -4.22418296e-01 9.06250834e-01 1.74523201e-02 -4.19254899e-01 9.07720029e-01 1.74523201e-02 -4.16010112e-01 9.09209728e-01 1.74523201e-02 -4.12837744e-01 9.10655975e-01 1.74523201e-02 -4.09745604e-01 9.12050962e-01 1.74523201e-02 -4.06600595e-01 9.13458586e-01 1.74523201e-02 -4.03309911e-01 9.14916158e-01 1.74523201e-02 -4.00176644e-01 9.16291595e-01 1.74523201e-02 -3.96971434e-01 9.17683780e-01 1.74523201e-02 -3.93760860e-01 9.19060886e-01 1.74523201e-02 -3.90638977e-01 9.20395672e-01 1.74523201e-02 -3.87401581e-01 9.21764970e-01 1.74523201e-02 -3.84135157e-01 9.23130333e-01 1.74523201e-02 -3.80827010e-01 9.24498916e-01 1.74523201e-02 -3.77610505e-01 9.25817966e-01 1.74523201e-02 -3.74380827e-01 9.27129447e-01 1.74523201e-02 -3.71182293e-01 9.28413272e-01 1.74523201e-02 -3.67940843e-01 9.29704309e-01 1.74523201e-02 -3.64660382e-01 9.30995643e-01 1.74523201e-02 -3.61372590e-01 9.32270765e-01 1.74523201e-02 -3.58207762e-01 9.33501720e-01 1.74523201e-02 -3.54973763e-01 9.34728563e-01 1.74523201e-02 -3.51622999e-01 9.35988069e-01 1.74523201e-02 -3.48339826e-01 9.37214196e-01 1.74523201e-02 -3.45156521e-01 9.38393414e-01 1.74523201e-02 -3.41981828e-01 9.39564228e-01 1.74523201e-02 -3.38618010e-01 9.40780044e-01 1.74523201e-02 -3.35307747e-01 9.41966057e-01 1.74523201e-02 -3.32055777e-01 9.43117023e-01 1.74523201e-02 -3.28740805e-01 9.44276869e-01 1.74523201e-02 -3.25464398e-01 9.45411921e-01 1.74523201e-02 -3.22106987e-01 9.46559846e-01 1.74523201e-02 -3.18865627e-01 9.47657287e-01 1.74523201e-02 -3.15547377e-01 9.48765993e-01 1.74523201e-02 -3.12211245e-01 9.49868321e-01 1.74523201e-02 -3.08887511e-01 9.50956404e-01 1.74523201e-02 -3.05571884e-01 9.52027142e-01 1.74523201e-02 -3.02250445e-01 9.53087747e-01 1.74523201e-02 -2.98853368e-01 9.54155624e-01 1.74523201e-02 -2.95518100e-01 9.55194473e-01 1.74523201e-02 -2.92174011e-01 9.56222594e-01 1.74523201e-02 -2.88851798e-01 9.57230687e-01 1.74523201e-02 -2.85530955e-01 9.58227634e-01 1.74523201e-02 -2.82168001e-01 9.59224820e-01 1.74523201e-02 -2.78824776e-01 9.60201800e-01 1.74523201e-02 -2.75537103e-01 9.61148977e-01 1.74523201e-02 -2.72172183e-01 9.62109089e-01 1.74523201e-02 -2.68756777e-01 9.63067353e-01 1.74523201e-02 -2.65381426e-01 9.64003265e-01 1.74523201e-02 -2.62090653e-01 9.64905322e-01 1.74523201e-02 -2.58801073e-01 9.65791523e-01 1.74523201e-02 -2.55380034e-01 9.66701031e-01 1.74523201e-02 -2.51990050e-01 9.67590153e-01 1.74523201e-02 -2.48607159e-01 9.68465149e-01 1.74523201e-02 -2.45230898e-01 9.69322979e-01 1.74523201e-02 -2.41845146e-01 9.70175147e-01 1.74523201e-02 -2.38334969e-01 9.71045315e-01 1.74523201e-02 -2.35048085e-01 9.71845508e-01 1.74523201e-02 -2.31646776e-01 9.72663522e-01 1.74523201e-02 -2.28252411e-01 9.73461568e-01 1.74523201e-02 -2.24875674e-01 9.74249661e-01 1.74523201e-02 -2.21455932e-01 9.75030661e-01 1.74523201e-02 -2.18175620e-01 9.75772023e-01 1.74523201e-02 -2.14638948e-01 9.76555586e-01 1.74523201e-02 -2.11119890e-01 9.77322042e-01 1.74523201e-02 -2.07708567e-01 9.78052437e-01 1.74523201e-02 -2.04306543e-01 9.78769243e-01 1.74523201e-02 -2.00995743e-01 9.79452848e-01 1.74523201e-02 -1.97561711e-01 9.80152190e-01 1.74523201e-02 -1.94034278e-01 9.80856240e-01 1.74523201e-02 -1.90597311e-01 9.81530130e-01 1.74523201e-02 -1.87171564e-01 9.82189655e-01 1.74523201e-02 -1.83849573e-01 9.82814670e-01 1.74523201e-02 -1.80426747e-01 9.83448744e-01 1.74523201e-02 -1.76983893e-01 9.84080195e-01 1.74523201e-02 -1.73535153e-01 9.84695733e-01 1.74523201e-02 -1.69997469e-01 9.85306084e-01 1.74523201e-02 -1.66652828e-01 9.85878110e-01 1.74523201e-02 -1.63222656e-01 9.86452758e-01 1.74523201e-02 -1.59763902e-01 9.87016022e-01 1.74523201e-02 -1.56351179e-01 9.87564504e-01 1.74523201e-02 -1.52766958e-01 9.88125324e-01 1.74523201e-02 -1.49423718e-01 9.88634825e-01 1.74523201e-02 -1.45977974e-01 9.89151180e-01 1.74523201e-02 -1.42512560e-01 9.89654422e-01 1.74523201e-02 -1.39061972e-01 9.90148962e-01 1.74523201e-02 -1.35515556e-01 9.90639687e-01 1.74523201e-02 -1.32134408e-01 9.91092622e-01 1.74523201e-02 -1.28669024e-01 9.91551697e-01 1.74523201e-02 -1.25112623e-01 9.92006779e-01 1.74523201e-02 -1.21663839e-01 9.92434263e-01 1.74523201e-02 -1.18305795e-01 9.92838681e-01 1.74523201e-02 -1.14918254e-01 9.93237197e-01 1.74523201e-02 -1.11350641e-01 9.93644953e-01 1.74523201e-02 -1.07789874e-01 9.94035780e-01 1.74523201e-02 -1.04307286e-01 9.94408667e-01 1.74523201e-02 -1.00824669e-01 9.94766474e-01 1.74523201e-02 -9.74346772e-02 9.95104373e-01 1.74523201e-02 -9.39955115e-02 9.95437324e-01 1.74523201e-02 -9.05175135e-02 9.95758414e-01 1.74523201e-02 -8.70515406e-02 9.96069491e-01 1.74523201e-02 -8.34569857e-02 9.96375144e-01 1.74523201e-02 -8.00894722e-02 9.96651888e-01 1.74523201e-02 -7.66327456e-02 9.96923506e-01 1.74523201e-02 -7.31327981e-02 9.97185946e-01 1.74523201e-02 -6.96424320e-02 9.97436047e-01 1.74523201e-02 -6.60524666e-02 9.97680962e-01 1.74523201e-02 -6.25604168e-02 9.97902632e-01 1.74523201e-02 -5.90902343e-02 9.98116195e-01 1.74523201e-02 -5.56848012e-02 9.98312235e-01 1.74523201e-02 -5.21986112e-02 9.98499155e-01 1.74523201e-02 -4.87134233e-02 9.98677015e-01 1.74523201e-02 -4.53408770e-02 9.98835266e-01 1.74523201e-02 -4.17729244e-02 9.98990893e-01 1.74523201e-02 -3.81694622e-02 9.99134898e-01 1.74523201e-02 -3.46697271e-02 9.99262154e-01 1.74523201e-02 -3.11717167e-02 9.99378264e-01 1.74523201e-02 -2.77725831e-02 9.99476969e-01 1.74523201e-02 -2.44045760e-02 9.99568522e-01 1.74523201e-02 -2.08053533e-02 9.99644160e-01 1.74523201e-02 -1.71962213e-02 9.99720931e-01 1.74523201e-02 -1.37379700e-02 9.99765337e-01 1.74523201e-02 -1.03481822e-02 9.99808609e-01 1.74523201e-02 -6.85743010e-03 9.99848068e-01 1.74523201e-02 -3.33162630e-03 9.99862552e-01 1.74523201e-02 1.34777452e-04 9.99865413e-01 1.74523201e-02 3.71635612e-03 9.99863207e-01 1.74523201e-02 7.13551184e-03 9.99842346e-01 1.74523201e-02 1.06107760e-02 9.99808609e-01 1.74523201e-02 1.41025791e-02 9.99760628e-01 1.74523201e-02 1.75651386e-02 9.99716401e-01 1.74523201e-02 2.10864507e-02 9.99640465e-01 1.74523201e-02 2.44846586e-02 9.99565303e-01 1.74523201e-02 2.80509889e-02 9.99472916e-01 1.74523201e-02 3.16321179e-02 9.99364197e-01 1.74523201e-02 3.51238325e-02 9.99248266e-01 1.74523201e-02 3.85893732e-02 9.99119759e-01 1.74523201e-02 4.19902429e-02 9.98983502e-01 1.74523201e-02 4.54974398e-02 9.98827994e-01 1.74523201e-02 4.90648821e-02 9.98660445e-01 1.74523201e-02 5.25493324e-02 9.98478651e-01 1.74523201e-02 5.60061745e-02 9.98295605e-01 1.74523201e-02 5.94179071e-02 9.98097360e-01 1.74523201e-02 6.28888384e-02 9.97882664e-01 1.74523201e-02 6.64725751e-02 9.97651041e-01 1.74523201e-02 6.99764937e-02 9.97410893e-01 1.74523201e-02 7.34726861e-02 9.97161448e-01 1.74523201e-02 7.68607557e-02 9.96903956e-01 1.74523201e-02 8.03322569e-02 9.96632218e-01 1.74523201e-02 8.38081390e-02 9.96344686e-01 1.74523201e-02 8.72708857e-02 9.96048331e-01 1.74523201e-02 9.08674076e-02 9.95726645e-01 1.74523201e-02 9.42632183e-02 9.95408714e-01 1.74523201e-02 9.76781622e-02 9.95082378e-01 1.74523201e-02 1.01190276e-01 9.94730711e-01 1.74523201e-02 1.04648463e-01 9.94372964e-01 1.74523201e-02 1.08138055e-01 9.93998349e-01 1.74523201e-02 1.11591108e-01 9.93619084e-01 1.74523201e-02 1.15166552e-01 9.93208051e-01 1.74523201e-02 1.18635230e-01 9.92799997e-01 1.74523201e-02 1.22071303e-01 9.92384076e-01 1.74523201e-02 1.25472963e-01 9.91962075e-01 1.74523201e-02 1.28845081e-01 9.91526961e-01 1.74523201e-02 1.32387206e-01 9.91061449e-01 1.74523201e-02 1.35914981e-01 9.90584493e-01 1.74523201e-02 1.39398143e-01 9.90099788e-01 1.74523201e-02 1.42847836e-01 9.89606500e-01 1.74523201e-02 1.46246463e-01 9.89109278e-01 1.74523201e-02 1.49664029e-01 9.88598943e-01 1.74523201e-02 1.53116122e-01 9.88070786e-01 1.74523201e-02 1.56567395e-01 9.87530053e-01 1.74523201e-02 1.60122186e-01 9.86959636e-01 1.74523201e-02 1.63468286e-01 9.86410975e-01 1.74523201e-02 1.66901529e-01 9.85837162e-01 1.74523201e-02 1.70341253e-01 9.85245943e-01 1.74523201e-02 1.73698381e-01 9.84664619e-01 1.74523201e-02 1.77214861e-01 9.84037638e-01 1.74523201e-02 1.80735528e-01 9.83392298e-01 1.74523201e-02 1.84186295e-01 9.82753456e-01 1.74523201e-02 1.87500000e-01 9.82125700e-01 1.74523201e-02 1.90942645e-01 9.81462836e-01 1.74523201e-02 1.94378540e-01 9.80788529e-01 1.74523201e-02 1.97700366e-01 9.80123162e-01 1.74523201e-02 2.01193810e-01 9.79414105e-01 1.74523201e-02 2.04711601e-01 9.78683293e-01 1.74523201e-02 2.08111241e-01 9.77967203e-01 1.74523201e-02 2.11550847e-01 9.77229118e-01 1.74523201e-02 2.14858577e-01 9.76503253e-01 1.74523201e-02 2.18270108e-01 9.75751817e-01 1.74523201e-02 2.21767038e-01 9.74959552e-01 1.74523201e-02 2.25155905e-01 9.74184394e-01 1.74523201e-02 2.28571162e-01 9.73389745e-01 1.74523201e-02 2.31879771e-01 9.72606003e-01 1.74523201e-02 2.35165939e-01 9.71819460e-01 1.74523201e-02 2.38575727e-01 9.70984578e-01 1.74523201e-02 2.42029324e-01 9.70128477e-01 1.74523201e-02 2.45502248e-01 9.69255447e-01 1.74523201e-02 2.48812273e-01 9.68412399e-01 1.74523201e-02 2.52187610e-01 9.67539370e-01 1.74523201e-02 2.55558878e-01 9.66654241e-01 1.74523201e-02 2.58910209e-01 9.65762913e-01 1.74523201e-02 2.62390077e-01 9.64822888e-01 1.74523201e-02 2.65684217e-01 9.63918447e-01 1.74523201e-02 2.69037575e-01 9.62989867e-01 1.74523201e-02 2.72409201e-01 9.62040186e-01 1.74523201e-02 2.75743842e-01 9.61090863e-01 1.74523201e-02 2.79204905e-01 9.60089505e-01 1.74523201e-02 2.82451540e-01 9.59140599e-01 1.74523201e-02 2.85797805e-01 9.58150327e-01 1.74523201e-02 2.89247632e-01 9.57111001e-01 1.74523201e-02 2.92554319e-01 9.56108630e-01 1.74523201e-02 2.95795351e-01 9.55110133e-01 1.74523201e-02 2.99038291e-01 9.54100132e-01 1.74523201e-02 3.02386016e-01 9.53044295e-01 1.74523201e-02 3.05810630e-01 9.51949358e-01 1.74523201e-02 3.09251338e-01 9.50837970e-01 1.74523201e-02 3.12550426e-01 9.49758291e-01 1.74523201e-02 3.15788716e-01 9.48686182e-01 1.74523201e-02 3.18999141e-01 9.47613895e-01 1.74523201e-02 3.22292715e-01 9.46495831e-01 1.74523201e-02 3.25672805e-01 9.45340335e-01 1.74523201e-02 3.29050064e-01 9.44167912e-01 1.74523201e-02 3.32291961e-01 9.43033099e-01 1.74523201e-02 3.35574538e-01 9.41871762e-01 1.74523201e-02 3.38858366e-01 9.40690279e-01 1.74523201e-02 3.42123479e-01 9.39512432e-01 1.74523201e-02 3.45496356e-01 9.38269377e-01 1.74523201e-02 3.48762453e-01 9.37056541e-01 1.74523201e-02 3.52039278e-01 9.35832620e-01 1.74523201e-02 3.55234772e-01 9.34626818e-01 1.74523201e-02 3.58489543e-01 9.33393657e-01 1.74523201e-02 3.61736000e-01 9.32131112e-01 1.74523201e-02 3.64898741e-01 9.30900574e-01 1.74523201e-02 3.68235856e-01 9.29587066e-01 1.74523201e-02 3.71560752e-01 9.28262293e-01 1.74523201e-02 3.74788761e-01 9.26961780e-01 1.74523201e-02 3.78004700e-01 9.25656974e-01 1.74523201e-02 3.81167710e-01 9.24356282e-01 1.74523201e-02 3.84302914e-01 9.23059642e-01 1.74523201e-02 3.87595177e-01 9.21682000e-01 1.74523201e-02 3.90909851e-01 9.20279562e-01 1.74523201e-02 3.94095182e-01 9.18920100e-01 1.74523201e-02 3.97241503e-01 9.17564988e-01 1.74523201e-02 4.00387019e-01 9.16199744e-01 1.74523201e-02 4.03567016e-01 9.14801836e-01 1.74523201e-02 4.06811297e-01 9.13365066e-01 1.74523201e-02 4.10064220e-01 9.11908209e-01 1.74523201e-02 4.13182646e-01 9.10498202e-01 1.74523201e-02 4.16289032e-01 9.09080982e-01 1.74523201e-02 4.19443011e-01 9.07630265e-01 1.74523201e-02 4.22623426e-01 9.06155348e-01 1.74523201e-02 4.25767124e-01 9.04681683e-01 1.74523201e-02 4.28928494e-01 9.03186917e-01 1.74523201e-02 4.32187140e-01 9.01630998e-01 1.74523201e-02 4.35329676e-01 9.00122702e-01 1.74523201e-02 4.38410550e-01 8.98626089e-01 1.74523201e-02 4.41489816e-01 8.97115231e-01 1.74523201e-02 4.44599211e-01 8.95578444e-01 1.74523201e-02 4.47802603e-01 8.93981576e-01 1.74523201e-02 4.50971454e-01 8.92387211e-01 1.74523201e-02 4.54075903e-01 8.90810847e-01 1.74523201e-02 4.57145751e-01 8.89238656e-01 1.74523201e-02 4.60158199e-01 8.87682199e-01 1.74523201e-02 4.63242710e-01 8.86081040e-01 1.74523201e-02 4.66406524e-01 8.84417951e-01 1.74523201e-02 4.69553858e-01 8.82751048e-01 1.74523201e-02 4.72634912e-01 8.81106138e-01 1.74523201e-02 4.75642771e-01 8.79482508e-01 1.74523201e-02 4.78651226e-01 8.77854407e-01 1.74523201e-02 4.81706381e-01 8.76179218e-01 1.74523201e-02 4.84807730e-01 8.74463916e-01 1.74523201e-02 4.87942696e-01 8.72720361e-01 1.74523201e-02 4.90933686e-01 8.71042013e-01 1.74523201e-02 4.93940949e-01 8.69339824e-01 1.74523201e-02 4.96984750e-01 8.67603958e-01 1.74523201e-02 4.99941677e-01 8.65902960e-01 1.74523201e-02 5.03037632e-01 8.64109218e-01 1.74523201e-02 5.06057024e-01 8.62343311e-01 1.74523201e-02 5.09052157e-01 8.60579073e-01 1.74523201e-02 5.12053251e-01 8.58794332e-01 1.74523201e-02 5.15045643e-01 8.57007027e-01 1.74523201e-02 5.18071115e-01 8.55178356e-01 1.74523201e-02 5.20959139e-01 8.53423834e-01 1.74523201e-02 5.23986459e-01 8.51568341e-01 1.74523201e-02 5.26966214e-01 8.49726975e-01 1.74523201e-02 5.29922366e-01 8.47887456e-01 1.74523201e-02 5.32898247e-01 8.46018553e-01 1.74523201e-02 5.35728872e-01 8.44229579e-01 1.74523201e-02 5.38722754e-01 8.42322230e-01 1.74523201e-02 5.41657627e-01 8.40437353e-01 1.74523201e-02 5.44622838e-01 8.38519216e-01 1.74523201e-02 5.47640681e-01 8.36551905e-01 1.74523201e-02 5.50500989e-01 8.34671497e-01 1.74523201e-02 5.53282082e-01 8.32827389e-01 1.74523201e-02 5.56177735e-01 8.30897927e-01 1.74523201e-02 5.59152603e-01 8.28900814e-01 1.74523219e-02 5.62091947e-01 8.26906264e-01 1.74523313e-02 5.64917982e-01 8.24974597e-01 1.74523313e-02 5.67715406e-01 8.23051035e-01 1.74523313e-02 5.70578575e-01 8.21066082e-01 1.74523313e-02 5.73439896e-01 8.19065928e-01 1.74523313e-02 5.76371431e-01 8.17000866e-01 1.74523611e-02 5.79186559e-01 8.15007091e-01 1.74523816e-02 5.81917584e-01 8.13059747e-01 1.74524244e-02 5.84730685e-01 8.11038733e-01 1.74524020e-02 5.87820768e-01 8.08802068e-01 1.74524076e-02 5.90163291e-01 8.07094812e-01 1.74524058e-02 5.92907012e-01 8.05081844e-01 1.74524039e-02 5.95923126e-01 8.02850723e-01 1.74524039e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 7.24903286e-01 6.88629448e-01 1.74524058e-02 7.26468563e-01 6.86976969e-01 1.74524076e-02 7.29092717e-01 6.84191406e-01 1.74523965e-02 7.31488168e-01 6.81629598e-01 1.74523611e-02 7.33791053e-01 6.79150701e-01 1.74523480e-02 7.36066580e-01 6.76697612e-01 1.74523313e-02 7.38401830e-01 6.74153328e-01 1.74523313e-02 7.40736902e-01 6.71590149e-01 1.74523257e-02 7.43119836e-01 6.68956339e-01 1.74523201e-02 7.45525002e-01 6.66270256e-01 1.74523201e-02 7.47765064e-01 6.63756967e-01 1.74523238e-02 7.49983549e-01 6.61248624e-01 1.74523219e-02 7.52273917e-01 6.58636570e-01 1.74523313e-02 7.54630029e-01 6.55937135e-01 1.74523313e-02 7.56957054e-01 6.53250992e-01 1.74523313e-02 7.59238243e-01 6.50594950e-01 1.74523313e-02 7.61431932e-01 6.48025036e-01 1.74523313e-02 7.63696969e-01 6.45356655e-01 1.74523313e-02 7.66020417e-01 6.42595232e-01 1.74523313e-02 7.68241525e-01 6.39936686e-01 1.74523313e-02 7.70417809e-01 6.37318671e-01 1.74523313e-02 7.72702634e-01 6.34550214e-01 1.74523294e-02 7.74965286e-01 6.31782293e-01 1.74523313e-02 7.77156711e-01 6.29085243e-01 1.74523313e-02 7.79301345e-01 6.26426160e-01 1.74523313e-02 7.81442940e-01 6.23759329e-01 1.74523201e-02 7.83582091e-01 6.21066630e-01 1.74523201e-02 7.85816908e-01 6.18241966e-01 1.74523201e-02 7.88035095e-01 6.15411043e-01 1.74523201e-02 7.90165186e-01 6.12673640e-01 1.74523201e-02 7.92243838e-01 6.09981418e-01 1.74523201e-02 7.94323504e-01 6.07272804e-01 1.74523201e-02 7.96447396e-01 6.04484499e-01 1.74523201e-02 7.98587382e-01 6.01656616e-01 1.74523201e-02 8.00744236e-01 5.98778069e-01 1.74523201e-02 8.02777529e-01 5.96049190e-01 1.74523201e-02 8.04787636e-01 5.93332529e-01 1.74523201e-02 8.06853592e-01 5.90519547e-01 1.74523201e-02 8.08974326e-01 5.87614417e-01 1.74523201e-02 8.11018229e-01 5.84785759e-01 1.74523201e-02 8.12996209e-01 5.82037270e-01 1.74523201e-02 8.15076709e-01 5.79121232e-01 1.74523201e-02 8.17101300e-01 5.76260924e-01 1.74523201e-02 8.19112062e-01 5.73397338e-01 1.74523201e-02 8.21109176e-01 5.70531130e-01 1.74523201e-02 8.23037803e-01 5.67750096e-01 1.74523201e-02 8.25052559e-01 5.64819455e-01 1.74523201e-02 8.27086031e-01 5.61833441e-01 1.74523201e-02 8.29043627e-01 5.58941245e-01 1.74523201e-02 8.30939770e-01 5.56116402e-01 1.74523201e-02 8.32806110e-01 5.53318083e-01 1.74523201e-02 8.34743440e-01 5.50392389e-01 1.74523201e-02 8.36711824e-01 5.47395349e-01 1.74523201e-02 8.38670254e-01 5.44389665e-01 1.74523201e-02 8.40511501e-01 5.41540921e-01 1.74523201e-02 8.42334390e-01 5.38702965e-01 1.74523201e-02 8.44204903e-01 5.35766125e-01 1.74523201e-02 8.46086264e-01 5.32794833e-01 1.74523201e-02 8.47994745e-01 5.29749811e-01 1.74523201e-02 8.49905908e-01 5.26678860e-01 1.74523201e-02 8.51686299e-01 5.23788691e-01 1.74523201e-02 8.53455603e-01 5.20909309e-01 1.74523201e-02 8.55257988e-01 5.17939150e-01 1.74523201e-02 8.57057512e-01 5.14956415e-01 1.74523201e-02 8.58855903e-01 5.11952817e-01 1.74523201e-02 8.60650361e-01 5.08930564e-01 1.74523201e-02 8.62420499e-01 5.05925536e-01 1.74523201e-02 8.64167333e-01 5.02935410e-01 1.74523201e-02 8.65960240e-01 4.99843538e-01 1.74523201e-02 8.67711484e-01 4.96794343e-01 1.74523201e-02 8.69383454e-01 4.93863374e-01 1.74523201e-02 8.71176541e-01 4.90698785e-01 1.74523201e-02 8.72938752e-01 4.87551093e-01 1.74523201e-02 8.74623537e-01 4.84520316e-01 1.74523201e-02 8.76258373e-01 4.81560200e-01 1.74523201e-02 8.77905846e-01 4.78553623e-01 1.74523201e-02 8.79570842e-01 4.75483358e-01 1.74523201e-02 8.81221056e-01 4.72418398e-01 1.74523201e-02 8.82907867e-01 4.69258755e-01 1.74523201e-02 8.84581685e-01 4.66096014e-01 1.74523201e-02 8.86166632e-01 4.63075072e-01 1.74523201e-02 8.87725115e-01 4.60079104e-01 1.74523201e-02 8.89336646e-01 4.56959873e-01 1.74523201e-02 8.90968561e-01 4.53765869e-01 1.74523201e-02 8.92582178e-01 4.50583607e-01 1.74523201e-02 8.94116223e-01 4.47528720e-01 1.74523201e-02 8.95626605e-01 4.44503218e-01 1.74523201e-02 8.97155464e-01 4.41408873e-01 1.74523201e-02 8.98734450e-01 4.38187748e-01 1.74523201e-02 9.00267720e-01 4.35028702e-01 1.74523201e-02 9.01738048e-01 4.31966305e-01 1.74523201e-02 9.03275371e-01 4.28742826e-01 1.74523201e-02 9.04769361e-01 4.25580472e-01 1.74523201e-02 9.06249225e-01 4.22426224e-01 1.74523201e-02 9.07727480e-01 4.19235557e-01 1.74523201e-02 9.09137726e-01 4.16166782e-01 1.74523201e-02 9.10626709e-01 4.12903100e-01 1.74523201e-02 9.12102222e-01 4.09634888e-01 1.74523201e-02 9.13516819e-01 4.06468987e-01 1.74523201e-02 9.14900482e-01 4.03339267e-01 1.74523201e-02 9.16279495e-01 4.00203347e-01 1.74523201e-02 9.17656898e-01 3.97032470e-01 1.74523201e-02 9.19034839e-01 3.93825322e-01 1.74523201e-02 9.20439839e-01 3.90536785e-01 1.74523201e-02 9.21805441e-01 3.87300044e-01 1.74523201e-02 9.23108041e-01 3.84189785e-01 1.74523201e-02 9.24446225e-01 3.80956173e-01 1.74523201e-02 9.25775647e-01 3.77713948e-01 1.74523201e-02 9.27112103e-01 3.74424070e-01 1.74523201e-02 9.28454816e-01 3.71081620e-01 1.74523201e-02 9.29716170e-01 3.67910028e-01 1.74523201e-02 9.30946648e-01 3.64789158e-01 1.74523201e-02 9.32212830e-01 3.61519277e-01 1.74523201e-02 9.33512151e-01 3.58177572e-01 1.74523201e-02 9.34762955e-01 3.54876578e-01 1.74523201e-02 9.35960352e-01 3.51695538e-01 1.74523201e-02 9.37204182e-01 3.48369926e-01 1.74523201e-02 9.38452482e-01 3.45001310e-01 1.74523201e-02 9.39649165e-01 3.41752172e-01 1.74523201e-02 9.40801501e-01 3.38547617e-01 1.74523201e-02 9.41950142e-01 3.35352510e-01 1.74523201e-02 9.43145037e-01 3.31975996e-01 1.74523201e-02 9.44337308e-01 3.28563988e-01 1.74523201e-02 9.45487201e-01 3.25247854e-01 1.74523201e-02 9.46576357e-01 3.22053760e-01 1.74523201e-02 9.47658241e-01 3.18863750e-01 1.74523201e-02 9.48769033e-01 3.15540403e-01 1.74523201e-02 9.49869275e-01 3.12213153e-01 1.74523201e-02 9.50974762e-01 3.08836311e-01 1.74523201e-02 9.52080071e-01 3.05404514e-01 1.74523201e-02 9.53115284e-01 3.02156806e-01 1.74523201e-02 9.54134405e-01 2.98930824e-01 1.74523201e-02 9.55170035e-01 2.95597136e-01 1.74523201e-02 9.56221402e-01 2.92182118e-01 1.74523201e-02 9.57260251e-01 2.88753271e-01 1.74523201e-02 9.58240211e-01 2.85487622e-01 1.74523201e-02 9.59206104e-01 2.82231450e-01 1.74523201e-02 9.60183442e-01 2.78883129e-01 1.74523201e-02 9.61163104e-01 2.75488317e-01 1.74523201e-02 9.62125003e-01 2.72113681e-01 1.74523201e-02 9.63053048e-01 2.68809497e-01 1.74523201e-02 9.63987410e-01 2.65435994e-01 1.74523201e-02 9.64903116e-01 2.62098491e-01 1.74523201e-02 9.65826392e-01 2.58662581e-01 1.74523201e-02 9.66735542e-01 2.55246907e-01 1.74523201e-02 9.67600226e-01 2.51952440e-01 1.74523201e-02 9.68461990e-01 2.48617351e-01 1.74523201e-02 9.69352365e-01 2.45114580e-01 1.74523201e-02 9.70212817e-01 2.41688922e-01 1.74523201e-02 9.71051276e-01 2.38306552e-01 1.74523201e-02 9.71859753e-01 2.34988645e-01 1.74523201e-02 9.72653091e-01 2.31681138e-01 1.74523201e-02 9.73454773e-01 2.28287384e-01 1.74523201e-02 9.74269271e-01 2.24786475e-01 1.74523201e-02 9.75050211e-01 2.21366569e-01 1.74523201e-02 9.75804150e-01 2.18030006e-01 1.74523201e-02 9.76555765e-01 2.14622721e-01 1.74523201e-02 9.77305532e-01 2.11190715e-01 1.74523201e-02 9.78033245e-01 2.07792982e-01 1.74523201e-02 9.78760242e-01 2.04351291e-01 1.74523201e-02 9.79469895e-01 2.00915292e-01 1.74523201e-02 9.80162084e-01 1.97515979e-01 1.74523201e-02 9.80855942e-01 1.94032833e-01 1.74523201e-02 9.81542170e-01 1.90536022e-01 1.74523201e-02 9.82175350e-01 1.87232196e-01 1.74523201e-02 9.82809365e-01 1.83886945e-01 1.74523201e-02 9.83457625e-01 1.80378497e-01 1.74523201e-02 9.84098732e-01 1.76879153e-01 1.74523201e-02 9.84711468e-01 1.73437163e-01 1.74523201e-02 9.85296130e-01 1.70048073e-01 1.74523201e-02 9.85870779e-01 1.66702449e-01 1.74523201e-02 9.86440659e-01 1.63282201e-01 1.74523201e-02 9.87008631e-01 1.59822971e-01 1.74523201e-02 9.87573206e-01 1.56302840e-01 1.74523201e-02 9.88124371e-01 1.52766883e-01 1.74523201e-02 9.88638818e-01 1.49392694e-01 1.74523201e-02 9.89140034e-01 1.46044388e-01 1.74523201e-02 9.89643216e-01 1.42590314e-01 1.74523201e-02 9.90150452e-01 1.39043376e-01 1.74523201e-02 9.90639269e-01 1.35513142e-01 1.74523201e-02 9.91090477e-01 1.32144213e-01 1.74523201e-02 9.91541028e-01 1.28739282e-01 1.74523201e-02 9.91980791e-01 1.25315055e-01 1.74523201e-02 9.92409289e-01 1.21867053e-01 1.74523201e-02 9.92833078e-01 1.18357584e-01 1.74523201e-02 9.93241549e-01 1.14880435e-01 1.74523201e-02 9.93647575e-01 1.11325614e-01 1.74523201e-02 9.94026303e-01 1.07886143e-01 1.74523201e-02 9.94393885e-01 1.04439981e-01 1.74523201e-02 9.94755566e-01 1.00927457e-01 1.74523201e-02 9.95093048e-01 9.75564420e-02 1.74523201e-02 9.95438099e-01 9.39957127e-02 1.74523201e-02 9.95764136e-01 9.04465988e-02 1.74523201e-02 9.96073246e-01 8.69791880e-02 1.74523201e-02 9.96367872e-01 8.35317448e-02 1.74523201e-02 9.96645749e-01 8.01602378e-02 1.74523201e-02 9.96916771e-01 7.66953304e-02 1.74523201e-02 9.97187495e-01 7.31153637e-02 1.74523201e-02 9.97439981e-01 6.95544630e-02 1.74523201e-02 9.97669101e-01 6.61828592e-02 1.74523201e-02 9.97889578e-01 6.27885684e-02 1.74523201e-02 9.98104095e-01 5.92819639e-02 1.74523201e-02 9.98307168e-01 5.58025911e-02 1.74523201e-02 9.98497963e-01 5.22414595e-02 1.74523201e-02 9.98680294e-01 4.86521646e-02 1.74523201e-02 9.98835802e-01 4.52780724e-02 1.74523201e-02 9.98988092e-01 4.18661907e-02 1.74523201e-02 9.99126613e-01 3.83984298e-02 1.74523201e-02 9.99258757e-01 3.47844176e-02 1.74523201e-02 9.99373734e-01 3.12899984e-02 1.74523201e-02 9.99475598e-01 2.79068220e-02 1.74523201e-02 9.99566913e-01 2.44235378e-02 1.74523201e-02 9.99644279e-01 2.09174864e-02 1.74523201e-02 9.99714851e-01 1.74453817e-02 1.74523201e-02 9.99762774e-01 1.39431702e-02 1.74523201e-02 9.99807596e-01 1.04550002e-02 1.74523201e-02 9.99848187e-01 6.86582364e-03 1.74523201e-02 9.99862909e-01 3.26689822e-03 1.74523201e-02 9.99864280e-01 -2.16528584e-04 1.74523201e-02 9.99862134e-01 -3.74491652e-03 1.74523201e-02 9.99841273e-01 -7.08248373e-03 1.74523201e-02 9.99809325e-01 -1.04811946e-02 1.74523201e-02 9.99762237e-01 -1.39735900e-02 1.74523201e-02 9.99712944e-01 -1.75947100e-02 1.74523201e-02 9.99637723e-01 -2.11862233e-02 1.74523201e-02 9.99561369e-01 -2.46484168e-02 1.74523201e-02 9.99470174e-01 -2.80262288e-02 1.74523201e-02 9.99367952e-01 -3.15090343e-02 1.74523201e-02 9.99249578e-01 -3.50561179e-02 1.74523201e-02 9.99125659e-01 -3.84225361e-02 1.74523201e-02 9.98987019e-01 -4.19056453e-02 1.74523201e-02 9.98829842e-01 -4.54743840e-02 1.74523201e-02 9.98659790e-01 -4.90622446e-02 1.74523201e-02 9.98481870e-01 -5.25361672e-02 1.74523201e-02 9.98295248e-01 -5.59638292e-02 1.74523201e-02 9.98100936e-01 -5.93460239e-02 1.74523201e-02 9.97888088e-01 -6.27995208e-02 1.74523201e-02 9.97658432e-01 -6.63738623e-02 1.74523201e-02 9.97409880e-01 -6.99811503e-02 1.74523201e-02 9.97161388e-01 -7.34793171e-02 1.74523201e-02 9.96903360e-01 -7.68647194e-02 1.74523201e-02 9.96639550e-01 -8.02279785e-02 1.74523201e-02 9.96353507e-01 -8.37111995e-02 1.74523201e-02 9.96046364e-01 -8.72964859e-02 1.74523201e-02 9.95730639e-01 -9.07988697e-02 1.74523201e-02 9.95425284e-01 -9.41036120e-02 1.74523201e-02 9.95087028e-01 -9.76261273e-02 1.74523201e-02 9.94740307e-01 -1.01099975e-01 1.74523201e-02 9.94381070e-01 -1.04571395e-01 1.74523201e-02 9.94001508e-01 -1.08112894e-01 1.74523201e-02 9.93618727e-01 -1.11581087e-01 1.74523201e-02 9.93233621e-01 -1.14952087e-01 1.74523201e-02 9.92817283e-01 -1.18491933e-01 1.74523201e-02 9.92395997e-01 -1.21974252e-01 1.74523201e-02 9.91964817e-01 -1.25447482e-01 1.74523201e-02 9.91506755e-01 -1.28997162e-01 1.74523201e-02 9.91067410e-01 -1.32332891e-01 1.74523201e-02 9.90595281e-01 -1.35833964e-01 1.74523201e-02 9.90103126e-01 -1.39377654e-01 1.74523201e-02 9.89621401e-01 -1.42741874e-01 1.74523201e-02 9.89117980e-01 -1.46192387e-01 1.74523201e-02 9.88597691e-01 -1.49661139e-01 1.74523201e-02 9.88077641e-01 -1.53068587e-01 1.74523201e-02 9.87527668e-01 -1.56568155e-01 1.74523201e-02 9.86978412e-01 -1.60007238e-01 1.74523201e-02 9.86419141e-01 -1.63417041e-01 1.74523201e-02 9.85839605e-01 -1.66880384e-01 1.74523201e-02 9.85233366e-01 -1.70409516e-01 1.74523201e-02 9.84638572e-01 -1.73846424e-01 1.74523201e-02 9.84040678e-01 -1.77196264e-01 1.74523201e-02 9.83426571e-01 -1.80543408e-01 1.74523201e-02 9.82795894e-01 -1.83962941e-01 1.74523201e-02 9.82124686e-01 -1.87501475e-01 1.74523201e-02 9.81454372e-01 -1.90986425e-01 1.74523201e-02 9.80780423e-01 -1.94416061e-01 1.74523201e-02 9.80114639e-01 -1.97740763e-01 1.74523201e-02 9.79433298e-01 -2.01092377e-01 1.74523201e-02 9.78717327e-01 -2.04545766e-01 1.74523201e-02 9.77988005e-01 -2.08012477e-01 1.74523201e-02 9.77258623e-01 -2.11417854e-01 1.74523201e-02 9.76512372e-01 -2.14827612e-01 1.74523201e-02 9.75752831e-01 -2.18254149e-01 1.74523201e-02 9.74986494e-01 -2.21651271e-01 1.74523201e-02 9.74212408e-01 -2.25032017e-01 1.74523201e-02 9.73412037e-01 -2.28474006e-01 1.74523201e-02 9.72606361e-01 -2.31875405e-01 1.74523201e-02 9.71827447e-01 -2.35126615e-01 1.74523201e-02 9.70976532e-01 -2.38608971e-01 1.74523201e-02 9.70134079e-01 -2.42000580e-01 1.74523201e-02 9.69285727e-01 -2.45381340e-01 1.74523201e-02 9.68407691e-01 -2.48827666e-01 1.74523201e-02 9.67560470e-01 -2.52096504e-01 1.74523201e-02 9.66664553e-01 -2.55522490e-01 1.74523201e-02 9.65758324e-01 -2.58920074e-01 1.74523201e-02 9.64888215e-01 -2.62145758e-01 1.74523201e-02 9.63943601e-01 -2.65590817e-01 1.74523201e-02 9.62993443e-01 -2.69021153e-01 1.74523201e-02 9.62066412e-01 -2.72319555e-01 1.74523201e-02 9.61073756e-01 -2.75799930e-01 1.74523201e-02 9.60121870e-01 -2.79089034e-01 1.74523201e-02 9.59175766e-01 -2.82329112e-01 1.74523201e-02 9.58165944e-01 -2.85745144e-01 1.74523201e-02 9.57125902e-01 -2.89198518e-01 1.74523201e-02 9.56104815e-01 -2.92562336e-01 1.74523201e-02 9.55104172e-01 -2.95812190e-01 1.74523201e-02 9.54109848e-01 -2.99002320e-01 1.74523201e-02 9.53051448e-01 -3.02359521e-01 1.74523201e-02 9.51970220e-01 -3.05749476e-01 1.74523201e-02 9.50868428e-01 -3.09155971e-01 1.74523201e-02 9.49784100e-01 -3.12469035e-01 1.74523201e-02 9.48701799e-01 -3.15742552e-01 1.74523201e-02 9.47624385e-01 -3.18962038e-01 1.74523201e-02 9.46514070e-01 -3.22242469e-01 1.74523201e-02 9.45359051e-01 -3.25617939e-01 1.74523201e-02 9.44207370e-01 -3.28933716e-01 1.74523201e-02 9.43062425e-01 -3.32208633e-01 1.74523201e-02 9.41899180e-01 -3.35494608e-01 1.74523201e-02 9.40723121e-01 -3.38776559e-01 1.74523201e-02 9.39531147e-01 -3.42070967e-01 1.74523201e-02 9.38329339e-01 -3.45335871e-01 1.74523201e-02 9.37103927e-01 -3.48630309e-01 1.74523201e-02 9.35921311e-01 -3.51798385e-01 1.74523201e-02 9.34673429e-01 -3.55112880e-01 1.74523201e-02 9.33415473e-01 -3.58434111e-01 1.74523201e-02 9.32139397e-01 -3.61710280e-01 1.74523201e-02 9.30879712e-01 -3.64959389e-01 1.74523201e-02 9.29599762e-01 -3.68200302e-01 1.74523201e-02 9.28318381e-01 -3.71421635e-01 1.74523201e-02 9.27006125e-01 -3.74681860e-01 1.74523201e-02 9.25742686e-01 -3.77793193e-01 1.74523201e-02 9.24378395e-01 -3.81118596e-01 1.74523201e-02 9.23038602e-01 -3.84350061e-01 1.74523201e-02 9.21692193e-01 -3.87571126e-01 1.74523201e-02 9.20286715e-01 -3.90891075e-01 1.74523201e-02 9.18948233e-01 -3.94026190e-01 1.74523201e-02 9.17627811e-01 -3.97095978e-01 1.74523201e-02 9.16195869e-01 -4.00394261e-01 1.74523201e-02 9.14752543e-01 -4.03678298e-01 1.74523201e-02 9.13344026e-01 -4.06854540e-01 1.74523201e-02 9.11928713e-01 -4.10018057e-01 1.74523201e-02 9.10540521e-01 -4.13086653e-01 1.74523201e-02 9.09105122e-01 -4.16234285e-01 1.74523201e-02 9.07612562e-01 -4.19483155e-01 1.74523201e-02 9.06098962e-01 -4.22743469e-01 1.74523201e-02 9.04615164e-01 -4.25906330e-01 1.74523201e-02 9.03155208e-01 -4.28996772e-01 1.74523201e-02 9.01685536e-01 -4.32074577e-01 1.74523201e-02 9.00172770e-01 -4.35225695e-01 1.74523201e-02 8.98606479e-01 -4.38451350e-01 1.74523201e-02 8.97057712e-01 -4.41605330e-01 1.74523201e-02 8.95515501e-01 -4.44726735e-01 1.74523201e-02 8.93970668e-01 -4.47820932e-01 1.74523201e-02 8.92456293e-01 -4.50835645e-01 1.74523201e-02 8.90886188e-01 -4.53928649e-01 1.74523201e-02 8.89245272e-01 -4.57137048e-01 1.74523201e-02 8.87628257e-01 -4.60260659e-01 1.74523201e-02 8.86055946e-01 -4.63290006e-01 1.74523201e-02 8.84445608e-01 -4.66352433e-01 1.74523201e-02 8.82759213e-01 -4.69540119e-01 1.74523201e-02 8.81114244e-01 -4.72616464e-01 1.74523201e-02 8.79477024e-01 -4.75658000e-01 1.74523201e-02 8.77792895e-01 -4.78761733e-01 1.74523201e-02 8.76177967e-01 -4.81704533e-01 1.74523201e-02 8.74473631e-01 -4.84789133e-01 1.74523201e-02 8.72731686e-01 -4.87922102e-01 1.74523201e-02 8.71025503e-01 -4.90960926e-01 1.74523201e-02 8.69324565e-01 -4.93965715e-01 1.74523201e-02 8.67584765e-01 -4.97019291e-01 1.74523201e-02 8.65861535e-01 -5.00014365e-01 1.74523201e-02 8.64064097e-01 -5.03113151e-01 1.74523201e-02 8.62349212e-01 -5.06046593e-01 1.74523201e-02 8.60606372e-01 -5.09003758e-01 1.74523201e-02 8.58827472e-01 -5.11998475e-01 1.74523201e-02 8.56994271e-01 -5.15064776e-01 1.74523201e-02 8.55125785e-01 -5.18157244e-01 1.74523201e-02 8.53355944e-01 -5.21069050e-01 1.74523201e-02 8.51591945e-01 -5.23945034e-01 1.74523201e-02 8.49754155e-01 -5.26923895e-01 1.74523201e-02 8.47862959e-01 -5.29962540e-01 1.74523201e-02 8.45952630e-01 -5.33004045e-01 1.74523201e-02 8.44100833e-01 -5.35930097e-01 1.74523201e-02 8.42291474e-01 -5.38768589e-01 1.74523201e-02 8.40391695e-01 -5.41729987e-01 1.74523201e-02 8.38440895e-01 -5.44743180e-01 1.74523201e-02 8.36526990e-01 -5.47675192e-01 1.74523201e-02 8.34611654e-01 -5.50591946e-01 1.74523201e-02 8.32737505e-01 -5.53416073e-01 1.74523201e-02 8.30861688e-01 -5.56234598e-01 1.74523201e-02 8.28918278e-01 -5.59127986e-01 1.74523201e-02 8.26884568e-01 -5.62129915e-01 1.74523201e-02 8.24891508e-01 -5.65050006e-01 1.74523201e-02 8.22913587e-01 -5.67929208e-01 1.74523201e-02 8.20971251e-01 -5.70729375e-01 1.74523201e-02 8.18973243e-01 -5.73593140e-01 1.74523201e-02 8.16969275e-01 -5.76447010e-01 1.74523201e-02 8.14953923e-01 -5.79291463e-01 1.74523201e-02 8.12917888e-01 -5.82145751e-01 1.74523201e-02 8.10931802e-01 -5.84904909e-01 1.74523201e-02 8.08861852e-01 -5.87768793e-01 1.74523201e-02 8.06823671e-01 -5.90560794e-01 1.74523201e-02 8.04713428e-01 -5.93435168e-01 1.74523201e-02 8.02583456e-01 -5.96312344e-01 1.74523201e-02 8.00550759e-01 -5.99034905e-01 1.74523201e-02 7.98466444e-01 -6.01816475e-01 1.74523201e-02 7.96338499e-01 -6.04627609e-01 1.74523201e-02 7.94260204e-01 -6.07356071e-01 1.74523201e-02 7.92137384e-01 -6.10119045e-01 1.74523201e-02 7.90035248e-01 -6.12840056e-01 1.74523201e-02 7.87842453e-01 -6.15655899e-01 1.74523201e-02 7.85636842e-01 -6.18469119e-01 1.74523201e-02 7.83509374e-01 -6.21159911e-01 1.74523201e-02 7.81395435e-01 -6.23820126e-01 1.74523201e-02 7.79229045e-01 -6.26523137e-01 1.74523201e-02 7.76976585e-01 -6.29317582e-01 1.74523201e-02 7.74751067e-01 -6.32048428e-01 1.74523201e-02 7.72614717e-01 -6.34660721e-01 1.74523201e-02 7.70390868e-01 -6.37358546e-01 1.74523201e-02 7.68180609e-01 -6.40022933e-01 1.74523201e-02 7.65938163e-01 -6.42703414e-01 1.74523201e-02 7.63612747e-01 -6.45464182e-01 1.74523201e-02 7.61345983e-01 -6.48135185e-01 1.74523201e-02 7.59162903e-01 -6.50691271e-01 1.74523201e-02 7.56884038e-01 -6.53342783e-01 1.74523201e-02 7.54575372e-01 -6.56007707e-01 1.74523201e-02 7.52222538e-01 -6.58703148e-01 1.74523201e-02 7.49868691e-01 -6.61380768e-01 1.74523201e-02 7.47606337e-01 -6.63935959e-01 1.74523201e-02 7.45344937e-01 -6.66477203e-01 1.74523201e-02 7.42958367e-01 -6.69137001e-01 1.74523201e-02 7.40633607e-01 -6.71709180e-01 1.74523201e-02 7.38286555e-01 -6.74286842e-01 1.74523201e-02 7.35915780e-01 -6.76873267e-01 1.74523201e-02 7.33628273e-01 -6.79351270e-01 1.74523201e-02 7.31250048e-01 -6.81908906e-01 1.74523201e-02 7.28799701e-01 -6.84527516e-01 1.74523201e-02 7.26399899e-01 -6.87072456e-01 1.74523201e-02 7.24008083e-01 -6.89599752e-01 1.74523201e-02 7.21585274e-01 -6.92123234e-01 1.74523201e-02 7.19188869e-01 -6.94627583e-01 1.74523201e-02 7.16743052e-01 -6.97146297e-01 1.74523201e-02 7.14368761e-01 -6.99576735e-01 1.74523201e-02 7.11866021e-01 -7.02125788e-01 1.74523201e-02 7.09376395e-01 -7.04636812e-01 1.74523275e-02 7.06925333e-01 -7.07085252e-01 1.74523257e-02 7.04395771e-01 -7.09611237e-01 1.74523313e-02 7.01997697e-01 -7.11983204e-01 1.74523313e-02 6.99584544e-01 -7.14349329e-01 1.74523313e-02 6.97082400e-01 -7.16784120e-01 1.74523424e-02 6.94580793e-01 -7.19200790e-01 1.74523611e-02 6.92143977e-01 -7.21548200e-01 1.74524002e-02 6.89665020e-01 -7.23917246e-01 1.74524058e-02 6.87192142e-01 -7.26265073e-01 1.74524076e-02 6.84881747e-01 -7.28444457e-01 1.74524039e-02 6.83169782e-01 -7.30050981e-01 1.74524039e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.55703282e-01 -8.31197500e-01 1.74524076e-02 5.52587569e-01 -8.33271384e-01 1.74524132e-02 5.50095081e-01 -8.34919214e-01 1.74523462e-02 5.47376633e-01 -8.36716473e-01 1.74523313e-02 5.44442236e-01 -8.38634014e-01 1.74523219e-02 5.41512907e-01 -8.40526998e-01 1.74523257e-02 5.38650334e-01 -8.42366159e-01 1.74523201e-02 5.35702705e-01 -8.44243586e-01 1.74523201e-02 5.32746911e-01 -8.46113920e-01 1.74523201e-02 5.29805362e-01 -8.47956955e-01 1.74523201e-02 5.26849389e-01 -8.49797368e-01 1.74523201e-02 5.24002373e-01 -8.51547956e-01 1.74523313e-02 5.21193087e-01 -8.53257895e-01 1.74523611e-02 5.18103182e-01 -8.55139256e-01 1.74524151e-02 5.14953613e-01 -8.57039630e-01 1.74524132e-02 5.12090445e-01 -8.58753681e-01 1.74524095e-02 5.08939862e-01 -8.60624552e-01 1.74524076e-02 5.05504906e-01 -8.62646759e-01 1.74524058e-02 5.02846122e-01 -8.64199102e-01 1.74524058e-02 4.99860078e-01 -8.65929425e-01 1.74524095e-02 4.96436507e-01 -8.67897153e-01 1.74524095e-02 4.93690431e-01 -8.69461954e-01 1.74524076e-02 4.90676731e-01 -8.71166170e-01 1.74524076e-02 4.87640917e-01 -8.72869015e-01 1.74524132e-02 4.84423697e-01 -8.74658942e-01 1.74524002e-02 4.81579006e-01 -8.76232624e-01 1.74523313e-02 4.78576332e-01 -8.77885520e-01 1.74523313e-02 4.75532502e-01 -8.79540205e-01 1.74523257e-02 4.72478002e-01 -8.81187081e-01 1.74523201e-02 4.69419152e-01 -8.82822156e-01 1.74523201e-02 4.66316015e-01 -8.84466171e-01 1.74523201e-02 4.63177770e-01 -8.86113465e-01 1.74523201e-02 4.60072696e-01 -8.87726665e-01 1.74523201e-02 4.57035005e-01 -8.89297366e-01 1.74523201e-02 4.53923523e-01 -8.90887618e-01 1.74523201e-02 4.50803041e-01 -8.92472029e-01 1.74523201e-02 4.47670162e-01 -8.94047320e-01 1.74523201e-02 4.44571763e-01 -8.95591080e-01 1.74523201e-02 4.41463202e-01 -8.97128761e-01 1.74523201e-02 4.38301235e-01 -8.98678243e-01 1.74523201e-02 4.35177505e-01 -9.00195181e-01 1.74523201e-02 4.32003975e-01 -9.01720047e-01 1.74523201e-02 4.28806633e-01 -9.03246164e-01 1.74523201e-02 4.25638944e-01 -9.04741704e-01 1.74523201e-02 4.22448605e-01 -9.06238854e-01 1.74523201e-02 4.19257045e-01 -9.07716691e-01 1.74523201e-02 4.16202962e-01 -9.09120858e-01 1.74523201e-02 4.13022399e-01 -9.10572410e-01 1.74523201e-02 4.09856766e-01 -9.12001431e-01 1.74523201e-02 4.06555384e-01 -9.13479269e-01 1.74523201e-02 4.03350830e-01 -9.14896607e-01 1.74523201e-02 4.00270581e-01 -9.16250765e-01 1.74523201e-02 3.97071064e-01 -9.17639613e-01 1.74523201e-02 3.93854439e-01 -9.19021845e-01 1.74523201e-02 3.90576959e-01 -9.20423388e-01 1.74523201e-02 3.87395173e-01 -9.21766937e-01 1.74523201e-02 3.84099543e-01 -9.23145294e-01 1.74523201e-02 3.80855411e-01 -9.24485385e-01 1.74523201e-02 3.77767026e-01 -9.25755024e-01 1.74523201e-02 3.74489605e-01 -9.27084804e-01 1.74523201e-02 3.71149004e-01 -9.28427339e-01 1.74523201e-02 3.67871612e-01 -9.29732144e-01 1.74523201e-02 3.64679605e-01 -9.30987537e-01 1.74523201e-02 3.61529619e-01 -9.32210207e-01 1.74523201e-02 3.58269602e-01 -9.33477700e-01 1.74523201e-02 3.55012506e-01 -9.34712648e-01 1.74523201e-02 3.51759285e-01 -9.35937583e-01 1.74523201e-02 3.48468065e-01 -9.37166691e-01 1.74523201e-02 3.45203996e-01 -9.38377321e-01 1.74523201e-02 3.41934294e-01 -9.39581335e-01 1.74523201e-02 3.38671088e-01 -9.40759361e-01 1.74523201e-02 3.35365415e-01 -9.41945553e-01 1.74523201e-02 3.32013756e-01 -9.43130732e-01 1.74523201e-02 3.28690469e-01 -9.44292665e-01 1.74523201e-02 3.25417280e-01 -9.45428610e-01 1.74523201e-02 3.22080791e-01 -9.46567655e-01 1.74523201e-02 3.18863362e-01 -9.47658777e-01 1.74523201e-02 3.15460861e-01 -9.48795199e-01 1.74523201e-02 3.12142462e-01 -9.49890256e-01 1.74523201e-02 3.08834672e-01 -9.50973153e-01 1.74523201e-02 3.05495083e-01 -9.52052474e-01 1.74523201e-02 3.02258581e-01 -9.53083456e-01 1.74523201e-02 2.98949420e-01 -9.54127312e-01 1.74523201e-02 2.95600414e-01 -9.55169916e-01 1.74523201e-02 2.92275488e-01 -9.56193209e-01 1.74523201e-02 2.88848728e-01 -9.57232177e-01 1.74523201e-02 2.85412610e-01 -9.58262861e-01 1.74523201e-02 2.82167286e-01 -9.59225237e-01 1.74523201e-02 2.78818935e-01 -9.60204065e-01 1.74523201e-02 2.75376946e-01 -9.61195946e-01 1.74523201e-02 2.72021413e-01 -9.62150276e-01 1.74523201e-02 2.68748581e-01 -9.63070989e-01 1.74523201e-02 2.65467227e-01 -9.63978410e-01 1.74523201e-02 2.62101740e-01 -9.64901984e-01 1.74523201e-02 2.58717656e-01 -9.65812087e-01 1.74523201e-02 2.55375296e-01 -9.66701806e-01 1.74523201e-02 2.52004981e-01 -9.67588544e-01 1.74523201e-02 2.48538896e-01 -9.68482912e-01 1.74523201e-02 2.45153069e-01 -9.69343305e-01 1.74523201e-02 2.41789699e-01 -9.70188618e-01 1.74523201e-02 2.38381818e-01 -9.71032619e-01 1.74523201e-02 2.35066190e-01 -9.71841514e-01 1.74523201e-02 2.31588364e-01 -9.72677886e-01 1.74523201e-02 2.28190511e-01 -9.73477125e-01 1.74523201e-02 2.24810809e-01 -9.74263966e-01 1.74523201e-02 2.21320242e-01 -9.75061715e-01 1.74523201e-02 2.18006298e-01 -9.75808501e-01 1.74523201e-02 2.14686915e-01 -9.76543307e-01 1.74523201e-02 2.11297527e-01 -9.77282882e-01 1.74523201e-02 2.07877353e-01 -9.78016019e-01 1.74523201e-02 2.04359397e-01 -9.78759766e-01 1.74523201e-02 2.00910047e-01 -9.79471624e-01 1.74523201e-02 1.97602242e-01 -9.80144620e-01 1.74523201e-02 1.94195643e-01 -9.80824769e-01 1.74523201e-02 1.90756053e-01 -9.81500328e-01 1.74523201e-02 1.87240139e-01 -9.82176602e-01 1.74523201e-02 1.83792397e-01 -9.82826352e-01 1.74523201e-02 1.80370674e-01 -9.83459830e-01 1.74523201e-02 1.76910594e-01 -9.84094203e-01 1.74523201e-02 1.73581228e-01 -9.84686315e-01 1.74523201e-02 1.70143709e-01 -9.85280097e-01 1.74523201e-02 1.66687295e-01 -9.85872805e-01 1.74523201e-02 1.63164079e-01 -9.86461580e-01 1.74523201e-02 1.59712821e-01 -9.87025559e-01 1.74523201e-02 1.56370029e-01 -9.87562239e-01 1.74523201e-02 1.52925715e-01 -9.88100946e-01 1.74523201e-02 1.49463460e-01 -9.88629222e-01 1.74523201e-02 1.45928204e-01 -9.89158928e-01 1.74523201e-02 1.42463371e-01 -9.89662230e-01 1.74523201e-02 1.39014378e-01 -9.90155578e-01 1.74523201e-02 1.35453269e-01 -9.90648746e-01 1.74523201e-02 1.32078320e-01 -9.91100490e-01 1.74523201e-02 1.28740445e-01 -9.91541862e-01 1.74523201e-02 1.25272125e-01 -9.91987169e-01 1.74523201e-02 1.21823967e-01 -9.92415786e-01 1.74523201e-02 1.18255474e-01 -9.92847323e-01 1.74523201e-02 1.14766777e-01 -9.93254542e-01 1.74523201e-02 1.11426868e-01 -9.93636191e-01 1.74523201e-02 1.07951701e-01 -9.94019032e-01 1.74523201e-02 1.04497515e-01 -9.94388461e-01 1.74523201e-02 1.00911841e-01 -9.94758129e-01 1.74523201e-02 9.74245891e-02 -9.95106339e-01 1.74523201e-02 9.39807445e-02 -9.95439947e-01 1.74523201e-02 9.05017257e-02 -9.95758832e-01 1.74523201e-02 8.70215297e-02 -9.96071756e-01 1.74523201e-02 8.34305733e-02 -9.96377051e-01 1.74523201e-02 8.00201967e-02 -9.96657550e-01 1.74523201e-02 7.65741691e-02 -9.96928930e-01 1.74523201e-02 7.30677769e-02 -9.97190118e-01 1.74523201e-02 6.96878135e-02 -9.97431338e-01 1.74523201e-02 6.62283152e-02 -9.97668564e-01 1.74523201e-02 6.27479553e-02 -9.97893095e-01 1.74523201e-02 5.91537841e-02 -9.98112977e-01 1.74523201e-02 5.56725711e-02 -9.98313427e-01 1.74523201e-02 5.22106364e-02 -9.98500347e-01 1.74523201e-02 4.87053469e-02 -9.98677492e-01 1.74523201e-02 4.52377051e-02 -9.98840809e-01 1.74523201e-02 4.16402332e-02 -9.98997629e-01 1.74523201e-02 3.82339396e-02 -9.99131620e-01 1.74523201e-02 3.48614343e-02 -9.99255776e-01 1.74523201e-02 3.12893763e-02 -9.99374211e-01 1.74523201e-02 2.77726855e-02 -9.99478817e-01 1.74523201e-02 2.43022572e-02 -9.99572217e-01 1.74523201e-02 2.08012611e-02 -9.99644876e-01 1.74523201e-02 1.73889566e-02 -9.99717414e-01 1.74523201e-02 1.38494344e-02 -9.99762833e-01 1.74523201e-02 1.03297802e-02 -9.99810696e-01 1.74523201e-02 6.92219380e-03 -9.99846816e-01 1.74523201e-02 3.43950628e-03 -9.99863684e-01 1.74523201e-02 -3.28057831e-05 -9.99865174e-01 1.74523201e-02 -3.49951349e-03 -9.99863982e-01 1.74523201e-02 -7.00816838e-03 -9.99847054e-01 1.74523201e-02 -1.05853947e-02 -9.99810874e-01 1.74523201e-02 -1.40817687e-02 -9.99760091e-01 1.74523201e-02 -1.75637212e-02 -9.99716818e-01 1.74523201e-02 -2.11640261e-02 -9.99638379e-01 1.74523201e-02 -2.45622620e-02 -9.99563873e-01 1.74523201e-02 -2.79408600e-02 -9.99475002e-01 1.74523201e-02 -3.14180739e-02 -9.99371290e-01 1.74523201e-02 -3.50022055e-02 -9.99252796e-01 1.74523201e-02 -3.86175849e-02 -9.99119699e-01 1.74523201e-02 -4.20041829e-02 -9.98982430e-01 1.74523201e-02 -4.53815944e-02 -9.98833954e-01 1.74523201e-02 -4.88912947e-02 -9.98669326e-01 1.74523201e-02 -5.23609295e-02 -9.98490989e-01 1.74523201e-02 -5.59260845e-02 -9.98300552e-01 1.74523201e-02 -5.94288893e-02 -9.98096645e-01 1.74523201e-02 -6.28928244e-02 -9.97884333e-01 1.74523201e-02 -6.63939342e-02 -9.97656047e-01 1.74523201e-02 -6.97880238e-02 -9.97423768e-01 1.74523201e-02 -7.33482093e-02 -9.97170508e-01 1.74523201e-02 -7.68526867e-02 -9.96905625e-01 1.74523201e-02 -8.03053007e-02 -9.96635377e-01 1.74523201e-02 -8.37924182e-02 -9.96346116e-01 1.74523201e-02 -8.71865973e-02 -9.96056080e-01 1.74523201e-02 -9.06651989e-02 -9.95744646e-01 1.74523201e-02 -9.41409320e-02 -9.95423436e-01 1.74523201e-02 -9.76927057e-02 -9.95082378e-01 1.74523201e-02 -1.01164974e-01 -9.94733989e-01 1.74523201e-02 -1.04615115e-01 -9.94377315e-01 1.74523201e-02 -1.08171366e-01 -9.93995070e-01 1.74523201e-02 -1.11570843e-01 -9.93620157e-01 1.74523201e-02 -1.14955790e-01 -9.93234098e-01 1.74523201e-02 -1.18404716e-01 -9.92827833e-01 1.74523201e-02 -1.21876255e-01 -9.92408037e-01 1.74523201e-02 -1.25418991e-01 -9.91970181e-01 1.74523201e-02 -1.28909439e-01 -9.91518378e-01 1.74523201e-02 -1.32265434e-01 -9.91078436e-01 1.74523201e-02 -1.35727987e-01 -9.90609169e-01 1.74523201e-02 -1.39180765e-01 -9.90131259e-01 1.74523201e-02 -1.42722726e-01 -9.89627302e-01 1.74523201e-02 -1.46182597e-01 -9.89119232e-01 1.74523201e-02 -1.49616525e-01 -9.88606274e-01 1.74523201e-02 -1.53058141e-01 -9.88079906e-01 1.74523201e-02 -1.56417072e-01 -9.87553120e-01 1.74523201e-02 -1.59864545e-01 -9.87001538e-01 1.74523201e-02 -1.63308293e-01 -9.86438870e-01 1.74523201e-02 -1.66859284e-01 -9.85844195e-01 1.74523201e-02 -1.70299724e-01 -9.85252798e-01 1.74523201e-02 -1.73637792e-01 -9.84676003e-01 1.74523201e-02 -1.77082673e-01 -9.84060943e-01 1.74523201e-02 -1.80520356e-01 -9.83431220e-01 1.74523201e-02 -1.84036523e-01 -9.82784212e-01 1.74523201e-02 -1.87466308e-01 -9.82132673e-01 1.74523201e-02 -1.90805659e-01 -9.81488168e-01 1.74523201e-02 -1.94216698e-01 -9.80821073e-01 1.74523201e-02 -1.97725609e-01 -9.80120838e-01 1.74523201e-02 -2.01159120e-01 -9.79419351e-01 1.74523201e-02 -2.04470873e-01 -9.78734255e-01 1.74523201e-02 -2.07917228e-01 -9.78008628e-01 1.74523201e-02 -2.11393237e-01 -9.77263570e-01 1.74523201e-02 -2.14819372e-01 -9.76512432e-01 1.74523201e-02 -2.18133137e-01 -9.75781500e-01 1.74523201e-02 -2.21545070e-01 -9.75011528e-01 1.74523201e-02 -2.24961504e-01 -9.74227548e-01 1.74523201e-02 -2.28450134e-01 -9.73420382e-01 1.74523201e-02 -2.31862098e-01 -9.72610295e-01 1.74523201e-02 -2.35137746e-01 -9.71824527e-01 1.74523201e-02 -2.38536313e-01 -9.70994830e-01 1.74523201e-02 -2.41934076e-01 -9.70152378e-01 1.74523201e-02 -2.45357513e-01 -9.69292104e-01 1.74523201e-02 -2.48782367e-01 -9.68419790e-01 1.74523201e-02 -2.52181858e-01 -9.67540145e-01 1.74523201e-02 -2.55558938e-01 -9.66654301e-01 1.74523201e-02 -2.58904189e-01 -9.65764165e-01 1.74523201e-02 -2.62367159e-01 -9.64829504e-01 1.74523201e-02 -2.65667289e-01 -9.63923395e-01 1.74523201e-02 -2.69022137e-01 -9.62994754e-01 1.74523201e-02 -2.72385478e-01 -9.62047279e-01 1.74523201e-02 -2.75639206e-01 -9.61120307e-01 1.74523201e-02 -2.78990209e-01 -9.60153520e-01 1.74523201e-02 -2.82336503e-01 -9.59174156e-01 1.74523201e-02 -2.85668164e-01 -9.58188832e-01 1.74523201e-02 -2.89017200e-01 -9.57181454e-01 1.74523201e-02 -2.92378575e-01 -9.56159234e-01 1.74523201e-02 -2.95776814e-01 -9.55117285e-01 1.74523201e-02 -2.99119413e-01 -9.54072297e-01 1.74523201e-02 -3.02457213e-01 -9.53022420e-01 1.74523201e-02 -3.05780321e-01 -9.51960683e-01 1.74523201e-02 -3.09012383e-01 -9.50915694e-01 1.74523201e-02 -3.12430084e-01 -9.49799299e-01 1.74523201e-02 -3.15727741e-01 -9.48707104e-01 1.74523201e-02 -3.19031090e-01 -9.47604001e-01 1.74523201e-02 -3.22348058e-01 -9.46477473e-01 1.74523201e-02 -3.25560302e-01 -9.45378721e-01 1.74523201e-02 -3.28920364e-01 -9.44213629e-01 1.74523201e-02 -3.32214653e-01 -9.43061769e-01 1.74523201e-02 -3.35516810e-01 -9.41891372e-01 1.74523201e-02 -3.38816017e-01 -9.40707147e-01 1.74523201e-02 -3.42086852e-01 -9.39527810e-01 1.74523201e-02 -3.45376194e-01 -9.38313544e-01 1.74523201e-02 -3.48554522e-01 -9.37134802e-01 1.74523201e-02 -3.51884902e-01 -9.35891986e-01 1.74523201e-02 -3.55154604e-01 -9.34658349e-01 1.74523201e-02 -3.58421117e-01 -9.33420181e-01 1.74523201e-02 -3.61766368e-01 -9.32120442e-01 1.74523201e-02 -3.64929795e-01 -9.30889428e-01 1.74523201e-02 -3.68089169e-01 -9.29645896e-01 1.74523201e-02 -3.71335059e-01 -9.28352118e-01 1.74523201e-02 -3.74585569e-01 -9.27046120e-01 1.74523201e-02 -3.77885073e-01 -9.25706267e-01 1.74523201e-02 -3.81140172e-01 -9.24367189e-01 1.74523201e-02 -3.84286642e-01 -9.23067629e-01 1.74523201e-02 -3.87479395e-01 -9.21731055e-01 1.74523201e-02 -3.90687764e-01 -9.20374751e-01 1.74523201e-02 -3.93990725e-01 -9.18965280e-01 1.74523201e-02 -3.97193134e-01 -9.17585194e-01 1.74523201e-02 -4.00396436e-01 -9.16196823e-01 1.74523201e-02 -4.03608352e-01 -9.14783061e-01 1.74523201e-02 -4.06719148e-01 -9.13405478e-01 1.74523201e-02 -4.09979194e-01 -9.11948383e-01 1.74523201e-02 -4.13166672e-01 -9.10505474e-01 1.74523201e-02 -4.16311175e-01 -9.09071028e-01 1.74523201e-02 -4.19482023e-01 -9.07612205e-01 1.74523201e-02 -4.22571272e-01 -9.06179667e-01 1.74523201e-02 -4.25747544e-01 -9.04691398e-01 1.74523201e-02 -4.28990453e-01 -9.03160453e-01 1.74523201e-02 -4.32127476e-01 -9.01660264e-01 1.74523201e-02 -4.35192257e-01 -9.00190353e-01 1.74523201e-02 -4.38409954e-01 -8.98627281e-01 1.74523201e-02 -4.41641927e-01 -8.97039950e-01 1.74523201e-02 -4.44691002e-01 -8.95532668e-01 1.74523201e-02 -4.47728127e-01 -8.94019008e-01 1.74523201e-02 -4.50844049e-01 -8.92452180e-01 1.74523201e-02 -4.53968793e-01 -8.90865743e-01 1.74523201e-02 -4.57134962e-01 -8.89245272e-01 1.74523201e-02 -4.60243255e-01 -8.87638330e-01 1.74523201e-02 -4.63240296e-01 -8.86081636e-01 1.74523201e-02 -4.66352046e-01 -8.84447575e-01 1.74523201e-02 -4.69426811e-01 -8.82818043e-01 1.74523201e-02 -4.72587824e-01 -8.81131947e-01 1.74523201e-02 -4.75668490e-01 -8.79469633e-01 1.74523201e-02 -4.78712618e-01 -8.77820134e-01 1.74523201e-02 -4.81795758e-01 -8.76128733e-01 1.74523201e-02 -4.84835893e-01 -8.74449193e-01 1.74523201e-02 -4.87954646e-01 -8.72712791e-01 1.74523201e-02 -4.90929663e-01 -8.71044695e-01 1.74523201e-02 -4.93961960e-01 -8.69328320e-01 1.74523201e-02 -4.96984750e-01 -8.67604911e-01 1.74523201e-02 -4.99944478e-01 -8.65901232e-01 1.74523201e-02 -5.03044605e-01 -8.64104867e-01 1.74523201e-02 -5.06072521e-01 -8.62334967e-01 1.74523201e-02 -5.09066761e-01 -8.60571027e-01 1.74523201e-02 -5.12065768e-01 -8.58787239e-01 1.74523201e-02 -5.15037179e-01 -8.57010365e-01 1.74523201e-02 -5.18052697e-01 -8.55189085e-01 1.74523201e-02 -5.21024227e-01 -8.53385448e-01 1.74523201e-02 -5.24084032e-01 -8.51507425e-01 1.74523201e-02 -5.26990771e-01 -8.49711955e-01 1.74523201e-02 -5.29846966e-01 -8.47934127e-01 1.74523201e-02 -5.32889366e-01 -8.46024811e-01 1.74523201e-02 -5.35920918e-01 -8.44107866e-01 1.74523201e-02 -5.38869083e-01 -8.42228115e-01 1.74523201e-02 -5.41725099e-01 -8.40393901e-01 1.74523201e-02 -5.44589579e-01 -8.38541627e-01 1.74523201e-02 -5.47521770e-01 -8.36628079e-01 1.74523201e-02 -5.50423980e-01 -8.34724665e-01 1.74523201e-02 -5.53328216e-01 -8.32798362e-01 1.74523201e-02 -5.56213200e-01 -8.30876589e-01 1.74523201e-02 -5.59188843e-01 -8.28879178e-01 1.74523201e-02 -5.62139452e-01 -8.26877534e-01 1.74523201e-02 -5.64932644e-01 -8.24974298e-01 1.74523201e-02 -5.67852259e-01 -8.22967291e-01 1.74523201e-02 -5.70724189e-01 -8.20977569e-01 1.74523201e-02 -5.73589027e-01 -8.18977773e-01 1.74523201e-02 -5.76529205e-01 -8.16911936e-01 1.74523201e-02 -5.79298019e-01 -8.14949095e-01 1.74523201e-02 -5.82116187e-01 -8.12940061e-01 1.74523201e-02 -5.84931791e-01 -8.10911059e-01 1.74523201e-02 -5.87763906e-01 -8.08867276e-01 1.74523201e-02 -5.90678871e-01 -8.06738377e-01 1.74523201e-02 -5.93504846e-01 -8.04661691e-01 1.74523201e-02 -5.96241057e-01 -8.02635550e-01 1.74523201e-02 -5.98947108e-01 -8.00618649e-01 1.74523201e-02 -6.01744831e-01 -7.98518062e-01 1.74523201e-02 -6.04592323e-01 -7.96366394e-01 1.74523201e-02 -6.07389212e-01 -7.94233501e-01 1.74523201e-02 -6.10155046e-01 -7.92110980e-01 1.74523201e-02 -6.12930298e-01 -7.89964736e-01 1.74523201e-02 -6.15596354e-01 -7.87889719e-01 1.74523201e-02 -6.18427813e-01 -7.85672367e-01 1.74523201e-02 -6.21170759e-01 -7.83500671e-01 1.74523201e-02 -6.23888373e-01 -7.81342506e-01 1.74523201e-02 -6.26627326e-01 -7.79144645e-01 1.74523201e-02 -6.29271805e-01 -7.77012706e-01 1.74523201e-02 -6.32038236e-01 -7.74762869e-01 1.74523201e-02 -6.34760559e-01 -7.72533476e-01 1.74523201e-02 -6.37371600e-01 -7.70380855e-01 1.74523201e-02 -6.40053630e-01 -7.68155038e-01 1.74523201e-02 -6.42767906e-01 -7.65883863e-01 1.74523201e-02 -6.45529330e-01 -7.63558507e-01 1.74523201e-02 -6.48146033e-01 -7.61336505e-01 1.74523201e-02 -6.50717974e-01 -7.59140670e-01 1.74523201e-02 -6.53365910e-01 -7.56865323e-01 1.74523201e-02 -6.56063199e-01 -7.54527628e-01 1.74523201e-02 -6.58757746e-01 -7.52174199e-01 1.74523201e-02 -6.61330223e-01 -7.49913275e-01 1.74523201e-02 -6.63855553e-01 -7.47680783e-01 1.74523201e-02 -6.66467845e-01 -7.45351374e-01 1.74523201e-02 -6.69062912e-01 -7.43023217e-01 1.74523201e-02 -6.71719909e-01 -7.40624845e-01 1.74523201e-02 -6.74325466e-01 -7.38248110e-01 1.74523201e-02 -6.76871538e-01 -7.35920310e-01 1.74523201e-02 -6.79429889e-01 -7.33554900e-01 1.74523201e-02 -6.81991339e-01 -7.31176019e-01 1.74523201e-02 -6.84610248e-01 -7.28721619e-01 1.74523201e-02 -6.87081397e-01 -7.26391673e-01 1.74523201e-02 -6.89607382e-01 -7.23999739e-01 1.74523201e-02 -6.92138851e-01 -7.21569359e-01 1.74523201e-02 -6.94601119e-01 -7.19215393e-01 1.74523201e-02 -6.97127223e-01 -7.16766953e-01 1.74523201e-02 -6.99629843e-01 -7.14318335e-01 1.74523201e-02 -7.02083230e-01 -7.11910903e-01 1.74523201e-02 -7.04555333e-01 -7.09466755e-01 1.74523201e-02 -7.07068086e-01 -7.06942260e-01 1.74523201e-02 -7.09550321e-01 -7.04470456e-01 1.74523201e-02 -7.12014079e-01 -7.01978743e-01 1.74523201e-02 -7.14467645e-01 -6.99477017e-01 1.74523201e-02 -7.16836035e-01 -6.97053909e-01 1.74523201e-02 -7.19288528e-01 -6.94526911e-01 1.74523201e-02 -7.21755683e-01 -6.91946268e-01 1.74523201e-02 -7.24182010e-01 -6.89415157e-01 1.74523201e-02 -7.26578891e-01 -6.86884165e-01 1.74523201e-02 -7.28953362e-01 -6.84361100e-01 1.74523201e-02 -7.31242418e-01 -6.81916535e-01 1.74523201e-02 -7.33676434e-01 -6.79302216e-01 1.74523201e-02 -7.36125350e-01 -6.76648974e-01 1.74523201e-02 -7.38434196e-01 -6.74122214e-01 1.74523201e-02 -7.40706027e-01 -6.71628714e-01 1.74523201e-02 -7.43052244e-01 -6.69031143e-01 1.74523201e-02 -7.45447099e-01 -6.66363120e-01 1.74523201e-02 -7.47786403e-01 -6.63735390e-01 1.74523201e-02 -7.50080705e-01 -6.61141455e-01 1.74523201e-02 -7.52376974e-01 -6.58524752e-01 1.74523201e-02 -7.54681349e-01 -6.55886054e-01 1.74523201e-02 -7.57027328e-01 -6.53176785e-01 1.74523201e-02 -7.59246826e-01 -6.50593817e-01 1.74523201e-02 -7.61455297e-01 -6.48006916e-01 1.74523201e-02 -7.63714075e-01 -6.45347297e-01 1.74523201e-02 -7.65995383e-01 -6.42635167e-01 1.74523201e-02 -7.68300474e-01 -6.39880002e-01 1.74523201e-02 -7.70501316e-01 -6.37222886e-01 1.74523201e-02 -7.72653162e-01 -6.34618521e-01 1.74523201e-02 -7.74872601e-01 -6.31903172e-01 1.74523201e-02 -7.77075052e-01 -6.29192173e-01 1.74523201e-02 -7.79310286e-01 -6.26425326e-01 1.74523201e-02 -7.81563699e-01 -6.23608530e-01 1.74523201e-02 -7.83731163e-01 -6.20881677e-01 1.74523201e-02 -7.85827339e-01 -6.18227065e-01 1.74523201e-02 -7.87917793e-01 -6.15562320e-01 1.74523201e-02 -7.90131629e-01 -6.12717628e-01 1.74523201e-02 -7.92308092e-01 -6.09900355e-01 1.74523201e-02 -7.94433594e-01 -6.07129633e-01 1.74523201e-02 -7.96524227e-01 -6.04381144e-01 1.74523201e-02 -7.98559844e-01 -6.01693332e-01 1.74523201e-02 -8.00701857e-01 -5.98837018e-01 1.74523201e-02 -8.02792251e-01 -5.96030116e-01 1.74523201e-02 -8.04828107e-01 -5.93279541e-01 1.74523201e-02 -8.06890607e-01 -5.90470433e-01 1.74523201e-02 -8.08972836e-01 -5.87616444e-01 1.74523201e-02 -8.11060965e-01 -5.84729075e-01 1.74523201e-02 -8.13077509e-01 -5.81923366e-01 1.74523201e-02 -8.15048873e-01 -5.79158723e-01 1.74523201e-02 -8.17062974e-01 -5.76317787e-01 1.74523201e-02 -8.19090962e-01 -5.73428094e-01 1.74523201e-02 -8.21130276e-01 -5.70502996e-01 1.74523201e-02 -8.23108137e-01 -5.67647874e-01 1.74523201e-02 -8.25032473e-01 -5.64847529e-01 1.74523201e-02 -8.26976597e-01 -5.61996281e-01 1.74523201e-02 -8.28930676e-01 -5.59112072e-01 1.74523201e-02 -8.30928385e-01 -5.56137085e-01 1.74523201e-02 -8.32877994e-01 -5.53207874e-01 1.74523201e-02 -8.34806025e-01 -5.50300241e-01 1.74523201e-02 -8.36734593e-01 -5.47358036e-01 1.74523201e-02 -8.38573396e-01 -5.44538081e-01 1.74523201e-02 -8.40464771e-01 -5.41617393e-01 1.74523201e-02 -8.42397511e-01 -5.38603961e-01 1.74523201e-02 -8.44299793e-01 -5.35615802e-01 1.74523201e-02 -8.46102536e-01 -5.32768488e-01 1.74523201e-02 -8.47940624e-01 -5.29833376e-01 1.74523201e-02 -8.49805772e-01 -5.26842594e-01 1.74523201e-02 -8.51626217e-01 -5.23889422e-01 1.74523201e-02 -8.53454709e-01 -5.20910561e-01 1.74523201e-02 -8.55276167e-01 -5.17910361e-01 1.74523201e-02 -8.57117712e-01 -5.14861405e-01 1.74523201e-02 -8.58966947e-01 -5.11763871e-01 1.74523201e-02 -8.60699594e-01 -5.08843958e-01 1.74523201e-02 -8.62469435e-01 -5.05843163e-01 1.74523201e-02 -8.64227653e-01 -5.02828896e-01 1.74523201e-02 -8.65951538e-01 -4.99859780e-01 1.74523201e-02 -8.67681921e-01 -4.96846616e-01 1.74523201e-02 -8.69393170e-01 -4.93844241e-01 1.74523201e-02 -8.71102929e-01 -4.90831077e-01 1.74523201e-02 -8.72809350e-01 -4.87782210e-01 1.74523201e-02 -8.74518871e-01 -4.84708190e-01 1.74523201e-02 -8.76231074e-01 -4.81612802e-01 1.74523201e-02 -8.77938926e-01 -4.78494406e-01 1.74523201e-02 -8.79573107e-01 -4.75477785e-01 1.74523201e-02 -8.81190598e-01 -4.72474903e-01 1.74523201e-02 -8.82876754e-01 -4.69316959e-01 1.74523201e-02 -8.84556592e-01 -4.66142505e-01 1.74523201e-02 -8.86166155e-01 -4.63078141e-01 1.74523201e-02 -8.87729287e-01 -4.60068673e-01 1.74523201e-02 -8.89298558e-01 -4.57032472e-01 1.74523201e-02 -8.90921116e-01 -4.53861684e-01 1.74523201e-02 -8.92552912e-01 -4.50643629e-01 1.74523201e-02 -8.94076765e-01 -4.47608620e-01 1.74523201e-02 -8.95583868e-01 -4.44588810e-01 1.74523201e-02 -8.97124052e-01 -4.41472858e-01 1.74523201e-02 -8.98662627e-01 -4.38333362e-01 1.74523201e-02 -9.00241971e-01 -4.35082614e-01 1.74523201e-02 -9.01794970e-01 -4.31849003e-01 1.74523201e-02 -9.03271556e-01 -4.28752363e-01 1.74523201e-02 -9.04713333e-01 -4.25700247e-01 1.74523201e-02 -9.06188369e-01 -4.22554076e-01 1.74523201e-02 -9.07697976e-01 -4.19306308e-01 1.74523201e-02 -9.09181535e-01 -4.16074365e-01 1.74523201e-02 -9.10587251e-01 -4.12992120e-01 1.74523201e-02 -9.11998570e-01 -4.09862876e-01 1.74523201e-02 -9.13418531e-01 -4.06693339e-01 1.74523201e-02 -9.14889991e-01 -4.03373063e-01 1.74523201e-02 -9.16333675e-01 -4.00081784e-01 1.74523201e-02 -9.17717278e-01 -3.96896601e-01 1.74523201e-02 -9.19099212e-01 -3.93672943e-01 1.74523201e-02 -9.20432270e-01 -3.90551865e-01 1.74523201e-02 -9.21749651e-01 -3.87436837e-01 1.74523201e-02 -9.23101783e-01 -3.84201705e-01 1.74523201e-02 -9.24475133e-01 -3.80884647e-01 1.74523201e-02 -9.25798714e-01 -3.77658039e-01 1.74523201e-02 -9.27075624e-01 -3.74512374e-01 1.74523201e-02 -9.28413272e-01 -3.71183634e-01 1.74523201e-02 -9.29699123e-01 -3.67952734e-01 1.74523201e-02 -9.30947840e-01 -3.64785880e-01 1.74523201e-02 -9.32210684e-01 -3.61529350e-01 1.74523201e-02 -9.33476686e-01 -3.58271241e-01 1.74523201e-02 -9.34753478e-01 -3.54909986e-01 1.74523201e-02 -9.35973108e-01 -3.51660550e-01 1.74523201e-02 -9.37161207e-01 -3.48484069e-01 1.74523201e-02 -9.38413024e-01 -3.45114946e-01 1.74523201e-02 -9.39652026e-01 -3.41740698e-01 1.74523201e-02 -9.40829396e-01 -3.38476032e-01 1.74523201e-02 -9.41979468e-01 -3.35269570e-01 1.74523201e-02 -9.43136990e-01 -3.31998020e-01 1.74523201e-02 -9.44298983e-01 -3.28674704e-01 1.74523201e-02 -9.45405483e-01 -3.25482935e-01 1.74523201e-02 -9.46530223e-01 -3.22190195e-01 1.74523201e-02 -9.47658300e-01 -3.18863183e-01 1.74523201e-02 -9.48798835e-01 -3.15453529e-01 1.74523201e-02 -9.49890733e-01 -3.12145829e-01 1.74523201e-02 -9.50947702e-01 -3.08916211e-01 1.74523201e-02 -9.52040851e-01 -3.05529565e-01 1.74523201e-02 -9.53104198e-01 -3.02191764e-01 1.74523201e-02 -9.54146564e-01 -2.98893362e-01 1.74523201e-02 -9.55184400e-01 -2.95552790e-01 1.74523201e-02 -9.56215382e-01 -2.92203367e-01 1.74523201e-02 -9.57252741e-01 -2.88781285e-01 1.74523201e-02 -9.58231330e-01 -2.85516679e-01 1.74523201e-02 -9.59220588e-01 -2.82182962e-01 1.74523201e-02 -9.60203350e-01 -2.78818011e-01 1.74523201e-02 -9.61167812e-01 -2.75472641e-01 1.74523201e-02 -9.62121964e-01 -2.72119164e-01 1.74523201e-02 -9.63047266e-01 -2.68833876e-01 1.74523201e-02 -9.63978767e-01 -2.65471309e-01 1.74523201e-02 -9.64898765e-01 -2.62111694e-01 1.74523201e-02 -9.65829074e-01 -2.58659184e-01 1.74523201e-02 -9.66752052e-01 -2.55189955e-01 1.74523201e-02 -9.67636824e-01 -2.51808345e-01 1.74523201e-02 -9.68484581e-01 -2.48533666e-01 1.74523201e-02 -9.69313323e-01 -2.45271161e-01 1.74523201e-02 -9.70192075e-01 -2.41775215e-01 1.74523201e-02 -9.71058965e-01 -2.38278359e-01 1.74523201e-02 -9.71882522e-01 -2.34901384e-01 1.74523201e-02 -9.72672343e-01 -2.31603891e-01 1.74523201e-02 -9.73454773e-01 -2.28293493e-01 1.74523201e-02 -9.74260926e-01 -2.24820092e-01 1.74523201e-02 -9.75071371e-01 -2.21279636e-01 1.74523201e-02 -9.75813627e-01 -2.17983320e-01 1.74523201e-02 -9.76565003e-01 -2.14594364e-01 1.74523201e-02 -9.77314234e-01 -2.11150318e-01 1.74523201e-02 -9.78018880e-01 -2.07865626e-01 1.74523201e-02 -9.78763223e-01 -2.04344228e-01 1.74523201e-02 -9.79491174e-01 -2.00818941e-01 1.74523201e-02 -9.80168343e-01 -1.97480947e-01 1.74523201e-02 -9.80829477e-01 -1.94171101e-01 1.74523201e-02 -9.81501102e-01 -1.90750703e-01 1.74523201e-02 -9.82174635e-01 -1.87246770e-01 1.74523201e-02 -9.82849002e-01 -1.83681950e-01 1.74523201e-02 -9.83462393e-01 -1.80347756e-01 1.74523201e-02 -9.84074175e-01 -1.77016392e-01 1.74523201e-02 -9.84687805e-01 -1.73565969e-01 1.74523201e-02 -9.85294759e-01 -1.70060873e-01 1.74523201e-02 -9.85898793e-01 -1.66528404e-01 1.74523201e-02 -9.86459970e-01 -1.63174793e-01 1.74523201e-02 -9.87026453e-01 -1.59718499e-01 1.74523201e-02 -9.87576365e-01 -1.56274199e-01 1.74523201e-02 -9.88112450e-01 -1.52846798e-01 1.74523201e-02 -9.88640964e-01 -1.49381071e-01 1.74523201e-02 -9.89153087e-01 -1.45965859e-01 1.74523201e-02 -9.89659965e-01 -1.42481729e-01 1.74523201e-02 -9.90135372e-01 -1.39145374e-01 1.74523201e-02 -9.90627587e-01 -1.35608926e-01 1.74523201e-02 -9.91094708e-01 -1.32120237e-01 1.74523201e-02 -9.91549909e-01 -1.28675297e-01 1.74523201e-02 -9.91994679e-01 -1.25208661e-01 1.74523201e-02 -9.92413580e-01 -1.21834934e-01 1.74523201e-02 -9.92842257e-01 -1.18283704e-01 1.74523201e-02 -9.93247569e-01 -1.14818029e-01 1.74523201e-02 -9.93631721e-01 -1.11464880e-01 1.74523201e-02 -9.94028628e-01 -1.07850723e-01 1.74523201e-02 -9.94407773e-01 -1.04305588e-01 1.74523201e-02 -9.94760454e-01 -1.00881837e-01 1.74523238e-02 -9.95095968e-01 -9.74819511e-02 1.74523313e-02 -9.95429873e-01 -9.40177068e-02 1.74523313e-02 -9.95751202e-01 -9.05167460e-02 1.74523313e-02 -9.96040881e-01 -8.72329399e-02 1.74523313e-02 -9.96335208e-01 -8.37304667e-02 1.74523462e-02 -9.96618986e-01 -8.02869424e-02 1.74523611e-02 -9.96879756e-01 -7.69784600e-02 1.74523983e-02 -9.97163296e-01 -7.32067749e-02 1.74524114e-02 -9.97405291e-01 -6.98329508e-02 1.74524076e-02 -9.97660220e-01 -6.60897419e-02 1.74524058e-02 -9.97797251e-01 -6.40001521e-02 1.74524039e-02 -9.97993469e-01 -6.08651116e-02 1.74524076e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98286366e-01 5.36922477e-02 2.32631359e-02 -9.98148561e-01 5.62038459e-02 2.32630335e-02 -9.97961998e-01 5.95357232e-02 2.32631639e-02 -9.97751892e-01 6.29855990e-02 2.32632440e-02 -9.97526348e-01 6.64844438e-02 2.32633110e-02 -9.97291923e-01 6.98798448e-02 2.32633073e-02 -9.97052372e-01 7.32708201e-02 2.32633855e-02 -9.96787429e-01 7.68096521e-02 2.32634284e-02 -9.96506393e-01 8.03743973e-02 2.32634116e-02 -9.96226907e-01 8.37600604e-02 2.32633762e-02 -9.95929480e-01 8.72386396e-02 2.32634358e-02 -9.95609999e-01 9.08064172e-02 2.32634041e-02 -9.95294213e-01 9.42053348e-02 2.32634041e-02 -9.94954824e-01 9.77235436e-02 2.32634135e-02 -9.94615853e-01 1.01122782e-01 2.32633781e-02 -9.94268179e-01 1.04477078e-01 2.32633874e-02 -9.93885279e-01 1.08061105e-01 2.32634563e-02 -9.93490458e-01 1.11638509e-01 2.32633986e-02 -9.93091881e-01 1.15113653e-01 2.32634060e-02 -9.92682219e-01 1.18590191e-01 2.32634097e-02 -9.92267072e-01 1.22029610e-01 2.32634079e-02 -9.91837025e-01 1.25488460e-01 2.32634041e-02 -9.91392314e-01 1.28945082e-01 2.32634246e-02 -9.90927517e-01 1.32464871e-01 2.32634209e-02 -9.90474701e-01 1.35811105e-01 2.32633688e-02 -9.90013540e-01 1.39143169e-01 2.32634135e-02 -9.89505172e-01 1.42708793e-01 2.32634563e-02 -9.88986552e-01 1.46247387e-01 2.32633948e-02 -9.88467634e-01 1.49712533e-01 2.32634284e-02 -9.87940848e-01 1.53162658e-01 2.32634321e-02 -9.87402439e-01 1.56596899e-01 2.32634172e-02 -9.86861289e-01 1.59966856e-01 2.32633911e-02 -9.86299574e-01 1.63408011e-01 2.32634563e-02 -9.85702157e-01 1.66964799e-01 2.32634172e-02 -9.85125422e-01 1.70330182e-01 2.32633930e-02 -9.84534621e-01 1.73736095e-01 2.32634526e-02 -9.83902812e-01 1.77277729e-01 2.32634358e-02 -9.83271718e-01 1.80718005e-01 2.32634302e-02 -9.82635558e-01 1.84157148e-01 2.32634321e-02 -9.82004762e-01 1.87481120e-01 2.32633855e-02 -9.81370151e-01 1.90777317e-01 2.32634284e-02 -9.80674803e-01 1.94330126e-01 2.32634638e-02 -9.79965508e-01 1.97874993e-01 2.32634302e-02 -9.79266584e-01 2.01303273e-01 2.32634284e-02 -9.78580415e-01 2.04608023e-01 2.32633818e-02 -9.77864325e-01 2.08018824e-01 2.32634563e-02 -9.77109492e-01 2.11529091e-01 2.32634172e-02 -9.76377428e-01 2.14868322e-01 2.32633818e-02 -9.75632608e-01 2.18245745e-01 2.32634563e-02 -9.74856138e-01 2.21673772e-01 2.32633874e-02 -9.74099755e-01 2.24976629e-01 2.32634209e-02 -9.73292172e-01 2.28461638e-01 2.32634563e-02 -9.72465158e-01 2.31946975e-01 2.32634079e-02 -9.71655846e-01 2.35319704e-01 2.32634079e-02 -9.70829546e-01 2.38697186e-01 2.32634209e-02 -9.69981015e-01 2.42117092e-01 2.32634284e-02 -9.69147503e-01 2.45430216e-01 2.32633855e-02 -9.68296647e-01 2.48774573e-01 2.32634731e-02 -9.67397690e-01 2.52249777e-01 2.32634284e-02 -9.66529965e-01 2.55555183e-01 2.32633948e-02 -9.65634346e-01 2.58918792e-01 2.32634693e-02 -9.64708209e-01 2.62349546e-01 2.32634321e-02 -9.63784218e-01 2.65714437e-01 2.32634377e-02 -9.62849617e-01 2.69092679e-01 2.32634377e-02 -9.61919427e-01 2.72392392e-01 2.32633948e-02 -9.60971773e-01 2.75716752e-01 2.32634563e-02 -9.59994912e-01 2.79095024e-01 2.32633967e-02 -9.59026456e-01 2.82410622e-01 2.32634675e-02 -9.58001673e-01 2.85869330e-01 2.32634228e-02 -9.57022071e-01 2.89123416e-01 2.32633874e-02 -9.56012666e-01 2.92450249e-01 2.32634563e-02 -9.54952121e-01 2.95893371e-01 2.32634172e-02 -9.53925192e-01 2.99187273e-01 2.32634228e-02 -9.52876806e-01 3.02508414e-01 2.32634284e-02 -9.51833427e-01 3.05778891e-01 2.32633986e-02 -9.50790882e-01 3.08999032e-01 2.32634209e-02 -9.49684024e-01 3.12388510e-01 2.32634563e-02 -9.48551595e-01 3.15808922e-01 2.32634321e-02 -9.47438419e-01 3.19134861e-01 2.32634284e-02 -9.46320057e-01 3.22434962e-01 2.32634321e-02 -9.45198059e-01 3.25714111e-01 2.32634153e-02 -9.44079101e-01 3.28936458e-01 2.32634116e-02 -9.42922354e-01 3.32240820e-01 2.32634563e-02 -9.41733599e-01 3.35599124e-01 2.32634321e-02 -9.40584481e-01 3.38798285e-01 2.32633930e-02 -9.39429104e-01 3.41995895e-01 2.32634284e-02 -9.38197553e-01 3.45345616e-01 2.32634563e-02 -9.36946869e-01 3.48710686e-01 2.32634284e-02 -9.35723186e-01 3.51985127e-01 2.32634284e-02 -9.34504926e-01 3.55217755e-01 2.32634116e-02 -9.33296442e-01 3.58405441e-01 2.32634041e-02 -9.32049751e-01 3.61614317e-01 2.32634284e-02 -9.30761874e-01 3.64925414e-01 2.32634451e-02 -9.29446399e-01 3.68261516e-01 2.32634172e-02 -9.28193033e-01 3.71405154e-01 2.32633818e-02 -9.26894844e-01 3.74636412e-01 2.32634563e-02 -9.25548255e-01 3.77953172e-01 2.32634377e-02 -9.24229681e-01 3.81158173e-01 2.32634116e-02 -9.22902167e-01 3.84364665e-01 2.32634265e-02 -9.21580255e-01 3.87522638e-01 2.32633948e-02 -9.20254886e-01 3.90659541e-01 2.32634284e-02 -9.18846786e-01 3.93954992e-01 2.32634731e-02 -9.17426527e-01 3.97258610e-01 2.32634321e-02 -9.16044593e-01 4.00436789e-01 2.32634097e-02 -9.14638877e-01 4.03637022e-01 2.32634321e-02 -9.13221776e-01 4.06832963e-01 2.32634321e-02 -9.11799371e-01 4.10010427e-01 2.32634284e-02 -9.10394311e-01 4.13118690e-01 2.32633967e-02 -9.08957422e-01 4.16268647e-01 2.32634563e-02 -9.07465398e-01 4.19513494e-01 2.32634377e-02 -9.06030476e-01 4.22603279e-01 2.32633874e-02 -9.04560983e-01 4.25741613e-01 2.32634451e-02 -9.03025270e-01 4.28989112e-01 2.32634172e-02 -9.01521683e-01 4.32137489e-01 2.32634284e-02 -9.00010049e-01 4.35284823e-01 2.32634284e-02 -8.98505688e-01 4.38380331e-01 2.32633967e-02 -8.97021532e-01 4.41403419e-01 2.32634321e-02 -8.95447135e-01 4.44592178e-01 2.32634451e-02 -8.93844604e-01 4.47801888e-01 2.32634284e-02 -8.92273188e-01 4.50929314e-01 2.32634377e-02 -8.90696108e-01 4.54034328e-01 2.32634246e-02 -8.89120996e-01 4.57112700e-01 2.32634265e-02 -8.87522578e-01 4.60204154e-01 2.32634209e-02 -8.85906935e-01 4.63308930e-01 2.32634228e-02 -8.84292960e-01 4.66385692e-01 2.32634209e-02 -8.82682383e-01 4.69423383e-01 2.32633874e-02 -8.81093025e-01 4.72401768e-01 2.32634284e-02 -8.79402041e-01 4.75542963e-01 2.32634582e-02 -8.77692044e-01 4.78693157e-01 2.32634209e-02 -8.76015246e-01 4.81754422e-01 2.32634321e-02 -8.74320626e-01 4.84813601e-01 2.32634190e-02 -8.72636199e-01 4.87842292e-01 2.32634172e-02 -8.70934606e-01 4.90877718e-01 2.32634172e-02 -8.69210601e-01 4.93923932e-01 2.32634451e-02 -8.67467940e-01 4.96978313e-01 2.32634321e-02 -8.65764439e-01 4.99937534e-01 2.32633892e-02 -8.64022613e-01 5.02945602e-01 2.32634563e-02 -8.62276137e-01 5.05929708e-01 2.32633874e-02 -8.60489845e-01 5.08965015e-01 2.32634563e-02 -8.58659029e-01 5.12045562e-01 2.32634172e-02 -8.56866658e-01 5.15039742e-01 2.32634302e-02 -8.55060756e-01 5.18029988e-01 2.32634172e-02 -8.53251636e-01 5.21011949e-01 2.32634377e-02 -8.51421356e-01 5.23991227e-01 2.32634321e-02 -8.49596441e-01 5.26950121e-01 2.32634284e-02 -8.47799599e-01 5.29832244e-01 2.32633892e-02 -8.45949888e-01 5.32781541e-01 2.32634563e-02 -8.44041348e-01 5.35798430e-01 2.32634060e-02 -8.42159390e-01 5.38752854e-01 2.32634451e-02 -8.40262711e-01 5.41705430e-01 2.32634004e-02 -8.38377416e-01 5.44616938e-01 2.32634116e-02 -8.36534500e-01 5.47441125e-01 2.32633930e-02 -8.34600151e-01 5.50390184e-01 2.32634563e-02 -8.32600117e-01 5.53407848e-01 2.32634377e-02 -8.30659211e-01 5.56320667e-01 2.32634284e-02 -8.28752995e-01 5.59157968e-01 2.32634041e-02 -8.26860130e-01 5.61950743e-01 2.32634135e-02 -8.24865818e-01 5.64875424e-01 2.32634470e-02 -8.22837710e-01 5.67826807e-01 2.32634321e-02 -8.20839047e-01 5.70710003e-01 2.32634246e-02 -8.18886936e-01 5.73502779e-01 2.32633799e-02 -8.16894770e-01 5.76346993e-01 2.32634731e-02 -8.14797759e-01 5.79300165e-01 2.32634284e-02 -8.12772512e-01 5.82140803e-01 2.32634321e-02 -8.10723066e-01 5.84987104e-01 2.32634228e-02 -8.08675587e-01 5.87818861e-01 2.32634284e-02 -8.06635499e-01 5.90612888e-01 2.32634284e-02 -8.04644585e-01 5.93320310e-01 2.32633837e-02 -8.02569032e-01 5.96126914e-01 2.32634638e-02 -8.00404668e-01 5.99029839e-01 2.32634265e-02 -7.98378766e-01 6.01726890e-01 2.32633799e-02 -7.96275914e-01 6.04511380e-01 2.32634712e-02 -7.94095695e-01 6.07370734e-01 2.32634228e-02 -7.91980326e-01 6.10124528e-01 2.32634228e-02 -7.89821804e-01 6.12915993e-01 2.32634339e-02 -7.87693381e-01 6.15649223e-01 2.32634060e-02 -7.85611212e-01 6.18304729e-01 2.32634004e-02 -7.83425391e-01 6.21072233e-01 2.32634731e-02 -7.81179070e-01 6.23897076e-01 2.32634321e-02 -7.78973877e-01 6.26647651e-01 2.32634284e-02 -7.76790798e-01 6.29351854e-01 2.32634116e-02 -7.74662912e-01 6.31965280e-01 2.32633892e-02 -7.72471964e-01 6.34645104e-01 2.32634284e-02 -7.70162404e-01 6.37445390e-01 2.32634004e-02 -7.67950177e-01 6.40107930e-01 2.32634116e-02 -7.65775323e-01 6.42709613e-01 2.32633892e-02 -7.63528645e-01 6.45376563e-01 2.32634563e-02 -7.61172414e-01 6.48150861e-01 2.32634246e-02 -7.58907735e-01 6.50803685e-01 2.32634246e-02 -7.56635666e-01 6.53446436e-01 2.32634228e-02 -7.54350185e-01 6.56079710e-01 2.32633986e-02 -7.52119422e-01 6.58635795e-01 2.32633874e-02 -7.49879777e-01 6.61184430e-01 2.32634228e-02 -7.47511327e-01 6.63862824e-01 2.32634563e-02 -7.45132089e-01 6.66533232e-01 2.32634321e-02 -7.42842197e-01 6.69079900e-01 2.32633874e-02 -7.40516543e-01 6.71660125e-01 2.32634563e-02 -7.38108754e-01 6.74299121e-01 2.32634265e-02 -7.35760093e-01 6.76864624e-01 2.32634209e-02 -7.33387530e-01 6.79434121e-01 2.32634079e-02 -7.31058955e-01 6.81936085e-01 2.32633911e-02 -7.28739142e-01 6.84415638e-01 2.32634097e-02 -7.26302505e-01 6.87000215e-01 2.32634563e-02 -7.23823428e-01 6.89613879e-01 2.32634135e-02 -7.21402466e-01 6.92139864e-01 2.32634135e-02 -7.18996644e-01 6.94651663e-01 2.32634209e-02 -7.16628075e-01 6.97091639e-01 2.32633874e-02 -7.14195311e-01 6.99583232e-01 2.32634451e-02 -7.11675227e-01 7.02147067e-01 2.32634284e-02 -7.09230185e-01 7.04620004e-01 2.32634209e-02 -7.06757605e-01 7.07081079e-01 2.32634060e-02 -7.04364240e-01 7.09483206e-01 2.32633874e-02 -7.01878428e-01 7.11941838e-01 2.32634563e-02 -6.99320674e-01 7.14451253e-01 2.32634041e-02 -6.96809471e-01 7.16903806e-01 2.32634209e-02 -6.94305122e-01 7.19332337e-01 2.32634209e-02 -6.91849232e-01 7.21680045e-01 2.32633874e-02 -6.89363778e-01 7.24062920e-01 2.32634079e-02 -6.86784923e-01 7.26505816e-01 2.32634507e-02 -6.84192240e-01 7.28948057e-01 2.32634246e-02 -6.81691766e-01 7.31283367e-01 2.32633892e-02 -6.79156721e-01 7.33644247e-01 2.32634451e-02 -6.76526129e-01 7.36072183e-01 2.32634172e-02 -6.74004078e-01 7.38378286e-01 2.32633874e-02 -6.71418488e-01 7.40733385e-01 2.32634507e-02 -6.68848395e-01 7.43053138e-01 2.32633892e-02 -6.66316032e-01 7.45324552e-01 2.32634228e-02 -6.63650513e-01 7.47702062e-01 2.32634563e-02 -6.61020041e-01 7.50025570e-01 2.32633948e-02 -6.58395648e-01 7.52329469e-01 2.32634731e-02 -6.55760109e-01 7.54629135e-01 2.32633855e-02 -6.53160632e-01 7.56881058e-01 2.32634768e-02 -6.50401056e-01 7.59253383e-01 2.32634246e-02 -6.47747517e-01 7.61517048e-01 2.32634321e-02 -6.45102084e-01 7.63760328e-01 2.32634209e-02 -6.42507732e-01 7.65943587e-01 2.32633874e-02 -6.39840722e-01 7.68175304e-01 2.32634619e-02 -6.37133598e-01 7.70418227e-01 2.32633837e-02 -6.34456515e-01 7.72629678e-01 2.32634638e-02 -6.31665945e-01 7.74908721e-01 2.32634377e-02 -6.28962398e-01 7.77105033e-01 2.32634377e-02 -6.26305997e-01 7.79244959e-01 2.32633855e-02 -6.23675048e-01 7.81356454e-01 2.32634377e-02 -6.20862305e-01 7.83591926e-01 2.32634638e-02 -6.18125379e-01 7.85753369e-01 2.32633948e-02 -6.15396798e-01 7.87893116e-01 2.32634563e-02 -6.12638056e-01 7.90039182e-01 2.32633874e-02 -6.09922647e-01 7.92137325e-01 2.32634395e-02 -6.07085824e-01 7.94313848e-01 2.32634451e-02 -6.04242623e-01 7.96479106e-01 2.32634321e-02 -6.01537704e-01 7.98523188e-01 2.32633948e-02 -5.98758280e-01 8.00607443e-01 2.32634693e-02 -5.95881760e-01 8.02751482e-01 2.32634246e-02 -5.93082488e-01 8.04821491e-01 2.32634172e-02 -5.90283990e-01 8.06876421e-01 2.32634209e-02 -5.87517858e-01 8.08894038e-01 2.32633892e-02 -5.84706724e-01 8.10927093e-01 2.32634563e-02 -5.81782341e-01 8.13029945e-01 2.32634190e-02 -5.78950286e-01 8.15048933e-01 2.32634302e-02 -5.76074362e-01 8.17084849e-01 2.32634284e-02 -5.73293030e-01 8.19035053e-01 2.32633892e-02 -5.70446610e-01 8.21021318e-01 2.32634563e-02 -5.67578018e-01 8.23007941e-01 2.32633706e-02 -5.64715981e-01 8.24976087e-01 2.32634563e-02 -5.61710775e-01 8.27022970e-01 2.32634321e-02 -5.58832645e-01 8.28970611e-01 2.32634116e-02 -5.56033850e-01 8.30849051e-01 2.32633855e-02 -5.53113401e-01 8.32796752e-01 2.32634451e-02 -5.50096333e-01 8.34794402e-01 2.32634246e-02 -5.47271609e-01 8.36645961e-01 2.32633799e-02 -5.44366956e-01 8.38540494e-01 2.32634563e-02 -5.41403949e-01 8.40455174e-01 2.32633855e-02 -5.38488567e-01 8.42327118e-01 2.32634619e-02 -5.35460949e-01 8.44255686e-01 2.32634209e-02 -5.32500148e-01 8.46126616e-01 2.32634321e-02 -5.29628694e-01 8.47925365e-01 2.32633911e-02 -5.26688278e-01 8.49759579e-01 2.32634656e-02 -5.23631871e-01 8.51641297e-01 2.32633911e-02 -5.20699143e-01 8.53439569e-01 2.32634004e-02 -5.17712772e-01 8.55254173e-01 2.32634563e-02 -5.14744759e-01 8.57042730e-01 2.32633930e-02 -5.11788011e-01 8.58813405e-01 2.32634451e-02 -5.08767545e-01 8.60603333e-01 2.32633948e-02 -5.05855620e-01 8.62321675e-01 2.32634228e-02 -5.02774000e-01 8.64121556e-01 2.32634488e-02 -4.99676943e-01 8.65915418e-01 2.32634172e-02 -4.96653914e-01 8.67652416e-01 2.32634228e-02 -4.93613362e-01 8.69385242e-01 2.32634135e-02 -4.90590572e-01 8.71097803e-01 2.32634209e-02 -4.87544060e-01 8.72803390e-01 2.32634321e-02 -4.84489292e-01 8.74501884e-01 2.32634321e-02 -4.81469482e-01 8.76169443e-01 2.32633837e-02 -4.78450298e-01 8.77823889e-01 2.32634526e-02 -4.75303113e-01 8.79528403e-01 2.32634284e-02 -4.72238958e-01 8.81178916e-01 2.32634172e-02 -4.69161808e-01 8.82821918e-01 2.32634116e-02 -4.66130555e-01 8.84426892e-01 2.32633930e-02 -4.63042170e-01 8.86045933e-01 2.32634377e-02 -4.59865868e-01 8.87698472e-01 2.32634284e-02 -4.56774622e-01 8.89293849e-01 2.32634116e-02 -4.53763962e-01 8.90832663e-01 2.32633818e-02 -4.50685024e-01 8.92395496e-01 2.32634544e-02 -4.47474957e-01 8.94009352e-01 2.32634172e-02 -4.44344610e-01 8.95568073e-01 2.32634172e-02 -4.41219360e-01 8.97112906e-01 2.32634116e-02 -4.38145459e-01 8.98618519e-01 2.32633743e-02 -4.35032278e-01 9.00131464e-01 2.32634246e-02 -4.31841940e-01 9.01662886e-01 2.32633892e-02 -4.28705513e-01 9.03159082e-01 2.32634414e-02 -4.25479323e-01 9.04684424e-01 2.32634172e-02 -4.22386765e-01 9.06132221e-01 2.32633911e-02 -4.19233441e-01 9.07596529e-01 2.32634451e-02 -4.16053683e-01 9.09055471e-01 2.32633911e-02 -4.12887216e-01 9.10501003e-01 2.32634563e-02 -4.09641087e-01 9.11966264e-01 2.32634284e-02 -4.06449616e-01 9.13392663e-01 2.32634004e-02 -4.03337479e-01 9.14769888e-01 2.32633818e-02 -4.00187880e-01 9.16154087e-01 2.32634433e-02 -3.96906108e-01 9.17580009e-01 2.32634451e-02 -3.93644154e-01 9.18979645e-01 2.32634153e-02 -3.90524566e-01 9.20312405e-01 2.32633874e-02 -3.87417436e-01 9.21624780e-01 2.32634190e-02 -3.84124666e-01 9.23003316e-01 2.32634563e-02 -3.80832374e-01 9.24364030e-01 2.32633948e-02 -3.77644807e-01 9.25672114e-01 2.32634209e-02 -3.74432266e-01 9.26977038e-01 2.32633874e-02 -3.71207029e-01 9.28272963e-01 2.32634451e-02 -3.67902696e-01 9.29587960e-01 2.32634079e-02 -3.64660621e-01 9.30865467e-01 2.32634265e-02 -3.61388743e-01 9.32134092e-01 2.32634097e-02 -3.58205557e-01 9.33372617e-01 2.32633911e-02 -3.54939967e-01 9.34611976e-01 2.32634563e-02 -3.51669192e-01 9.35839593e-01 2.32633874e-02 -3.48412484e-01 9.37057912e-01 2.32634451e-02 -3.45078260e-01 9.38293397e-01 2.32633967e-02 -3.41863424e-01 9.39478517e-01 2.32633911e-02 -3.38583827e-01 9.40663397e-01 2.32634563e-02 -3.35251898e-01 9.41857457e-01 2.32633911e-02 -3.31988335e-01 9.43011582e-01 2.32634246e-02 -3.28646004e-01 9.44180012e-01 2.32634004e-02 -3.25337678e-01 9.45327401e-01 2.32634135e-02 -3.22143137e-01 9.46418345e-01 2.32633874e-02 -3.18809539e-01 9.47548866e-01 2.32634563e-02 -3.15444887e-01 9.48672295e-01 2.32634004e-02 -3.12153876e-01 9.49759662e-01 2.32633986e-02 -3.08872730e-01 9.50831950e-01 2.32633837e-02 -3.05560231e-01 9.51904178e-01 2.32634451e-02 -3.02173287e-01 9.52982545e-01 2.32634004e-02 -2.98864633e-01 9.54025686e-01 2.32633930e-02 -2.95512706e-01 9.55070376e-01 2.32633967e-02 -2.92256743e-01 9.56069767e-01 2.32633632e-02 -2.88905501e-01 9.57087517e-01 2.32634377e-02 -2.85457224e-01 9.58122969e-01 2.32634079e-02 -2.82129914e-01 9.59109306e-01 2.32634135e-02 -2.78770894e-01 9.60090101e-01 2.32634302e-02 -2.75518596e-01 9.61027861e-01 2.32633706e-02 -2.72172183e-01 9.61982489e-01 2.32634544e-02 -2.68793762e-01 9.62931871e-01 2.32633762e-02 -2.65552670e-01 9.63829219e-01 2.32634135e-02 -2.62067884e-01 9.64784861e-01 2.32634582e-02 -2.58580893e-01 9.65722740e-01 2.32634023e-02 -2.55218685e-01 9.66617763e-01 2.32634284e-02 -2.51852155e-01 9.67500269e-01 2.32634004e-02 -2.48582944e-01 9.68344867e-01 2.32633688e-02 -2.45177716e-01 9.69210982e-01 2.32634488e-02 -2.41671816e-01 9.70092237e-01 2.32634079e-02 -2.38286287e-01 9.70930398e-01 2.32634079e-02 -2.34891161e-01 9.71759975e-01 2.32634097e-02 -2.31598988e-01 9.72548127e-01 2.32633688e-02 -2.28221208e-01 9.73346770e-01 2.32634433e-02 -2.24812284e-01 9.74137902e-01 2.32633743e-02 -2.21412033e-01 9.74916577e-01 2.32634451e-02 -2.17923209e-01 9.75703597e-01 2.32633930e-02 -2.14497939e-01 9.76458430e-01 2.32633930e-02 -2.11097494e-01 9.77200627e-01 2.32634004e-02 -2.07760021e-01 9.77915883e-01 2.32633706e-02 -2.04386100e-01 9.78629708e-01 2.32634451e-02 -2.00837240e-01 9.79363680e-01 2.32634079e-02 -1.97435394e-01 9.80052114e-01 2.32633892e-02 -1.94018826e-01 9.80735540e-01 2.32634060e-02 -1.90678194e-01 9.81390357e-01 2.32633818e-02 -1.87244177e-01 9.82052028e-01 2.32634507e-02 -1.83795378e-01 9.82701600e-01 2.32633706e-02 -1.80465251e-01 9.83317733e-01 2.32634041e-02 -1.76942468e-01 9.83963788e-01 2.32634414e-02 -1.73386291e-01 9.84596252e-01 2.32633948e-02 -1.69983104e-01 9.85185623e-01 2.32633986e-02 -1.66542634e-01 9.85773444e-01 2.32634079e-02 -1.63179547e-01 9.86335158e-01 2.32633818e-02 -1.59824148e-01 9.86884236e-01 2.32634060e-02 -1.56303674e-01 9.87449348e-01 2.32634451e-02 -1.52749315e-01 9.88006532e-01 2.32634377e-02 -1.49299741e-01 9.88529980e-01 2.32634209e-02 -1.45830348e-01 9.89049613e-01 2.32634246e-02 -1.42385855e-01 9.89550054e-01 2.32634004e-02 -1.39038295e-01 9.90026832e-01 2.32633688e-02 -1.35599881e-01 9.90506053e-01 2.32634526e-02 -1.32022664e-01 9.90986705e-01 2.32634116e-02 -1.28666133e-01 9.91426826e-01 2.32633781e-02 -1.25222683e-01 9.91869152e-01 2.32634451e-02 -1.21742316e-01 9.92301941e-01 2.32633781e-02 -1.18250318e-01 9.92724776e-01 2.32634563e-02 -1.14686936e-01 9.93142545e-01 2.32634209e-02 -1.11222349e-01 9.93536413e-01 2.32634079e-02 -1.07737750e-01 9.93919075e-01 2.32634041e-02 -1.04275592e-01 9.94287670e-01 2.32633930e-02 -1.00797243e-01 9.94648099e-01 2.32634172e-02 -9.74087194e-02 9.94985223e-01 2.32633818e-02 -9.40483585e-02 9.95309114e-01 2.32633986e-02 -9.04759541e-02 9.95640099e-01 2.32634246e-02 -8.69052336e-02 9.95959222e-01 2.32634041e-02 -8.34267884e-02 9.96255457e-01 2.32634060e-02 -7.99330696e-02 9.96542037e-01 2.32634172e-02 -7.65613317e-02 9.96803105e-01 2.32633576e-02 -7.30678588e-02 9.97069955e-01 2.32634563e-02 -6.94995672e-02 9.97322202e-01 2.32634060e-02 -6.60161301e-02 9.97560382e-01 2.32633948e-02 -6.25413954e-02 9.97782230e-01 2.32633967e-02 -5.91689572e-02 9.97989774e-01 2.32633799e-02 -5.56905568e-02 9.98191833e-01 2.32634563e-02 -5.21609560e-02 9.98378932e-01 2.32633818e-02 -4.87093739e-02 9.98557448e-01 2.32634451e-02 -4.51380834e-02 9.98721302e-01 2.32634004e-02 -4.16506119e-02 9.98874962e-01 2.32634172e-02 -3.81474122e-02 9.99013841e-01 2.32634172e-02 -3.47645804e-02 9.99137819e-01 2.32633855e-02 -3.12748440e-02 9.99252915e-01 2.32634377e-02 -2.77685020e-02 9.99355316e-01 2.32633725e-02 -2.42902972e-02 9.99451280e-01 2.32634395e-02 -2.07084492e-02 9.99525547e-01 2.32634135e-02 -1.72916595e-02 9.99595582e-01 2.32633799e-02 -1.38235837e-02 9.99643445e-01 2.32634451e-02 -1.03230141e-02 9.99687910e-01 2.32633837e-02 -6.93162950e-03 9.99724984e-01 2.32634172e-02 -3.36141465e-03 9.99742508e-01 2.32634451e-02 2.32503997e-04 9.99743164e-01 2.32634079e-02 3.71300243e-03 9.99741614e-01 2.32634060e-02 7.17845233e-03 9.99721289e-01 2.32633986e-02 1.05972122e-02 9.99684989e-01 2.32633706e-02 1.39925322e-02 9.99640584e-01 2.32634135e-02 1.75514854e-02 9.99594271e-01 2.32634451e-02 2.11540647e-02 9.99517679e-01 2.32634060e-02 2.46629789e-02 9.99438763e-01 2.32634135e-02 2.81615611e-02 9.99348223e-01 2.32634209e-02 3.16318944e-02 9.99242663e-01 2.32634116e-02 3.50488462e-02 9.99128520e-01 2.32633632e-02 3.85018550e-02 9.99002218e-01 2.32634451e-02 4.21028249e-02 9.98856902e-01 2.32634228e-02 4.56073955e-02 9.98700857e-01 2.32634041e-02 4.90807183e-02 9.98537779e-01 2.32634079e-02 5.24821393e-02 9.98361051e-01 2.32633818e-02 5.59377819e-02 9.98177469e-01 2.32634451e-02 5.94434962e-02 9.97973323e-01 2.32633669e-02 6.29181340e-02 9.97759283e-01 2.32634544e-02 6.65052608e-02 9.97527957e-01 2.32634116e-02 6.99674711e-02 9.97289181e-01 2.32634023e-02 7.34534413e-02 9.97041821e-01 2.32634153e-02 7.69465938e-02 9.96776342e-01 2.32634246e-02 8.03420395e-02 9.96508420e-01 2.32633818e-02 8.38132575e-02 9.96223807e-01 2.32634377e-02 8.73575881e-02 9.95919108e-01 2.32634228e-02 9.08482522e-02 9.95605767e-01 2.32634116e-02 9.43174884e-02 9.95283484e-01 2.32633930e-02 9.77292508e-02 9.94954467e-01 2.32633818e-02 1.01175182e-01 9.94610488e-01 2.32634526e-02 1.04655989e-01 9.94249701e-01 2.32633874e-02 1.08127452e-01 9.93879855e-01 2.32634731e-02 1.11689463e-01 9.93483543e-01 2.32634284e-02 1.15074590e-01 9.93096292e-01 2.32633892e-02 1.18517786e-01 9.92692828e-01 2.32634563e-02 1.21996418e-01 9.92270708e-01 2.32633930e-02 1.25440300e-01 9.91842747e-01 2.32634563e-02 1.29004776e-01 9.91383255e-01 2.32634135e-02 1.32469922e-01 9.90926862e-01 2.32634041e-02 1.35932103e-01 9.90459979e-01 2.32634265e-02 1.39281616e-01 9.89994645e-01 2.32633930e-02 1.42752960e-01 9.89498436e-01 2.32634451e-02 1.46212474e-01 9.88992214e-01 2.32633818e-02 1.49646938e-01 9.88477945e-01 2.32634451e-02 1.53200909e-01 9.87936080e-01 2.32634116e-02 1.56563580e-01 9.87404943e-01 2.32633818e-02 1.59982949e-01 9.86859620e-01 2.32634451e-02 1.63443595e-01 9.86292958e-01 2.32633892e-02 1.66784599e-01 9.85732257e-01 2.32634116e-02 1.70290887e-01 9.85133410e-01 2.32634451e-02 1.73846185e-01 9.84515548e-01 2.32634060e-02 1.77292928e-01 9.83901620e-01 2.32634172e-02 1.80728123e-01 9.83271360e-01 2.32634135e-02 1.84062302e-01 9.82652724e-01 2.32633874e-02 1.87396213e-01 9.82022643e-01 2.32634284e-02 1.90836489e-01 9.81359839e-01 2.32634172e-02 1.94324031e-01 9.80675697e-01 2.32634563e-02 1.97833329e-01 9.79973316e-01 2.32634135e-02 2.01257959e-01 9.79275882e-01 2.32634246e-02 2.04692081e-01 9.78563130e-01 2.32634284e-02 2.08020672e-01 9.77862716e-01 2.32633874e-02 2.11398974e-01 9.77137089e-01 2.32634563e-02 2.14904547e-01 9.76371527e-01 2.32634284e-02 2.18336985e-01 9.75610673e-01 2.32634284e-02 2.21770510e-01 9.74833727e-01 2.32633874e-02 2.25071386e-01 9.74077821e-01 2.32633594e-02 2.28441969e-01 9.73297238e-01 2.32634563e-02 2.31855273e-01 9.72486019e-01 2.32633594e-02 2.35153720e-01 9.71696854e-01 2.32634228e-02 2.38634661e-01 9.70846057e-01 2.32634563e-02 2.42120877e-01 9.69980121e-01 2.32634097e-02 2.45479360e-01 9.69134808e-01 2.32634060e-02 2.48846248e-01 9.68279064e-01 2.32634172e-02 2.52149969e-01 9.67422426e-01 2.32633874e-02 2.55440861e-01 9.66560662e-01 2.32634321e-02 2.58926302e-01 9.65631723e-01 2.32634563e-02 2.62400627e-01 9.64694440e-01 2.32634284e-02 2.65725106e-01 9.63780522e-01 2.32634023e-02 2.68984854e-01 9.62878048e-01 2.32633669e-02 2.72347420e-01 9.61932361e-01 2.32634377e-02 2.75725573e-01 9.60969567e-01 2.32633706e-02 2.79045969e-01 9.60010648e-01 2.32634321e-02 2.82517910e-01 9.58994210e-01 2.32634284e-02 2.85784781e-01 9.58027303e-01 2.32633837e-02 2.89113998e-01 9.57024455e-01 2.32634563e-02 2.92486340e-01 9.56000030e-01 2.32633818e-02 2.95735955e-01 9.55002606e-01 2.32634451e-02 2.99179614e-01 9.53928947e-01 2.32634451e-02 3.02436352e-01 9.52898026e-01 2.32633781e-02 3.05774748e-01 9.51835275e-01 2.32634582e-02 3.09112430e-01 9.50754404e-01 2.32633911e-02 3.12420338e-01 9.49674487e-01 2.32634563e-02 3.15731496e-01 9.48576987e-01 2.32633892e-02 3.18936467e-01 9.47506487e-01 2.32634284e-02 3.22331637e-01 9.46356416e-01 2.32634600e-02 3.25731546e-01 9.45191205e-01 2.32634153e-02 3.29014927e-01 9.44051862e-01 2.32634172e-02 3.32285285e-01 9.42907095e-01 2.32634116e-02 3.35526228e-01 9.41760182e-01 2.32633874e-02 3.38773876e-01 9.40594912e-01 2.32634451e-02 3.42166245e-01 9.39366519e-01 2.32634246e-02 3.45445096e-01 9.38157737e-01 2.32634060e-02 3.48695219e-01 9.36952114e-01 2.32634190e-02 3.51906776e-01 9.35750484e-01 2.32633874e-02 3.55167150e-01 9.34526145e-01 2.32634488e-02 3.58417153e-01 9.33292508e-01 2.32633892e-02 3.61670852e-01 9.32029009e-01 2.32634563e-02 3.64974588e-01 9.30740535e-01 2.32634265e-02 3.68172526e-01 9.29479897e-01 2.32633818e-02 3.71421129e-01 9.28187311e-01 2.32634451e-02 3.74630958e-01 9.26895499e-01 2.32633874e-02 3.77854884e-01 9.25587475e-01 2.32634470e-02 3.81082058e-01 9.24260855e-01 2.32633986e-02 3.84297013e-01 9.22931135e-01 2.32634563e-02 3.87604624e-01 9.21546817e-01 2.32634321e-02 3.90726745e-01 9.20225143e-01 2.32633818e-02 3.93925905e-01 9.18859661e-01 2.32634451e-02 3.97150517e-01 9.17471588e-01 2.32633911e-02 4.00259644e-01 9.16123688e-01 2.32634172e-02 4.03524578e-01 9.14688647e-01 2.32634451e-02 4.06795055e-01 9.13238347e-01 2.32634116e-02 4.09975916e-01 9.11814988e-01 2.32634321e-02 4.13159400e-01 9.10376966e-01 2.32634172e-02 4.16271120e-01 9.08955395e-01 2.32633948e-02 4.19351786e-01 9.07539189e-01 2.32634209e-02 4.22574282e-01 9.06045318e-01 2.32634451e-02 4.25839871e-01 9.04512405e-01 2.32633911e-02 4.28970695e-01 9.03033257e-01 2.32634116e-02 4.32060599e-01 9.01556373e-01 2.32633669e-02 4.35196340e-01 9.00052547e-01 2.32634339e-02 4.38322097e-01 8.98534536e-01 2.32633911e-02 4.41458285e-01 8.96995306e-01 2.32634563e-02 4.44676578e-01 8.95403922e-01 2.32634246e-02 4.47812259e-01 8.93840194e-01 2.32634377e-02 4.50911522e-01 8.92282426e-01 2.32634284e-02 4.53958154e-01 8.90734911e-01 2.32633799e-02 4.57005680e-01 8.89175653e-01 2.32634284e-02 4.60175574e-01 8.87534797e-01 2.32633669e-02 4.63198662e-01 8.85966241e-01 2.32634041e-02 4.66347545e-01 8.84312034e-01 2.32634563e-02 4.69498783e-01 8.82642567e-01 2.32634079e-02 4.72567558e-01 8.81004035e-01 2.32634284e-02 4.75653738e-01 8.79340529e-01 2.32634284e-02 4.78640467e-01 8.77720416e-01 2.32633874e-02 4.81691539e-01 8.76048803e-01 2.32634563e-02 4.84845519e-01 8.74304175e-01 2.32634321e-02 4.87893194e-01 8.72607410e-01 2.32634116e-02 4.90962386e-01 8.70885968e-01 2.32634004e-02 4.93881613e-01 8.69231880e-01 2.32633818e-02 4.96914059e-01 8.67505074e-01 2.32634563e-02 4.99941111e-01 8.65762770e-01 2.32633725e-02 5.02971888e-01 8.64006877e-01 2.32634451e-02 5.06065071e-01 8.62198174e-01 2.32634377e-02 5.09009540e-01 8.60461950e-01 2.32633967e-02 5.11971116e-01 8.58705819e-01 2.32634563e-02 5.14974713e-01 8.56904864e-01 2.32633930e-02 5.17958283e-01 8.55105281e-01 2.32634526e-02 5.21000147e-01 8.53257179e-01 2.32634265e-02 5.23914993e-01 8.51467133e-01 2.32633948e-02 5.26890337e-01 8.49633873e-01 2.32634563e-02 5.29850960e-01 8.47788095e-01 2.32633911e-02 5.32788277e-01 8.45945954e-01 2.32634451e-02 5.35760283e-01 8.44064355e-01 2.32633837e-02 5.38684487e-01 8.42200696e-01 2.32634190e-02 5.41700780e-01 8.40264440e-01 2.32634116e-02 5.44550240e-01 8.38419020e-01 2.32633315e-02 5.47443271e-01 8.36531639e-01 2.32633408e-02 5.50363779e-01 8.34610879e-01 2.32632197e-02 5.53176045e-01 8.32749009e-01 2.32632253e-02 5.56205392e-01 8.30727816e-01 2.32631788e-02 5.59067070e-01 8.28800261e-01 2.32630335e-02 5.61921537e-01 8.26865256e-01 2.32630335e-02 5.64772546e-01 8.24915767e-01 2.32630651e-02 5.67522287e-01 8.23029995e-01 2.32631601e-02 5.70415378e-01 8.21025968e-01 2.32631490e-02 5.73288023e-01 8.19022894e-01 2.32631397e-02 5.75958967e-01 8.17146599e-01 2.32631415e-02 5.77843666e-01 8.15815866e-01 2.32631415e-02 0. 0. 0. 5.83383381e-01 8.11863720e-01 2.32631397e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 7.13973641e-01 6.99785590e-01 2.32631397e-02 7.17314124e-01 6.96360707e-01 2.32631434e-02 7.19373882e-01 6.94229543e-01 2.32631005e-02 7.21754491e-01 6.91760063e-01 2.32630335e-02 7.24161744e-01 6.89245403e-01 2.32631061e-02 7.26483107e-01 6.86801732e-01 2.32631601e-02 7.28873253e-01 6.84267819e-01 2.32633017e-02 7.31313705e-01 6.81658983e-01 2.32632793e-02 7.33651280e-01 6.79145336e-01 2.32633296e-02 7.35964477e-01 6.76640689e-01 2.32633501e-02 7.38277197e-01 6.74114048e-01 2.32633818e-02 7.40685046e-01 6.71472251e-01 2.32634246e-02 7.43074119e-01 6.68824553e-01 2.32633948e-02 7.45409191e-01 6.66220129e-01 2.32634004e-02 7.47668087e-01 6.63685024e-01 2.32633669e-02 7.49933064e-01 6.61124706e-01 2.32633986e-02 7.52255738e-01 6.58478320e-01 2.32634209e-02 7.54584789e-01 6.55809999e-01 2.32634097e-02 7.56896853e-01 6.53141201e-01 2.32634451e-02 7.59181380e-01 6.50484562e-01 2.32633948e-02 7.61365891e-01 6.47922337e-01 2.32633781e-02 7.63618410e-01 6.45270169e-01 2.32634228e-02 7.65869021e-01 6.42596483e-01 2.32634060e-02 7.68145502e-01 6.39875531e-01 2.32634451e-02 7.70430446e-01 6.37118876e-01 2.32634097e-02 7.72607863e-01 6.34479105e-01 2.32633911e-02 7.74800181e-01 6.31799936e-01 2.32634377e-02 7.77052820e-01 6.29027247e-01 2.32634284e-02 7.79254735e-01 6.26298010e-01 2.32634377e-02 7.81389713e-01 6.23631418e-01 2.32633892e-02 7.83492565e-01 6.20988190e-01 2.32634284e-02 7.85711527e-01 6.18179321e-01 2.32634563e-02 7.87917674e-01 6.15364015e-01 2.32634321e-02 7.90073454e-01 6.12595022e-01 2.32634507e-02 7.92162836e-01 6.09887719e-01 2.32633706e-02 7.94211149e-01 6.07219934e-01 2.32634321e-02 7.96392381e-01 6.04357779e-01 2.32634619e-02 7.98547745e-01 6.01504862e-01 2.32634246e-02 8.00647736e-01 5.98704636e-01 2.32634265e-02 8.02686393e-01 5.95969021e-01 2.32633837e-02 8.04682016e-01 5.93271136e-01 2.32634116e-02 8.06804240e-01 5.90384245e-01 2.32634563e-02 8.08922529e-01 5.87477982e-01 2.32634377e-02 8.10982883e-01 5.84626377e-01 2.32634153e-02 8.13008606e-01 5.81809461e-01 2.32634060e-02 8.14971209e-01 5.79058290e-01 2.32633874e-02 8.16949606e-01 5.76267779e-01 2.32634414e-02 8.18963766e-01 5.73396802e-01 2.32634284e-02 8.21005166e-01 5.70470452e-01 2.32634731e-02 8.23021531e-01 5.67558050e-01 2.32633837e-02 8.24929416e-01 5.64781010e-01 2.32634246e-02 8.26948345e-01 5.61822236e-01 2.32634731e-02 8.28913510e-01 5.58915317e-01 2.32633781e-02 8.30810010e-01 5.56093454e-01 2.32634433e-02 8.32750857e-01 5.53183615e-01 2.32634172e-02 8.34642828e-01 5.50325811e-01 2.32634246e-02 8.36623132e-01 5.47309637e-01 2.32634451e-02 8.38565767e-01 5.44327915e-01 2.32634172e-02 8.40422332e-01 5.41455209e-01 2.32633874e-02 8.42250645e-01 5.38609922e-01 2.32634246e-02 8.44113886e-01 5.35682917e-01 2.32634451e-02 8.46064985e-01 5.32600701e-01 2.32634563e-02 8.47974241e-01 5.29550970e-01 2.32634395e-02 8.49809170e-01 5.26602924e-01 2.32634023e-02 8.51583123e-01 5.23725510e-01 2.32633967e-02 8.53365779e-01 5.20821810e-01 2.32634284e-02 8.55182350e-01 5.17830670e-01 2.32634246e-02 8.56989145e-01 5.14836550e-01 2.32634172e-02 8.58823419e-01 5.11770666e-01 2.32634582e-02 8.60659182e-01 5.08676648e-01 2.32634284e-02 8.62380445e-01 5.05752861e-01 2.32633892e-02 8.64135623e-01 5.02750695e-01 2.32634563e-02 8.65893066e-01 4.99716967e-01 2.32633892e-02 8.67619574e-01 4.96711910e-01 2.32634563e-02 8.69381309e-01 4.93617207e-01 2.32634079e-02 8.71054590e-01 4.90665704e-01 2.32633986e-02 8.72775793e-01 4.87593770e-01 2.32634563e-02 8.74475777e-01 4.84535038e-01 2.32634041e-02 8.76163960e-01 4.81480002e-01 2.32634414e-02 8.77829909e-01 4.78437126e-01 2.32633967e-02 8.79459620e-01 4.75433618e-01 2.32634339e-02 8.81149769e-01 4.72294539e-01 2.32634563e-02 8.82839799e-01 4.69129264e-01 2.32634377e-02 8.84479523e-01 4.66028899e-01 2.32634246e-02 8.86051714e-01 4.63033020e-01 2.32633892e-02 8.87612343e-01 4.60031599e-01 2.32634060e-02 8.89255524e-01 4.56851184e-01 2.32634563e-02 8.90894294e-01 4.53644991e-01 2.32634284e-02 8.92470062e-01 4.50537771e-01 2.32634153e-02 8.94045055e-01 4.47403938e-01 2.32634079e-02 8.95567536e-01 4.44344431e-01 2.32633781e-02 8.97086978e-01 4.41273957e-01 2.32634321e-02 8.98647547e-01 4.38086540e-01 2.32633892e-02 9.00150001e-01 4.34994131e-01 2.32634563e-02 9.01716411e-01 4.31734264e-01 2.32634284e-02 9.03172195e-01 4.28678602e-01 2.32633874e-02 9.04651463e-01 4.25548255e-01 2.32634563e-02 9.06142771e-01 4.22364295e-01 2.32633911e-02 9.07612503e-01 4.19200182e-01 2.32634693e-02 9.09105122e-01 4.15946960e-01 2.32634284e-02 9.10518229e-01 4.12843615e-01 2.32633781e-02 9.11949277e-01 4.09678757e-01 2.32634563e-02 9.13375914e-01 4.06484127e-01 2.32633930e-02 9.14785564e-01 4.03305680e-01 2.32634563e-02 9.16193843e-01 4.00094569e-01 2.32633762e-02 9.17556882e-01 3.96957815e-01 2.32634246e-02 9.18963492e-01 3.93684775e-01 2.32634563e-02 9.20369685e-01 3.90390843e-01 2.32634172e-02 9.21722770e-01 3.87185752e-01 2.32634209e-02 9.23035264e-01 3.84043545e-01 2.32633892e-02 9.24330652e-01 3.80914420e-01 2.32634339e-02 9.25688744e-01 3.77605647e-01 2.32634563e-02 9.27051306e-01 3.74249846e-01 2.32634172e-02 9.28349912e-01 3.71013761e-01 2.32634153e-02 9.29607749e-01 3.67855400e-01 2.32633781e-02 9.30839837e-01 3.64728451e-01 2.32634172e-02 9.32128608e-01 3.61408770e-01 2.32634563e-02 9.33402121e-01 3.58128786e-01 2.32633930e-02 9.34633076e-01 3.54882687e-01 2.32634563e-02 9.35905933e-01 3.51497263e-01 2.32634284e-02 9.37094867e-01 3.48306865e-01 2.32633855e-02 9.38301861e-01 3.45063508e-01 2.32634563e-02 9.39511001e-01 3.41775268e-01 2.32633818e-02 9.40688014e-01 3.38516355e-01 2.32634563e-02 9.41894948e-01 3.35146040e-01 2.32634116e-02 9.43037152e-01 3.31914872e-01 2.32633837e-02 9.44182575e-01 3.28641713e-01 2.32634526e-02 9.45352554e-01 3.25262815e-01 2.32634041e-02 9.46463704e-01 3.22010607e-01 2.32634079e-02 9.47565615e-01 3.18757296e-01 2.32633743e-02 9.48656917e-01 3.15492898e-01 2.32634172e-02 9.49774504e-01 3.12114447e-01 2.32634563e-02 9.50880229e-01 3.08730602e-01 2.32634116e-02 9.51956213e-01 3.05397123e-01 2.32634172e-02 9.52984035e-01 3.02167624e-01 2.32633594e-02 9.54012036e-01 2.98908979e-01 2.32634060e-02 9.55074370e-01 2.95498639e-01 2.32634451e-02 9.56128240e-01 2.92066276e-01 2.32634041e-02 9.57134128e-01 2.88753897e-01 2.32633986e-02 9.58112597e-01 2.85486519e-01 2.32633725e-02 9.59077001e-01 2.82234997e-01 2.32633855e-02 9.60087061e-01 2.78783917e-01 2.32634321e-02 9.61050987e-01 2.75436431e-01 2.32633706e-02 9.62008476e-01 2.72079378e-01 2.32634433e-02 9.62967336e-01 2.68662930e-01 2.32634004e-02 9.63876009e-01 2.65379280e-01 2.32633632e-02 9.64799404e-01 2.62017399e-01 2.32634451e-02 9.65735674e-01 2.58535594e-01 2.32634060e-02 9.66625392e-01 2.55191743e-01 2.32633967e-02 9.67512846e-01 2.51805454e-01 2.32634172e-02 9.68370438e-01 2.48488456e-01 2.32633706e-02 9.69222605e-01 2.45133415e-01 2.32634377e-02 9.70076442e-01 2.41737857e-01 2.32633837e-02 9.70912755e-01 2.38363355e-01 2.32634451e-02 9.71744359e-01 2.34948233e-01 2.32633855e-02 9.72533584e-01 2.31663808e-01 2.32634079e-02 9.73352611e-01 2.28202298e-01 2.32634451e-02 9.74162340e-01 2.24706948e-01 2.32634097e-02 9.74940240e-01 2.21309096e-01 2.32634209e-02 9.75712359e-01 2.17884019e-01 2.32634116e-02 9.76449609e-01 2.14540154e-01 2.32633725e-02 9.77186322e-01 2.11166903e-01 2.32634377e-02 9.77936983e-01 2.07664207e-01 2.32633967e-02 9.78662074e-01 2.04227209e-01 2.32633911e-02 9.79363382e-01 2.00834528e-01 2.32633986e-02 9.80044723e-01 1.97476476e-01 2.32633743e-02 9.80721831e-01 1.94084361e-01 2.32634321e-02 9.81396496e-01 1.90642491e-01 2.32633464e-02 9.82055962e-01 1.87213317e-01 2.32634321e-02 9.82717335e-01 1.83714911e-01 2.32633948e-02 9.83329117e-01 1.80394456e-01 2.32633557e-02 9.83969390e-01 1.76918760e-01 2.32634451e-02 9.84588683e-01 1.73425496e-01 2.32633781e-02 9.85177219e-01 1.70029640e-01 2.32633986e-02 9.85757411e-01 1.66629717e-01 2.32633613e-02 9.86318469e-01 1.63279176e-01 2.32634079e-02 9.86898720e-01 1.59742162e-01 2.32634544e-02 9.87464309e-01 1.56200990e-01 2.32634172e-02 9.88000393e-01 1.52772069e-01 2.32634116e-02 9.88514900e-01 1.49397239e-01 2.32633818e-02 9.89018559e-01 1.46037802e-01 2.32634079e-02 9.89535093e-01 1.42499641e-01 2.32634507e-02 9.90037501e-01 1.38970211e-01 2.32634041e-02 9.90516007e-01 1.35520995e-01 2.32633874e-02 9.90983248e-01 1.32047534e-01 2.32633874e-02 9.91429448e-01 1.28646895e-01 2.32633334e-02 9.91873741e-01 1.25190586e-01 2.32634079e-02 9.92313504e-01 1.21648774e-01 2.32633930e-02 9.92729068e-01 1.18194468e-01 2.32633874e-02 9.93139148e-01 1.14709169e-01 2.32633986e-02 9.93520856e-01 1.11356221e-01 2.32633706e-02 9.93907154e-01 1.07859559e-01 2.32634339e-02 9.94277239e-01 1.04390711e-01 2.32633706e-02 9.94631767e-01 1.00946702e-01 2.32634116e-02 9.94989038e-01 9.73779485e-02 2.32633892e-02 9.95313287e-01 9.39875171e-02 2.32633539e-02 9.95636463e-01 9.05220360e-02 2.32634321e-02 9.95948493e-01 8.70172381e-02 2.32633576e-02 9.96244550e-01 8.35574344e-02 2.32634284e-02 9.96533096e-01 8.00243616e-02 2.32633501e-02 9.96804059e-01 7.66014978e-02 2.32634451e-02 9.97072458e-01 7.30124936e-02 2.32634135e-02 9.97320950e-01 6.95124641e-02 2.32634023e-02 9.97558594e-01 6.60450608e-02 2.32634116e-02 9.97775853e-01 6.26542345e-02 2.32633818e-02 9.97982800e-01 5.92687316e-02 2.32634041e-02 9.98191118e-01 5.56977242e-02 2.32634451e-02 9.98384356e-01 5.20906635e-02 2.32634004e-02 9.98561442e-01 4.86033596e-02 2.32634079e-02 9.98716712e-01 4.52248268e-02 2.32633669e-02 9.98865664e-01 4.18844782e-02 2.32634041e-02 9.99005973e-01 3.83645669e-02 2.32634153e-02 9.99133885e-01 3.48764285e-02 2.32634060e-02 9.99254167e-01 3.12751941e-02 2.32634451e-02 9.99359310e-01 2.76866537e-02 2.32634004e-02 9.99447942e-01 2.43100803e-02 2.32633594e-02 9.99522030e-01 2.09185109e-02 2.32633967e-02 9.99595106e-01 1.74149293e-02 2.32634004e-02 9.99641597e-01 1.39467251e-02 2.32633911e-02 9.99688804e-01 1.04222214e-02 2.32634060e-02 9.99723792e-01 6.96163299e-03 2.32633967e-02 9.99742568e-01 3.35754920e-03 2.32634377e-02 9.99742210e-01 -1.36812174e-04 2.32633669e-02 9.99742091e-01 -3.58635397e-03 2.32634284e-02 9.99720097e-01 -7.15238973e-03 2.32633632e-02 9.99685347e-01 -1.05185034e-02 2.32633855e-02 9.99639273e-01 -1.40453773e-02 2.32634116e-02 9.99588788e-01 -1.76680349e-02 2.32633837e-02 9.99518871e-01 -2.10875068e-02 2.32633706e-02 9.99443054e-01 -2.45846584e-02 2.32634451e-02 9.99347210e-01 -2.80665625e-02 2.32633650e-02 9.99245584e-01 -3.15285288e-02 2.32634246e-02 9.99129474e-01 -3.50313708e-02 2.32633781e-02 9.99003828e-01 -3.84183787e-02 2.32634041e-02 9.98864830e-01 -4.19075266e-02 2.32634041e-02 9.98708963e-01 -4.54532206e-02 2.32634563e-02 9.98539090e-01 -4.90612537e-02 2.32633986e-02 9.98359025e-01 -5.25467619e-02 2.32634079e-02 9.98173535e-01 -5.59599586e-02 2.32633781e-02 9.97979641e-01 -5.93355596e-02 2.32634041e-02 9.97765660e-01 -6.28121868e-02 2.32634004e-02 9.97536421e-01 -6.63792789e-02 2.32634228e-02 9.97288764e-01 -6.99535683e-02 2.32633818e-02 9.97043371e-01 -7.34199286e-02 2.32633930e-02 9.96784449e-01 -7.68329874e-02 2.32633818e-02 9.96516287e-01 -8.02484825e-02 2.32633986e-02 9.96232569e-01 -8.36948007e-02 2.32633948e-02 9.95924711e-01 -8.72850269e-02 2.32634135e-02 9.95614767e-01 -9.07452032e-02 2.32633613e-02 9.95301545e-01 -9.41246375e-02 2.32633967e-02 9.94965911e-01 -9.76102501e-02 2.32633855e-02 9.94609058e-01 -1.01187386e-01 2.32634321e-02 9.94250536e-01 -1.04646765e-01 2.32633725e-02 9.93880510e-01 -1.08103521e-01 2.32634414e-02 9.93496299e-01 -1.11576460e-01 2.32633669e-02 9.93113935e-01 -1.14925750e-01 2.32634060e-02 9.92696226e-01 -1.18493043e-01 2.32634339e-02 9.92273211e-01 -1.21973231e-01 2.32633669e-02 9.91845906e-01 -1.25427619e-01 2.32634321e-02 9.91384685e-01 -1.28996775e-01 2.32634246e-02 9.90940213e-01 -1.32362828e-01 2.32633688e-02 9.90479290e-01 -1.35791272e-01 2.32634284e-02 9.89983439e-01 -1.39356509e-01 2.32634079e-02 9.89501536e-01 -1.42730296e-01 2.32633632e-02 9.88998115e-01 -1.46179840e-01 2.32634321e-02 9.88481402e-01 -1.49625331e-01 2.32633781e-02 9.87954080e-01 -1.53070182e-01 2.32634377e-02 9.87409890e-01 -1.56537324e-01 2.32633725e-02 9.86864626e-01 -1.59949929e-01 2.32634079e-02 9.86298978e-01 -1.63400367e-01 2.32633688e-02 9.85721171e-01 -1.66853800e-01 2.32634116e-02 9.85117793e-01 -1.70365706e-01 2.32634041e-02 9.84526575e-01 -1.73782468e-01 2.32634004e-02 9.83924627e-01 -1.77152291e-01 2.32633855e-02 9.83309448e-01 -1.80507854e-01 2.32633948e-02 9.82674718e-01 -1.83951497e-01 2.32633967e-02 9.82015669e-01 -1.87429294e-01 2.32634321e-02 9.81337070e-01 -1.90949738e-01 2.32634079e-02 9.80662882e-01 -1.94386765e-01 2.32634004e-02 9.79993045e-01 -1.97728619e-01 2.32633743e-02 9.79318559e-01 -2.01044664e-01 2.32633930e-02 9.78610396e-01 -2.04470754e-01 2.32634209e-02 9.77875471e-01 -2.07965553e-01 2.32634563e-02 9.77140009e-01 -2.11385742e-01 2.32633855e-02 9.76408958e-01 -2.14730710e-01 2.32634246e-02 9.75650370e-01 -2.18159914e-01 2.32633855e-02 9.74873424e-01 -2.21600547e-01 2.32634414e-02 9.74092185e-01 -2.25011483e-01 2.32633799e-02 9.73300934e-01 -2.28422493e-01 2.32634451e-02 9.72493351e-01 -2.31828153e-01 2.32633706e-02 9.71710980e-01 -2.35092714e-01 2.32634060e-02 9.70862031e-01 -2.38565788e-01 2.32634451e-02 9.70018804e-01 -2.41964370e-01 2.32633837e-02 9.69165981e-01 -2.45358989e-01 2.32634451e-02 9.68275785e-01 -2.48851985e-01 2.32634004e-02 9.67427731e-01 -2.52124965e-01 2.32633501e-02 9.66547370e-01 -2.55495220e-01 2.32634451e-02 9.65648115e-01 -2.58862168e-01 2.32633650e-02 9.64764118e-01 -2.62142658e-01 2.32634060e-02 9.63822067e-01 -2.65580386e-01 2.32634451e-02 9.62880015e-01 -2.68982142e-01 2.32633837e-02 9.61935699e-01 -2.72335887e-01 2.32634284e-02 9.60956156e-01 -2.75767475e-01 2.32634209e-02 9.60009813e-01 -2.79040307e-01 2.32633688e-02 9.59059477e-01 -2.82295674e-01 2.32634060e-02 9.58046198e-01 -2.85720140e-01 2.32634321e-02 9.57020164e-01 -2.89126575e-01 2.32634041e-02 9.56007779e-01 -2.92463601e-01 2.32634153e-02 9.54997182e-01 -2.95750111e-01 2.32633837e-02 9.53988016e-01 -2.98985869e-01 2.32634060e-02 9.52941656e-01 -3.02303046e-01 2.32634116e-02 9.51853037e-01 -3.05716068e-01 2.32634358e-02 9.50740457e-01 -3.09155345e-01 2.32634135e-02 9.49655175e-01 -3.12474519e-01 2.32634079e-02 9.48587418e-01 -3.15702289e-01 2.32633818e-02 9.47522342e-01 -3.18884552e-01 2.32634060e-02 9.46397781e-01 -3.22206289e-01 2.32634004e-02 9.45242822e-01 -3.25580060e-01 2.32634451e-02 9.44082677e-01 -3.28924030e-01 2.32633855e-02 9.42963183e-01 -3.32122654e-01 2.32633967e-02 9.41809118e-01 -3.35381091e-01 2.32634079e-02 9.40602243e-01 -3.38755310e-01 2.32634470e-02 9.39408183e-01 -3.42055529e-01 2.32633837e-02 9.38199401e-01 -3.45337957e-01 2.32634284e-02 9.36979890e-01 -3.48615140e-01 2.32633837e-02 9.35800612e-01 -3.51777405e-01 2.32634041e-02 9.34571028e-01 -3.55041116e-01 2.32634041e-02 9.33328152e-01 -3.58320385e-01 2.32634209e-02 9.32064593e-01 -3.61575425e-01 2.32634284e-02 9.30772781e-01 -3.64900410e-01 2.32634451e-02 9.29490209e-01 -3.68147612e-01 2.32633818e-02 9.28210139e-01 -3.71364266e-01 2.32634451e-02 9.26896870e-01 -3.74626458e-01 2.32633837e-02 9.25625145e-01 -3.77760738e-01 2.32634079e-02 9.24267948e-01 -3.81068617e-01 2.32634451e-02 9.22923863e-01 -3.84312034e-01 2.32633911e-02 9.21581388e-01 -3.87525499e-01 2.32634414e-02 9.20177162e-01 -3.90840083e-01 2.32634172e-02 9.18841124e-01 -3.93968582e-01 2.32633818e-02 9.17518258e-01 -3.97045165e-01 2.32633967e-02 9.16086674e-01 -4.00345206e-01 2.32634507e-02 9.14622664e-01 -4.03673053e-01 2.32634172e-02 9.13208783e-01 -4.06860799e-01 2.32634041e-02 9.11798775e-01 -4.10010844e-01 2.32633855e-02 9.10398781e-01 -4.13108677e-01 2.32633874e-02 9.08978105e-01 -4.16221559e-01 2.32634041e-02 9.07499135e-01 -4.19438690e-01 2.32634358e-02 9.05983508e-01 -4.22702342e-01 2.32634172e-02 9.04482365e-01 -4.25905496e-01 2.32634153e-02 9.03035641e-01 -4.28963721e-01 2.32633706e-02 9.01597440e-01 -4.31977749e-01 2.32634246e-02 9.00076151e-01 -4.35146987e-01 2.32634190e-02 8.98507297e-01 -4.38378930e-01 2.32634451e-02 8.96941066e-01 -4.41566616e-01 2.32634004e-02 8.95407140e-01 -4.44669515e-01 2.32634116e-02 8.93852472e-01 -4.47784603e-01 2.32633743e-02 8.92344117e-01 -4.50787336e-01 2.32634041e-02 8.90760779e-01 -4.53908086e-01 2.32634153e-02 8.89136672e-01 -4.57081467e-01 2.32634507e-02 8.87523532e-01 -4.60200787e-01 2.32633874e-02 8.85907471e-01 -4.63309914e-01 2.32634246e-02 8.84303570e-01 -4.66363251e-01 2.32633874e-02 8.82710934e-01 -4.69367534e-01 2.32633874e-02 8.81054699e-01 -4.72472280e-01 2.32634209e-02 8.79361868e-01 -4.75615591e-01 2.32634563e-02 8.77685249e-01 -4.78704184e-01 2.32633837e-02 8.76061857e-01 -4.81666684e-01 2.32634209e-02 8.74367237e-01 -4.84731197e-01 2.32634060e-02 8.72648776e-01 -4.87821251e-01 2.32634451e-02 8.70926261e-01 -4.90890235e-01 2.32633706e-02 8.69206131e-01 -4.93930697e-01 2.32634563e-02 8.67479324e-01 -4.96958792e-01 2.32633743e-02 8.65750730e-01 -4.99963999e-01 2.32634526e-02 8.63984048e-01 -5.03008068e-01 2.32633781e-02 8.62271309e-01 -5.05942047e-01 2.32634209e-02 8.60480666e-01 -5.08979917e-01 2.32634135e-02 8.58683765e-01 -5.12003601e-01 2.32634172e-02 8.56864750e-01 -5.15043736e-01 2.32634377e-02 8.55039299e-01 -5.18065214e-01 2.32634284e-02 8.53254557e-01 -5.21003604e-01 2.32633874e-02 8.51488233e-01 -5.23882747e-01 2.32634284e-02 8.49661946e-01 -5.26841760e-01 2.32634135e-02 8.47771764e-01 -5.29876530e-01 2.32634563e-02 8.45879197e-01 -5.32893598e-01 2.32634209e-02 8.44045937e-01 -5.35789251e-01 2.32633874e-02 8.42218280e-01 -5.38658500e-01 2.32634116e-02 8.40284944e-01 -5.41671515e-01 2.32634563e-02 8.38339508e-01 -5.44675171e-01 2.32634135e-02 8.36436629e-01 -5.47590435e-01 2.32634004e-02 8.34519386e-01 -5.50513804e-01 2.32634209e-02 8.32631230e-01 -5.53356528e-01 2.32633669e-02 8.30752373e-01 -5.56177497e-01 2.32633911e-02 8.28822553e-01 -5.59055150e-01 2.32634060e-02 8.26805651e-01 -5.62029958e-01 2.32634246e-02 8.24784100e-01 -5.64992845e-01 2.32633892e-02 8.22826624e-01 -5.67841053e-01 2.32633874e-02 8.20882678e-01 -5.70645332e-01 2.32633781e-02 8.18901837e-01 -5.73484361e-01 2.32634004e-02 8.16887498e-01 -5.76352835e-01 2.32633874e-02 8.14854562e-01 -5.79221785e-01 2.32634321e-02 8.12823892e-01 -5.82067847e-01 2.32633650e-02 8.10817897e-01 -5.84855020e-01 2.32634172e-02 8.08737159e-01 -5.87732971e-01 2.32634209e-02 8.06633353e-01 -5.90614974e-01 2.32634060e-02 8.04570854e-01 -5.93424439e-01 2.32634246e-02 8.02467108e-01 -5.96264601e-01 2.32634004e-02 8.00440490e-01 -5.98980546e-01 2.32633669e-02 7.98370779e-01 -6.01740837e-01 2.32634563e-02 7.96251893e-01 -6.04539514e-01 2.32633743e-02 7.94144332e-01 -6.07307911e-01 2.32634451e-02 7.92015016e-01 -6.10078812e-01 2.32633781e-02 7.89938688e-01 -6.12765491e-01 2.32634209e-02 7.87738919e-01 -6.15591407e-01 2.32634451e-02 7.85528362e-01 -6.18409514e-01 2.32634116e-02 7.83411026e-01 -6.21088386e-01 2.32633855e-02 7.81306446e-01 -6.23737037e-01 2.32634153e-02 7.79066980e-01 -6.26532733e-01 2.32634451e-02 7.76821852e-01 -6.29313290e-01 2.32634209e-02 7.74653018e-01 -6.31976306e-01 2.32633911e-02 7.72508085e-01 -6.34600580e-01 2.32634209e-02 7.70291388e-01 -6.37288928e-01 2.32634172e-02 7.68079102e-01 -6.39953732e-01 2.32634284e-02 7.65842319e-01 -6.42628968e-01 2.32634153e-02 7.63533056e-01 -6.45370901e-01 2.32634451e-02 7.61284292e-01 -6.48019612e-01 2.32633837e-02 7.59066939e-01 -6.50617182e-01 2.32634265e-02 7.56804705e-01 -6.53248549e-01 2.32634116e-02 7.54490912e-01 -6.55920744e-01 2.32634377e-02 7.52141953e-01 -6.58611238e-01 2.32634377e-02 7.49794483e-01 -6.61281943e-01 2.32634041e-02 7.47518897e-01 -6.63853109e-01 2.32633818e-02 7.45272875e-01 -6.66374326e-01 2.32634209e-02 7.42892861e-01 -6.69028640e-01 2.32634433e-02 7.40548790e-01 -6.71621323e-01 2.32633855e-02 7.38198161e-01 -6.74203932e-01 2.32634582e-02 7.35835016e-01 -6.76781297e-01 2.32633688e-02 7.33545005e-01 -6.79262638e-01 2.32634135e-02 7.31177926e-01 -6.81808829e-01 2.32634135e-02 7.28734910e-01 -6.84419751e-01 2.32634377e-02 7.26309299e-01 -6.86990738e-01 2.32633576e-02 7.23901689e-01 -6.89534307e-01 2.32634377e-02 7.21486151e-01 -6.92050874e-01 2.32633390e-02 7.19100356e-01 -6.94545031e-01 2.32634004e-02 7.16642976e-01 -6.97072685e-01 2.32632961e-02 7.14326680e-01 -6.99442148e-01 2.32632514e-02 7.12064147e-01 -7.01731741e-01 2.32630335e-02 7.09159493e-01 -7.04663992e-01 2.32631713e-02 7.07407832e-01 -7.06423104e-01 2.32631322e-02 7.04264283e-01 -7.09555924e-01 2.32631415e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.67043245e-01 -8.23358834e-01 2.32631415e-02 5.64340234e-01 -8.25210571e-01 2.32630633e-02 5.61824799e-01 -8.26936483e-01 2.32631285e-02 5.58949828e-01 -8.28888059e-01 2.32632626e-02 5.56091130e-01 -8.30809772e-01 2.32633408e-02 5.53152978e-01 -8.32768857e-01 2.32633930e-02 5.50214946e-01 -8.34713101e-01 2.32633483e-02 5.47370434e-01 -8.36581111e-01 2.32633688e-02 5.44468045e-01 -8.38473499e-01 2.32633818e-02 5.41544020e-01 -8.40365946e-01 2.32633874e-02 5.38620412e-01 -8.42241228e-01 2.32633911e-02 5.35667956e-01 -8.44122410e-01 2.32634004e-02 5.32727242e-01 -8.45985055e-01 2.32633967e-02 5.29781401e-01 -8.47828686e-01 2.32633874e-02 5.26822031e-01 -8.49674702e-01 2.32633948e-02 5.23863614e-01 -8.51498783e-01 2.32633930e-02 5.20882130e-01 -8.53329301e-01 2.32633892e-02 5.17903030e-01 -8.55137289e-01 2.32633986e-02 5.14913440e-01 -8.56942475e-01 2.32634004e-02 5.11836052e-01 -8.58784914e-01 2.32634377e-02 5.08813143e-01 -8.60577285e-01 2.32633799e-02 5.05911767e-01 -8.62287700e-01 2.32634097e-02 5.02900481e-01 -8.64046216e-01 2.32634004e-02 4.99774545e-01 -8.65860403e-01 2.32634451e-02 4.96741056e-01 -8.67602050e-01 2.32633781e-02 4.93797719e-01 -8.69278908e-01 2.32633930e-02 4.90756899e-01 -8.71004283e-01 2.32634041e-02 4.87728983e-01 -8.72700095e-01 2.32634060e-02 4.84690726e-01 -8.74389470e-01 2.32634321e-02 4.81648535e-01 -8.76071811e-01 2.32634041e-02 4.78571057e-01 -8.77757490e-01 2.32634060e-02 4.75479901e-01 -8.79433572e-01 2.32634153e-02 4.72421288e-01 -8.81080747e-01 2.32634135e-02 4.69342500e-01 -8.82724941e-01 2.32634265e-02 4.66264784e-01 -8.84356558e-01 2.32634209e-02 4.63100940e-01 -8.86016071e-01 2.32634563e-02 4.59988266e-01 -8.87633860e-01 2.32633837e-02 4.56971347e-01 -8.89193118e-01 2.32634209e-02 4.53862458e-01 -8.90782714e-01 2.32634116e-02 4.50754791e-01 -8.92359972e-01 2.32634209e-02 4.47625339e-01 -8.93932998e-01 2.32634284e-02 4.44495171e-01 -8.95495355e-01 2.32634284e-02 4.41370994e-01 -8.97038937e-01 2.32634246e-02 4.38216895e-01 -8.98584008e-01 2.32634135e-02 4.35074300e-01 -9.00110304e-01 2.32634135e-02 4.31945860e-01 -9.01612818e-01 2.32634172e-02 4.28684205e-01 -9.03169334e-01 2.32634731e-02 4.25505549e-01 -9.04670238e-01 2.32633818e-02 4.22391236e-01 -9.06131029e-01 2.32634563e-02 4.19195831e-01 -9.07611370e-01 2.32633762e-02 4.16134059e-01 -9.09019113e-01 2.32634246e-02 4.12958831e-01 -9.10467923e-01 2.32634190e-02 4.09765869e-01 -9.11909163e-01 2.32634246e-02 4.06509668e-01 -9.13366377e-01 2.32634563e-02 4.03292239e-01 -9.14789319e-01 2.32633874e-02 4.00209457e-01 -9.16144371e-01 2.32634135e-02 3.97003710e-01 -9.17536378e-01 2.32634321e-02 3.93792152e-01 -9.18916523e-01 2.32634284e-02 3.90534252e-01 -9.20308948e-01 2.32634321e-02 3.87342036e-01 -9.21658158e-01 2.32634079e-02 3.84147257e-01 -9.22994018e-01 2.32634395e-02 3.80903155e-01 -9.24335599e-01 2.32634060e-02 3.77724111e-01 -9.25641358e-01 2.32634246e-02 3.74491781e-01 -9.26952302e-01 2.32634284e-02 3.71159732e-01 -9.28292215e-01 2.32634563e-02 3.67891133e-01 -9.29592729e-01 2.32633948e-02 3.64714891e-01 -9.30844784e-01 2.32634246e-02 3.61488730e-01 -9.32094812e-01 2.32634209e-02 3.58229995e-01 -9.33362305e-01 2.32634321e-02 3.54944408e-01 -9.34608519e-01 2.32634284e-02 3.51704597e-01 -9.35828328e-01 2.32634284e-02 3.48411232e-01 -9.37058628e-01 2.32634321e-02 3.45070451e-01 -9.38299060e-01 2.32634563e-02 3.41781765e-01 -9.39508200e-01 2.32633855e-02 3.38550925e-01 -9.40675080e-01 2.32634470e-02 3.35267037e-01 -9.41851616e-01 2.32634004e-02 3.31934005e-01 -9.43031251e-01 2.32634563e-02 3.28651994e-01 -9.44177449e-01 2.32633948e-02 3.25344026e-01 -9.45324957e-01 2.32634563e-02 3.22039098e-01 -9.46452260e-01 2.32633892e-02 3.18813413e-01 -9.47547495e-01 2.32634321e-02 3.15492839e-01 -9.48656678e-01 2.32634377e-02 3.12170446e-01 -9.49753881e-01 2.32634023e-02 3.08894664e-01 -9.50825095e-01 2.32634246e-02 3.05563718e-01 -9.51902986e-01 2.32634284e-02 3.02253246e-01 -9.52957153e-01 2.32634172e-02 2.98927933e-01 -9.54007030e-01 2.32634321e-02 2.95583546e-01 -9.55048382e-01 2.32634190e-02 2.92247832e-01 -9.56074476e-01 2.32634246e-02 2.88856328e-01 -9.57102239e-01 2.32634563e-02 2.85494119e-01 -9.58111286e-01 2.32633967e-02 2.82221466e-01 -9.59081590e-01 2.32634209e-02 2.78795898e-01 -9.60083544e-01 2.32634563e-02 2.75348932e-01 -9.61077511e-01 2.32634302e-02 2.71994799e-01 -9.62031782e-01 2.32634172e-02 2.68747360e-01 -9.62944388e-01 2.32633855e-02 2.65484184e-01 -9.63848650e-01 2.32634190e-02 2.62111485e-01 -9.64773893e-01 2.32634284e-02 2.58761466e-01 -9.65675056e-01 2.32634209e-02 2.55284488e-01 -9.66600835e-01 2.32634731e-02 2.51888126e-01 -9.67490911e-01 2.32633874e-02 2.48531908e-01 -9.68358457e-01 2.32634563e-02 2.45124578e-01 -9.69224572e-01 2.32633855e-02 2.41777241e-01 -9.70066011e-01 2.32634563e-02 2.38342822e-01 -9.70916510e-01 2.32633892e-02 2.35050246e-01 -9.71720874e-01 2.32634339e-02 2.31643885e-01 -9.72539186e-01 2.32634451e-02 2.28234947e-01 -9.73343849e-01 2.32634135e-02 2.24877343e-01 -9.74124849e-01 2.32634284e-02 2.21358716e-01 -9.74929512e-01 2.32634563e-02 2.17953295e-01 -9.75696743e-01 2.32633892e-02 2.14621082e-01 -9.76433456e-01 2.32634135e-02 2.11202472e-01 -9.77179408e-01 2.32634284e-02 2.07808435e-01 -9.77907538e-01 2.32634246e-02 2.04327703e-01 -9.78641868e-01 2.32634563e-02 2.00892210e-01 -9.79351819e-01 2.32633930e-02 1.97560072e-01 -9.80028927e-01 2.32634358e-02 1.94130614e-01 -9.80713844e-01 2.32634284e-02 1.90701097e-01 -9.81387019e-01 2.32634321e-02 1.87195227e-01 -9.82061028e-01 2.32634638e-02 1.83758944e-01 -9.82708514e-01 2.32633874e-02 1.80330068e-01 -9.83343244e-01 2.32634451e-02 1.76884204e-01 -9.83974636e-01 2.32633874e-02 1.73554659e-01 -9.84567285e-01 2.32634246e-02 1.70127437e-01 -9.85159576e-01 2.32634284e-02 1.66687995e-01 -9.85750258e-01 2.32634321e-02 1.63242355e-01 -9.86324549e-01 2.32634377e-02 1.59808531e-01 -9.86887336e-01 2.32634284e-02 1.56371549e-01 -9.87438977e-01 2.32634377e-02 1.52920291e-01 -9.87978876e-01 2.32634358e-02 1.49469927e-01 -9.88504171e-01 2.32634284e-02 1.45987749e-01 -9.89026248e-01 2.32634563e-02 1.42535880e-01 -9.89527583e-01 2.32634004e-02 1.39104277e-01 -9.90017414e-01 2.32634172e-02 1.35546178e-01 -9.90512550e-01 2.32634600e-02 1.32079720e-01 -9.90978062e-01 2.32633874e-02 1.28705472e-01 -9.91423965e-01 2.32634209e-02 1.25270903e-01 -9.91864681e-01 2.32634284e-02 1.21785700e-01 -9.92297113e-01 2.32634377e-02 1.18227251e-01 -9.92728353e-01 2.32634749e-02 1.14759818e-01 -9.93132949e-01 2.32633948e-02 1.11397415e-01 -9.93517160e-01 2.32634321e-02 1.07916310e-01 -9.93900657e-01 2.32634284e-02 1.04462199e-01 -9.94269848e-01 2.32634321e-02 1.00890145e-01 -9.94637489e-01 2.32634582e-02 9.74134058e-02 -9.94985044e-01 2.32633930e-02 9.39615592e-02 -9.95320082e-01 2.32634731e-02 9.04497877e-02 -9.95643258e-01 2.32633967e-02 8.70006308e-02 -9.95951295e-01 2.32634563e-02 8.34329575e-02 -9.96254742e-01 2.32634265e-02 8.00490156e-02 -9.96532977e-01 2.32633930e-02 7.66517445e-02 -9.96799409e-01 2.32634377e-02 7.31675923e-02 -9.97062683e-01 2.32634321e-02 6.96979165e-02 -9.97308850e-01 2.32634321e-02 6.62099496e-02 -9.97548163e-01 2.32634284e-02 6.27448484e-02 -9.97772038e-01 2.32634284e-02 5.92381805e-02 -9.97986019e-01 2.32634321e-02 5.57597503e-02 -9.98187184e-01 2.32634284e-02 5.22758588e-02 -9.98373628e-01 2.32634284e-02 4.88174893e-02 -9.98551548e-01 2.32634284e-02 4.53495234e-02 -9.98714507e-01 2.32634377e-02 4.17415760e-02 -9.98870909e-01 2.32634731e-02 3.82505693e-02 -9.99009669e-01 2.32633892e-02 3.48857008e-02 -9.99133587e-01 2.32634209e-02 3.12979855e-02 -9.99252498e-01 2.32634563e-02 2.77738236e-02 -9.99356925e-01 2.32633948e-02 2.42881421e-02 -9.99450862e-01 2.32634656e-02 2.07896736e-02 -9.99524117e-01 2.32633874e-02 1.74332354e-02 -9.99594867e-01 2.32634190e-02 1.38443364e-02 -9.99642074e-01 2.32634731e-02 1.03297578e-02 -9.99688089e-01 2.32633892e-02 6.94443332e-03 -9.99725044e-01 2.32634284e-02 3.47160595e-03 -9.99742389e-01 2.32634284e-02 -4.56681664e-05 -9.99743521e-01 2.32634321e-02 -3.62157146e-03 -9.99742627e-01 2.32634563e-02 -7.10815564e-03 -9.99723136e-01 2.32633948e-02 -1.05872145e-02 -9.99687910e-01 2.32634563e-02 -1.40710948e-02 -9.99639273e-01 2.32633930e-02 -1.75501388e-02 -9.99595404e-01 2.32634563e-02 -2.11275928e-02 -9.99517977e-01 2.32634339e-02 -2.45517548e-02 -9.99443293e-01 2.32634116e-02 -2.79665608e-02 -9.99352753e-01 2.32634377e-02 -3.14489156e-02 -9.99249816e-01 2.32634377e-02 -3.49262394e-02 -9.99134660e-01 2.32634451e-02 -3.85160707e-02 -9.99001861e-01 2.32634731e-02 -4.20261659e-02 -9.98859406e-01 2.32633986e-02 -4.53839935e-02 -9.98711705e-01 2.32634451e-02 -4.88782451e-02 -9.98549044e-01 2.32634321e-02 -5.23520857e-02 -9.98369515e-01 2.32634321e-02 -5.59088178e-02 -9.98180687e-01 2.32634600e-02 -5.94093241e-02 -9.97976124e-01 2.32633948e-02 -6.28927127e-02 -9.97760415e-01 2.32634563e-02 -6.63697124e-02 -9.97536242e-01 2.32633986e-02 -6.97671399e-02 -9.97304380e-01 2.32634321e-02 -7.33184367e-02 -9.97051775e-01 2.32634693e-02 -7.68111944e-02 -9.96786416e-01 2.32634060e-02 -8.02775323e-02 -9.96515095e-01 2.32634563e-02 -8.37635174e-02 -9.96226370e-01 2.32634023e-02 -8.71607512e-02 -9.95936155e-01 2.32634321e-02 -9.07120258e-02 -9.95619059e-01 2.32634731e-02 -9.42037478e-02 -9.95293379e-01 2.32634004e-02 -9.76613164e-02 -9.94961858e-01 2.32634731e-02 -1.01140395e-01 -9.94613945e-01 2.32633892e-02 -1.04595035e-01 -9.94257629e-01 2.32634768e-02 -1.08183540e-01 -9.93872225e-01 2.32634284e-02 -1.11552380e-01 -9.93499458e-01 2.32633930e-02 -1.14915207e-01 -9.93116200e-01 2.32634321e-02 -1.18396163e-01 -9.92706716e-01 2.32634377e-02 -1.21848293e-01 -9.92290378e-01 2.32634414e-02 -1.25401631e-01 -9.91848290e-01 2.32634731e-02 -1.28899440e-01 -9.91396844e-01 2.32634060e-02 -1.32244661e-01 -9.90958750e-01 2.32634321e-02 -1.35692403e-01 -9.90491867e-01 2.32634321e-02 -1.39140636e-01 -9.90013957e-01 2.32634451e-02 -1.42702118e-01 -9.89505947e-01 2.32634731e-02 -1.46154955e-01 -9.89000499e-01 2.32633967e-02 -1.49587408e-01 -9.88487780e-01 2.32634731e-02 -1.53050810e-01 -9.87959445e-01 2.32633986e-02 -1.56391591e-01 -9.87434387e-01 2.32634377e-02 -1.59857690e-01 -9.86880600e-01 2.32634451e-02 -1.63283601e-01 -9.86320078e-01 2.32634284e-02 -1.66837037e-01 -9.85726058e-01 2.32634731e-02 -1.70289546e-01 -9.85131562e-01 2.32633948e-02 -1.73620105e-01 -9.84555483e-01 2.32634451e-02 -1.77113533e-01 -9.83932316e-01 2.32634563e-02 -1.80554688e-01 -9.83301580e-01 2.32634209e-02 -1.84029162e-01 -9.82661545e-01 2.32634731e-02 -1.87471956e-01 -9.82007504e-01 2.32633874e-02 -1.90792069e-01 -9.81368423e-01 2.32634377e-02 -1.94227636e-01 -9.80694771e-01 2.32634377e-02 -1.97710037e-01 -9.79999721e-01 2.32634731e-02 -2.01170698e-01 -9.79292691e-01 2.32634060e-02 -2.04500884e-01 -9.78603303e-01 2.32634377e-02 -2.07903743e-01 -9.77889061e-01 2.32634377e-02 -2.11391509e-01 -9.77140188e-01 2.32634600e-02 -2.14825585e-01 -9.76386726e-01 2.32634041e-02 -2.18129680e-01 -9.75657403e-01 2.32634377e-02 -2.21542165e-01 -9.74887311e-01 2.32634451e-02 -2.24934235e-01 -9.74109828e-01 2.32634377e-02 -2.28415176e-01 -9.73303914e-01 2.32634675e-02 -2.31816590e-01 -9.72496450e-01 2.32634041e-02 -2.35116422e-01 -9.71705496e-01 2.32634377e-02 -2.38580763e-01 -9.70859587e-01 2.32634731e-02 -2.41990760e-01 -9.70012724e-01 2.32634041e-02 -2.45361745e-01 -9.69165564e-01 2.32634731e-02 -2.48748288e-01 -9.68303442e-01 2.32633986e-02 -2.52023488e-01 -9.67455626e-01 2.32634321e-02 -2.55418807e-01 -9.66566086e-01 2.32634321e-02 -2.58869231e-01 -9.65646684e-01 2.32634619e-02 -2.62340784e-01 -9.64709818e-01 2.32634284e-02 -2.65640438e-01 -9.63804603e-01 2.32633986e-02 -2.68867701e-01 -9.62912321e-01 2.32634451e-02 -2.72259086e-01 -9.61958289e-01 2.32634414e-02 -2.75618285e-01 -9.60999489e-01 2.32634377e-02 -2.78965622e-01 -9.60034490e-01 2.32634321e-02 -2.82307446e-01 -9.59056377e-01 2.32634451e-02 -2.85642892e-01 -9.58070159e-01 2.32634451e-02 -2.88991749e-01 -9.57062244e-01 2.32634451e-02 -2.92332590e-01 -9.56046522e-01 2.32634451e-02 -2.95749098e-01 -9.54999506e-01 2.32634731e-02 -2.99110800e-01 -9.53948557e-01 2.32634135e-02 -3.02428156e-01 -9.52903986e-01 2.32634675e-02 -3.05746347e-01 -9.51844335e-01 2.32634041e-02 -3.08948547e-01 -9.50808942e-01 2.32634377e-02 -3.12363416e-01 -9.49692965e-01 2.32634731e-02 -3.15739661e-01 -9.48575437e-01 2.32634302e-02 -3.19046587e-01 -9.47470248e-01 2.32634526e-02 -3.22301030e-01 -9.46365476e-01 2.32634060e-02 -3.25500160e-01 -9.45270956e-01 2.32634451e-02 -3.28834325e-01 -9.44114864e-01 2.32634563e-02 -3.32134187e-01 -9.42960322e-01 2.32634377e-02 -3.35459709e-01 -9.41782117e-01 2.32634544e-02 -3.38756949e-01 -9.40599442e-01 2.32633986e-02 -3.42029512e-01 -9.39418137e-01 2.32634731e-02 -3.45309556e-01 -9.38208759e-01 2.32634116e-02 -3.48509789e-01 -9.37021613e-01 2.32634451e-02 -3.51773679e-01 -9.35802519e-01 2.32634451e-02 -3.55038017e-01 -9.34574544e-01 2.32634451e-02 -3.58386815e-01 -9.33303177e-01 2.32634731e-02 -3.61740917e-01 -9.32000339e-01 2.32634451e-02 -3.64912450e-01 -9.30765927e-01 2.32633930e-02 -3.68056864e-01 -9.29527402e-01 2.32634284e-02 -3.71288359e-01 -9.28240359e-01 2.32634451e-02 -3.74522179e-01 -9.26941037e-01 2.32634321e-02 -3.77834380e-01 -9.25596058e-01 2.32634731e-02 -3.81164938e-01 -9.24226999e-01 2.32634321e-02 -3.84308755e-01 -9.22925532e-01 2.32633986e-02 -3.87422860e-01 -9.21623111e-01 2.32634377e-02 -3.90654653e-01 -9.20258164e-01 2.32634451e-02 -3.93936068e-01 -9.18854773e-01 2.32634768e-02 -3.97167116e-01 -9.17464554e-01 2.32633986e-02 -4.00361180e-01 -9.16079462e-01 2.32634731e-02 -4.03560787e-01 -9.14671719e-01 2.32634041e-02 -4.06663626e-01 -9.13297534e-01 2.32634451e-02 -4.09861416e-01 -9.11867142e-01 2.32634284e-02 -4.13022995e-01 -9.10437286e-01 2.32634246e-02 -4.16268080e-01 -9.08958316e-01 2.32634600e-02 -4.19428647e-01 -9.07503247e-01 2.32634041e-02 -4.22528595e-01 -9.06065643e-01 2.32634377e-02 -4.25692439e-01 -9.04583752e-01 2.32634321e-02 -4.28923666e-01 -9.03056562e-01 2.32634731e-02 -4.32080299e-01 -9.01548028e-01 2.32634079e-02 -4.35144007e-01 -9.00078714e-01 2.32634395e-02 -4.38293457e-01 -8.98548841e-01 2.32634321e-02 -4.41489995e-01 -8.96979690e-01 2.32634563e-02 -4.44617391e-01 -8.95434916e-01 2.32633967e-02 -4.47644591e-01 -8.93924177e-01 2.32634302e-02 -4.50787604e-01 -8.92345726e-01 2.32634377e-02 -4.53883499e-01 -8.90773833e-01 2.32634358e-02 -4.57068354e-01 -8.89144182e-01 2.32634656e-02 -4.60176229e-01 -8.87536287e-01 2.32633948e-02 -4.63183075e-01 -8.85975420e-01 2.32634377e-02 -4.66269016e-01 -8.84352863e-01 2.32634265e-02 -4.69345957e-01 -8.82724285e-01 2.32634377e-02 -4.72513914e-01 -8.81034493e-01 2.32634563e-02 -4.75599587e-01 -8.79368544e-01 2.32633967e-02 -4.78639543e-01 -8.77721190e-01 2.32634563e-02 -4.81714606e-01 -8.76034617e-01 2.32633855e-02 -4.84777391e-01 -8.74343872e-01 2.32634768e-02 -4.87920582e-01 -8.72593641e-01 2.32634321e-02 -4.90877122e-01 -8.70934188e-01 2.32633986e-02 -4.93896157e-01 -8.69227409e-01 2.32634768e-02 -4.96949196e-01 -8.67484570e-01 2.32633967e-02 -4.99882728e-01 -8.65796804e-01 2.32634451e-02 -5.02910495e-01 -8.64041746e-01 2.32634451e-02 -5.05927801e-01 -8.62278521e-01 2.32634377e-02 -5.08928299e-01 -8.60511124e-01 2.32634377e-02 -5.11917830e-01 -8.58735621e-01 2.32634377e-02 -5.14905870e-01 -8.56947660e-01 2.32634321e-02 -5.17920554e-01 -8.55127931e-01 2.32634451e-02 -5.20983517e-01 -8.53268564e-01 2.32634563e-02 -5.24013519e-01 -8.51408422e-01 2.32634377e-02 -5.26918828e-01 -8.49613607e-01 2.32633986e-02 -5.29779911e-01 -8.47833335e-01 2.32634433e-02 -5.32821596e-01 -8.45924795e-01 2.32634768e-02 -5.35794079e-01 -8.44043851e-01 2.32634004e-02 -5.38725019e-01 -8.42176259e-01 2.32634731e-02 -5.41679859e-01 -8.40277791e-01 2.32633892e-02 -5.44509292e-01 -8.38447571e-01 2.32634321e-02 -5.47507942e-01 -8.36492777e-01 2.32634768e-02 -5.50442934e-01 -8.34565520e-01 2.32633948e-02 -5.53241134e-01 -8.32709610e-01 2.32634377e-02 -5.56154728e-01 -8.30769062e-01 2.32634377e-02 -5.59129477e-01 -8.28773797e-01 2.32634768e-02 -5.62045455e-01 -8.26793194e-01 2.32633892e-02 -5.64840376e-01 -8.24891150e-01 2.32634246e-02 -5.67710698e-01 -8.22917759e-01 2.32634321e-02 -5.70568442e-01 -8.20937991e-01 2.32634451e-02 -5.73523343e-01 -8.18874896e-01 2.32634768e-02 -5.76489627e-01 -8.16793442e-01 2.32634377e-02 -5.79255760e-01 -8.14829469e-01 2.32633911e-02 -5.81996679e-01 -8.12876225e-01 2.32634451e-02 -5.84833920e-01 -8.10832918e-01 2.32634339e-02 -5.87676823e-01 -8.08780074e-01 2.32634377e-02 -5.90560734e-01 -8.06674123e-01 2.32634563e-02 -5.93447745e-01 -8.04553032e-01 2.32634377e-02 -5.96194565e-01 -8.02520096e-01 2.32633986e-02 -5.98905146e-01 -8.00497591e-01 2.32634377e-02 -6.01698458e-01 -7.98401892e-01 2.32634377e-02 -6.04535997e-01 -7.96258211e-01 2.32634582e-02 -6.07341766e-01 -7.94117153e-01 2.32634004e-02 -6.10103607e-01 -7.91997850e-01 2.32634693e-02 -6.12863481e-01 -7.89862812e-01 2.32633948e-02 -6.15539432e-01 -7.87779570e-01 2.32634414e-02 -6.18369281e-01 -7.85562456e-01 2.32634731e-02 -6.21095836e-01 -7.83406198e-01 2.32633930e-02 -6.23820424e-01 -7.81240523e-01 2.32634731e-02 -6.26550734e-01 -7.79050529e-01 2.32633930e-02 -6.29179418e-01 -7.76932240e-01 2.32634377e-02 -6.31890357e-01 -7.74724543e-01 2.32634377e-02 -6.34587705e-01 -7.72519290e-01 2.32634358e-02 -6.37339294e-01 -7.70251513e-01 2.32634731e-02 -6.40040159e-01 -7.68005788e-01 2.32633874e-02 -6.42647684e-01 -7.65827298e-01 2.32634284e-02 -6.45372927e-01 -7.63532281e-01 2.32634731e-02 -6.48046672e-01 -7.61261523e-01 2.32633855e-02 -6.50620520e-01 -7.59064734e-01 2.32634358e-02 -6.53282344e-01 -7.56776094e-01 2.32634302e-02 -6.55905724e-01 -7.54504681e-01 2.32634321e-02 -6.58617079e-01 -7.52135158e-01 2.32634563e-02 -6.61231577e-01 -7.49838352e-01 2.32633837e-02 -6.63773000e-01 -7.47590005e-01 2.32634079e-02 -6.66377425e-01 -7.45269358e-01 2.32634284e-02 -6.68976545e-01 -7.42937684e-01 2.32634321e-02 -6.71618164e-01 -7.40552843e-01 2.32634563e-02 -6.74203396e-01 -7.38195360e-01 2.32633986e-02 -6.76783621e-01 -7.35836864e-01 2.32634563e-02 -6.79355443e-01 -7.33458996e-01 2.32633874e-02 -6.81907356e-01 -7.31087506e-01 2.32634563e-02 -6.84525013e-01 -7.28636265e-01 2.32634321e-02 -6.87000215e-01 -7.26300776e-01 2.32633892e-02 -6.89501882e-01 -7.23931730e-01 2.32634563e-02 -6.92057133e-01 -7.21480310e-01 2.32633743e-02 -6.94492102e-01 -7.19150662e-01 2.32634116e-02 -6.96996987e-01 -7.16722071e-01 2.32634246e-02 -6.99474990e-01 -7.14300752e-01 2.32634284e-02 -7.02042282e-01 -7.11780965e-01 2.32634731e-02 -7.04551280e-01 -7.09297478e-01 2.32633818e-02 -7.06913292e-01 -7.06925809e-01 2.32634395e-02 -7.09392071e-01 -7.04456866e-01 2.32634284e-02 -7.11925387e-01 -7.01895773e-01 2.32634768e-02 -7.14392900e-01 -6.99379086e-01 2.32633818e-02 -7.16739297e-01 -6.96979105e-01 2.32634172e-02 -7.19160855e-01 -6.94482028e-01 2.32634284e-02 -7.21640944e-01 -6.91891730e-01 2.32634563e-02 -7.24131525e-01 -6.89292908e-01 2.32634246e-02 -7.26536810e-01 -6.86753035e-01 2.32634321e-02 -7.28875518e-01 -6.84267700e-01 2.32633818e-02 -7.31172085e-01 -6.81813896e-01 2.32634228e-02 -7.33620524e-01 -6.79182291e-01 2.32634563e-02 -7.35989213e-01 -6.76615119e-01 2.32633948e-02 -7.38288462e-01 -6.74104512e-01 2.32634377e-02 -7.40648031e-01 -6.71512783e-01 2.32634339e-02 -7.42992640e-01 -6.68916345e-01 2.32634246e-02 -7.45320261e-01 -6.66321278e-01 2.32634246e-02 -7.47637391e-01 -6.63722813e-01 2.32634246e-02 -7.50012219e-01 -6.61035895e-01 2.32634563e-02 -7.52313137e-01 -6.58413589e-01 2.32633874e-02 -7.54602492e-01 -6.55790567e-01 2.32634563e-02 -7.56950378e-01 -6.53078198e-01 2.32634135e-02 -7.59165466e-01 -6.50503099e-01 2.32633725e-02 -7.61420906e-01 -6.47861123e-01 2.32634563e-02 -7.63694644e-01 -6.45181239e-01 2.32633892e-02 -7.65877008e-01 -6.42587543e-01 2.32634284e-02 -7.68161476e-01 -6.39857888e-01 2.32634563e-02 -7.70401895e-01 -6.37154281e-01 2.32633930e-02 -7.72569060e-01 -6.34528458e-01 2.32634246e-02 -7.74770796e-01 -6.31834209e-01 2.32634321e-02 -7.76966631e-01 -6.29134417e-01 2.32634209e-02 -7.79214263e-01 -6.26349211e-01 2.32634563e-02 -7.81453729e-01 -6.23553157e-01 2.32634284e-02 -7.83630371e-01 -6.20814443e-01 2.32634321e-02 -7.85749316e-01 -6.18130028e-01 2.32634041e-02 -7.87838936e-01 -6.15465701e-01 2.32634377e-02 -7.90033937e-01 -6.12646222e-01 2.32634563e-02 -7.92170048e-01 -6.09880447e-01 2.32633986e-02 -7.94282913e-01 -6.07127190e-01 2.32634731e-02 -7.96407521e-01 -6.04335010e-01 2.32633930e-02 -7.98443913e-01 -6.01643682e-01 2.32634284e-02 -8.00525784e-01 -5.98868668e-01 2.32634284e-02 -8.02608728e-01 -5.96072853e-01 2.32634451e-02 -8.04745913e-01 -5.93186378e-01 2.32634693e-02 -8.06824267e-01 -5.90355635e-01 2.32634041e-02 -8.08891058e-01 -5.87522805e-01 2.32634731e-02 -8.10992301e-01 -5.84613144e-01 2.32634172e-02 -8.12957823e-01 -5.81881642e-01 2.32633986e-02 -8.14980388e-01 -5.79047084e-01 2.32634731e-02 -8.17011654e-01 -5.76176226e-01 2.32633986e-02 -8.18956316e-01 -5.73408306e-01 2.32634451e-02 -8.21006477e-01 -5.70468366e-01 2.32634805e-02 -8.23005497e-01 -5.67582190e-01 2.32633874e-02 -8.24911535e-01 -5.64808309e-01 2.32634563e-02 -8.26892912e-01 -5.61902702e-01 2.32634358e-02 -8.28850806e-01 -5.59012771e-01 2.32634433e-02 -8.30842733e-01 -5.56045890e-01 2.32634768e-02 -8.32797945e-01 -5.53109050e-01 2.32634041e-02 -8.34715962e-01 -5.50214469e-01 2.32634731e-02 -8.36636424e-01 -5.47287405e-01 2.32633986e-02 -8.38488400e-01 -5.44448912e-01 2.32634321e-02 -8.40378463e-01 -5.41525304e-01 2.32634339e-02 -8.42253804e-01 -5.38603365e-01 2.32634209e-02 -8.44173729e-01 -5.35590053e-01 2.32634563e-02 -8.46039057e-01 -5.32639921e-01 2.32634004e-02 -8.47844660e-01 -5.29758215e-01 2.32634190e-02 -8.49689186e-01 -5.26799917e-01 2.32634339e-02 -8.51519167e-01 -5.23831546e-01 2.32634284e-02 -8.53388190e-01 -5.20786703e-01 2.32634563e-02 -8.55211914e-01 -5.17781138e-01 2.32634023e-02 -8.57002914e-01 -5.14816523e-01 2.32634675e-02 -8.58788610e-01 -5.11825264e-01 2.32634041e-02 -8.60527277e-01 -5.08899987e-01 2.32634246e-02 -8.62327099e-01 -5.05846977e-01 2.32634563e-02 -8.64095390e-01 -5.02816617e-01 2.32633948e-02 -8.65806282e-01 -4.99868274e-01 2.32634284e-02 -8.67528498e-01 -4.96869743e-01 2.32634321e-02 -8.69268239e-01 -4.93819177e-01 2.32634451e-02 -8.70992243e-01 -4.90778685e-01 2.32634358e-02 -8.72692287e-01 -4.87741947e-01 2.32634433e-02 -8.74376655e-01 -4.84714836e-01 2.32634377e-02 -8.76124561e-01 -4.81554389e-01 2.32634563e-02 -8.77809763e-01 -4.78476435e-01 2.32633911e-02 -8.79419923e-01 -4.75505859e-01 2.32634321e-02 -8.81088614e-01 -4.72408980e-01 2.32634451e-02 -8.82785261e-01 -4.69231606e-01 2.32634600e-02 -8.84460807e-01 -4.66064483e-01 2.32634209e-02 -8.86028528e-01 -4.63076502e-01 2.32633874e-02 -8.87590349e-01 -4.60076153e-01 2.32634228e-02 -8.89196992e-01 -4.56965059e-01 2.32634209e-02 -8.90830576e-01 -4.53770131e-01 2.32634563e-02 -8.92412364e-01 -4.50650394e-01 2.32633911e-02 -8.93929064e-01 -4.47634339e-01 2.32634451e-02 -8.95525932e-01 -4.44435179e-01 2.32634563e-02 -8.97084236e-01 -4.41276044e-01 2.32633855e-02 -8.98578286e-01 -4.38231379e-01 2.32634321e-02 -9.00142848e-01 -4.35010910e-01 2.32634731e-02 -9.01700854e-01 -4.31765199e-01 2.32634377e-02 -9.03204560e-01 -4.28611070e-01 2.32634284e-02 -9.04655993e-01 -4.25535738e-01 2.32633892e-02 -9.06091869e-01 -4.22475606e-01 2.32634321e-02 -9.07604814e-01 -4.19215560e-01 2.32634563e-02 -9.09108043e-01 -4.15942550e-01 2.32634321e-02 -9.10508990e-01 -4.12866265e-01 2.32634041e-02 -9.11911070e-01 -4.09761906e-01 2.32634321e-02 -9.13331628e-01 -4.06584978e-01 2.32634377e-02 -9.14778173e-01 -4.03322846e-01 2.32634731e-02 -9.16189849e-01 -4.00106996e-01 2.32633930e-02 -9.17575896e-01 -3.96915317e-01 2.32634731e-02 -9.18955266e-01 -3.93699646e-01 2.32634004e-02 -9.20285523e-01 -3.90587598e-01 2.32634302e-02 -9.21678066e-01 -3.87295693e-01 2.32634582e-02 -9.23029840e-01 -3.84057373e-01 2.32633948e-02 -9.24356937e-01 -3.80855381e-01 2.32634731e-02 -9.25691128e-01 -3.77597243e-01 2.32633911e-02 -9.26966488e-01 -3.74456316e-01 2.32634284e-02 -9.28299308e-01 -3.71140897e-01 2.32634563e-02 -9.29596186e-01 -3.67881835e-01 2.32633874e-02 -9.30868924e-01 -3.64656121e-01 2.32634731e-02 -9.32139993e-01 -3.61371964e-01 2.32634004e-02 -9.33366716e-01 -3.58220041e-01 2.32634339e-02 -9.34637725e-01 -3.54873121e-01 2.32634731e-02 -9.35861409e-01 -3.51613224e-01 2.32633930e-02 -9.37046409e-01 -3.48443538e-01 2.32634228e-02 -9.38288748e-01 -3.45097810e-01 2.32634563e-02 -9.39500213e-01 -3.41803104e-01 2.32634079e-02 -9.40687954e-01 -3.38513494e-01 2.32634563e-02 -9.41863954e-01 -3.35231841e-01 2.32633948e-02 -9.43018854e-01 -3.31966549e-01 2.32634563e-02 -9.44177508e-01 -3.28651667e-01 2.32633948e-02 -9.45292234e-01 -3.25439215e-01 2.32634246e-02 -9.46420491e-01 -3.22140753e-01 2.32634265e-02 -9.47533071e-01 -3.18854660e-01 2.32634321e-02 -9.48668361e-01 -3.15456003e-01 2.32634563e-02 -9.49769080e-01 -3.12124938e-01 2.32633986e-02 -9.50827777e-01 -3.08889985e-01 2.32634284e-02 -9.51927304e-01 -3.05487037e-01 2.32634563e-02 -9.52989995e-01 -3.02153498e-01 2.32633948e-02 -9.54034209e-01 -2.98844308e-01 2.32634656e-02 -9.55073237e-01 -2.95498192e-01 2.32633892e-02 -9.56094384e-01 -2.92181313e-01 2.32634731e-02 -9.57109213e-01 -2.88834810e-01 2.32633874e-02 -9.58074033e-01 -2.85620660e-01 2.32634284e-02 -9.59096253e-01 -2.82175094e-01 2.32634731e-02 -9.60080922e-01 -2.78805345e-01 2.32633930e-02 -9.61023092e-01 -2.75536746e-01 2.32634284e-02 -9.61974978e-01 -2.72196740e-01 2.32634284e-02 -9.62924063e-01 -2.68820941e-01 2.32634284e-02 -9.63855207e-01 -2.65459210e-01 2.32634321e-02 -9.64776158e-01 -2.62104571e-01 2.32634321e-02 -9.65680659e-01 -2.58739531e-01 2.32634321e-02 -9.66604352e-01 -2.55273968e-01 2.32634749e-02 -9.67520356e-01 -2.51777649e-01 2.32634284e-02 -9.68374789e-01 -2.48471603e-01 2.32633930e-02 -9.69206512e-01 -2.45196059e-01 2.32634284e-02 -9.70077217e-01 -2.41735145e-01 2.32634675e-02 -9.70945239e-01 -2.38231093e-01 2.32634321e-02 -9.71748710e-01 -2.34928340e-01 2.32633874e-02 -9.72537041e-01 -2.31649026e-01 2.32634246e-02 -9.73337591e-01 -2.28258893e-01 2.32634265e-02 -9.74148035e-01 -2.24770680e-01 2.32634563e-02 -9.74932849e-01 -2.21338719e-01 2.32633874e-02 -9.75675166e-01 -2.18051285e-01 2.32634321e-02 -9.76443827e-01 -2.14579046e-01 2.32634563e-02 -9.77188349e-01 -2.11154252e-01 2.32633967e-02 -9.77908611e-01 -2.07803905e-01 2.32634284e-02 -9.78623390e-01 -2.04410940e-01 2.32634209e-02 -9.79351044e-01 -2.00905353e-01 2.32634563e-02 -9.80058491e-01 -1.97415426e-01 2.32634321e-02 -9.80725169e-01 -1.94073513e-01 2.32633874e-02 -9.81383860e-01 -1.90720633e-01 2.32634284e-02 -9.82052803e-01 -1.87234312e-01 2.32634451e-02 -9.82716203e-01 -1.83723584e-01 2.32634060e-02 -9.83337164e-01 -1.80355459e-01 2.32633911e-02 -9.83952105e-01 -1.77010447e-01 2.32634135e-02 -9.84563708e-01 -1.73582599e-01 2.32634284e-02 -9.85169232e-01 -1.70077443e-01 2.32634451e-02 -9.85772371e-01 -1.66551724e-01 2.32634209e-02 -9.86332238e-01 -1.63194269e-01 2.32633855e-02 -9.86882269e-01 -1.59841686e-01 2.32634060e-02 -9.87439990e-01 -1.56359717e-01 2.32634041e-02 -9.87991095e-01 -1.52842015e-01 2.32634451e-02 -9.88512814e-01 -1.49414062e-01 2.32633818e-02 -9.89033639e-01 -1.45944327e-01 2.32634563e-02 -9.89535809e-01 -1.42485395e-01 2.32633855e-02 -9.90015626e-01 -1.39126882e-01 2.32634135e-02 -9.90504622e-01 -1.35603696e-01 2.32634451e-02 -9.90973175e-01 -1.32118270e-01 2.32633781e-02 -9.91429389e-01 -1.28669143e-01 2.32634377e-02 -9.91870999e-01 -1.25208870e-01 2.32633688e-02 -9.92290914e-01 -1.21831700e-01 2.32633911e-02 -9.92721140e-01 -1.18269891e-01 2.32634284e-02 -9.93126452e-01 -1.14795074e-01 2.32633501e-02 -9.93522704e-01 -1.11347213e-01 2.32633892e-02 -9.93909836e-01 -1.07813455e-01 2.32633129e-02 -9.94272113e-01 -1.04406908e-01 2.32632365e-02 -9.94629741e-01 -1.00944214e-01 2.32632440e-02 -9.94967103e-01 -9.75158662e-02 2.32630670e-02 -9.95278001e-01 -9.41980481e-02 2.32630447e-02 -9.95590627e-01 -9.08763781e-02 2.32631657e-02 -9.95892823e-01 -8.74942467e-02 2.32631415e-02 -9.96182799e-01 -8.41334015e-02 2.32631397e-02 -9.96438801e-01 -8.10468346e-02 2.32631415e-02 -9.96756136e-01 -7.70462379e-02 2.32631397e-02 -9.97057080e-01 -7.30443746e-02 2.32631397e-02 -9.97269154e-01 -7.00856522e-02 2.32631415e-02 -9.97634351e-01 -6.46887869e-02 2.32631397e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98494804e-01 4.65380289e-02 2.90905628e-02 -9.98362124e-01 4.91874367e-02 2.90906969e-02 -9.98194396e-01 5.24666943e-02 2.90907361e-02 -9.98013496e-01 5.58007769e-02 2.90907528e-02 -9.97805834e-01 5.94137646e-02 2.90907715e-02 -9.97585356e-01 6.30036145e-02 2.90907752e-02 -9.97361779e-01 6.64873272e-02 2.90907752e-02 -9.97126162e-01 6.99705631e-02 2.90907789e-02 -9.96881902e-01 7.34007061e-02 2.90907808e-02 -9.96618450e-01 7.68948719e-02 2.90907826e-02 -9.96342897e-01 8.03943053e-02 2.90907808e-02 -9.96056378e-01 8.38714913e-02 2.90907826e-02 -9.95760202e-01 8.72681141e-02 2.90907752e-02 -9.95468199e-01 9.05918777e-02 2.90907826e-02 -9.95139420e-01 9.41759273e-02 2.90907901e-02 -9.94790196e-01 9.77432653e-02 2.90907808e-02 -9.94442463e-01 1.01217702e-01 2.90907789e-02 -9.94082987e-01 1.04696937e-01 2.90907808e-02 -9.93714809e-01 1.08097516e-01 2.90907733e-02 -9.93348300e-01 1.11457027e-01 2.90907808e-02 -9.92942572e-01 1.15024716e-01 2.90907864e-02 -9.92520511e-01 1.18593104e-01 2.90907826e-02 -9.92109299e-01 1.21972315e-01 2.90907770e-02 -9.91687298e-01 1.25401542e-01 2.90907864e-02 -9.91223514e-01 1.28983766e-01 2.90907808e-02 -9.90764499e-01 1.32456079e-01 2.90907808e-02 -9.90296900e-01 1.35926679e-01 2.90907808e-02 -9.89821196e-01 1.39337927e-01 2.90907789e-02 -9.89345312e-01 1.42669588e-01 2.90907789e-02 -9.88838255e-01 1.46169737e-01 2.90907901e-02 -9.88302171e-01 1.49735272e-01 2.90907826e-02 -9.87772882e-01 1.53197810e-01 2.90907845e-02 -9.87243652e-01 1.56547293e-01 2.90907770e-02 -9.86699998e-01 1.59980133e-01 2.90907882e-02 -9.86113906e-01 1.63535208e-01 2.90907826e-02 -9.85547006e-01 1.66895702e-01 2.90907770e-02 -9.84969437e-01 1.70302495e-01 2.90907882e-02 -9.84365344e-01 1.73757926e-01 2.90907975e-02 -9.83773172e-01 1.77089185e-01 2.90907826e-02 -9.83132839e-01 1.80601865e-01 2.90907901e-02 -9.82473731e-01 1.84144288e-01 2.90907826e-02 -9.81826782e-01 1.87557817e-01 2.90907808e-02 -9.81169581e-01 1.90970346e-01 2.90907845e-02 -9.80494022e-01 1.94414154e-01 2.90907826e-02 -9.79825854e-01 1.97728485e-01 2.90907770e-02 -9.79134917e-01 2.01155663e-01 2.90907882e-02 -9.78402734e-01 2.04666436e-01 2.90907808e-02 -9.77698863e-01 2.08001375e-01 2.90907752e-02 -9.76972938e-01 2.11408824e-01 2.90907864e-02 -9.76212382e-01 2.14872986e-01 2.90907808e-02 -9.75453138e-01 2.18296781e-01 2.90907808e-02 -9.74685252e-01 2.21700341e-01 2.90907826e-02 -9.73915398e-01 2.25052372e-01 2.90907770e-02 -9.73151207e-01 2.28348732e-01 2.90907808e-02 -9.72349644e-01 2.31741533e-01 2.90907826e-02 -9.71520901e-01 2.35200226e-01 2.90907864e-02 -9.70666587e-01 2.38686442e-01 2.90907826e-02 -9.69845772e-01 2.41982445e-01 2.90907770e-02 -9.69002187e-01 2.45362252e-01 2.90907882e-02 -9.68111277e-01 2.48850316e-01 2.90908013e-02 -9.67242837e-01 2.52206624e-01 2.90907826e-02 -9.66358125e-01 2.55575746e-01 2.90907845e-02 -9.65475917e-01 2.58880287e-01 2.90907789e-02 -9.64596629e-01 2.62145072e-01 2.90907826e-02 -9.63657200e-01 2.65578151e-01 2.90907882e-02 -9.62694645e-01 2.69048363e-01 2.90907845e-02 -9.61741984e-01 2.72427976e-01 2.90907826e-02 -9.60788846e-01 2.75767744e-01 2.90907826e-02 -9.59822655e-01 2.79111058e-01 2.90907826e-02 -9.58847702e-01 2.82448083e-01 2.90907826e-02 -9.57851648e-01 2.85810381e-01 2.90907826e-02 -9.56848919e-01 2.89141327e-01 2.90907826e-02 -9.55854952e-01 2.92405397e-01 2.90907770e-02 -9.54865932e-01 2.95632571e-01 2.90907826e-02 -9.53802168e-01 2.99050719e-01 2.90907882e-02 -9.52723563e-01 3.02458763e-01 2.90907845e-02 -9.51676548e-01 3.05728793e-01 2.90907770e-02 -9.50620949e-01 3.09006363e-01 2.90907845e-02 -9.49520588e-01 3.12368542e-01 2.90907826e-02 -9.48423326e-01 3.15681219e-01 2.90907808e-02 -9.47314739e-01 3.19004774e-01 2.90907864e-02 -9.46176231e-01 3.22361171e-01 2.90907845e-02 -9.45071995e-01 3.25577468e-01 2.90907975e-02 -9.43942308e-01 3.28852266e-01 2.90907901e-02 -9.42756057e-01 3.32230300e-01 2.90907845e-02 -9.41606581e-01 3.35476995e-01 2.90907826e-02 -9.40431356e-01 3.38752896e-01 2.90907845e-02 -9.39260364e-01 3.41983914e-01 2.90907789e-02 -9.38088834e-01 3.45170587e-01 2.90907845e-02 -9.36838508e-01 3.48549157e-01 2.90907901e-02 -9.35581565e-01 3.51906687e-01 2.90907845e-02 -9.34356987e-01 3.55153471e-01 2.90907826e-02 -9.33122516e-01 3.58411044e-01 2.90907845e-02 -9.31851208e-01 3.61679763e-01 2.90907845e-02 -9.30617273e-01 3.64839077e-01 2.90907770e-02 -9.29361820e-01 3.68036568e-01 2.90907845e-02 -9.28048372e-01 3.71336550e-01 2.90907845e-02 -9.26726282e-01 3.74620408e-01 2.90907826e-02 -9.25438225e-01 3.77788931e-01 2.90907789e-02 -9.24129605e-01 3.80987942e-01 2.90907882e-02 -9.22755837e-01 3.84297460e-01 2.90907826e-02 -9.21410620e-01 3.87515098e-01 2.90907826e-02 -9.20052052e-01 3.90726805e-01 2.90907845e-02 -9.18675601e-01 3.93946201e-01 2.90907826e-02 -9.17331696e-01 3.97063583e-01 2.90907789e-02 -9.15941477e-01 4.00277406e-01 2.90907864e-02 -9.14515495e-01 4.03520495e-01 2.90907845e-02 -9.13093567e-01 4.06725317e-01 2.90907845e-02 -9.11662102e-01 4.09920514e-01 2.90907826e-02 -9.10241187e-01 4.13068324e-01 2.90907845e-02 -9.08794880e-01 4.16233361e-01 2.90907826e-02 -9.07335341e-01 4.19409394e-01 2.90907826e-02 -9.05860543e-01 4.22584653e-01 2.90907808e-02 -9.04414296e-01 4.25663710e-01 2.90907752e-02 -9.02970672e-01 4.28727031e-01 2.90907845e-02 -9.01432872e-01 4.31955069e-01 2.90907882e-02 -8.99883926e-01 4.35174286e-01 2.90907826e-02 -8.98358822e-01 4.38316822e-01 2.90907845e-02 -8.96835029e-01 4.41416055e-01 2.90907808e-02 -8.95286918e-01 4.44553554e-01 2.90908031e-02 -8.93744946e-01 4.47640479e-01 2.90907808e-02 -8.92175496e-01 4.50768441e-01 2.90907882e-02 -8.90560269e-01 4.53948349e-01 2.90907845e-02 -8.89010489e-01 4.56968397e-01 2.90907789e-02 -8.87417495e-01 4.60063130e-01 2.90907864e-02 -8.85773480e-01 4.63219047e-01 2.90907826e-02 -8.84133935e-01 4.66339946e-01 2.90907826e-02 -8.82503748e-01 4.69417363e-01 2.90907826e-02 -8.80868256e-01 4.72479314e-01 2.90907826e-02 -8.79241347e-01 4.75489765e-01 2.90907770e-02 -8.77581477e-01 4.78565097e-01 2.90907882e-02 -8.75857234e-01 4.81704235e-01 2.90907826e-02 -8.74180913e-01 4.84735012e-01 2.90907826e-02 -8.72526646e-01 4.87701684e-01 2.90907770e-02 -8.70830536e-01 4.90738243e-01 2.90907882e-02 -8.69053304e-01 4.93871212e-01 2.90907826e-02 -8.67344499e-01 4.96866494e-01 2.90907808e-02 -8.65609705e-01 4.99887377e-01 2.90907845e-02 -8.63884985e-01 5.02851009e-01 2.90907752e-02 -8.62184167e-01 5.05771577e-01 2.90907845e-02 -8.60348225e-01 5.08889377e-01 2.90907882e-02 -8.58508587e-01 5.11986554e-01 2.90907845e-02 -8.56710255e-01 5.14988363e-01 2.90907826e-02 -8.54905248e-01 5.17977357e-01 2.90907845e-02 -8.53141189e-01 5.20876229e-01 2.90907789e-02 -8.51321518e-01 5.23850620e-01 2.90907882e-02 -8.49442899e-01 5.26891053e-01 2.90907826e-02 -8.47604334e-01 5.29842377e-01 2.90907845e-02 -8.45791161e-01 5.32724559e-01 2.90907752e-02 -8.43938351e-01 5.35667360e-01 2.90907901e-02 -8.41993630e-01 5.38712621e-01 2.90907826e-02 -8.40110481e-01 5.41645169e-01 2.90907845e-02 -8.38200986e-01 5.44594288e-01 2.90907845e-02 -8.36306453e-01 5.47494650e-01 2.90907826e-02 -8.34461033e-01 5.50305724e-01 2.90907808e-02 -8.32589328e-01 5.53130388e-01 2.90907826e-02 -8.30602050e-01 5.56120753e-01 2.90907901e-02 -8.28585863e-01 5.59117794e-01 2.90907826e-02 -8.26676250e-01 5.61925948e-01 2.90907752e-02 -8.24723840e-01 5.64803720e-01 2.90907901e-02 -8.22687328e-01 5.67760408e-01 2.90907826e-02 -8.20701599e-01 5.70626020e-01 2.90907826e-02 -8.18688929e-01 5.73508799e-01 2.90907845e-02 -8.16734910e-01 5.76286316e-01 2.90907789e-02 -8.14770579e-01 5.79063058e-01 2.90907845e-02 -8.12702954e-01 5.81967056e-01 2.90907901e-02 -8.10579300e-01 5.84912777e-01 2.90907864e-02 -8.08530748e-01 5.87744176e-01 2.90907826e-02 -8.06475937e-01 5.90556502e-01 2.90907826e-02 -8.04423153e-01 5.93350887e-01 2.90907826e-02 -8.02368402e-01 5.96126795e-01 2.90907826e-02 -8.00283015e-01 5.98924398e-01 2.90907826e-02 -7.98166692e-01 6.01743340e-01 2.90907826e-02 -7.96123087e-01 6.04439080e-01 2.90907770e-02 -7.94028640e-01 6.07196331e-01 2.90907882e-02 -7.91798949e-01 6.10094190e-01 2.90907826e-02 -7.89666295e-01 6.12854004e-01 2.90907845e-02 -7.87518203e-01 6.15613163e-01 2.90907845e-02 -7.85408914e-01 6.18298054e-01 2.90907789e-02 -7.83278525e-01 6.20999515e-01 2.90907845e-02 -7.81080544e-01 6.23763800e-01 2.90907864e-02 -7.78867245e-01 6.26522839e-01 2.90907845e-02 -7.76677907e-01 6.29235089e-01 2.90907826e-02 -7.74514735e-01 6.31884158e-01 2.90907752e-02 -7.72329867e-01 6.34564042e-01 2.90907845e-02 -7.70033240e-01 6.37346566e-01 2.90907808e-02 -7.67816901e-01 6.40017390e-01 2.90907826e-02 -7.65570641e-01 6.42701089e-01 2.90907826e-02 -7.63369083e-01 6.45309150e-01 2.90907770e-02 -7.61182308e-01 6.47892177e-01 2.90907826e-02 -7.58873403e-01 6.50598109e-01 2.90907864e-02 -7.56518424e-01 6.53334260e-01 2.90907826e-02 -7.54236341e-01 6.55966043e-01 2.90907845e-02 -7.51938224e-01 6.58597291e-01 2.90907826e-02 -7.49646127e-01 6.61207736e-01 2.90907826e-02 -7.47327566e-01 6.63826108e-01 2.90907826e-02 -7.45005667e-01 6.66432440e-01 2.90907826e-02 -7.42669106e-01 6.69033229e-01 2.90907826e-02 -7.40396738e-01 6.71546459e-01 2.90907770e-02 -7.38122761e-01 6.74044430e-01 2.90907826e-02 -7.35708654e-01 6.76687598e-01 2.90907882e-02 -7.33266532e-01 6.79325819e-01 2.90907826e-02 -7.30884433e-01 6.81887388e-01 2.90907826e-02 -7.28518307e-01 6.84413016e-01 2.90907789e-02 -7.26107419e-01 6.86971009e-01 2.90907826e-02 -7.23769426e-01 6.89433634e-01 2.90907770e-02 -7.21359968e-01 6.91953063e-01 2.90907864e-02 -7.18884289e-01 6.94533765e-01 2.90907789e-02 -7.16494083e-01 6.96993113e-01 2.90907752e-02 -7.14067936e-01 6.99485362e-01 2.90907882e-02 -7.11563945e-01 7.02029824e-01 2.90908013e-02 -7.09113002e-01 7.04508007e-01 2.90907808e-02 -7.06642091e-01 7.06969023e-01 2.90907845e-02 -7.04239428e-01 7.09375560e-01 2.90907752e-02 -7.01768816e-01 7.11827695e-01 2.90907882e-02 -6.99200153e-01 7.14344323e-01 2.90907845e-02 -6.96750224e-01 7.16732740e-01 2.90907770e-02 -6.94252133e-01 7.19163239e-01 2.90907882e-02 -6.91723228e-01 7.21570790e-01 2.90907752e-02 -6.89238608e-01 7.23966599e-01 2.90907901e-02 -6.86605096e-01 7.26452768e-01 2.90908013e-02 -6.84052706e-01 7.28856623e-01 2.90907826e-02 -6.81538761e-01 7.31206417e-01 2.90908013e-02 -6.79046035e-01 7.33521223e-01 2.90907770e-02 -6.76504314e-01 7.35879064e-01 2.90907882e-02 -6.73904777e-01 7.38249004e-01 2.90907770e-02 -6.71349585e-01 7.40580857e-01 2.90907882e-02 -6.68650329e-01 7.43017614e-01 2.90907845e-02 -6.66121721e-01 7.45279312e-01 2.90907789e-02 -6.63603246e-01 7.47528136e-01 2.90907826e-02 -6.60939634e-01 7.49886036e-01 2.90907901e-02 -6.58224046e-01 7.52264678e-01 2.90907826e-02 -6.55608356e-01 7.54548371e-01 2.90907826e-02 -6.52983904e-01 7.56819367e-01 2.90907826e-02 -6.50381982e-01 7.59053111e-01 2.90907770e-02 -6.47751212e-01 7.61305451e-01 2.90907882e-02 -6.45005584e-01 7.63632417e-01 2.90907845e-02 -6.42324507e-01 7.65888095e-01 2.90907826e-02 -6.39717519e-01 7.68063605e-01 2.90907789e-02 -6.37051582e-01 7.70282030e-01 2.90907882e-02 -6.34270847e-01 7.72573113e-01 2.90907845e-02 -6.31637394e-01 7.74720371e-01 2.90907789e-02 -6.28951848e-01 7.76909888e-01 2.90907864e-02 -6.26217782e-01 7.79107928e-01 2.90907789e-02 -6.23516083e-01 7.81280696e-01 2.90907882e-02 -6.20705247e-01 7.83509851e-01 2.90907826e-02 -6.18023992e-01 7.85626411e-01 2.90907808e-02 -6.15272403e-01 7.87787557e-01 2.90907882e-02 -6.12444520e-01 7.89984584e-01 2.90907845e-02 -6.09686494e-01 7.92112768e-01 2.90907808e-02 -6.06980264e-01 7.94188917e-01 2.90907789e-02 -6.04220212e-01 7.96296835e-01 2.90907864e-02 -6.01350665e-01 7.98462808e-01 2.90907845e-02 -5.98541856e-01 8.00568581e-01 2.90907826e-02 -5.95819950e-01 8.02590847e-01 2.90907752e-02 -5.93054116e-01 8.04645360e-01 2.90907882e-02 -5.90112150e-01 8.06801617e-01 2.90907826e-02 -5.87389886e-01 8.08782935e-01 2.90907752e-02 -5.84597230e-01 8.10808361e-01 2.90907882e-02 -5.81722915e-01 8.12870979e-01 2.90907770e-02 -5.78904212e-01 8.14886928e-01 2.90907882e-02 -5.75969636e-01 8.16961050e-01 2.90907808e-02 -5.73095977e-01 8.18976581e-01 2.90907826e-02 -5.70327938e-01 8.20904493e-01 2.90907770e-02 -5.67499936e-01 8.22869241e-01 2.90907864e-02 -5.64524531e-01 8.24906230e-01 2.90907752e-02 -5.61683714e-01 8.26841414e-01 2.90907770e-02 -5.58826685e-01 8.28784347e-01 2.90907882e-02 -5.55893719e-01 8.30744088e-01 2.90907752e-02 -5.53056479e-01 8.32641244e-01 2.90907845e-02 -5.50127089e-01 8.34576428e-01 2.90907770e-02 -5.47212422e-01 8.36495042e-01 2.90907864e-02 -5.44222057e-01 8.38441610e-01 2.90907808e-02 -5.41347623e-01 8.40298772e-01 2.90907789e-02 -5.38420796e-01 8.42182159e-01 2.90907882e-02 -5.35461605e-01 8.44059706e-01 2.90907789e-02 -5.32534420e-01 8.45916212e-01 2.90907845e-02 -5.29512823e-01 8.47809434e-01 2.90907826e-02 -5.26533544e-01 8.49664509e-01 2.90907826e-02 -5.23620307e-01 8.51455867e-01 2.90907770e-02 -5.20667970e-01 8.53274107e-01 2.90907882e-02 -5.17612278e-01 8.55126262e-01 2.90907826e-02 -5.14690220e-01 8.56885374e-01 2.90907789e-02 -5.11723042e-01 8.58667910e-01 2.90907882e-02 -5.08707166e-01 8.60449910e-01 2.90907789e-02 -5.05690932e-01 8.62232208e-01 2.90908050e-02 -5.02609968e-01 8.64030778e-01 2.90907826e-02 -4.99592990e-01 8.65777552e-01 2.90907826e-02 -4.96666580e-01 8.67454886e-01 2.90907752e-02 -4.93649542e-01 8.69181812e-01 2.90907882e-02 -4.90522504e-01 8.70949268e-01 2.90907826e-02 -4.87495095e-01 8.72645736e-01 2.90907826e-02 -4.84413207e-01 8.74359369e-01 2.90907826e-02 -4.81437624e-01 8.76001179e-01 2.90907770e-02 -4.78398412e-01 8.77670646e-01 2.90907864e-02 -4.75304574e-01 8.79342318e-01 2.90907770e-02 -4.72248256e-01 8.80993307e-01 2.90907845e-02 -4.69091117e-01 8.82676721e-01 2.90907826e-02 -4.66068059e-01 8.84274900e-01 2.90907770e-02 -4.62986261e-01 8.85896325e-01 2.90907864e-02 -4.59889174e-01 8.87500823e-01 2.90907770e-02 -4.56786543e-01 8.89109612e-01 2.90907864e-02 -4.53628004e-01 8.90721679e-01 2.90907826e-02 -4.50490624e-01 8.92311037e-01 2.90907789e-02 -4.47457373e-01 8.93833876e-01 2.90907752e-02 -4.44373697e-01 8.95376503e-01 2.90907845e-02 -4.41154808e-01 8.96964192e-01 2.90907826e-02 -4.38081473e-01 8.98466229e-01 2.90907752e-02 -4.35044765e-01 8.99944603e-01 2.90907808e-02 -4.31899607e-01 9.01455224e-01 2.90907808e-02 -4.28690284e-01 9.02991593e-01 2.90907882e-02 -4.25500333e-01 9.04491782e-01 2.90907770e-02 -4.22444433e-01 9.05927122e-01 2.90907808e-02 -4.19278204e-01 9.07397389e-01 2.90907808e-02 -4.16116208e-01 9.08850431e-01 2.90907826e-02 -4.12896723e-01 9.10319686e-01 2.90907845e-02 -4.09690470e-01 9.11764801e-01 2.90907789e-02 -4.06505436e-01 9.13192928e-01 2.90907864e-02 -4.03299510e-01 9.14609790e-01 2.90907789e-02 -4.00104105e-01 9.16017354e-01 2.90907864e-02 -3.96904826e-01 9.17400181e-01 2.90907770e-02 -3.93688858e-01 9.18786824e-01 2.90907864e-02 -3.90426069e-01 9.20179009e-01 2.90907826e-02 -3.87269557e-01 9.21510041e-01 2.90907770e-02 -3.84054035e-01 9.22858894e-01 2.90907864e-02 -3.80764276e-01 9.24216628e-01 2.90907808e-02 -3.77547443e-01 9.25537288e-01 2.90907808e-02 -3.74313772e-01 9.26850557e-01 2.90907808e-02 -3.71073365e-01 9.28152442e-01 2.90907826e-02 -3.67915779e-01 9.29407001e-01 2.90907770e-02 -3.64667565e-01 9.30691600e-01 2.90907864e-02 -3.61350417e-01 9.31974590e-01 2.90907789e-02 -3.58179837e-01 9.33208048e-01 2.90907770e-02 -3.54967237e-01 9.34426963e-01 2.90907808e-02 -3.51724505e-01 9.35647666e-01 2.90907826e-02 -3.48410696e-01 9.36885893e-01 2.90907826e-02 -3.45097035e-01 9.38109815e-01 2.90907752e-02 -3.41924459e-01 9.39282238e-01 2.90907808e-02 -3.38637024e-01 9.40469623e-01 2.90907808e-02 -3.35268468e-01 9.41682637e-01 2.90907864e-02 -3.31855178e-01 9.42885995e-01 2.90907808e-02 -3.28656852e-01 9.44001436e-01 2.90907752e-02 -3.25374424e-01 9.45146441e-01 2.90907864e-02 -3.22077692e-01 9.46266413e-01 2.90907752e-02 -3.18803370e-01 9.47382510e-01 2.90907864e-02 -3.15472424e-01 9.48489189e-01 2.90907752e-02 -3.12266916e-01 9.49553370e-01 2.90907808e-02 -3.08828205e-01 9.50682104e-01 2.90907882e-02 -3.05406719e-01 9.51782227e-01 2.90907808e-02 -3.02091151e-01 9.52839196e-01 2.90907789e-02 -2.98748702e-01 9.53889489e-01 2.90907752e-02 -2.95527637e-01 9.54888761e-01 2.90907752e-02 -2.92184532e-01 9.55927730e-01 2.90907882e-02 -2.88746536e-01 9.56967115e-01 2.90907808e-02 -2.85393178e-01 9.57971990e-01 2.90907994e-02 -2.82050103e-01 9.58964646e-01 2.90907826e-02 -2.78793484e-01 9.59911764e-01 2.90907752e-02 -2.75541812e-01 9.60853100e-01 2.90907826e-02 -2.72189170e-01 9.61809516e-01 2.90907826e-02 -2.68737853e-01 9.62781668e-01 2.90907864e-02 -2.65262187e-01 9.63742495e-01 2.90907808e-02 -2.61998653e-01 9.64632869e-01 2.90907752e-02 -2.58647621e-01 9.65540707e-01 2.90907882e-02 -2.55250096e-01 9.66440082e-01 2.90907770e-02 -2.51905531e-01 9.67322290e-01 2.90907864e-02 -2.48403102e-01 9.68225121e-01 2.90907808e-02 -2.45117649e-01 9.69057500e-01 2.90907733e-02 -2.41749078e-01 9.69908535e-01 2.90907864e-02 -2.38334715e-01 9.70749319e-01 2.90907752e-02 -2.34945342e-01 9.71582651e-01 2.90907864e-02 -2.31553748e-01 9.72388923e-01 2.90907733e-02 -2.28253067e-01 9.73171473e-01 2.90907808e-02 -2.24752530e-01 9.73986864e-01 2.90907845e-02 -2.21267179e-01 9.74782884e-01 2.90907789e-02 -2.17877120e-01 9.75546658e-01 2.90907789e-02 -2.14459777e-01 9.76301730e-01 2.90907789e-02 -2.11131215e-01 9.77025390e-01 2.90907752e-02 -2.07827970e-01 9.77736056e-01 2.90907789e-02 -2.04332396e-01 9.78475392e-01 2.90907826e-02 -2.00775370e-01 9.79211092e-01 2.90907808e-02 -1.97355539e-01 9.79902446e-01 2.90907789e-02 -1.94047526e-01 9.80562150e-01 2.90907752e-02 -1.90736189e-01 9.81214941e-01 2.90907808e-02 -1.87326819e-01 9.81869757e-01 2.90907808e-02 -1.83773130e-01 9.82544243e-01 2.90907845e-02 -1.80246010e-01 9.83191907e-01 2.90907789e-02 -1.76908925e-01 9.83802378e-01 2.90907752e-02 -1.73495889e-01 9.84415174e-01 2.90907845e-02 -1.70064345e-01 9.85003233e-01 2.90907752e-02 -1.66594028e-01 9.85604167e-01 2.90907882e-02 -1.63047090e-01 9.86193657e-01 2.90907826e-02 -1.59690261e-01 9.86738682e-01 2.90907733e-02 -1.56259820e-01 9.87294674e-01 2.90907864e-02 -1.52794331e-01 9.87831414e-01 2.90907733e-02 -1.49349198e-01 9.88363147e-01 2.90907864e-02 -1.45786107e-01 9.88890886e-01 2.90907808e-02 -1.42441973e-01 9.89374220e-01 2.90907752e-02 -1.39003292e-01 9.89872992e-01 2.90907864e-02 -1.35444984e-01 9.90362048e-01 2.90907826e-02 -1.31991535e-01 9.90829289e-01 2.90907808e-02 -1.28617287e-01 9.91269171e-01 2.90907770e-02 -1.25256181e-01 9.91702676e-01 2.90907808e-02 -1.21774472e-01 9.92135823e-01 2.90907826e-02 -1.18213080e-01 9.92568254e-01 2.90907864e-02 -1.14636995e-01 9.92984533e-01 2.90907826e-02 -1.11192204e-01 9.93377090e-01 2.90907808e-02 -1.07815638e-01 9.93745029e-01 2.90907752e-02 -1.04354709e-01 9.94119227e-01 2.90907845e-02 -1.00842297e-01 9.94479418e-01 2.90907770e-02 -9.73903835e-02 9.94826674e-01 2.90907864e-02 -9.38198790e-02 9.95165944e-01 2.90907770e-02 -9.04550031e-02 9.95476544e-01 2.90907752e-02 -8.69761184e-02 9.95792627e-01 2.90907845e-02 -8.34960863e-02 9.96084392e-01 2.90907752e-02 -8.00492615e-02 9.96372402e-01 2.90907845e-02 -7.65175670e-02 9.96643066e-01 2.90907752e-02 -7.30734617e-02 9.96909022e-01 2.90907864e-02 -6.95048794e-02 9.97160196e-01 2.90907826e-02 -6.61059171e-02 9.97387946e-01 2.90907752e-02 -6.26178309e-02 9.97617960e-01 2.90907864e-02 -5.91435358e-02 9.97827530e-01 2.90907752e-02 -5.57416156e-02 9.98027205e-01 2.90907808e-02 -5.21837175e-02 9.98218060e-01 2.90907864e-02 -4.86105606e-02 9.98399973e-01 2.90907808e-02 -4.51250561e-02 9.98559833e-01 2.90907808e-02 -4.16641049e-02 9.98713315e-01 2.90907826e-02 -3.82454209e-02 9.98844743e-01 2.90907752e-02 -3.48734818e-02 9.98971641e-01 2.90907808e-02 -3.12874541e-02 9.99093354e-01 2.90907864e-02 -2.76611578e-02 9.99196291e-01 2.90907808e-02 -2.41768695e-02 9.99292433e-01 2.90907808e-02 -2.07976792e-02 9.99360979e-01 2.90907752e-02 -1.74332652e-02 9.99432266e-01 2.90907808e-02 -1.39030293e-02 9.99481261e-01 2.90907826e-02 -1.03474380e-02 9.99531686e-01 2.90907864e-02 -6.72898907e-03 9.99565601e-01 2.90907826e-02 -3.33801773e-03 9.99575615e-01 2.90907752e-02 1.19421362e-04 9.99584556e-01 2.90907864e-02 3.64675350e-03 9.99575794e-01 2.90907752e-02 7.10394699e-03 9.99563932e-01 2.90907864e-02 1.07177952e-02 9.99521613e-01 2.90907789e-02 1.41919367e-02 9.99475956e-01 2.90907826e-02 1.76769942e-02 9.99428034e-01 2.90907808e-02 2.11779717e-02 9.99355197e-01 2.90907808e-02 2.46528946e-02 9.99277234e-01 2.90907808e-02 2.81428155e-02 9.99186158e-01 2.90907826e-02 3.15610953e-02 9.99079168e-01 2.90907752e-02 3.50215286e-02 9.98968959e-01 2.90907845e-02 3.85937914e-02 9.98836696e-01 2.90907808e-02 4.21163328e-02 9.98694479e-01 2.90907808e-02 4.55942415e-02 9.98540223e-01 2.90907808e-02 4.90027033e-02 9.98375475e-01 2.90907752e-02 5.23752235e-02 9.98205543e-01 2.90907826e-02 5.58640398e-02 9.98019278e-01 2.90907826e-02 5.94429523e-02 9.97814476e-01 2.90907882e-02 6.30188733e-02 9.97592151e-01 2.90907826e-02 6.64051399e-02 9.97368217e-01 2.90907752e-02 6.98794723e-02 9.97137010e-01 2.90907864e-02 7.33572394e-02 9.96883988e-01 2.90907770e-02 7.68514425e-02 9.96625960e-01 2.90907864e-02 8.04086775e-02 9.96341527e-01 2.90907826e-02 8.38872418e-02 9.96054411e-01 2.90907808e-02 8.73743892e-02 9.95756388e-01 2.90907826e-02 9.07930359e-02 9.95447159e-01 2.90907789e-02 9.43334699e-02 9.95119035e-01 2.90907789e-02 9.76925343e-02 9.94793653e-01 2.90907770e-02 1.01156592e-01 9.94452596e-01 2.90907882e-02 1.04739174e-01 9.94079769e-01 2.90907826e-02 1.08198136e-01 9.93709266e-01 2.90907845e-02 1.11675821e-01 9.93323922e-01 2.90907826e-02 1.15148842e-01 9.92926538e-01 2.90907826e-02 1.18522197e-01 9.92526710e-01 2.90907994e-02 1.21953093e-01 9.92117465e-01 2.90907882e-02 1.25536010e-01 9.91668820e-01 2.90907826e-02 1.28994331e-01 9.91222143e-01 2.90907826e-02 1.32460833e-01 9.90765035e-01 2.90907808e-02 1.35819510e-01 9.90308881e-01 2.90907957e-02 1.39259800e-01 9.89836156e-01 2.90907864e-02 1.42736271e-01 9.89333510e-01 2.90907752e-02 1.46165311e-01 9.88838553e-01 2.90907864e-02 1.49710491e-01 9.88304436e-01 2.90907808e-02 1.53081119e-01 9.87787843e-01 2.90907770e-02 1.56522050e-01 9.87251878e-01 2.90907882e-02 1.60064340e-01 9.86682057e-01 2.90907826e-02 1.63494736e-01 9.86120462e-01 2.90907808e-02 1.66938812e-01 9.85543013e-01 2.90907808e-02 1.70405537e-01 9.84948158e-01 2.90907826e-02 1.73844129e-01 9.84351575e-01 2.90907826e-02 1.77196100e-01 9.83750939e-01 2.90907770e-02 1.80581540e-01 9.83136237e-01 2.90907882e-02 1.84131861e-01 9.82475758e-01 2.90907808e-02 1.87464610e-01 9.81843114e-01 2.90907789e-02 1.90889224e-01 9.81187522e-01 2.90907882e-02 1.94431320e-01 9.80489254e-01 2.90907826e-02 1.97813138e-01 9.79812086e-01 2.90907808e-02 2.01209843e-01 9.79121447e-01 2.90907826e-02 2.04561695e-01 9.78423297e-01 2.90907770e-02 2.07890883e-01 9.77727711e-01 2.90907864e-02 2.11410746e-01 9.76972699e-01 2.90907882e-02 2.14925125e-01 9.76203322e-01 2.90907845e-02 2.18305737e-01 9.75451112e-01 2.90907826e-02 2.21650928e-01 9.74691033e-01 2.90907752e-02 2.24935040e-01 9.73943770e-01 2.90907826e-02 2.28311703e-01 9.73157465e-01 2.90907808e-02 2.31784806e-01 9.72341478e-01 2.90907864e-02 2.35298052e-01 9.71495628e-01 2.90907845e-02 2.38691986e-01 9.70664024e-01 2.90907826e-02 2.42079899e-01 9.69823837e-01 2.90907826e-02 2.45385870e-01 9.68991518e-01 2.90907789e-02 2.48732001e-01 9.68141258e-01 2.90907864e-02 2.52228647e-01 9.67236638e-01 2.90907845e-02 2.55540341e-01 9.66364563e-01 2.90907770e-02 2.58894861e-01 9.65474069e-01 2.90907864e-02 2.62309015e-01 9.64551508e-01 2.90907808e-02 2.65651226e-01 9.63635087e-01 2.90907845e-02 2.68977225e-01 9.62711513e-01 2.90907770e-02 2.72224873e-01 9.61798608e-01 2.90907808e-02 2.75683522e-01 9.60815012e-01 2.90907864e-02 2.79139668e-01 9.59813297e-01 2.90907808e-02 2.82446980e-01 9.58846033e-01 2.90907808e-02 2.85705745e-01 9.57877934e-01 2.90907770e-02 2.88994193e-01 9.56892371e-01 2.90907808e-02 2.92305797e-01 9.55887914e-01 2.90907845e-02 2.95740396e-01 9.54834819e-01 2.90907882e-02 2.99147487e-01 9.53769624e-01 2.90907826e-02 3.02408904e-01 9.52734947e-01 2.90907770e-02 3.05664927e-01 9.51700568e-01 2.90907826e-02 3.09043378e-01 9.50609267e-01 2.90907864e-02 3.12344044e-01 9.49526131e-01 2.90907789e-02 3.15645248e-01 9.48439837e-01 2.90907882e-02 3.19033116e-01 9.47303772e-01 2.90907826e-02 3.22331488e-01 9.46184695e-01 2.90907826e-02 3.25651646e-01 9.45048273e-01 2.90907826e-02 3.28880072e-01 9.43926930e-01 2.90907808e-02 3.32178980e-01 9.42774475e-01 2.90907845e-02 3.35426182e-01 9.41622794e-01 2.90907789e-02 3.38712901e-01 9.40446615e-01 2.90907864e-02 3.42064083e-01 9.39233065e-01 2.90907826e-02 3.45330387e-01 9.38028693e-01 2.90907808e-02 3.48605007e-01 9.36813593e-01 2.90907826e-02 3.51810247e-01 9.35613036e-01 2.90907770e-02 3.54977489e-01 9.34423268e-01 2.90907826e-02 3.58322352e-01 9.33157027e-01 2.90907882e-02 3.61629397e-01 9.31870222e-01 2.90907826e-02 3.64897341e-01 9.30597901e-01 2.90907808e-02 3.68165165e-01 9.29308593e-01 2.90907789e-02 3.71306628e-01 9.28056836e-01 2.90907770e-02 3.74539018e-01 9.26762581e-01 2.90907882e-02 3.77852082e-01 9.25414562e-01 2.90907845e-02 3.81068140e-01 9.24093366e-01 2.90907826e-02 3.84291172e-01 9.22759533e-01 2.90907845e-02 3.87440532e-01 9.21437800e-01 2.90907975e-02 3.90634686e-01 9.20090973e-01 2.90907845e-02 3.93842399e-01 9.18718398e-01 2.90907808e-02 3.97041380e-01 9.17347491e-01 2.90907882e-02 4.00348395e-01 9.15908635e-01 2.90907845e-02 4.03545827e-01 9.14503753e-01 2.90907845e-02 4.06717032e-01 9.13099051e-01 2.90907845e-02 4.09826547e-01 9.11701202e-01 2.90907752e-02 4.12979305e-01 9.10282433e-01 2.90907864e-02 4.16184872e-01 9.08816218e-01 2.90907789e-02 4.19317991e-01 9.07379210e-01 2.90907864e-02 4.22565192e-01 9.05868232e-01 2.90907789e-02 4.25695628e-01 9.04398441e-01 2.90907752e-02 4.28819716e-01 9.02927279e-01 2.90907845e-02 4.32033151e-01 9.01391029e-01 2.90907808e-02 4.35068280e-01 8.99932861e-01 2.90907789e-02 4.38253909e-01 8.98392260e-01 2.90907901e-02 4.41492766e-01 8.96799266e-01 2.90907845e-02 4.44618225e-01 8.95253718e-01 2.90907826e-02 4.47736740e-01 8.93699646e-01 2.90907845e-02 4.50811863e-01 8.92150819e-01 2.90907808e-02 4.53868538e-01 8.90598536e-01 2.90907789e-02 4.56935167e-01 8.89026046e-01 2.90907752e-02 4.60088909e-01 8.87401998e-01 2.90907826e-02 4.63236809e-01 8.85762990e-01 2.90907808e-02 4.66307551e-01 8.84151161e-01 2.90907826e-02 4.69426244e-01 8.82499158e-01 2.90907826e-02 4.72476125e-01 8.80869687e-01 2.90907826e-02 4.75536376e-01 8.79221320e-01 2.90907845e-02 4.78613377e-01 8.77551556e-01 2.90907826e-02 4.81653720e-01 8.75885129e-01 2.90907808e-02 4.84705359e-01 8.74197900e-01 2.90907826e-02 4.87729520e-01 8.72512996e-01 2.90907789e-02 4.90758181e-01 8.70818615e-01 2.90907882e-02 4.93889928e-01 8.69042635e-01 2.90907826e-02 4.96901393e-01 8.67325187e-01 2.90907808e-02 4.99938428e-01 8.65578949e-01 2.90907845e-02 5.02969325e-01 8.63822401e-01 2.90907845e-02 5.05975544e-01 8.62064779e-01 2.90907826e-02 5.08962095e-01 8.60304177e-01 2.90907845e-02 5.11876285e-01 8.58568966e-01 2.90907770e-02 5.14897346e-01 8.56768191e-01 2.90907882e-02 5.17957568e-01 8.54916334e-01 2.90907845e-02 5.20930469e-01 8.53112400e-01 2.90907845e-02 5.23927748e-01 8.51272047e-01 2.90907845e-02 5.26793182e-01 8.49497378e-01 2.90907752e-02 5.29754817e-01 8.47662330e-01 2.90907901e-02 5.32704651e-01 8.45801830e-01 2.90907752e-02 5.35645902e-01 8.43947828e-01 2.90907845e-02 5.38686156e-01 8.42008710e-01 2.90907826e-02 5.41544497e-01 8.40163529e-01 2.90907715e-02 5.44348776e-01 8.38349223e-01 2.90907733e-02 5.47307551e-01 8.36419404e-01 2.90907659e-02 5.50242901e-01 8.34493160e-01 2.90907584e-02 5.53177714e-01 8.32548976e-01 2.90907528e-02 5.56180179e-01 8.30548286e-01 2.90907286e-02 5.58973372e-01 8.28670382e-01 2.90906765e-02 5.61679065e-01 8.26843023e-01 2.90905200e-02 5.64588606e-01 8.24859977e-01 2.90905554e-02 5.67868173e-01 8.22604656e-01 2.90905274e-02 5.70078850e-01 8.21073771e-01 2.90905293e-02 5.73202193e-01 8.18896413e-01 2.90905330e-02 5.76520443e-01 8.16563785e-01 2.90905330e-02 5.80315351e-01 8.13872159e-01 2.90905293e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 7.10345030e-01 7.03252196e-01 2.90905349e-02 7.12270319e-01 7.01302528e-01 2.90905535e-02 7.14339197e-01 6.99193537e-01 2.90905759e-02 7.16715097e-01 6.96758509e-01 2.90907063e-02 7.19055176e-01 6.94337070e-01 2.90907342e-02 7.21554160e-01 6.91739500e-01 2.90907584e-02 7.24027395e-01 6.89154029e-01 2.90907640e-02 7.26346016e-01 6.86706722e-01 2.90907621e-02 7.28679478e-01 6.84229851e-01 2.90907752e-02 7.31113553e-01 6.81636810e-01 2.90907789e-02 7.33503342e-01 6.79063022e-01 2.90907752e-02 7.35864043e-01 6.76514566e-01 2.90907826e-02 7.38272429e-01 6.73878551e-01 2.90907808e-02 7.40563273e-01 6.71358168e-01 2.90907752e-02 7.42900848e-01 6.68778419e-01 2.90907826e-02 7.45225966e-01 6.66180193e-01 2.90907752e-02 7.47497499e-01 6.63633585e-01 2.90907789e-02 7.49799728e-01 6.61032498e-01 2.90907808e-02 7.52171040e-01 6.58336103e-01 2.90907882e-02 7.54533112e-01 6.55624211e-01 2.90907808e-02 7.56736755e-01 6.53075278e-01 2.90907770e-02 7.59016454e-01 6.50432885e-01 2.90907882e-02 7.61303365e-01 6.47740722e-01 2.90907752e-02 7.63477445e-01 6.45187914e-01 2.90907808e-02 7.65788496e-01 6.42445207e-01 2.90907864e-02 7.68015444e-01 6.39772534e-01 2.90907733e-02 7.70272553e-01 6.37063801e-01 2.90907882e-02 7.72482812e-01 6.34373605e-01 2.90907770e-02 7.74621189e-01 6.31762266e-01 2.90907826e-02 7.76901782e-01 6.28963828e-01 2.90907901e-02 7.79156983e-01 6.26160860e-01 2.90907826e-02 7.81331956e-01 6.23445570e-01 2.90907826e-02 7.83430338e-01 6.20799959e-01 2.90907752e-02 7.85527110e-01 6.18153274e-01 2.90907826e-02 7.87736595e-01 6.15339935e-01 2.90907901e-02 7.89892554e-01 6.12559676e-01 2.90907770e-02 7.92030036e-01 6.09802485e-01 2.90907901e-02 7.94231176e-01 6.06926620e-01 2.90907808e-02 7.96346605e-01 6.04149938e-01 2.90907845e-02 7.98465490e-01 6.01347804e-01 2.90907845e-02 8.00483942e-01 5.98648012e-01 2.90907752e-02 8.02554965e-01 5.95880449e-01 2.90907882e-02 8.04637074e-01 5.93057990e-01 2.90907789e-02 8.06710303e-01 5.90243518e-01 2.90907901e-02 8.08828890e-01 5.87332249e-01 2.90907808e-02 8.10792565e-01 5.84611416e-01 2.90907770e-02 8.12823057e-01 5.81795514e-01 2.90907882e-02 8.14859688e-01 5.78933239e-01 2.90907770e-02 8.16816032e-01 5.76180935e-01 2.90907882e-02 8.18911195e-01 5.73198080e-01 2.90907882e-02 8.20964098e-01 5.70249140e-01 2.90907864e-02 8.22936952e-01 5.67396164e-01 2.90907808e-02 8.24848533e-01 5.64611733e-01 2.90907789e-02 8.26783895e-01 5.61776102e-01 2.90907845e-02 8.28746021e-01 5.58880091e-01 2.90907845e-02 8.30683291e-01 5.55991471e-01 2.90907826e-02 8.32660019e-01 5.53034961e-01 2.90907901e-02 8.34598124e-01 5.50094664e-01 2.90907789e-02 8.36454511e-01 5.47272563e-01 2.90907826e-02 8.38402927e-01 5.44288993e-01 2.90907901e-02 8.40308666e-01 5.41329205e-01 2.90907770e-02 8.42194498e-01 5.38401067e-01 2.90907864e-02 8.44122350e-01 5.35372198e-01 2.90908031e-02 8.45934093e-01 5.32498658e-01 2.90907770e-02 8.47777903e-01 5.29569864e-01 2.90907901e-02 8.49608779e-01 5.26616037e-01 2.90907994e-02 8.51401687e-01 5.23716271e-01 2.90907845e-02 8.53233576e-01 5.20730078e-01 2.90907826e-02 8.55087221e-01 5.17683089e-01 2.90907882e-02 8.56936157e-01 5.14613807e-01 2.90907845e-02 8.58733892e-01 5.11606812e-01 2.90907864e-02 8.60521197e-01 5.08594632e-01 2.90907826e-02 8.62239063e-01 5.05670786e-01 2.90907770e-02 8.63946259e-01 5.02751946e-01 2.90907826e-02 8.65737677e-01 4.99670058e-01 2.90907901e-02 8.67483914e-01 4.96621698e-01 2.90907808e-02 8.69197011e-01 4.93625492e-01 2.90907882e-02 8.70937347e-01 4.90543008e-01 2.90907789e-02 8.72603118e-01 4.87569571e-01 2.90907826e-02 8.74332964e-01 4.84466672e-01 2.90907882e-02 8.76025498e-01 4.81392473e-01 2.90907789e-02 8.77696097e-01 4.78354186e-01 2.90907901e-02 8.79364908e-01 4.75261599e-01 2.90907770e-02 8.80961478e-01 4.72306460e-01 2.90907845e-02 8.82647693e-01 4.69150156e-01 2.90907882e-02 8.84285331e-01 4.66049254e-01 2.90907789e-02 8.85859489e-01 4.63054299e-01 2.90907845e-02 8.87512803e-01 4.59880918e-01 2.90907901e-02 8.89170408e-01 4.56662953e-01 2.90907826e-02 8.90751362e-01 4.53571379e-01 2.90907845e-02 8.92280400e-01 4.50546533e-01 2.90907752e-02 8.93859208e-01 4.47420537e-01 2.90907882e-02 8.95406485e-01 4.44302052e-01 2.90907770e-02 8.96916628e-01 4.41251814e-01 2.90907808e-02 8.98491323e-01 4.38049108e-01 2.90907882e-02 9.00019765e-01 4.34889853e-01 2.90907770e-02 9.01520252e-01 4.31773037e-01 2.90907882e-02 9.03019071e-01 4.28623229e-01 2.90907789e-02 9.04471934e-01 4.25549895e-01 2.90907845e-02 9.05993998e-01 4.22311604e-01 2.90907901e-02 9.07511711e-01 4.19034481e-01 2.90907845e-02 9.08968210e-01 4.15858001e-01 2.90907826e-02 9.10375834e-01 4.12762254e-01 2.90907770e-02 9.11762476e-01 4.09700245e-01 2.90907826e-02 9.13186371e-01 4.06515568e-01 2.90907826e-02 9.14608121e-01 4.03309166e-01 2.90907826e-02 9.16041076e-01 4.00047690e-01 2.90907882e-02 9.17443216e-01 3.96809518e-01 2.90907789e-02 9.18777227e-01 3.93710554e-01 2.90907845e-02 9.20186579e-01 3.90416712e-01 2.90907901e-02 9.21543062e-01 3.87190580e-01 2.90907770e-02 9.22845483e-01 3.84083211e-01 2.90907845e-02 9.24213767e-01 3.80785286e-01 2.90908068e-02 9.25578177e-01 3.77451897e-01 2.90907826e-02 9.26882863e-01 3.74232471e-01 2.90907808e-02 9.28152800e-01 3.71067375e-01 2.90907770e-02 9.29406464e-01 3.67926151e-01 2.90907826e-02 9.30691540e-01 3.64667982e-01 2.90907845e-02 9.31951404e-01 3.61414701e-01 2.90907826e-02 9.33248401e-01 3.58080089e-01 2.90907882e-02 9.34509635e-01 3.54749948e-01 2.90907826e-02 9.35736835e-01 3.51486832e-01 2.90907826e-02 9.36931729e-01 3.48274589e-01 2.90907752e-02 9.38107610e-01 3.45117986e-01 2.90907826e-02 9.39324558e-01 3.41811687e-01 2.90907826e-02 9.40540433e-01 3.38453144e-01 2.90907864e-02 9.41735208e-01 3.35113019e-01 2.90907808e-02 9.42874134e-01 3.31884116e-01 2.90907752e-02 9.43998039e-01 3.28675598e-01 2.90907808e-02 9.45165753e-01 3.25315326e-01 2.90907864e-02 9.46290076e-01 3.22010070e-01 2.90907752e-02 9.47422147e-01 3.18686098e-01 2.90907864e-02 9.48542953e-01 3.15321386e-01 2.90907826e-02 9.49607372e-01 3.12092334e-01 2.90907770e-02 9.50695932e-01 3.08780223e-01 2.90907882e-02 9.51775432e-01 3.05421948e-01 2.90907752e-02 9.52800274e-01 3.02216440e-01 2.90907808e-02 9.53879118e-01 2.98802674e-01 2.90907864e-02 9.54941571e-01 2.95373946e-01 2.90907808e-02 9.55961466e-01 2.92058080e-01 2.90907808e-02 9.56947446e-01 2.88802296e-01 2.90907752e-02 9.57929671e-01 2.85536855e-01 2.90907808e-02 9.58923221e-01 2.82189131e-01 2.90907808e-02 9.59899306e-01 2.78842002e-01 2.90907770e-02 9.60893750e-01 2.75405198e-01 2.90907864e-02 9.61866498e-01 2.71981776e-01 2.90907789e-02 9.62810755e-01 2.68623978e-01 2.90907808e-02 9.63721693e-01 2.65325457e-01 2.90907752e-02 9.64621544e-01 2.62054890e-01 2.90907808e-02 9.65552807e-01 2.58598238e-01 2.90907864e-02 9.66472924e-01 2.55134493e-01 2.90907808e-02 9.67360139e-01 2.51750469e-01 2.90907808e-02 9.68205631e-01 2.48470202e-01 2.90907770e-02 9.69046891e-01 2.45168135e-01 2.90907826e-02 9.69885826e-01 2.41820469e-01 2.90907789e-02 9.70731199e-01 2.38418609e-01 2.90907826e-02 9.71585572e-01 2.34929875e-01 2.90907864e-02 9.72411752e-01 2.31471673e-01 2.90907808e-02 9.73189056e-01 2.28158981e-01 2.90907752e-02 9.73988116e-01 2.24752039e-01 2.90907864e-02 9.74762976e-01 2.21349001e-01 2.90907752e-02 9.75531638e-01 2.17969567e-01 2.90907864e-02 9.76279020e-01 2.14553759e-01 2.90907770e-02 9.77030873e-01 2.11132601e-01 2.90907864e-02 9.77775514e-01 2.07644448e-01 2.90907808e-02 9.78475809e-01 2.04303697e-01 2.90907752e-02 9.79186773e-01 2.00910270e-01 2.90907864e-02 9.79880273e-01 1.97460458e-01 2.90907770e-02 9.80546772e-01 1.94142610e-01 2.90907808e-02 9.81238008e-01 1.90634266e-01 2.90907864e-02 9.81892526e-01 1.87200025e-01 2.90907752e-02 9.82539058e-01 1.83800012e-01 2.90907845e-02 9.83170211e-01 1.80357963e-01 2.90907770e-02 9.83788848e-01 1.77000538e-01 2.90907789e-02 9.84413922e-01 1.73506320e-01 2.90908050e-02 9.85023916e-01 1.69957176e-01 2.90907789e-02 9.85615253e-01 1.66504771e-01 2.90907808e-02 9.86167908e-01 1.63178742e-01 2.90907752e-02 9.86720800e-01 1.59823224e-01 2.90907808e-02 9.87293422e-01 1.56275049e-01 2.90907882e-02 9.87830222e-01 1.52809054e-01 2.90907789e-02 9.88352358e-01 1.49413124e-01 2.90907864e-02 9.88868952e-01 1.45933926e-01 2.90907975e-02 9.89356637e-01 1.42588630e-01 2.90907808e-02 9.89865303e-01 1.39059722e-01 2.90907882e-02 9.90342021e-01 1.35564923e-01 2.90907752e-02 9.90815282e-01 1.32103279e-01 2.90907845e-02 9.91268456e-01 1.28605723e-01 2.90907752e-02 9.91712749e-01 1.25194535e-01 2.90907845e-02 9.92153347e-01 1.21636704e-01 2.90907808e-02 9.92574275e-01 1.18120290e-01 2.90907789e-02 9.92980421e-01 1.14679396e-01 2.90907808e-02 9.93360281e-01 1.11305855e-01 2.90907752e-02 9.93735969e-01 1.07930280e-01 2.90907789e-02 9.94115233e-01 1.04399286e-01 2.90907845e-02 9.94471371e-01 1.00873493e-01 2.90907752e-02 9.94821370e-01 9.74396914e-02 2.90907864e-02 9.95150983e-01 9.39379334e-02 2.90907752e-02 9.95466053e-01 9.05913040e-02 2.90907770e-02 9.95777309e-01 8.71159658e-02 2.90907789e-02 9.96075213e-01 8.35930482e-02 2.90907752e-02 9.96373177e-01 8.00413415e-02 2.90907864e-02 9.96653974e-01 7.64421150e-02 2.90907808e-02 9.96911168e-01 7.29969069e-02 2.90907808e-02 9.97157812e-01 6.95281178e-02 2.90907808e-02 9.97389257e-01 6.61234409e-02 2.90907770e-02 9.97611046e-01 6.27309904e-02 2.90907826e-02 9.97824788e-01 5.92346229e-02 2.90907826e-02 9.98031318e-01 5.56884296e-02 2.90907864e-02 9.98222351e-01 5.20861745e-02 2.90908013e-02 9.98390675e-01 4.86947857e-02 2.90907752e-02 9.98552501e-01 4.53142114e-02 2.90907789e-02 9.98705566e-01 4.18212675e-02 2.90907808e-02 9.98845458e-01 3.83334607e-02 2.90907808e-02 9.98975933e-01 3.47916745e-02 2.90907845e-02 9.99093771e-01 3.11839841e-02 2.90907808e-02 9.99190867e-01 2.77993176e-02 2.90907752e-02 9.99285698e-01 2.43740100e-02 2.90907808e-02 9.99360681e-01 2.08873693e-02 2.90907808e-02 9.99432147e-01 1.74055509e-02 2.90907789e-02 9.99479234e-01 1.38776554e-02 2.90907770e-02 9.99524772e-01 1.04262829e-02 2.90907789e-02 9.99562085e-01 6.93626562e-03 2.90907789e-02 9.99583185e-01 3.37898755e-03 2.90907864e-02 9.99577165e-01 -1.22488040e-04 2.90907752e-02 9.99583364e-01 -3.62201780e-03 2.90907882e-02 9.99557018e-01 -7.12528685e-03 2.90907752e-02 9.99525011e-01 -1.05004022e-02 2.90907808e-02 9.99479115e-01 -1.40741123e-02 2.90907864e-02 9.99426007e-01 -1.76830329e-02 2.90907789e-02 9.99354243e-01 -2.10661106e-02 2.90907752e-02 9.99283314e-01 -2.45389342e-02 2.90907845e-02 9.99184787e-01 -2.80455817e-02 2.90907752e-02 9.99086201e-01 -3.15354876e-02 2.90907864e-02 9.98964310e-01 -3.50293517e-02 2.90907733e-02 9.98842120e-01 -3.84269133e-02 2.90907808e-02 9.98703241e-01 -4.19038683e-02 2.90907808e-02 9.98548925e-01 -4.54754680e-02 2.90907864e-02 9.98378098e-01 -4.90535982e-02 2.90907826e-02 9.98197794e-01 -5.25434539e-02 2.90907826e-02 9.98010993e-01 -5.59449233e-02 2.90907752e-02 9.97818589e-01 -5.93180396e-02 2.90907789e-02 9.97603059e-01 -6.27968609e-02 2.90907789e-02 9.97378349e-01 -6.63512573e-02 2.90907864e-02 9.97130334e-01 -6.99249953e-02 2.90907808e-02 9.96881723e-01 -7.34029934e-02 2.90907808e-02 9.96620357e-01 -7.68303052e-02 2.90907752e-02 9.96357858e-01 -8.02160129e-02 2.90907808e-02 9.96071696e-01 -8.36806968e-02 2.90907808e-02 9.95769024e-01 -8.72363895e-02 2.90907845e-02 9.95451450e-01 -9.07275528e-02 2.90907770e-02 9.95139837e-01 -9.41114649e-02 2.90907789e-02 9.94806290e-01 -9.75880548e-02 2.90907826e-02 9.94454920e-01 -1.01123489e-01 2.90907864e-02 9.94089603e-01 -1.04608648e-01 2.90907770e-02 9.93721783e-01 -1.08078562e-01 2.90907845e-02 9.93332744e-01 -1.11571804e-01 2.90907752e-02 9.92952645e-01 -1.14903130e-01 2.90907808e-02 9.92538273e-01 -1.18458711e-01 2.90907845e-02 9.92108822e-01 -1.21967569e-01 2.90907752e-02 9.91686940e-01 -1.25395790e-01 2.90907845e-02 9.91229594e-01 -1.28926188e-01 2.90907808e-02 9.90780592e-01 -1.32315099e-01 2.90907752e-02 9.90318298e-01 -1.35778457e-01 2.90907845e-02 9.89826083e-01 -1.39290482e-01 2.90907752e-02 9.89337504e-01 -1.42707512e-01 2.90907752e-02 9.88840580e-01 -1.46136835e-01 2.90907826e-02 9.88318026e-01 -1.49604410e-01 2.90907733e-02 9.87799406e-01 -1.53013349e-01 2.90907808e-02 9.87248778e-01 -1.56496003e-01 2.90907752e-02 9.86709833e-01 -1.59896806e-01 2.90907826e-02 9.86141682e-01 -1.63345948e-01 2.90907770e-02 9.85570312e-01 -1.66784972e-01 2.90907845e-02 9.84957457e-01 -1.70343086e-01 2.90907808e-02 9.84360278e-01 -1.73787788e-01 2.90907808e-02 9.83763039e-01 -1.77115858e-01 2.90907752e-02 9.83151793e-01 -1.80461735e-01 2.90907789e-02 9.82518494e-01 -1.83899879e-01 2.90907789e-02 9.81857955e-01 -1.87397689e-01 2.90907845e-02 9.81179953e-01 -1.90899640e-01 2.90907789e-02 9.80504453e-01 -1.94350168e-01 2.90907808e-02 9.79832113e-01 -1.97696030e-01 2.90907752e-02 9.79158580e-01 -2.01010913e-01 2.90907770e-02 9.78448868e-01 -2.04446971e-01 2.90907789e-02 9.77716982e-01 -2.07944125e-01 2.90907882e-02 9.76980329e-01 -2.11343318e-01 2.90907752e-02 9.76240039e-01 -2.14742631e-01 2.90907808e-02 9.75480378e-01 -2.18164176e-01 2.90907752e-02 9.74715829e-01 -2.21574903e-01 2.90907864e-02 9.73924339e-01 -2.25002378e-01 2.90907752e-02 9.73147988e-01 -2.28380084e-01 2.90907882e-02 9.72337902e-01 -2.31767803e-01 2.90907733e-02 9.71549809e-01 -2.35071287e-01 2.90907808e-02 9.70702171e-01 -2.38546371e-01 2.90907864e-02 9.69861090e-01 -2.41915047e-01 2.90907752e-02 9.69018996e-01 -2.45289207e-01 2.90907864e-02 9.68121827e-01 -2.48798609e-01 2.90907789e-02 9.67273712e-01 -2.52059966e-01 2.90907752e-02 9.66386676e-01 -2.55465984e-01 2.90907845e-02 9.65485394e-01 -2.58836865e-01 2.90907752e-02 9.64607358e-01 -2.62101740e-01 2.90907808e-02 9.63666975e-01 -2.65535176e-01 2.90907826e-02 9.62712228e-01 -2.68962562e-01 2.90907752e-02 9.61779535e-01 -2.72300422e-01 2.90907864e-02 9.60791945e-01 -2.75749832e-01 2.90907789e-02 9.59848464e-01 -2.79003441e-01 2.90907752e-02 9.58907306e-01 -2.82237709e-01 2.90907826e-02 9.57890332e-01 -2.85682082e-01 2.90907864e-02 9.56855774e-01 -2.89112985e-01 2.90907808e-02 9.55839276e-01 -2.92461723e-01 2.90907789e-02 9.54837680e-01 -2.95707375e-01 2.90907752e-02 9.53833640e-01 -2.98931807e-01 2.90907789e-02 9.52784717e-01 -3.02268088e-01 2.90907826e-02 9.51721251e-01 -3.05599391e-01 2.90908013e-02 9.50627148e-01 -3.08990180e-01 2.90907864e-02 9.49512720e-01 -3.12381208e-01 2.90907770e-02 9.48429465e-01 -3.15654993e-01 2.90907752e-02 9.47354317e-01 -3.18878174e-01 2.90907808e-02 9.46241498e-01 -3.22161645e-01 2.90907808e-02 9.45090950e-01 -3.25529456e-01 2.90907864e-02 9.43937242e-01 -3.28842580e-01 2.90907770e-02 9.42794621e-01 -3.32119703e-01 2.90907845e-02 9.41619933e-01 -3.35429877e-01 2.90907752e-02 9.40450191e-01 -3.38704735e-01 2.90907864e-02 9.39261138e-01 -3.41975510e-01 2.90907752e-02 9.38048363e-01 -3.45290244e-01 2.90907882e-02 9.36823726e-01 -3.48565727e-01 2.90907770e-02 9.35650885e-01 -3.51711839e-01 2.90907789e-02 9.34425533e-01 -3.54969472e-01 2.90907808e-02 9.33146656e-01 -3.58353734e-01 2.90907882e-02 9.31866169e-01 -3.61624151e-01 2.90907752e-02 9.30625439e-01 -3.64835411e-01 2.90907864e-02 9.29330587e-01 -3.68106276e-01 2.90907770e-02 9.28048313e-01 -3.71341169e-01 2.90907864e-02 9.26740825e-01 -3.74574155e-01 2.90907752e-02 9.25475478e-01 -3.77698749e-01 2.90907808e-02 9.24102724e-01 -3.81053358e-01 2.90907882e-02 9.22757983e-01 -3.84277761e-01 2.90907752e-02 9.21433926e-01 -3.87460262e-01 2.90907864e-02 9.20021296e-01 -3.90794009e-01 2.90907826e-02 9.18689370e-01 -3.93906325e-01 2.90907770e-02 9.17360127e-01 -3.96997899e-01 2.90907770e-02 9.15926874e-01 -4.00311559e-01 2.90907864e-02 9.14479494e-01 -4.03594077e-01 2.90907808e-02 9.13077891e-01 -4.06749010e-01 2.90907752e-02 9.11687613e-01 -4.09860492e-01 2.90907770e-02 9.10283089e-01 -4.12970334e-01 2.90907808e-02 9.08850610e-01 -4.16107655e-01 2.90907789e-02 9.07336175e-01 -4.19413716e-01 2.90907882e-02 9.05827999e-01 -4.22650993e-01 2.90907789e-02 9.04354453e-01 -4.25797343e-01 2.90907808e-02 9.02904034e-01 -4.28859919e-01 2.90907770e-02 9.01439130e-01 -4.31936234e-01 2.90907826e-02 8.99929583e-01 -4.35073882e-01 2.90907770e-02 8.98360193e-01 -4.38315123e-01 2.90907882e-02 8.96821260e-01 -4.41437781e-01 2.90907752e-02 8.95280600e-01 -4.44563955e-01 2.90907826e-02 8.93724024e-01 -4.47675794e-01 2.90907752e-02 8.92199516e-01 -4.50715363e-01 2.90907808e-02 8.90628219e-01 -4.53813374e-01 2.90907826e-02 8.88995826e-01 -4.57005471e-01 2.90907864e-02 8.87385368e-01 -4.60105479e-01 2.90907752e-02 8.85805964e-01 -4.63157564e-01 2.90907826e-02 8.84200096e-01 -4.66209203e-01 2.90907770e-02 8.82521212e-01 -4.69386697e-01 2.90907882e-02 8.80876780e-01 -4.72456306e-01 2.90907770e-02 8.79232407e-01 -4.75520462e-01 2.90907882e-02 8.77546728e-01 -4.78617013e-01 2.90907770e-02 8.75917435e-01 -4.81588811e-01 2.90907789e-02 8.74234438e-01 -4.84634578e-01 2.90907789e-02 8.72551382e-01 -4.87662077e-01 2.90907808e-02 8.70831788e-01 -4.90731418e-01 2.90907826e-02 8.69079173e-01 -4.93829638e-01 2.90907864e-02 8.67332935e-01 -4.96883869e-01 2.90907770e-02 8.65606129e-01 -4.99893010e-01 2.90907845e-02 8.63848031e-01 -5.02920687e-01 2.90907789e-02 8.62145185e-01 -5.05835474e-01 2.90907789e-02 8.60369563e-01 -5.08849084e-01 2.90907808e-02 8.58589888e-01 -5.11845112e-01 2.90907826e-02 8.56755614e-01 -5.14916897e-01 2.90907864e-02 8.54912043e-01 -5.17960131e-01 2.90907789e-02 8.53142262e-01 -5.20876288e-01 2.90907808e-02 8.51357043e-01 -5.23787379e-01 2.90907826e-02 8.49534988e-01 -5.26740253e-01 2.90907826e-02 8.47652674e-01 -5.29767752e-01 2.90907882e-02 8.45746577e-01 -5.32799900e-01 2.90907808e-02 8.43902469e-01 -5.35711467e-01 2.90907770e-02 8.42082441e-01 -5.38574159e-01 2.90907826e-02 8.40148032e-01 -5.41590154e-01 2.90907864e-02 8.38198662e-01 -5.44599831e-01 2.90907826e-02 8.36307704e-01 -5.47490358e-01 2.90907789e-02 8.34406316e-01 -5.50390840e-01 2.90907826e-02 8.32502127e-01 -5.53252935e-01 2.90907752e-02 8.30634713e-01 -5.56064963e-01 2.90907808e-02 8.28688622e-01 -5.58961511e-01 2.90907789e-02 8.26671064e-01 -5.61944127e-01 2.90907845e-02 8.24700415e-01 -5.64818978e-01 2.90907752e-02 8.22723567e-01 -5.67708194e-01 2.90907864e-02 8.20732296e-01 -5.70570230e-01 2.90907752e-02 8.18730295e-01 -5.73450744e-01 2.90907864e-02 8.16726565e-01 -5.76290429e-01 2.90907752e-02 8.14727485e-01 -5.79126000e-01 2.90907864e-02 8.12684655e-01 -5.81981778e-01 2.90907752e-02 8.10686648e-01 -5.84760785e-01 2.90907826e-02 8.08583319e-01 -5.87669551e-01 2.90907808e-02 8.06528389e-01 -5.90482414e-01 2.90907770e-02 8.04466069e-01 -5.93293846e-01 2.90907826e-02 8.02363098e-01 -5.96129715e-01 2.90907789e-02 8.00329626e-01 -5.98856628e-01 2.90907770e-02 7.98250198e-01 -6.01635456e-01 2.90907864e-02 7.96135962e-01 -6.04421437e-01 2.90907770e-02 7.94081330e-01 -6.07123971e-01 2.90907826e-02 7.91932523e-01 -6.09924257e-01 2.90907845e-02 7.89751291e-01 -6.12744033e-01 2.90907845e-02 7.87560463e-01 -6.15556240e-01 2.90907808e-02 7.85405636e-01 -6.18303359e-01 2.90907789e-02 7.83312201e-01 -6.20948970e-01 2.90907752e-02 7.81189919e-01 -6.23622298e-01 2.90907826e-02 7.78999507e-01 -6.26358747e-01 2.90907826e-02 7.76763618e-01 -6.29132867e-01 2.90907864e-02 7.74512708e-01 -6.31893992e-01 2.90907808e-02 7.72351205e-01 -6.34531617e-01 2.90907770e-02 7.70199955e-01 -6.37149572e-01 2.90907845e-02 7.67976046e-01 -6.39824271e-01 2.90907808e-02 7.65745163e-01 -6.42493308e-01 2.90907826e-02 7.63431013e-01 -6.45244062e-01 2.90907864e-02 7.61156023e-01 -6.47917926e-01 2.90907770e-02 7.58897126e-01 -6.50571644e-01 2.90907882e-02 7.56596446e-01 -6.53236866e-01 2.90907752e-02 7.54365623e-01 -6.55820429e-01 2.90907845e-02 7.52002358e-01 -6.58527672e-01 2.90907864e-02 7.49680638e-01 -6.61165416e-01 2.90907789e-02 7.47440040e-01 -6.63694203e-01 2.90907752e-02 7.45180428e-01 -6.66235566e-01 2.90907826e-02 7.42777824e-01 -6.68918192e-01 2.90907882e-02 7.40416944e-01 -6.71521544e-01 2.90907752e-02 7.38070786e-01 -6.74107492e-01 2.90907882e-02 7.35698760e-01 -6.76686525e-01 2.90907752e-02 7.33409882e-01 -6.79170430e-01 2.90907826e-02 7.31047034e-01 -6.81709707e-01 2.90907808e-02 7.28572488e-01 -6.84358537e-01 2.90907845e-02 7.26173639e-01 -6.86892927e-01 2.90907752e-02 7.23796189e-01 -6.89407945e-01 2.90907808e-02 7.21365929e-01 -6.91934645e-01 2.90907733e-02 7.18970656e-01 -6.94435775e-01 2.90907752e-02 7.16556668e-01 -6.96920395e-01 2.90907361e-02 7.14350760e-01 -6.99181616e-01 2.90905256e-02 7.11822271e-01 -7.01752782e-01 2.90905479e-02 7.09498167e-01 -7.04105556e-01 2.90905256e-02 7.06730962e-01 -7.06883192e-01 2.90905274e-02 7.04165339e-01 -7.09438920e-01 2.90905349e-02 7.01821446e-01 -7.11757600e-01 2.90905349e-02 6.99506879e-01 -7.14032531e-01 2.90905368e-02 6.96994245e-01 -7.16484725e-01 2.90905330e-02 6.94238901e-01 -7.19156563e-01 2.90905349e-02 6.92479551e-01 -7.20850766e-01 2.90905368e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.72392881e-01 -8.19462836e-01 2.90905274e-02 5.70187151e-01 -8.20996225e-01 2.90906653e-02 5.67507088e-01 -8.22850823e-01 2.90907342e-02 5.64674199e-01 -8.24796617e-01 2.90907640e-02 5.61843038e-01 -8.26728821e-01 2.90907752e-02 5.58944821e-01 -8.28693211e-01 2.90907752e-02 5.56066275e-01 -8.30628514e-01 2.90907752e-02 5.53086817e-01 -8.32619846e-01 2.90907826e-02 5.50123811e-01 -8.34577262e-01 2.90907733e-02 5.47301650e-01 -8.36430371e-01 2.90907752e-02 5.44333518e-01 -8.38370025e-01 2.90907845e-02 5.41391909e-01 -8.40266049e-01 2.90907752e-02 5.38535595e-01 -8.42103720e-01 2.90907789e-02 5.35589993e-01 -8.43979418e-01 2.90907789e-02 5.32637298e-01 -8.45850050e-01 2.90907808e-02 5.29690623e-01 -8.47693563e-01 2.90907789e-02 5.26753485e-01 -8.49526584e-01 2.90907789e-02 5.23752868e-01 -8.51377130e-01 2.90907808e-02 5.20791411e-01 -8.53194535e-01 2.90907789e-02 5.17788649e-01 -8.55017424e-01 2.90907808e-02 5.14799714e-01 -8.56821239e-01 2.90907808e-02 5.11808097e-01 -8.58610511e-01 2.90907808e-02 5.08794546e-01 -8.60400915e-01 2.90907808e-02 5.05794644e-01 -8.62169027e-01 2.90907808e-02 5.02780914e-01 -8.63927484e-01 2.90907808e-02 4.99692410e-01 -8.65722775e-01 2.90907864e-02 4.96673644e-01 -8.67450714e-01 2.90907733e-02 4.93705243e-01 -8.69145870e-01 2.90907808e-02 4.90685940e-01 -8.70858252e-01 2.90907808e-02 4.87628400e-01 -8.72570753e-01 2.90907826e-02 4.84602213e-01 -8.74253213e-01 2.90907808e-02 4.81509656e-01 -8.75964165e-01 2.90907826e-02 4.78455514e-01 -8.77636611e-01 2.90908013e-02 4.75409001e-01 -8.79288852e-01 2.90907826e-02 4.72318023e-01 -8.80955160e-01 2.90907845e-02 4.69240397e-01 -8.82595956e-01 2.90907826e-02 4.66163397e-01 -8.84227216e-01 2.90907826e-02 4.62980002e-01 -8.85900080e-01 2.90907882e-02 4.59876835e-01 -8.87506843e-01 2.90907770e-02 4.56879973e-01 -8.89058828e-01 2.90907826e-02 4.53767598e-01 -8.90650272e-01 2.90907826e-02 4.50642258e-01 -8.92237127e-01 2.90907845e-02 4.47518408e-01 -8.93807352e-01 2.90907845e-02 4.44400430e-01 -8.95360947e-01 2.90907826e-02 4.41275418e-01 -8.96906555e-01 2.90907826e-02 4.38135445e-01 -8.98445487e-01 2.90907845e-02 4.34993804e-01 -8.99970114e-01 2.90907826e-02 4.31866378e-01 -9.01472449e-01 2.90907826e-02 4.28732634e-01 -9.02967632e-01 2.90907826e-02 4.25547063e-01 -9.04472768e-01 2.90907826e-02 4.22334760e-01 -9.05982316e-01 2.90907882e-02 4.19142723e-01 -9.07457054e-01 2.90907789e-02 4.16070998e-01 -9.08871889e-01 2.90907845e-02 4.12884653e-01 -9.10324991e-01 2.90907845e-02 4.09710407e-01 -9.11758006e-01 2.90907826e-02 4.06453282e-01 -9.13218260e-01 2.90907882e-02 4.03238714e-01 -9.14635718e-01 2.90907789e-02 4.00124073e-01 -9.16006267e-01 2.90907826e-02 3.96923810e-01 -9.17397201e-01 2.90907845e-02 3.93703043e-01 -9.18779492e-01 2.90907845e-02 3.90448958e-01 -9.20172393e-01 2.90907882e-02 3.87210876e-01 -9.21535909e-01 2.90907789e-02 3.84016782e-01 -9.22876596e-01 2.90907882e-02 3.80768061e-01 -9.24212813e-01 2.90907770e-02 3.77628595e-01 -9.25506592e-01 2.90907826e-02 3.74412835e-01 -9.26811635e-01 2.90907845e-02 3.71083528e-01 -9.28152025e-01 2.90907882e-02 3.67755473e-01 -9.29474294e-01 2.90907845e-02 3.64583492e-01 -9.30720568e-01 2.90907789e-02 3.61437082e-01 -9.31942642e-01 2.90907845e-02 3.58163923e-01 -9.33215559e-01 2.90907826e-02 3.54914367e-01 -9.34447587e-01 2.90907826e-02 3.51592362e-01 -9.35700774e-01 2.90907882e-02 3.48335296e-01 -9.36913133e-01 2.90907808e-02 3.45111370e-01 -9.38111722e-01 2.90907826e-02 3.41838628e-01 -9.39315438e-01 2.90907826e-02 3.38554800e-01 -9.40501273e-01 2.90907845e-02 3.35263848e-01 -9.41682637e-01 2.90907845e-02 3.31969559e-01 -9.42846894e-01 2.90907845e-02 3.28680843e-01 -9.43997562e-01 2.90907826e-02 3.25309515e-01 -9.45169270e-01 2.90907882e-02 3.21997106e-01 -9.46297646e-01 2.90907808e-02 3.18805337e-01 -9.47380662e-01 2.90907845e-02 3.15492421e-01 -9.48488533e-01 2.90907845e-02 3.12178969e-01 -9.49582160e-01 2.90907826e-02 3.08779806e-01 -9.50698197e-01 2.90907901e-02 3.05448800e-01 -9.51767325e-01 2.90907770e-02 3.02234590e-01 -9.52795386e-01 2.90907845e-02 2.98901349e-01 -9.53846455e-01 2.90907845e-02 2.95571953e-01 -9.54882741e-01 2.90907826e-02 2.92223603e-01 -9.55912888e-01 2.90907826e-02 2.88827628e-01 -9.56945360e-01 2.90907882e-02 2.85449862e-01 -9.57955062e-01 2.90907789e-02 2.82195538e-01 -9.58921850e-01 2.90907826e-02 2.78767854e-01 -9.59928036e-01 2.90907901e-02 2.75296271e-01 -9.60924327e-01 2.90907845e-02 2.71931708e-01 -9.61881459e-01 2.90907826e-02 2.68657744e-01 -9.62800086e-01 2.90907770e-02 2.65409112e-01 -9.63704050e-01 2.90907845e-02 2.62035310e-01 -9.64626849e-01 2.90907808e-02 2.58663982e-01 -9.65534270e-01 2.90907845e-02 2.55260795e-01 -9.66442764e-01 2.90907882e-02 2.51876146e-01 -9.67326999e-01 2.90907808e-02 2.48530760e-01 -9.68194067e-01 2.90907845e-02 2.45134398e-01 -9.69055593e-01 2.90907826e-02 2.41679907e-01 -9.69926000e-01 2.90907864e-02 2.38290489e-01 -9.70763385e-01 2.90907808e-02 2.34999359e-01 -9.71569359e-01 2.90907845e-02 2.31614277e-01 -9.72379804e-01 2.90907826e-02 2.28203639e-01 -9.73185539e-01 2.90907826e-02 2.24729016e-01 -9.73995626e-01 2.90907882e-02 2.21211836e-01 -9.74797130e-01 2.90907826e-02 2.17912376e-01 -9.75537658e-01 2.90907770e-02 2.14605078e-01 -9.76272702e-01 2.90907845e-02 2.11201057e-01 -9.77015018e-01 2.90907845e-02 2.07806379e-01 -9.77742434e-01 2.90907826e-02 2.04287082e-01 -9.78489637e-01 2.90907901e-02 2.00852007e-01 -9.79193389e-01 2.90907789e-02 1.97537124e-01 -9.79870737e-01 2.90907845e-02 1.94111869e-01 -9.80553329e-01 2.90907845e-02 1.90700412e-01 -9.81223404e-01 2.90907845e-02 1.87197357e-01 -9.81899440e-01 2.90907882e-02 1.83723718e-01 -9.82549071e-01 2.90907789e-02 1.80302635e-01 -9.83186245e-01 2.90907882e-02 1.76846579e-01 -9.83816147e-01 2.90907770e-02 1.73542351e-01 -9.84408081e-01 2.90907845e-02 1.70084611e-01 -9.85003829e-01 2.90907845e-02 1.66640177e-01 -9.85597014e-01 2.90907864e-02 1.63220808e-01 -9.86167192e-01 2.90907845e-02 1.59765124e-01 -9.86732244e-01 2.90907845e-02 1.56318635e-01 -9.87284184e-01 2.90907845e-02 1.52891099e-01 -9.87821162e-01 2.90907845e-02 1.49435297e-01 -9.88348007e-01 2.90907845e-02 1.45998240e-01 -9.88862574e-01 2.90907826e-02 1.42552540e-01 -9.89363372e-01 2.90907826e-02 1.38993829e-01 -9.89874959e-01 2.90907901e-02 1.35425627e-01 -9.90366399e-01 2.90907826e-02 1.32063374e-01 -9.90816951e-01 2.90907789e-02 1.28701404e-01 -9.91260946e-01 2.90907826e-02 1.25234306e-01 -9.91709173e-01 2.90907864e-02 1.21770807e-01 -9.92137194e-01 2.90908031e-02 1.18230484e-01 -9.92567420e-01 2.90908068e-02 1.14749394e-01 -9.92969990e-01 2.90907808e-02 1.11388624e-01 -9.93355632e-01 2.90907845e-02 1.07906371e-01 -9.93740499e-01 2.90907845e-02 1.04442723e-01 -9.94109273e-01 2.90907826e-02 1.00888900e-01 -9.94477928e-01 2.90907882e-02 9.74123925e-02 -9.94821072e-01 2.90907789e-02 9.39639956e-02 -9.95161891e-01 2.90907901e-02 9.04607549e-02 -9.95478392e-01 2.90907770e-02 8.70010108e-02 -9.95792389e-01 2.90907901e-02 8.34271237e-02 -9.96095061e-01 2.90907845e-02 8.00420493e-02 -9.96370912e-01 2.90907789e-02 7.66574964e-02 -9.96638834e-01 2.90907864e-02 7.31793344e-02 -9.96900678e-01 2.90907845e-02 6.96946010e-02 -9.97147560e-01 2.90908013e-02 6.62326142e-02 -9.97385681e-01 2.90907826e-02 6.27502501e-02 -9.97611105e-01 2.90907864e-02 5.92549257e-02 -9.97823536e-01 2.90907845e-02 5.57770878e-02 -9.98025894e-01 2.90907864e-02 5.21990620e-02 -9.98220265e-01 2.90907901e-02 4.86848913e-02 -9.98393953e-01 2.90907789e-02 4.52165119e-02 -9.98561561e-01 2.90908068e-02 4.16432545e-02 -9.98715818e-01 2.90907845e-02 3.82290594e-02 -9.98848259e-01 2.90907789e-02 3.48670967e-02 -9.98973191e-01 2.90907826e-02 3.12878788e-02 -9.99092996e-01 2.90907882e-02 2.77796853e-02 -9.99194324e-01 2.90907789e-02 2.43023671e-02 -9.99292254e-01 2.90907882e-02 2.07942091e-02 -9.99361217e-01 2.90907789e-02 1.73996743e-02 -9.99435663e-01 2.90907845e-02 1.39166862e-02 -9.99480724e-01 2.90907845e-02 1.04115522e-02 -9.99529421e-01 2.90907845e-02 6.93580974e-03 -9.99563396e-01 2.90907826e-02 3.45207634e-03 -9.99581873e-01 2.90907845e-02 -3.40984443e-05 -9.99582887e-01 2.90907845e-02 -3.51034431e-03 -9.99581277e-01 2.90907845e-02 -6.99303066e-03 -9.99566257e-01 2.90907864e-02 -1.04922438e-02 -9.99526739e-01 2.90907845e-02 -1.39995161e-02 -9.99480069e-01 2.90907845e-02 -1.75565686e-02 -9.99437451e-01 2.90907901e-02 -2.11279504e-02 -9.99357998e-01 2.90907864e-02 -2.45421529e-02 -9.99281526e-01 2.90907808e-02 -2.79442612e-02 -9.99193907e-01 2.90907864e-02 -3.14212292e-02 -9.99089956e-01 2.90907845e-02 -3.49094942e-02 -9.98975158e-01 2.90907864e-02 -3.84898447e-02 -9.98845160e-01 2.90907901e-02 -4.19753380e-02 -9.98700440e-01 2.90907808e-02 -4.53605019e-02 -9.98552859e-01 2.90907864e-02 -4.88368422e-02 -9.98390496e-01 2.90907864e-02 -5.23342080e-02 -9.98208582e-01 2.90907845e-02 -5.58975860e-02 -9.98023152e-01 2.90907919e-02 -5.93982153e-02 -9.97812927e-01 2.90907789e-02 -6.28604665e-02 -9.97604191e-01 2.90907901e-02 -6.63467720e-02 -9.97375548e-01 2.90907808e-02 -6.97529167e-02 -9.97145057e-01 2.90907845e-02 -7.32140690e-02 -9.96899426e-01 2.90907864e-02 -7.66997039e-02 -9.96636808e-01 2.90907864e-02 -8.02684724e-02 -9.96357083e-01 2.90907919e-02 -8.37610587e-02 -9.96063948e-01 2.90907789e-02 -8.71213749e-02 -9.95778143e-01 2.90907845e-02 -9.06050727e-02 -9.95468915e-01 2.90907864e-02 -9.41026658e-02 -9.95143771e-01 2.90907864e-02 -9.75554287e-02 -9.94810998e-01 2.90907845e-02 -1.01020284e-01 -9.94465828e-01 2.90907845e-02 -1.04589961e-01 -9.94099975e-01 2.90907901e-02 -1.08158633e-01 -9.93713796e-01 2.90907845e-02 -1.11546457e-01 -9.93337452e-01 2.90907994e-02 -1.14889242e-01 -9.92956758e-01 2.90908031e-02 -1.18366033e-01 -9.92548943e-01 2.90907864e-02 -1.21832870e-01 -9.92130578e-01 2.90907845e-02 -1.25394061e-01 -9.91691470e-01 2.90907919e-02 -1.28889591e-01 -9.91234303e-01 2.90907789e-02 -1.32231295e-01 -9.90798652e-01 2.90907864e-02 -1.35684863e-01 -9.90331709e-01 2.90907864e-02 -1.39137894e-01 -9.89851773e-01 2.90907845e-02 -1.42686263e-01 -9.89347219e-01 2.90908068e-02 -1.46149755e-01 -9.88837302e-01 2.90907808e-02 -1.49583906e-01 -9.88328815e-01 2.90907901e-02 -1.53060302e-01 -9.87793148e-01 2.90907808e-02 -1.56418815e-01 -9.87267554e-01 2.90907845e-02 -1.59853637e-01 -9.86719489e-01 2.90908031e-02 -1.63309425e-01 -9.86153543e-01 2.90907845e-02 -1.66828960e-01 -9.85565901e-01 2.90907901e-02 -1.70282975e-01 -9.84968662e-01 2.90907808e-02 -1.73626140e-01 -9.84392941e-01 2.90907864e-02 -1.77059293e-01 -9.83779252e-01 2.90907845e-02 -1.80475414e-01 -9.83153105e-01 2.90907845e-02 -1.84005558e-01 -9.82505739e-01 2.90907919e-02 -1.87457100e-01 -9.81844783e-01 2.90907789e-02 -1.90745935e-01 -9.81213450e-01 2.90907845e-02 -1.94171667e-01 -9.80544686e-01 2.90907864e-02 -1.97719142e-01 -9.79835212e-01 2.90907919e-02 -2.01129660e-01 -9.79134560e-01 2.90907789e-02 -2.04422414e-01 -9.78457034e-01 2.90907845e-02 -2.07874537e-01 -9.77730870e-01 2.90907845e-02 -2.11362928e-01 -9.76986825e-01 2.90907901e-02 -2.14781910e-01 -9.76231575e-01 2.90907789e-02 -2.18099371e-01 -9.75500584e-01 2.90908050e-02 -2.21465841e-01 -9.74741220e-01 2.90907864e-02 -2.24911138e-01 -9.73951161e-01 2.90907864e-02 -2.28374392e-01 -9.73150074e-01 2.90907901e-02 -2.31785864e-01 -9.72337186e-01 2.90907789e-02 -2.35077783e-01 -9.71550345e-01 2.90907864e-02 -2.38531336e-01 -9.70708966e-01 2.90907901e-02 -2.41928428e-01 -9.69862223e-01 2.90907808e-02 -2.45240286e-01 -9.69030917e-01 2.90907845e-02 -2.48621270e-01 -9.68169808e-01 2.90907845e-02 -2.52093703e-01 -9.67275023e-01 2.90907901e-02 -2.55480140e-01 -9.66381550e-01 2.90907789e-02 -2.58829683e-01 -9.65494692e-01 2.90907901e-02 -2.62273788e-01 -9.64563727e-01 2.90907845e-02 -2.65565425e-01 -9.63657498e-01 2.90907808e-02 -2.68912166e-01 -9.62735713e-01 2.90907901e-02 -2.72270411e-01 -9.61785913e-01 2.90907789e-02 -2.75538296e-01 -9.60856497e-01 2.90907845e-02 -2.78895319e-01 -9.59887981e-01 2.90907845e-02 -2.82244593e-01 -9.58907306e-01 2.90907845e-02 -2.85601437e-01 -9.57916796e-01 2.90907882e-02 -2.88947672e-01 -9.56907749e-01 2.90907845e-02 -2.92283148e-01 -9.55894649e-01 2.90907845e-02 -2.95683265e-01 -9.54852283e-01 2.90907901e-02 -2.99026012e-01 -9.53806162e-01 2.90907808e-02 -3.02357405e-01 -9.52759087e-01 2.90907901e-02 -3.05680692e-01 -9.51695085e-01 2.90907808e-02 -3.08916241e-01 -9.50650156e-01 2.90907864e-02 -3.12324882e-01 -9.49539721e-01 2.90907901e-02 -3.15655649e-01 -9.48432446e-01 2.90907808e-02 -3.18941742e-01 -9.47337985e-01 2.90907901e-02 -3.22264314e-01 -9.46205616e-01 2.90907789e-02 -3.25443774e-01 -9.45120931e-01 2.90907864e-02 -3.28738809e-01 -9.43977892e-01 2.90908031e-02 -3.32022637e-01 -9.42829609e-01 2.90907845e-02 -3.35407943e-01 -9.41632152e-01 2.90907882e-02 -3.38716567e-01 -9.40440238e-01 2.90907789e-02 -3.41978401e-01 -9.39269066e-01 2.90907919e-02 -3.45281780e-01 -9.38045859e-01 2.90907808e-02 -3.48454654e-01 -9.36872900e-01 2.90907882e-02 -3.51734430e-01 -9.35646176e-01 2.90907845e-02 -3.54983330e-01 -9.34424281e-01 2.90907864e-02 -3.58263761e-01 -9.33179200e-01 2.90907864e-02 -3.61595988e-01 -9.31887865e-01 2.90907901e-02 -3.64842147e-01 -9.30618346e-01 2.90907789e-02 -3.67997676e-01 -9.29378927e-01 2.90907845e-02 -3.71228158e-01 -9.28091407e-01 2.90907845e-02 -3.74457121e-01 -9.26794410e-01 2.90907864e-02 -3.77776146e-01 -9.25449133e-01 2.90907901e-02 -3.81017476e-01 -9.24111009e-01 2.90907808e-02 -3.84170949e-01 -9.22810435e-01 2.90907845e-02 -3.87369484e-01 -9.21471417e-01 2.90907845e-02 -3.90583038e-01 -9.20113087e-01 2.90907845e-02 -3.93852770e-01 -9.18717444e-01 2.90907882e-02 -3.97060126e-01 -9.17335033e-01 2.90907826e-02 -4.00271714e-01 -9.15946066e-01 2.90907901e-02 -4.03457016e-01 -9.14540291e-01 2.90907808e-02 -4.06590402e-01 -9.13155138e-01 2.90907864e-02 -4.09761667e-01 -9.11736846e-01 2.90907845e-02 -4.12957668e-01 -9.10291433e-01 2.90907845e-02 -4.16198909e-01 -9.08814549e-01 2.90907901e-02 -4.19377714e-01 -9.07346189e-01 2.90907770e-02 -4.22439545e-01 -9.05929565e-01 2.90907845e-02 -4.25590456e-01 -9.04454708e-01 2.90907864e-02 -4.28837836e-01 -9.02922451e-01 2.90907901e-02 -4.31998402e-01 -9.01407421e-01 2.90907808e-02 -4.35055971e-01 -8.99943054e-01 2.90907845e-02 -4.38207775e-01 -8.98412049e-01 2.90907864e-02 -4.41427499e-01 -8.96835804e-01 2.90907919e-02 -4.44554448e-01 -8.95281792e-01 2.90907789e-02 -4.47610885e-01 -8.93763602e-01 2.90907882e-02 -4.50710267e-01 -8.92204940e-01 2.90907864e-02 -4.53796208e-01 -8.90638411e-01 2.90907864e-02 -4.56990957e-01 -8.89004648e-01 2.90907882e-02 -4.60114986e-01 -8.87385547e-01 2.90907789e-02 -4.63134766e-01 -8.85818958e-01 2.90907845e-02 -4.66205955e-01 -8.84205759e-01 2.90907845e-02 -4.69281435e-01 -8.82575214e-01 2.90907845e-02 -4.72434461e-01 -8.80895793e-01 2.90907901e-02 -4.75543469e-01 -8.79216015e-01 2.90907826e-02 -4.78622586e-01 -8.77550006e-01 2.90907864e-02 -4.81637955e-01 -8.75891626e-01 2.90907808e-02 -4.84698236e-01 -8.74207258e-01 2.90907919e-02 -4.87840831e-01 -8.72454345e-01 2.90907864e-02 -4.90802288e-01 -8.70788813e-01 2.90907789e-02 -4.93776649e-01 -8.69108617e-01 2.90907864e-02 -4.96798128e-01 -8.67386997e-01 2.90907845e-02 -4.99803394e-01 -8.65658402e-01 2.90907864e-02 -5.02815187e-01 -8.63912642e-01 2.90907845e-02 -5.05818605e-01 -8.62157762e-01 2.90907864e-02 -5.08843362e-01 -8.60374391e-01 2.90907845e-02 -5.11829793e-01 -8.58601153e-01 2.90907845e-02 -5.14832318e-01 -8.56805086e-01 2.90907845e-02 -5.17816246e-01 -8.55004132e-01 2.90907864e-02 -5.20838857e-01 -8.53168249e-01 2.90907864e-02 -5.23895562e-01 -8.51294935e-01 2.90907882e-02 -5.26839793e-01 -8.49472582e-01 2.90907789e-02 -5.29766917e-01 -8.47656667e-01 2.90907901e-02 -5.32822609e-01 -8.45736384e-01 2.90907882e-02 -5.35795391e-01 -8.43853354e-01 2.90907845e-02 -5.38728178e-01 -8.41983259e-01 2.90907845e-02 -5.41597724e-01 -8.40136528e-01 2.90907789e-02 -5.44446409e-01 -8.38297307e-01 2.90907845e-02 -5.47366738e-01 -8.36393297e-01 2.90907845e-02 -5.50283968e-01 -8.34478498e-01 2.90907845e-02 -5.53188443e-01 -8.32553625e-01 2.90907864e-02 -5.56095183e-01 -8.30617666e-01 2.90907845e-02 -5.58984518e-01 -8.28676343e-01 2.90907845e-02 -5.61878145e-01 -8.26714277e-01 2.90907826e-02 -5.64762712e-01 -8.24748635e-01 2.90907845e-02 -5.67660034e-01 -8.22756946e-01 2.90907845e-02 -5.70541441e-01 -8.20762992e-01 2.90907864e-02 -5.73442280e-01 -8.18736553e-01 2.90907864e-02 -5.76362431e-01 -8.16686928e-01 2.90907864e-02 -5.79156041e-01 -8.14700782e-01 2.90907789e-02 -5.81904054e-01 -8.12744081e-01 2.90907845e-02 -5.84757805e-01 -8.10690224e-01 2.90907845e-02 -5.87572277e-01 -8.08655024e-01 2.90907826e-02 -5.90458751e-01 -8.06552529e-01 2.90907882e-02 -5.93280375e-01 -8.04473579e-01 2.90907789e-02 -5.95985830e-01 -8.02473068e-01 2.90907826e-02 -5.98788142e-01 -8.00381899e-01 2.90907826e-02 -6.01585269e-01 -7.98285902e-01 2.90907845e-02 -6.04381084e-01 -7.96172857e-01 2.90908031e-02 -6.07152224e-01 -7.94061124e-01 2.90907845e-02 -6.09970868e-01 -7.91898370e-01 2.90907882e-02 -6.12752914e-01 -7.89744794e-01 2.90907808e-02 -6.15432441e-01 -7.87657976e-01 2.90907826e-02 -6.18170798e-01 -7.85513759e-01 2.90907845e-02 -6.20913744e-01 -7.83346057e-01 2.90907845e-02 -6.23699963e-01 -7.81132221e-01 2.90907882e-02 -6.26428723e-01 -7.78939545e-01 2.90907789e-02 -6.29079640e-01 -7.76804686e-01 2.90907845e-02 -6.31767511e-01 -7.74616420e-01 2.90907845e-02 -6.34483814e-01 -7.72395730e-01 2.90907845e-02 -6.37192667e-01 -7.70164132e-01 2.90907864e-02 -6.39896333e-01 -7.67916858e-01 2.90907826e-02 -6.42566621e-01 -7.65685499e-01 2.90907845e-02 -6.45279646e-01 -7.63403714e-01 2.90907882e-02 -6.47935331e-01 -7.61142135e-01 2.90907789e-02 -6.50590301e-01 -7.58882165e-01 2.90907901e-02 -6.53217196e-01 -7.56617486e-01 2.90907789e-02 -6.55788958e-01 -7.54392505e-01 2.90907845e-02 -6.58505142e-01 -7.52024293e-01 2.90907882e-02 -6.61114156e-01 -7.49723017e-01 2.90907770e-02 -6.63635314e-01 -7.47497857e-01 2.90907826e-02 -6.66237712e-01 -7.45180011e-01 2.90907845e-02 -6.68846011e-01 -7.42839634e-01 2.90907845e-02 -6.71437263e-01 -7.40501404e-01 2.90907864e-02 -6.74045026e-01 -7.38123417e-01 2.90907845e-02 -6.76679373e-01 -7.35718727e-01 2.90907901e-02 -6.79260433e-01 -7.33322978e-01 2.90907957e-02 -6.81791782e-01 -7.30978012e-01 2.90907864e-02 -6.84404969e-01 -7.28527009e-01 2.90907808e-02 -6.86888218e-01 -7.26179063e-01 2.90907752e-02 -6.89400196e-01 -7.23807335e-01 2.90907864e-02 -6.91955447e-01 -7.21352756e-01 2.90907789e-02 -6.94398880e-01 -7.19018400e-01 2.90907826e-02 -6.96902156e-01 -7.16590226e-01 2.90907845e-02 -6.99388206e-01 -7.14159787e-01 2.90907826e-02 -7.01876938e-01 -7.11717010e-01 2.90907845e-02 -7.04370022e-01 -7.09253013e-01 2.90907845e-02 -7.06851423e-01 -7.06762493e-01 2.90907864e-02 -7.09343374e-01 -7.04276502e-01 2.90907826e-02 -7.11763263e-01 -7.01829910e-01 2.90907826e-02 -7.14207232e-01 -6.99341834e-01 2.90907845e-02 -7.16640115e-01 -6.96849108e-01 2.90907826e-02 -7.19065726e-01 -6.94348693e-01 2.90907845e-02 -7.21554101e-01 -6.91751838e-01 2.90907882e-02 -7.23965168e-01 -6.89227879e-01 2.90907752e-02 -7.26353765e-01 -6.86715007e-01 2.90907882e-02 -7.28757560e-01 -6.84153974e-01 2.90907752e-02 -7.31067061e-01 -6.81689501e-01 2.90907826e-02 -7.33450770e-01 -6.79128289e-01 2.90907845e-02 -7.35821962e-01 -6.76560521e-01 2.90907826e-02 -7.38172889e-01 -6.73990667e-01 2.90907808e-02 -7.40560949e-01 -6.71369791e-01 2.90907845e-02 -7.42897809e-01 -6.68777525e-01 2.90907789e-02 -7.45192051e-01 -6.66220844e-01 2.90907808e-02 -7.47505605e-01 -6.63625896e-01 2.90907808e-02 -7.49871910e-01 -6.60953581e-01 2.90907845e-02 -7.52192497e-01 -6.58304334e-01 2.90907770e-02 -7.54437745e-01 -6.55734301e-01 2.90907826e-02 -7.56759524e-01 -6.53054655e-01 2.90907864e-02 -7.59036660e-01 -6.50402009e-01 2.90907770e-02 -7.61234820e-01 -6.47830546e-01 2.90907826e-02 -7.63492167e-01 -6.45172954e-01 2.90907845e-02 -7.65752017e-01 -6.42485082e-01 2.90907826e-02 -7.68048227e-01 -6.39745772e-01 2.90907882e-02 -7.70261049e-01 -6.37066782e-01 2.90907752e-02 -7.72445798e-01 -6.34429097e-01 2.90907882e-02 -7.74662554e-01 -6.31710172e-01 2.90907808e-02 -7.76839197e-01 -6.29036903e-01 2.90907845e-02 -7.79104292e-01 -6.26233160e-01 2.90907882e-02 -7.81289220e-01 -6.23494089e-01 2.90907752e-02 -7.83452094e-01 -6.20782673e-01 2.90907901e-02 -7.85613120e-01 -6.18039489e-01 2.90907770e-02 -7.87696779e-01 -6.15385771e-01 2.90907845e-02 -7.89850533e-01 -6.12621009e-01 2.90907845e-02 -7.91972995e-01 -6.09870374e-01 2.90907826e-02 -7.94156432e-01 -6.07030332e-01 2.90907882e-02 -7.96277463e-01 -6.04237676e-01 2.90907789e-02 -7.98327267e-01 -6.01533532e-01 2.90907845e-02 -8.00424695e-01 -5.98737478e-01 2.90907864e-02 -8.02510142e-01 -5.95938385e-01 2.90907845e-02 -8.04637015e-01 -5.93067288e-01 2.90907901e-02 -8.06708515e-01 -5.90238392e-01 2.90907808e-02 -8.08726013e-01 -5.87476909e-01 2.90907845e-02 -8.10806036e-01 -5.84604442e-01 2.90907901e-02 -8.12845051e-01 -5.81762075e-01 2.90907808e-02 -8.14807832e-01 -5.79011798e-01 2.90907864e-02 -8.16827834e-01 -5.76160014e-01 2.90907845e-02 -8.18831146e-01 -5.73310375e-01 2.90907882e-02 -8.20885777e-01 -5.70364118e-01 2.90907901e-02 -8.22868586e-01 -5.67496777e-01 2.90907808e-02 -8.24789822e-01 -5.64703465e-01 2.90907864e-02 -8.26747954e-01 -5.61829805e-01 2.90907845e-02 -8.28719318e-01 -5.58920562e-01 2.90907864e-02 -8.30695033e-01 -5.55983007e-01 2.90907901e-02 -8.32631111e-01 -5.53069890e-01 2.90907808e-02 -8.34568679e-01 -5.50150275e-01 2.90907901e-02 -8.36458087e-01 -5.47260165e-01 2.90907770e-02 -8.38316619e-01 -5.44418871e-01 2.90907845e-02 -8.40219319e-01 -5.41474283e-01 2.90907845e-02 -8.42098355e-01 -5.38547814e-01 2.90907845e-02 -8.44035506e-01 -5.35513461e-01 2.90907901e-02 -8.45893681e-01 -5.32562613e-01 2.90907770e-02 -8.47689748e-01 -5.29703319e-01 2.90907845e-02 -8.49522352e-01 -5.26762962e-01 2.90907826e-02 -8.51363778e-01 -5.23778200e-01 2.90907826e-02 -8.53191495e-01 -5.20802498e-01 2.90907864e-02 -8.55002582e-01 -5.17816246e-01 2.90907826e-02 -8.56819928e-01 -5.14806390e-01 2.90907864e-02 -8.58615220e-01 -5.11806250e-01 2.90907845e-02 -8.60387564e-01 -5.08817911e-01 2.90907826e-02 -8.62214744e-01 -5.05725145e-01 2.90907901e-02 -8.63973081e-01 -5.02700269e-01 2.90907770e-02 -8.65668654e-01 -4.99785930e-01 2.90907845e-02 -8.67403984e-01 -4.96763110e-01 2.90907845e-02 -8.69125962e-01 -4.93744910e-01 2.90907845e-02 -8.70866001e-01 -4.90677267e-01 2.90907864e-02 -8.72565866e-01 -4.87639278e-01 2.90907845e-02 -8.74260604e-01 -4.84590679e-01 2.90907845e-02 -8.76006961e-01 -4.81443107e-01 2.90907901e-02 -8.77683163e-01 -4.78369564e-01 2.90907789e-02 -8.79297853e-01 -4.75395203e-01 2.90907845e-02 -8.80960643e-01 -4.72309709e-01 2.90907845e-02 -8.82648647e-01 -4.69150692e-01 2.90907882e-02 -8.84278178e-01 -4.66060907e-01 2.90907770e-02 -8.85859787e-01 -4.63051796e-01 2.90907826e-02 -8.87464702e-01 -4.59966689e-01 2.90907826e-02 -8.89057100e-01 -4.56885040e-01 2.90907845e-02 -8.90658796e-01 -4.53754783e-01 2.90907845e-02 -8.92240584e-01 -4.50635761e-01 2.90907845e-02 -8.93801391e-01 -4.47529584e-01 2.90907826e-02 -8.95358801e-01 -4.44405854e-01 2.90907826e-02 -8.96908283e-01 -4.41273659e-01 2.90907845e-02 -8.98440242e-01 -4.38147426e-01 2.90907845e-02 -9.00009274e-01 -4.34922010e-01 2.90907901e-02 -9.01561856e-01 -4.31682080e-01 2.90907845e-02 -9.03025389e-01 -4.28610533e-01 2.90907789e-02 -9.04476345e-01 -4.25541908e-01 2.90907845e-02 -9.05948400e-01 -4.22402829e-01 2.90907845e-02 -9.07463729e-01 -4.19145316e-01 2.90908068e-02 -9.08915639e-01 -4.15968269e-01 2.90907789e-02 -9.10321236e-01 -4.12893623e-01 2.90907845e-02 -9.11754549e-01 -4.09721404e-01 2.90907845e-02 -9.13195491e-01 -4.06498879e-01 2.90907864e-02 -9.14605618e-01 -4.03315723e-01 2.90907845e-02 -9.16014314e-01 -4.00108904e-01 2.90907864e-02 -9.17437553e-01 -3.96835476e-01 2.90907882e-02 -9.18801546e-01 -3.93646985e-01 2.90907789e-02 -9.20130849e-01 -3.90540808e-01 2.90907845e-02 -9.21497643e-01 -3.87310058e-01 2.90907845e-02 -9.22842860e-01 -3.84092987e-01 2.90907845e-02 -9.24210787e-01 -3.80795628e-01 2.90907901e-02 -9.25532401e-01 -3.77559006e-01 2.90907789e-02 -9.26811934e-01 -3.74404460e-01 2.90907808e-02 -9.28146660e-01 -3.71096760e-01 2.90907882e-02 -9.29439366e-01 -3.67839485e-01 2.90907789e-02 -9.30679977e-01 -3.64698440e-01 2.90907845e-02 -9.31943715e-01 -3.61437887e-01 2.90907845e-02 -9.33213294e-01 -3.58171582e-01 2.90907845e-02 -9.34483290e-01 -3.54831576e-01 2.90907882e-02 -9.35708165e-01 -3.51556122e-01 2.90907770e-02 -9.36897755e-01 -3.48383427e-01 2.90907845e-02 -9.38146293e-01 -3.45027179e-01 2.90907901e-02 -9.39346254e-01 -3.41749340e-01 2.90907789e-02 -9.40530896e-01 -3.38486612e-01 2.90907901e-02 -9.41703618e-01 -3.35195541e-01 2.90907770e-02 -9.42866087e-01 -3.31924409e-01 2.90907901e-02 -9.44020271e-01 -3.28607112e-01 2.90907789e-02 -9.45129037e-01 -3.25421005e-01 2.90907845e-02 -9.46261823e-01 -3.22106332e-01 2.90907826e-02 -9.47377920e-01 -3.18812549e-01 2.90907845e-02 -9.48525071e-01 -3.15391988e-01 2.90907901e-02 -9.49617982e-01 -3.12065929e-01 2.90907789e-02 -9.50668335e-01 -3.08862865e-01 2.90907845e-02 -9.51745391e-01 -3.05530697e-01 2.90907864e-02 -9.52799261e-01 -3.02224517e-01 2.90907864e-02 -9.53883171e-01 -2.98795402e-01 2.90907901e-02 -9.54922616e-01 -2.95437276e-01 2.90907789e-02 -9.55921471e-01 -2.92201400e-01 2.90907845e-02 -9.56927538e-01 -2.88879573e-01 2.90907845e-02 -9.57932115e-01 -2.85529286e-01 2.90907826e-02 -9.58951592e-01 -2.82104999e-01 2.90907882e-02 -9.59928989e-01 -2.78738469e-01 2.90907789e-02 -9.60870028e-01 -2.75487721e-01 2.90907845e-02 -9.61822867e-01 -2.72142529e-01 2.90907826e-02 -9.62776184e-01 -2.68756002e-01 2.90907845e-02 -9.63698983e-01 -2.65421361e-01 2.90907845e-02 -9.64623690e-01 -2.62052327e-01 2.90907826e-02 -9.65532541e-01 -2.58674085e-01 2.90907845e-02 -9.66454446e-01 -2.55215794e-01 2.90907901e-02 -9.67341185e-01 -2.51819789e-01 2.90907789e-02 -9.68187451e-01 -2.48548582e-01 2.90907826e-02 -9.69044566e-01 -2.45183110e-01 2.90907845e-02 -9.69917417e-01 -2.41718054e-01 2.90907864e-02 -9.70753908e-01 -2.38323390e-01 2.90907789e-02 -9.71564770e-01 -2.35011131e-01 2.90907826e-02 -9.72377002e-01 -2.31627479e-01 2.90907826e-02 -9.73184228e-01 -2.28209689e-01 2.90907826e-02 -9.73986983e-01 -2.24759042e-01 2.90907864e-02 -9.74766195e-01 -2.21339762e-01 2.90907789e-02 -9.75511730e-01 -2.18042344e-01 2.90907826e-02 -9.76284325e-01 -2.14560777e-01 2.90907882e-02 -9.77025270e-01 -2.11142421e-01 2.90907789e-02 -9.77736712e-01 -2.07835317e-01 2.90907826e-02 -9.78464723e-01 -2.04382151e-01 2.90907826e-02 -9.79189992e-01 -2.00896740e-01 2.90907882e-02 -9.79874849e-01 -1.97492003e-01 2.90907770e-02 -9.80543673e-01 -1.94156140e-01 2.90907826e-02 -9.81212616e-01 -1.90743163e-01 2.90907808e-02 -9.81897473e-01 -1.87205523e-01 2.90907882e-02 -9.82542157e-01 -1.83758214e-01 2.90907770e-02 -9.83157218e-01 -1.80449590e-01 2.90907826e-02 -9.83789384e-01 -1.77001953e-01 2.90907826e-02 -9.84398723e-01 -1.73582271e-01 2.90907826e-02 -9.85017478e-01 -1.70024350e-01 2.90907882e-02 -9.85599995e-01 -1.66583866e-01 2.90907752e-02 -9.86160219e-01 -1.63240835e-01 2.90907826e-02 -9.86743867e-01 -1.59700558e-01 2.90907864e-02 -9.87291276e-01 -1.56249240e-01 2.90907770e-02 -9.87817764e-01 -1.52910590e-01 2.90907826e-02 -9.88341689e-01 -1.49476603e-01 2.90907826e-02 -9.88875747e-01 -1.45931244e-01 2.90907901e-02 -9.89376366e-01 -1.42450601e-01 2.90907770e-02 -9.89859343e-01 -1.39083222e-01 2.90907826e-02 -9.90351677e-01 -1.35554940e-01 2.90907882e-02 -9.90813076e-01 -1.32080138e-01 2.90907752e-02 -9.91256237e-01 -1.28729686e-01 2.90907808e-02 -9.91699278e-01 -1.25277951e-01 2.90907789e-02 -9.92125332e-01 -1.21844158e-01 2.90907770e-02 -9.92554247e-01 -1.18299052e-01 2.90907808e-02 -9.92956877e-01 -1.14796124e-01 2.90907715e-02 -9.93343651e-01 -1.11417294e-01 2.90907659e-02 -9.93733287e-01 -1.07882500e-01 2.90907659e-02 -9.94111776e-01 -1.04352452e-01 2.90907435e-02 -9.94462729e-01 -1.00950710e-01 2.90907193e-02 -9.94803369e-01 -9.75386202e-02 2.90906318e-02 -9.95116353e-01 -9.43349153e-02 2.90905666e-02 -9.95452285e-01 -9.07060429e-02 2.90905330e-02 -9.95709598e-01 -8.78389850e-02 2.90905368e-02 -9.96085703e-01 -8.34689364e-02 2.90905368e-02 0. 0. 0. -9.96636629e-01 -7.65998140e-02 2.90905349e-02 -9.96808767e-01 -7.43381679e-02 2.90905368e-02 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. 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. 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. 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. 0. 0. -9.97177064e-01 6.30865097e-02 4.07072827e-02 -9.96955872e-01 6.64923191e-02 4.07072864e-02 -9.96717453e-01 6.99769035e-02 4.07072827e-02 -9.96495605e-01 7.30615258e-02 4.07072827e-02 -9.96195138e-01 7.70527795e-02 4.07072864e-02 -9.95971560e-01 7.98933133e-02 4.07072864e-02 -9.95709896e-01 8.30869898e-02 4.07072864e-02 -9.95277226e-01 8.81256387e-02 4.07072827e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.93932009e-01 1.02186859e-01 4.07072864e-02 -9.93605793e-01 1.05309024e-01 4.07072827e-02 -9.93212163e-01 1.08943880e-01 4.07072790e-02 -9.92910981e-01 1.11697562e-01 4.07072864e-02 -9.92523849e-01 1.15057684e-01 4.07071412e-02 -9.92118776e-01 1.18454881e-01 4.07070704e-02 -9.91702855e-01 1.21858716e-01 4.07070369e-02 -9.91261423e-01 1.25385925e-01 4.07069772e-02 -9.90807891e-01 1.28911406e-01 4.07069623e-02 -9.90365028e-01 1.32272035e-01 4.07069586e-02 -9.89898622e-01 1.35716245e-01 4.07069176e-02 -9.89407480e-01 1.39248282e-01 4.07069176e-02 -9.88929391e-01 1.42605141e-01 4.07069214e-02 -9.88420963e-01 1.46071792e-01 4.07069176e-02 -9.87909555e-01 1.49504080e-01 4.07069176e-02 -9.87394691e-01 1.52866468e-01 4.07069176e-02 -9.86841321e-01 1.56385779e-01 4.07069176e-02 -9.86273587e-01 1.59937099e-01 4.07069176e-02 -9.85705733e-01 1.63404420e-01 4.07069176e-02 -9.85125959e-01 1.66866466e-01 4.07069176e-02 -9.84544575e-01 1.70251757e-01 4.07069176e-02 -9.83944833e-01 1.73712716e-01 4.07069176e-02 -9.83327270e-01 1.77171409e-01 4.07069176e-02 -9.82696056e-01 1.80608958e-01 4.07069176e-02 -9.82082486e-01 1.83937579e-01 4.07069437e-02 -9.81455505e-01 1.87242165e-01 4.07069176e-02 -9.80776966e-01 1.90753177e-01 4.07069176e-02 -9.80086446e-01 1.94280788e-01 4.07069176e-02 -9.79403555e-01 1.97700039e-01 4.07069176e-02 -9.78707433e-01 2.01118395e-01 4.07069176e-02 -9.77995813e-01 2.04541653e-01 4.07069176e-02 -9.77293372e-01 2.07885444e-01 4.07069176e-02 -9.76568699e-01 2.11257890e-01 4.07069176e-02 -9.75797474e-01 2.14783937e-01 4.07069176e-02 -9.75064099e-01 2.18101248e-01 4.07069176e-02 -9.74295378e-01 2.21497089e-01 4.07069176e-02 -9.73491490e-01 2.25015730e-01 4.07069176e-02 -9.72700417e-01 2.28413329e-01 4.07069176e-02 -9.71898854e-01 2.31802851e-01 4.07069176e-02 -9.71109927e-01 2.35091373e-01 4.07069214e-02 -9.70308006e-01 2.38366336e-01 4.07069176e-02 -9.69438136e-01 2.41869196e-01 4.07069176e-02 -9.68561769e-01 2.45359525e-01 4.07069176e-02 -9.67698157e-01 2.48750031e-01 4.07069176e-02 -9.66850460e-01 2.52027333e-01 4.07069176e-02 -9.65976179e-01 2.55358785e-01 4.07069176e-02 -9.65069056e-01 2.58767933e-01 4.07069176e-02 -9.64155555e-01 2.62145013e-01 4.07069176e-02 -9.63212252e-01 2.65585959e-01 4.07069176e-02 -9.62303519e-01 2.68875331e-01 4.07069214e-02 -9.61387932e-01 2.72121370e-01 4.07069176e-02 -9.60404515e-01 2.75566638e-01 4.07069176e-02 -9.59405005e-01 2.79030412e-01 4.07069176e-02 -9.58434701e-01 2.82344908e-01 4.07069176e-02 -9.57459629e-01 2.85638481e-01 4.07069176e-02 -9.56449509e-01 2.88992018e-01 4.07069176e-02 -9.55446422e-01 2.92300612e-01 4.07069176e-02 -9.54424322e-01 2.95617044e-01 4.07069176e-02 -9.53359663e-01 2.99034417e-01 4.07069176e-02 -9.52332556e-01 3.02289695e-01 4.07069176e-02 -9.51275408e-01 3.05595905e-01 4.07069176e-02 -9.50181425e-01 3.08980942e-01 4.07069176e-02 -9.49093997e-01 3.12305868e-01 4.07069176e-02 -9.47996438e-01 3.15622479e-01 4.07069176e-02 -9.46886420e-01 3.18945467e-01 4.07069176e-02 -9.45798218e-01 3.22150826e-01 4.07069214e-02 -9.44698155e-01 3.25364828e-01 4.07069176e-02 -9.43529129e-01 3.28730732e-01 4.07069176e-02 -9.42343354e-01 3.32119972e-01 4.07069176e-02 -9.41211402e-01 3.35323513e-01 4.07069176e-02 -9.40031767e-01 3.38605970e-01 4.07069176e-02 -9.38812673e-01 3.41976583e-01 4.07069176e-02 -9.37610149e-01 3.45243067e-01 4.07069176e-02 -9.36399221e-01 3.48502725e-01 4.07069176e-02 -9.35202539e-01 3.51704240e-01 4.07069176e-02 -9.34013247e-01 3.54863375e-01 4.07069176e-02 -9.32746947e-01 3.58199418e-01 4.07069176e-02 -9.31445241e-01 3.61551404e-01 4.07069176e-02 -9.30174649e-01 3.64816397e-01 4.07069176e-02 -9.28899765e-01 3.68050873e-01 4.07069176e-02 -9.27607119e-01 3.71294647e-01 4.07069176e-02 -9.26308155e-01 3.74521345e-01 4.07069176e-02 -9.25002337e-01 3.77739161e-01 4.07069176e-02 -9.23670590e-01 3.80978853e-01 4.07069176e-02 -9.22368467e-01 3.84124726e-01 4.07069214e-02 -9.21064138e-01 3.87241960e-01 4.07069176e-02 -9.19668078e-01 3.90541285e-01 4.07069176e-02 -9.18263137e-01 3.93833667e-01 4.07069176e-02 -9.16907191e-01 3.96983117e-01 4.07069214e-02 -9.15531933e-01 4.00147855e-01 4.07069176e-02 -9.14134264e-01 4.03328270e-01 4.07069176e-02 -9.12725747e-01 4.06504661e-01 4.07069176e-02 -9.11275387e-01 4.09747392e-01 4.07069176e-02 -9.09818411e-01 4.12971646e-01 4.07069176e-02 -9.08405423e-01 4.16068375e-01 4.07069214e-02 -9.06964064e-01 4.19200659e-01 4.07069176e-02 -9.05452728e-01 4.22456503e-01 4.07069176e-02 -9.03980017e-01 4.25598502e-01 4.07069176e-02 -9.02497530e-01 4.28735137e-01 4.07069176e-02 -9.00993347e-01 4.31884259e-01 4.07069176e-02 -8.99523497e-01 4.34947819e-01 4.07069176e-02 -8.97978187e-01 4.38123792e-01 4.07069176e-02 -8.96398008e-01 4.41345036e-01 4.07069176e-02 -8.94866049e-01 4.44444865e-01 4.07069176e-02 -8.93306673e-01 4.47567940e-01 4.07069176e-02 -8.91744018e-01 4.50676024e-01 4.07069176e-02 -8.90199065e-01 4.53723401e-01 4.07069214e-02 -8.88652027e-01 4.56743121e-01 4.07069176e-02 -8.87020111e-01 4.59902048e-01 4.07069176e-02 -8.85371089e-01 4.63073343e-01 4.07069176e-02 -8.83784533e-01 4.66095150e-01 4.07069214e-02 -8.82160425e-01 4.69154865e-01 4.07069176e-02 -8.80480349e-01 4.72303331e-01 4.07069176e-02 -8.78826737e-01 4.75371987e-01 4.07069176e-02 -8.77155840e-01 4.78452891e-01 4.07069176e-02 -8.75471354e-01 4.81525987e-01 4.07069176e-02 -8.73836875e-01 4.84481543e-01 4.07069214e-02 -8.72148931e-01 4.87514377e-01 4.07069176e-02 -8.70398760e-01 4.90636259e-01 4.07069176e-02 -8.68672132e-01 4.93682355e-01 4.07069176e-02 -8.66948724e-01 4.96706367e-01 4.07069176e-02 -8.65217805e-01 4.99716848e-01 4.07069176e-02 -8.63479316e-01 5.02712727e-01 4.07069176e-02 -8.61716390e-01 5.05728424e-01 4.07069176e-02 -8.59942615e-01 5.08737326e-01 4.07069176e-02 -8.58198941e-01 5.11675715e-01 4.07069214e-02 -8.56440604e-01 5.14613211e-01 4.07069176e-02 -8.54586065e-01 5.17682254e-01 4.07069176e-02 -8.52756858e-01 5.20696938e-01 4.07069176e-02 -8.50938022e-01 5.23658216e-01 4.07069176e-02 -8.49097133e-01 5.26643276e-01 4.07069176e-02 -8.47259521e-01 5.29590845e-01 4.07069176e-02 -8.45453024e-01 5.32473087e-01 4.07069176e-02 -8.43580425e-01 5.35431206e-01 4.07069176e-02 -8.41656983e-01 5.38450122e-01 4.07069176e-02 -8.39819729e-01 5.41311324e-01 4.07069176e-02 -8.37934613e-01 5.44221878e-01 4.07069176e-02 -8.36003423e-01 5.47185957e-01 4.07069176e-02 -8.34080458e-01 5.50114155e-01 4.07069176e-02 -8.32132816e-01 5.53053260e-01 4.07069176e-02 -8.30207705e-01 5.55941582e-01 4.07069176e-02 -8.28315675e-01 5.58760166e-01 4.07069214e-02 -8.26350272e-01 5.61657369e-01 4.07069176e-02 -8.24321091e-01 5.64633191e-01 4.07069176e-02 -8.22351277e-01 5.67498505e-01 4.07069176e-02 -8.20419252e-01 5.70288956e-01 4.07069214e-02 -8.18436027e-01 5.73126972e-01 4.07069176e-02 -8.16380143e-01 5.76057553e-01 4.07069176e-02 -8.14356625e-01 5.78909099e-01 4.07069176e-02 -8.12313437e-01 5.81777751e-01 4.07069176e-02 -8.10344756e-01 5.84512353e-01 4.07069214e-02 -8.08338165e-01 5.87286949e-01 4.07069176e-02 -8.06218088e-01 5.90189517e-01 4.07069176e-02 -8.04105163e-01 5.93068063e-01 4.07069176e-02 -8.02025378e-01 5.95876455e-01 4.07069176e-02 -7.99937487e-01 5.98676383e-01 4.07069176e-02 -7.97849417e-01 6.01458192e-01 4.07069176e-02 -7.95752168e-01 6.04232728e-01 4.07069176e-02 -7.93638766e-01 6.07003450e-01 4.07069176e-02 -7.91534424e-01 6.09744966e-01 4.07069176e-02 -7.89420605e-01 6.12480938e-01 4.07069474e-02 -7.87295222e-01 6.15204811e-01 4.07069176e-02 -7.85067797e-01 6.18050694e-01 4.07069176e-02 -7.82908559e-01 6.20780647e-01 4.07069176e-02 -7.80744374e-01 6.23504817e-01 4.07069176e-02 -7.78544605e-01 6.26247644e-01 4.07069176e-02 -7.76360214e-01 6.28952742e-01 4.07069176e-02 -7.74251461e-01 6.31545067e-01 4.07069474e-02 -7.72024035e-01 6.34267926e-01 4.07069176e-02 -7.69762933e-01 6.37011707e-01 4.07069176e-02 -7.67583251e-01 6.39634371e-01 4.07069437e-02 -7.65350044e-01 6.42302334e-01 4.07069176e-02 -7.63054967e-01 6.45030677e-01 4.07069176e-02 -7.60793746e-01 6.47692919e-01 4.07069176e-02 -7.58494914e-01 6.50384963e-01 4.07069176e-02 -7.56246805e-01 6.53001189e-01 4.07069176e-02 -7.54035175e-01 6.55553102e-01 4.07069176e-02 -7.51698375e-01 6.58226788e-01 4.07069176e-02 -7.49317884e-01 6.60937309e-01 4.07069176e-02 -7.46996284e-01 6.63560688e-01 4.07069176e-02 -7.44684279e-01 6.66155636e-01 4.07069176e-02 -7.42360234e-01 6.68741822e-01 4.07069176e-02 -7.40030348e-01 6.71324193e-01 4.07069176e-02 -7.37674594e-01 6.73906088e-01 4.07069176e-02 -7.35322773e-01 6.76476061e-01 4.07069176e-02 -7.33032167e-01 6.78957343e-01 4.07069214e-02 -7.30650306e-01 6.81515872e-01 4.07069176e-02 -7.28173196e-01 6.84163034e-01 4.07069176e-02 -7.25783944e-01 6.86696827e-01 4.07069176e-02 -7.23386109e-01 6.89224482e-01 4.07069176e-02 -7.20982730e-01 6.91732168e-01 4.07069176e-02 -7.18576789e-01 6.94243670e-01 4.07069176e-02 -7.16209114e-01 6.96685016e-01 4.07069176e-02 -7.13761330e-01 6.99188352e-01 4.07069176e-02 -7.11266518e-01 7.01728463e-01 4.07069176e-02 -7.08847344e-01 7.04175472e-01 4.07069325e-02 -7.06391752e-01 7.06618786e-01 4.07069176e-02 -7.03876436e-01 7.09142923e-01 4.07069176e-02 -7.01392233e-01 7.11599827e-01 4.07069176e-02 -6.98901534e-01 7.14042723e-01 4.07069176e-02 -6.96431875e-01 7.16454923e-01 4.07069176e-02 -6.93987191e-01 7.18823493e-01 4.07069176e-02 -6.91460252e-01 7.21242368e-01 4.07069176e-02 -6.88869834e-01 7.23726094e-01 4.07069176e-02 -6.86337471e-01 7.26122022e-01 4.07069176e-02 -6.83791459e-01 7.28520989e-01 4.07069176e-02 -6.81251109e-01 7.30894744e-01 4.07069176e-02 -6.78699970e-01 7.33268261e-01 4.07069176e-02 -6.76123500e-01 7.35645890e-01 4.07069176e-02 -6.73564613e-01 7.37987280e-01 4.07069176e-02 -6.70963049e-01 7.40356028e-01 4.07069176e-02 -6.68463647e-01 7.42613435e-01 4.07069214e-02 -6.65870368e-01 7.44937301e-01 4.07069176e-02 -6.63198829e-01 7.47318864e-01 4.07069176e-02 -6.60578668e-01 7.49634683e-01 4.07069176e-02 -6.57950044e-01 7.51941323e-01 4.07069176e-02 -6.55329406e-01 7.54227817e-01 4.07069176e-02 -6.52752161e-01 7.56460667e-01 4.07069176e-02 -6.50104582e-01 7.58734345e-01 4.07069176e-02 -6.47387385e-01 7.61055470e-01 4.07069176e-02 -6.44779682e-01 7.63268232e-01 4.07069176e-02 -6.42130852e-01 7.65494287e-01 4.07069176e-02 -6.39397979e-01 7.67780542e-01 4.07069176e-02 -6.36718631e-01 7.70003021e-01 4.07069176e-02 -6.34011507e-01 7.72235751e-01 4.07069176e-02 -6.31387651e-01 7.74380684e-01 4.07069251e-02 -6.28684998e-01 7.76576936e-01 4.07069176e-02 -6.25880122e-01 7.78838277e-01 4.07069176e-02 -6.23233736e-01 7.80958414e-01 4.07069176e-02 -6.20490730e-01 7.83138454e-01 4.07069176e-02 -6.17762744e-01 7.85294592e-01 4.07069214e-02 -6.15043044e-01 7.87424088e-01 4.07069176e-02 -6.12197220e-01 7.89640367e-01 4.07069176e-02 -6.09501779e-01 7.91724265e-01 4.07069474e-02 -6.06779039e-01 7.93809772e-01 4.07069176e-02 -6.03962779e-01 7.95955837e-01 4.07069214e-02 -6.01181507e-01 7.98059225e-01 4.07069176e-02 -5.98388731e-01 8.00154924e-01 4.07069214e-02 -5.95619738e-01 8.02215457e-01 4.07069176e-02 -5.92702031e-01 8.04373920e-01 4.07069176e-02 -5.89897811e-01 8.06433737e-01 4.07069176e-02 -5.87145865e-01 8.08442473e-01 4.07069214e-02 -5.84395885e-01 8.10428441e-01 4.07069176e-02 -5.81463158e-01 8.12537670e-01 4.07069176e-02 -5.78654468e-01 8.14542174e-01 4.07069214e-02 -5.75838029e-01 8.16534698e-01 4.07069176e-02 -5.72979391e-01 8.18542480e-01 4.07069214e-02 -5.70115089e-01 8.20536792e-01 4.07069176e-02 -5.67168117e-01 8.22579086e-01 4.07069176e-02 -5.64278662e-01 8.24564695e-01 4.07069176e-02 -5.61481833e-01 8.26469660e-01 4.07069176e-02 -5.58676481e-01 8.28369856e-01 4.07069176e-02 -5.55705130e-01 8.30364048e-01 4.07069176e-02 -5.52781224e-01 8.32313418e-01 4.07069176e-02 -5.49897015e-01 8.34223151e-01 4.07069176e-02 -5.46986639e-01 8.36134970e-01 4.07069176e-02 -5.44089675e-01 8.38021398e-01 4.07069176e-02 -5.41075349e-01 8.39971364e-01 4.07069176e-02 -5.38134575e-01 8.41858029e-01 4.07069176e-02 -5.35164475e-01 8.43748927e-01 4.07069176e-02 -5.32213092e-01 8.45615864e-01 4.07069176e-02 -5.29256582e-01 8.47468913e-01 4.07069176e-02 -5.26389360e-01 8.49254727e-01 4.07069214e-02 -5.23429275e-01 8.51078570e-01 4.07069176e-02 -5.20345092e-01 8.52970481e-01 4.07069176e-02 -5.17338157e-01 8.54795456e-01 4.07069176e-02 -5.14446616e-01 8.56540382e-01 4.07069214e-02 -5.11477768e-01 8.58314574e-01 4.07069176e-02 -5.08364260e-01 8.60163748e-01 4.07069176e-02 -5.05440414e-01 8.61886144e-01 4.07069214e-02 -5.02460837e-01 8.63625228e-01 4.07069176e-02 -4.99420017e-01 8.65390062e-01 4.07069214e-02 -4.96414095e-01 8.67113352e-01 4.07069176e-02 -4.93296862e-01 8.68892848e-01 4.07069176e-02 -4.90286380e-01 8.70597243e-01 4.07069176e-02 -4.87345159e-01 8.72243464e-01 4.07069176e-02 -4.84259188e-01 8.73959243e-01 4.07069176e-02 -4.81130600e-01 8.75689089e-01 4.07069176e-02 -4.78170425e-01 8.77309978e-01 4.07069214e-02 -4.75090057e-01 8.78978133e-01 4.07069176e-02 -4.71994698e-01 8.80646110e-01 4.07069176e-02 -4.68947172e-01 8.82272482e-01 4.07069176e-02 -4.65858310e-01 8.83909345e-01 4.07069214e-02 -4.62790430e-01 8.85516644e-01 4.07069176e-02 -4.59632009e-01 8.87161016e-01 4.07069176e-02 -4.56516743e-01 8.88768733e-01 4.07069176e-02 -4.53404069e-01 8.90359819e-01 4.07069176e-02 -4.50352073e-01 8.91909122e-01 4.07069176e-02 -4.47250336e-01 8.93466532e-01 4.07069176e-02 -4.44096267e-01 8.95039439e-01 4.07069176e-02 -4.40930694e-01 8.96602094e-01 4.07069176e-02 -4.37855393e-01 8.98109853e-01 4.07069214e-02 -4.34720814e-01 8.99630785e-01 4.07069176e-02 -4.31511462e-01 9.01172936e-01 4.07069176e-02 -4.28365290e-01 9.02672231e-01 4.07069176e-02 -4.25209463e-01 9.04163778e-01 4.07069176e-02 -4.22131926e-01 9.05605555e-01 4.07069176e-02 -4.18957204e-01 9.07077551e-01 4.07069176e-02 -4.15708840e-01 9.08569455e-01 4.07069176e-02 -4.12544012e-01 9.10012543e-01 4.07069176e-02 -4.09470052e-01 9.11401868e-01 4.07069214e-02 -4.06312943e-01 9.12811399e-01 4.07069176e-02 -4.03025866e-01 9.14268494e-01 4.07069176e-02 -3.99899602e-01 9.15642858e-01 4.07069176e-02 -3.96693617e-01 9.17032659e-01 4.07069176e-02 -3.93485337e-01 9.18410957e-01 4.07069176e-02 -3.90365928e-01 9.19743538e-01 4.07069176e-02 -3.87143940e-01 9.21106219e-01 4.07069176e-02 -3.83870989e-01 9.22473073e-01 4.07069176e-02 -3.80553871e-01 9.23847020e-01 4.07069176e-02 -3.77348721e-01 9.25161004e-01 4.07069176e-02 -3.74110341e-01 9.26475942e-01 4.07069176e-02 -3.70899230e-01 9.27765250e-01 4.07069176e-02 -3.67674023e-01 9.29048896e-01 4.07069176e-02 -3.64393651e-01 9.30340648e-01 4.07069176e-02 -3.61117780e-01 9.31611776e-01 4.07069176e-02 -3.57960612e-01 9.32840407e-01 4.07069176e-02 -3.54717344e-01 9.34068859e-01 4.07069176e-02 -3.51368338e-01 9.35328662e-01 4.07069176e-02 -3.48092288e-01 9.36552107e-01 4.07069176e-02 -3.44911695e-01 9.37731862e-01 4.07069176e-02 -3.41742426e-01 9.38899219e-01 4.07069176e-02 -3.38376522e-01 9.40114021e-01 4.07069176e-02 -3.35075796e-01 9.41300094e-01 4.07069214e-02 -3.31818968e-01 9.42449749e-01 4.07069176e-02 -3.28527927e-01 9.43603396e-01 4.07069214e-02 -3.25250715e-01 9.44737077e-01 4.07069176e-02 -3.21879476e-01 9.45890546e-01 4.07069176e-02 -3.18650991e-01 9.46985066e-01 4.07069214e-02 -3.15324903e-01 9.48094428e-01 4.07069176e-02 -3.11989397e-01 9.49198127e-01 4.07069176e-02 -3.08680177e-01 9.50279117e-01 4.07069176e-02 -3.05365562e-01 9.51352417e-01 4.07069214e-02 -3.02048773e-01 9.52409327e-01 4.07069176e-02 -2.98645645e-01 9.53481138e-01 4.07069176e-02 -2.95315206e-01 9.54518020e-01 4.07069176e-02 -2.91978836e-01 9.55543280e-01 4.07069176e-02 -2.88651943e-01 9.56553221e-01 4.07069176e-02 -2.85316259e-01 9.57554281e-01 4.07069176e-02 -2.81970739e-01 9.58546519e-01 4.07069176e-02 -2.78616607e-01 9.59526002e-01 4.07069176e-02 -2.75352180e-01 9.60467458e-01 4.07069176e-02 -2.71987617e-01 9.61425543e-01 4.07069176e-02 -2.68566608e-01 9.62387025e-01 4.07069176e-02 -2.65196294e-01 9.63321030e-01 4.07069176e-02 -2.61894524e-01 9.64226782e-01 4.07069214e-02 -2.58624315e-01 9.65107322e-01 4.07069176e-02 -2.55201608e-01 9.66016531e-01 4.07069176e-02 -2.51807868e-01 9.66908455e-01 4.07069214e-02 -2.48430893e-01 9.67779458e-01 4.07069176e-02 -2.45078161e-01 9.68634725e-01 4.07069288e-02 -2.41669789e-01 9.69489038e-01 4.07069176e-02 -2.38178089e-01 9.70356166e-01 4.07069176e-02 -2.34875977e-01 9.71161723e-01 4.07069214e-02 -2.31479868e-01 9.71975088e-01 4.07069176e-02 -2.28091434e-01 9.72776055e-01 4.07069474e-02 -2.24726766e-01 9.73557234e-01 4.07069176e-02 -2.21308991e-01 9.74340975e-01 4.07069288e-02 -2.18019307e-01 9.75082636e-01 4.07069176e-02 -2.14485854e-01 9.75863934e-01 4.07069176e-02 -2.10978433e-01 9.76629436e-01 4.07069176e-02 -2.07566261e-01 9.77359951e-01 4.07069176e-02 -2.04157308e-01 9.78078663e-01 4.07069176e-02 -2.00853854e-01 9.78762686e-01 4.07069474e-02 -1.97421670e-01 9.79457617e-01 4.07069176e-02 -1.93892241e-01 9.80163991e-01 4.07069176e-02 -1.90472931e-01 9.80834544e-01 4.07069176e-02 -1.87034667e-01 9.81496334e-01 4.07069176e-02 -1.83740169e-01 9.82118249e-01 4.07069549e-02 -1.80268213e-01 9.82758582e-01 4.07069176e-02 -1.76851913e-01 9.83387172e-01 4.07069214e-02 -1.73417374e-01 9.83997703e-01 4.07069176e-02 -1.69886991e-01 9.84608054e-01 4.07069176e-02 -1.66552410e-01 9.85180318e-01 4.07069214e-02 -1.63104013e-01 9.85754311e-01 4.07069176e-02 -1.59649029e-01 9.86320674e-01 4.07069400e-02 -1.56238124e-01 9.86865819e-01 4.07069176e-02 -1.52666226e-01 9.87425387e-01 4.07069176e-02 -1.49329692e-01 9.87936020e-01 4.07069214e-02 -1.45880073e-01 9.88450050e-01 4.07069176e-02 -1.42413914e-01 9.88955796e-01 4.07069214e-02 -1.38968855e-01 9.89446580e-01 4.07069176e-02 -1.35424703e-01 9.89938915e-01 4.07069176e-02 -1.32047117e-01 9.90392745e-01 4.07069214e-02 -1.28589228e-01 9.90848422e-01 4.07069176e-02 -1.25024661e-01 9.91305411e-01 4.07069176e-02 -1.21586785e-01 9.91731882e-01 4.07069176e-02 -1.18213736e-01 9.92139339e-01 4.07069214e-02 -1.14844009e-01 9.92534399e-01 4.07069176e-02 -1.11275256e-01 9.92941141e-01 4.07069176e-02 -1.07716382e-01 9.93332922e-01 4.07069176e-02 -1.04235277e-01 9.93705094e-01 4.07069176e-02 -1.00750610e-01 9.94063675e-01 4.07069176e-02 -9.73828882e-02 9.94401574e-01 4.07069437e-02 -9.39338133e-02 9.94731843e-01 4.07069176e-02 -9.04569402e-02 9.95056510e-01 4.07069437e-02 -8.69877413e-02 9.95363951e-01 4.07069176e-02 -8.33981782e-02 9.95671451e-01 4.07069176e-02 -8.00330117e-02 9.95948792e-01 4.07069214e-02 -7.65728578e-02 9.96217608e-01 4.07069176e-02 -7.30763152e-02 9.96482909e-01 4.07069474e-02 -6.95773885e-02 9.96730387e-01 4.07069176e-02 -6.59923628e-02 9.96976614e-01 4.07069176e-02 -6.25022948e-02 9.97198641e-01 4.07069176e-02 -5.90506569e-02 9.97410715e-01 4.07069176e-02 -5.56576028e-02 9.97607648e-01 4.07069474e-02 -5.21751978e-02 9.97791290e-01 4.07069176e-02 -4.86795940e-02 9.97971952e-01 4.07069214e-02 -4.53048162e-02 9.98129487e-01 4.07069176e-02 -4.17318493e-02 9.98284340e-01 4.07069176e-02 -3.81448343e-02 9.98428643e-01 4.07069176e-02 -3.46492194e-02 9.98555720e-01 4.07069176e-02 -3.11558973e-02 9.98671591e-01 4.07069176e-02 -2.77530029e-02 9.98772264e-01 4.07069437e-02 -2.43878588e-02 9.98861432e-01 4.07069176e-02 -2.07856800e-02 9.98937130e-01 4.07069176e-02 -1.71971507e-02 9.99013782e-01 4.07069176e-02 -1.37064848e-02 9.99061406e-01 4.07069214e-02 -1.03427805e-02 9.99103546e-01 4.07069474e-02 -6.86151162e-03 9.99139369e-01 4.07069176e-02 -3.32587631e-03 9.99157369e-01 4.07069214e-02 1.23153746e-04 9.99157786e-01 4.07069176e-02 3.70853511e-03 9.99157012e-01 4.07069214e-02 7.12478813e-03 9.99136567e-01 4.07069437e-02 1.05958572e-02 9.99100566e-01 4.07069176e-02 1.40905259e-02 9.99056220e-01 4.07069437e-02 1.75613575e-02 9.99007821e-01 4.07069176e-02 2.10828856e-02 9.98935819e-01 4.07069437e-02 2.44786888e-02 9.98858392e-01 4.07069176e-02 2.80223470e-02 9.98764813e-01 4.07069176e-02 3.15860584e-02 9.98658180e-01 4.07069176e-02 3.50996703e-02 9.98542070e-01 4.07069176e-02 3.85670513e-02 9.98414397e-01 4.07069214e-02 4.19665016e-02 9.98278201e-01 4.07069214e-02 4.54657562e-02 9.98120725e-01 4.07069176e-02 4.90387119e-02 9.97954071e-01 4.07069176e-02 5.25003970e-02 9.97774541e-01 4.07069176e-02 5.59851788e-02 9.97588456e-01 4.07069176e-02 5.94039038e-02 9.97391224e-01 4.07069214e-02 6.28483295e-02 9.97175694e-01 4.07069176e-02 6.64172545e-02 9.96946573e-01 4.07069176e-02 6.99506328e-02 9.96703804e-01 4.07069176e-02 7.34306946e-02 9.96456087e-01 4.07069176e-02 7.68053532e-02 9.96200800e-01 4.07069214e-02 8.02469179e-02 9.95928347e-01 4.07069176e-02 8.37668404e-02 9.95640993e-01 4.07069474e-02 8.72056633e-02 9.95343506e-01 4.07069176e-02 9.07883272e-02 9.95024085e-01 4.07069176e-02 9.42006484e-02 9.94707704e-01 4.07069586e-02 9.76098999e-02 9.94378090e-01 4.07069176e-02 1.01122305e-01 9.94029462e-01 4.07069474e-02 1.04577601e-01 9.93668258e-01 4.07069176e-02 1.08072095e-01 9.93296742e-01 4.07069474e-02 1.11515097e-01 9.92914677e-01 4.07069176e-02 1.15094028e-01 9.92504776e-01 4.07069176e-02 1.18526943e-01 9.92100358e-01 4.07069176e-02 1.21984579e-01 9.91682649e-01 4.07069176e-02 1.25386655e-01 9.91261303e-01 4.07069214e-02 1.28767937e-01 9.90824282e-01 4.07069176e-02 1.32283732e-01 9.90361571e-01 4.07069176e-02 1.35822520e-01 9.89883244e-01 4.07069176e-02 1.39291003e-01 9.89401400e-01 4.07069176e-02 1.42754853e-01 9.88906443e-01 4.07069176e-02 1.46138087e-01 9.88413155e-01 4.07069437e-02 1.49555936e-01 9.87899721e-01 4.07069176e-02 1.52999938e-01 9.87375319e-01 4.07069214e-02 1.56456858e-01 9.86830473e-01 4.07069176e-02 1.60007164e-01 9.86262321e-01 4.07069176e-02 1.63349137e-01 9.85715628e-01 4.07069214e-02 1.66759059e-01 9.85143244e-01 4.07069176e-02 1.70223564e-01 9.84551013e-01 4.07069400e-02 1.73551917e-01 9.83973086e-01 4.07069214e-02 1.77073061e-01 9.83344018e-01 4.07069176e-02 1.80620655e-01 9.82695580e-01 4.07069176e-02 1.84048042e-01 9.82059896e-01 4.07069176e-02 1.87361404e-01 9.81433392e-01 4.07069176e-02 1.90799847e-01 9.80769873e-01 4.07069176e-02 1.94247648e-01 9.80095088e-01 4.07069214e-02 1.97554737e-01 9.79431212e-01 4.07069176e-02 2.01053917e-01 9.78719711e-01 4.07069176e-02 2.04567939e-01 9.77991164e-01 4.07069176e-02 2.07965806e-01 9.77275848e-01 4.07069176e-02 2.11389139e-01 9.76540685e-01 4.07069176e-02 2.14710817e-01 9.75813568e-01 4.07069214e-02 2.18077853e-01 9.75069582e-01 4.07069176e-02 2.21598551e-01 9.74272966e-01 4.07069214e-02 2.25016996e-01 9.73491013e-01 4.07069176e-02 2.28410766e-01 9.72701609e-01 4.07069176e-02 2.31712267e-01 9.71920907e-01 4.07069474e-02 2.35000908e-01 9.71132100e-01 4.07069176e-02 2.38422722e-01 9.70294595e-01 4.07069176e-02 2.41853490e-01 9.69442904e-01 4.07069176e-02 2.45320067e-01 9.68572676e-01 4.07069176e-02 2.48646423e-01 9.67726648e-01 4.07069214e-02 2.52015322e-01 9.66852009e-01 4.07069176e-02 2.55390048e-01 9.65969384e-01 4.07069214e-02 2.58735508e-01 9.65076089e-01 4.07069176e-02 2.62203932e-01 9.64140654e-01 4.07069176e-02 2.65499145e-01 9.63237703e-01 4.07069214e-02 2.68830448e-01 9.62312400e-01 4.07069176e-02 2.72213340e-01 9.61362541e-01 4.07069474e-02 2.75544196e-01 9.60410774e-01 4.07069176e-02 2.79015660e-01 9.59409416e-01 4.07069176e-02 2.82260031e-01 9.58460867e-01 4.07069176e-02 2.85593867e-01 9.57472026e-01 4.07069176e-02 2.89064497e-01 9.56428111e-01 4.07069176e-02 2.92349488e-01 9.55431998e-01 4.07069176e-02 2.95570672e-01 9.54441190e-01 4.07069214e-02 2.98839360e-01 9.53421414e-01 4.07069176e-02 3.02170724e-01 9.52370167e-01 4.07069176e-02 3.05596918e-01 9.51274157e-01 4.07069176e-02 3.09043974e-01 9.50161219e-01 4.07069176e-02 3.12320113e-01 9.49089170e-01 4.07069176e-02 3.15556258e-01 9.48020220e-01 4.07069214e-02 3.18774402e-01 9.46943164e-01 4.07069176e-02 3.22070777e-01 9.45825040e-01 4.07069176e-02 3.25436473e-01 9.44672644e-01 4.07069176e-02 3.28821898e-01 9.43498135e-01 4.07069176e-02 3.32055360e-01 9.42368448e-01 4.07069214e-02 3.35321248e-01 9.41210330e-01 4.07069176e-02 3.38624537e-01 9.40025270e-01 4.07069214e-02 3.41863751e-01 9.38853264e-01 4.07069176e-02 3.45245481e-01 9.37608659e-01 4.07069176e-02 3.48516762e-01 9.36393917e-01 4.07069176e-02 3.51784319e-01 9.35172498e-01 4.07069176e-02 3.54988128e-01 9.33965802e-01 4.07069214e-02 3.58229548e-01 9.32734847e-01 4.07069176e-02 3.61488074e-01 9.31470096e-01 4.07069176e-02 3.64641309e-01 9.30243015e-01 4.07069176e-02 3.67983341e-01 9.28925872e-01 4.07069176e-02 3.71298820e-01 9.27606225e-01 4.07069176e-02 3.74519050e-01 9.26308751e-01 4.07069176e-02 3.77738595e-01 9.25002277e-01 4.07069176e-02 3.80904078e-01 9.23701584e-01 4.07069176e-02 3.84029448e-01 9.22407568e-01 4.07069176e-02 3.87340873e-01 9.21020448e-01 4.07069176e-02 3.90620619e-01 9.19634402e-01 4.07069176e-02 3.93827081e-01 9.18265760e-01 4.07069176e-02 3.96959007e-01 9.16918039e-01 4.07069176e-02 4.00099844e-01 9.15553570e-01 4.07069176e-02 4.03286636e-01 9.14152801e-01 4.07069176e-02 4.06525552e-01 9.12716627e-01 4.07069176e-02 4.09780592e-01 9.11259949e-01 4.07069176e-02 4.12893534e-01 9.09853935e-01 4.07069176e-02 4.15992945e-01 9.08439398e-01 4.07069176e-02 4.19128925e-01 9.06996846e-01 4.07069176e-02 4.22302276e-01 9.05525684e-01 4.07069176e-02 4.25482541e-01 9.04035270e-01 4.07069176e-02 4.28635359e-01 9.02543485e-01 4.07069176e-02 4.31881130e-01 9.00994182e-01 4.07069176e-02 4.35015023e-01 8.99489582e-01 4.07069176e-02 4.38101679e-01 8.97990823e-01 4.07069176e-02 4.41188008e-01 8.96475136e-01 4.07069176e-02 4.44294304e-01 8.94940794e-01 4.07069176e-02 4.47473347e-01 8.93354416e-01 4.07069176e-02 4.50659394e-01 8.91752779e-01 4.07069176e-02 4.53758359e-01 8.90178800e-01 4.07069176e-02 4.56823587e-01 8.88611972e-01 4.07069474e-02 4.59826708e-01 8.87058377e-01 4.07069176e-02 4.62921828e-01 8.85451257e-01 4.07069176e-02 4.66070414e-01 8.83795083e-01 4.07069176e-02 4.69217837e-01 8.82129550e-01 4.07069176e-02 4.72290099e-01 8.80487919e-01 4.07069176e-02 4.75300401e-01 8.78864527e-01 4.07069176e-02 4.78312850e-01 8.77233386e-01 4.07069176e-02 4.81371641e-01 8.75556588e-01 4.07069176e-02 4.84467208e-01 8.73842895e-01 4.07069176e-02 4.87580508e-01 8.72112691e-01 4.07069176e-02 4.90601271e-01 8.70418847e-01 4.07069214e-02 4.93575841e-01 8.68732810e-01 4.07069176e-02 4.96627688e-01 8.66996229e-01 4.07069214e-02 4.99598235e-01 8.65284860e-01 4.07069176e-02 5.02685547e-01 8.63495111e-01 4.07069176e-02 5.05702615e-01 8.61731648e-01 4.07069176e-02 5.08689225e-01 8.59969974e-01 4.07069176e-02 5.11692107e-01 8.58188391e-01 4.07069176e-02 5.14678121e-01 8.56400549e-01 4.07069176e-02 5.17701089e-01 8.54576409e-01 4.07069176e-02 5.20589411e-01 8.52821708e-01 4.07069176e-02 5.23615003e-01 8.50964069e-01 4.07069176e-02 5.26607871e-01 8.49118233e-01 4.07069176e-02 5.29553175e-01 8.47282946e-01 4.07069176e-02 5.32524228e-01 8.45420718e-01 4.07069176e-02 5.35365343e-01 8.43623996e-01 4.07069176e-02 5.38338542e-01 8.41727614e-01 4.07069176e-02 5.41275680e-01 8.39843154e-01 4.07069176e-02 5.44233680e-01 8.37927699e-01 4.07069176e-02 5.47238052e-01 8.35971415e-01 4.07069176e-02 5.50098598e-01 8.34092855e-01 4.07069288e-02 5.52896619e-01 8.32236767e-01 4.07069214e-02 5.55789351e-01 8.30311894e-01 4.07069549e-02 5.58761477e-01 8.28316689e-01 4.07069698e-02 5.61709881e-01 8.26320291e-01 4.07070071e-02 5.64556599e-01 8.24381173e-01 4.07070629e-02 5.67363858e-01 8.22453916e-01 4.07070629e-02 5.70198715e-01 8.20490241e-01 4.07070704e-02 5.73118091e-01 8.18455458e-01 4.07070741e-02 5.75986803e-01 8.16445708e-01 4.07071374e-02 5.78738868e-01 8.14499319e-01 4.07072119e-02 5.81527829e-01 8.12509894e-01 4.07073796e-02 5.84468782e-01 8.10394704e-01 4.07072194e-02 5.87157965e-01 8.08447123e-01 4.07072939e-02 5.90200186e-01 8.06229472e-01 4.07072864e-02 5.93090355e-01 8.04105639e-01 4.07072790e-02 5.96850157e-01 8.01319420e-01 4.07072827e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 7.25412965e-01 6.87108934e-01 4.07072827e-02 7.27528274e-01 6.84869051e-01 4.07072864e-02 7.31579244e-01 6.80540085e-01 4.07072790e-02 7.32647240e-01 6.79390132e-01 4.07072790e-02 7.35014439e-01 6.76828027e-01 4.07072827e-02 7.37372398e-01 6.74258471e-01 4.07072827e-02 7.40189910e-01 6.71163440e-01 4.07072827e-02 7.42971480e-01 6.68083012e-01 4.07072827e-02 7.45128632e-01 6.65676236e-01 4.07072827e-02 7.47467220e-01 6.63049638e-01 4.07072864e-02 7.49745667e-01 6.60472035e-01 4.07072864e-02 7.52126575e-01 6.57760143e-01 4.07072641e-02 7.54225314e-01 6.55350149e-01 4.07072380e-02 7.56564379e-01 6.52654588e-01 4.07073721e-02 7.58762896e-01 6.50096297e-01 4.07071747e-02 7.60963023e-01 6.47505879e-01 4.07070629e-02 7.63215601e-01 6.44846618e-01 4.07070071e-02 7.65484631e-01 6.42144978e-01 4.07069474e-02 7.67708898e-01 6.39486790e-01 4.07069474e-02 7.69877791e-01 6.36870503e-01 4.07069176e-02 7.72156775e-01 6.34107172e-01 4.07069176e-02 7.74418533e-01 6.31339848e-01 4.07069176e-02 7.76606560e-01 6.28647983e-01 4.07069176e-02 7.78738976e-01 6.26003921e-01 4.07069176e-02 7.80878305e-01 6.23335660e-01 4.07069176e-02 7.83024907e-01 6.20633423e-01 4.07069176e-02 7.85250366e-01 6.17815971e-01 4.07069176e-02 7.87471354e-01 6.14982367e-01 4.07069176e-02 7.89598763e-01 6.12249494e-01 4.07069176e-02 7.91679859e-01 6.09557390e-01 4.07069176e-02 7.93753445e-01 6.06852889e-01 4.07069176e-02 7.95875967e-01 6.04067385e-01 4.07069176e-02 7.98024833e-01 6.01227403e-01 4.07069176e-02 8.00179660e-01 5.98351777e-01 4.07069176e-02 8.02209795e-01 5.95629632e-01 4.07069176e-02 8.04226041e-01 5.92903435e-01 4.07069176e-02 8.06281805e-01 5.90102971e-01 4.07069176e-02 8.08394372e-01 5.87207913e-01 4.07069176e-02 8.10449958e-01 5.84367692e-01 4.07069176e-02 8.12418461e-01 5.81628799e-01 4.07069176e-02 8.14501941e-01 5.78706861e-01 4.07069176e-02 8.16528082e-01 5.75848818e-01 4.07069176e-02 8.18531096e-01 5.72991550e-01 4.07069176e-02 8.20529342e-01 5.70129812e-01 4.07069214e-02 8.22449386e-01 5.67357540e-01 4.07069176e-02 8.24469328e-01 5.64416528e-01 4.07069176e-02 8.26500297e-01 5.61437726e-01 4.07069176e-02 8.28459203e-01 5.58544040e-01 4.07069176e-02 8.30348909e-01 5.55730045e-01 4.07069176e-02 8.32215965e-01 5.52928507e-01 4.07069176e-02 8.34151268e-01 5.50004840e-01 4.07069176e-02 8.36124778e-01 5.46998262e-01 4.07069176e-02 8.38076532e-01 5.44005990e-01 4.07069176e-02 8.39918554e-01 5.41158915e-01 4.07069176e-02 8.41737151e-01 5.38324833e-01 4.07069176e-02 8.43605101e-01 5.35391688e-01 4.07069176e-02 8.45483303e-01 5.32423198e-01 4.07069176e-02 8.47393692e-01 5.29373109e-01 4.07069176e-02 8.49301279e-01 5.26311576e-01 4.07069176e-02 8.51078868e-01 5.23429453e-01 4.07069176e-02 8.52854729e-01 5.20534813e-01 4.07069176e-02 8.54654133e-01 5.17571568e-01 4.07069176e-02 8.56448829e-01 5.14596641e-01 4.07069176e-02 8.58238816e-01 5.11606753e-01 4.07069176e-02 8.60043228e-01 5.08566976e-01 4.07069176e-02 8.61813724e-01 5.05563021e-01 4.07069176e-02 8.63557577e-01 5.02576590e-01 4.07069176e-02 8.65349710e-01 4.99483526e-01 4.07069176e-02 8.67102504e-01 4.96438354e-01 4.07069214e-02 8.68766904e-01 4.93515879e-01 4.07069176e-02 8.70559931e-01 4.90349621e-01 4.07069176e-02 8.72320354e-01 4.87206846e-01 4.07069176e-02 8.74006927e-01 4.84174728e-01 4.07069176e-02 8.75640750e-01 4.81217712e-01 4.07069176e-02 8.77280295e-01 4.78223532e-01 4.07069176e-02 8.78944218e-01 4.75153923e-01 4.07069176e-02 8.80603135e-01 4.72075045e-01 4.07069176e-02 8.82276773e-01 4.68934804e-01 4.07069176e-02 8.83952200e-01 4.65773046e-01 4.07069176e-02 8.85539293e-01 4.62751567e-01 4.07069176e-02 8.87092233e-01 4.59763736e-01 4.07069176e-02 8.88708174e-01 4.56633478e-01 4.07069176e-02 8.90335977e-01 4.53446597e-01 4.07069176e-02 8.91953588e-01 4.50260520e-01 4.07069176e-02 8.93484294e-01 4.47216034e-01 4.07069214e-02 8.94991815e-01 4.44190115e-01 4.07069176e-02 8.96520913e-01 4.41098124e-01 4.07069176e-02 8.98106992e-01 4.37858701e-01 4.07069176e-02 8.99630785e-01 4.34724778e-01 4.07069176e-02 9.01103497e-01 4.31654245e-01 4.07069176e-02 9.02631938e-01 4.28447008e-01 4.07069176e-02 9.04131293e-01 4.25277978e-01 4.07069176e-02 9.05609667e-01 4.22121793e-01 4.07069176e-02 9.07088280e-01 4.18935388e-01 4.07069176e-02 9.08498287e-01 4.15866554e-01 4.07069176e-02 9.09977794e-01 4.12617564e-01 4.07069176e-02 9.11459982e-01 4.09337848e-01 4.07069176e-02 9.12871778e-01 4.06178892e-01 4.07069176e-02 9.14259553e-01 4.03042644e-01 4.07069176e-02 9.15630221e-01 3.99924785e-01 4.07069176e-02 9.17009592e-01 3.96746010e-01 4.07069176e-02 9.18390274e-01 3.93534184e-01 4.07069176e-02 9.19790030e-01 3.90253901e-01 4.07069176e-02 9.21151400e-01 3.87034595e-01 4.07069176e-02 9.22454000e-01 3.83919954e-01 4.07069176e-02 9.23791409e-01 3.80686402e-01 4.07069176e-02 9.25121427e-01 3.77448559e-01 4.07069176e-02 9.26459610e-01 3.74148011e-01 4.07069176e-02 9.27795887e-01 3.70825976e-01 4.07069176e-02 9.29060400e-01 3.67650688e-01 4.07069214e-02 9.30296183e-01 3.64510924e-01 4.07069176e-02 9.31558251e-01 3.61253828e-01 4.07069176e-02 9.32853520e-01 3.57918501e-01 4.07069176e-02 9.34103072e-01 3.54624093e-01 4.07069176e-02 9.35294688e-01 3.51458371e-01 4.07069176e-02 9.36545253e-01 3.48109245e-01 4.07069176e-02 9.37788725e-01 3.44757140e-01 4.07069176e-02 9.38988268e-01 3.41502637e-01 4.07069176e-02 9.40139949e-01 3.38301986e-01 4.07069363e-02 9.41283762e-01 3.35117787e-01 4.07069176e-02 9.42480087e-01 3.31731915e-01 4.07069176e-02 9.43667591e-01 3.28337610e-01 4.07069176e-02 9.44818556e-01 3.25019836e-01 4.07069176e-02 9.45910990e-01 3.21821809e-01 4.07069400e-02 9.46990490e-01 3.18634570e-01 4.07069176e-02 9.48106289e-01 3.15293849e-01 4.07069176e-02 9.49203312e-01 3.11974645e-01 4.07069176e-02 9.50300217e-01 3.08619946e-01 4.07069176e-02 9.51412320e-01 3.05173397e-01 4.07069176e-02 9.52447474e-01 3.01931471e-01 4.07069400e-02 9.53462243e-01 2.98710495e-01 4.07069176e-02 9.54500020e-01 2.95373797e-01 4.07069176e-02 9.55542922e-01 2.91979134e-01 4.07069176e-02 9.56585109e-01 2.88544327e-01 4.07069176e-02 9.57566917e-01 2.85278499e-01 4.07069437e-02 9.58530724e-01 2.82023847e-01 4.07069176e-02 9.59506571e-01 2.78681487e-01 4.07069176e-02 9.60484385e-01 2.75289685e-01 4.07069176e-02 9.61448193e-01 2.71912992e-01 4.07069214e-02 9.62375581e-01 2.68611521e-01 4.07069176e-02 9.63307321e-01 2.65242219e-01 4.07069176e-02 9.64223087e-01 2.61907220e-01 4.07069176e-02 9.65146542e-01 2.58464813e-01 4.07069176e-02 9.66057658e-01 2.55052239e-01 4.07069214e-02 9.66914296e-01 2.51785427e-01 4.07069176e-02 9.67780828e-01 2.48428389e-01 4.07069176e-02 9.68667209e-01 2.44939655e-01 4.07069176e-02 9.69531596e-01 2.41504431e-01 4.07069214e-02 9.70367193e-01 2.38132000e-01 4.07069176e-02 9.71174955e-01 2.34818727e-01 4.07069214e-02 9.71967101e-01 2.31512174e-01 4.07069176e-02 9.72765982e-01 2.28131518e-01 4.07069176e-02 9.73582149e-01 2.24615932e-01 4.07069176e-02 9.74359035e-01 2.21226290e-01 4.07069363e-02 9.75107670e-01 2.17908293e-01 4.07069176e-02 9.75860059e-01 2.14504719e-01 4.07069214e-02 9.76617515e-01 2.11027518e-01 4.07069176e-02 9.77345645e-01 2.07637519e-01 4.07069363e-02 9.78069127e-01 2.04199016e-01 4.07069176e-02 9.78777587e-01 2.00780705e-01 4.07069214e-02 9.79469597e-01 1.97368667e-01 4.07069176e-02 9.80165005e-01 1.93889841e-01 4.07069176e-02 9.80844557e-01 1.90426037e-01 4.07069176e-02 9.81484294e-01 1.87092409e-01 4.07069214e-02 9.82114315e-01 1.83761716e-01 4.07069176e-02 9.82763171e-01 1.80245414e-01 4.07069176e-02 9.83406723e-01 1.76741064e-01 4.07069176e-02 9.84016716e-01 1.73309594e-01 4.07069176e-02 9.84600723e-01 1.69936255e-01 4.07069474e-02 9.85173762e-01 1.66590244e-01 4.07069176e-02 9.85744536e-01 1.63162753e-01 4.07069176e-02 9.86310840e-01 1.59708753e-01 4.07069176e-02 9.86872792e-01 1.56197697e-01 4.07069176e-02 9.87425327e-01 1.52665272e-01 4.07069176e-02 9.87940669e-01 1.49291903e-01 4.07069214e-02 9.88439977e-01 1.45950779e-01 4.07069176e-02 9.88944530e-01 1.42487243e-01 4.07069176e-02 9.89446461e-01 1.38965577e-01 4.07069176e-02 9.89940107e-01 1.35419101e-01 4.07069214e-02 9.90394652e-01 1.32038131e-01 4.07069474e-02 9.90840435e-01 1.28658012e-01 4.07069176e-02 9.91279960e-01 1.25229672e-01 4.07069176e-02 9.91708994e-01 1.21777311e-01 4.07069176e-02 9.92132723e-01 1.18268378e-01 4.07069176e-02 9.92539763e-01 1.14796251e-01 4.07069176e-02 9.92943883e-01 1.11254118e-01 4.07069176e-02 9.93327200e-01 1.07795320e-01 4.07069325e-02 9.93690073e-01 1.04368344e-01 4.07069176e-02 9.94055748e-01 1.00846507e-01 4.07069474e-02 9.94390607e-01 9.74787921e-02 4.07069176e-02 9.94733632e-01 9.39357877e-02 4.07069176e-02 9.95062709e-01 9.03671682e-02 4.07069176e-02 9.95371342e-01 8.69103372e-02 4.07069214e-02 9.95664001e-01 8.34936276e-02 4.07069437e-02 9.95942712e-01 8.01037699e-02 4.07069214e-02 9.96212125e-01 7.66426697e-02 4.07069176e-02 9.96481299e-01 7.30686188e-02 4.07069176e-02 9.96735454e-01 6.95018619e-02 4.07069176e-02 9.96966004e-01 6.61366209e-02 4.07069363e-02 9.97184575e-01 6.27406538e-02 4.07069176e-02 9.97397542e-01 5.92505336e-02 4.07069176e-02 9.97601748e-01 5.57598583e-02 4.07069176e-02 9.97790933e-01 5.22117354e-02 4.07069176e-02 9.97975171e-01 4.86144722e-02 4.07069176e-02 9.98133421e-01 4.52306010e-02 4.07069474e-02 9.98281002e-01 4.18555178e-02 4.07069176e-02 9.98420835e-01 3.83821800e-02 4.07069176e-02 9.98551548e-01 3.47657837e-02 4.07069176e-02 9.98669803e-01 3.12693529e-02 4.07069437e-02 9.98769820e-01 2.78873984e-02 4.07069176e-02 9.98861969e-01 2.43851244e-02 4.07069176e-02 9.98938203e-01 2.09069643e-02 4.07069176e-02 9.99009609e-01 1.74376871e-02 4.07069176e-02 9.99058664e-01 1.39230601e-02 4.07069288e-02 9.99102414e-01 1.04479445e-02 4.07069176e-02 9.99140859e-01 6.86630001e-03 4.07069176e-02 9.99157250e-01 3.26848100e-03 4.07069176e-02 9.99158382e-01 -2.07584875e-04 4.07069176e-02 9.99157250e-01 -3.71565204e-03 4.07069214e-02 9.99137759e-01 -7.09776115e-03 4.07069549e-02 9.99103189e-01 -1.04597937e-02 4.07069176e-02 9.99056101e-01 -1.39523009e-02 4.07069176e-02 9.99006808e-01 -1.75807159e-02 4.07069176e-02 9.98931468e-01 -2.11810675e-02 4.07069176e-02 9.98855650e-01 -2.46267542e-02 4.07069176e-02 9.98766840e-01 -2.79913619e-02 4.07069400e-02 9.98660028e-01 -3.15087922e-02 4.07069176e-02 9.98545825e-01 -3.50092947e-02 4.07069214e-02 9.98419046e-01 -3.84002067e-02 4.07069176e-02 9.98281658e-01 -4.18767594e-02 4.07069176e-02 9.98122394e-01 -4.54414897e-02 4.07069176e-02 9.97953653e-01 -4.90437374e-02 4.07069176e-02 9.97775376e-01 -5.25035895e-02 4.07069176e-02 9.97590959e-01 -5.59321269e-02 4.07069214e-02 9.97395873e-01 -5.93012758e-02 4.07069176e-02 9.97182727e-01 -6.27550557e-02 4.07069176e-02 9.96951580e-01 -6.63362592e-02 4.07069176e-02 9.96705294e-01 -6.99361116e-02 4.07069176e-02 9.96456563e-01 -7.34301507e-02 4.07069176e-02 9.96200264e-01 -7.68174976e-02 4.07069214e-02 9.95935321e-01 -8.01750124e-02 4.07069176e-02 9.95650828e-01 -8.36435035e-02 4.07069176e-02 9.95340526e-01 -8.72520059e-02 4.07069176e-02 9.95030582e-01 -9.07106400e-02 4.07069214e-02 9.94720757e-01 -9.40508917e-02 4.07069176e-02 9.94385064e-01 -9.75559428e-02 4.07069176e-02 9.94037032e-01 -1.01020627e-01 4.07069176e-02 9.93676960e-01 -1.04506493e-01 4.07069176e-02 9.93297458e-01 -1.08041711e-01 4.07069176e-02 9.92918551e-01 -1.11497894e-01 4.07069214e-02 9.92531300e-01 -1.14873342e-01 4.07069176e-02 9.92115080e-01 -1.18408233e-01 4.07069176e-02 9.91697013e-01 -1.21883593e-01 4.07069214e-02 9.91262734e-01 -1.25356108e-01 4.07069176e-02 9.90806699e-01 -1.28904864e-01 4.07069176e-02 9.90368843e-01 -1.32235110e-01 4.07069176e-02 9.89897072e-01 -1.35718584e-01 4.07069176e-02 9.89407480e-01 -1.39257446e-01 4.07069176e-02 9.88923132e-01 -1.42644837e-01 4.07069214e-02 9.88419294e-01 -1.46077797e-01 4.07069176e-02 9.87900078e-01 -1.49557322e-01 4.07069214e-02 9.87375379e-01 -1.52986273e-01 4.07069176e-02 9.86833394e-01 -1.56450599e-01 4.07069288e-02 9.86281812e-01 -1.59886658e-01 4.07069176e-02 9.85720873e-01 -1.63318217e-01 4.07069214e-02 9.85144079e-01 -1.66754425e-01 4.07069176e-02 9.84541059e-01 -1.70269012e-01 4.07069176e-02 9.83939528e-01 -1.73739791e-01 4.07069176e-02 9.83345985e-01 -1.77072376e-01 4.07069214e-02 9.82731760e-01 -1.80412754e-01 4.07069176e-02 9.82099295e-01 -1.83842912e-01 4.07069176e-02 9.81431305e-01 -1.87359184e-01 4.07069176e-02 9.80759084e-01 -1.90862626e-01 4.07069176e-02 9.80091572e-01 -1.94259062e-01 4.07069176e-02 9.79422450e-01 -1.97608218e-01 4.07069437e-02 9.78742421e-01 -2.00945407e-01 4.07069176e-02 9.78025138e-01 -2.04407260e-01 4.07069176e-02 9.77292895e-01 -2.07879469e-01 4.07069176e-02 9.76571083e-01 -2.11260915e-01 4.07069214e-02 9.75824654e-01 -2.14664429e-01 4.07069176e-02 9.75061774e-01 -2.18115330e-01 4.07069400e-02 9.74303007e-01 -2.21468195e-01 4.07069176e-02 9.73522663e-01 -2.24883959e-01 4.07069214e-02 9.72727418e-01 -2.28297189e-01 4.07069176e-02 9.71926689e-01 -2.31689662e-01 4.07069214e-02 9.71141398e-01 -2.34958619e-01 4.07069176e-02 9.70290303e-01 -2.38436699e-01 4.07069176e-02 9.69449580e-01 -2.41833121e-01 4.07069437e-02 9.68598068e-01 -2.45215654e-01 4.07069176e-02 9.67719972e-01 -2.48670682e-01 4.07069214e-02 9.66878295e-01 -2.51920283e-01 4.07069437e-02 9.65978265e-01 -2.55352378e-01 4.07069176e-02 9.65080500e-01 -2.58727103e-01 4.07069214e-02 9.64202404e-01 -2.61978418e-01 4.07069176e-02 9.63260829e-01 -2.65405744e-01 4.07069176e-02 9.62306976e-01 -2.68862039e-01 4.07069549e-02 9.61380124e-01 -2.72146463e-01 4.07069176e-02 9.60393727e-01 -2.75608718e-01 4.07069176e-02 9.59446430e-01 -2.78889656e-01 4.07069474e-02 9.58502769e-01 -2.82114625e-01 4.07069176e-02 9.57490027e-01 -2.85536230e-01 4.07069176e-02 9.56455231e-01 -2.88974851e-01 4.07069176e-02 9.55432177e-01 -2.92347580e-01 4.07069176e-02 9.54428196e-01 -2.95612276e-01 4.07069437e-02 9.53431547e-01 -2.98805326e-01 4.07069176e-02 9.52380598e-01 -3.02139282e-01 4.07069176e-02 9.51292038e-01 -3.05548370e-01 4.07069176e-02 9.50196624e-01 -3.08937520e-01 4.07069176e-02 9.49111760e-01 -3.12253475e-01 4.07069176e-02 9.48031843e-01 -3.15521806e-01 4.07069214e-02 9.46958005e-01 -3.18729848e-01 4.07069176e-02 9.45844293e-01 -3.22018892e-01 4.07069176e-02 9.44693565e-01 -3.25376779e-01 4.07069176e-02 9.43544269e-01 -3.28693271e-01 4.07069214e-02 9.42394137e-01 -3.31977069e-01 4.07069176e-02 9.41236615e-01 -3.35253835e-01 4.07069400e-02 9.40055490e-01 -3.38541180e-01 4.07069176e-02 9.38869715e-01 -3.41828704e-01 4.07069437e-02 9.37658429e-01 -3.45109224e-01 4.07069176e-02 9.36443925e-01 -3.48381758e-01 4.07069214e-02 9.35259461e-01 -3.51551294e-01 4.07069176e-02 9.34025764e-01 -3.54827970e-01 4.07069176e-02 9.32753384e-01 -3.58184278e-01 4.07069176e-02 9.31484640e-01 -3.61448586e-01 4.07069214e-02 9.30217803e-01 -3.64706844e-01 4.07069176e-02 9.28944767e-01 -3.67939234e-01 4.07069437e-02 9.27661002e-01 -3.71159405e-01 4.07069176e-02 9.26353574e-01 -3.74414265e-01 4.07069214e-02 9.25085783e-01 -3.77532482e-01 4.07069176e-02 9.23726320e-01 -3.80841970e-01 4.07069176e-02 9.22383845e-01 -3.84089231e-01 4.07069214e-02 9.21036065e-01 -3.87304068e-01 4.07069176e-02 9.19635594e-01 -3.90616685e-01 4.07069176e-02 9.18306768e-01 -3.93731713e-01 4.07069214e-02 9.16973054e-01 -3.96831244e-01 4.07069176e-02 9.15545464e-01 -4.00116920e-01 4.07069176e-02 9.14106309e-01 -4.03392971e-01 4.07069176e-02 9.12694335e-01 -4.06576276e-01 4.07069176e-02 9.11288083e-01 -4.09723073e-01 4.07069214e-02 9.09894347e-01 -4.12801564e-01 4.07069176e-02 9.08474803e-01 -4.15915430e-01 4.07069176e-02 9.06964421e-01 -4.19198692e-01 4.07069176e-02 9.05461431e-01 -4.22438920e-01 4.07069176e-02 9.03970897e-01 -4.25617307e-01 4.07069176e-02 9.02519584e-01 -4.28690046e-01 4.07069214e-02 9.01049018e-01 -4.31766331e-01 4.07069176e-02 8.99550796e-01 -4.34889227e-01 4.07069176e-02 8.97971272e-01 -4.38139200e-01 4.07069176e-02 8.96432757e-01 -4.41277027e-01 4.07069176e-02 8.94882023e-01 -4.44412261e-01 4.07069176e-02 8.93342078e-01 -4.47502196e-01 4.07069214e-02 8.91817808e-01 -4.50532526e-01 4.07069176e-02 8.90251577e-01 -4.53618735e-01 4.07069176e-02 8.88606131e-01 -4.56831157e-01 4.07069176e-02 8.87012422e-01 -4.59918439e-01 4.07069474e-02 8.85433733e-01 -4.62953478e-01 4.07069176e-02 8.83832037e-01 -4.66003090e-01 4.07069214e-02 8.82130980e-01 -4.69214022e-01 4.07069176e-02 8.80492389e-01 -4.72284406e-01 4.07069214e-02 8.78858387e-01 -4.75313902e-01 4.07069176e-02 8.77175152e-01 -4.78421032e-01 4.07069176e-02 8.75559628e-01 -4.81364042e-01 4.07069176e-02 8.73857796e-01 -4.84443456e-01 4.07069176e-02 8.72134268e-01 -4.87540632e-01 4.07069176e-02 8.70420635e-01 -4.90597814e-01 4.07069176e-02 8.68709028e-01 -4.93617743e-01 4.07069176e-02 8.66970599e-01 -4.96672183e-01 4.07069214e-02 8.65245223e-01 -4.99667615e-01 4.07069176e-02 8.63461256e-01 -5.02745152e-01 4.07069176e-02 8.61750364e-01 -5.05671859e-01 4.07069176e-02 8.59991252e-01 -5.08656561e-01 4.07069176e-02 8.58218193e-01 -5.11640489e-01 4.07069176e-02 8.56389225e-01 -5.14696717e-01 4.07069176e-02 8.54519665e-01 -5.17794132e-01 4.07069176e-02 8.52754891e-01 -5.20700514e-01 4.07069176e-02 8.50977719e-01 -5.23593664e-01 4.07069176e-02 8.49151075e-01 -5.26555300e-01 4.07069176e-02 8.47265303e-01 -5.29581726e-01 4.07069176e-02 8.45357180e-01 -5.32623470e-01 4.07069176e-02 8.43502700e-01 -5.35555422e-01 4.07069176e-02 8.41693163e-01 -5.38394213e-01 4.07069176e-02 8.39789093e-01 -5.41357934e-01 4.07069176e-02 8.37845743e-01 -5.44361711e-01 4.07069176e-02 8.35942745e-01 -5.47277391e-01 4.07069176e-02 8.34020674e-01 -5.50205231e-01 4.07069176e-02 8.32152784e-01 -5.53025126e-01 4.07069474e-02 8.30271125e-01 -5.55846870e-01 4.07069176e-02 8.28335524e-01 -5.58729708e-01 4.07069176e-02 8.26311409e-01 -5.61715722e-01 4.07069176e-02 8.24318409e-01 -5.64638674e-01 4.07069176e-02 8.22324395e-01 -5.67540586e-01 4.07069176e-02 8.20402920e-01 -5.70312738e-01 4.07069363e-02 8.18391621e-01 -5.73190212e-01 4.07069176e-02 8.16402256e-01 -5.76029181e-01 4.07069474e-02 8.14372599e-01 -5.78888416e-01 4.07069176e-02 8.12339723e-01 -5.81742883e-01 4.07069474e-02 8.10360253e-01 -5.84488392e-01 4.07069176e-02 8.08301091e-01 -5.87338865e-01 4.07069176e-02 8.06249559e-01 -5.90149522e-01 4.07069176e-02 8.04147363e-01 -5.93009889e-01 4.07069176e-02 8.02016139e-01 -5.95891774e-01 4.07069176e-02 7.99995780e-01 -5.98599792e-01 4.07069214e-02 7.97913492e-01 -6.01372421e-01 4.07069176e-02 7.95787573e-01 -6.04185939e-01 4.07069214e-02 7.93697715e-01 -6.06925845e-01 4.07069176e-02 7.91584432e-01 -6.09680772e-01 4.07069176e-02 7.89484620e-01 -6.12396121e-01 4.07069176e-02 7.87286937e-01 -6.15218282e-01 4.07069176e-02 7.85088718e-01 -6.18022263e-01 4.07069176e-02 7.82949209e-01 -6.20730579e-01 4.07069214e-02 7.80849993e-01 -6.23369038e-01 4.07069176e-02 7.78671443e-01 -6.26089156e-01 4.07069176e-02 7.76426017e-01 -6.28871500e-01 4.07069176e-02 7.74215937e-01 -6.31587744e-01 4.07069176e-02 7.72074401e-01 -6.34205103e-01 4.07069176e-02 7.69853055e-01 -6.36900187e-01 4.07069176e-02 7.67640293e-01 -6.39564991e-01 4.07069176e-02 7.65395582e-01 -6.42250776e-01 4.07069176e-02 7.63072133e-01 -6.45007372e-01 4.07069176e-02 7.60811806e-01 -6.47674143e-01 4.07069214e-02 7.58629680e-01 -6.50227904e-01 4.07069176e-02 7.56350398e-01 -6.52878702e-01 4.07069176e-02 7.54032254e-01 -6.55554950e-01 4.07069176e-02 7.51685739e-01 -6.58241868e-01 4.07069176e-02 7.49350846e-01 -6.60899580e-01 4.07069176e-02 7.47080624e-01 -6.63465679e-01 4.07069176e-02 7.44820952e-01 -6.66001558e-01 4.07069176e-02 7.42441058e-01 -6.68653369e-01 4.07069176e-02 7.40123868e-01 -6.71220124e-01 4.07069176e-02 7.37756252e-01 -6.73817337e-01 4.07069176e-02 7.35403717e-01 -6.76387131e-01 4.07069176e-02 7.33100593e-01 -6.78881228e-01 4.07069176e-02 7.30724335e-01 -6.81436300e-01 4.07069176e-02 7.28290319e-01 -6.84036851e-01 4.07069176e-02 7.25887597e-01 -6.86586857e-01 4.07069176e-02 7.23498583e-01 -6.89106703e-01 4.07069176e-02 7.21076488e-01 -6.91634476e-01 4.07069214e-02 7.18684375e-01 -6.94131732e-01 4.07069176e-02 7.16236413e-01 -6.96657002e-01 4.07069214e-02 7.13868558e-01 -6.99079514e-01 4.07069176e-02 7.11377740e-01 -7.01615393e-01 4.07069176e-02 7.08897412e-01 -7.04125345e-01 4.07069772e-02 7.06441045e-01 -7.06575096e-01 4.07069586e-02 7.03898132e-01 -7.09122002e-01 4.07069772e-02 7.01494634e-01 -7.11504579e-01 4.07070331e-02 6.99080884e-01 -7.13872969e-01 4.07070220e-02 6.96579814e-01 -7.16318250e-01 4.07070592e-02 6.94046259e-01 -7.18768358e-01 4.07070629e-02 6.91491425e-01 -7.21235693e-01 4.07071076e-02 6.88940465e-01 -7.23672807e-01 4.07071374e-02 6.86496139e-01 -7.25997329e-01 4.07073535e-02 6.84278488e-01 -7.28085637e-01 4.07072976e-02 6.81881607e-01 -7.30328500e-01 4.07072678e-02 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. 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. 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. 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. 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. 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. 0. 0. 0. 5.19616008e-01 -8.53429317e-01 4.07072864e-02 5.17406940e-01 -8.54772747e-01 4.07073051e-02 5.14456749e-01 -8.56550872e-01 4.07071784e-02 5.11495054e-01 -8.58313620e-01 4.07070629e-02 5.08479238e-01 -8.60102713e-01 4.07070480e-02 5.05540490e-01 -8.61829996e-01 4.07069959e-02 5.02550662e-01 -8.63574982e-01 4.07069586e-02 4.99474287e-01 -8.65356684e-01 4.07069176e-02 4.96474564e-01 -8.67081463e-01 4.07069176e-02 4.93523479e-01 -8.68763208e-01 4.07069176e-02 4.90500778e-01 -8.70477438e-01 4.07069176e-02 4.87462848e-01 -8.72177780e-01 4.07069176e-02 4.84400362e-01 -8.73880446e-01 4.07069176e-02 4.81352627e-01 -8.75566304e-01 4.07069176e-02 4.78313208e-01 -8.77231300e-01 4.07069176e-02 4.75232810e-01 -8.78902376e-01 4.07069176e-02 4.72164720e-01 -8.80554378e-01 4.07069176e-02 4.69094336e-01 -8.82193923e-01 4.07069176e-02 4.65983123e-01 -8.83841872e-01 4.07069176e-02 4.62840855e-01 -8.85490000e-01 4.07069176e-02 4.59730715e-01 -8.87109041e-01 4.07069214e-02 4.56711471e-01 -8.88668776e-01 4.07069176e-02 4.53593552e-01 -8.90262485e-01 4.07069176e-02 4.50479031e-01 -8.91843379e-01 4.07069176e-02 4.47365612e-01 -8.93408954e-01 4.07069176e-02 4.44255233e-01 -8.94959748e-01 4.07069176e-02 4.41147387e-01 -8.96495283e-01 4.07069176e-02 4.38004911e-01 -8.98035645e-01 4.07069176e-02 4.34871525e-01 -8.99558187e-01 4.07069176e-02 4.31702316e-01 -9.01080310e-01 4.07069176e-02 4.28515732e-01 -9.02600884e-01 4.07069176e-02 4.25344527e-01 -9.04099762e-01 4.07069176e-02 4.22157556e-01 -9.05592680e-01 4.07069176e-02 4.18965936e-01 -9.07074034e-01 4.07069176e-02 4.15913373e-01 -9.08476055e-01 4.07069176e-02 4.12740529e-01 -9.09923792e-01 4.07069176e-02 4.09563512e-01 -9.11358535e-01 4.07069176e-02 4.06276613e-01 -9.12827730e-01 4.07069176e-02 4.03061777e-01 -9.14253652e-01 4.07069214e-02 3.99979323e-01 -9.15606260e-01 4.07069176e-02 3.96793127e-01 -9.16989267e-01 4.07069176e-02 3.93576890e-01 -9.18371260e-01 4.07069176e-02 3.90300959e-01 -9.19770956e-01 4.07069176e-02 3.87116402e-01 -9.21118021e-01 4.07069176e-02 3.83847743e-01 -9.22482073e-01 4.07069176e-02 3.80594730e-01 -9.23829675e-01 4.07069176e-02 3.77490282e-01 -9.25104499e-01 4.07069176e-02 3.74201596e-01 -9.26437676e-01 4.07069176e-02 3.70876402e-01 -9.27774072e-01 4.07069176e-02 3.67595911e-01 -9.29080963e-01 4.07069176e-02 3.64416629e-01 -9.30333376e-01 4.07069176e-02 3.61276001e-01 -9.31549788e-01 4.07069176e-02 3.58013541e-01 -9.32818532e-01 4.07069176e-02 3.54764432e-01 -9.34050620e-01 4.07069176e-02 3.51512760e-01 -9.35274601e-01 4.07069176e-02 3.48220825e-01 -9.36504126e-01 4.07069176e-02 3.44949663e-01 -9.37717915e-01 4.07069176e-02 3.41690451e-01 -9.38917398e-01 4.07069176e-02 3.38418603e-01 -9.40098345e-01 4.07069176e-02 3.35128814e-01 -9.41279054e-01 4.07069176e-02 3.31770986e-01 -9.42464948e-01 4.07069176e-02 3.28452051e-01 -9.43628311e-01 4.07069176e-02 3.25179309e-01 -9.44760978e-01 4.07069176e-02 3.21856707e-01 -9.45898354e-01 4.07069176e-02 3.18637103e-01 -9.46989298e-01 4.07069176e-02 3.15253407e-01 -9.48118031e-01 4.07069176e-02 3.11924279e-01 -9.49218512e-01 4.07069176e-02 3.08612198e-01 -9.50301111e-01 4.07069176e-02 3.05268049e-01 -9.51384008e-01 4.07069176e-02 3.02049220e-01 -9.52408135e-01 4.07069176e-02 2.98733026e-01 -9.53454137e-01 4.07069176e-02 2.95404732e-01 -9.54490602e-01 4.07069176e-02 2.92056829e-01 -9.55520689e-01 4.07069176e-02 2.88650542e-01 -9.56552088e-01 4.07069176e-02 2.85210699e-01 -9.57585394e-01 4.07069176e-02 2.81975597e-01 -9.58545685e-01 4.07069176e-02 2.78618127e-01 -9.59525168e-01 4.07069176e-02 2.75179178e-01 -9.60517228e-01 4.07069176e-02 2.71829039e-01 -9.61469650e-01 4.07069176e-02 2.68558025e-01 -9.62391078e-01 4.07069176e-02 2.65277952e-01 -9.63297248e-01 4.07069176e-02 2.61920691e-01 -9.64218736e-01 4.07069176e-02 2.58539885e-01 -9.65127230e-01 4.07069176e-02 2.55184382e-01 -9.66020823e-01 4.07069176e-02 2.51825035e-01 -9.66903925e-01 4.07069176e-02 2.48371199e-01 -9.67794836e-01 4.07069176e-02 2.44981408e-01 -9.68658388e-01 4.07069176e-02 2.41625160e-01 -9.69500005e-01 4.07069176e-02 2.38205567e-01 -9.70348775e-01 4.07069176e-02 2.34896734e-01 -9.71154988e-01 4.07069176e-02 2.31434166e-01 -9.71986711e-01 4.07069176e-02 2.28038266e-01 -9.72787797e-01 4.07069176e-02 2.24640459e-01 -9.73576486e-01 4.07069176e-02 2.21152097e-01 -9.74375010e-01 4.07069176e-02 2.17852995e-01 -9.75119710e-01 4.07069176e-02 2.14541465e-01 -9.75850940e-01 4.07069176e-02 2.11138234e-01 -9.76593792e-01 4.07069176e-02 2.07729757e-01 -9.77323949e-01 4.07069176e-02 2.04205275e-01 -9.78068113e-01 4.07069176e-02 2.00777560e-01 -9.78778660e-01 4.07069214e-02 1.97458938e-01 -9.79452193e-01 4.07069176e-02 1.94063127e-01 -9.80129957e-01 4.07069176e-02 1.90618262e-01 -9.80806530e-01 4.07069176e-02 1.87090829e-01 -9.81483459e-01 4.07069176e-02 1.83675379e-01 -9.82130826e-01 4.07069214e-02 1.80228814e-01 -9.82765198e-01 4.07069176e-02 1.76777408e-01 -9.83401120e-01 4.07069176e-02 1.73443839e-01 -9.83992338e-01 4.07069176e-02 1.70030698e-01 -9.84581590e-01 4.07069176e-02 1.66579291e-01 -9.85173941e-01 4.07069176e-02 1.63041070e-01 -9.85763907e-01 4.07069176e-02 1.59601107e-01 -9.86328781e-01 4.07069214e-02 1.56260148e-01 -9.86864030e-01 4.07069176e-02 1.52825743e-01 -9.87401009e-01 4.07069176e-02 1.49364576e-01 -9.87928629e-01 4.07069176e-02 1.45822346e-01 -9.88458812e-01 4.07069176e-02 1.42372906e-01 -9.88962054e-01 4.07069176e-02 1.38925374e-01 -9.89452541e-01 4.07069176e-02 1.35351166e-01 -9.89948869e-01 4.07069176e-02 1.31979913e-01 -9.90401924e-01 4.07069214e-02 1.28654361e-01 -9.90839899e-01 4.07069176e-02 1.25179961e-01 -9.91286635e-01 4.07069176e-02 1.21730193e-01 -9.91714537e-01 4.07069176e-02 1.18173972e-01 -9.92143214e-01 4.07069176e-02 1.14687748e-01 -9.92553055e-01 4.07069176e-02 1.11353412e-01 -9.92932975e-01 4.07069176e-02 1.07892215e-01 -9.93314207e-01 4.07069176e-02 1.04425177e-01 -9.93684411e-01 4.07069176e-02 1.00839786e-01 -9.94053245e-01 4.07069176e-02 9.73449424e-02 -9.94404912e-01 4.07069176e-02 9.39146355e-02 -9.94734287e-01 4.07069176e-02 9.04337317e-02 -9.95056450e-01 4.07069176e-02 8.69430825e-02 -9.95367229e-01 4.07069176e-02 8.33722278e-02 -9.95671690e-01 4.07069176e-02 7.99747482e-02 -9.95953381e-01 4.07069214e-02 7.65157565e-02 -9.96222675e-01 4.07069176e-02 7.30134547e-02 -9.96486187e-01 4.07069176e-02 6.96352646e-02 -9.96725559e-01 4.07069176e-02 6.61810338e-02 -9.96962726e-01 4.07069176e-02 6.26999736e-02 -9.97187436e-01 4.07069176e-02 5.91111481e-02 -9.97406185e-01 4.07069176e-02 5.56341261e-02 -9.97608781e-01 4.07069176e-02 5.21525070e-02 -9.97793794e-01 4.07069176e-02 4.86593470e-02 -9.97972906e-01 4.07069176e-02 4.52021398e-02 -9.98133004e-01 4.07069176e-02 4.15994748e-02 -9.98291254e-01 4.07069176e-02 3.82132381e-02 -9.98426497e-01 4.07069214e-02 3.48298326e-02 -9.98549461e-01 4.07069176e-02 3.12591568e-02 -9.98666644e-01 4.07069176e-02 2.77573783e-02 -9.98772681e-01 4.07069176e-02 2.42805928e-02 -9.98863876e-01 4.07069176e-02 2.07802132e-02 -9.98939276e-01 4.07069176e-02 1.73873715e-02 -9.99010324e-01 4.07069176e-02 1.38429217e-02 -9.99054492e-01 4.07069176e-02 1.03179412e-02 -9.99104917e-01 4.07069176e-02 6.92418125e-03 -9.99139905e-01 4.07069176e-02 3.43944971e-03 -9.99156415e-01 4.07069176e-02 -2.53111557e-05 -9.99157727e-01 4.07069176e-02 -3.49684595e-03 -9.99156237e-01 4.07069176e-02 -6.99954573e-03 -9.99139369e-01 4.07069176e-02 -1.05707552e-02 -9.99102116e-01 4.07069176e-02 -1.40728978e-02 -9.99054492e-01 4.07069176e-02 -1.75536387e-02 -9.99008119e-01 4.07069176e-02 -2.11475156e-02 -9.98931050e-01 4.07069176e-02 -2.45551709e-02 -9.98857796e-01 4.07069176e-02 -2.79233940e-02 -9.98767853e-01 4.07069176e-02 -3.13994512e-02 -9.98663962e-01 4.07069176e-02 -3.49787325e-02 -9.98543978e-01 4.07069176e-02 -3.85873280e-02 -9.98412549e-01 4.07069176e-02 -4.19776142e-02 -9.98276889e-01 4.07069176e-02 -4.53514270e-02 -9.98126864e-01 4.07069176e-02 -4.88564335e-02 -9.97962356e-01 4.07069176e-02 -5.23289964e-02 -9.97784376e-01 4.07069176e-02 -5.58913238e-02 -9.97592568e-01 4.07069176e-02 -5.93975857e-02 -9.97391164e-01 4.07069176e-02 -6.28420860e-02 -9.97176886e-01 4.07069176e-02 -6.63454831e-02 -9.96951580e-01 4.07069176e-02 -6.97410926e-02 -9.96717989e-01 4.07069176e-02 -7.33072907e-02 -9.96462882e-01 4.07069176e-02 -7.67974779e-02 -9.96201575e-01 4.07069176e-02 -8.02449510e-02 -9.95929122e-01 4.07069176e-02 -8.37336630e-02 -9.95641887e-01 4.07069176e-02 -8.71270150e-02 -9.95350838e-01 4.07069176e-02 -9.06108320e-02 -9.95038986e-01 4.07069176e-02 -9.40674096e-02 -9.94719386e-01 4.07069176e-02 -9.76205841e-02 -9.94377434e-01 4.07069176e-02 -1.01095401e-01 -9.94031310e-01 4.07069176e-02 -1.04541808e-01 -9.93672371e-01 4.07069176e-02 -1.08093515e-01 -9.93292093e-01 4.07069176e-02 -1.11484982e-01 -9.92919266e-01 4.07069176e-02 -1.14869229e-01 -9.92532074e-01 4.07069176e-02 -1.18324660e-01 -9.92124617e-01 4.07069176e-02 -1.21789940e-01 -9.91705477e-01 4.07069176e-02 -1.25337943e-01 -9.91265416e-01 4.07069176e-02 -1.28814146e-01 -9.90818739e-01 4.07069176e-02 -1.32172659e-01 -9.90376592e-01 4.07069176e-02 -1.35628387e-01 -9.89908814e-01 4.07069176e-02 -1.39079303e-01 -9.89431262e-01 4.07069176e-02 -1.42621651e-01 -9.88925576e-01 4.07069176e-02 -1.46072760e-01 -9.88421500e-01 4.07069176e-02 -1.49519607e-01 -9.87904310e-01 4.07069176e-02 -1.52946219e-01 -9.87382293e-01 4.07069176e-02 -1.56301633e-01 -9.86855149e-01 4.07069176e-02 -1.59755155e-01 -9.86302614e-01 4.07069176e-02 -1.63185343e-01 -9.85741913e-01 4.07069176e-02 -1.66742831e-01 -9.85144675e-01 4.07069176e-02 -1.70181394e-01 -9.84556556e-01 4.07069176e-02 -1.73514843e-01 -9.83979404e-01 4.07069176e-02 -1.76959157e-01 -9.83363926e-01 4.07069176e-02 -1.80385977e-01 -9.82736647e-01 4.07069176e-02 -1.83906659e-01 -9.82087135e-01 4.07069176e-02 -1.87346876e-01 -9.81436372e-01 4.07069176e-02 -1.90674976e-01 -9.80792820e-01 4.07069176e-02 -1.94080546e-01 -9.80126619e-01 4.07069176e-02 -1.97588176e-01 -9.79425132e-01 4.07069176e-02 -2.01015636e-01 -9.78728116e-01 4.07069176e-02 -2.04334602e-01 -9.78039563e-01 4.07069176e-02 -2.07759708e-01 -9.77319002e-01 4.07069176e-02 -2.11251765e-01 -9.76569295e-01 4.07069176e-02 -2.14677826e-01 -9.75820720e-01 4.07069176e-02 -2.17971772e-01 -9.75092709e-01 4.07069176e-02 -2.21386492e-01 -9.74321306e-01 4.07069176e-02 -2.24807516e-01 -9.73537147e-01 4.07069176e-02 -2.28293747e-01 -9.72728610e-01 4.07069176e-02 -2.31705487e-01 -9.71922159e-01 4.07069176e-02 -2.34972060e-01 -9.71136808e-01 4.07069176e-02 -2.38368943e-01 -9.70307350e-01 4.07069176e-02 -2.41771072e-01 -9.69463885e-01 4.07069176e-02 -2.45180532e-01 -9.68605936e-01 4.07069176e-02 -2.48603716e-01 -9.67736244e-01 4.07069176e-02 -2.52003551e-01 -9.66854095e-01 4.07069176e-02 -2.55379677e-01 -9.65971529e-01 4.07069176e-02 -2.58726180e-01 -9.65078354e-01 4.07069176e-02 -2.62186408e-01 -9.64145362e-01 4.07069176e-02 -2.65476227e-01 -9.63243723e-01 4.07069176e-02 -2.68831670e-01 -9.62312043e-01 4.07069176e-02 -2.72193134e-01 -9.61368084e-01 4.07069214e-02 -2.75445074e-01 -9.60439980e-01 4.07069176e-02 -2.78791755e-01 -9.59474027e-01 4.07069176e-02 -2.82137424e-01 -9.58495319e-01 4.07069176e-02 -2.85468906e-01 -9.57509935e-01 4.07069176e-02 -2.88813800e-01 -9.56503153e-01 4.07069176e-02 -2.92168468e-01 -9.55483973e-01 4.07069176e-02 -2.95582265e-01 -9.54435885e-01 4.07069176e-02 -2.98908800e-01 -9.53398705e-01 4.07069214e-02 -3.02238107e-01 -9.52348053e-01 4.07069176e-02 -3.05562109e-01 -9.51289535e-01 4.07069176e-02 -3.08795720e-01 -9.50242102e-01 4.07069176e-02 -3.12216252e-01 -9.49123025e-01 4.07069176e-02 -3.15507084e-01 -9.48035538e-01 4.07069176e-02 -3.18820387e-01 -9.46927190e-01 4.07069176e-02 -3.22119534e-01 -9.45809603e-01 4.07069176e-02 -3.25335443e-01 -9.44708347e-01 4.07069176e-02 -3.28666478e-01 -9.43551958e-01 4.07069176e-02 -3.31976742e-01 -9.42396224e-01 4.07069176e-02 -3.35285187e-01 -9.41221714e-01 4.07069176e-02 -3.38591695e-01 -9.40037072e-01 4.07069176e-02 -3.41842264e-01 -9.38862801e-01 4.07069176e-02 -3.45128357e-01 -9.37651694e-01 4.07069176e-02 -3.48320454e-01 -9.36466396e-01 4.07069176e-02 -3.51647466e-01 -9.35223937e-01 4.07069176e-02 -3.54890108e-01 -9.34002578e-01 4.07069176e-02 -3.58155876e-01 -9.32763159e-01 4.07069176e-02 -3.61513585e-01 -9.31459248e-01 4.07069176e-02 -3.64675403e-01 -9.30230737e-01 4.07069176e-02 -3.67847949e-01 -9.28979993e-01 4.07069176e-02 -3.71075988e-01 -9.27693784e-01 4.07069176e-02 -3.74321997e-01 -9.26389396e-01 4.07069176e-02 -3.77629012e-01 -9.25045252e-01 4.07069176e-02 -3.80867451e-01 -9.23715591e-01 4.07069176e-02 -3.84012908e-01 -9.22415257e-01 4.07069176e-02 -3.87214243e-01 -9.21074986e-01 4.07069176e-02 -3.90411258e-01 -9.19723332e-01 4.07069176e-02 -3.93715233e-01 -9.18312848e-01 4.07069176e-02 -3.96911800e-01 -9.16937888e-01 4.07069214e-02 -4.00102735e-01 -9.15551662e-01 4.07069176e-02 -4.03336257e-01 -9.14131761e-01 4.07069176e-02 -4.06431049e-01 -9.12759304e-01 4.07069176e-02 -4.09690440e-01 -9.11301076e-01 4.07069176e-02 -4.12880778e-01 -9.09859776e-01 4.07069214e-02 -4.16020095e-01 -9.08424437e-01 4.07069176e-02 -4.19193864e-01 -9.06967819e-01 4.07069176e-02 -4.22277331e-01 -9.05536711e-01 4.07069176e-02 -4.25442547e-01 -9.04053628e-01 4.07069176e-02 -4.28678721e-01 -9.02524292e-01 4.07069176e-02 -4.31827813e-01 -9.01020944e-01 4.07069214e-02 -4.34887469e-01 -8.99551094e-01 4.07069176e-02 -4.38105345e-01 -8.97987008e-01 4.07069176e-02 -4.41325128e-01 -8.96408081e-01 4.07069176e-02 -4.44381595e-01 -8.94897997e-01 4.07069176e-02 -4.47415531e-01 -8.93384516e-01 4.07069176e-02 -4.50511098e-01 -8.91827643e-01 4.07069176e-02 -4.53641564e-01 -8.90239239e-01 4.07069176e-02 -4.56818789e-01 -8.88610959e-01 4.07069176e-02 -4.59916681e-01 -8.87012780e-01 4.07069214e-02 -4.62904930e-01 -8.85458767e-01 4.07069176e-02 -4.66023535e-01 -8.83820534e-01 4.07069176e-02 -4.69096333e-01 -8.82192016e-01 4.07069176e-02 -4.72252339e-01 -8.80507588e-01 4.07069176e-02 -4.75323230e-01 -8.78853023e-01 4.07069176e-02 -4.78363901e-01 -8.77203763e-01 4.07069176e-02 -4.81444567e-01 -8.75516534e-01 4.07069214e-02 -4.84506696e-01 -8.73821795e-01 4.07069176e-02 -4.87618029e-01 -8.72090578e-01 4.07069176e-02 -4.90573257e-01 -8.70434523e-01 4.07069176e-02 -4.93614674e-01 -8.68710637e-01 4.07069176e-02 -4.96633232e-01 -8.66992235e-01 4.07069176e-02 -4.99593168e-01 -8.65287542e-01 4.07069176e-02 -5.02675414e-01 -8.63499880e-01 4.07069176e-02 -5.05710483e-01 -8.61728907e-01 4.07069214e-02 -5.08695126e-01 -8.59967828e-01 4.07069176e-02 -5.11703908e-01 -8.58181357e-01 4.07069214e-02 -5.14674425e-01 -8.56401980e-01 4.07069176e-02 -5.17673612e-01 -8.54593396e-01 4.07069176e-02 -5.20659208e-01 -8.52779508e-01 4.07069176e-02 -5.23723781e-01 -8.50898325e-01 4.07069176e-02 -5.26619434e-01 -8.49111199e-01 4.07069214e-02 -5.29472709e-01 -8.47333610e-01 4.07069176e-02 -5.32520711e-01 -8.45419943e-01 4.07069176e-02 -5.35546660e-01 -8.43507051e-01 4.07069176e-02 -5.38484752e-01 -8.41634870e-01 4.07069176e-02 -5.41346431e-01 -8.39797556e-01 4.07069214e-02 -5.44210494e-01 -8.37944388e-01 4.07069176e-02 -5.47135234e-01 -8.36035192e-01 4.07069176e-02 -5.50031483e-01 -8.34135950e-01 4.07069176e-02 -5.52934110e-01 -8.32211792e-01 4.07069176e-02 -5.55823088e-01 -8.30286562e-01 4.07069176e-02 -5.58802366e-01 -8.28285515e-01 4.07069176e-02 -5.61735034e-01 -8.26298356e-01 4.07069176e-02 -5.64532936e-01 -8.24391603e-01 4.07069176e-02 -5.67444444e-01 -8.22387636e-01 4.07069176e-02 -5.70316494e-01 -8.20401549e-01 4.07069176e-02 -5.73177338e-01 -8.18401098e-01 4.07069176e-02 -5.76125443e-01 -8.16331685e-01 4.07069176e-02 -5.78887880e-01 -8.14375341e-01 4.07069214e-02 -5.81680775e-01 -8.12380910e-01 4.07069176e-02 -5.84515154e-01 -8.10341239e-01 4.07069176e-02 -5.87349534e-01 -8.08292210e-01 4.07069176e-02 -5.90241492e-01 -8.06181550e-01 4.07069176e-02 -5.93095660e-01 -8.04084063e-01 4.07069176e-02 -5.95825016e-01 -8.02065849e-01 4.07069214e-02 -5.98525763e-01 -8.00049305e-01 4.07069176e-02 -6.01319253e-01 -7.97953248e-01 4.07069176e-02 -6.04170918e-01 -7.95798004e-01 4.07069176e-02 -6.06954277e-01 -7.93677032e-01 4.07069176e-02 -6.09718382e-01 -7.91552186e-01 4.07069176e-02 -6.12491369e-01 -7.89412081e-01 4.07069176e-02 -6.15151882e-01 -7.87338316e-01 4.07069176e-02 -6.17977619e-01 -7.85123467e-01 4.07069176e-02 -6.20725155e-01 -7.82953024e-01 4.07069176e-02 -6.23458207e-01 -7.80777931e-01 4.07069176e-02 -6.26196861e-01 -7.78584838e-01 4.07069176e-02 -6.28821969e-01 -7.76466310e-01 4.07069176e-02 -6.31596744e-01 -7.74208426e-01 4.07069176e-02 -6.34307325e-01 -7.71992028e-01 4.07069214e-02 -6.36928022e-01 -7.69829929e-01 4.07069176e-02 -6.39604211e-01 -7.67607868e-01 4.07069176e-02 -6.42324626e-01 -7.65331328e-01 4.07069176e-02 -6.45069420e-01 -7.63021171e-01 4.07069176e-02 -6.47681773e-01 -7.60803461e-01 4.07069176e-02 -6.50254011e-01 -7.58606791e-01 4.07069176e-02 -6.52902067e-01 -7.56331086e-01 4.07069176e-02 -6.55599952e-01 -7.53991485e-01 4.07069176e-02 -6.58297420e-01 -7.51637399e-01 4.07069176e-02 -6.60854459e-01 -7.49392331e-01 4.07069214e-02 -6.63398921e-01 -7.47140825e-01 4.07069176e-02 -6.66001856e-01 -7.44819820e-01 4.07069176e-02 -6.68587267e-01 -7.42499709e-01 4.07069176e-02 -6.71250939e-01 -7.40093589e-01 4.07069176e-02 -6.73853278e-01 -7.37724304e-01 4.07069176e-02 -6.76402390e-01 -7.35389650e-01 4.07069176e-02 -6.78959548e-01 -7.33028710e-01 4.07069176e-02 -6.81494951e-01 -7.30669618e-01 4.07069176e-02 -6.84128821e-01 -7.28204548e-01 4.07069176e-02 -6.86602831e-01 -7.25872338e-01 4.07069176e-02 -6.89118743e-01 -7.23486781e-01 4.07069176e-02 -6.91657186e-01 -7.21054614e-01 4.07069214e-02 -6.94112718e-01 -7.18704522e-01 4.07069176e-02 -6.96636081e-01 -7.16256380e-01 4.07069176e-02 -6.99128687e-01 -7.13820517e-01 4.07069176e-02 -7.01578438e-01 -7.11414814e-01 4.07069176e-02 -7.04051137e-01 -7.08969235e-01 4.07069176e-02 -7.06573009e-01 -7.06435382e-01 4.07069176e-02 -7.09050119e-01 -7.03971744e-01 4.07069176e-02 -7.11511672e-01 -7.01479077e-01 4.07069176e-02 -7.13961780e-01 -6.98984504e-01 4.07069176e-02 -7.16332793e-01 -6.96556747e-01 4.07069176e-02 -7.18779922e-01 -6.94034338e-01 4.07069176e-02 -7.21247852e-01 -6.91452444e-01 4.07069176e-02 -7.23668158e-01 -6.88930452e-01 4.07069176e-02 -7.26066649e-01 -6.86395884e-01 4.07069176e-02 -7.28431523e-01 -6.83887124e-01 4.07069214e-02 -7.30731845e-01 -6.81427300e-01 4.07069176e-02 -7.33161807e-01 -6.78815067e-01 4.07069176e-02 -7.35598087e-01 -6.76175952e-01 4.07069176e-02 -7.37917781e-01 -6.73642218e-01 4.07069214e-02 -7.40174651e-01 -6.71161294e-01 4.07069176e-02 -7.42524028e-01 -6.68562174e-01 4.07069176e-02 -7.44924247e-01 -6.65883720e-01 4.07069176e-02 -7.47259915e-01 -6.63265586e-01 4.07069214e-02 -7.49555230e-01 -6.60665989e-01 4.07069176e-02 -7.51849294e-01 -6.58055842e-01 4.07069176e-02 -7.54139662e-01 -6.55428350e-01 4.07069176e-02 -7.56487906e-01 -6.52717829e-01 4.07069176e-02 -7.58712769e-01 -6.50132298e-01 4.07069176e-02 -7.60914385e-01 -6.47550464e-01 4.07069176e-02 -7.63168573e-01 -6.44897044e-01 4.07069176e-02 -7.65456259e-01 -6.42176807e-01 4.07069176e-02 -7.67746270e-01 -6.39440238e-01 4.07069176e-02 -7.69949675e-01 -6.36782229e-01 4.07069176e-02 -7.72105515e-01 -6.34171247e-01 4.07069176e-02 -7.74325490e-01 -6.31453454e-01 4.07069176e-02 -7.76514709e-01 -6.28761053e-01 4.07069176e-02 -7.78760493e-01 -6.25976741e-01 4.07069176e-02 -7.81012535e-01 -6.23165607e-01 4.07069176e-02 -7.83176064e-01 -6.20444238e-01 4.07069176e-02 -7.85278559e-01 -6.17782176e-01 4.07069176e-02 -7.87361562e-01 -6.15125239e-01 4.07069176e-02 -7.89568365e-01 -6.12287521e-01 4.07069176e-02 -7.91745067e-01 -6.09472871e-01 4.07069176e-02 -7.93868601e-01 -6.06702447e-01 4.07069176e-02 -7.95948684e-01 -6.03972316e-01 4.07069214e-02 -7.97986805e-01 -6.01278424e-01 4.07069176e-02 -8.00133824e-01 -5.98413467e-01 4.07069176e-02 -8.02227855e-01 -5.95606387e-01 4.07069176e-02 -8.04248810e-01 -5.92871130e-01 4.07069176e-02 -8.06319952e-01 -5.90053201e-01 4.07069176e-02 -8.08394372e-01 -5.87207496e-01 4.07069176e-02 -8.10483754e-01 -5.84318459e-01 4.07069176e-02 -8.12497973e-01 -5.81519008e-01 4.07069176e-02 -8.14470172e-01 -5.78752458e-01 4.07069176e-02 -8.16483676e-01 -5.75911343e-01 4.07069176e-02 -8.18510234e-01 -5.73022544e-01 4.07069176e-02 -8.20541918e-01 -5.70109248e-01 4.07069176e-02 -8.22519481e-01 -5.67257404e-01 4.07069176e-02 -8.24444532e-01 -5.64453185e-01 4.07069176e-02 -8.26392055e-01 -5.61598063e-01 4.07069176e-02 -8.28342974e-01 -5.58717906e-01 4.07069176e-02 -8.30345273e-01 -5.55732846e-01 4.07069176e-02 -8.32289100e-01 -5.52819014e-01 4.07069176e-02 -8.34213257e-01 -5.49910009e-01 4.07069176e-02 -8.36140513e-01 -5.46977580e-01 4.07069214e-02 -8.37974668e-01 -5.44162512e-01 4.07069176e-02 -8.39870751e-01 -5.41232526e-01 4.07069176e-02 -8.41799378e-01 -5.38224339e-01 4.07069176e-02 -8.43702793e-01 -5.35238743e-01 4.07069176e-02 -8.45513165e-01 -5.32378137e-01 4.07069176e-02 -8.47331524e-01 -5.29473186e-01 4.07069176e-02 -8.49196017e-01 -5.26482880e-01 4.07069176e-02 -8.51027429e-01 -5.23512542e-01 4.07069176e-02 -8.52851689e-01 -5.20541430e-01 4.07069176e-02 -8.54665220e-01 -5.17553747e-01 4.07069176e-02 -8.56513441e-01 -5.14490366e-01 4.07069176e-02 -8.58357131e-01 -5.11406064e-01 4.07069176e-02 -8.60094011e-01 -5.08480787e-01 4.07069176e-02 -8.61855686e-01 -5.05488157e-01 4.07069176e-02 -8.63617420e-01 -5.02473831e-01 4.07069176e-02 -8.65349829e-01 -4.99485403e-01 4.07069176e-02 -8.67070735e-01 -4.96492237e-01 4.07069176e-02 -8.68770063e-01 -4.93510127e-01 4.07069176e-02 -8.70487154e-01 -4.90481794e-01 4.07069176e-02 -8.72200251e-01 -4.87422049e-01 4.07069176e-02 -8.73890877e-01 -4.84381944e-01 4.07069176e-02 -8.75614285e-01 -4.81264174e-01 4.07069176e-02 -8.77314627e-01 -4.78162289e-01 4.07069176e-02 -8.78950834e-01 -4.75142986e-01 4.07069176e-02 -8.80573630e-01 -4.72128928e-01 4.07069176e-02 -8.82243931e-01 -4.68997538e-01 4.07069176e-02 -8.83926690e-01 -4.65820014e-01 4.07069176e-02 -8.85532856e-01 -4.62763488e-01 4.07069176e-02 -8.87102008e-01 -4.59742665e-01 4.07069176e-02 -8.88665080e-01 -4.56717998e-01 4.07069176e-02 -8.90291512e-01 -4.53535050e-01 4.07069176e-02 -8.91925156e-01 -4.50316638e-01 4.07069176e-02 -8.93448949e-01 -4.47286397e-01 4.07069176e-02 -8.94950986e-01 -4.44272906e-01 4.07069176e-02 -8.96485567e-01 -4.41167712e-01 4.07069176e-02 -8.98025692e-01 -4.38025534e-01 4.07069176e-02 -8.99597168e-01 -4.34787035e-01 4.07069176e-02 -9.01158094e-01 -4.31540400e-01 4.07069176e-02 -9.02630568e-01 -4.28455144e-01 4.07069176e-02 -9.04071629e-01 -4.25401211e-01 4.07069176e-02 -9.05542552e-01 -4.22264069e-01 4.07069176e-02 -9.07055020e-01 -4.19006199e-01 4.07069176e-02 -9.08540547e-01 -4.15776730e-01 4.07069176e-02 -9.09938395e-01 -4.12710428e-01 4.07069176e-02 -9.11350846e-01 -4.09577727e-01 4.07069176e-02 -9.12775338e-01 -4.06397909e-01 4.07069176e-02 -9.14237797e-01 -4.03093129e-01 4.07069176e-02 -9.15685117e-01 -3.99799317e-01 4.07069176e-02 -9.17068422e-01 -3.96614522e-01 4.07069176e-02 -9.18448925e-01 -3.93394142e-01 4.07069176e-02 -9.19782639e-01 -3.90276074e-01 4.07069176e-02 -9.21099126e-01 -3.87157053e-01 4.07069176e-02 -9.22452271e-01 -3.83921057e-01 4.07069176e-02 -9.23819840e-01 -3.80614966e-01 4.07069176e-02 -9.25142050e-01 -3.77397835e-01 4.07069176e-02 -9.26416337e-01 -3.74256372e-01 4.07069176e-02 -9.27750468e-01 -3.70932877e-01 4.07069176e-02 -9.29046869e-01 -3.67681026e-01 4.07069176e-02 -9.30288792e-01 -3.64528030e-01 4.07069176e-02 -9.31551099e-01 -3.61273915e-01 4.07069176e-02 -9.32819486e-01 -3.58007789e-01 4.07069176e-02 -9.34090078e-01 -3.54662031e-01 4.07069176e-02 -9.35309470e-01 -3.51419419e-01 4.07069176e-02 -9.36498940e-01 -3.48235577e-01 4.07069176e-02 -9.37747836e-01 -3.44869167e-01 4.07069176e-02 -9.38989878e-01 -3.41491163e-01 4.07069176e-02 -9.40163851e-01 -3.38236451e-01 4.07069176e-02 -9.41309750e-01 -3.35045248e-01 4.07069176e-02 -9.42470193e-01 -3.31758052e-01 4.07069176e-02 -9.43630815e-01 -3.28444660e-01 4.07069176e-02 -9.44736004e-01 -3.25255454e-01 4.07069176e-02 -9.45862234e-01 -3.21958125e-01 4.07069176e-02 -9.46985006e-01 -3.18646550e-01 4.07069176e-02 -9.48126316e-01 -3.15229803e-01 4.07069176e-02 -9.49225724e-01 -3.11909467e-01 4.07069176e-02 -9.50271845e-01 -3.08706969e-01 4.07069176e-02 -9.51366425e-01 -3.05311501e-01 4.07069176e-02 -9.52430487e-01 -3.01979929e-01 4.07069176e-02 -9.53470528e-01 -2.98682541e-01 4.07069176e-02 -9.54510629e-01 -2.95340538e-01 4.07069176e-02 -9.55538094e-01 -2.91994721e-01 4.07069176e-02 -9.56574380e-01 -2.88581401e-01 4.07069176e-02 -9.57555413e-01 -2.85313189e-01 4.07069176e-02 -9.58537996e-01 -2.81993210e-01 4.07069176e-02 -9.59522247e-01 -2.78630704e-01 4.07069176e-02 -9.60484266e-01 -2.75285423e-01 4.07069176e-02 -9.61440265e-01 -2.71935225e-01 4.07069176e-02 -9.62365806e-01 -2.68643111e-01 4.07069176e-02 -9.63294685e-01 -2.65290707e-01 4.07069176e-02 -9.64216173e-01 -2.61926323e-01 4.07069176e-02 -9.65144575e-01 -2.58476228e-01 4.07069176e-02 -9.66069758e-01 -2.55003899e-01 4.07069176e-02 -9.66953158e-01 -2.51628220e-01 4.07069176e-02 -9.67803597e-01 -2.48349562e-01 4.07069214e-02 -9.68629122e-01 -2.45093226e-01 4.07069176e-02 -9.69502985e-01 -2.41609380e-01 4.07069176e-02 -9.70371664e-01 -2.38111913e-01 4.07069176e-02 -9.71196711e-01 -2.34729275e-01 4.07069176e-02 -9.71988022e-01 -2.31431708e-01 4.07069176e-02 -9.72765923e-01 -2.28134319e-01 4.07069176e-02 -9.73569393e-01 -2.24666595e-01 4.07069176e-02 -9.74379599e-01 -2.21132159e-01 4.07069176e-02 -9.75125909e-01 -2.17824832e-01 4.07069176e-02 -9.75874424e-01 -2.14436248e-01 4.07069176e-02 -9.76622999e-01 -2.11007878e-01 4.07069214e-02 -9.77326334e-01 -2.07722485e-01 4.07069176e-02 -9.78066742e-01 -2.04212502e-01 4.07069176e-02 -9.78798687e-01 -2.00675294e-01 4.07069176e-02 -9.79475617e-01 -1.97345316e-01 4.07069176e-02 -9.80137050e-01 -1.94026604e-01 4.07069176e-02 -9.80808437e-01 -1.90609366e-01 4.07069176e-02 -9.81480598e-01 -1.87107027e-01 4.07069176e-02 -9.82153952e-01 -1.83553413e-01 4.07069176e-02 -9.82768357e-01 -1.80221751e-01 4.07069176e-02 -9.83378232e-01 -1.76894024e-01 4.07069176e-02 -9.83990431e-01 -1.73451155e-01 4.07069176e-02 -9.84597981e-01 -1.69932321e-01 4.07069176e-02 -9.85202074e-01 -1.66410059e-01 4.07069176e-02 -9.85761642e-01 -1.63070753e-01 4.07069176e-02 -9.86326754e-01 -1.59610361e-01 4.07069176e-02 -9.86878157e-01 -1.56174034e-01 4.07069214e-02 -9.87412214e-01 -1.52742729e-01 4.07069176e-02 -9.87940371e-01 -1.49294510e-01 4.07069176e-02 -9.88453686e-01 -1.45855799e-01 4.07069176e-02 -9.88960564e-01 -1.42387301e-01 4.07069176e-02 -9.89437044e-01 -1.39036313e-01 4.07069176e-02 -9.89927471e-01 -1.35502577e-01 4.07069176e-02 -9.90396440e-01 -1.32023826e-01 4.07069176e-02 -9.90847886e-01 -1.28585503e-01 4.07069176e-02 -9.91294563e-01 -1.25123426e-01 4.07069214e-02 -9.91712451e-01 -1.21746913e-01 4.07069176e-02 -9.92140591e-01 -1.18195064e-01 4.07069176e-02 -9.92547035e-01 -1.14737518e-01 4.07069214e-02 -9.92931128e-01 -1.11368775e-01 4.07069176e-02 -9.93324280e-01 -1.07789584e-01 4.07069176e-02 -9.93706822e-01 -1.04225047e-01 4.07069176e-02 -9.94058907e-01 -1.00814812e-01 4.07069214e-02 -9.94396865e-01 -9.74389687e-02 4.07069772e-02 -9.94729698e-01 -9.39892083e-02 4.07069810e-02 -9.95059013e-01 -9.04781073e-02 4.07070592e-02 -9.95359004e-01 -8.71185586e-02 4.07070629e-02 -9.95658576e-01 -8.36419389e-02 4.07070667e-02 -9.95948553e-01 -8.01419541e-02 4.07070853e-02 -9.96228039e-01 -7.65795112e-02 4.07071076e-02 -9.96493995e-01 -7.31236264e-02 4.07072753e-02 -9.96728897e-01 -6.98533133e-02 4.07073796e-02 -9.96969104e-01 -6.63162246e-02 4.07072976e-02 -9.97195184e-01 -6.27798885e-02 4.07072604e-02 -9.97406363e-01 -5.93547747e-02 4.07072641e-02 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. 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. 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. 0. 0. 0. -9.97204304e-01 4.69396822e-02 5.81390262e-02 -9.97056067e-01 4.99852933e-02 5.81390262e-02 -9.96917605e-01 5.27940877e-02 5.81393205e-02 -9.96734381e-01 5.59923127e-02 5.81394657e-02 -9.96533275e-01 5.94251230e-02 5.81395105e-02 -9.96319056e-01 6.28973097e-02 5.81395365e-02 -9.96090293e-01 6.63928762e-02 5.81395738e-02 -9.95856345e-01 6.97930306e-02 5.81395738e-02 -9.95615780e-01 7.31552243e-02 5.81393391e-02 -9.95348334e-01 7.67078623e-02 5.81391864e-02 -9.95066881e-01 8.02802518e-02 5.81393018e-02 -9.94789183e-01 8.36546645e-02 5.81394285e-02 -9.94492114e-01 8.71077552e-02 5.81391156e-02 -9.94173765e-01 9.06741619e-02 5.81392720e-02 -9.93856788e-01 9.40921083e-02 5.81393205e-02 -9.93519962e-01 9.75752473e-02 5.81391789e-02 -9.93181050e-01 1.00986369e-01 5.81394210e-02 -9.92833018e-01 1.04342565e-01 5.81393465e-02 -9.92451251e-01 1.07894354e-01 5.81390746e-02 -9.92057562e-01 1.11476891e-01 5.81392683e-02 -9.91657913e-01 1.14962541e-01 5.81392497e-02 -9.91250157e-01 1.18421145e-01 5.81392311e-02 -9.90835547e-01 1.21854067e-01 5.81393167e-02 -9.90408421e-01 1.25290811e-01 5.81393018e-02 -9.89961147e-01 1.28764600e-01 5.81392236e-02 -9.89496350e-01 1.32280618e-01 5.81392050e-02 -9.89045143e-01 1.35631278e-01 5.81395179e-02 -9.88586605e-01 1.38931170e-01 5.81392609e-02 -9.88078296e-01 1.42485991e-01 5.81390448e-02 -9.87558067e-01 1.46049410e-01 5.81393167e-02 -9.87043202e-01 1.49483591e-01 5.81392199e-02 -9.86514866e-01 1.52942315e-01 5.81392460e-02 -9.85975444e-01 1.56387374e-01 5.81392720e-02 -9.85437632e-01 1.59741819e-01 5.81395216e-02 -9.84875202e-01 1.63170978e-01 5.81390783e-02 -9.84278262e-01 1.66733682e-01 5.81392534e-02 -9.83707428e-01 1.70070648e-01 5.81394434e-02 -9.83111918e-01 1.73493013e-01 5.81390969e-02 -9.82481420e-01 1.77029610e-01 5.81391864e-02 -9.81851995e-01 1.80460140e-01 5.81392311e-02 -9.81217325e-01 1.83891758e-01 5.81392236e-02 -9.80586648e-01 1.87224239e-01 5.81394434e-02 -9.79951560e-01 1.90513253e-01 5.81392013e-02 -9.79258478e-01 1.94047585e-01 5.81389964e-02 -9.78551924e-01 1.97585985e-01 5.81391789e-02 -9.77853417e-01 2.01012969e-01 5.81391789e-02 -9.77168620e-01 2.04318613e-01 5.81394695e-02 -9.76450086e-01 2.07727522e-01 5.81390336e-02 -9.75697100e-01 2.11235821e-01 5.81392460e-02 -9.74970102e-01 2.14557335e-01 5.81394173e-02 -9.74227130e-01 2.17914313e-01 5.81390671e-02 -9.73450959e-01 2.21354112e-01 5.81394657e-02 -9.72695589e-01 2.24643961e-01 5.81392273e-02 -9.71889257e-01 2.28121474e-01 5.81390485e-02 -9.71059442e-01 2.31623724e-01 5.81393056e-02 -9.70256448e-01 2.34972015e-01 5.81393056e-02 -9.69425023e-01 2.38368601e-01 5.81391715e-02 -9.68581676e-01 2.41763756e-01 5.81391640e-02 -9.67751682e-01 2.45071203e-01 5.81394508e-02 -9.66894865e-01 2.48427331e-01 5.81390373e-02 -9.66001213e-01 2.51887232e-01 5.81392832e-02 -9.65137005e-01 2.55183220e-01 5.81393540e-02 -9.64238346e-01 2.58550286e-01 5.81390448e-02 -9.63315964e-01 2.61969775e-01 5.81392236e-02 -9.62393105e-01 2.65332103e-01 5.81392273e-02 -9.61460352e-01 2.68703043e-01 5.81392013e-02 -9.60533023e-01 2.71997780e-01 5.81394024e-02 -9.59588945e-01 2.75302202e-01 5.81391156e-02 -9.58613813e-01 2.78681844e-01 5.81393279e-02 -9.57644641e-01 2.81991571e-01 5.81390969e-02 -9.56625164e-01 2.85437524e-01 5.81392311e-02 -9.55645621e-01 2.88695246e-01 5.81394322e-02 -9.54631031e-01 2.92029023e-01 5.81390038e-02 -9.53579187e-01 2.95449495e-01 5.81392311e-02 -9.52548623e-01 2.98758745e-01 5.81392944e-02 -9.51497793e-01 3.02084327e-01 5.81392087e-02 -9.50460970e-01 3.05337250e-01 5.81393242e-02 -9.49422717e-01 3.08541656e-01 5.81392646e-02 -9.48311031e-01 3.11942250e-01 5.81390969e-02 -9.47182298e-01 3.15353513e-01 5.81392050e-02 -9.46071863e-01 3.18672419e-01 5.81392311e-02 -9.44960296e-01 3.21952760e-01 5.81392050e-02 -9.43831980e-01 3.25252175e-01 5.81392795e-02 -9.42709982e-01 3.28482896e-01 5.81392981e-02 -9.41557586e-01 3.31769317e-01 5.81390932e-02 -9.40372407e-01 3.35120618e-01 5.81391975e-02 -9.39225376e-01 3.38318080e-01 5.81393801e-02 -9.38076735e-01 3.41494381e-01 5.81392050e-02 -9.36846554e-01 3.44837964e-01 5.81390411e-02 -9.35598493e-01 3.48197252e-01 5.81391677e-02 -9.34368670e-01 3.51488799e-01 5.81392311e-02 -9.33154643e-01 3.54711503e-01 5.81392646e-02 -9.31953728e-01 3.57878268e-01 5.81392869e-02 -9.30701613e-01 3.61100346e-01 5.81392013e-02 -9.29411948e-01 3.64414304e-01 5.81390858e-02 -9.28105056e-01 3.67730379e-01 5.81391975e-02 -9.26851749e-01 3.70878130e-01 5.81394583e-02 -9.25559640e-01 3.74087065e-01 5.81390448e-02 -9.24212575e-01 3.77406955e-01 5.81391715e-02 -9.22895312e-01 3.80610794e-01 5.81392720e-02 -9.21567976e-01 3.83816302e-01 5.81392720e-02 -9.20252025e-01 3.86962175e-01 5.81393763e-02 -9.18928027e-01 3.90093714e-01 5.81392311e-02 -9.17521656e-01 3.93381625e-01 5.81390411e-02 -9.16101515e-01 3.96687984e-01 5.81392609e-02 -9.14725602e-01 3.99853170e-01 5.81392348e-02 -9.13318813e-01 4.03054059e-01 5.81391864e-02 -9.11903203e-01 4.06247020e-01 5.81392162e-02 -9.10485506e-01 4.09413785e-01 5.81392236e-02 -9.09087062e-01 4.12511051e-01 5.81394210e-02 -9.07645047e-01 4.15667772e-01 5.81391193e-02 -9.06160712e-01 4.18896437e-01 5.81392534e-02 -9.04716909e-01 4.22009557e-01 5.81394434e-02 -9.03251529e-01 4.25133377e-01 5.81391081e-02 -9.01726544e-01 4.28361416e-01 5.81392199e-02 -9.00214434e-01 4.31525946e-01 5.81392869e-02 -8.98714960e-01 4.34649050e-01 5.81392050e-02 -8.97215724e-01 4.37736779e-01 5.81393391e-02 -8.95729005e-01 4.40762401e-01 5.81392124e-02 -8.94153714e-01 4.43950415e-01 5.81391044e-02 -8.92557621e-01 4.47148681e-01 5.81392124e-02 -8.90994310e-01 4.50260371e-01 5.81391975e-02 -8.89409482e-01 4.53382164e-01 5.81392534e-02 -8.87842953e-01 4.56443995e-01 5.81392311e-02 -8.86242628e-01 4.59539711e-01 5.81393167e-02 -8.84631395e-01 4.62634146e-01 5.81392124e-02 -8.83011520e-01 4.65723783e-01 5.81392273e-02 -8.81413281e-01 4.68740284e-01 5.81394024e-02 -8.79820943e-01 4.71721590e-01 5.81392571e-02 -8.78129244e-01 4.74860996e-01 5.81391044e-02 -8.76427650e-01 4.77998316e-01 5.81393018e-02 -8.74747932e-01 4.81064379e-01 5.81392311e-02 -8.73062134e-01 4.84107971e-01 5.81392720e-02 -8.71367991e-01 4.87154216e-01 5.81392422e-02 -8.69676769e-01 4.90171105e-01 5.81392795e-02 -8.67949247e-01 4.93223131e-01 5.81391715e-02 -8.66209805e-01 4.96271372e-01 5.81392124e-02 -8.64520133e-01 4.99210954e-01 5.81393912e-02 -8.62777531e-01 5.02214193e-01 5.81390709e-02 -8.61027300e-01 5.05210042e-01 5.81393950e-02 -8.59247744e-01 5.08229256e-01 5.81390746e-02 -8.57421219e-01 5.11305451e-01 5.81392236e-02 -8.55628669e-01 5.14297843e-01 5.81392609e-02 -8.53831828e-01 5.17273962e-01 5.81392646e-02 -8.52017224e-01 5.20262837e-01 5.81391864e-02 -8.50181818e-01 5.23252487e-01 5.81391901e-02 -8.48360181e-01 5.26206493e-01 5.81392199e-02 -8.46572399e-01 5.29076278e-01 5.81394397e-02 -8.44732404e-01 5.32005727e-01 5.81390113e-02 -8.42820644e-01 5.35029709e-01 5.81393167e-02 -8.40941310e-01 5.37979066e-01 5.81391454e-02 -8.39047551e-01 5.40927768e-01 5.81392348e-02 -8.37158322e-01 5.43845952e-01 5.81392422e-02 -8.35315287e-01 5.46672523e-01 5.81393503e-02 -8.33392024e-01 5.49601197e-01 5.81390522e-02 -8.31402659e-01 5.52603006e-01 5.81391528e-02 -8.29469025e-01 5.55504799e-01 5.81391715e-02 -8.27562332e-01 5.58344185e-01 5.81393763e-02 -8.25670362e-01 5.61134636e-01 5.81393316e-02 -8.23695898e-01 5.64030886e-01 5.81391081e-02 -8.21665585e-01 5.66984296e-01 5.81391566e-02 -8.19655001e-01 5.69886029e-01 5.81392236e-02 -8.17709684e-01 5.72672248e-01 5.81395067e-02 -8.15712690e-01 5.75515985e-01 5.81389889e-02 -8.13622832e-01 5.78462839e-01 5.81392571e-02 -8.11600864e-01 5.81299782e-01 5.81392720e-02 -8.09553862e-01 5.84141731e-01 5.81392497e-02 -8.07518840e-01 5.86957097e-01 5.81393130e-02 -8.05484116e-01 5.89743793e-01 5.81392683e-02 -8.03490579e-01 5.92457116e-01 5.81394844e-02 -8.01401138e-01 5.95278144e-01 5.81390671e-02 -7.99252212e-01 5.98161042e-01 5.81392199e-02 -7.97224641e-01 6.00864351e-01 5.81394993e-02 -7.95121551e-01 6.03643894e-01 5.81390709e-02 -7.92953908e-01 6.06489182e-01 5.81392720e-02 -7.90844500e-01 6.09235823e-01 5.81392832e-02 -7.88671434e-01 6.12045288e-01 5.81392981e-02 -7.86567569e-01 6.14748180e-01 5.81394024e-02 -7.84495533e-01 6.17391527e-01 5.81393391e-02 -7.82279372e-01 6.20194137e-01 5.81391007e-02 -7.80043304e-01 6.23008013e-01 5.81392944e-02 -7.77850389e-01 6.25742137e-01 5.81392348e-02 -7.75673628e-01 6.28439546e-01 5.81393354e-02 -7.73542702e-01 6.31058276e-01 5.81394732e-02 -7.71343529e-01 6.33746564e-01 5.81392236e-02 -7.69063413e-01 6.36511385e-01 5.81393726e-02 -7.66842604e-01 6.39184594e-01 5.81393205e-02 -7.64682233e-01 6.41769826e-01 5.81395738e-02 -7.62427986e-01 6.44442856e-01 5.81391156e-02 -7.60080159e-01 6.47209108e-01 5.81392497e-02 -7.57816792e-01 6.49860263e-01 5.81392497e-02 -7.55536020e-01 6.52512550e-01 5.81392795e-02 -7.53277004e-01 6.55115962e-01 5.81393167e-02 -7.51036704e-01 6.57685280e-01 5.81394210e-02 -7.48784602e-01 6.60245359e-01 5.81392236e-02 -7.46429443e-01 6.62907422e-01 5.81391491e-02 -7.44051993e-01 6.65576518e-01 5.81392460e-02 -7.41761267e-01 6.68126881e-01 5.81394844e-02 -7.39441991e-01 6.70695245e-01 5.81390969e-02 -7.37037122e-01 6.73333228e-01 5.81392422e-02 -7.34677911e-01 6.75911009e-01 5.81393130e-02 -7.32318580e-01 6.78466439e-01 5.81393689e-02 -7.30003953e-01 6.80954278e-01 5.81393987e-02 -7.27696836e-01 6.83420062e-01 5.81392795e-02 -7.25254476e-01 6.86007202e-01 5.81391230e-02 -7.22796559e-01 6.88601673e-01 5.81394359e-02 -7.20351458e-01 6.91153407e-01 5.81393763e-02 -7.17950881e-01 6.93659127e-01 5.81393018e-02 -7.15585172e-01 6.96097255e-01 5.81394508e-02 -7.13156104e-01 6.98581517e-01 5.81391677e-02 -7.10648239e-01 7.01134324e-01 5.81392758e-02 -7.08197594e-01 7.03613400e-01 5.81392981e-02 -7.05733955e-01 7.06066549e-01 5.81393763e-02 -7.03355372e-01 7.08453774e-01 5.81394359e-02 -7.00859189e-01 7.10920274e-01 5.81390858e-02 -6.98299646e-01 7.13433564e-01 5.81393503e-02 -6.95809066e-01 7.15865672e-01 5.81393279e-02 -6.93309605e-01 7.18287408e-01 5.81394508e-02 -6.90845191e-01 7.20646679e-01 5.81394508e-02 -6.88377142e-01 7.23010480e-01 5.81392646e-02 -6.85803711e-01 7.25448549e-01 5.81391789e-02 -6.83210671e-01 7.27891028e-01 5.81393987e-02 -6.80697262e-01 7.30239987e-01 5.81395142e-02 -6.78163707e-01 7.32596278e-01 5.81391193e-02 -6.75550520e-01 7.35009015e-01 5.81393279e-02 -6.73040152e-01 7.37306654e-01 5.81394732e-02 -6.70455515e-01 7.39658475e-01 5.81391715e-02 -6.67885184e-01 7.41980433e-01 5.81394583e-02 -6.65350437e-01 7.44253993e-01 5.81393093e-02 -6.62702024e-01 7.46612906e-01 5.81390597e-02 -6.60067141e-01 7.48944104e-01 5.81394695e-02 -6.57452643e-01 7.51236141e-01 5.81390522e-02 -6.54819071e-01 7.53537953e-01 5.81395067e-02 -6.52206063e-01 7.55797744e-01 5.81389964e-02 -6.49465799e-01 7.58154452e-01 5.81392385e-02 -6.46808028e-01 7.60423005e-01 5.81392460e-02 -6.44173265e-01 7.62656868e-01 5.81392758e-02 -6.41591728e-01 7.64830887e-01 5.81395291e-02 -6.38919055e-01 7.67064393e-01 5.81391789e-02 -6.36217296e-01 7.69305408e-01 5.81394508e-02 -6.33560359e-01 7.71497369e-01 5.81391305e-02 -6.30743146e-01 7.73798943e-01 5.81393205e-02 -6.28043234e-01 7.75993884e-01 5.81392050e-02 -6.25402272e-01 7.78123379e-01 5.81394732e-02 -6.22771680e-01 7.80230820e-01 5.81391752e-02 -6.19968414e-01 7.82458186e-01 5.81391379e-02 -6.17223203e-01 7.84628153e-01 5.81394397e-02 -6.14499271e-01 7.86762059e-01 5.81391305e-02 -6.11749709e-01 7.88904428e-01 5.81394695e-02 -6.09039187e-01 7.90996432e-01 5.81391864e-02 -6.06203973e-01 7.93171048e-01 5.81391826e-02 -6.03378177e-01 7.95324385e-01 5.81392720e-02 -6.00665510e-01 7.97375381e-01 5.81394210e-02 -5.97905219e-01 7.99442768e-01 5.81390858e-02 -5.95029593e-01 8.01587522e-01 5.81392273e-02 -5.92241168e-01 8.03649962e-01 5.81392944e-02 -5.89429319e-01 8.05713832e-01 5.81392758e-02 -5.86662233e-01 8.07734430e-01 5.81393801e-02 -5.83860219e-01 8.09757054e-01 5.81390671e-02 -5.80940306e-01 8.11858892e-01 5.81392832e-02 -5.78113854e-01 8.13873053e-01 5.81392422e-02 -5.75248778e-01 8.15901816e-01 5.81392907e-02 -5.72464824e-01 8.17856133e-01 5.81394620e-02 -5.69632828e-01 8.19828808e-01 5.81391603e-02 -5.66747963e-01 8.21830332e-01 5.81394620e-02 -5.63889503e-01 8.23791683e-01 5.81390522e-02 -5.60910881e-01 8.25822055e-01 5.81392609e-02 -5.58026791e-01 8.27774048e-01 5.81393167e-02 -5.55249810e-01 8.29639554e-01 5.81394956e-02 -5.52321732e-01 8.31589937e-01 5.81391416e-02 -5.49323559e-01 8.33575487e-01 5.81392422e-02 -5.46488106e-01 8.35436106e-01 5.81394471e-02 -5.43584883e-01 8.37327302e-01 5.81390746e-02 -5.40640116e-01 8.39233279e-01 5.81394583e-02 -5.37722528e-01 8.41103137e-01 5.81390411e-02 -5.34687281e-01 8.43037665e-01 5.81392869e-02 -5.31740010e-01 8.44899416e-01 5.81392087e-02 -5.28869450e-01 8.46700072e-01 5.81393912e-02 -5.25921702e-01 8.48536015e-01 5.81390671e-02 -5.22893727e-01 8.50403368e-01 5.81394248e-02 -5.19952178e-01 8.52207065e-01 5.81393950e-02 -5.16972005e-01 8.54015350e-01 5.81391044e-02 -5.14012694e-01 8.55801284e-01 5.81394322e-02 -5.11056364e-01 8.57569337e-01 5.81391566e-02 -5.08040845e-01 8.59358132e-01 5.81394099e-02 -5.05118608e-01 8.61081779e-01 5.81392497e-02 -5.02058327e-01 8.62867594e-01 5.81391379e-02 -4.98969406e-01 8.64659190e-01 5.81392907e-02 -4.95929748e-01 8.66404772e-01 5.81392311e-02 -4.92908776e-01 8.68127048e-01 5.81394210e-02 -4.89874721e-01 8.69845629e-01 5.81393242e-02 -4.86838132e-01 8.71545315e-01 5.81392609e-02 -4.83780056e-01 8.73245299e-01 5.81392944e-02 -4.80792403e-01 8.74897301e-01 5.81395067e-02 -4.77755159e-01 8.76558840e-01 5.81391454e-02 -4.74623233e-01 8.78256559e-01 5.81392720e-02 -4.71541375e-01 8.79916370e-01 5.81392944e-02 -4.68474030e-01 8.81554306e-01 5.81393279e-02 -4.65447485e-01 8.83157194e-01 5.81394844e-02 -4.62367803e-01 8.84770215e-01 5.81391789e-02 -4.59196746e-01 8.86420369e-01 5.81392720e-02 -4.56106782e-01 8.88016105e-01 5.81393540e-02 -4.53113705e-01 8.89546573e-01 5.81395254e-02 -4.50021863e-01 8.91113341e-01 5.81391156e-02 -4.46819246e-01 8.92724633e-01 5.81392832e-02 -4.43711370e-01 8.94272923e-01 5.81393391e-02 -4.40558195e-01 8.95831108e-01 5.81392944e-02 -4.37518656e-01 8.97321224e-01 5.81394993e-02 -4.34393704e-01 8.98837626e-01 5.81391528e-02 -4.31231439e-01 9.00356710e-01 5.81394210e-02 -4.28102702e-01 9.01847601e-01 5.81391789e-02 -4.24866557e-01 9.03378248e-01 5.81393279e-02 -4.21777993e-01 9.04825747e-01 5.81394248e-02 -4.18629259e-01 9.06285524e-01 5.81391305e-02 -4.15448725e-01 9.07747149e-01 5.81393950e-02 -4.12285179e-01 9.09189522e-01 5.81391081e-02 -4.09036189e-01 9.10656750e-01 5.81392981e-02 -4.05854136e-01 9.12079334e-01 5.81393167e-02 -4.02749717e-01 9.13454771e-01 5.81394583e-02 -3.99583757e-01 9.14842963e-01 5.81391975e-02 -3.96317661e-01 9.16262448e-01 5.81391752e-02 -3.93084556e-01 9.17649984e-01 5.81392944e-02 -3.89966786e-01 9.18983877e-01 5.81394508e-02 -3.86866361e-01 9.20291781e-01 5.81393167e-02 -3.83574873e-01 9.21668351e-01 5.81391081e-02 -3.80301535e-01 9.23023939e-01 5.81393838e-02 -3.77106667e-01 9.24333155e-01 5.81392013e-02 -3.73889506e-01 9.25641835e-01 5.81394620e-02 -3.70671570e-01 9.26932693e-01 5.81391528e-02 -3.67376626e-01 9.28245008e-01 5.81393279e-02 -3.64130288e-01 9.29523647e-01 5.81392422e-02 -3.60878855e-01 9.30784702e-01 5.81392869e-02 -3.57688367e-01 9.32026386e-01 5.81393577e-02 -3.54430556e-01 9.33261275e-01 5.81391156e-02 -3.51165086e-01 9.34489250e-01 5.81394620e-02 -3.47915679e-01 9.35703039e-01 5.81391938e-02 -3.44579309e-01 9.36940372e-01 5.81395030e-02 -3.41349334e-01 9.38132942e-01 5.81395738e-02 -3.38099062e-01 9.39303279e-01 5.81391789e-02 -3.34772706e-01 9.40499365e-01 5.81395738e-02 -3.31491053e-01 9.41657186e-01 5.81393056e-02 -3.28163743e-01 9.42821383e-01 5.81393391e-02 -3.24880958e-01 9.43959773e-01 5.81393018e-02 -3.21668059e-01 9.45057631e-01 5.81394546e-02 -3.18359762e-01 9.46177125e-01 5.81391342e-02 -3.14987004e-01 9.47305202e-01 5.81393987e-02 -3.11688542e-01 9.48394775e-01 5.81393577e-02 -3.08411807e-01 9.49466527e-01 5.81394657e-02 -3.05115789e-01 9.50531185e-01 5.81391677e-02 -3.01757574e-01 9.51602161e-01 5.81394397e-02 -2.98427135e-01 9.52652514e-01 5.81394918e-02 -2.95092762e-01 9.53691006e-01 5.81393279e-02 -2.91839689e-01 9.54691529e-01 5.81395738e-02 -2.88494676e-01 9.55703676e-01 5.81391156e-02 -2.85052866e-01 9.56738770e-01 5.81393093e-02 -2.81716347e-01 9.57727492e-01 5.81393279e-02 -2.78359950e-01 9.58707333e-01 5.81392087e-02 -2.75113255e-01 9.59644854e-01 5.81395067e-02 -2.71779835e-01 9.60593224e-01 5.81390932e-02 -2.68412977e-01 9.61542308e-01 5.81395328e-02 -2.65172422e-01 9.62437868e-01 5.81392609e-02 -2.61681706e-01 9.63393509e-01 5.81390522e-02 -2.58220255e-01 9.64326322e-01 5.81393018e-02 -2.54843414e-01 9.65225041e-01 5.81392422e-02 -2.51481056e-01 9.66106951e-01 5.81393465e-02 -2.48215646e-01 9.66951966e-01 5.81395552e-02 -2.44822726e-01 9.67811644e-01 5.81390895e-02 -2.41317734e-01 9.68693912e-01 5.81392646e-02 -2.37937018e-01 9.69531119e-01 5.81392944e-02 -2.34563097e-01 9.70355272e-01 5.81393056e-02 -2.31262088e-01 9.71147299e-01 5.81395365e-02 -2.27900535e-01 9.71939981e-01 5.81391044e-02 -2.24489689e-01 9.72733855e-01 5.81395105e-02 -2.21101075e-01 9.73506510e-01 5.81391081e-02 -2.17605606e-01 9.74297404e-01 5.81393652e-02 -2.14193255e-01 9.75049257e-01 5.81392944e-02 -2.10782170e-01 9.75793302e-01 5.81392422e-02 -2.07482055e-01 9.76502120e-01 5.81395067e-02 -2.04086706e-01 9.77217674e-01 5.81391789e-02 -2.00557441e-01 9.77948725e-01 5.81393018e-02 -1.97146803e-01 9.78639722e-01 5.81392981e-02 -1.93731010e-01 9.79322314e-01 5.81392534e-02 -1.90400884e-01 9.79976177e-01 5.81394471e-02 -1.86969087e-01 9.80635047e-01 5.81391267e-02 -1.83556944e-01 9.81280327e-01 5.81395738e-02 -1.80190891e-01 9.81901884e-01 5.81393391e-02 -1.76700518e-01 9.82540965e-01 5.81391603e-02 -1.73151657e-01 9.83173251e-01 5.81393242e-02 -1.69733673e-01 9.83765066e-01 5.81392609e-02 -1.66304991e-01 9.84351099e-01 5.81392832e-02 -1.62954971e-01 9.84911442e-01 5.81395067e-02 -1.59613267e-01 9.85457599e-01 5.81393056e-02 -1.56082705e-01 9.86023188e-01 5.81391379e-02 -1.52527139e-01 9.86580670e-01 5.81392311e-02 -1.49068192e-01 9.87106562e-01 5.81392460e-02 -1.45621821e-01 9.87622440e-01 5.81392422e-02 -1.42187655e-01 9.88122165e-01 5.81393018e-02 -1.38846606e-01 9.88598824e-01 5.81395365e-02 -1.35399655e-01 9.89076495e-01 5.81390522e-02 -1.31833956e-01 9.89556909e-01 5.81393056e-02 -1.28492624e-01 9.89996612e-01 5.81395216e-02 -1.25045598e-01 9.90437210e-01 5.81391528e-02 -1.21564358e-01 9.90872085e-01 5.81395105e-02 -1.18066221e-01 9.91293192e-01 5.81390932e-02 -1.14538938e-01 9.91707504e-01 5.81392534e-02 -1.11075528e-01 9.92101610e-01 5.81393167e-02 -1.07586056e-01 9.92485344e-01 5.81393391e-02 -1.04133695e-01 9.92853343e-01 5.81393503e-02 -1.00654729e-01 9.93212640e-01 5.81392869e-02 -9.72678885e-02 9.93550956e-01 5.81394844e-02 -9.39151570e-02 9.93873239e-01 5.81393018e-02 -9.03568938e-02 9.94201899e-01 5.81391416e-02 -8.67837891e-02 9.94521976e-01 5.81393242e-02 -8.33046436e-02 9.94818270e-01 5.81392646e-02 -7.98213333e-02 9.95103896e-01 5.81392609e-02 -7.64430985e-02 9.95368302e-01 5.81395105e-02 -7.29927346e-02 9.95628178e-01 5.81390932e-02 -6.94020018e-02 9.95883763e-01 5.81393503e-02 -6.59137964e-02 9.96122301e-01 5.81394061e-02 -6.24436885e-02 9.96343791e-01 5.81393503e-02 -5.90686128e-02 9.96552825e-01 5.81395589e-02 -5.56300133e-02 9.96749282e-01 5.81391789e-02 -5.20864651e-02 9.96939778e-01 5.81394359e-02 -4.86344211e-02 9.97116148e-01 5.81391342e-02 -4.50573713e-02 9.97281730e-01 5.81393428e-02 -4.15853746e-02 9.97434378e-01 5.81393428e-02 -3.80930789e-02 9.97572601e-01 5.81392944e-02 -3.47133018e-02 9.97697830e-01 5.81394881e-02 -3.12565938e-02 9.97809410e-01 5.81391603e-02 -2.77288388e-02 9.97915089e-01 5.81395067e-02 -2.42608935e-02 9.98008728e-01 5.81391416e-02 -2.06743758e-02 9.98083770e-01 5.81393167e-02 -1.72863565e-02 9.98154461e-01 5.81395440e-02 -1.37973307e-02 9.98200655e-01 5.81392124e-02 -1.03051569e-02 9.98246312e-01 5.81395738e-02 -6.91969786e-03 9.98282373e-01 5.81394583e-02 -3.34351393e-03 9.98299539e-01 5.81392273e-02 2.19750422e-04 9.98301208e-01 5.81393875e-02 3.70920449e-03 9.98299778e-01 5.81393987e-02 7.17414496e-03 9.98279154e-01 5.81393950e-02 1.05694802e-02 9.98244405e-01 5.81395738e-02 1.39553212e-02 9.98198867e-01 5.81393354e-02 1.75211579e-02 9.98150945e-01 5.81391975e-02 2.11287867e-02 9.98075962e-01 5.81393205e-02 2.46386584e-02 9.97996449e-01 5.81393279e-02 2.81171426e-02 9.97906506e-01 5.81392497e-02 3.16084847e-02 9.97800171e-01 5.81393391e-02 3.49931419e-02 9.97689664e-01 5.81395738e-02 3.84440534e-02 9.97560263e-01 5.81391640e-02 4.20550071e-02 9.97415364e-01 5.81393130e-02 4.55443710e-02 9.97260809e-01 5.81393987e-02 4.90236133e-02 9.97096717e-01 5.81393167e-02 5.24063595e-02 9.96922195e-01 5.81395030e-02 5.58587573e-02 9.96736288e-01 5.81392273e-02 5.93809560e-02 9.96534109e-01 5.81395738e-02 6.28253073e-02 9.96318817e-01 5.81391156e-02 6.64101020e-02 9.96088803e-01 5.81393279e-02 6.98712990e-02 9.95850623e-01 5.81393018e-02 7.33502209e-02 9.95603085e-01 5.81393205e-02 7.68328160e-02 9.95338202e-01 5.81392571e-02 8.02244395e-02 9.95072126e-01 5.81395738e-02 8.36898163e-02 9.94785786e-01 5.81391864e-02 8.72175172e-02 9.94483471e-01 5.81392497e-02 9.07231197e-02 9.94169354e-01 5.81393093e-02 9.41768810e-02 9.93848801e-01 5.81395216e-02 9.75812897e-02 9.93521750e-01 5.81395738e-02 1.01047814e-01 9.93172646e-01 5.81391528e-02 1.04505263e-01 9.92816567e-01 5.81394583e-02 1.07960835e-01 9.92445469e-01 5.81390522e-02 1.11524515e-01 9.92051065e-01 5.81392981e-02 1.14913397e-01 9.91664052e-01 5.81395291e-02 1.18367575e-01 9.91256952e-01 5.81391454e-02 1.21809438e-01 9.90841389e-01 5.81394359e-02 1.25264898e-01 9.90409732e-01 5.81391156e-02 1.28826007e-01 9.89952207e-01 5.81392944e-02 1.32279560e-01 9.89497662e-01 5.81393577e-02 1.35732055e-01 9.89031374e-01 5.81393167e-02 1.39072001e-01 9.88568723e-01 5.81394434e-02 1.42550066e-01 9.88070071e-01 5.81391938e-02 1.45993546e-01 9.87567723e-01 5.81394993e-02 1.49426073e-01 9.87051606e-01 5.81391193e-02 1.52965367e-01 9.86513257e-01 5.81393465e-02 1.56339392e-01 9.85981822e-01 5.81395030e-02 1.59762159e-01 9.85433578e-01 5.81391789e-02 1.63204968e-01 9.84871864e-01 5.81395030e-02 1.66536227e-01 9.84311700e-01 5.81393205e-02 1.70058444e-01 9.83708799e-01 5.81391379e-02 1.73592940e-01 9.83095884e-01 5.81393354e-02 1.77027643e-01 9.82483923e-01 5.81393242e-02 1.80463240e-01 9.81853545e-01 5.81392832e-02 1.83800697e-01 9.81235862e-01 5.81395738e-02 1.87121406e-01 9.80606377e-01 5.81392907e-02 1.90542713e-01 9.79947686e-01 5.81394099e-02 1.94034189e-01 9.79261637e-01 5.81391528e-02 1.97567910e-01 9.78555620e-01 5.81393428e-02 2.00977191e-01 9.77861106e-01 5.81392869e-02 2.04393148e-01 9.77151752e-01 5.81392534e-02 2.07719877e-01 9.76453841e-01 5.81395105e-02 2.11104065e-01 9.75724459e-01 5.81391752e-02 2.14595586e-01 9.74962234e-01 5.81392385e-02 2.18015224e-01 9.74204838e-01 5.81393056e-02 2.21433163e-01 9.73431945e-01 5.81394434e-02 2.24752247e-01 9.72673476e-01 5.81395738e-02 2.28104502e-01 9.71893251e-01 5.81391938e-02 2.31543958e-01 9.71079588e-01 5.81395738e-02 2.34813467e-01 9.70294952e-01 5.81392758e-02 2.38284662e-01 9.69445765e-01 5.81391379e-02 2.41778016e-01 9.68579173e-01 5.81393652e-02 2.45122522e-01 9.67737854e-01 5.81393912e-02 2.48476803e-01 9.66884494e-01 5.81392944e-02 2.51789451e-01 9.66027081e-01 5.81394657e-02 2.55057901e-01 9.65169966e-01 5.81392944e-02 2.58543462e-01 9.64239299e-01 5.81391081e-02 2.62021840e-01 9.63302553e-01 5.81392236e-02 2.65344650e-01 9.62389886e-01 5.81393503e-02 2.68607765e-01 9.61488008e-01 5.81395738e-02 2.71968842e-01 9.60539997e-01 5.81391789e-02 2.75318265e-01 9.59587514e-01 5.81394956e-02 2.78668702e-01 9.58617210e-01 5.81391938e-02 2.82098979e-01 9.57613051e-01 5.81392534e-02 2.85379916e-01 9.56644595e-01 5.81394620e-02 2.88694441e-01 9.55643058e-01 5.81391342e-02 2.92057604e-01 9.54624116e-01 5.81394508e-02 2.95315921e-01 9.53622103e-01 5.81391528e-02 2.98747450e-01 9.52552080e-01 5.81392087e-02 3.02003741e-01 9.51523960e-01 5.81394956e-02 3.05315495e-01 9.50466216e-01 5.81390560e-02 3.08677852e-01 9.49380219e-01 5.81394508e-02 3.11965138e-01 9.48304355e-01 5.81391007e-02 3.15280706e-01 9.47207689e-01 5.81394024e-02 3.18473965e-01 9.46139932e-01 5.81392497e-02 3.21870625e-01 9.44988251e-01 5.81390858e-02 3.25266153e-01 9.43825841e-01 5.81392795e-02 3.28539103e-01 9.42690015e-01 5.81392609e-02 3.31799656e-01 9.41548884e-01 5.81393391e-02 3.35053176e-01 9.40398872e-01 5.81394583e-02 3.38299900e-01 9.39231396e-01 5.81390932e-02 3.41665149e-01 9.38013732e-01 5.81392124e-02 3.44936967e-01 9.36808288e-01 5.81392869e-02 3.48181784e-01 9.35604036e-01 5.81392832e-02 3.51398855e-01 9.34401810e-01 5.81394583e-02 3.54646921e-01 9.33179498e-01 5.81391566e-02 3.57897282e-01 9.31948900e-01 5.81394918e-02 3.61140519e-01 9.30685759e-01 5.81391081e-02 3.64453822e-01 9.29395318e-01 5.81393354e-02 3.67645919e-01 9.28138494e-01 5.81394695e-02 3.70888591e-01 9.26845670e-01 5.81392124e-02 3.74093175e-01 9.25557911e-01 5.81394397e-02 3.77307206e-01 9.24251914e-01 5.81391193e-02 3.80535215e-01 9.22926426e-01 5.81393652e-02 3.83753538e-01 9.21593785e-01 5.81391267e-02 3.87044549e-01 9.20217454e-01 5.81392236e-02 3.90166938e-01 9.18897629e-01 5.81394583e-02 3.93361330e-01 9.17531490e-01 5.81391081e-02 3.96583229e-01 9.16146278e-01 5.81394508e-02 3.99673998e-01 9.14805293e-01 5.81392795e-02 4.02937591e-01 9.13369775e-01 5.81390858e-02 4.06214178e-01 9.11918342e-01 5.81392981e-02 4.09376204e-01 9.10502493e-01 5.81392534e-02 4.12567437e-01 9.09061491e-01 5.81392944e-02 4.15675730e-01 9.07642543e-01 5.81394248e-02 4.18745875e-01 9.06229973e-01 5.81392460e-02 4.21977967e-01 9.04730320e-01 5.81390709e-02 4.25212026e-01 9.03213978e-01 5.81392571e-02 4.28349972e-01 9.01730955e-01 5.81392348e-02 4.31441039e-01 9.00255919e-01 5.81394285e-02 4.34559882e-01 8.98758054e-01 5.81392124e-02 4.37705785e-01 8.97231698e-01 5.81394918e-02 4.40826327e-01 8.95697057e-01 5.81390932e-02 4.44037676e-01 8.94110799e-01 5.81391938e-02 4.47168738e-01 8.92548382e-01 5.81391677e-02 4.50254053e-01 8.90998006e-01 5.81391789e-02 4.53305036e-01 8.89450252e-01 5.81394657e-02 4.56362516e-01 8.87884021e-01 5.81392348e-02 4.59524691e-01 8.86249661e-01 5.81395328e-02 4.62525725e-01 8.84690166e-01 5.81392199e-02 4.65671331e-01 8.83036375e-01 5.81390597e-02 4.68810171e-01 8.81375194e-01 5.81392832e-02 4.71870542e-01 8.79739940e-01 5.81391789e-02 4.74964172e-01 8.78073275e-01 5.81391864e-02 4.77951288e-01 8.76454413e-01 5.81393912e-02 4.80998397e-01 8.74782085e-01 5.81390448e-02 4.84155625e-01 8.73036981e-01 5.81392087e-02 4.87190753e-01 8.71347904e-01 5.81393316e-02 4.90253538e-01 8.69630873e-01 5.81393652e-02 4.93168533e-01 8.67979825e-01 5.81394471e-02 4.96203095e-01 8.66248250e-01 5.81390448e-02 4.99229968e-01 8.64509404e-01 5.81394210e-02 5.02230704e-01 8.62768531e-01 5.81390895e-02 5.05338013e-01 8.60952258e-01 5.81391640e-02 5.08261859e-01 8.59229445e-01 5.81393503e-02 5.11235774e-01 8.57463062e-01 5.81390895e-02 5.14233351e-01 8.55669081e-01 5.81393689e-02 5.17208636e-01 8.53871584e-01 5.81391305e-02 5.20235837e-01 8.52033436e-01 5.81392460e-02 5.23156524e-01 8.50240827e-01 5.81393652e-02 5.26122034e-01 8.48412156e-01 5.81390820e-02 5.29085219e-01 8.46566439e-01 5.81394099e-02 5.32014370e-01 8.44727159e-01 5.81391230e-02 5.34987450e-01 8.42847824e-01 5.81393838e-02 5.37897766e-01 8.40991914e-01 5.81391975e-02 5.40914059e-01 8.39055479e-01 5.81392571e-02 5.43782353e-01 8.37201118e-01 5.81395477e-02 5.46663225e-01 8.35320473e-01 5.81393577e-02 5.49588263e-01 8.33403409e-01 5.81395365e-02 5.52401543e-01 8.31540763e-01 5.81395365e-02 5.55404544e-01 8.29537570e-01 5.81395403e-02 5.58293998e-01 8.27599466e-01 5.81394993e-02 5.61178088e-01 8.25645030e-01 5.81395216e-02 5.64146996e-01 8.23622823e-01 5.81394583e-02 5.66911757e-01 8.21729004e-01 5.81393652e-02 5.69597900e-01 8.19867849e-01 5.81391938e-02 5.72398305e-01 8.17910254e-01 5.81389368e-02 5.75291514e-01 8.15879464e-01 5.81390411e-02 5.78142226e-01 8.13861430e-01 5.81390262e-02 5.80713332e-01 8.12029302e-01 5.81390262e-02 5.82836986e-01 8.10506582e-01 5.81390262e-02 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. 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. 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. 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. 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. 0. 0. 0. 0. 7.13995278e-01 6.97732449e-01 5.81390299e-02 7.16238320e-01 6.95428252e-01 5.81389815e-02 7.18350708e-01 6.93249464e-01 5.81391230e-02 7.20696867e-01 6.90806508e-01 5.81394434e-02 7.23119199e-01 6.88266993e-01 5.81394807e-02 7.25439548e-01 6.85820818e-01 5.81394956e-02 7.27816820e-01 6.83292687e-01 5.81395440e-02 7.30246305e-01 6.80696964e-01 5.81395403e-02 7.32599437e-01 6.78163528e-01 5.81395589e-02 7.34882236e-01 6.75690413e-01 5.81395328e-02 7.37197220e-01 6.73159420e-01 5.81393912e-02 7.39617288e-01 6.70501411e-01 5.81392013e-02 7.42001057e-01 6.67862236e-01 5.81393614e-02 7.44330823e-01 6.65262461e-01 5.81393391e-02 7.46591032e-01 6.62728965e-01 5.81395403e-02 7.48849452e-01 6.60174012e-01 5.81393316e-02 7.51175344e-01 6.57522678e-01 5.81392571e-02 7.53501296e-01 6.54858410e-01 5.81392832e-02 7.55804360e-01 6.52198374e-01 5.81391677e-02 7.58080840e-01 6.49553478e-01 5.81394136e-02 7.60280192e-01 6.46975219e-01 5.81395216e-02 7.62517631e-01 6.44339204e-01 5.81392460e-02 7.64771640e-01 6.41660392e-01 5.81393130e-02 7.67033160e-01 6.38955414e-01 5.81391491e-02 7.69328892e-01 6.36187255e-01 5.81392609e-02 7.71494389e-01 6.33564413e-01 5.81394061e-02 7.73675263e-01 6.30895734e-01 5.81392162e-02 7.75924444e-01 6.28128588e-01 5.81392758e-02 7.78135002e-01 6.25387847e-01 5.81392236e-02 7.80262887e-01 6.22732818e-01 5.81394359e-02 7.82360017e-01 6.20094538e-01 5.81392497e-02 7.84578204e-01 6.17284298e-01 5.81391081e-02 7.86776602e-01 6.14481330e-01 5.81392832e-02 7.88930237e-01 6.11713648e-01 5.81391938e-02 7.91022480e-01 6.09006643e-01 5.81395477e-02 7.93057084e-01 6.06353760e-01 5.81393018e-02 7.95240641e-01 6.03486776e-01 5.81391230e-02 7.97400773e-01 6.00630105e-01 5.81392646e-02 7.99490273e-01 5.97843885e-01 5.81392013e-02 8.01519811e-01 5.95123470e-01 5.81394807e-02 8.03527534e-01 5.92406929e-01 5.81393056e-02 8.05631101e-01 5.89542091e-01 5.81390746e-02 8.07744265e-01 5.86645246e-01 5.81391789e-02 8.09816778e-01 5.83777964e-01 5.81392981e-02 8.11834931e-01 5.80972373e-01 5.81392981e-02 8.13800633e-01 5.78217745e-01 5.81394695e-02 8.15759003e-01 5.75451910e-01 5.81392124e-02 8.17782044e-01 5.72570860e-01 5.81392683e-02 8.19815874e-01 5.69651961e-01 5.81390336e-02 8.21842372e-01 5.66729546e-01 5.81394881e-02 8.23742032e-01 5.63961327e-01 5.81392497e-02 8.25755775e-01 5.61007977e-01 5.81390187e-02 8.27718973e-01 5.58109999e-01 5.81395105e-02 8.29616964e-01 5.55280626e-01 5.81391379e-02 8.31555784e-01 5.52375555e-01 5.81393465e-02 8.33446205e-01 5.49519598e-01 5.81392311e-02 8.35414052e-01 5.46520889e-01 5.81391118e-02 8.37359905e-01 5.43536305e-01 5.81392497e-02 8.39203000e-01 5.40686786e-01 5.81394434e-02 8.41035545e-01 5.37832260e-01 5.81392571e-02 8.42905164e-01 5.34892321e-01 5.81391603e-02 8.44845116e-01 5.31827748e-01 5.81390858e-02 8.46753240e-01 5.28782666e-01 5.81391975e-02 8.48588347e-01 5.25836706e-01 5.81393652e-02 8.50355327e-01 5.22969663e-01 5.81394024e-02 8.52140784e-01 5.20060122e-01 5.81392832e-02 8.53950620e-01 5.17079473e-01 5.81392236e-02 8.55745077e-01 5.14105558e-01 5.81392944e-02 8.57582331e-01 5.11031806e-01 5.81390932e-02 8.59411538e-01 5.07952809e-01 5.81392609e-02 8.61138582e-01 5.05020857e-01 5.81394434e-02 8.62882078e-01 5.02032518e-01 5.81390709e-02 8.64645481e-01 4.98994529e-01 5.81394285e-02 8.66368890e-01 4.95990664e-01 5.81390858e-02 8.68114352e-01 4.92927969e-01 5.81393726e-02 8.69782269e-01 4.89987493e-01 5.81393912e-02 8.71507525e-01 4.86904144e-01 5.81390783e-02 8.73212278e-01 4.83840227e-01 5.81393577e-02 8.74894500e-01 4.80795622e-01 5.81392460e-02 8.76566470e-01 4.77743268e-01 5.81394210e-02 8.78187180e-01 4.74754363e-01 5.81392832e-02 8.79878342e-01 4.71611112e-01 5.81391118e-02 8.81568849e-01 4.68446344e-01 5.81392124e-02 8.83198678e-01 4.65366036e-01 5.81392944e-02 8.84772778e-01 4.62368488e-01 5.81394732e-02 8.86331201e-01 4.59369004e-01 5.81393018e-02 8.87975037e-01 4.56184000e-01 5.81390932e-02 8.89610410e-01 4.52986836e-01 5.81392534e-02 8.91184092e-01 4.49884504e-01 5.81392944e-02 8.92751157e-01 4.46766585e-01 5.81392162e-02 8.94273639e-01 4.43711817e-01 5.81395067e-02 8.95797551e-01 4.40624654e-01 5.81391528e-02 8.97345483e-01 4.37469095e-01 5.81394807e-02 8.98854017e-01 4.34357136e-01 5.81391007e-02 9.00408924e-01 4.31123078e-01 5.81392720e-02 9.01869178e-01 4.28063005e-01 5.81395254e-02 9.03347194e-01 4.24929202e-01 5.81391454e-02 9.04832840e-01 4.21763510e-01 5.81394844e-02 9.06304300e-01 4.18589324e-01 5.81391156e-02 9.07797515e-01 4.15338635e-01 5.81392944e-02 9.09208715e-01 4.12243068e-01 5.81395067e-02 9.10626650e-01 4.09099668e-01 5.81390671e-02 9.12057698e-01 4.05900359e-01 5.81394471e-02 9.13465679e-01 4.02720660e-01 5.81391007e-02 9.14877474e-01 3.99506807e-01 5.81394061e-02 9.16229129e-01 3.96393687e-01 5.81392571e-02 9.17635977e-01 3.93117368e-01 5.81391156e-02 9.19041872e-01 3.89828026e-01 5.81393242e-02 9.20390904e-01 3.86632144e-01 5.81393167e-02 9.21702087e-01 3.83495659e-01 5.81394918e-02 9.22999203e-01 3.80358607e-01 5.81392683e-02 9.24352765e-01 3.77058268e-01 5.81391044e-02 9.25712347e-01 3.73713791e-01 5.81392758e-02 9.27015543e-01 3.70466113e-01 5.81393018e-02 9.28267539e-01 3.67325932e-01 5.81394807e-02 9.29497659e-01 3.64200294e-01 5.81392869e-02 9.30788338e-01 3.60871255e-01 5.81391305e-02 9.32059646e-01 3.57604384e-01 5.81394508e-02 9.33286309e-01 3.54363143e-01 5.81391454e-02 9.34554219e-01 3.50992441e-01 5.81392646e-02 9.35745478e-01 3.47801358e-01 5.81395365e-02 9.36949551e-01 3.44556719e-01 5.81391379e-02 9.38159287e-01 3.41277212e-01 5.81395626e-02 9.39331710e-01 3.38021308e-01 5.81391230e-02 9.40541923e-01 3.34647596e-01 5.81393503e-02 9.41677332e-01 3.31436872e-01 5.81394508e-02 9.42814946e-01 3.28179359e-01 5.81391267e-02 9.43984985e-01 3.24804574e-01 5.81392944e-02 9.45098281e-01 3.21546346e-01 5.81393391e-02 9.46201861e-01 3.18293124e-01 5.81395738e-02 9.47286785e-01 3.15041810e-01 5.81393205e-02 9.48402703e-01 3.11663896e-01 5.81391342e-02 9.49508786e-01 3.08282793e-01 5.81393577e-02 9.50578928e-01 3.04968387e-01 5.81393875e-02 9.51614797e-01 3.01721573e-01 5.81395738e-02 9.52634215e-01 2.98483133e-01 5.81393801e-02 9.53699827e-01 2.95059502e-01 5.81392311e-02 9.54753697e-01 2.91630477e-01 5.81393987e-02 9.55752254e-01 2.88341999e-01 5.81393763e-02 9.56732512e-01 2.85073012e-01 5.81394807e-02 9.57701743e-01 2.81802416e-01 5.81393801e-02 9.58699048e-01 2.78390497e-01 5.81392162e-02 9.59665060e-01 2.75043011e-01 5.81395105e-02 9.60613906e-01 2.71706641e-01 5.81391491e-02 9.61579561e-01 2.68272161e-01 5.81393652e-02 9.62491453e-01 2.64982224e-01 5.81395738e-02 9.63408589e-01 2.61631101e-01 5.81391305e-02 9.64342654e-01 2.58162349e-01 5.81393316e-02 9.65234339e-01 2.54810899e-01 5.81393093e-02 9.66117203e-01 2.51441181e-01 5.81392720e-02 9.66971040e-01 2.48147622e-01 5.81395254e-02 9.67825413e-01 2.44773388e-01 5.81392460e-02 9.68671978e-01 2.41415933e-01 5.81395552e-02 9.69518721e-01 2.37989664e-01 5.81391118e-02 9.70342457e-01 2.34614030e-01 5.81394583e-02 9.71133351e-01 2.31318444e-01 5.81393801e-02 9.71947074e-01 2.27873638e-01 5.81392050e-02 9.72762644e-01 2.24359900e-01 5.81394359e-02 9.73534048e-01 2.20987007e-01 5.81392162e-02 9.74306107e-01 2.17563599e-01 5.81393167e-02 9.75042403e-01 2.14230999e-01 5.81395663e-02 9.75779891e-01 2.10844755e-01 5.81392311e-02 9.76526856e-01 2.07365081e-01 5.81394099e-02 9.77248728e-01 2.03941718e-01 5.81393503e-02 9.77951884e-01 2.00539723e-01 5.81393279e-02 9.78629768e-01 1.97202951e-01 5.81394434e-02 9.79301214e-01 1.93827152e-01 5.81391528e-02 9.79983985e-01 1.90366775e-01 5.81395738e-02 9.80635107e-01 1.86962351e-01 5.81391603e-02 9.81300116e-01 1.83449626e-01 5.81392944e-02 9.81917799e-01 1.80103779e-01 5.81394285e-02 9.82546449e-01 1.76676810e-01 5.81391454e-02 9.83170867e-01 1.73169985e-01 5.81393577e-02 9.83756721e-01 1.69782311e-01 5.81393391e-02 9.84340727e-01 1.66369691e-01 5.81395738e-02 9.84895289e-01 1.63044110e-01 5.81392497e-02 9.85474706e-01 1.59505844e-01 5.81391305e-02 9.86039698e-01 1.55975416e-01 5.81392609e-02 9.86575246e-01 1.52549893e-01 5.81392907e-02 9.87090886e-01 1.49176493e-01 5.81394881e-02 9.87591445e-01 1.45829991e-01 5.81393205e-02 9.88107681e-01 1.42282516e-01 5.81391826e-02 9.88609374e-01 1.38770983e-01 5.81393465e-02 9.89087462e-01 1.35331184e-01 5.81394620e-02 9.89556313e-01 1.31846696e-01 5.81394546e-02 9.90002573e-01 1.28453970e-01 5.81395738e-02 9.90441203e-01 1.25022098e-01 5.81392534e-02 9.90882218e-01 1.21475250e-01 5.81393912e-02 9.91297781e-01 1.18025348e-01 5.81394248e-02 9.91705596e-01 1.14554927e-01 5.81393726e-02 9.92088556e-01 1.11199908e-01 5.81395142e-02 9.92472351e-01 1.07707314e-01 5.81392087e-02 9.92845118e-01 1.04235508e-01 5.81395216e-02 9.93197620e-01 1.00794174e-01 5.81393056e-02 9.93555665e-01 9.72183570e-02 5.81393428e-02 9.93880451e-01 9.38481688e-02 5.81395738e-02 9.94200349e-01 9.03845131e-02 5.81392124e-02 9.94512677e-01 8.69026259e-02 5.81395738e-02 9.94808435e-01 8.34154487e-02 5.81392124e-02 9.95096385e-01 7.99259618e-02 5.81395738e-02 9.95364428e-01 7.64985383e-02 5.81392124e-02 9.95633900e-01 7.29110911e-02 5.81393465e-02 9.95882750e-01 6.94107562e-02 5.81394061e-02 9.96119916e-01 6.59445003e-02 5.81393354e-02 9.96338129e-01 6.25612736e-02 5.81395477e-02 9.96543169e-01 5.91832362e-02 5.81393316e-02 9.96749759e-01 5.56201302e-02 5.81391230e-02 9.96943772e-01 5.20276874e-02 5.81393652e-02 9.97120559e-01 4.85417545e-02 5.81392944e-02 9.97278273e-01 4.51570936e-02 5.81395328e-02 9.97425079e-01 4.18250859e-02 5.81393763e-02 9.97564256e-01 3.83216627e-02 5.81392609e-02 9.97693062e-01 3.48139256e-02 5.81393130e-02 9.97811377e-01 3.12368330e-02 5.81391528e-02 9.97918189e-01 2.76423227e-02 5.81393279e-02 9.98009026e-01 2.42511015e-02 5.81395738e-02 9.98080790e-01 2.08854750e-02 5.81393875e-02 9.98152912e-01 1.74074378e-02 5.81393801e-02 9.98200476e-01 1.39111318e-02 5.81394210e-02 9.98247206e-01 1.03956424e-02 5.81393838e-02 9.98282373e-01 6.94046170e-03 5.81393689e-02 9.98299420e-01 3.35443229e-03 5.81391528e-02 9.98301744e-01 -1.36674178e-04 5.81395589e-02 9.98299479e-01 -3.58012156e-03 5.81392497e-02 9.98279810e-01 -7.13022426e-03 5.81395738e-02 9.98245895e-01 -1.04841907e-02 5.81393689e-02 9.98196840e-01 -1.40329637e-02 5.81392422e-02 9.98148680e-01 -1.76399574e-02 5.81392832e-02 9.98077631e-01 -2.10395977e-02 5.81394695e-02 9.98000205e-01 -2.45430972e-02 5.81391007e-02 9.97907579e-01 -2.80330796e-02 5.81395589e-02 9.97803569e-01 -3.14837024e-02 5.81392311e-02 9.97689664e-01 -3.49681824e-02 5.81394695e-02 9.97562766e-01 -3.83690447e-02 5.81393242e-02 9.97423768e-01 -4.18553613e-02 5.81393242e-02 9.97267067e-01 -4.53824662e-02 5.81391007e-02 9.97099042e-01 -4.89948615e-02 5.81393391e-02 9.96919274e-01 -5.24615608e-02 5.81393018e-02 9.96734798e-01 -5.58822006e-02 5.81394657e-02 9.96539116e-01 -5.92557937e-02 5.81392832e-02 9.96325672e-01 -6.27252534e-02 5.81392683e-02 9.96097922e-01 -6.62766770e-02 5.81392050e-02 9.95852411e-01 -6.98428676e-02 5.81394099e-02 9.95606184e-01 -7.33041465e-02 5.81392981e-02 9.95347619e-01 -7.67239332e-02 5.81394359e-02 9.95079279e-01 -8.01288635e-02 5.81393093e-02 9.94795382e-01 -8.35788026e-02 5.81393465e-02 9.94488120e-01 -8.71573314e-02 5.81392087e-02 9.94179547e-01 -9.06174481e-02 5.81394769e-02 9.93866265e-01 -9.39909890e-02 5.81392944e-02 9.93532777e-01 -9.74573344e-02 5.81393167e-02 9.93174314e-01 -1.01026580e-01 5.81390820e-02 9.92817938e-01 -1.04491986e-01 5.81394844e-02 9.92446423e-01 -1.07937329e-01 5.81390895e-02 9.92065907e-01 -1.11410983e-01 5.81395552e-02 9.91682053e-01 -1.14754245e-01 5.81392646e-02 9.91264522e-01 -1.18312091e-01 5.81391491e-02 9.90845144e-01 -1.21787243e-01 5.81394918e-02 9.90413427e-01 -1.25251383e-01 5.81391379e-02 9.89954889e-01 -1.28802791e-01 5.81391864e-02 9.89511847e-01 -1.32177278e-01 5.81394993e-02 9.89051104e-01 -1.35587975e-01 5.81391715e-02 9.88556504e-01 -1.39146611e-01 5.81392944e-02 9.88075614e-01 -1.42522573e-01 5.81395067e-02 9.87571895e-01 -1.45959392e-01 5.81391379e-02 9.87058282e-01 -1.49398297e-01 5.81394173e-02 9.86532331e-01 -1.52821288e-01 5.81391305e-02 9.85986173e-01 -1.56316489e-01 5.81395738e-02 9.85438287e-01 -1.59735262e-01 5.81392534e-02 9.84883428e-01 -1.63128510e-01 5.81394583e-02 9.84300733e-01 -1.66604891e-01 5.81391864e-02 9.83696640e-01 -1.70120284e-01 5.81393130e-02 9.83104765e-01 -1.73539877e-01 5.81392869e-02 9.82503474e-01 -1.76911190e-01 5.81394061e-02 9.81888354e-01 -1.80264562e-01 5.81393614e-02 9.81256366e-01 -1.83693573e-01 5.81393391e-02 9.80598092e-01 -1.87159717e-01 5.81391640e-02 9.79922593e-01 -1.90668255e-01 5.81392832e-02 9.79249775e-01 -1.94100186e-01 5.81393279e-02 9.78578687e-01 -1.97453216e-01 5.81395067e-02 9.77902949e-01 -2.00771853e-01 5.81393875e-02 9.77197468e-01 -2.04182968e-01 5.81394210e-02 9.76460278e-01 -2.07680389e-01 5.81391230e-02 9.75730658e-01 -2.11084574e-01 5.81394769e-02 9.75003064e-01 -2.14407846e-01 5.81392422e-02 9.74241734e-01 -2.17854217e-01 5.81394359e-02 9.73466814e-01 -2.21275806e-01 5.81391118e-02 9.72688019e-01 -2.24689096e-01 5.81395254e-02 9.71899152e-01 -2.28078201e-01 5.81391305e-02 9.71091509e-01 -2.31494680e-01 5.81395291e-02 9.70312834e-01 -2.34738603e-01 5.81393279e-02 9.69456196e-01 -2.38238841e-01 5.81391528e-02 9.68617499e-01 -2.41628498e-01 5.81395254e-02 9.67758417e-01 -2.45040134e-01 5.81391864e-02 9.66878057e-01 -2.48498321e-01 5.81393950e-02 9.66031492e-01 -2.51773059e-01 5.81395738e-02 9.65161026e-01 -2.55093694e-01 5.81392124e-02 9.64254320e-01 -2.58501291e-01 5.81395738e-02 9.63378251e-01 -2.61744291e-01 5.81393540e-02 9.62434292e-01 -2.65184581e-01 5.81392422e-02 9.61494684e-01 -2.68585891e-01 5.81395738e-02 9.60547745e-01 -2.71941632e-01 5.81392311e-02 9.59564090e-01 -2.75388390e-01 5.81392795e-02 9.58623052e-01 -2.78651357e-01 5.81395738e-02 9.57677841e-01 -2.81881571e-01 5.81393205e-02 9.56660807e-01 -2.85317570e-01 5.81392385e-02 9.55641508e-01 -2.88703263e-01 5.81393912e-02 9.54631329e-01 -2.92032808e-01 5.81393503e-02 9.53623235e-01 -2.95315474e-01 5.81395142e-02 9.52613115e-01 -2.98552960e-01 5.81393391e-02 9.51572239e-01 -3.01851809e-01 5.81393763e-02 9.50475335e-01 -3.05287421e-01 5.81391789e-02 9.49368119e-01 -3.08710963e-01 5.81392534e-02 9.48292315e-01 -3.12003106e-01 5.81394397e-02 9.47220623e-01 -3.15245628e-01 5.81395738e-02 9.46149588e-01 -3.18443447e-01 5.81393614e-02 9.45035398e-01 -3.21733952e-01 5.81393689e-02 9.43881691e-01 -3.25101197e-01 5.81391789e-02 9.42721248e-01 -3.28451544e-01 5.81394844e-02 9.41603303e-01 -3.31645399e-01 5.81394024e-02 9.40447092e-01 -3.34907025e-01 5.81393056e-02 9.39241409e-01 -3.38274300e-01 5.81391491e-02 9.38057840e-01 -3.41552168e-01 5.81395552e-02 9.36845779e-01 -3.44837546e-01 5.81392385e-02 9.35628593e-01 -3.48113209e-01 5.81395105e-02 9.34449255e-01 -3.51274014e-01 5.81392832e-02 9.33219552e-01 -3.54539037e-01 5.81393391e-02 9.31983769e-01 -3.57798785e-01 5.81393279e-02 9.30716813e-01 -3.61061007e-01 5.81392832e-02 9.29428160e-01 -3.64375561e-01 5.81391715e-02 9.28149283e-01 -3.67619067e-01 5.81395254e-02 9.26874578e-01 -3.70817035e-01 5.81391528e-02 9.25560296e-01 -3.74087960e-01 5.81394993e-02 9.24289465e-01 -3.77217829e-01 5.81393056e-02 9.22932625e-01 -3.80521655e-01 5.81391789e-02 9.21589494e-01 -3.83768290e-01 5.81394583e-02 9.20238972e-01 -3.86994630e-01 5.81391715e-02 9.18848574e-01 -3.90278995e-01 5.81392832e-02 9.17513430e-01 -3.93408358e-01 5.81395403e-02 9.16202486e-01 -3.96455586e-01 5.81393763e-02 9.14767325e-01 -3.99759144e-01 5.81391715e-02 9.13305521e-01 -4.03083891e-01 5.81392236e-02 9.11893129e-01 -4.06269938e-01 5.81393503e-02 9.10482407e-01 -4.09425139e-01 5.81394918e-02 9.09080088e-01 -4.12525505e-01 5.81394844e-02 9.07677114e-01 -4.15600002e-01 5.81393912e-02 9.06186342e-01 -4.18840110e-01 5.81392869e-02 9.04675364e-01 -4.22095507e-01 5.81393391e-02 9.03180659e-01 -4.25285369e-01 5.81393167e-02 9.01732981e-01 -4.28348303e-01 5.81395105e-02 9.00293291e-01 -4.31361854e-01 5.81393093e-02 8.98773968e-01 -4.34526950e-01 5.81392944e-02 8.97209346e-01 -4.37747598e-01 5.81392050e-02 8.95639539e-01 -4.40945834e-01 5.81393726e-02 8.94107580e-01 -4.44044471e-01 5.81393130e-02 8.92567694e-01 -4.47132319e-01 5.81395105e-02 8.91054928e-01 -4.50141311e-01 5.81393316e-02 8.89475882e-01 -4.53252226e-01 5.81392832e-02 8.87849867e-01 -4.56427634e-01 5.81391267e-02 8.86246443e-01 -4.59533095e-01 5.81394210e-02 8.84629548e-01 -4.62641001e-01 5.81392832e-02 8.83031547e-01 -4.65685427e-01 5.81394508e-02 8.81433606e-01 -4.68699604e-01 5.81394210e-02 8.79788518e-01 -4.71781164e-01 5.81392720e-02 8.78085852e-01 -4.74939317e-01 5.81390671e-02 8.76420379e-01 -4.78014141e-01 5.81395216e-02 8.74801993e-01 -4.80962962e-01 5.81393018e-02 8.73104751e-01 -4.84034121e-01 5.81393354e-02 8.71378958e-01 -4.87135351e-01 5.81391752e-02 8.69670749e-01 -4.90183771e-01 5.81395440e-02 8.67951751e-01 -4.93215472e-01 5.81390858e-02 8.66228223e-01 -4.96243656e-01 5.81394918e-02 8.64507377e-01 -4.99229282e-01 5.81391640e-02 8.62732053e-01 -5.02294898e-01 5.81395067e-02 8.61025870e-01 -5.05213022e-01 5.81393018e-02 8.59235704e-01 -5.08252323e-01 5.81392609e-02 8.57436359e-01 -5.11279583e-01 5.81392795e-02 8.55625451e-01 -5.14304459e-01 5.81391752e-02 8.53808939e-01 -5.17312229e-01 5.81392720e-02 8.52024019e-01 -5.20251811e-01 5.81394248e-02 8.50257695e-01 -5.23128331e-01 5.81392236e-02 8.48437250e-01 -5.26080906e-01 5.81392944e-02 8.46548557e-01 -5.29109180e-01 5.81391044e-02 8.44651341e-01 -5.32135189e-01 5.81392609e-02 8.42835128e-01 -5.35007834e-01 5.81394210e-02 8.41001570e-01 -5.37884176e-01 5.81392720e-02 8.39072406e-01 -5.40888309e-01 5.81391193e-02 8.37122977e-01 -5.43901622e-01 5.81392944e-02 8.35236311e-01 -5.46791315e-01 5.81393391e-02 8.33325624e-01 -5.49702823e-01 5.81393056e-02 8.31441581e-01 -5.52545428e-01 5.81395738e-02 8.29550743e-01 -5.55381179e-01 5.81393950e-02 8.27627182e-01 -5.58248520e-01 5.81392869e-02 8.25611055e-01 -5.61221004e-01 5.81392087e-02 8.23588908e-01 -5.64187109e-01 5.81394024e-02 8.21626544e-01 -5.67043126e-01 5.81394210e-02 8.19709361e-01 -5.69808841e-01 5.81394918e-02 8.17728937e-01 -5.72644591e-01 5.81393167e-02 8.15714002e-01 -5.75516462e-01 5.81394769e-02 8.13678324e-01 -5.78386366e-01 5.81391864e-02 8.11653674e-01 -5.81227899e-01 5.81395738e-02 8.09641004e-01 -5.84021091e-01 5.81392646e-02 8.07571292e-01 -5.86884141e-01 5.81392944e-02 8.05467427e-01 -5.89766860e-01 5.81392981e-02 8.03404331e-01 -5.92575192e-01 5.81392646e-02 8.01319063e-01 -5.95392108e-01 5.81393726e-02 7.99292088e-01 -5.98110557e-01 5.81395477e-02 7.97223628e-01 -6.00864828e-01 5.81390671e-02 7.95100510e-01 -6.03673279e-01 5.81395179e-02 7.92988658e-01 -6.06442392e-01 5.81390858e-02 7.90866375e-01 -6.09208822e-01 5.81394657e-02 7.88807571e-01 -6.11870348e-01 5.81392795e-02 7.86609650e-01 -6.14692450e-01 5.81390820e-02 7.84388781e-01 -6.17525876e-01 5.81393018e-02 7.82286108e-01 -6.20186746e-01 5.81394248e-02 7.80184150e-01 -6.22830927e-01 5.81392124e-02 7.77950346e-01 -6.25617862e-01 5.81390820e-02 7.75704026e-01 -6.28401875e-01 5.81392609e-02 7.73547113e-01 -6.31050766e-01 5.81393689e-02 7.71401942e-01 -6.33674383e-01 5.81392385e-02 7.69181013e-01 -6.36369169e-01 5.81393167e-02 7.66974032e-01 -6.39026523e-01 5.81392385e-02 7.64742255e-01 -6.41695380e-01 5.81392422e-02 7.62431085e-01 -6.44438744e-01 5.81391305e-02 7.60178447e-01 -6.47095263e-01 5.81394322e-02 7.57977724e-01 -6.49670780e-01 5.81392385e-02 7.55712807e-01 -6.52306139e-01 5.81393093e-02 7.53407419e-01 -6.54967427e-01 5.81391454e-02 7.51052082e-01 -6.57665074e-01 5.81391081e-02 7.48702466e-01 -6.60339475e-01 5.81392869e-02 7.46445656e-01 -6.62891269e-01 5.81394359e-02 7.44203389e-01 -6.65406942e-01 5.81392422e-02 7.41826057e-01 -6.68055296e-01 5.81390969e-02 7.39484906e-01 -6.70648038e-01 5.81394210e-02 7.37128019e-01 -6.73233390e-01 5.81390075e-02 7.34778702e-01 -6.75801396e-01 5.81395067e-02 7.32493877e-01 -6.78274989e-01 5.81392422e-02 7.30129898e-01 -6.80817425e-01 5.81392273e-02 7.27683187e-01 -6.83431685e-01 5.81390522e-02 7.25272834e-01 -6.85989857e-01 5.81394508e-02 7.22865880e-01 -6.88528895e-01 5.81390373e-02 7.20452726e-01 -6.91047430e-01 5.81395365e-02 7.18071818e-01 -6.93534374e-01 5.81391193e-02 7.15623319e-01 -6.96059048e-01 5.81395738e-02 7.13263392e-01 -6.98472798e-01 5.81395663e-02 7.10791707e-01 -7.00992227e-01 5.81395552e-02 7.08298981e-01 -7.03510821e-01 5.81395067e-02 7.05861032e-01 -7.05956101e-01 5.81394695e-02 7.03376532e-01 -7.08438039e-01 5.81393652e-02 7.00997055e-01 -7.10787296e-01 5.81389032e-02 6.98622584e-01 -7.13121474e-01 5.81389330e-02 6.96172416e-01 -7.15516746e-01 5.81390634e-02 6.93516076e-01 -7.18090653e-01 5.81390448e-02 6.91173196e-01 -7.20345974e-01 5.81390262e-02 6.89209759e-01 -7.22225547e-01 5.81390262e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.69604397e-01 -8.19858670e-01 5.81390262e-02 5.66244304e-01 -8.22182775e-01 5.81389442e-02 5.63848615e-01 -8.23829234e-01 5.81394136e-02 5.61051369e-01 -8.25731993e-01 5.81394993e-02 5.58164358e-01 -8.27685535e-01 5.81395403e-02 5.55294454e-01 -8.29610467e-01 5.81395663e-02 5.52341700e-01 -8.31577361e-01 5.81394099e-02 5.49411833e-01 -8.33517790e-01 5.81395701e-02 5.46581328e-01 -8.35375726e-01 5.81394956e-02 5.43700516e-01 -8.37253869e-01 5.81393465e-02 5.40768802e-01 -8.39150608e-01 5.81392907e-02 5.37840426e-01 -8.41028273e-01 5.81392422e-02 5.34898162e-01 -8.42902839e-01 5.81392050e-02 5.31968713e-01 -8.44758749e-01 5.81392869e-02 5.29025197e-01 -8.46600533e-01 5.81392832e-02 5.26067138e-01 -8.48445833e-01 5.81392832e-02 5.23111343e-01 -8.50267947e-01 5.81392273e-02 5.20141304e-01 -8.52092385e-01 5.81392422e-02 5.17158926e-01 -8.53901744e-01 5.81392311e-02 5.14168739e-01 -8.55706990e-01 5.81392646e-02 5.11106253e-01 -8.57539237e-01 5.81390895e-02 5.08083463e-01 -8.59334528e-01 5.81394173e-02 5.05174220e-01 -8.61047924e-01 5.81392311e-02 5.02165318e-01 -8.62805963e-01 5.81392758e-02 4.99065369e-01 -8.64602447e-01 5.81390560e-02 4.96024609e-01 -8.66352141e-01 5.81394173e-02 4.93074358e-01 -8.68031919e-01 5.81392795e-02 4.90072101e-01 -8.69734704e-01 5.81392758e-02 4.87031281e-01 -8.71437669e-01 5.81392273e-02 4.83992755e-01 -8.73126686e-01 5.81391789e-02 4.80944902e-01 -8.74813437e-01 5.81392646e-02 4.77882326e-01 -8.76490116e-01 5.81393018e-02 4.74794507e-01 -8.78163934e-01 5.81392124e-02 4.71731126e-01 -8.79814565e-01 5.81392720e-02 4.68661875e-01 -8.81453097e-01 5.81392534e-02 4.65578288e-01 -8.83087933e-01 5.81393018e-02 4.62444723e-01 -8.84729624e-01 5.81390671e-02 4.59333092e-01 -8.86349857e-01 5.81393801e-02 4.56302464e-01 -8.87915254e-01 5.81392571e-02 4.53216523e-01 -8.89493704e-01 5.81392683e-02 4.50099826e-01 -8.91075015e-01 5.81392422e-02 4.46986258e-01 -8.92639816e-01 5.81392720e-02 4.43857133e-01 -8.94201279e-01 5.81392050e-02 4.40732539e-01 -8.95745575e-01 5.81392609e-02 4.37593609e-01 -8.97283196e-01 5.81392720e-02 4.34443414e-01 -8.98812950e-01 5.81392273e-02 4.31320518e-01 -9.00313139e-01 5.81392683e-02 4.28066820e-01 -9.01863217e-01 5.81389889e-02 4.24900919e-01 -9.03362334e-01 5.81394508e-02 4.21780884e-01 -9.04822767e-01 5.81390336e-02 4.18593436e-01 -9.06302691e-01 5.81394359e-02 4.15528506e-01 -9.07709956e-01 5.81392422e-02 4.12370771e-01 -9.09150422e-01 5.81392534e-02 4.09173697e-01 -9.10593629e-01 5.81392348e-02 4.05920506e-01 -9.12048221e-01 5.81390448e-02 4.02706057e-01 -9.13472533e-01 5.81394508e-02 3.99617642e-01 -9.14829314e-01 5.81392795e-02 3.96436453e-01 -9.16209400e-01 5.81391938e-02 3.93225223e-01 -9.17590082e-01 5.81391789e-02 3.89979333e-01 -9.18976724e-01 5.81392124e-02 3.86787981e-01 -9.20326233e-01 5.81392683e-02 3.83593768e-01 -9.21661377e-01 5.81391901e-02 3.80354434e-01 -9.23002183e-01 5.81393279e-02 3.77173692e-01 -9.24308240e-01 5.81392907e-02 3.73959661e-01 -9.25611496e-01 5.81392087e-02 3.70632112e-01 -9.26948130e-01 5.81390448e-02 3.67356807e-01 -9.28253591e-01 5.81393652e-02 3.64202648e-01 -9.29496229e-01 5.81392422e-02 3.60972315e-01 -9.30748224e-01 5.81392571e-02 3.57717931e-01 -9.32013154e-01 5.81392013e-02 3.54441851e-01 -9.33256507e-01 5.81392422e-02 3.51192445e-01 -9.34479356e-01 5.81392236e-02 3.47912520e-01 -9.35704410e-01 5.81392422e-02 3.44571680e-01 -9.36944664e-01 5.81390597e-02 3.41287822e-01 -9.38153684e-01 5.81394136e-02 3.38046044e-01 -9.39322412e-01 5.81390895e-02 3.34755212e-01 -9.40503538e-01 5.81394173e-02 3.31462532e-01 -9.41666126e-01 5.81391007e-02 3.28179002e-01 -9.42815781e-01 5.81393838e-02 3.24883789e-01 -9.43956792e-01 5.81390820e-02 3.21567923e-01 -9.45090532e-01 5.81394322e-02 3.18361104e-01 -9.46177304e-01 5.81392162e-02 3.15039933e-01 -9.47286248e-01 5.81391789e-02 3.11720967e-01 -9.48384106e-01 5.81393391e-02 3.08449268e-01 -9.49453235e-01 5.81392422e-02 3.05105865e-01 -9.50534046e-01 5.81391715e-02 3.01815331e-01 -9.51582968e-01 5.81392683e-02 2.98504114e-01 -9.52627718e-01 5.81392311e-02 2.95154572e-01 -9.53671336e-01 5.81392683e-02 2.91833431e-01 -9.54692900e-01 5.81392460e-02 2.88445681e-01 -9.55718338e-01 5.81390932e-02 2.85089821e-01 -9.56727624e-01 5.81393689e-02 2.81817019e-01 -9.57697034e-01 5.81392534e-02 2.78389782e-01 -9.58698332e-01 5.81390820e-02 2.74955183e-01 -9.59689140e-01 5.81391789e-02 2.71602809e-01 -9.60643709e-01 5.81392348e-02 2.68363178e-01 -9.61555362e-01 5.81394471e-02 2.65107036e-01 -9.62456226e-01 5.81392609e-02 2.61739820e-01 -9.63380039e-01 5.81392385e-02 2.58387268e-01 -9.64281440e-01 5.81392311e-02 2.54909635e-01 -9.65206325e-01 5.81390075e-02 2.51520634e-01 -9.66097772e-01 5.81394546e-02 2.48169616e-01 -9.66960967e-01 5.81390671e-02 2.44765341e-01 -9.67829168e-01 5.81394508e-02 2.41432503e-01 -9.68663990e-01 5.81390858e-02 2.38007665e-01 -9.69514549e-01 5.81393912e-02 2.34710038e-01 -9.70318675e-01 5.81392236e-02 2.31307223e-01 -9.71135736e-01 5.81391305e-02 2.27901325e-01 -9.71940637e-01 5.81392609e-02 2.24533111e-01 -9.72723722e-01 5.81391864e-02 2.21032336e-01 -9.73523021e-01 5.81390187e-02 2.17631340e-01 -9.74291503e-01 5.81394061e-02 2.14330703e-01 -9.75020468e-01 5.81392497e-02 2.10901216e-01 -9.75768507e-01 5.81392422e-02 2.07513690e-01 -9.76495266e-01 5.81392534e-02 2.04020843e-01 -9.77231145e-01 5.81390932e-02 2.00589448e-01 -9.77942407e-01 5.81394136e-02 1.97266027e-01 -9.78616238e-01 5.81392460e-02 1.93854034e-01 -9.79298115e-01 5.81392571e-02 1.90430865e-01 -9.79969442e-01 5.81391938e-02 1.86923206e-01 -9.80642676e-01 5.81390932e-02 1.83498234e-01 -9.81291115e-01 5.81394210e-02 1.80068880e-01 -9.81923997e-01 5.81391081e-02 1.76630840e-01 -9.82555449e-01 5.81394099e-02 1.73304290e-01 -9.83146787e-01 5.81392422e-02 1.69884205e-01 -9.83737469e-01 5.81392050e-02 1.66454360e-01 -9.84326482e-01 5.81392236e-02 1.63015306e-01 -9.84899938e-01 5.81392460e-02 1.59574404e-01 -9.85464096e-01 5.81392609e-02 1.56144589e-01 -9.86014009e-01 5.81392050e-02 1.52717978e-01 -9.86550272e-01 5.81392124e-02 1.49258554e-01 -9.87077355e-01 5.81392162e-02 1.45763353e-01 -9.87600386e-01 5.81391007e-02 1.42315447e-01 -9.88102436e-01 5.81393428e-02 1.38905674e-01 -9.88588691e-01 5.81392907e-02 1.35356382e-01 -9.89080966e-01 5.81390634e-02 1.31887183e-01 -9.89549637e-01 5.81394061e-02 1.28522620e-01 -9.89993036e-01 5.81392609e-02 1.25082582e-01 -9.90434110e-01 5.81392124e-02 1.21618032e-01 -9.90863740e-01 5.81391715e-02 1.18059099e-01 -9.91293788e-01 5.81390336e-02 1.14594445e-01 -9.91700590e-01 5.81393540e-02 1.11242123e-01 -9.92082894e-01 5.81392422e-02 1.07760601e-01 -9.92466629e-01 5.81392609e-02 1.04317188e-01 -9.92834270e-01 5.81392422e-02 1.00753203e-01 -9.93200123e-01 5.81390597e-02 9.72767770e-02 -9.93549943e-01 5.81394061e-02 9.38219428e-02 -9.93882596e-01 5.81390336e-02 9.03297365e-02 -9.94206786e-01 5.81394359e-02 8.68895352e-02 -9.94511664e-01 5.81390858e-02 8.33240971e-02 -9.94816303e-01 5.81392236e-02 7.99360871e-02 -9.95095849e-01 5.81394024e-02 7.65422061e-02 -9.95360434e-01 5.81391640e-02 7.30727166e-02 -9.95622873e-01 5.81391938e-02 6.95914328e-02 -9.95870054e-01 5.81391826e-02 6.61061779e-02 -9.96109307e-01 5.81392162e-02 6.26576021e-02 -9.96331871e-01 5.81391789e-02 5.91644645e-02 -9.96544898e-01 5.81392311e-02 5.56750000e-02 -9.96746957e-01 5.81391975e-02 5.22039421e-02 -9.96932566e-01 5.81392422e-02 4.87378277e-02 -9.97110963e-01 5.81392124e-02 4.52746302e-02 -9.97273147e-01 5.81391864e-02 4.16769795e-02 -9.97427881e-01 5.81389777e-02 3.81917618e-02 -9.97569442e-01 5.81394322e-02 3.48458365e-02 -9.97691393e-01 5.81392236e-02 3.12457643e-02 -9.97809947e-01 5.81390783e-02 2.77433079e-02 -9.97915804e-01 5.81393577e-02 2.42533535e-02 -9.98007298e-01 5.81390411e-02 2.07658093e-02 -9.98082817e-01 5.81394322e-02 1.74134392e-02 -9.98152673e-01 5.81391975e-02 1.38317076e-02 -9.98197615e-01 5.81389926e-02 1.03151863e-02 -9.98247266e-01 5.81393763e-02 6.94960915e-03 -9.98282492e-01 5.81391677e-02 3.45439557e-03 -9.98299539e-01 5.81391938e-02 -3.91421454e-05 -9.98300552e-01 5.81391677e-02 -3.61077930e-03 -9.98298883e-01 5.81390522e-02 -7.09374389e-03 -9.98281717e-01 5.81393912e-02 -1.05787376e-02 -9.98244166e-01 5.81390597e-02 -1.40488949e-02 -9.98197794e-01 5.81393726e-02 -1.75228324e-02 -9.98151720e-01 5.81390597e-02 -2.10969839e-02 -9.98075128e-01 5.81391826e-02 -2.45146342e-02 -9.98001635e-01 5.81393316e-02 -2.79218927e-02 -9.97910440e-01 5.81391826e-02 -3.13946232e-02 -9.97807622e-01 5.81391789e-02 -3.48700583e-02 -9.97692406e-01 5.81391267e-02 -3.84548008e-02 -9.97558832e-01 5.81389889e-02 -4.19494137e-02 -9.97419775e-01 5.81393614e-02 -4.53256182e-02 -9.97269869e-01 5.81391715e-02 -4.87944297e-02 -9.97108281e-01 5.81391789e-02 -5.22748530e-02 -9.96928692e-01 5.81392050e-02 -5.58259562e-02 -9.96738911e-01 5.81390336e-02 -5.93230464e-02 -9.96537209e-01 5.81393614e-02 -6.27978966e-02 -9.96319950e-01 5.81390858e-02 -6.62728250e-02 -9.96097624e-01 5.81393503e-02 -6.96499646e-02 -9.95866477e-01 5.81391864e-02 -7.32129514e-02 -9.95611727e-01 5.81390336e-02 -7.66976327e-02 -9.95348871e-01 5.81393093e-02 -8.01645815e-02 -9.95075643e-01 5.81390858e-02 -8.36510733e-02 -9.94788706e-01 5.81393316e-02 -8.70366469e-02 -9.94498610e-01 5.81392050e-02 -9.05829221e-02 -9.94180799e-01 5.81390187e-02 -9.40706655e-02 -9.93857920e-01 5.81393354e-02 -9.75236446e-02 -9.93524194e-01 5.81390038e-02 -1.00997724e-01 -9.93179321e-01 5.81394136e-02 -1.04446672e-01 -9.92821038e-01 5.81389666e-02 -1.08028695e-01 -9.92437959e-01 5.81392013e-02 -1.11389704e-01 -9.92066979e-01 5.81393614e-02 -1.14739053e-01 -9.91684020e-01 5.81391789e-02 -1.18223198e-01 -9.91274238e-01 5.81391603e-02 -1.21666037e-01 -9.90858734e-01 5.81391416e-02 -1.25224024e-01 -9.90415335e-01 5.81389889e-02 -1.28706560e-01 -9.89967704e-01 5.81393205e-02 -1.32050961e-01 -9.89528656e-01 5.81391640e-02 -1.35491148e-01 -9.89063084e-01 5.81391677e-02 -1.38935447e-01 -9.88585472e-01 5.81391267e-02 -1.42510951e-01 -9.88074303e-01 5.81390150e-02 -1.45942330e-01 -9.87574577e-01 5.81393652e-02 -1.49376586e-01 -9.87059057e-01 5.81390001e-02 -1.52835786e-01 -9.86533821e-01 5.81393801e-02 -1.56165853e-01 -9.86009121e-01 5.81391864e-02 -1.59633800e-01 -9.85454798e-01 5.81391715e-02 -1.63051650e-01 -9.84896064e-01 5.81392236e-02 -1.66594520e-01 -9.84302223e-01 5.81390038e-02 -1.70050994e-01 -9.83710051e-01 5.81394061e-02 -1.73380315e-01 -9.83132303e-01 5.81391454e-02 -1.76875517e-01 -9.82508302e-01 5.81390932e-02 -1.80301756e-01 -9.81881380e-01 5.81392571e-02 -1.83759332e-01 -9.81242776e-01 5.81390113e-02 -1.87199891e-01 -9.80591834e-01 5.81394173e-02 -1.90519273e-01 -9.79952037e-01 5.81392311e-02 -1.93950474e-01 -9.79278624e-01 5.81391975e-02 -1.97429702e-01 -9.78583157e-01 5.81390671e-02 -2.00880781e-01 -9.77880180e-01 5.81393801e-02 -2.04206929e-01 -9.77190793e-01 5.81392236e-02 -2.07591251e-01 -9.76480126e-01 5.81392124e-02 -2.11092100e-01 -9.75727856e-01 5.81390709e-02 -2.14512423e-01 -9.74978864e-01 5.81393279e-02 -2.17815384e-01 -9.74249065e-01 5.81392050e-02 -2.21217886e-01 -9.73480821e-01 5.81391826e-02 -2.24618062e-01 -9.72701848e-01 5.81392013e-02 -2.28086114e-01 -9.71898079e-01 5.81390671e-02 -2.31483296e-01 -9.71093297e-01 5.81393316e-02 -2.34779879e-01 -9.70302165e-01 5.81391975e-02 -2.38232851e-01 -9.69458282e-01 5.81390560e-02 -2.41636664e-01 -9.68615174e-01 5.81393503e-02 -2.45019123e-01 -9.67762828e-01 5.81390522e-02 -2.48388320e-01 -9.66907084e-01 5.81393763e-02 -2.51666903e-01 -9.66057777e-01 5.81392422e-02 -2.55056500e-01 -9.65169311e-01 5.81392199e-02 -2.58494586e-01 -9.64252174e-01 5.81390448e-02 -2.61959255e-01 -9.63318706e-01 5.81392087e-02 -2.65241563e-01 -9.62419450e-01 5.81393950e-02 -2.68494934e-01 -9.61517930e-01 5.81391677e-02 -2.71877050e-01 -9.60566759e-01 5.81391864e-02 -2.75216073e-01 -9.59613562e-01 5.81391975e-02 -2.78568089e-01 -9.58647490e-01 5.81392348e-02 -2.81898290e-01 -9.57672358e-01 5.81391975e-02 -2.85233498e-01 -9.56685960e-01 5.81391975e-02 -2.88576573e-01 -9.55680072e-01 5.81392124e-02 -2.91907519e-01 -9.54667449e-01 5.81391938e-02 -2.95320809e-01 -9.53620374e-01 5.81390820e-02 -2.98688591e-01 -9.52569842e-01 5.81393465e-02 -3.01992327e-01 -9.51527059e-01 5.81391305e-02 -3.05302799e-01 -9.50472176e-01 5.81393950e-02 -3.08512628e-01 -9.49433625e-01 5.81392385e-02 -3.11914235e-01 -9.48320568e-01 5.81390634e-02 -3.15291882e-01 -9.47203815e-01 5.81392981e-02 -3.18578660e-01 -9.46105182e-01 5.81392013e-02 -3.21841955e-01 -9.44999039e-01 5.81394397e-02 -3.25035393e-01 -9.43905413e-01 5.81392609e-02 -3.28352720e-01 -9.42754567e-01 5.81392050e-02 -3.31650168e-01 -9.41601336e-01 5.81392609e-02 -3.34985167e-01 -9.40419555e-01 5.81392422e-02 -3.38276714e-01 -9.39239681e-01 5.81394285e-02 -3.41544032e-01 -9.38058197e-01 5.81391379e-02 -3.44807833e-01 -9.36856091e-01 5.81394136e-02 -3.47996354e-01 -9.35672700e-01 5.81392236e-02 -3.51272076e-01 -9.34448838e-01 5.81392609e-02 -3.54539156e-01 -9.33219850e-01 5.81392236e-02 -3.57884496e-01 -9.31949794e-01 5.81391081e-02 -3.61228675e-01 -9.30651069e-01 5.81391938e-02 -3.64388704e-01 -9.29422498e-01 5.81394695e-02 -3.67523611e-01 -9.28187132e-01 5.81392534e-02 -3.70746285e-01 -9.26903367e-01 5.81392460e-02 -3.73974979e-01 -9.25606072e-01 5.81392981e-02 -3.77292722e-01 -9.24257457e-01 5.81389964e-02 -3.80609632e-01 -9.22895670e-01 5.81392646e-02 -3.83759141e-01 -9.21592474e-01 5.81394434e-02 -3.86864036e-01 -9.20293152e-01 5.81392050e-02 -3.90092760e-01 -9.18928862e-01 5.81392236e-02 -3.93377364e-01 -9.17523384e-01 5.81391156e-02 -3.96598577e-01 -9.16140497e-01 5.81394807e-02 -3.99757892e-01 -9.14766967e-01 5.81391267e-02 -4.02985424e-01 -9.13350105e-01 5.81394769e-02 -4.06059533e-01 -9.11986887e-01 5.81392832e-02 -4.09267664e-01 -9.10552859e-01 5.81393689e-02 -4.12443697e-01 -9.09116030e-01 5.81392869e-02 -4.15656507e-01 -9.07650173e-01 5.81390746e-02 -4.18840796e-01 -9.06187057e-01 5.81393987e-02 -4.21921611e-01 -9.04756546e-01 5.81392609e-02 -4.25076038e-01 -9.03279662e-01 5.81392571e-02 -4.28308994e-01 -9.01749969e-01 5.81390522e-02 -4.31461304e-01 -9.00245249e-01 5.81393912e-02 -4.34509248e-01 -8.98783386e-01 5.81392422e-02 -4.37656313e-01 -8.97254467e-01 5.81392460e-02 -4.40854311e-01 -8.95683706e-01 5.81391081e-02 -4.43975270e-01 -8.94144297e-01 5.81393987e-02 -4.47009861e-01 -8.92629206e-01 5.81392162e-02 -4.50133801e-01 -8.91058981e-01 5.81392236e-02 -4.53229964e-01 -8.89487684e-01 5.81392273e-02 -4.56406325e-01 -8.87861013e-01 5.81390522e-02 -4.59507167e-01 -8.86259377e-01 5.81393912e-02 -4.62516963e-01 -8.84695470e-01 5.81392124e-02 -4.65597272e-01 -8.83076251e-01 5.81392348e-02 -4.68655974e-01 -8.81456912e-01 5.81392124e-02 -4.71827060e-01 -8.79764140e-01 5.81391267e-02 -4.74913508e-01 -8.78100514e-01 5.81394061e-02 -4.77967441e-01 -8.76443386e-01 5.81390671e-02 -4.81013924e-01 -8.74775112e-01 5.81394434e-02 -4.84073877e-01 -8.73082459e-01 5.81390150e-02 -4.87210959e-01 -8.71336818e-01 5.81392609e-02 -4.90162790e-01 -8.69682133e-01 5.81394359e-02 -4.93173629e-01 -8.67976367e-01 5.81389964e-02 -4.96232897e-01 -8.66233468e-01 5.81394508e-02 -4.99158353e-01 -8.64549398e-01 5.81391975e-02 -5.02184570e-01 -8.62794161e-01 5.81391640e-02 -5.05187631e-01 -8.61040771e-01 5.81392460e-02 -5.08185565e-01 -8.59274447e-01 5.81392311e-02 -5.11168897e-01 -8.57501864e-01 5.81392944e-02 -5.14175713e-01 -8.55704188e-01 5.81392609e-02 -5.17180145e-01 -8.53888869e-01 5.81391230e-02 -5.20238101e-01 -8.52031946e-01 5.81391305e-02 -5.23264050e-01 -8.50174487e-01 5.81391454e-02 -5.26158452e-01 -8.48388374e-01 5.81393465e-02 -5.29023290e-01 -8.46605122e-01 5.81391789e-02 -5.32061815e-01 -8.44696224e-01 5.81389852e-02 -5.35017014e-01 -8.42829168e-01 5.81394061e-02 -5.37943900e-01 -8.40962589e-01 5.81390597e-02 -5.40895581e-01 -8.39068174e-01 5.81394061e-02 -5.43717146e-01 -8.37242424e-01 5.81392385e-02 -5.46722531e-01 -8.35280836e-01 5.81390336e-02 -5.49644113e-01 -8.33365917e-01 5.81394657e-02 -5.52443981e-01 -8.31507206e-01 5.81392460e-02 -5.55362701e-01 -8.29562962e-01 5.81392236e-02 -5.58334172e-01 -8.27567935e-01 5.81389740e-02 -5.61241448e-01 -8.25596273e-01 5.81394024e-02 -5.64009488e-01 -8.23711812e-01 5.81392497e-02 -5.66894710e-01 -8.21727753e-01 5.81392981e-02 -5.69751620e-01 -8.19748104e-01 5.81391938e-02 -5.72691023e-01 -8.17694068e-01 5.81389777e-02 -5.75663567e-01 -8.15608859e-01 5.81391528e-02 -5.78427196e-01 -8.13650072e-01 5.81394285e-02 -5.81158578e-01 -8.11701834e-01 5.81391789e-02 -5.83974421e-01 -8.09674203e-01 5.81392534e-02 -5.86829364e-01 -8.07611465e-01 5.81391975e-02 -5.89715004e-01 -8.05503964e-01 5.81390858e-02 -5.92600942e-01 -8.03384960e-01 5.81392646e-02 -5.95324159e-01 -8.01370144e-01 5.81393987e-02 -5.98030984e-01 -7.99350142e-01 5.81392795e-02 -6.00826502e-01 -7.97251761e-01 5.81392013e-02 -6.03658617e-01 -7.95111656e-01 5.81390858e-02 -6.06462121e-01 -7.92974651e-01 5.81394136e-02 -6.09223068e-01 -7.90853500e-01 5.81390522e-02 -6.11975133e-01 -7.88727760e-01 5.81394769e-02 -6.14651620e-01 -7.86642432e-01 5.81392087e-02 -6.17459595e-01 -7.84441173e-01 5.81390671e-02 -6.20200574e-01 -7.82275796e-01 5.81394508e-02 -6.22925639e-01 -7.80106723e-01 5.81390448e-02 -6.25650644e-01 -7.77924597e-01 5.81394173e-02 -6.28272712e-01 -7.75809824e-01 5.81391975e-02 -6.30981565e-01 -7.73604155e-01 5.81391826e-02 -6.33669555e-01 -7.71406293e-01 5.81392422e-02 -6.36433482e-01 -7.69127548e-01 5.81390969e-02 -6.39122128e-01 -7.66894341e-01 5.81394099e-02 -6.41711533e-01 -7.64729500e-01 5.81392124e-02 -6.44456387e-01 -7.62415826e-01 5.81389815e-02 -6.47116244e-01 -7.60161221e-01 5.81394061e-02 -6.49687648e-01 -7.57964015e-01 5.81391416e-02 -6.52331531e-01 -7.55691290e-01 5.81391975e-02 -6.54953480e-01 -7.53420293e-01 5.81392087e-02 -6.57661378e-01 -7.51053512e-01 5.81390485e-02 -6.60277128e-01 -7.48758078e-01 5.81394024e-02 -6.62819862e-01 -7.46508360e-01 5.81392311e-02 -6.65424347e-01 -7.44186342e-01 5.81392124e-02 -6.68006301e-01 -7.41870344e-01 5.81391864e-02 -6.70660019e-01 -7.39474058e-01 5.81390932e-02 -6.73238039e-01 -7.37124085e-01 5.81393167e-02 -6.75810874e-01 -7.34769464e-01 5.81390634e-02 -6.78373098e-01 -7.32403576e-01 5.81393279e-02 -6.80921316e-01 -7.30031788e-01 5.81390150e-02 -6.83540225e-01 -7.27582037e-01 5.81391715e-02 -6.86011016e-01 -7.25252509e-01 5.81393726e-02 -6.88505352e-01 -7.22888589e-01 5.81390820e-02 -6.91056132e-01 -7.20444083e-01 5.81394210e-02 -6.93480909e-01 -7.18122482e-01 5.81391938e-02 -6.95980132e-01 -7.15698361e-01 5.81391864e-02 -6.98458791e-01 -7.13275433e-01 5.81391715e-02 -7.01028526e-01 -7.10751414e-01 5.81389442e-02 -7.03520775e-01 -7.08288908e-01 5.81394061e-02 -7.05887616e-01 -7.05909073e-01 5.81391230e-02 -7.08367527e-01 -7.03440785e-01 5.81391715e-02 -7.10892916e-01 -7.00885355e-01 5.81389330e-02 -7.13360846e-01 -6.98372900e-01 5.81393912e-02 -7.15708852e-01 -6.95970297e-01 5.81391677e-02 -7.18128085e-01 -6.93475246e-01 5.81391715e-02 -7.20596194e-01 -6.90895200e-01 5.81390262e-02 -7.23089218e-01 -6.88295543e-01 5.81391901e-02 -7.25491822e-01 -6.85756445e-01 5.81391379e-02 -7.27827609e-01 -6.83277965e-01 5.81393912e-02 -7.30122626e-01 -6.80823505e-01 5.81392124e-02 -7.32563794e-01 -6.78198218e-01 5.81390597e-02 -7.34933197e-01 -6.75633609e-01 5.81393801e-02 -7.37221837e-01 -6.73133254e-01 5.81391826e-02 -7.39576101e-01 -6.70546710e-01 5.81392013e-02 -7.41921902e-01 -6.67949259e-01 5.81392013e-02 -7.44236469e-01 -6.65369630e-01 5.81392422e-02 -7.46558189e-01 -6.62765205e-01 5.81391826e-02 -7.48932421e-01 -6.60077691e-01 5.81390411e-02 -7.51225471e-01 -6.57468855e-01 5.81394285e-02 -7.53509223e-01 -6.54846966e-01 5.81390373e-02 -7.55866528e-01 -6.52125537e-01 5.81392311e-02 -7.58073211e-01 -6.49562657e-01 5.81394136e-02 -7.60320544e-01 -6.46925569e-01 5.81389740e-02 -7.62593150e-01 -6.44250751e-01 5.81393503e-02 -7.64771163e-01 -6.41659617e-01 5.81391454e-02 -7.67058015e-01 -6.38926327e-01 5.81390262e-02 -7.69295335e-01 -6.36230230e-01 5.81393391e-02 -7.71450996e-01 -6.33615851e-01 5.81391864e-02 -7.73651421e-01 -6.30923450e-01 5.81391677e-02 -7.75853872e-01 -6.28215611e-01 5.81392534e-02 -7.78086543e-01 -6.25447333e-01 5.81390075e-02 -7.80327320e-01 -6.22649968e-01 5.81391603e-02 -7.82499075e-01 -6.19917989e-01 5.81391901e-02 -7.84615993e-01 -6.17238164e-01 5.81392869e-02 -7.86710918e-01 -6.14566207e-01 5.81391975e-02 -7.88896203e-01 -6.11756921e-01 5.81390485e-02 -7.91019619e-01 -6.09010398e-01 5.81393391e-02 -7.93137550e-01 -6.06247127e-01 5.81389889e-02 -7.95257926e-01 -6.03465259e-01 5.81393912e-02 -7.97289133e-01 -6.00779414e-01 5.81391864e-02 -7.99372613e-01 -5.98001003e-01 5.81392087e-02 -8.01450312e-01 -5.95211685e-01 5.81391454e-02 -8.03578019e-01 -5.92336893e-01 5.81390336e-02 -8.05655658e-01 -5.89511335e-01 5.81393391e-02 -8.07730734e-01 -5.86662650e-01 5.81390224e-02 -8.09818268e-01 -5.83775342e-01 5.81392422e-02 -8.11788440e-01 -5.81039190e-01 5.81393652e-02 -8.13799381e-01 -5.78215301e-01 5.81389889e-02 -8.15834463e-01 -5.75343966e-01 5.81393689e-02 -8.17777574e-01 -5.72575688e-01 5.81391715e-02 -8.19815874e-01 -5.69651306e-01 5.81389777e-02 -8.21822286e-01 -5.66759050e-01 5.81394359e-02 -8.23714972e-01 -5.64002275e-01 5.81391305e-02 -8.25696707e-01 -5.61095595e-01 5.81392087e-02 -8.27653646e-01 -5.58207214e-01 5.81391864e-02 -8.29647839e-01 -5.55234730e-01 5.81389852e-02 -8.31594110e-01 -5.52315891e-01 5.81393465e-02 -8.33506405e-01 -5.49424648e-01 5.81389889e-02 -8.35438192e-01 -5.46485186e-01 5.81393428e-02 -8.37282479e-01 -5.43656707e-01 5.81392050e-02 -8.39159787e-01 -5.40753305e-01 5.81391826e-02 -8.41033280e-01 -5.37834466e-01 5.81392124e-02 -8.42955053e-01 -5.34815729e-01 5.81390820e-02 -8.44812036e-01 -5.31881750e-01 5.81393316e-02 -8.46619725e-01 -5.28996527e-01 5.81392236e-02 -8.48457932e-01 -5.26047647e-01 5.81391864e-02 -8.50289583e-01 -5.23076653e-01 5.81392236e-02 -8.52153957e-01 -5.20037293e-01 5.81390373e-02 -8.53977919e-01 -5.17035484e-01 5.81393167e-02 -8.55762601e-01 -5.14076471e-01 5.81390224e-02 -8.57554018e-01 -5.11080027e-01 5.81393167e-02 -8.59287798e-01 -5.08160889e-01 5.81391826e-02 -8.61084223e-01 -5.05111992e-01 5.81390411e-02 -8.62847924e-01 -5.02092600e-01 5.81393093e-02 -8.64555478e-01 -4.99148667e-01 5.81391975e-02 -8.66279662e-01 -4.96146977e-01 5.81391901e-02 -8.68013799e-01 -4.93105531e-01 5.81391267e-02 -8.69730115e-01 -4.90079343e-01 5.81391566e-02 -8.71426463e-01 -4.87049341e-01 5.81391640e-02 -8.73126447e-01 -4.83994156e-01 5.81392236e-02 -8.74857068e-01 -4.80862468e-01 5.81390187e-02 -8.76536429e-01 -4.77800399e-01 5.81393838e-02 -8.78154576e-01 -4.74813133e-01 5.81392311e-02 -8.79813612e-01 -4.71731991e-01 5.81391230e-02 -8.81505311e-01 -4.68563378e-01 5.81390336e-02 -8.83178771e-01 -4.65403557e-01 5.81393167e-02 -8.84750783e-01 -4.62409496e-01 5.81394397e-02 -8.86313081e-01 -4.59405392e-01 5.81392273e-02 -8.87912154e-01 -4.56309170e-01 5.81392273e-02 -8.89545441e-01 -4.53112423e-01 5.81390038e-02 -8.91124666e-01 -4.50003266e-01 5.81393652e-02 -8.92640889e-01 -4.46983308e-01 5.81391305e-02 -8.94239306e-01 -4.43779945e-01 5.81390187e-02 -8.95787239e-01 -4.40647691e-01 5.81394248e-02 -8.97277415e-01 -4.37606484e-01 5.81391975e-02 -8.98842812e-01 -4.34382051e-01 5.81390001e-02 -9.00397658e-01 -4.31144536e-01 5.81391156e-02 -9.01898086e-01 -4.27998215e-01 5.81391864e-02 -9.03351545e-01 -4.24921244e-01 5.81393540e-02 -9.04783130e-01 -4.21866953e-01 5.81391491e-02 -9.06288147e-01 -4.18621778e-01 5.81390262e-02 -9.07793641e-01 -4.15346265e-01 5.81391715e-02 -9.09191370e-01 -4.12279457e-01 5.81393242e-02 -9.10590649e-01 -4.09181058e-01 5.81391789e-02 -9.12015438e-01 -4.05993253e-01 5.81391640e-02 -9.13454413e-01 -4.02745396e-01 5.81389815e-02 -9.14868236e-01 -3.99529368e-01 5.81393428e-02 -9.16244090e-01 -3.96356553e-01 5.81389554e-02 -9.17633116e-01 -3.93124968e-01 5.81393391e-02 -9.18956935e-01 -3.90024841e-01 5.81391789e-02 -9.20351207e-01 -3.86724144e-01 5.81390001e-02 -9.21698987e-01 -3.83503884e-01 5.81393503e-02 -9.23025668e-01 -3.80294144e-01 5.81390150e-02 -9.24354613e-01 -3.77057225e-01 5.81393763e-02 -9.25627232e-01 -3.73918861e-01 5.81391864e-02 -9.26954091e-01 -3.70615482e-01 5.81390224e-02 -9.28257048e-01 -3.67348999e-01 5.81393912e-02 -9.29520309e-01 -3.64139497e-01 5.81389889e-02 -9.30798471e-01 -3.60842705e-01 5.81393056e-02 -9.32017028e-01 -3.57709467e-01 5.81391603e-02 -9.33284700e-01 -3.54369462e-01 5.81389815e-02 -9.34511065e-01 -3.51108134e-01 5.81393652e-02 -9.35693383e-01 -3.47942740e-01 5.81391640e-02 -9.36932564e-01 -3.44602764e-01 5.81390522e-02 -9.38143551e-01 -3.41313452e-01 5.81393093e-02 -9.39326108e-01 -3.38035405e-01 5.81390336e-02 -9.40502167e-01 -3.34758103e-01 5.81393279e-02 -9.41657722e-01 -3.31485659e-01 5.81390448e-02 -9.42812443e-01 -3.28187853e-01 5.81393614e-02 -9.43927765e-01 -3.24970245e-01 5.81392124e-02 -9.45052207e-01 -3.21682692e-01 5.81391789e-02 -9.46167111e-01 -3.18389714e-01 5.81391752e-02 -9.47299719e-01 -3.14996630e-01 5.81390411e-02 -9.48396742e-01 -3.11682105e-01 5.81393279e-02 -9.49457109e-01 -3.08439583e-01 5.81392124e-02 -9.50551450e-01 -3.05049747e-01 5.81390373e-02 -9.51614082e-01 -3.01723361e-01 5.81394024e-02 -9.52657044e-01 -2.98410445e-01 5.81390187e-02 -9.53695238e-01 -2.95074612e-01 5.81393912e-02 -9.54714656e-01 -2.91755021e-01 5.81390299e-02 -9.55728889e-01 -2.88420647e-01 5.81394024e-02 -9.56694961e-01 -2.85196036e-01 5.81392162e-02 -9.57714021e-01 -2.81757146e-01 5.81390522e-02 -9.58695114e-01 -2.78408289e-01 5.81394061e-02 -9.59634304e-01 -2.75144160e-01 5.81392311e-02 -9.60589945e-01 -2.71792293e-01 5.81392013e-02 -9.61537480e-01 -2.68422961e-01 5.81392460e-02 -9.62460816e-01 -2.65088886e-01 5.81391975e-02 -9.63382304e-01 -2.61731356e-01 5.81392162e-02 -9.64287341e-01 -2.58364737e-01 5.81392311e-02 -9.65206325e-01 -2.54911035e-01 5.81389964e-02 -9.66126263e-01 -2.51405597e-01 5.81391864e-02 -9.66980398e-01 -2.48105571e-01 5.81394061e-02 -9.67806876e-01 -2.44845584e-01 5.81392087e-02 -9.68674600e-01 -2.41391033e-01 5.81390113e-02 -9.69541550e-01 -2.37897679e-01 5.81391789e-02 -9.70344603e-01 -2.34603480e-01 5.81394508e-02 -9.71134543e-01 -2.31309935e-01 5.81392236e-02 -9.71935749e-01 -2.27915511e-01 5.81392124e-02 -9.72740173e-01 -2.24452198e-01 5.81391118e-02 -9.73523021e-01 -2.21037894e-01 5.81394359e-02 -9.74264681e-01 -2.17746273e-01 5.81392385e-02 -9.75034535e-01 -2.14265823e-01 5.81390932e-02 -9.75782156e-01 -2.10836664e-01 5.81393726e-02 -9.76496935e-01 -2.07505524e-01 5.81392311e-02 -9.77211535e-01 -2.04115450e-01 5.81392534e-02 -9.77933526e-01 -2.00632170e-01 5.81390969e-02 -9.78644609e-01 -1.97128490e-01 5.81391975e-02 -9.79312241e-01 -1.93788931e-01 5.81394471e-02 -9.79967237e-01 -1.90447152e-01 5.81392050e-02 -9.80635345e-01 -1.86964482e-01 5.81391156e-02 -9.81298983e-01 -1.83457389e-01 5.81392832e-02 -9.81919527e-01 -1.80094063e-01 5.81393912e-02 -9.82531786e-01 -1.76760063e-01 5.81392497e-02 -9.83143628e-01 -1.73326716e-01 5.81392050e-02 -9.83748496e-01 -1.69823810e-01 5.81391528e-02 -9.84349489e-01 -1.66314974e-01 5.81392609e-02 -9.84912038e-01 -1.62948132e-01 5.81394397e-02 -9.85458612e-01 -1.59612313e-01 5.81392758e-02 -9.86014783e-01 -1.56136796e-01 5.81392571e-02 -9.86564577e-01 -1.52622774e-01 5.81390709e-02 -9.87088561e-01 -1.49197221e-01 5.81394210e-02 -9.87604916e-01 -1.45736337e-01 5.81390522e-02 -9.88110304e-01 -1.42272934e-01 5.81394508e-02 -9.88586605e-01 -1.38927430e-01 5.81392124e-02 -9.89075482e-01 -1.35402992e-01 5.81390932e-02 -9.89544094e-01 -1.31934687e-01 5.81394657e-02 -9.89999235e-01 -1.28472492e-01 5.81391081e-02 -9.90443170e-01 -1.25016838e-01 5.81394844e-02 -9.90861654e-01 -1.21636689e-01 5.81392944e-02 -9.91285205e-01 -1.18127592e-01 5.81391826e-02 -9.91696417e-01 -1.14629738e-01 5.81394956e-02 -9.92090702e-01 -1.11172527e-01 5.81392236e-02 -9.92484152e-01 -1.07611865e-01 5.81395067e-02 -9.92844045e-01 -1.04249768e-01 5.81395514e-02 -9.93198693e-01 -1.00818828e-01 5.81395552e-02 -9.93548155e-01 -9.73280296e-02 5.81395105e-02 -9.93882596e-01 -9.38617662e-02 5.81395142e-02 -9.94208574e-01 -9.03768986e-02 5.81394583e-02 -9.94505763e-01 -8.70682523e-02 5.81394024e-02 -9.94810641e-01 -8.35462511e-02 5.81392944e-02 -9.95097399e-01 -8.00669938e-02 5.81392646e-02 -9.95374322e-01 -7.65180141e-02 5.81391156e-02 -9.95625854e-01 -7.31117725e-02 5.81389181e-02 -9.95837271e-01 -7.02002198e-02 5.81390560e-02 -9.96049583e-01 -6.71179816e-02 5.81390262e-02 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.95407999e-01 5.04251570e-02 8.13644752e-02 -9.95252371e-01 5.34080416e-02 8.13644528e-02 -9.95097935e-01 5.61359078e-02 8.13640431e-02 -9.94918108e-01 5.93912192e-02 8.13640654e-02 -9.94711041e-01 6.27349317e-02 8.13641250e-02 -9.94496703e-01 6.60795644e-02 8.13645795e-02 -9.94251132e-01 6.96785823e-02 8.13649669e-02 -9.93997097e-01 7.32464120e-02 8.13649818e-02 -9.93734002e-01 7.67110810e-02 8.13650191e-02 -9.93465662e-01 8.01497623e-02 8.13651159e-02 -9.93176162e-01 8.36432725e-02 8.13651159e-02 -9.92886841e-01 8.70078132e-02 8.13650042e-02 -9.92581308e-01 9.04427543e-02 8.13652724e-02 -9.92248893e-01 9.40169618e-02 8.13651532e-02 -9.91925359e-01 9.73727852e-02 8.13650340e-02 -9.91580904e-01 1.00818478e-01 8.13653097e-02 -9.91211712e-01 1.04385942e-01 8.13650936e-02 -9.90841746e-01 1.07843667e-01 8.13651532e-02 -9.90461349e-01 1.11297533e-01 8.13651681e-02 -9.90068555e-01 1.14713736e-01 8.13651457e-02 -9.89671350e-01 1.18085831e-01 8.13651159e-02 -9.89259720e-01 1.21505313e-01 8.13651457e-02 -9.88823593e-01 1.25014126e-01 8.13652575e-02 -9.88364756e-01 1.28575563e-01 8.13651606e-02 -9.87921417e-01 1.31930649e-01 8.13650340e-02 -9.87460256e-01 1.35360792e-01 8.13652575e-02 -9.86966074e-01 1.38908431e-01 8.13651457e-02 -9.86488581e-01 1.42256618e-01 8.13650489e-02 -9.85986054e-01 1.45699441e-01 8.13652873e-02 -9.85471308e-01 1.49137095e-01 8.13650638e-02 -9.84961629e-01 1.52470365e-01 8.13651532e-02 -9.84408140e-01 1.56007409e-01 8.13653544e-02 -9.83838499e-01 1.59557238e-01 8.13651457e-02 -9.83273685e-01 1.63007855e-01 8.13651681e-02 -9.82702076e-01 1.66420817e-01 8.13651681e-02 -9.82115626e-01 1.69836730e-01 8.13651755e-02 -9.81519401e-01 1.73277497e-01 8.13651904e-02 -9.80902135e-01 1.76732466e-01 8.13651606e-02 -9.80274677e-01 1.80151314e-01 8.13651830e-02 -9.79655921e-01 1.83496818e-01 8.13650340e-02 -9.79040682e-01 1.86751962e-01 8.13651904e-02 -9.78362322e-01 1.90267414e-01 8.13654885e-02 -9.77669895e-01 1.93796977e-01 8.13651532e-02 -9.76991117e-01 1.97198570e-01 8.13651755e-02 -9.76292372e-01 2.00630799e-01 8.13652053e-02 -9.75583732e-01 2.04039946e-01 8.13651904e-02 -9.74881947e-01 2.07371056e-01 8.13650861e-02 -9.74160731e-01 2.10740596e-01 8.13653916e-02 -9.73390043e-01 2.14259222e-01 8.13651830e-02 -9.72657084e-01 2.17568651e-01 8.13651085e-02 -9.71893489e-01 2.20952749e-01 8.13653618e-02 -9.71094906e-01 2.24443972e-01 8.13651979e-02 -9.70302522e-01 2.27846757e-01 8.13651830e-02 -9.69504118e-01 2.31222302e-01 8.13651755e-02 -9.68712568e-01 2.34514043e-01 8.13650265e-02 -9.67914581e-01 2.37782240e-01 8.13651904e-02 -9.67047572e-01 2.41276890e-01 8.13653842e-02 -9.66172457e-01 2.44758964e-01 8.13652128e-02 -9.65310693e-01 2.48141259e-01 8.13651830e-02 -9.64464664e-01 2.51405358e-01 8.13650489e-02 -9.63593304e-01 2.54735082e-01 8.13653022e-02 -9.62685108e-01 2.58141965e-01 8.13651457e-02 -9.61775780e-01 2.61509567e-01 8.13652799e-02 -9.60837662e-01 2.64928132e-01 8.13651979e-02 -9.59924340e-01 2.68226027e-01 8.13650638e-02 -9.59019303e-01 2.71441251e-01 8.13651681e-02 -9.58036602e-01 2.74888158e-01 8.13653618e-02 -9.57041442e-01 2.78332591e-01 8.13651606e-02 -9.56073701e-01 2.81637698e-01 8.13651383e-02 -9.55095649e-01 2.84941524e-01 8.13651383e-02 -9.54096258e-01 2.88263172e-01 8.13652501e-02 -9.53097939e-01 2.91548789e-01 8.13650414e-02 -9.52075362e-01 2.94875652e-01 8.13652650e-02 -9.51009035e-01 2.98294455e-01 8.13651159e-02 -9.49988365e-01 3.01525772e-01 8.13650489e-02 -9.48930740e-01 3.04843098e-01 8.13652650e-02 -9.47834313e-01 3.08228970e-01 8.13651308e-02 -9.46751237e-01 3.11541229e-01 8.13651681e-02 -9.45659935e-01 3.14839423e-01 8.13651532e-02 -9.44553256e-01 3.18152755e-01 8.13651457e-02 -9.43460882e-01 3.21365654e-01 8.13650340e-02 -9.42368627e-01 3.24562907e-01 8.13651755e-02 -9.41202402e-01 3.27923208e-01 8.13653320e-02 -9.40020025e-01 3.31299007e-01 8.13651681e-02 -9.38893139e-01 3.34485412e-01 8.13650340e-02 -9.37711954e-01 3.37778628e-01 8.13652724e-02 -9.36496854e-01 3.41134369e-01 8.13651457e-02 -9.35299873e-01 3.44384432e-01 8.13651681e-02 -9.34091747e-01 3.47636789e-01 8.13651532e-02 -9.32895482e-01 3.50834936e-01 8.13650638e-02 -9.31708992e-01 3.53988171e-01 8.13651457e-02 -9.30449843e-01 3.57309282e-01 8.13652501e-02 -9.29144979e-01 3.60667676e-01 8.13651681e-02 -9.27876830e-01 3.63927394e-01 8.13651830e-02 -9.26601112e-01 3.67163509e-01 8.13651830e-02 -9.25320506e-01 3.70376140e-01 8.13651532e-02 -9.24023807e-01 3.73597801e-01 8.13651606e-02 -9.22718346e-01 3.76814455e-01 8.13651904e-02 -9.21395481e-01 3.80030811e-01 8.13651308e-02 -9.20090437e-01 3.83181453e-01 8.13650638e-02 -9.18792903e-01 3.86285931e-01 8.13651681e-02 -9.17407691e-01 3.89561802e-01 8.13652575e-02 -9.16005850e-01 3.92845273e-01 8.13651830e-02 -9.14639473e-01 3.96016002e-01 8.13651159e-02 -9.13267791e-01 3.99176776e-01 8.13652202e-02 -9.11874354e-01 4.02343929e-01 8.13651010e-02 -9.10478950e-01 4.05495584e-01 8.13652277e-02 -9.09028471e-01 4.08737332e-01 8.13652501e-02 -9.07573402e-01 4.11956310e-01 8.13651681e-02 -9.06161785e-01 4.15045261e-01 8.13650414e-02 -9.04718220e-01 4.18188930e-01 8.13653618e-02 -9.03214931e-01 4.21422243e-01 8.13651830e-02 -9.01743710e-01 4.24562663e-01 8.13651532e-02 -9.00267303e-01 4.27687466e-01 8.13651681e-02 -8.98774207e-01 4.30812091e-01 8.13651681e-02 -8.97303402e-01 4.33876783e-01 8.13651383e-02 -8.95763814e-01 4.37045246e-01 8.13653320e-02 -8.94193649e-01 4.40243840e-01 8.13651532e-02 -8.92655730e-01 4.43355173e-01 8.13651532e-02 -8.91103446e-01 4.46464539e-01 8.13652053e-02 -8.89539719e-01 4.49574709e-01 8.13651681e-02 -8.88004839e-01 4.52599317e-01 8.13650638e-02 -8.86463761e-01 4.55609441e-01 8.13651606e-02 -8.84830117e-01 4.58774209e-01 8.13652873e-02 -8.83188307e-01 4.61929083e-01 8.13651830e-02 -8.81603837e-01 4.64944512e-01 8.13650563e-02 -8.79990757e-01 4.67989355e-01 8.13652501e-02 -8.78307939e-01 4.71139550e-01 8.13651681e-02 -8.76653373e-01 4.74210203e-01 8.13651830e-02 -8.74995232e-01 4.77268338e-01 8.13651532e-02 -8.73316884e-01 4.80329663e-01 8.13651755e-02 -8.71683598e-01 4.83279854e-01 8.13650563e-02 -8.69997501e-01 4.86314058e-01 8.13652501e-02 -8.68257225e-01 4.89417106e-01 8.13651830e-02 -8.66531312e-01 4.92462516e-01 8.13651830e-02 -8.64812613e-01 4.95478034e-01 8.13651457e-02 -8.63093674e-01 4.98467028e-01 8.13651532e-02 -8.61350298e-01 5.01472235e-01 8.13651532e-02 -8.59590590e-01 5.04483521e-01 8.13651979e-02 -8.57817948e-01 5.07490396e-01 8.13651755e-02 -8.56085181e-01 5.10406911e-01 8.13650563e-02 -8.54337871e-01 5.13329268e-01 8.13652277e-02 -8.52485120e-01 5.16396642e-01 8.13652426e-02 -8.50657701e-01 5.19406199e-01 8.13651606e-02 -8.48831534e-01 5.22379696e-01 8.13652053e-02 -8.46998215e-01 5.25353312e-01 8.13651606e-02 -8.45167875e-01 5.28287828e-01 8.13651681e-02 -8.43368948e-01 5.31156182e-01 8.13651010e-02 -8.41503620e-01 5.34106195e-01 8.13653320e-02 -8.39584708e-01 5.37117541e-01 8.13652053e-02 -8.37747037e-01 5.39975464e-01 8.13650712e-02 -8.35870147e-01 5.42879224e-01 8.13653618e-02 -8.33939016e-01 5.45839310e-01 8.13651383e-02 -8.32030058e-01 5.48747718e-01 8.13651904e-02 -8.30086112e-01 5.51680207e-01 8.13651904e-02 -8.28147590e-01 5.54588616e-01 8.13651830e-02 -8.26267958e-01 5.57386816e-01 8.13650638e-02 -8.24315488e-01 5.60269177e-01 8.13653842e-02 -8.22292745e-01 5.63234508e-01 8.13651681e-02 -8.20318818e-01 5.66105604e-01 8.13651755e-02 -8.18387508e-01 5.68891525e-01 8.13650191e-02 -8.16421926e-01 5.71708620e-01 8.13653693e-02 -8.14377308e-01 5.74621737e-01 8.13651532e-02 -8.12357247e-01 5.77471256e-01 8.13652575e-02 -8.10319245e-01 5.80329299e-01 8.13651681e-02 -8.08338404e-01 5.83078802e-01 8.13650265e-02 -8.06340575e-01 5.85844040e-01 8.13652202e-02 -8.04237068e-01 5.88725388e-01 8.13651979e-02 -8.02118123e-01 5.91611028e-01 8.13651830e-02 -8.00043523e-01 5.94412863e-01 8.13651830e-02 -7.97959030e-01 5.97208321e-01 8.13651532e-02 -7.95886755e-01 5.99968970e-01 8.13651606e-02 -7.93793559e-01 6.02736890e-01 8.13651383e-02 -7.91682124e-01 6.05505347e-01 8.13651606e-02 -7.89566875e-01 6.08258724e-01 8.13650489e-02 -7.87489653e-01 6.10945404e-01 8.13649893e-02 -7.85355747e-01 6.13687336e-01 8.13653916e-02 -7.83124685e-01 6.16533875e-01 8.13651606e-02 -7.80968189e-01 6.19261384e-01 8.13651234e-02 -7.78812647e-01 6.21973515e-01 8.13651383e-02 -7.76628256e-01 6.24696851e-01 8.13651457e-02 -7.74455309e-01 6.27389073e-01 8.13651681e-02 -7.72351503e-01 6.29971147e-01 8.13649148e-02 -7.70130098e-01 6.32691801e-01 8.13651532e-02 -7.67860711e-01 6.35442972e-01 8.13650936e-02 -7.65683472e-01 6.38061821e-01 8.13649669e-02 -7.63470232e-01 6.40710890e-01 8.13652575e-02 -7.61165679e-01 6.43446922e-01 8.13650936e-02 -7.58914053e-01 6.46098495e-01 8.13651383e-02 -7.56621480e-01 6.48785055e-01 8.13651830e-02 -7.54381418e-01 6.51389837e-01 8.13650936e-02 -7.52196193e-01 6.53910458e-01 8.13650340e-02 -7.49852240e-01 6.56594932e-01 8.13652724e-02 -7.47470498e-01 6.59307003e-01 8.13651904e-02 -7.45153546e-01 6.61924481e-01 8.13651681e-02 -7.42851973e-01 6.64506793e-01 8.13651159e-02 -7.40531445e-01 6.67089701e-01 8.13650489e-02 -7.38205135e-01 6.69667363e-01 8.13650638e-02 -7.35867023e-01 6.72230721e-01 8.13651085e-02 -7.33520627e-01 6.74793720e-01 8.13651159e-02 -7.31226563e-01 6.77278280e-01 8.13650116e-02 -7.28840172e-01 6.79845452e-01 8.13652351e-02 -7.26382852e-01 6.82469845e-01 8.13651681e-02 -7.23996341e-01 6.85000181e-01 8.13651234e-02 -7.21615374e-01 6.87509775e-01 8.13651010e-02 -7.19209492e-01 6.90019786e-01 8.13650340e-02 -7.16798425e-01 6.92537308e-01 8.13651010e-02 -7.14421868e-01 6.94987118e-01 8.13650265e-02 -7.12011456e-01 6.97454214e-01 8.13652053e-02 -7.09512055e-01 6.99997187e-01 8.13651532e-02 -7.07102835e-01 7.02432275e-01 8.13650116e-02 -7.04644799e-01 7.04881191e-01 8.13652501e-02 -7.02144325e-01 7.07389474e-01 8.13651457e-02 -6.99677289e-01 7.09829152e-01 8.13651159e-02 -6.97168112e-01 7.12290466e-01 8.13650712e-02 -6.94730401e-01 7.14670897e-01 8.13650340e-02 -6.92264557e-01 7.17059672e-01 8.13649669e-02 -6.89762175e-01 7.19458342e-01 8.13651979e-02 -6.87155545e-01 7.21954763e-01 8.13651234e-02 -6.84652805e-01 7.24323988e-01 8.13651383e-02 -6.82119370e-01 7.26709783e-01 8.13650936e-02 -6.79563046e-01 7.29099393e-01 8.13650563e-02 -6.77026212e-01 7.31458843e-01 8.13651383e-02 -6.74468875e-01 7.33820915e-01 8.13651681e-02 -6.71888053e-01 7.36181438e-01 8.13651457e-02 -6.69342518e-01 7.38498509e-01 8.13651159e-02 -6.66798413e-01 7.40793824e-01 8.13650042e-02 -6.64228022e-01 7.43101180e-01 8.13653618e-02 -6.61559165e-01 7.45478988e-01 8.13651606e-02 -6.58956468e-01 7.47778833e-01 8.13651681e-02 -6.56342268e-01 7.50073135e-01 8.13650638e-02 -6.53704703e-01 7.52375007e-01 8.13650861e-02 -6.51141465e-01 7.54593492e-01 8.13650340e-02 -6.48512602e-01 7.56854177e-01 8.13651606e-02 -6.45780027e-01 7.59186983e-01 8.13651159e-02 -6.43196046e-01 7.61378229e-01 8.13650265e-02 -6.40547454e-01 7.63607264e-01 8.13652351e-02 -6.37804747e-01 7.65900493e-01 8.13651085e-02 -6.35142565e-01 7.68107891e-01 8.13651383e-02 -6.32452905e-01 7.70326614e-01 8.13651681e-02 -6.29841268e-01 7.72459209e-01 8.13649669e-02 -6.27128005e-01 7.74667561e-01 8.13651755e-02 -6.24339819e-01 7.76914358e-01 8.13651532e-02 -6.21690750e-01 7.79035151e-01 8.13650340e-02 -6.18974209e-01 7.81197190e-01 8.13652351e-02 -6.16238236e-01 7.83355474e-01 8.13649669e-02 -6.13527179e-01 7.85482466e-01 8.13652873e-02 -6.10687912e-01 7.87692547e-01 8.13651755e-02 -6.07995868e-01 7.89771199e-01 8.13649818e-02 -6.05275512e-01 7.91857958e-01 8.13652202e-02 -6.02472544e-01 7.93991446e-01 8.13650340e-02 -5.99709034e-01 7.96083629e-01 8.13652724e-02 -5.96907496e-01 7.98183084e-01 8.13650340e-02 -5.94142914e-01 8.00244749e-01 8.13653320e-02 -5.91246784e-01 8.02384973e-01 8.13651532e-02 -5.88432193e-01 8.04452240e-01 8.13651606e-02 -5.85706115e-01 8.06440473e-01 8.13650340e-02 -5.82949281e-01 8.08434010e-01 8.13651904e-02 -5.80031753e-01 8.10532391e-01 8.13652277e-02 -5.77232122e-01 8.12527359e-01 8.13649744e-02 -5.74418724e-01 8.14521074e-01 8.13652053e-02 -5.71560800e-01 8.16525340e-01 8.13650042e-02 -5.68723023e-01 8.18504691e-01 8.13652277e-02 -5.65779984e-01 8.20542991e-01 8.13651234e-02 -5.62906742e-01 8.22516799e-01 8.13650489e-02 -5.60087860e-01 8.24436069e-01 8.13650265e-02 -5.57285488e-01 8.26336384e-01 8.13651383e-02 -5.54327786e-01 8.28321636e-01 8.13651979e-02 -5.51424265e-01 8.30255747e-01 8.13650414e-02 -5.48538864e-01 8.32168460e-01 8.13651979e-02 -5.45629740e-01 8.34075749e-01 8.13650340e-02 -5.42752683e-01 8.35952222e-01 8.13652575e-02 -5.39755821e-01 8.37889910e-01 8.13651606e-02 -5.36801517e-01 8.39786172e-01 8.13651532e-02 -5.33861041e-01 8.41657460e-01 8.13651532e-02 -5.30895352e-01 8.43532801e-01 8.13651532e-02 -5.27945220e-01 8.45381021e-01 8.13651383e-02 -5.25080562e-01 8.47163975e-01 8.13649669e-02 -5.22133350e-01 8.48984480e-01 8.13652873e-02 -5.19061208e-01 8.50866556e-01 8.13651234e-02 -5.16064346e-01 8.52685571e-01 8.13651234e-02 -5.13173163e-01 8.54428768e-01 8.13649744e-02 -5.10220647e-01 8.56197417e-01 8.13653097e-02 -5.07106125e-01 8.58044326e-01 8.13651159e-02 -5.04195869e-01 8.59757543e-01 8.13650116e-02 -5.01212239e-01 8.61501932e-01 8.13652501e-02 -4.98191267e-01 8.63251626e-01 8.13649744e-02 -4.95179445e-01 8.64982307e-01 8.13653320e-02 -4.92070794e-01 8.66754889e-01 8.13651457e-02 -4.89083201e-01 8.68446052e-01 8.13651010e-02 -4.86140966e-01 8.70093107e-01 8.13651383e-02 -4.83054727e-01 8.71810853e-01 8.13652277e-02 -4.79938477e-01 8.73530686e-01 8.13649893e-02 -4.76986974e-01 8.75146449e-01 8.13649669e-02 -4.73918974e-01 8.76811683e-01 8.13653469e-02 -4.70826745e-01 8.78474832e-01 8.13650042e-02 -4.67785835e-01 8.80099952e-01 8.13651830e-02 -4.64706719e-01 8.81728768e-01 8.13650563e-02 -4.61642385e-01 8.83337379e-01 8.13652351e-02 -4.58477050e-01 8.84983242e-01 8.13651606e-02 -4.55388635e-01 8.86577368e-01 8.13651532e-02 -4.52288091e-01 8.88162792e-01 8.13651830e-02 -4.49240535e-01 8.89708340e-01 8.13650414e-02 -4.46142524e-01 8.91265869e-01 8.13651830e-02 -4.42973882e-01 8.92845094e-01 8.13651532e-02 -4.39843982e-01 8.94389868e-01 8.13651532e-02 -4.36781704e-01 8.95889997e-01 8.13650340e-02 -4.33667392e-01 8.97403896e-01 8.13652575e-02 -4.30458546e-01 8.98944139e-01 8.13651159e-02 -4.27289963e-01 9.00454402e-01 8.13650638e-02 -4.24187094e-01 9.01920676e-01 8.13650563e-02 -4.21094775e-01 9.03368592e-01 8.13650265e-02 -4.17908102e-01 9.04848158e-01 8.13651979e-02 -4.14687008e-01 9.06327367e-01 8.13651830e-02 -4.11526352e-01 9.07768130e-01 8.13651532e-02 -4.08456117e-01 9.09153998e-01 8.13649967e-02 -4.05301899e-01 9.10565257e-01 8.13652501e-02 -4.02024984e-01 9.12016332e-01 8.13651457e-02 -3.98896962e-01 9.13390696e-01 8.13650414e-02 -3.95716220e-01 9.14771855e-01 8.13652575e-02 -3.92510712e-01 9.16146219e-01 8.13650340e-02 -3.89398366e-01 9.17476892e-01 8.13651010e-02 -3.86176288e-01 9.18839157e-01 8.13650414e-02 -3.82916600e-01 9.20202553e-01 8.13652128e-02 -3.79622608e-01 9.21565533e-01 8.13651830e-02 -3.76420289e-01 9.22878206e-01 8.13651383e-02 -3.73188674e-01 9.24190581e-01 8.13651457e-02 -3.70005041e-01 9.25467849e-01 8.13650638e-02 -3.66779476e-01 9.26753640e-01 8.13652277e-02 -3.63488883e-01 9.28048432e-01 8.13651755e-02 -3.60233158e-01 9.29310739e-01 8.13650861e-02 -3.57083499e-01 9.30536568e-01 8.13650414e-02 -3.53836685e-01 9.31767166e-01 8.13651904e-02 -3.50513607e-01 9.33017135e-01 8.13651681e-02 -3.47242028e-01 9.34238076e-01 8.13651010e-02 -3.44059229e-01 9.35416520e-01 8.13649669e-02 -3.40892494e-01 9.36585784e-01 8.13649893e-02 -3.37551117e-01 9.37792838e-01 8.13652277e-02 -3.34247768e-01 9.38977182e-01 8.13649595e-02 -3.30973566e-01 9.40134585e-01 8.13651159e-02 -3.27703685e-01 9.41278815e-01 8.13650116e-02 -3.24429572e-01 9.42414045e-01 8.13652351e-02 -3.21090341e-01 9.43555593e-01 8.13650936e-02 -3.17856520e-01 9.44650710e-01 8.13650563e-02 -3.14544410e-01 9.45757508e-01 8.13652053e-02 -3.11206073e-01 9.46859896e-01 8.13649669e-02 -3.07902157e-01 9.47942019e-01 8.13653022e-02 -3.04630488e-01 9.48998392e-01 8.13649967e-02 -3.01307201e-01 9.50058460e-01 8.13650936e-02 -2.97895610e-01 9.51132596e-01 8.13650787e-02 -2.94589877e-01 9.52161789e-01 8.13650936e-02 -2.91257352e-01 9.53186274e-01 8.13651159e-02 -2.87927061e-01 9.54197466e-01 8.13651010e-02 -2.84616649e-01 9.55190957e-01 8.13651383e-02 -2.81263232e-01 9.56184804e-01 8.13651159e-02 -2.77924627e-01 9.57161188e-01 8.13651606e-02 -2.74674118e-01 9.58097637e-01 8.13650563e-02 -2.71314681e-01 9.59056020e-01 8.13652202e-02 -2.67900020e-01 9.60014045e-01 8.13651383e-02 -2.64553845e-01 9.60941613e-01 8.13651457e-02 -2.61259586e-01 9.61844742e-01 8.13650414e-02 -2.57990211e-01 9.62725878e-01 8.13651606e-02 -2.54565984e-01 9.63635921e-01 8.13652426e-02 -2.51190931e-01 9.64521408e-01 8.13650489e-02 -2.47814193e-01 9.65394676e-01 8.13651830e-02 -2.44457081e-01 9.66247857e-01 8.13650042e-02 -2.41068766e-01 9.67100263e-01 8.13652873e-02 -2.37582251e-01 9.67964470e-01 8.13651606e-02 -2.34297484e-01 9.68764246e-01 8.13649818e-02 -2.30905667e-01 9.69579637e-01 8.13652650e-02 -2.27535412e-01 9.70372558e-01 8.13649520e-02 -2.24172175e-01 9.71157134e-01 8.13652351e-02 -2.20764607e-01 9.71935511e-01 8.13649669e-02 -2.17484206e-01 9.72676754e-01 8.13651383e-02 -2.13956982e-01 9.73458707e-01 8.13653320e-02 -2.10457340e-01 9.74220455e-01 8.13651383e-02 -2.07066372e-01 9.74946797e-01 8.13651681e-02 -2.03660548e-01 9.75664079e-01 8.13650563e-02 -2.00344965e-01 9.76349115e-01 8.13649669e-02 -1.96931511e-01 9.77044165e-01 8.13653097e-02 -1.93411455e-01 9.77746904e-01 8.13651383e-02 -1.89987704e-01 9.78417814e-01 8.13650936e-02 -1.86580941e-01 9.79073524e-01 8.13651234e-02 -1.83255941e-01 9.79698837e-01 8.13648552e-02 -1.79849997e-01 9.80330646e-01 8.13651830e-02 -1.76435560e-01 9.80956614e-01 8.13650191e-02 -1.73008963e-01 9.81567800e-01 8.13652501e-02 -1.69479907e-01 9.82177436e-01 8.13650414e-02 -1.66122600e-01 9.82751489e-01 8.13649669e-02 -1.62715182e-01 9.83321309e-01 8.13652053e-02 -1.59261853e-01 9.83884692e-01 8.13650042e-02 -1.55860916e-01 9.84431446e-01 8.13651681e-02 -1.52273029e-01 9.84991848e-01 8.13650638e-02 -1.48947060e-01 9.85500097e-01 8.13650042e-02 -1.45527035e-01 9.86011863e-01 8.13652501e-02 -1.42062202e-01 9.86515224e-01 8.13650042e-02 -1.38625547e-01 9.87007439e-01 8.13652575e-02 -1.35080040e-01 9.87498343e-01 8.13651085e-02 -1.31713226e-01 9.87949550e-01 8.13650116e-02 -1.28266379e-01 9.88405704e-01 8.13652128e-02 -1.24721669e-01 9.88859177e-01 8.13651383e-02 -1.21275045e-01 9.89286959e-01 8.13651457e-02 -1.17937088e-01 9.89688158e-01 8.13649818e-02 -1.14537910e-01 9.90088224e-01 8.13650861e-02 -1.10986821e-01 9.90494847e-01 8.13652351e-02 -1.07444994e-01 9.90883052e-01 8.13651159e-02 -1.03982091e-01 9.91253912e-01 8.13651755e-02 -1.00510493e-01 9.91610348e-01 8.13651383e-02 -9.71403494e-02 9.91947234e-01 8.13650265e-02 -9.37093720e-02 9.92278516e-01 8.13652575e-02 -9.02360231e-02 9.92600024e-01 8.13650191e-02 -8.67751464e-02 9.92909849e-01 8.13652724e-02 -8.32038075e-02 9.93214250e-01 8.13651457e-02 -7.98418820e-02 9.93490398e-01 8.13650191e-02 -7.64013529e-02 9.93760288e-01 8.13652650e-02 -7.29063004e-02 9.94022727e-01 8.13650265e-02 -6.94129169e-02 9.94272530e-01 8.13652873e-02 -6.58409297e-02 9.94516492e-01 8.13651681e-02 -6.23605400e-02 9.94737804e-01 8.13651234e-02 -5.89043945e-02 9.94950533e-01 8.13651532e-02 -5.54907806e-02 9.95146096e-01 8.13649669e-02 -5.20451404e-02 9.95331287e-01 8.13652724e-02 -4.85593863e-02 9.95508611e-01 8.13650116e-02 -4.51908596e-02 9.95667517e-01 8.13651457e-02 -4.16142419e-02 9.95823443e-01 8.13652277e-02 -3.80409025e-02 9.95965958e-01 8.13651532e-02 -3.45715620e-02 9.96092379e-01 8.13651606e-02 -3.10765896e-02 9.96208012e-01 8.13651681e-02 -2.76977792e-02 9.96307015e-01 8.13650340e-02 -2.43155435e-02 9.96398747e-01 8.13651681e-02 -2.07396839e-02 9.96474028e-01 8.13652202e-02 -1.71362869e-02 9.96549904e-01 8.13651383e-02 -1.36935897e-02 9.96595144e-01 8.13651010e-02 -1.03178462e-02 9.96636569e-01 8.13649371e-02 -6.82226429e-03 9.96675730e-01 8.13651904e-02 -3.31232254e-03 9.96691406e-01 8.13649818e-02 1.27463121e-04 9.96694088e-01 8.13652724e-02 3.69562162e-03 9.96692002e-01 8.13651383e-02 7.10513489e-03 9.96671736e-01 8.13650489e-02 1.05665717e-02 9.96637404e-01 8.13652724e-02 1.40511403e-02 9.96589899e-01 8.13650787e-02 1.75214391e-02 9.96545136e-01 8.13652575e-02 2.10199393e-02 9.96470213e-01 8.13650340e-02 2.44111847e-02 9.96395171e-01 8.13651532e-02 2.79521495e-02 9.96302724e-01 8.13652724e-02 3.15291807e-02 9.96194661e-01 8.13651457e-02 3.50210741e-02 9.96078670e-01 8.13651457e-02 3.84715423e-02 9.95951414e-01 8.13651532e-02 4.18655165e-02 9.95814919e-01 8.13650787e-02 4.53472994e-02 9.95660245e-01 8.13652575e-02 4.89188395e-02 9.95492578e-01 8.13651681e-02 5.23890071e-02 9.95311618e-01 8.13651457e-02 5.58331944e-02 9.95128393e-01 8.13651383e-02 5.92323579e-02 9.94931579e-01 8.13650340e-02 6.26829788e-02 9.94718194e-01 8.13653097e-02 6.62685260e-02 9.94486094e-01 8.13651457e-02 6.97622523e-02 9.94246602e-01 8.13651681e-02 7.32422546e-02 9.93998706e-01 8.13651532e-02 7.66126961e-02 9.93742645e-01 8.13650414e-02 8.00725818e-02 9.93471086e-01 8.13653693e-02 8.35382715e-02 9.93184686e-01 8.13649669e-02 8.70090723e-02 9.92887259e-01 8.13652501e-02 9.05885696e-02 9.92567480e-01 8.13651830e-02 9.39532891e-02 9.92253006e-01 8.13649669e-02 9.73892733e-02 9.91923809e-01 8.13653618e-02 1.00880302e-01 9.91574883e-01 8.13650414e-02 1.04320668e-01 9.91218686e-01 8.13653395e-02 1.07794777e-01 9.90845859e-01 8.13650191e-02 1.11238092e-01 9.90467131e-01 8.13652724e-02 1.14795886e-01 9.90058601e-01 8.13651681e-02 1.18251704e-01 9.89651561e-01 8.13651532e-02 1.21676154e-01 9.89237547e-01 8.13651532e-02 1.25085711e-01 9.88814116e-01 8.13650489e-02 1.28437698e-01 9.88381922e-01 8.13651532e-02 1.31955042e-01 9.87919867e-01 8.13652351e-02 1.35486662e-01 9.87441897e-01 8.13651457e-02 1.38957918e-01 9.86959100e-01 8.13651532e-02 1.42396897e-01 9.86467421e-01 8.13651234e-02 1.45774245e-01 9.85973895e-01 8.13650414e-02 1.49194434e-01 9.85463023e-01 8.13652724e-02 1.52636126e-01 9.84935939e-01 8.13650489e-02 1.56071499e-01 9.84397590e-01 8.13652873e-02 1.59602553e-01 9.83831227e-01 8.13651681e-02 1.62956834e-01 9.83281374e-01 8.13650340e-02 1.66353479e-01 9.82713282e-01 8.13652426e-02 1.69796646e-01 9.82122183e-01 8.13650712e-02 1.73155248e-01 9.81539905e-01 8.13651457e-02 1.76647767e-01 9.80917394e-01 8.13652575e-02 1.80157036e-01 9.80274379e-01 8.13651383e-02 1.83598354e-01 9.79636669e-01 8.13651457e-02 1.86911136e-01 9.79009748e-01 8.13650936e-02 1.90352112e-01 9.78346586e-01 8.13651830e-02 1.93749547e-01 9.77680087e-01 8.13650340e-02 1.97067395e-01 9.77015555e-01 8.13651606e-02 2.00562105e-01 9.76306140e-01 8.13652724e-02 2.04055116e-01 9.75580215e-01 8.13651755e-02 2.07455710e-01 9.74864364e-01 8.13651159e-02 2.10865527e-01 9.74132776e-01 8.13651830e-02 2.14181826e-01 9.73405242e-01 8.13650712e-02 2.17543051e-01 9.72663939e-01 8.13651755e-02 2.21053198e-01 9.71869230e-01 8.13651383e-02 2.24452585e-01 9.71091807e-01 8.13651383e-02 2.27842122e-01 9.70303655e-01 8.13651383e-02 2.31121421e-01 9.69525993e-01 8.13649669e-02 2.34432042e-01 9.68733847e-01 8.13651457e-02 2.37817615e-01 9.67905164e-01 8.13651457e-02 2.41263554e-01 9.67051148e-01 8.13652799e-02 2.44728357e-01 9.66179967e-01 8.13651606e-02 2.48015329e-01 9.65343058e-01 8.13650340e-02 2.51402736e-01 9.64465976e-01 8.13651532e-02 2.54752666e-01 9.63587105e-01 8.13650340e-02 2.58093774e-01 9.62697864e-01 8.13652575e-02 2.61545688e-01 9.61765587e-01 8.13651383e-02 2.64845759e-01 9.60859835e-01 8.13650489e-02 2.68181294e-01 9.59935725e-01 8.13652277e-02 2.71548748e-01 9.58987892e-01 8.13650340e-02 2.74881691e-01 9.58038568e-01 8.13653693e-02 2.78312653e-01 9.57047403e-01 8.13651532e-02 2.81561792e-01 9.56096470e-01 8.13650787e-02 2.84899205e-01 9.55109119e-01 8.13653097e-02 2.88341045e-01 9.54071939e-01 8.13651457e-02 2.91628569e-01 9.53075409e-01 8.13651457e-02 2.94862151e-01 9.52079177e-01 8.13650489e-02 2.98106402e-01 9.51068699e-01 8.13651830e-02 3.01425517e-01 9.50021505e-01 8.13652053e-02 3.04847717e-01 9.48927820e-01 8.13653618e-02 3.08271110e-01 9.47821736e-01 8.13651755e-02 3.11546475e-01 9.46750045e-01 8.13651830e-02 3.14785630e-01 9.45677876e-01 8.13650191e-02 3.17978412e-01 9.44611251e-01 8.13651755e-02 3.21270466e-01 9.43494081e-01 8.13651532e-02 3.24615538e-01 9.42350090e-01 8.13652575e-02 3.28005493e-01 9.41172838e-01 8.13651681e-02 3.31231713e-01 9.40044165e-01 8.13650712e-02 3.34504753e-01 9.38886166e-01 8.13653618e-02 3.37795675e-01 9.37703669e-01 8.13650936e-02 3.41036052e-01 9.36533153e-01 8.13653320e-02 3.44397098e-01 9.35295761e-01 8.13652053e-02 3.47653061e-01 9.34085548e-01 8.13651383e-02 3.50915432e-01 9.32866991e-01 8.13651904e-02 3.54096442e-01 9.31666732e-01 8.13650340e-02 3.57339114e-01 9.30438161e-01 8.13652426e-02 3.60598266e-01 9.29169893e-01 8.13650340e-02 3.63738209e-01 9.27949548e-01 8.13650936e-02 3.67072195e-01 9.26636755e-01 8.13652277e-02 3.70383561e-01 9.25317407e-01 8.13651383e-02 3.73590887e-01 9.24025297e-01 8.13651532e-02 3.76806498e-01 9.22720850e-01 8.13651234e-02 3.79971474e-01 9.21419442e-01 8.13650712e-02 3.83086562e-01 9.20130789e-01 8.13651830e-02 3.86394948e-01 9.18746054e-01 8.13653246e-02 3.89662474e-01 9.17363882e-01 8.13651532e-02 3.92844141e-01 9.16005611e-01 8.13651606e-02 3.95996928e-01 9.14648116e-01 8.13650712e-02 3.99115175e-01 9.13294435e-01 8.13651532e-02 4.02289987e-01 9.11898971e-01 8.13651532e-02 4.05517459e-01 9.10469413e-01 8.13653320e-02 4.08763498e-01 9.09015715e-01 8.13651681e-02 4.11869884e-01 9.07611549e-01 8.13650936e-02 4.14973408e-01 9.06195760e-01 8.13651830e-02 4.18102115e-01 9.04756129e-01 8.13651606e-02 4.21270847e-01 9.03286934e-01 8.13651755e-02 4.24411058e-01 9.01815295e-01 8.13651532e-02 4.27614599e-01 9.00299489e-01 8.13651234e-02 4.30822492e-01 8.98769200e-01 8.13652053e-02 4.33960348e-01 8.97261739e-01 8.13651457e-02 4.37020540e-01 8.95775557e-01 8.13650787e-02 4.40097392e-01 8.94265950e-01 8.13651755e-02 4.43191499e-01 8.92737269e-01 8.13651755e-02 4.46370155e-01 8.91152143e-01 8.13653618e-02 4.49547768e-01 8.89553964e-01 8.13651755e-02 4.52631593e-01 8.87987614e-01 8.13651755e-02 4.55699354e-01 8.86415839e-01 8.13649371e-02 4.58711743e-01 8.84859204e-01 8.13650563e-02 4.61773306e-01 8.83270860e-01 8.13651457e-02 4.64927673e-01 8.81612897e-01 8.13652277e-02 4.68069404e-01 8.79948616e-01 8.13651532e-02 4.71131772e-01 8.78313482e-01 8.13652053e-02 4.74137008e-01 8.76691699e-01 8.13651010e-02 4.77130920e-01 8.75070930e-01 8.13651606e-02 4.80180532e-01 8.73398602e-01 8.13651457e-02 4.83269721e-01 8.71690273e-01 8.13652202e-02 4.86396313e-01 8.69951665e-01 8.13651681e-02 4.89373386e-01 8.68280709e-01 8.13651010e-02 4.92370337e-01 8.66584897e-01 8.13653618e-02 4.95420218e-01 8.64845693e-01 8.13650265e-02 4.98343498e-01 8.63163531e-01 8.13651681e-02 5.01447260e-01 8.61365259e-01 8.13652650e-02 5.04457355e-01 8.59604716e-01 8.13651234e-02 5.07440507e-01 8.57847869e-01 8.13653320e-02 5.10428727e-01 8.56071115e-01 8.13650712e-02 5.13417065e-01 8.54284883e-01 8.13653320e-02 5.16419709e-01 8.52470815e-01 8.13651457e-02 5.19305885e-01 8.50717902e-01 8.13651383e-02 5.22314191e-01 8.48874152e-01 8.13653991e-02 5.25297284e-01 8.47030520e-01 8.13651234e-02 5.28246760e-01 8.45194936e-01 8.13653544e-02 5.31213343e-01 8.43332350e-01 8.13650936e-02 5.34041524e-01 8.41544807e-01 8.13651606e-02 5.37020266e-01 8.39647353e-01 8.13652575e-02 5.39943933e-01 8.37769091e-01 8.13651457e-02 5.42903483e-01 8.35855067e-01 8.13653395e-02 5.45910537e-01 8.33895385e-01 8.13652351e-02 5.48746586e-01 8.32031310e-01 8.13650414e-02 5.51552773e-01 8.30169380e-01 8.13651457e-02 5.54437697e-01 8.28249037e-01 8.13651159e-02 5.57384312e-01 8.26270938e-01 8.13651159e-02 5.60307205e-01 8.24286222e-01 8.13648701e-02 5.63164949e-01 8.22336376e-01 8.13645571e-02 5.65971494e-01 8.20406318e-01 8.13643783e-02 5.68809986e-01 8.18439424e-01 8.13642070e-02 5.71696281e-01 8.16425562e-01 8.13641250e-02 5.74582815e-01 8.14396203e-01 8.13639984e-02 5.77326119e-01 8.12452078e-01 8.13639984e-02 5.80213130e-01 8.10390711e-01 8.13639984e-02 5.83032310e-01 8.08360755e-01 8.13640356e-02 5.85752547e-01 8.06389868e-01 8.13641101e-02 5.88659942e-01 8.04275990e-01 8.13644156e-02 5.91077805e-01 8.02498579e-01 8.13645348e-02 5.93673348e-01 8.00581694e-01 8.13644677e-02 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. 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. 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. 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. 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. 7.18161881e-01 6.91103041e-01 8.13644752e-02 7.20005333e-01 6.89182699e-01 8.13644454e-02 7.21964538e-01 6.87129080e-01 8.13642740e-02 7.24292934e-01 6.84667587e-01 8.13640580e-02 7.26657987e-01 6.82166398e-01 8.13639984e-02 7.29099989e-01 6.79559469e-01 8.13643336e-02 7.31405437e-01 6.77080095e-01 8.13643709e-02 7.33715713e-01 6.74579859e-01 8.13647509e-02 7.36031592e-01 6.72050357e-01 8.13650340e-02 7.38359153e-01 6.69496536e-01 8.13650489e-02 7.40758121e-01 6.66840672e-01 8.13652053e-02 7.43147314e-01 6.64173543e-01 8.13650936e-02 7.45397568e-01 6.61647856e-01 8.13649073e-02 7.47631907e-01 6.59122944e-01 8.13650563e-02 7.49935210e-01 6.56499684e-01 8.13651010e-02 7.52231598e-01 6.53868914e-01 8.13650563e-02 7.54558086e-01 6.51184201e-01 8.13651383e-02 7.56829739e-01 6.48540258e-01 8.13648775e-02 7.59023368e-01 6.45970166e-01 8.13649967e-02 7.61274576e-01 6.43319011e-01 8.13649669e-02 7.63562143e-01 6.40600145e-01 8.13650861e-02 7.65802264e-01 6.37919724e-01 8.13648254e-02 7.67978907e-01 6.35297537e-01 8.13649669e-02 7.70249188e-01 6.32547796e-01 8.13651383e-02 7.72494495e-01 6.29799604e-01 8.13650265e-02 7.74698555e-01 6.27088130e-01 8.13649967e-02 7.76813507e-01 6.24463737e-01 8.13649818e-02 7.78948069e-01 6.21803641e-01 8.13651010e-02 7.81088471e-01 6.19108677e-01 8.13650936e-02 7.83305645e-01 6.16305411e-01 8.13653097e-02 7.85528898e-01 6.13466442e-01 8.13651904e-02 7.87656307e-01 6.10734046e-01 8.13651532e-02 7.89726019e-01 6.08053684e-01 8.13650265e-02 7.91806936e-01 6.05343223e-01 8.13651755e-02 7.93926001e-01 6.02560699e-01 8.13651457e-02 7.96053112e-01 5.99750698e-01 8.13653320e-02 7.98201621e-01 5.96882761e-01 8.13651681e-02 8.00235212e-01 5.94153523e-01 8.13650340e-02 8.02243412e-01 5.91440678e-01 8.13651681e-02 8.04292142e-01 5.88649452e-01 8.13651904e-02 8.06416750e-01 5.85739374e-01 8.13652575e-02 8.08457971e-01 5.82914233e-01 8.13650638e-02 8.10421944e-01 5.80186069e-01 8.13651830e-02 8.12488437e-01 5.77287853e-01 8.13653618e-02 8.14516962e-01 5.74423790e-01 8.13651234e-02 8.16515744e-01 5.71575701e-01 8.13653320e-02 8.18504155e-01 5.68722904e-01 8.13650340e-02 8.20417106e-01 5.65964282e-01 8.13651830e-02 8.22439671e-01 5.63023388e-01 8.13653618e-02 8.24455738e-01 5.60062170e-01 8.13651681e-02 8.26408267e-01 5.57177663e-01 8.13651904e-02 8.28300774e-01 5.54358482e-01 8.13650489e-02 8.30171108e-01 5.51552773e-01 8.13651457e-02 8.32097352e-01 5.48644006e-01 8.13651830e-02 8.34061861e-01 5.45653045e-01 8.13652351e-02 8.36010933e-01 5.42662024e-01 8.13651383e-02 8.37844610e-01 5.39825737e-01 8.13650340e-02 8.39660585e-01 5.36997199e-01 8.13651234e-02 8.41528654e-01 5.34064531e-01 8.13651532e-02 8.43399167e-01 5.31110764e-01 8.13651755e-02 8.45301032e-01 5.28075039e-01 8.13653767e-02 8.47213268e-01 5.25003314e-01 8.13651457e-02 8.48987281e-01 5.22124410e-01 8.13650489e-02 8.50756705e-01 5.19243121e-01 8.13651755e-02 8.52546811e-01 5.16294658e-01 8.13651755e-02 8.54335785e-01 5.13328254e-01 8.13651532e-02 8.56130004e-01 5.10332406e-01 8.13652053e-02 8.57924819e-01 5.07308543e-01 8.13652053e-02 8.59686255e-01 5.04319966e-01 8.13651308e-02 8.61421287e-01 5.01348853e-01 8.13652053e-02 8.63215089e-01 4.98255312e-01 8.13653320e-02 8.64961207e-01 4.95215356e-01 8.13650340e-02 8.66626501e-01 4.92295831e-01 8.13652426e-02 8.68404806e-01 4.89157766e-01 8.13653618e-02 8.70164394e-01 4.86014217e-01 8.13652202e-02 8.71851981e-01 4.82978225e-01 8.13651234e-02 8.73474240e-01 4.80041564e-01 8.13650489e-02 8.75111520e-01 4.77053285e-01 8.13651457e-02 8.76779974e-01 4.73976493e-01 8.13651830e-02 8.78435493e-01 4.70901847e-01 8.13651159e-02 8.80103290e-01 4.67777729e-01 8.13653097e-02 8.81773651e-01 4.64622438e-01 8.13651606e-02 8.83355141e-01 4.61607963e-01 8.13650489e-02 8.84913564e-01 4.58610892e-01 8.13651383e-02 8.86521220e-01 4.55498755e-01 8.13651755e-02 8.88148248e-01 4.52314794e-01 8.13652575e-02 8.89749885e-01 4.49157685e-01 8.13651606e-02 8.91279817e-01 4.46111798e-01 8.13650340e-02 8.92784059e-01 4.43095446e-01 8.13651532e-02 8.94309044e-01 4.40010250e-01 8.13651681e-02 8.95883679e-01 4.36798036e-01 8.13652351e-02 8.97413373e-01 4.33647901e-01 8.13650414e-02 8.98876905e-01 4.30598408e-01 8.13651681e-02 9.00408387e-01 4.27387118e-01 8.13652501e-02 9.01896536e-01 4.24237549e-01 8.13650489e-02 9.03371453e-01 4.21093136e-01 8.13653097e-02 9.04845953e-01 4.17909443e-01 8.13650340e-02 9.06257927e-01 4.14838791e-01 8.13651159e-02 9.07736242e-01 4.11595225e-01 8.13652202e-02 9.09209967e-01 4.08333093e-01 8.13651681e-02 9.10627127e-01 4.05162007e-01 8.13651457e-02 9.12007272e-01 4.02041227e-01 8.13650936e-02 9.13369894e-01 3.98942053e-01 8.13651383e-02 9.14748311e-01 3.95766884e-01 8.13651532e-02 9.16118801e-01 3.92577797e-01 8.13651383e-02 9.17520821e-01 3.89295757e-01 8.13653097e-02 9.18882251e-01 3.86070311e-01 8.13650265e-02 9.20178354e-01 3.82974386e-01 8.13651830e-02 9.21513915e-01 3.79746169e-01 8.13651830e-02 9.22843039e-01 3.76507640e-01 8.13651159e-02 9.24169362e-01 3.73240888e-01 8.13652501e-02 9.25512016e-01 3.69898915e-01 8.13651383e-02 9.26767051e-01 3.66744101e-01 8.13649893e-02 9.27996576e-01 3.63624543e-01 8.13651755e-02 9.29258108e-01 3.60368967e-01 8.13651383e-02 9.30550337e-01 3.57043922e-01 8.13652277e-02 9.31797564e-01 3.53750706e-01 8.13650563e-02 9.32994187e-01 3.50570589e-01 8.13650563e-02 9.34232593e-01 3.47260296e-01 8.13652202e-02 9.35476124e-01 3.43903840e-01 8.13650861e-02 9.36674058e-01 3.40654105e-01 8.13651234e-02 9.37825978e-01 3.37447673e-01 8.13649669e-02 9.38967049e-01 3.34276974e-01 8.13651159e-02 9.40155387e-01 3.30918282e-01 8.13652873e-02 9.41346169e-01 3.27509105e-01 8.13651308e-02 9.42485213e-01 3.24225038e-01 8.13651159e-02 9.43569541e-01 3.21046114e-01 8.13649520e-02 9.44657087e-01 3.17837775e-01 8.13650489e-02 9.45766270e-01 3.14520210e-01 8.13651681e-02 9.46859419e-01 3.11212271e-01 8.13651159e-02 9.47958171e-01 3.07854265e-01 8.13651755e-02 9.49063659e-01 3.04426491e-01 8.13650638e-02 9.50099289e-01 3.01177263e-01 8.13649669e-02 9.51115489e-01 2.97955871e-01 8.13651159e-02 9.52146292e-01 2.94642240e-01 8.13650563e-02 9.53190029e-01 2.91249096e-01 8.13652202e-02 9.54224765e-01 2.87835270e-01 8.13651234e-02 9.55202997e-01 2.84575731e-01 8.13650191e-02 9.56164777e-01 2.81333953e-01 8.13651308e-02 9.57138956e-01 2.77996033e-01 8.13651234e-02 9.58110273e-01 2.74629682e-01 8.13651979e-02 9.59075451e-01 2.71244168e-01 8.13650638e-02 9.59994078e-01 2.67973304e-01 8.13650712e-02 9.60929334e-01 2.64594346e-01 8.13651457e-02 9.61843193e-01 2.61264354e-01 8.13651159e-02 9.62764919e-01 2.57835209e-01 8.13651979e-02 9.63670731e-01 2.54431427e-01 8.13650116e-02 9.64527011e-01 2.51170367e-01 8.13651159e-02 9.65395391e-01 2.47808158e-01 8.13651159e-02 9.66276526e-01 2.44344592e-01 8.13652128e-02 9.67138886e-01 2.40908951e-01 8.13650638e-02 9.67970729e-01 2.37554953e-01 8.13651457e-02 9.68778372e-01 2.34239236e-01 8.13650489e-02 9.69563186e-01 2.30966240e-01 8.13651159e-02 9.70367610e-01 2.27558210e-01 8.13650340e-02 9.71180975e-01 2.24066287e-01 8.13653022e-02 9.71955836e-01 2.20673859e-01 8.13650191e-02 9.72703457e-01 2.17364848e-01 8.13650936e-02 9.73453045e-01 2.13969752e-01 8.13650340e-02 9.74202931e-01 2.10534453e-01 8.13651681e-02 9.74935532e-01 2.07117155e-01 8.13650265e-02 9.75658119e-01 2.03691542e-01 8.13652053e-02 9.76360142e-01 2.00294167e-01 8.13650265e-02 9.77052331e-01 1.96893767e-01 8.13652501e-02 9.77749109e-01 1.93398789e-01 8.13650489e-02 9.78424489e-01 1.89958304e-01 8.13651681e-02 9.79059517e-01 1.86644047e-01 8.13650489e-02 9.79692459e-01 1.83302313e-01 8.13651159e-02 9.80335534e-01 1.79826051e-01 8.13653395e-02 9.80976999e-01 1.76323742e-01 8.13651234e-02 9.81588781e-01 1.72888756e-01 8.13651681e-02 9.82169032e-01 1.69522434e-01 8.13649967e-02 9.82742429e-01 1.66187376e-01 8.13651681e-02 9.83314931e-01 1.62747681e-01 8.13651532e-02 9.83876348e-01 1.59325242e-01 8.13651681e-02 9.84441280e-01 1.55803755e-01 8.13653618e-02 9.84991789e-01 1.52273208e-01 8.13651532e-02 9.85502601e-01 1.48923501e-01 8.13650340e-02 9.85999644e-01 1.45604178e-01 8.13651532e-02 9.86504614e-01 1.42140061e-01 8.13651681e-02 9.87007737e-01 1.38615400e-01 8.13652202e-02 9.87496972e-01 1.35085285e-01 8.13650414e-02 9.87947643e-01 1.31725892e-01 8.13649669e-02 9.88393843e-01 1.28350779e-01 8.13650712e-02 9.88834202e-01 1.24919437e-01 8.13651383e-02 9.89265323e-01 1.21451810e-01 8.13651383e-02 9.89684403e-01 1.17978804e-01 8.13651010e-02 9.90088761e-01 1.14540800e-01 8.13651755e-02 9.90496755e-01 1.10969603e-01 8.13652351e-02 9.90875065e-01 1.07534438e-01 8.13650489e-02 9.91240263e-01 1.04109310e-01 8.13652053e-02 9.91601467e-01 1.00598946e-01 8.13650191e-02 9.91937220e-01 9.72429961e-02 8.13651532e-02 9.92280066e-01 9.37107876e-02 8.13652128e-02 9.92607296e-01 9.01523009e-02 8.13651383e-02 9.92915988e-01 8.66901875e-02 8.13651159e-02 9.93205309e-01 8.33061412e-02 8.13650489e-02 9.93484855e-01 7.99108446e-02 8.13651457e-02 9.93754983e-01 7.64538199e-02 8.13651532e-02 9.94025290e-01 7.28791580e-02 8.13652724e-02 9.94276226e-01 6.93359748e-02 8.13651457e-02 9.94505227e-01 6.59743100e-02 8.13650340e-02 9.94725168e-01 6.25915602e-02 8.13651904e-02 9.94938552e-01 5.90881445e-02 8.13651681e-02 9.95140314e-01 5.56341000e-02 8.13651606e-02 9.95331109e-01 5.20736724e-02 8.13652575e-02 9.95513558e-01 4.84906994e-02 8.13651532e-02 9.95669305e-01 4.51219492e-02 8.13650191e-02 9.95819032e-01 4.17445041e-02 8.13651755e-02 9.95957553e-01 3.82891968e-02 8.13651681e-02 9.96089339e-01 3.46722491e-02 8.13652501e-02 9.96204972e-01 3.11971884e-02 8.13650340e-02 9.96306181e-01 2.78152209e-02 8.13651457e-02 9.96397674e-01 2.43283827e-02 8.13651457e-02 9.96472895e-01 2.08438691e-02 8.13651159e-02 9.96545017e-01 1.73829012e-02 8.13651159e-02 9.96591687e-01 1.38901146e-02 8.13650563e-02 9.96637106e-01 1.04202190e-02 8.13650861e-02 9.96677518e-01 6.84079155e-03 8.13652351e-02 9.96692240e-01 3.25688068e-03 8.13651383e-02 9.96693254e-01 -1.99594841e-04 8.13651234e-02 9.96691525e-01 -3.72031494e-03 8.13650712e-02 9.96671319e-01 -7.07528647e-03 8.13649744e-02 9.96639371e-01 -1.04420232e-02 8.13651606e-02 9.96590972e-01 -1.39301708e-02 8.13651010e-02 9.96544003e-01 -1.75331160e-02 8.13652501e-02 9.96467113e-01 -2.11309157e-02 8.13651159e-02 9.96390998e-01 -2.45646853e-02 8.13651085e-02 9.96301830e-01 -2.79207211e-02 8.13650265e-02 9.96198237e-01 -3.14166173e-02 8.13652873e-02 9.96081471e-01 -3.49261910e-02 8.13650191e-02 9.95955646e-01 -3.83270495e-02 8.13651532e-02 9.95819569e-01 -4.17667590e-02 8.13651383e-02 9.95661736e-01 -4.53347266e-02 8.13652575e-02 9.95492101e-01 -4.89166975e-02 8.13651383e-02 9.95314658e-01 -5.23721538e-02 8.13651532e-02 9.95129347e-01 -5.57855666e-02 8.13650265e-02 9.94935453e-01 -5.91567755e-02 8.13651606e-02 9.94722247e-01 -6.26142547e-02 8.13651532e-02 9.94493365e-01 -6.61796108e-02 8.13651979e-02 9.94247735e-01 -6.97557330e-02 8.13651755e-02 9.93998408e-01 -7.32551068e-02 8.13651457e-02 9.93742168e-01 -7.66182914e-02 8.13650191e-02 9.93479490e-01 -7.99648538e-02 8.13651383e-02 9.93193448e-01 -8.34489837e-02 8.13651159e-02 9.92888927e-01 -8.70102718e-02 8.13652724e-02 9.92576480e-01 -9.04738083e-02 8.13650340e-02 9.92268384e-01 -9.38059092e-02 8.13651457e-02 9.91932750e-01 -9.73113775e-02 8.13651308e-02 9.91584420e-01 -1.00783706e-01 8.13651830e-02 9.91223931e-01 -1.04266681e-01 8.13651308e-02 9.90849257e-01 -1.07769012e-01 8.13652501e-02 9.90467429e-01 -1.11230336e-01 8.13650414e-02 9.90083396e-01 -1.14588469e-01 8.13651532e-02 9.89668131e-01 -1.18115231e-01 8.13651755e-02 9.89248693e-01 -1.21588208e-01 8.13650265e-02 9.88818765e-01 -1.25050113e-01 8.13652873e-02 9.88360584e-01 -1.28603026e-01 8.13651010e-02 9.87922609e-01 -1.31926700e-01 8.13650340e-02 9.87454891e-01 -1.35397032e-01 8.13652202e-02 9.86964583e-01 -1.38925105e-01 8.13650712e-02 9.86479700e-01 -1.42311990e-01 8.13650116e-02 9.85981405e-01 -1.45726979e-01 8.13652873e-02 9.85462368e-01 -1.49186596e-01 8.13650563e-02 9.84939218e-01 -1.52614847e-01 8.13651606e-02 9.84398544e-01 -1.56057954e-01 8.13649893e-02 9.83851671e-01 -1.59481257e-01 8.13652501e-02 9.83288646e-01 -1.62910447e-01 8.13650116e-02 9.82715666e-01 -1.66340545e-01 8.13652724e-02 9.82112885e-01 -1.69846326e-01 8.13651457e-02 9.81512666e-01 -1.73312545e-01 8.13651755e-02 9.80919719e-01 -1.76633716e-01 8.13650340e-02 9.80307996e-01 -1.79965600e-01 8.13651383e-02 9.79678750e-01 -1.83376923e-01 8.13651159e-02 9.79011238e-01 -1.86899275e-01 8.13652724e-02 9.78340864e-01 -1.90386161e-01 8.13651234e-02 9.77672279e-01 -1.93786666e-01 8.13651457e-02 9.77005541e-01 -1.97116509e-01 8.13649744e-02 9.76328433e-01 -2.00445861e-01 8.13650861e-02 9.75615203e-01 -2.03888714e-01 8.13651159e-02 9.74882901e-01 -2.07369491e-01 8.13652501e-02 9.74162579e-01 -2.10731968e-01 8.13650116e-02 9.73412335e-01 -2.14160845e-01 8.13651904e-02 9.72660482e-01 -2.17552096e-01 8.13650191e-02 9.71901000e-01 -2.20920309e-01 8.13651979e-02 9.71120656e-01 -2.24326730e-01 8.13650489e-02 9.70330358e-01 -2.27727205e-01 8.13652053e-02 9.69527245e-01 -2.31121749e-01 8.13650340e-02 9.68744993e-01 -2.34380230e-01 8.13650712e-02 9.67895091e-01 -2.37858713e-01 8.13651904e-02 9.67057526e-01 -2.41232440e-01 8.13649818e-02 9.66209710e-01 -2.44611397e-01 8.13652501e-02 9.65335727e-01 -2.48040721e-01 8.13650116e-02 9.64493513e-01 -2.51290441e-01 8.13650340e-02 9.63593721e-01 -2.54730016e-01 8.13651830e-02 9.62700427e-01 -2.58080453e-01 8.13650116e-02 9.61830199e-01 -2.61307657e-01 8.13651010e-02 9.60882962e-01 -2.64760584e-01 8.13651904e-02 9.59937394e-01 -2.68179297e-01 8.13650116e-02 9.59008157e-01 -2.71481723e-01 8.13652277e-02 9.58027184e-01 -2.74920553e-01 8.13651383e-02 9.57074404e-01 -2.78214276e-01 8.13650042e-02 9.56140220e-01 -2.81411648e-01 8.13650936e-02 9.55130398e-01 -2.84828365e-01 8.13652501e-02 9.54097569e-01 -2.88257360e-01 8.13651681e-02 9.53074694e-01 -2.91629523e-01 8.13651606e-02 9.52074111e-01 -2.94876248e-01 8.13649893e-02 9.51080859e-01 -2.98065096e-01 8.13651457e-02 9.50033426e-01 -3.01385283e-01 8.13650861e-02 9.48946893e-01 -3.04792136e-01 8.13652202e-02 9.47851956e-01 -3.08177233e-01 8.13651457e-02 9.46771085e-01 -3.11481029e-01 8.13651383e-02 9.45693195e-01 -3.14739674e-01 8.13650489e-02 9.44622695e-01 -3.17940205e-01 8.13650712e-02 9.43510830e-01 -3.21226180e-01 8.13651830e-02 9.42363977e-01 -3.24574620e-01 8.13651830e-02 9.41218197e-01 -3.27874750e-01 8.13650191e-02 9.40068603e-01 -3.31163287e-01 8.13652277e-02 9.38911259e-01 -3.34432214e-01 8.13650191e-02 9.37739670e-01 -3.37702185e-01 8.13652575e-02 9.36550915e-01 -3.40987533e-01 8.13649669e-02 9.35347378e-01 -3.44257474e-01 8.13652501e-02 9.34132516e-01 -3.47523957e-01 8.13650563e-02 9.32952702e-01 -3.50683331e-01 8.13651383e-02 9.31716263e-01 -3.53966534e-01 8.13651010e-02 9.30456221e-01 -3.57293874e-01 8.13653097e-02 9.29182172e-01 -3.60564858e-01 8.13650414e-02 9.27928805e-01 -3.63796592e-01 8.13652575e-02 9.26650405e-01 -3.67035627e-01 8.13650042e-02 9.25375104e-01 -3.70240062e-01 8.13652501e-02 9.24068689e-01 -3.73487324e-01 8.13650265e-02 9.22804713e-01 -3.76599669e-01 8.13651532e-02 9.21449661e-01 -3.79902601e-01 8.13652501e-02 9.20104682e-01 -3.83146971e-01 8.13650191e-02 9.18761730e-01 -3.86358738e-01 8.13652724e-02 9.17368531e-01 -3.89649123e-01 8.13651234e-02 9.16037619e-01 -3.92766684e-01 8.13650265e-02 9.14711356e-01 -3.95850658e-01 8.13650638e-02 9.13286805e-01 -3.99132520e-01 8.13652277e-02 9.11850572e-01 -4.02400881e-01 8.13651532e-02 9.10445392e-01 -4.05566603e-01 8.13650638e-02 9.09039974e-01 -4.08710182e-01 8.13650265e-02 9.07648861e-01 -4.11785156e-01 8.13650638e-02 9.06237304e-01 -4.14879173e-01 8.13650340e-02 9.04729009e-01 -4.18163687e-01 8.13651979e-02 9.03229177e-01 -4.21393722e-01 8.13651159e-02 9.01746273e-01 -4.24555540e-01 8.13651383e-02 9.00292277e-01 -4.27633107e-01 8.13650489e-02 8.98823678e-01 -4.30707335e-01 8.13651532e-02 8.97325456e-01 -4.33828771e-01 8.13650861e-02 8.95747423e-01 -4.37077820e-01 8.13652128e-02 8.94222736e-01 -4.40183401e-01 8.13650191e-02 8.92666280e-01 -4.43332255e-01 8.13651532e-02 8.91139269e-01 -4.46394652e-01 8.13650489e-02 8.89619350e-01 -4.49417859e-01 8.13651159e-02 8.88056993e-01 -4.52498734e-01 8.13651681e-02 8.86422336e-01 -4.55690920e-01 8.13652873e-02 8.84813190e-01 -4.58799541e-01 8.13648999e-02 8.83253574e-01 -4.61804628e-01 8.13651681e-02 8.81652236e-01 -4.64850157e-01 8.13650340e-02 8.79953921e-01 -4.68060821e-01 8.13652873e-02 8.78315806e-01 -4.71125633e-01 8.13650042e-02 8.76692235e-01 -4.74141330e-01 8.13652501e-02 8.75005782e-01 -4.77249086e-01 8.13650489e-02 8.73397648e-01 -4.80180830e-01 8.13651383e-02 8.71706128e-01 -4.83241439e-01 8.13651457e-02 8.69975269e-01 -4.86353338e-01 8.13651830e-02 8.68267357e-01 -4.89396602e-01 8.13650414e-02 8.66564214e-01 -4.92405981e-01 8.13651979e-02 8.64836454e-01 -4.95437592e-01 8.13650489e-02 8.63100886e-01 -4.98453230e-01 8.13652948e-02 8.61330569e-01 -5.01505256e-01 8.13651159e-02 8.59618247e-01 -5.04435480e-01 8.13650936e-02 8.57874393e-01 -5.07393777e-01 8.13651457e-02 8.56101394e-01 -5.10378361e-01 8.13651532e-02 8.54279339e-01 -5.13427079e-01 8.13653469e-02 8.52418065e-01 -5.16506135e-01 8.13651904e-02 8.50642204e-01 -5.19428611e-01 8.13650414e-02 8.48881781e-01 -5.22298515e-01 8.13651755e-02 8.47059846e-01 -5.25251746e-01 8.13651457e-02 8.45176339e-01 -5.28276920e-01 8.13653171e-02 8.43272448e-01 -5.31309128e-01 8.13651457e-02 8.41420472e-01 -5.34235954e-01 8.13651383e-02 8.39617312e-01 -5.37065029e-01 8.13650563e-02 8.37726116e-01 -5.40011823e-01 8.13652277e-02 8.35783362e-01 -5.43012023e-01 8.13651234e-02 8.33873928e-01 -5.45937717e-01 8.13651383e-02 8.31973016e-01 -5.48832417e-01 8.13650638e-02 8.30093980e-01 -5.51664412e-01 8.13649073e-02 8.28223288e-01 -5.54475546e-01 8.13651532e-02 8.26293647e-01 -5.57349086e-01 8.13650861e-02 8.24269533e-01 -5.60336590e-01 8.13651681e-02 8.22274148e-01 -5.63260436e-01 8.13650340e-02 8.20302188e-01 -5.66130459e-01 8.13650787e-02 8.18382680e-01 -5.68897605e-01 8.13649669e-02 8.16374600e-01 -5.71776450e-01 8.13651904e-02 8.14374685e-01 -5.74623883e-01 8.13649446e-02 8.12363386e-01 -5.77462733e-01 8.13651979e-02 8.10341895e-01 -5.80296636e-01 8.13649669e-02 8.08365107e-01 -5.83041728e-01 8.13651159e-02 8.06310773e-01 -5.85884988e-01 8.13650936e-02 8.04263473e-01 -5.88689685e-01 8.13651234e-02 8.02163839e-01 -5.91548324e-01 8.13651755e-02 8.00029576e-01 -5.94431937e-01 8.13650861e-02 7.98021197e-01 -5.97123086e-01 8.13650414e-02 7.95937181e-01 -5.99903226e-01 8.13653320e-02 7.93821037e-01 -6.02698565e-01 8.13650340e-02 7.91732907e-01 -6.05438888e-01 8.13652202e-02 7.89622009e-01 -6.08188570e-01 8.13650563e-02 7.87531674e-01 -6.10892594e-01 8.13651830e-02 7.85340011e-01 -6.13708496e-01 8.13651830e-02 7.83157229e-01 -6.16491914e-01 8.13651979e-02 7.81027853e-01 -6.19185030e-01 8.13650489e-02 7.78924584e-01 -6.21831715e-01 8.13651830e-02 7.76747704e-01 -6.24548793e-01 8.13651532e-02 7.74517655e-01 -6.27313972e-01 8.13652873e-02 7.72302389e-01 -6.30033076e-01 8.13650563e-02 7.70168304e-01 -6.32643461e-01 8.13651830e-02 7.67955601e-01 -6.35328591e-01 8.13651532e-02 7.65739799e-01 -6.37997508e-01 8.13651681e-02 7.63508439e-01 -6.40665710e-01 8.13651532e-02 7.61186123e-01 -6.43422246e-01 8.13653320e-02 7.58931518e-01 -6.46077991e-01 8.13650340e-02 7.56756246e-01 -6.48626566e-01 8.13651830e-02 7.54484117e-01 -6.51269674e-01 8.13651979e-02 7.52167761e-01 -6.53943121e-01 8.13652053e-02 7.49826729e-01 -6.56624973e-01 8.13652202e-02 7.47501314e-01 -6.59271359e-01 8.13651979e-02 7.45237052e-01 -6.61829233e-01 8.13650712e-02 7.42981374e-01 -6.64362133e-01 8.13651681e-02 7.40615249e-01 -6.66999340e-01 8.13652426e-02 7.38296270e-01 -6.69566512e-01 8.13650787e-02 7.35938847e-01 -6.72154903e-01 8.13653097e-02 7.33587444e-01 -6.74720466e-01 8.13650489e-02 7.31297195e-01 -6.77201569e-01 8.13651606e-02 7.28935838e-01 -6.79740965e-01 8.13651755e-02 7.26491332e-01 -6.82354212e-01 8.13653246e-02 7.24100947e-01 -6.84888065e-01 8.13650489e-02 7.21715689e-01 -6.87407851e-01 8.13652724e-02 7.19297349e-01 -6.89927101e-01 8.13650489e-02 7.16908514e-01 -6.92425311e-01 8.13653618e-02 7.14469671e-01 -6.94936872e-01 8.13650414e-02 7.12104678e-01 -6.97358072e-01 8.13651755e-02 7.09612846e-01 -6.99895859e-01 8.13652351e-02 7.07144380e-01 -7.02390671e-01 8.13650340e-02 7.04672396e-01 -7.04852939e-01 8.13651159e-02 7.02164948e-01 -7.07366407e-01 8.13649669e-02 6.99752271e-01 -7.09751129e-01 8.13646540e-02 6.97381139e-01 -7.12078273e-01 8.13646540e-02 6.94898129e-01 -7.14503229e-01 8.13643932e-02 6.92321181e-01 -7.16996789e-01 8.13643187e-02 6.89778566e-01 -7.19438374e-01 8.13639984e-02 6.87288046e-01 -7.21816540e-01 8.13639984e-02 6.84754491e-01 -7.24215925e-01 8.13639984e-02 6.82321846e-01 -7.26504505e-01 8.13640207e-02 6.80044711e-01 -7.28639662e-01 8.13641623e-02 6.77648485e-01 -7.30870903e-01 8.13644752e-02 6.75058424e-01 -7.33263731e-01 8.13644752e-02 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.56479752e-01 -8.26866508e-01 8.13645273e-02 5.54209828e-01 -8.28386068e-01 8.13640207e-02 5.51388502e-01 -8.30275297e-01 8.13642442e-02 5.48535526e-01 -8.32165956e-01 8.13646093e-02 5.45697451e-01 -8.34030509e-01 8.13649371e-02 5.42726040e-01 -8.35968971e-01 8.13651159e-02 5.39797902e-01 -8.37862551e-01 8.13649818e-02 5.36946893e-01 -8.39692533e-01 8.13651681e-02 5.33998966e-01 -8.41569424e-01 8.13651532e-02 5.31068504e-01 -8.43425214e-01 8.13651606e-02 5.28122544e-01 -8.45270038e-01 8.13651606e-02 5.25177717e-01 -8.47104728e-01 8.13650489e-02 5.22226870e-01 -8.48923922e-01 8.13649669e-02 5.19263923e-01 -8.50742161e-01 8.13649446e-02 5.16290724e-01 -8.52547646e-01 8.13650340e-02 5.13311386e-01 -8.54347229e-01 8.13650861e-02 5.10272026e-01 -8.56165469e-01 8.13651383e-02 5.07281542e-01 -8.57940435e-01 8.13650116e-02 5.04335940e-01 -8.59675109e-01 8.13649148e-02 5.01322448e-01 -8.61434817e-01 8.13648254e-02 4.98242229e-01 -8.63221467e-01 8.13649669e-02 4.95239913e-01 -8.64946485e-01 8.13648105e-02 4.92312968e-01 -8.66615832e-01 8.13649893e-02 4.89282787e-01 -8.68333101e-01 8.13649669e-02 4.86257881e-01 -8.70027542e-01 8.13650340e-02 4.83199447e-01 -8.71728003e-01 8.13650563e-02 4.80150908e-01 -8.73413742e-01 8.13650787e-02 4.77129191e-01 -8.75070095e-01 8.13651457e-02 4.74057674e-01 -8.76736701e-01 8.13651532e-02 4.71005857e-01 -8.78379345e-01 8.13651606e-02 4.67935294e-01 -8.80019248e-01 8.13651755e-02 4.64839458e-01 -8.81659329e-01 8.13651755e-02 4.61706311e-01 -8.83303702e-01 8.13652575e-02 4.58617628e-01 -8.84909272e-01 8.13650787e-02 4.55584973e-01 -8.86476934e-01 8.13651681e-02 4.52484041e-01 -8.88062060e-01 8.13651681e-02 4.49372590e-01 -8.89641881e-01 8.13651830e-02 4.46266621e-01 -8.91203582e-01 8.13651681e-02 4.43163544e-01 -8.92750204e-01 8.13651681e-02 4.40051198e-01 -8.94288778e-01 8.13651830e-02 4.36918557e-01 -8.95824313e-01 8.13651979e-02 4.33795899e-01 -8.97340834e-01 8.13651606e-02 4.30631489e-01 -8.98861051e-01 8.13652053e-02 4.27441597e-01 -9.00383830e-01 8.13652277e-02 4.24292803e-01 -9.01870608e-01 8.13650638e-02 4.21107262e-01 -9.03364837e-01 8.13653097e-02 4.17933136e-01 -9.04835105e-01 8.13650414e-02 4.14891571e-01 -9.06233430e-01 8.13651532e-02 4.11712706e-01 -9.07684147e-01 8.13651681e-02 4.08569634e-01 -9.09103096e-01 8.13651532e-02 4.05280679e-01 -9.10575271e-01 8.13653618e-02 4.02070850e-01 -9.11995649e-01 8.13650116e-02 3.98999870e-01 -9.13345218e-01 8.13652053e-02 3.95816207e-01 -9.14727032e-01 8.13651681e-02 3.92601639e-01 -9.16108489e-01 8.13651681e-02 3.89344364e-01 -9.17500675e-01 8.13652277e-02 3.86169225e-01 -9.18842316e-01 8.13651085e-02 3.82893950e-01 -9.20211673e-01 8.13653842e-02 3.79648387e-01 -9.21552837e-01 8.13650414e-02 3.76568705e-01 -9.22818601e-01 8.13651532e-02 3.73292118e-01 -9.24148440e-01 8.13652501e-02 3.69972318e-01 -9.25482094e-01 8.13652202e-02 3.66684735e-01 -9.26791191e-01 8.13651830e-02 3.63524854e-01 -9.28034186e-01 8.13650489e-02 3.60385865e-01 -9.29252207e-01 8.13651830e-02 3.57120425e-01 -9.30521846e-01 8.13651830e-02 3.53901476e-01 -9.31741655e-01 8.13651383e-02 3.50643754e-01 -9.32968736e-01 8.13651681e-02 3.47352773e-01 -9.34197962e-01 8.13651681e-02 3.44103515e-01 -9.35402691e-01 8.13651457e-02 3.40850353e-01 -9.36601222e-01 8.13651681e-02 3.37590963e-01 -9.37777400e-01 8.13651681e-02 3.34300637e-01 -9.38958347e-01 8.13651457e-02 3.30963552e-01 -9.40138161e-01 8.13653320e-02 3.27638358e-01 -9.41301107e-01 8.13650638e-02 3.24384123e-01 -9.42430079e-01 8.13653097e-02 3.21065396e-01 -9.43563521e-01 8.13650787e-02 3.17857444e-01 -9.44651067e-01 8.13651532e-02 3.14471304e-01 -9.45782065e-01 8.13653097e-02 3.11159581e-01 -9.46875155e-01 8.13650638e-02 3.07835817e-01 -9.47963417e-01 8.13652873e-02 3.04529786e-01 -9.49031949e-01 8.13650936e-02 3.01296324e-01 -9.50061738e-01 8.13651532e-02 2.97994286e-01 -9.51103270e-01 8.13651830e-02 2.94674456e-01 -9.52137053e-01 8.13651755e-02 2.91352957e-01 -9.53159213e-01 8.13651830e-02 2.87930012e-01 -9.54196334e-01 8.13652501e-02 2.84507990e-01 -9.55223501e-01 8.13651606e-02 2.81270593e-01 -9.56183314e-01 8.13650638e-02 2.77933270e-01 -9.57159221e-01 8.13653618e-02 2.74498940e-01 -9.58148777e-01 8.13651830e-02 2.71159887e-01 -9.59098220e-01 8.13651830e-02 2.67896563e-01 -9.60016429e-01 8.13650936e-02 2.64628619e-01 -9.60920036e-01 8.13651532e-02 2.61285067e-01 -9.61837590e-01 8.13651532e-02 2.57893085e-01 -9.62750018e-01 8.13652053e-02 2.54569471e-01 -9.63634551e-01 8.13651532e-02 2.51210511e-01 -9.64518249e-01 8.13651830e-02 2.47758672e-01 -9.65408742e-01 8.13652501e-02 2.44386256e-01 -9.66265976e-01 8.13650638e-02 2.41019219e-01 -9.67112482e-01 8.13653097e-02 2.37618446e-01 -9.67954814e-01 8.13651159e-02 2.34314710e-01 -9.68760610e-01 8.13651904e-02 2.30859891e-01 -9.69591439e-01 8.13652501e-02 2.27487117e-01 -9.70385373e-01 8.13651159e-02 2.24086523e-01 -9.71176505e-01 8.13653320e-02 2.20611930e-01 -9.71970618e-01 8.13651681e-02 2.17323825e-01 -9.72711921e-01 8.13650563e-02 2.14019611e-01 -9.73442852e-01 8.13651830e-02 2.10621148e-01 -9.74184394e-01 8.13651755e-02 2.07219005e-01 -9.74913776e-01 8.13652202e-02 2.03704581e-01 -9.75656807e-01 8.13653842e-02 2.00289577e-01 -9.76361811e-01 8.13650340e-02 1.96983576e-01 -9.77034152e-01 8.13651681e-02 1.93577617e-01 -9.77714241e-01 8.13651904e-02 1.90147802e-01 -9.78387952e-01 8.13651830e-02 1.86642021e-01 -9.79061902e-01 8.13653842e-02 1.83222324e-01 -9.79706824e-01 8.13650265e-02 1.79799542e-01 -9.80340362e-01 8.13654214e-02 1.76346421e-01 -9.80973661e-01 8.13650340e-02 1.73029989e-01 -9.81563389e-01 8.13651830e-02 1.69603810e-01 -9.82154906e-01 8.13651979e-02 1.66164562e-01 -9.82744873e-01 8.13651755e-02 1.62651360e-01 -9.83331859e-01 8.13653618e-02 1.59214884e-01 -9.83893573e-01 8.13650489e-02 1.55881777e-01 -9.84428585e-01 8.13651606e-02 1.52437493e-01 -9.84967470e-01 8.13651904e-02 1.48982525e-01 -9.85494614e-01 8.13651830e-02 1.45466432e-01 -9.86021459e-01 8.13652873e-02 1.42013803e-01 -9.86523211e-01 8.13650638e-02 1.38569072e-01 -9.87015724e-01 8.13653618e-02 1.35018229e-01 -9.87507164e-01 8.13651681e-02 1.31657422e-01 -9.87957656e-01 8.13650414e-02 1.28326580e-01 -9.88397419e-01 8.13651606e-02 1.24874197e-01 -9.88841534e-01 8.13651681e-02 1.21432818e-01 -9.89268422e-01 8.13651979e-02 1.17881335e-01 -9.89698231e-01 8.13654214e-02 1.14405587e-01 -9.90104079e-01 8.13650712e-02 1.11073144e-01 -9.90484655e-01 8.13651830e-02 1.07626833e-01 -9.90864336e-01 8.13651904e-02 1.04163572e-01 -9.91234541e-01 8.13651904e-02 1.00601494e-01 -9.91602004e-01 8.13653916e-02 9.71084684e-02 -9.91951168e-01 8.13651010e-02 9.36796218e-02 -9.92282629e-01 8.13653618e-02 9.02009681e-02 -9.92602110e-01 8.13650489e-02 8.67341086e-02 -9.92913246e-01 8.13653618e-02 8.31625238e-02 -9.93216813e-01 8.13651830e-02 7.97627196e-02 -9.93496716e-01 8.13650340e-02 7.63318241e-02 -9.93767023e-01 8.13653991e-02 7.28342533e-02 -9.94027674e-01 8.13651159e-02 6.94761649e-02 -9.94266689e-01 8.13651830e-02 6.60231337e-02 -9.94503975e-01 8.13652053e-02 6.25412688e-02 -9.94728506e-01 8.13651681e-02 5.89598939e-02 -9.94947672e-01 8.13653171e-02 5.54989502e-02 -9.95146930e-01 8.13650563e-02 5.20319864e-02 -9.95333791e-01 8.13653320e-02 4.85522375e-02 -9.95510161e-01 8.13650936e-02 4.50976752e-02 -9.95672524e-01 8.13654214e-02 4.15049978e-02 -9.95829463e-01 8.13651904e-02 3.81169282e-02 -9.95962739e-01 8.13650340e-02 3.47538367e-02 -9.96086121e-01 8.13651681e-02 3.11864577e-02 -9.96204495e-01 8.13652501e-02 2.76949499e-02 -9.96308386e-01 8.13651159e-02 2.42266320e-02 -9.96401250e-01 8.13653544e-02 2.07325108e-02 -9.96474922e-01 8.13650936e-02 1.73460059e-02 -9.96546686e-01 8.13651755e-02 1.38071356e-02 -9.96591985e-01 8.13653618e-02 1.02994675e-02 -9.96640146e-01 8.13651159e-02 6.89581083e-03 -9.96675968e-01 8.13651830e-02 3.42771690e-03 -9.96692419e-01 8.13651755e-02 -2.88938954e-05 -9.96693671e-01 8.13651904e-02 -3.48685333e-03 -9.96692657e-01 8.13652351e-02 -6.98643504e-03 -9.96675551e-01 8.13651979e-02 -1.05443094e-02 -9.96639431e-01 8.13653842e-02 -1.40450569e-02 -9.96589363e-01 8.13650489e-02 -1.75075494e-02 -9.96545374e-01 8.13653320e-02 -2.10907031e-02 -9.96467888e-01 8.13652202e-02 -2.44880617e-02 -9.96393681e-01 8.13650936e-02 -2.78488938e-02 -9.96305108e-01 8.13651904e-02 -3.13116387e-02 -9.96201694e-01 8.13652128e-02 -3.48907150e-02 -9.96083260e-01 8.13654736e-02 -3.84906270e-02 -9.95950937e-01 8.13652053e-02 -4.18726765e-02 -9.95814145e-01 8.13650936e-02 -4.52522710e-02 -9.95665133e-01 8.13652053e-02 -4.87325899e-02 -9.95501935e-01 8.13652277e-02 -5.21999933e-02 -9.95323896e-01 8.13652053e-02 -5.57469688e-02 -9.95134115e-01 8.13653469e-02 -5.92477061e-02 -9.94930506e-01 8.13651010e-02 -6.26832992e-02 -9.94719565e-01 8.13653842e-02 -6.61901906e-02 -9.94491458e-01 8.13651234e-02 -6.95646852e-02 -9.94260311e-01 8.13651904e-02 -7.31081292e-02 -9.94008183e-01 8.13653618e-02 -7.65992999e-02 -9.93744552e-01 8.13651159e-02 -8.00497904e-02 -9.93473947e-01 8.13653767e-02 -8.35256353e-02 -9.93185818e-01 8.13651457e-02 -8.69200826e-02 -9.92895961e-01 8.13652202e-02 -9.03799459e-02 -9.92586076e-01 8.13652128e-02 -9.38328505e-02 -9.92266953e-01 8.13652277e-02 -9.73742977e-02 -9.91926610e-01 8.13653618e-02 -1.00847319e-01 -9.91578698e-01 8.13650787e-02 -1.04283981e-01 -9.91223037e-01 8.13653842e-02 -1.07825115e-01 -9.90842462e-01 8.13651681e-02 -1.11212842e-01 -9.90469217e-01 8.13650936e-02 -1.14586994e-01 -9.90084350e-01 8.13652128e-02 -1.18030638e-01 -9.89678383e-01 8.13652128e-02 -1.21488169e-01 -9.89260554e-01 8.13652202e-02 -1.25033394e-01 -9.88822162e-01 8.13654661e-02 -1.28484532e-01 -9.88375723e-01 8.13650563e-02 -1.31851822e-01 -9.87934053e-01 8.13652277e-02 -1.35292441e-01 -9.87467825e-01 8.13651904e-02 -1.38724774e-01 -9.86992896e-01 8.13652053e-02 -1.42273515e-01 -9.86487687e-01 8.13654661e-02 -1.45710841e-01 -9.85983133e-01 8.13651010e-02 -1.49138510e-01 -9.85470712e-01 8.13653320e-02 -1.52567595e-01 -9.84946549e-01 8.13651234e-02 -1.55916467e-01 -9.84421551e-01 8.13652053e-02 -1.59352630e-01 -9.83871758e-01 8.13651904e-02 -1.62784368e-01 -9.83311057e-01 8.13652128e-02 -1.66335642e-01 -9.82716203e-01 8.13654512e-02 -1.69751704e-01 -9.82129276e-01 8.13650861e-02 -1.73085719e-01 -9.81553078e-01 8.13651904e-02 -1.76518738e-01 -9.80940104e-01 8.13652277e-02 -1.79934055e-01 -9.80314672e-01 8.13651904e-02 -1.83455467e-01 -9.79666471e-01 8.13654363e-02 -1.86880663e-01 -9.79016066e-01 8.13651383e-02 -1.90202758e-01 -9.78374660e-01 8.13651979e-02 -1.93600520e-01 -9.77710247e-01 8.13651904e-02 -1.97094396e-01 -9.77012575e-01 8.13653916e-02 -2.00524017e-01 -9.76312280e-01 8.13650936e-02 -2.03821585e-01 -9.75630045e-01 8.13651830e-02 -2.07246780e-01 -9.74909306e-01 8.13652128e-02 -2.10726261e-01 -9.74163353e-01 8.13653618e-02 -2.14136600e-01 -9.73415732e-01 8.13650638e-02 -2.17443377e-01 -9.72686291e-01 8.13652128e-02 -2.20846996e-01 -9.71917689e-01 8.13652277e-02 -2.24245876e-01 -9.71138060e-01 8.13652053e-02 -2.27734670e-01 -9.70330417e-01 8.13654512e-02 -2.31134921e-01 -9.69523489e-01 8.13650861e-02 -2.34389544e-01 -9.68742728e-01 8.13651904e-02 -2.37791196e-01 -9.67912197e-01 8.13651830e-02 -2.41165325e-01 -9.67075765e-01 8.13652277e-02 -2.44594216e-01 -9.66213822e-01 8.13652724e-02 -2.48006344e-01 -9.65344727e-01 8.13651159e-02 -2.51385421e-01 -9.64470148e-01 8.13653842e-02 -2.54748523e-01 -9.63588357e-01 8.13650936e-02 -2.58092344e-01 -9.62698579e-01 8.13653395e-02 -2.61536449e-01 -9.61769164e-01 8.13652202e-02 -2.64830261e-01 -9.60864544e-01 8.13650563e-02 -2.68169224e-01 -9.59940135e-01 8.13653842e-02 -2.71519601e-01 -9.58996236e-01 8.13650340e-02 -2.74765491e-01 -9.58071530e-01 8.13651457e-02 -2.78104424e-01 -9.57107842e-01 8.13652128e-02 -2.81435758e-01 -9.56132889e-01 8.13651681e-02 -2.84761906e-01 -9.55149233e-01 8.13651755e-02 -2.88107008e-01 -9.54143345e-01 8.13651979e-02 -2.91450292e-01 -9.53126848e-01 8.13651904e-02 -2.94828773e-01 -9.52091098e-01 8.13653842e-02 -2.98173577e-01 -9.51045394e-01 8.13650787e-02 -3.01495701e-01 -9.49999630e-01 8.13653544e-02 -3.04810971e-01 -9.48941410e-01 8.13650712e-02 -3.08015674e-01 -9.47904468e-01 8.13651085e-02 -3.11456203e-01 -9.46780264e-01 8.13653097e-02 -3.14726532e-01 -9.45697546e-01 8.13651383e-02 -3.18013757e-01 -9.44600165e-01 8.13653693e-02 -3.21327329e-01 -9.43475008e-01 8.13651159e-02 -3.24536204e-01 -9.42377269e-01 8.13651606e-02 -3.27862978e-01 -9.41223264e-01 8.13652873e-02 -3.31143230e-01 -9.40076828e-01 8.13651159e-02 -3.34456265e-01 -9.38901961e-01 8.13652575e-02 -3.37760001e-01 -9.37716246e-01 8.13650116e-02 -3.41016233e-01 -9.36541975e-01 8.13652575e-02 -3.44282150e-01 -9.35336709e-01 8.13650936e-02 -3.47453117e-01 -9.34160411e-01 8.13652053e-02 -3.50776702e-01 -9.32919681e-01 8.13652948e-02 -3.54040980e-01 -9.31687534e-01 8.13650414e-02 -3.57287556e-01 -9.30458784e-01 8.13653395e-02 -3.60625058e-01 -9.29160416e-01 8.13651532e-02 -3.63779396e-01 -9.27934051e-01 8.13650638e-02 -3.66925627e-01 -9.26695347e-01 8.13651830e-02 -3.70157659e-01 -9.25407052e-01 8.13651457e-02 -3.73404622e-01 -9.24102426e-01 8.13651532e-02 -3.76691192e-01 -9.22767937e-01 8.13654885e-02 -3.79945666e-01 -9.21428978e-01 8.13650489e-02 -3.83069217e-01 -9.20138896e-01 8.13651755e-02 -3.86256516e-01 -9.18805003e-01 8.13651755e-02 -3.89458686e-01 -9.17451143e-01 8.13651830e-02 -3.92740935e-01 -9.16050434e-01 8.13653618e-02 -3.95949394e-01 -9.14668083e-01 8.13650936e-02 -3.99119735e-01 -9.13294017e-01 8.13653842e-02 -4.02330130e-01 -9.11880732e-01 8.13651234e-02 -4.05433178e-01 -9.10506487e-01 8.13651904e-02 -4.08690929e-01 -9.09049630e-01 8.13653246e-02 -4.11860496e-01 -9.07615662e-01 8.13650787e-02 -4.14995521e-01 -9.06184971e-01 8.13653618e-02 -4.18169856e-01 -9.04724896e-01 8.13650712e-02 -4.21238661e-01 -9.03301597e-01 8.13651904e-02 -4.24402356e-01 -9.01819646e-01 8.13651830e-02 -4.27622944e-01 -9.00299072e-01 8.13653842e-02 -4.30761665e-01 -8.98797750e-01 8.13650861e-02 -4.33823824e-01 -8.97328854e-01 8.13652202e-02 -4.37030166e-01 -8.95771325e-01 8.13654140e-02 -4.40233767e-01 -8.94198179e-01 8.13651681e-02 -4.43271309e-01 -8.92696619e-01 8.13651234e-02 -4.46310908e-01 -8.91181648e-01 8.13651830e-02 -4.49412823e-01 -8.89622152e-01 8.13652277e-02 -4.52524871e-01 -8.88042271e-01 8.13651830e-02 -4.55678165e-01 -8.86428118e-01 8.13653618e-02 -4.58782881e-01 -8.84823024e-01 8.13650563e-02 -4.61774379e-01 -8.83269489e-01 8.13652128e-02 -4.64876294e-01 -8.81640136e-01 8.13652351e-02 -4.67939883e-01 -8.80016506e-01 8.13652053e-02 -4.71097231e-01 -8.78332019e-01 8.13653618e-02 -4.74162340e-01 -8.76678348e-01 8.13651159e-02 -4.77198124e-01 -8.75033557e-01 8.13653246e-02 -4.80251342e-01 -8.73359084e-01 8.13650414e-02 -4.83299375e-01 -8.71675193e-01 8.13653246e-02 -4.86393780e-01 -8.69951785e-01 8.13651904e-02 -4.89377737e-01 -8.68278623e-01 8.13651457e-02 -4.92392838e-01 -8.66572082e-01 8.13653097e-02 -4.95400995e-01 -8.64856958e-01 8.13650936e-02 -4.98361558e-01 -8.63153160e-01 8.13651755e-02 -5.01447201e-01 -8.61365378e-01 8.13654065e-02 -5.04454136e-01 -8.59606981e-01 8.13650489e-02 -5.07449508e-01 -8.57842743e-01 8.13653618e-02 -5.10435641e-01 -8.56066883e-01 8.13650489e-02 -5.13410449e-01 -8.54287565e-01 8.13653097e-02 -5.16403854e-01 -8.52479994e-01 8.13650563e-02 -5.19373894e-01 -8.50677609e-01 8.13652799e-02 -5.22429705e-01 -8.48801792e-01 8.13652277e-02 -5.25306523e-01 -8.47025096e-01 8.13650936e-02 -5.28165698e-01 -8.45245421e-01 8.13651755e-02 -5.31208217e-01 -8.43335986e-01 8.13653991e-02 -5.34219742e-01 -8.41431320e-01 8.13652202e-02 -5.37151575e-01 -8.39563131e-01 8.13651681e-02 -5.40010989e-01 -8.37725639e-01 8.13651159e-02 -5.42857528e-01 -8.35885346e-01 8.13652277e-02 -5.45780122e-01 -8.33978057e-01 8.13651606e-02 -5.48686743e-01 -8.32070529e-01 8.13651606e-02 -5.51566660e-01 -8.30160856e-01 8.13651755e-02 -5.54459751e-01 -8.28233778e-01 8.13651904e-02 -5.57422996e-01 -8.26245427e-01 8.13653842e-02 -5.60346544e-01 -8.24261665e-01 8.13651457e-02 -5.63139975e-01 -8.22358131e-01 8.13651532e-02 -5.66047788e-01 -8.20359528e-01 8.13653320e-02 -5.68920910e-01 -8.18368912e-01 8.13650340e-02 -5.71767986e-01 -8.16380918e-01 8.13653767e-02 -5.74706674e-01 -8.14316750e-01 8.13651904e-02 -5.77458262e-01 -8.12365890e-01 8.13650489e-02 -5.80252945e-01 -8.10374379e-01 8.13653320e-02 -5.83074987e-01 -8.08341444e-01 8.13651457e-02 -5.85902810e-01 -8.06298614e-01 8.13653320e-02 -5.88807464e-01 -8.04178596e-01 8.13652426e-02 -5.91624856e-01 -8.02107334e-01 8.13652575e-02 -5.94346941e-01 -8.00092399e-01 8.13650414e-02 -5.97050190e-01 -7.98076749e-01 8.13652053e-02 -5.99828959e-01 -7.95990944e-01 8.13651904e-02 -6.02680266e-01 -7.93836832e-01 8.13654065e-02 -6.05463803e-01 -7.91713774e-01 8.13650861e-02 -6.08222544e-01 -7.89596498e-01 8.13655332e-02 -6.10971212e-01 -7.87470877e-01 8.13650340e-02 -6.13644242e-01 -7.85390258e-01 8.13652277e-02 -6.16466403e-01 -7.83179641e-01 8.13654438e-02 -6.19199276e-01 -7.81016886e-01 8.13651159e-02 -6.21911407e-01 -7.78862178e-01 8.13654140e-02 -6.24654889e-01 -7.76662230e-01 8.13651234e-02 -6.27272666e-01 -7.74550557e-01 8.13651830e-02 -6.30038023e-01 -7.72301257e-01 8.13653097e-02 -6.32745564e-01 -7.70084381e-01 8.13650638e-02 -6.35350883e-01 -7.67936587e-01 8.13651830e-02 -6.38033986e-01 -7.65710056e-01 8.13652053e-02 -6.40738249e-01 -7.63446987e-01 8.13653320e-02 -6.43472493e-01 -7.61143386e-01 8.13652575e-02 -6.46088004e-01 -7.58923292e-01 8.13651159e-02 -6.48648441e-01 -7.56738126e-01 8.13651979e-02 -6.51293576e-01 -7.54464686e-01 8.13652128e-02 -6.53978944e-01 -7.52136767e-01 8.13653618e-02 -6.56665504e-01 -7.49790847e-01 8.13652053e-02 -6.59231722e-01 -7.47535765e-01 8.13650861e-02 -6.61758363e-01 -7.45301843e-01 8.13651830e-02 -6.64349020e-01 -7.42992580e-01 8.13652053e-02 -6.66942358e-01 -7.40665376e-01 8.13652053e-02 -6.69596434e-01 -7.38269746e-01 8.13654736e-02 -6.72186613e-01 -7.35907495e-01 8.13651159e-02 -6.74733102e-01 -7.33578742e-01 8.13653618e-02 -6.77288413e-01 -7.31215954e-01 8.13650861e-02 -6.79819405e-01 -7.28864908e-01 8.13655183e-02 -6.82431102e-01 -7.26418078e-01 8.13651979e-02 -6.84909940e-01 -7.24080682e-01 8.13651085e-02 -6.87419951e-01 -7.21703470e-01 8.13653842e-02 -6.89946592e-01 -7.19278753e-01 8.13650936e-02 -6.92396581e-01 -7.16935635e-01 8.13652053e-02 -6.94905341e-01 -7.14504004e-01 8.13653469e-02 -6.97401464e-01 -7.12062299e-01 8.13651606e-02 -6.99853599e-01 -7.09655643e-01 8.13652277e-02 -7.02321112e-01 -7.07216024e-01 8.13652202e-02 -7.04839230e-01 -7.04687297e-01 8.13653320e-02 -7.07314730e-01 -7.02220619e-01 8.13651457e-02 -7.09756494e-01 -6.99751019e-01 8.13653842e-02 -7.12206066e-01 -6.97254479e-01 8.13651159e-02 -7.14568675e-01 -6.94837630e-01 8.13652128e-02 -7.17023551e-01 -6.92306042e-01 8.13652351e-02 -7.19487131e-01 -6.89729512e-01 8.13652948e-02 -7.21868694e-01 -6.87246025e-01 8.13651010e-02 -7.24269748e-01 -6.84710562e-01 8.13652202e-02 -7.26640284e-01 -6.82193279e-01 8.13650712e-02 -7.28935897e-01 -6.79739892e-01 8.13651904e-02 -7.31351435e-01 -6.77144587e-01 8.13653097e-02 -7.33785450e-01 -6.74508989e-01 8.13652426e-02 -7.36092746e-01 -6.71983957e-01 8.13650340e-02 -7.38350868e-01 -6.69505060e-01 8.13652277e-02 -7.40684748e-01 -6.66921854e-01 8.13652053e-02 -7.43085206e-01 -6.64246082e-01 8.13654959e-02 -7.45413542e-01 -6.61632538e-01 8.13650489e-02 -7.47698724e-01 -6.59048855e-01 8.13653097e-02 -7.49994755e-01 -6.56431615e-01 8.13650489e-02 -7.52284229e-01 -6.53809190e-01 8.13653469e-02 -7.54626632e-01 -6.51104867e-01 8.13651979e-02 -7.56845474e-01 -6.48523927e-01 8.13651383e-02 -7.59044349e-01 -6.45945966e-01 8.13651904e-02 -7.61287630e-01 -6.43304944e-01 8.13652053e-02 -7.63568223e-01 -6.40593469e-01 8.13652724e-02 -7.65849531e-01 -6.37867272e-01 8.13652501e-02 -7.68052280e-01 -6.35208905e-01 8.13651457e-02 -7.70204425e-01 -6.32604122e-01 8.13652277e-02 -7.72420943e-01 -6.29890859e-01 8.13652053e-02 -7.74602294e-01 -6.27208710e-01 8.13651904e-02 -7.76833892e-01 -6.24443710e-01 8.13654661e-02 -7.79083073e-01 -6.21632397e-01 8.13652277e-02 -7.81241536e-01 -6.18917465e-01 8.13652426e-02 -7.83343256e-01 -6.16255283e-01 8.13650712e-02 -7.85416424e-01 -6.13612056e-01 8.13651979e-02 -7.87620723e-01 -6.10780537e-01 8.13655108e-02 -7.89794564e-01 -6.07965648e-01 8.13651681e-02 -7.91906595e-01 -6.05212271e-01 8.13653097e-02 -7.93995082e-01 -6.02468073e-01 8.13650936e-02 -7.96025336e-01 -5.99787116e-01 8.13652053e-02 -7.98160672e-01 -5.96938968e-01 8.13653618e-02 -8.00252318e-01 -5.94131768e-01 8.13651383e-02 -8.02271307e-01 -5.91402471e-01 8.13652575e-02 -8.04328918e-01 -5.88600338e-01 8.13651532e-02 -8.06400955e-01 -5.85760772e-01 8.13652575e-02 -8.08483005e-01 -5.82881272e-01 8.13652575e-02 -8.10500741e-01 -5.80075204e-01 8.13651159e-02 -8.12461972e-01 -5.77324033e-01 8.13652351e-02 -8.14476788e-01 -5.74482679e-01 8.13651979e-02 -8.16487312e-01 -5.71616530e-01 8.13652351e-02 -8.18518341e-01 -5.68704426e-01 8.13652575e-02 -8.20492506e-01 -5.65855026e-01 8.13651383e-02 -8.22412968e-01 -5.63059449e-01 8.13651681e-02 -8.24365675e-01 -5.60195863e-01 8.13651830e-02 -8.26300502e-01 -5.57339072e-01 8.13651830e-02 -8.28292727e-01 -5.54373026e-01 8.13654959e-02 -8.30241382e-01 -5.51445782e-01 8.13650638e-02 -8.32155585e-01 -5.48557341e-01 8.13654736e-02 -8.34082782e-01 -5.45618713e-01 8.13650489e-02 -8.35910320e-01 -5.42816997e-01 8.13651830e-02 -8.37795019e-01 -5.39905071e-01 8.13652053e-02 -8.39723825e-01 -5.36898732e-01 8.13653395e-02 -8.41628432e-01 -5.33907235e-01 8.13651383e-02 -8.43434691e-01 -5.31054735e-01 8.13651681e-02 -8.45245838e-01 -5.28160453e-01 8.13651830e-02 -8.47101271e-01 -5.25186062e-01 8.13652202e-02 -8.48936141e-01 -5.22209883e-01 8.13652053e-02 -8.50752950e-01 -5.19250274e-01 8.13651904e-02 -8.52559209e-01 -5.16275465e-01 8.13652351e-02 -8.54402840e-01 -5.13221622e-01 8.13654959e-02 -8.56242537e-01 -5.10141015e-01 8.13652202e-02 -8.57973039e-01 -5.07225752e-01 8.13651383e-02 -8.59736860e-01 -5.04233360e-01 8.13654959e-02 -8.61492753e-01 -5.01224220e-01 8.13651159e-02 -8.63207161e-01 -4.98271734e-01 8.13653097e-02 -8.64932537e-01 -4.95267510e-01 8.13651681e-02 -8.66631687e-01 -4.92285788e-01 8.13651979e-02 -8.68346274e-01 -4.89262581e-01 8.13652202e-02 -8.70047629e-01 -4.86223161e-01 8.13652053e-02 -8.71737242e-01 -4.83185321e-01 8.13652351e-02 -8.73459578e-01 -4.80071068e-01 8.13653544e-02 -8.75151157e-01 -4.76983666e-01 8.13651979e-02 -8.76784861e-01 -4.73966897e-01 8.13651532e-02 -8.78407001e-01 -4.70955282e-01 8.13651681e-02 -8.80074978e-01 -4.67830688e-01 8.13653097e-02 -8.81741941e-01 -4.64680463e-01 8.13652053e-02 -8.83355618e-01 -4.61609662e-01 8.13651532e-02 -8.84920180e-01 -4.58597481e-01 8.13651234e-02 -8.86478603e-01 -4.55582350e-01 8.13651979e-02 -8.88098478e-01 -4.52415854e-01 8.13654065e-02 -8.89722764e-01 -4.49213415e-01 8.13652501e-02 -8.91242802e-01 -4.46185946e-01 8.13650712e-02 -8.92744303e-01 -4.43176210e-01 8.13651830e-02 -8.94275427e-01 -4.40078646e-01 8.13651979e-02 -8.95818293e-01 -4.36931819e-01 8.13652053e-02 -8.97382319e-01 -4.33711618e-01 8.13655108e-02 -8.98931682e-01 -4.30485189e-01 8.13652277e-02 -9.00404871e-01 -4.27395701e-01 8.13651159e-02 -9.01845753e-01 -4.24346030e-01 8.13652128e-02 -9.03312445e-01 -4.21216995e-01 8.13651830e-02 -9.04818773e-01 -4.17975903e-01 8.13655183e-02 -9.06300485e-01 -4.14748788e-01 8.13651457e-02 -9.07696605e-01 -4.11686361e-01 8.13651457e-02 -9.09102261e-01 -4.08570796e-01 8.13652128e-02 -9.10523355e-01 -4.05399919e-01 8.13652351e-02 -9.11985874e-01 -4.02097911e-01 8.13655257e-02 -9.13424790e-01 -3.98818493e-01 8.13651904e-02 -9.14805949e-01 -3.95638615e-01 8.13652128e-02 -9.16181743e-01 -3.92428517e-01 8.13652053e-02 -9.17508602e-01 -3.89325172e-01 8.13651159e-02 -9.18827951e-01 -3.86202633e-01 8.13652501e-02 -9.20175195e-01 -3.82980078e-01 8.13651979e-02 -9.21540320e-01 -3.79682869e-01 8.13653618e-02 -9.22863483e-01 -3.76457393e-01 8.13651085e-02 -9.24134672e-01 -3.73325825e-01 8.13652202e-02 -9.25465405e-01 -3.70014042e-01 8.13654140e-02 -9.26753581e-01 -3.66777897e-01 8.13651457e-02 -9.27998722e-01 -3.63619685e-01 8.13652351e-02 -9.29255247e-01 -3.60379875e-01 8.13652501e-02 -9.30521607e-01 -3.57119620e-01 8.13652650e-02 -9.31794107e-01 -3.53770286e-01 8.13653544e-02 -9.33006048e-01 -3.50542545e-01 8.13651159e-02 -9.34193134e-01 -3.47368151e-01 8.13652277e-02 -9.35434878e-01 -3.44024450e-01 8.13654214e-02 -9.36672747e-01 -3.40654075e-01 8.13652202e-02 -9.37847793e-01 -3.37396204e-01 8.13651979e-02 -9.38992918e-01 -3.34203005e-01 8.13651159e-02 -9.40144956e-01 -3.30946833e-01 8.13653842e-02 -9.41304326e-01 -3.27629983e-01 8.13651159e-02 -9.42409873e-01 -3.24443191e-01 8.13651904e-02 -9.43532407e-01 -3.21156532e-01 8.13652128e-02 -9.44648921e-01 -3.17863107e-01 8.13652202e-02 -9.45786953e-01 -3.14461648e-01 8.13654959e-02 -9.46879923e-01 -3.11151326e-01 8.13650936e-02 -9.47929025e-01 -3.07944834e-01 8.13652053e-02 -9.49021637e-01 -3.04559141e-01 8.13653618e-02 -9.50080335e-01 -3.01236212e-01 8.13651234e-02 -9.51119244e-01 -2.97948807e-01 8.13653618e-02 -9.52158809e-01 -2.94602573e-01 8.13651383e-02 -9.53183293e-01 -2.91273057e-01 8.13653767e-02 -9.54214692e-01 -2.87871689e-01 8.13652053e-02 -9.55193579e-01 -2.84606546e-01 8.13650638e-02 -9.56178308e-01 -2.81286508e-01 8.13652650e-02 -9.57155883e-01 -2.77941048e-01 8.13651159e-02 -9.58117306e-01 -2.74605453e-01 8.13653842e-02 -9.59070265e-01 -2.71257669e-01 8.13651085e-02 -9.59990978e-01 -2.67987072e-01 8.13651830e-02 -9.60919082e-01 -2.64636397e-01 8.13651830e-02 -9.61838007e-01 -2.61282504e-01 8.13651755e-02 -9.62765753e-01 -2.57837772e-01 8.13653618e-02 -9.63685274e-01 -2.54381001e-01 8.13651755e-02 -9.64565456e-01 -2.51019061e-01 8.13651830e-02 -9.65414703e-01 -2.47738495e-01 8.13650489e-02 -9.66241479e-01 -2.44482249e-01 8.13651830e-02 -9.67115462e-01 -2.41005585e-01 8.13653618e-02 -9.67977345e-01 -2.37529263e-01 8.13651904e-02 -9.68801916e-01 -2.34150723e-01 8.13651979e-02 -9.69587743e-01 -2.30868533e-01 8.13650638e-02 -9.70366776e-01 -2.27572694e-01 8.13651830e-02 -9.71171021e-01 -2.24106848e-01 8.13653842e-02 -9.71975386e-01 -2.20591262e-01 8.13651681e-02 -9.72720563e-01 -2.17285618e-01 8.13650936e-02 -9.73469436e-01 -2.13905618e-01 8.13653842e-02 -9.74212527e-01 -2.10489497e-01 8.13650712e-02 -9.74915743e-01 -2.07211331e-01 8.13652128e-02 -9.75658894e-01 -2.03695744e-01 8.13653395e-02 -9.76383209e-01 -2.00187534e-01 8.13652053e-02 -9.77060914e-01 -1.96848452e-01 8.13650638e-02 -9.77718294e-01 -1.93556070e-01 8.13651830e-02 -9.78389382e-01 -1.90139219e-01 8.13651755e-02 -9.79062498e-01 -1.86637655e-01 8.13652873e-02 -9.79731083e-01 -1.83104664e-01 8.13651755e-02 -9.80343938e-01 -1.79772720e-01 8.13650563e-02 -9.80952561e-01 -1.76458284e-01 8.13651830e-02 -9.81562912e-01 -1.73029363e-01 8.13651904e-02 -9.82169867e-01 -1.69519290e-01 8.13653842e-02 -9.82773900e-01 -1.65987864e-01 8.13651606e-02 -9.83331323e-01 -1.62658215e-01 8.13650936e-02 -9.83893812e-01 -1.59223750e-01 8.13652873e-02 -9.84443426e-01 -1.55783847e-01 8.13650489e-02 -9.84976530e-01 -1.52373388e-01 8.13652501e-02 -9.85504508e-01 -1.48915753e-01 8.13651159e-02 -9.86016035e-01 -1.45500436e-01 8.13652873e-02 -9.86519337e-01 -1.42042041e-01 8.13651085e-02 -9.86996889e-01 -1.38691619e-01 8.13651755e-02 -9.87485409e-01 -1.35181263e-01 8.13652575e-02 -9.87953961e-01 -1.31688222e-01 8.13650787e-02 -9.88404691e-01 -1.28268301e-01 8.13652575e-02 -9.88848209e-01 -1.24814406e-01 8.13651159e-02 -9.89265501e-01 -1.21451467e-01 8.13651532e-02 -9.89695191e-01 -1.17899552e-01 8.13653097e-02 -9.90098357e-01 -1.14452563e-01 8.13650712e-02 -9.90481138e-01 -1.11099884e-01 8.13651606e-02 -9.90876555e-01 -1.07512884e-01 8.13652724e-02 -9.91254807e-01 -1.03969194e-01 8.13651159e-02 -9.91606474e-01 -1.00556433e-01 8.13651159e-02 -9.91943002e-01 -9.71709490e-02 8.13649073e-02 -9.92276192e-01 -9.37409550e-02 8.13651159e-02 -9.92596388e-01 -9.02494565e-02 8.13645571e-02 -9.92893040e-01 -8.69141817e-02 8.13644677e-02 -9.93191183e-01 -8.34295824e-02 8.13643113e-02 -9.93480146e-01 -7.99087659e-02 8.13641399e-02 -9.93757963e-01 -7.63611123e-02 8.13642442e-02 -9.94020998e-01 -7.28489012e-02 8.13639984e-02 -9.94255006e-01 -6.95665181e-02 8.13639984e-02 -9.94497597e-01 -6.59933612e-02 8.13639984e-02 -9.94724214e-01 -6.24222569e-02 8.13640207e-02 -9.94931221e-01 -5.90577461e-02 8.13641623e-02 -9.95095730e-01 -5.62603697e-02 8.13644454e-02 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. 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. 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. -9.91631746e-01 4.25875485e-02 1.21869333e-01 -9.91504610e-01 4.55656834e-02 1.21868946e-01 -9.91357088e-01 4.86655645e-02 1.21869788e-01 -9.91183341e-01 5.20694926e-02 1.21870235e-01 -9.90989149e-01 5.56620508e-02 1.21870197e-01 -9.90791321e-01 5.90882860e-02 1.21870413e-01 -9.90577221e-01 6.25463724e-02 1.21870510e-01 -9.90355372e-01 6.59920648e-02 1.21870615e-01 -9.90122080e-01 6.93835169e-02 1.21870533e-01 -9.89883006e-01 7.27365240e-02 1.21870615e-01 -9.89618242e-01 7.62586519e-02 1.21870682e-01 -9.89338398e-01 7.98033178e-02 1.21870622e-01 -9.89060521e-01 8.31783488e-02 1.21870548e-01 -9.88766134e-01 8.66106376e-02 1.21870689e-01 -9.88448501e-01 9.01602507e-02 1.21870615e-01 -9.88135457e-01 9.35362279e-02 1.21870600e-01 -9.87799942e-01 9.70126092e-02 1.21870637e-01 -9.87462997e-01 1.00394465e-01 1.21870562e-01 -9.87114847e-01 1.03757866e-01 1.21870607e-01 -9.86735463e-01 1.07291326e-01 1.21870704e-01 -9.86344755e-01 1.10840455e-01 1.21870629e-01 -9.85949636e-01 1.14288881e-01 1.21870637e-01 -9.85542715e-01 1.17738977e-01 1.21870629e-01 -9.85128999e-01 1.21161304e-01 1.21870615e-01 -9.84704614e-01 1.24576680e-01 1.21870622e-01 -9.84260082e-01 1.28033623e-01 1.21870644e-01 -9.83799279e-01 1.31518945e-01 1.21870644e-01 -9.83350456e-01 1.34842113e-01 1.21870503e-01 -9.82894242e-01 1.38131335e-01 1.21870622e-01 -9.82390344e-01 1.41662329e-01 1.21870704e-01 -9.81869459e-01 1.45224243e-01 1.21870600e-01 -9.81358707e-01 1.48632094e-01 1.21870637e-01 -9.80835140e-01 1.52060762e-01 1.21870629e-01 -9.80299056e-01 1.55482590e-01 1.21870622e-01 -9.79764283e-01 1.58812121e-01 1.21870525e-01 -9.79205489e-01 1.62229180e-01 1.21870697e-01 -9.78614569e-01 1.65754169e-01 1.21870644e-01 -9.78042424e-01 1.69094965e-01 1.21870577e-01 -9.77450609e-01 1.72500089e-01 1.21870704e-01 -9.76824045e-01 1.76014930e-01 1.21870637e-01 -9.76197064e-01 1.79432184e-01 1.21870637e-01 -9.75568891e-01 1.82827786e-01 1.21870637e-01 -9.74941909e-01 1.86135575e-01 1.21870548e-01 -9.74309325e-01 1.89416140e-01 1.21870652e-01 -9.73619521e-01 1.92936942e-01 1.21870711e-01 -9.72920597e-01 1.96434125e-01 1.21870629e-01 -9.72223163e-01 1.99856326e-01 1.21870644e-01 -9.71539855e-01 2.03149810e-01 1.21870562e-01 -9.70828950e-01 2.06529379e-01 1.21870726e-01 -9.70079243e-01 2.10020334e-01 1.21870644e-01 -9.69357073e-01 2.13316098e-01 1.21870562e-01 -9.68614280e-01 2.16679096e-01 1.21870719e-01 -9.67846930e-01 2.20073313e-01 1.21870555e-01 -9.67097342e-01 2.23341540e-01 1.21870622e-01 -9.66290653e-01 2.26822004e-01 1.21870711e-01 -9.65467811e-01 2.30291262e-01 1.21870629e-01 -9.64669466e-01 2.33619884e-01 1.21870607e-01 -9.63847041e-01 2.36981422e-01 1.21870629e-01 -9.63003159e-01 2.40379959e-01 1.21870622e-01 -9.62179780e-01 2.43657455e-01 1.21870540e-01 -9.61330831e-01 2.46988252e-01 1.21870682e-01 -9.60437000e-01 2.50445783e-01 1.21870592e-01 -9.59579289e-01 2.53714919e-01 1.21870540e-01 -9.58689630e-01 2.57051528e-01 1.21870689e-01 -9.57770348e-01 2.60459632e-01 1.21870607e-01 -9.56847191e-01 2.63820648e-01 1.21870615e-01 -9.55921829e-01 2.67166585e-01 1.21870629e-01 -9.55002189e-01 2.70430863e-01 1.21870548e-01 -9.54061270e-01 2.73726910e-01 1.21870667e-01 -9.53095078e-01 2.77072728e-01 1.21870562e-01 -9.52126741e-01 2.80383646e-01 1.21870689e-01 -9.51111197e-01 2.83814281e-01 1.21870629e-01 -9.50142741e-01 2.87032425e-01 1.21870548e-01 -9.49136436e-01 2.90344477e-01 1.21870711e-01 -9.48087096e-01 2.93754250e-01 1.21870607e-01 -9.47062910e-01 2.97040015e-01 1.21870600e-01 -9.46023285e-01 3.00332576e-01 1.21870607e-01 -9.44988728e-01 3.03577363e-01 1.21870562e-01 -9.43951786e-01 3.06778461e-01 1.21870592e-01 -9.42850947e-01 3.10147166e-01 1.21870667e-01 -9.41731811e-01 3.13528806e-01 1.21870607e-01 -9.40623999e-01 3.16839725e-01 1.21870600e-01 -9.39515829e-01 3.20109874e-01 1.21870622e-01 -9.38398004e-01 3.23377073e-01 1.21870592e-01 -9.37285423e-01 3.26581448e-01 1.21870585e-01 -9.36138093e-01 3.29854876e-01 1.21870667e-01 -9.34961915e-01 3.33181083e-01 1.21870637e-01 -9.33812261e-01 3.36382985e-01 1.21870562e-01 -9.32674706e-01 3.39530021e-01 1.21870615e-01 -9.31453228e-01 3.42850715e-01 1.21870674e-01 -9.30213809e-01 3.46187234e-01 1.21870629e-01 -9.28994417e-01 3.49449843e-01 1.21870629e-01 -9.27785039e-01 3.52658749e-01 1.21870585e-01 -9.26591337e-01 3.55809271e-01 1.21870577e-01 -9.25348580e-01 3.59007001e-01 1.21870622e-01 -9.24062610e-01 3.62310946e-01 1.21870667e-01 -9.22765851e-01 3.65601838e-01 1.21870607e-01 -9.21514511e-01 3.68741959e-01 1.21870548e-01 -9.20228779e-01 3.71938527e-01 1.21870711e-01 -9.18888688e-01 3.75240654e-01 1.21870637e-01 -9.17580545e-01 3.78421187e-01 1.21870607e-01 -9.16265488e-01 3.81597906e-01 1.21870592e-01 -9.14956152e-01 3.84726882e-01 1.21870570e-01 -9.13636267e-01 3.87849241e-01 1.21870629e-01 -9.12236929e-01 3.91122788e-01 1.21870697e-01 -9.10826862e-01 3.94403160e-01 1.21870607e-01 -9.09455895e-01 3.97557557e-01 1.21870600e-01 -9.08061862e-01 4.00729358e-01 1.21870607e-01 -9.06653643e-01 4.03906405e-01 1.21870629e-01 -9.05243754e-01 4.07055408e-01 1.21870615e-01 -9.03850019e-01 4.10139859e-01 1.21870525e-01 -9.02415514e-01 4.13283199e-01 1.21870659e-01 -9.00938869e-01 4.16493624e-01 1.21870622e-01 -8.99506569e-01 4.19581085e-01 1.21870555e-01 -8.98052931e-01 4.22682673e-01 1.21870667e-01 -8.96533668e-01 4.25896913e-01 1.21870629e-01 -8.95036399e-01 4.29031104e-01 1.21870615e-01 -8.93538177e-01 4.32151705e-01 1.21870629e-01 -8.92051876e-01 4.35211271e-01 1.21870548e-01 -8.90577614e-01 4.38213229e-01 1.21870615e-01 -8.89009535e-01 4.41386878e-01 1.21870659e-01 -8.87419283e-01 4.44573134e-01 1.21870622e-01 -8.85863602e-01 4.47669506e-01 1.21870629e-01 -8.84297788e-01 4.50753570e-01 1.21870615e-01 -8.82726252e-01 4.53823984e-01 1.21870607e-01 -8.81140709e-01 4.56890702e-01 1.21870592e-01 -8.79536808e-01 4.59972650e-01 1.21870622e-01 -8.77921402e-01 4.63053644e-01 1.21870607e-01 -8.76338303e-01 4.66040462e-01 1.21870540e-01 -8.74756277e-01 4.69003439e-01 1.21870615e-01 -8.73074830e-01 4.72125113e-01 1.21870682e-01 -8.71377289e-01 4.75254387e-01 1.21870600e-01 -8.69712234e-01 4.78292584e-01 1.21870637e-01 -8.68027449e-01 4.81334060e-01 1.21870615e-01 -8.66351604e-01 4.84347910e-01 1.21870600e-01 -8.64666283e-01 4.87354368e-01 1.21870607e-01 -8.62952352e-01 4.90382910e-01 1.21870652e-01 -8.61231804e-01 4.93397832e-01 1.21870622e-01 -8.59539390e-01 4.96340275e-01 1.21870533e-01 -8.57806325e-01 4.99329984e-01 1.21870674e-01 -8.56071472e-01 5.02298057e-01 1.21870540e-01 -8.54296505e-01 5.05310118e-01 1.21870697e-01 -8.52480888e-01 5.08367777e-01 1.21870615e-01 -8.50705326e-01 5.11332214e-01 1.21870629e-01 -8.48914087e-01 5.14298260e-01 1.21870615e-01 -8.47112536e-01 5.17265320e-01 1.21870637e-01 -8.45296085e-01 5.20225883e-01 1.21870637e-01 -8.43479812e-01 5.23169518e-01 1.21870629e-01 -8.41697454e-01 5.26030004e-01 1.21870533e-01 -8.39868486e-01 5.28944075e-01 1.21870697e-01 -8.37974429e-01 5.31937778e-01 1.21870592e-01 -8.36104155e-01 5.34873903e-01 1.21870667e-01 -8.34212244e-01 5.37819803e-01 1.21870622e-01 -8.32341194e-01 5.40711522e-01 1.21870607e-01 -8.30505431e-01 5.43523073e-01 1.21870570e-01 -8.28599036e-01 5.46428144e-01 1.21870689e-01 -8.26620102e-01 5.49413800e-01 1.21870659e-01 -8.24690104e-01 5.52310109e-01 1.21870622e-01 -8.22790086e-01 5.55139959e-01 1.21870562e-01 -8.20912659e-01 5.57908416e-01 1.21870600e-01 -8.18938434e-01 5.60804784e-01 1.21870644e-01 -8.16924393e-01 5.63734472e-01 1.21870637e-01 -8.14923465e-01 5.66622615e-01 1.21870592e-01 -8.12999129e-01 5.69376886e-01 1.21870480e-01 -8.11016023e-01 5.72203517e-01 1.21870689e-01 -8.08929861e-01 5.75142920e-01 1.21870600e-01 -8.06925893e-01 5.77955425e-01 1.21870592e-01 -8.04899096e-01 5.80769479e-01 1.21870585e-01 -8.02861035e-01 5.83587885e-01 1.21870562e-01 -8.00834239e-01 5.86364508e-01 1.21870600e-01 -7.98853219e-01 5.89059949e-01 1.21870510e-01 -7.96792805e-01 5.91842890e-01 1.21870697e-01 -7.94647574e-01 5.94720721e-01 1.21870592e-01 -7.92629719e-01 5.97409070e-01 1.21870510e-01 -7.90552318e-01 6.00158274e-01 1.21870704e-01 -7.88386583e-01 6.02999389e-01 1.21870615e-01 -7.86285937e-01 6.05734825e-01 1.21870607e-01 -7.84124851e-01 6.08527601e-01 1.21870607e-01 -7.82038569e-01 6.11208081e-01 1.21870585e-01 -7.79974461e-01 6.13840222e-01 1.21870592e-01 -7.77788162e-01 6.16606832e-01 1.21870697e-01 -7.75548279e-01 6.19424820e-01 1.21870615e-01 -7.73369074e-01 6.22142494e-01 1.21870607e-01 -7.71195590e-01 6.24836028e-01 1.21870570e-01 -7.69088924e-01 6.27423584e-01 1.21870488e-01 -7.66901970e-01 6.30096972e-01 1.21870644e-01 -7.64647424e-01 6.32830679e-01 1.21870555e-01 -7.62429714e-01 6.35500491e-01 1.21870592e-01 -7.60268807e-01 6.38085365e-01 1.21870488e-01 -7.58024454e-01 6.40749216e-01 1.21870682e-01 -7.55712092e-01 6.43472850e-01 1.21870592e-01 -7.53460348e-01 6.46110654e-01 1.21870592e-01 -7.51197994e-01 6.48741424e-01 1.21870600e-01 -7.48937607e-01 6.51346743e-01 1.21870548e-01 -7.46716619e-01 6.53892279e-01 1.21870503e-01 -7.44489908e-01 6.56425118e-01 1.21870577e-01 -7.42138982e-01 6.59082592e-01 1.21870652e-01 -7.39762783e-01 6.61750317e-01 1.21870592e-01 -7.37491190e-01 6.64277613e-01 1.21870480e-01 -7.35187471e-01 6.66831017e-01 1.21870644e-01 -7.32791603e-01 6.69458568e-01 1.21870592e-01 -7.30453968e-01 6.72011912e-01 1.21870585e-01 -7.28105426e-01 6.74555302e-01 1.21870577e-01 -7.25794375e-01 6.77039206e-01 1.21870518e-01 -7.23514557e-01 6.79476142e-01 1.21870577e-01 -7.21059084e-01 6.82079136e-01 1.21870644e-01 -7.18626201e-01 6.84644878e-01 1.21870577e-01 -7.16206849e-01 6.87169313e-01 1.21870592e-01 -7.13822842e-01 6.89657867e-01 1.21870592e-01 -7.11477101e-01 6.92075253e-01 1.21870510e-01 -7.09062517e-01 6.94547057e-01 1.21870644e-01 -7.06571996e-01 6.97082400e-01 1.21870607e-01 -7.04111338e-01 6.99569523e-01 1.21870577e-01 -7.01675653e-01 7.01994479e-01 1.21870585e-01 -6.99295163e-01 7.04383969e-01 1.21870510e-01 -6.96824968e-01 7.06827104e-01 1.21870667e-01 -6.94284439e-01 7.09319890e-01 1.21870585e-01 -6.91805422e-01 7.11739838e-01 1.21870570e-01 -6.89323068e-01 7.14145839e-01 1.21870555e-01 -6.86855793e-01 7.16507137e-01 1.21870518e-01 -6.84404373e-01 7.18856692e-01 1.21870570e-01 -6.81837559e-01 7.21287966e-01 1.21870644e-01 -6.79278433e-01 7.23698318e-01 1.21870570e-01 -6.76775873e-01 7.26036131e-01 1.21870510e-01 -6.74267650e-01 7.28371263e-01 1.21870659e-01 -6.71654582e-01 7.30782986e-01 1.21870592e-01 -6.69163108e-01 7.33062208e-01 1.21870518e-01 -6.66594028e-01 7.35400081e-01 1.21870644e-01 -6.64035380e-01 7.37711489e-01 1.21870488e-01 -6.61517799e-01 7.39969134e-01 1.21870570e-01 -6.58876717e-01 7.42323458e-01 1.21870652e-01 -6.56266272e-01 7.44630933e-01 1.21870510e-01 -6.53658867e-01 7.46918857e-01 1.21870667e-01 -6.51049256e-01 7.49197364e-01 1.21870480e-01 -6.48465037e-01 7.51434028e-01 1.21870689e-01 -6.45724595e-01 7.53791273e-01 1.21870585e-01 -6.43080115e-01 7.56047010e-01 1.21870585e-01 -6.40458345e-01 7.58270204e-01 1.21870570e-01 -6.37879610e-01 7.60440886e-01 1.21870495e-01 -6.35247231e-01 7.62642086e-01 1.21870659e-01 -6.32562697e-01 7.64868200e-01 1.21870525e-01 -6.29885972e-01 7.67077029e-01 1.21870674e-01 -6.27127171e-01 7.69331634e-01 1.21870622e-01 -6.24430060e-01 7.71522939e-01 1.21870622e-01 -6.21805787e-01 7.73638070e-01 1.21870495e-01 -6.19188309e-01 7.75737047e-01 1.21870615e-01 -6.16392314e-01 7.77958155e-01 1.21870629e-01 -6.13678873e-01 7.80102551e-01 1.21870473e-01 -6.10972524e-01 7.82223642e-01 1.21870629e-01 -6.08235896e-01 7.84354448e-01 1.21870458e-01 -6.05524719e-01 7.86447585e-01 1.21870577e-01 -6.02710247e-01 7.88606644e-01 1.21870600e-01 -5.99900067e-01 7.90747702e-01 1.21870548e-01 -5.97205937e-01 7.92783797e-01 1.21870480e-01 -5.94456673e-01 7.94845700e-01 1.21870615e-01 -5.91599703e-01 7.96976328e-01 1.21870548e-01 -5.88828146e-01 7.99025357e-01 1.21870548e-01 -5.86034656e-01 8.01075220e-01 1.21870585e-01 -5.83291531e-01 8.03077340e-01 1.21870510e-01 -5.80515087e-01 8.05083275e-01 1.21870644e-01 -5.77594161e-01 8.07185054e-01 1.21870570e-01 -5.74792206e-01 8.09181631e-01 1.21870577e-01 -5.71940660e-01 8.11201453e-01 1.21870570e-01 -5.69176733e-01 8.13140512e-01 1.21870495e-01 -5.66358685e-01 8.15105021e-01 1.21870644e-01 -5.63496113e-01 8.17089379e-01 1.21870510e-01 -5.60663581e-01 8.19034696e-01 1.21870659e-01 -5.57682037e-01 8.21066499e-01 1.21870562e-01 -5.54825425e-01 8.22999895e-01 1.21870555e-01 -5.52038670e-01 8.24871123e-01 1.21870480e-01 -5.49132347e-01 8.26808214e-01 1.21870644e-01 -5.46149015e-01 8.28783393e-01 1.21870585e-01 -5.43338716e-01 8.30627382e-01 1.21870495e-01 -5.40468276e-01 8.32497358e-01 1.21870644e-01 -5.37526846e-01 8.34400237e-01 1.21870458e-01 -5.34623325e-01 8.36263120e-01 1.21870667e-01 -5.31615019e-01 8.38179708e-01 1.21870548e-01 -5.28681397e-01 8.40033352e-01 1.21870592e-01 -5.25827885e-01 8.41821671e-01 1.21870525e-01 -5.22900641e-01 8.43647242e-01 1.21870667e-01 -5.19876897e-01 8.45509470e-01 1.21870503e-01 -5.16966403e-01 8.47294569e-01 1.21870503e-01 -5.14009953e-01 8.49089146e-01 1.21870659e-01 -5.11041105e-01 8.50880682e-01 1.21870495e-01 -5.08108616e-01 8.52635086e-01 1.21870600e-01 -5.05114615e-01 8.54410648e-01 1.21870503e-01 -5.02206504e-01 8.56125116e-01 1.21870555e-01 -4.99154776e-01 8.57907474e-01 1.21870607e-01 -4.96089339e-01 8.59683871e-01 1.21870525e-01 -4.93079245e-01 8.61413419e-01 1.21870570e-01 -4.90071982e-01 8.63127410e-01 1.21870548e-01 -4.87072259e-01 8.64826441e-01 1.21870548e-01 -4.84041214e-01 8.66523504e-01 1.21870570e-01 -4.80992675e-01 8.68218124e-01 1.21870548e-01 -4.78018761e-01 8.69861484e-01 1.21870473e-01 -4.75005269e-01 8.71512115e-01 1.21870615e-01 -4.71876204e-01 8.73207092e-01 1.21870585e-01 -4.68830556e-01 8.74847651e-01 1.21870548e-01 -4.65785027e-01 8.76473844e-01 1.21870570e-01 -4.62788194e-01 8.78060222e-01 1.21870510e-01 -4.59713399e-01 8.79672527e-01 1.21870644e-01 -4.56563532e-01 8.81310582e-01 1.21870600e-01 -4.53482330e-01 8.82901669e-01 1.21870577e-01 -4.50505406e-01 8.84423137e-01 1.21870503e-01 -4.47430342e-01 8.85983288e-01 1.21870652e-01 -4.44244921e-01 8.87585282e-01 1.21870600e-01 -4.41160738e-01 8.89121056e-01 1.21870577e-01 -4.38044906e-01 8.90661418e-01 1.21870562e-01 -4.34999794e-01 8.92153442e-01 1.21870488e-01 -4.31903780e-01 8.93657088e-01 1.21870644e-01 -4.28746074e-01 8.95173192e-01 1.21870525e-01 -4.25649017e-01 8.96650016e-01 1.21870637e-01 -4.22418505e-01 8.98177624e-01 1.21870577e-01 -4.19359893e-01 8.99610817e-01 1.21870503e-01 -4.16220188e-01 9.01066601e-01 1.21870629e-01 -4.13067728e-01 9.02514994e-01 1.21870518e-01 -4.09916699e-01 9.03952003e-01 1.21870667e-01 -4.06688184e-01 9.05409694e-01 1.21870585e-01 -4.03507471e-01 9.06831682e-01 1.21870555e-01 -4.00435239e-01 9.08192039e-01 1.21870495e-01 -3.97300810e-01 9.09568191e-01 1.21870622e-01 -3.94051075e-01 9.10980046e-01 1.21870615e-01 -3.90815973e-01 9.12368357e-01 1.21870562e-01 -3.87731582e-01 9.13687527e-01 1.21870510e-01 -3.84635180e-01 9.14994657e-01 1.21870570e-01 -3.81359130e-01 9.16365147e-01 1.21870674e-01 -3.78103316e-01 9.17711496e-01 1.21870510e-01 -3.74910653e-01 9.19021904e-01 1.21870607e-01 -3.71748775e-01 9.20306504e-01 1.21870540e-01 -3.68534237e-01 9.21597064e-01 1.21870644e-01 -3.65257740e-01 9.22901928e-01 1.21870555e-01 -3.62031102e-01 9.24173057e-01 1.21870592e-01 -3.58801723e-01 9.25425351e-01 1.21870592e-01 -3.55632752e-01 9.26658690e-01 1.21870555e-01 -3.52387697e-01 9.27889049e-01 1.21870689e-01 -3.49153697e-01 9.29104030e-01 1.21870518e-01 -3.45918447e-01 9.30313468e-01 1.21870644e-01 -3.42584670e-01 9.31548715e-01 1.21870518e-01 -3.39391619e-01 9.32727337e-01 1.21870466e-01 -3.36147755e-01 9.33896840e-01 1.21870637e-01 -3.32852244e-01 9.35079634e-01 1.21870525e-01 -3.29613328e-01 9.36224341e-01 1.21870555e-01 -3.26270282e-01 9.37393308e-01 1.21870525e-01 -3.23023647e-01 9.38520193e-01 1.21870540e-01 -3.19796115e-01 9.39622343e-01 1.21870443e-01 -3.16517293e-01 9.40732718e-01 1.21870644e-01 -3.13176960e-01 9.41849232e-01 1.21870570e-01 -3.09882373e-01 9.42937672e-01 1.21870540e-01 -3.06635350e-01 9.43999290e-01 1.21870480e-01 -3.03356886e-01 9.45059240e-01 1.21870667e-01 -3.00023705e-01 9.46121156e-01 1.21870555e-01 -2.96716630e-01 9.47163641e-01 1.21870548e-01 -2.93386012e-01 9.48201597e-01 1.21870570e-01 -2.90157616e-01 9.49194074e-01 1.21870495e-01 -2.86838919e-01 9.50199962e-01 1.21870667e-01 -2.83398300e-01 9.51233685e-01 1.21870577e-01 -2.80103087e-01 9.52210248e-01 1.21870600e-01 -2.76760638e-01 9.53186333e-01 1.21870615e-01 -2.73541689e-01 9.54115987e-01 1.21870480e-01 -2.70220190e-01 9.55061972e-01 1.21870659e-01 -2.66863585e-01 9.56005931e-01 1.21870488e-01 -2.63665706e-01 9.56890643e-01 1.21870600e-01 -2.60184139e-01 9.57845032e-01 1.21870674e-01 -2.56737828e-01 9.58772779e-01 1.21870555e-01 -2.53369898e-01 9.59669352e-01 1.21870577e-01 -2.50046641e-01 9.60540473e-01 1.21870570e-01 -2.46784836e-01 9.61383879e-01 1.21870488e-01 -2.43410453e-01 9.62240338e-01 1.21870674e-01 -2.39952922e-01 9.63110149e-01 1.21870585e-01 -2.36574262e-01 9.63947058e-01 1.21870555e-01 -2.33207643e-01 9.64768827e-01 1.21870562e-01 -2.29925513e-01 9.65555906e-01 1.21870473e-01 -2.26567522e-01 9.66348767e-01 1.21870652e-01 -2.23193944e-01 9.67132986e-01 1.21870495e-01 -2.19806209e-01 9.67906535e-01 1.21870644e-01 -2.16343969e-01 9.68688905e-01 1.21870533e-01 -2.12961420e-01 9.69434798e-01 1.21870540e-01 -2.09581226e-01 9.70172584e-01 1.21870570e-01 -2.06289992e-01 9.70878363e-01 1.21870495e-01 -2.02908263e-01 9.71591949e-01 1.21870652e-01 -1.99378461e-01 9.72322822e-01 1.21870548e-01 -1.96014255e-01 9.73004043e-01 1.21870548e-01 -1.92623898e-01 9.73681748e-01 1.21870592e-01 -1.89292267e-01 9.74335492e-01 1.21870510e-01 -1.85886309e-01 9.74990249e-01 1.21870652e-01 -1.82496950e-01 9.75630105e-01 1.21870443e-01 -1.79167122e-01 9.76246059e-01 1.21870525e-01 -1.75664395e-01 9.76887643e-01 1.21870644e-01 -1.72178388e-01 9.77507830e-01 1.21870555e-01 -1.68728560e-01 9.78105485e-01 1.21870562e-01 -1.65351689e-01 9.78682399e-01 1.21870577e-01 -1.62008479e-01 9.79240894e-01 1.21870503e-01 -1.58692688e-01 9.79783654e-01 1.21870577e-01 -1.55200437e-01 9.80343759e-01 1.21870644e-01 -1.51643991e-01 9.80901122e-01 1.21870600e-01 -1.48202062e-01 9.81424093e-01 1.21870592e-01 -1.44780546e-01 9.81936038e-01 1.21870600e-01 -1.41347513e-01 9.82435822e-01 1.21870555e-01 -1.38046488e-01 9.82906044e-01 1.21870458e-01 -1.34637043e-01 9.83379602e-01 1.21870652e-01 -1.31074503e-01 9.83858824e-01 1.21870555e-01 -1.27762303e-01 9.84294951e-01 1.21870399e-01 -1.24310501e-01 9.84736383e-01 1.21870622e-01 -1.20875560e-01 9.85164702e-01 1.21870503e-01 -1.17404252e-01 9.85583961e-01 1.21870682e-01 -1.13887683e-01 9.85996187e-01 1.21870585e-01 -1.10424727e-01 9.86390531e-01 1.21870585e-01 -1.06973372e-01 9.86769557e-01 1.21870585e-01 -1.03539273e-01 9.87135530e-01 1.21870540e-01 -1.00064054e-01 9.87495422e-01 1.21870570e-01 -9.67183411e-02 9.87828195e-01 1.21870503e-01 -9.33745876e-02 9.88150418e-01 1.21870585e-01 -8.98296088e-02 9.88478780e-01 1.21870652e-01 -8.62821266e-02 9.88795638e-01 1.21870607e-01 -8.28314349e-02 9.89089787e-01 1.21870592e-01 -7.93504789e-02 9.89375412e-01 1.21870585e-01 -7.60070309e-02 9.89635706e-01 1.21870458e-01 -7.25664794e-02 9.89896357e-01 1.21870674e-01 -6.89898059e-02 9.90150034e-01 1.21870555e-01 -6.55572563e-02 9.90384817e-01 1.21870525e-01 -6.20848723e-02 9.90607321e-01 1.21870555e-01 -5.87253645e-02 9.90813851e-01 1.21870480e-01 -5.52877858e-02 9.91012037e-01 1.21870644e-01 -5.17973453e-02 9.91198480e-01 1.21870488e-01 -4.83282991e-02 9.91376579e-01 1.21870622e-01 -4.47822325e-02 9.91540074e-01 1.21870533e-01 -4.13574688e-02 9.91690695e-01 1.21870585e-01 -3.78846675e-02 9.91828382e-01 1.21870585e-01 -3.45129780e-02 9.91952658e-01 1.21870518e-01 -3.10540069e-02 9.92065430e-01 1.21870652e-01 -2.75835861e-02 9.92167950e-01 1.21870495e-01 -2.41092704e-02 9.92262781e-01 1.21870644e-01 -2.05580853e-02 9.92336869e-01 1.21870585e-01 -1.71803851e-02 9.92406309e-01 1.21870510e-01 -1.37202945e-02 9.92453396e-01 1.21870652e-01 -1.02503393e-02 9.92496967e-01 1.21870458e-01 -6.87351311e-03 9.92533326e-01 1.21870518e-01 -3.32591799e-03 9.92551506e-01 1.21870629e-01 2.33366809e-04 9.92552876e-01 1.21870570e-01 3.67082725e-03 9.92551267e-01 1.21870562e-01 7.11168861e-03 9.92530942e-01 1.21870548e-01 1.05128493e-02 9.92495835e-01 1.21870480e-01 1.38887335e-02 9.92451310e-01 1.21870577e-01 1.74290687e-02 9.92404401e-01 1.21870652e-01 2.10132934e-02 9.92329240e-01 1.21870577e-01 2.44679693e-02 9.92251277e-01 1.21870577e-01 2.79655084e-02 9.92159724e-01 1.21870577e-01 3.14101763e-02 9.92054999e-01 1.21870570e-01 3.47960293e-02 9.91943300e-01 1.21870451e-01 3.82460617e-02 9.91815507e-01 1.21870607e-01 4.18129638e-02 9.91672456e-01 1.21870600e-01 4.52764183e-02 9.91518497e-01 1.21870570e-01 4.87294197e-02 9.91355836e-01 1.21870592e-01 5.20966947e-02 9.91182089e-01 1.21870458e-01 5.55486344e-02 9.90996480e-01 1.21870615e-01 5.90234399e-02 9.90796447e-01 1.21870466e-01 6.24696352e-02 9.90582049e-01 1.21870667e-01 6.60172775e-02 9.90354180e-01 1.21870570e-01 6.94874078e-02 9.90114987e-01 1.21870585e-01 7.29351416e-02 9.89869893e-01 1.21870592e-01 7.63926730e-02 9.89606619e-01 1.21870600e-01 7.97686577e-02 9.89341736e-01 1.21870518e-01 8.32025409e-02 9.89059031e-01 1.21870652e-01 8.67210403e-02 9.88756716e-01 1.21870600e-01 9.02003869e-02 9.88445163e-01 1.21870585e-01 9.36402529e-02 9.88125384e-01 1.21870577e-01 9.70124751e-02 9.87800777e-01 1.21870466e-01 1.00447655e-01 9.87456501e-01 1.21870659e-01 1.03910908e-01 9.87098932e-01 1.21870540e-01 1.07345320e-01 9.86730576e-01 1.21870697e-01 1.10895634e-01 9.86337006e-01 1.21870615e-01 1.14247553e-01 9.85953987e-01 1.21870525e-01 1.17674448e-01 9.85551238e-01 1.21870659e-01 1.21125534e-01 9.85133588e-01 1.21870540e-01 1.24546468e-01 9.84707117e-01 1.21870667e-01 1.28083020e-01 9.84252274e-01 1.21870600e-01 1.31514266e-01 9.83800352e-01 1.21870548e-01 1.34962916e-01 9.83334482e-01 1.21870570e-01 1.38271898e-01 9.82876003e-01 1.21870548e-01 1.41725346e-01 9.82381701e-01 1.21870644e-01 1.45153418e-01 9.81880426e-01 1.21870503e-01 1.48570433e-01 9.81367826e-01 1.21870659e-01 1.52087480e-01 9.80832517e-01 1.21870570e-01 1.55435145e-01 9.80304480e-01 1.21870510e-01 1.58826128e-01 9.79762733e-01 1.21870629e-01 1.62278384e-01 9.79198098e-01 1.21870525e-01 1.65592253e-01 9.78641152e-01 1.21870577e-01 1.69090122e-01 9.78043497e-01 1.21870667e-01 1.72577247e-01 9.77437854e-01 1.21870562e-01 1.76020324e-01 9.76824522e-01 1.21870600e-01 1.79430604e-01 9.76198733e-01 1.21870570e-01 1.82736322e-01 9.75586057e-01 1.21870495e-01 1.86041430e-01 9.74960387e-01 1.21870592e-01 1.89456627e-01 9.74302530e-01 1.21870592e-01 1.92926079e-01 9.73621488e-01 1.21870644e-01 1.96407422e-01 9.72925305e-01 1.21870585e-01 1.99818596e-01 9.72231209e-01 1.21870615e-01 2.03216687e-01 9.71525669e-01 1.21870615e-01 2.06505820e-01 9.70834494e-01 1.21870510e-01 2.09865317e-01 9.70111668e-01 1.21870652e-01 2.13371992e-01 9.69346285e-01 1.21870615e-01 2.16743812e-01 9.68598604e-01 1.21870577e-01 2.20177174e-01 9.67822194e-01 1.21870548e-01 2.23468959e-01 9.67069507e-01 1.21870443e-01 2.26794228e-01 9.66296732e-01 1.21870652e-01 2.30196238e-01 9.65490699e-01 1.21870480e-01 2.33459264e-01 9.64708626e-01 1.21870600e-01 2.36916497e-01 9.63863075e-01 1.21870659e-01 2.40370095e-01 9.63006079e-01 1.21870600e-01 2.43713737e-01 9.62164760e-01 1.21870577e-01 2.47051045e-01 9.61315930e-01 1.21870592e-01 2.50347406e-01 9.60462153e-01 1.21870510e-01 2.53597856e-01 9.59610224e-01 1.21870629e-01 2.57054567e-01 9.58687961e-01 1.21870674e-01 2.60517806e-01 9.57754970e-01 1.21870629e-01 2.63804197e-01 9.56851602e-01 1.21870577e-01 2.67053306e-01 9.55953538e-01 1.21870495e-01 2.70412445e-01 9.55006897e-01 1.21870659e-01 2.73735672e-01 9.54060793e-01 1.21870540e-01 2.77039886e-01 9.53105092e-01 1.21870682e-01 2.80480295e-01 9.52097774e-01 1.21870629e-01 2.83729494e-01 9.51137543e-01 1.21870518e-01 2.87038326e-01 9.50139523e-01 1.21870682e-01 2.90377796e-01 9.49126124e-01 1.21870570e-01 2.93600768e-01 9.48136032e-01 1.21870644e-01 2.97013521e-01 9.47072089e-01 1.21870659e-01 3.00278842e-01 9.46039855e-01 1.21870540e-01 3.03563982e-01 9.44992423e-01 1.21870704e-01 3.06891441e-01 9.43916202e-01 1.21870555e-01 3.10174972e-01 9.42842484e-01 1.21870674e-01 3.13462466e-01 9.41754222e-01 1.21870525e-01 3.16648662e-01 9.40689743e-01 1.21870615e-01 3.20029199e-01 9.39544022e-01 1.21870674e-01 3.23403031e-01 9.38388169e-01 1.21870592e-01 3.26648563e-01 9.37261760e-01 1.21870615e-01 3.29897553e-01 9.36124563e-01 1.21870615e-01 3.33103895e-01 9.34990227e-01 1.21870548e-01 3.36352736e-01 9.33823586e-01 1.21870659e-01 3.39708775e-01 9.32609379e-01 1.21870629e-01 3.42954516e-01 9.31412935e-01 1.21870600e-01 3.46172690e-01 9.30218577e-01 1.21870615e-01 3.49378943e-01 9.29019511e-01 1.21870533e-01 3.52607340e-01 9.27805722e-01 1.21870652e-01 3.55832011e-01 9.26583707e-01 1.21870533e-01 3.59068722e-01 9.25324857e-01 1.21870697e-01 3.62356246e-01 9.24043536e-01 1.21870577e-01 3.65530968e-01 9.22793150e-01 1.21870488e-01 3.68736207e-01 9.21516001e-01 1.21870637e-01 3.71923178e-01 9.20234442e-01 1.21870525e-01 3.75131190e-01 9.18932080e-01 1.21870674e-01 3.78353149e-01 9.17608678e-01 1.21870570e-01 3.81545335e-01 9.16287363e-01 1.21870674e-01 3.84808898e-01 9.14921999e-01 1.21870637e-01 3.87925923e-01 9.13603365e-01 1.21870533e-01 3.91104341e-01 9.12245452e-01 1.21870674e-01 3.94302487e-01 9.10869479e-01 1.21870548e-01 3.97380650e-01 9.09534752e-01 1.21870615e-01 4.00636017e-01 9.08103347e-01 1.21870674e-01 4.03868079e-01 9.06670392e-01 1.21870629e-01 4.07027274e-01 9.05256391e-01 1.21870652e-01 4.10192370e-01 9.03827250e-01 1.21870607e-01 4.13258165e-01 9.02426958e-01 1.21870495e-01 4.16340142e-01 9.01009381e-01 1.21870555e-01 4.19569463e-01 8.99512291e-01 1.21870674e-01 4.22762603e-01 8.98014188e-01 1.21870629e-01 4.25887793e-01 8.96537364e-01 1.21870644e-01 4.28952008e-01 8.95074129e-01 1.21870555e-01 4.32057291e-01 8.93583238e-01 1.21870674e-01 4.35172826e-01 8.92070949e-01 1.21870577e-01 4.38282609e-01 8.90543282e-01 1.21870704e-01 4.41489875e-01 8.88958395e-01 1.21870644e-01 4.44595128e-01 8.87408733e-01 1.21870652e-01 4.47665453e-01 8.85866225e-01 1.21870644e-01 4.50683683e-01 8.84334028e-01 1.21870525e-01 4.53728884e-01 8.82775366e-01 1.21870592e-01 4.56855625e-01 8.81158173e-01 1.21870466e-01 4.59864259e-01 8.79595637e-01 1.21870615e-01 4.62990552e-01 8.77952814e-01 1.21870667e-01 4.66111302e-01 8.76300097e-01 1.21870577e-01 4.69151855e-01 8.74676168e-01 1.21870652e-01 4.72231746e-01 8.73016298e-01 1.21870644e-01 4.75199074e-01 8.71407807e-01 1.21870562e-01 4.78232324e-01 8.69744420e-01 1.21870704e-01 4.81356233e-01 8.68016601e-01 1.21870629e-01 4.84404296e-01 8.66319895e-01 1.21870577e-01 4.87415552e-01 8.64631593e-01 1.21870629e-01 4.90328431e-01 8.62981737e-01 1.21870548e-01 4.93342280e-01 8.61263633e-01 1.21870697e-01 4.96355265e-01 8.59530687e-01 1.21870525e-01 4.99349445e-01 8.57795119e-01 1.21870674e-01 5.02434075e-01 8.55991781e-01 1.21870652e-01 5.05335331e-01 8.54281545e-01 1.21870585e-01 5.08295178e-01 8.52524996e-01 1.21870689e-01 5.11278450e-01 8.50738704e-01 1.21870585e-01 5.14239609e-01 8.48949850e-01 1.21870682e-01 5.17235756e-01 8.47130477e-01 1.21870615e-01 5.20149946e-01 8.45341682e-01 1.21870562e-01 5.23099661e-01 8.43523979e-01 1.21870704e-01 5.26039183e-01 8.41690779e-01 1.21870570e-01 5.28952777e-01 8.39862645e-01 1.21870674e-01 5.31901598e-01 8.37997794e-01 1.21870562e-01 5.34807324e-01 8.36145818e-01 1.21870644e-01 5.37797809e-01 8.34225595e-01 1.21870629e-01 5.40655077e-01 8.32377613e-01 1.21870525e-01 5.43531299e-01 8.30499947e-01 1.21870644e-01 5.46432257e-01 8.28595638e-01 1.21870503e-01 5.49236596e-01 8.26737404e-01 1.21870562e-01 5.52217484e-01 8.24752331e-01 1.21870600e-01 5.55072129e-01 8.22835565e-01 1.21870436e-01 5.57945073e-01 8.20888400e-01 1.21870525e-01 5.60887992e-01 8.18879783e-01 1.21870212e-01 5.63684642e-01 8.16959321e-01 1.21869899e-01 5.66418231e-01 8.15064013e-01 1.21870004e-01 5.69247842e-01 8.13089788e-01 1.21869847e-01 5.72182655e-01 8.11028779e-01 1.21869914e-01 5.75046062e-01 8.08999658e-01 1.21869564e-01 5.77776372e-01 8.07052016e-01 1.21869080e-01 5.80516815e-01 8.05082440e-01 1.21869072e-01 5.83417416e-01 8.02980244e-01 1.21869594e-01 5.85772872e-01 8.01260114e-01 1.21869393e-01 5.88409543e-01 7.99325585e-01 1.21869348e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.05470502e-01 6.98182762e-01 1.21869355e-01 7.07391381e-01 6.96236014e-01 1.21869385e-01 7.09369659e-01 6.94223762e-01 1.21869534e-01 7.11739600e-01 6.91799581e-01 1.21869020e-01 7.14099109e-01 6.89359248e-01 1.21869542e-01 7.16471553e-01 6.86895728e-01 1.21870100e-01 7.18934596e-01 6.84319377e-01 1.21870004e-01 7.21241653e-01 6.81887746e-01 1.21870093e-01 7.23621070e-01 6.79360032e-01 1.21870458e-01 7.26036608e-01 6.76778018e-01 1.21870466e-01 7.28350699e-01 6.74289346e-01 1.21870495e-01 7.30655491e-01 6.71793699e-01 1.21870495e-01 7.32959330e-01 6.69275045e-01 1.21870562e-01 7.35358715e-01 6.66642010e-01 1.21870652e-01 7.37751186e-01 6.63991213e-01 1.21870585e-01 7.40054727e-01 6.61420882e-01 1.21870600e-01 7.42297053e-01 6.58906102e-01 1.21870533e-01 7.44527578e-01 6.56383336e-01 1.21870622e-01 7.46842861e-01 6.53745413e-01 1.21870644e-01 7.49162912e-01 6.51087940e-01 1.21870615e-01 7.51463532e-01 6.48431122e-01 1.21870659e-01 7.53715456e-01 6.45812869e-01 1.21870577e-01 7.55906105e-01 6.43244505e-01 1.21870548e-01 7.58125961e-01 6.40630186e-01 1.21870637e-01 7.60366261e-01 6.37969077e-01 1.21870600e-01 7.62631238e-01 6.35260463e-01 1.21870682e-01 7.64898658e-01 6.32526040e-01 1.21870629e-01 7.67050385e-01 6.29917264e-01 1.21870562e-01 7.69232869e-01 6.27247810e-01 1.21870667e-01 7.71461010e-01 6.24506176e-01 1.21870615e-01 7.73652673e-01 6.21790290e-01 1.21870637e-01 7.75763869e-01 6.19155109e-01 1.21870555e-01 7.77856588e-01 6.16522014e-01 1.21870629e-01 7.80061960e-01 6.13729894e-01 1.21870674e-01 7.82252431e-01 6.10934913e-01 1.21870600e-01 7.84390569e-01 6.08188927e-01 1.21870674e-01 7.86470592e-01 6.05496883e-01 1.21870503e-01 7.88502812e-01 6.02846682e-01 1.21870615e-01 7.90652752e-01 6.00024700e-01 1.21870689e-01 7.92802155e-01 5.97182035e-01 1.21870607e-01 7.94887602e-01 5.94401538e-01 1.21870637e-01 7.96908081e-01 5.91690779e-01 1.21870503e-01 7.98914969e-01 5.88977218e-01 1.21870562e-01 8.01003397e-01 5.86133778e-01 1.21870682e-01 8.03098559e-01 5.83259642e-01 1.21870622e-01 8.05157244e-01 5.80411911e-01 1.21870585e-01 8.07165563e-01 5.77619910e-01 1.21870592e-01 8.09116840e-01 5.74884534e-01 1.21870525e-01 8.11063290e-01 5.72136641e-01 1.21870629e-01 8.13059390e-01 5.69293857e-01 1.21870629e-01 8.15097988e-01 5.66369653e-01 1.21870719e-01 8.17100227e-01 5.63479602e-01 1.21870533e-01 8.18988740e-01 5.60729146e-01 1.21870607e-01 8.20998371e-01 5.57782173e-01 1.21870719e-01 8.22947025e-01 5.54904282e-01 1.21870488e-01 8.24836016e-01 5.52089691e-01 1.21870667e-01 8.26774299e-01 5.49184680e-01 1.21870570e-01 8.28647435e-01 5.46354771e-01 1.21870622e-01 8.30601990e-01 5.43376982e-01 1.21870674e-01 8.32539320e-01 5.40405691e-01 1.21870607e-01 8.34366977e-01 5.37578881e-01 1.21870525e-01 8.36186171e-01 5.34746408e-01 1.21870600e-01 8.38050008e-01 5.31816483e-01 1.21870644e-01 8.39981437e-01 5.28764665e-01 1.21870682e-01 8.41877162e-01 5.25739312e-01 1.21870644e-01 8.43701005e-01 5.22810221e-01 1.21870577e-01 8.45457971e-01 5.19959867e-01 1.21870555e-01 8.47236156e-01 5.17063379e-01 1.21870615e-01 8.49038899e-01 5.14094412e-01 1.21870615e-01 8.50826323e-01 5.11130750e-01 1.21870600e-01 8.52634728e-01 5.08107007e-01 1.21870682e-01 8.54458511e-01 5.05035400e-01 1.21870592e-01 8.56175721e-01 5.02119541e-01 1.21870518e-01 8.57916176e-01 4.99139249e-01 1.21870637e-01 8.59663367e-01 4.96126384e-01 1.21870525e-01 8.61382246e-01 4.93133426e-01 1.21870667e-01 8.63123477e-01 4.90076780e-01 1.21870555e-01 8.64784181e-01 4.87147689e-01 1.21870533e-01 8.66499305e-01 4.84084487e-01 1.21870667e-01 8.68193448e-01 4.81037199e-01 1.21870570e-01 8.69862020e-01 4.78017867e-01 1.21870629e-01 8.71516466e-01 4.74996328e-01 1.21870533e-01 8.73128891e-01 4.72023487e-01 1.21870607e-01 8.74811769e-01 4.68897134e-01 1.21870667e-01 8.76494765e-01 4.65745121e-01 1.21870629e-01 8.78122032e-01 4.62669879e-01 1.21870592e-01 8.79677773e-01 4.59705591e-01 1.21870503e-01 8.81228805e-01 4.56722289e-01 1.21870585e-01 8.82855296e-01 4.53572214e-01 1.21870667e-01 8.84489715e-01 4.50376034e-01 1.21870607e-01 8.86048973e-01 4.47301775e-01 1.21870585e-01 8.87614131e-01 4.44187611e-01 1.21870622e-01 8.89122009e-01 4.41160589e-01 1.21870495e-01 8.90638769e-01 4.38090235e-01 1.21870637e-01 8.92179370e-01 4.34946358e-01 1.21870518e-01 8.93684387e-01 4.31846023e-01 1.21870674e-01 8.95228922e-01 4.28632677e-01 1.21870607e-01 8.96682262e-01 4.25583512e-01 1.21870510e-01 8.98142517e-01 4.22490418e-01 1.21870674e-01 8.99630249e-01 4.19317573e-01 1.21870525e-01 9.01082933e-01 4.16186273e-01 1.21870674e-01 9.02569830e-01 4.12947357e-01 1.21870600e-01 9.03970540e-01 4.09874082e-01 1.21870495e-01 9.05385733e-01 4.06740963e-01 1.21870667e-01 9.06811297e-01 4.03550565e-01 1.21870503e-01 9.08209741e-01 4.00394499e-01 1.21870644e-01 9.09610927e-01 3.97205114e-01 1.21870510e-01 9.10949469e-01 3.94120246e-01 1.21870592e-01 9.12359118e-01 3.90838534e-01 1.21870659e-01 9.13751304e-01 3.87580723e-01 1.21870585e-01 9.15091038e-01 3.84406656e-01 1.21870600e-01 9.16395843e-01 3.81283700e-01 1.21870540e-01 9.17676926e-01 3.78188521e-01 1.21870622e-01 9.19033110e-01 3.74882191e-01 1.21870689e-01 9.20382440e-01 3.71561706e-01 1.21870622e-01 9.21675682e-01 3.68338674e-01 1.21870615e-01 9.22922909e-01 3.65207851e-01 1.21870518e-01 9.24148142e-01 3.62096369e-01 1.21870600e-01 9.25427735e-01 3.58798534e-01 1.21870682e-01 9.26696479e-01 3.55534941e-01 1.21870533e-01 9.27911222e-01 3.52326572e-01 1.21870667e-01 9.29174960e-01 3.48967731e-01 1.21870629e-01 9.30355906e-01 3.45801085e-01 1.21870525e-01 9.31554079e-01 3.42576891e-01 1.21870682e-01 9.32760537e-01 3.39300811e-01 1.21870533e-01 9.33924258e-01 3.36073011e-01 1.21870704e-01 9.35128391e-01 3.32713634e-01 1.21870622e-01 9.36254621e-01 3.29529583e-01 1.21870555e-01 9.37391400e-01 3.26277286e-01 1.21870682e-01 9.38551664e-01 3.22928846e-01 1.21870622e-01 9.39660192e-01 3.19683671e-01 1.21870600e-01 9.40759897e-01 3.16439301e-01 1.21870570e-01 9.41830814e-01 3.13232601e-01 1.21870615e-01 9.42943156e-01 3.09869140e-01 1.21870697e-01 9.44039464e-01 3.06514531e-01 1.21870615e-01 9.45105672e-01 3.03211123e-01 1.21870600e-01 9.46140110e-01 2.99966067e-01 1.21870510e-01 9.47147429e-01 2.96768636e-01 1.21870607e-01 9.48206663e-01 2.93366879e-01 1.21870682e-01 9.49253500e-01 2.89959311e-01 1.21870637e-01 9.50251102e-01 2.86674321e-01 1.21870637e-01 9.51221824e-01 2.83434033e-01 1.21870562e-01 9.52184916e-01 2.80187964e-01 1.21870629e-01 9.53177631e-01 2.76795447e-01 1.21870697e-01 9.54135180e-01 2.73468018e-01 1.21870555e-01 9.55088913e-01 2.70123601e-01 1.21870711e-01 9.56043243e-01 2.66725332e-01 1.21870600e-01 9.56945121e-01 2.63469458e-01 1.21870495e-01 9.57858622e-01 2.60136813e-01 1.21870682e-01 9.58787799e-01 2.56684065e-01 1.21870577e-01 9.59674537e-01 2.53351361e-01 1.21870600e-01 9.60554004e-01 2.49995396e-01 1.21870592e-01 9.61403906e-01 2.46712491e-01 1.21870525e-01 9.62251723e-01 2.43369117e-01 1.21870629e-01 9.63097870e-01 2.40007788e-01 1.21870510e-01 9.63933229e-01 2.36634806e-01 1.21870689e-01 9.64754283e-01 2.33265474e-01 1.21870533e-01 9.65540648e-01 2.29988903e-01 1.21870577e-01 9.66351032e-01 2.26560906e-01 1.21870659e-01 9.67160225e-01 2.23072559e-01 1.21870525e-01 9.67929065e-01 2.19714567e-01 1.21870629e-01 9.68694031e-01 2.16319472e-01 1.21870607e-01 9.69424009e-01 2.13012025e-01 1.21870510e-01 9.70159233e-01 2.09641486e-01 1.21870689e-01 9.70904052e-01 2.06169665e-01 1.21870562e-01 9.71623123e-01 2.02758491e-01 1.21870548e-01 9.72321749e-01 1.99382469e-01 1.21870585e-01 9.72996175e-01 1.96059063e-01 1.21870548e-01 9.73663628e-01 1.92706287e-01 1.21870674e-01 9.74340320e-01 1.89268932e-01 1.21870488e-01 9.74991858e-01 1.85871735e-01 1.21870667e-01 9.75647509e-01 1.82405248e-01 1.21870600e-01 9.76261675e-01 1.79077506e-01 1.21870570e-01 9.76889849e-01 1.75659657e-01 1.21870697e-01 9.77508008e-01 1.72183216e-01 1.21870607e-01 9.78093326e-01 1.68798864e-01 1.21870615e-01 9.78671253e-01 1.65416360e-01 1.21870495e-01 9.79223251e-01 1.62113994e-01 1.21870652e-01 9.79798138e-01 1.58602893e-01 1.21870711e-01 9.80361998e-01 1.55078515e-01 1.21870629e-01 9.80894625e-01 1.51671782e-01 1.21870637e-01 9.81406808e-01 1.48315683e-01 1.21870548e-01 9.81906652e-01 1.44977719e-01 1.21870615e-01 9.82417941e-01 1.41470999e-01 1.21870682e-01 9.82919097e-01 1.37953445e-01 1.21870622e-01 9.83391941e-01 1.34553239e-01 1.21870562e-01 9.83856797e-01 1.31093323e-01 1.21870555e-01 9.84304011e-01 1.27690807e-01 1.21870443e-01 9.84739661e-01 1.24293894e-01 1.21870600e-01 9.85175073e-01 1.20782971e-01 1.21870577e-01 9.85589802e-01 1.17346048e-01 1.21870585e-01 9.85996068e-01 1.13888070e-01 1.21870562e-01 9.86376345e-01 1.10551663e-01 1.21870518e-01 9.86756980e-01 1.07095294e-01 1.21870652e-01 9.87127125e-01 1.03635982e-01 1.21870525e-01 9.87478375e-01 1.00223519e-01 1.21870585e-01 9.87834394e-01 9.66597646e-02 1.21870607e-01 9.88155901e-01 9.33167934e-02 1.21870480e-01 9.88474250e-01 8.98839235e-02 1.21870659e-01 9.88783777e-01 8.64167586e-02 1.21870525e-01 9.89079475e-01 8.29495639e-02 1.21870659e-01 9.89364862e-01 7.94750527e-02 1.21870488e-01 9.89633203e-01 7.60643631e-02 1.21870659e-01 9.89901245e-01 7.24899918e-02 1.21870615e-01 9.90147829e-01 6.90157786e-02 1.21870607e-01 9.90383983e-01 6.55740127e-02 1.21870615e-01 9.90600407e-01 6.22001849e-02 1.21870525e-01 9.90805089e-01 5.88380061e-02 1.21870592e-01 9.91011202e-01 5.52969724e-02 1.21870697e-01 9.91203010e-01 5.17356545e-02 1.21870600e-01 9.91379142e-01 4.82627749e-02 1.21870622e-01 9.91535604e-01 4.48923856e-02 1.21870540e-01 9.91681695e-01 4.15773205e-02 1.21870600e-01 9.91820335e-01 3.81004363e-02 1.21870644e-01 9.91947591e-01 3.46325114e-02 1.21870607e-01 9.92066920e-01 3.10433060e-02 1.21870682e-01 9.92172241e-01 2.74877120e-02 1.21870607e-01 9.92262006e-01 2.41196528e-02 1.21870518e-01 9.92333472e-01 2.07608603e-02 1.21870570e-01 9.92406130e-01 1.72955114e-02 1.21870600e-01 9.92451668e-01 1.38272420e-02 1.21870607e-01 9.92499173e-01 1.03270728e-02 1.21870577e-01 9.92533982e-01 6.90103462e-03 1.21870585e-01 9.92551684e-01 3.34459334e-03 1.21870689e-01 9.92552757e-01 -1.27781983e-04 1.21870533e-01 9.92551565e-01 -3.55373556e-03 1.21870644e-01 9.92531180e-01 -7.09785661e-03 1.21870503e-01 9.92497861e-01 -1.04305791e-02 1.21870600e-01 9.92448986e-01 -1.39501458e-02 1.21870644e-01 9.92401719e-01 -1.75269973e-02 1.21870615e-01 9.92330492e-01 -2.09170710e-02 1.21870533e-01 9.92254615e-01 -2.43945979e-02 1.21870682e-01 9.92161036e-01 -2.78658643e-02 1.21870510e-01 9.92058516e-01 -3.13028283e-02 1.21870644e-01 9.91944253e-01 -3.47693413e-02 1.21870548e-01 9.91818190e-01 -3.81565504e-02 1.21870607e-01 9.91680741e-01 -4.16043252e-02 1.21870600e-01 9.91525412e-01 -4.51220237e-02 1.21870682e-01 9.91358519e-01 -4.86943871e-02 1.21870577e-01 9.91179168e-01 -5.21568954e-02 1.21870607e-01 9.90995169e-01 -5.55556305e-02 1.21870525e-01 9.90801394e-01 -5.89117743e-02 1.21870600e-01 9.90589261e-01 -6.23630844e-02 1.21870629e-01 9.90362644e-01 -6.58968240e-02 1.21870667e-01 9.90117133e-01 -6.94488660e-02 1.21870570e-01 9.89872575e-01 -7.28951097e-02 1.21870622e-01 9.89616036e-01 -7.62861893e-02 1.21870570e-01 9.89349782e-01 -7.96634480e-02 1.21870615e-01 9.89068449e-01 -8.30820277e-02 1.21870607e-01 9.88762021e-01 -8.66545215e-02 1.21870637e-01 9.88454700e-01 -9.00929347e-02 1.21870540e-01 9.88144577e-01 -9.34409276e-02 1.21870622e-01 9.87812638e-01 -9.68861580e-02 1.21870607e-01 9.87456739e-01 -1.00440122e-01 1.21870689e-01 9.87100422e-01 -1.03890955e-01 1.21870533e-01 9.86733556e-01 -1.07306458e-01 1.21870682e-01 9.86353040e-01 -1.10767432e-01 1.21870510e-01 9.85972106e-01 -1.14093266e-01 1.21870615e-01 9.85556901e-01 -1.17636442e-01 1.21870674e-01 9.85138953e-01 -1.21086575e-01 1.21870533e-01 9.84711170e-01 -1.24531195e-01 1.21870674e-01 9.84255075e-01 -1.28062353e-01 1.21870637e-01 9.83810902e-01 -1.31434515e-01 1.21870525e-01 9.83357430e-01 -1.34801924e-01 1.21870652e-01 9.82864201e-01 -1.38347432e-01 1.21870600e-01 9.82385755e-01 -1.41705036e-01 1.21870503e-01 9.81882811e-01 -1.45140558e-01 1.21870659e-01 9.81374025e-01 -1.48541301e-01 1.21870555e-01 9.80852008e-01 -1.51945233e-01 1.21870644e-01 9.80308294e-01 -1.55414522e-01 1.21870503e-01 9.79764640e-01 -1.58814549e-01 1.21870615e-01 9.79212582e-01 -1.62186593e-01 1.21870555e-01 9.78634357e-01 -1.65641591e-01 1.21870667e-01 9.78032649e-01 -1.69140309e-01 1.21870607e-01 9.77445185e-01 -1.72534674e-01 1.21870600e-01 9.76846635e-01 -1.75888985e-01 1.21870548e-01 9.76234853e-01 -1.79224744e-01 1.21870600e-01 9.75605786e-01 -1.82636648e-01 1.21870592e-01 9.74952281e-01 -1.86081335e-01 1.21870644e-01 9.74279344e-01 -1.89574927e-01 1.21870592e-01 9.73612547e-01 -1.92975357e-01 1.21870585e-01 9.72945929e-01 -1.96305498e-01 1.21870540e-01 9.72270489e-01 -1.99622735e-01 1.21870577e-01 9.71577525e-01 -2.02973917e-01 1.21870585e-01 9.70836580e-01 -2.06492662e-01 1.21870682e-01 9.70112622e-01 -2.09864989e-01 1.21870533e-01 9.69388068e-01 -2.13179395e-01 1.21870637e-01 9.68628883e-01 -2.16612548e-01 1.21870555e-01 9.67862070e-01 -2.20002547e-01 1.21870689e-01 9.67087150e-01 -2.23392561e-01 1.21870518e-01 9.66302812e-01 -2.26768374e-01 1.21870689e-01 9.65502739e-01 -2.30147883e-01 1.21870540e-01 9.64724422e-01 -2.33392835e-01 1.21870600e-01 9.63876545e-01 -2.36859262e-01 1.21870682e-01 9.63043809e-01 -2.40220129e-01 1.21870548e-01 9.62190986e-01 -2.43610546e-01 1.21870682e-01 9.61308897e-01 -2.47073442e-01 1.21870592e-01 9.60471213e-01 -2.50310600e-01 1.21870510e-01 9.59600210e-01 -2.53638595e-01 1.21870659e-01 9.58699703e-01 -2.57017016e-01 1.21870503e-01 9.57829177e-01 -2.60243326e-01 1.21870607e-01 9.56888735e-01 -2.63672948e-01 1.21870682e-01 9.55958843e-01 -2.67033428e-01 1.21870510e-01 9.55016732e-01 -2.70376325e-01 1.21870652e-01 9.54043984e-01 -2.73785114e-01 1.21870652e-01 9.53107595e-01 -2.77028859e-01 1.21870510e-01 9.52163875e-01 -2.80257463e-01 1.21870607e-01 9.51148689e-01 -2.83688158e-01 1.21870637e-01 9.50140238e-01 -2.87035525e-01 1.21870577e-01 9.49131727e-01 -2.90361673e-01 1.21870622e-01 9.48132217e-01 -2.93613285e-01 1.21870540e-01 9.47126031e-01 -2.96838343e-01 1.21870607e-01 9.46085811e-01 -3.00135553e-01 1.21870615e-01 9.45008099e-01 -3.03512871e-01 1.21870674e-01 9.43903208e-01 -3.06929171e-01 1.21870622e-01 9.42826867e-01 -3.10221821e-01 1.21870607e-01 9.41765666e-01 -3.13431889e-01 1.21870540e-01 9.40700948e-01 -3.16611409e-01 1.21870607e-01 9.39593196e-01 -3.19883436e-01 1.21870585e-01 9.38448727e-01 -3.23224604e-01 1.21870667e-01 9.37292635e-01 -3.26559603e-01 1.21870540e-01 9.36174333e-01 -3.29754949e-01 1.21870577e-01 9.35030162e-01 -3.32985729e-01 1.21870570e-01 9.33832347e-01 -3.36331338e-01 1.21870689e-01 9.32649672e-01 -3.39601606e-01 1.21870562e-01 9.31457400e-01 -3.42836767e-01 1.21870637e-01 9.30241287e-01 -3.46110016e-01 1.21870555e-01 9.29071665e-01 -3.49244297e-01 1.21870607e-01 9.27850902e-01 -3.52486104e-01 1.21870615e-01 9.26621497e-01 -3.55726331e-01 1.21870622e-01 9.25361335e-01 -3.58973920e-01 1.21870629e-01 9.24075961e-01 -3.62280399e-01 1.21870682e-01 9.22803700e-01 -3.65504414e-01 1.21870525e-01 9.21538711e-01 -3.68680477e-01 1.21870667e-01 9.20228064e-01 -3.71940225e-01 1.21870533e-01 9.18968141e-01 -3.75043213e-01 1.21870615e-01 9.17623222e-01 -3.78319949e-01 1.21870667e-01 9.16287899e-01 -3.81544173e-01 1.21870555e-01 9.14948583e-01 -3.84747595e-01 1.21870667e-01 9.13557887e-01 -3.88031811e-01 1.21870637e-01 9.12230253e-01 -3.91141295e-01 1.21870518e-01 9.10915792e-01 -3.94197941e-01 1.21870585e-01 9.09498453e-01 -3.97462130e-01 1.21870659e-01 9.08044934e-01 -4.00767535e-01 1.21870637e-01 9.06635642e-01 -4.03945357e-01 1.21870600e-01 9.05251980e-01 -4.07038867e-01 1.21870540e-01 9.03843105e-01 -4.10155356e-01 1.21870540e-01 9.02452171e-01 -4.13202196e-01 1.21870600e-01 9.00969505e-01 -4.16426569e-01 1.21870644e-01 8.99469912e-01 -4.19656664e-01 1.21870607e-01 8.97979856e-01 -4.22837198e-01 1.21870607e-01 8.96542609e-01 -4.25876588e-01 1.21870503e-01 8.95110905e-01 -4.28874522e-01 1.21870615e-01 8.93598020e-01 -4.32026863e-01 1.21870615e-01 8.92045021e-01 -4.35224056e-01 1.21870652e-01 8.90482783e-01 -4.38407063e-01 1.21870570e-01 8.88967097e-01 -4.41471428e-01 1.21870592e-01 8.87422204e-01 -4.44568187e-01 1.21870510e-01 8.85929048e-01 -4.47539389e-01 1.21870592e-01 8.84355009e-01 -4.50642228e-01 1.21870607e-01 8.82737577e-01 -4.53800470e-01 1.21870682e-01 8.81140888e-01 -4.56890941e-01 1.21870555e-01 8.79539847e-01 -4.59969342e-01 1.21870622e-01 8.77935946e-01 -4.63023931e-01 1.21870540e-01 8.76360476e-01 -4.65996534e-01 1.21870548e-01 8.74718547e-01 -4.69072938e-01 1.21870629e-01 8.73034596e-01 -4.72197682e-01 1.21870704e-01 8.71374965e-01 -4.75258648e-01 1.21870533e-01 8.69760156e-01 -4.78203267e-01 1.21870615e-01 8.68083239e-01 -4.81236786e-01 1.21870585e-01 8.66364121e-01 -4.84327167e-01 1.21870674e-01 8.64665449e-01 -4.87355590e-01 1.21870503e-01 8.62955451e-01 -4.90374506e-01 1.21870689e-01 8.61239314e-01 -4.93387163e-01 1.21870525e-01 8.59518528e-01 -4.96375382e-01 1.21870689e-01 8.57775390e-01 -4.99382406e-01 1.21870495e-01 8.56068313e-01 -5.02305329e-01 1.21870615e-01 8.54296744e-01 -5.05311012e-01 1.21870592e-01 8.52505445e-01 -5.08326173e-01 1.21870615e-01 8.50700617e-01 -5.11340320e-01 1.21870659e-01 8.48894596e-01 -5.14330983e-01 1.21870600e-01 8.47124040e-01 -5.17246425e-01 1.21870548e-01 8.45358968e-01 -5.20120978e-01 1.21870629e-01 8.43550801e-01 -5.23054898e-01 1.21870615e-01 8.41674328e-01 -5.26064575e-01 1.21870689e-01 8.39789331e-01 -5.29070139e-01 1.21870607e-01 8.37986231e-01 -5.31920433e-01 1.21870555e-01 8.36155236e-01 -5.34791708e-01 1.21870622e-01 8.34246039e-01 -5.37766814e-01 1.21870682e-01 8.32302570e-01 -5.40768683e-01 1.21870622e-01 8.30426753e-01 -5.43644309e-01 1.21870585e-01 8.28526080e-01 -5.46541512e-01 1.21870615e-01 8.26649249e-01 -5.49369276e-01 1.21870495e-01 8.24775577e-01 -5.52180350e-01 1.21870600e-01 8.22860360e-01 -5.55036366e-01 1.21870592e-01 8.20865870e-01 -5.57977915e-01 1.21870644e-01 8.18847120e-01 -5.60936809e-01 1.21870577e-01 8.16896737e-01 -5.63775659e-01 1.21870562e-01 8.14985096e-01 -5.66532552e-01 1.21870540e-01 8.13019633e-01 -5.69349229e-01 1.21870622e-01 8.11002195e-01 -5.72222888e-01 1.21870540e-01 8.08988869e-01 -5.75062275e-01 1.21870659e-01 8.06974471e-01 -5.77887535e-01 1.21870540e-01 8.04973006e-01 -5.80666661e-01 1.21870607e-01 8.02915692e-01 -5.83512962e-01 1.21870622e-01 8.00833762e-01 -5.86364508e-01 1.21870622e-01 7.98780620e-01 -5.89160621e-01 1.21870644e-01 7.96693504e-01 -5.91978252e-01 1.21870592e-01 7.94689238e-01 -5.94665527e-01 1.21870518e-01 7.92630374e-01 -5.97410619e-01 1.21870704e-01 7.90523469e-01 -6.00195467e-01 1.21870533e-01 7.88422942e-01 -6.02951467e-01 1.21870674e-01 7.86309719e-01 -6.05704784e-01 1.21870548e-01 7.84255087e-01 -6.08360887e-01 1.21870637e-01 7.82070994e-01 -6.11166894e-01 1.21870689e-01 7.79873669e-01 -6.13967776e-01 1.21870615e-01 7.77791917e-01 -6.16602838e-01 1.21870540e-01 7.75690377e-01 -6.19246781e-01 1.21870629e-01 7.73468554e-01 -6.22018635e-01 1.21870697e-01 7.71231234e-01 -6.24791503e-01 1.21870615e-01 7.69087851e-01 -6.27423346e-01 1.21870555e-01 7.66967595e-01 -6.30016506e-01 1.21870637e-01 7.64755428e-01 -6.32700801e-01 1.21870622e-01 7.62559950e-01 -6.35345340e-01 1.21870629e-01 7.60333836e-01 -6.38006389e-01 1.21870615e-01 7.58041561e-01 -6.40727937e-01 1.21870674e-01 7.55808175e-01 -6.43361866e-01 1.21870555e-01 7.53608465e-01 -6.45936310e-01 1.21870644e-01 7.51355708e-01 -6.48557007e-01 1.21870600e-01 7.49059260e-01 -6.51208758e-01 1.21870674e-01 7.46720195e-01 -6.53887928e-01 1.21870659e-01 7.44393349e-01 -6.56535625e-01 1.21870615e-01 7.42153406e-01 -6.59067273e-01 1.21870555e-01 7.39920616e-01 -6.61573410e-01 1.21870622e-01 7.37558484e-01 -6.64205015e-01 1.21870682e-01 7.35227585e-01 -6.66785777e-01 1.21870533e-01 7.32893348e-01 -6.69348121e-01 1.21870719e-01 7.30547786e-01 -6.71910048e-01 1.21870525e-01 7.28284061e-01 -6.74361169e-01 1.21870615e-01 7.25923061e-01 -6.76901460e-01 1.21870615e-01 7.23493099e-01 -6.79497957e-01 1.21870697e-01 7.21094489e-01 -6.82041407e-01 1.21870548e-01 7.18699753e-01 -6.84569120e-01 1.21870704e-01 7.16298819e-01 -6.87073588e-01 1.21870525e-01 7.13923097e-01 -6.89556181e-01 1.21870719e-01 7.11501062e-01 -6.92050636e-01 1.21870510e-01 7.09166646e-01 -6.94439232e-01 1.21870615e-01 7.06708312e-01 -6.96943939e-01 1.21870629e-01 7.04244852e-01 -6.99435115e-01 1.21870555e-01 7.01739132e-01 -7.01931536e-01 1.21870592e-01 6.99234366e-01 -7.04442739e-01 1.21870495e-01 6.96838796e-01 -7.06812203e-01 1.21870376e-01 6.94449902e-01 -7.09156513e-01 1.21870451e-01 6.91952527e-01 -7.11597323e-01 1.21870242e-01 6.89403117e-01 -7.14066148e-01 1.21870317e-01 6.86899841e-01 -7.16468275e-01 1.21869959e-01 6.84451222e-01 -7.18807459e-01 1.21869795e-01 6.81921005e-01 -7.21208870e-01 1.21868968e-01 6.79918885e-01 -7.23092914e-01 1.21869497e-01 6.77480161e-01 -7.25374103e-01 1.21869333e-01 6.74630880e-01 -7.28025079e-01 1.21869355e-01 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. 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. 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. 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. 0. 0. 5.70435762e-01 -8.12250495e-01 1.21869348e-01 5.65691590e-01 -8.15562427e-01 1.21869333e-01 5.63358605e-01 -8.17182004e-01 1.21869028e-01 5.60641289e-01 -8.19049001e-01 1.21869996e-01 5.57833731e-01 -8.20963204e-01 1.21870346e-01 5.54989219e-01 -8.22890937e-01 1.21870480e-01 5.52114069e-01 -8.24820697e-01 1.21870562e-01 5.49174845e-01 -8.26780677e-01 1.21870659e-01 5.46244085e-01 -8.28720450e-01 1.21870562e-01 5.43435454e-01 -8.30563605e-01 1.21870592e-01 5.40569127e-01 -8.32432926e-01 1.21870622e-01 5.37652612e-01 -8.34320188e-01 1.21870644e-01 5.34749389e-01 -8.36181760e-01 1.21870637e-01 5.31831503e-01 -8.38041663e-01 1.21870644e-01 5.28914988e-01 -8.39888692e-01 1.21870637e-01 5.25983155e-01 -8.41723561e-01 1.21870629e-01 5.23038387e-01 -8.43560398e-01 1.21870615e-01 5.20088673e-01 -8.45379412e-01 1.21870637e-01 5.17148077e-01 -8.47184777e-01 1.21870629e-01 5.14186978e-01 -8.48982096e-01 1.21870629e-01 5.11220217e-01 -8.50773275e-01 1.21870615e-01 5.08171439e-01 -8.52596760e-01 1.21870689e-01 5.05160630e-01 -8.54384422e-01 1.21870562e-01 5.02268553e-01 -8.56088519e-01 1.21870629e-01 4.99276072e-01 -8.57836068e-01 1.21870615e-01 4.96195972e-01 -8.59622955e-01 1.21870697e-01 4.93170172e-01 -8.61362219e-01 1.21870548e-01 4.90251243e-01 -8.63024235e-01 1.21870600e-01 4.87246126e-01 -8.64729464e-01 1.21870615e-01 4.84218895e-01 -8.66424859e-01 1.21870615e-01 4.81201708e-01 -8.68102193e-01 1.21870644e-01 4.78167802e-01 -8.69781077e-01 1.21870629e-01 4.75129157e-01 -8.71444464e-01 1.21870615e-01 4.72075135e-01 -8.73100400e-01 1.21870644e-01 4.69021320e-01 -8.74744594e-01 1.21870622e-01 4.65956420e-01 -8.76381338e-01 1.21870629e-01 4.62905228e-01 -8.77998888e-01 1.21870629e-01 4.59762424e-01 -8.79646599e-01 1.21870704e-01 4.56676573e-01 -8.81252050e-01 1.21870570e-01 4.53685045e-01 -8.82797480e-01 1.21870622e-01 4.50605094e-01 -8.84373009e-01 1.21870629e-01 4.47507292e-01 -8.85944724e-01 1.21870637e-01 4.44405049e-01 -8.87504101e-01 1.21870629e-01 4.41296369e-01 -8.89054894e-01 1.21870644e-01 4.38194096e-01 -8.90588403e-01 1.21870622e-01 4.35069859e-01 -8.92118871e-01 1.21870629e-01 4.31943476e-01 -8.93637538e-01 1.21870644e-01 4.28845465e-01 -8.95125449e-01 1.21870629e-01 4.25599128e-01 -8.96673083e-01 1.21870741e-01 4.22458291e-01 -8.98158073e-01 1.21870548e-01 4.19344395e-01 -8.99616957e-01 1.21870711e-01 4.16181803e-01 -9.01084125e-01 1.21870548e-01 4.13128316e-01 -9.02486980e-01 1.21870622e-01 4.09990132e-01 -9.03918743e-01 1.21870622e-01 4.06818271e-01 -9.05350804e-01 1.21870629e-01 4.03576195e-01 -9.06800508e-01 1.21870704e-01 4.00386631e-01 -9.08212841e-01 1.21870562e-01 3.97319168e-01 -9.09560382e-01 1.21870607e-01 3.94150585e-01 -9.10935879e-01 1.21870659e-01 3.90955567e-01 -9.12309289e-01 1.21870644e-01 3.87739301e-01 -9.13683236e-01 1.21870637e-01 3.84567410e-01 -9.15024698e-01 1.21870607e-01 3.81386042e-01 -9.16354418e-01 1.21870652e-01 3.78163606e-01 -9.17687595e-01 1.21870585e-01 3.75008166e-01 -9.18983459e-01 1.21870622e-01 3.71797115e-01 -9.20286059e-01 1.21870652e-01 3.68487865e-01 -9.21615958e-01 1.21870697e-01 3.65241110e-01 -9.22908664e-01 1.21870570e-01 3.62104148e-01 -9.24145162e-01 1.21870629e-01 3.58882308e-01 -9.25393462e-01 1.21870629e-01 3.55645090e-01 -9.26651955e-01 1.21870652e-01 3.52399647e-01 -9.27883625e-01 1.21870637e-01 3.49162400e-01 -9.29102004e-01 1.21870637e-01 3.45907867e-01 -9.30317402e-01 1.21870622e-01 3.42594415e-01 -9.31548059e-01 1.21870711e-01 3.39326203e-01 -9.32750106e-01 1.21870555e-01 3.36106420e-01 -9.33912098e-01 1.21870674e-01 3.32832843e-01 -9.35086250e-01 1.21870570e-01 3.29552919e-01 -9.36245322e-01 1.21870682e-01 3.26283991e-01 -9.37388480e-01 1.21870562e-01 3.23011398e-01 -9.38522577e-01 1.21870689e-01 3.19721520e-01 -9.39646363e-01 1.21870548e-01 3.16529989e-01 -9.40728843e-01 1.21870652e-01 3.13234419e-01 -9.41829681e-01 1.21870659e-01 3.09925407e-01 -9.42923307e-01 1.21870600e-01 3.06664765e-01 -9.43988979e-01 1.21870622e-01 3.03347111e-01 -9.45062459e-01 1.21870644e-01 3.00074577e-01 -9.46104765e-01 1.21870615e-01 2.96777397e-01 -9.47145283e-01 1.21870629e-01 2.93465465e-01 -9.48176801e-01 1.21870622e-01 2.90147305e-01 -9.49197888e-01 1.21870629e-01 2.86789179e-01 -9.50214624e-01 1.21870674e-01 2.83439070e-01 -9.51221168e-01 1.21870562e-01 2.80187905e-01 -9.52184498e-01 1.21870622e-01 2.76797980e-01 -9.53175843e-01 1.21870697e-01 2.73374498e-01 -9.54162896e-01 1.21870644e-01 2.70040810e-01 -9.55112219e-01 1.21870637e-01 2.66813964e-01 -9.56019402e-01 1.21870555e-01 2.63569832e-01 -9.56917703e-01 1.21870629e-01 2.60225147e-01 -9.57835078e-01 1.21870637e-01 2.56890655e-01 -9.58731949e-01 1.21870615e-01 2.53445685e-01 -9.59648550e-01 1.21870726e-01 2.50078768e-01 -9.60532844e-01 1.21870555e-01 2.46739268e-01 -9.61394191e-01 1.21870704e-01 2.43357137e-01 -9.62255418e-01 1.21870555e-01 2.40033522e-01 -9.63089287e-01 1.21870689e-01 2.36639068e-01 -9.63931680e-01 1.21870570e-01 2.33362585e-01 -9.64731157e-01 1.21870644e-01 2.29969233e-01 -9.65545952e-01 1.21870674e-01 2.26588547e-01 -9.66344476e-01 1.21870622e-01 2.23246336e-01 -9.67121661e-01 1.21870644e-01 2.19755232e-01 -9.67919588e-01 1.21870711e-01 2.16374829e-01 -9.68682230e-01 1.21870570e-01 2.13087663e-01 -9.69408333e-01 1.21870622e-01 2.09692523e-01 -9.70149159e-01 1.21870644e-01 2.06319287e-01 -9.70872402e-01 1.21870637e-01 2.02855736e-01 -9.71602976e-01 1.21870689e-01 1.99446261e-01 -9.72308755e-01 1.21870562e-01 1.96144313e-01 -9.72978771e-01 1.21870644e-01 1.92734137e-01 -9.73660231e-01 1.21870629e-01 1.89326227e-01 -9.74328935e-01 1.21870637e-01 1.85846746e-01 -9.74997103e-01 1.21870711e-01 1.82435825e-01 -9.75641608e-01 1.21870555e-01 1.79048255e-01 -9.76267338e-01 1.21870704e-01 1.75619945e-01 -9.76896524e-01 1.21870562e-01 1.72300518e-01 -9.77486849e-01 1.21870615e-01 1.68903053e-01 -9.78074074e-01 1.21870637e-01 1.65484041e-01 -9.78661060e-01 1.21870652e-01 1.62069932e-01 -9.79229987e-01 1.21870652e-01 1.58660710e-01 -9.79789019e-01 1.21870629e-01 1.55252650e-01 -9.80335772e-01 1.21870637e-01 1.51822567e-01 -9.80872750e-01 1.21870652e-01 1.48392081e-01 -9.81394887e-01 1.21870629e-01 1.44911826e-01 -9.81916130e-01 1.21870674e-01 1.41485885e-01 -9.82414484e-01 1.21870592e-01 1.38111711e-01 -9.82895672e-01 1.21870622e-01 1.34570077e-01 -9.83387709e-01 1.21870697e-01 1.31135494e-01 -9.83850420e-01 1.21870555e-01 1.27777606e-01 -9.84293461e-01 1.21870615e-01 1.24359109e-01 -9.84731972e-01 1.21870637e-01 1.20931052e-01 -9.85157013e-01 1.21870637e-01 1.17371991e-01 -9.85587835e-01 1.21870711e-01 1.13936163e-01 -9.85990345e-01 1.21870570e-01 1.10599034e-01 -9.86370862e-01 1.21870622e-01 1.07141517e-01 -9.86752033e-01 1.21870622e-01 1.03717364e-01 -9.87117589e-01 1.21870629e-01 1.00173347e-01 -9.87482071e-01 1.21870682e-01 9.67185423e-02 -9.87828434e-01 1.21870562e-01 9.32849050e-02 -9.88160193e-01 1.21870719e-01 8.98059085e-02 -9.88482118e-01 1.21870548e-01 8.63883793e-02 -9.88786101e-01 1.21870689e-01 8.28396305e-02 -9.89088893e-01 1.21870622e-01 7.94661567e-02 -9.89366353e-01 1.21870548e-01 7.61075541e-02 -9.89629209e-01 1.21870652e-01 7.26503655e-02 -9.89890575e-01 1.21870637e-01 6.92005083e-02 -9.90135312e-01 1.21870637e-01 6.57341406e-02 -9.90373433e-01 1.21870637e-01 6.23038150e-02 -9.90594804e-01 1.21870644e-01 5.88200055e-02 -9.90807474e-01 1.21870637e-01 5.53505793e-02 -9.91008282e-01 1.21870622e-01 5.18989600e-02 -9.91192698e-01 1.21870622e-01 4.84565161e-02 -9.91370022e-01 1.21870622e-01 4.50216755e-02 -9.91531134e-01 1.21870652e-01 4.14383598e-02 -9.91686046e-01 1.21870719e-01 3.79765667e-02 -9.91825104e-01 1.21870548e-01 3.46371010e-02 -9.91947293e-01 1.21870629e-01 3.10693551e-02 -9.92065251e-01 1.21870697e-01 2.75807958e-02 -9.92169559e-01 1.21870570e-01 2.41135936e-02 -9.92261827e-01 1.21870719e-01 2.06423588e-02 -9.92335677e-01 1.21870548e-01 1.73129085e-02 -9.92405891e-01 1.21870652e-01 1.37510030e-02 -9.92451012e-01 1.21870734e-01 1.02583533e-02 -9.92499053e-01 1.21870570e-01 6.90137129e-03 -9.92534697e-01 1.21870637e-01 3.44172562e-03 -9.92551744e-01 1.21870644e-01 -3.88504850e-05 -9.92552817e-01 1.21870667e-01 -3.59176029e-03 -9.92551386e-01 1.21870697e-01 -7.05872476e-03 -9.92533445e-01 1.21870570e-01 -1.05100134e-02 -9.92497146e-01 1.21870704e-01 -1.39668509e-02 -9.92449939e-01 1.21870577e-01 -1.74269322e-02 -9.92405355e-01 1.21870711e-01 -2.09727176e-02 -9.92328763e-01 1.21870652e-01 -2.43697725e-02 -9.92255092e-01 1.21870585e-01 -2.77694520e-02 -9.92164552e-01 1.21870644e-01 -3.12173869e-02 -9.92062628e-01 1.21870659e-01 -3.46771143e-02 -9.91947889e-01 1.21870674e-01 -3.82293873e-02 -9.91815925e-01 1.21870719e-01 -4.17083167e-02 -9.91676450e-01 1.21870577e-01 -4.50650752e-02 -9.91527975e-01 1.21870652e-01 -4.85190079e-02 -9.91367221e-01 1.21870644e-01 -5.19708432e-02 -9.91188884e-01 1.21870644e-01 -5.55043481e-02 -9.91000593e-01 1.21870726e-01 -5.89763112e-02 -9.90799367e-01 1.21870555e-01 -6.24380037e-02 -9.90583837e-01 1.21870697e-01 -6.58871531e-02 -9.90362227e-01 1.21870577e-01 -6.92566484e-02 -9.90131915e-01 1.21870644e-01 -7.27831349e-02 -9.89880323e-01 1.21870711e-01 -7.62645453e-02 -9.89617109e-01 1.21870600e-01 -7.96969011e-02 -9.89347219e-01 1.21870689e-01 -8.31555501e-02 -9.89061952e-01 1.21870577e-01 -8.65365714e-02 -9.88772571e-01 1.21870652e-01 -9.00626108e-02 -9.88457084e-01 1.21870719e-01 -9.35229287e-02 -9.88135576e-01 1.21870562e-01 -9.69501361e-02 -9.87805545e-01 1.21870726e-01 -1.00416459e-01 -9.87460434e-01 1.21870555e-01 -1.03848368e-01 -9.87105012e-01 1.21870726e-01 -1.07407525e-01 -9.86723721e-01 1.21870629e-01 -1.10749312e-01 -9.86354411e-01 1.21870570e-01 -1.14079818e-01 -9.85974073e-01 1.21870652e-01 -1.17548190e-01 -9.85566199e-01 1.21870652e-01 -1.20977163e-01 -9.85152423e-01 1.21870667e-01 -1.24502473e-01 -9.84713256e-01 1.21870711e-01 -1.27973601e-01 -9.84266400e-01 1.21870592e-01 -1.31293893e-01 -9.83831108e-01 1.21870644e-01 -1.34712070e-01 -9.83368576e-01 1.21870652e-01 -1.38143957e-01 -9.82892692e-01 1.21870674e-01 -1.41680241e-01 -9.82387483e-01 1.21870719e-01 -1.45105615e-01 -9.81887519e-01 1.21870577e-01 -1.48518816e-01 -9.81376350e-01 1.21870719e-01 -1.51947856e-01 -9.80854213e-01 1.21870570e-01 -1.55267224e-01 -9.80332017e-01 1.21870652e-01 -1.58715308e-01 -9.79781032e-01 1.21870674e-01 -1.62113264e-01 -9.79225397e-01 1.21870629e-01 -1.65644318e-01 -9.78634119e-01 1.21870719e-01 -1.69067100e-01 -9.78046238e-01 1.21870562e-01 -1.72382176e-01 -9.77471709e-01 1.21870652e-01 -1.75844789e-01 -9.76853967e-01 1.21870674e-01 -1.79251239e-01 -9.76229966e-01 1.21870622e-01 -1.82706729e-01 -9.75592673e-01 1.21870719e-01 -1.86116576e-01 -9.74946320e-01 1.21870548e-01 -1.89418405e-01 -9.74310100e-01 1.21870644e-01 -1.92827672e-01 -9.73641634e-01 1.21870644e-01 -1.96290970e-01 -9.72949624e-01 1.21870704e-01 -1.99723005e-01 -9.72249389e-01 1.21870577e-01 -2.03030959e-01 -9.71564353e-01 1.21870644e-01 -2.06404701e-01 -9.70856190e-01 1.21870659e-01 -2.09877014e-01 -9.70109999e-01 1.21870704e-01 -2.13272229e-01 -9.69366193e-01 1.21870585e-01 -2.16574505e-01 -9.68636930e-01 1.21870644e-01 -2.19955921e-01 -9.67873633e-01 1.21870659e-01 -2.23321691e-01 -9.67102110e-01 1.21870644e-01 -2.26764128e-01 -9.66304660e-01 1.21870704e-01 -2.30152905e-01 -9.65501130e-01 1.21870592e-01 -2.33429953e-01 -9.64715183e-01 1.21870652e-01 -2.36863434e-01 -9.63876426e-01 1.21870704e-01 -2.40236670e-01 -9.63039696e-01 1.21870592e-01 -2.43606091e-01 -9.62191939e-01 1.21870726e-01 -2.46961385e-01 -9.61338818e-01 1.21870577e-01 -2.50216633e-01 -9.60495651e-01 1.21870637e-01 -2.53578395e-01 -9.59614754e-01 1.21870644e-01 -2.57004976e-01 -9.58701611e-01 1.21870726e-01 -2.60450065e-01 -9.57772553e-01 1.21870637e-01 -2.63717473e-01 -9.56876338e-01 1.21870577e-01 -2.66935766e-01 -9.55985665e-01 1.21870674e-01 -2.70306975e-01 -9.55037534e-01 1.21870652e-01 -2.73642182e-01 -9.54085648e-01 1.21870637e-01 -2.76964247e-01 -9.53127980e-01 1.21870644e-01 -2.80277282e-01 -9.52157974e-01 1.21870659e-01 -2.83595979e-01 -9.51176524e-01 1.21870644e-01 -2.86913782e-01 -9.50178087e-01 1.21870644e-01 -2.90224016e-01 -9.49171662e-01 1.21870652e-01 -2.93615818e-01 -9.48131680e-01 1.21870711e-01 -2.96960741e-01 -9.47087288e-01 1.21870592e-01 -3.00261319e-01 -9.46046472e-01 1.21870697e-01 -3.03544313e-01 -9.44999456e-01 1.21870577e-01 -3.06742579e-01 -9.43964839e-01 1.21870652e-01 -3.10117871e-01 -9.42861140e-01 1.21870719e-01 -3.13468665e-01 -9.41752315e-01 1.21870615e-01 -3.16743672e-01 -9.40657854e-01 1.21870659e-01 -3.19979370e-01 -9.39560592e-01 1.21870577e-01 -3.23156804e-01 -9.38472748e-01 1.21870637e-01 -3.26487452e-01 -9.37317669e-01 1.21870659e-01 -3.29744756e-01 -9.36178029e-01 1.21870637e-01 -3.33045065e-01 -9.35008407e-01 1.21870674e-01 -3.36316496e-01 -9.33835685e-01 1.21870555e-01 -3.39578420e-01 -9.32656884e-01 1.21870682e-01 -3.42823625e-01 -9.31461573e-01 1.21870585e-01 -3.45992893e-01 -9.30285394e-01 1.21870652e-01 -3.49244863e-01 -9.29070950e-01 1.21870644e-01 -3.52497488e-01 -9.27847087e-01 1.21870659e-01 -3.55806589e-01 -9.26590443e-01 1.21870711e-01 -3.59136820e-01 -9.25297320e-01 1.21870659e-01 -3.62284154e-01 -9.24073696e-01 1.21870562e-01 -3.65397871e-01 -9.22846198e-01 1.21870629e-01 -3.68628412e-01 -9.21559632e-01 1.21870637e-01 -3.71824294e-01 -9.20275569e-01 1.21870622e-01 -3.75120670e-01 -9.18936074e-01 1.21870719e-01 -3.78419340e-01 -9.17581379e-01 1.21870629e-01 -3.81538004e-01 -9.16290343e-01 1.21870555e-01 -3.84641290e-01 -9.14992511e-01 1.21870659e-01 -3.87834281e-01 -9.13643181e-01 1.21870659e-01 -3.91101360e-01 -9.12245452e-01 1.21870711e-01 -3.94311041e-01 -9.10866618e-01 1.21870540e-01 -3.97474527e-01 -9.09492612e-01 1.21870719e-01 -4.00656134e-01 -9.08094227e-01 1.21870570e-01 -4.03743833e-01 -9.06725883e-01 1.21870659e-01 -4.06897426e-01 -9.05315876e-01 1.21870622e-01 -4.10046756e-01 -9.03892100e-01 1.21870622e-01 -4.13275212e-01 -9.02419686e-01 1.21870689e-01 -4.16425467e-01 -9.00970399e-01 1.21870577e-01 -4.19488400e-01 -8.99549127e-01 1.21870644e-01 -4.22634035e-01 -8.98076117e-01 1.21870629e-01 -4.25848186e-01 -8.96556079e-01 1.21870704e-01 -4.28966641e-01 -8.95066440e-01 1.21870570e-01 -4.32005644e-01 -8.93608868e-01 1.21870637e-01 -4.35142517e-01 -8.92085671e-01 1.21870637e-01 -4.38322425e-01 -8.90523911e-01 1.21870704e-01 -4.41413373e-01 -8.88997912e-01 1.21870577e-01 -4.44426656e-01 -8.87494028e-01 1.21870652e-01 -4.47540432e-01 -8.85929286e-01 1.21870622e-01 -4.50619370e-01 -8.84366870e-01 1.21870644e-01 -4.53782946e-01 -8.82747114e-01 1.21870711e-01 -4.56859082e-01 -8.81156921e-01 1.21870555e-01 -4.59853500e-01 -8.79602194e-01 1.21870637e-01 -4.62913781e-01 -8.77993047e-01 1.21870644e-01 -4.65951115e-01 -8.76384914e-01 1.21870644e-01 -4.69104379e-01 -8.74702156e-01 1.21870667e-01 -4.72184926e-01 -8.73040676e-01 1.21870570e-01 -4.75223213e-01 -8.71393263e-01 1.21870704e-01 -4.78245914e-01 -8.69736791e-01 1.21870555e-01 -4.81296450e-01 -8.68050575e-01 1.21870734e-01 -4.84409094e-01 -8.66318107e-01 1.21870652e-01 -4.87345576e-01 -8.64670932e-01 1.21870585e-01 -4.90337014e-01 -8.62978101e-01 1.21870749e-01 -4.93367881e-01 -8.61249328e-01 1.21870577e-01 -4.96280223e-01 -8.59573364e-01 1.21870622e-01 -4.99290049e-01 -8.57828617e-01 1.21870652e-01 -5.02294779e-01 -8.56073558e-01 1.21870637e-01 -5.05261183e-01 -8.54325116e-01 1.21870644e-01 -5.08239448e-01 -8.52556527e-01 1.21870622e-01 -5.11201084e-01 -8.50784183e-01 1.21870637e-01 -5.14192939e-01 -8.48978877e-01 1.21870667e-01 -5.17227054e-01 -8.47136497e-01 1.21870689e-01 -5.20250440e-01 -8.45280468e-01 1.21870644e-01 -5.23128271e-01 -8.43503296e-01 1.21870577e-01 -5.25976539e-01 -8.41731191e-01 1.21870629e-01 -5.28987288e-01 -8.39840293e-01 1.21870711e-01 -5.31942546e-01 -8.37971628e-01 1.21870540e-01 -5.34848690e-01 -8.36119056e-01 1.21870689e-01 -5.37781715e-01 -8.34236443e-01 1.21870548e-01 -5.40582240e-01 -8.32424164e-01 1.21870622e-01 -5.43555737e-01 -8.30484867e-01 1.21870697e-01 -5.46483219e-01 -8.28564048e-01 1.21870525e-01 -5.49264550e-01 -8.26718450e-01 1.21870644e-01 -5.52165091e-01 -8.24786603e-01 1.21870629e-01 -5.55108786e-01 -8.22810829e-01 1.21870711e-01 -5.57999372e-01 -8.20849061e-01 1.21870533e-01 -5.60774684e-01 -8.18959653e-01 1.21870615e-01 -5.63623369e-01 -8.17000926e-01 1.21870629e-01 -5.66461861e-01 -8.15034926e-01 1.21870659e-01 -5.69388747e-01 -8.12991083e-01 1.21870726e-01 -5.72341979e-01 -8.10919166e-01 1.21870652e-01 -5.75090766e-01 -8.08968484e-01 1.21870533e-01 -5.77794075e-01 -8.07040870e-01 1.21870622e-01 -5.80619514e-01 -8.05006802e-01 1.21870622e-01 -5.83437443e-01 -8.02971125e-01 1.21870629e-01 -5.86323440e-01 -8.00864220e-01 1.21870674e-01 -5.89183629e-01 -7.98762858e-01 1.21870615e-01 -5.91906905e-01 -7.96747208e-01 1.21870555e-01 -5.94598830e-01 -7.94739127e-01 1.21870622e-01 -5.97370207e-01 -7.92659819e-01 1.21870652e-01 -6.00195110e-01 -7.90524662e-01 1.21870711e-01 -6.02977097e-01 -7.88403213e-01 1.21870585e-01 -6.05716646e-01 -7.86299169e-01 1.21870726e-01 -6.08453810e-01 -7.84183741e-01 1.21870570e-01 -6.11117423e-01 -7.82109320e-01 1.21870652e-01 -6.13914430e-01 -7.79916584e-01 1.21870711e-01 -6.16631925e-01 -7.77769983e-01 1.21870585e-01 -6.19340181e-01 -7.75615931e-01 1.21870711e-01 -6.22051656e-01 -7.73441553e-01 1.21870555e-01 -6.24648511e-01 -7.71347940e-01 1.21870629e-01 -6.27350688e-01 -7.69148350e-01 1.21870644e-01 -6.30023658e-01 -7.66962290e-01 1.21870637e-01 -6.32767498e-01 -7.64700770e-01 1.21870704e-01 -6.35437846e-01 -7.62481451e-01 1.21870570e-01 -6.38021469e-01 -7.60322571e-01 1.21870644e-01 -6.40731573e-01 -7.58037388e-01 1.21870741e-01 -6.43383980e-01 -7.55788326e-01 1.21870540e-01 -6.45953178e-01 -7.53594637e-01 1.21870652e-01 -6.48574710e-01 -7.51340032e-01 1.21870629e-01 -6.51198924e-01 -7.49068260e-01 1.21870629e-01 -6.53871357e-01 -7.46733069e-01 1.21870726e-01 -6.56482816e-01 -7.44439840e-01 1.21870562e-01 -6.59001589e-01 -7.42211163e-01 1.21870629e-01 -6.61583245e-01 -7.39910364e-01 1.21870652e-01 -6.64155722e-01 -7.37602234e-01 1.21870622e-01 -6.66795492e-01 -7.35219300e-01 1.21870682e-01 -6.69360280e-01 -7.32880890e-01 1.21870592e-01 -6.71929121e-01 -7.30530262e-01 1.21870697e-01 -6.74474239e-01 -7.28180170e-01 1.21870562e-01 -6.77002311e-01 -7.25828528e-01 1.21870704e-01 -6.79599941e-01 -7.23396778e-01 1.21870644e-01 -6.82065845e-01 -7.21072078e-01 1.21870562e-01 -6.84548020e-01 -7.18720376e-01 1.21870682e-01 -6.87069178e-01 -7.16302097e-01 1.21870555e-01 -6.89495206e-01 -7.13981211e-01 1.21870629e-01 -6.91971362e-01 -7.11579442e-01 1.21870637e-01 -6.94446564e-01 -7.09160209e-01 1.21870637e-01 -6.96988344e-01 -7.06664026e-01 1.21870719e-01 -6.99472845e-01 -7.04207540e-01 1.21870540e-01 -7.01831281e-01 -7.01838255e-01 1.21870659e-01 -7.04286158e-01 -6.99394703e-01 1.21870629e-01 -7.06802905e-01 -6.96848750e-01 1.21870719e-01 -7.09258676e-01 -6.94345832e-01 1.21870540e-01 -7.11590230e-01 -6.91960096e-01 1.21870637e-01 -7.13991642e-01 -6.89484596e-01 1.21870629e-01 -7.16456711e-01 -6.86908007e-01 1.21870697e-01 -7.18922615e-01 -6.84335887e-01 1.21870637e-01 -7.21300900e-01 -6.81823313e-01 1.21870644e-01 -7.23647773e-01 -6.79331601e-01 1.21870510e-01 -7.25921214e-01 -6.76901519e-01 1.21870615e-01 -7.28345513e-01 -6.74295306e-01 1.21870674e-01 -7.30703652e-01 -6.71739817e-01 1.21870540e-01 -7.32983351e-01 -6.69249952e-01 1.21870622e-01 -7.35315561e-01 -6.66688263e-01 1.21870629e-01 -7.37644970e-01 -6.64108694e-01 1.21870615e-01 -7.39953995e-01 -6.61534846e-01 1.21870607e-01 -7.42264330e-01 -6.58943295e-01 1.21870629e-01 -7.44621277e-01 -6.56275988e-01 1.21870674e-01 -7.46902883e-01 -6.53678894e-01 1.21870525e-01 -7.49184132e-01 -6.51063323e-01 1.21870682e-01 -7.51513064e-01 -6.48372769e-01 1.21870615e-01 -7.53715873e-01 -6.45813286e-01 1.21870503e-01 -7.55940199e-01 -6.43206060e-01 1.21870704e-01 -7.58199275e-01 -6.40545011e-01 1.21870540e-01 -7.60364532e-01 -6.37970090e-01 1.21870615e-01 -7.62642145e-01 -6.35247052e-01 1.21870674e-01 -7.64860809e-01 -6.32573009e-01 1.21870533e-01 -7.67006397e-01 -6.29971862e-01 1.21870615e-01 -7.69209862e-01 -6.27275646e-01 1.21870607e-01 -7.71383345e-01 -6.24602497e-01 1.21870615e-01 -7.73611069e-01 -6.21841729e-01 1.21870711e-01 -7.75833189e-01 -6.19067669e-01 1.21870622e-01 -7.78000712e-01 -6.16339564e-01 1.21870637e-01 -7.80097306e-01 -6.13685369e-01 1.21870592e-01 -7.82174170e-01 -6.11036658e-01 1.21870637e-01 -7.84347117e-01 -6.08245313e-01 1.21870697e-01 -7.86463022e-01 -6.05506837e-01 1.21870555e-01 -7.88571775e-01 -6.02756858e-01 1.21870711e-01 -7.90681243e-01 -5.99986792e-01 1.21870540e-01 -7.92698741e-01 -5.97320437e-01 1.21870637e-01 -7.94770002e-01 -5.94557941e-01 1.21870615e-01 -7.96835124e-01 -5.91786325e-01 1.21870644e-01 -7.98951149e-01 -5.88927507e-01 1.21870689e-01 -8.01020265e-01 -5.86110771e-01 1.21870562e-01 -8.03072393e-01 -5.83296955e-01 1.21870704e-01 -8.05156708e-01 -5.80413282e-01 1.21870585e-01 -8.07112813e-01 -5.77695072e-01 1.21870548e-01 -8.09122443e-01 -5.74874938e-01 1.21870689e-01 -8.11134636e-01 -5.72033167e-01 1.21870525e-01 -8.13068807e-01 -5.69279909e-01 1.21870637e-01 -8.15103352e-01 -5.66362679e-01 1.21870719e-01 -8.17085028e-01 -5.63502789e-01 1.21870510e-01 -8.18977356e-01 -5.60747206e-01 1.21870659e-01 -8.20946455e-01 -5.57858765e-01 1.21870607e-01 -8.22896421e-01 -5.54980397e-01 1.21870637e-01 -8.24873388e-01 -5.52035749e-01 1.21870719e-01 -8.26806247e-01 -5.49134970e-01 1.21870562e-01 -8.28713000e-01 -5.46254277e-01 1.21870697e-01 -8.30628216e-01 -5.43337643e-01 1.21870555e-01 -8.32462907e-01 -5.40524423e-01 1.21870629e-01 -8.34328890e-01 -5.37637830e-01 1.21870652e-01 -8.36194336e-01 -5.34732044e-01 1.21870615e-01 -8.38106573e-01 -5.31728506e-01 1.21870689e-01 -8.39951694e-01 -5.28811693e-01 1.21870562e-01 -8.41747463e-01 -5.25945842e-01 1.21870622e-01 -8.43580067e-01 -5.23006916e-01 1.21870622e-01 -8.45396638e-01 -5.20059645e-01 1.21870615e-01 -8.47253978e-01 -5.17034769e-01 1.21870682e-01 -8.49057496e-01 -5.14063418e-01 1.21870570e-01 -8.50835860e-01 -5.11116922e-01 1.21870704e-01 -8.52612197e-01 -5.08144796e-01 1.21870570e-01 -8.54336381e-01 -5.05241573e-01 1.21870629e-01 -8.56125712e-01 -5.02205193e-01 1.21870689e-01 -8.57881963e-01 -4.99197632e-01 1.21870585e-01 -8.59576464e-01 -4.96276319e-01 1.21870644e-01 -8.61291051e-01 -4.93292481e-01 1.21870637e-01 -8.63017619e-01 -4.90264744e-01 1.21870659e-01 -8.64726663e-01 -4.87250745e-01 1.21870644e-01 -8.66420805e-01 -4.84224945e-01 1.21870637e-01 -8.68085146e-01 -4.81233120e-01 1.21870637e-01 -8.69816124e-01 -4.78102177e-01 1.21870719e-01 -8.71493995e-01 -4.75040019e-01 1.21870570e-01 -8.73100221e-01 -4.72076029e-01 1.21870629e-01 -8.74743879e-01 -4.69024152e-01 1.21870652e-01 -8.76427710e-01 -4.65870440e-01 1.21870697e-01 -8.78100038e-01 -4.62710679e-01 1.21870600e-01 -8.79660606e-01 -4.59738493e-01 1.21870548e-01 -8.81210446e-01 -4.56759632e-01 1.21870637e-01 -8.82794857e-01 -4.53691155e-01 1.21870622e-01 -8.84425879e-01 -4.50500280e-01 1.21870704e-01 -8.85990858e-01 -4.47416753e-01 1.21870548e-01 -8.87496114e-01 -4.44420487e-01 1.21870637e-01 -8.89084935e-01 -4.41237420e-01 1.21870689e-01 -8.90632749e-01 -4.38102931e-01 1.21870533e-01 -8.92114103e-01 -4.35081452e-01 1.21870637e-01 -8.93673480e-01 -4.31869626e-01 1.21870711e-01 -8.95211875e-01 -4.28666681e-01 1.21870659e-01 -8.96703124e-01 -4.25538361e-01 1.21870644e-01 -8.98149967e-01 -4.22474802e-01 1.21870548e-01 -8.99571717e-01 -4.19443309e-01 1.21870637e-01 -9.01069283e-01 -4.16215003e-01 1.21870697e-01 -9.02562022e-01 -4.12965775e-01 1.21870629e-01 -9.03955042e-01 -4.09908742e-01 1.21870570e-01 -9.05347228e-01 -4.06825751e-01 1.21870637e-01 -9.06764507e-01 -4.03656095e-01 1.21870652e-01 -9.08200800e-01 -4.00414973e-01 1.21870711e-01 -9.09599304e-01 -3.97231668e-01 1.21870570e-01 -9.10970628e-01 -3.94071907e-01 1.21870734e-01 -9.12350893e-01 -3.90857130e-01 1.21870585e-01 -9.13666546e-01 -3.87777746e-01 1.21870659e-01 -9.15050983e-01 -3.84502679e-01 1.21870726e-01 -9.16390598e-01 -3.81297588e-01 1.21870570e-01 -9.17712510e-01 -3.78103435e-01 1.21870719e-01 -9.19031501e-01 -3.74886602e-01 1.21870555e-01 -9.20304537e-01 -3.71749997e-01 1.21870652e-01 -9.21617627e-01 -3.68480742e-01 1.21870711e-01 -9.22907650e-01 -3.65244120e-01 1.21870570e-01 -9.24175084e-01 -3.62027496e-01 1.21870719e-01 -9.25439835e-01 -3.58762771e-01 1.21870577e-01 -9.26650107e-01 -3.55652273e-01 1.21870644e-01 -9.27911103e-01 -3.52329642e-01 1.21870711e-01 -9.29135859e-01 -3.49071383e-01 1.21870562e-01 -9.30305302e-01 -3.45941871e-01 1.21870637e-01 -9.31535542e-01 -3.42626989e-01 1.21870697e-01 -9.32740211e-01 -3.39352548e-01 1.21870592e-01 -9.33918774e-01 -3.36086273e-01 1.21870697e-01 -9.35089767e-01 -3.32821310e-01 1.21870570e-01 -9.36236203e-01 -3.29576880e-01 1.21870667e-01 -9.37386870e-01 -3.26289058e-01 1.21870562e-01 -9.38492775e-01 -3.23100001e-01 1.21870622e-01 -9.39612269e-01 -3.19826663e-01 1.21870629e-01 -9.40718412e-01 -3.16559643e-01 1.21870637e-01 -9.41841245e-01 -3.13197285e-01 1.21870689e-01 -9.42936301e-01 -3.09886307e-01 1.21870577e-01 -9.43988502e-01 -3.06669712e-01 1.21870637e-01 -9.45079088e-01 -3.03293049e-01 1.21870704e-01 -9.46133614e-01 -2.99988955e-01 1.21870562e-01 -9.47169065e-01 -2.96703190e-01 1.21870704e-01 -9.48202312e-01 -2.93379307e-01 1.21870555e-01 -9.49212193e-01 -2.90094465e-01 1.21870719e-01 -9.50224161e-01 -2.86763459e-01 1.21870533e-01 -9.51188147e-01 -2.83548832e-01 1.21870637e-01 -9.52199757e-01 -2.80137420e-01 1.21870697e-01 -9.53174233e-01 -2.76805937e-01 1.21870555e-01 -9.54109132e-01 -2.73560524e-01 1.21870622e-01 -9.55055833e-01 -2.70238996e-01 1.21870622e-01 -9.56004381e-01 -2.66866624e-01 1.21870629e-01 -9.56922114e-01 -2.63551444e-01 1.21870629e-01 -9.57837343e-01 -2.60216534e-01 1.21870615e-01 -9.58738744e-01 -2.56864160e-01 1.21870629e-01 -9.59651470e-01 -2.53436744e-01 1.21870711e-01 -9.60563898e-01 -2.49956518e-01 1.21870629e-01 -9.61408854e-01 -2.46691138e-01 1.21870555e-01 -9.62233543e-01 -2.43440479e-01 1.21870637e-01 -9.63102043e-01 -2.39985839e-01 1.21870697e-01 -9.63959217e-01 -2.36527011e-01 1.21870622e-01 -9.64758039e-01 -2.33249202e-01 1.21870525e-01 -9.65541422e-01 -2.29984954e-01 1.21870629e-01 -9.66334760e-01 -2.26625100e-01 1.21870629e-01 -9.67140794e-01 -2.23155662e-01 1.21870659e-01 -9.67916906e-01 -2.19764993e-01 1.21870533e-01 -9.68655050e-01 -2.16493264e-01 1.21870629e-01 -9.69424307e-01 -2.13016972e-01 1.21870682e-01 -9.70161617e-01 -2.09629968e-01 1.21870577e-01 -9.70872521e-01 -2.06320390e-01 1.21870622e-01 -9.71585751e-01 -2.02936471e-01 1.21870629e-01 -9.72303510e-01 -1.99475005e-01 1.21870667e-01 -9.73011672e-01 -1.95983946e-01 1.21870637e-01 -9.73673820e-01 -1.92668304e-01 1.21870510e-01 -9.74324584e-01 -1.89352021e-01 1.21870615e-01 -9.74988341e-01 -1.85892060e-01 1.21870659e-01 -9.75649297e-01 -1.82396144e-01 1.21870622e-01 -9.76265728e-01 -1.79055929e-01 1.21870555e-01 -9.76875067e-01 -1.75740272e-01 1.21870629e-01 -9.77483094e-01 -1.72329202e-01 1.21870637e-01 -9.78083313e-01 -1.68853134e-01 1.21870674e-01 -9.78684306e-01 -1.65343791e-01 1.21870644e-01 -9.79240417e-01 -1.62009537e-01 1.21870555e-01 -9.79783833e-01 -1.58695549e-01 1.21870622e-01 -9.80336964e-01 -1.55240446e-01 1.21870607e-01 -9.80884492e-01 -1.51744366e-01 1.21870697e-01 -9.81404305e-01 -1.48338422e-01 1.21870548e-01 -9.81919646e-01 -1.44894391e-01 1.21870697e-01 -9.82417643e-01 -1.41472057e-01 1.21870548e-01 -9.82894540e-01 -1.38130412e-01 1.21870622e-01 -9.83380735e-01 -1.34627566e-01 1.21870697e-01 -9.83846366e-01 -1.31170377e-01 1.21870555e-01 -9.84299302e-01 -1.27735168e-01 1.21870689e-01 -9.84738708e-01 -1.24305159e-01 1.21870540e-01 -9.85155225e-01 -1.20944545e-01 1.21870607e-01 -9.85581875e-01 -1.17417261e-01 1.21870697e-01 -9.85986531e-01 -1.13960221e-01 1.21870548e-01 -9.86380875e-01 -1.10513158e-01 1.21870682e-01 -9.86768484e-01 -1.06994003e-01 1.21870607e-01 -9.87125218e-01 -1.03639007e-01 1.21870548e-01 -9.87476766e-01 -1.00237221e-01 1.21870659e-01 -9.87825990e-01 -9.67485830e-02 1.21870480e-01 -9.88157392e-01 -9.33169797e-02 1.21870533e-01 -9.88477170e-01 -8.98577869e-02 1.21870272e-01 -9.88774180e-01 -8.65301192e-02 1.21870212e-01 -9.89070415e-01 -8.30608159e-02 1.21870086e-01 -9.89355564e-01 -7.95959085e-02 1.21870026e-01 -9.89634156e-01 -7.60282502e-02 1.21870093e-01 -9.89892364e-01 -7.26047680e-02 1.21869683e-01 -9.90131021e-01 -6.92671910e-02 1.21869519e-01 -9.90374744e-01 -6.56994432e-02 1.21869363e-01 -9.90591586e-01 -6.23307601e-02 1.21869221e-01 -9.90727663e-01 -6.00531623e-02 1.21869370e-01 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. 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. 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. 0. 0. 0. -9.82737422e-01 4.53133546e-02 1.79368854e-01 -9.82564032e-01 4.89089377e-02 1.79368347e-01 -9.82417047e-01 5.17902710e-02 1.79367706e-01 -9.82231975e-01 5.51502220e-02 1.79367647e-01 -9.82030809e-01 5.86055927e-02 1.79367572e-01 -9.81826186e-01 6.19111359e-02 1.79367557e-01 -9.81609106e-01 6.52258843e-02 1.79367498e-01 -9.81365621e-01 6.87711611e-02 1.79367498e-01 -9.81115639e-01 7.22851381e-02 1.79367498e-01 -9.80857372e-01 7.56843165e-02 1.79367498e-01 -9.80588436e-01 7.91198909e-02 1.79367498e-01 -9.80303943e-01 8.25539604e-02 1.79367498e-01 -9.80020463e-01 8.58632922e-02 1.79367498e-01 -9.79715407e-01 8.92654881e-02 1.79367498e-01 -9.79389250e-01 9.27856714e-02 1.79367498e-01 -9.79068458e-01 9.61227491e-02 1.79367498e-01 -9.78725195e-01 9.95307192e-02 1.79367498e-01 -9.78363097e-01 1.03045680e-01 1.79367498e-01 -9.77998674e-01 1.06447421e-01 1.79367498e-01 -9.77622628e-01 1.09861039e-01 1.79367498e-01 -9.77236331e-01 1.13225661e-01 1.79367498e-01 -9.76843596e-01 1.16559297e-01 1.79367498e-01 -9.76437330e-01 1.19931974e-01 1.79367498e-01 -9.76003647e-01 1.23410910e-01 1.79367498e-01 -9.75553453e-01 1.26911074e-01 1.79367498e-01 -9.75117922e-01 1.30219132e-01 1.79367498e-01 -9.74658728e-01 1.33613199e-01 1.79367498e-01 -9.74172235e-01 1.37115061e-01 1.79367498e-01 -9.73703504e-01 1.40407518e-01 1.79367498e-01 -9.73204792e-01 1.43812716e-01 1.79367498e-01 -9.72697794e-01 1.47209167e-01 1.79367498e-01 -9.72194195e-01 1.50502041e-01 1.79367498e-01 -9.71648335e-01 1.53979197e-01 1.79367498e-01 -9.71089363e-01 1.57471836e-01 1.79367498e-01 -9.70530450e-01 1.60883546e-01 1.79367498e-01 -9.69961405e-01 1.64282307e-01 1.79367498e-01 -9.69385386e-01 1.67637318e-01 1.79367498e-01 -9.68796134e-01 1.71036303e-01 1.79367498e-01 -9.68190372e-01 1.74429640e-01 1.79367498e-01 -9.67565060e-01 1.77836135e-01 1.79367498e-01 -9.66960490e-01 1.81111887e-01 1.79367498e-01 -9.66351330e-01 1.84328586e-01 1.79367498e-01 -9.65680599e-01 1.87796190e-01 1.79367498e-01 -9.64996696e-01 1.91290051e-01 1.79367498e-01 -9.64326680e-01 1.94645971e-01 1.79367498e-01 -9.63637233e-01 1.98031500e-01 1.79367498e-01 -9.62939203e-01 2.01390386e-01 1.79367498e-01 -9.62249160e-01 2.04673484e-01 1.79367498e-01 -9.61529493e-01 2.08024010e-01 1.79367498e-01 -9.60775077e-01 2.11471841e-01 1.79367498e-01 -9.60048735e-01 2.14758545e-01 1.79367498e-01 -9.59292710e-01 2.18096837e-01 1.79367498e-01 -9.58505929e-01 2.21541122e-01 1.79367498e-01 -9.57726002e-01 2.24890277e-01 1.79367498e-01 -9.56932127e-01 2.28248477e-01 1.79367498e-01 -9.56158042e-01 2.31474400e-01 1.79367498e-01 -9.55370605e-01 2.34690785e-01 1.79367498e-01 -9.54512060e-01 2.38147408e-01 1.79367498e-01 -9.53653157e-01 2.41569966e-01 1.79367498e-01 -9.52801585e-01 2.44913489e-01 1.79367498e-01 -9.51962233e-01 2.48157352e-01 1.79367498e-01 -9.51102555e-01 2.51433909e-01 1.79367498e-01 -9.50208843e-01 2.54790813e-01 1.79367498e-01 -9.49307442e-01 2.58125007e-01 1.79367498e-01 -9.48380828e-01 2.61503875e-01 1.79367498e-01 -9.47483063e-01 2.64751166e-01 1.79367498e-01 -9.46585357e-01 2.67933995e-01 1.79367498e-01 -9.45621669e-01 2.71310449e-01 1.79367498e-01 -9.44634855e-01 2.74729729e-01 1.79367498e-01 -9.43680823e-01 2.77989179e-01 1.79367498e-01 -9.42716658e-01 2.81246692e-01 1.79367498e-01 -9.41724122e-01 2.84542173e-01 1.79367498e-01 -9.40742433e-01 2.87779540e-01 1.79367498e-01 -9.39732909e-01 2.91055977e-01 1.79367498e-01 -9.38679039e-01 2.94439703e-01 1.79367498e-01 -9.37668800e-01 2.97640115e-01 1.79367498e-01 -9.36634004e-01 3.00878942e-01 1.79367498e-01 -9.35549796e-01 3.04232836e-01 1.79367498e-01 -9.34478819e-01 3.07505578e-01 1.79367498e-01 -9.33399916e-01 3.10766160e-01 1.79367498e-01 -9.32308018e-01 3.14035982e-01 1.79367498e-01 -9.31232512e-01 3.17202330e-01 1.79367498e-01 -9.30146933e-01 3.20377082e-01 1.79367498e-01 -9.28999007e-01 3.23681802e-01 1.79367498e-01 -9.27830577e-01 3.27017993e-01 1.79367498e-01 -9.26719487e-01 3.30164045e-01 1.79367498e-01 -9.25556600e-01 3.33399683e-01 1.79367498e-01 -9.24364328e-01 3.36697072e-01 1.79367498e-01 -9.23177063e-01 3.39919627e-01 1.79367498e-01 -9.21983838e-01 3.43132317e-01 1.79367498e-01 -9.20806468e-01 3.46282095e-01 1.79367498e-01 -9.19633329e-01 3.49398166e-01 1.79367498e-01 -9.18386638e-01 3.52683544e-01 1.79367498e-01 -9.17101502e-01 3.55993241e-01 1.79367498e-01 -9.15854514e-01 3.59198540e-01 1.79367498e-01 -9.14599001e-01 3.62382948e-01 1.79367498e-01 -9.13327932e-01 3.65573317e-01 1.79367498e-01 -9.12045956e-01 3.68758082e-01 1.79367498e-01 -9.10758376e-01 3.71929556e-01 1.79367498e-01 -9.09451723e-01 3.75108331e-01 1.79367498e-01 -9.08166349e-01 3.78213316e-01 1.79367498e-01 -9.06881213e-01 3.81284714e-01 1.79367498e-01 -9.05510962e-01 3.84524286e-01 1.79367498e-01 -9.04126227e-01 3.87767673e-01 1.79367498e-01 -9.02784646e-01 3.90883088e-01 1.79367498e-01 -9.01427388e-01 3.94008517e-01 1.79367498e-01 -9.00057971e-01 3.97124141e-01 1.79367498e-01 -8.98681939e-01 4.00226921e-01 1.79367498e-01 -8.97249341e-01 4.03430402e-01 1.79367498e-01 -8.95805776e-01 4.06624287e-01 1.79367498e-01 -8.94416153e-01 4.09669071e-01 1.79367498e-01 -8.92991662e-01 4.12765115e-01 1.79367498e-01 -8.91512752e-01 4.15948957e-01 1.79367498e-01 -8.90063584e-01 4.19043154e-01 1.79367498e-01 -8.88605595e-01 4.22128558e-01 1.79367498e-01 -8.87120545e-01 4.25235838e-01 1.79367498e-01 -8.85681927e-01 4.28235233e-01 1.79367498e-01 -8.84159505e-01 4.31365818e-01 1.79367498e-01 -8.82594228e-01 4.34556156e-01 1.79367498e-01 -8.81092966e-01 4.37593699e-01 1.79367498e-01 -8.79552841e-01 4.40677345e-01 1.79367498e-01 -8.78009260e-01 4.43748295e-01 1.79367498e-01 -8.76499116e-01 4.46726412e-01 1.79367498e-01 -8.74974132e-01 4.49703246e-01 1.79367498e-01 -8.73363614e-01 4.52821195e-01 1.79367498e-01 -8.71737421e-01 4.55948442e-01 1.79367498e-01 -8.70173693e-01 4.58926052e-01 1.79367498e-01 -8.68575633e-01 4.61939126e-01 1.79367498e-01 -8.66925895e-01 4.65029150e-01 1.79367498e-01 -8.65294337e-01 4.68056768e-01 1.79367498e-01 -8.63652110e-01 4.71085608e-01 1.79367498e-01 -8.61993134e-01 4.74110365e-01 1.79367498e-01 -8.60377789e-01 4.77031708e-01 1.79367498e-01 -8.58721912e-01 4.80007499e-01 1.79367498e-01 -8.57005954e-01 4.83068377e-01 1.79367498e-01 -8.55307341e-01 4.86066401e-01 1.79367498e-01 -8.53603959e-01 4.89055723e-01 1.79367498e-01 -8.51900458e-01 4.92018759e-01 1.79367498e-01 -8.50177407e-01 4.94987607e-01 1.79367498e-01 -8.48447382e-01 4.97946978e-01 1.79367498e-01 -8.46702695e-01 5.00907123e-01 1.79367498e-01 -8.44992518e-01 5.03789485e-01 1.79367498e-01 -8.43257427e-01 5.06686985e-01 1.79367498e-01 -8.41433227e-01 5.09705901e-01 1.79367498e-01 -8.39630067e-01 5.12676954e-01 1.79367498e-01 -8.37838471e-01 5.15594065e-01 1.79367498e-01 -8.36020231e-01 5.18541873e-01 1.79367498e-01 -8.34218681e-01 5.21432996e-01 1.79367498e-01 -8.32431853e-01 5.24283350e-01 1.79367498e-01 -8.30585837e-01 5.27198792e-01 1.79367498e-01 -8.28691840e-01 5.30173182e-01 1.79367498e-01 -8.26889396e-01 5.32979071e-01 1.79367498e-01 -8.25033963e-01 5.35843670e-01 1.79367498e-01 -8.23132396e-01 5.38762987e-01 1.79367498e-01 -8.21243346e-01 5.41637897e-01 1.79367498e-01 -8.19326341e-01 5.44531524e-01 1.79367498e-01 -8.17421257e-01 5.47390103e-01 1.79367498e-01 -8.15569460e-01 5.50148189e-01 1.79367512e-01 -8.13629150e-01 5.53009927e-01 1.79367498e-01 -8.11627626e-01 5.55944443e-01 1.79367498e-01 -8.09696257e-01 5.58756113e-01 1.79367498e-01 -8.07784855e-01 5.61515033e-01 1.79367512e-01 -8.05839479e-01 5.64298272e-01 1.79367498e-01 -8.03815901e-01 5.67182958e-01 1.79367498e-01 -8.01829398e-01 5.69983602e-01 1.79367498e-01 -7.99816310e-01 5.72808027e-01 1.79367498e-01 -7.97864377e-01 5.75521052e-01 1.79367527e-01 -7.95889556e-01 5.78251362e-01 1.79367498e-01 -7.93797612e-01 5.81117690e-01 1.79367498e-01 -7.91720450e-01 5.83945990e-01 1.79367498e-01 -7.89676130e-01 5.86706519e-01 1.79367498e-01 -7.87616313e-01 5.89469194e-01 1.79367498e-01 -7.85562038e-01 5.92204869e-01 1.79367498e-01 -7.83502638e-01 5.94927490e-01 1.79367498e-01 -7.81435013e-01 5.97640932e-01 1.79367498e-01 -7.79318571e-01 6.00396276e-01 1.79367498e-01 -7.77283251e-01 6.03030086e-01 1.79367512e-01 -7.75173604e-01 6.05736315e-01 1.79367498e-01 -7.72972465e-01 6.08546615e-01 1.79367498e-01 -7.70850301e-01 6.11230969e-01 1.79367498e-01 -7.68706322e-01 6.13928437e-01 1.79367498e-01 -7.66555607e-01 6.16609454e-01 1.79367498e-01 -7.64417648e-01 6.19257867e-01 1.79367498e-01 -7.62326300e-01 6.21828437e-01 1.79367527e-01 -7.60147512e-01 6.24491930e-01 1.79367498e-01 -7.57899642e-01 6.27218187e-01 1.79367498e-01 -7.55766988e-01 6.29788160e-01 1.79367557e-01 -7.53558457e-01 6.32425368e-01 1.79367498e-01 -7.51298010e-01 6.35112107e-01 1.79367512e-01 -7.49084532e-01 6.37718558e-01 1.79367498e-01 -7.46821821e-01 6.40368760e-01 1.79367498e-01 -7.44596422e-01 6.42956018e-01 1.79367498e-01 -7.42418289e-01 6.45469308e-01 1.79367498e-01 -7.40136325e-01 6.48081422e-01 1.79367498e-01 -7.37774372e-01 6.50770545e-01 1.79367498e-01 -7.35500753e-01 6.53339684e-01 1.79367498e-01 -7.33216584e-01 6.55903161e-01 1.79367498e-01 -7.30937541e-01 6.58440053e-01 1.79367498e-01 -7.28635132e-01 6.60990357e-01 1.79367498e-01 -7.26324916e-01 6.63522959e-01 1.79367498e-01 -7.24013448e-01 6.66049182e-01 1.79367498e-01 -7.21736729e-01 6.68515503e-01 1.79367498e-01 -7.19400585e-01 6.71024799e-01 1.79367498e-01 -7.16973662e-01 6.73619330e-01 1.79367453e-01 -7.14633942e-01 6.76100194e-01 1.79367498e-01 -7.12256789e-01 6.78604066e-01 1.79367498e-01 -7.09885120e-01 6.81079566e-01 1.79367498e-01 -7.07502007e-01 6.83567166e-01 1.79367498e-01 -7.05173016e-01 6.85968757e-01 1.79367498e-01 -7.02772677e-01 6.88423097e-01 1.79367498e-01 -7.00315773e-01 6.90924942e-01 1.79367498e-01 -6.97936118e-01 6.93331838e-01 1.79367498e-01 -6.95520818e-01 6.95735157e-01 1.79367498e-01 -6.93038404e-01 6.98225856e-01 1.79367498e-01 -6.90598011e-01 7.00639486e-01 1.79367498e-01 -6.88139379e-01 7.03051567e-01 1.79367498e-01 -6.85711443e-01 7.05424011e-01 1.79367498e-01 -6.83311045e-01 7.07748890e-01 1.79367498e-01 -6.80827200e-01 7.10128188e-01 1.79367498e-01 -6.78262651e-01 7.12585092e-01 1.79367498e-01 -6.75774455e-01 7.14940250e-01 1.79367498e-01 -6.73261762e-01 7.17307389e-01 1.79367498e-01 -6.70760572e-01 7.19644666e-01 1.79367498e-01 -6.68266952e-01 7.21965373e-01 1.79367498e-01 -6.65724039e-01 7.24311829e-01 1.79367498e-01 -6.63187087e-01 7.26632655e-01 1.79367498e-01 -6.60651684e-01 7.28941262e-01 1.79367498e-01 -6.58156931e-01 7.31194437e-01 1.79367498e-01 -6.55618191e-01 7.33468533e-01 1.79367498e-01 -6.53003812e-01 7.35800445e-01 1.79367498e-01 -6.50414705e-01 7.38088429e-01 1.79367498e-01 -6.47839606e-01 7.40347803e-01 1.79367498e-01 -6.45243645e-01 7.42614269e-01 1.79367498e-01 -6.42707288e-01 7.44810581e-01 1.79367498e-01 -6.40095532e-01 7.47054040e-01 1.79367498e-01 -6.37432754e-01 7.49328613e-01 1.79367498e-01 -6.34856641e-01 7.51514018e-01 1.79367498e-01 -6.32240295e-01 7.53712595e-01 1.79367498e-01 -6.29550695e-01 7.55962968e-01 1.79367498e-01 -6.26929343e-01 7.58137524e-01 1.79367498e-01 -6.24253213e-01 7.60344386e-01 1.79367498e-01 -6.21659160e-01 7.62464404e-01 1.79367498e-01 -6.19014502e-01 7.64614642e-01 1.79367498e-01 -6.16253257e-01 7.66840994e-01 1.79367498e-01 -6.13641858e-01 7.68932402e-01 1.79367498e-01 -6.10937893e-01 7.71081388e-01 1.79367498e-01 -6.08254611e-01 7.73201883e-01 1.79367498e-01 -6.05574310e-01 7.75300562e-01 1.79367498e-01 -6.02779746e-01 7.77477384e-01 1.79367498e-01 -6.00109756e-01 7.79540718e-01 1.79367498e-01 -5.97426772e-01 7.81597078e-01 1.79367498e-01 -5.94664514e-01 7.83701718e-01 1.79367498e-01 -5.91932476e-01 7.85767794e-01 1.79367498e-01 -5.89193583e-01 7.87822664e-01 1.79367498e-01 -5.86443722e-01 7.89870083e-01 1.79367498e-01 -5.83580136e-01 7.91988254e-01 1.79367498e-01 -5.80829084e-01 7.94008493e-01 1.79367498e-01 -5.78133047e-01 7.95977056e-01 1.79367512e-01 -5.75378776e-01 7.97965825e-01 1.79367498e-01 -5.72528422e-01 8.00015509e-01 1.79367498e-01 -5.69745600e-01 8.02001357e-01 1.79367498e-01 -5.66977561e-01 8.03960621e-01 1.79367498e-01 -5.64151883e-01 8.05944145e-01 1.79367498e-01 -5.61339915e-01 8.07903171e-01 1.79367498e-01 -5.58455169e-01 8.09901595e-01 1.79367498e-01 -5.55614889e-01 8.11853409e-01 1.79367498e-01 -5.52839816e-01 8.13743174e-01 1.79367498e-01 -5.50067782e-01 8.15622449e-01 1.79367498e-01 -5.47144771e-01 8.17584515e-01 1.79367498e-01 -5.44279754e-01 8.19494545e-01 1.79367498e-01 -5.41450322e-01 8.21367025e-01 1.79367498e-01 -5.38561106e-01 8.23264360e-01 1.79367498e-01 -5.35735607e-01 8.25104296e-01 1.79367498e-01 -5.32763720e-01 8.27027678e-01 1.79367498e-01 -5.29845893e-01 8.28899801e-01 1.79367498e-01 -5.26946247e-01 8.30746531e-01 1.79367498e-01 -5.24022520e-01 8.32595050e-01 1.79367498e-01 -5.21108329e-01 8.34420621e-01 1.79367498e-01 -5.18292487e-01 8.36174548e-01 1.79367498e-01 -5.15353441e-01 8.37986648e-01 1.79367498e-01 -5.12322485e-01 8.39845598e-01 1.79367498e-01 -5.09371817e-01 8.41636002e-01 1.79367498e-01 -5.06537020e-01 8.43346536e-01 1.79367498e-01 -5.03604412e-01 8.45100164e-01 1.79367498e-01 -5.00532985e-01 8.46923590e-01 1.79367498e-01 -4.97673690e-01 8.48608255e-01 1.79367498e-01 -4.94723290e-01 8.50330174e-01 1.79367498e-01 -4.91735369e-01 8.52063775e-01 1.79367498e-01 -4.88781571e-01 8.53758395e-01 1.79367498e-01 -4.85697716e-01 8.55518460e-01 1.79367498e-01 -4.82745588e-01 8.57189059e-01 1.79367498e-01 -4.79841352e-01 8.58815074e-01 1.79367498e-01 -4.76800770e-01 8.60506177e-01 1.79367498e-01 -4.73718822e-01 8.62209439e-01 1.79367498e-01 -4.70804065e-01 8.63805950e-01 1.79367498e-01 -4.67787892e-01 8.65439057e-01 1.79367498e-01 -4.64713126e-01 8.67096066e-01 1.79367498e-01 -4.61733401e-01 8.68686318e-01 1.79367498e-01 -4.58689183e-01 8.70298743e-01 1.79367498e-01 -4.55679744e-01 8.71876299e-01 1.79367498e-01 -4.52566147e-01 8.73496354e-01 1.79367498e-01 -4.49487627e-01 8.75086129e-01 1.79367498e-01 -4.46430624e-01 8.76648486e-01 1.79367498e-01 -4.43424642e-01 8.78174067e-01 1.79367498e-01 -4.40366387e-01 8.79710257e-01 1.79367498e-01 -4.37245339e-01 8.81266654e-01 1.79367498e-01 -4.34144914e-01 8.82796764e-01 1.79367498e-01 -4.31119889e-01 8.84279728e-01 1.79367498e-01 -4.28051263e-01 8.85768712e-01 1.79367498e-01 -4.24876988e-01 8.87293696e-01 1.79367498e-01 -4.21772391e-01 8.88774157e-01 1.79367498e-01 -4.18689132e-01 8.90231311e-01 1.79367498e-01 -4.15647328e-01 8.91656399e-01 1.79367498e-01 -4.12501812e-01 8.93114328e-01 1.79367498e-01 -4.09312516e-01 8.94579768e-01 1.79367498e-01 -4.06193733e-01 8.96001518e-01 1.79367498e-01 -4.03167486e-01 8.97368789e-01 1.79367498e-01 -4.00059164e-01 8.98757339e-01 1.79367498e-01 -3.96827370e-01 9.00189519e-01 1.79367498e-01 -3.93741876e-01 9.01545882e-01 1.79367498e-01 -3.90585303e-01 9.02914345e-01 1.79367498e-01 -3.87420058e-01 9.04275239e-01 1.79367498e-01 -3.84371817e-01 9.05576825e-01 1.79367498e-01 -3.81175846e-01 9.06928658e-01 1.79367498e-01 -3.77952963e-01 9.08274829e-01 1.79367498e-01 -3.74700040e-01 9.09620702e-01 1.79367498e-01 -3.71515006e-01 9.10927773e-01 1.79367498e-01 -3.68355811e-01 9.12209988e-01 1.79367498e-01 -3.65213722e-01 9.13472116e-01 1.79367498e-01 -3.62027109e-01 9.14740086e-01 1.79367498e-01 -3.58780116e-01 9.16018963e-01 1.79367498e-01 -3.55568051e-01 9.17264760e-01 1.79367498e-01 -3.52454215e-01 9.18478251e-01 1.79367498e-01 -3.49263787e-01 9.19684470e-01 1.79367498e-01 -3.45977962e-01 9.20920968e-01 1.79367498e-01 -3.42721403e-01 9.22136605e-01 1.79367498e-01 -3.39607269e-01 9.23292160e-01 1.79367498e-01 -3.36475223e-01 9.24446523e-01 1.79367498e-01 -3.33158165e-01 9.25642490e-01 1.79367498e-01 -3.29907477e-01 9.26811278e-01 1.79367498e-01 -3.26698393e-01 9.27943647e-01 1.79367498e-01 -3.23468298e-01 9.29075599e-01 1.79367498e-01 -3.20243239e-01 9.30191994e-01 1.79367498e-01 -3.16917211e-01 9.31329548e-01 1.79367498e-01 -3.13729793e-01 9.32411015e-01 1.79367498e-01 -3.10442775e-01 9.33507204e-01 1.79367498e-01 -3.07180136e-01 9.34586287e-01 1.79367498e-01 -3.03903282e-01 9.35656428e-01 1.79367498e-01 -3.00672710e-01 9.36702371e-01 1.79367498e-01 -2.97395289e-01 9.37746823e-01 1.79367498e-01 -2.94056833e-01 9.38798249e-01 1.79367498e-01 -2.90765494e-01 9.39822674e-01 1.79367498e-01 -2.87470162e-01 9.40835595e-01 1.79367498e-01 -2.84201145e-01 9.41828132e-01 1.79367498e-01 -2.80939311e-01 9.42807257e-01 1.79367498e-01 -2.77622551e-01 9.43790317e-01 1.79367498e-01 -2.74329931e-01 9.44752216e-01 1.79367498e-01 -2.71104425e-01 9.45682943e-01 1.79367498e-01 -2.67786950e-01 9.46627200e-01 1.79367498e-01 -2.64426112e-01 9.47571695e-01 1.79367498e-01 -2.61116177e-01 9.48488653e-01 1.79367498e-01 -2.57874250e-01 9.49378192e-01 1.79367498e-01 -2.54645586e-01 9.50247645e-01 1.79367498e-01 -2.51252502e-01 9.51149046e-01 1.79367498e-01 -2.47920275e-01 9.52024221e-01 1.79367498e-01 -2.44627729e-01 9.52874541e-01 1.79367498e-01 -2.41283387e-01 9.53726411e-01 1.79367498e-01 -2.37940505e-01 9.54565048e-01 1.79367498e-01 -2.34495386e-01 9.55420196e-01 1.79367498e-01 -2.31249496e-01 9.56211805e-01 1.79367498e-01 -2.27910459e-01 9.57011819e-01 1.79367498e-01 -2.24584594e-01 9.57797587e-01 1.79367498e-01 -2.21271411e-01 9.58567381e-01 1.79367498e-01 -2.17897549e-01 9.59341049e-01 1.79367498e-01 -2.14655787e-01 9.60071564e-01 1.79367498e-01 -2.11191297e-01 9.60838139e-01 1.79367498e-01 -2.07737520e-01 9.61591721e-01 1.79367498e-01 -2.04379305e-01 9.62310553e-01 1.79367498e-01 -2.01032713e-01 9.63016152e-01 1.79367498e-01 -1.97760627e-01 9.63693380e-01 1.79367498e-01 -1.94379911e-01 9.64378536e-01 1.79367498e-01 -1.90905765e-01 9.65073526e-01 1.79367498e-01 -1.87522560e-01 9.65736926e-01 1.79367498e-01 -1.84185848e-01 9.66379642e-01 1.79367498e-01 -1.80868119e-01 9.67005730e-01 1.79367498e-01 -1.77535489e-01 9.67619956e-01 1.79367498e-01 -1.74138591e-01 9.68245149e-01 1.79367498e-01 -1.70756295e-01 9.68846321e-01 1.79367498e-01 -1.67286441e-01 9.69446659e-01 1.79367498e-01 -1.63994238e-01 9.70011711e-01 1.79367498e-01 -1.60599247e-01 9.70577419e-01 1.79367498e-01 -1.57185182e-01 9.71135855e-01 1.79367498e-01 -1.53813407e-01 9.71675515e-01 1.79367498e-01 -1.50339708e-01 9.72219169e-01 1.79367498e-01 -1.47042319e-01 9.72723663e-01 1.79367498e-01 -1.43629268e-01 9.73232806e-01 1.79367498e-01 -1.40226915e-01 9.73729074e-01 1.79367498e-01 -1.36819273e-01 9.74215031e-01 1.79367498e-01 -1.33327782e-01 9.74699974e-01 1.79367498e-01 -1.29997641e-01 9.75146830e-01 1.79367498e-01 -1.26614764e-01 9.75592434e-01 1.79367498e-01 -1.23088628e-01 9.76044595e-01 1.79367498e-01 -1.19720295e-01 9.76461947e-01 1.79367498e-01 -1.16381884e-01 9.76865172e-01 1.79367498e-01 -1.13075547e-01 9.77252960e-01 1.79367498e-01 -1.09556571e-01 9.77654517e-01 1.79367498e-01 -1.06066510e-01 9.78038609e-01 1.79367498e-01 -1.02621943e-01 9.78406489e-01 1.79367498e-01 -9.92050096e-02 9.78757739e-01 1.79367498e-01 -9.58848968e-02 9.79091227e-01 1.79367498e-01 -9.24864039e-02 9.79417026e-01 1.79367498e-01 -8.90781805e-02 9.79734421e-01 1.79367498e-01 -8.56522098e-02 9.80038881e-01 1.79367498e-01 -8.21202695e-02 9.80341136e-01 1.79367498e-01 -7.88102299e-02 9.80614126e-01 1.79367498e-01 -7.53946453e-02 9.80879962e-01 1.79367498e-01 -7.19585046e-02 9.81140196e-01 1.79367498e-01 -6.85077533e-02 9.81384158e-01 1.79367498e-01 -6.49904609e-02 9.81625617e-01 1.79367498e-01 -6.15578145e-02 9.81844425e-01 1.79367498e-01 -5.81264049e-02 9.82054770e-01 1.79367498e-01 -5.47766872e-02 9.82249141e-01 1.79367498e-01 -5.13677821e-02 9.82429385e-01 1.79367498e-01 -4.79263067e-02 9.82606828e-01 1.79367498e-01 -4.46011983e-02 9.82762396e-01 1.79367498e-01 -4.10856791e-02 9.82914031e-01 1.79367498e-01 -3.75572294e-02 9.83056545e-01 1.79367498e-01 -3.41091193e-02 9.83182073e-01 1.79367498e-01 -3.06765884e-02 9.83295560e-01 1.79367498e-01 -2.73421779e-02 9.83394325e-01 1.79367498e-01 -2.40035374e-02 9.83483315e-01 1.79367498e-01 -2.04557274e-02 9.83558118e-01 1.79367498e-01 -1.69282574e-02 9.83632922e-01 1.79367498e-01 -1.35063268e-02 9.83678818e-01 1.79367498e-01 -1.01857260e-02 9.83721018e-01 1.79367498e-01 -6.74577104e-03 9.83756959e-01 1.79367498e-01 -3.28092277e-03 9.83774066e-01 1.79367498e-01 1.24369151e-04 9.83774424e-01 1.79367498e-01 3.65776336e-03 9.83773649e-01 1.79367498e-01 6.99726259e-03 9.83753502e-01 1.79367498e-01 1.04463464e-02 9.83718276e-01 1.79367498e-01 1.38738118e-02 9.83674228e-01 1.79367498e-01 1.72954928e-02 9.83626783e-01 1.79367498e-01 2.07641833e-02 9.83555257e-01 1.79367498e-01 2.40914617e-02 9.83480155e-01 1.79367498e-01 2.76030526e-02 9.83387589e-01 1.79367498e-01 3.11161596e-02 9.83282208e-01 1.79367498e-01 3.45595330e-02 9.83168185e-01 1.79367498e-01 3.79778855e-02 9.83041763e-01 1.79367498e-01 4.13281769e-02 9.82908487e-01 1.79367498e-01 4.47601266e-02 9.82753992e-01 1.79367498e-01 4.82824035e-02 9.82589424e-01 1.79367498e-01 5.16964123e-02 9.82412159e-01 1.79367498e-01 5.51117286e-02 9.82229888e-01 1.79367498e-01 5.84533438e-02 9.82038021e-01 1.79367498e-01 6.18842244e-02 9.81822789e-01 1.79367498e-01 6.54212609e-02 9.81595814e-01 1.79367498e-01 6.88580424e-02 9.81360018e-01 1.79367498e-01 7.22919479e-02 9.81115341e-01 1.79367498e-01 7.56096542e-02 9.80864465e-01 1.79367498e-01 7.90347904e-02 9.80592906e-01 1.79367498e-01 8.24773014e-02 9.80311632e-01 1.79367498e-01 8.58551264e-02 9.80019510e-01 1.79367498e-01 8.94134194e-02 9.79702055e-01 1.79367498e-01 9.27317962e-02 9.79393959e-01 1.79367498e-01 9.61306393e-02 9.79065657e-01 1.79367498e-01 9.95680913e-02 9.78723824e-01 1.79367498e-01 1.02971196e-01 9.78369236e-01 1.79367498e-01 1.06398307e-01 9.78004992e-01 1.79367498e-01 1.09788232e-01 9.77629066e-01 1.79367498e-01 1.13324381e-01 9.77223754e-01 1.79367498e-01 1.16721354e-01 9.76823807e-01 1.79367498e-01 1.20113701e-01 9.76413846e-01 1.79367498e-01 1.23473264e-01 9.75997448e-01 1.79367498e-01 1.26778886e-01 9.75570917e-01 1.79367498e-01 1.30258843e-01 9.75112319e-01 1.79367498e-01 1.33728847e-01 9.74643230e-01 1.79367498e-01 1.37158066e-01 9.74167824e-01 1.79367498e-01 1.40555292e-01 9.73681152e-01 1.79367498e-01 1.43885463e-01 9.73195434e-01 1.79367498e-01 1.47244483e-01 9.72690821e-01 1.79367498e-01 1.50672749e-01 9.72168684e-01 1.79367498e-01 1.54055119e-01 9.71636236e-01 1.79367498e-01 1.57543302e-01 9.71077442e-01 1.79367498e-01 1.60840437e-01 9.70538318e-01 1.79367498e-01 1.64213493e-01 9.69972312e-01 1.79367498e-01 1.67583942e-01 9.69395459e-01 1.79367498e-01 1.70917764e-01 9.68816996e-01 1.79367498e-01 1.74347609e-01 9.68204021e-01 1.79367498e-01 1.77833408e-01 9.67566729e-01 1.79367498e-01 1.81210801e-01 9.66940522e-01 1.79367498e-01 1.84466228e-01 9.66324925e-01 1.79367498e-01 1.87871054e-01 9.65667784e-01 1.79367498e-01 1.91245049e-01 9.65007782e-01 1.79367498e-01 1.94513619e-01 9.64351714e-01 1.79367498e-01 1.97959840e-01 9.63651180e-01 1.79367498e-01 2.01408133e-01 9.62935865e-01 1.79367498e-01 2.04768702e-01 9.62228537e-01 1.79367498e-01 2.08125859e-01 9.61507380e-01 1.79367498e-01 2.11391509e-01 9.60793257e-01 1.79367498e-01 2.14742824e-01 9.60052133e-01 1.79367498e-01 2.18188643e-01 9.59272623e-01 1.79367498e-01 2.21542805e-01 9.58505690e-01 1.79367498e-01 2.24890366e-01 9.57726836e-01 1.79367498e-01 2.28148594e-01 9.56955671e-01 1.79367498e-01 2.31391415e-01 9.56178188e-01 1.79367498e-01 2.34752476e-01 9.55355585e-01 1.79367498e-01 2.38135755e-01 9.54516113e-01 1.79367498e-01 2.41547823e-01 9.53659058e-01 1.79367498e-01 2.44811654e-01 9.52829123e-01 1.79367498e-01 2.48129562e-01 9.51967895e-01 1.79367498e-01 2.51455873e-01 9.51097250e-01 1.79367498e-01 2.54749268e-01 9.50218260e-01 1.79367498e-01 2.58162022e-01 9.49298084e-01 1.79367498e-01 2.61403412e-01 9.48410153e-01 1.79367498e-01 2.64705032e-01 9.47492599e-01 1.79367498e-01 2.68037975e-01 9.46556628e-01 1.79367498e-01 2.71314114e-01 9.45621014e-01 1.79367498e-01 2.74698555e-01 9.44644392e-01 1.79367498e-01 2.77921140e-01 9.43701923e-01 1.79367498e-01 2.81197399e-01 9.42730606e-01 1.79367498e-01 2.84589916e-01 9.41709876e-01 1.79367498e-01 2.87855953e-01 9.40719962e-01 1.79367498e-01 2.91017473e-01 9.39746916e-01 1.79367498e-01 2.94246763e-01 9.38739657e-01 1.79367498e-01 2.97521353e-01 9.37706351e-01 1.79367498e-01 3.00897121e-01 9.36625957e-01 1.79367498e-01 3.04263651e-01 9.35539901e-01 1.79367498e-01 3.07515800e-01 9.34476316e-01 1.79367498e-01 3.10699046e-01 9.33423936e-01 1.79367498e-01 3.13874632e-01 9.32361424e-01 1.79367498e-01 3.17102015e-01 9.31266904e-01 1.79367498e-01 3.20411623e-01 9.30133164e-01 1.79367498e-01 3.23750257e-01 9.28974986e-01 1.79367498e-01 3.26937616e-01 9.27861512e-01 1.79367498e-01 3.30160111e-01 9.26718771e-01 1.79367498e-01 3.33422542e-01 9.25548494e-01 1.79367498e-01 3.36596847e-01 9.24399972e-01 1.79367498e-01 3.39931458e-01 9.23172534e-01 1.79367498e-01 3.43152642e-01 9.21976686e-01 1.79367498e-01 3.46362650e-01 9.20776844e-01 1.79367498e-01 3.49525571e-01 9.19585049e-01 1.79367498e-01 3.52715999e-01 9.18373704e-01 1.79367498e-01 3.55905622e-01 9.17134702e-01 1.79367498e-01 3.59021485e-01 9.15923238e-01 1.79367498e-01 3.62301230e-01 9.14630234e-01 1.79367498e-01 3.65586579e-01 9.13322806e-01 1.79367498e-01 3.68762791e-01 9.12043154e-01 1.79367498e-01 3.71926039e-01 9.10759568e-01 1.79367498e-01 3.75041604e-01 9.09478962e-01 1.79367498e-01 3.78118694e-01 9.08205211e-01 1.79367498e-01 3.81365508e-01 9.06845570e-01 1.79367498e-01 3.84615779e-01 9.05471921e-01 1.79367498e-01 3.87758881e-01 9.04130161e-01 1.79367498e-01 3.90845090e-01 9.02801871e-01 1.79367498e-01 3.93948227e-01 9.01454210e-01 1.79367498e-01 3.97071958e-01 9.00081098e-01 1.79367498e-01 4.00260180e-01 8.98667395e-01 1.79367498e-01 4.03466552e-01 8.97232711e-01 1.79367498e-01 4.06529009e-01 8.95849109e-01 1.79367498e-01 4.09592718e-01 8.94450903e-01 1.79367498e-01 4.12692964e-01 8.93024564e-01 1.79367498e-01 4.15820718e-01 8.91574383e-01 1.79367498e-01 4.18914735e-01 8.90124261e-01 1.79367498e-01 4.22047079e-01 8.88642490e-01 1.79367498e-01 4.25204873e-01 8.87134731e-01 1.79367498e-01 4.28332180e-01 8.85634065e-01 1.79367498e-01 4.31353390e-01 8.84166718e-01 1.79367498e-01 4.34392244e-01 8.82674336e-01 1.79367453e-01 4.37450826e-01 8.81163776e-01 1.79367498e-01 4.40583736e-01 8.79600227e-01 1.79367498e-01 4.43712682e-01 8.78027439e-01 1.79367498e-01 4.46796060e-01 8.76462102e-01 1.79367498e-01 4.49785888e-01 8.74932706e-01 1.79367498e-01 4.52743441e-01 8.73403311e-01 1.79367498e-01 4.55791444e-01 8.71820271e-01 1.79367498e-01 4.58912492e-01 8.70178521e-01 1.79367498e-01 4.62003112e-01 8.68542135e-01 1.79367498e-01 4.65027601e-01 8.66927326e-01 1.79367498e-01 4.67993200e-01 8.65328133e-01 1.79367498e-01 4.70939666e-01 8.63731861e-01 1.79367498e-01 4.73952860e-01 8.62079918e-01 1.79367498e-01 4.77006674e-01 8.60390306e-01 1.79367498e-01 4.80105489e-01 8.58667910e-01 1.79367498e-01 4.83029276e-01 8.57028008e-01 1.79367498e-01 4.85982656e-01 8.55354607e-01 1.79367498e-01 4.88991708e-01 8.53641212e-01 1.79367498e-01 4.91887659e-01 8.51973891e-01 1.79367498e-01 4.94946808e-01 8.50199640e-01 1.79367498e-01 4.97912139e-01 8.48467410e-01 1.79367498e-01 5.00856161e-01 8.46730947e-01 1.79367498e-01 5.03825724e-01 8.44968319e-01 1.79367498e-01 5.06757259e-01 8.43214273e-01 1.79367498e-01 5.09721339e-01 8.41424704e-01 1.79367498e-01 5.12562752e-01 8.39698195e-01 1.79367498e-01 5.15547872e-01 8.37866485e-01 1.79367498e-01 5.18497050e-01 8.36047471e-01 1.79367498e-01 5.21397591e-01 8.34239602e-01 1.79367498e-01 5.24307013e-01 8.32415640e-01 1.79367498e-01 5.27119517e-01 8.30637455e-01 1.79367498e-01 5.30057490e-01 8.28764260e-01 1.79367498e-01 5.32933593e-01 8.26917589e-01 1.79367498e-01 5.35864472e-01 8.25020611e-01 1.79367498e-01 5.38828552e-01 8.23089242e-01 1.79367498e-01 5.41633427e-01 8.21248412e-01 1.79367498e-01 5.44407427e-01 8.19407284e-01 1.79367498e-01 5.47237933e-01 8.17522645e-01 1.79367498e-01 5.50165832e-01 8.15557182e-01 1.79367498e-01 5.53070843e-01 8.13588560e-01 1.79367498e-01 5.55878341e-01 8.11674774e-01 1.79367512e-01 5.58647037e-01 8.09771359e-01 1.79367498e-01 5.61457276e-01 8.07824671e-01 1.79367498e-01 5.64302087e-01 8.05839002e-01 1.79367512e-01 5.67129731e-01 8.03855360e-01 1.79367542e-01 5.69861233e-01 8.01919520e-01 1.79367557e-01 5.72726011e-01 7.99876928e-01 1.79367557e-01 5.75506866e-01 7.97881603e-01 1.79367647e-01 5.78257322e-01 7.95890987e-01 1.79367647e-01 5.80996811e-01 7.93898344e-01 1.79367706e-01 5.83626211e-01 7.91967869e-01 1.79367959e-01 5.86484969e-01 7.89847553e-01 1.79368705e-01 5.88962674e-01 7.88003445e-01 1.79368928e-01 5.91917574e-01 7.85786450e-01 1.79368854e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.05804586e-01 6.85321629e-01 1.79368898e-01 7.08069086e-01 6.82980120e-01 1.79368660e-01 7.10268497e-01 6.80701256e-01 1.79367796e-01 7.12476969e-01 6.78379536e-01 1.79367647e-01 7.14825273e-01 6.75900280e-01 1.79367557e-01 7.17214108e-01 6.73362136e-01 1.79367498e-01 7.19628692e-01 6.70780241e-01 1.79367498e-01 7.21914411e-01 6.68322980e-01 1.79367498e-01 7.24175632e-01 6.65872455e-01 1.79367498e-01 7.26477563e-01 6.63356423e-01 1.79367498e-01 7.28813052e-01 6.60792947e-01 1.79367498e-01 7.31151998e-01 6.58201873e-01 1.79367498e-01 7.33522058e-01 6.55556262e-01 1.79367498e-01 7.35729396e-01 6.53082669e-01 1.79367498e-01 7.37944186e-01 6.50576890e-01 1.79367498e-01 7.40215480e-01 6.47989511e-01 1.79367498e-01 7.42470980e-01 6.45407021e-01 1.79367498e-01 7.44783759e-01 6.42735779e-01 1.79367498e-01 7.47008026e-01 6.40150487e-01 1.79367498e-01 7.49181688e-01 6.37601972e-01 1.79367498e-01 7.51411259e-01 6.34975791e-01 1.79367498e-01 7.53680646e-01 6.32278502e-01 1.79367498e-01 7.55888581e-01 6.29640341e-01 1.79367498e-01 7.58003950e-01 6.27089202e-01 1.79367498e-01 7.60268211e-01 6.24344766e-01 1.79367498e-01 7.62497962e-01 6.21617138e-01 1.79367498e-01 7.64651716e-01 6.18967354e-01 1.79367498e-01 7.66742587e-01 6.16373897e-01 1.79367498e-01 7.68840790e-01 6.13758147e-01 1.79367498e-01 7.70961106e-01 6.11088455e-01 1.79367498e-01 7.73155212e-01 6.08311415e-01 1.79367498e-01 7.75349498e-01 6.05510712e-01 1.79367498e-01 7.77444243e-01 6.02820635e-01 1.79367498e-01 7.79494226e-01 6.00168705e-01 1.79367498e-01 7.81540692e-01 5.97500384e-01 1.79367498e-01 7.83628941e-01 5.94758630e-01 1.79367498e-01 7.85735965e-01 5.91972828e-01 1.79367498e-01 7.87860990e-01 5.89139879e-01 1.79367498e-01 7.89854825e-01 5.86465240e-01 1.79367498e-01 7.91842163e-01 5.83777249e-01 1.79367498e-01 7.93873012e-01 5.81011593e-01 1.79367498e-01 7.95955420e-01 5.78156829e-01 1.79367498e-01 7.97974646e-01 5.75366318e-01 1.79367498e-01 7.99919367e-01 5.72662950e-01 1.79367498e-01 8.01956177e-01 5.69804311e-01 1.79367498e-01 8.03948700e-01 5.66994131e-01 1.79367498e-01 8.05926085e-01 5.64173222e-01 1.79367498e-01 8.07888746e-01 5.61362386e-01 1.79367498e-01 8.09773982e-01 5.58641732e-01 1.79367498e-01 8.11781406e-01 5.55719733e-01 1.79367498e-01 8.13772082e-01 5.52798808e-01 1.79367498e-01 8.15693259e-01 5.49960375e-01 1.79367498e-01 8.17562580e-01 5.47177255e-01 1.79367498e-01 8.19410682e-01 5.44405401e-01 1.79367498e-01 8.21318388e-01 5.41523993e-01 1.79367498e-01 8.23251367e-01 5.38579047e-01 1.79367498e-01 8.25183570e-01 5.35614610e-01 1.79367498e-01 8.26989293e-01 5.32823205e-01 1.79367498e-01 8.28780830e-01 5.30032277e-01 1.79367498e-01 8.30624461e-01 5.27136624e-01 1.79367498e-01 8.32465529e-01 5.24229407e-01 1.79367498e-01 8.34339976e-01 5.21233797e-01 1.79367498e-01 8.36230695e-01 5.18199980e-01 1.79367498e-01 8.37981641e-01 5.15360057e-01 1.79367498e-01 8.39725018e-01 5.12519777e-01 1.79367498e-01 8.41501117e-01 5.09594738e-01 1.79367498e-01 8.43265831e-01 5.06668866e-01 1.79367498e-01 8.45028281e-01 5.03724396e-01 1.79367498e-01 8.46800745e-01 5.00739753e-01 1.79367498e-01 8.48545015e-01 4.97781187e-01 1.79367498e-01 8.50261569e-01 4.94840354e-01 1.79367498e-01 8.52028072e-01 4.91790950e-01 1.79367498e-01 8.53753090e-01 4.88793194e-01 1.79367498e-01 8.55396092e-01 4.85908955e-01 1.79367498e-01 8.57158244e-01 4.82797772e-01 1.79367498e-01 8.58887136e-01 4.79710847e-01 1.79367498e-01 8.60549808e-01 4.76721555e-01 1.79367498e-01 8.62159073e-01 4.73809689e-01 1.79367498e-01 8.63767564e-01 4.70871359e-01 1.79367498e-01 8.65419984e-01 4.67824399e-01 1.79367498e-01 8.67046714e-01 4.64804202e-01 1.79367498e-01 8.68705869e-01 4.61693168e-01 1.79367498e-01 8.70348811e-01 4.58590120e-01 1.79367498e-01 8.71908724e-01 4.55619931e-01 1.79367498e-01 8.73444080e-01 4.52665925e-01 1.79367498e-01 8.75025332e-01 4.49603379e-01 1.79367498e-01 8.76637220e-01 4.46448475e-01 1.79367453e-01 8.78217220e-01 4.43335146e-01 1.79367498e-01 8.79730165e-01 4.40325916e-01 1.79367498e-01 8.81212771e-01 4.37350363e-01 1.79367498e-01 8.82724762e-01 4.34291661e-01 1.79367498e-01 8.84274065e-01 4.31129187e-01 1.79367498e-01 8.85786951e-01 4.28016573e-01 1.79367498e-01 8.87228966e-01 4.25008774e-01 1.79367498e-01 8.88735831e-01 4.21848923e-01 1.79367498e-01 8.90210152e-01 4.18732315e-01 1.79367498e-01 8.91662896e-01 4.15630758e-01 1.79367498e-01 8.93121719e-01 4.12487566e-01 1.79367498e-01 8.94507170e-01 4.09470022e-01 1.79367498e-01 8.95962834e-01 4.06275451e-01 1.79367498e-01 8.97421956e-01 4.03044939e-01 1.79367498e-01 8.98817003e-01 3.99925441e-01 1.79367498e-01 9.00182366e-01 3.96839768e-01 1.79367498e-01 9.01527405e-01 3.93779069e-01 1.79367498e-01 9.02888238e-01 3.90645504e-01 1.79367498e-01 9.04247165e-01 3.87482405e-01 1.79367498e-01 9.05626178e-01 3.84251952e-01 1.79367498e-01 9.06971991e-01 3.81067991e-01 1.79367498e-01 9.08255041e-01 3.78000706e-01 1.79367498e-01 9.09564376e-01 3.74835312e-01 1.79367498e-01 9.10872281e-01 3.71649384e-01 1.79367498e-01 9.12193179e-01 3.68393004e-01 1.79367498e-01 9.13514316e-01 3.65108132e-01 1.79367498e-01 9.14749563e-01 3.62006903e-01 1.79367498e-01 9.15965319e-01 3.58918250e-01 1.79367498e-01 9.17212725e-01 3.55697811e-01 1.79367498e-01 9.18488085e-01 3.52414578e-01 1.79367498e-01 9.19720829e-01 3.49167198e-01 1.79367498e-01 9.20900345e-01 3.46032262e-01 1.79367498e-01 9.22126949e-01 3.42748016e-01 1.79367498e-01 9.23349142e-01 3.39453667e-01 1.79367498e-01 9.24533546e-01 3.36236417e-01 1.79367498e-01 9.25669193e-01 3.33082467e-01 1.79367498e-01 9.26794410e-01 3.29948723e-01 1.79367498e-01 9.27967012e-01 3.26631427e-01 1.79367498e-01 9.29141402e-01 3.23273897e-01 1.79367498e-01 9.30269599e-01 3.20021898e-01 1.79367498e-01 9.31342721e-01 3.16878796e-01 1.79367498e-01 9.32408631e-01 3.13731164e-01 1.79367498e-01 9.33504403e-01 3.10452551e-01 1.79367498e-01 9.34585750e-01 3.07181448e-01 1.79367498e-01 9.35667694e-01 3.03872406e-01 1.79367498e-01 9.36760783e-01 3.00482780e-01 1.79367498e-01 9.37780201e-01 2.97289014e-01 1.79367498e-01 9.38782692e-01 2.94110984e-01 1.79367498e-01 9.39804256e-01 2.90824711e-01 1.79367498e-01 9.40832138e-01 2.87479699e-01 1.79367498e-01 9.41857576e-01 2.84100741e-01 1.79367498e-01 9.42822576e-01 2.80888915e-01 1.79367498e-01 9.43768084e-01 2.77696103e-01 1.79367498e-01 9.44730282e-01 2.74402261e-01 1.79367498e-01 9.45689797e-01 2.71071613e-01 1.79367498e-01 9.46644068e-01 2.67731816e-01 1.79367498e-01 9.47553992e-01 2.64490187e-01 1.79367498e-01 9.48473573e-01 2.61166781e-01 1.79367498e-01 9.49378967e-01 2.57870376e-01 1.79367498e-01 9.50281262e-01 2.54507601e-01 1.79367498e-01 9.51181591e-01 2.51132488e-01 1.79367498e-01 9.52026010e-01 2.47912258e-01 1.79367498e-01 9.52881932e-01 2.44597897e-01 1.79367498e-01 9.53748047e-01 2.41188079e-01 1.79367498e-01 9.54602778e-01 2.37787530e-01 1.79367498e-01 9.55425143e-01 2.34473839e-01 1.79367498e-01 9.56221640e-01 2.31207520e-01 1.79367498e-01 9.57002223e-01 2.27949783e-01 1.79367498e-01 9.57789481e-01 2.24617362e-01 1.79367498e-01 9.58591938e-01 2.21158653e-01 1.79367498e-01 9.59357381e-01 2.17819124e-01 1.79367498e-01 9.60098207e-01 2.14537933e-01 1.79367498e-01 9.60839748e-01 2.11179867e-01 1.79367498e-01 9.61575925e-01 2.07804829e-01 1.79367498e-01 9.62295055e-01 2.04452768e-01 1.79367498e-01 9.63010907e-01 2.01053694e-01 1.79367498e-01 9.63710606e-01 1.97676465e-01 1.79367498e-01 9.64385092e-01 1.94353804e-01 1.79367498e-01 9.65077877e-01 1.90882087e-01 1.79367498e-01 9.65743065e-01 1.87491298e-01 1.79367498e-01 9.66377139e-01 1.84191287e-01 1.79367498e-01 9.66991305e-01 1.80942550e-01 1.79367498e-01 9.67630386e-01 1.77478105e-01 1.79367498e-01 9.68264818e-01 1.74023867e-01 1.79367498e-01 9.68863249e-01 1.70660809e-01 1.79367498e-01 9.69445288e-01 1.67293444e-01 1.79367498e-01 9.70004439e-01 1.64030999e-01 1.79367498e-01 9.70567405e-01 1.60651192e-01 1.79367498e-01 9.71124530e-01 1.57252252e-01 1.79367498e-01 9.71678317e-01 1.53794348e-01 1.79367498e-01 9.72223938e-01 1.50305659e-01 1.79367498e-01 9.72731769e-01 1.46980882e-01 1.79367498e-01 9.73220944e-01 1.43706784e-01 1.79367498e-01 9.73717093e-01 1.40301809e-01 1.79367498e-01 9.74214375e-01 1.36811182e-01 1.79367498e-01 9.74698722e-01 1.33329734e-01 1.79367498e-01 9.75147307e-01 1.29995078e-01 1.79367498e-01 9.75584269e-01 1.26678169e-01 1.79367498e-01 9.76018429e-01 1.23294681e-01 1.79367498e-01 9.76440191e-01 1.19899698e-01 1.79367498e-01 9.76856112e-01 1.16455659e-01 1.79367498e-01 9.77258086e-01 1.13030918e-01 1.79367498e-01 9.77657437e-01 1.09527595e-01 1.79367498e-01 9.78032529e-01 1.06138341e-01 1.79367498e-01 9.78393376e-01 1.02738149e-01 1.79367498e-01 9.78747666e-01 9.93123427e-02 1.79367498e-01 9.79078889e-01 9.59906951e-02 1.79367498e-01 9.79418695e-01 9.24867913e-02 1.79367498e-01 9.79742169e-01 8.89758989e-02 1.79367498e-01 9.80045974e-01 8.55745003e-02 1.79367498e-01 9.80333686e-01 8.22134688e-02 1.79367498e-01 9.80608225e-01 7.88663253e-02 1.79367498e-01 9.80873644e-01 7.54696205e-02 1.79367498e-01 9.81138825e-01 7.19403550e-02 1.79367498e-01 9.81388807e-01 6.84343725e-02 1.79367498e-01 9.81615961e-01 6.51192218e-02 1.79367498e-01 9.81831551e-01 6.17760122e-02 1.79367498e-01 9.82042015e-01 5.83240762e-02 1.79367498e-01 9.82241988e-01 5.49061261e-02 1.79367498e-01 9.82428789e-01 5.14025912e-02 1.79367498e-01 9.82609034e-01 4.78768423e-02 1.79367498e-01 9.82764482e-01 4.45482992e-02 1.79367498e-01 9.82911706e-01 4.12023589e-02 1.79367498e-01 9.83048439e-01 3.77864912e-02 1.79367498e-01 9.83176589e-01 3.42275798e-02 1.79367498e-01 9.83292997e-01 3.07941865e-02 1.79367498e-01 9.83392537e-01 2.74693519e-02 1.79367498e-01 9.83482599e-01 2.40245946e-02 1.79367498e-01 9.83557105e-01 2.05724798e-02 1.79367498e-01 9.83628869e-01 1.71735734e-02 1.79367498e-01 9.83673513e-01 1.37281483e-02 1.79367498e-01 9.83721316e-01 1.02809696e-02 1.79367498e-01 9.83758211e-01 6.75417390e-03 1.79367498e-01 9.83773649e-01 3.22139962e-03 1.79367498e-01 9.83774960e-01 -2.21365277e-04 1.79367498e-01 9.83773232e-01 -3.66925541e-03 1.79367498e-01 9.83754873e-01 -6.98249089e-03 1.79367498e-01 9.83721197e-01 -1.03115514e-02 1.79367498e-01 9.83673215e-01 -1.37522230e-02 1.79367498e-01 9.83626544e-01 -1.73033271e-02 1.79367498e-01 9.83550608e-01 -2.08574329e-02 1.79367498e-01 9.83476639e-01 -2.42433306e-02 1.79367498e-01 9.83389318e-01 -2.75671016e-02 1.79367498e-01 9.83283579e-01 -3.10290456e-02 1.79367498e-01 9.83171940e-01 -3.44697013e-02 1.79367498e-01 9.83046234e-01 -3.78294662e-02 1.79367498e-01 9.82911348e-01 -4.12372202e-02 1.79367498e-01 9.82754886e-01 -4.47453447e-02 1.79367498e-01 9.82589424e-01 -4.82768044e-02 1.79367498e-01 9.82411802e-01 -5.17226420e-02 1.79367498e-01 9.82232094e-01 -5.50608337e-02 1.79367498e-01 9.82039988e-01 -5.83828166e-02 1.79367498e-01 9.81828153e-01 -6.18071333e-02 1.79367498e-01 9.81602252e-01 -6.53121918e-02 1.79367498e-01 9.81358409e-01 -6.88830167e-02 1.79367498e-01 9.81114626e-01 -7.23031610e-02 1.79367498e-01 9.80863094e-01 -7.56280646e-02 1.79367498e-01 9.80602324e-01 -7.89346173e-02 1.79367498e-01 9.80319798e-01 -8.23716223e-02 1.79367498e-01 9.80018377e-01 -8.58839676e-02 1.79367498e-01 9.79711056e-01 -8.93132314e-02 1.79367498e-01 9.79405105e-01 -9.26069319e-02 1.79367498e-01 9.79076028e-01 -9.60434899e-02 1.79367498e-01 9.78731334e-01 -9.94789675e-02 1.79367498e-01 9.78376925e-01 -1.02909125e-01 1.79367498e-01 9.78006661e-01 -1.06356516e-01 1.79367498e-01 9.77630377e-01 -1.09785900e-01 1.79367498e-01 9.77250874e-01 -1.13099866e-01 1.79367498e-01 9.76840496e-01 -1.16582796e-01 1.79367498e-01 9.76428151e-01 -1.20010346e-01 1.79367498e-01 9.76001024e-01 -1.23429127e-01 1.79367498e-01 9.75552857e-01 -1.26912296e-01 1.79367498e-01 9.75119054e-01 -1.30210191e-01 1.79367498e-01 9.74654496e-01 -1.33646592e-01 1.79367498e-01 9.74170506e-01 -1.37138605e-01 1.79367498e-01 9.73697484e-01 -1.40446231e-01 1.79367498e-01 9.73201096e-01 -1.43831164e-01 1.79367498e-01 9.72691953e-01 -1.47240430e-01 1.79367498e-01 9.72166538e-01 -1.50675371e-01 1.79367498e-01 9.71641660e-01 -1.54028103e-01 1.79367498e-01 9.71098304e-01 -1.57413512e-01 1.79367498e-01 9.70544159e-01 -1.60802975e-01 1.79367498e-01 9.69977796e-01 -1.64179593e-01 1.79367453e-01 9.69380856e-01 -1.67656422e-01 1.79367498e-01 9.68793809e-01 -1.71046302e-01 1.79367498e-01 9.68206644e-01 -1.74342752e-01 1.79367498e-01 9.67600107e-01 -1.77641779e-01 1.79367498e-01 9.66977775e-01 -1.81014523e-01 1.79367498e-01 9.66321051e-01 -1.84472710e-01 1.79367498e-01 9.65661824e-01 -1.87910929e-01 1.79367498e-01 9.65002120e-01 -1.91262022e-01 1.79367498e-01 9.64343548e-01 -1.94560885e-01 1.79367498e-01 9.63668406e-01 -1.97877079e-01 1.79367498e-01 9.62972522e-01 -2.01231197e-01 1.79367498e-01 9.62247491e-01 -2.04671487e-01 1.79367498e-01 9.61535335e-01 -2.08007157e-01 1.79367498e-01 9.60793912e-01 -2.11389333e-01 1.79367498e-01 9.60053384e-01 -2.14736521e-01 1.79367498e-01 9.59303677e-01 -2.18055010e-01 1.79367498e-01 9.58535969e-01 -2.21410125e-01 1.79367498e-01 9.57754195e-01 -2.24769130e-01 1.79367498e-01 9.56961036e-01 -2.28128180e-01 1.79367498e-01 9.56189036e-01 -2.31340811e-01 1.79367498e-01 9.55351889e-01 -2.34763682e-01 1.79367498e-01 9.54523265e-01 -2.38110334e-01 1.79367498e-01 9.53683615e-01 -2.41446719e-01 1.79367498e-01 9.52820301e-01 -2.44840235e-01 1.79367498e-01 9.51991618e-01 -2.48039052e-01 1.79367498e-01 9.51101124e-01 -2.51437187e-01 1.79367498e-01 9.50223327e-01 -2.54737556e-01 1.79367498e-01 9.49362814e-01 -2.57921606e-01 1.79367498e-01 9.48414862e-01 -2.61374205e-01 1.79367498e-01 9.47502851e-01 -2.64677256e-01 1.79367498e-01 9.46575582e-01 -2.67966092e-01 1.79367498e-01 9.45605934e-01 -2.71370202e-01 1.79367498e-01 9.44674194e-01 -2.74596184e-01 1.79367498e-01 9.43747640e-01 -2.77760923e-01 1.79367498e-01 9.42750812e-01 -2.81130433e-01 1.79367498e-01 9.41731691e-01 -2.84518510e-01 1.79367498e-01 9.40720201e-01 -2.87852257e-01 1.79367498e-01 9.39737737e-01 -2.91046888e-01 1.79367498e-01 9.38754857e-01 -2.94197619e-01 1.79367498e-01 9.37715173e-01 -2.97495663e-01 1.79367498e-01 9.36650455e-01 -3.00827175e-01 1.79367498e-01 9.35572386e-01 -3.04164618e-01 1.79367498e-01 9.34490740e-01 -3.07468981e-01 1.79367498e-01 9.33439195e-01 -3.10652018e-01 1.79367498e-01 9.32379901e-01 -3.13817203e-01 1.79367498e-01 9.31279600e-01 -3.17066640e-01 1.79367498e-01 9.30146933e-01 -3.20371896e-01 1.79367498e-01 9.29017544e-01 -3.23632658e-01 1.79367498e-01 9.27883267e-01 -3.26869369e-01 1.79367498e-01 9.26741719e-01 -3.30099702e-01 1.79367498e-01 9.25589561e-01 -3.33310276e-01 1.79367498e-01 9.24404800e-01 -3.36591452e-01 1.79367498e-01 9.23222661e-01 -3.39796215e-01 1.79367498e-01 9.22028720e-01 -3.43010962e-01 1.79367498e-01 9.20857847e-01 -3.46145034e-01 1.79367498e-01 9.19643521e-01 -3.49370748e-01 1.79367498e-01 9.18394744e-01 -3.52662146e-01 1.79367498e-01 9.17140424e-01 -3.55889142e-01 1.79367498e-01 9.15900767e-01 -3.59079361e-01 1.79367498e-01 9.14642096e-01 -3.62276018e-01 1.79367498e-01 9.13375854e-01 -3.65450442e-01 1.79367498e-01 9.12092626e-01 -3.68645579e-01 1.79367498e-01 9.10842180e-01 -3.71721596e-01 1.79367498e-01 9.09506321e-01 -3.74975294e-01 1.79367498e-01 9.08184707e-01 -3.78170669e-01 1.79367498e-01 9.06857908e-01 -3.81335557e-01 1.79367498e-01 9.05476034e-01 -3.84603739e-01 1.79367498e-01 9.04173553e-01 -3.87658805e-01 1.79367498e-01 9.02842999e-01 -3.90749246e-01 1.79367498e-01 9.01452720e-01 -3.93948972e-01 1.79367498e-01 9.00034845e-01 -3.97176355e-01 1.79367498e-01 8.98642123e-01 -4.00316387e-01 1.79367498e-01 8.97262990e-01 -4.03402507e-01 1.79367498e-01 8.95898104e-01 -4.06417727e-01 1.79367498e-01 8.94473791e-01 -4.09540415e-01 1.79367498e-01 8.93004239e-01 -4.12736595e-01 1.79367498e-01 8.91524315e-01 -4.15926814e-01 1.79367498e-01 8.90057445e-01 -4.19054836e-01 1.79367498e-01 8.88623178e-01 -4.22091722e-01 1.79367498e-01 8.87188315e-01 -4.25094575e-01 1.79367498e-01 8.85686338e-01 -4.28223759e-01 1.79367498e-01 8.84144247e-01 -4.31397825e-01 1.79367498e-01 8.82622719e-01 -4.34500903e-01 1.79367498e-01 8.81099224e-01 -4.37579036e-01 1.79367498e-01 8.79581630e-01 -4.40623999e-01 1.79367498e-01 8.78087044e-01 -4.43596333e-01 1.79367498e-01 8.76548052e-01 -4.46629167e-01 1.79367498e-01 8.74931633e-01 -4.49784189e-01 1.79367498e-01 8.73337448e-01 -4.52870607e-01 1.79367498e-01 8.71812880e-01 -4.55804169e-01 1.79367498e-01 8.70213270e-01 -4.58847344e-01 1.79367498e-01 8.68546724e-01 -4.61993277e-01 1.79367498e-01 8.66931796e-01 -4.65021223e-01 1.79367498e-01 8.65325809e-01 -4.67998713e-01 1.79367498e-01 8.63675892e-01 -4.71043915e-01 1.79367498e-01 8.62066925e-01 -4.73975301e-01 1.79367498e-01 8.60415518e-01 -4.76963133e-01 1.79367498e-01 8.58691037e-01 -4.80061680e-01 1.79367498e-01 8.57018173e-01 -4.83046561e-01 1.79367498e-01 8.55331063e-01 -4.86023754e-01 1.79367498e-01 8.53629708e-01 -4.89011854e-01 1.79367498e-01 8.51916730e-01 -4.91985351e-01 1.79367498e-01 8.50160122e-01 -4.95015502e-01 1.79367498e-01 8.48466039e-01 -4.97913361e-01 1.79367498e-01 8.46755266e-01 -5.00817537e-01 1.79367498e-01 8.45006824e-01 -5.03758550e-01 1.79367498e-01 8.43192577e-01 -5.06792009e-01 1.79367498e-01 8.41364145e-01 -5.09818614e-01 1.79367498e-01 8.39623928e-01 -5.12685657e-01 1.79367498e-01 8.37880194e-01 -5.15527010e-01 1.79367498e-01 8.36080313e-01 -5.18443823e-01 1.79367498e-01 8.34219098e-01 -5.21428943e-01 1.79367498e-01 8.32338154e-01 -5.24429440e-01 1.79367498e-01 8.30515802e-01 -5.27308822e-01 1.79367498e-01 8.28734815e-01 -5.30103862e-01 1.79367498e-01 8.26863348e-01 -5.33017039e-01 1.79367498e-01 8.24956000e-01 -5.35965860e-01 1.79367498e-01 8.23069572e-01 -5.38856566e-01 1.79367498e-01 8.21191072e-01 -5.41717589e-01 1.79367498e-01 8.19333315e-01 -5.44519663e-01 1.79367498e-01 8.17489386e-01 -5.47287107e-01 1.79367498e-01 8.15573096e-01 -5.50140381e-01 1.79367498e-01 8.13596070e-01 -5.53058565e-01 1.79367498e-01 8.11608076e-01 -5.55971980e-01 1.79367498e-01 8.09674025e-01 -5.58787227e-01 1.79367498e-01 8.07756901e-01 -5.61554134e-01 1.79367498e-01 8.05805147e-01 -5.64346671e-01 1.79367498e-01 8.03818285e-01 -5.67179382e-01 1.79367498e-01 8.01838160e-01 -5.69971085e-01 1.79367498e-01 7.99825728e-01 -5.72796047e-01 1.79367498e-01 7.97883272e-01 -5.75491607e-01 1.79367498e-01 7.95860350e-01 -5.78290224e-01 1.79367498e-01 7.93851674e-01 -5.81042588e-01 1.79367498e-01 7.91778505e-01 -5.83863795e-01 1.79367498e-01 7.89656937e-01 -5.86732209e-01 1.79367498e-01 7.87677109e-01 -5.89385331e-01 1.79367498e-01 7.85617709e-01 -5.92127979e-01 1.79367498e-01 7.83524752e-01 -5.94897628e-01 1.79367498e-01 7.81473219e-01 -5.97587585e-01 1.79367498e-01 7.79385507e-01 -6.00308061e-01 1.79367498e-01 7.77319789e-01 -6.02980137e-01 1.79367498e-01 7.75159895e-01 -6.05752707e-01 1.79367498e-01 7.72998393e-01 -6.08510315e-01 1.79367498e-01 7.70901203e-01 -6.11165166e-01 1.79367453e-01 7.68822253e-01 -6.13779426e-01 1.79367498e-01 7.66687214e-01 -6.16445005e-01 1.79367498e-01 7.64471829e-01 -6.19189322e-01 1.79367498e-01 7.62292743e-01 -6.21867537e-01 1.79367498e-01 7.60179758e-01 -6.24449730e-01 1.79367498e-01 7.58001149e-01 -6.27093256e-01 1.79367498e-01 7.55820572e-01 -6.29719973e-01 1.79367498e-01 7.53618538e-01 -6.32354319e-01 1.79367498e-01 7.51327634e-01 -6.35071218e-01 1.79367498e-01 7.49101758e-01 -6.37696624e-01 1.79367498e-01 7.46948183e-01 -6.40217066e-01 1.79367498e-01 7.44697154e-01 -6.42835796e-01 1.79367498e-01 7.42423475e-01 -6.45459592e-01 1.79367498e-01 7.40113735e-01 -6.48106039e-01 1.79367498e-01 7.37818062e-01 -6.50718927e-01 1.79367498e-01 7.35582948e-01 -6.53245211e-01 1.79367453e-01 7.33351767e-01 -6.55749381e-01 1.79367498e-01 7.31008530e-01 -6.58360064e-01 1.79367498e-01 7.28723109e-01 -6.60891593e-01 1.79367498e-01 7.26406634e-01 -6.63433015e-01 1.79367498e-01 7.24075437e-01 -6.65979147e-01 1.79367498e-01 7.21822262e-01 -6.68419242e-01 1.79367498e-01 7.19482124e-01 -6.70935750e-01 1.79367498e-01 7.17075706e-01 -6.73507214e-01 1.79367498e-01 7.14722455e-01 -6.76004887e-01 1.79367498e-01 7.12358356e-01 -6.78498626e-01 1.79367498e-01 7.09979594e-01 -6.80980742e-01 1.79367498e-01 7.07610548e-01 -6.83453739e-01 1.79367498e-01 7.05204368e-01 -6.85934842e-01 1.79367498e-01 7.02867508e-01 -6.88325465e-01 1.79367498e-01 7.00409532e-01 -6.90828562e-01 1.79367498e-01 6.97982848e-01 -6.93284571e-01 1.79367498e-01 6.95553660e-01 -6.95700228e-01 1.79367498e-01 6.93064570e-01 -6.98200285e-01 1.79367498e-01 6.90691948e-01 -7.00547159e-01 1.79367498e-01 6.88330710e-01 -7.02864170e-01 1.79367498e-01 6.85878813e-01 -7.05262184e-01 1.79367527e-01 6.83362961e-01 -7.07698941e-01 1.79367527e-01 6.80840313e-01 -7.10122883e-01 1.79367602e-01 6.78346515e-01 -7.12506890e-01 1.79367587e-01 6.75904632e-01 -7.14825213e-01 1.79367661e-01 6.73482955e-01 -7.17110097e-01 1.79367691e-01 6.70995057e-01 -7.19443321e-01 1.79367706e-01 6.68851614e-01 -7.21430123e-01 1.79368466e-01 6.66081488e-01 -7.23989904e-01 1.79368913e-01 6.64221823e-01 -7.25696921e-01 1.79368854e-01 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. 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. 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. 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. 0. 0. 5.58068812e-01 -8.10176194e-01 1.79368868e-01 5.55376172e-01 -8.12024593e-01 1.79368928e-01 5.52698195e-01 -8.13852131e-01 1.79368034e-01 5.50024390e-01 -8.15663278e-01 1.79367706e-01 5.47156990e-01 -8.17581475e-01 1.79367632e-01 5.44302464e-01 -8.19479764e-01 1.79367498e-01 5.41433275e-01 -8.21379721e-01 1.79367512e-01 5.38601816e-01 -8.23236883e-01 1.79367498e-01 5.35693884e-01 -8.25132191e-01 1.79367498e-01 5.32815754e-01 -8.26995015e-01 1.79367498e-01 5.29991388e-01 -8.28805685e-01 1.79367498e-01 5.27076721e-01 -8.30661535e-01 1.79367498e-01 5.24183571e-01 -8.32494020e-01 1.79367498e-01 5.21281660e-01 -8.34311366e-01 1.79367498e-01 5.18369138e-01 -8.36126983e-01 1.79367498e-01 5.15435755e-01 -8.37935328e-01 1.79367498e-01 5.12522340e-01 -8.39724004e-01 1.79367498e-01 5.09606361e-01 -8.41493309e-01 1.79367498e-01 5.06650746e-01 -8.43276918e-01 1.79367498e-01 5.03657579e-01 -8.45066786e-01 1.79367498e-01 5.00704348e-01 -8.46822739e-01 1.79367498e-01 4.97800887e-01 -8.48532975e-01 1.79367498e-01 4.94827360e-01 -8.50269675e-01 1.79367498e-01 4.91794884e-01 -8.52026761e-01 1.79367498e-01 4.88824457e-01 -8.53735387e-01 1.79367498e-01 4.85925019e-01 -8.55387092e-01 1.79367498e-01 4.82939571e-01 -8.57079744e-01 1.79367498e-01 4.79955554e-01 -8.58751059e-01 1.79367498e-01 4.76949751e-01 -8.60422254e-01 1.79367498e-01 4.73938972e-01 -8.62087846e-01 1.79367498e-01 4.70938444e-01 -8.63731205e-01 1.79367498e-01 4.67915952e-01 -8.65370929e-01 1.79367498e-01 4.64907944e-01 -8.66990626e-01 1.79367498e-01 4.61863011e-01 -8.68616641e-01 1.79367498e-01 4.58808482e-01 -8.70233774e-01 1.79367498e-01 4.55724239e-01 -8.71851742e-01 1.79367498e-01 4.52662796e-01 -8.73445809e-01 1.79367498e-01 4.49682742e-01 -8.74984920e-01 1.79367498e-01 4.46605146e-01 -8.76558185e-01 1.79367498e-01 4.43539709e-01 -8.78114402e-01 1.79367498e-01 4.40478444e-01 -8.79653573e-01 1.79367498e-01 4.37415987e-01 -8.81180227e-01 1.79367498e-01 4.34353411e-01 -8.82693887e-01 1.79367498e-01 4.31251585e-01 -8.84214461e-01 1.79367498e-01 4.28173363e-01 -8.85709822e-01 1.79367498e-01 4.25058305e-01 -8.87206256e-01 1.79367498e-01 4.21908885e-01 -8.88708711e-01 1.79367498e-01 4.18793827e-01 -8.90180886e-01 1.79367498e-01 4.15655524e-01 -8.91651213e-01 1.79367498e-01 4.12522018e-01 -8.93105507e-01 1.79367498e-01 4.09500986e-01 -8.94493103e-01 1.79367498e-01 4.06379461e-01 -8.95917058e-01 1.79367498e-01 4.03268546e-01 -8.97321701e-01 1.79367498e-01 4.00017947e-01 -8.98775339e-01 1.79367453e-01 3.96865517e-01 -9.00173783e-01 1.79367498e-01 3.93824577e-01 -9.01507735e-01 1.79367498e-01 3.90691757e-01 -9.02867973e-01 1.79367498e-01 3.87500405e-01 -9.04239297e-01 1.79367498e-01 3.84311497e-01 -9.05602276e-01 1.79367498e-01 3.81167203e-01 -9.06931698e-01 1.79367453e-01 3.77916485e-01 -9.08288717e-01 1.79367498e-01 3.74726355e-01 -9.09609675e-01 1.79367498e-01 3.71688366e-01 -9.10857022e-01 1.79367498e-01 3.68453145e-01 -9.12169099e-01 1.79367498e-01 3.65175784e-01 -9.13485944e-01 1.79367498e-01 3.61930072e-01 -9.14778829e-01 1.79367498e-01 3.58808190e-01 -9.16008234e-01 1.79367498e-01 3.55704367e-01 -9.17211175e-01 1.79367498e-01 3.52504551e-01 -9.18455482e-01 1.79367498e-01 3.49305153e-01 -9.19668972e-01 1.79367498e-01 3.46107692e-01 -9.20872629e-01 1.79367498e-01 3.42859745e-01 -9.22085643e-01 1.79367498e-01 3.39646041e-01 -9.23277855e-01 1.79367498e-01 3.36438149e-01 -9.24458504e-01 1.79367498e-01 3.33208352e-01 -9.25624371e-01 1.79367498e-01 3.29969198e-01 -9.26786661e-01 1.79367498e-01 3.26667905e-01 -9.27953362e-01 1.79367498e-01 3.23392123e-01 -9.29100990e-01 1.79367498e-01 3.20174724e-01 -9.30214822e-01 1.79367498e-01 3.16892654e-01 -9.31338131e-01 1.79367498e-01 3.13739896e-01 -9.32406425e-01 1.79367498e-01 3.10402989e-01 -9.33519185e-01 1.79367498e-01 3.07120740e-01 -9.34604645e-01 1.79367498e-01 3.03853482e-01 -9.35672224e-01 1.79367498e-01 3.00578713e-01 -9.36733067e-01 1.79367498e-01 2.97401160e-01 -9.37743664e-01 1.79367498e-01 2.94133723e-01 -9.38774347e-01 1.79367498e-01 2.90849626e-01 -9.39797103e-01 1.79367498e-01 2.87569940e-01 -9.40806091e-01 1.79367498e-01 2.84206539e-01 -9.41824973e-01 1.79367498e-01 2.80822337e-01 -9.42841291e-01 1.79367498e-01 2.77623713e-01 -9.43790734e-01 1.79367498e-01 2.74328947e-01 -9.44751859e-01 1.79367498e-01 2.70937234e-01 -9.45730329e-01 1.79367498e-01 2.67645299e-01 -9.46666360e-01 1.79367498e-01 2.64437556e-01 -9.47570205e-01 1.79367498e-01 2.61191279e-01 -9.48467135e-01 1.79367498e-01 2.57886678e-01 -9.49373662e-01 1.79367498e-01 2.54547209e-01 -9.50271189e-01 1.79367498e-01 2.51255393e-01 -9.51148152e-01 1.79367498e-01 2.47946829e-01 -9.52017844e-01 1.79367498e-01 2.44541615e-01 -9.52895880e-01 1.79367498e-01 2.41212517e-01 -9.53744054e-01 1.79367498e-01 2.37892851e-01 -9.54576313e-01 1.79367453e-01 2.34548703e-01 -9.55406249e-01 1.79367498e-01 2.31272548e-01 -9.56204712e-01 1.79367498e-01 2.27861553e-01 -9.57024395e-01 1.79367498e-01 2.24524155e-01 -9.57811475e-01 1.79367498e-01 2.21175894e-01 -9.58588421e-01 1.79367498e-01 2.17763349e-01 -9.59369838e-01 1.79367498e-01 2.14501023e-01 -9.60106015e-01 1.79367498e-01 2.11232603e-01 -9.60827947e-01 1.79367498e-01 2.07886666e-01 -9.61558104e-01 1.79367498e-01 2.04518229e-01 -9.62279916e-01 1.79367498e-01 2.01066673e-01 -9.63008523e-01 1.79367498e-01 1.97692618e-01 -9.63707745e-01 1.79367498e-01 1.94434121e-01 -9.64369118e-01 1.79367498e-01 1.91081151e-01 -9.65038478e-01 1.79367498e-01 1.87687308e-01 -9.65705216e-01 1.79367498e-01 1.84224069e-01 -9.66369927e-01 1.79367498e-01 1.80827752e-01 -9.67012763e-01 1.79367498e-01 1.77461877e-01 -9.67632949e-01 1.79367498e-01 1.74057364e-01 -9.68260288e-01 1.79367498e-01 1.70781970e-01 -9.68841076e-01 1.79367498e-01 1.67408153e-01 -9.69423413e-01 1.79367498e-01 1.64001971e-01 -9.70008135e-01 1.79367498e-01 1.60527274e-01 -9.70587552e-01 1.79367498e-01 1.57142982e-01 -9.71142888e-01 1.79367498e-01 1.53861672e-01 -9.71668363e-01 1.79367498e-01 1.50456965e-01 -9.72201169e-01 1.79367498e-01 1.47060022e-01 -9.72719014e-01 1.79367498e-01 1.43580317e-01 -9.73239839e-01 1.79367498e-01 1.40175626e-01 -9.73736644e-01 1.79367498e-01 1.36769727e-01 -9.74221528e-01 1.79367498e-01 1.33277044e-01 -9.74705696e-01 1.79367498e-01 1.29950449e-01 -9.75153148e-01 1.79367498e-01 1.26667932e-01 -9.75585401e-01 1.79367498e-01 1.23254150e-01 -9.76024449e-01 1.79367498e-01 1.19850732e-01 -9.76446807e-01 1.79367498e-01 1.16347909e-01 -9.76869226e-01 1.79367498e-01 1.12927727e-01 -9.77270901e-01 1.79367498e-01 1.09631136e-01 -9.77646172e-01 1.79367498e-01 1.06221445e-01 -9.78021979e-01 1.79367498e-01 1.02816075e-01 -9.78385866e-01 1.79367498e-01 9.92849097e-02 -9.78749037e-01 1.79367498e-01 9.58552584e-02 -9.79093850e-01 1.79367498e-01 9.24627334e-02 -9.79420066e-01 1.79367498e-01 8.90293717e-02 -9.79737163e-01 1.79367498e-01 8.56099278e-02 -9.80041921e-01 1.79367498e-01 8.21000487e-02 -9.80341136e-01 1.79367498e-01 7.87423849e-02 -9.80619550e-01 1.79367498e-01 7.53344893e-02 -9.80885148e-01 1.79367498e-01 7.18870908e-02 -9.81144309e-01 1.79367498e-01 6.85833991e-02 -9.81378317e-01 1.79367498e-01 6.51620924e-02 -9.81613338e-01 1.79367498e-01 6.17301688e-02 -9.81834829e-01 1.79367498e-01 5.81952073e-02 -9.82050180e-01 1.79367498e-01 5.47719374e-02 -9.82249498e-01 1.79367498e-01 5.13569601e-02 -9.82431471e-01 1.79367498e-01 4.79153693e-02 -9.82607603e-01 1.79367498e-01 4.45059165e-02 -9.82765496e-01 1.79367498e-01 4.09687087e-02 -9.82921362e-01 1.79367498e-01 3.76319587e-02 -9.83054042e-01 1.79367498e-01 3.43049131e-02 -9.83174801e-01 1.79367498e-01 3.07802204e-02 -9.83291149e-01 1.79367498e-01 2.73291469e-02 -9.83395278e-01 1.79367498e-01 2.39125174e-02 -9.83485162e-01 1.79367498e-01 2.04657391e-02 -9.83559251e-01 1.79367498e-01 1.71149988e-02 -9.83629704e-01 1.79367498e-01 1.36317965e-02 -9.83672678e-01 1.79367498e-01 1.01616802e-02 -9.83722508e-01 1.79367498e-01 6.80943672e-03 -9.83757019e-01 1.79367498e-01 3.38525418e-03 -9.83773351e-01 1.79367498e-01 -3.27450689e-05 -9.83774543e-01 1.79367498e-01 -3.44888726e-03 -9.83773053e-01 1.79367498e-01 -6.89807348e-03 -9.83756661e-01 1.79367498e-01 -1.04151713e-02 -9.83719945e-01 1.79367498e-01 -1.38575044e-02 -9.83672798e-01 1.79367498e-01 -1.72796063e-02 -9.83627677e-01 1.79367498e-01 -2.08210982e-02 -9.83551443e-01 1.79367498e-01 -2.41691936e-02 -9.83479381e-01 1.79367498e-01 -2.75006015e-02 -9.83390570e-01 1.79367498e-01 -3.09066046e-02 -9.83288646e-01 1.79367498e-01 -3.44382636e-02 -9.83170927e-01 1.79367498e-01 -3.79881673e-02 -9.83041286e-01 1.79367498e-01 -4.13281433e-02 -9.82907295e-01 1.79367498e-01 -4.46432233e-02 -9.82760072e-01 1.79367498e-01 -4.81121391e-02 -9.82597113e-01 1.79367498e-01 -5.15156239e-02 -9.82422769e-01 1.79367498e-01 -5.50214127e-02 -9.82234180e-01 1.79367498e-01 -5.84705696e-02 -9.82035577e-01 1.79367498e-01 -6.18839003e-02 -9.81823921e-01 1.79367498e-01 -6.53317571e-02 -9.81601715e-01 1.79367498e-01 -6.86628371e-02 -9.81372774e-01 1.79367498e-01 -7.21644834e-02 -9.81122375e-01 1.79367498e-01 -7.56108388e-02 -9.80863988e-01 1.79367498e-01 -7.90157616e-02 -9.80595171e-01 1.79367498e-01 -8.24384019e-02 -9.80313182e-01 1.79367498e-01 -8.57794359e-02 -9.80026722e-01 1.79367498e-01 -8.92137364e-02 -9.79719460e-01 1.79367498e-01 -9.26171392e-02 -9.79404926e-01 1.79367498e-01 -9.61164758e-02 -9.79067922e-01 1.79367498e-01 -9.95418876e-02 -9.78726685e-01 1.79367498e-01 -1.02922924e-01 -9.78374422e-01 1.79367498e-01 -1.06422953e-01 -9.77999866e-01 1.79367498e-01 -1.09776385e-01 -9.77631330e-01 1.79367498e-01 -1.13103501e-01 -9.77250397e-01 1.79367498e-01 -1.16509654e-01 -9.76848960e-01 1.79367498e-01 -1.19903862e-01 -9.76438522e-01 1.79367498e-01 -1.23411976e-01 -9.76003647e-01 1.79367498e-01 -1.26826435e-01 -9.75564361e-01 1.79367498e-01 -1.30143091e-01 -9.75128055e-01 1.79367498e-01 -1.33539006e-01 -9.74667966e-01 1.79367498e-01 -1.36928439e-01 -9.74198759e-01 1.79367498e-01 -1.40426666e-01 -9.73699868e-01 1.79367498e-01 -1.43824518e-01 -9.73203242e-01 1.79367498e-01 -1.47212714e-01 -9.72695053e-01 1.79367498e-01 -1.50597408e-01 -9.72179353e-01 1.79367498e-01 -1.53898403e-01 -9.71660674e-01 1.79367498e-01 -1.57289863e-01 -9.71118331e-01 1.79367498e-01 -1.60669670e-01 -9.70565975e-01 1.79367498e-01 -1.64173022e-01 -9.69978094e-01 1.79367498e-01 -1.67557195e-01 -9.69398975e-01 1.79367498e-01 -1.70848995e-01 -9.68828857e-01 1.79367498e-01 -1.74234197e-01 -9.68224108e-01 1.79367498e-01 -1.77608162e-01 -9.67606068e-01 1.79367498e-01 -1.81070775e-01 -9.66967821e-01 1.79367498e-01 -1.84457138e-01 -9.66327012e-01 1.79367498e-01 -1.87740996e-01 -9.65692043e-01 1.79367498e-01 -1.91090956e-01 -9.65036631e-01 1.79367498e-01 -1.94547027e-01 -9.64345753e-01 1.79367498e-01 -1.97911769e-01 -9.63661134e-01 1.79367498e-01 -2.01181665e-01 -9.62983310e-01 1.79367498e-01 -2.04558209e-01 -9.62272346e-01 1.79367498e-01 -2.07989201e-01 -9.61536109e-01 1.79367498e-01 -2.11363912e-01 -9.60798621e-01 1.79367498e-01 -2.14615077e-01 -9.60079908e-01 1.79367498e-01 -2.17978597e-01 -9.59320605e-01 1.79367498e-01 -2.21345514e-01 -9.58548427e-01 1.79367498e-01 -2.24775493e-01 -9.57753360e-01 1.79367498e-01 -2.28132024e-01 -9.56959307e-01 1.79367498e-01 -2.31352448e-01 -9.56185460e-01 1.79367498e-01 -2.34697908e-01 -9.55368400e-01 1.79367498e-01 -2.38035485e-01 -9.54541087e-01 1.79367498e-01 -2.41411820e-01 -9.53691840e-01 1.79367498e-01 -2.44776383e-01 -9.52836454e-01 1.79367498e-01 -2.48121858e-01 -9.51968670e-01 1.79367498e-01 -2.51450807e-01 -9.51098144e-01 1.79367498e-01 -2.54728019e-01 -9.50223982e-01 1.79367498e-01 -2.58142859e-01 -9.49303329e-01 1.79367498e-01 -2.61392802e-01 -9.48412001e-01 1.79367498e-01 -2.64688313e-01 -9.47497547e-01 1.79367498e-01 -2.67999977e-01 -9.46567237e-01 1.79367498e-01 -2.71204770e-01 -9.45652783e-01 1.79367498e-01 -2.74483323e-01 -9.44706500e-01 1.79367498e-01 -2.77784139e-01 -9.43740785e-01 1.79367498e-01 -2.81056941e-01 -9.42773044e-01 1.79367498e-01 -2.84356058e-01 -9.41779971e-01 1.79367498e-01 -2.87666678e-01 -9.40773904e-01 1.79367498e-01 -2.91025341e-01 -9.39743340e-01 1.79367498e-01 -2.94308782e-01 -9.38719153e-01 1.79367498e-01 -2.97586471e-01 -9.37685072e-01 1.79367498e-01 -3.00859421e-01 -9.36642885e-01 1.79367498e-01 -3.04048091e-01 -9.35610235e-01 1.79367498e-01 -3.07389617e-01 -9.34516966e-01 1.79367498e-01 -3.10646892e-01 -9.33440149e-01 1.79367498e-01 -3.13888937e-01 -9.32356238e-01 1.79367498e-01 -3.17152888e-01 -9.31249976e-01 1.79367498e-01 -3.20316344e-01 -9.30167019e-01 1.79367498e-01 -3.23608577e-01 -9.29024160e-01 1.79367498e-01 -3.26842695e-01 -9.27895129e-01 1.79367498e-01 -3.30111474e-01 -9.26734567e-01 1.79367498e-01 -3.33376348e-01 -9.25564826e-01 1.79367498e-01 -3.36577803e-01 -9.24408615e-01 1.79367498e-01 -3.39819163e-01 -9.23214316e-01 1.79367498e-01 -3.42953950e-01 -9.22049999e-01 1.79367498e-01 -3.46229613e-01 -9.20826495e-01 1.79367498e-01 -3.49446565e-01 -9.19614732e-01 1.79367498e-01 -3.52651209e-01 -9.18398857e-01 1.79367498e-01 -3.55939746e-01 -9.17121470e-01 1.79367498e-01 -3.59053671e-01 -9.15911376e-01 1.79367498e-01 -3.62172484e-01 -9.14682090e-01 1.79367498e-01 -3.65361363e-01 -9.13411736e-01 1.79367498e-01 -3.68558168e-01 -9.12126839e-01 1.79367498e-01 -3.71800989e-01 -9.10808682e-01 1.79367498e-01 -3.75014454e-01 -9.09489274e-01 1.79367498e-01 -3.78099382e-01 -9.08213735e-01 1.79367498e-01 -3.81246954e-01 -9.06896532e-01 1.79367498e-01 -3.84408802e-01 -9.05559838e-01 1.79367498e-01 -3.87646556e-01 -9.04177487e-01 1.79367498e-01 -3.90804291e-01 -9.02818620e-01 1.79367498e-01 -3.93948942e-01 -9.01453197e-01 1.79367498e-01 -3.97112638e-01 -9.00062978e-01 1.79367498e-01 -4.00165200e-01 -8.98709655e-01 1.79367498e-01 -4.03379023e-01 -8.97271991e-01 1.79367498e-01 -4.06519830e-01 -8.95853341e-01 1.79367498e-01 -4.09623235e-01 -8.94434988e-01 1.79367498e-01 -4.12740260e-01 -8.93003643e-01 1.79367498e-01 -4.15775239e-01 -8.91594708e-01 1.79367498e-01 -4.18892056e-01 -8.90134335e-01 1.79367498e-01 -4.22093600e-01 -8.88621747e-01 1.79367498e-01 -4.25177902e-01 -8.87149036e-01 1.79367498e-01 -4.28201407e-01 -8.85696769e-01 1.79367498e-01 -4.31354553e-01 -8.84164095e-01 1.79367498e-01 -4.34531987e-01 -8.82605374e-01 1.79367498e-01 -4.37531441e-01 -8.81123662e-01 1.79367498e-01 -4.40531105e-01 -8.79627347e-01 1.79367498e-01 -4.43595409e-01 -8.78086388e-01 1.79367498e-01 -4.46663409e-01 -8.76529276e-01 1.79367498e-01 -4.49778676e-01 -8.74933600e-01 1.79367498e-01 -4.52834696e-01 -8.73356402e-01 1.79367498e-01 -4.55793470e-01 -8.71818006e-01 1.79367498e-01 -4.58845407e-01 -8.70214462e-01 1.79367498e-01 -4.61878031e-01 -8.68607879e-01 1.79367498e-01 -4.64980662e-01 -8.66951585e-01 1.79367498e-01 -4.68012363e-01 -8.65318179e-01 1.79367498e-01 -4.71000075e-01 -8.63697410e-01 1.79367498e-01 -4.74038035e-01 -8.62033129e-01 1.79367453e-01 -4.77020949e-01 -8.60382497e-01 1.79367498e-01 -4.80103046e-01 -8.58667791e-01 1.79367498e-01 -4.83029962e-01 -8.57027531e-01 1.79367498e-01 -4.86000001e-01 -8.55344355e-01 1.79367498e-01 -4.88986909e-01 -8.53643239e-01 1.79367498e-01 -4.91901964e-01 -8.51964056e-01 1.79367498e-01 -4.94947106e-01 -8.50198865e-01 1.79367498e-01 -4.97927725e-01 -8.48459303e-01 1.79367498e-01 -5.00873744e-01 -8.46720755e-01 1.79367498e-01 -5.03825665e-01 -8.44968140e-01 1.79367498e-01 -5.06749392e-01 -8.43217492e-01 1.79367498e-01 -5.09710789e-01 -8.41430604e-01 1.79367498e-01 -5.12626886e-01 -8.39659095e-01 1.79367498e-01 -5.15654802e-01 -8.37801278e-01 1.79367498e-01 -5.18496990e-01 -8.36047411e-01 1.79367498e-01 -5.21316230e-01 -8.34290445e-01 1.79367498e-01 -5.24309874e-01 -8.32411051e-01 1.79367498e-01 -5.27299464e-01 -8.30521703e-01 1.79367498e-01 -5.30196309e-01 -8.28675330e-01 1.79367498e-01 -5.33010840e-01 -8.26868117e-01 1.79367498e-01 -5.35817087e-01 -8.25052559e-01 1.79367498e-01 -5.38705349e-01 -8.23167920e-01 1.79367498e-01 -5.41558266e-01 -8.21295798e-01 1.79367498e-01 -5.44415355e-01 -8.19402039e-01 1.79367498e-01 -5.47267556e-01 -8.17501068e-01 1.79367498e-01 -5.50190270e-01 -8.15538764e-01 1.79367498e-01 -5.53084075e-01 -8.13577592e-01 1.79367498e-01 -5.55836380e-01 -8.11702132e-01 1.79367498e-01 -5.58708310e-01 -8.09725523e-01 1.79367498e-01 -5.61542630e-01 -8.07765365e-01 1.79367498e-01 -5.64351261e-01 -8.05800617e-01 1.79367498e-01 -5.67251384e-01 -8.03765178e-01 1.79367498e-01 -5.69975078e-01 -8.01836014e-01 1.79367498e-01 -5.72743118e-01 -7.99860060e-01 1.79367498e-01 -5.75530589e-01 -7.97854900e-01 1.79367498e-01 -5.78303397e-01 -7.95850158e-01 1.79367498e-01 -5.81175089e-01 -7.93753684e-01 1.79367498e-01 -5.83960116e-01 -7.91707695e-01 1.79367498e-01 -5.86646855e-01 -7.89720356e-01 1.79367498e-01 -5.89307964e-01 -7.87734389e-01 1.79367498e-01 -5.92068732e-01 -7.85662293e-01 1.79367498e-01 -5.94865024e-01 -7.83547997e-01 1.79367498e-01 -5.97622454e-01 -7.81447947e-01 1.79367498e-01 -6.00341320e-01 -7.79356718e-01 1.79367498e-01 -6.03062630e-01 -7.77256906e-01 1.79367498e-01 -6.05688751e-01 -7.75210321e-01 1.79367498e-01 -6.08478189e-01 -7.73024082e-01 1.79367498e-01 -6.11170053e-01 -7.70896733e-01 1.79367498e-01 -6.13833129e-01 -7.68778384e-01 1.79367498e-01 -6.16546273e-01 -7.66605437e-01 1.79367498e-01 -6.19139731e-01 -7.64512122e-01 1.79367498e-01 -6.21868789e-01 -7.62291014e-01 1.79367498e-01 -6.24547839e-01 -7.60100782e-01 1.79367498e-01 -6.27113402e-01 -7.57984340e-01 1.79367498e-01 -6.29749656e-01 -7.55795300e-01 1.79367498e-01 -6.32424951e-01 -7.53557086e-01 1.79367498e-01 -6.35123610e-01 -7.51284719e-01 1.79367498e-01 -6.37710273e-01 -7.49089301e-01 1.79367498e-01 -6.40238404e-01 -7.46930540e-01 1.79367498e-01 -6.42849326e-01 -7.44686663e-01 1.79367498e-01 -6.45509124e-01 -7.42380023e-01 1.79367498e-01 -6.48153424e-01 -7.40071237e-01 1.79367498e-01 -6.50686085e-01 -7.37847984e-01 1.79367498e-01 -6.53181851e-01 -7.35639572e-01 1.79367498e-01 -6.55734360e-01 -7.33365059e-01 1.79367498e-01 -6.58305049e-01 -7.31058121e-01 1.79367498e-01 -6.60915673e-01 -7.28698730e-01 1.79367498e-01 -6.63478911e-01 -7.26364553e-01 1.79367498e-01 -6.65982366e-01 -7.24073052e-01 1.79367498e-01 -6.68507278e-01 -7.21741498e-01 1.79367498e-01 -6.71012759e-01 -7.19410658e-01 1.79367498e-01 -6.73592150e-01 -7.16996670e-01 1.79367498e-01 -6.76034153e-01 -7.14693785e-01 1.79367498e-01 -6.78513110e-01 -7.12344050e-01 1.79367498e-01 -6.80996537e-01 -7.09963381e-01 1.79367498e-01 -6.83414876e-01 -7.07649469e-01 1.79367498e-01 -6.85902059e-01 -7.05237329e-01 1.79367498e-01 -6.88362777e-01 -7.02831507e-01 1.79367498e-01 -6.90778434e-01 -7.00460076e-01 1.79367498e-01 -6.93217933e-01 -6.98048711e-01 1.79367498e-01 -6.95697546e-01 -6.95556819e-01 1.79367498e-01 -6.98136866e-01 -6.93129838e-01 1.79367498e-01 -7.00559795e-01 -6.90676630e-01 1.79367498e-01 -7.02965796e-01 -6.88226759e-01 1.79367498e-01 -7.05307007e-01 -6.85829580e-01 1.79367498e-01 -7.07716942e-01 -6.83344245e-01 1.79367498e-01 -7.10141361e-01 -6.80809081e-01 1.79367498e-01 -7.12515414e-01 -6.78334534e-01 1.79367498e-01 -7.14894891e-01 -6.75819933e-01 1.79367498e-01 -7.17215359e-01 -6.73358738e-01 1.79367498e-01 -7.19486773e-01 -6.70929193e-01 1.79367498e-01 -7.21863270e-01 -6.68374419e-01 1.79367498e-01 -7.24280655e-01 -6.65757775e-01 1.79367498e-01 -7.26550698e-01 -6.63277090e-01 1.79367498e-01 -7.28776813e-01 -6.60830379e-01 1.79367498e-01 -7.31083274e-01 -6.58277035e-01 1.79367498e-01 -7.33446717e-01 -6.55641198e-01 1.79367498e-01 -7.35754848e-01 -6.53053701e-01 1.79367498e-01 -7.38005698e-01 -6.50505364e-01 1.79367498e-01 -7.40275979e-01 -6.47921979e-01 1.79367498e-01 -7.42532253e-01 -6.45334363e-01 1.79367498e-01 -7.44837821e-01 -6.42673016e-01 1.79367498e-01 -7.47033775e-01 -6.40120208e-01 1.79367498e-01 -7.49196351e-01 -6.37584329e-01 1.79367498e-01 -7.51423955e-01 -6.34961009e-01 1.79367498e-01 -7.53662348e-01 -6.32299244e-01 1.79367498e-01 -7.55928099e-01 -6.29590809e-01 1.79367498e-01 -7.58092165e-01 -6.26981914e-01 1.79367498e-01 -7.60220528e-01 -6.24404490e-01 1.79367498e-01 -7.62407959e-01 -6.21726215e-01 1.79367498e-01 -7.64557183e-01 -6.19084001e-01 1.79367498e-01 -7.66771853e-01 -6.16337299e-01 1.79367498e-01 -7.68984318e-01 -6.13575161e-01 1.79367498e-01 -7.71117628e-01 -6.10890925e-01 1.79367498e-01 -7.73186088e-01 -6.08273447e-01 1.79367498e-01 -7.75234401e-01 -6.05660439e-01 1.79367498e-01 -7.77406335e-01 -6.02867663e-01 1.79367498e-01 -7.79558957e-01 -6.00083411e-01 1.79367498e-01 -7.81642377e-01 -5.97365916e-01 1.79367498e-01 -7.83704996e-01 -5.94658554e-01 1.79367498e-01 -7.85707295e-01 -5.92012882e-01 1.79367498e-01 -7.87815273e-01 -5.89200020e-01 1.79367498e-01 -7.89875805e-01 -5.86436987e-01 1.79367498e-01 -7.91868091e-01 -5.83741963e-01 1.79367498e-01 -7.93905675e-01 -5.80968082e-01 1.79367498e-01 -7.95935631e-01 -5.78183651e-01 1.79367498e-01 -7.98003614e-01 -5.75323880e-01 1.79367498e-01 -7.99989581e-01 -5.72565973e-01 1.79367498e-01 -8.01933587e-01 -5.69836140e-01 1.79367498e-01 -8.03921342e-01 -5.67033648e-01 1.79367498e-01 -8.05906355e-01 -5.64203322e-01 1.79367498e-01 -8.07902873e-01 -5.61340928e-01 1.79367498e-01 -8.09855759e-01 -5.58524370e-01 1.79367498e-01 -8.11752617e-01 -5.55760562e-01 1.79367498e-01 -8.13675702e-01 -5.52941442e-01 1.79367498e-01 -8.15588534e-01 -5.50117731e-01 1.79367498e-01 -8.17555845e-01 -5.47184706e-01 1.79367498e-01 -8.19476068e-01 -5.44306338e-01 1.79367498e-01 -8.21375787e-01 -5.41434646e-01 1.79367498e-01 -8.23265433e-01 -5.38558662e-01 1.79367498e-01 -8.25076222e-01 -5.35779357e-01 1.79367498e-01 -8.26939762e-01 -5.32900333e-01 1.79367498e-01 -8.28841031e-01 -5.29934585e-01 1.79367498e-01 -8.30708385e-01 -5.27006269e-01 1.79367498e-01 -8.32498372e-01 -5.24177432e-01 1.79367498e-01 -8.34285855e-01 -5.21321297e-01 1.79367498e-01 -8.36129427e-01 -5.18365562e-01 1.79367498e-01 -8.37930202e-01 -5.15444577e-01 1.79367498e-01 -8.39732766e-01 -5.12508333e-01 1.79367498e-01 -8.41506779e-01 -5.09586632e-01 1.79367498e-01 -8.43325615e-01 -5.06571352e-01 1.79367498e-01 -8.45137537e-01 -5.03540576e-01 1.79367498e-01 -8.46847832e-01 -5.00660241e-01 1.79367498e-01 -8.48585069e-01 -4.97710496e-01 1.79367498e-01 -8.50327611e-01 -4.94726390e-01 1.79367498e-01 -8.52021754e-01 -4.91806835e-01 1.79367498e-01 -8.53718102e-01 -4.88854647e-01 1.79367498e-01 -8.55403960e-01 -4.85894889e-01 1.79367498e-01 -8.57077241e-01 -4.82944906e-01 1.79367498e-01 -8.58760893e-01 -4.79937822e-01 1.79367498e-01 -8.60439658e-01 -4.76918846e-01 1.79367498e-01 -8.62140357e-01 -4.73842591e-01 1.79367498e-01 -8.63815904e-01 -4.70786631e-01 1.79367498e-01 -8.65422726e-01 -4.67819154e-01 1.79367498e-01 -8.67017984e-01 -4.64858115e-01 1.79367498e-01 -8.68659854e-01 -4.61781740e-01 1.79367498e-01 -8.70322764e-01 -4.58641499e-01 1.79367498e-01 -8.71903718e-01 -4.55632865e-01 1.79367498e-01 -8.73445809e-01 -4.52664137e-01 1.79367498e-01 -8.74986768e-01 -4.49679554e-01 1.79367498e-01 -8.76589239e-01 -4.46544737e-01 1.79367498e-01 -8.78199995e-01 -4.43371326e-01 1.79367498e-01 -8.79703939e-01 -4.40379411e-01 1.79367498e-01 -8.81180465e-01 -4.37416494e-01 1.79367498e-01 -8.82697523e-01 -4.34347361e-01 1.79367498e-01 -8.84202063e-01 -4.31277752e-01 1.79367498e-01 -8.85749459e-01 -4.28090960e-01 1.79367498e-01 -8.87286782e-01 -4.24890906e-01 1.79367498e-01 -8.88738215e-01 -4.21848834e-01 1.79367498e-01 -8.90159845e-01 -4.18837368e-01 1.79367498e-01 -8.91606152e-01 -4.15754050e-01 1.79367498e-01 -8.93096745e-01 -4.12540585e-01 1.79367498e-01 -8.94561648e-01 -4.09356564e-01 1.79367498e-01 -8.95933628e-01 -4.06344563e-01 1.79367498e-01 -8.97324920e-01 -4.03261840e-01 1.79367498e-01 -8.98718417e-01 -4.00149405e-01 1.79367498e-01 -9.00160372e-01 -3.96892458e-01 1.79367498e-01 -9.01586294e-01 -3.93646896e-01 1.79367498e-01 -9.02948022e-01 -3.90509486e-01 1.79367498e-01 -9.04306710e-01 -3.87341291e-01 1.79367498e-01 -9.05619919e-01 -3.84272307e-01 1.79367498e-01 -9.06921327e-01 -3.81191403e-01 1.79367498e-01 -9.08257425e-01 -3.77993703e-01 1.79367498e-01 -9.09595430e-01 -3.74761581e-01 1.79367498e-01 -9.10905302e-01 -3.71573031e-01 1.79367498e-01 -9.12158132e-01 -3.68482023e-01 1.79367498e-01 -9.13469911e-01 -3.65216672e-01 1.79367498e-01 -9.14742649e-01 -3.62024754e-01 1.79367498e-01 -9.15968955e-01 -3.58908772e-01 1.79367498e-01 -9.17210817e-01 -3.55706662e-01 1.79367498e-01 -9.18461680e-01 -3.52488786e-01 1.79367498e-01 -9.19714749e-01 -3.49184424e-01 1.79367498e-01 -9.20909703e-01 -3.46006334e-01 1.79367498e-01 -9.22080874e-01 -3.42872560e-01 1.79367498e-01 -9.23307061e-01 -3.39568377e-01 1.79367498e-01 -9.24530923e-01 -3.36242467e-01 1.79367498e-01 -9.25690174e-01 -3.33024591e-01 1.79367498e-01 -9.26823497e-01 -3.29873502e-01 1.79367498e-01 -9.27959323e-01 -3.26652855e-01 1.79367498e-01 -9.29101050e-01 -3.23391348e-01 1.79367498e-01 -9.30195272e-01 -3.20237398e-01 1.79367498e-01 -9.31305587e-01 -3.16984355e-01 1.79367498e-01 -9.32403028e-01 -3.13747644e-01 1.79367498e-01 -9.33524847e-01 -3.10391963e-01 1.79367498e-01 -9.34611499e-01 -3.07106256e-01 1.79367498e-01 -9.35643077e-01 -3.03948373e-01 1.79367498e-01 -9.36721563e-01 -3.00606102e-01 1.79367498e-01 -9.37767386e-01 -2.97330141e-01 1.79367498e-01 -9.38788533e-01 -2.94090837e-01 1.79367498e-01 -9.39813793e-01 -2.90798753e-01 1.79367498e-01 -9.40827310e-01 -2.87497669e-01 1.79367498e-01 -9.41844404e-01 -2.84146070e-01 1.79367498e-01 -9.42813814e-01 -2.80919075e-01 1.79367498e-01 -9.43782628e-01 -2.77645260e-01 1.79367498e-01 -9.44749117e-01 -2.74342477e-01 1.79367498e-01 -9.45700169e-01 -2.71035075e-01 1.79367498e-01 -9.46638405e-01 -2.67746955e-01 1.79367498e-01 -9.47543323e-01 -2.64529288e-01 1.79367498e-01 -9.48464513e-01 -2.61202306e-01 1.79367498e-01 -9.49372113e-01 -2.57891178e-01 1.79367498e-01 -9.50284421e-01 -2.54500419e-01 1.79367498e-01 -9.51194048e-01 -2.51086563e-01 1.79367498e-01 -9.52062249e-01 -2.47768179e-01 1.79367498e-01 -9.52901840e-01 -2.44532049e-01 1.79367498e-01 -9.53714311e-01 -2.41327897e-01 1.79367498e-01 -9.54576254e-01 -2.37892836e-01 1.79367498e-01 -9.55430984e-01 -2.34449923e-01 1.79367498e-01 -9.56239283e-01 -2.31133118e-01 1.79367498e-01 -9.57021832e-01 -2.27875397e-01 1.79367498e-01 -9.57788587e-01 -2.24626765e-01 1.79367498e-01 -9.58582759e-01 -2.21199781e-01 1.79367498e-01 -9.59379017e-01 -2.17723057e-01 1.79367498e-01 -9.60112989e-01 -2.14471087e-01 1.79367498e-01 -9.60852385e-01 -2.11125314e-01 1.79367498e-01 -9.61586595e-01 -2.07763195e-01 1.79367498e-01 -9.62279081e-01 -2.04529032e-01 1.79367498e-01 -9.63013291e-01 -2.01047897e-01 1.79367498e-01 -9.63727653e-01 -1.97591200e-01 1.79367498e-01 -9.64394510e-01 -1.94310457e-01 1.79367498e-01 -9.65046585e-01 -1.91044092e-01 1.79367498e-01 -9.65707004e-01 -1.87679991e-01 1.79367498e-01 -9.66371894e-01 -1.84216157e-01 1.79367498e-01 -9.67031717e-01 -1.80732712e-01 1.79367498e-01 -9.67639327e-01 -1.77438736e-01 1.79367498e-01 -9.68236506e-01 -1.74178228e-01 1.79367498e-01 -9.68839884e-01 -1.70786738e-01 1.79367498e-01 -9.69439507e-01 -1.67315438e-01 1.79367498e-01 -9.70034361e-01 -1.63844988e-01 1.79367498e-01 -9.70585704e-01 -1.60553396e-01 1.79367498e-01 -9.71140921e-01 -1.57156035e-01 1.79367498e-01 -9.71684575e-01 -1.53770357e-01 1.79367498e-01 -9.72212493e-01 -1.50376901e-01 1.79367498e-01 -9.72731233e-01 -1.46985546e-01 1.79367498e-01 -9.73234594e-01 -1.43616706e-01 1.79367498e-01 -9.73734856e-01 -1.40195176e-01 1.79367498e-01 -9.74203944e-01 -1.36893719e-01 1.79367498e-01 -9.74685013e-01 -1.33428872e-01 1.79367498e-01 -9.75147903e-01 -1.29989326e-01 1.79367498e-01 -9.75594521e-01 -1.26592010e-01 1.79367498e-01 -9.76033032e-01 -1.23185799e-01 1.79367498e-01 -9.76443887e-01 -1.19871333e-01 1.79367498e-01 -9.76864398e-01 -1.16382264e-01 1.79367498e-01 -9.77267027e-01 -1.12959318e-01 1.79367498e-01 -9.77643967e-01 -1.09652571e-01 1.79367498e-01 -9.78031993e-01 -1.06118374e-01 1.79367498e-01 -9.78406608e-01 -1.02621540e-01 1.79367498e-01 -9.78755295e-01 -9.92398337e-02 1.79367498e-01 -9.79089677e-01 -9.58950892e-02 1.79367498e-01 -9.79415894e-01 -9.25209224e-02 1.79367498e-01 -9.79736567e-01 -8.90660062e-02 1.79367512e-01 -9.80030835e-01 -8.57605711e-02 1.79367498e-01 -9.80323315e-01 -8.23497325e-02 1.79367527e-01 -9.80608642e-01 -7.88990408e-02 1.79367572e-01 -9.80884910e-01 -7.53752366e-02 1.79367587e-01 -9.81148005e-01 -7.19199106e-02 1.79367602e-01 -9.81382608e-01 -6.86301291e-02 1.79367676e-01 -9.81622279e-01 -6.51127547e-02 1.79367661e-01 -9.81852233e-01 -6.16259947e-02 1.79367706e-01 -9.82042730e-01 -5.84997274e-02 1.79368034e-01 -9.82187927e-01 -5.59766814e-02 1.79368898e-01 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. 0. 0. -9.83641624e-01 -1.65931135e-02 1.79368854e-01 -9.83672321e-01 -1.46800885e-02 1.79368868e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.65297818e-01 3.48422974e-02 2.58819133e-01 -9.65210319e-01 3.71014886e-02 2.58819193e-01 -9.65068519e-01 4.06998582e-02 2.58819193e-01 -9.64920700e-01 4.40961681e-02 2.58819193e-01 -9.64766622e-01 4.73422818e-02 2.58819193e-01 -9.64596629e-01 5.07023707e-02 2.58819193e-01 -9.64411199e-01 5.41697256e-02 2.58819193e-01 -9.64217842e-01 5.74862957e-02 2.58819193e-01 -9.64011848e-01 6.08263426e-02 2.58819193e-01 -9.63794887e-01 6.42069131e-02 2.58819193e-01 -9.63566422e-01 6.75152689e-02 2.58819193e-01 -9.63335276e-01 7.07645118e-02 2.58819193e-01 -9.63076591e-01 7.42150322e-02 2.58819193e-01 -9.62803245e-01 7.76729584e-02 2.58819193e-01 -9.62533116e-01 8.09468403e-02 2.58819193e-01 -9.62247789e-01 8.42865184e-02 2.58819193e-01 -9.61938500e-01 8.77355412e-02 2.58819193e-01 -9.61631417e-01 9.10408124e-02 2.58819193e-01 -9.61305559e-01 9.44212452e-02 2.58819193e-01 -9.60977614e-01 9.77087542e-02 2.58819193e-01 -9.60641384e-01 1.00957677e-01 2.58819193e-01 -9.60272491e-01 1.04405425e-01 2.58819193e-01 -9.59890723e-01 1.07864052e-01 2.58819193e-01 -9.59506810e-01 1.11213639e-01 2.58819193e-01 -9.59111452e-01 1.14568643e-01 2.58819193e-01 -9.58709002e-01 1.17899157e-01 2.58819193e-01 -9.58293021e-01 1.21244669e-01 2.58819193e-01 -9.57860708e-01 1.24608472e-01 2.58819193e-01 -9.57413316e-01 1.27992168e-01 2.58819193e-01 -9.56974566e-01 1.31236851e-01 2.58819193e-01 -9.56531823e-01 1.34433582e-01 2.58819193e-01 -9.56042230e-01 1.37864783e-01 2.58819193e-01 -9.55537021e-01 1.41316861e-01 2.58819193e-01 -9.55038786e-01 1.44641966e-01 2.58819193e-01 -9.54527617e-01 1.47987574e-01 2.58819193e-01 -9.54008460e-01 1.51302263e-01 2.58819193e-01 -9.53484952e-01 1.54558539e-01 2.58819193e-01 -9.52943087e-01 1.57879978e-01 2.58819193e-01 -9.52366233e-01 1.61315426e-01 2.58819193e-01 -9.51809645e-01 1.64562970e-01 2.58819193e-01 -9.51237500e-01 1.67860478e-01 2.58819193e-01 -9.50626373e-01 1.71285823e-01 2.58819193e-01 -9.50017691e-01 1.74603894e-01 2.58819193e-01 -9.49401259e-01 1.77936912e-01 2.58819193e-01 -9.48791862e-01 1.81148842e-01 2.58819193e-01 -9.48179066e-01 1.84331894e-01 2.58819193e-01 -9.47507024e-01 1.87765121e-01 2.58819193e-01 -9.46823835e-01 1.91179127e-01 2.58819193e-01 -9.46146846e-01 1.94499910e-01 2.58819193e-01 -9.45483625e-01 1.97694704e-01 2.58819193e-01 -9.44793224e-01 2.00982854e-01 2.58819193e-01 -9.44060743e-01 2.04390615e-01 2.58819193e-01 -9.43356156e-01 2.07604423e-01 2.58819193e-01 -9.42637086e-01 2.10860372e-01 2.58819193e-01 -9.41884577e-01 2.14184925e-01 2.58819193e-01 -9.41154361e-01 2.17373848e-01 2.58819193e-01 -9.40375865e-01 2.20732942e-01 2.58819193e-01 -9.39575672e-01 2.24106163e-01 2.58819193e-01 -9.38791811e-01 2.27373108e-01 2.58819193e-01 -9.37991142e-01 2.30646074e-01 2.58819193e-01 -9.37174022e-01 2.33937547e-01 2.58819193e-01 -9.36372578e-01 2.37123087e-01 2.58819193e-01 -9.35546637e-01 2.40370020e-01 2.58819193e-01 -9.34678435e-01 2.43724033e-01 2.58819193e-01 -9.33844149e-01 2.46905282e-01 2.58819193e-01 -9.32977200e-01 2.50158817e-01 2.58819193e-01 -9.32079256e-01 2.53485173e-01 2.58819193e-01 -9.31185484e-01 2.56738931e-01 2.58819193e-01 -9.30288017e-01 2.59984791e-01 2.58819193e-01 -9.29387927e-01 2.63177037e-01 2.58819193e-01 -9.28471684e-01 2.66391098e-01 2.58819193e-01 -9.27529573e-01 2.69650519e-01 2.58819193e-01 -9.26591098e-01 2.72863179e-01 2.58819193e-01 -9.25601006e-01 2.76204377e-01 2.58819193e-01 -9.24657106e-01 2.79339284e-01 2.58819193e-01 -9.23680127e-01 2.82559842e-01 2.58819193e-01 -9.22658503e-01 2.85876274e-01 2.58819193e-01 -9.21664357e-01 2.89065689e-01 2.58819193e-01 -9.20646250e-01 2.92290449e-01 2.58819193e-01 -9.19645011e-01 2.95428991e-01 2.58819193e-01 -9.18639541e-01 2.98533350e-01 2.58819193e-01 -9.17566121e-01 3.01821530e-01 2.58819193e-01 -9.16472256e-01 3.05126250e-01 2.58819193e-01 -9.15398061e-01 3.08335453e-01 2.58819193e-01 -9.14317131e-01 3.11525226e-01 2.58819193e-01 -9.13226426e-01 3.14712971e-01 2.58819193e-01 -9.12146866e-01 3.17822784e-01 2.58819193e-01 -9.11035359e-01 3.20995778e-01 2.58819193e-01 -9.09887552e-01 3.24240565e-01 2.58819193e-01 -9.08770144e-01 3.27350438e-01 2.58819193e-01 -9.07664061e-01 3.30413043e-01 2.58819193e-01 -9.06469882e-01 3.33660096e-01 2.58819193e-01 -9.05262113e-01 3.36908847e-01 2.58819193e-01 -9.04073536e-01 3.40090007e-01 2.58819193e-01 -9.02893424e-01 3.43221635e-01 2.58819193e-01 -9.01730239e-01 3.46289545e-01 2.58819193e-01 -9.00529027e-01 3.49381179e-01 2.58819193e-01 -8.99276376e-01 3.52600485e-01 2.58819193e-01 -8.98014963e-01 3.55800718e-01 2.58819193e-01 -8.96801293e-01 3.58844459e-01 2.58819193e-01 -8.95550013e-01 3.61959368e-01 2.58819193e-01 -8.94250453e-01 3.65160435e-01 2.58819193e-01 -8.92968655e-01 3.68276983e-01 2.58819193e-01 -8.91688228e-01 3.71369511e-01 2.58819193e-01 -8.90410781e-01 3.74420851e-01 2.58819193e-01 -8.89138818e-01 3.77431601e-01 2.58819193e-01 -8.87770116e-01 3.80633920e-01 2.58819193e-01 -8.86401772e-01 3.83817255e-01 2.58819193e-01 -8.85065079e-01 3.86891872e-01 2.58819193e-01 -8.83706748e-01 3.89983445e-01 2.58819193e-01 -8.82340193e-01 3.93065542e-01 2.58819193e-01 -8.80961895e-01 3.96143824e-01 2.58819193e-01 -8.79612386e-01 3.99129778e-01 2.58819193e-01 -8.78214300e-01 4.02194947e-01 2.58819193e-01 -8.76772225e-01 4.05329525e-01 2.58819193e-01 -8.75386119e-01 4.08316195e-01 2.58819193e-01 -8.73964965e-01 4.11350787e-01 2.58819193e-01 -8.72487247e-01 4.14475858e-01 2.58819193e-01 -8.71032834e-01 4.17520255e-01 2.58819193e-01 -8.69576514e-01 4.20554370e-01 2.58819193e-01 -8.68123651e-01 4.23544079e-01 2.58819193e-01 -8.66683900e-01 4.26475614e-01 2.58819193e-01 -8.65169287e-01 4.29542691e-01 2.58819193e-01 -8.63618910e-01 4.32648569e-01 2.58819193e-01 -8.62099648e-01 4.35672134e-01 2.58819193e-01 -8.60583305e-01 4.38657850e-01 2.58819193e-01 -8.59046638e-01 4.41660970e-01 2.58819193e-01 -8.57505143e-01 4.44642842e-01 2.58819193e-01 -8.55954587e-01 4.47622865e-01 2.58819193e-01 -8.54382217e-01 4.50621575e-01 2.58819193e-01 -8.52833211e-01 4.53541458e-01 2.58819193e-01 -8.51295888e-01 4.56422329e-01 2.58819193e-01 -8.49664330e-01 4.59452450e-01 2.58819193e-01 -8.48003685e-01 4.62512493e-01 2.58819193e-01 -8.46387208e-01 4.65462446e-01 2.58819193e-01 -8.44761074e-01 4.68398601e-01 2.58819193e-01 -8.43120277e-01 4.71348882e-01 2.58819193e-01 -8.41477990e-01 4.74278629e-01 2.58819193e-01 -8.39812100e-01 4.77220207e-01 2.58819193e-01 -8.38126421e-01 4.80176747e-01 2.58819193e-01 -8.36488545e-01 4.83023047e-01 2.58819193e-01 -8.34808588e-01 4.85923022e-01 2.58819193e-01 -8.33102524e-01 4.88838792e-01 2.58819193e-01 -8.31392884e-01 4.91742641e-01 2.58819193e-01 -8.29620123e-01 4.94726568e-01 2.58819193e-01 -8.27893198e-01 4.97610599e-01 2.58819193e-01 -8.26137960e-01 5.00518501e-01 2.58819193e-01 -8.24383318e-01 5.03408074e-01 2.58819193e-01 -8.22622716e-01 5.06276190e-01 2.58819193e-01 -8.20860267e-01 5.09130895e-01 2.58819193e-01 -8.19125712e-01 5.11915147e-01 2.58819193e-01 -8.17345202e-01 5.14755309e-01 2.58819193e-01 -8.15499544e-01 5.17670989e-01 2.58819193e-01 -8.13680589e-01 5.20527661e-01 2.58819193e-01 -8.11835289e-01 5.23397684e-01 2.58819193e-01 -8.10022473e-01 5.26199281e-01 2.58819193e-01 -8.08238328e-01 5.28933704e-01 2.58819193e-01 -8.06373596e-01 5.31777143e-01 2.58819193e-01 -8.04449975e-01 5.34678757e-01 2.58819193e-01 -8.02573323e-01 5.37494600e-01 2.58819193e-01 -8.00726414e-01 5.40244401e-01 2.58819193e-01 -7.98890114e-01 5.42951703e-01 2.58819193e-01 -7.96980202e-01 5.45755863e-01 2.58819193e-01 -7.95027554e-01 5.48596203e-01 2.58819193e-01 -7.93072999e-01 5.51415801e-01 2.58819193e-01 -7.91201293e-01 5.54093838e-01 2.58819193e-01 -7.89268255e-01 5.56853354e-01 2.58819193e-01 -7.87236035e-01 5.59714139e-01 2.58819193e-01 -7.85285532e-01 5.62451720e-01 2.58819193e-01 -7.83303201e-01 5.65203547e-01 2.58819193e-01 -7.81333029e-01 5.67928374e-01 2.58819193e-01 -7.79352725e-01 5.70640981e-01 2.58819193e-01 -7.77433932e-01 5.73251367e-01 2.58819193e-01 -7.75417149e-01 5.75977147e-01 2.58819193e-01 -7.73337126e-01 5.78766763e-01 2.58819193e-01 -7.71378160e-01 5.81375420e-01 2.58819193e-01 -7.69345224e-01 5.84066451e-01 2.58819193e-01 -7.67237723e-01 5.86831689e-01 2.58819193e-01 -7.65180230e-01 5.89509249e-01 2.58819193e-01 -7.63101518e-01 5.92197716e-01 2.58819193e-01 -7.61062920e-01 5.94815612e-01 2.58819193e-01 -7.59057164e-01 5.97373486e-01 2.58819193e-01 -7.56933153e-01 6.00064397e-01 2.58819193e-01 -7.54743516e-01 6.02816820e-01 2.58819193e-01 -7.52619386e-01 6.05466247e-01 2.58819193e-01 -7.50533342e-01 6.08049273e-01 2.58819193e-01 -7.48452663e-01 6.10605717e-01 2.58819193e-01 -7.46329188e-01 6.13202274e-01 2.58819193e-01 -7.44141459e-01 6.15854383e-01 2.58819193e-01 -7.41969943e-01 6.18468583e-01 2.58819193e-01 -7.39876688e-01 6.20971918e-01 2.58819193e-01 -7.37693787e-01 6.23564243e-01 2.58819193e-01 -7.35433280e-01 6.26226425e-01 2.58819193e-01 -7.33223855e-01 6.28813267e-01 2.58819193e-01 -7.31025517e-01 6.31370366e-01 2.58819193e-01 -7.28845179e-01 6.33882821e-01 2.58819193e-01 -7.26682127e-01 6.36361539e-01 2.58819193e-01 -7.24523544e-01 6.38817430e-01 2.58819193e-01 -7.22228467e-01 6.41412795e-01 2.58819193e-01 -7.19922066e-01 6.44001782e-01 2.58819193e-01 -7.17711508e-01 6.46459997e-01 2.58819193e-01 -7.15469718e-01 6.48945034e-01 2.58819193e-01 -7.13138163e-01 6.51502252e-01 2.58819193e-01 -7.10876644e-01 6.53972864e-01 2.58819193e-01 -7.08558619e-01 6.56482518e-01 2.58819193e-01 -7.06327081e-01 6.58881128e-01 2.58819193e-01 -7.04094827e-01 6.61267281e-01 2.58819193e-01 -7.01719940e-01 6.63785040e-01 2.58819193e-01 -6.99344933e-01 6.66289747e-01 2.58819193e-01 -6.97005332e-01 6.68731511e-01 2.58819193e-01 -6.94681346e-01 6.71156645e-01 2.58819193e-01 -6.92386210e-01 6.73520327e-01 2.58819193e-01 -6.90041542e-01 6.75922215e-01 2.58819193e-01 -6.87610209e-01 6.78396881e-01 2.58819193e-01 -6.85232639e-01 6.80800200e-01 2.58819193e-01 -6.82832718e-01 6.83190763e-01 2.58819193e-01 -6.80529296e-01 6.85499787e-01 2.58819193e-01 -6.78160548e-01 6.87844753e-01 2.58819193e-01 -6.75644100e-01 6.90313101e-01 2.58819193e-01 -6.73260510e-01 6.92640007e-01 2.58819193e-01 -6.70808077e-01 6.95016623e-01 2.58819193e-01 -6.68431282e-01 6.97291672e-01 2.58819193e-01 -6.66057229e-01 6.99566722e-01 2.58819193e-01 -6.63545966e-01 7.01946080e-01 2.58819193e-01 -6.61051035e-01 7.04295874e-01 2.58819193e-01 -6.58628881e-01 7.06559062e-01 2.58819193e-01 -6.56168818e-01 7.08849549e-01 2.58819193e-01 -6.53650761e-01 7.11173475e-01 2.58819193e-01 -6.51201487e-01 7.13413835e-01 2.58819193e-01 -6.48716807e-01 7.15676546e-01 2.58819193e-01 -6.46237254e-01 7.17913508e-01 2.58819193e-01 -6.43781483e-01 7.20117867e-01 2.58819193e-01 -6.41211510e-01 7.22408831e-01 2.58819193e-01 -6.38663709e-01 7.24659324e-01 2.58819193e-01 -6.36129856e-01 7.26883769e-01 2.58819193e-01 -6.33581340e-01 7.29107797e-01 2.58819193e-01 -6.31058216e-01 7.31293559e-01 2.58819193e-01 -6.28416479e-01 7.33563840e-01 2.58819193e-01 -6.25828505e-01 7.35772192e-01 2.58819193e-01 -6.23292208e-01 7.37923026e-01 2.58819193e-01 -6.20781839e-01 7.40034938e-01 2.58819193e-01 -6.18197620e-01 7.42197752e-01 2.58819193e-01 -6.15589261e-01 7.44360328e-01 2.58819193e-01 -6.12999678e-01 7.46499062e-01 2.58819193e-01 -6.10298276e-01 7.48703539e-01 2.58819193e-01 -6.07675195e-01 7.50835955e-01 2.58819193e-01 -6.05120420e-01 7.52894223e-01 2.58819193e-01 -6.02592409e-01 7.54922092e-01 2.58819193e-01 -5.99857390e-01 7.57095933e-01 2.58819193e-01 -5.97210705e-01 7.59185314e-01 2.58819193e-01 -5.94590485e-01 7.61241198e-01 2.58819193e-01 -5.91918707e-01 7.63318717e-01 2.58819193e-01 -5.89300632e-01 7.65342593e-01 2.58819193e-01 -5.86548209e-01 7.67453849e-01 2.58819193e-01 -5.83827436e-01 7.69526601e-01 2.58819193e-01 -5.81189752e-01 7.71519482e-01 2.58819193e-01 -5.78512132e-01 7.73527920e-01 2.58819193e-01 -5.75729012e-01 7.75602221e-01 2.58819193e-01 -5.73043287e-01 7.77587473e-01 2.58819193e-01 -5.70328712e-01 7.79581189e-01 2.58819193e-01 -5.67663491e-01 7.81525314e-01 2.58819193e-01 -5.64932883e-01 7.83499479e-01 2.58819193e-01 -5.62128007e-01 7.85517037e-01 2.58819193e-01 -5.59384704e-01 7.87472010e-01 2.58819193e-01 -5.56592822e-01 7.89448321e-01 2.58819193e-01 -5.53906381e-01 7.91332901e-01 2.58819193e-01 -5.51162481e-01 7.93246984e-01 2.58819193e-01 -5.48366189e-01 7.95185566e-01 2.58819193e-01 -5.45615971e-01 7.97075331e-01 2.58819193e-01 -5.42717755e-01 7.99049199e-01 2.58819193e-01 -5.39931357e-01 8.00935447e-01 2.58819193e-01 -5.37231266e-01 8.02747488e-01 2.58819193e-01 -5.34424305e-01 8.04619431e-01 2.58819193e-01 -5.31500995e-01 8.06554317e-01 2.58819193e-01 -5.28756976e-01 8.08353841e-01 2.58819193e-01 -5.25941610e-01 8.10188890e-01 2.58819193e-01 -5.23101807e-01 8.12025368e-01 2.58819193e-01 -5.20277798e-01 8.13838780e-01 2.58819193e-01 -5.17348111e-01 8.15705061e-01 2.58819193e-01 -5.14505863e-01 8.17500234e-01 2.58819193e-01 -5.11719286e-01 8.19245934e-01 2.58819193e-01 -5.08861780e-01 8.21028352e-01 2.58819193e-01 -5.05937815e-01 8.22828352e-01 2.58819193e-01 -5.03093898e-01 8.24572980e-01 2.58819193e-01 -5.00217974e-01 8.26320350e-01 2.58819193e-01 -4.97335792e-01 8.28057945e-01 2.58819193e-01 -4.94491369e-01 8.29759836e-01 2.58819193e-01 -4.91569668e-01 8.31492245e-01 2.58819193e-01 -4.88741696e-01 8.33160162e-01 2.58819193e-01 -4.85779434e-01 8.34890366e-01 2.58819193e-01 -4.82782483e-01 8.36627424e-01 2.58819193e-01 -4.79856968e-01 8.38308394e-01 2.58819193e-01 -4.76937860e-01 8.39972198e-01 2.58819193e-01 -4.74005789e-01 8.41632724e-01 2.58819193e-01 -4.71056342e-01 8.43283772e-01 2.58819193e-01 -4.68089163e-01 8.44933689e-01 2.58819193e-01 -4.65202093e-01 8.46528530e-01 2.58819193e-01 -4.62276995e-01 8.48131120e-01 2.58819193e-01 -4.59228754e-01 8.49782944e-01 2.58819193e-01 -4.56271529e-01 8.51375580e-01 2.58819193e-01 -4.53284860e-01 8.52970064e-01 2.58819193e-01 -4.50360864e-01 8.54517639e-01 2.58819193e-01 -4.47385460e-01 8.56078625e-01 2.58819193e-01 -4.44323987e-01 8.57670605e-01 2.58819193e-01 -4.41330880e-01 8.59215915e-01 2.58819193e-01 -4.38416600e-01 8.60705018e-01 2.58819193e-01 -4.35457617e-01 8.62207532e-01 2.58819193e-01 -4.32336032e-01 8.63776505e-01 2.58819193e-01 -4.29324955e-01 8.65276158e-01 2.58819193e-01 -4.26287293e-01 8.66777897e-01 2.58819193e-01 -4.23341960e-01 8.68220270e-01 2.58819193e-01 -4.20318097e-01 8.69690061e-01 2.58819193e-01 -4.17249978e-01 8.71162474e-01 2.58819193e-01 -4.14231062e-01 8.72602582e-01 2.58819193e-01 -4.11092877e-01 8.74086142e-01 2.58819193e-01 -4.08106476e-01 8.75484765e-01 2.58819193e-01 -4.05063421e-01 8.76897335e-01 2.58819193e-01 -4.01981771e-01 8.78311932e-01 2.58819193e-01 -3.98924381e-01 8.79707098e-01 2.58819193e-01 -3.95784855e-01 8.81123781e-01 2.58819193e-01 -3.92676473e-01 8.82513344e-01 2.58819193e-01 -3.89699072e-01 8.83831739e-01 2.58819193e-01 -3.86646509e-01 8.85172725e-01 2.58819193e-01 -3.83485764e-01 8.86545122e-01 2.58819193e-01 -3.80310535e-01 8.87907624e-01 2.58819193e-01 -3.77326548e-01 8.89183342e-01 2.58819193e-01 -3.74318361e-01 8.90453815e-01 2.58819193e-01 -3.71145546e-01 8.91782045e-01 2.58819193e-01 -3.67943704e-01 8.93104494e-01 2.58819193e-01 -3.64857048e-01 8.94372582e-01 2.58819193e-01 -3.61777395e-01 8.95622492e-01 2.58819193e-01 -3.58659983e-01 8.96875858e-01 2.58819193e-01 -3.55464548e-01 8.98147285e-01 2.58819193e-01 -3.52334529e-01 8.99380326e-01 2.58819193e-01 -3.49192351e-01 9.00599003e-01 2.58819193e-01 -3.46101791e-01 9.01802421e-01 2.58819193e-01 -3.42950851e-01 9.02995944e-01 2.58819193e-01 -3.39786232e-01 9.04184818e-01 2.58819193e-01 -3.36642712e-01 9.05360699e-01 2.58819193e-01 -3.33402336e-01 9.06560957e-01 2.58819193e-01 -3.30285192e-01 9.07711148e-01 2.58819193e-01 -3.27142596e-01 9.08845484e-01 2.58819193e-01 -3.23926657e-01 9.09998953e-01 2.58819193e-01 -3.20760727e-01 9.11118150e-01 2.58819193e-01 -3.17529768e-01 9.12247241e-01 2.58819193e-01 -3.14347774e-01 9.13352370e-01 2.58819193e-01 -3.11240792e-01 9.14413035e-01 2.58819193e-01 -3.08036804e-01 9.15499091e-01 2.58819193e-01 -3.04785401e-01 9.16584790e-01 2.58819193e-01 -3.01578015e-01 9.17645335e-01 2.58819193e-01 -2.98445404e-01 9.18668568e-01 2.58819193e-01 -2.95216113e-01 9.19713616e-01 2.58819193e-01 -2.91967452e-01 9.20748353e-01 2.58819193e-01 -2.88743168e-01 9.21764612e-01 2.58819193e-01 -2.85538435e-01 9.22763884e-01 2.58819193e-01 -2.82396942e-01 9.23728704e-01 2.58819193e-01 -2.79144466e-01 9.24715877e-01 2.58819193e-01 -2.75814056e-01 9.25715923e-01 2.58819193e-01 -2.72575796e-01 9.26675379e-01 2.58819193e-01 -2.69331753e-01 9.27622676e-01 2.58819193e-01 -2.66202539e-01 9.28526044e-01 2.58819193e-01 -2.62974143e-01 9.29446101e-01 2.58819193e-01 -2.59713739e-01 9.30362821e-01 2.58819193e-01 -2.56574541e-01 9.31231558e-01 2.58819193e-01 -2.53198385e-01 9.32157516e-01 2.58819193e-01 -2.49847606e-01 9.33058798e-01 2.58819193e-01 -2.46575981e-01 9.33930039e-01 2.58819193e-01 -2.43325472e-01 9.34782028e-01 2.58819193e-01 -2.40174994e-01 9.35595810e-01 2.58819193e-01 -2.36885458e-01 9.36432242e-01 2.58819193e-01 -2.33512029e-01 9.37280178e-01 2.58819193e-01 -2.30225280e-01 9.38094199e-01 2.58819193e-01 -2.26958081e-01 9.38892484e-01 2.58819193e-01 -2.23765194e-01 9.39656675e-01 2.58819193e-01 -2.20506340e-01 9.40428019e-01 2.58819193e-01 -2.17219517e-01 9.41190779e-01 2.58819193e-01 -2.13928550e-01 9.41943407e-01 2.58819193e-01 -2.10547000e-01 9.42707241e-01 2.58819193e-01 -2.07241103e-01 9.43435729e-01 2.58819193e-01 -2.03947380e-01 9.44154680e-01 2.58819193e-01 -2.00760648e-01 9.44837451e-01 2.58819193e-01 -1.97465152e-01 9.45534110e-01 2.58819193e-01 -1.94037274e-01 9.46243405e-01 2.58819193e-01 -1.90760523e-01 9.46906865e-01 2.58819193e-01 -1.87453255e-01 9.47568119e-01 2.58819193e-01 -1.84215590e-01 9.48202550e-01 2.58819193e-01 -1.80927023e-01 9.48835433e-01 2.58819193e-01 -1.77588716e-01 9.49464560e-01 2.58819193e-01 -1.74350709e-01 9.50063884e-01 2.58819193e-01 -1.70966625e-01 9.50684786e-01 2.58819193e-01 -1.67531297e-01 9.51295614e-01 2.58819193e-01 -1.64228991e-01 9.51867521e-01 2.58819193e-01 -1.60910666e-01 9.52434421e-01 2.58819193e-01 -1.57665431e-01 9.52976108e-01 2.58819193e-01 -1.54432088e-01 9.53505695e-01 2.58819193e-01 -1.51030019e-01 9.54051793e-01 2.58819193e-01 -1.47607893e-01 9.54588056e-01 2.58819193e-01 -1.44245580e-01 9.55098867e-01 2.58819193e-01 -1.40877798e-01 9.55602705e-01 2.58819193e-01 -1.37564138e-01 9.56084728e-01 2.58819193e-01 -1.34348974e-01 9.56542611e-01 2.58819193e-01 -1.31010801e-01 9.57007527e-01 2.58819193e-01 -1.27552554e-01 9.57471967e-01 2.58819193e-01 -1.24319054e-01 9.57896471e-01 2.58819193e-01 -1.20982692e-01 9.58324909e-01 2.58819193e-01 -1.17624015e-01 9.58742380e-01 2.58819193e-01 -1.14260405e-01 9.59150374e-01 2.58819193e-01 -1.10809311e-01 9.59554553e-01 2.58819193e-01 -1.07461661e-01 9.59935009e-01 2.58819193e-01 -1.04100525e-01 9.60304558e-01 2.58819193e-01 -1.00755006e-01 9.60660875e-01 2.58819193e-01 -9.74104553e-02 9.61006939e-01 2.58819193e-01 -9.41294953e-02 9.61333334e-01 2.58819193e-01 -9.08808336e-02 9.61647153e-01 2.58819193e-01 -8.74240175e-02 9.61967230e-01 2.58819193e-01 -8.39780942e-02 9.62274790e-01 2.58819193e-01 -8.06082934e-02 9.62562144e-01 2.58819193e-01 -7.72376060e-02 9.62838709e-01 2.58819193e-01 -7.39552006e-02 9.63093579e-01 2.58819193e-01 -7.06282854e-02 9.63346899e-01 2.58819193e-01 -6.71441928e-02 9.63593602e-01 2.58819193e-01 -6.37655780e-02 9.63824987e-01 2.58819193e-01 -6.04187846e-02 9.64038014e-01 2.58819193e-01 -5.71775548e-02 9.64237154e-01 2.58819193e-01 -5.38034961e-02 9.64432895e-01 2.58819193e-01 -5.03865071e-02 9.64614451e-01 2.58819193e-01 -4.70532849e-02 9.64786947e-01 2.58819193e-01 -4.36073653e-02 9.64945138e-01 2.58819193e-01 -4.02365103e-02 9.65093315e-01 2.58819193e-01 -3.68531235e-02 9.65227604e-01 2.58819193e-01 -3.35745439e-02 9.65347826e-01 2.58819193e-01 -3.02259326e-02 9.65457618e-01 2.58819193e-01 -2.68237442e-02 9.65557575e-01 2.58819193e-01 -2.34505665e-02 9.65650558e-01 2.58819193e-01 -2.00013332e-02 9.65721786e-01 2.58819193e-01 -1.67102050e-02 9.65789080e-01 2.58819193e-01 -1.33663146e-02 9.65835869e-01 2.58819193e-01 -9.97548271e-03 9.65877354e-01 2.58819193e-01 -6.66522747e-03 9.65913534e-01 2.58819193e-01 -3.23785818e-03 9.65931237e-01 2.58819193e-01 2.24264382e-04 9.65932071e-01 2.58819193e-01 3.58755700e-03 9.65930641e-01 2.58819193e-01 6.94901962e-03 9.65910673e-01 2.58819193e-01 1.02339294e-02 9.65875566e-01 2.58819193e-01 1.35150412e-02 9.65832770e-01 2.58819193e-01 1.69693045e-02 9.65787709e-01 2.58819193e-01 2.04538591e-02 9.65714335e-01 2.58819193e-01 2.38351412e-02 9.65637803e-01 2.58819193e-01 2.72032265e-02 9.65550840e-01 2.58819193e-01 3.05818543e-02 9.65447724e-01 2.58819193e-01 3.38728428e-02 9.65337813e-01 2.58819193e-01 3.71907502e-02 9.65216398e-01 2.58819193e-01 4.07021828e-02 9.65074420e-01 2.58819193e-01 4.40763757e-02 9.64924753e-01 2.58819193e-01 4.74166274e-02 9.64767575e-01 2.58819193e-01 5.07069118e-02 9.64597046e-01 2.58819193e-01 5.40656112e-02 9.64418054e-01 2.58819193e-01 5.74380234e-02 9.64221537e-01 2.58819193e-01 6.07775748e-02 9.64015841e-01 2.58819193e-01 6.42533898e-02 9.63792086e-01 2.58819193e-01 6.76140487e-02 9.63560283e-01 2.58819193e-01 7.09677488e-02 9.63321865e-01 2.58819193e-01 7.43453205e-02 9.63065207e-01 2.58819193e-01 7.76260421e-02 9.62806761e-01 2.58819193e-01 8.09546337e-02 9.62533712e-01 2.58819193e-01 8.43962282e-02 9.62237954e-01 2.58819193e-01 8.77685919e-02 9.61935520e-01 2.58819193e-01 9.11245197e-02 9.61623788e-01 2.58819193e-01 9.44304988e-02 9.61304903e-01 2.58819193e-01 9.77586284e-02 9.60972428e-01 2.58819193e-01 1.01116292e-01 9.60624576e-01 2.58819193e-01 1.04469247e-01 9.60266590e-01 2.58819193e-01 1.07925124e-01 9.59882319e-01 2.58819193e-01 1.11170888e-01 9.59510982e-01 2.58819193e-01 1.14527136e-01 9.59117651e-01 2.58819193e-01 1.17859863e-01 9.58713472e-01 2.58819193e-01 1.21207200e-01 9.58296776e-01 2.58819193e-01 1.24650531e-01 9.57853317e-01 2.58819193e-01 1.27996907e-01 9.57412958e-01 2.58819193e-01 1.31322116e-01 9.56963956e-01 2.58819193e-01 1.34578109e-01 9.56511855e-01 2.58819193e-01 1.37934580e-01 9.56032574e-01 2.58819193e-01 1.41261965e-01 9.55545604e-01 2.58819193e-01 1.44570366e-01 9.55050170e-01 2.58819193e-01 1.48005188e-01 9.54526365e-01 2.58819193e-01 1.51256502e-01 9.54013169e-01 2.58819193e-01 1.54580265e-01 9.53482687e-01 2.58819193e-01 1.57922015e-01 9.52935755e-01 2.58819193e-01 1.61154747e-01 9.52393234e-01 2.58819193e-01 1.64525956e-01 9.51817393e-01 2.58819193e-01 1.67962849e-01 9.51219738e-01 2.58819193e-01 1.71286017e-01 9.50628459e-01 2.58819193e-01 1.74605981e-01 9.50019062e-01 2.58819193e-01 1.77841604e-01 9.49418783e-01 2.58819193e-01 1.81049824e-01 9.48812306e-01 2.58819193e-01 1.84365854e-01 9.48173344e-01 2.58819193e-01 1.87742352e-01 9.47510898e-01 2.58819193e-01 1.91138461e-01 9.46831644e-01 2.58819193e-01 1.94468543e-01 9.46153522e-01 2.58819193e-01 1.97766364e-01 9.45468843e-01 2.58819193e-01 2.00978070e-01 9.44793284e-01 2.58819193e-01 2.04258427e-01 9.44088578e-01 2.58819193e-01 2.07647756e-01 9.43348348e-01 2.58819193e-01 2.10954264e-01 9.42615032e-01 2.58819193e-01 2.14261860e-01 9.41866577e-01 2.58819193e-01 2.17468679e-01 9.41133022e-01 2.58819193e-01 2.20711917e-01 9.40380275e-01 2.58819193e-01 2.24029183e-01 9.39592957e-01 2.58819193e-01 2.27184787e-01 9.38837469e-01 2.58819193e-01 2.30566606e-01 9.38010514e-01 2.58819193e-01 2.33934656e-01 9.37174439e-01 2.58819193e-01 2.37170324e-01 9.36360002e-01 2.58819193e-01 2.40423054e-01 9.35533345e-01 2.58819193e-01 2.43626192e-01 9.34703052e-01 2.58819193e-01 2.46799096e-01 9.33872223e-01 2.58819193e-01 2.50160217e-01 9.32975769e-01 2.58819193e-01 2.53519118e-01 9.32069898e-01 2.58819193e-01 2.56738633e-01 9.31185722e-01 2.58819193e-01 2.59919107e-01 9.30305243e-01 2.58819193e-01 2.63137639e-01 9.29399014e-01 2.58819193e-01 2.66383827e-01 9.28474665e-01 2.58819193e-01 2.69621521e-01 9.27539289e-01 2.58819193e-01 2.72957772e-01 9.26561713e-01 2.58819193e-01 2.76129514e-01 9.25623238e-01 2.58819193e-01 2.79341400e-01 9.24655914e-01 2.58819193e-01 2.82570094e-01 9.23675895e-01 2.58819193e-01 2.85730571e-01 9.22704995e-01 2.58819193e-01 2.89045006e-01 9.21671748e-01 2.58819193e-01 2.92213529e-01 9.20668602e-01 2.58819193e-01 2.95420110e-01 9.19647992e-01 2.58819193e-01 2.98659235e-01 9.18598950e-01 2.58819193e-01 3.01859349e-01 9.17552888e-01 2.58819193e-01 3.05045605e-01 9.16497767e-01 2.58819193e-01 3.08144182e-01 9.15462792e-01 2.58819193e-01 3.11435372e-01 9.14348304e-01 2.58819193e-01 3.14724565e-01 9.13220882e-01 2.58819193e-01 3.17872107e-01 9.12128747e-01 2.58819193e-01 3.21038514e-01 9.11020577e-01 2.58819193e-01 3.24161589e-01 9.09915745e-01 2.58819193e-01 3.27315181e-01 9.08783317e-01 2.58819193e-01 3.30591619e-01 9.07598138e-01 2.58819193e-01 3.33744079e-01 9.06434417e-01 2.58819193e-01 3.36899698e-01 9.05263841e-01 2.58819193e-01 3.39994311e-01 9.04106319e-01 2.58819193e-01 3.43143731e-01 9.02922392e-01 2.58819193e-01 3.46281201e-01 9.01733339e-01 2.58819193e-01 3.49422902e-01 9.00512815e-01 2.58819193e-01 3.52639586e-01 8.99258971e-01 2.58819193e-01 3.55715752e-01 8.98046494e-01 2.58819193e-01 3.58836919e-01 8.96804273e-01 2.58819193e-01 3.61962616e-01 8.95546794e-01 2.58819193e-01 3.65070283e-01 8.94285560e-01 2.58819193e-01 3.68203491e-01 8.92997324e-01 2.58819193e-01 3.71301562e-01 8.91716361e-01 2.58819193e-01 3.74488026e-01 8.90382946e-01 2.58819193e-01 3.77520889e-01 8.89099479e-01 2.58819193e-01 3.80603969e-01 8.87783587e-01 2.58819193e-01 3.83722872e-01 8.86440635e-01 2.58819193e-01 3.86725754e-01 8.85138631e-01 2.58819193e-01 3.89885336e-01 8.83750021e-01 2.58819193e-01 3.93045425e-01 8.82348597e-01 2.58819193e-01 3.96119982e-01 8.80972683e-01 2.58819193e-01 3.99194062e-01 8.79584491e-01 2.58819193e-01 4.02195930e-01 8.78213048e-01 2.58819193e-01 4.05175090e-01 8.76843393e-01 2.58819193e-01 4.08301055e-01 8.75393987e-01 2.58819193e-01 4.11419302e-01 8.73931050e-01 2.58819193e-01 4.14470583e-01 8.72489929e-01 2.58819193e-01 4.17454511e-01 8.71063411e-01 2.58819193e-01 4.20475870e-01 8.69613767e-01 2.58819193e-01 4.23511475e-01 8.68139744e-01 2.58819193e-01 4.26535517e-01 8.66654694e-01 2.58819193e-01 4.29639935e-01 8.65120590e-01 2.58819193e-01 4.32671785e-01 8.63608301e-01 2.58819193e-01 4.35657322e-01 8.62107575e-01 2.58819193e-01 4.38589752e-01 8.60618114e-01 2.58819193e-01 4.41587031e-01 8.59083951e-01 2.58819193e-01 4.44623321e-01 8.57513428e-01 2.58819193e-01 4.47535276e-01 8.56001914e-01 2.58819193e-01 4.50580895e-01 8.54402006e-01 2.58819193e-01 4.53620791e-01 8.52791309e-01 2.58819193e-01 4.56601232e-01 8.51199687e-01 2.58819193e-01 4.59566355e-01 8.49601746e-01 2.58819193e-01 4.62455064e-01 8.48034978e-01 2.58819193e-01 4.65411752e-01 8.46414924e-01 2.58819193e-01 4.68454927e-01 8.44730854e-01 2.58819193e-01 4.71409857e-01 8.43086600e-01 2.58819193e-01 4.74346846e-01 8.41439903e-01 2.58819193e-01 4.77178723e-01 8.39835227e-01 2.58819193e-01 4.80117053e-01 8.38160634e-01 2.58819193e-01 4.83032167e-01 8.36483419e-01 2.58819193e-01 4.85956937e-01 8.34789515e-01 2.58819193e-01 4.88954931e-01 8.33036423e-01 2.58819193e-01 4.91778523e-01 8.31370294e-01 2.58819193e-01 4.94661480e-01 8.29661012e-01 2.58819193e-01 4.97559488e-01 8.27924609e-01 2.58819193e-01 5.00429451e-01 8.26192617e-01 2.58819193e-01 5.03375709e-01 8.24402213e-01 2.58819193e-01 5.06205320e-01 8.22664917e-01 2.58819193e-01 5.09076357e-01 8.20896387e-01 2.58819193e-01 5.11935413e-01 8.19113433e-01 2.58819193e-01 5.14764965e-01 8.17338705e-01 2.58819193e-01 5.17639399e-01 8.15519333e-01 2.58819193e-01 5.20482123e-01 8.13707769e-01 2.58819193e-01 5.23389161e-01 8.11841488e-01 2.58819193e-01 5.26147783e-01 8.10056329e-01 2.58819193e-01 5.28971732e-01 8.08214128e-01 2.58819193e-01 5.31780422e-01 8.06369424e-01 2.58819193e-01 5.34510374e-01 8.04561019e-01 2.58819193e-01 5.37401021e-01 8.02635849e-01 2.58819193e-01 5.40200830e-01 8.00754964e-01 2.58819193e-01 5.42971134e-01 7.98878729e-01 2.58819193e-01 5.45872688e-01 7.96898305e-01 2.58819193e-01 5.48557758e-01 7.95050859e-01 2.58819193e-01 5.51228702e-01 7.93200433e-01 2.58819193e-01 5.53985953e-01 7.91276038e-01 2.58819193e-01 5.56845546e-01 7.89269984e-01 2.58819193e-01 5.59667110e-01 7.87267268e-01 2.58819193e-01 5.62331498e-01 7.85367489e-01 2.58819193e-01 5.65070093e-01 7.83397555e-01 2.58819193e-01 5.67808807e-01 7.81412601e-01 2.58819193e-01 5.70460439e-01 7.79475033e-01 2.58819193e-01 5.73217750e-01 7.77451932e-01 2.58819193e-01 5.75561047e-01 7.75721014e-01 2.58819073e-01 5.77747881e-01 7.74092972e-01 2.58819044e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 6.83562458e-01 6.82462335e-01 2.58819073e-01 6.85751617e-01 6.80262864e-01 2.58819073e-01 6.88060224e-01 6.77928448e-01 2.58819133e-01 6.90284908e-01 6.75657570e-01 2.58819193e-01 6.92565978e-01 6.73333466e-01 2.58819193e-01 6.94917202e-01 6.70903385e-01 2.58819193e-01 6.97245657e-01 6.68479621e-01 2.58819193e-01 6.99642241e-01 6.65978074e-01 2.58819193e-01 7.01891065e-01 6.63603485e-01 2.58819193e-01 7.04201281e-01 6.61152840e-01 2.58819193e-01 7.06564963e-01 6.58625603e-01 2.58819193e-01 7.08823144e-01 6.56196892e-01 2.58819193e-01 7.11053908e-01 6.53781593e-01 2.58819193e-01 7.13292301e-01 6.51334167e-01 2.58819193e-01 7.15635419e-01 6.48762405e-01 2.58819193e-01 7.17953205e-01 6.46195352e-01 2.58819193e-01 7.20198572e-01 6.43689394e-01 2.58819193e-01 7.22384334e-01 6.41238689e-01 2.58819193e-01 7.24565566e-01 6.38771594e-01 2.58819193e-01 7.26806998e-01 6.36218071e-01 2.58819193e-01 7.29074538e-01 6.33620739e-01 2.58819193e-01 7.31303036e-01 6.31047189e-01 2.58819193e-01 7.33507872e-01 6.28484368e-01 2.58819193e-01 7.35629201e-01 6.25996411e-01 2.58819193e-01 7.37791300e-01 6.23450160e-01 2.58819193e-01 7.39980221e-01 6.20849192e-01 2.58819193e-01 7.42164016e-01 6.18238270e-01 2.58819193e-01 7.44382441e-01 6.15563273e-01 2.58819193e-01 7.46480286e-01 6.13018870e-01 2.58819193e-01 7.48595893e-01 6.10432744e-01 2.58819193e-01 7.50756860e-01 6.07773364e-01 2.58819193e-01 7.52891183e-01 6.05127513e-01 2.58819193e-01 7.54964232e-01 6.02539718e-01 2.58819193e-01 7.56995440e-01 5.99985242e-01 2.58819193e-01 7.59137332e-01 5.97274601e-01 2.58819193e-01 7.61277914e-01 5.94541848e-01 2.58819193e-01 7.63358176e-01 5.91870844e-01 2.58819193e-01 7.65368044e-01 5.89267015e-01 2.58819193e-01 7.67356336e-01 5.86676538e-01 2.58819193e-01 7.69449174e-01 5.83930552e-01 2.58819193e-01 7.71534443e-01 5.81170678e-01 2.58819193e-01 7.73565412e-01 5.78463078e-01 2.58819193e-01 7.75539815e-01 5.75813532e-01 2.58819193e-01 7.77477860e-01 5.73193312e-01 2.58819193e-01 7.79518843e-01 5.70417225e-01 2.58819193e-01 7.81575739e-01 5.67595303e-01 2.58819193e-01 7.83557832e-01 5.64851582e-01 2.58819193e-01 7.85523236e-01 5.62119961e-01 2.58819193e-01 7.87413716e-01 5.59468329e-01 2.58819193e-01 7.89321184e-01 5.56777298e-01 2.58819193e-01 7.91258752e-01 5.54016352e-01 2.58819193e-01 7.93235481e-01 5.51182032e-01 2.58819193e-01 7.95188606e-01 5.48361242e-01 2.58819193e-01 7.97026575e-01 5.45686066e-01 2.58819193e-01 7.98979104e-01 5.42823613e-01 2.58819193e-01 8.00876915e-01 5.40017307e-01 2.58819193e-01 8.02721262e-01 5.37271857e-01 2.58819193e-01 8.04596186e-01 5.34460604e-01 2.58819193e-01 8.06424320e-01 5.31698644e-01 2.58819193e-01 8.08331907e-01 5.28793514e-01 2.58819193e-01 8.10220420e-01 5.25895476e-01 2.58819193e-01 8.11996400e-01 5.23147821e-01 2.58819193e-01 8.13768566e-01 5.20389318e-01 2.58819193e-01 8.15574825e-01 5.17551303e-01 2.58819193e-01 8.17456126e-01 5.14579058e-01 2.58819193e-01 8.19299936e-01 5.11635780e-01 2.58819193e-01 8.21066976e-01 5.08797646e-01 2.58819193e-01 8.22782397e-01 5.06013691e-01 2.58819193e-01 8.24513137e-01 5.03193080e-01 2.58819193e-01 8.26263189e-01 5.00313044e-01 2.58819193e-01 8.28008413e-01 4.97419864e-01 2.58819193e-01 8.29776764e-01 4.94464040e-01 2.58819193e-01 8.31549048e-01 4.91478205e-01 2.58819193e-01 8.33216548e-01 4.88645256e-01 2.58819193e-01 8.34908366e-01 4.85750556e-01 2.58819193e-01 8.36600304e-01 4.82831448e-01 2.58819193e-01 8.38277876e-01 4.79910403e-01 2.58819193e-01 8.39975059e-01 4.76929754e-01 2.58819193e-01 8.41583312e-01 4.74093556e-01 2.58819193e-01 8.43255341e-01 4.71109420e-01 2.58819193e-01 8.44912529e-01 4.68127042e-01 2.58819193e-01 8.46536636e-01 4.65188891e-01 2.58819193e-01 8.48146617e-01 4.62247640e-01 2.58819193e-01 8.49711418e-01 4.59363490e-01 2.58819193e-01 8.51348042e-01 4.56324816e-01 2.58819193e-01 8.52983117e-01 4.53261346e-01 2.58819193e-01 8.54566514e-01 4.50267911e-01 2.58819193e-01 8.56088579e-01 4.47367311e-01 2.58819193e-01 8.57593000e-01 4.44474757e-01 2.58819193e-01 8.59179258e-01 4.41403568e-01 2.58819193e-01 8.60760093e-01 4.38311219e-01 2.58819193e-01 8.62281382e-01 4.35311764e-01 2.58819193e-01 8.63803625e-01 4.32283223e-01 2.58819193e-01 8.65280986e-01 4.29315001e-01 2.58819193e-01 8.66759896e-01 4.26324457e-01 2.58819193e-01 8.68245244e-01 4.23292249e-01 2.58819193e-01 8.69719207e-01 4.20257032e-01 2.58819193e-01 8.71219635e-01 4.17134345e-01 2.58819193e-01 8.72627437e-01 4.14179921e-01 2.58819193e-01 8.74053717e-01 4.11160320e-01 2.58819193e-01 8.75499249e-01 4.08075958e-01 2.58819193e-01 8.76915753e-01 4.05025721e-01 2.58819193e-01 8.78363252e-01 4.01870459e-01 2.58819193e-01 8.79724622e-01 3.98881555e-01 2.58819193e-01 8.81103218e-01 3.95833582e-01 2.58819193e-01 8.82491827e-01 3.92723560e-01 2.58819193e-01 8.83849502e-01 3.89661878e-01 2.58819193e-01 8.85210872e-01 3.86557817e-01 2.58819193e-01 8.86514723e-01 3.83558005e-01 2.58819193e-01 8.87883723e-01 3.80371153e-01 2.58819193e-01 8.89239907e-01 3.77194017e-01 2.58819193e-01 8.90549600e-01 3.74093413e-01 2.58819193e-01 8.91817570e-01 3.71057242e-01 2.58819193e-01 8.93070817e-01 3.68029445e-01 2.58819193e-01 8.94380689e-01 3.64838362e-01 2.58819193e-01 8.95690620e-01 3.61613214e-01 2.58819193e-01 8.96957576e-01 3.58454913e-01 2.58819193e-01 8.98165405e-01 3.55423480e-01 2.58819193e-01 8.99353504e-01 3.52407187e-01 2.58819193e-01 9.00602698e-01 3.49189490e-01 2.58819193e-01 9.01838481e-01 3.46006364e-01 2.58819193e-01 9.03022826e-01 3.42882752e-01 2.58819193e-01 9.04250801e-01 3.39616925e-01 2.58819193e-01 9.05399859e-01 3.36535752e-01 2.58819193e-01 9.06566679e-01 3.33399385e-01 2.58819193e-01 9.07736599e-01 3.30216855e-01 2.58819193e-01 9.08872545e-01 3.27073038e-01 2.58819193e-01 9.10043657e-01 3.23801607e-01 2.58819193e-01 9.11144435e-01 3.20688426e-01 2.58819193e-01 9.12247300e-01 3.17537040e-01 2.58819193e-01 9.13379014e-01 3.14268082e-01 2.58819193e-01 9.14456010e-01 3.11115474e-01 2.58819193e-01 9.15523231e-01 3.07965875e-01 2.58819193e-01 9.16571796e-01 3.04828405e-01 2.58819193e-01 9.17654037e-01 3.01557392e-01 2.58819193e-01 9.18724656e-01 2.98278987e-01 2.58819193e-01 9.19757903e-01 2.95077741e-01 2.58819193e-01 9.20761585e-01 2.91928411e-01 2.58819193e-01 9.21745300e-01 2.88808107e-01 2.58819193e-01 9.22775209e-01 2.85502017e-01 2.58819193e-01 9.23796654e-01 2.82174677e-01 2.58819193e-01 9.24764991e-01 2.78986365e-01 2.58819193e-01 9.25709188e-01 2.75834143e-01 2.58819193e-01 9.26645398e-01 2.72678643e-01 2.58819193e-01 9.27614808e-01 2.69367546e-01 2.58819193e-01 9.28546488e-01 2.66127288e-01 2.58819193e-01 9.29475904e-01 2.62871981e-01 2.58819193e-01 9.30402935e-01 2.59566218e-01 2.58819193e-01 9.31281388e-01 2.56394446e-01 2.58819193e-01 9.32170630e-01 2.53153056e-01 2.58819193e-01 9.33073640e-01 2.49794021e-01 2.58819193e-01 9.33932900e-01 2.46567070e-01 2.58819193e-01 9.34791982e-01 2.43289903e-01 2.58819193e-01 9.35619175e-01 2.40091205e-01 2.58819193e-01 9.36444342e-01 2.36840680e-01 2.58819193e-01 9.37267721e-01 2.33566388e-01 2.58819193e-01 9.38079417e-01 2.30293363e-01 2.58819193e-01 9.38877046e-01 2.27016658e-01 2.58819193e-01 9.39640284e-01 2.23838717e-01 2.58819193e-01 9.40438032e-01 2.20466062e-01 2.58819193e-01 9.41217780e-01 2.17100233e-01 2.58819193e-01 9.41970348e-01 2.13814944e-01 2.58819193e-01 9.42716420e-01 2.10505322e-01 2.58819193e-01 9.43422616e-01 2.07300857e-01 2.58819193e-01 9.44139719e-01 2.04017222e-01 2.58819193e-01 9.44864273e-01 2.00634629e-01 2.58819193e-01 9.45561767e-01 1.97333097e-01 2.58819193e-01 9.46244121e-01 1.94031507e-01 2.58819193e-01 9.46898341e-01 1.90808326e-01 2.58819193e-01 9.47551847e-01 1.87528774e-01 2.58819193e-01 9.48206782e-01 1.84195563e-01 2.58819193e-01 9.48840678e-01 1.80897281e-01 2.58819193e-01 9.49482203e-01 1.77502930e-01 2.58819193e-01 9.50079083e-01 1.74266279e-01 2.58819193e-01 9.50690806e-01 1.70942947e-01 2.58819193e-01 9.51292038e-01 1.67557985e-01 2.58819193e-01 9.51859117e-01 1.64275765e-01 2.58819193e-01 9.52421725e-01 1.60985515e-01 2.58819193e-01 9.52961326e-01 1.57758996e-01 2.58819193e-01 9.53519464e-01 1.54355168e-01 2.58819193e-01 9.54067707e-01 1.50923789e-01 2.58819193e-01 9.54585075e-01 1.47613898e-01 2.58819193e-01 9.55083132e-01 1.44347191e-01 2.58819193e-01 9.55568850e-01 1.41103819e-01 2.58819193e-01 9.56069469e-01 1.37672111e-01 2.58819193e-01 9.56555068e-01 1.34268418e-01 2.58819193e-01 9.57017720e-01 1.30930290e-01 2.58819193e-01 9.57470238e-01 1.27575874e-01 2.58819193e-01 9.57900047e-01 1.24300309e-01 2.58819193e-01 9.58325744e-01 1.20984390e-01 2.58819193e-01 9.58755255e-01 1.17521532e-01 2.58819193e-01 9.59157526e-01 1.14185773e-01 2.58819193e-01 9.59547579e-01 1.10864826e-01 2.58819193e-01 9.59921062e-01 1.07582822e-01 2.58819193e-01 9.60291266e-01 1.04230158e-01 2.58819193e-01 9.60649610e-01 1.00875832e-01 2.58819193e-01 9.60995436e-01 9.75155309e-02 2.58819193e-01 9.61340249e-01 9.40664336e-02 2.58819193e-01 9.61652100e-01 9.08212736e-02 2.58819193e-01 9.61963594e-01 8.74735042e-02 2.58819193e-01 9.62264001e-01 8.40968862e-02 2.58819193e-01 9.62552965e-01 8.07171017e-02 2.58819193e-01 9.62829530e-01 7.73457959e-02 2.58819193e-01 9.63090777e-01 7.40327463e-02 2.58819193e-01 9.63351071e-01 7.05534518e-02 2.58819193e-01 9.63591218e-01 6.71724230e-02 2.58819193e-01 9.63822305e-01 6.38064146e-02 2.58819193e-01 9.64031398e-01 6.05320074e-02 2.58819193e-01 9.64230895e-01 5.72702773e-02 2.58819193e-01 9.64432359e-01 5.38171120e-02 2.58819193e-01 9.64618802e-01 5.03403433e-02 2.58819193e-01 9.64789867e-01 4.69719879e-02 2.58819193e-01 9.64940667e-01 4.37036790e-02 2.58819193e-01 9.65084791e-01 4.04557437e-02 2.58819193e-01 9.65219617e-01 3.70752960e-02 2.58819193e-01 9.65343237e-01 3.36990841e-02 2.58819193e-01 9.65459645e-01 3.02184429e-02 2.58819193e-01 9.65561628e-01 2.67479289e-02 2.58819193e-01 9.65648174e-01 2.34823022e-02 2.58819193e-01 9.65717793e-01 2.02194378e-02 2.58819193e-01 9.65789914e-01 1.68333370e-02 2.58819193e-01 9.65833664e-01 1.34691373e-02 2.58819193e-01 9.65878665e-01 1.00873355e-02 2.58819193e-01 9.65913832e-01 6.69648033e-03 2.58819193e-01 9.65931475e-01 3.23619833e-03 2.58819193e-01 9.65931296e-01 -1.17596763e-04 2.58819193e-01 9.65930879e-01 -3.48523422e-03 2.58819193e-01 9.65909541e-01 -6.89132558e-03 2.58819193e-01 9.65876639e-01 -1.01541532e-02 2.58819193e-01 9.65831697e-01 -1.35950344e-02 2.58819193e-01 9.65781748e-01 -1.70808956e-02 2.58819193e-01 9.65715826e-01 -2.03609522e-02 2.58819193e-01 9.65641499e-01 -2.37402488e-02 2.58819193e-01 9.65548694e-01 -2.71314718e-02 2.58819193e-01 9.65451539e-01 -3.04545145e-02 2.58819193e-01 9.65339243e-01 -3.38458717e-02 2.58819193e-01 9.65216815e-01 -3.71464677e-02 2.58819193e-01 9.65082586e-01 -4.05117162e-02 2.58819193e-01 9.64931190e-01 -4.39359248e-02 2.58819193e-01 9.64767516e-01 -4.74207141e-02 2.58819193e-01 9.64594603e-01 -5.07661663e-02 2.58819193e-01 9.64415610e-01 -5.40753417e-02 2.58819193e-01 9.64228213e-01 -5.73305003e-02 2.58819193e-01 9.64021802e-01 -6.06870763e-02 2.58819193e-01 9.63800788e-01 -6.41357452e-02 2.58819193e-01 9.63563979e-01 -6.75624236e-02 2.58819193e-01 9.63322341e-01 -7.09558129e-02 2.58819193e-01 9.63073850e-01 -7.42392689e-02 2.58819193e-01 9.62814569e-01 -7.75333270e-02 2.58819193e-01 9.62539673e-01 -8.08691531e-02 2.58819193e-01 9.62243557e-01 -8.43312517e-02 2.58819193e-01 9.61943626e-01 -8.76740292e-02 2.58819193e-01 9.61641133e-01 -9.09493789e-02 2.58819193e-01 9.61317539e-01 -9.43016633e-02 2.58819193e-01 9.60973799e-01 -9.77412164e-02 2.58819193e-01 9.60624516e-01 -1.01114765e-01 2.58819193e-01 9.60269153e-01 -1.04436755e-01 2.58819193e-01 9.59897935e-01 -1.07793726e-01 2.58819193e-01 9.59528208e-01 -1.11032486e-01 2.58819193e-01 9.59124804e-01 -1.14478230e-01 2.58819193e-01 9.58716631e-01 -1.17836222e-01 2.58819193e-01 9.58301902e-01 -1.21186376e-01 2.58819193e-01 9.57857788e-01 -1.24622799e-01 2.58819193e-01 9.57427025e-01 -1.27892524e-01 2.58819193e-01 9.56982017e-01 -1.31199136e-01 2.58819193e-01 9.56504464e-01 -1.34630010e-01 2.58819193e-01 9.56034660e-01 -1.37913093e-01 2.58819193e-01 9.55552697e-01 -1.41222402e-01 2.58819193e-01 9.55052435e-01 -1.44557118e-01 2.58819193e-01 9.54543829e-01 -1.47878125e-01 2.58819193e-01 9.54014540e-01 -1.51253194e-01 2.58819193e-01 9.53489304e-01 -1.54540628e-01 2.58819193e-01 9.52950597e-01 -1.57828823e-01 2.58819193e-01 9.52387750e-01 -1.61198899e-01 2.58819193e-01 9.51799512e-01 -1.64615020e-01 2.58819193e-01 9.51228678e-01 -1.67912975e-01 2.58819193e-01 9.50648606e-01 -1.71161816e-01 2.58819193e-01 9.50051010e-01 -1.74420908e-01 2.58819193e-01 9.49439585e-01 -1.77738875e-01 2.58819193e-01 9.48804677e-01 -1.81088433e-01 2.58819193e-01 9.48149502e-01 -1.84485987e-01 2.58819193e-01 9.47498858e-01 -1.87803969e-01 2.58819193e-01 9.46850538e-01 -1.91041350e-01 2.58819193e-01 9.46200609e-01 -1.94238171e-01 2.58819193e-01 9.45514917e-01 -1.97549567e-01 2.58819193e-01 9.44801867e-01 -2.00940266e-01 2.58819193e-01 9.44092214e-01 -2.04241917e-01 2.58819193e-01 9.43386495e-01 -2.07474574e-01 2.58819193e-01 9.42656040e-01 -2.10774705e-01 2.58819193e-01 9.41906691e-01 -2.14092344e-01 2.58819193e-01 9.41149533e-01 -2.17397913e-01 2.58819193e-01 9.40389216e-01 -2.20673487e-01 2.58819193e-01 9.39605653e-01 -2.23979801e-01 2.58819193e-01 9.38846946e-01 -2.27145731e-01 2.58819193e-01 9.38028038e-01 -2.30497479e-01 2.58819193e-01 9.37212169e-01 -2.33785585e-01 2.58819193e-01 9.36379135e-01 -2.37098545e-01 2.58819193e-01 9.35528040e-01 -2.40439638e-01 2.58819193e-01 9.34705138e-01 -2.43616596e-01 2.58819193e-01 9.33866680e-01 -2.46825144e-01 2.58819193e-01 9.32985127e-01 -2.50128031e-01 2.58819193e-01 9.32135940e-01 -2.53277838e-01 2.58819193e-01 9.31232929e-01 -2.56572425e-01 2.58819193e-01 9.30314779e-01 -2.59888828e-01 2.58819193e-01 9.29404616e-01 -2.63119906e-01 2.58819193e-01 9.28458035e-01 -2.66436130e-01 2.58819193e-01 9.27541792e-01 -2.69605845e-01 2.58819193e-01 9.26626980e-01 -2.72739470e-01 2.58819193e-01 9.25647140e-01 -2.76050031e-01 2.58819193e-01 9.24656868e-01 -2.79336900e-01 2.58819193e-01 9.23676670e-01 -2.82569915e-01 2.58819193e-01 9.22699034e-01 -2.85749048e-01 2.58819193e-01 9.21725869e-01 -2.88871557e-01 2.58819193e-01 9.20708001e-01 -2.92097807e-01 2.58819193e-01 9.19660985e-01 -2.95379341e-01 2.58819193e-01 9.18585181e-01 -2.98703909e-01 2.58819193e-01 9.17535365e-01 -3.01914036e-01 2.58819193e-01 9.16503549e-01 -3.05033982e-01 2.58819193e-01 9.15476143e-01 -3.08104634e-01 2.58819193e-01 9.14391398e-01 -3.11308563e-01 2.58819193e-01 9.13275182e-01 -3.14568758e-01 2.58819193e-01 9.12159860e-01 -3.17783058e-01 2.58819193e-01 9.11078513e-01 -3.20875227e-01 2.58819193e-01 9.09951270e-01 -3.24055284e-01 2.58819193e-01 9.08789337e-01 -3.27304661e-01 2.58819193e-01 9.07638431e-01 -3.30484688e-01 2.58819193e-01 9.06476676e-01 -3.33640695e-01 2.58819193e-01 9.05296624e-01 -3.36812437e-01 2.58819193e-01 9.04152274e-01 -3.39881063e-01 2.58819193e-01 9.02960181e-01 -3.43046337e-01 2.58819193e-01 9.01767910e-01 -3.46189439e-01 2.58819193e-01 9.00537908e-01 -3.49358261e-01 2.58819193e-01 8.99294615e-01 -3.52557778e-01 2.58819193e-01 8.98052812e-01 -3.55701983e-01 2.58819193e-01 8.96818638e-01 -3.58802557e-01 2.58819193e-01 8.95549238e-01 -3.61957699e-01 2.58819193e-01 8.94324481e-01 -3.64976257e-01 2.58819193e-01 8.93005073e-01 -3.68191391e-01 2.58819193e-01 8.91709626e-01 -3.71317685e-01 2.58819193e-01 8.90404940e-01 -3.74438763e-01 2.58819193e-01 8.89057100e-01 -3.77621502e-01 2.58819193e-01 8.87765884e-01 -3.80644679e-01 2.58819193e-01 8.86483610e-01 -3.83627206e-01 2.58819193e-01 8.85100722e-01 -3.86813670e-01 2.58819193e-01 8.83691728e-01 -3.90016586e-01 2.58819193e-01 8.82322848e-01 -3.93103331e-01 2.58819193e-01 8.80970836e-01 -3.96124452e-01 2.58819193e-01 8.79608691e-01 -3.99137884e-01 2.58819193e-01 8.78247857e-01 -4.02119964e-01 2.58819193e-01 8.76798630e-01 -4.05273467e-01 2.58819193e-01 8.75341654e-01 -4.08409685e-01 2.58819193e-01 8.73892963e-01 -4.11500871e-01 2.58819193e-01 8.72491896e-01 -4.14462537e-01 2.58819193e-01 8.71101499e-01 -4.17376757e-01 2.58819193e-01 8.69636714e-01 -4.20428514e-01 2.58819193e-01 8.68122697e-01 -4.23546940e-01 2.58819193e-01 8.66603911e-01 -4.26638633e-01 2.58819193e-01 8.65121603e-01 -4.29637462e-01 2.58819193e-01 8.63635898e-01 -4.32614237e-01 2.58819193e-01 8.62163126e-01 -4.35546458e-01 2.58819193e-01 8.60635102e-01 -4.38557297e-01 2.58819193e-01 8.59069288e-01 -4.41616714e-01 2.58819193e-01 8.57499421e-01 -4.44653243e-01 2.58819193e-01 8.55949938e-01 -4.47634012e-01 2.58819193e-01 8.54402363e-01 -4.50578719e-01 2.58819193e-01 8.52848709e-01 -4.53510582e-01 2.58819193e-01 8.51264536e-01 -4.56480622e-01 2.58819193e-01 8.49623799e-01 -4.59525973e-01 2.58819193e-01 8.48008335e-01 -4.62503493e-01 2.58819193e-01 8.46438885e-01 -4.65365529e-01 2.58819193e-01 8.44795048e-01 -4.68340605e-01 2.58819193e-01 8.43130231e-01 -4.71332788e-01 2.58819193e-01 8.41465175e-01 -4.74300474e-01 2.58819193e-01 8.39810431e-01 -4.77224559e-01 2.58819193e-01 8.38136852e-01 -4.80159670e-01 2.58819193e-01 8.36475551e-01 -4.83045608e-01 2.58819193e-01 8.34769428e-01 -4.85987127e-01 2.58819193e-01 8.33117068e-01 -4.88817424e-01 2.58819193e-01 8.31381798e-01 -4.91760910e-01 2.58819193e-01 8.29643607e-01 -4.94687229e-01 2.58819193e-01 8.27886164e-01 -4.97624397e-01 2.58819193e-01 8.26123416e-01 -5.00541329e-01 2.58819193e-01 8.24403465e-01 -5.03373086e-01 2.58819193e-01 8.22697282e-01 -5.06154537e-01 2.58819193e-01 8.20921302e-01 -5.09033740e-01 2.58819193e-01 8.19103122e-01 -5.11950672e-01 2.58819193e-01 8.17261338e-01 -5.14886081e-01 2.58819193e-01 8.15509200e-01 -5.17656088e-01 2.58819193e-01 8.13735127e-01 -5.20440221e-01 2.58819193e-01 8.11873317e-01 -5.23341596e-01 2.58819193e-01 8.09989333e-01 -5.26251733e-01 2.58819193e-01 8.08151364e-01 -5.29066801e-01 2.58819193e-01 8.06301117e-01 -5.31886339e-01 2.58819193e-01 8.04476738e-01 -5.34635365e-01 2.58819193e-01 8.02662313e-01 -5.37359595e-01 2.58819193e-01 8.00792158e-01 -5.40147901e-01 2.58819193e-01 7.98838973e-01 -5.43028772e-01 2.58819193e-01 7.96895385e-01 -5.45878232e-01 2.58819193e-01 7.95001626e-01 -5.48633695e-01 2.58819193e-01 7.93129504e-01 -5.51334858e-01 2.58819193e-01 7.91206062e-01 -5.54091096e-01 2.58819193e-01 7.89259851e-01 -5.56862235e-01 2.58819193e-01 7.87291944e-01 -5.59638679e-01 2.58819193e-01 7.85330713e-01 -5.62389016e-01 2.58819193e-01 7.83387482e-01 -5.65087974e-01 2.58819193e-01 7.81371415e-01 -5.67876697e-01 2.58819193e-01 7.79356480e-01 -5.70635974e-01 2.58819193e-01 7.77361155e-01 -5.73354840e-01 2.58819193e-01 7.75340557e-01 -5.76081216e-01 2.58819193e-01 7.73376763e-01 -5.78713775e-01 2.58819193e-01 7.71366894e-01 -5.81394732e-01 2.58819193e-01 7.69320846e-01 -5.84096849e-01 2.58819193e-01 7.67284453e-01 -5.86771667e-01 2.58819193e-01 7.65224636e-01 -5.89452624e-01 2.58819193e-01 7.63222933e-01 -5.92041135e-01 2.58819193e-01 7.61088729e-01 -5.94785035e-01 2.58819193e-01 7.58965552e-01 -5.97489476e-01 2.58819193e-01 7.56919920e-01 -6.00078523e-01 2.58819193e-01 7.54883885e-01 -6.02641284e-01 2.58819193e-01 7.52723694e-01 -6.05337501e-01 2.58819193e-01 7.50547469e-01 -6.08033180e-01 2.58819193e-01 7.48459995e-01 -6.10596061e-01 2.58819193e-01 7.46393681e-01 -6.13123775e-01 2.58819193e-01 7.44245231e-01 -6.15730345e-01 2.58819193e-01 7.42109060e-01 -6.18303180e-01 2.58819193e-01 7.39948094e-01 -6.20887995e-01 2.58819193e-01 7.37718105e-01 -6.23535037e-01 2.58819193e-01 7.35537291e-01 -6.26104712e-01 2.58819193e-01 7.33402133e-01 -6.28606558e-01 2.58819193e-01 7.31207371e-01 -6.31159067e-01 2.58819193e-01 7.28974819e-01 -6.33737147e-01 2.58819193e-01 7.26699889e-01 -6.36342585e-01 2.58819193e-01 7.24430561e-01 -6.38924599e-01 2.58819193e-01 7.22248077e-01 -6.41391337e-01 2.58819193e-01 7.20075727e-01 -6.43829405e-01 2.58819193e-01 7.17775941e-01 -6.46394372e-01 2.58819193e-01 7.15505302e-01 -6.48905575e-01 2.58819193e-01 7.13230073e-01 -6.51404798e-01 2.58819193e-01 7.10950613e-01 -6.53891206e-01 2.58819193e-01 7.08746970e-01 -6.56279087e-01 2.58819193e-01 7.06454039e-01 -6.58745646e-01 2.58819193e-01 7.04089403e-01 -6.61273777e-01 2.58819193e-01 7.01755166e-01 -6.63747072e-01 2.58819193e-01 6.99420094e-01 -6.66214228e-01 2.58819193e-01 6.97089076e-01 -6.68643057e-01 2.58819193e-01 6.94784224e-01 -6.71054006e-01 2.58819193e-01 6.92418158e-01 -6.73489630e-01 2.58819193e-01 6.90139651e-01 -6.75822020e-01 2.58819193e-01 6.87772751e-01 -6.78233922e-01 2.58819193e-01 6.85379803e-01 -6.80652380e-01 2.58819193e-01 6.82931483e-01 -6.83091044e-01 2.58819193e-01 6.80484653e-01 -6.85546517e-01 2.58819193e-01 6.78148508e-01 -6.87855184e-01 2.58819193e-01 6.75806940e-01 -6.90154493e-01 2.58819193e-01 6.73399448e-01 -6.92506015e-01 2.58819193e-01 6.70912206e-01 -6.94918454e-01 2.58819193e-01 6.68463051e-01 -6.97259784e-01 2.58819193e-01 6.66041791e-01 -6.99579895e-01 2.58819193e-01 6.63595855e-01 -7.01893449e-01 2.58819193e-01 6.61331832e-01 -7.04018533e-01 2.58819193e-01 6.59033895e-01 -7.06179261e-01 2.58819133e-01 6.56624556e-01 -7.08417654e-01 2.58819044e-01 6.54183984e-01 -7.10672498e-01 2.58819073e-01 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. 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. 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. 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. 5.53353071e-01 -7.91716337e-01 2.58819073e-01 5.50962925e-01 -7.93373883e-01 2.58819193e-01 5.48272371e-01 -7.95237064e-01 2.58819193e-01 5.45629501e-01 -7.97058880e-01 2.58819193e-01 5.42877972e-01 -7.98937440e-01 2.58819193e-01 5.40082693e-01 -8.00832987e-01 2.58819193e-01 5.37311494e-01 -8.02694798e-01 2.58819193e-01 5.34438372e-01 -8.04610729e-01 2.58819193e-01 5.31610072e-01 -8.06482732e-01 2.58819193e-01 5.28872132e-01 -8.08280170e-01 2.58819193e-01 5.26057720e-01 -8.10114861e-01 2.58819193e-01 5.23229063e-01 -8.11945796e-01 2.58819193e-01 5.20408452e-01 -8.13754916e-01 2.58819193e-01 5.17558694e-01 -8.15571129e-01 2.58819193e-01 5.14722824e-01 -8.17367017e-01 2.58819193e-01 5.11875629e-01 -8.19148481e-01 2.58819193e-01 5.09015501e-01 -8.20932686e-01 2.58819193e-01 5.06140232e-01 -8.22705984e-01 2.58819193e-01 5.03278911e-01 -8.24462593e-01 2.58819193e-01 5.00384808e-01 -8.26219082e-01 2.58819193e-01 4.97500062e-01 -8.27961564e-01 2.58819193e-01 4.94533986e-01 -8.29736054e-01 2.58819193e-01 4.91613835e-01 -8.31468225e-01 2.58819193e-01 4.88811702e-01 -8.33119154e-01 2.58819193e-01 4.85879838e-01 -8.34832013e-01 2.58819193e-01 4.82880831e-01 -8.36571813e-01 2.58819193e-01 4.79937434e-01 -8.38262677e-01 2.58819193e-01 4.77100492e-01 -8.39878798e-01 2.58819193e-01 4.74177569e-01 -8.41536939e-01 2.58819193e-01 4.71235394e-01 -8.43185365e-01 2.58819193e-01 4.68305707e-01 -8.44814003e-01 2.58819193e-01 4.65346336e-01 -8.46450925e-01 2.58819193e-01 4.62390631e-01 -8.48069549e-01 2.58819193e-01 4.59411204e-01 -8.49685192e-01 2.58819193e-01 4.56445932e-01 -8.51281881e-01 2.58819193e-01 4.53468680e-01 -8.52871597e-01 2.58819193e-01 4.50481355e-01 -8.54454875e-01 2.58819193e-01 4.47433382e-01 -8.56053770e-01 2.58819193e-01 4.44435716e-01 -8.57612133e-01 2.58819193e-01 4.41511661e-01 -8.59124064e-01 2.58819193e-01 4.38518733e-01 -8.60654235e-01 2.58819193e-01 4.35507149e-01 -8.62182260e-01 2.58819193e-01 4.32491541e-01 -8.63698125e-01 2.58819193e-01 4.29464519e-01 -8.65208924e-01 2.58819193e-01 4.26441878e-01 -8.66702318e-01 2.58819193e-01 4.23403054e-01 -8.68191004e-01 2.58819193e-01 4.20360357e-01 -8.69668782e-01 2.58819193e-01 4.17340130e-01 -8.71119380e-01 2.58819193e-01 4.14190829e-01 -8.72621834e-01 2.58819193e-01 4.11114901e-01 -8.74074817e-01 2.58819193e-01 4.08100367e-01 -8.75488222e-01 2.58819193e-01 4.05015022e-01 -8.76918793e-01 2.58819193e-01 4.02060807e-01 -8.78276467e-01 2.58819193e-01 3.98991466e-01 -8.79676521e-01 2.58819193e-01 3.95907193e-01 -8.81068647e-01 2.58819193e-01 3.92753184e-01 -8.82479906e-01 2.58819193e-01 3.89641523e-01 -8.83856237e-01 2.58819193e-01 3.86665046e-01 -8.85164976e-01 2.58819193e-01 3.83583993e-01 -8.86502683e-01 2.58819193e-01 3.80464584e-01 -8.87843251e-01 2.58819193e-01 3.77336115e-01 -8.89179826e-01 2.58819193e-01 3.74246180e-01 -8.90486360e-01 2.58819193e-01 3.71154130e-01 -8.91778827e-01 2.58819193e-01 3.68026644e-01 -8.93073142e-01 2.58819193e-01 3.64950031e-01 -8.94336224e-01 2.58819193e-01 3.61830056e-01 -8.95601928e-01 2.58819193e-01 3.58613372e-01 -8.96894753e-01 2.58819193e-01 3.55441242e-01 -8.98157537e-01 2.58819193e-01 3.52388591e-01 -8.99360895e-01 2.58819193e-01 3.49256873e-01 -9.00574386e-01 2.58819193e-01 3.46109331e-01 -9.01797712e-01 2.58819193e-01 3.42952371e-01 -9.02996004e-01 2.58819193e-01 3.39800924e-01 -9.04182076e-01 2.58819193e-01 3.36635828e-01 -9.05364394e-01 2.58819193e-01 3.33408862e-01 -9.06563401e-01 2.58819193e-01 3.30219865e-01 -9.07735348e-01 2.58819193e-01 3.27102333e-01 -9.08861160e-01 2.58819193e-01 3.23913515e-01 -9.10003781e-01 2.58819193e-01 3.20715725e-01 -9.11134779e-01 2.58819193e-01 3.17537576e-01 -9.12245512e-01 2.58819193e-01 3.14341813e-01 -9.13353860e-01 2.58819193e-01 3.11143309e-01 -9.14445519e-01 2.58819193e-01 3.08033556e-01 -9.15500700e-01 2.58819193e-01 3.04823041e-01 -9.16573286e-01 2.58819193e-01 3.01612109e-01 -9.17633951e-01 2.58819193e-01 2.98434556e-01 -9.18672562e-01 2.58819193e-01 2.95210868e-01 -9.19715822e-01 2.58819193e-01 2.92030066e-01 -9.20729101e-01 2.58819193e-01 2.88815260e-01 -9.21743810e-01 2.58819193e-01 2.85586625e-01 -9.22748804e-01 2.58819193e-01 2.82374829e-01 -9.23737407e-01 2.58819193e-01 2.79090017e-01 -9.24732387e-01 2.58819193e-01 2.75841355e-01 -9.25707459e-01 2.58819193e-01 2.72679865e-01 -9.26644981e-01 2.58819193e-01 2.69365638e-01 -9.27614391e-01 2.58819193e-01 2.66044199e-01 -9.28572059e-01 2.58819193e-01 2.62798131e-01 -9.29495692e-01 2.58819193e-01 2.59659827e-01 -9.30377483e-01 2.58819193e-01 2.56498873e-01 -9.31253552e-01 2.58819193e-01 2.53252804e-01 -9.32143986e-01 2.58819193e-01 2.50003219e-01 -9.33017612e-01 2.58819193e-01 2.46654227e-01 -9.33909416e-01 2.58819193e-01 2.43366763e-01 -9.34772015e-01 2.58819193e-01 2.40119338e-01 -9.35610354e-01 2.58819193e-01 2.36825630e-01 -9.36447978e-01 2.58819193e-01 2.33592927e-01 -9.37260091e-01 2.58819193e-01 2.30299294e-01 -9.38076556e-01 2.58819193e-01 2.27103859e-01 -9.38856661e-01 2.58819193e-01 2.23801598e-01 -9.39649940e-01 2.58819193e-01 2.20511436e-01 -9.40426946e-01 2.58819193e-01 2.17256501e-01 -9.41183865e-01 2.58819193e-01 2.13858396e-01 -9.41960692e-01 2.58819193e-01 2.10572571e-01 -9.42701042e-01 2.58819193e-01 2.07376868e-01 -9.43407595e-01 2.58819193e-01 2.04072833e-01 -9.44128573e-01 2.58819193e-01 2.00786799e-01 -9.44833279e-01 2.58819193e-01 1.97406262e-01 -9.45546627e-01 2.58819193e-01 1.94089219e-01 -9.46232498e-01 2.58819193e-01 1.90881953e-01 -9.46883678e-01 2.58819193e-01 1.87580392e-01 -9.47543263e-01 2.58819193e-01 1.84256226e-01 -9.48195875e-01 2.58819193e-01 1.80861250e-01 -9.48848248e-01 2.58819193e-01 1.77545160e-01 -9.49473858e-01 2.58819193e-01 1.74232379e-01 -9.50086713e-01 2.58819193e-01 1.70907885e-01 -9.50695455e-01 2.58819193e-01 1.67686716e-01 -9.51269150e-01 2.58819193e-01 1.64368197e-01 -9.51842606e-01 2.58819193e-01 1.61054134e-01 -9.52411652e-01 2.58819193e-01 1.57721117e-01 -9.52967346e-01 2.58819193e-01 1.54397592e-01 -9.53511953e-01 2.58819193e-01 1.51084125e-01 -9.54043806e-01 2.58819193e-01 1.47745818e-01 -9.54566419e-01 2.58819193e-01 1.44404545e-01 -9.55074966e-01 2.58819193e-01 1.41035929e-01 -9.55579519e-01 2.58819193e-01 1.37708187e-01 -9.56063330e-01 2.58819193e-01 1.34396121e-01 -9.56535578e-01 2.58819193e-01 1.30964756e-01 -9.57012892e-01 2.58819193e-01 1.27619416e-01 -9.57462907e-01 2.58819193e-01 1.24351487e-01 -9.57894266e-01 2.58819193e-01 1.21020794e-01 -9.58321750e-01 2.58819193e-01 1.17678978e-01 -9.58736300e-01 2.58819193e-01 1.14224210e-01 -9.59154785e-01 2.58819193e-01 1.10876977e-01 -9.59545910e-01 2.58819193e-01 1.07622311e-01 -9.59917486e-01 2.58819193e-01 1.04265720e-01 -9.60287094e-01 2.58819193e-01 1.00930281e-01 -9.60643649e-01 2.58819193e-01 9.74838585e-02 -9.60998356e-01 2.58819193e-01 9.41230208e-02 -9.61334348e-01 2.58819193e-01 9.07812342e-02 -9.61658418e-01 2.58819193e-01 8.74003544e-02 -9.61969793e-01 2.58819193e-01 8.40560421e-02 -9.62268531e-01 2.58819193e-01 8.06139708e-02 -9.62561488e-01 2.58819193e-01 7.73354992e-02 -9.62830782e-01 2.58819193e-01 7.40682334e-02 -9.63087201e-01 2.58819193e-01 7.06990212e-02 -9.63341892e-01 2.58819193e-01 6.73317611e-02 -9.63580906e-01 2.58819193e-01 6.39757365e-02 -9.63810980e-01 2.58819193e-01 6.06239960e-02 -9.64027584e-01 2.58819193e-01 5.72435446e-02 -9.64233696e-01 2.58819193e-01 5.38698919e-02 -9.64429021e-01 2.58819193e-01 5.05131595e-02 -9.64608252e-01 2.58819193e-01 4.71655838e-02 -9.64780688e-01 2.58819193e-01 4.38094810e-02 -9.64938521e-01 2.58819193e-01 4.03252766e-02 -9.65089202e-01 2.58819193e-01 3.69539037e-02 -9.65223670e-01 2.58819193e-01 3.36977430e-02 -9.65343475e-01 2.58819193e-01 3.02320998e-02 -9.65458453e-01 2.58819193e-01 2.68378481e-02 -9.65559065e-01 2.58819193e-01 2.34701913e-02 -9.65649962e-01 2.58819193e-01 2.00947952e-02 -9.65719938e-01 2.58819193e-01 1.68474223e-02 -9.65789735e-01 2.58819193e-01 1.33807240e-02 -9.65833724e-01 2.58819193e-01 9.97865200e-03 -9.65879381e-01 2.58819193e-01 6.72208657e-03 -9.65914726e-01 2.58819193e-01 3.35456221e-03 -9.65931296e-01 2.58819193e-01 -3.49282891e-05 -9.65932488e-01 2.58819193e-01 -3.49457562e-03 -9.65931594e-01 2.58819193e-01 -6.87471591e-03 -9.65913057e-01 2.58819193e-01 -1.02297096e-02 -9.65879083e-01 2.58819193e-01 -1.35823563e-02 -9.65831995e-01 2.58819193e-01 -1.69644803e-02 -9.65789676e-01 2.58819193e-01 -2.04088241e-02 -9.65714216e-01 2.58819193e-01 -2.37201061e-02 -9.65642095e-01 2.58819193e-01 -2.70136297e-02 -9.65554893e-01 2.58819193e-01 -3.03730201e-02 -9.65455770e-01 2.58819193e-01 -3.37420106e-02 -9.65344071e-01 2.58819193e-01 -3.72048691e-02 -9.65215683e-01 2.58819193e-01 -4.05950993e-02 -9.65078771e-01 2.58819193e-01 -4.38527353e-02 -9.64935541e-01 2.58819193e-01 -4.72206101e-02 -9.64778483e-01 2.58819193e-01 -5.05692475e-02 -9.64605391e-01 2.58819193e-01 -5.40188029e-02 -9.64422166e-01 2.58819193e-01 -5.73906377e-02 -9.64225352e-01 2.58819193e-01 -6.07671104e-02 -9.64016199e-01 2.58819193e-01 -6.41309917e-02 -9.63799238e-01 2.58819193e-01 -6.74003512e-02 -9.63576615e-01 2.58819193e-01 -7.08417818e-02 -9.63331103e-01 2.58819193e-01 -7.42194504e-02 -9.63075101e-01 2.58819193e-01 -7.75698721e-02 -9.62812424e-01 2.58819193e-01 -8.09381753e-02 -9.62533712e-01 2.58819193e-01 -8.42134133e-02 -9.62253809e-01 2.58819193e-01 -8.76479596e-02 -9.61947143e-01 2.58819193e-01 -9.10236984e-02 -9.61632490e-01 2.58819193e-01 -9.43561494e-02 -9.61312354e-01 2.58819193e-01 -9.77313966e-02 -9.60975111e-01 2.58819193e-01 -1.01064220e-01 -9.60631073e-01 2.58819193e-01 -1.04523398e-01 -9.60259914e-01 2.58819193e-01 -1.07770473e-01 -9.59900796e-01 2.58819193e-01 -1.11026704e-01 -9.59529519e-01 2.58819193e-01 -1.14395149e-01 -9.59133506e-01 2.58819193e-01 -1.17721073e-01 -9.58732307e-01 2.58819193e-01 -1.21170469e-01 -9.58303154e-01 2.58819193e-01 -1.24539725e-01 -9.57868159e-01 2.58819193e-01 -1.27771348e-01 -9.57444668e-01 2.58819193e-01 -1.31097183e-01 -9.56994832e-01 2.58819193e-01 -1.34431496e-01 -9.56532419e-01 2.58819193e-01 -1.37877494e-01 -9.56040502e-01 2.58819193e-01 -1.41217142e-01 -9.55551982e-01 2.58819193e-01 -1.44533142e-01 -9.55056846e-01 2.58819193e-01 -1.47877023e-01 -9.54546273e-01 2.58819193e-01 -1.51109383e-01 -9.54038441e-01 2.58819193e-01 -1.54464319e-01 -9.53502178e-01 2.58819193e-01 -1.57769293e-01 -9.52961564e-01 2.58819193e-01 -1.61194682e-01 -9.52388525e-01 2.58819193e-01 -1.64529517e-01 -9.51814711e-01 2.58819193e-01 -1.67753503e-01 -9.51257229e-01 2.58819193e-01 -1.71124980e-01 -9.50655580e-01 2.58819193e-01 -1.74446657e-01 -9.50046718e-01 2.58819193e-01 -1.77805454e-01 -9.49428141e-01 2.58819193e-01 -1.81124493e-01 -9.48797703e-01 2.58819193e-01 -1.84345096e-01 -9.48177516e-01 2.58819193e-01 -1.87660441e-01 -9.47527289e-01 2.58819193e-01 -1.91026285e-01 -9.46855664e-01 2.58819193e-01 -1.94367081e-01 -9.46173310e-01 2.58819193e-01 -1.97583333e-01 -9.45507407e-01 2.58819193e-01 -2.00866446e-01 -9.44818556e-01 2.58819193e-01 -2.04250798e-01 -9.44091618e-01 2.58819193e-01 -2.07554504e-01 -9.43366647e-01 2.58819193e-01 -2.10762188e-01 -9.42658722e-01 2.58819193e-01 -2.14051649e-01 -9.41916406e-01 2.58819193e-01 -2.17332229e-01 -9.41164076e-01 2.58819193e-01 -2.20683157e-01 -9.40388501e-01 2.58819193e-01 -2.23978356e-01 -9.39606369e-01 2.58819193e-01 -2.27163479e-01 -9.38842654e-01 2.58819193e-01 -2.30520323e-01 -9.38023090e-01 2.58819193e-01 -2.33805269e-01 -9.37207699e-01 2.58819193e-01 -2.37070769e-01 -9.36386585e-01 2.58819193e-01 -2.40343019e-01 -9.35553610e-01 2.58819193e-01 -2.43507117e-01 -9.34734523e-01 2.58819193e-01 -2.46787071e-01 -9.33875024e-01 2.58819193e-01 -2.50119030e-01 -9.32987273e-01 2.58819193e-01 -2.53472388e-01 -9.32082713e-01 2.58819193e-01 -2.56649643e-01 -9.31210697e-01 2.58819193e-01 -2.59774119e-01 -9.30346906e-01 2.58819193e-01 -2.63050973e-01 -9.29424703e-01 2.58819193e-01 -2.66298026e-01 -9.28497970e-01 2.58819193e-01 -2.69527584e-01 -9.27567124e-01 2.58819193e-01 -2.72763044e-01 -9.26620185e-01 2.58819193e-01 -2.75976747e-01 -9.25669789e-01 2.58819193e-01 -2.79217362e-01 -9.24694300e-01 2.58819193e-01 -2.82444447e-01 -9.23713446e-01 2.58819193e-01 -2.85736948e-01 -9.22704339e-01 2.58819193e-01 -2.88995117e-01 -9.21686113e-01 2.58819193e-01 -2.92203158e-01 -9.20675516e-01 2.58819193e-01 -2.95399904e-01 -9.19655085e-01 2.58819193e-01 -2.98510224e-01 -9.18649316e-01 2.58819193e-01 -3.01796317e-01 -9.17575300e-01 2.58819193e-01 -3.05049777e-01 -9.16498005e-01 2.58819193e-01 -3.08230549e-01 -9.15435374e-01 2.58819193e-01 -3.11393082e-01 -9.14362311e-01 2.58819193e-01 -3.14486474e-01 -9.13303852e-01 2.58819193e-01 -3.17713529e-01 -9.12185013e-01 2.58819193e-01 -3.20907265e-01 -9.11067367e-01 2.58819193e-01 -3.24111074e-01 -9.09932494e-01 2.58819193e-01 -3.27300012e-01 -9.08787727e-01 2.58819193e-01 -3.30467910e-01 -9.07644212e-01 2.58819193e-01 -3.33625257e-01 -9.06480789e-01 2.58819193e-01 -3.36721748e-01 -9.05331671e-01 2.58819193e-01 -3.39855582e-01 -9.04160976e-01 2.58819193e-01 -3.43039304e-01 -9.02963459e-01 2.58819193e-01 -3.46255481e-01 -9.01742935e-01 2.58819193e-01 -3.49502057e-01 -9.00481761e-01 2.58819193e-01 -3.52568179e-01 -8.99288297e-01 2.58819193e-01 -3.55605632e-01 -8.98092330e-01 2.58819193e-01 -3.58720213e-01 -8.96851778e-01 2.58819193e-01 -3.61852854e-01 -8.95592511e-01 2.58819193e-01 -3.65064293e-01 -8.94288957e-01 2.58819193e-01 -3.68269771e-01 -8.92971337e-01 2.58819193e-01 -3.71307611e-01 -8.91713798e-01 2.58819193e-01 -3.74322981e-01 -8.90453041e-01 2.58819193e-01 -3.77440214e-01 -8.89135718e-01 2.58819193e-01 -3.80613476e-01 -8.87778878e-01 2.58819193e-01 -3.83747071e-01 -8.86431575e-01 2.58819193e-01 -3.86823446e-01 -8.85096550e-01 2.58819193e-01 -3.89912218e-01 -8.83737743e-01 2.58819193e-01 -3.92903060e-01 -8.82413268e-01 2.58819193e-01 -3.95990759e-01 -8.81032586e-01 2.58819193e-01 -3.99052799e-01 -8.79647791e-01 2.58819193e-01 -4.02184427e-01 -8.78220022e-01 2.58819193e-01 -4.05258149e-01 -8.76805067e-01 2.58819193e-01 -4.08246636e-01 -8.75419021e-01 2.58819193e-01 -4.11294550e-01 -8.73991072e-01 2.58819193e-01 -4.14426804e-01 -8.72511029e-01 2.58819193e-01 -4.17464972e-01 -8.71058404e-01 2.58819193e-01 -4.20430511e-01 -8.69637012e-01 2.58819193e-01 -4.23470497e-01 -8.68160069e-01 2.58819193e-01 -4.26553696e-01 -8.66646588e-01 2.58819193e-01 -4.29580480e-01 -8.65151286e-01 2.58819193e-01 -4.32504803e-01 -8.63692403e-01 2.58819193e-01 -4.35537934e-01 -8.62168789e-01 2.58819193e-01 -4.38532144e-01 -8.60648990e-01 2.58819193e-01 -4.41614866e-01 -8.59071195e-01 2.58819193e-01 -4.44604814e-01 -8.57524335e-01 2.58819193e-01 -4.47525531e-01 -8.56008470e-01 2.58819193e-01 -4.50499624e-01 -8.54444265e-01 2.58819193e-01 -4.53463942e-01 -8.52874637e-01 2.58819193e-01 -4.56526995e-01 -8.51241171e-01 2.58819193e-01 -4.59514648e-01 -8.49628627e-01 2.58819193e-01 -4.62464929e-01 -8.48029554e-01 2.58819193e-01 -4.65422779e-01 -8.46407950e-01 2.58819193e-01 -4.68381822e-01 -8.44773829e-01 2.58819193e-01 -4.71417814e-01 -8.43083084e-01 2.58819193e-01 -4.74277824e-01 -8.41478050e-01 2.58819193e-01 -4.77180690e-01 -8.39836717e-01 2.58819193e-01 -4.80131924e-01 -8.38152349e-01 2.58819193e-01 -4.82971847e-01 -8.36518288e-01 2.58819193e-01 -4.85896409e-01 -8.34823787e-01 2.58819193e-01 -4.88823026e-01 -8.33113432e-01 2.58819193e-01 -4.91704196e-01 -8.31415296e-01 2.58819193e-01 -4.94603992e-01 -8.29693675e-01 2.58819193e-01 -4.97495323e-01 -8.27963650e-01 2.58819193e-01 -5.00404179e-01 -8.26207578e-01 2.58819193e-01 -5.03364503e-01 -8.24410975e-01 2.58819193e-01 -5.06290853e-01 -8.22613716e-01 2.58819193e-01 -5.09100437e-01 -8.20878863e-01 2.58819193e-01 -5.11866987e-01 -8.19157183e-01 2.58819193e-01 -5.14808953e-01 -8.17310810e-01 2.58819193e-01 -5.17676473e-01 -8.15496862e-01 2.58819193e-01 -5.20501435e-01 -8.13696563e-01 2.58819193e-01 -5.23357749e-01 -8.11861396e-01 2.58819193e-01 -5.26096344e-01 -8.10090065e-01 2.58819193e-01 -5.28990269e-01 -8.08202863e-01 2.58819193e-01 -5.31820834e-01 -8.06344569e-01 2.58819193e-01 -5.34538031e-01 -8.04542720e-01 2.58819193e-01 -5.37350833e-01 -8.02669466e-01 2.58819193e-01 -5.40225029e-01 -8.00740182e-01 2.58819193e-01 -5.43046236e-01 -7.98824310e-01 2.58819193e-01 -5.45727730e-01 -7.97000229e-01 2.58819193e-01 -5.48507273e-01 -7.95089126e-01 2.58819193e-01 -5.51278293e-01 -7.93169737e-01 2.58819193e-01 -5.54131389e-01 -7.91177571e-01 2.58819193e-01 -5.56998312e-01 -7.89165497e-01 2.58819193e-01 -5.59671700e-01 -7.87268221e-01 2.58819193e-01 -5.62312126e-01 -7.85385966e-01 2.58819193e-01 -5.65054476e-01 -7.83411026e-01 2.58819193e-01 -5.67804039e-01 -7.81424999e-01 2.58819193e-01 -5.70588946e-01 -7.79392064e-01 2.58819193e-01 -5.73387146e-01 -7.77335405e-01 2.58819193e-01 -5.76033950e-01 -7.75376618e-01 2.58819193e-01 -5.78647733e-01 -7.73426414e-01 2.58819193e-01 -5.81350923e-01 -7.71398783e-01 2.58819193e-01 -5.84096253e-01 -7.69324124e-01 2.58819193e-01 -5.86804569e-01 -7.67258048e-01 2.58819193e-01 -5.89473367e-01 -7.65210032e-01 2.58819193e-01 -5.92135966e-01 -7.63151109e-01 2.58819193e-01 -5.94727457e-01 -7.61132836e-01 2.58819193e-01 -5.97439826e-01 -7.59007692e-01 2.58819193e-01 -6.00087047e-01 -7.56914616e-01 2.58819193e-01 -6.02723897e-01 -7.54818618e-01 2.58819193e-01 -6.05371058e-01 -7.52694666e-01 2.58819193e-01 -6.07903242e-01 -7.50654042e-01 2.58819193e-01 -6.10516846e-01 -7.48526275e-01 2.58819193e-01 -6.13124728e-01 -7.46393383e-01 2.58819193e-01 -6.15791857e-01 -7.44195640e-01 2.58819193e-01 -6.18391871e-01 -7.42034316e-01 2.58819193e-01 -6.20902419e-01 -7.39936411e-01 2.58819193e-01 -6.23549044e-01 -7.37707198e-01 2.58819193e-01 -6.26132131e-01 -7.35514581e-01 2.58819193e-01 -6.28617942e-01 -7.33391762e-01 2.58819193e-01 -6.31187141e-01 -7.31184006e-01 2.58819193e-01 -6.33731067e-01 -7.28981018e-01 2.58819193e-01 -6.36345565e-01 -7.26697326e-01 2.58819193e-01 -6.38871610e-01 -7.24477351e-01 2.58819193e-01 -6.41322434e-01 -7.22309232e-01 2.58819193e-01 -6.43848240e-01 -7.20057607e-01 2.58819193e-01 -6.46344662e-01 -7.17818081e-01 2.58819193e-01 -6.48904264e-01 -7.15507865e-01 2.58819193e-01 -6.51409566e-01 -7.13222921e-01 2.58819193e-01 -6.53904080e-01 -7.10941911e-01 2.58819193e-01 -6.56385601e-01 -7.08648264e-01 2.58819193e-01 -6.58838093e-01 -7.06368804e-01 2.58819193e-01 -6.61372006e-01 -7.03996897e-01 2.58819193e-01 -6.63768709e-01 -7.01735258e-01 2.58819193e-01 -6.66185319e-01 -6.99447095e-01 2.58819193e-01 -6.68643236e-01 -6.97087944e-01 2.58819193e-01 -6.70996189e-01 -6.94838345e-01 2.58819193e-01 -6.73415363e-01 -6.92491651e-01 2.58819193e-01 -6.75818920e-01 -6.90141857e-01 2.58819193e-01 -6.78299308e-01 -6.87707722e-01 2.58819193e-01 -6.80710316e-01 -6.85321212e-01 2.58819193e-01 -6.83003783e-01 -6.83019340e-01 2.58819193e-01 -6.85397446e-01 -6.80635750e-01 2.58819193e-01 -6.87847495e-01 -6.78159297e-01 2.58819193e-01 -6.90232456e-01 -6.75726056e-01 2.58819193e-01 -6.92503214e-01 -6.73403978e-01 2.58819193e-01 -6.94841564e-01 -6.70992196e-01 2.58819193e-01 -6.97237492e-01 -6.68489635e-01 2.58819193e-01 -6.99638546e-01 -6.65985167e-01 2.58819193e-01 -7.01965332e-01 -6.63525760e-01 2.58819193e-01 -7.04233408e-01 -6.61117136e-01 2.58819193e-01 -7.06460655e-01 -6.58737540e-01 2.58819193e-01 -7.08810687e-01 -6.56212032e-01 2.58819193e-01 -7.11108565e-01 -6.53720379e-01 2.58819193e-01 -7.13325202e-01 -6.51300669e-01 2.58819193e-01 -7.15594232e-01 -6.48808181e-01 2.58819193e-01 -7.17864752e-01 -6.46293461e-01 2.58819193e-01 -7.20106840e-01 -6.43794239e-01 2.58819193e-01 -7.22351074e-01 -6.41277015e-01 2.58819193e-01 -7.24652529e-01 -6.38673663e-01 2.58819193e-01 -7.26863980e-01 -6.36153996e-01 2.58819193e-01 -7.29082465e-01 -6.33611083e-01 2.58819193e-01 -7.31360853e-01 -6.30979121e-01 2.58819193e-01 -7.33495653e-01 -6.28498137e-01 2.58819193e-01 -7.35663235e-01 -6.25957310e-01 2.58819193e-01 -7.37862289e-01 -6.23366952e-01 2.58819193e-01 -7.39974320e-01 -6.20855749e-01 2.58819193e-01 -7.42184460e-01 -6.18215919e-01 2.58819193e-01 -7.44351685e-01 -6.15600467e-01 2.58819193e-01 -7.46442318e-01 -6.13066852e-01 2.58819193e-01 -7.48572409e-01 -6.10460520e-01 2.58819193e-01 -7.50695527e-01 -6.07848525e-01 2.58819193e-01 -7.52863884e-01 -6.05164051e-01 2.58819193e-01 -7.55031168e-01 -6.02457345e-01 2.58819193e-01 -7.57131338e-01 -5.99813342e-01 2.58819193e-01 -7.59176672e-01 -5.97222805e-01 2.58819193e-01 -7.61197627e-01 -5.94645500e-01 2.58819193e-01 -7.63321042e-01 -5.91918528e-01 2.58819193e-01 -7.65371442e-01 -5.89263380e-01 2.58819193e-01 -7.67422676e-01 -5.86590052e-01 2.58819193e-01 -7.69481778e-01 -5.83884597e-01 2.58819193e-01 -7.71439910e-01 -5.81297278e-01 2.58819193e-01 -7.73461282e-01 -5.78601897e-01 2.58819193e-01 -7.75463343e-01 -5.75915277e-01 2.58819193e-01 -7.77524769e-01 -5.73131204e-01 2.58819193e-01 -7.79535234e-01 -5.70393264e-01 2.58819193e-01 -7.81532049e-01 -5.67655981e-01 2.58819193e-01 -7.83558726e-01 -5.64849794e-01 2.58819193e-01 -7.85475969e-01 -5.62185585e-01 2.58819193e-01 -7.87424147e-01 -5.59453964e-01 2.58819193e-01 -7.89380431e-01 -5.56689620e-01 2.58819193e-01 -7.91262925e-01 -5.54010868e-01 2.58819193e-01 -7.93239951e-01 -5.51176012e-01 2.58819193e-01 -7.95177937e-01 -5.48377395e-01 2.58819193e-01 -7.97014654e-01 -5.45704126e-01 2.58819193e-01 -7.98928738e-01 -5.42896509e-01 2.58819193e-01 -8.00823569e-01 -5.40100157e-01 2.58819193e-01 -8.02744448e-01 -5.37239432e-01 2.58819193e-01 -8.04629743e-01 -5.34408450e-01 2.58819193e-01 -8.06479514e-01 -5.31615138e-01 2.58819193e-01 -8.08343947e-01 -5.28774023e-01 2.58819193e-01 -8.10134172e-01 -5.26030898e-01 2.58819193e-01 -8.11956823e-01 -5.23211300e-01 2.58819193e-01 -8.13772500e-01 -5.20382404e-01 2.58819193e-01 -8.15625191e-01 -5.17474353e-01 2.58819193e-01 -8.17426920e-01 -5.14623821e-01 2.58819193e-01 -8.19175124e-01 -5.11834204e-01 2.58819193e-01 -8.20951700e-01 -5.08983970e-01 2.58819193e-01 -8.22722316e-01 -5.06112695e-01 2.58819193e-01 -8.24528098e-01 -5.03170669e-01 2.58819193e-01 -8.26285422e-01 -5.00274301e-01 2.58819193e-01 -8.28013539e-01 -4.97412264e-01 2.58819193e-01 -8.29751253e-01 -4.94503945e-01 2.58819193e-01 -8.31428528e-01 -4.91680682e-01 2.58819193e-01 -8.33163500e-01 -4.88736928e-01 2.58819193e-01 -8.34877908e-01 -4.85798508e-01 2.58819193e-01 -8.36519182e-01 -4.82972622e-01 2.58819193e-01 -8.38192284e-01 -4.80059803e-01 2.58819193e-01 -8.39871049e-01 -4.77114916e-01 2.58819193e-01 -8.41532648e-01 -4.74184394e-01 2.58819193e-01 -8.43177795e-01 -4.71246272e-01 2.58819193e-01 -8.44813466e-01 -4.68306035e-01 2.58819193e-01 -8.46496582e-01 -4.65262711e-01 2.58819193e-01 -8.48120809e-01 -4.62296844e-01 2.58819193e-01 -8.49680305e-01 -4.59420413e-01 2.58819193e-01 -8.51291478e-01 -4.56428677e-01 2.58819193e-01 -8.52926373e-01 -4.53367174e-01 2.58819193e-01 -8.54548335e-01 -4.50301886e-01 2.58819193e-01 -8.56069565e-01 -4.47403014e-01 2.58819193e-01 -8.57574046e-01 -4.44511741e-01 2.58819193e-01 -8.59129369e-01 -4.41499889e-01 2.58819193e-01 -8.60703349e-01 -4.38421309e-01 2.58819193e-01 -8.62234056e-01 -4.35403079e-01 2.58819193e-01 -8.63701224e-01 -4.32484597e-01 2.58819193e-01 -8.65246534e-01 -4.29388881e-01 2.58819193e-01 -8.66747320e-01 -4.26346928e-01 2.58819193e-01 -8.68191123e-01 -4.23403442e-01 2.58819193e-01 -8.69702101e-01 -4.20293659e-01 2.58819193e-01 -8.71198595e-01 -4.17175233e-01 2.58819193e-01 -8.72659564e-01 -4.14112121e-01 2.58819193e-01 -8.74066293e-01 -4.11131144e-01 2.58819193e-01 -8.75454485e-01 -4.08172131e-01 2.58819193e-01 -8.76910865e-01 -4.05033946e-01 2.58819193e-01 -8.78360748e-01 -4.01876211e-01 2.58819193e-01 -8.79716814e-01 -3.98898572e-01 2.58819193e-01 -8.81067097e-01 -3.95909458e-01 2.58819193e-01 -8.82450044e-01 -3.92817676e-01 2.58819193e-01 -8.83838832e-01 -3.89683872e-01 2.58819193e-01 -8.85201037e-01 -3.86582434e-01 2.58819193e-01 -8.86542678e-01 -3.83492798e-01 2.58819193e-01 -8.87876213e-01 -3.80383492e-01 2.58819193e-01 -8.89157414e-01 -3.77387702e-01 2.58819193e-01 -8.90511155e-01 -3.74186933e-01 2.58819193e-01 -8.91813219e-01 -3.71069044e-01 2.58819193e-01 -8.93099666e-01 -3.67962003e-01 2.58819193e-01 -8.94385159e-01 -3.64824444e-01 2.58819193e-01 -8.95615518e-01 -3.61793309e-01 2.58819193e-01 -8.96903574e-01 -3.58590037e-01 2.58819193e-01 -8.98160040e-01 -3.55432481e-01 2.58819193e-01 -8.99386048e-01 -3.52323979e-01 2.58819193e-01 -9.00619745e-01 -3.49136382e-01 2.58819193e-01 -9.01805401e-01 -3.46093297e-01 2.58819193e-01 -9.03026819e-01 -3.42872739e-01 2.58819193e-01 -9.04213130e-01 -3.39712858e-01 2.58819193e-01 -9.05352294e-01 -3.36665064e-01 2.58819193e-01 -9.06552434e-01 -3.33433867e-01 2.58819193e-01 -9.07729685e-01 -3.30235153e-01 2.58819193e-01 -9.08875406e-01 -3.27059329e-01 2.58819193e-01 -9.10012662e-01 -3.23888123e-01 2.58819193e-01 -9.11124408e-01 -3.20742160e-01 2.58819193e-01 -9.12246525e-01 -3.17532569e-01 2.58819193e-01 -9.13324594e-01 -3.14426005e-01 2.58819193e-01 -9.14413929e-01 -3.11240107e-01 2.58819193e-01 -9.15491402e-01 -3.08060437e-01 2.58819193e-01 -9.16583419e-01 -3.04788977e-01 2.58819193e-01 -9.17647421e-01 -3.01569313e-01 2.58819193e-01 -9.18669701e-01 -2.98444360e-01 2.58819193e-01 -9.19733822e-01 -2.95152187e-01 2.58819193e-01 -9.20757890e-01 -2.91939229e-01 2.58819193e-01 -9.21772063e-01 -2.88723975e-01 2.58819193e-01 -9.22774434e-01 -2.85497218e-01 2.58819193e-01 -9.23757970e-01 -2.82303035e-01 2.58819193e-01 -9.24734354e-01 -2.79083759e-01 2.58819193e-01 -9.25676942e-01 -2.75943518e-01 2.58819193e-01 -9.26659465e-01 -2.72631139e-01 2.58819193e-01 -9.27612245e-01 -2.69369066e-01 2.58819193e-01 -9.28519905e-01 -2.66221762e-01 2.58819193e-01 -9.29442465e-01 -2.62985557e-01 2.58819193e-01 -9.30357158e-01 -2.59731978e-01 2.58819193e-01 -9.31254208e-01 -2.56492019e-01 2.58819193e-01 -9.32149649e-01 -2.53229618e-01 2.58819193e-01 -9.33025837e-01 -2.49972522e-01 2.58819193e-01 -9.33916152e-01 -2.46631131e-01 2.58819193e-01 -9.34800029e-01 -2.43257001e-01 2.58819193e-01 -9.35620725e-01 -2.40082562e-01 2.58819193e-01 -9.36428487e-01 -2.36902192e-01 2.58819193e-01 -9.37270999e-01 -2.33553141e-01 2.58819193e-01 -9.38104331e-01 -2.30187371e-01 2.58819193e-01 -9.38882887e-01 -2.26989850e-01 2.58819193e-01 -9.39643264e-01 -2.23824084e-01 2.58819193e-01 -9.40421104e-01 -2.20530480e-01 2.58819193e-01 -9.41202044e-01 -2.17171356e-01 2.58819193e-01 -9.41955209e-01 -2.13875666e-01 2.58819193e-01 -9.42678511e-01 -2.10672811e-01 2.58819193e-01 -9.43423510e-01 -2.07305744e-01 2.58819193e-01 -9.44139659e-01 -2.04013288e-01 2.58819193e-01 -9.44835007e-01 -2.00779215e-01 2.58819193e-01 -9.45529342e-01 -1.97483584e-01 2.58819193e-01 -9.46224749e-01 -1.94130704e-01 2.58819193e-01 -9.46914732e-01 -1.90728322e-01 2.58819193e-01 -9.47556198e-01 -1.87514380e-01 2.58819193e-01 -9.48190749e-01 -1.84282601e-01 2.58819193e-01 -9.48841274e-01 -1.80895358e-01 2.58819193e-01 -9.49482918e-01 -1.77499428e-01 2.58819193e-01 -9.50082958e-01 -1.74243838e-01 2.58819193e-01 -9.50674117e-01 -1.71028867e-01 2.58819193e-01 -9.51264977e-01 -1.67716190e-01 2.58819193e-01 -9.51848567e-01 -1.64337859e-01 2.58819193e-01 -9.52432871e-01 -1.60921812e-01 2.58819193e-01 -9.52975929e-01 -1.57667384e-01 2.58819193e-01 -9.53506708e-01 -1.54432639e-01 2.58819193e-01 -9.54046428e-01 -1.51061237e-01 2.58819193e-01 -9.54578042e-01 -1.47669435e-01 2.58819193e-01 -9.55082834e-01 -1.44353598e-01 2.58819193e-01 -9.55583692e-01 -1.41013712e-01 2.58819193e-01 -9.56067920e-01 -1.37675002e-01 2.58819193e-01 -9.56532180e-01 -1.34430438e-01 2.58819193e-01 -9.57007706e-01 -1.31005615e-01 2.58819193e-01 -9.57460105e-01 -1.27640486e-01 2.58819193e-01 -9.57898617e-01 -1.24323092e-01 2.58819193e-01 -9.58326280e-01 -1.20974898e-01 2.58819193e-01 -9.58735764e-01 -1.17679976e-01 2.58819193e-01 -9.59146798e-01 -1.14281103e-01 2.58819193e-01 -9.59541082e-01 -1.10903695e-01 2.58819193e-01 -9.59926367e-01 -1.07546292e-01 2.58819193e-01 -9.60303783e-01 -1.04116194e-01 2.58819193e-01 -9.60649371e-01 -1.00862004e-01 2.58819193e-01 -9.60994780e-01 -9.75262076e-02 2.58819193e-01 -9.61330533e-01 -9.41590741e-02 2.58819193e-01 -9.61656511e-01 -9.07921121e-02 2.58819193e-01 -9.61966515e-01 -8.74260664e-02 2.58819193e-01 -9.62256312e-01 -8.41863155e-02 2.58819193e-01 -9.62541819e-01 -8.08266997e-02 2.58819193e-01 -9.62819397e-01 -7.74583593e-02 2.58819193e-01 -9.63087142e-01 -7.40149617e-02 2.58819193e-01 -9.63337481e-01 -7.06479251e-02 2.58819193e-01 -9.63568866e-01 -6.73964173e-02 2.58819193e-01 -9.63801622e-01 -6.39727861e-02 2.58819193e-01 -9.63997066e-01 -6.10250533e-02 2.58819193e-01 -9.64172721e-01 -5.81550300e-02 2.58819073e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.65476871e-01 -2.94565745e-02 2.58818895e-01 -9.65552568e-01 -2.68579274e-02 2.58819133e-01 -9.65636551e-01 -2.35829391e-02 2.58819193e-01 -9.65708375e-01 -2.05187816e-02 2.58819133e-01 -9.65750992e-01 -1.83748249e-02 2.58819044e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/ouster64.yaml ================================================ common: lid_topic: "/os_cloud_node/points" imu_topic: "/os_cloud_node/imu" time_sync_en: false # ONLY turn on when external time synchronization is really not possible time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 preprocess: lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, scan_line: 64 timestamp_unit: 3 # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. blind: 4 mapping: acc_cov: 0.1 gyr_cov: 0.1 b_acc_cov: 0.0001 b_gyr_cov: 0.0001 fov_degree: 180 det_range: 150.0 extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic extrinsic_T: [ 0.0, 0.0, 0.0 ] extrinsic_R: [1, 0, 0, 0, 1, 0, 0, 0, 1] publish: path_en: false scan_publish_en: true # false: close all the point cloud output dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame pcd_save: pcd_save_en: true interval: -1 # how many LiDAR frames saved in each pcd file; # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. ================================================ FILE: config/rs128.yaml ================================================ common: #NCLT # lid_topic: "/points_raw" # imu_topic: "/imu_raw" #KITTI # lid_topic: "/kitti/velo/pointcloud" # imu_topic: "/kitti/oxts/imu" #RS LiDar lid_topic: "/rslidar" imu_topic: "/imu" time_sync_en: false # ONLY turn on when external time synchronization is really not possible preprocess: lidar_type: 4 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 4 RS scan_line: 128 scan_rate: 10 # only need to be set for velodyne, unit: Hz, blind: 2.5 mapping: acc_cov: 0.1 gyr_cov: 0.1 b_acc_cov: 0.0001 b_gyr_cov: 0.0001 fov_degree: 180 det_range: 100.0 extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic, extrinsic_T: [ 1.494363791111, 0.000030061324, 0.903719820280] extrinsic_R: [ -0.508348737805, 0.861029086113, -0.014507709641, -0.861100925582, -0.508429079519, -0.002251013466, -0.009314329527, 0.011348302346, 0.999892223842] time_delay: 0.0 #time delay from IMU to LiDAR publish: path_en: true scan_publish_en: true # false: close all the point cloud output dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame pcd_save: pcd_save_en: true interval: 1 # how many LiDAR frames saved in each pcd file; # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. ================================================ FILE: config/velodyne.yaml ================================================ common: lid_topic: "/velodyne_points" imu_topic: "/handsfree/imu" time_sync_en: false # ONLY turn on when external time synchronization is really not possible time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 preprocess: lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, scan_line: 32 scan_rate: 10 # only need to be set for velodyne, unit: Hz, timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. blind: 2 mapping: acc_cov: 0.1 gyr_cov: 0.1 b_acc_cov: 0.0001 b_gyr_cov: 0.0001 fov_degree: 180 det_range: 100.0 extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic, extrinsic_T: [0.27255, -0.00053, 0.17954] extrinsic_R: [ 1, 0, 0, 0, 1, 0, 0, 0, 1] publish: path_en: true scan_publish_en: true # false: close all the point cloud output dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame pcd_save: pcd_save_en: false interval: -1 # how many LiDAR frames saved in each pcd file; # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. ================================================ FILE: config/velodyne_m2dgr.yaml ================================================ common: lid_topic: "/velodyne_points" imu_topic: "/handsfree/imu" time_sync_en: false # ONLY turn on when external time synchronization is really not possible time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 preprocess: lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, scan_line: 32 scan_rate: 10 # only need to be set for velodyne, unit: Hz, timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. Horizon_SCAN: 1800 # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048) blind: 2 mapping: acc_cov: 3.7686306102624571e-02 gyr_cov: 2.3417543020438883e-03 b_acc_cov: 1.1416642385952368e-03 b_gyr_cov: 1.4428407712885209e-05 fov_degree: 180 det_range: 100.0 extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic, extrinsic_T: [0.27255, -0.00053, 0.17954] extrinsic_R: [ 1, 0, 0, 0, 1, 0, 0, 0, 1] #voxel map voxel_hash_en: false # for association voxel_size: 1.0 max_layer: 4 # 4 layer, 0, 1, 2, 3 layer_point_size: [ 5, 5, 5, 5, 5 ] # min points plane update threshold plannar_threshold: 0.01 max_points_size: 1000 max_cov_points_size: 1000 publish: path_en: true scan_publish_en: true # false: close all the point cloud output dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame pcd_save: pcd_save_en: false interval: -1 # how many LiDAR frames saved in each pcd file; # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. save_ikdtree_map: false save_final_map: false normal: compute_table: false ring_table_dir: "/config/m2dgr" compute_normal: true check_normal: true surfel: surfel_points_min: 25 # points inside the voxel larger than the value, do pca surfel_points_max: 100 # max points inside a voxel planarity: 0.6 # larger than the value is plane [0, 1.0] mid2min: 100.0 # larger than the value is plane angle_threshold: 30.0 # angle between ring Fals and surfel normal cloud_surfel: true # point-to-neighbor surfel association point_surfel: true # point-to-point surfel association # prism or RTK in IMU frame ground_truth: extrinsic_T: [ 0.16, 0.0, 0.84 ] ## GNSS in IMU frame # extrinsic_T: [ 0.27255, -0.00053, 0.17954] ## LiDAR in IMU frame extrinsic_R: [ 1, 0, 0, 0, 1, 0, 0, 0, 1 ] ================================================ FILE: config/viral/ring16_M_0.xml ================================================ 16 1024
f
2.08049975e+06 3.35299034e+01 2.18502598e+01 2.27834072e+01 2.40774364e+01 2.57045021e+01 2.76908798e+01 3.00798893e+01 3.28298111e+01 3.59471092e+01 3.92713509e+01 4.30075417e+01 4.71208534e+01 5.15169487e+01 5.62478218e+01 6.13165207e+01 6.69016190e+01 7.26871185e+01 7.88025970e+01 8.53937683e+01 9.23432007e+01 9.95728607e+01 1.07047104e+02 1.14937019e+02 1.23066505e+02 1.31555161e+02 1.40633621e+02 1.50010834e+02 1.59611618e+02 1.69266907e+02 1.79555313e+02 1.90097595e+02 2.00654327e+02 2.12207489e+02 2.23757858e+02 2.35659714e+02 2.48105133e+02 2.60643341e+02 2.73504547e+02 2.86655304e+02 2.99660522e+02 3.13433746e+02 3.27561768e+02 3.42227936e+02 3.56763275e+02 3.71421844e+02 3.87581970e+02 4.02891449e+02 4.17354553e+02 4.34163391e+02 4.51978821e+02 4.68040009e+02 4.84798065e+02 5.01711761e+02 5.18780273e+02 5.37152954e+02 5.57695740e+02 5.75061768e+02 5.91684265e+02 6.11388062e+02 6.32123413e+02 6.51897156e+02 6.70326111e+02 6.90431152e+02 7.08998291e+02 7.30027405e+02 7.53516235e+02 7.73003723e+02 7.92188660e+02 8.13058777e+02 8.36891479e+02 8.61748962e+02 8.80154419e+02 8.99046753e+02 9.23865601e+02 9.51991089e+02 9.74451843e+02 9.93915649e+02 1.02141376e+03 1.04442419e+03 1.06309863e+03 1.09087476e+03 1.11768408e+03 1.13937024e+03 1.15918774e+03 1.19089783e+03 1.20910291e+03 1.24015955e+03 2.42617651e+03 3.76773096e+03 2.10150605e+04 -3337964. -97662904. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -14636766. 8.18164688e+04 1.83805703e+04 2.38207373e+03 2.29994824e+03 1.85945007e+03 1.88419373e+03 1.90292981e+03 1.91659033e+03 1.94161511e+03 1.98834546e+03 2.02573901e+03 2.06301367e+03 2.08066455e+03 2.10941333e+03 2.13734937e+03 2.15814771e+03 2.20563257e+03 2.22784790e+03 2.25155273e+03 2.29365381e+03 2.30940649e+03 2.33017065e+03 2.36149780e+03 2.39778931e+03 2.42939941e+03 2.46365845e+03 2.50146704e+03 2.50922754e+03 2.53532568e+03 2.57353101e+03 2.58345972e+03 2.62659985e+03 2.65605273e+03 2.66930615e+03 2.70549048e+03 2.74259668e+03 2.77251099e+03 2.79456445e+03 2.83262207e+03 2.86340186e+03 2.87188086e+03 2.91514478e+03 2.94005835e+03 2.96708032e+03 3.00513208e+03 3.01291284e+03 3.04627783e+03 3.06818579e+03 3.08556689e+03 3.11836768e+03 3.15075195e+03 3.18558130e+03 3.22137720e+03 3.23295874e+03 3.26618701e+03 3.28772046e+03 3.29948267e+03 3.33419897e+03 3.36828564e+03 3.39327051e+03 3.41718066e+03 3.44494067e+03 3.47620972e+03 3.50172949e+03 3.51767993e+03 3.55117676e+03 3.57288599e+03 3.57022607e+03 3.61228027e+03 3.65069214e+03 3.66716675e+03 3.69895020e+03 3.70897095e+03 3.73520239e+03 3.76945312e+03 3.77700122e+03 3.79593677e+03 3.82288818e+03 3.86527515e+03 3.87405200e+03 3.88481958e+03 3.91344312e+03 3.93290137e+03 3.94988745e+03 3.98255566e+03 4.01829883e+03 4.01866772e+03 4.04186963e+03 4.06673535e+03 4.06706812e+03 4.09127686e+03 4.12110498e+03 4.14394580e+03 4.16912891e+03 4.18203027e+03 4.18056592e+03 4.20649512e+03 4.23687646e+03 4.23437891e+03 4.26279492e+03 4.29361230e+03 4.29316357e+03 4.29806787e+03 4.32405176e+03 4.34145410e+03 4.35581543e+03 4.37960449e+03 4.38569971e+03 4.39833984e+03 4.41898877e+03 4.42765527e+03 4.44127393e+03 4.46024756e+03 4.46258789e+03 4.47854492e+03 4.49187842e+03 4.49572217e+03 4.51417041e+03 4.53062793e+03 4.53964844e+03 4.54723242e+03 4.55809863e+03 4.56784912e+03 4.57013232e+03 4.58450342e+03 4.59573438e+03 4.60562598e+03 4.61338574e+03 4.61715967e+03 4.62455762e+03 4.63432373e+03 4.64399707e+03 4.64448096e+03 4.64830371e+03 4.65898779e+03 4.66489795e+03 4.67105469e+03 4.67451562e+03 4.67659326e+03 4.67919678e+03 4.68608936e+03 4.68818262e+03 4.68908496e+03 4.69444385e+03 4.69610205e+03 4.69741895e+03 4.70053174e+03 4.70065283e+03 4.70105420e+03 4.70205518e+03 4.70204639e+03 4.70196436e+03 4.70068994e+03 4.69975732e+03 4.69917188e+03 4.69692188e+03 4.69699121e+03 4.69316748e+03 4.68809229e+03 4.68791797e+03 4.68336230e+03 4.67844141e+03 4.67922559e+03 4.67517090e+03 4.66410010e+03 4.65817090e+03 4.66004980e+03 4.65209717e+03 4.63860693e+03 4.63469385e+03 4.63370947e+03 4.62485840e+03 4.61446143e+03 4.60939795e+03 4.59786182e+03 4.58606250e+03 4.58139062e+03 4.57749023e+03 4.56810498e+03 4.55378320e+03 4.54478906e+03 4.53263135e+03 4.51589062e+03 4.51091113e+03 4.50055957e+03 4.48526270e+03 4.47399756e+03 4.46413477e+03 4.45417432e+03 4.43692383e+03 4.42096924e+03 4.40575635e+03 4.39379150e+03 4.38588867e+03 4.36729688e+03 4.34791455e+03 4.34507715e+03 4.32325977e+03 4.28570996e+03 4.28149219e+03 4.27587012e+03 4.26293359e+03 4.24260693e+03 4.21428320e+03 4.19744336e+03 4.18280518e+03 4.18358789e+03 4.15613965e+03 4.11979980e+03 4.10285596e+03 4.09126050e+03 4.07871631e+03 4.05459644e+03 4.03515210e+03 4.00461279e+03 3.98616357e+03 3.98947485e+03 3.95766895e+03 3.91815527e+03 3.89718848e+03 3.88846924e+03 3.87458789e+03 3.84050928e+03 3.79625391e+03 3.78819116e+03 3.78891943e+03 3.75802295e+03 3.71851074e+03 3.71571191e+03 3.68872876e+03 3.64505835e+03 3.63238403e+03 3.61650488e+03 3.58208521e+03 3.54011279e+03 3.54215161e+03 3.52214111e+03 3.46739575e+03 3.44932300e+03 3.43507959e+03 3.41895874e+03 3.39187500e+03 3.34591162e+03 3.32325562e+03 3.31377051e+03 3.28178345e+03 3.25001953e+03 3.22457202e+03 3.19257153e+03 3.16031445e+03 3.14952832e+03 3.11929663e+03 3.08641479e+03 3.06139087e+03 3.04038208e+03 3.01190137e+03 2.98104468e+03 2.95786938e+03 2.91128809e+03 2.90205591e+03 2.88564819e+03 2.84052002e+03 2.80409521e+03 2.77143823e+03 2.75277026e+03 2.73042749e+03 2.69987695e+03 2.67962842e+03 2.63964600e+03 2.61424341e+03 2.57866260e+03 2.54364795e+03 2.53794873e+03 2.50237769e+03 2.46423315e+03 2.45581689e+03 2.41013989e+03 2.37543188e+03 2.35606396e+03 2.32493677e+03 2.29706982e+03 2.26452051e+03 2.24218213e+03 2.20800708e+03 2.17964453e+03 2.15451709e+03 2.12142041e+03 2.10240161e+03 2.07597046e+03 2.03682910e+03 2.01103711e+03 1.98643164e+03 1.95300940e+03 1.92124146e+03 1.90279297e+03 1.86984192e+03 1.83120947e+03 1.82164124e+03 1.78895789e+03 1.75521375e+03 1.73539429e+03 1.70677698e+03 1.68005518e+03 1.64651575e+03 1.61361670e+03 1.59328430e+03 1.56833435e+03 1.54289160e+03 1.51781775e+03 1.48405469e+03 1.46185193e+03 1.43648132e+03 1.40297375e+03 1.37862805e+03 1.35624414e+03 1.33163733e+03 1.30640723e+03 1.27865344e+03 1.25195068e+03 1.22673315e+03 1.20259973e+03 1.17846448e+03 1.15334595e+03 1.12186609e+03 1.10214722e+03 1.08228540e+03 1.05574805e+03 1.03550940e+03 1.00852509e+03 9.83519653e+02 9.64266235e+02 9.39077209e+02 9.16030762e+02 8.94907471e+02 8.73964722e+02 8.49868530e+02 8.27078979e+02 8.05330444e+02 7.83709412e+02 7.62197876e+02 7.43278687e+02 7.25080078e+02 7.01016968e+02 6.82299316e+02 6.63254700e+02 6.40452087e+02 6.21207153e+02 6.03440491e+02 5.86336365e+02 5.68455505e+02 5.48966492e+02 5.28856934e+02 5.11638123e+02 4.95469696e+02 4.76620087e+02 4.60256805e+02 4.45513550e+02 4.28512543e+02 4.10863525e+02 3.96135803e+02 3.80218903e+02 3.64901886e+02 3.51193359e+02 3.35990906e+02 3.21730408e+02 3.08400604e+02 2.93848450e+02 2.80907349e+02 2.68487579e+02 2.54937286e+02 2.42683151e+02 2.30582474e+02 2.18605148e+02 2.07494202e+02 1.96560944e+02 1.85761261e+02 1.75185471e+02 1.65196899e+02 1.55398895e+02 1.45787918e+02 1.36755875e+02 1.27945793e+02 1.19647919e+02 1.11520943e+02 1.03712883e+02 9.62865067e+01 8.92633591e+01 8.25211716e+01 7.60336533e+01 6.99610062e+01 6.42974319e+01 5.89577217e+01 5.39786758e+01 4.92927742e+01 4.49397049e+01 4.09053116e+01 3.73051834e+01 3.40591316e+01 3.11349068e+01 2.85618896e+01 2.63440285e+01 2.44586525e+01 2.29424877e+01 2.17788391e+01 2.09796410e+01 2.05261230e+01 2.04219913e+01 2.06689663e+01 2.12733421e+01 2.22136536e+01 2.34913692e+01 2.51380672e+01 2.71489716e+01 2.94941750e+01 3.21915588e+01 3.52583199e+01 3.86298447e+01 4.23925705e+01 4.65103912e+01 5.09500847e+01 5.57348824e+01 6.08812180e+01 6.64759369e+01 7.22632675e+01 7.83562469e+01 8.49168854e+01 9.18313065e+01 9.90873642e+01 1.06649147e+02 1.14585052e+02 1.22648819e+02 1.31027283e+02 1.40133591e+02 1.49534592e+02 1.59074448e+02 1.68945526e+02 1.79316895e+02 1.89762192e+02 2.00299805e+02 2.11642899e+02 2.23115631e+02 2.35010574e+02 2.47660294e+02 2.60247162e+02 2.72969299e+02 2.85994720e+02 2.99266632e+02 3.12924469e+02 3.27103973e+02 3.41823456e+02 3.56225189e+02 3.71111877e+02 3.87205597e+02 4.02171875e+02 4.16884674e+02 4.34155182e+02 4.51026031e+02 4.67476074e+02 4.84175232e+02 5.01307495e+02 5.18817871e+02 5.36820435e+02 5.57032166e+02 5.74308655e+02 5.91063049e+02 6.11062988e+02 6.30635803e+02 6.51417908e+02 6.70505554e+02 6.89511536e+02 7.08175110e+02 7.29636047e+02 7.52733398e+02 7.72785400e+02 7.91747803e+02 8.13009216e+02 8.35700378e+02 8.60513062e+02 8.78639160e+02 8.97805115e+02 9.24754944e+02 9.51777954e+02 9.72642395e+02 9.91722534e+02 1.02044965e+03 1.04482947e+03 1.06379993e+03 1.08963171e+03 1.11682678e+03 1.13696204e+03 1.15779407e+03 1.18922217e+03 1.21552576e+03 1.23456323e+03 1.26103931e+03 1.28957874e+03 1.31682825e+03 1.34312317e+03 1.36233777e+03 1.38934119e+03 1.42078467e+03 1.44505212e+03 1.47183350e+03 1.49723267e+03 1.52435156e+03 1.54851526e+03 1.57563794e+03 1.60735767e+03 1.63470020e+03 1.66145544e+03 1.68766479e+03 1.71416162e+03 1.74407739e+03 1.77391260e+03 1.78954688e+03 1.82575977e+03 1.86492737e+03 1.88144971e+03 1.90658777e+03 1.92995740e+03 1.96381824e+03 1.99372852e+03 2.02765137e+03 2.06222656e+03 2.07508130e+03 2.10762744e+03 2.13892358e+03 2.15767822e+03 2.20845752e+03 2.22422559e+03 2.24926831e+03 2.29033350e+03 2.31020898e+03 2.33259155e+03 2.36594116e+03 2.39220532e+03 2.42884448e+03 2.44413354e+03 2.48494995e+03 2.50849487e+03 2.53745264e+03 2.56897925e+03 2.58511963e+03 2.63799219e+03 2.66116235e+03 2.67677832e+03 2.71451733e+03 2.74007617e+03 2.75966260e+03 2.79426831e+03 2.83199561e+03 2.85153320e+03 2.85994653e+03 2.91382739e+03 2.93698755e+03 2.95471240e+03 2.99754419e+03 3.01790259e+03 3.05383667e+03 3.07124072e+03 3.09109351e+03 3.12987207e+03 3.15386963e+03 3.18351514e+03 3.21569775e+03 3.23337427e+03 3.26225586e+03 3.28605908e+03 3.30976050e+03 3.33823633e+03 3.36655396e+03 3.39716016e+03 3.42279248e+03 3.44641309e+03 3.46995068e+03 3.49497290e+03 3.51753516e+03 3.54591016e+03 3.57109155e+03 3.57665601e+03 3.61193823e+03 3.64943262e+03 3.66480615e+03 3.69814941e+03 3.70975366e+03 3.73049854e+03 3.76566235e+03 3.78029419e+03 3.79972314e+03 3.82823999e+03 3.85561914e+03 3.87600146e+03 3.88829028e+03 3.91291089e+03 3.93332080e+03 3.94719238e+03 3.98131763e+03 4.01828052e+03 4.01445972e+03 4.04034863e+03 4.07000635e+03 4.06922949e+03 4.08564844e+03 4.11700830e+03 4.14457373e+03 4.16891504e+03 4.17948340e+03 4.18027979e+03 4.20506787e+03 4.23502783e+03 4.23555078e+03 4.25824512e+03 4.29076367e+03 4.29606006e+03 4.29783447e+03 4.32491260e+03 4.33910547e+03 4.35472510e+03 4.38193555e+03 4.38408740e+03 4.39262842e+03 4.42123389e+03 4.42421875e+03 4.44002246e+03 4.46504785e+03 4.46058301e+03 4.47607031e+03 4.49159570e+03 4.49830615e+03 4.51355176e+03 4.53053857e+03 4.53787842e+03 4.54893604e+03 4.56123877e+03 4.56492090e+03 4.57022705e+03 4.58505664e+03 4.59353223e+03 4.60472510e+03 4.61243945e+03 4.61885254e+03 4.62514014e+03 4.63284521e+03 4.64248340e+03 4.64454248e+03 4.65020996e+03 4.65707617e+03 4.66305664e+03 4.67120117e+03 4.67541162e+03 4.67703223e+03 4.67924023e+03 4.68430908e+03 4.68839062e+03 4.68982812e+03 4.69333643e+03 4.69596777e+03 4.69758496e+03 4.70043506e+03 4.70064941e+03 4.70098096e+03 4.70193750e+03 4.70205762e+03 4.70203516e+03 4.70077344e+03 4.69996436e+03 4.69930176e+03 4.69700098e+03 4.69670410e+03 4.69270215e+03 4.68908252e+03 4.68746094e+03 4.68350732e+03 4.68009229e+03 4.67869336e+03 4.67380029e+03 4.66364453e+03 4.65852832e+03 4.65866602e+03 4.65122314e+03 4.64183545e+03 4.63563428e+03 4.63091992e+03 4.62676611e+03 4.61452490e+03 4.60722021e+03 4.60035938e+03 4.58835254e+03 4.58104736e+03 4.57765186e+03 4.56885742e+03 4.55312988e+03 4.54418213e+03 4.53266602e+03 4.51643701e+03 4.51051514e+03 4.50064746e+03 4.48245947e+03 4.47276270e+03 4.46455127e+03 4.45598047e+03 4.44034766e+03 4.41745996e+03 4.40312012e+03 4.39648389e+03 4.38833789e+03 4.36570117e+03 4.34507617e+03 4.34061621e+03 4.32130029e+03 4.29076660e+03 4.28514355e+03 4.27811719e+03 4.26203125e+03 4.23994580e+03 4.21699219e+03 4.19879053e+03 4.18246436e+03 4.18209375e+03 4.15545068e+03 4.11959668e+03 4.10692529e+03 4.09040576e+03 4.08027637e+03 4.05764844e+03 4.03251978e+03 4.00508716e+03 3.98623340e+03 3.98175977e+03 3.95675513e+03 3.92170947e+03 3.90030737e+03 3.88838599e+03 3.87474243e+03 3.84089111e+03 3.79870752e+03 3.79130200e+03 3.78811719e+03 3.75730420e+03 3.71633594e+03 3.71322412e+03 3.69127710e+03 3.64397754e+03 3.63944409e+03 3.61870703e+03 3.58440210e+03 3.54031470e+03 3.54007520e+03 3.52086572e+03 3.46962354e+03 3.45349512e+03 3.43720361e+03 3.41435913e+03 3.38949048e+03 3.35415601e+03 3.32922217e+03 3.31087622e+03 3.28168555e+03 3.25068262e+03 3.22123706e+03 3.19309888e+03 3.16803003e+03 3.14673804e+03 3.11700488e+03 3.08591943e+03 3.06681763e+03 3.04672656e+03 3.00714380e+03 2.98123193e+03 2.95573730e+03 2.91066968e+03 2.90513647e+03 2.88038818e+03 2.84174854e+03 2.80720679e+03 2.77519067e+03 2.75610376e+03 2.73022510e+03 2.69703394e+03 2.68145996e+03 2.63805981e+03 2.61100073e+03 2.58445679e+03 2.54440918e+03 2.54198169e+03 2.50039722e+03 2.46567749e+03 2.45379028e+03 2.41470923e+03 2.37928394e+03 2.35295483e+03 2.32597559e+03 2.30036304e+03 2.26333130e+03 2.24290918e+03 2.21048633e+03 2.18253442e+03 2.15040063e+03 2.11277954e+03 2.10075366e+03 2.07360034e+03 2.03435229e+03 2.01157129e+03 1.98094690e+03 1.94632666e+03 1.92434241e+03 1.89896716e+03 1.87675513e+03 1.84134167e+03 2.27053735e+03 2.34337549e+03 -1.12628312e+06 50174852. 0. 0. 0. 0. 90900200. 90900200. 90900200. 0. 0. 0. 102866952. 5.58788867e+04 1.32145723e+04 3.61331860e+03 2.75712036e+03 1.32729297e+03 1.28700720e+03 1.27024243e+03 1.24649927e+03 1.19664954e+03 1.17574707e+03 1.15184058e+03 1.12287769e+03 1.10351123e+03 1.08243042e+03 1.05791284e+03 1.03630298e+03 1.00862170e+03 9.85228699e+02 9.63436951e+02 9.32795471e+02 9.06517090e+02 8.86175354e+02 8.67849609e+02 8.47580994e+02 8.26430115e+02 8.06866577e+02 7.92274292e+02 7.82329468e+02 7.59830444e+02 7.27842346e+02 6.96874939e+02 6.80569397e+02 6.69815491e+02 6.44644409e+02 6.21829651e+02 6.03521484e+02 5.86061707e+02 5.68245422e+02 5.49556641e+02 5.29234985e+02 5.11903839e+02 4.96087341e+02 4.76990662e+02 4.61169708e+02 4.45745575e+02 4.28411377e+02 4.11352234e+02 3.96224030e+02 3.80647583e+02 3.65471344e+02 3.51519623e+02 3.36233398e+02 3.22066467e+02 3.08704498e+02 2.94108124e+02 2.81343781e+02 2.68879761e+02 2.55118561e+02 2.42972092e+02 2.30833054e+02 2.18857269e+02 2.07812332e+02 1.96771072e+02 1.85993759e+02 1.75604797e+02 1.65618301e+02 1.55792007e+02 1.46038055e+02 1.37006271e+02 1.28320770e+02 1.20069710e+02 1.11928085e+02 1.04124557e+02 9.67296906e+01 8.97237396e+01 8.29557343e+01 7.64629440e+01 7.04055634e+01 6.47728958e+01 5.94715385e+01 5.44671288e+01 4.97898140e+01 4.55473022e+01 4.16608162e+01 3.79813499e+01 3.46319389e+01 3.17310486e+01 2.91799755e+01 2.69523830e+01 2.50961037e+01 2.36188755e+01 2.24359360e+01 2.15930672e+01 2.21706409e+01 2.14212061e+03 1.14235268e+01 7.22229481e+00 8.12064171e+00 9.36616325e+00 1.09594135e+01 1.29154634e+01 1.52137547e+01 1.78573627e+01 2.08626270e+01 2.42185478e+01 2.79470329e+01 3.19935665e+01 3.63667908e+01 4.11042824e+01 4.61791077e+01 5.16295815e+01 5.74105110e+01 6.35184860e+01 6.99589539e+01 7.67925262e+01 8.39964600e+01 9.14389801e+01 9.92726822e+01 1.07438843e+02 1.15838608e+02 1.24749832e+02 1.34077515e+02 1.43574966e+02 1.53273422e+02 1.63526123e+02 1.73977097e+02 1.84710068e+02 1.95943298e+02 2.07409302e+02 2.19064316e+02 2.31291153e+02 2.43746002e+02 2.56960999e+02 2.69785828e+02 2.82541473e+02 2.96135406e+02 3.10641968e+02 3.25346436e+02 3.39550293e+02 3.54556885e+02 3.70146362e+02 3.85431641e+02 3.99850189e+02 4.17094879e+02 4.34171417e+02 4.49958008e+02 4.67125702e+02 4.84062836e+02 5.00850769e+02 5.19984619e+02 5.38656006e+02 5.56284912e+02 5.74752075e+02 5.93199463e+02 6.12750793e+02 6.32164734e+02 6.49992004e+02 6.72035950e+02 6.90903687e+02 7.10244446e+02 7.34798889e+02 7.54262024e+02 7.73903320e+02 7.96562073e+02 8.17514343e+02 8.40233154e+02 8.61871277e+02 8.82275024e+02 9.05410828e+02 9.31141785e+02 9.52586975e+02 9.72481445e+02 1.00044330e+03 1.02377673e+03 1.04455920e+03 1.06968994e+03 1.09602710e+03 1.12061267e+03 1.14062756e+03 1.46786829e+03 1.56943494e+03 1.85960474e+03 2.98412720e+03 3.77544946e+03 2.10896953e+04 -6.89769050e+06 -195325808. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -80139704. 1.87943906e+04 3.87671216e+03 2.59630518e+03 2.36678467e+03 2.30324756e+03 1.83500684e+03 1.86392651e+03 1.88285706e+03 1.90547156e+03 1.93234900e+03 1.96857849e+03 2.00579089e+03 2.03455823e+03 2.05241431e+03 2.08599414e+03 2.11368408e+03 2.13690039e+03 2.17502588e+03 2.20277393e+03 2.22610425e+03 2.26160132e+03 2.28721973e+03 2.31485181e+03 2.34484473e+03 2.37032642e+03 2.40319434e+03 2.43417505e+03 2.46160986e+03 2.47975635e+03 2.51737671e+03 2.54812256e+03 2.56205176e+03 2.60039136e+03 2.63070923e+03 2.64961328e+03 2.68881177e+03 2.71342114e+03 2.74620654e+03 2.77688477e+03 2.80467383e+03 2.82431030e+03 2.84803711e+03 2.88993433e+03 2.90969141e+03 2.93790186e+03 2.97052173e+03 2.99483252e+03 3.01915332e+03 3.04290820e+03 3.06493872e+03 3.10174146e+03 3.12149048e+03 3.15178906e+03 3.19369556e+03 3.21460034e+03 3.23838599e+03 3.25438770e+03 3.28251758e+03 3.31719067e+03 3.34303931e+03 3.36068408e+03 3.38912134e+03 3.42596655e+03 3.44159131e+03 3.47102734e+03 3.49995532e+03 3.52606641e+03 3.53651831e+03 3.55167969e+03 3.58988721e+03 3.62232690e+03 3.64247705e+03 3.66634058e+03 3.68727124e+03 3.70958740e+03 3.73727881e+03 3.75757251e+03 3.77330347e+03 3.79751172e+03 3.83231665e+03 3.84783716e+03 3.86153003e+03 3.89077612e+03 3.90904077e+03 3.92500879e+03 3.95120166e+03 3.98527466e+03 3.99360229e+03 4.01233325e+03 4.03677881e+03 4.04943823e+03 4.07046240e+03 4.08838965e+03 4.10608057e+03 4.13885205e+03 4.15207568e+03 4.15450732e+03 4.18620850e+03 4.20873975e+03 4.21427148e+03 4.22569385e+03 4.26311865e+03 4.26770947e+03 4.27359473e+03 4.30344580e+03 4.31516895e+03 4.32782227e+03 4.34736963e+03 4.36135352e+03 4.37472412e+03 4.38570508e+03 4.39816943e+03 4.41421387e+03 4.43446875e+03 4.44124609e+03 4.44771191e+03 4.46395410e+03 4.47331836e+03 4.48856152e+03 4.50115479e+03 4.50880176e+03 4.52259033e+03 4.53125000e+03 4.53909229e+03 4.54739893e+03 4.55893652e+03 4.56818457e+03 4.57752148e+03 4.58600732e+03 4.59120459e+03 4.59900732e+03 4.60730664e+03 4.61620117e+03 4.61810303e+03 4.62195996e+03 4.63198389e+03 4.63901758e+03 4.64415527e+03 4.64744531e+03 4.65003711e+03 4.65251367e+03 4.65943506e+03 4.66200635e+03 4.66262012e+03 4.66804883e+03 4.66979541e+03 4.67104053e+03 4.67433203e+03 4.67454199e+03 4.67488232e+03 4.67601465e+03 4.67606543e+03 4.67601758e+03 4.67484521e+03 4.67393408e+03 4.67338379e+03 4.67104541e+03 4.67041406e+03 4.66771143e+03 4.66358691e+03 4.66246045e+03 4.65797070e+03 4.65264404e+03 4.65210059e+03 4.64795605e+03 4.64012646e+03 4.63519824e+03 4.63304492e+03 4.62577441e+03 4.61663232e+03 4.61085400e+03 4.60897754e+03 4.59974805e+03 4.58894678e+03 4.58416846e+03 4.57459814e+03 4.56373193e+03 4.55647949e+03 4.55094092e+03 4.54179688e+03 4.52933691e+03 4.51928955e+03 4.50956543e+03 4.49636670e+03 4.48818164e+03 4.47597217e+03 4.46209814e+03 4.44883789e+03 4.43843066e+03 4.43331396e+03 4.41367676e+03 4.39693604e+03 4.37792041e+03 4.37084766e+03 4.36196289e+03 4.34148877e+03 4.33051318e+03 4.32166553e+03 4.29627734e+03 4.26683350e+03 4.26279395e+03 4.25272461e+03 4.23231885e+03 4.21908252e+03 4.19494922e+03 4.17588184e+03 4.16592285e+03 4.15211475e+03 4.13278467e+03 4.11045117e+03 4.08246216e+03 4.07116504e+03 4.05197388e+03 4.01948804e+03 4.01272192e+03 3.98934888e+03 3.95942822e+03 3.95915454e+03 3.93338281e+03 3.89997339e+03 3.88809985e+03 3.86604980e+03 3.84419482e+03 3.82474902e+03 3.78813574e+03 3.76704541e+03 3.76453052e+03 3.73386304e+03 3.69601270e+03 3.69333594e+03 3.66517749e+03 3.63316748e+03 3.61012354e+03 3.58965210e+03 3.56435596e+03 3.52995947e+03 3.51697119e+03 3.49988062e+03 3.46152222e+03 3.43064453e+03 3.41644141e+03 3.39881665e+03 3.36239673e+03 3.32923926e+03 3.31172217e+03 3.28925073e+03 3.26039819e+03 3.23405469e+03 3.20507666e+03 3.17858618e+03 3.15537378e+03 3.12410132e+03 3.09705640e+03 3.07520874e+03 3.04289307e+03 3.01835327e+03 2.99649609e+03 2.96635767e+03 2.93210693e+03 2.89776123e+03 2.88533130e+03 2.85432886e+03 2.82075122e+03 2.79124536e+03 2.75851880e+03 2.73335034e+03 2.71127612e+03 2.68590015e+03 2.65826978e+03 2.61829834e+03 2.59061377e+03 2.56800732e+03 2.53442188e+03 2.51251880e+03 2.48652808e+03 2.45303857e+03 2.42925122e+03 2.39630981e+03 2.36804858e+03 2.33871484e+03 2.30956909e+03 2.28336572e+03 2.24917163e+03 2.22655444e+03 2.19549805e+03 2.16744385e+03 2.14097290e+03 2.10836206e+03 2.08671533e+03 2.05102124e+03 2.02249463e+03 1.99981763e+03 1.96962292e+03 1.94277979e+03 1.91388696e+03 1.88822961e+03 1.85055554e+03 1.81819421e+03 1.80287939e+03 1.76726660e+03 1.73989490e+03 1.72240613e+03 1.69039587e+03 1.66320435e+03 1.62957422e+03 1.60046948e+03 1.58202673e+03 1.55410498e+03 1.52383191e+03 1.50535168e+03 1.47356763e+03 1.44528271e+03 1.41789282e+03 1.39069592e+03 1.36932336e+03 1.34278735e+03 1.31278833e+03 1.29088318e+03 1.26648035e+03 1.23631934e+03 1.21177258e+03 1.19138892e+03 1.16443640e+03 1.13774402e+03 1.11099438e+03 1.09026611e+03 1.06843164e+03 1.04360339e+03 1.01967151e+03 9.94642334e+02 9.70006836e+02 9.50170288e+02 9.25511963e+02 9.02451599e+02 8.81417480e+02 8.59435913e+02 8.36972900e+02 8.14359009e+02 7.92498779e+02 7.71457031e+02 7.50036926e+02 7.29708557e+02 7.11333679e+02 6.89208984e+02 6.68769958e+02 6.49289490e+02 6.28845764e+02 6.09896606e+02 5.91109863e+02 5.71507019e+02 5.54332642e+02 5.35539368e+02 5.16186096e+02 4.99657227e+02 4.82769379e+02 4.64232574e+02 4.47198334e+02 4.32287750e+02 4.15127075e+02 3.97993286e+02 3.83683258e+02 3.67833862e+02 3.52162170e+02 3.37820190e+02 3.23213257e+02 3.08928711e+02 2.94960388e+02 2.80801331e+02 2.67876038e+02 2.55405670e+02 2.42195374e+02 2.29508423e+02 2.17444687e+02 2.05817093e+02 1.94539688e+02 1.83479446e+02 1.72571930e+02 1.62230911e+02 1.52056015e+02 1.42209259e+02 1.32702286e+02 1.23598785e+02 1.14761826e+02 1.06375397e+02 9.82643814e+01 9.04641342e+01 8.30134659e+01 7.59045029e+01 6.91332779e+01 6.26547661e+01 5.65563545e+01 5.08408737e+01 4.54618912e+01 4.04272346e+01 3.57069626e+01 3.13340683e+01 2.72974682e+01 2.36513481e+01 2.03470688e+01 1.73782253e+01 1.47697639e+01 1.25043669e+01 1.05893869e+01 9.02890301e+00 7.81750107e+00 6.96053314e+00 6.45541143e+00 6.30099154e+00 6.49658966e+00 7.04456806e+00 7.94338083e+00 9.18973923e+00 1.07879553e+01 1.27430582e+01 1.50452051e+01 1.76970673e+01 2.07035484e+01 2.40478058e+01 2.77434330e+01 3.18064499e+01 3.62050896e+01 4.09375954e+01 4.60251083e+01 5.14882736e+01 5.72527313e+01 6.33578339e+01 6.98057556e+01 7.66271286e+01 8.38347473e+01 9.12857056e+01 9.91344833e+01 1.07269051e+02 1.15658997e+02 1.24564766e+02 1.33912201e+02 1.43360001e+02 1.53082245e+02 1.63348450e+02 1.73798004e+02 1.84613220e+02 1.95716965e+02 2.07131409e+02 2.18908295e+02 2.31134979e+02 2.43510757e+02 2.56659851e+02 2.69585815e+02 2.82406433e+02 2.95938812e+02 3.10556274e+02 3.24996765e+02 3.39236389e+02 3.54166626e+02 3.70019562e+02 3.84874664e+02 3.99461670e+02 4.16768463e+02 4.33571777e+02 4.49618073e+02 4.66500916e+02 4.83996979e+02 5.00882385e+02 5.19567871e+02 5.38297241e+02 5.55815674e+02 5.73979126e+02 5.92374878e+02 6.12662598e+02 6.32310547e+02 6.50308167e+02 6.71531738e+02 6.90705505e+02 7.10772400e+02 7.33643250e+02 7.53749878e+02 7.73947021e+02 7.96471497e+02 8.16378113e+02 8.39515198e+02 8.60214905e+02 8.81420532e+02 9.05899048e+02 9.31404175e+02 9.51768616e+02 9.71686646e+02 9.99708618e+02 1.02453845e+03 1.04520569e+03 1.06867700e+03 1.09468408e+03 1.11735864e+03 1.13855823e+03 1.16717786e+03 1.19381787e+03 1.21712329e+03 1.23907935e+03 1.26787097e+03 1.29632727e+03 1.31764124e+03 1.34238989e+03 1.37124548e+03 1.39752966e+03 1.42232373e+03 1.45209241e+03 1.47396265e+03 1.50122314e+03 1.53073938e+03 1.55310974e+03 1.58455945e+03 1.61523535e+03 1.63580054e+03 1.66607935e+03 1.69494922e+03 1.72151648e+03 1.74656885e+03 1.76801306e+03 1.80376038e+03 1.83605066e+03 1.86427136e+03 1.88539929e+03 1.91063928e+03 1.93721094e+03 1.96662122e+03 2.00873669e+03 2.03542932e+03 2.05011450e+03 2.08619092e+03 2.11527588e+03 2.14012549e+03 2.17202588e+03 2.19582227e+03 2.22800220e+03 2.25765039e+03 2.28537109e+03 2.30775366e+03 2.34329932e+03 2.37310400e+03 2.40496655e+03 2.42358960e+03 2.45381226e+03 2.48063525e+03 2.51788257e+03 2.54788525e+03 2.56609546e+03 2.60526562e+03 2.63019336e+03 2.65062061e+03 2.69621143e+03 2.70939429e+03 2.74013989e+03 2.77752148e+03 2.80138354e+03 2.81945044e+03 2.84903979e+03 2.88610181e+03 2.90726636e+03 2.92722266e+03 2.97146973e+03 2.99491553e+03 3.02740991e+03 3.04551392e+03 3.06369824e+03 3.10727979e+03 3.12596826e+03 3.15267358e+03 3.19173413e+03 3.21457788e+03 3.23233862e+03 3.25620898e+03 3.28596313e+03 3.32022949e+03 3.34183667e+03 3.36506104e+03 3.39294238e+03 3.42265723e+03 3.43848828e+03 3.46729077e+03 3.49994873e+03 3.52222876e+03 3.53457861e+03 3.55441919e+03 3.58707861e+03 3.62186523e+03 3.64190918e+03 3.66523560e+03 3.68372046e+03 3.70709521e+03 3.73770557e+03 3.75624194e+03 3.77454492e+03 3.80108130e+03 3.82472046e+03 3.84966235e+03 3.86381665e+03 3.88786768e+03 3.90705908e+03 3.92495215e+03 3.94930151e+03 3.98361499e+03 3.99071167e+03 4.00937256e+03 4.03548242e+03 4.05130176e+03 4.06830786e+03 4.08870459e+03 4.10396631e+03 4.13406445e+03 4.15153027e+03 4.15659375e+03 4.18408398e+03 4.20356494e+03 4.21188672e+03 4.22949561e+03 4.26125488e+03 4.26777148e+03 4.27466602e+03 4.30358887e+03 4.31518945e+03 4.32619580e+03 4.34712451e+03 4.35899268e+03 4.37111816e+03 4.38801172e+03 4.39538623e+03 4.41243848e+03 4.43900342e+03 4.44126660e+03 4.44461670e+03 4.46109668e+03 4.47475098e+03 4.48689307e+03 4.50157520e+03 4.50909424e+03 4.52329883e+03 4.53308691e+03 4.53759570e+03 4.54644482e+03 4.55786182e+03 4.56687354e+03 4.57724707e+03 4.58542773e+03 4.59227490e+03 4.59857227e+03 4.60678369e+03 4.61568262e+03 4.61801562e+03 4.62334424e+03 4.63067432e+03 4.63679004e+03 4.64395947e+03 4.64838721e+03 4.65048340e+03 4.65238574e+03 4.65753760e+03 4.66209375e+03 4.66338428e+03 4.66718896e+03 4.66956055e+03 4.67106885e+03 4.67419922e+03 4.67445752e+03 4.67475146e+03 4.67585400e+03 4.67596729e+03 4.67598926e+03 4.67481445e+03 4.67393262e+03 4.67341602e+03 4.67107520e+03 4.67025146e+03 4.66741553e+03 4.66392041e+03 4.66171045e+03 4.65809180e+03 4.65446191e+03 4.65197363e+03 4.64718604e+03 4.63938184e+03 4.63542041e+03 4.63219287e+03 4.62528906e+03 4.61919482e+03 4.61203467e+03 4.60589014e+03 4.60081104e+03 4.58921191e+03 4.58228076e+03 4.57602686e+03 4.56400732e+03 4.55636621e+03 4.55411914e+03 4.54193945e+03 4.52899121e+03 4.51831689e+03 4.50897314e+03 4.49681494e+03 4.48795508e+03 4.47720166e+03 4.45969141e+03 4.44707617e+03 4.43781006e+03 4.43506641e+03 4.41761621e+03 4.39432422e+03 4.37643945e+03 4.37462891e+03 4.36594922e+03 4.34105469e+03 4.32711816e+03 4.31938232e+03 4.29622656e+03 4.26628320e+03 4.26379102e+03 4.25512109e+03 4.23163477e+03 4.21728467e+03 4.19805127e+03 4.17756299e+03 4.16648584e+03 4.15340967e+03 4.13242188e+03 4.10690479e+03 4.08629590e+03 4.07032080e+03 4.05252515e+03 4.02564160e+03 4.01321094e+03 3.98887305e+03 3.95917407e+03 3.95698413e+03 3.93232910e+03 3.90129370e+03 3.89007959e+03 3.86608008e+03 3.84592603e+03 3.82303369e+03 3.79212354e+03 3.77186060e+03 3.76390576e+03 3.73145410e+03 3.69607715e+03 3.69344824e+03 3.66845288e+03 3.63554102e+03 3.60928003e+03 3.59199365e+03 3.56557861e+03 3.53329541e+03 3.51967334e+03 3.49517480e+03 3.46651758e+03 3.43511206e+03 3.41825806e+03 3.39548364e+03 3.35973438e+03 3.33220850e+03 3.31174463e+03 3.28804077e+03 3.26233179e+03 3.23716309e+03 3.19901880e+03 3.17688501e+03 3.15728125e+03 3.11792017e+03 3.09696118e+03 3.07615796e+03 3.04359888e+03 3.01819116e+03 2.99797314e+03 2.96427051e+03 2.92906665e+03 2.90186816e+03 2.88254712e+03 2.85435498e+03 2.82280298e+03 2.79026758e+03 2.75936938e+03 2.73672656e+03 2.70737427e+03 2.68751733e+03 2.65780981e+03 2.62157251e+03 2.59811548e+03 2.56577808e+03 2.53407202e+03 2.51886255e+03 2.48819165e+03 2.45196802e+03 2.42547217e+03 2.39937134e+03 2.36903931e+03 2.34059375e+03 2.30725244e+03 2.28358716e+03 2.25300830e+03 2.22921899e+03 2.19533130e+03 2.16806616e+03 2.14009790e+03 2.10352661e+03 2.08136157e+03 2.04944141e+03 2.01731116e+03 1.99934521e+03 1.96485034e+03 1.93563184e+03 1.90886096e+03 1.88092712e+03 1.85322876e+03 1.82357373e+03 2.26747852e+03 2.29575391e+03 3.92003271e+03 4.61716455e+03 -14438716. 27835730. 0. 0. 90900200. 90900200. 90900200. 0. 0. 0. 102866952. 5.58788867e+04 1.32145723e+04 3.63528711e+03 3.22567749e+03 1.88984766e+03 1.77030408e+03 1.25484900e+03 1.21657886e+03 1.18943762e+03 1.16434155e+03 1.13858679e+03 1.11139722e+03 1.08950500e+03 1.06793042e+03 1.04342834e+03 1.02050836e+03 9.94166199e+02 9.72749878e+02 9.50558105e+02 9.23389648e+02 9.00234070e+02 8.77472717e+02 8.57423645e+02 8.35811279e+02 8.14010071e+02 7.92457581e+02 7.71940247e+02 7.53230530e+02 7.31805481e+02 7.10741333e+02 6.87831848e+02 6.67543640e+02 6.50352173e+02 6.32432068e+02 6.15167358e+02 5.92063782e+02 5.70852478e+02 5.54394165e+02 5.35148987e+02 5.16303162e+02 4.99997528e+02 4.83310669e+02 4.64464386e+02 4.47435181e+02 4.32470001e+02 4.15532715e+02 3.98108002e+02 3.83525940e+02 3.67935089e+02 3.52533905e+02 3.38046417e+02 3.23311066e+02 3.08889313e+02 2.95122253e+02 2.80977905e+02 2.68150452e+02 2.55734543e+02 2.42335922e+02 2.29713913e+02 2.17608627e+02 2.05919785e+02 1.94827789e+02 1.83626785e+02 1.72650116e+02 1.62400620e+02 1.52224426e+02 1.42381927e+02 1.32848206e+02 1.23723534e+02 1.14944839e+02 1.06573662e+02 9.84172897e+01 9.06066208e+01 8.31786423e+01 7.61094131e+01 6.93031235e+01 6.28222466e+01 5.67460518e+01 5.10327377e+01 4.56467667e+01 4.06006203e+01 3.58938141e+01 3.15308037e+01 2.74145222e+01 2.37733650e+01 2.04902077e+01 1.75509987e+01 1.49591360e+01 1.26929207e+01 1.07653427e+01 9.11740208e+00 7.77801752e+00 6.90580750e+00 7.59033632e+00 1.13627734e+03 7.59925508e+00 4.83469629e+00 5.65107393e+00 6.81739092e+00 8.35549164e+00 1.02570486e+01 1.24656506e+01 1.49535065e+01 1.78606663e+01 2.11689835e+01 2.47561588e+01 2.87501354e+01 3.30107765e+01 3.76085091e+01 4.25451088e+01 4.78157616e+01 5.34297256e+01 5.93950310e+01 6.56086960e+01 7.22463684e+01 7.92699051e+01 8.64987640e+01 9.42186966e+01 1.02178055e+02 1.10246437e+02 1.19007835e+02 1.28191772e+02 1.37303986e+02 1.46733429e+02 1.56786972e+02 1.67245865e+02 1.77778381e+02 1.88530899e+02 1.99537903e+02 2.11049973e+02 2.23143158e+02 2.35330887e+02 2.48077118e+02 2.60590973e+02 2.73339081e+02 2.86807953e+02 3.00549408e+02 3.14630890e+02 3.29299744e+02 3.43617096e+02 3.58347076e+02 3.74117645e+02 3.88536011e+02 4.04370880e+02 4.21596283e+02 4.37571350e+02 4.54462921e+02 4.70589478e+02 4.87214752e+02 5.05815674e+02 5.23849060e+02 5.41564758e+02 5.59471375e+02 5.77173462e+02 5.97282898e+02 6.16113037e+02 6.33105835e+02 6.53824829e+02 6.74631287e+02 6.93074097e+02 7.14764587e+02 7.35840759e+02 7.55727966e+02 7.76181702e+02 7.98549622e+02 8.20116638e+02 8.42271301e+02 8.62334229e+02 8.83911621e+02 9.07982605e+02 9.29112488e+02 9.53234802e+02 9.75508606e+02 9.99320557e+02 1.02186005e+03 1.04481897e+03 1.07060291e+03 1.37972607e+03 1.44981104e+03 2.61290088e+03 1.99709058e+03 3.62720776e+03 1.34587617e+04 -1.19490977e+05 -195325808. -195325808. 6143239. -532820992. -532820992. 0. 0. 0. 0. 0. 0. -82559888. -5875128. 6.26400635e+03 4.29522559e+03 3.76725049e+03 2.15637671e+03 1.70983521e+03 1.73930688e+03 1.76745813e+03 1.79611890e+03 1.82152576e+03 1.84689551e+03 1.88142493e+03 1.90266614e+03 1.92827112e+03 1.96739868e+03 1.99114966e+03 2.01636963e+03 2.04860913e+03 2.07288599e+03 2.09628247e+03 2.12858008e+03 2.15622974e+03 2.18253125e+03 2.21114160e+03 2.24030444e+03 2.27337378e+03 2.29642651e+03 2.32467676e+03 2.35845703e+03 2.37947412e+03 2.41088452e+03 2.44476514e+03 2.46471143e+03 2.49391846e+03 2.52487720e+03 2.55278198e+03 2.58194336e+03 2.61155811e+03 2.63711597e+03 2.65625684e+03 2.69251514e+03 2.72585156e+03 2.74485913e+03 2.76802539e+03 2.80139697e+03 2.83674536e+03 2.85057642e+03 2.88230664e+03 2.91148120e+03 2.94650513e+03 2.96502441e+03 2.98383179e+03 3.01543311e+03 3.05164624e+03 3.06787183e+03 3.08849463e+03 3.12798145e+03 3.16242651e+03 3.17824365e+03 3.19820752e+03 3.22889600e+03 3.26051343e+03 3.28159814e+03 3.30016064e+03 3.32820776e+03 3.35883618e+03 3.37600171e+03 3.40590259e+03 3.44377368e+03 3.45703564e+03 3.47445361e+03 3.49918384e+03 3.52857446e+03 3.55475854e+03 3.58080640e+03 3.59512500e+03 3.61857642e+03 3.64986182e+03 3.66920142e+03 3.69838818e+03 3.71573267e+03 3.72144067e+03 3.75934277e+03 3.78632666e+03 3.79109570e+03 3.81762915e+03 3.85023730e+03 3.86136475e+03 3.87589575e+03 3.90910449e+03 3.92710791e+03 3.94217578e+03 3.96474829e+03 3.98337036e+03 4.00272559e+03 4.02190601e+03 4.03376270e+03 4.06560864e+03 4.08003271e+03 4.08324292e+03 4.11372559e+03 4.13646484e+03 4.14018408e+03 4.15306787e+03 4.18341406e+03 4.19500098e+03 4.20574365e+03 4.22989746e+03 4.24193018e+03 4.25021191e+03 4.27151709e+03 4.29030029e+03 4.30692969e+03 4.31271826e+03 4.31658203e+03 4.33763672e+03 4.36248926e+03 4.36801318e+03 4.37326318e+03 4.38551123e+03 4.39729932e+03 4.41535840e+03 4.42520117e+03 4.43260938e+03 4.44961572e+03 4.45690430e+03 4.46100146e+03 4.47185010e+03 4.48237109e+03 4.49382861e+03 4.50488672e+03 4.50886719e+03 4.51754492e+03 4.52594727e+03 4.53057715e+03 4.53960742e+03 4.54142432e+03 4.54427393e+03 4.55714648e+03 4.56477295e+03 4.56810498e+03 4.57192480e+03 4.57494287e+03 4.57652881e+03 4.58250293e+03 4.58694092e+03 4.58786084e+03 4.59220654e+03 4.59423193e+03 4.59575439e+03 4.59889795e+03 4.59922949e+03 4.59958203e+03 4.60088037e+03 4.60100342e+03 4.60099902e+03 4.60005273e+03 4.59924609e+03 4.59871436e+03 4.59580273e+03 4.59572314e+03 4.59314111e+03 4.58927490e+03 4.58926221e+03 4.58425977e+03 4.57827588e+03 4.57748193e+03 4.57458740e+03 4.56684033e+03 4.56448584e+03 4.55984424e+03 4.55324902e+03 4.54609717e+03 4.53692871e+03 4.53596191e+03 4.52647852e+03 4.51406250e+03 4.51474951e+03 4.50620312e+03 4.49024951e+03 4.48556543e+03 4.48144238e+03 4.46732178e+03 4.45524316e+03 4.44895654e+03 4.44331641e+03 4.43042773e+03 4.41812109e+03 4.40155957e+03 4.38827783e+03 4.38138574e+03 4.37319629e+03 4.36315869e+03 4.34549268e+03 4.33130225e+03 4.30981201e+03 4.30387646e+03 4.29622754e+03 4.27707275e+03 4.26052344e+03 4.24845410e+03 4.23339746e+03 4.20317578e+03 4.19564600e+03 4.18526758e+03 4.16778857e+03 4.15558008e+03 4.13015820e+03 4.11418848e+03 4.10277246e+03 4.08587500e+03 4.07042847e+03 4.04917627e+03 4.02218213e+03 4.00835767e+03 3.99008325e+03 3.96270239e+03 3.94962646e+03 3.93548804e+03 3.90419116e+03 3.88914380e+03 3.87353247e+03 3.84942407e+03 3.82906030e+03 3.81285596e+03 3.78785059e+03 3.77007886e+03 3.73775635e+03 3.71374292e+03 3.70518018e+03 3.67012817e+03 3.65265698e+03 3.63239551e+03 3.60304248e+03 3.58858813e+03 3.55785986e+03 3.53397852e+03 3.50728052e+03 3.48767188e+03 3.46599023e+03 3.44412427e+03 3.41748608e+03 3.38714722e+03 3.36697437e+03 3.34760645e+03 3.31238721e+03 3.28474023e+03 3.26174097e+03 3.23237378e+03 3.21313477e+03 3.19074341e+03 3.15595215e+03 3.13370435e+03 3.11076880e+03 3.07802222e+03 3.05864697e+03 3.03660449e+03 3.00165552e+03 2.97646338e+03 2.94090234e+03 2.91684326e+03 2.89177539e+03 2.86961401e+03 2.84599658e+03 2.80728906e+03 2.78274097e+03 2.75423657e+03 2.72911890e+03 2.69763574e+03 2.66778540e+03 2.64915405e+03 2.61600098e+03 2.58770679e+03 2.56089111e+03 2.52893921e+03 2.50049316e+03 2.47885327e+03 2.44819604e+03 2.41529980e+03 2.38659473e+03 2.36394360e+03 2.34385742e+03 2.31193042e+03 2.27695972e+03 2.24933569e+03 2.22218188e+03 2.19829395e+03 2.16829468e+03 2.13154736e+03 2.10808350e+03 2.08720630e+03 2.05454980e+03 2.02635620e+03 2.00567236e+03 1.97141235e+03 1.93794983e+03 1.91438879e+03 1.88899609e+03 1.85691345e+03 1.82792017e+03 1.80450842e+03 1.78275574e+03 1.74755872e+03 1.72239856e+03 1.69645740e+03 1.67055835e+03 1.63922546e+03 1.60766187e+03 1.58476965e+03 1.56479700e+03 1.53618713e+03 1.50388696e+03 1.48369885e+03 1.45742041e+03 1.42514343e+03 1.39800903e+03 1.37452173e+03 1.35214417e+03 1.32517688e+03 1.29809338e+03 1.27211682e+03 1.24921765e+03 1.22150769e+03 1.19921667e+03 1.17786121e+03 1.15040027e+03 1.12178760e+03 1.09967139e+03 1.07748010e+03 1.05524951e+03 1.03272888e+03 1.00550995e+03 9.83490295e+02 9.60642151e+02 9.38252930e+02 9.16882751e+02 8.92856506e+02 8.68061401e+02 8.48108337e+02 8.28199707e+02 8.04361938e+02 7.82904785e+02 7.64590759e+02 7.43004395e+02 7.20838318e+02 7.02057251e+02 6.81493347e+02 6.60825439e+02 6.42224426e+02 6.22586060e+02 6.03687744e+02 5.84314148e+02 5.65302063e+02 5.47969360e+02 5.29378845e+02 5.10857269e+02 4.94706573e+02 4.77819946e+02 4.59457611e+02 4.42239471e+02 4.27463959e+02 4.10665710e+02 3.93937897e+02 3.79500977e+02 3.63906769e+02 3.48355713e+02 3.34322968e+02 3.19963654e+02 3.06044159e+02 2.91862213e+02 2.77661896e+02 2.65062775e+02 2.52712463e+02 2.39668259e+02 2.27012054e+02 2.15124817e+02 2.03812759e+02 1.92693497e+02 1.81484268e+02 1.70698883e+02 1.60577774e+02 1.50411346e+02 1.40522781e+02 1.31153458e+02 1.22155800e+02 1.13472977e+02 1.05085609e+02 9.69364624e+01 8.92366867e+01 8.18011322e+01 7.46877060e+01 6.79905472e+01 6.14928780e+01 5.54220581e+01 4.97508202e+01 4.43668747e+01 3.93108101e+01 3.45913925e+01 3.02047653e+01 2.61479492e+01 2.24763145e+01 1.91491566e+01 1.61392689e+01 1.34868317e+01 1.11770287e+01 9.21091175e+00 7.59283733e+00 6.31824684e+00 5.39111900e+00 4.81031799e+00 4.57587910e+00 4.68576670e+00 5.14146614e+00 5.94451666e+00 7.09189701e+00 8.58146477e+00 1.04250288e+01 1.26084309e+01 1.51344385e+01 1.80148506e+01 2.12254524e+01 2.47761421e+01 2.86925545e+01 3.29484558e+01 3.75261650e+01 4.24690247e+01 4.77306633e+01 5.33334694e+01 5.93130455e+01 6.55276642e+01 7.21443863e+01 7.91679764e+01 8.64018936e+01 9.41130600e+01 1.02089363e+02 1.10150459e+02 1.18888062e+02 1.28080856e+02 1.37207565e+02 1.46601547e+02 1.56664932e+02 1.67139236e+02 1.77722702e+02 1.88454224e+02 1.99284531e+02 2.10944916e+02 2.23098526e+02 2.35237305e+02 2.47850525e+02 2.60383179e+02 2.73262604e+02 2.86650574e+02 3.00585724e+02 3.14632202e+02 3.29038116e+02 3.43643311e+02 3.58391693e+02 3.73549225e+02 3.88161163e+02 4.04620392e+02 4.21288239e+02 4.37526672e+02 4.53928406e+02 4.70462280e+02 4.87532288e+02 5.05665253e+02 5.23476257e+02 5.41144409e+02 5.58815979e+02 5.76755554e+02 5.96930786e+02 6.16166077e+02 6.33939087e+02 6.54248230e+02 6.74292603e+02 6.92930176e+02 7.14523682e+02 7.35794373e+02 7.55551025e+02 7.76472595e+02 7.96868103e+02 8.19572754e+02 8.41319092e+02 8.61515381e+02 8.84382141e+02 9.07235168e+02 9.28098694e+02 9.50909424e+02 9.76251587e+02 9.99171387e+02 1.02266071e+03 1.04483557e+03 1.06884412e+03 1.09259265e+03 1.11547302e+03 1.14235645e+03 1.16795239e+03 1.19157788e+03 1.21069214e+03 1.23920703e+03 1.26957117e+03 1.28926514e+03 1.31348230e+03 1.34212744e+03 1.36257019e+03 1.39106396e+03 1.42275708e+03 1.44095386e+03 1.46993054e+03 1.49929419e+03 1.51934070e+03 1.55234375e+03 1.58023474e+03 1.60657849e+03 1.63293945e+03 1.65224182e+03 1.68213025e+03 1.70981677e+03 1.73846802e+03 1.77056116e+03 1.79651453e+03 1.82360535e+03 1.84881470e+03 1.87894702e+03 1.90035828e+03 1.92833252e+03 1.96776721e+03 1.99095020e+03 2.01236047e+03 2.04586511e+03 2.07570923e+03 2.09696899e+03 2.12570142e+03 2.15554541e+03 2.18175317e+03 2.20757300e+03 2.24099268e+03 2.27236328e+03 2.29751196e+03 2.32413257e+03 2.36055151e+03 2.37682202e+03 2.41079150e+03 2.44394556e+03 2.46169141e+03 2.49331030e+03 2.52187085e+03 2.55542896e+03 2.57957300e+03 2.60607275e+03 2.64364819e+03 2.65136133e+03 2.68974219e+03 2.72684937e+03 2.74156006e+03 2.76510083e+03 2.80158472e+03 2.83653247e+03 2.85267114e+03 2.87992847e+03 2.90970386e+03 2.94270996e+03 2.96592676e+03 2.98272949e+03 3.01462158e+03 3.05261230e+03 3.07193359e+03 3.09307617e+03 3.13047388e+03 3.16182617e+03 3.17517700e+03 3.19508838e+03 3.23134497e+03 3.26107617e+03 3.27802124e+03 3.30157642e+03 3.32889185e+03 3.35889648e+03 3.37603589e+03 3.40609058e+03 3.43836011e+03 3.45839136e+03 3.46838159e+03 3.49906421e+03 3.52612744e+03 3.55281494e+03 3.57841187e+03 3.59507812e+03 3.61499048e+03 3.64402637e+03 3.67329028e+03 3.69634277e+03 3.71183008e+03 3.72645776e+03 3.75664014e+03 3.78454688e+03 3.79458740e+03 3.81498486e+03 3.84915405e+03 3.86053003e+03 3.87583447e+03 3.90931055e+03 3.92175732e+03 3.94190942e+03 3.96756714e+03 3.98409839e+03 4.00089062e+03 4.02052905e+03 4.03496118e+03 4.06675562e+03 4.07935278e+03 4.08497485e+03 4.11441260e+03 4.13383398e+03 4.13975781e+03 4.15711816e+03 4.18567725e+03 4.19647266e+03 4.20322900e+03 4.23208936e+03 4.24197998e+03 4.24897607e+03 4.27087549e+03 4.28810645e+03 4.30192871e+03 4.31407568e+03 4.31954980e+03 4.33710449e+03 4.36341260e+03 4.36635889e+03 4.37218457e+03 4.38447070e+03 4.39834521e+03 4.41553760e+03 4.42617090e+03 4.43301855e+03 4.45008008e+03 4.45811719e+03 4.45977197e+03 4.46903564e+03 4.48176123e+03 4.49507031e+03 4.50432764e+03 4.50808008e+03 4.51833545e+03 4.52332715e+03 4.52999219e+03 4.54074463e+03 4.54130420e+03 4.54592236e+03 4.55605371e+03 4.56244043e+03 4.56766846e+03 4.57275195e+03 4.57516504e+03 4.57624854e+03 4.58162842e+03 4.58711572e+03 4.58804834e+03 4.59144775e+03 4.59404541e+03 4.59574072e+03 4.59874707e+03 4.59910547e+03 4.59952588e+03 4.60084424e+03 4.60097070e+03 4.60101855e+03 4.60016699e+03 4.59928027e+03 4.59877344e+03 4.59612402e+03 4.59543066e+03 4.59306787e+03 4.59009668e+03 4.58854980e+03 4.58418457e+03 4.58008447e+03 4.57804004e+03 4.57369141e+03 4.56613281e+03 4.56392578e+03 4.55914209e+03 4.55249902e+03 4.54840234e+03 4.53850146e+03 4.53354834e+03 4.52689062e+03 4.51552344e+03 4.51313867e+03 4.50742676e+03 4.49081055e+03 4.48555273e+03 4.48444531e+03 4.46923828e+03 4.45510449e+03 4.44675879e+03 4.44252734e+03 4.43051660e+03 4.41746875e+03 4.40235303e+03 4.38943750e+03 4.37995703e+03 4.37228711e+03 4.36482520e+03 4.34811523e+03 4.32947510e+03 4.31032617e+03 4.30477783e+03 4.29768115e+03 4.27633252e+03 4.26138770e+03 4.24966309e+03 4.23288672e+03 4.20634766e+03 4.19826807e+03 4.18648779e+03 4.16884131e+03 4.15533887e+03 4.13119580e+03 4.11364648e+03 4.10236475e+03 4.08937329e+03 4.06975488e+03 4.04742017e+03 4.02559497e+03 4.01128418e+03 3.99210767e+03 3.96390259e+03 3.95115479e+03 3.93476416e+03 3.90122949e+03 3.89206250e+03 3.87880298e+03 3.84766211e+03 3.82690796e+03 3.81058447e+03 3.78861035e+03 3.76874902e+03 3.73748389e+03 3.71473462e+03 3.70504419e+03 3.67112378e+03 3.65246021e+03 3.63175757e+03 3.60800024e+03 3.58645654e+03 3.55855176e+03 3.53689917e+03 3.51155786e+03 3.48833130e+03 3.46760767e+03 3.44220996e+03 3.41420728e+03 3.38701025e+03 3.36717798e+03 3.34479907e+03 3.31611255e+03 3.28607886e+03 3.26427539e+03 3.23509253e+03 3.21599927e+03 3.19394873e+03 3.15465283e+03 3.13346973e+03 3.11224585e+03 3.07544824e+03 3.06060864e+03 3.03189624e+03 3.00287158e+03 2.98240527e+03 2.94563159e+03 2.91681226e+03 2.88865381e+03 2.86453735e+03 2.84641455e+03 2.80960352e+03 2.78758276e+03 2.75108789e+03 2.73244922e+03 2.69958130e+03 2.66645190e+03 2.64951831e+03 2.62249414e+03 2.58613330e+03 2.56115698e+03 2.53377368e+03 2.50560645e+03 2.48235840e+03 2.45103149e+03 2.41895850e+03 2.38235889e+03 2.36162939e+03 2.34580371e+03 2.30795996e+03 2.27961011e+03 2.25361914e+03 2.21507642e+03 2.19727441e+03 2.16920264e+03 2.13481177e+03 2.10811426e+03 2.08179443e+03 2.05221631e+03 2.02354468e+03 1.99303870e+03 1.96735913e+03 1.93432104e+03 1.91039014e+03 1.88855310e+03 1.85519385e+03 1.82781702e+03 1.80289246e+03 1.77994873e+03 1.74709546e+03 2.17547827e+03 2.22731909e+03 3.80262354e+03 4.61329834e+03 -9.38247625e+05 49285152. 0. 0. 0. 713521472. 713521472. 713521472. 0. 0. 0. 43894564. -1.93737825e+06 4.40698682e+03 3.18491016e+03 1.88721167e+03 1.71235779e+03 1.56109290e+03 1.14819739e+03 1.12038062e+03 1.09417810e+03 1.07407715e+03 1.05497314e+03 1.02997571e+03 1.00472028e+03 9.80754700e+02 9.60977417e+02 9.39390076e+02 9.14196594e+02 8.88877625e+02 8.65387024e+02 8.46596436e+02 8.27862366e+02 8.04500793e+02 7.82329834e+02 7.64149414e+02 7.44465027e+02 7.21666931e+02 7.01833435e+02 6.80398987e+02 6.62344055e+02 6.42973755e+02 6.24076477e+02 6.09082336e+02 5.86817322e+02 5.65698425e+02 5.49662231e+02 5.29399719e+02 5.09969666e+02 4.94569305e+02 4.77795776e+02 4.59604248e+02 4.42406372e+02 4.27569611e+02 4.10921631e+02 3.94208313e+02 3.79353119e+02 3.64300598e+02 3.48740173e+02 3.34577820e+02 3.20244537e+02 3.06195312e+02 2.91779297e+02 2.77726288e+02 2.65410706e+02 2.53026947e+02 2.39769135e+02 2.27278137e+02 2.15344696e+02 2.03882050e+02 1.92922119e+02 1.81668564e+02 1.70830139e+02 1.60707397e+02 1.50533081e+02 1.40672974e+02 1.31280869e+02 1.22288734e+02 1.13618713e+02 1.05257576e+02 9.70670547e+01 8.93258743e+01 8.17869949e+01 7.46957321e+01 6.79803848e+01 6.14582710e+01 5.53719864e+01 4.96347275e+01 4.42369080e+01 3.92380104e+01 3.43446732e+01 2.98258610e+01 2.57607975e+01 2.21234703e+01 1.88278694e+01 1.58219347e+01 1.31679668e+01 1.08467064e+01 8.87200356e+00 7.22163582e+00 5.92455196e+00 5.02972317e+00 5.99661589e+00 1.98225723e+02 5.85063553e+00 3.55649519e+00 4.41856432e+00 5.61031294e+00 7.15329981e+00 9.07115364e+00 1.13194370e+01 1.38281870e+01 1.67215595e+01 1.99892349e+01 2.35640106e+01 2.75204983e+01 3.17708778e+01 3.63785820e+01 4.13304710e+01 4.65461426e+01 5.21336365e+01 5.81124840e+01 6.44105682e+01 7.11870499e+01 7.82064438e+01 8.54226303e+01 9.30460281e+01 1.00922005e+02 1.09125046e+02 1.17714790e+02 1.26639465e+02 1.35735718e+02 1.45203537e+02 1.55161453e+02 1.65528244e+02 1.75909836e+02 1.86734634e+02 1.97700439e+02 2.08996628e+02 2.20855652e+02 2.32993271e+02 2.45604034e+02 2.58196259e+02 2.70822021e+02 2.84105133e+02 2.97791229e+02 3.11685822e+02 3.26307312e+02 3.40340240e+02 3.54695160e+02 3.70563721e+02 3.84742340e+02 4.00735657e+02 4.17319275e+02 4.32521088e+02 4.49836884e+02 4.66390289e+02 4.82450348e+02 5.01454590e+02 5.17837891e+02 5.35466980e+02 5.55477966e+02 5.72527283e+02 5.90260925e+02 6.08745667e+02 6.26270325e+02 6.47591553e+02 6.68537964e+02 6.85278381e+02 7.06616577e+02 7.28347412e+02 7.48834717e+02 7.69329041e+02 7.88875427e+02 8.10836426e+02 8.32934326e+02 8.54341370e+02 8.74779236e+02 8.96954102e+02 9.18815186e+02 9.43848206e+02 9.64129272e+02 9.86639832e+02 1.00889246e+03 1.32606104e+03 1.41777454e+03 2.45822412e+03 2.90688330e+03 -13031731. 7.06329350e+06 -25215720. -25215720. 0. -9965397. -9965397. 33539572. -532820992. -532820992. 0. 0. 0. 0. -98674960. -1.93392062e+05 4.32095850e+03 3.64095996e+03 2.36790430e+03 2.11082812e+03 2.06572046e+03 1.66446167e+03 1.68893262e+03 1.71851636e+03 1.74695142e+03 1.77302625e+03 1.80168225e+03 1.82813037e+03 1.85958044e+03 1.87858704e+03 1.90678430e+03 1.94878271e+03 1.96610107e+03 1.98748999e+03 2.02174084e+03 2.05245166e+03 2.07712378e+03 2.10052759e+03 2.13253369e+03 2.15456177e+03 2.17671167e+03 2.21585864e+03 2.25226538e+03 2.27309473e+03 2.29659570e+03 2.33439746e+03 2.35685767e+03 2.38171582e+03 2.41246191e+03 2.43888159e+03 2.46924438e+03 2.49152734e+03 2.51843555e+03 2.55075146e+03 2.57576343e+03 2.60716968e+03 2.62244019e+03 2.65685718e+03 2.69795264e+03 2.71176514e+03 2.73716113e+03 2.77142285e+03 2.79332739e+03 2.81483228e+03 2.84869604e+03 2.87528809e+03 2.90105908e+03 2.92582910e+03 2.95017749e+03 2.98895068e+03 3.01284668e+03 3.02928174e+03 3.05254443e+03 3.08837085e+03 3.12262207e+03 3.12945410e+03 3.15762891e+03 3.19605103e+03 3.22515479e+03 3.23625269e+03 3.25733765e+03 3.29129248e+03 3.31658569e+03 3.33390991e+03 3.35920752e+03 3.39655298e+03 3.41405444e+03 3.42790820e+03 3.46087988e+03 3.48255103e+03 3.50137671e+03 3.53981665e+03 3.54616919e+03 3.56980493e+03 3.60259961e+03 3.61962622e+03 3.65063989e+03 3.66671313e+03 3.67958813e+03 3.70315015e+03 3.73317065e+03 3.74403223e+03 3.77075586e+03 3.80275415e+03 3.81288013e+03 3.82700952e+03 3.84824707e+03 3.87508105e+03 3.89030249e+03 3.91120142e+03 3.93945825e+03 3.95419556e+03 3.96522876e+03 3.97295068e+03 4.00516260e+03 4.02162085e+03 4.03642651e+03 4.06452222e+03 4.08125171e+03 4.08859155e+03 4.09356079e+03 4.12551416e+03 4.13808643e+03 4.15108252e+03 4.17604492e+03 4.18709521e+03 4.19374414e+03 4.21110645e+03 4.23257373e+03 4.25035840e+03 4.25343213e+03 4.26012109e+03 4.28037451e+03 4.30281445e+03 4.30975781e+03 4.31381445e+03 4.32623975e+03 4.33807861e+03 4.35349121e+03 4.36531348e+03 4.37279834e+03 4.38377588e+03 4.39464062e+03 4.40209033e+03 4.41497021e+03 4.42182031e+03 4.42945312e+03 4.43836523e+03 4.44534082e+03 4.45540918e+03 4.46322510e+03 4.46725732e+03 4.47454492e+03 4.48061182e+03 4.48317969e+03 4.49329980e+03 4.50022510e+03 4.50322119e+03 4.50762451e+03 4.51141406e+03 4.51388965e+03 4.51746777e+03 4.52192822e+03 4.52433350e+03 4.52782715e+03 4.52933252e+03 4.53087305e+03 4.53398584e+03 4.53421338e+03 4.53451904e+03 4.53569385e+03 4.53578223e+03 4.53575244e+03 4.53465381e+03 4.53400732e+03 4.53322559e+03 4.53018896e+03 4.52963818e+03 4.52744971e+03 4.52481006e+03 4.52408887e+03 4.51874316e+03 4.51222363e+03 4.51034766e+03 4.50682324e+03 4.50255176e+03 4.50107715e+03 4.49197510e+03 4.48572559e+03 4.48264795e+03 4.47335303e+03 4.46956396e+03 4.45945703e+03 4.44905518e+03 4.44721729e+03 4.43826611e+03 4.43077441e+03 4.42200049e+03 4.41238232e+03 4.40071387e+03 4.38937891e+03 4.38341016e+03 4.37947217e+03 4.36648730e+03 4.35365771e+03 4.33826074e+03 4.32415088e+03 4.31577148e+03 4.30508887e+03 4.29828857e+03 4.28184814e+03 4.26912891e+03 4.24736475e+03 4.24005615e+03 4.23203174e+03 4.21135156e+03 4.20249463e+03 4.18525732e+03 4.16930420e+03 4.14463330e+03 4.13736377e+03 4.11994092e+03 4.09673145e+03 4.09363135e+03 4.07277661e+03 4.05424878e+03 4.04626904e+03 4.01548486e+03 4.00364697e+03 4.00130859e+03 3.96964600e+03 3.94253027e+03 3.92703320e+03 3.89852954e+03 3.88959863e+03 3.88054028e+03 3.84292725e+03 3.82562500e+03 3.81706226e+03 3.79526562e+03 3.77248804e+03 3.74792041e+03 3.72584692e+03 3.71179688e+03 3.69082642e+03 3.65822607e+03 3.63750220e+03 3.61502515e+03 3.59875049e+03 3.56858691e+03 3.54664282e+03 3.53281494e+03 3.49867798e+03 3.47372534e+03 3.45931250e+03 3.43910547e+03 3.41170337e+03 3.38898755e+03 3.37076636e+03 3.33209033e+03 3.31300562e+03 3.29387256e+03 3.25523901e+03 3.23363770e+03 3.21613159e+03 3.18070679e+03 3.16123584e+03 3.13964502e+03 3.09980542e+03 3.08535669e+03 3.07034692e+03 3.02754224e+03 3.00696021e+03 2.98346216e+03 2.95216675e+03 2.93095361e+03 2.89924121e+03 2.87117505e+03 2.84285840e+03 2.82824658e+03 2.79187793e+03 2.75611694e+03 2.74556299e+03 2.71361914e+03 2.68488208e+03 2.65464160e+03 2.62778125e+03 2.61092358e+03 2.57262109e+03 2.53780591e+03 2.51442163e+03 2.50018237e+03 2.46825928e+03 2.42530688e+03 2.40829932e+03 2.37324609e+03 2.33849683e+03 2.32560352e+03 2.30965723e+03 2.27043628e+03 2.23731812e+03 2.21133057e+03 2.19006055e+03 2.16301904e+03 2.13431860e+03 2.10039746e+03 2.07341846e+03 2.04586377e+03 2.01710083e+03 1.98920410e+03 1.96729126e+03 1.93937695e+03 1.89846289e+03 1.88003345e+03 1.86102417e+03 1.82587097e+03 1.79524280e+03 1.77387158e+03 1.74647144e+03 1.71482483e+03 1.69234045e+03 1.66290393e+03 1.64060510e+03 1.61051489e+03 1.58217249e+03 1.55916748e+03 1.53559412e+03 1.50631396e+03 1.47306335e+03 1.45174329e+03 1.43054553e+03 1.39867773e+03 1.37304871e+03 1.35251367e+03 1.33024561e+03 1.29956091e+03 1.27007324e+03 1.24952576e+03 1.22734692e+03 1.19699731e+03 1.17414197e+03 1.15567261e+03 1.12801904e+03 1.10077539e+03 1.07979297e+03 1.05632764e+03 1.03235352e+03 1.01264746e+03 9.85625549e+02 9.62196045e+02 9.42249695e+02 9.19519165e+02 8.98270020e+02 8.74967285e+02 8.51028259e+02 8.29393494e+02 8.11379944e+02 7.88110718e+02 7.66548950e+02 7.48386475e+02 7.26940491e+02 7.05240417e+02 6.85421936e+02 6.66732910e+02 6.46471863e+02 6.27852905e+02 6.10153503e+02 5.90417114e+02 5.71090698e+02 5.50910156e+02 5.34692322e+02 5.16989258e+02 4.99338684e+02 4.83960236e+02 4.66068451e+02 4.48170624e+02 4.31378174e+02 4.16658630e+02 4.00402802e+02 3.83951385e+02 3.69590332e+02 3.54502747e+02 3.39325104e+02 3.25189880e+02 3.11258759e+02 2.97578796e+02 2.83667450e+02 2.70010864e+02 2.57328125e+02 2.45105347e+02 2.32683640e+02 2.20031372e+02 2.08556458e+02 1.97409058e+02 1.86191269e+02 1.75418060e+02 1.64921173e+02 1.54810318e+02 1.44890457e+02 1.35307388e+02 1.26224899e+02 1.17295662e+02 1.08745529e+02 1.00481712e+02 9.25727997e+01 8.50692444e+01 7.77645721e+01 7.08145523e+01 6.42818375e+01 5.80047760e+01 5.20766830e+01 4.65249863e+01 4.12736511e+01 3.63468513e+01 3.17666531e+01 2.75224438e+01 2.36055374e+01 2.00394192e+01 1.68241444e+01 1.39317827e+01 1.13837929e+01 9.17231178e+00 7.30237150e+00 5.77499580e+00 4.58609295e+00 3.73969579e+00 3.23470473e+00 3.07002950e+00 3.24751496e+00 3.76478910e+00 4.62537718e+00 5.82724428e+00 7.36566877e+00 9.25123692e+00 1.14738216e+01 1.40351410e+01 1.69441910e+01 2.01768570e+01 2.37426338e+01 2.76666145e+01 3.19275494e+01 3.65291443e+01 4.14846001e+01 4.67005272e+01 5.22975883e+01 5.83141327e+01 6.45201263e+01 7.10781860e+01 7.80279160e+01 8.52520447e+01 9.28895721e+01 1.00815567e+02 1.09041191e+02 1.17612953e+02 1.26547813e+02 1.35658127e+02 1.45111572e+02 1.55029953e+02 1.65437866e+02 1.75892471e+02 1.86662491e+02 1.97564667e+02 2.08994049e+02 2.20869492e+02 2.32855972e+02 2.45377182e+02 2.58022461e+02 2.70898163e+02 2.84035278e+02 2.97761597e+02 3.11577026e+02 3.25955078e+02 3.40232239e+02 3.54639191e+02 3.70082428e+02 3.84409973e+02 4.00562988e+02 4.17359650e+02 4.32605835e+02 4.49515350e+02 4.66071350e+02 4.82569855e+02 5.01644318e+02 5.17597656e+02 5.35375183e+02 5.55080017e+02 5.71572937e+02 5.89909607e+02 6.08756714e+02 6.26289124e+02 6.47452759e+02 6.68974670e+02 6.85183838e+02 7.06217529e+02 7.28046753e+02 7.48525940e+02 7.68640015e+02 7.88168396e+02 8.10623169e+02 8.32701172e+02 8.54511902e+02 8.75684937e+02 8.96843628e+02 9.18910034e+02 9.41561829e+02 9.63470215e+02 9.87186035e+02 1.01195874e+03 1.03284521e+03 1.05790320e+03 1.08114331e+03 1.10438000e+03 1.12871997e+03 1.15507568e+03 1.17978210e+03 1.19835095e+03 1.22655786e+03 1.25493433e+03 1.27300098e+03 1.29920862e+03 1.32882690e+03 1.34686658e+03 1.37510339e+03 1.40549316e+03 1.42517456e+03 1.45462134e+03 1.48526489e+03 1.50522070e+03 1.53280408e+03 1.56150806e+03 1.58423047e+03 1.60946179e+03 1.63551196e+03 1.66496399e+03 1.68863037e+03 1.72046765e+03 1.74472705e+03 1.77107288e+03 1.80413647e+03 1.82893933e+03 1.85774951e+03 1.87645215e+03 1.90621545e+03 1.94869739e+03 1.96519666e+03 1.98504236e+03 2.01918054e+03 2.05225220e+03 2.07771118e+03 2.09543726e+03 2.12773145e+03 2.16007397e+03 2.17689722e+03 2.21555884e+03 2.24798291e+03 2.27414526e+03 2.29466309e+03 2.33076074e+03 2.35226880e+03 2.37853833e+03 2.41434888e+03 2.44505225e+03 2.46784399e+03 2.48647095e+03 2.51655957e+03 2.54473535e+03 2.57406689e+03 2.60508569e+03 2.62179150e+03 2.65475806e+03 2.69558521e+03 2.71402515e+03 2.73499097e+03 2.76781836e+03 2.79781958e+03 2.81951123e+03 2.84535425e+03 2.87435181e+03 2.90510693e+03 2.93056250e+03 2.95198828e+03 2.98488989e+03 3.01684229e+03 3.03418848e+03 3.04929272e+03 3.08178418e+03 3.11817383e+03 3.13424146e+03 3.15323340e+03 3.19534863e+03 3.22330859e+03 3.23740894e+03 3.25419946e+03 3.28852515e+03 3.31725708e+03 3.33165503e+03 3.36115015e+03 3.39594385e+03 3.41164502e+03 3.42745312e+03 3.46170923e+03 3.48181567e+03 3.50041040e+03 3.53956421e+03 3.54770239e+03 3.56799390e+03 3.60030737e+03 3.62074023e+03 3.64701147e+03 3.66722314e+03 3.67696948e+03 3.70214355e+03 3.73239136e+03 3.74501562e+03 3.76531958e+03 3.79835645e+03 3.81413257e+03 3.83218042e+03 3.84937500e+03 3.87301392e+03 3.89101807e+03 3.91136768e+03 3.93677783e+03 3.95040527e+03 3.96665308e+03 3.97420801e+03 4.00574023e+03 4.02058667e+03 4.03297534e+03 4.06615747e+03 4.07764502e+03 4.08683887e+03 4.09800928e+03 4.12634619e+03 4.13743408e+03 4.14839307e+03 4.17553271e+03 4.18393848e+03 4.19355176e+03 4.21321631e+03 4.22969775e+03 4.24475928e+03 4.25471533e+03 4.26278857e+03 4.27830322e+03 4.30123535e+03 4.30939844e+03 4.31167139e+03 4.32453564e+03 4.34064307e+03 4.35384131e+03 4.36426123e+03 4.37307275e+03 4.38491943e+03 4.39354639e+03 4.40107080e+03 4.41214990e+03 4.42031836e+03 4.43011182e+03 4.43769336e+03 4.44439307e+03 4.45673047e+03 4.46105273e+03 4.46681592e+03 4.47605176e+03 4.48029102e+03 4.48390332e+03 4.49272510e+03 4.49870020e+03 4.50216650e+03 4.50745801e+03 4.51132666e+03 4.51366650e+03 4.51687256e+03 4.52193311e+03 4.52443994e+03 4.52728906e+03 4.52908496e+03 4.53057812e+03 4.53361572e+03 4.53397803e+03 4.53431641e+03 4.53540869e+03 4.53556299e+03 4.53555273e+03 4.53459033e+03 4.53389990e+03 4.53303906e+03 4.53046875e+03 4.52944189e+03 4.52744287e+03 4.52529443e+03 4.52317969e+03 4.51852734e+03 4.51366016e+03 4.51118555e+03 4.50634863e+03 4.50197559e+03 4.49958398e+03 4.49162988e+03 4.48662451e+03 4.48361914e+03 4.47432275e+03 4.46926270e+03 4.45852393e+03 4.45012646e+03 4.44753662e+03 4.43841504e+03 4.42948389e+03 4.42184229e+03 4.41498340e+03 4.40292578e+03 4.38958594e+03 4.38293701e+03 4.37723438e+03 4.36439795e+03 4.35437793e+03 4.34029346e+03 4.32571240e+03 4.31425195e+03 4.30519092e+03 4.29833398e+03 4.28454443e+03 4.26714111e+03 4.24727002e+03 4.24113086e+03 4.23198926e+03 4.21108105e+03 4.19731055e+03 4.18664258e+03 4.17138135e+03 4.14388330e+03 4.13757861e+03 4.12384326e+03 4.10024512e+03 4.09358789e+03 4.07358276e+03 4.05288916e+03 4.04920923e+03 4.01932446e+03 4.00080591e+03 3.99916333e+03 3.96521167e+03 3.94489014e+03 3.92762354e+03 3.89726758e+03 3.88920459e+03 3.88014429e+03 3.84502490e+03 3.82770605e+03 3.81810547e+03 3.79225464e+03 3.77226392e+03 3.74786450e+03 3.72817383e+03 3.70966284e+03 3.68992944e+03 3.66048340e+03 3.63897119e+03 3.61755420e+03 3.60155762e+03 3.57168018e+03 3.54949658e+03 3.53314185e+03 3.49631152e+03 3.47976782e+03 3.45890918e+03 3.43924048e+03 3.40817944e+03 3.38866113e+03 3.37003223e+03 3.33124487e+03 3.31431787e+03 3.29548462e+03 3.25754419e+03 3.23576416e+03 3.21575977e+03 3.17934082e+03 3.16161523e+03 3.13948828e+03 3.10626343e+03 3.08515967e+03 3.07017090e+03 3.02712354e+03 3.00493579e+03 2.97831909e+03 2.95482422e+03 2.92880981e+03 2.89629932e+03 2.87177271e+03 2.84650830e+03 2.82841431e+03 2.79432910e+03 2.75927856e+03 2.74653003e+03 2.70982544e+03 2.68794434e+03 2.65239331e+03 2.62376001e+03 2.61211816e+03 2.57292896e+03 2.53584131e+03 2.52181128e+03 2.49762476e+03 2.46750415e+03 2.42935522e+03 2.40564575e+03 2.37572656e+03 2.33974585e+03 2.32728491e+03 2.30562573e+03 2.27358032e+03 2.24158569e+03 2.21323901e+03 2.18605688e+03 2.15492188e+03 2.13535083e+03 2.10515747e+03 2.07714917e+03 2.04425562e+03 2.01751978e+03 1.99008789e+03 1.96220557e+03 1.93630933e+03 1.90270728e+03 1.87564893e+03 1.85693762e+03 1.82399304e+03 1.79515491e+03 1.77053125e+03 1.74568164e+03 1.71665845e+03 1.69046045e+03 1.66600195e+03 2.11047656e+03 2.21820801e+03 3.69891431e+03 4.44196826e+03 3727017. 20257630. 0. 713521472. 713521472. 713521472. 0. 0. 33937456. 33937456. 33937456. 760031232. 4569421. 6.34410449e+03 3.25050171e+03 2.82735181e+03 1.56501404e+03 1.45449402e+03 1.08091711e+03 1.05636157e+03 1.03375171e+03 1.01027869e+03 9.84843933e+02 9.65726624e+02 9.46719849e+02 9.18390320e+02 8.95488281e+02 8.73664856e+02 8.50708557e+02 8.30413635e+02 8.10001038e+02 7.87893433e+02 7.65623718e+02 7.46902527e+02 7.27394653e+02 7.08208618e+02 6.88286865e+02 6.67007324e+02 6.47605713e+02 6.26761719e+02 6.08777344e+02 5.93300049e+02 5.72901917e+02 5.52590149e+02 5.35436829e+02 5.16079163e+02 4.99147003e+02 4.83938416e+02 4.66002716e+02 4.48549957e+02 4.31231659e+02 4.16821625e+02 4.00501129e+02 3.83618988e+02 3.69642944e+02 3.54681213e+02 3.39659241e+02 3.25439911e+02 3.11120178e+02 2.97571899e+02 2.83585693e+02 2.70156769e+02 2.57600677e+02 2.45320541e+02 2.32675995e+02 2.20278152e+02 2.08623398e+02 1.97173569e+02 1.86272003e+02 1.75168381e+02 1.64520035e+02 1.54707550e+02 1.44779846e+02 1.35152084e+02 1.26038391e+02 1.17146866e+02 1.08613525e+02 1.00402893e+02 9.24461288e+01 8.49502716e+01 7.76019135e+01 7.06512680e+01 6.41417465e+01 5.78341103e+01 5.19219284e+01 4.63452644e+01 4.11100578e+01 3.62283936e+01 3.15446815e+01 2.72336693e+01 2.33781738e+01 1.98886566e+01 1.67013950e+01 1.37839756e+01 1.12262249e+01 8.99308872e+00 7.10917234e+00 5.56864309e+00 4.40313911e+00 3.60106635e+00 4.35714769e+00 7.46772034e+02 4.54834700e+00 2.79576349e+00 4.47074127e+00 1.39153709e+01 1.61175156e+01 1.90921669e+01 2.26232071e+01 2.61214714e+01 3.04178982e+01 3.52134628e+01 4.04513092e+01 4.64356766e+01 5.28480301e+01 5.18805923e+01 4.04221191e+01 4.58670311e+01 5.12120018e+01 5.70201950e+01 6.32235413e+01 6.99353638e+01 7.68729630e+01 8.40899048e+01 9.16283264e+01 9.94499207e+01 1.07674400e+02 1.16203270e+02 1.25012573e+02 1.34136490e+02 1.43640869e+02 1.53541290e+02 1.63817657e+02 1.73982391e+02 1.84708847e+02 1.95592178e+02 2.06913986e+02 2.18740494e+02 2.30713531e+02 2.43142166e+02 2.55747147e+02 2.68519501e+02 2.81539764e+02 2.95048584e+02 3.08875793e+02 3.23121765e+02 3.37722534e+02 3.51930695e+02 3.66984436e+02 3.81616333e+02 3.97328918e+02 4.13551849e+02 4.29045532e+02 4.45516663e+02 4.61917664e+02 4.79143768e+02 4.96857117e+02 5.14062378e+02 5.30763184e+02 5.49616516e+02 5.67773987e+02 5.85799622e+02 6.04159729e+02 6.22273804e+02 6.42128601e+02 6.62632874e+02 6.80954102e+02 7.01361389e+02 7.22827942e+02 7.41897034e+02 7.61895386e+02 7.82529602e+02 8.04585022e+02 8.26269531e+02 8.46041138e+02 8.67751465e+02 8.89734314e+02 9.11709656e+02 9.35287415e+02 9.54087402e+02 9.76281128e+02 1.28156006e+03 2.34175195e+03 2.87324536e+03 -1.88177500e+05 80529656. 0. -25215720. -25215720. -25215720. 0. -9965397. -9965397. 33539572. -532820992. -48039468. -18605012. -18605012. 0. 6.92991950e+06 1.66620859e+04 3.50602490e+03 2.06968579e+03 1.99783997e+03 1.57166943e+03 1.60066064e+03 1.62216138e+03 1.64751660e+03 1.67929785e+03 1.70503833e+03 1.73590417e+03 1.76339124e+03 1.78662512e+03 1.81380457e+03 1.84074329e+03 1.86609509e+03 1.89166199e+03 1.92275867e+03 1.94834546e+03 1.97255823e+03 2.00447961e+03 2.03392480e+03 2.05889355e+03 2.08405713e+03 2.10992310e+03 2.13779126e+03 2.16405615e+03 2.19433081e+03 2.22645239e+03 2.24877539e+03 2.27730591e+03 2.31369287e+03 2.32830469e+03 2.36135815e+03 2.38842041e+03 2.41368872e+03 2.44493530e+03 2.47458936e+03 2.50084180e+03 2.52516089e+03 2.55605933e+03 2.58110278e+03 2.60414917e+03 2.63654395e+03 2.66561426e+03 2.68474146e+03 2.71131396e+03 2.74530542e+03 2.76841431e+03 2.79774072e+03 2.82249048e+03 2.84901465e+03 2.88197363e+03 2.89965210e+03 2.92804419e+03 2.95931055e+03 2.98054150e+03 3.00534644e+03 3.02662769e+03 3.05796411e+03 3.08322437e+03 3.10276050e+03 3.13245996e+03 3.16701880e+03 3.19453223e+03 3.20775513e+03 3.23148022e+03 3.26774438e+03 3.28450098e+03 3.30079468e+03 3.32770703e+03 3.36169360e+03 3.38237769e+03 3.40024927e+03 3.43325659e+03 3.44970874e+03 3.47432007e+03 3.50575146e+03 3.51801587e+03 3.53840161e+03 3.56406982e+03 3.58618457e+03 3.61324487e+03 3.63156689e+03 3.65416333e+03 3.67869165e+03 3.69660547e+03 3.71154907e+03 3.72991919e+03 3.76036133e+03 3.78090283e+03 3.79929907e+03 3.81603198e+03 3.84023828e+03 3.85512866e+03 3.87703857e+03 3.90025244e+03 3.91289380e+03 3.92995557e+03 3.94583423e+03 3.96905347e+03 3.98579761e+03 4.00399829e+03 4.02720020e+03 4.03785254e+03 4.04943042e+03 4.06541699e+03 4.08433667e+03 4.10142627e+03 4.11719238e+03 4.13723535e+03 4.14777441e+03 4.15983398e+03 4.17347461e+03 4.19067871e+03 4.20775928e+03 4.21417480e+03 4.22628516e+03 4.24090137e+03 4.25978418e+03 4.26878223e+03 4.27796582e+03 4.28862158e+03 4.29686914e+03 4.31185645e+03 4.32617480e+03 4.33758350e+03 4.34236621e+03 4.35294824e+03 4.36288477e+03 4.37318848e+03 4.38104590e+03 4.38849707e+03 4.39654004e+03 4.40551855e+03 4.41416113e+03 4.42024316e+03 4.42595557e+03 4.43259912e+03 4.44134375e+03 4.44470996e+03 4.45089209e+03 4.45681689e+03 4.46006250e+03 4.46629004e+03 4.46981738e+03 4.47327100e+03 4.47621729e+03 4.47945264e+03 4.48330225e+03 4.48611230e+03 4.48723535e+03 4.48885645e+03 4.49148047e+03 4.49205713e+03 4.49249951e+03 4.49345410e+03 4.49353613e+03 4.49344678e+03 4.49250879e+03 4.49204150e+03 4.49073389e+03 4.48791992e+03 4.48739355e+03 4.48450635e+03 4.48257227e+03 4.48120117e+03 4.47649268e+03 4.47108398e+03 4.46752393e+03 4.46444971e+03 4.46138232e+03 4.45827686e+03 4.44866895e+03 4.44351416e+03 4.43874414e+03 4.43135205e+03 4.42758838e+03 4.41655322e+03 4.40925879e+03 4.40492627e+03 4.39579297e+03 4.38891650e+03 4.38058203e+03 4.37012305e+03 4.35996875e+03 4.34878320e+03 4.34110010e+03 4.33772510e+03 4.32371289e+03 4.30944727e+03 4.29616162e+03 4.28522461e+03 4.27598730e+03 4.26413721e+03 4.25397119e+03 4.24235547e+03 4.22622363e+03 4.20906348e+03 4.20071631e+03 4.18662158e+03 4.17439990e+03 4.16184375e+03 4.14216943e+03 4.12985742e+03 4.10939209e+03 4.09739209e+03 4.07843188e+03 4.06154517e+03 4.04766162e+03 4.03400659e+03 4.02020312e+03 4.00183521e+03 3.98155005e+03 3.96286426e+03 3.95191162e+03 3.93131177e+03 3.90871802e+03 3.89131006e+03 3.86806104e+03 3.84944678e+03 3.83648535e+03 3.81567261e+03 3.79325928e+03 3.77846167e+03 3.75571802e+03 3.73060034e+03 3.71092139e+03 3.69205786e+03 3.67658618e+03 3.64347656e+03 3.62406592e+03 3.60501367e+03 3.57631445e+03 3.56542407e+03 3.53549609e+03 3.50994312e+03 3.49668286e+03 3.46750293e+03 3.44123096e+03 3.41826172e+03 3.40214478e+03 3.37452368e+03 3.35367651e+03 3.33303857e+03 3.30142896e+03 3.27861865e+03 3.25556226e+03 3.22674414e+03 3.20432617e+03 3.18174561e+03 3.15143188e+03 3.12700049e+03 3.10340723e+03 3.07546143e+03 3.05549048e+03 3.02966333e+03 2.99968701e+03 2.97424658e+03 2.94238306e+03 2.92236670e+03 2.90523486e+03 2.86074414e+03 2.84515405e+03 2.82500757e+03 2.79077710e+03 2.75970996e+03 2.74034399e+03 2.71785840e+03 2.68213184e+03 2.65502905e+03 2.62026489e+03 2.60497217e+03 2.58031689e+03 2.54584766e+03 2.51169580e+03 2.48672339e+03 2.47246997e+03 2.43765430e+03 2.40079517e+03 2.37627417e+03 2.35289282e+03 2.32205273e+03 2.29720093e+03 2.27861011e+03 2.24650171e+03 2.21204663e+03 2.19184009e+03 2.16119385e+03 2.13940015e+03 2.11091821e+03 2.07771606e+03 2.05019873e+03 2.02881140e+03 1.99440845e+03 1.96726306e+03 1.94397900e+03 1.91407397e+03 1.88260632e+03 1.85938733e+03 1.83709338e+03 1.80689819e+03 1.77667676e+03 1.75484998e+03 1.72622827e+03 1.69847144e+03 1.67109692e+03 1.64488538e+03 1.62353186e+03 1.59278625e+03 1.56440820e+03 1.54482764e+03 1.51596899e+03 1.48667957e+03 1.45875574e+03 1.43633337e+03 1.41317456e+03 1.38378015e+03 1.36129004e+03 1.33894409e+03 1.31059790e+03 1.28242969e+03 1.25734204e+03 1.23768311e+03 1.21303430e+03 1.18320056e+03 1.15918750e+03 1.14116895e+03 1.11591577e+03 1.08862256e+03 1.06752856e+03 1.04289587e+03 1.02080554e+03 1.00055408e+03 9.73707092e+02 9.50885010e+02 9.29655273e+02 9.06752930e+02 8.86088074e+02 8.64161438e+02 8.41338257e+02 8.19904907e+02 8.00406738e+02 7.78397095e+02 7.56380554e+02 7.37158630e+02 7.17176758e+02 6.97051270e+02 6.76698669e+02 6.57772278e+02 6.37776733e+02 6.19164795e+02 6.01185669e+02 5.81944458e+02 5.62841797e+02 5.44490906e+02 5.27062744e+02 5.09671326e+02 4.93213196e+02 4.76127472e+02 4.58330719e+02 4.41781067e+02 4.25412506e+02 4.09762848e+02 3.94123962e+02 3.78495270e+02 3.63691498e+02 3.48744354e+02 3.34232086e+02 3.19608429e+02 3.05990875e+02 2.92642975e+02 2.78543915e+02 2.65308868e+02 2.52832336e+02 2.40438950e+02 2.28217590e+02 2.16095825e+02 2.04590118e+02 1.93287689e+02 1.82242416e+02 1.71754593e+02 1.61487137e+02 1.51259064e+02 1.41515579e+02 1.32123810e+02 1.23068390e+02 1.14298378e+02 1.05875114e+02 9.77153015e+01 8.98939590e+01 8.24569550e+01 7.52537384e+01 6.84210510e+01 6.19535255e+01 5.58008156e+01 4.99520569e+01 4.44477959e+01 3.92688179e+01 3.44141998e+01 2.99156055e+01 2.57381535e+01 2.18977146e+01 1.83866177e+01 1.52210703e+01 1.23897219e+01 9.89284420e+00 7.73123264e+00 5.90726900e+00 4.42132235e+00 3.27395082e+00 2.46385407e+00 1.99218655e+00 1.85789514e+00 2.06293678e+00 2.60509658e+00 3.48686123e+00 4.70619059e+00 6.26125002e+00 8.15836906e+00 1.03886738e+01 1.29603434e+01 1.58695793e+01 1.91025829e+01 2.26719398e+01 2.65818558e+01 3.08332195e+01 3.54244347e+01 4.03626099e+01 4.55532875e+01 5.11246948e+01 5.70942879e+01 6.32971649e+01 6.98595123e+01 7.67733688e+01 8.39682236e+01 9.15037689e+01 9.93846893e+01 1.07623367e+02 1.16118744e+02 1.24918472e+02 1.34062927e+02 1.43455170e+02 1.53351654e+02 1.63693436e+02 1.73937134e+02 1.84598816e+02 1.95433609e+02 2.06909164e+02 2.18723969e+02 2.30685135e+02 2.43099518e+02 2.55553848e+02 2.68387024e+02 2.81387299e+02 2.94906342e+02 3.08764954e+02 3.23002289e+02 3.37273254e+02 3.51820282e+02 3.66663147e+02 3.81342255e+02 3.97215149e+02 4.13327881e+02 4.29040497e+02 4.45243073e+02 4.61857910e+02 4.78977783e+02 4.96689911e+02 5.14047180e+02 5.30864685e+02 5.49252014e+02 5.67337830e+02 5.84817261e+02 6.03816223e+02 6.22327087e+02 6.41731384e+02 6.61801208e+02 6.81028320e+02 7.01672424e+02 7.22178406e+02 7.41645691e+02 7.61593933e+02 7.81776794e+02 8.04608032e+02 8.26927979e+02 8.45779053e+02 8.67655151e+02 8.88876526e+02 9.10807495e+02 9.35500305e+02 9.56602844e+02 9.78495972e+02 1.00295990e+03 1.02375958e+03 1.04786243e+03 1.07144861e+03 1.09608582e+03 1.11841602e+03 1.14431287e+03 1.16955359e+03 1.18841309e+03 1.21640430e+03 1.24302161e+03 1.26365833e+03 1.29051587e+03 1.31763770e+03 1.33946008e+03 1.36404919e+03 1.38987268e+03 1.41289258e+03 1.44116577e+03 1.47189697e+03 1.49259680e+03 1.51905029e+03 1.54372583e+03 1.57296204e+03 1.60277783e+03 1.62144751e+03 1.65026257e+03 1.67973303e+03 1.70480249e+03 1.72959314e+03 1.76237891e+03 1.78562183e+03 1.81312952e+03 1.83694043e+03 1.86289209e+03 1.89502686e+03 1.92677515e+03 1.94493054e+03 1.96875366e+03 2.00196985e+03 2.03736414e+03 2.05779028e+03 2.07951416e+03 2.10692871e+03 2.13536768e+03 2.16283472e+03 2.19185938e+03 2.22651831e+03 2.24769922e+03 2.27436133e+03 2.30962012e+03 2.33354175e+03 2.36210059e+03 2.39226855e+03 2.41734717e+03 2.44565430e+03 2.46839941e+03 2.49364795e+03 2.52061743e+03 2.55362305e+03 2.58207007e+03 2.60169556e+03 2.63063184e+03 2.66404395e+03 2.68728467e+03 2.71633765e+03 2.74168628e+03 2.77060889e+03 2.79763599e+03 2.81737622e+03 2.84444507e+03 2.88089282e+03 2.90055273e+03 2.92893140e+03 2.95837817e+03 2.98265723e+03 3.00382544e+03 3.02686450e+03 3.05834229e+03 3.08385620e+03 3.10418774e+03 3.13153857e+03 3.16475098e+03 3.19354102e+03 3.20171484e+03 3.23339331e+03 3.26363916e+03 3.28596777e+03 3.30104663e+03 3.32759058e+03 3.36553735e+03 3.38192456e+03 3.39868115e+03 3.42774976e+03 3.45274048e+03 3.47619531e+03 3.50576611e+03 3.51726782e+03 3.53552612e+03 3.56642261e+03 3.58637891e+03 3.61098340e+03 3.63117651e+03 3.65126245e+03 3.67915283e+03 3.69729150e+03 3.71012769e+03 3.73202979e+03 3.75665601e+03 3.77773682e+03 3.80240503e+03 3.81851807e+03 3.83570874e+03 3.85412061e+03 3.87949780e+03 3.89826562e+03 3.91027197e+03 3.92931812e+03 3.94892700e+03 3.96612720e+03 3.98242261e+03 4.00529785e+03 4.02674609e+03 4.03337231e+03 4.05152612e+03 4.06881714e+03 4.08407520e+03 4.10159131e+03 4.11727539e+03 4.13129248e+03 4.14755322e+03 4.16106104e+03 4.17449414e+03 4.18778613e+03 4.20544238e+03 4.21523828e+03 4.22708154e+03 4.24201807e+03 4.25917188e+03 4.26873193e+03 4.27570117e+03 4.28847217e+03 4.29886084e+03 4.31152490e+03 4.32598877e+03 4.33717969e+03 4.34240869e+03 4.35259375e+03 4.36202734e+03 4.37278125e+03 4.38072021e+03 4.38891602e+03 4.39484521e+03 4.40380811e+03 4.41522754e+03 4.41886426e+03 4.42494727e+03 4.43394385e+03 4.44147559e+03 4.44490430e+03 4.45058643e+03 4.45637256e+03 4.45941699e+03 4.46530811e+03 4.46957764e+03 4.47330469e+03 4.47584766e+03 4.47912012e+03 4.48335156e+03 4.48558398e+03 4.48679492e+03 4.48848535e+03 4.49113623e+03 4.49175098e+03 4.49209180e+03 4.49291553e+03 4.49331738e+03 4.49315430e+03 4.49221045e+03 4.49165674e+03 4.49028613e+03 4.48831445e+03 4.48735645e+03 4.48459668e+03 4.48305078e+03 4.48043506e+03 4.47590381e+03 4.47170654e+03 4.46809326e+03 4.46368115e+03 4.46066113e+03 4.45703125e+03 4.44832568e+03 4.44455176e+03 4.43958887e+03 4.43146094e+03 4.42697070e+03 4.41608838e+03 4.40944238e+03 4.40580615e+03 4.39559570e+03 4.38841113e+03 4.38069775e+03 4.37144482e+03 4.36141699e+03 4.34791064e+03 4.34138623e+03 4.33718750e+03 4.32233594e+03 4.31121289e+03 4.29579541e+03 4.28505859e+03 4.27693115e+03 4.26403955e+03 4.25444775e+03 4.24225635e+03 4.22582275e+03 4.20950830e+03 4.19952393e+03 4.18717334e+03 4.17514209e+03 4.16212354e+03 4.14465869e+03 4.13051953e+03 4.11062061e+03 4.09811035e+03 4.08007520e+03 4.05936987e+03 4.04877197e+03 4.03378540e+03 4.01834692e+03 4.00095605e+03 3.98330884e+03 3.96049536e+03 3.94991626e+03 3.93154541e+03 3.90708911e+03 3.89098535e+03 3.86602148e+03 3.84896289e+03 3.83920410e+03 3.81425244e+03 3.79413013e+03 3.77900342e+03 3.75491211e+03 3.73164136e+03 3.71054956e+03 3.69014233e+03 3.67537915e+03 3.64791162e+03 3.62492896e+03 3.60186646e+03 3.57718579e+03 3.56904370e+03 3.53628955e+03 3.51121582e+03 3.49648804e+03 3.46677222e+03 3.44394141e+03 3.42372656e+03 3.40223413e+03 3.37358325e+03 3.35619141e+03 3.33285498e+03 3.30110547e+03 3.27744775e+03 3.25926587e+03 3.22983252e+03 3.20462451e+03 3.18349390e+03 3.15375635e+03 3.13007812e+03 3.10234375e+03 3.07544629e+03 3.05086401e+03 3.03606445e+03 3.00413989e+03 2.97601465e+03 2.94516626e+03 2.92690015e+03 2.90268042e+03 2.85746313e+03 2.84368213e+03 2.82309155e+03 2.79526782e+03 2.76020825e+03 2.74152100e+03 2.71620654e+03 2.68468726e+03 2.65610986e+03 2.62455518e+03 2.60196118e+03 2.57554932e+03 2.54551147e+03 2.51008472e+03 2.49275342e+03 2.47262720e+03 2.43985840e+03 2.40750269e+03 2.37958081e+03 2.34869238e+03 2.32311060e+03 2.29483936e+03 2.28069946e+03 2.24459497e+03 2.21871069e+03 2.19562500e+03 2.16053101e+03 2.13568652e+03 2.11229004e+03 2.08049316e+03 2.05316821e+03 2.02702051e+03 1.99441602e+03 1.97136743e+03 1.94409778e+03 1.91440710e+03 1.88349219e+03 1.85995190e+03 1.83506653e+03 1.80546179e+03 1.77616455e+03 1.75020251e+03 1.72718433e+03 1.69805737e+03 1.66918750e+03 1.64715674e+03 1.62083606e+03 1.59246130e+03 1.99878076e+03 2.03869055e+03 3.60685010e+03 3.90550439e+03 -6930322. 10217729. 713521472. 713521472. 14900514. 14900514. 10108346. 33937456. 33937456. 0. 0. 0. 22295666. -11308298. 3.08682397e+03 2.73711572e+03 1.63173108e+03 1.48642017e+03 1.33532935e+03 1.00078729e+03 9.75895447e+02 9.52192261e+02 9.30033325e+02 9.07742798e+02 8.86155701e+02 8.64153503e+02 8.42510925e+02 8.20518921e+02 7.99434875e+02 7.77646973e+02 7.56065369e+02 7.37684021e+02 7.17932434e+02 6.97872192e+02 6.77392639e+02 6.57489441e+02 6.38400757e+02 6.19445923e+02 6.00866333e+02 5.81784424e+02 5.63968506e+02 5.45966858e+02 5.27350830e+02 5.09604645e+02 4.93386078e+02 4.75816620e+02 4.58469330e+02 4.42157593e+02 4.25602844e+02 4.09612549e+02 3.94123932e+02 3.78528870e+02 3.63733978e+02 3.49081787e+02 3.34283844e+02 3.19800812e+02 3.06074951e+02 2.92394562e+02 2.78725647e+02 2.65403107e+02 2.52976852e+02 2.40653198e+02 2.28265106e+02 2.16161499e+02 2.04598816e+02 1.93247040e+02 1.82355850e+02 1.71645035e+02 1.61340225e+02 1.51335938e+02 1.41554459e+02 1.32094864e+02 1.23049629e+02 1.14272285e+02 1.05887291e+02 9.77387924e+01 8.98866653e+01 8.24717255e+01 7.52367401e+01 6.83848495e+01 6.19752998e+01 5.58291626e+01 5.00264244e+01 4.46297379e+01 3.92231979e+01 4.98161964e+01 3.03463230e+01 3.92558060e+01 3.85284157e+01 2.03382034e+01 1.65653610e+01 1.24275265e+01 9.89704037e+00 7.67455482e+00 5.85161781e+00 4.38874769e+00 3.24023104e+00 2.41792655e+00 3.04449177e+00 2.81415475e+06 1.01244650e+01 7.08099651e+00 1.26324234e+01 1.85739059e+01 1.53890381e+01 1.25533276e+01 -16908724. -4.75296350e+06 6.04157257e+01 4.89269905e+01 3.15443058e+01 3.73344841e+01 3.67243118e+01 4.19643478e+01 3.87004051e+01 4.40780144e+01 4.94389343e+01 5.51795425e+01 6.13218765e+01 6.78983612e+01 7.47480392e+01 8.19071426e+01 8.93429565e+01 9.71149292e+01 1.05251656e+02 1.13689674e+02 1.22370529e+02 1.31453995e+02 1.40825287e+02 1.50601837e+02 1.60879990e+02 1.70932587e+02 1.81397964e+02 1.92264908e+02 2.03565704e+02 2.15252258e+02 2.26983566e+02 2.39555923e+02 2.52178284e+02 2.64381775e+02 2.77311554e+02 2.91147736e+02 3.04738129e+02 3.18221039e+02 3.32736023e+02 3.47646851e+02 3.62182495e+02 3.76963074e+02 3.92041718e+02 4.07976929e+02 4.23769684e+02 4.40027435e+02 4.56846008e+02 4.72989014e+02 4.90306976e+02 5.07257141e+02 5.24928711e+02 5.43298157e+02 5.60914246e+02 5.78625793e+02 5.97968445e+02 6.16044373e+02 6.34928650e+02 6.54902954e+02 6.73023254e+02 6.93410339e+02 7.14466187e+02 7.34909729e+02 7.53990784e+02 7.73379822e+02 7.95939453e+02 8.16784668e+02 8.37093201e+02 8.59684631e+02 8.79796204e+02 9.01904297e+02 1.19319006e+03 1.29860754e+03 1.45791101e+03 2.43095630e+03 1.30651650e+04 6.99199650e+06 0. 0. -63417180. -63417180. -63417180. 0. 0. -9965397. -9965397. -9965397. 0. -18605012. -18605012. -11747172. 31217334. 4.18840723e+03 3.41613330e+03 1.90982959e+03 1.50438696e+03 1.53129541e+03 1.55921204e+03 1.58386047e+03 1.60996765e+03 1.63355249e+03 1.66552625e+03 1.68795239e+03 1.71502185e+03 1.74906079e+03 1.77233887e+03 1.79412952e+03 1.82389624e+03 1.84792822e+03 1.87605334e+03 1.90609692e+03 1.92958533e+03 1.95384253e+03 1.98303308e+03 2.01748315e+03 2.04087683e+03 2.06489819e+03 2.09045044e+03 2.12151758e+03 2.14955762e+03 2.17338037e+03 2.20001782e+03 2.23201367e+03 2.26165234e+03 2.28318652e+03 2.31625610e+03 2.34198315e+03 2.36947485e+03 2.39695142e+03 2.42271289e+03 2.45269873e+03 2.47627954e+03 2.50623511e+03 2.53732642e+03 2.55765454e+03 2.58767578e+03 2.61333081e+03 2.64452026e+03 2.66777490e+03 2.69473120e+03 2.71516846e+03 2.74601123e+03 2.78137964e+03 2.79827930e+03 2.82418262e+03 2.86028394e+03 2.87537622e+03 2.90387476e+03 2.93417456e+03 2.95825195e+03 2.97718359e+03 3.00690137e+03 3.03755664e+03 3.05519067e+03 3.07682739e+03 3.11423047e+03 3.14468286e+03 3.16446021e+03 3.17675854e+03 3.21465088e+03 3.24164307e+03 3.26132275e+03 3.28295850e+03 3.30287695e+03 3.32810474e+03 3.35763647e+03 3.37234204e+03 3.39041235e+03 3.42367432e+03 3.45611719e+03 3.47757324e+03 3.49368433e+03 3.51399536e+03 3.53567773e+03 3.56126147e+03 3.58465527e+03 3.59694678e+03 3.62967822e+03 3.64674829e+03 3.66239282e+03 3.68633716e+03 3.70597998e+03 3.73239282e+03 3.75190308e+03 3.76999097e+03 3.78508960e+03 3.80921924e+03 3.82601318e+03 3.84823657e+03 3.87007080e+03 3.88382300e+03 3.90011182e+03 3.92257275e+03 3.93823340e+03 3.95442651e+03 3.97317188e+03 3.99033618e+03 4.00656055e+03 4.02587158e+03 4.03878809e+03 4.05158447e+03 4.07125684e+03 4.08756519e+03 4.09982666e+03 4.11589355e+03 4.13437354e+03 4.14916650e+03 4.15705664e+03 4.16850293e+03 4.18288818e+03 4.19880762e+03 4.21020215e+03 4.22654443e+03 4.23778174e+03 4.24701074e+03 4.25688867e+03 4.26755469e+03 4.28009326e+03 4.29357568e+03 4.30599170e+03 4.31124756e+03 4.32349072e+03 4.33174414e+03 4.33943945e+03 4.34958154e+03 4.35857910e+03 4.36445703e+03 4.37240430e+03 4.38079883e+03 4.38632617e+03 4.39483691e+03 4.40077832e+03 4.40935254e+03 4.41513867e+03 4.41830908e+03 4.42238770e+03 4.42725195e+03 4.43426562e+03 4.43853027e+03 4.44318652e+03 4.44452295e+03 4.44685498e+03 4.45212500e+03 4.45428662e+03 4.45505811e+03 4.45704004e+03 4.45931006e+03 4.46007910e+03 4.46076270e+03 4.46154541e+03 4.46171582e+03 4.46155713e+03 4.46081006e+03 4.46046094e+03 4.45877930e+03 4.45663037e+03 4.45596924e+03 4.45281055e+03 4.45189258e+03 4.44936182e+03 4.44500732e+03 4.44038623e+03 4.43565137e+03 4.43347217e+03 4.43088867e+03 4.42577295e+03 4.41754736e+03 4.41120264e+03 4.40727637e+03 4.40316455e+03 4.39492676e+03 4.38633398e+03 4.38139795e+03 4.37409521e+03 4.36397656e+03 4.35801660e+03 4.35019629e+03 4.33987305e+03 4.33181641e+03 4.31879590e+03 4.31221875e+03 4.30594434e+03 4.29085205e+03 4.27991992e+03 4.26823193e+03 4.25695605e+03 4.24712207e+03 4.23464355e+03 4.22567236e+03 4.21314941e+03 4.19731299e+03 4.18563623e+03 4.17208203e+03 4.15859619e+03 4.14380029e+03 4.13189209e+03 4.11527734e+03 4.10250537e+03 4.08907080e+03 4.06818579e+03 4.05108911e+03 4.03417822e+03 4.02086694e+03 4.01092261e+03 3.99154956e+03 3.97083594e+03 3.95230151e+03 3.93714014e+03 3.92373926e+03 3.90053003e+03 3.88061865e+03 3.86580469e+03 3.84514819e+03 3.82662915e+03 3.80937744e+03 3.78489282e+03 3.76780347e+03 3.75584814e+03 3.73483521e+03 3.70651978e+03 3.68454492e+03 3.66758325e+03 3.64253540e+03 3.62273120e+03 3.60486304e+03 3.57797363e+03 3.55740234e+03 3.54320923e+03 3.51791406e+03 3.49481641e+03 3.46439722e+03 3.43927710e+03 3.42870947e+03 3.39860962e+03 3.38460547e+03 3.35727588e+03 3.33276025e+03 3.31540503e+03 3.28359668e+03 3.25905225e+03 3.23166895e+03 3.20007764e+03 3.18295117e+03 3.16528442e+03 3.13836719e+03 3.10872852e+03 3.07449365e+03 3.06215454e+03 3.03516992e+03 3.01308691e+03 2.98646362e+03 2.94994702e+03 2.92507202e+03 2.90428906e+03 2.88808862e+03 2.85346851e+03 2.82483252e+03 2.80802808e+03 2.76794507e+03 2.73988306e+03 2.73350342e+03 2.69956934e+03 2.66177100e+03 2.63537354e+03 2.60510596e+03 2.58365063e+03 2.56216528e+03 2.53456909e+03 2.49905176e+03 2.47336670e+03 2.45455518e+03 2.42700610e+03 2.38808716e+03 2.36167871e+03 2.34028174e+03 2.31456982e+03 2.28536157e+03 2.25483252e+03 2.23316626e+03 2.20560107e+03 2.17074194e+03 2.15113770e+03 2.12165015e+03 2.09726562e+03 2.06766455e+03 2.03840796e+03 2.00866516e+03 1.98390454e+03 1.95438354e+03 1.92977429e+03 1.90243018e+03 1.87506482e+03 1.85124072e+03 1.82617114e+03 1.79648169e+03 1.77114722e+03 1.73471594e+03 1.71480420e+03 1.69408606e+03 1.66052771e+03 1.63551660e+03 1.61199622e+03 1.58347864e+03 1.55684595e+03 1.53345056e+03 1.50458105e+03 1.47942554e+03 1.44971204e+03 1.42917188e+03 1.40307153e+03 1.37400964e+03 1.35392651e+03 1.32915466e+03 1.30350769e+03 1.27466699e+03 1.24869385e+03 1.23167627e+03 1.20728748e+03 1.17650427e+03 1.15359509e+03 1.13399243e+03 1.10775989e+03 1.08273120e+03 1.05832385e+03 1.03626428e+03 1.01755750e+03 9.93268921e+02 9.70307068e+02 9.45877808e+02 9.24199463e+02 9.02814575e+02 8.80427124e+02 8.58367554e+02 8.37840881e+02 8.15330627e+02 7.94657227e+02 7.75311646e+02 7.53171936e+02 7.33740540e+02 7.12843567e+02 6.93335022e+02 6.72524902e+02 6.53470947e+02 6.34494995e+02 6.16027832e+02 5.97961243e+02 5.78403015e+02 5.59656555e+02 5.42446411e+02 5.24392578e+02 5.06684113e+02 4.89765961e+02 4.72829071e+02 4.56213684e+02 4.39698883e+02 4.23611969e+02 4.07855682e+02 3.91780853e+02 3.76362793e+02 3.61351044e+02 3.46822327e+02 3.32460327e+02 3.18343903e+02 3.04044952e+02 2.90327454e+02 2.77323944e+02 2.64169006e+02 2.51166855e+02 2.39101929e+02 2.26955933e+02 2.14883286e+02 2.03314133e+02 1.92066315e+02 1.81125778e+02 1.70696518e+02 1.60344742e+02 1.50263016e+02 1.40683670e+02 1.31212677e+02 1.22092644e+02 1.13426781e+02 1.05058525e+02 9.68996964e+01 8.90735550e+01 8.16394806e+01 7.45181808e+01 6.77197113e+01 6.12077713e+01 5.50966568e+01 4.92758522e+01 4.37383728e+01 3.85562134e+01 3.37202110e+01 2.92284050e+01 2.50484104e+01 2.12097988e+01 1.76867809e+01 1.45101948e+01 1.16717758e+01 9.15744305e+00 6.97497368e+00 5.13189554e+00 3.62638521e+00 2.45449662e+00 1.61823094e+00 1.11787474e+00 9.53773320e-01 1.12567008e+00 1.63314235e+00 2.47695446e+00 3.65606380e+00 5.16992378e+00 7.02123642e+00 9.20431232e+00 1.17281017e+01 1.45823326e+01 1.77651749e+01 2.12826214e+01 2.51272030e+01 2.93271980e+01 3.38574219e+01 3.87071190e+01 4.38672752e+01 4.93438911e+01 5.51919518e+01 6.13927956e+01 6.78749771e+01 7.47084732e+01 8.18549652e+01 8.92842026e+01 9.70515213e+01 1.05187050e+02 1.13646965e+02 1.22370552e+02 1.31458084e+02 1.40716904e+02 1.50431549e+02 1.60726166e+02 1.70863205e+02 1.81298706e+02 1.92127014e+02 2.03671631e+02 2.15297623e+02 2.26972763e+02 2.39444672e+02 2.51977478e+02 2.64408112e+02 2.77206696e+02 2.91011841e+02 3.04921204e+02 3.17952332e+02 3.32383118e+02 3.47532288e+02 3.62096558e+02 3.76812103e+02 3.92070343e+02 4.07909668e+02 4.23783844e+02 4.40022247e+02 4.56736267e+02 4.73111938e+02 4.90231293e+02 5.07368774e+02 5.24782898e+02 5.43439697e+02 5.60516113e+02 5.78530579e+02 5.96899902e+02 6.15891724e+02 6.35307922e+02 6.54671021e+02 6.73336792e+02 6.93351868e+02 7.14356934e+02 7.34497192e+02 7.54115112e+02 7.73326477e+02 7.95860840e+02 8.16657410e+02 8.37172180e+02 8.59847229e+02 8.79422729e+02 9.02614380e+02 9.25448059e+02 9.47411438e+02 9.69251038e+02 9.90237366e+02 1.01505310e+03 1.03975696e+03 1.06192871e+03 1.08624548e+03 1.10824963e+03 1.13220605e+03 1.15752222e+03 1.17816406e+03 1.20535217e+03 1.23133240e+03 1.24873889e+03 1.27726599e+03 1.30606531e+03 1.32829077e+03 1.35220459e+03 1.37320435e+03 1.40166479e+03 1.42962244e+03 1.45755469e+03 1.48095569e+03 1.50266345e+03 1.52905457e+03 1.55796509e+03 1.58761389e+03 1.60995764e+03 1.63638269e+03 1.66720691e+03 1.68913000e+03 1.71322205e+03 1.74864136e+03 1.77159827e+03 1.79456384e+03 1.82408167e+03 1.84481580e+03 1.87720117e+03 1.90926978e+03 1.93148145e+03 1.95393970e+03 1.98331970e+03 2.01993713e+03 2.04332532e+03 2.06217920e+03 2.09016187e+03 2.12359497e+03 2.15062622e+03 2.17682935e+03 2.20238428e+03 2.23135254e+03 2.25604126e+03 2.28393481e+03 2.31573730e+03 2.34210449e+03 2.36914673e+03 2.39797119e+03 2.42233911e+03 2.45130884e+03 2.47327759e+03 2.50348047e+03 2.53236523e+03 2.55915479e+03 2.58013062e+03 2.61349658e+03 2.63672314e+03 2.66760815e+03 2.69639453e+03 2.71177686e+03 2.74375781e+03 2.78071411e+03 2.79512451e+03 2.82302783e+03 2.85553809e+03 2.87551392e+03 2.90793213e+03 2.93923975e+03 2.95310718e+03 2.98067090e+03 3.00708643e+03 3.03542383e+03 3.06039331e+03 3.07867676e+03 3.11196484e+03 3.14283228e+03 3.15743359e+03 3.18397607e+03 3.20873706e+03 3.24481006e+03 3.26309912e+03 3.27588550e+03 3.30464868e+03 3.33439355e+03 3.35656641e+03 3.37419092e+03 3.39048291e+03 3.42613892e+03 3.45802930e+03 3.47664111e+03 3.49368823e+03 3.51342969e+03 3.53387573e+03 3.56196777e+03 3.58406299e+03 3.59977344e+03 3.63016748e+03 3.64714844e+03 3.66360254e+03 3.68906006e+03 3.70603271e+03 3.73167505e+03 3.74585059e+03 3.76989453e+03 3.78393799e+03 3.80372778e+03 3.82542188e+03 3.84912793e+03 3.87059888e+03 3.88404736e+03 3.90029321e+03 3.92184985e+03 3.93674097e+03 3.94982764e+03 3.97357495e+03 3.99044189e+03 4.00483472e+03 4.02427808e+03 4.04377783e+03 4.05514453e+03 4.06758765e+03 4.08597412e+03 4.09676758e+03 4.11278662e+03 4.13316699e+03 4.14947607e+03 4.15428516e+03 4.16753320e+03 4.18396924e+03 4.19846094e+03 4.21157715e+03 4.22733984e+03 4.23715723e+03 4.24551709e+03 4.25642578e+03 4.26680225e+03 4.27958936e+03 4.29418701e+03 4.30538574e+03 4.31154102e+03 4.32300781e+03 4.33158789e+03 4.33828662e+03 4.34902539e+03 4.35902490e+03 4.36375879e+03 4.37112939e+03 4.37992920e+03 4.38653174e+03 4.39455273e+03 4.40047803e+03 4.40964209e+03 4.41513525e+03 4.41821387e+03 4.42215869e+03 4.42704492e+03 4.43350439e+03 4.43785596e+03 4.44280957e+03 4.44438770e+03 4.44659424e+03 4.45208008e+03 4.45410791e+03 4.45477441e+03 4.45663281e+03 4.45904443e+03 4.45991406e+03 4.46051953e+03 4.46132959e+03 4.46148096e+03 4.46135156e+03 4.46062305e+03 4.46024023e+03 4.45860449e+03 4.45690869e+03 4.45588184e+03 4.45257324e+03 4.45187598e+03 4.44885107e+03 4.44460742e+03 4.44069141e+03 4.43565869e+03 4.43316699e+03 4.43038574e+03 4.42483447e+03 4.41750000e+03 4.41178516e+03 4.40706543e+03 4.40222852e+03 4.39470215e+03 4.38678955e+03 4.38177002e+03 4.37459375e+03 4.36348828e+03 4.35744873e+03 4.35017871e+03 4.34107520e+03 4.33118066e+03 4.31868408e+03 4.31217334e+03 4.30705859e+03 4.29229541e+03 4.27935742e+03 4.26520557e+03 4.25678955e+03 4.24832471e+03 4.23369141e+03 4.22586133e+03 4.21368799e+03 4.19607959e+03 4.18256641e+03 4.17277979e+03 4.15771875e+03 4.14400781e+03 4.13091455e+03 4.11620898e+03 4.10391504e+03 4.08734131e+03 4.06987720e+03 4.04996753e+03 4.03451196e+03 4.02468091e+03 4.01041577e+03 3.99058862e+03 3.97196191e+03 3.95005298e+03 3.93690625e+03 3.92811670e+03 3.90140649e+03 3.88082788e+03 3.86503003e+03 3.84619702e+03 3.82596289e+03 3.81116724e+03 3.78309570e+03 3.76770898e+03 3.75509033e+03 3.73188135e+03 3.70848218e+03 3.68164600e+03 3.66455933e+03 3.64521997e+03 3.62428613e+03 3.60346313e+03 3.57469824e+03 3.55638672e+03 3.54482324e+03 3.51658496e+03 3.49169556e+03 3.46335571e+03 3.44225171e+03 3.42971045e+03 3.40034790e+03 3.37874512e+03 3.35367236e+03 3.33579517e+03 3.31724072e+03 3.28237158e+03 3.25575244e+03 3.23220850e+03 3.20479956e+03 3.18195947e+03 3.16196313e+03 3.13708618e+03 3.10693774e+03 3.07762866e+03 3.05651465e+03 3.03620557e+03 3.01154663e+03 2.98316406e+03 2.95344434e+03 2.92035620e+03 2.90867310e+03 2.88376953e+03 2.84962598e+03 2.82642725e+03 2.80716479e+03 2.77368335e+03 2.73596265e+03 2.72711963e+03 2.69826318e+03 2.66221509e+03 2.63515894e+03 2.60966479e+03 2.58845898e+03 2.56445312e+03 2.53098730e+03 2.49922412e+03 2.47293286e+03 2.45493408e+03 2.42667896e+03 2.39145190e+03 2.36604712e+03 2.33891626e+03 2.31392773e+03 2.28539551e+03 2.25561548e+03 2.23350586e+03 2.20209717e+03 2.17627222e+03 2.15124756e+03 2.11977515e+03 2.09548291e+03 2.06805762e+03 2.04133630e+03 2.01158716e+03 1.98605444e+03 1.95665234e+03 1.93209485e+03 1.90261414e+03 1.87562317e+03 1.85322925e+03 1.82373413e+03 1.79636487e+03 1.77258130e+03 1.73786267e+03 1.71476465e+03 1.69180981e+03 1.65993311e+03 1.63638025e+03 1.61283411e+03 1.58419031e+03 1.55452112e+03 1.53166394e+03 1.94270557e+03 1.95357385e+03 3.36067432e+03 1.71724434e+04 26356860. 0. 14900514. 14900514. 10108346. 33937456. 33937456. 0. 0. 0. 0. 0. -21283070. -10102348. 3.30707568e+03 3.38007324e+03 2.47920703e+03 1.49290759e+03 1.32237573e+03 1.20005261e+03 9.26954102e+02 9.02053162e+02 8.79509155e+02 8.57444397e+02 8.37704041e+02 8.15318787e+02 7.93641113e+02 7.75445618e+02 7.54700928e+02 7.34510559e+02 7.14106567e+02 6.94693726e+02 6.73062317e+02 6.53716003e+02 6.34630920e+02 6.15687012e+02 5.97359924e+02 5.78481812e+02 5.59936768e+02 5.42525330e+02 5.24206055e+02 5.06418915e+02 4.90213440e+02 4.72931702e+02 4.56096924e+02 4.39948029e+02 4.24141815e+02 4.07487488e+02 3.91877472e+02 3.76577301e+02 3.61569885e+02 3.46979553e+02 3.32608917e+02 3.18217285e+02 3.04301575e+02 2.90430328e+02 2.77248901e+02 2.64226471e+02 2.51280441e+02 2.39292648e+02 2.27007675e+02 2.14884247e+02 2.03231094e+02 1.92031189e+02 1.81171021e+02 1.70555252e+02 1.60284088e+02 1.50330368e+02 1.40702957e+02 1.31196426e+02 1.22098610e+02 1.13436371e+02 1.05103119e+02 9.69730682e+01 8.90963821e+01 8.17126541e+01 7.45801468e+01 6.77465057e+01 6.12862625e+01 5.51774940e+01 4.93923607e+01 4.39913788e+01 3.85028572e+01 7.28105698e+01 4.92233963e+01 8.49516602e+01 1.15274040e+02 3.51792870e+01 2.87257710e+01 2.12947216e+01 1.00222740e+01 1.08889313e+01 1.02462282e+01 8.88067150e+00 7.13788891e+00 5.83121300e+00 6.87794447e+00 -5282419. 8606623. 8606623. 9267666. -14096770. -14096770. -14096770. 0. 0. -30964656. 2.51081100e+02 5.53665123e+01 3.68245926e+01 3.77961121e+01 4.23002663e+01 3.79959755e+01 4.33242950e+01 4.87563705e+01 5.45078125e+01 6.06239929e+01 6.71139526e+01 7.39409637e+01 8.09750290e+01 8.84402695e+01 9.62953720e+01 1.04251297e+02 1.12630974e+02 1.21369896e+02 1.30350952e+02 1.39782852e+02 1.49459930e+02 1.59537415e+02 1.69825851e+02 1.80099136e+02 1.90996918e+02 2.02304260e+02 2.13834686e+02 2.25602570e+02 2.37952866e+02 2.50359161e+02 2.62781952e+02 2.75862671e+02 2.89217255e+02 3.02800018e+02 3.16193878e+02 3.30844482e+02 3.45689697e+02 3.59552917e+02 3.74672882e+02 3.90043823e+02 4.06144592e+02 4.21827576e+02 4.37419525e+02 4.54201813e+02 4.70821198e+02 4.87157501e+02 5.04755981e+02 5.22112427e+02 5.39688171e+02 5.57550415e+02 5.76144165e+02 5.95268188e+02 6.13964722e+02 6.31175537e+02 6.50757874e+02 6.71310486e+02 6.90835754e+02 7.09371094e+02 7.29731140e+02 7.52078308e+02 7.69538818e+02 7.91375732e+02 8.14251160e+02 8.32237061e+02 8.55488342e+02 1.13268457e+03 1.23262170e+03 2.20934473e+03 3.06429150e+03 7.82593945e+03 -3.74507125e+06 56295564. 0. -253570160. -253570160. -2.38166605e+09 -63417180. -63417180. 0. 0. 0. 0. 0. 0. -10204807. 1.62732031e+04 2.25240283e+03 3.33064526e+03 1.93105432e+03 1.86424988e+03 1.47170508e+03 1.49734656e+03 1.52781189e+03 1.55302710e+03 1.57809851e+03 1.60204456e+03 1.62710364e+03 1.65613257e+03 1.68345654e+03 1.70572375e+03 1.73507397e+03 1.76021460e+03 1.78496716e+03 1.81812671e+03 1.84002600e+03 1.86817798e+03 1.89789270e+03 1.92129675e+03 1.94479370e+03 1.97708752e+03 2.00333411e+03 2.03184412e+03 2.06075195e+03 2.08157300e+03 2.11137109e+03 2.14272998e+03 2.16255347e+03 2.18827441e+03 2.22141602e+03 2.24841992e+03 2.27416504e+03 2.30173926e+03 2.33609424e+03 2.36185132e+03 2.37670776e+03 2.41557935e+03 2.44243457e+03 2.45826514e+03 2.48880493e+03 2.52065503e+03 2.54625464e+03 2.57730371e+03 2.60080688e+03 2.62579419e+03 2.65076343e+03 2.68345972e+03 2.70100439e+03 2.73097095e+03 2.76817773e+03 2.78155566e+03 2.81303662e+03 2.84502148e+03 2.86546606e+03 2.88328638e+03 2.90703687e+03 2.94830396e+03 2.97065161e+03 2.99098462e+03 3.01747998e+03 3.04311401e+03 3.07019751e+03 3.10068628e+03 3.12808984e+03 3.14054004e+03 3.17195801e+03 3.20113501e+03 3.22912402e+03 3.24715283e+03 3.26722803e+03 3.28539697e+03 3.31271118e+03 3.34093091e+03 3.35420703e+03 3.37356104e+03 3.40945044e+03 3.44029517e+03 3.46421216e+03 3.47796753e+03 3.49805298e+03 3.51739526e+03 3.54451953e+03 3.56789844e+03 3.57858057e+03 3.60959741e+03 3.63025439e+03 3.65034546e+03 3.67584351e+03 3.68552588e+03 3.71083521e+03 3.73602783e+03 3.74947998e+03 3.76787134e+03 3.78966846e+03 3.80772656e+03 3.82980371e+03 3.84754175e+03 3.86389648e+03 3.88401318e+03 3.90750781e+03 3.91799707e+03 3.93504346e+03 3.95335864e+03 3.96895850e+03 3.98725244e+03 4.00914136e+03 4.02140918e+03 4.03155078e+03 4.05078979e+03 4.07028613e+03 4.08380225e+03 4.09505322e+03 4.11135547e+03 4.12646240e+03 4.13928271e+03 4.15175342e+03 4.16418848e+03 4.17797607e+03 4.19055957e+03 4.20485107e+03 4.21910400e+03 4.22736230e+03 4.23524658e+03 4.24887646e+03 4.26102490e+03 4.27317920e+03 4.28126172e+03 4.29230127e+03 4.30358496e+03 4.30837744e+03 4.31960498e+03 4.32867578e+03 4.33827539e+03 4.34587598e+03 4.35069580e+03 4.36022754e+03 4.36620605e+03 4.37470410e+03 4.38056250e+03 4.38553027e+03 4.39353369e+03 4.39771094e+03 4.40085254e+03 4.40661572e+03 4.41279834e+03 4.41672559e+03 4.42164795e+03 4.42352686e+03 4.42602881e+03 4.43108643e+03 4.43264990e+03 4.43370312e+03 4.43552588e+03 4.43746191e+03 4.43879492e+03 4.43949023e+03 4.44010986e+03 4.44025537e+03 4.44010449e+03 4.43942773e+03 4.43898486e+03 4.43729102e+03 4.43509766e+03 4.43427686e+03 4.43161914e+03 4.43009668e+03 4.42720557e+03 4.42413232e+03 4.41998242e+03 4.41448730e+03 4.41246582e+03 4.40900195e+03 4.40196484e+03 4.39637842e+03 4.39168848e+03 4.38533350e+03 4.38124902e+03 4.37327881e+03 4.36640039e+03 4.36074512e+03 4.35355566e+03 4.34553223e+03 4.33502979e+03 4.32743555e+03 4.31989600e+03 4.31144336e+03 4.29884912e+03 4.28887158e+03 4.28417285e+03 4.27218945e+03 4.25921094e+03 4.24763477e+03 4.23979199e+03 4.22676221e+03 4.21231885e+03 4.20384326e+03 4.19351025e+03 4.17779834e+03 4.16222852e+03 4.15044336e+03 4.13969238e+03 4.12445264e+03 4.11059375e+03 4.09431714e+03 4.07976807e+03 4.06691724e+03 4.04900024e+03 4.03520581e+03 4.02050732e+03 3.99865991e+03 3.98892969e+03 3.97477539e+03 3.95065454e+03 3.93357837e+03 3.91934644e+03 3.90163721e+03 3.88181738e+03 3.86421582e+03 3.84841943e+03 3.82757471e+03 3.80499097e+03 3.78975464e+03 3.76831616e+03 3.74954468e+03 3.73309009e+03 3.70886963e+03 3.69766333e+03 3.66848389e+03 3.64184839e+03 3.63133691e+03 3.60469897e+03 3.58749146e+03 3.55915161e+03 3.53262524e+03 3.52414478e+03 3.50735742e+03 3.47680225e+03 3.44470386e+03 3.42393970e+03 3.41055713e+03 3.38077734e+03 3.36426587e+03 3.33907031e+03 3.31605811e+03 3.30199878e+03 3.26865088e+03 3.24478198e+03 3.21504150e+03 3.18257178e+03 3.16724805e+03 3.14073340e+03 3.11826685e+03 3.08867554e+03 3.05720386e+03 3.04583081e+03 3.02105957e+03 2.99233691e+03 2.97071729e+03 2.93611548e+03 2.91983838e+03 2.89604419e+03 2.86353711e+03 2.83321265e+03 2.80668750e+03 2.79122485e+03 2.75915161e+03 2.72233594e+03 2.70899634e+03 2.68283447e+03 2.65297290e+03 2.63057617e+03 2.59839697e+03 2.56884668e+03 2.55402759e+03 2.51655200e+03 2.48556323e+03 2.46284790e+03 2.44336841e+03 2.41349707e+03 2.38060693e+03 2.35454639e+03 2.32986108e+03 2.30235742e+03 2.26923413e+03 2.24467529e+03 2.21942261e+03 2.18903442e+03 2.16472095e+03 2.13984570e+03 2.12065210e+03 2.08543164e+03 2.05102686e+03 2.03113672e+03 2.00350781e+03 1.96911243e+03 1.94425830e+03 1.92031042e+03 1.89367151e+03 1.87080933e+03 1.83691614e+03 1.81387378e+03 1.78414661e+03 1.76262000e+03 1.72853723e+03 1.70346326e+03 1.68601160e+03 1.65450220e+03 1.62948413e+03 1.60464038e+03 1.57509656e+03 1.54629553e+03 1.52084277e+03 1.49993115e+03 1.47336401e+03 1.44229883e+03 1.41954004e+03 1.39604700e+03 1.36947925e+03 1.34630688e+03 1.32125195e+03 1.29327527e+03 1.26793359e+03 1.24579004e+03 1.22550793e+03 1.19976672e+03 1.17162024e+03 1.14704028e+03 1.12752148e+03 1.10242114e+03 1.07581531e+03 1.05172424e+03 1.03105200e+03 1.01235663e+03 9.87632751e+02 9.64650269e+02 9.41256653e+02 9.17380371e+02 8.96787292e+02 8.76835510e+02 8.54343750e+02 8.32571045e+02 8.10850464e+02 7.89619995e+02 7.70884583e+02 7.48235413e+02 7.27962463e+02 7.09041748e+02 6.88803467e+02 6.69137573e+02 6.49517822e+02 6.30894653e+02 6.12124573e+02 5.93603394e+02 5.74735474e+02 5.56549927e+02 5.39889587e+02 5.20934387e+02 5.03405975e+02 4.86889587e+02 4.69419861e+02 4.53065887e+02 4.37245972e+02 4.20488129e+02 4.04334625e+02 3.89025726e+02 3.74317474e+02 3.59295135e+02 3.44367889e+02 3.29887939e+02 3.15802826e+02 3.01953156e+02 2.88507080e+02 2.74978912e+02 2.62065247e+02 2.49449890e+02 2.36960922e+02 2.24969681e+02 2.13218933e+02 2.01616837e+02 1.90383255e+02 1.79584518e+02 1.69175934e+02 1.58755676e+02 1.48867584e+02 1.39289734e+02 1.29774918e+02 1.20812584e+02 1.12180969e+02 1.03855072e+02 9.58051147e+01 8.79373093e+01 8.05414124e+01 7.35277176e+01 6.67388229e+01 6.02206764e+01 5.41241493e+01 4.83712730e+01 4.28750725e+01 3.77202644e+01 3.29215355e+01 2.84447899e+01 2.42884769e+01 2.04726009e+01 1.69749718e+01 1.38192005e+01 1.09978571e+01 8.49918556e+00 6.33334732e+00 4.50419617e+00 3.01284313e+00 1.85231245e+00 1.02580214e+00 5.34043193e-01 3.76486599e-01 5.53140938e-01 1.06391275e+00 1.90932274e+00 3.08862972e+00 4.60107088e+00 6.44903755e+00 8.62905979e+00 1.11455221e+01 1.39907722e+01 1.71675873e+01 2.06725006e+01 2.45081196e+01 2.86927166e+01 3.32028770e+01 3.80213928e+01 4.31840401e+01 4.86670341e+01 5.44397087e+01 6.05824814e+01 6.71101608e+01 7.39575195e+01 8.09821167e+01 8.84454575e+01 9.62594833e+01 1.04192093e+02 1.12634995e+02 1.21441551e+02 1.30394440e+02 1.39679276e+02 1.49349991e+02 1.59502701e+02 1.69745895e+02 1.80053131e+02 1.91012314e+02 2.02384109e+02 2.13809128e+02 2.25552521e+02 2.38009674e+02 2.50466599e+02 2.62852325e+02 2.75771515e+02 2.88987823e+02 3.03021149e+02 3.16349670e+02 3.30717987e+02 3.45474792e+02 3.59678009e+02 3.74940918e+02 3.90162445e+02 4.05659485e+02 4.21624756e+02 4.37534821e+02 4.54123718e+02 4.70851196e+02 4.87383789e+02 5.04553711e+02 5.22139404e+02 5.40222351e+02 5.57915283e+02 5.75732544e+02 5.94906189e+02 6.13272217e+02 6.31142090e+02 6.51060791e+02 6.70201416e+02 6.90067383e+02 7.10063599e+02 7.29512268e+02 7.51679443e+02 7.69705261e+02 7.90368713e+02 8.13955078e+02 8.32901245e+02 8.55757141e+02 8.76294250e+02 8.96425659e+02 9.20647217e+02 9.44924438e+02 9.64710388e+02 9.85098022e+02 1.01096936e+03 1.03501379e+03 1.05650500e+03 1.08183081e+03 1.10390588e+03 1.12763269e+03 1.15300720e+03 1.17310742e+03 1.20084814e+03 1.22405225e+03 1.24399121e+03 1.27196790e+03 1.29569800e+03 1.32199329e+03 1.34535852e+03 1.36807227e+03 1.39659814e+03 1.42045923e+03 1.44539441e+03 1.47396191e+03 1.49799719e+03 1.52313367e+03 1.54980688e+03 1.58102576e+03 1.60129004e+03 1.62681836e+03 1.65908728e+03 1.68313989e+03 1.70276990e+03 1.73505334e+03 1.76251282e+03 1.78550159e+03 1.81620349e+03 1.83832556e+03 1.86982507e+03 1.89892261e+03 1.92119641e+03 1.94377234e+03 1.97294849e+03 2.00393945e+03 2.03680957e+03 2.05734033e+03 2.08452930e+03 2.11018506e+03 2.13987793e+03 2.15912866e+03 2.18920850e+03 2.22360376e+03 2.24341870e+03 2.27340918e+03 2.30274829e+03 2.33744556e+03 2.36295190e+03 2.37635547e+03 2.41066333e+03 2.44126489e+03 2.46268506e+03 2.48627856e+03 2.51998828e+03 2.54615479e+03 2.57317456e+03 2.60255688e+03 2.62638989e+03 2.65236353e+03 2.68282349e+03 2.70174316e+03 2.73184912e+03 2.76666113e+03 2.78641235e+03 2.81288477e+03 2.84614746e+03 2.86212671e+03 2.88077026e+03 2.92061890e+03 2.94809546e+03 2.96699243e+03 2.98885596e+03 3.02118994e+03 3.04636523e+03 3.06747974e+03 3103. 3.12543970e+03 3.14164893e+03 3.16693237e+03 3.19249902e+03 3.22985327e+03 3.25204297e+03 3.25957324e+03 3.28655933e+03 3.32020166e+03 3.33983252e+03 3.35581885e+03 3.37655884e+03 3.40797705e+03 3.44352930e+03 3.45863452e+03 3.47715601e+03 3.50049194e+03 3.51413452e+03 3.54081909e+03 3.56778345e+03 3.58189917e+03 3.60992236e+03 3.62767725e+03 3.64809888e+03 3.67597583e+03 3.68893408e+03 3.71037012e+03 3.73435571e+03 3.74890479e+03 3.76272705e+03 3.78879346e+03 3.80994458e+03 3.83127783e+03 3.85134961e+03 3.86395239e+03 3.88231177e+03 3.90952490e+03 3.91935303e+03 3.92832031e+03 3.95347021e+03 3.96557910e+03 3.98385474e+03 4.00719507e+03 4.02104395e+03 4.03055005e+03 4.04961548e+03 4.07178564e+03 4.08071899e+03 4.09541162e+03 4.11305566e+03 4.12596338e+03 4.13648926e+03 4.14966406e+03 4.16366309e+03 4.17895508e+03 4.19108350e+03 5.47631201e+03 4.21846533e+03 5.48653906e+03 4.23717871e+03 4.24959033e+03 5.54340967e+03 4.27212842e+03 5.56631738e+03 4.29284814e+03 4.30358496e+03 4.30858789e+03 4.31657812e+03 4.32873486e+03 4.33943701e+03 4.34610400e+03 4.35175391e+03 4.35859082e+03 4.36706250e+03 4.37531494e+03 4.37840771e+03 4.38526953e+03 4.39374365e+03 4.39801562e+03 4.40095117e+03 4.40651709e+03 4.41245166e+03 4.41592725e+03 4.42076855e+03 4.42350098e+03 4.42617822e+03 4.43111768e+03 4.43261182e+03 4.43340039e+03 4.43504395e+03 4.43736182e+03 4.43871240e+03 4.43926611e+03 4.43979395e+03 4.44001562e+03 4.44005273e+03 4.43923730e+03 4.43878613e+03 4.43718701e+03 4.43515967e+03 4.43422510e+03 4.43158740e+03 4.43016309e+03 4.42683740e+03 4.42356982e+03 4.41974609e+03 4.41429688e+03 4.41214355e+03 4.40825586e+03 4.40205127e+03 4.39686963e+03 4.39120752e+03 4.38525830e+03 4.38019824e+03 4.37285596e+03 4.36691748e+03 4.35991162e+03 4.35432275e+03 4.34643555e+03 4.33305322e+03 4.32783691e+03 4.32138818e+03 4.30882324e+03 4.29735742e+03 4.29002295e+03 4.28576221e+03 4.27465771e+03 4.25765918e+03 4.24577148e+03 4.23851514e+03 4.23026074e+03 4.21248486e+03 4.20312451e+03 4.19284277e+03 4.17551465e+03 4.16296191e+03 4.14970557e+03 4.13832520e+03 4.12479785e+03 4.11065186e+03 4.09461719e+03 4.07910449e+03 4.06613525e+03 4.04837109e+03 4.03536597e+03 4.01741943e+03 3.99926880e+03 3.98775391e+03 3.97290625e+03 3.95195312e+03 3.93508813e+03 3.91759644e+03 3.90088672e+03 3.88222217e+03 3.86497021e+03 3.84894922e+03 3.82903174e+03 3.80733521e+03 3.78620142e+03 3.77033911e+03 3.75127075e+03 3.72961255e+03 3.71134619e+03 3.69928003e+03 3.66482202e+03 3.64282837e+03 3.63357300e+03 3.60736865e+03 3.58870312e+03 3.56175708e+03 3.53212695e+03 3.52374097e+03 3.50564478e+03 3.47536182e+03 3.44145068e+03 3.42427026e+03 3.41215649e+03 3.38336572e+03 3.36374634e+03 3.33915967e+03 3.31808301e+03 3.30056177e+03 3.26758374e+03 3.24264502e+03 3.21285181e+03 3.18764722e+03 3.17052881e+03 3.14417627e+03 3.11726221e+03 3.09469922e+03 3.06340991e+03 3.04662720e+03 3.02154736e+03 2.99018311e+03 2.96993799e+03 2.93529883e+03 2.91294092e+03 2.89521631e+03 2.86733813e+03 2.83360278e+03 2.80517847e+03 2.79184253e+03 2.76409912e+03 2.72159570e+03 2.70737744e+03 2.68385400e+03 2.65310645e+03 2.62785376e+03 2.59983716e+03 2.56928394e+03 2.54968042e+03 2.51615991e+03 2.48455200e+03 2.46248193e+03 2.43544458e+03 2.41442188e+03 2.38392798e+03 2.35268799e+03 2.33192432e+03 2.30383740e+03 2.26871729e+03 2.24278760e+03 2.21955640e+03 2.18890723e+03 2.16645117e+03 2.13747168e+03 2.12214062e+03 2.08934351e+03 2.05075317e+03 2.03324365e+03 2.00375537e+03 1.97013599e+03 1.94547302e+03 1.92373145e+03 1.89202271e+03 1.86675476e+03 1.84165161e+03 1.81387146e+03 1.78410950e+03 1.76049683e+03 1.73092444e+03 1.70389551e+03 1.68775378e+03 1.65290747e+03 1.62804028e+03 1.60693506e+03 1.57200586e+03 1.54598853e+03 1.52030347e+03 1.49871204e+03 1.47371045e+03 1.86486646e+03 3.38586230e+03 4.14469336e+03 6969246. -7.06871350e+06 14900514. 14900514. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -16899564. -3.75695225e+06 3.02178369e+03 3.02075098e+03 2.28471924e+03 1.19621777e+03 8.97120667e+02 8.74891357e+02 8.52673584e+02 8.32384033e+02 8.11377869e+02 7.89450378e+02 7.70628967e+02 7.49313538e+02 7.29815430e+02 7.09574280e+02 6.89145691e+02 6.68178650e+02 6.49197144e+02 6.30797180e+02 6.12248291e+02 5.94268188e+02 5.74945801e+02 5.56509216e+02 5.39476013e+02 5.20944153e+02 5.03754211e+02 4.86925354e+02 4.69245880e+02 4.53061493e+02 4.37097015e+02 4.20718842e+02 4.04321045e+02 3.88855255e+02 3.74478302e+02 3.59525482e+02 3.44502747e+02 3.29928894e+02 3.15570587e+02 3.02061127e+02 2.88318451e+02 2.74923218e+02 2.62191467e+02 2.49422241e+02 2.37127853e+02 2.25023239e+02 2.13240082e+02 2.01645157e+02 1.90491653e+02 1.79670685e+02 1.69136261e+02 1.58735870e+02 1.48843628e+02 1.39277771e+02 1.29775772e+02 1.20857124e+02 1.12167427e+02 1.03844849e+02 9.58153992e+01 8.79499130e+01 8.05669327e+01 7.35339127e+01 6.67393417e+01 6.02690735e+01 5.41626396e+01 4.84070625e+01 4.29752655e+01 3.76878014e+01 1.40155670e+02 9.44805832e+01 -14063035. -14063035. -35223920. -8527352. 3.07315352e+04 1.68889046e+01 2.27701778e+01 3.09519958e+01 1.28563125e+05 4.67178203e+04 4.68858050e+06 -2.74401425e+06 0. 0. -62709180. 19002828. 3.47374039e+01 -34552112. -14096770. 0. 0. -30964656. 2.51081100e+02 5.53665123e+01 3.68245926e+01 4.13518257e+01 4.39291191e+01 3.76503372e+01 4.28308868e+01 4.83227158e+01 5.40933304e+01 6.02006569e+01 6.66836090e+01 7.34612503e+01 8.04920578e+01 8.79668579e+01 9.57724152e+01 1.03749641e+02 1.12108238e+02 1.20850014e+02 1.29823715e+02 1.39149780e+02 1.48790070e+02 1.58725952e+02 1.69049072e+02 1.79431717e+02 1.90386658e+02 2.01698792e+02 2.13154770e+02 2.24888718e+02 2.36985016e+02 2.49425186e+02 2.61835297e+02 2.75122070e+02 2.88496307e+02 3.01950684e+02 3.15340973e+02 3.29345459e+02 3.44169403e+02 3.58587616e+02 3.73636932e+02 3.89174561e+02 4.05076813e+02 4.20689789e+02 4.36508179e+02 4.53019226e+02 4.69126465e+02 4.85799713e+02 5.02995117e+02 5.21138428e+02 5.38763916e+02 5.56096558e+02 5.74469788e+02 5.93159729e+02 6.11377563e+02 6.30207275e+02 6.49607544e+02 6.68735352e+02 6.87839600e+02 7.07070984e+02 7.29357239e+02 7.50287903e+02 7.67042114e+02 7.89453979e+02 8.11049622e+02 1.07255957e+03 1.15928528e+03 2.08430371e+03 2.77744507e+03 3.53654175e+06 7219683. -36641328. -36641328. 0. 0. -253570160. -253570160. -2.38166605e+09 -63417180. -63417180. 0. 0. 0. 0. 17405112. 12330150. 4.02433740e+03 3.24454224e+03 1.88469421e+03 1.81377026e+03 1.41929333e+03 1.44192444e+03 1.46683875e+03 1.49606567e+03 1.52398413e+03 1.54620801e+03 1.57228625e+03 1.60407361e+03 1.62308606e+03 1.65148865e+03 1.67999792e+03 1.70304272e+03 1.73277979e+03 1.75855115e+03 1.78282849e+03 1.80995667e+03 1.83375977e+03 1.86086340e+03 1.89552881e+03 1.91393530e+03 1.94438037e+03 1.97196350e+03 1.99513916e+03 2.02771021e+03 2.05713843e+03 2.07753491e+03 2.10536548e+03 2.13887158e+03 2.15747144e+03 2.18718286e+03 2.21701685e+03 2.24573755e+03 2.26901440e+03 2.29752100e+03 2.32759619e+03 2.35313477e+03 2.37697095e+03 2.40913379e+03 2.43333081e+03 2.45365063e+03 2.48674146e+03 2.51782739e+03 2.53933765e+03 2.56915674e+03 2.59877051e+03 2.62162744e+03 2.64796045e+03 2.67704932e+03 2.69583838e+03 2.72777417e+03 2.76195337e+03 2.77922021e+03 2.80917114e+03 2.83597729e+03 2.86045557e+03 2.87751416e+03 2.90346167e+03 2.94138550e+03 2.96077637e+03 2.98208423e+03 3.01201807e+03 3.04407666e+03 3.05824878e+03 3.09316870e+03 3.11427173e+03 3.13365381e+03 3.16497021e+03 3.19414258e+03 3.21661108e+03 3.23607300e+03 3.26322241e+03 3.28388232e+03 3.30386694e+03 3.32898438e+03 3.34836450e+03 3.37507104e+03 3.40211597e+03 3.42778174e+03 3.45053418e+03 3.47624805e+03 3.49328906e+03 3.51223486e+03 3.54150293e+03 3.55667334e+03 3.57399707e+03 3.60308887e+03 3.61581714e+03 3.64039795e+03 3.66984180e+03 3.68305029e+03 3.70479175e+03 3.72557227e+03 3.74450269e+03 3.75254102e+03 3.78072559e+03 3.80448022e+03 3.81936768e+03 3.84211621e+03 3.85671338e+03 3.87326440e+03 3.89554492e+03 3.91303345e+03 3.92878271e+03 3.94329980e+03 3.95706250e+03 3.98136987e+03 3.99766675e+03 4.01216528e+03 4.02811060e+03 4.04248291e+03 4.05592236e+03 4.07370508e+03 4.08724512e+03 4.09853125e+03 4.11553125e+03 4.13124707e+03 4.14497559e+03 4.15605859e+03 4.16902881e+03 4.18376221e+03 4.19686182e+03 4.20665771e+03 4.22079590e+03 4.22941064e+03 4.23792236e+03 4.25147363e+03 4.26577100e+03 4.27256543e+03 4.28329443e+03 4.29514307e+03 4.29939160e+03 4.31159961e+03 4.31917480e+03 4.32721973e+03 4.33785645e+03 4.34104980e+03 4.34971094e+03 4.36011279e+03 4.36567236e+03 4.37111182e+03 4.37331299e+03 4.38332617e+03 4.38906592e+03 4.39193994e+03 4.39927490e+03 4.40330615e+03 4.40651367e+03 4.41244531e+03 4.41408838e+03 4.41705420e+03 4.42166699e+03 4.42283203e+03 4.42481396e+03 4.42622217e+03 4.42806787e+03 4.42954053e+03 4.43011426e+03 4.43084619e+03 4.43094141e+03 4.43081055e+03 4.43009912e+03 4.42937207e+03 4.42794141e+03 4.42606201e+03 4.42498486e+03 4.42282861e+03 4.42043945e+03 4.41754053e+03 4.41480811e+03 4.41114355e+03 4.40598389e+03 4.40276562e+03 4.39854346e+03 4.39209521e+03 4.38757617e+03 4.38203125e+03 4.37685059e+03 4.37170850e+03 4.36293408e+03 4.35747314e+03 4.35163867e+03 4.34473096e+03 4.33545361e+03 5.60901074e+03 5.88351318e+03 6.46811328e+03 6.45650000e+03 6.43521484e+03 6.42117285e+03 6.41030420e+03 6.39402588e+03 6.37584424e+03 6.36315918e+03 6.34832959e+03 6.32983203e+03 6.30520264e+03 6.29118799e+03 6.27651025e+03 6.25362939e+03 6.22958496e+03 6.21205029e+03 5.68988574e+03 6.17311084e+03 5.60770166e+03 6.13127100e+03 5.57123828e+03 5.29324707e+03 4.04187305e+03 4.02722412e+03 4.00848975e+03 3.99569897e+03 3.97965894e+03 3.96242261e+03 3.94488525e+03 3.92365796e+03 3.91220337e+03 3.89633398e+03 3.87283740e+03 3.85405273e+03 3.83718579e+03 3.81634937e+03 3.79947607e+03 3.78775049e+03 3.75847925e+03 3.74047095e+03 3.72313721e+03 3.70720264e+03 3.69275708e+03 3.66154932e+03 3.63350684e+03 3.61970923e+03 3.60179883e+03 3.57690381e+03 3.54966846e+03 3.53077710e+03 3.51568311e+03 3.49599097e+03 3.47390234e+03 3.43696606e+03 3.41354346e+03 3.40339380e+03 3.38097559e+03 3.35486084e+03 3.33107056e+03 3.31028271e+03 3.29361719e+03 3.26132861e+03 3.23535547e+03 3.20672119e+03 3.18003027e+03 3.16623169e+03 3.13745435e+03 3.11510107e+03 3.08502881e+03 3.06138867e+03 3.03967407e+03 3.01356470e+03 2.99508374e+03 2.95983667e+03 2.93010181e+03 2.91450366e+03 2.88360205e+03 2.85789136e+03 2.83276562e+03 2.80128906e+03 2.77952173e+03 2.75609424e+03 2.72246924e+03 2.70266675e+03 2.67658984e+03 2.64606689e+03 2.62339575e+03 2.58999951e+03 2.56170850e+03 2.54752393e+03 2.50927612e+03 2.48556616e+03 2.45921509e+03 2.42877466e+03 2.40515747e+03 2.37866406e+03 2.34674585e+03 2.32082764e+03 2.29765137e+03 2.26701709e+03 2.24175073e+03 2.21819238e+03 2.18427563e+03 2.15735693e+03 2.13389795e+03 2.11151660e+03 2.07921191e+03 2.05325732e+03 2.02732227e+03 1.99915210e+03 1.96913794e+03 1.94505957e+03 1.92097095e+03 1.88947388e+03 1.86167932e+03 1.83670593e+03 1.80907788e+03 1.77980139e+03 1.75811719e+03 1.72495374e+03 1.69988562e+03 1.68419873e+03 1.65240088e+03 1.62571265e+03 1.60014331e+03 1.57258374e+03 1.54175793e+03 1.51727478e+03 1.49799988e+03 1.46857434e+03 1.43786890e+03 1.41690845e+03 1.39624585e+03 1.36481189e+03 1.34325293e+03 1.31593359e+03 1.28932898e+03 1.26597363e+03 1.24485474e+03 1.22090283e+03 1.19598315e+03 1.17031665e+03 1.14705969e+03 1.12329993e+03 1.09898901e+03 1.07507471e+03 1.05121106e+03 1.03021045e+03 1.00765607e+03 9.84572754e+02 9.62743042e+02 9.39328186e+02 9.15932190e+02 8.96179321e+02 8.75209717e+02 8.52825439e+02 8.30843628e+02 8.08574829e+02 7.88682556e+02 7.68913269e+02 7.47257324e+02 7.27337585e+02 7.07449036e+02 6.87366333e+02 6.66306946e+02 6.47509888e+02 6.30098511e+02 6.11255737e+02 5.92663208e+02 5.73416931e+02 5.54880615e+02 5.38282532e+02 5.20145264e+02 5.01756165e+02 4.84907806e+02 4.68117706e+02 4.52733368e+02 4.35939545e+02 4.19398682e+02 4.03997894e+02 3.88081726e+02 3.72737000e+02 3.58626282e+02 3.43725403e+02 3.28849091e+02 3.15006439e+02 3.01259338e+02 2.87761353e+02 2.74276245e+02 2.61401093e+02 2.48818268e+02 2.36353592e+02 2.24299713e+02 2.12688385e+02 2.01202301e+02 1.89846375e+02 1.79009186e+02 1.68619751e+02 1.58227859e+02 1.48379166e+02 1.38814957e+02 1.29343033e+02 1.20436211e+02 1.11770317e+02 1.03371880e+02 9.53917084e+01 8.75601349e+01 8.01794815e+01 7.32202454e+01 6.63896408e+01 5.98819923e+01 5.37710495e+01 4.80430946e+01 4.25745354e+01 3.74189529e+01 3.26450195e+01 2.81646080e+01 2.40086708e+01 2.01972408e+01 1.67063980e+01 1.35561419e+01 1.07343597e+01 8.24018288e+00 6.08081293e+00 4.25320339e+00 2.76142526e+00 1.60157537e+00 7.74985909e-01 2.82194406e-01 1.22906558e-01 2.97228515e-01 8.05079758e-01 1.64659488e+00 2.82153535e+00 4.32905865e+00 6.17046261e+00 8.34576416e+00 1.08535681e+01 1.36886969e+01 1.68628006e+01 2.03630505e+01 2.41849384e+01 2.83545818e+01 3.28472252e+01 3.76459084e+01 4.28166580e+01 4.83043060e+01 5.40414314e+01 6.01732178e+01 6.67019882e+01 7.34884033e+01 8.04839325e+01 8.79476242e+01 9.57764359e+01 1.03744255e+02 1.12118622e+02 1.20836487e+02 1.29776978e+02 1.39184250e+02 1.48756226e+02 1.58656738e+02 1.69044693e+02 1.79393417e+02 1.90450668e+02 2.01600159e+02 2.13105560e+02 2.24983551e+02 2.36887939e+02 2.49354935e+02 2.61931305e+02 2.74923676e+02 2.88465149e+02 3.01860199e+02 3.15467957e+02 3.29756500e+02 3.44222321e+02 3.58676086e+02 3.73812408e+02 3.89157623e+02 4.04680573e+02 4.20740479e+02 4.36519867e+02 4.52985565e+02 4.69495667e+02 4.86318848e+02 5.02427948e+02 5.20948730e+02 5.39442505e+02 5.56379333e+02 5.74001038e+02 5.93168335e+02 6.10780884e+02 6.29982910e+02 6.49978394e+02 6.68193848e+02 6.87231873e+02 7.08219055e+02 7.29152161e+02 7.50562317e+02 7.68401794e+02 7.88815063e+02 8.10689148e+02 8.32182251e+02 8.52379456e+02 8.72910950e+02 8.96678345e+02 9.17865784e+02 9.41647766e+02 9.63535767e+02 9.82590637e+02 1.00750641e+03 1.03337097e+03 1.05417566e+03 1.07588354e+03 1.09980078e+03 1.12624902e+03 1.15134937e+03 1.17069690e+03 1.19724487e+03 1.21786487e+03 1.24217700e+03 1.26904541e+03 1.29246497e+03 1.32117761e+03 1.34354370e+03 1.36693835e+03 1.39228674e+03 1.42004163e+03 1.44482312e+03 1.46970935e+03 1.49596484e+03 1.51779028e+03 1.54240356e+03 1.57411499e+03 1.60209949e+03 1.62467590e+03 1.65168213e+03 1.68019177e+03 1.70031897e+03 1.73087769e+03 1.75942566e+03 1.78296838e+03 1.81342432e+03 1.83334705e+03 1.86010681e+03 1.89363220e+03 1.91725879e+03 1.94706628e+03 1.96871277e+03 1.99650244e+03 2.02930432e+03 2.05667480e+03 2.07842651e+03 2.10669189e+03 2.13787280e+03 2.15834644e+03 2.18314648e+03 2.21980444e+03 2.24342407e+03 2.26789453e+03 2.29797632e+03 2.32895850e+03 2.35391992e+03 2.37670776e+03 2.40598022e+03 2.43250269e+03 2.45609741e+03 2.48604688e+03 2.51495728e+03 2.54418506e+03 2.56537354e+03 2.59335400e+03 2.62563232e+03 2.64750024e+03 2.67564014e+03 2.69469897e+03 2.72487012e+03 2.76334009e+03 2.78467554e+03 2.80520215e+03 2.83696460e+03 2.85821582e+03 2.88092700e+03 2.91344385e+03 2.94393872e+03 2.96047266e+03 2.98162646e+03 3.01252441e+03 3.04148730e+03 3.06132422e+03 3.08844214e+03 3.11510181e+03 3.13193774e+03 3.16792114e+03 3.18969824e+03 3.21665234e+03 3.23840869e+03 3.25720728e+03 3.28685815e+03 3.30924634e+03 3.33298535e+03 3.34919946e+03 3.37283569e+03 3.40444946e+03 3.42581128e+03 3.44646875e+03 3.47379980e+03 3.49451514e+03 3.50703467e+03 3.53543799e+03 3.56289673e+03 3.58153589e+03 3.59764648e+03 3.61552319e+03 3.64218237e+03 3.66776172e+03 3.68058936e+03 3.70561914e+03 3.72540503e+03 3.74105566e+03 3.75202417e+03 3.77798242e+03 3.80665503e+03 3.82441943e+03 3.84279150e+03 3.85287646e+03 3.87425952e+03 3.89716968e+03 3.91129297e+03 3.92169336e+03 3.94310815e+03 3.95691284e+03 3.98171533e+03 3.99988843e+03 4.01048267e+03 4.02525000e+03 4.04145947e+03 4.05794214e+03 4.07155859e+03 4.08632324e+03 4.10227197e+03 4.11756152e+03 4.12744824e+03 4.13988867e+03 4.15534619e+03 4.17216211e+03 4.18227441e+03 8.17934766e+03 5.84625635e+03 1.01332607e+04 6.34297461e+03 6.36769385e+03 1.01720732e+04 6.39264697e+03 1.02625420e+04 6.42958301e+03 6.44425928e+03 6.45177637e+03 5.87172412e+03 6.47914502e+03 4.33354150e+03 5.67350830e+03 4.34563379e+03 4.34933496e+03 4.35996289e+03 4.36706543e+03 4.36973584e+03 4.37423975e+03 4.38350781e+03 4.38978857e+03 4.39257471e+03 4.39798096e+03 4.40294531e+03 4.40667529e+03 4.41149072e+03 4.41427783e+03 4.41800684e+03 4.42126025e+03 4.42283447e+03 4.42502539e+03 4.42609912e+03 4.42798145e+03 4.42970410e+03 4.43015967e+03 4.43069775e+03 4.43089746e+03 4.43075586e+03 4.42999805e+03 4.42946338e+03 4.42789111e+03 4.42607471e+03 4.42474707e+03 4.42282861e+03 4.42069922e+03 4.41741602e+03 4.41448877e+03 4.41098828e+03 4.40634033e+03 4.40374609e+03 4.39797070e+03 4.39127588e+03 4.38817871e+03 4.38313379e+03 4.37642773e+03 4.37036768e+03 4.36333301e+03 4.35874756e+03 4.35046484e+03 4.34448291e+03 4.33763867e+03 4.32619385e+03 4.31857959e+03 4.31241748e+03 4.30017139e+03 4.28895996e+03 4.28058057e+03 4.27313672e+03 4.26436621e+03 4.25018701e+03 4.23906445e+03 4.22889551e+03 4.21922168e+03 4.20665625e+03 4.19438428e+03 4.18308691e+03 4.16839355e+03 4.15554785e+03 4.14232178e+03 4.12936865e+03 4.11760693e+03 4.10169287e+03 4.08757251e+03 4.07032251e+03 4.05594995e+03 4.04375415e+03 4.02689697e+03 4.00756006e+03 3.99533105e+03 3.97739062e+03 3.96225854e+03 3.94669116e+03 3.92245288e+03 3.91162891e+03 3.89670483e+03 3.87242700e+03 3.85445459e+03 3.83810693e+03 3.81922412e+03 3.79968433e+03 3.78178198e+03 3.76124658e+03 3.73550391e+03 3.71884521e+03 3.70717407e+03 3.69221289e+03 3.65680688e+03 3.63340210e+03 3.62221948e+03 3.60333643e+03 3.57650146e+03 3.54837598e+03 3.53424634e+03 3.51344556e+03 3.49876392e+03 3.47380371e+03 3.43728857e+03 3.41418774e+03 3.40394678e+03 3.37844189e+03 3.35548364e+03 3.33208032e+03 3.31211401e+03 3.29354468e+03 3.26113135e+03 3.24104346e+03 3.20665381e+03 3.17803003e+03 3.16581079e+03 3.13665259e+03 3.11085059e+03 3.08927026e+03 3.06009399e+03 3.03950293e+03 3.01228174e+03 2.99036426e+03 2.96111328e+03 2.92943457e+03 2.90684521e+03 2.88122729e+03 2.85882080e+03 2.83125391e+03 2.80230396e+03 2.77767261e+03 2.76129517e+03 2.72167139e+03 2.69756201e+03 2.67614697e+03 2.65156274e+03 2.62660645e+03 2.59071997e+03 2.56001172e+03 2.54376807e+03 2.51306274e+03 2.48715088e+03 2.45701074e+03 2.42951270e+03 2.40770020e+03 2.37903784e+03 2.34969751e+03 2.32063354e+03 2.30231006e+03 2.26741870e+03 2.23966943e+03 2.22049976e+03 2.18467065e+03 2.15877637e+03 2.13396313e+03 2.10875317e+03 2.08018823e+03 2.05177661e+03 2.02639136e+03 2.00307629e+03 1.96793604e+03 1.94106958e+03 1.91737524e+03 1.88685657e+03 1.86000293e+03 1.83955725e+03 1.81151770e+03 1.77828931e+03 1.75459082e+03 1.72615369e+03 1.69998865e+03 1.68253552e+03 1.65270618e+03 1.62350098e+03 2.08875952e+03 2.14421118e+03 2.30904492e+03 2.27582788e+03 2.24410547e+03 2.20225537e+03 1.97288232e+03 2.82675293e+03 1.89866382e+03 3.23336938e+03 4.15582227e+03 14340757. -28238276. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -111221776. 1.03778730e+04 1.95794360e+03 8.94837341e+02 1.13313110e+03 8.51831238e+02 8.30965881e+02 8.08680725e+02 7.88979736e+02 7.68480652e+02 7.47365112e+02 7.28193481e+02 7.07884033e+02 6.87583313e+02 6.66012146e+02 6.48100403e+02 6.30043884e+02 6.10828613e+02 5.92633057e+02 5.73119141e+02 5.55309570e+02 5.38023315e+02 5.19932007e+02 5.02374725e+02 4.85570587e+02 4.68437195e+02 4.52599792e+02 4.36065155e+02 4.19638489e+02 4.04040894e+02 3.87916656e+02 3.72902039e+02 3.58477753e+02 3.43856262e+02 3.28820831e+02 3.14792480e+02 3.01357330e+02 2.87749420e+02 2.74386322e+02 2.61498810e+02 2.48761780e+02 2.36264725e+02 2.24256973e+02 2.12652832e+02 2.01246964e+02 1.89872192e+02 1.79068115e+02 1.68538849e+02 1.58167038e+02 1.48352951e+02 1.38798111e+02 1.29337067e+02 1.20463814e+02 1.11734505e+02 1.03374840e+02 9.54117279e+01 8.75633545e+01 8.01750717e+01 7.31930542e+01 6.63945847e+01 5.99257698e+01 5.37895508e+01 4.80274086e+01 4.25907593e+01 3.74401627e+01 1.39713593e+02 6161644. 0. 0. 0. 0. 0. 19860368. 19860368. 19860368. 0. 0. 0. 0. 0. 0. -62709180. 19002828. 1.30415812e+01 2.02347183e+01 3.86390650e+06 -17726338. 0. 0. 2.01049450e+06 25902990. 3.21859351e+03 8.94355850e+01 7.99006729e+01 5.65080185e+01 6.42349854e+01 6.61287079e+01 8.10979691e+01 6.03057251e+01 1.00088181e+02 1.01251762e+02 1.20714317e+02 1.31960541e+02 1.43661713e+02 1.55678452e+02 1.68148483e+02 1.81163849e+02 1.94547958e+02 2.08735626e+02 2.23326324e+02 2.37890610e+02 2.53446686e+02 2.69337189e+02 2.85719971e+02 3.02296051e+02 2.92382233e+02 3.37559601e+02 3.26926239e+02 3.73586365e+02 3.93052826e+02 4.12939758e+02 4.32013550e+02 4.52259308e+02 4.74173218e+02 4.94716461e+02 5.15910339e+02 5.37302612e+02 5.59915405e+02 5.83982178e+02 6.07690308e+02 6.30373230e+02 6.54119202e+02 6.78937195e+02 7.04420471e+02 6.64362732e+02 6.53297058e+02 5.21220520e+02 5.38572327e+02 5.56502625e+02 5.75423523e+02 5.93441711e+02 6.11967529e+02 6.30662720e+02 6.50448608e+02 6.70380310e+02 6.88887451e+02 7.07170105e+02 7.29304749e+02 7.51112854e+02 1.00050824e+03 1.08756567e+03 1.21727283e+03 1.99922522e+03 2.57644971e+03 -6.37295812e+05 30728158. 0. -36641328. -36641328. -36641328. 0. 0. -253570160. -253570160. -253570160. 0. 0. 0. 0. 0. 20699484. 1.55547021e+04 3.16185986e+03 1.82809705e+03 1.75915076e+03 1.37065564e+03 1.39437683e+03 1.41929980e+03 1.44592517e+03 1.90797791e+03 2.05336279e+03 2.28690063e+03 2.31836230e+03 2.35564990e+03 2.40232544e+03 2.43310767e+03 2.25532568e+03 2.18571802e+03 1.70588232e+03 1.73170276e+03 1.75850183e+03 1.78732825e+03 1.81491919e+03 1.83550989e+03 1.86357666e+03 1.89187549e+03 1.91832495e+03 1.94591028e+03 1.97855225e+03 1.99895276e+03 2.02579114e+03 2.05755957e+03 2.07899658e+03 2.10564478e+03 2.13627661e+03 2.15521558e+03 2.19390405e+03 2.21776074e+03 2.24296899e+03 2.26919189e+03 2.30212305e+03 2.32822070e+03 2.35555273e+03 2.37304761e+03 2.40890039e+03 2.43785229e+03 2.46036426e+03 2.48680884e+03 2.51500537e+03 2.54500220e+03 2.56989722e+03 2.59568848e+03 2.62498584e+03 2.65071484e+03 2.67662012e+03 2.69847559e+03 2.73212988e+03 2.76132739e+03 2.78281396e+03 2.81076758e+03 2.83686987e+03 2.85859229e+03 2.88882300e+03 2.90823218e+03 2.94026294e+03 2.97222046e+03 2.98850391e+03 3.01252148e+03 3.04479932e+03 3.06869458e+03 3.08769043e+03 3.11504761e+03 3.12949805e+03 3.16523682e+03 3.19655908e+03 3.21724316e+03 3.24011182e+03 3.25976978e+03 3.28001733e+03 3.30773511e+03 3.33055103e+03 3.35138843e+03 3.37911816e+03 3.40341431e+03 3.42476953e+03 3.45103198e+03 3.47193164e+03 3.49427490e+03 3.51445850e+03 3.54115723e+03 3.56497925e+03 3.57769995e+03 3.59875244e+03 3.62122046e+03 3.64589014e+03 3.67276611e+03 3.68524292e+03 3.70217432e+03 3.72846533e+03 3.75032520e+03 3.76359424e+03 3.78155688e+03 3.80855737e+03 3.82323047e+03 3.84234741e+03 3.86413916e+03 3.87530029e+03 3.89222046e+03 3.91603271e+03 3.93173608e+03 3.94568457e+03 3.96746143e+03 3.98475562e+03 3.99483960e+03 4.01117285e+03 4.03363306e+03 4.04611816e+03 4.05618237e+03 4.07733496e+03 4.09133862e+03 4.10229102e+03 4.11635205e+03 4.13472461e+03 4.15238037e+03 4.15841748e+03 4.16795947e+03 4.18538281e+03 4.20041211e+03 4.20887500e+03 4.22365674e+03 4.23607715e+03 4.23852051e+03 4.25199902e+03 4.26920361e+03 4.27743408e+03 4.28364697e+03 4.29552979e+03 4.30604785e+03 4.31629297e+03 4.32139844e+03 4.32904004e+03 4.34018115e+03 4.34532959e+03 4.35505762e+03 4.36131494e+03 4.36585254e+03 4.37529443e+03 4.37827734e+03 4.38395215e+03 4.39195264e+03 4.39694092e+03 4.40319580e+03 4.40641748e+03 4.40791846e+03 4.41450635e+03 4.41751318e+03 4.42036182e+03 4.42455566e+03 4.42539160e+03 4.42819824e+03 4.42902930e+03 4.43089600e+03 4.43266602e+03 4.43299414e+03 4.43375586e+03 4.43388232e+03 4.43376611e+03 4.43303857e+03 4.43221094e+03 4.43106104e+03 4.42920117e+03 4.42727393e+03 4.42634229e+03 4.42366748e+03 4.41963818e+03 4.41703516e+03 4.41413281e+03 4.40995801e+03 4.40521289e+03 4.40088818e+03 4.39569580e+03 4.39118066e+03 4.38605127e+03 4.37984668e+03 5.68693994e+03 6.06118994e+03 5.97866064e+03 5.65024951e+03 4.34629883e+03 4.34065186e+03 5.32631641e+03 5.33434229e+03 6.46993164e+03 6.46063379e+03 6.44477344e+03 6.42462744e+03 6.41559619e+03 6.40145850e+03 6.38222266e+03 6.37254004e+03 6.35771973e+03 6.33587793e+03 6.31052246e+03 6.28923633e+03 6.27775000e+03 6.26790527e+03 6.24134473e+03 6.21415674e+03 5.11749268e+03 6.17780078e+03 5.06102539e+03 6.13716504e+03 5.04122852e+03 5.00433496e+03 4.04702344e+03 4.03362231e+03 4.01158911e+03 3.99406421e+03 3.97972559e+03 3.96558667e+03 3.94493726e+03 3.92909741e+03 3.91571216e+03 3.89543481e+03 3.87607129e+03 3.86191431e+03 3.84032422e+03 3.81461035e+03 3.80027563e+03 3.78820898e+03 3.76591406e+03 3.74241943e+03 3.72784033e+03 3.70521094e+03 3.69432471e+03 3.66436719e+03 3.63584595e+03 3.62638281e+03 3.60267676e+03 3.57285669e+03 3.55371240e+03 3.53377783e+03 3.51654663e+03 3.49980908e+03 3.46929126e+03 3.44108789e+03 3.42330200e+03 3.40552173e+03 3.38301147e+03 3.35147949e+03 3.33206396e+03 3.31380908e+03 3.29275049e+03 3.26504077e+03 3.23444141e+03 3.20657788e+03 3.18850464e+03 3.16788354e+03 3.13212573e+03 3.11561230e+03 3.08794043e+03 3.06519263e+03 3.04371191e+03 3.01329858e+03 2.99347949e+03 2.95828516e+03 2.93668726e+03 2.91498535e+03 2.88368970e+03 2.85534595e+03 2.82944971e+03 2.80819556e+03 2.78691211e+03 2.76031665e+03 2.72367993e+03 2.70175732e+03 2.67877319e+03 2.64812695e+03 2.62483374e+03 2.59122632e+03 2.56577734e+03 2.54672803e+03 2.51272388e+03 2.49011597e+03 2.46257202e+03 2.42890552e+03 2.40501074e+03 2.38139185e+03 2.34614014e+03 2.32484399e+03 2.30334082e+03 2.26581445e+03 2.24682471e+03 2.21883862e+03 2.18205688e+03 2.16127881e+03 2.13765527e+03 2.11242896e+03 2.08213599e+03 2.04706787e+03 2.02720959e+03 2.00233533e+03 1.97071436e+03 1.94471155e+03 1.91590137e+03 1.89359216e+03 1.86838196e+03 1.83652258e+03 1.81209558e+03 1.78455432e+03 1.76030347e+03 1.72959058e+03 1.70503345e+03 1.67894031e+03 1.65074756e+03 1.62525024e+03 1.59923657e+03 1.57080896e+03 1.54708228e+03 1.51953613e+03 1.49636133e+03 1.46683179e+03 1.44194458e+03 1.42029419e+03 1.39672314e+03 1.36751868e+03 1.34218628e+03 1.31788879e+03 1.28769824e+03 1.26788489e+03 1.24649890e+03 1.21864404e+03 1.19597644e+03 1.17179858e+03 1.14701978e+03 1.12297083e+03 1.10002576e+03 1.07503625e+03 1.05352600e+03 1.03020178e+03 1.00693628e+03 9.84961853e+02 9.62090332e+02 9.40344238e+02 9.16818359e+02 8.95595032e+02 8.76674377e+02 8.53232849e+02 8.29951965e+02 8.09123474e+02 7.89476501e+02 7.69040710e+02 7.47825745e+02 7.27546021e+02 7.07042786e+02 6.88194153e+02 6.68091614e+02 6.48083435e+02 6.30501648e+02 6.11102234e+02 5.92403442e+02 5.74423035e+02 5.54984741e+02 5.37972839e+02 5.20660095e+02 5.02804565e+02 4.85540649e+02 4.69074280e+02 4.52723358e+02 4.35840454e+02 4.19187164e+02 4.04345947e+02 3.88618683e+02 3.72962067e+02 3.58874542e+02 3.43896271e+02 3.28990295e+02 3.15172455e+02 3.01406860e+02 2.88088989e+02 2.74549530e+02 2.61433594e+02 2.48906067e+02 2.36618622e+02 2.24451218e+02 2.12838486e+02 2.01531021e+02 1.89909698e+02 1.79084763e+02 1.68784363e+02 1.58424438e+02 1.48410355e+02 1.38845566e+02 1.29573212e+02 1.20637596e+02 1.11876915e+02 1.03418205e+02 9.54450226e+01 8.76951675e+01 8.03105621e+01 7.32630005e+01 6.64379425e+01 6.00089226e+01 5.38890610e+01 4.81011620e+01 4.26543884e+01 3.75205078e+01 3.27156448e+01 2.82290382e+01 2.40798359e+01 2.02704353e+01 1.67776909e+01 1.36249638e+01 1.08016987e+01 8.31040573e+00 6.15578508e+00 4.32840538e+00 2.83433223e+00 1.67603445e+00 8.51112843e-01 3.59360963e-01 2.01589018e-01 3.77722830e-01 8.87710810e-01 1.73128223e+00 2.90838003e+00 4.41829586e+00 6.26139498e+00 8.44092178e+00 1.09527979e+01 1.37881527e+01 1.69646931e+01 2.04760628e+01 2.43075600e+01 2.84636745e+01 3.29541588e+01 3.77769661e+01 4.29411659e+01 4.84480019e+01 5.42115173e+01 6.03273506e+01 6.68437881e+01 7.36086960e+01 8.06660538e+01 8.81161346e+01 9.59214401e+01 1.03963051e+02 1.12306000e+02 1.20930740e+02 1.29964798e+02 1.39437683e+02 1.49105591e+02 1.58931183e+02 1.69132370e+02 1.79779205e+02 1.90904404e+02 2.01849701e+02 2.13325607e+02 2.25381027e+02 2.37013901e+02 2.49400040e+02 2.62389740e+02 2.75344299e+02 2.88508850e+02 3.02085175e+02 3.15908813e+02 3.29934692e+02 3.44637909e+02 3.59054962e+02 3.74367218e+02 3.89898041e+02 4.05442108e+02 4.20490051e+02 4.36630249e+02 4.53072876e+02 4.69643524e+02 4.86837799e+02 5.03483276e+02 5.21582825e+02 5.39203613e+02 5.56812988e+02 5.75258362e+02 5.93286011e+02 6.11812439e+02 6.30521240e+02 6.50629211e+02 6.69480835e+02 6.88179504e+02 7.09038635e+02 7.28845520e+02 7.50212463e+02 7.69664124e+02 7.88753418e+02 8.12319519e+02 8.33081787e+02 8.51688843e+02 8.73554871e+02 8.97544678e+02 9.18586060e+02 9.42948181e+02 9.63266479e+02 9.84035889e+02 1.00864258e+03 1.03378723e+03 1.05540088e+03 1.07652710e+03 1.10122876e+03 1.12746045e+03 1.15086426e+03 1.17378748e+03 1.19722681e+03 1.21793140e+03 1.24491028e+03 1.26891516e+03 1.29134167e+03 1.32076709e+03 1.34286145e+03 1.36846643e+03 1.39511829e+03 1.42053516e+03 1.44663660e+03 1.46792261e+03 1.49899292e+03 1.52150952e+03 1.54647607e+03 1.57335950e+03 1.59867712e+03 1.62671387e+03 1.65555127e+03 1.68233594e+03 1.70206116e+03 1.73096655e+03 1.76402039e+03 1.78508154e+03 1.81144836e+03 1.83576379e+03 1.86479980e+03 1.89517163e+03 1.91767908e+03 1.94673438e+03 1.97573840e+03 2.00058777e+03 2.03039136e+03 2.05773389e+03 2.07729028e+03 2.10542261e+03 2.14050928e+03 2.15712964e+03 2.19159375e+03 2.21813159e+03 2.23859448e+03 2.27443530e+03 2.30331177e+03 2.33430542e+03 2.35449146e+03 2.37929712e+03 2.40662817e+03 2.43894971e+03 2.46150684e+03 2.48959424e+03 2.51550195e+03 2.54841943e+03 2.57064331e+03 2.59259106e+03 2.62753809e+03 2.64785938e+03 2.67942944e+03 2.70134692e+03 2.72976538e+03 2.75732593e+03 2.78378345e+03 2.80867065e+03 2.83257275e+03 2.86274438e+03 2.88911597e+03 2.91549927e+03 2.94249390e+03 2.96248926e+03 2.98690601e+03 3.01962476e+03 3.04804175e+03 3.06438281e+03 3.08932715e+03 3.11656152e+03 3.13436426e+03 3.16840186e+03 3.19343359e+03 3.21574902e+03 3.23961230e+03 3.26113428e+03 3.28556616e+03 3.31237915e+03 3.33112598e+03 3.35252612e+03 3.37933008e+03 3.40486841e+03 3.42694067e+03 3.44643335e+03 3.46914624e+03 3.49841870e+03 3.51337402e+03 3.53816895e+03 3.56818604e+03 3.58314233e+03 3.59511938e+03 3.61836182e+03 3.64723511e+03 3.66747729e+03 3.68498584e+03 3.70372607e+03 3.72547314e+03 3.75155151e+03 3.76392822e+03 3.78063477e+03 3.80737012e+03 3.82768652e+03 3.84152515e+03 3.86061401e+03 3.87656128e+03 3.89447510e+03 3.91651855e+03 3.93076636e+03 3.94642969e+03 3.96517505e+03 3.98417090e+03 3.99871655e+03 4.01043774e+03 4.02911133e+03 4.04207764e+03 4.05881958e+03 4.07859888e+03 4.09235596e+03 4.10465430e+03 4.11773242e+03 4.13143359e+03 4.14690918e+03 4.15864600e+03 4.17152295e+03 4.18724512e+03 8.14598633e+03 5.22710107e+03 1.01630605e+04 6.35435791e+03 6.36966943e+03 1.02218457e+04 6.40312354e+03 1.02927598e+04 6.42625537e+03 6.44690625e+03 6.46148828e+03 5.33902783e+03 6.48538477e+03 4.33264404e+03 5.35091211e+03 4.34722803e+03 4.35299414e+03 4.36304980e+03 4.37106299e+03 4.37307080e+03 4.37831006e+03 4.38556885e+03 4.39291797e+03 4.39584473e+03 4.40224854e+03 4.40631055e+03 4.41550537e+03 4.41414551e+03 4.41694971e+03 4.42190479e+03 4.42425146e+03 4.42543994e+03 4.42840918e+03 4.42900146e+03 4.43098779e+03 4.43288086e+03 4.43315918e+03 4.43373779e+03 4.43400684e+03 4.43378320e+03 4.43309180e+03 4.43239746e+03 4.43099365e+03 4.42914893e+03 4.42732812e+03 4.42628857e+03 4.42365820e+03 4.42000488e+03 4.41721240e+03 4.41394824e+03 4.41126611e+03 4.40623047e+03 4.39960303e+03 4.39489160e+03 4.39110156e+03 4.38699561e+03 4.38041455e+03 4.37265869e+03 4.36631641e+03 4.36085303e+03 4.35333984e+03 4.34711230e+03 4.33963623e+03 4.33043018e+03 4.32130566e+03 4.31208008e+03 4.30372998e+03 4.29266064e+03 4.28472461e+03 4.27693848e+03 4.26535498e+03 4.25375879e+03 4.24370361e+03 4.23274756e+03 4.22155469e+03 4.21051807e+03 4.19313428e+03 4.18242090e+03 4.17001123e+03 4.15866650e+03 4.14541553e+03 4.13305859e+03 4.11867725e+03 4.10187451e+03 4.09241211e+03 4.07422803e+03 4.05732666e+03 4.04751050e+03 4.03409985e+03 4.01110156e+03 3.99187866e+03 3.97853687e+03 3.96692090e+03 3.94976611e+03 3.92972339e+03 3.91385034e+03 3.89578418e+03 3.87829785e+03 3.86188525e+03 3.83727734e+03 3.82096777e+03 3.80141333e+03 3.78664404e+03 3.76787915e+03 3.74276025e+03 3.72107056e+03 3.70771118e+03 3.69613550e+03 3.66160229e+03 3.63415259e+03 3.62881055e+03 3.60732031e+03 3.57292627e+03 3.55172925e+03 3.53509521e+03 3.51608911e+03 3.50296851e+03 3.47191333e+03 3.44083960e+03 3.42054517e+03 3.40474976e+03 3.37874512e+03 3.35414209e+03 3.33764160e+03 3.31670654e+03 3.29092920e+03 3.26066357e+03 3.23930151e+03 3.21020654e+03 3.18465918e+03 3.16234058e+03 3.13497046e+03 3.11812402e+03 3.08960132e+03 3.06519873e+03 3.04515430e+03 3.01137109e+03 2.98970264e+03 2.96232397e+03 2.93581567e+03 2.91390771e+03 2.88583374e+03 2.85683740e+03 2.83070996e+03 2.80840088e+03 2.78536450e+03 2.76007007e+03 2.72122559e+03 2.69815601e+03 2.67847803e+03 2.64902905e+03 2.62282642e+03 2.58990625e+03 2.56602832e+03 2.54313916e+03 2.51586938e+03 2.48775781e+03 2.46156055e+03 2.43117383e+03 2.40447437e+03 2.38501221e+03 2.35036401e+03 2.32471313e+03 2.30209546e+03 2.26460229e+03 2.24335449e+03 2.21866235e+03 2.18545874e+03 2.16027832e+03 2.13766553e+03 2.11216699e+03 2.07653052e+03 2.05154175e+03 2.03039282e+03 2.00326965e+03 1.97600293e+03 1.94728784e+03 1.94412769e+03 2.45704492e+03 2.55172266e+03 2.75617627e+03 2.71087891e+03 2.67018408e+03 2.62974561e+03 2.59007935e+03 2.55246851e+03 2.52370532e+03 2.48009546e+03 2.19393433e+03 2.53000977e+03 1.94889404e+03 2.31625366e+03 2.27734985e+03 2.24777173e+03 2.20761157e+03 1.78220276e+03 1.74697754e+03 1.39478027e+03 1.77328870e+03 2.47055737e+03 3.05867261e+03 -12775147. -294347136. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -11114503. 1.10133486e+04 1.34243201e+03 2.09170947e+03 1.27731921e+03 1.24467029e+03 1.21367297e+03 1.07918396e+03 1.00040735e+03 7.47507324e+02 7.27597229e+02 7.08414551e+02 6.88778625e+02 6.67793945e+02 6.48766235e+02 6.30051514e+02 6.11044373e+02 5.91951477e+02 5.73984924e+02 5.55981689e+02 5.38431702e+02 5.20208557e+02 5.03146515e+02 4.86240051e+02 4.68442505e+02 4.52698090e+02 4.36005371e+02 4.19419739e+02 4.04433105e+02 3.88330292e+02 3.73167450e+02 3.58998566e+02 3.43991089e+02 3.28981506e+02 3.15030060e+02 3.01420807e+02 2.88147217e+02 2.74522858e+02 2.61370667e+02 2.49107468e+02 2.36575378e+02 2.24290848e+02 2.12832901e+02 2.01552353e+02 1.89985718e+02 1.79116714e+02 1.68781738e+02 1.58318680e+02 1.48387131e+02 1.38827484e+02 1.29495132e+02 1.20639473e+02 1.11870514e+02 1.03429665e+02 9.54841843e+01 8.76682205e+01 8.02710419e+01 9.49521790e+01 9.07582703e+01 8.98118591e+01 8.05912628e+01 7.19174194e+01 6.37854919e+01 5.60917664e+01 2.09256851e+02 4635721. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 167394016. 167394016. 0. 0. -62709180. 19002828. 1.30415812e+01 2.02347183e+01 3.86390650e+06 -17726338. 0. 0. 0. 0. 0. 6787545. 4.33280060e+02 1.19085220e+02 2.95851906e+05 1.35169815e+02 1.62970123e+02 9.10728302e+01 2.01379089e+02 2.38428726e+02 2.26882406e+05 5.07661523e+04 7.10055250e+05 1717054. 5.27628672e+04 6784100. 3.35428625e+06 4671694. 1.48542219e+05 9.31237312e+05 9.81923672e+04 7.76303984e+04 5.62897644e+02 6.04435242e+02 3.53912994e+02 6.76233459e+02 7.37222290e+02 2.02995750e+05 -5030195. 6.82042312e+05 19080620. 11166871. 1.33953555e+04 1.62232295e+04 1.53159938e+05 1.22741725e+06 1.49905261e+03 2.23917051e+04 2.43836450e+03 1.43389538e+06 -6858559. 2.73652969e+05 2.63978825e+06 1.42263550e+03 1.19565894e+03 7.83289368e+02 8.09412537e+02 8.35809875e+02 7.83698669e+02 7.66522888e+02 6.13904419e+02 6.33056213e+02 6.52583496e+02 8.78662415e+02 9.60080444e+02 1.06427197e+03 1.09742432e+03 1.12606750e+03 1.87257251e+03 2.46132544e+03 3.04972719e+05 8.22009550e+06 55700324. 0. 0. 0. -36641328. -36641328. -36641328. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9745361. 7.27453223e+03 1.70889905e+03 1.32352063e+03 1.34942334e+03 1.37452734e+03 1.39839978e+03 1.42519385e+03 1.44965430e+03 1.81224878e+03 1.85265320e+03 2.29403247e+03 2.32877905e+03 2.36950854e+03 2.41120361e+03 2.44907715e+03 2.04910938e+03 2.07658740e+03 1.71094910e+03 1.73871887e+03 1.76471533e+03 1.78962524e+03 1.81605664e+03 1.84448096e+03 1.87054663e+03 1.90005884e+03 1.92709509e+03 1.95687024e+03 1.97965686e+03 2.00368774e+03 2.03208105e+03 2.06501367e+03 2.08444751e+03 2.11542725e+03 2.14475562e+03 2.16953394e+03 2.19558276e+03 2.22705737e+03 2.25095776e+03 2.28259302e+03 2.30612158e+03 2.32733252e+03 2.35933057e+03 2.39043066e+03 2.41715649e+03 2.44610791e+03 2.46849927e+03 2.49538013e+03 2.52635107e+03 2.54816797e+03 2.57554028e+03 2.61131006e+03 2.63705322e+03 2.65579443e+03 2.68283447e+03 2.70903833e+03 2.73861987e+03 2.76731909e+03 2.79118677e+03 2.81810742e+03 2.84598267e+03 2.86615283e+03 2.89855762e+03 2.92364282e+03 2.94789209e+03 2.97063257e+03 2.99721948e+03 3.02465820e+03 3.05670215e+03 3.07397510e+03 3.09805737e+03 3.12629150e+03 3.14822241e+03 3.17646191e+03 3.20768384e+03 3.22284375e+03 3.25029248e+03 3.27386719e+03 3.29221191e+03 3.32388159e+03 3.34260303e+03 3.36250244e+03 3.39744604e+03 3.41355420e+03 3.43504272e+03 3.46299976e+03 3.48068701e+03 3.50898267e+03 3.52645728e+03 3.55201099e+03 3.57116089e+03 3.59106641e+03 3.61318750e+03 3.63602417e+03 3.66091284e+03 3.67742188e+03 3.69746851e+03 3.71442969e+03 3.74387866e+03 3.76376440e+03 3.77268384e+03 3.79606934e+03 3.81639307e+03 3.83237305e+03 3.85537158e+03 3.87548755e+03 3.88895898e+03 3.90975293e+03 3.92925488e+03 3.94431982e+03 3.95894165e+03 3.97759180e+03 3.99869897e+03 4.00714233e+03 4.02213086e+03 4.04860083e+03 4.05914160e+03 4.07146729e+03 4.08879663e+03 4.10568311e+03 4.11953174e+03 4.13033740e+03 4.14737451e+03 4.16362305e+03 4.17277100e+03 4.18312744e+03 4.19816992e+03 4.21093115e+03 4.22365576e+03 4.23919043e+03 4.25046338e+03 4.25261865e+03 4.26559131e+03 4.28085889e+03 4.29218994e+03 4.29835352e+03 4.31121729e+03 4.32107373e+03 4.32754492e+03 4.33682129e+03 4.34382764e+03 4.35153906e+03 4.35983740e+03 4.36937744e+03 4.37492041e+03 4.38026514e+03 4.39091943e+03 4.39568604e+03 4.39830713e+03 4.40479248e+03 4.41266602e+03 4.41742676e+03 4.42057031e+03 4.42276758e+03 4.42826074e+03 4.43234033e+03 4.43484717e+03 4.43832275e+03 4.44030762e+03 4.44348682e+03 4.44372119e+03 4.44555859e+03 4.44743848e+03 4.44771924e+03 4.44844775e+03 4.44860010e+03 4.44855273e+03 4.44766797e+03 4.44680420e+03 4.44618359e+03 4.44416602e+03 4.44173682e+03 4.44105127e+03 4.43850488e+03 4.43379736e+03 4.43135205e+03 4.42881689e+03 4.42424316e+03 4.41857324e+03 4.41629541e+03 4.41251709e+03 4.40494336e+03 4.39903857e+03 4.39386035e+03 5.40208643e+03 5.41420557e+03 5.40533447e+03 5.38066113e+03 4.36113867e+03 4.35418262e+03 5.66922412e+03 5.98785205e+03 6.50533984e+03 6.49428027e+03 6.47980176e+03 1.02928711e+04 1.28328506e+04 1.29271494e+04 1.01552129e+04 6.39959473e+03 6.39141016e+03 6.36811719e+03 6.34689795e+03 6.32638916e+03 6.30887695e+03 6.29447656e+03 6.27265186e+03 6.25176318e+03 5.67139404e+03 6.21238135e+03 5.65917139e+03 6.16178809e+03 5.61516309e+03 5.28418555e+03 4.06033960e+03 4.04552051e+03 4.02453198e+03 4.00868677e+03 3.99385986e+03 3.97425781e+03 3.95932202e+03 3.94587476e+03 3.92838184e+03 3.90994092e+03 3.88516724e+03 3.87407471e+03 3.85292114e+03 3.83069971e+03 3.81709570e+03 3.79683032e+03 3.77911157e+03 3.75529297e+03 3.73499365e+03 3.72279028e+03 3.70236499e+03 3.68143066e+03 3.65200464e+03 3.63238013e+03 3.61801172e+03 3.58621094e+03 3.56816772e+03 3.54725000e+03 3.52304810e+03 3.51117480e+03 3.48128711e+03 3.45659473e+03 3.43439185e+03 3.41886182e+03 3.39386255e+03 3.36628003e+03 3.34579272e+03 3.31833740e+03 3.30184839e+03 3.27537646e+03 3.23936255e+03 3.21147144e+03 3.19933325e+03 3.17465918e+03 3.14258057e+03 3.12498267e+03 3.10123682e+03 3.08058032e+03 3.05268066e+03 3.02356885e+03 3.00396558e+03 2.97131348e+03 2.94554736e+03 2.91662891e+03 2.89030664e+03 2.86928516e+03 2.83809180e+03 2.81449194e+03 2.79190503e+03 2.76006763e+03 2.73802197e+03 2.71443774e+03 2.69075024e+03 2.65642798e+03 2.62941382e+03 2.60066943e+03 2.57377783e+03 2.55205835e+03 2.52724438e+03 2.50364160e+03 2.47106836e+03 2.43940552e+03 2.41532764e+03 2.38978857e+03 2.35659302e+03 2.32986011e+03 2.31046582e+03 2.28240723e+03 2.25376440e+03 2.21912695e+03 2.19739307e+03 2.16873413e+03 2.14520508e+03 2.11438916e+03 2.08497314e+03 2.05963306e+03 2.03236584e+03 2.00715283e+03 1.98127417e+03 1.95468311e+03 1.92602466e+03 1.89567627e+03 1.86927478e+03 1.84689551e+03 1.82124121e+03 1.79023706e+03 1.76315039e+03 1.73226453e+03 1.71135876e+03 1.68395471e+03 1.65629968e+03 1.63396606e+03 1.60601111e+03 1.57761768e+03 1.55301697e+03 1.53127356e+03 1.50228369e+03 1.46912781e+03 1.44504297e+03 1.42793994e+03 1.40186243e+03 1.37452112e+03 1.34771326e+03 1.32019080e+03 1.29461877e+03 1.27129968e+03 1.25208142e+03 1.22287769e+03 1.19973767e+03 1.17625793e+03 1.15098523e+03 1.12787646e+03 1.10404175e+03 1.08049646e+03 1.05771143e+03 1.03377002e+03 1.01243213e+03 9.88769897e+02 9.64797485e+02 9.44035217e+02 9.20636292e+02 8.99917175e+02 8.78354309e+02 8.56273315e+02 8.33492920e+02 8.12244080e+02 7.92718506e+02 7.70686584e+02 7.51479492e+02 7.30561462e+02 7.10206238e+02 6.91287354e+02 6.70507874e+02 6.51264404e+02 6.32549744e+02 6.13524414e+02 5.94963867e+02 5.76449097e+02 5.57529236e+02 5.40625854e+02 5.22953491e+02 5.05270538e+02 4.87840271e+02 4.70572296e+02 4.54589813e+02 4.37598846e+02 4.21289001e+02 4.06480042e+02 3.90431427e+02 3.74759369e+02 3.60135071e+02 3.45607330e+02 3.30896362e+02 3.16528687e+02 3.02964478e+02 2.89501709e+02 2.75841248e+02 2.62831268e+02 2.50098938e+02 2.37840637e+02 2.25698822e+02 2.14052246e+02 2.02538208e+02 1.91027451e+02 1.80174927e+02 1.69662872e+02 1.59439911e+02 1.49411392e+02 1.39834717e+02 1.30467346e+02 1.21432793e+02 1.12752373e+02 1.04266922e+02 9.61319580e+01 8.84206543e+01 8.10465851e+01 7.39397583e+01 6.71032257e+01 6.06717567e+01 5.45362740e+01 4.86977310e+01 4.32328224e+01 3.81017494e+01 3.32561188e+01 2.87524834e+01 2.45942955e+01 2.07684917e+01 1.72679119e+01 1.40928049e+01 1.12582788e+01 8.76297569e+00 6.60359764e+00 4.76890135e+00 3.26424408e+00 2.10053873e+00 1.27147102e+00 7.76011705e-01 6.15636170e-01 7.90274441e-01 1.29956794e+00 2.14330029e+00 3.32259679e+00 4.83450794e+00 6.68067312e+00 8.86600304e+00 1.13840942e+01 1.42249069e+01 1.74086781e+01 2.09312782e+01 2.47691135e+01 2.89398174e+01 3.34419098e+01 3.82793732e+01 4.34520073e+01 4.89638901e+01 5.47841911e+01 6.09180984e+01 6.74062881e+01 7.41770477e+01 8.12943573e+01 8.87530136e+01 9.65601044e+01 1.04708572e+02 1.13031693e+02 1.21644669e+02 1.30849594e+02 1.40288239e+02 1.49803085e+02 1.59906937e+02 1.70200378e+02 1.80609253e+02 1.91500793e+02 2.02833801e+02 2.14414261e+02 2.26320724e+02 2.38295624e+02 2.50622025e+02 2.63445007e+02 2.76485901e+02 2.89974121e+02 3.03360931e+02 3.17135986e+02 3.31416351e+02 3.46018158e+02 3.60463379e+02 3.75824524e+02 3.91520844e+02 4.06935486e+02 4.22339935e+02 4.38664062e+02 4.54971039e+02 4.71247437e+02 4.88483032e+02 5.05526733e+02 5.23298523e+02 5.40878479e+02 5.57966309e+02 5.77242126e+02 5.95276855e+02 6.14608276e+02 6.33366211e+02 6.52219604e+02 6.71774902e+02 6.90304932e+02 7.11386414e+02 7.33536316e+02 7.53041748e+02 7.73232788e+02 7.92324158e+02 8.12988647e+02 8.37293945e+02 8.54615601e+02 8.77802979e+02 9.01080688e+02 9.20226379e+02 9.45648010e+02 9.67600403e+02 9.88131348e+02 1.01226807e+03 1.03554810e+03 1.05745203e+03 1.08053381e+03 1.10556348e+03 1.12898181e+03 1.15552124e+03 1.17894934e+03 1.19810315e+03 1.22175073e+03 1.25109192e+03 1.27387341e+03 1.29677783e+03 1.32490466e+03 1.35000830e+03 1.37566956e+03 1.39883496e+03 1.42603638e+03 1.45292639e+03 1.47456274e+03 1.50324231e+03 1.52532092e+03 1.55259863e+03 1.57873438e+03 1.60485059e+03 1.63215442e+03 1.66084924e+03 1.68321179e+03 1.70938342e+03 1.73861279e+03 1.76476770e+03 1.79079297e+03 1.81814148e+03 1.84269373e+03 1.87015271e+03 1.89816260e+03 1.92578564e+03 1.95411511e+03 1.98359558e+03 2.00945251e+03 2.03200415e+03 2.05971802e+03 2.08508008e+03 2.11515527e+03 2.14676465e+03 2.17243555e+03 2.19813281e+03 2.22007080e+03 2.25191919e+03 2.27913965e+03 2.30981616e+03 2.33679688e+03 2.36175317e+03 2.38866748e+03 2.41797119e+03 2.43685498e+03 2.47189600e+03 2.49896362e+03 2.52507251e+03 2.55336938e+03 2.57289771e+03 2.60329858e+03 2.63426538e+03 2.66077246e+03 2.68927783e+03 2.70951929e+03 2.74204102e+03 2.76736401e+03 2.78768384e+03 2.82204443e+03 2.85077661e+03 2.86624048e+03 2.89786914e+03 2.92777222e+03 2.94587866e+03 2.96970679e+03 2.99564648e+03 3.03329614e+03 3.05916870e+03 3.07756494e+03 3.09570288e+03 3.12603564e+03 3.14006689e+03 3.17745190e+03 3.21039697e+03 3.22352979e+03 3.24941748e+03 3.27573291e+03 3.29330737e+03 3.32497437e+03 3.34445215e+03 3.36166821e+03 3.39693140e+03 3.41723804e+03 3.43944727e+03 3.45979297e+03 3.48094824e+03 3.50936768e+03 3.52609155e+03 3.55365186e+03 3.57644873e+03 3.59458179e+03 3.60901489e+03 3.63280615e+03 3.66204346e+03 3.67522583e+03 3.69891113e+03 3.71490234e+03 3.73944946e+03 3.76550928e+03 3.77687134e+03 3.79589136e+03 3.81351221e+03 3.83367188e+03 3.85423169e+03 3.87321802e+03 3.88957349e+03 3.90984790e+03 3.92976758e+03 3.94502661e+03 3.96146875e+03 3.97737061e+03 3.99850952e+03 4.01017310e+03 4.02325659e+03 4.04784131e+03 4.05603809e+03 4.07202759e+03 4.08817163e+03 4.10268848e+03 4.11988232e+03 4.13131592e+03 4.14746289e+03 4.16144922e+03 4.17079004e+03 4.18389209e+03 4.19796289e+03 5.47464844e+03 5.80295654e+03 6.36460693e+03 6.38379932e+03 6.39885156e+03 6.41151709e+03 6.43426270e+03 6.44799707e+03 6.45973486e+03 6.47807812e+03 6.49407568e+03 6.02382568e+03 6.51680029e+03 4.34740771e+03 5.67274072e+03 4.35855176e+03 4.36699072e+03 4.38229883e+03 4.38858594e+03 4.38890723e+03 4.39466406e+03 4.40055518e+03 4.40722705e+03 4.41064941e+03 4.41555029e+03 4.42086230e+03 4.43073877e+03 4.42864404e+03 4.43194238e+03 4.43650879e+03 4.43868164e+03 4.44015967e+03 4.44320361e+03 4.44414941e+03 4.44578418e+03 4.44754395e+03 4.44791260e+03 4.44854443e+03 4.44877246e+03 4.44837744e+03 4.44762695e+03 4.44680566e+03 4.44591895e+03 4.44433447e+03 4.44209521e+03 4.44092773e+03 4.43793945e+03 4.43428662e+03 4.43201465e+03 4.42863330e+03 4.42529199e+03 4.42066260e+03 4.41517920e+03 4.41123047e+03 4.40539893e+03 4.39993555e+03 4.39406543e+03 4.38816895e+03 4.38132861e+03 4.37526660e+03 4.36768311e+03 4.36061670e+03 4.35344824e+03 4.34621289e+03 4.33580469e+03 4.32615381e+03 4.31933643e+03 4.31001807e+03 4.29878662e+03 4.29305273e+03 4.28198779e+03 4.26681055e+03 4.25383936e+03 4.24549219e+03 4.23478271e+03 4.22582812e+03 4.21252148e+03 4.19844385e+03 4.18354199e+03 4.16931104e+03 4.16067529e+03 4.14634619e+03 4.13472852e+03 4.11863281e+03 4.10126367e+03 4.08631958e+03 4.07427466e+03 4.06092651e+03 4.04703906e+03 4.02522949e+03 4.00751709e+03 3.99190234e+03 3.97891699e+03 3.96385229e+03 3.94125073e+03 3.92642871e+03 3.91157397e+03 3.88905762e+03 3.87404248e+03 3.85079883e+03 3.83328613e+03 3.81609717e+03 3.79844824e+03 3.77759692e+03 3.75130786e+03 3.73368311e+03 3.72483032e+03 3.70395630e+03 3.67712036e+03 3.65191553e+03 3.63351245e+03 3.62336035e+03 3.58587744e+03 3.56803174e+03 3.55058936e+03 3.52107690e+03 3.51294556e+03 3.48302173e+03 3.45418506e+03 3.43813379e+03 3.41774072e+03 3.39080786e+03 3.36562646e+03 3.34721240e+03 3.32137720e+03 3.29927295e+03 3.27337793e+03 3.24461621e+03 3.22274243e+03 3.20350122e+03 3.16947754e+03 3.14802344e+03 3.12574219e+03 3.09740088e+03 3.07905786e+03 3.05196753e+03 3.02376270e+03 3.00793970e+03 2.97103223e+03 2.95130713e+03 2.91613184e+03 2.89388989e+03 2.87457568e+03 2.83844360e+03 2.81632666e+03 2.79304272e+03 2.76202271e+03 2.73641235e+03 2.71414087e+03 2.69043237e+03 2.66005908e+03 2.62817065e+03 2.59773657e+03 2.57093042e+03 2.54660278e+03 2.52305249e+03 2.50052319e+03 2.47244727e+03 2.43854199e+03 2.41694409e+03 2.39087134e+03 2.35570898e+03 2.33040503e+03 2.30769019e+03 2.27575146e+03 2.25287842e+03 2.22109009e+03 2.19278735e+03 2.17299292e+03 2.14433447e+03 2.11850854e+03 2.08125195e+03 2.06010815e+03 2.03042566e+03 2.00224121e+03 1.97783972e+03 1.96071069e+03 1.95068604e+03 2.33116357e+03 2.31101904e+03 2.77876611e+03 2.73104639e+03 2.68527759e+03 2.63875464e+03 2.59962964e+03 2.56712354e+03 2.52820630e+03 2.48482129e+03 2.01302563e+03 2.54919458e+03 2.20402222e+03 2.33376733e+03 2.29980615e+03 2.25987744e+03 2.21733032e+03 1.95191760e+03 1.83407312e+03 1.39902039e+03 1.37340613e+03 1.66140503e+03 1.71598706e+03 3.26729907e+03 1.34163818e+04 44211268. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 110894328. 110894328. -4.58628650e+06 -5.12428950e+06 3.41022485e+03 4.75776797e+04 -36507392. 2.43835815e+03 1.89152124e+03 1.12722522e+03 1.09261511e+03 1.06426331e+03 1.03491553e+03 9.27769226e+02 8.50860840e+02 6.32942749e+02 6.13375793e+02 5.94827271e+02 5.76336243e+02 5.57819336e+02 6.96484070e+02 7.06463928e+02 7.55792664e+02 7.31103027e+02 7.03916199e+02 6.80261902e+02 6.55808899e+02 6.31401367e+02 6.08760254e+02 5.83894775e+02 5.60852417e+02 5.38871826e+02 5.17304504e+02 4.94611145e+02 4.73467621e+02 4.53673889e+02 4.33787720e+02 4.12841461e+02 3.68099152e+02 3.74593536e+02 3.20146576e+02 3.37533722e+02 3.20184052e+02 3.03518585e+02 2.86230896e+02 2.69828156e+02 2.54286331e+02 2.38780334e+02 2.23651596e+02 2.09281937e+02 1.95382797e+02 1.81992783e+02 1.68971863e+02 1.56259552e+02 1.44388947e+02 1.32453979e+02 1.21341537e+02 1.70192657e+02 1.85852875e+02 4.01035125e+06 14211816. 2.08770906e+05 3.68123867e+04 2.37243906e+04 -7879596. 51399696. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 167394016. 167394016. 0. 0. 0. 0. 80714408. 3.86390650e+06 3.86390650e+06 -17726338. 0. 30247302. -12440534. -40506572. 78546784. 6.17565750e+06 1853350144. 1853350144. 0. 45419428. 45419428. 2.72597075e+06 -48693588. -48693588. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 19682908. 19682908. 7511577. -35412232. -35412232. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 153645680. 153645680. 153645680. 0. 0. 30179786. 5.96337012e+03 3.03805396e+03 7.92145386e+02 1.29073474e+03 8.43261169e+02 7.19905823e+02 7.39244812e+02 6.18549316e+02 8.34278320e+02 9.12388794e+02 1.66114795e+03 2.21005859e+03 8.69517438e+05 1.57631953e+05 4.41979594e+05 -4562151. -11331764. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 40177980. 3.57540975e+06 2.50564172e+05 3.56201001e+03 2.53625562e+03 1.30738879e+03 1.33243933e+03 1.35495032e+03 1.38196472e+03 1.40991687e+03 1.43422705e+03 1.45849023e+03 1.90614258e+03 2.03330200e+03 2.31797144e+03 2.35373730e+03 2.39375464e+03 2.44015234e+03 2.47678760e+03 2.33973193e+03 2.23613940e+03 1.72284912e+03 1.75130774e+03 1.77376624e+03 1.80020276e+03 1.83034998e+03 1.85766125e+03 1.88484058e+03 1.91201172e+03 1.93623059e+03 1.96392993e+03 1.99233765e+03 2.02235327e+03 2.04844019e+03 2.07756567e+03 2.09961377e+03 2.12711914e+03 2.15787036e+03 2.18418506e+03 2.21337085e+03 2.23982983e+03 2.26768555e+03 2.29434448e+03 2.32249316e+03 2.35105981e+03 2.38468628e+03 2.40685815e+03 2.43125659e+03 2.45188843e+03 2.48733984e+03 2.51501147e+03 2.53774683e+03 2.56403711e+03 2.59362915e+03 2.61750488e+03 2.65195728e+03 2.68109692e+03 2.70053857e+03 2.72065820e+03 2.75618213e+03 2.78668604e+03 2.80747729e+03 2.84124731e+03 2.86076123e+03 2.88659277e+03 2.91363184e+03 2.93936572e+03 2.96809692e+03 2.99186255e+03 3.01917920e+03 3.04350415e+03 3.06801147e+03 3.09817505e+03 3.11577051e+03 3.14415527e+03 3.17349536e+03 3.19136548e+03 3.22349365e+03 3.25006250e+03 3.27055908e+03 3.29169507e+03 3.31445386e+03 3.33872461e+03 3.36464429e+03 3.39171631e+03 3.40865942e+03 3.43311108e+03 3.46171606e+03 3.48380786e+03 3.50029590e+03 3.52589111e+03 3.54599438e+03 3.57537158e+03 3.59873584e+03 3.61457642e+03 3.63120044e+03 3.65499976e+03 3.68671582e+03 3.69901196e+03 3.71772803e+03 3.74146338e+03 3.76516333e+03 3.78338159e+03 3.80038916e+03 3.82213623e+03 3.83692725e+03 3.85925391e+03 3.88212524e+03 3.89748315e+03 3.91314404e+03 3.92918262e+03 3.95251782e+03 3.97015674e+03 3.98226685e+03 4.00232935e+03 4.01966260e+03 4.03193530e+03 4.04868164e+03 4.06756738e+03 4.08468994e+03 4.10024316e+03 4.11425000e+03 4.12658984e+03 4.14223291e+03 4.15807959e+03 4.17184814e+03 4.18593604e+03 4.19868311e+03 4.21155322e+03 4.21830615e+03 4.23448242e+03 4.25335693e+03 4.26064258e+03 4.27383594e+03 4.28195605e+03 4.29284033e+03 4.30494629e+03 4.31551562e+03 4.32738916e+03 4.33660938e+03 4.34461475e+03 4.35328271e+03 4.36200977e+03 4.37134326e+03 4.37685156e+03 4.38512305e+03 4.39652295e+03 4.39966699e+03 4.40732520e+03 4.41778857e+03 4.42267627e+03 4.42472461e+03 4.43146191e+03 4.43853418e+03 4.44186279e+03 4.44795605e+03 4.44958105e+03 4.45367969e+03 4.45878564e+03 4.46100732e+03 4.46456152e+03 4.46705664e+03 4.46968945e+03 4.47016211e+03 4.47192139e+03 4.47401953e+03 4.47419922e+03 4.47479346e+03 4.47499463e+03 4.47493311e+03 4.47401514e+03 4.47339453e+03 4.47277002e+03 4.47043945e+03 4.46803857e+03 4.46747705e+03 4.46473633e+03 4.45997314e+03 4.45764795e+03 4.45487109e+03 4.45048828e+03 4.44587549e+03 4.44228174e+03 4.43902246e+03 4.43181445e+03 4.42533789e+03 4.42017041e+03 5.70635693e+03 5.91690137e+03 5.97964893e+03 5.68162598e+03 4.38636719e+03 4.37880420e+03 4.36885156e+03 4.36033594e+03 4.35101221e+03 4.34663135e+03 4.33756006e+03 5.33493359e+03 5.34727686e+03 5.30398438e+03 5.27041260e+03 4.28350000e+03 4.27267871e+03 4.25975000e+03 4.24782324e+03 4.23440674e+03 5.46022607e+03 5.72950635e+03 6.27265186e+03 6.25176318e+03 5.71379248e+03 5.38608398e+03 4.14124219e+03 4.12636475e+03 4.11363525e+03 4.09730957e+03 4.08133398e+03 4.06862915e+03 4.04989062e+03 4.03453516e+03 4.01653564e+03 3.99801025e+03 3.98679565e+03 3.96877368e+03 3.94923950e+03 3.93538916e+03 3.91360986e+03 3.89380200e+03 3.87416772e+03 3.86086865e+03 3.83733716e+03 3.81717969e+03 3.80191626e+03 3.78023096e+03 3.75602417e+03 3.73973096e+03 3.72508862e+03 3.70470801e+03 3.67395557e+03 3.65503174e+03 3.64236279e+03 3.61340869e+03 3.58850171e+03 3.56329980e+03 3.54376855e+03 3.53433325e+03 3.49667944e+03 3.46822070e+03 3.45981299e+03 3.44521484e+03 3.41767383e+03 3.38457617e+03 3.36516626e+03 3.33936987e+03 3.31900854e+03 3.29516846e+03 3.25671533e+03 3.23858447e+03 3.22195947e+03 3.19326685e+03 3.16670117e+03 3.14646948e+03 3.11735425e+03 3.09475366e+03 3.07629077e+03 3.04480737e+03 3.01825684e+03 2.99316992e+03 2.96552222e+03 2.93513306e+03 2.90678369e+03 2.89084204e+03 2.86215234e+03 2.83399243e+03 2.80879834e+03 2.77824731e+03 2.75501953e+03 2.73035986e+03 2.70064624e+03 2.67225684e+03 2.64986133e+03 2.61961523e+03 2.59255859e+03 2.56833374e+03 2.53568604e+03 2.51030835e+03 2.48429077e+03 2.46197925e+03 2.42972803e+03 2.40291333e+03 2.37046460e+03 2.34403784e+03 2.32452637e+03 2.29208813e+03 2.26496045e+03 2.23354395e+03 2.20447314e+03 2.18018848e+03 2.15630322e+03 2.13583032e+03 2.10347681e+03 2.07539893e+03 2.04566638e+03 2.01549878e+03 1.99131909e+03 1.96844092e+03 1.93591638e+03 1.90606335e+03 1.87763196e+03 1.85353967e+03 1.82922705e+03 1.80492627e+03 1.77432251e+03 1.74160596e+03 1.72242200e+03 1.69441101e+03 1.66818213e+03 1.64332788e+03 1.61066785e+03 1.58706042e+03 1.56365967e+03 1.53796606e+03 1.51015723e+03 1.47982642e+03 1.45923962e+03 1.43584924e+03 1.40569006e+03 1.38394641e+03 1.35461182e+03 1.32956775e+03 1.30658105e+03 1.27947424e+03 1.25754077e+03 1.23325269e+03 1.20639246e+03 1.18238672e+03 1.15919287e+03 1.13268164e+03 1.10961987e+03 1.08908386e+03 1.06429675e+03 1.03816211e+03 1.01832709e+03 9.95701904e+02 9.70623352e+02 9.50059387e+02 9.26012085e+02 9.05108826e+02 8.83870728e+02 8.61006714e+02 8.38334351e+02 8.17318970e+02 7.99390320e+02 7.76271179e+02 7.55344971e+02 7.35564514e+02 7.15391846e+02 6.95302185e+02 6.74923462e+02 6.55579468e+02 6.35879517e+02 6.17569580e+02 5.99330994e+02 5.80128235e+02 5.61253479e+02 5.43368591e+02 5.26431396e+02 5.08703613e+02 4.90773163e+02 4.74073456e+02 4.57161560e+02 4.40526825e+02 4.24551147e+02 4.08766357e+02 3.93173767e+02 3.78028839e+02 3.62724457e+02 3.47487885e+02 3.33188019e+02 3.19229492e+02 3.05047424e+02 2.91389893e+02 2.78239136e+02 2.65037476e+02 2.52046112e+02 2.39594055e+02 2.27512009e+02 2.15661423e+02 2.04206741e+02 1.92913727e+02 1.81848434e+02 1.71095245e+02 1.60837006e+02 1.50991791e+02 1.41205688e+02 1.31733948e+02 1.22711266e+02 1.13955254e+02 1.05496727e+02 9.72843323e+01 8.95426178e+01 8.21330795e+01 7.49300461e+01 6.81252060e+01 6.16586342e+01 5.55139771e+01 4.96425285e+01 4.41096802e+01 3.89659271e+01 3.41019096e+01 2.95882454e+01 2.54071865e+01 2.15572758e+01 1.80511112e+01 1.48565826e+01 1.20061092e+01 9.50333405e+00 7.34184551e+00 5.50333691e+00 3.99195981e+00 2.82769561e+00 1.99922705e+00 1.50589156e+00 1.34964359e+00 1.52779138e+00 2.04270744e+00 2.89573979e+00 4.08750343e+00 5.61364889e+00 7.47529793e+00 9.67941570e+00 1.22205868e+01 1.50859156e+01 1.82915821e+01 2.18417778e+01 2.57034092e+01 2.98883362e+01 3.44278412e+01 3.93177071e+01 4.45020294e+01 5.00541954e+01 5.59703789e+01 6.21099281e+01 6.85858459e+01 7.54201431e+01 8.26602020e+01 9.01678619e+01 9.79104462e+01 1.06040321e+02 1.14547134e+02 1.23378113e+02 1.32490082e+02 1.41842194e+02 1.51546066e+02 1.61708649e+02 1.72044449e+02 1.82479279e+02 1.93528549e+02 2.05107254e+02 2.16571945e+02 2.28341751e+02 2.40334030e+02 2.53109283e+02 2.66045380e+02 2.79101776e+02 2.92188660e+02 3.06097595e+02 3.20122620e+02 3.34503967e+02 3.48694061e+02 3.63631958e+02 3.79397461e+02 3.94222351e+02 4.09825653e+02 4.25927826e+02 4.42101105e+02 4.58490021e+02 4.74682098e+02 4.92851227e+02 5.09976624e+02 5.27275696e+02 5.46047485e+02 5.63070251e+02 5.81024597e+02 5.99432434e+02 6.19739868e+02 6.37748230e+02 6.56402588e+02 6.77578735e+02 6.96329285e+02 7.16450928e+02 7.37294739e+02 7.57609741e+02 7.77192688e+02 7.97557373e+02 8.19759094e+02 8.43239197e+02 8.62298462e+02 8.84270020e+02 9.05372925e+02 9.27203186e+02 9.51721069e+02 9.72232971e+02 9.95073486e+02 1.01922260e+03 1.04392981e+03 1.06620374e+03 1.08537854e+03 1.11165332e+03 1.13726587e+03 1.16217395e+03 1.18693860e+03 1.20650183e+03 1.23219312e+03 1.25884302e+03 1.28116602e+03 1.30993445e+03 1.33375415e+03 1.35385864e+03 1.38287024e+03 1.41183105e+03 1.43438672e+03 1.45701746e+03 1.48550806e+03 1.51336621e+03 1.53471460e+03 1.56080530e+03 1.58775488e+03 1.61504761e+03 1.64535974e+03 1.67460522e+03 1.69277466e+03 1.72225134e+03 1.75198926e+03 1.77744629e+03 1.79931641e+03 1.82909009e+03 1.85948840e+03 1.88012231e+03 1.91043701e+03 1.94067383e+03 1.96538367e+03 1.99854211e+03 2.02164075e+03 2.04420325e+03 2.06864233e+03 2.09441235e+03 2.12733350e+03 2.15878345e+03 2.18285840e+03 2.21578638e+03 2.23296533e+03 2.25798779e+03 2.29441357e+03 2.32280151e+03 2.35410156e+03 2.38291284e+03 2.40679712e+03 2.42828857e+03 2.44598730e+03 2.48683838e+03 2.52383032e+03 2.54316553e+03 2.56110156e+03 2.58735522e+03 2.62314355e+03 2.65555151e+03 2.67948218e+03 2.69483276e+03 2.72106689e+03 2.76344775e+03 2.78455615e+03 2.80542188e+03 2.84134912e+03 2.86173730e+03 2.88441382e+03 2.91536987e+03 2.93814429e+03 2.96682910e+03 2.98961108e+03 3.01760352e+03 3.04995508e+03 3.06413843e+03 3.09805688e+03 3.11565967e+03 3.14360669e+03 3.16686743e+03 3.18755908e+03 3.22568091e+03 3.24547461e+03 3.27075415e+03 3.29680737e+03 3.31385693e+03 3.34149829e+03 3.36308716e+03 3.38894897e+03 3.41740332e+03 3.43174438e+03 3.46527808e+03 3.48253149e+03 3.49820337e+03 3.52718994e+03 3.54448242e+03 3.57712183e+03 3.59475317e+03 3.61301440e+03 3.62862598e+03 3.65269678e+03 3.68796436e+03 3.69935352e+03 3.71713721e+03 3.73871509e+03 3.76694043e+03 3.78470752e+03 3.80156445e+03 3.82051318e+03 3.83661255e+03 3.85911328e+03 3.88017773e+03 3.89716919e+03 3.91181787e+03 3.93272119e+03 3.95212769e+03 3.96929126e+03 3.98649097e+03 4.00242285e+03 4.01919971e+03 4.03292236e+03 4.04850244e+03 4.06852197e+03 4.08222925e+03 4.09982471e+03 4.11384961e+03 4.12789111e+03 4.14611816e+03 4.15487988e+03 4.17112598e+03 4.18630811e+03 4.19699561e+03 4.20903906e+03 4.22267969e+03 4.23685254e+03 4.25035986e+03 4.25855859e+03 4.27148291e+03 4.28292041e+03 4.29213281e+03 4.30541016e+03 4.31426709e+03 4.32295166e+03 5.61395410e+03 4.34482324e+03 5.65457080e+03 4.36082910e+03 4.37117676e+03 4.37808203e+03 4.38863867e+03 4.39650342e+03 4.40459131e+03 4.41311621e+03 4.41528857e+03 4.42069824e+03 4.42699902e+03 4.43215039e+03 4.43691846e+03 4.44293750e+03 4.44775342e+03 4.45485352e+03 4.45420410e+03 4.45816406e+03 4.46192480e+03 4.46497217e+03 4.46696924e+03 4.46953857e+03 4.47028955e+03 4.47216211e+03 4.47390332e+03 4.47418848e+03 4.47486572e+03 4.47507959e+03 4.47483789e+03 4.47387402e+03 4.47316650e+03 4.47283154e+03 4.47058594e+03 4.46815186e+03 4.46742822e+03 4.46424854e+03 4.46058057e+03 4.45848047e+03 4.45436670e+03 4.45126025e+03 4.44611475e+03 4.44107959e+03 4.43857764e+03 4.43135645e+03 4.42483496e+03 4.42118945e+03 4.41466748e+03 4.40678467e+03 4.39977393e+03 4.39377588e+03 4.38790918e+03 4.37896387e+03 4.36959375e+03 4.36145557e+03 4.35468164e+03 4.34573828e+03 4.33588330e+03 4.32226074e+03 4.31619531e+03 4.30769531e+03 4.29002979e+03 4.28288184e+03 4.27463770e+03 4.26142139e+03 4.24749561e+03 4.22987061e+03 4.22212695e+03 4.21011035e+03 4.19675098e+03 4.18428027e+03 4.17166797e+03 4.15745361e+03 4.14356934e+03 4.12349854e+03 4.11113965e+03 4.10096533e+03 4.08406323e+03 4.06753564e+03 4.05144946e+03 4.03149219e+03 4.01390063e+03 3.99722217e+03 3.98807544e+03 3.96891675e+03 3.94636963e+03 3.93408862e+03 3.91714941e+03 3.89064307e+03 3.87108252e+03 3.86354614e+03 3.83716870e+03 3.81506396e+03 3.80158154e+03 3.77803247e+03 3.75768726e+03 3.74285547e+03 3.72414526e+03 3.70029565e+03 3.67363696e+03 3.65436890e+03 3.64315454e+03 3.61305103e+03 3.59139209e+03 3.56693433e+03 3.54308667e+03 3.53629102e+03 3.49534277e+03 3.47051196e+03 3.45892505e+03 3.44435718e+03 3.41486523e+03 3.38626831e+03 3.36494385e+03 3.33773975e+03 3.32077808e+03 3.29796558e+03 3.25968555e+03 3.24207690e+03 3.22114307e+03 3.19140234e+03 3.16713818e+03 3.14256543e+03 3.11213989e+03 3.09444873e+03 3.07360229e+03 3.04303589e+03 3.01657642e+03 2.98658057e+03 2.96651636e+03 2.93937549e+03 2.90850879e+03 2.88745972e+03 2.86067725e+03 2.83608691e+03 2.80967871e+03 2.77724487e+03 2.75369604e+03 2.72963794e+03 2.70261499e+03 2.67149072e+03 2.64283545e+03 2.62250317e+03 2.58968359e+03 2.56927881e+03 2.53762891e+03 2.50709253e+03 2.48691333e+03 2.45665894e+03 2.42466309e+03 2.40015918e+03 2.36989697e+03 2.34837012e+03 2.32022778e+03 2.28839624e+03 2.26871484e+03 2.23573755e+03 2.20316968e+03 2.18085522e+03 2.15854834e+03 2.13567944e+03 2.10447266e+03 2.07566821e+03 2.03915588e+03 2.00924805e+03 1.99193127e+03 1.97118555e+03 1.95947095e+03 2.50057153e+03 2.62805884e+03 2.79325830e+03 2.75378589e+03 2.72264282e+03 2.66423071e+03 2.62286450e+03 2.59571729e+03 2.55435669e+03 2.51249951e+03 2.22588477e+03 2.07424561e+03 1.58725586e+03 1.55995129e+03 1.53543823e+03 1.51177576e+03 1.48292834e+03 1.45793481e+03 1.43288794e+03 1.40469580e+03 1.38305603e+03 1.78370703e+03 1.32934924e+03 1.96577417e+03 3.04092676e+03 3.39072363e+03 -37326692. 26072950. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 126097896. -101956840. 3.95259141e+04 1.87338638e+06 1.73922638e+06 -92542896. 1.91639917e+03 1.29948950e+03 6.38564575e+02 6.18078796e+02 5.98971985e+02 5.80281860e+02 5.61732483e+02 6.73354126e+02 6.54176208e+02 1.19953699e+03 1.42378503e+03 8.36051062e+05 9.83205312e+05 3.21020350e+06 -20673566. -7.83384350e+06 -14925324. 1.72000962e+06 4.01030125e+06 3.43360375e+06 9.26092125e+05 71196. 1.74366675e+06 3.99674150e+06 1.49545225e+06 8.55673279e+02 7.53226318e+02 6.60771423e+02 2.89809575e+06 3.11492062e+05 9019683. 2.55615875e+06 2.08251425e+06 -10650502. 3.34680625e+06 3.80895425e+06 2164739. 4.25754688e+05 6.01425078e+04 1.40987531e+05 3.01024094e+05 4.69926250e+06 1.54699395e+04 1.34544355e+04 20613264. -7151259. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 167394016. 167394016. 0. 0. 12727925. 12727925. 12727925. 0. 0. 0. 0. 30247302. -12440534. -40506572. 78546784. 6.17565750e+06 1853350144. 1853350144. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 19682908. 19682908. 19682908. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 153645680. 153645680. 153645680. 0. 0. 30179786. -14955691. -14955691. -24728490. 9.36673062e+05 2.40003242e+04 1.96654211e+03 1.55099695e+03 9.37185669e+02 1.57636206e+03 2.07569995e+03 81317368. 128093976. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.39977050e+06 -39397588. 3.96718750e+03 3.05529932e+03 1.87266003e+03 1.76480261e+03 1.69876624e+03 1.31937305e+03 1.34392773e+03 1.36559753e+03 1.39001929e+03 1.41884839e+03 1.44769983e+03 1.46661804e+03 1.49558398e+03 1.52387463e+03 1.54991382e+03 1.57262305e+03 1.60085107e+03 1.63108472e+03 1.65512097e+03 1.67977417e+03 1.70785315e+03 1.73896594e+03 1.76699890e+03 1.78633057e+03 1.81164868e+03 1.84664795e+03 1.87362976e+03 1.89796338e+03 1.92714319e+03 1.95261072e+03 1.97641687e+03 2.00528198e+03 2.03781921e+03 2.06007202e+03 2.09033618e+03 2.11518701e+03 2.14259155e+03 2.17021094e+03 2.20261694e+03 2.22619824e+03 2.25613330e+03 2.28444800e+03 2.31309155e+03 2.33746533e+03 2.36880664e+03 2.39629004e+03 2.42210034e+03 2.44481860e+03 2.47279541e+03 2.50243970e+03 2.53523413e+03 2.56117822e+03 2.57997437e+03 2.61077222e+03 2.63888135e+03 2.66813696e+03 2.70238989e+03 2.72217017e+03 2.74118457e+03 2.77564233e+03 2.80657324e+03 2.83249243e+03 2.86965991e+03 2.88169556e+03 2.90752173e+03 2.93355103e+03 2.96192456e+03 2.99781274e+03 3.01153882e+03 3.04300513e+03 3.07397144e+03 3.09059595e+03 3.12054224e+03 3.13927393e+03 3.17431616e+03 3.19784644e+03 3.21733008e+03 3.24448315e+03 3.26966040e+03 3.29214575e+03 3.31764551e+03 3.34429785e+03 3.36667554e+03 3.38712109e+03 3.41888428e+03 3.43797974e+03 3.45627466e+03 3.48811206e+03 3.51376611e+03 3.53480420e+03 3.55219775e+03 3.57107666e+03 3.60524072e+03 3.62371436e+03 3.64483008e+03 3.66187598e+03 3.68788647e+03 3.71190381e+03 3.72246899e+03 3.74873022e+03 3.77066772e+03 3.79585986e+03 3.81074927e+03 3.82637476e+03 3.85490991e+03 3.86726416e+03 3.88855884e+03 3.91620508e+03 3.92782837e+03 3.94387427e+03 3.96534521e+03 3.98183276e+03 3.99976318e+03 4.01680835e+03 4.03392456e+03 4.05166919e+03 4.06678027e+03 4.08011548e+03 4.10008105e+03 4.11904248e+03 4.13559277e+03 4.14695850e+03 4.15876660e+03 4.17541260e+03 4.19264746e+03 4.20473389e+03 4.21861035e+03 4.23548926e+03 4.24622070e+03 4.25566602e+03 4.26615820e+03 4.28560547e+03 4.29811377e+03 4.30792773e+03 4.31674512e+03 4.33086914e+03 4.34266895e+03 4.34936133e+03 4.36249854e+03 4.36947363e+03 4.37815332e+03 4.38976904e+03 4.39766357e+03 4.40717871e+03 4.41326660e+03 4.42080615e+03 4.43162207e+03 4.43687158e+03 4.44623340e+03 4.45173877e+03 4.45748291e+03 4.46305176e+03 4.46784131e+03 4.47372070e+03 4.47811719e+03 4.48513281e+03 4.48729053e+03 4.49048145e+03 4.49547803e+03 4.49763770e+03 4.50103174e+03 4.50465576e+03 4.50647314e+03 4.50715918e+03 4.50927344e+03 4.51099707e+03 4.51139844e+03 4.51217578e+03 4.51237305e+03 4.51232178e+03 4.51121338e+03 4.51054590e+03 4.51025146e+03 4.50790967e+03 4.50576709e+03 4.50426123e+03 4.50176465e+03 4.49835596e+03 4.49456445e+03 4.49191699e+03 4.48837012e+03 4.48393018e+03 4.47893701e+03 4.47538037e+03 4.46898193e+03 4.46077539e+03 4.45664160e+03 4.45034570e+03 4.44030713e+03 4.43893115e+03 4.43735352e+03 4.42363330e+03 4.41386963e+03 4.40678174e+03 4.39324268e+03 4.38699707e+03 4.38706689e+03 4.37779053e+03 5.73280322e+03 6.03702539e+03 5.97805713e+03 5.66616797e+03 5.62292041e+03 5.82932959e+03 6.41138672e+03 6.39589209e+03 5.79006104e+03 6.61071924e+03 5.18934912e+03 6.35154150e+03 6.33527734e+03 5.25182959e+03 5.20637354e+03 4.17962109e+03 4.16403174e+03 4.15016357e+03 4.13199023e+03 5.35254639e+03 5.64256201e+03 6.09940430e+03 6.07809277e+03 6.04575879e+03 5.47571240e+03 5.14725342e+03 3.99394067e+03 3.98166431e+03 3.97285498e+03 3.95153662e+03 3.92488892e+03 3.91105322e+03 3.89852295e+03 3.87253760e+03 3.84840210e+03 3.83024731e+03 3.81465845e+03 3.78694434e+03 3.77327710e+03 3.75774292e+03 3.73728613e+03 3.70916235e+03 3.68356543e+03 3.67613501e+03 3.65230884e+03 3.61997876e+03 3.59345825e+03 3.57361743e+03 3.56380566e+03 3.53332080e+03 3.50062305e+03 3.48703955e+03 3.47189795e+03 3.44375903e+03 3.42040430e+03 3.39002271e+03 3.36464014e+03 3.35236304e+03 3.32618823e+03 3.28778784e+03 3.27640283e+03 3.25262842e+03 3.22051953e+03 3.20218140e+03 3.17111865e+03 3.14246362e+03 3.12180176e+03 3.09939600e+03 3.06792603e+03 3.03280151e+03 3.01535498e+03 2.99723364e+03 2.96519849e+03 2.93175537e+03 2.91092749e+03 2.89415356e+03 2.85815063e+03 2.83177344e+03 2.80696704e+03 2.78543506e+03 2.75846826e+03 2.72460352e+03 2.69508618e+03 2.67037280e+03 2.64567163e+03 2.61816406e+03 2.59364209e+03 2.56307837e+03 2.53073389e+03 2.50698999e+03 2.48128491e+03 2.45499536e+03 2.41936450e+03 2.39471851e+03 2.36718237e+03 2.34351147e+03 2.31977148e+03 2.28596704e+03 2.25585913e+03 2.23086475e+03 2.19879932e+03 2.17027051e+03 2.14853833e+03 2.12509497e+03 2.09451245e+03 2.06050415e+03 2.03457251e+03 2.00775122e+03 1.98827783e+03 1.95463562e+03 1.92196631e+03 1.89618323e+03 1.87248303e+03 1.84763977e+03 1.82230383e+03 1.78699377e+03 1.75981445e+03 1.74028259e+03 1.70989722e+03 1.68682935e+03 1.65976001e+03 1.62501245e+03 1.60265869e+03 1.57656750e+03 1.54980322e+03 1.52650269e+03 1.49573193e+03 1.47516931e+03 1.44706592e+03 1.41801257e+03 1.39879187e+03 1.36907068e+03 1.34477307e+03 1.32156006e+03 1.29441504e+03 1.26952246e+03 1.24381628e+03 1.21924963e+03 1.19490588e+03 1.17121814e+03 1.14713220e+03 1.12100562e+03 1.10137463e+03 1.07599084e+03 1.04798511e+03 1.02933813e+03 1.00703296e+03 9.81892578e+02 9.59073425e+02 9.35839050e+02 9.16682373e+02 8.92705017e+02 8.71774475e+02 8.48549072e+02 8.26523376e+02 8.07631897e+02 7.83732727e+02 7.64283691e+02 7.44321838e+02 7.24851440e+02 7.03032166e+02 6.82314636e+02 6.64144104e+02 6.43726562e+02 6.25092468e+02 6.06708374e+02 5.87026917e+02 5.68039612e+02 5.50311646e+02 5.32551697e+02 5.14414917e+02 4.97264862e+02 4.80057770e+02 4.63410736e+02 4.46809418e+02 4.30298431e+02 4.14453796e+02 3.98472992e+02 3.83116119e+02 3.67871979e+02 3.52714569e+02 3.38093475e+02 3.23801208e+02 3.09673126e+02 2.95680145e+02 2.82417816e+02 2.69202087e+02 2.56123718e+02 2.43291245e+02 2.31074020e+02 2.19331100e+02 2.07617889e+02 1.96271973e+02 1.85304733e+02 1.74464294e+02 1.63945236e+02 1.53925583e+02 1.44012680e+02 1.34549500e+02 1.25431931e+02 1.16535210e+02 1.08023628e+02 9.97078094e+01 9.18451309e+01 8.43962708e+01 7.71692276e+01 7.02257309e+01 6.36168060e+01 5.74404678e+01 5.15289993e+01 4.59026451e+01 4.06803894e+01 3.57734337e+01 3.12121296e+01 2.69669571e+01 2.30480022e+01 1.94961987e+01 1.62510777e+01 1.33435707e+01 1.07977448e+01 8.60313416e+00 6.71954823e+00 5.16966915e+00 3.97276545e+00 3.11225390e+00 2.58962154e+00 2.40740728e+00 2.56531858e+00 3.06490731e+00 3.89988685e+00 5.07869720e+00 6.59451675e+00 8.44394970e+00 1.06410542e+01 1.31755009e+01 1.60412827e+01 1.92310715e+01 2.27860508e+01 2.66686954e+01 3.08597565e+01 3.54109917e+01 4.03048592e+01 4.55152855e+01 5.10802689e+01 5.70008278e+01 6.31837616e+01 6.97223053e+01 7.66298294e+01 8.38370209e+01 9.13709106e+01 9.92128296e+01 1.07369476e+02 1.15872780e+02 1.24729256e+02 1.33874939e+02 1.43241135e+02 1.53117584e+02 1.63327652e+02 1.73734421e+02 1.84225372e+02 1.95175613e+02 2.06879562e+02 2.18584167e+02 2.30278732e+02 2.42628357e+02 2.55288300e+02 2.68381378e+02 2.81661713e+02 2.94542664e+02 3.08261993e+02 3.23195862e+02 3.37408386e+02 3.51450836e+02 3.66219574e+02 3.81553406e+02 3.97480438e+02 4.13558411e+02 4.29468719e+02 4.45239410e+02 4.61932007e+02 4.78709747e+02 4.96096893e+02 5.13565918e+02 5.30926392e+02 5.49373413e+02 5.67747864e+02 5.85619812e+02 6.04283142e+02 6.23865051e+02 6.42258057e+02 6.61588440e+02 6.82799805e+02 7.01833923e+02 7.21347961e+02 7.41875366e+02 7.62896729e+02 7.83698181e+02 8.04804688e+02 8.26111816e+02 8.50006714e+02 8.70825256e+02 8.89975403e+02 9.11214478e+02 9.33502869e+02 9.59613037e+02 9.82184143e+02 1.00136688e+03 1.02475134e+03 1.05069324e+03 1.07378308e+03 1.09637024e+03 1.11914209e+03 1.14233826e+03 1.17019958e+03 1.19515015e+03 1.21485266e+03 1.24188831e+03 1.26886487e+03 1.29071643e+03 1.31738428e+03 1.34475183e+03 1.36665503e+03 1.39278882e+03 1.42121777e+03 1.44151172e+03 1.46643652e+03 1.49617908e+03 1.52259387e+03 1.55091614e+03 1.57105920e+03 1.60181152e+03 1.62919495e+03 1.65295923e+03 1.68374329e+03 1.70776611e+03 1.73553723e+03 1.76644714e+03 1.78963757e+03 1.81235596e+03 1.84196057e+03 1.87003162e+03 1.89809424e+03 1.92751160e+03 1.95540723e+03 1.98045264e+03 2.01261975e+03 2.03863831e+03 2.05947241e+03 2.08814819e+03 2.11563867e+03 2.14565625e+03 2.17156274e+03 2.20557739e+03 2.22449341e+03 2.25125195e+03 2.29029150e+03 2.30695312e+03 2.33206934e+03 2.36998608e+03 2.40046362e+03 2.42728906e+03 2.44500903e+03 2.46975732e+03 2.50974878e+03 2.54009033e+03 2.56485376e+03 2.58457837e+03 2.60511670e+03 2.64177661e+03 2.67645825e+03 2.70475537e+03 2.71469702e+03 2.74007642e+03 2.78129224e+03 2.80496094e+03 2.82892847e+03 2.86862769e+03 2.88133813e+03 2.90407617e+03 2.93432275e+03 2.96057446e+03 2.99140234e+03 3.00855078e+03 3.04885229e+03 3.06922852e+03 3.08711548e+03 3.11970483e+03 3.13964795e+03 3.16832666e+03 3.19730054e+03 3.21851831e+03 3.24783936e+03 3.26664014e+03 3.29487109e+03 3.32158105e+03 3.34491968e+03 3.37035205e+03 3.38871484e+03 3.41859497e+03 3.44700684e+03 3.45628784e+03 3.49086011e+03 3.51635938e+03 3.52961353e+03 3.55222778e+03 3.57088623e+03 3.61036694e+03 3.62286279e+03 3.63978076e+03 3.66321484e+03 3.68327246e+03 3.71240869e+03 3.72452588e+03 3.74556958e+03 3.77094116e+03 3.79733545e+03 3.80956177e+03 3.82590698e+03 3.85418408e+03 3.86569946e+03 3.88991260e+03 3.91191138e+03 3.92336987e+03 3.94381250e+03 3.96764868e+03 3.97901880e+03 3.99647778e+03 4.01581494e+03 4.02568018e+03 5.31974316e+03 5.59603125e+03 6.09017334e+03 6.12380420e+03 6.15066406e+03 5.55286084e+03 5.32581445e+03 4.16266504e+03 4.17763428e+03 4.18819873e+03 4.20472803e+03 4.21855664e+03 4.23092627e+03 4.24760498e+03 4.25657031e+03 5.58456250e+03 4.44129248e+03 6.40543555e+03 5.56314795e+03 5.79457178e+03 5.56408057e+03 4.33848682e+03 4.34825098e+03 4.36197021e+03 5.32683496e+03 4.38065332e+03 5.45896094e+03 4.39735791e+03 4.40747559e+03 4.41289014e+03 4.41680859e+03 4.42750244e+03 4.44433838e+03 4.44857812e+03 4.45202637e+03 4.45746240e+03 4.46439990e+03 4.46874609e+03 4.47369531e+03 4.47882715e+03 4.48387695e+03 4.48749316e+03 4.49139307e+03 4.49534814e+03 4.49767041e+03 4.50129248e+03 4.50406738e+03 4.50626514e+03 4.50752588e+03 4.50918262e+03 4.51068750e+03 4.51132666e+03 4.51197607e+03 4.51205762e+03 4.51182764e+03 4.51088916e+03 4.51031592e+03 4.51030713e+03 4.50807275e+03 4.50539209e+03 4.50408887e+03 4.50134521e+03 4.49854297e+03 4.49528906e+03 4.49118799e+03 4.48805322e+03 4.48399854e+03 4.47867676e+03 4.47469434e+03 4.46892139e+03 4.46175781e+03 4.45817578e+03 4.45208105e+03 4.44494238e+03 4.43847803e+03 4.43065527e+03 4.42339209e+03 4.41749707e+03 4.40625635e+03 4.39809473e+03 4.39201416e+03 4.38097314e+03 4.37016650e+03 4.36034424e+03 4.35280664e+03 4.34365332e+03 4.32758496e+03 4.31772803e+03 4.31142822e+03 4.29813232e+03 4.28252441e+03 4.26655273e+03 4.26088379e+03 4.24867383e+03 4.23585596e+03 4.21701904e+03 4.20089746e+03 4.19803125e+03 4.18332178e+03 4.15952783e+03 4.14007666e+03 4.13088525e+03 4.11850928e+03 4.10443604e+03 4.08820068e+03 4.06890161e+03 4.05230273e+03 4.03353027e+03 4.01721021e+03 3.99963330e+03 3.98031250e+03 3.96709692e+03 3.94760083e+03 3.92713550e+03 3.90662793e+03 3.89517383e+03 3.87194507e+03 3.84769507e+03 3.83545850e+03 3.81346436e+03 3.78558252e+03 3.77013599e+03 3.75827246e+03 3.73737964e+03 3.71119287e+03 3.68329297e+03 3.67502612e+03 3.65092798e+03 3.62175684e+03 3.59279199e+03 3.57285010e+03 3.56198096e+03 3.53152905e+03 3.50243457e+03 3.48796973e+03 3.46998682e+03 3.44488867e+03 3.41982202e+03 3.38900635e+03 3.36412524e+03 3.34919360e+03 3.32622217e+03 3.28881494e+03 3.27545801e+03 3.25349756e+03 3.21880273e+03 3.19875903e+03 3.17144727e+03 3.13989062e+03 3.11709888e+03 3.10239185e+03 3.06844775e+03 3.03594922e+03 3.01631226e+03 3.00088599e+03 2.96721753e+03 2.93005371e+03 2.91081641e+03 2.89349316e+03 2.86020825e+03 2.83391650e+03 2.80674658e+03 2.78224707e+03 2.75646802e+03 2.71726929e+03 2.69240186e+03 2.66828711e+03 2.64619995e+03 2.61701123e+03 2.58832593e+03 2.56447437e+03 2.53013696e+03 2.50904297e+03 2.48172437e+03 2.44900415e+03 2.42281860e+03 2.39523999e+03 2.36827271e+03 2.33935474e+03 2.31870142e+03 2.28636426e+03 2.25568652e+03 2.23187695e+03 2.20143408e+03 2.17151392e+03 2.15418555e+03 2.12729541e+03 2.09424048e+03 2.05923584e+03 2.03119373e+03 2.01107800e+03 1.98947461e+03 1.95812109e+03 1.92275366e+03 1.89397986e+03 1.87389136e+03 1.85009631e+03 1.82485144e+03 1.78763037e+03 1.76080933e+03 1.73994812e+03 1.71130090e+03 1.68355005e+03 1.65876233e+03 1.62624902e+03 1.60163403e+03 1.57499866e+03 1.54978857e+03 1.52764648e+03 1.49746497e+03 1.47482886e+03 1.44661609e+03 1.41995825e+03 1.39774573e+03 1.36669287e+03 1.34163477e+03 1.31462024e+03 1.70427600e+03 1.74818481e+03 2.97285132e+03 3.65034473e+03 7.82700500e+05 -19553474. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -18657606. -18657606. -18657606. 0. 0. -670057472. 2.62148120e+03 6.47867126e+02 6.26042114e+02 7.67888794e+02 7.71712952e+02 7.91745605e+02 1.32814380e+03 1.03857471e+03 3.93993050e+06 7.44076750e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -32257340. -32257340. -32257340. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 12727925. 12727925. 12727925. 0. 0. 0. 0. 30247302. -12440534. -40506572. 78546784. 201744784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 10261072. -6.94920250e+06 5.95356797e+04 16085460. 22475532. -30726230. 4464497. -949169984. 4.55070350e+06 1.52777312e+06 122140848. -32310668. 19720868. 19720868. 0. 0. 0. 0. 0. 0. 0. 153645680. 153645680. 153645680. 0. 0. 30179786. -14955691. -14955691. -24728490. 9.36673062e+05 2.40003242e+04 1.99801453e+05 4674864. 3.86163469e+05 -11022960. -23343830. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.70130250e+06 7.23571191e+03 1.73279150e+03 1.64427759e+03 1.25500781e+03 1.28211707e+03 1.30484473e+03 1.33311011e+03 1.35830347e+03 1.38014050e+03 1.40732886e+03 1.43635242e+03 1.46243347e+03 1.48519543e+03 1.51424316e+03 2.02182141e+03 2.17371143e+03 2.12857178e+03 2.06643433e+03 1.64736279e+03 1.67483740e+03 1.70026550e+03 1.72556177e+03 1.75608118e+03 1.78700439e+03 1.80769250e+03 1.83091809e+03 1.86342664e+03 1.89381836e+03 1.92144739e+03 1.94591418e+03 1.97048303e+03 2.00281226e+03 2.03065759e+03 2.05652393e+03 2.08582275e+03 2.11115259e+03 2.79677539e+03 2.99268018e+03 3.27637524e+03 3.31872583e+03 3.36112769e+03 3.07822192e+03 2.96904321e+03 2.33397510e+03 2.36742017e+03 2.39360132e+03 2.41917017e+03 2.44343726e+03 2.47880225e+03 2.50666577e+03 2.53649683e+03 2.55865967e+03 2.58492334e+03 2.61442505e+03 2.64132300e+03 2.66619897e+03 2.70010571e+03 2.73686841e+03 2.75390674e+03 2.77447388e+03 2.80986206e+03 2.83053979e+03 2.86791821e+03 2.89507739e+03 2.91338745e+03 2.94241040e+03 2.96432739e+03 2.99115283e+03 3.02726562e+03 3.04931616e+03 3.08313135e+03 3.10713306e+03 3.12750513e+03 3.15326221e+03 3.17531323e+03 3.20105054e+03 3.23237793e+03 3.26032446e+03 3.27413867e+03 3.30552539e+03 3.33402026e+03 3.35560596e+03 3.38765796e+03 3.40181104e+03 3.42919629e+03 3.46201807e+03 3.47664355e+03 3.49716284e+03 3.52395825e+03 3.55580493e+03 3.57301050e+03 3.58840063e+03 3.61477295e+03 3.63960059e+03 3.66522241e+03 3.69146411e+03 3.70350122e+03 3.73021655e+03 3.75147168e+03 3.76680151e+03 3.79464771e+03 3.81739844e+03 3.83899487e+03 3.84867261e+03 3.86656152e+03 3.89706396e+03 3.91627124e+03 3.93645508e+03 3.96028320e+03 3.97668481e+03 3.98280298e+03 4.00548315e+03 4.03327808e+03 4.04498682e+03 4.06583740e+03 4.07999854e+03 4.09612988e+03 4.11291992e+03 4.12841211e+03 4.14598730e+03 4.16923047e+03 4.18138281e+03 4.19161914e+03 4.20748340e+03 4.22258545e+03 4.24136523e+03 4.25200342e+03 4.26629883e+03 4.28399951e+03 4.29186865e+03 4.30603125e+03 4.32026416e+03 4.33357422e+03 4.34249854e+03 4.35803955e+03 4.37007764e+03 4.37884961e+03 4.38962500e+03 4.39927246e+03 4.41341699e+03 4.42000732e+03 4.42984180e+03 4.43916309e+03 4.44872412e+03 4.45740576e+03 4.46328662e+03 4.47354541e+03 4.48431299e+03 4.48679297e+03 4.49724072e+03 4.50220557e+03 4.50691260e+03 4.51569971e+03 4.52091895e+03 4.52467188e+03 4.53019775e+03 4.53751367e+03 4.53902051e+03 4.54324316e+03 4.54857861e+03 4.55042822e+03 4.55300830e+03 4.55643799e+03 4.55865479e+03 4.56004736e+03 4.56202588e+03 4.56322852e+03 4.56407861e+03 4.56509082e+03 4.56499805e+03 4.56477490e+03 4.56391211e+03 4.56323535e+03 4.56264307e+03 4.56073291e+03 4.55872559e+03 4.55639990e+03 4.55441748e+03 4.55120801e+03 4.54655273e+03 4.54421582e+03 4.54164990e+03 4.53729932e+03 4.53084766e+03 4.52733203e+03 4.52303760e+03 4.51351514e+03 4.50945557e+03 4.50569922e+03 4.49764600e+03 4.48984131e+03 4.48285303e+03 4.47390137e+03 4.46655029e+03 4.45854297e+03 4.44470947e+03 4.43543408e+03 4.44067969e+03 4.43145166e+03 4.41158887e+03 4.39827002e+03 4.38397168e+03 4.37536865e+03 5.42254102e+03 5.43691357e+03 6.52098096e+03 6.49771484e+03 5.29305176e+03 6.76285400e+03 5.92413721e+03 1.02400156e+04 1.25541191e+04 1.25792939e+04 1.01280068e+04 6.30034619e+03 5.87105664e+03 5.49554736e+03 4.18202051e+03 5.16075732e+03 5.16597754e+03 6.20649951e+03 6.18864648e+03 6.14852588e+03 5.00855029e+03 4.96627490e+03 4.03277075e+03 5.19548828e+03 5.34571680e+03 5.98351758e+03 5.92758936e+03 5.90070117e+03 5.88206592e+03 5.85108545e+03 5.80674756e+03 5.77762256e+03 5.28743701e+03 4.99775293e+03 3.81674512e+03 3.80454810e+03 3.78304224e+03 3.75398950e+03 3.73385278e+03 3.71491138e+03 3.69264575e+03 3.66528882e+03 3.63549561e+03 3.61727051e+03 3.60425610e+03 3.57603906e+03 3.54473486e+03 3.52576318e+03 3.49943359e+03 3.46685840e+03 3.45689673e+03 3.44289575e+03 3.39689233e+03 3.40023047e+03 3.37695288e+03 3.33508350e+03 3.32095166e+03 3.29214893e+03 3.26045483e+03 3.24231885e+03 3.21487109e+03 3.17672949e+03 3.15787964e+03 3.13917993e+03 3.10625073e+03 3.07081787e+03 3.05413647e+03 3.02942065e+03 3.00084912e+03 2.96812891e+03 2.94752368e+03 2.92597974e+03 2.89871680e+03 2.86515112e+03 2.84186597e+03 2.81834277e+03 2.79312061e+03 2.75767944e+03 2.72820850e+03 2.70614038e+03 2.67768091e+03 2.65291895e+03 2.62348730e+03 2.59606860e+03 2.56762085e+03 2.53752173e+03 2.51262866e+03 2.48526025e+03 2.45738281e+03 2.42884229e+03 2.40107739e+03 2.37410986e+03 2.34327515e+03 2.31103223e+03 2.28993872e+03 2.25725171e+03 2.23241821e+03 2.20151343e+03 2.17290308e+03 2.14780835e+03 2.12176758e+03 2.09151343e+03 2.06227905e+03 2.03758740e+03 2.01211584e+03 1.98000391e+03 1.94825293e+03 1.92132751e+03 1.89744812e+03 1.87226172e+03 1.84608386e+03 1.81143018e+03 1.78123145e+03 1.76455566e+03 1.73406006e+03 1.71168579e+03 1.67852832e+03 1.64393298e+03 1.62799463e+03 1.59776196e+03 1.56607507e+03 1.54572925e+03 1.51853247e+03 1.49581250e+03 1.46672498e+03 1.43630359e+03 1.41325537e+03 1.38663953e+03 1.36176733e+03 1.33953162e+03 1.31172510e+03 1.28248352e+03 1.26143750e+03 1.23777869e+03 1.20969458e+03 1.19018213e+03 1.16244458e+03 1.13793921e+03 1.11794861e+03 1.09028577e+03 1.06559680e+03 1.04205652e+03 1.01998199e+03 9.96255981e+02 9.72858826e+02 9.50601257e+02 9.28593323e+02 9.05510254e+02 8.84101501e+02 8.60782227e+02 8.38785645e+02 8.19352661e+02 7.95806274e+02 7.74518188e+02 7.55805603e+02 7.35796082e+02 7.12282227e+02 6.91914307e+02 6.74100342e+02 6.54685913e+02 6.35097046e+02 6.16461426e+02 5.97556763e+02 5.76025696e+02 5.58184143e+02 5.41390015e+02 5.23327515e+02 5.05662628e+02 4.87783173e+02 4.70516937e+02 4.53731415e+02 4.37788971e+02 4.21804382e+02 4.05404175e+02 3.89993866e+02 3.74268005e+02 3.59075562e+02 3.43982849e+02 3.29495880e+02 3.15216400e+02 3.01278107e+02 2.87648193e+02 2.74235565e+02 2.61317627e+02 2.48240631e+02 2.35692780e+02 2.23627075e+02 2.12085159e+02 2.00665955e+02 1.89275284e+02 1.78307526e+02 1.67834137e+02 1.57632401e+02 1.47500793e+02 1.38029114e+02 1.28708588e+02 1.19649818e+02 1.11010399e+02 1.02624435e+02 9.47280502e+01 8.71741104e+01 7.98115540e+01 7.27806015e+01 6.60637131e+01 5.97931137e+01 5.38245621e+01 4.81030693e+01 4.27666359e+01 3.77845993e+01 3.31606522e+01 2.88516922e+01 2.48646927e+01 2.12489929e+01 1.79589787e+01 1.49859695e+01 1.23876400e+01 1.01584377e+01 8.23023415e+00 6.63746214e+00 5.40541506e+00 4.51295996e+00 3.96684217e+00 3.76274967e+00 3.90341377e+00 4.38974142e+00 5.21699333e+00 6.38854408e+00 7.90279627e+00 9.75008106e+00 1.19466534e+01 1.44857254e+01 1.73540115e+01 2.05378685e+01 2.41141758e+01 2.80478592e+01 3.22528877e+01 3.68300667e+01 4.17625275e+01 4.70322380e+01 5.26441460e+01 5.85804176e+01 6.48233337e+01 7.14391098e+01 7.83844910e+01 8.56184845e+01 9.31702194e+01 1.01159523e+02 1.09368164e+02 1.17916496e+02 1.26860527e+02 1.36142426e+02 1.45589523e+02 1.55540405e+02 1.65795547e+02 1.76273773e+02 1.86987503e+02 1.98108826e+02 2.09923798e+02 2.21703796e+02 2.33204285e+02 2.45544479e+02 2.58814362e+02 2.72062592e+02 2.85000671e+02 2.98186981e+02 3.12355957e+02 3.27021545e+02 3.41612732e+02 3.55889313e+02 3.70989929e+02 3.86346222e+02 4.01864624e+02 4.18363190e+02 4.34833466e+02 4.50318054e+02 4.67628387e+02 4.84733521e+02 5.01807007e+02 5.19804565e+02 5.37524963e+02 5.55496948e+02 5.74045593e+02 5.92579529e+02 6.11854248e+02 6.30389404e+02 6.49447449e+02 6.69381348e+02 6.89386047e+02 7.09681458e+02 7.29997009e+02 7.49530762e+02 7.71508423e+02 7.93229858e+02 8.14834839e+02 8.36238464e+02 8.56994080e+02 8.80304932e+02 9.00316162e+02 9.21469360e+02 9.45639282e+02 9.69240173e+02 9.92436951e+02 1.01329987e+03 1.03758972e+03 1.06434167e+03 1.08785168e+03 1.10629272e+03 1.13074109e+03 1.15633557e+03 1.18237170e+03 1.20598975e+03 1.23158374e+03 1.25620020e+03 1.27918787e+03 1.30623364e+03 1.33476843e+03 1.36255298e+03 1.38091577e+03 1.40479578e+03 1.43660107e+03 1.45739783e+03 1.48522266e+03 1.51252698e+03 1.53607922e+03 1.56704138e+03 1.59105103e+03 1.61921741e+03 1.64939990e+03 1.67184863e+03 1.70186865e+03 1.72656970e+03 1.75265161e+03 1.78496362e+03 1.80652307e+03 1.83373535e+03 1.86569226e+03 1.88892029e+03 1.92270862e+03 1.94883105e+03 1.96968982e+03 2.00499939e+03 2.03599817e+03 2.05300439e+03 2.08359912e+03 2.11808228e+03 2.14240698e+03 2.16499487e+03 2.19538794e+03 2.23131274e+03 2.24783447e+03 2.27883716e+03 2.30561304e+03 2.33576392e+03 2.36655249e+03 2.39450586e+03 2.42844946e+03 2.44886060e+03 2.47172192e+03 2.50089648e+03 2.54085693e+03 2.56431982e+03 2.59545605e+03 2.61345801e+03 2.64036328e+03 2.66672485e+03 2.70313428e+03 2.73907251e+03 2.74585303e+03 2.76972559e+03 2.81259839e+03 2.83948438e+03 2.86597510e+03 2.89227124e+03 2.90804956e+03 2.94313599e+03 2.96659302e+03 2.99465332e+03 3.02674512e+03 3.04887988e+03 3.08650903e+03 3.10472437e+03 3.11734155e+03 3.15521802e+03 3.17534961e+03 3.20142310e+03 3.23655811e+03 3.25786279e+03 3.28035278e+03 3.30426831e+03 3.33363281e+03 3.35509009e+03 3.38604443e+03 3.40703296e+03 3.42524390e+03 3.45897119e+03 3.48253467e+03 3.49625366e+03 3.52616040e+03 3.55112207e+03 3.57060352e+03 3.59323291e+03 3.61375488e+03 3.64676074e+03 3.65950562e+03 3.68068433e+03 3.70424292e+03 3.72625732e+03 3.75074756e+03 3.76611377e+03 3.78903613e+03 3.81366113e+03 4.97602686e+03 5.24525146e+03 5.76123779e+03 5.80354541e+03 5.83287451e+03 5.86850244e+03 5.89813770e+03 5.91562451e+03 5.93998389e+03 5.97101562e+03 5.49064551e+03 5.21312207e+03 4.06187476e+03 4.07290771e+03 5.07232275e+03 5.13020117e+03 6.19823193e+03 6.21692139e+03 6.24901367e+03 5.12957861e+03 5.13365674e+03 5.44572168e+03 5.76058301e+03 6.31397119e+03 5.80175781e+03 6.35023047e+03 5.81257275e+03 5.90462158e+03 5.58879785e+03 5.34896875e+03 4.37135498e+03 6.51628271e+03 5.59518701e+03 5.35926758e+03 5.36024902e+03 4.38983740e+03 4.39661670e+03 4.41270117e+03 5.75929297e+03 4.42919482e+03 5.82892188e+03 4.44979297e+03 4.45945996e+03 4.46404150e+03 4.47381250e+03 4.48357422e+03 4.48770947e+03 4.49604053e+03 4.50297900e+03 4.50809912e+03 4.51496045e+03 4.51925098e+03 4.52457568e+03 4.53096680e+03 4.53617432e+03 4.53852637e+03 4.54345020e+03 4.54847705e+03 4.54965430e+03 4.55284717e+03 4.55622119e+03 4.55818848e+03 4.55973047e+03 4.56146191e+03 4.56292285e+03 4.56368604e+03 4.56432129e+03 4.56441895e+03 4.56425586e+03 4.56351172e+03 4.56301611e+03 4.56284375e+03 4.56069580e+03 4.55776025e+03 4.55640967e+03 4.55434961e+03 4.55100049e+03 4.54638232e+03 4.54363232e+03 4.54167285e+03 4.53704541e+03 4.52992871e+03 4.52664941e+03 4.52172119e+03 4.51471387e+03 4.51108740e+03 4.50436914e+03 4.49694629e+03 4.49163672e+03 4.48372754e+03 4.47610156e+03 4.46707812e+03 4.45663623e+03 4.45103027e+03 4.44495410e+03 4.43429541e+03 4.42032666e+03 4.41024609e+03 4.40320654e+03 4.39213379e+03 4.38068066e+03 4.37136865e+03 4.36348535e+03 4.35027539e+03 4.33044873e+03 4.31480957e+03 4.31122021e+03 4.30267725e+03 4.28639502e+03 4.26608838e+03 4.25183008e+03 4.24340381e+03 4.23105225e+03 4.21285547e+03 4.19160547e+03 4.17939111e+03 4.16607715e+03 4.15286768e+03 4.13629443e+03 4.11675293e+03 4.10239209e+03 4.08208618e+03 4.06096338e+03 4.05170020e+03 4.03620776e+03 4.01133960e+03 3.99854370e+03 3.97364624e+03 3.95696289e+03 3.93995728e+03 3.91914551e+03 3.89721875e+03 3.87444971e+03 3.85683154e+03 3.83368311e+03 3.81473584e+03 3.80062646e+03 3.78196411e+03 3.75994751e+03 3.73340601e+03 3.71291602e+03 3.69621167e+03 3.66760010e+03 3.64044849e+03 3.61929639e+03 3.60092944e+03 3.57755469e+03 3.54948462e+03 3.52992847e+03 3.51320654e+03 3.48831958e+03 3.45866187e+03 3.43364404e+03 3.40998560e+03 3.38323853e+03 3.36281055e+03 3.33625952e+03 3.31567944e+03 3.29064868e+03 3.25718286e+03 3.24007349e+03 3.21124292e+03 3.18155859e+03 3.15162134e+03 3.13508545e+03 3.10935254e+03 3.07295532e+03 3.05415063e+03 3.03520264e+03 3.00312354e+03 2.96287842e+03 2.94521875e+03 2.93584229e+03 2.89910718e+03 2.86103442e+03 2.83851221e+03 2.82274219e+03 2.78794482e+03 2.75031323e+03 2.72553735e+03 2.70244409e+03 2.68065161e+03 2.64371851e+03 2.62135913e+03 2.59386011e+03 2.56158008e+03 2.54073608e+03 2.51395508e+03 2.47965991e+03 2.45775122e+03 2.42384448e+03 2.38916187e+03 2.35819067e+03 2.98779761e+03 3.04284033e+03 3.41573682e+03 3.37294434e+03 3.11784473e+03 2.88989331e+03 2.17924585e+03 2.15305518e+03 2.11938086e+03 2.08697729e+03 2.05960620e+03 2.03723767e+03 2.01168066e+03 1.98467322e+03 1.95133630e+03 1.91855579e+03 1.89242456e+03 1.87166687e+03 1.84644727e+03 1.81223975e+03 1.78571033e+03 1.76126843e+03 1.73396436e+03 1.71101709e+03 2.12644165e+03 1.63764795e+03 2.14450806e+03 1.60179553e+03 1.57493677e+03 1.55241345e+03 1.52073901e+03 1.49458643e+03 1.46630591e+03 1.43741748e+03 1.41324426e+03 1.38889453e+03 1.36238391e+03 1.33626917e+03 1.30890881e+03 1.27776233e+03 1.62599500e+03 2.24415234e+03 1.50785293e+04 -19553474. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -18657606. -18657606. -18657606. 0. 0. -50522692. 4.03750708e+03 1.00698303e+03 9.62168518e+02 1.36887524e+03 1.52998730e+03 1.93237634e+03 1.66651855e+03 1.44145813e+03 3.93993050e+06 7.44076750e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 778711424. 778711424. 778711424. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 12727925. 12727925. 12727925. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -198920800. -198920800. -198920800. 0. 0. 0. 0. 0. 0. 0. 0. 0. 10261072. -6.94920250e+06 5.95356797e+04 16085460. 22475532. -30726230. 4464497. -949169984. 5.36350403e+02 7.49841736e+02 3.39260083e+03 6.19126221e+02 3.03437402e+03 3.03437402e+03 4.35720050e+06 63911824. 63911824. 39548096. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.70130250e+06 7.23571191e+03 1.83044971e+03 1.86703906e+03 1.90412939e+03 1.73150366e+03 1.68722119e+03 1.35590808e+03 1.38326746e+03 1.40654175e+03 1.43393152e+03 1.46268469e+03 1.96124316e+03 2.13013135e+03 2.29415332e+03 3.86580811e+03 5.09516260e+03 4.43171191e+03 3.74336279e+03 2.50180029e+03 2.54018213e+03 2.57460034e+03 2.61722583e+03 2.66194922e+03 2.70149805e+03 2.74179199e+03 2.49111328e+03 2.42252026e+03 1.92740698e+03 1.95388293e+03 1.98368835e+03 2.00371436e+03 2.03527393e+03 2.06186255e+03 2.74383252e+03 2.95436426e+03 3.20390625e+03 5.34313623e+03 6.93326123e+03 -2107832. 361611392. 3.65511175e+06 6.49792725e+03 5.42887500e+03 3.54013037e+03 3.57799951e+03 3.62754810e+03 3.66724658e+03 3.69447949e+03 3.74655664e+03 3.79659155e+03 3.46568799e+03 3.33375391e+03 2.63013672e+03 2.66042798e+03 2.68059863e+03 2.71186548e+03 2.74256812e+03 2.77559863e+03 2.80211206e+03 2.82392578e+03 2.85385083e+03 2.87438062e+03 2.91117847e+03 2.94647437e+03 2.96631079e+03 2.99245020e+03 3.01220288e+03 3.03612280e+03 3.07269873e+03 3.10422510e+03 3.13789014e+03 3.16039795e+03 3.17819971e+03 3.19947021e+03 3.23007812e+03 3.26021509e+03 3.28484009e+03 3.30897754e+03 3.32694580e+03 3.35427539e+03 3.38657520e+03 3.41376831e+03 3.43928174e+03 3.45857471e+03 3.47890430e+03 3.50895972e+03 3.53137451e+03 3.55526392e+03 3.57565063e+03 3.61107227e+03 3.63494434e+03 3.64810498e+03 3.67365161e+03 3.69958423e+03 3.72351465e+03 3.74849976e+03 3.75678223e+03 3.78495825e+03 3.81045044e+03 3.82330615e+03 3.85119019e+03 3.87679785e+03 3.89818042e+03 3.90701562e+03 3.92359351e+03 3.95667725e+03 3.97950098e+03 3.99054321e+03 4.01569727e+03 4.04034937e+03 4.04494922e+03 4.07048340e+03 4.09252100e+03 4.10555566e+03 4.12850879e+03 4.14184424e+03 4.15839404e+03 4.17441309e+03 4.18953906e+03 4.21173291e+03 4.23064697e+03 4.24256689e+03 4.25643555e+03 4.27375244e+03 4.29089062e+03 4.30225342e+03 4.31747754e+03 4.33158887e+03 4.34726123e+03 4.35926416e+03 4.37004395e+03 4.38422461e+03 4.39732568e+03 4.40657227e+03 4.42221631e+03 4.43419824e+03 4.44343945e+03 4.45487354e+03 4.46607715e+03 4.47851221e+03 4.48482080e+03 4.49557812e+03 4.50474023e+03 4.51334375e+03 4.52408838e+03 4.52967383e+03 4.53858350e+03 4.54863428e+03 4.55389600e+03 4.56182227e+03 4.56838672e+03 4.57561182e+03 4.58202295e+03 4.58555957e+03 4.59108350e+03 4.59783301e+03 4.60221387e+03 4.60484668e+03 4.60945996e+03 4.61422656e+03 4.61667627e+03 4.61905811e+03 4.62231104e+03 4.62445166e+03 4.62628809e+03 4.62802539e+03 4.62880127e+03 4.62981592e+03 4.63060449e+03 4.63059131e+03 4.63035498e+03 4.62949365e+03 4.62893164e+03 4.62832812e+03 4.62637402e+03 4.62416943e+03 4.62090869e+03 4.61863428e+03 4.61660010e+03 4.61172803e+03 4.60864648e+03 4.60635791e+03 4.60227539e+03 4.59617725e+03 4.59120459e+03 4.58557861e+03 4.57842041e+03 4.57353613e+03 4.56955371e+03 4.56187402e+03 4.55429883e+03 4.54728564e+03 4.53608447e+03 4.52893408e+03 4.52392188e+03 4.51310352e+03 4.50224023e+03 4.49625537e+03 4.48586377e+03 4.47415039e+03 4.46353662e+03 4.44912012e+03 4.43958838e+03 5.79033496e+03 6.13277344e+03 6.66044922e+03 6.64454053e+03 6.06664746e+03 5.70678516e+03 4.35219385e+03 5.37506592e+03 5.38601758e+03 6.47317676e+03 6.44698535e+03 6.42221582e+03 5.24312402e+03 5.21175488e+03 5.42975195e+03 7.57099658e+03 1.29064297e+04 -9.01588688e+05 1.37221462e+06 -3.89348312e+05 1.21623838e+04 1.00017324e+04 6.13329150e+03 9.67563086e+03 1.10278721e+04 3.32580219e+05 5.40147650e+06 8779364. -1901297. -1.24552362e+06 8.25727150e+06 1.18984072e+04 9.00494727e+03 5.79415674e+03 5.76642334e+03 4.98508887e+03 5.71154883e+03 4.76706299e+03 5.63863965e+03 5.60879639e+03 5.57212402e+03 5.54122510e+03 4.74274023e+03 4.63084082e+03 4.53083398e+03 3.63327124e+03 5.35401465e+03 3.55671460e+03 4.57615283e+03 3.50144678e+03 3.48205762e+03 3.54514136e+03 3.44842236e+03 3.42002173e+03 3.42748706e+03 3.36871875e+03 3.34344678e+03 3.32925610e+03 3.29592456e+03 3.27048926e+03 3.24358008e+03 3.22197949e+03 3.19523120e+03 3.99165942e+03 3.21242700e+03 3.84458130e+03 4.06616382e+03 3.85821313e+03 4.52784033e+03 4.48423975e+03 4.45202246e+03 4.41368408e+03 4.37651660e+03 4.33287988e+03 4.28909082e+03 4.25605762e+03 4.21407910e+03 4.16586572e+03 4.11328418e+03 4.09185669e+03 4.03877661e+03 3.99587817e+03 3.97015186e+03 3.91203101e+03 3.87274487e+03 3.83225439e+03 3.79195459e+03 3.51397876e+03 3.26529053e+03 2.45906323e+03 2.43153662e+03 2.40226440e+03 2.37578906e+03 2.34149365e+03 2.31953833e+03 2.28903345e+03 2.26125415e+03 2.22659790e+03 2.20178638e+03 2.17409985e+03 2.14450586e+03 2.11734253e+03 2.09092383e+03 2.06369019e+03 2.03173254e+03 2.00328052e+03 1.97604980e+03 1.94703784e+03 1.91744897e+03 1.89180286e+03 1.86882349e+03 1.83625842e+03 1.80605090e+03 1.78331970e+03 1.75717676e+03 1.72969189e+03 1.69551123e+03 1.67039160e+03 1.64799805e+03 1.61416650e+03 1.58627893e+03 1.56244165e+03 1.53849573e+03 1.51234680e+03 1.48540247e+03 1.45651147e+03 1.42690515e+03 1.40286304e+03 1.38022791e+03 1.35394482e+03 1.32764343e+03 1.29853003e+03 1.27327869e+03 1.25160547e+03 1.22740747e+03 1.20215869e+03 1.17628455e+03 1.15211536e+03 1.12739185e+03 1.10304163e+03 1.07881238e+03 1.05283252e+03 1.03155029e+03 1.00938171e+03 9.84975891e+02 9.61756836e+02 9.38471252e+02 9.15849670e+02 8.93835022e+02 8.69641418e+02 8.48267334e+02 8.28499207e+02 8.04776184e+02 7.83459656e+02 7.64967041e+02 7.43439819e+02 7.20231873e+02 6.99378662e+02 6.81546692e+02 6.62747375e+02 6.41021362e+02 6.21825562e+02 6.03913208e+02 5.82804138e+02 5.65085510e+02 5.47017090e+02 5.28440735e+02 5.11838684e+02 4.93173523e+02 4.76029419e+02 4.58895569e+02 4.42003662e+02 4.26491943e+02 4.09959778e+02 3.93882690e+02 3.78010254e+02 3.63197937e+02 3.48179077e+02 3.33078125e+02 3.18807526e+02 3.04913879e+02 2.90705597e+02 2.77267303e+02 2.64110931e+02 2.51158188e+02 2.38673004e+02 2.26347458e+02 2.14527725e+02 2.02885452e+02 1.91507309e+02 1.80555649e+02 1.69913330e+02 1.59406433e+02 1.49428894e+02 1.39896164e+02 1.30380661e+02 1.21373047e+02 1.12665977e+02 1.04130661e+02 9.61208801e+01 8.85389938e+01 8.11998672e+01 7.41182556e+01 6.73933029e+01 6.10519295e+01 5.50361938e+01 4.93476791e+01 4.39944687e+01 3.90054588e+01 3.43552170e+01 3.00409794e+01 2.60681095e+01 2.24506912e+01 1.91779251e+01 1.62186050e+01 1.36505404e+01 1.14545937e+01 9.56187630e+00 8.00707626e+00 6.81791401e+00 5.96976471e+00 5.47618723e+00 5.33084488e+00 5.52959585e+00 6.08648348e+00 6.98665047e+00 8.23933983e+00 9.83672714e+00 1.17644615e+01 1.40531702e+01 1.66837749e+01 1.96626911e+01 2.29774685e+01 2.66662979e+01 3.07289066e+01 3.50502701e+01 3.97501717e+01 4.47993965e+01 5.02187157e+01 5.59549522e+01 6.19942436e+01 6.84120102e+01 7.52059860e+01 8.22698822e+01 8.95939484e+01 9.73386383e+01 1.05513252e+02 1.13902596e+02 1.22548164e+02 1.31673416e+02 1.41292358e+02 1.50870499e+02 1.61013748e+02 1.71624008e+02 1.82057968e+02 1.92995224e+02 2.04336273e+02 2.16377396e+02 2.28429260e+02 2.40374268e+02 2.53005478e+02 2.66231476e+02 2.79551666e+02 2.92834381e+02 3.06494568e+02 3.21081573e+02 3.35533295e+02 3.50056061e+02 3.65346558e+02 3.80543915e+02 3.95736908e+02 4.11683746e+02 4.28790009e+02 4.44675476e+02 4.61138245e+02 4.79710785e+02 4.97023438e+02 5.12820129e+02 5.31265686e+02 5.49919617e+02 5.66821045e+02 5.86813416e+02 6.07040833e+02 6.25875061e+02 6.43185364e+02 6.63463867e+02 6.85401123e+02 7.04399353e+02 7.24479248e+02 7.45708740e+02 7.65936951e+02 7.87920654e+02 8.09039429e+02 8.31217590e+02 8.53021484e+02 8.74158997e+02 8.97560669e+02 9.18868530e+02 9.41406006e+02 9.63462097e+02 9.87859314e+02 1.01412366e+03 1.03311060e+03 1.05578198e+03 1.08230957e+03 1.10753394e+03 1.13119934e+03 1.15436206e+03 1.17637097e+03 1.20504089e+03 1.22984534e+03 1.25358435e+03 1.28107495e+03 1.30518958e+03 1.33220374e+03 1.35587463e+03 1.38486389e+03 1.41071680e+03 1.43160242e+03 1.46029871e+03 1.48459448e+03 1.51477795e+03 1.54127844e+03 1.56345679e+03 1.59829578e+03 1.62127612e+03 1.64611951e+03 1.67974487e+03 1.69973975e+03 1.73202734e+03 1.75672168e+03 1.78353406e+03 1.81672266e+03 1.83924756e+03 1.86778894e+03 1.90057581e+03 1.92190906e+03 1.95393677e+03 1.98341968e+03 2.00311475e+03 2.04124121e+03 2.07038184e+03 2.08392529e+03 2.12289209e+03 2.15176611e+03 2.17790601e+03 2.20231714e+03 2.23139014e+03 2.26762769e+03 2.28813989e+03 2.31932056e+03 2.34856445e+03 2.37967749e+03 2.40455859e+03 2.42826001e+03 2.46247314e+03 2.48797461e+03 2.51564282e+03 2.54910913e+03 2.57976147e+03 2.59911426e+03 3.42990771e+03 3.68027979e+03 3.59173120e+03 4.03378223e+03 3.78966968e+03 4.12222266e+03 4.16451807e+03 4.19458252e+03 4.24638086e+03 3.64125830e+03 3.76370996e+03 3.68011084e+03 4.00841309e+03 4.45346094e+03 4.48384814e+03 4.52132227e+03 3.87057983e+03 3.88850024e+03 3.20082617e+03 3.93521118e+03 4.37627246e+03 4.06592798e+03 4.79632568e+03 4.22092822e+03 4.88539502e+03 4.93013135e+03 4.96239941e+03 4.99157861e+03 5.03716602e+03 5.07404980e+03 5.10554980e+03 5.15272217e+03 5.17880127e+03 5.22493506e+03 5.25932764e+03 5.27981689e+03 5.32931592e+03 5.37020947e+03 5.39707080e+03 4.97384814e+03 5.46082227e+03 5.10760205e+03 5.53426611e+03 5.56200586e+03 5.59925293e+03 5.63086572e+03 5.66249805e+03 5.69206348e+03 5.73183838e+03 5.76390088e+03 9.43783887e+03 1.19472988e+04 -5.19399250e+06 7.52440750e+05 3.06865150e+06 -16891350. -5.54176550e+06 1.16204258e+04 1.19711182e+04 1.23321445e+04 1.16095801e+04 9.45010156e+03 6.13503174e+03 6.16468262e+03 9.63804883e+03 1.23141543e+04 -2.33879525e+06 2.42576094e+05 -1.21797525e+06 1.29557109e+04 7.69213232e+03 6.85078662e+03 5.36847754e+03 6.45422412e+03 5.30855420e+03 6.49566455e+03 5.39208398e+03 5.35838477e+03 5.35481885e+03 5.70446240e+03 4.46969385e+03 6.66300293e+03 6.32032080e+03 6.18539502e+03 5.83099268e+03 4.45211182e+03 4.46502539e+03 4.47808252e+03 4.48559375e+03 4.49422119e+03 4.50452588e+03 4.51471680e+03 4.52387402e+03 4.52877295e+03 4.53770117e+03 4.54732031e+03 4.55445996e+03 4.56139209e+03 4.56826465e+03 4.57464746e+03 4.58078613e+03 4.58472266e+03 4.59135645e+03 4.59795557e+03 4.60054639e+03 4.60360889e+03 4.60931592e+03 4.61391748e+03 4.61597412e+03 4.61927344e+03 4.62193506e+03 4.62323730e+03 4.62537402e+03 4.62713428e+03 4.62822070e+03 4.62923584e+03 4.62977344e+03 4.62982764e+03 4.62957666e+03 4.62874756e+03 4.62811133e+03 4.62774121e+03 4.62578125e+03 4623. 4.62057178e+03 4.61860352e+03 4.61590430e+03 4.61091846e+03 4.60821094e+03 4.60553418e+03 4.60148389e+03 4.59553711e+03 4.58983252e+03 4.58449268e+03 4.57885449e+03 4.57299072e+03 4.56789404e+03 4.56036475e+03 4.55503076e+03 4.54646777e+03 4.53608936e+03 4.53113818e+03 4.52245264e+03 4.51259619e+03 4.50350000e+03 4.49481592e+03 4.48280713e+03 4.47546680e+03 4.46784570e+03 4.45200537e+03 4.44127344e+03 4.42770898e+03 4.42191113e+03 4.40862793e+03 4.39078760e+03 4.37880908e+03 4.37176611e+03 4.35708350e+03 4.34254346e+03 4.32777686e+03 4.31193457e+03 4.30083301e+03 4.28769482e+03 4.27469531e+03 4.25346484e+03 4.23631494e+03 4.22253564e+03 4.21089551e+03 4.19049902e+03 4.17350488e+03 4.16543506e+03 4.14418750e+03 4.11571045e+03 4.10020557e+03 4.08841406e+03 4.06083789e+03 4.04797168e+03 4.03754272e+03 4.01144214e+03 3.98219897e+03 3.97222754e+03 3.96117212e+03 3.92899878e+03 3.90595264e+03 3.88590942e+03 3.87160059e+03 3.85400854e+03 3.83022583e+03 3.80253540e+03 3.77714575e+03 3.75973071e+03 3.74654248e+03 3.71742700e+03 3.69555029e+03 3.66515942e+03 3.64253711e+03 3.63291138e+03 3.59887573e+03 3.57357178e+03 3.55691333e+03 3.53281543e+03 3.50769043e+03 3.47963037e+03 3.45079663e+03 3.42978491e+03 3.40736890e+03 3.37952344e+03 3.36148389e+03 3.33330200e+03 3.30170093e+03 3.27848315e+03 3.25406665e+03 3.22315015e+03 3.19724976e+03 3.17794531e+03 3.15216333e+03 3.11466870e+03 3.09081665e+03 3.07569092e+03 3.04186328e+03 3.00468677e+03 2.98123901e+03 2.96351807e+03 2.93709058e+03 2.89869360e+03 2.87687451e+03 2.85147290e+03 2.82258911e+03 2.79189868e+03 2.76716357e+03 2.74418774e+03 2.71044360e+03 2.67808081e+03 2.65699219e+03 2.61847998e+03 2.59262988e+03 2.56516919e+03 3.21499219e+03 3.29766162e+03 3.71032178e+03 3.65514648e+03 3.60062598e+03 3.55832544e+03 5.58589209e+03 6.45227100e+03 7342948. -6257809. 7.08647803e+03 5.44781055e+03 3.29058984e+03 3.25012476e+03 3.19334009e+03 3.16048730e+03 3.12037964e+03 3.08255713e+03 3.02811890e+03 2.99248633e+03 2.95562988e+03 2.90003784e+03 2.86312988e+03 2.82784692e+03 2.77754370e+03 2.73872925e+03 2.55540137e+03 2.64917920e+03 2.34013379e+03 2.59618848e+03 3.83134058e+03 2.47936328e+03 4.16603125e+03 2.43580737e+03 2.40887134e+03 2.36668481e+03 2.30687183e+03 2.12424268e+03 1.96241589e+03 1.45780017e+03 1.42821777e+03 1.76266101e+03 1.78830542e+03 2.02053687e+03 1.98043567e+03 1.94139307e+03 1.88798669e+03 3.00601416e+03 1.50785293e+04 -19553474. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.24914875e+05 -3.24914875e+05 -3.24914875e+05 0. 0. 0. 0. -18657606. -18657606. -18657606. 0. 0. -55990996. 4.24583350e+06 5.49655188e+05 5.59019312e+05 -24067328. 70125600. -32333158. -32333158. -32333158. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 778711424. 778711424. 778711424. 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. 68003496. 68003496. 68003496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -198920800. -198920800. -198920800. 0. 0. 0. 0. 0. 0. 0. 0. 0. 10261072. -6.94920250e+06 5.95356797e+04 16085460. 22475532. -30726230. 4464497. -949169984. 5.36350403e+02 7.49841736e+02 3.39260083e+03 6.19126221e+02 3.03437402e+03 3.03437402e+03 4.35720050e+06 63911824. 63911824. 39548096. 0. 0. 0. 0. 42786116. 42786116. 42786116. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.10557491e+09 -9.10557491e+09 -9.10557491e+09 0. 0. 0. 0. 0. 0. 0. 43699436. 43699436. 43699436. 0. -34302968. 1.74063112e+06 3.46943938e+05 3.86972950e+06 3.98657475e+06 3.58150488e+03 3.05345117e+03 2.06539819e+03 2.10833350e+03 2.14649243e+03 2.18710767e+03 2.22333765e+03 3.78860742e+03 5.08322803e+03 493434. 1.71369875e+06 19267934. 17098978. 2.06678750e+04 5.32802979e+03 2.42915275e+06 3.85092950e+06 3880984. 5.14558350e+03 5.44151318e+03 5.75336035e+03 5.21246094e+03 4.41460498e+03 2.92647412e+03 2.97087988e+03 3.01064990e+03 3.04346729e+03 3.09372046e+03 3.13400342e+03 3.19509204e+03 5.19508398e+03 7.03469434e+03 2.40404824e+04 -539095360. 115016168. 0. 0. 5869157. 2.85609414e+04 7.33434668e+03 -9995063. -10143668. -3240292. 10659016. 4665596. 1.40627288e+06 7.32572168e+03 6.10433350e+03 3.98427686e+03 3.62896680e+03 3.50640527e+03 2.76409009e+03 2.79015771e+03 2.82808643e+03 2.84874365e+03 2.87560449e+03 2.91128711e+03 2.93598975e+03 2.96615259e+03 2.99599097e+03 3.02070654e+03 3.05045581e+03 3.06459253e+03 3.09547070e+03 3.12865161e+03 3.15669092e+03 3.19036401e+03 3.21599878e+03 3.24047803e+03 3.25891260e+03 3.29282715e+03 3.31763184e+03 4.36212939e+03 4.65319971e+03 4.56170020e+03 4.38261475e+03 3.44797339e+03 3.47625171e+03 3.50297583e+03 3.52513550e+03 4.62026318e+03 4.92583838e+03 4.85391895e+03 4.65868311e+03 3.64414575e+03 3.67248486e+03 3.69491748e+03 3.71867041e+03 3.74464990e+03 3.76182764e+03 3.79169678e+03 3.81515747e+03 3.82984375e+03 3.85198145e+03 3.88602197e+03 3.89757129e+03 3.91758008e+03 3.94947339e+03 3.97148975e+03 3.97813159e+03 4.00138916e+03 4.03078198e+03 4.05246558e+03 4.06745068e+03 4.08458423e+03 4.10821338e+03 4.11977930e+03 4.14400488e+03 4.16420264e+03 4.18227197e+03 4.20469238e+03 4.21821924e+03 4.23561230e+03 4.25523438e+03 4.26853174e+03 4.28714941e+03 4.30605566e+03 4.31954443e+03 4.33277002e+03 4.35091553e+03 4.36705322e+03 4.38003955e+03 4.39614209e+03 4.40771191e+03 4.42237109e+03 4.43740283e+03 4.44971045e+03 4.46335889e+03 4.47531494e+03 4.48762842e+03 4.50224756e+03 4.51310449e+03 4.52399854e+03 4.53308008e+03 4.54569971e+03 4.55978809e+03 4.56520605e+03 4.57605664e+03 4.58584229e+03 4.59421338e+03 4.60377637e+03 4.61216895e+03 4.62034131e+03 4.62936719e+03 4.63422461e+03 4.64251123e+03 4.65117188e+03 4.65582715e+03 4.66363184e+03 4.66862305e+03 4.67248877e+03 4.67786523e+03 4.68210303e+03 4.68644971e+03 4.69054346e+03 4.69534570e+03 4.69893945e+03 4.70101904e+03 4.70330762e+03 4.70585889e+03 4.70783105e+03 4.70917432e+03 4.71012402e+03 4.71123926e+03 4.71173975e+03 4.71176270e+03 4.71143555e+03 4.71059277e+03 4.71002637e+03 4.70922314e+03 4.70718799e+03 4.70472510e+03 4.70150537e+03 4.69892529e+03 4.69681982e+03 4.69280566e+03 4.68932520e+03 4.68569434e+03 4.68141162e+03 4.67660986e+03 4.67189990e+03 4.66419092e+03 4.65887158e+03 4.65230469e+03 4.64649951e+03 4.64138477e+03 4.63324463e+03 4.62453564e+03 4.61498584e+03 4.60799023e+03 4.60215967e+03 4.59181689e+03 4.57906494e+03 4.57294922e+03 4.56407666e+03 4.55207080e+03 4.54038525e+03 4.52790186e+03 4.51932959e+03 4.50857373e+03 4.49544482e+03 4.48206348e+03 4.47170312e+03 4.45871826e+03 4.44217529e+03 4.42686084e+03 5.79525977e+03 6.14029443e+03 6.64320898e+03 6.61853418e+03 6.59607666e+03 5.94513184e+03 5.62650000e+03 5.32715039e+03 8.46118945e+03 6.42113623e+03 1.25540029e+04 1.23634414e+04 -3.89348312e+05 -9.85765312e+05 6.93837812e+05 4.26318867e+04 3.08830080e+09 2.34924262e+09 0. 0. 0. 0. 0. 0. 56720204. 5.75220234e+04 1.34240967e+04 3.17325438e+05 1.89798125e+04 1.35392510e+04 8.38892285e+03 1326454. 3.27268008e+04 4.02774453e+04 1.34375625e+06 1.31700566e+04 9.49220801e+03 7.90935205e+03 6.17235645e+03 1.07801523e+04 5.82154199e+03 8.84363379e+03 5.28075830e+03 5.26806641e+03 5.82042969e+03 5.20681982e+03 5.14566943e+03 4.58447021e+03 5.12216650e+03 5.03929688e+03 5.08621094e+03 5.03277441e+03 4.92119189e+03 4.89980811e+03 4.92620068e+03 4.86701709e+03 7.21855078e+03 5.37015381e+03 6.66788574e+03 8.67306055e+03 7.21133789e+03 9.09284375e+03 3.46019531e+04 5.61396812e+05 1.18445562e+06 862841. -3234621. -11270646. -5178627. -3011321. -14215858. 2.39761450e+06 5.48749150e+06 2852853. -2.01192738e+06 -1.96299588e+06 -2.47023025e+06 -6229155. -5.80058150e+06 4580287. 8.09653613e+03 6.17486572e+03 3.72308374e+03 3.48460522e+03 3.21798828e+03 2.41161938e+03 2.37993164e+03 2.35314136e+03 2.32279053e+03 2.29519897e+03 2.26633032e+03 2.23591211e+03 2.20539868e+03 2.18312061e+03 2.14936694e+03 2.11939844e+03 2.09571973e+03 2.06351074e+03 2.03406726e+03 2.00658972e+03 1.98232849e+03 1.94753796e+03 1.91978149e+03 1.89256836e+03 1.86400769e+03 1.83688635e+03 1.80852380e+03 1.78234509e+03 1.75451624e+03 1.72256067e+03 1.69709204e+03 1.67213782e+03 1.63881348e+03 1.61183960e+03 1.58716956e+03 1.56176672e+03 1.53522400e+03 1.50906738e+03 1.47958679e+03 1.44943738e+03 1.42602893e+03 1.40165173e+03 1.37635620e+03 1.34853601e+03 1.31741711e+03 1.29359497e+03 1.26893359e+03 1.24618005e+03 1.22049622e+03 1.19350525e+03 1.16973962e+03 1.14576587e+03 1.11838159e+03 1.09736267e+03 1.06881543e+03 1.04528833e+03 1.02376917e+03 1.00055371e+03 9.77057800e+02 9.52830750e+02 9.29622559e+02 9.08079102e+02 8.83604004e+02 8.61506165e+02 8.40899292e+02 8.16273743e+02 7.94913513e+02 7.76091919e+02 7.54364197e+02 7.30572021e+02 7.10563965e+02 6.91353271e+02 6.72307190e+02 6.50596130e+02 6.30965820e+02 6.12448181e+02 5.92384155e+02 5.74116028e+02 5.55036316e+02 5.36471130e+02 5.19241211e+02 5.01220520e+02 4.83201508e+02 4.65998047e+02 4.48987427e+02 4.32818756e+02 4.16114075e+02 3.99954254e+02 3.83885803e+02 3.68627136e+02 3.53340729e+02 3.37842743e+02 3.23680145e+02 3.09843323e+02 2.95421387e+02 2.81687592e+02 2.68330872e+02 2.55233673e+02 2.42540482e+02 2.29925430e+02 2.18157410e+02 2.06401031e+02 1.94869781e+02 1.83629089e+02 1.72812973e+02 1.62331161e+02 1.52243225e+02 1.42504333e+02 1.32922180e+02 1.23811043e+02 1.14995430e+02 1.06347046e+02 9.82255554e+01 9.05535278e+01 8.31082916e+01 7.59897995e+01 6.92570114e+01 6.28080177e+01 5.67438469e+01 5.10231819e+01 4.56173744e+01 4.06036758e+01 3.59187660e+01 3.15923061e+01 2.76039257e+01 2.39797001e+01 2.07001629e+01 1.77543545e+01 1.51945934e+01 1.30055351e+01 1.11320086e+01 9.60314941e+00 8.43588448e+00 7.62664175e+00 7.17304611e+00 7.07624483e+00 7.33619452e+00 7.95126677e+00 8.92033195e+00 1.02315016e+01 1.19000893e+01 1.39238119e+01 1.63023701e+01 1.90257244e+01 2.21134338e+01 2.55601673e+01 2.93572235e+01 3.35118217e+01 3.79954453e+01 4.28255386e+01 4.80027275e+01 5.35273056e+01 5.94303055e+01 6.56331940e+01 7.22025146e+01 7.91618500e+01 8.63897247e+01 9.39247665e+01 1.01883972e+02 1.10240807e+02 1.18859970e+02 1.27736137e+02 1.37077164e+02 1.46825424e+02 1.56666046e+02 1.66858963e+02 1.77719528e+02 1.88618683e+02 1.99722107e+02 2.11498535e+02 2.23564407e+02 2.35613098e+02 2.48204025e+02 2.60992432e+02 2.74468262e+02 2.88042999e+02 3.01392059e+02 3.15753632e+02 3.30593231e+02 3.44800934e+02 3.59851349e+02 3.75686951e+02 3.91398041e+02 4.07381927e+02 4.23276215e+02 4.39467682e+02 4.56271027e+02 4.73606659e+02 4.91600555e+02 5.09551025e+02 5.26438416e+02 5.44699463e+02 5.64081360e+02 5.81787415e+02 6.01022217e+02 6.21650513e+02 6.41222290e+02 6.59176392e+02 6.79321106e+02 7.00745056e+02 7.19716736e+02 7.41101379e+02 7.63694153e+02 7.84990173e+02 8.07399353e+02 8.27597046e+02 8.49661987e+02 8.71024597e+02 8.92358398e+02 9.19192627e+02 9.40443176e+02 9.62051636e+02 9.86354431e+02 1.01006250e+03 1.03405688e+03 1.05784204e+03 1.08113879e+03 1.10708728e+03 1.13136047e+03 1.15616577e+03 1.18056238e+03 1.20560120e+03 1.23062769e+03 1.25492065e+03 1.28248828e+03 1.30888049e+03 1.33223938e+03 1.36126599e+03 1.38620312e+03 1.41343225e+03 1.43869836e+03 1.46143140e+03 1.49261414e+03 1.51585461e+03 1.54624426e+03 1.57360522e+03 1.59968042e+03 1.62968738e+03 1.65495886e+03 1.68254565e+03 1.71147717e+03 1.73755786e+03 1.76510486e+03 1.79524207e+03 1.82065125e+03 1.85116174e+03 1.87488013e+03 1.90928906e+03 1.94128540e+03 1.96368384e+03 1.99430029e+03 2.02152771e+03 2.04578406e+03 2.08213306e+03 2.11233740e+03 2.12919360e+03 2.16226440e+03 2.19552148e+03 2.22147754e+03 2.24904663e+03 2.27824731e+03 2.30970312e+03 2.33754224e+03 2.36448071e+03 2.39082373e+03 2.42135278e+03 2.45397021e+03 3.24738232e+03 3.49578662e+03 3.77863721e+03 3.81198413e+03 3.86265869e+03 3.90698633e+03 3.94450757e+03 6.52640137e+03 8.48387109e+03 7.59488086e+03 8.17260889e+03 8.75207617e+03 -3243249. 1.95816462e+06 -2595369. -5279803. 6.98544678e+03 7.83478711e+03 6.37032812e+03 9.62830859e+03 1.87449925e+06 6.70014875e+05 5330503. 7.45583154e+03 7.41145117e+03 5.72779492e+03 6.78009375e+03 9.98150293e+03 8.17625732e+03 9.87830566e+03 1.17239131e+04 1.45107450e+06 -1.67412612e+06 -2.29385225e+06 4.23581150e+06 -8061725. -2.53256025e+06 -27454628. -4.80775950e+06 -1.27362225e+06 -7489968. -1238131. 1.16288788e+06 1.41525738e+06 1.06137354e+04 1.08780518e+04 6.01293115e+03 1.10122656e+04 1.14587188e+04 1.04888888e+06 1.69645797e+05 1.77056312e+05 4.20830450e+06 4.34890750e+05 -9819683. 3.07182375e+06 1.11850312e+04 4.53553789e+04 25803048. 0. 0. 0. 0. 0. 252914224. 252914224. 252914224. -2.66114950e+06 -1.16418625e+05 1.67457906e+05 4.59538250e+06 1.11376512e+06 4.44612656e+05 1.24523887e+04 1.01265879e+04 6.45217822e+03 6.47852930e+03 5.38100684e+03 6.79565088e+03 6.31497021e+03 6.62857227e+03 6.09806836e+03 6.67327832e+03 6.01118994e+03 6.19916699e+03 5.83783252e+03 4.46043799e+03 4.47541406e+03 4.48826514e+03 4.49856348e+03 4.51062061e+03 4.52278027e+03 4.53130957e+03 4.54498145e+03 4.55802539e+03 4.56493701e+03 4.57275244e+03 4.58419727e+03 4.59517969e+03 4.60209619e+03 4.60997998e+03 4.61833643e+03 4.62747217e+03 4.63417480e+03 4.64194385e+03 4.64931885e+03 4.65514160e+03 4.66132178e+03 4.66601709e+03 4.67198145e+03 4.67763721e+03 4.68094580e+03 4.68472314e+03 4.68956299e+03 4.69467920e+03 4.69763428e+03 4.70002881e+03 4.70272119e+03 4.70448438e+03 4.70645850e+03 4.70813965e+03 4.70916016e+03 4.70999072e+03 4.71046826e+03 4.71049951e+03 4.71015869e+03 4.70945215e+03 4.70864111e+03 4.70779932e+03 4.70579004e+03 4.70320947e+03 4.70085645e+03 4.69867725e+03 4.69538232e+03 4.69122314e+03 4.68820654e+03 4.68465771e+03 4.68003027e+03 4.67504297e+03 4.66996240e+03 4.66287891e+03 4.65800244e+03 4.65094922e+03 4.64497705e+03 4.63933545e+03 4.63201514e+03 4.62263574e+03 4.61444092e+03 4.60853418e+03 4.60101807e+03 4.59197266e+03 4.57991357e+03 4.57033984e+03 4.56060107e+03 4.55092822e+03 4.54166797e+03 4.53033936e+03 4.51712012e+03 4.50535889e+03 4.49689160e+03 4.48254932e+03 4.46806055e+03 4.45738721e+03 4.44464697e+03 4.43021045e+03 4.41407959e+03 4.40373242e+03 4.38841846e+03 4.37047949e+03 4.35764941e+03 4.34578662e+03 4.32732568e+03 4.31319434e+03 4.29601953e+03 4.27671240e+03 4.25661377e+03 4.24305469e+03 4.23399219e+03 4.21464453e+03 4.18718018e+03 4.16903271e+03 4.15785449e+03 4.13565283e+03 4.11483643e+03 4.10048828e+03 4.08058008e+03 4.05512964e+03 4.03819629e+03 4.02033813e+03 3.99504614e+03 3.97412036e+03 3.95388672e+03 3.93704761e+03 3.91657397e+03 3.89231689e+03 3.86536450e+03 3.83934717e+03 3.81583423e+03 3.80923877e+03 3.77987549e+03 3.75629419e+03 3.73087378e+03 3.69985547e+03 3.68827319e+03 3.66176929e+03 3.63071289e+03 3.61563159e+03 3.59026733e+03 3.56443481e+03 3.53921997e+03 3.51100146e+03 3.48296558e+03 3.46285107e+03 3.43674438e+03 3.41466260e+03 3.38917627e+03 3.35656934e+03 3.32784937e+03 3.30315747e+03 3.28017407e+03 3.24922437e+03 3.23667920e+03 3.20629004e+03 3.17137427e+03 3.14403564e+03 3.12319824e+03 3.08807617e+03 3.06299316e+03 3.03384180e+03 3.01182837e+03 2.98705054e+03 2.94568213e+03 2.92248608e+03 2.89863013e+03 2.86389502e+03 2.83729810e+03 2.80954858e+03 2.78773047e+03 2.75242651e+03 2.71862793e+03 2.69292871e+03 3.44100293e+03 3.65173364e+03 3.71556909e+03 5.41999268e+03 6.34085107e+03 -1.34573412e+06 2.22904688e+04 3.42269961e+04 6.20294500e+05 -19368350. 48147936. 0. 0. 55562712. 32158140. -2288150. 3.36228925e+06 -1.30065375e+06 5.44895850e+06 -4.14901925e+06 4660946. 1.34036625e+06 2694181. 6.11704150e+03 5.82583594e+03 5.53250195e+03 -2.21085150e+06 -16728557. 5.21826750e+06 5.75133545e+03 5.33977588e+03 4.95700293e+03 3.69510781e+04 24808316. -2.93262550e+06 -96895768. 460592. 1.03932312e+05 1.19154867e+05 1.87393175e+06 5.22279785e+03 3.83494092e+03 2.21573828e+03 2.17485229e+03 3.18345044e+03 3.66832227e+03 -13607461. -125338944. 7.36119125e+05 5.20794385e+03 352392352. -31555864. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.24914875e+05 -3.24914875e+05 -3.24914875e+05 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. 0. 0. 0. 0. 0. 0. 0. 778711424. 778711424. 778711424. 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. 68003496. 68003496. -30845244. -17023598. -17023598. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -99460400. -99460400. -99460400. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -362740096. -362740096. -362740096. 116247424. 3.63525425e+06 3.63525425e+06 2.17860025e+06 31955912. 31955912. 19774048. 0. 0. 0. 0. 42786116. 42786116. 42786116. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.10557491e+09 -9.10557491e+09 -9.10557491e+09 0. 0. 0. 0. 0. 0. 0. 43699436. 43699436. 43699436. 0. 0. 0. 0. 0. 0. 30787892. -4.08357825e+06 -1098699. 1.07584950e+06 -10287971. -1.55708462e+06 8.38449250e+05 -11475065. 10266380. 0. 0. 0. -31925790. -31925790. -31925790. 0. 0. 0. 170554400. 170554400. 170554400. 48634240. -3985833. 1.31381025e+06 1.97891862e+06 -3692916. 4.86751350e+06 3.27921025e+06 15375841. 5.28774316e+03 -1.32631975e+06 -98618296. 115016168. 115016168. 115016168. 0. 0. -53085276. -53085276. -53085276. 0. 0. 0. 0. 0. 0. -13892832. 1.25672250e+06 3930654. 3.83118701e+03 3.55613330e+03 2.79143164e+03 2.81963013e+03 2.85175537e+03 2.87301709e+03 2.89871338e+03 2.93649097e+03 2.96376685e+03 2.99302222e+03 3.02008887e+03 3.03970825e+03 3.07465137e+03 3.09219067e+03 3.12145972e+03 3.15242627e+03 3.18895898e+03 3.21410864e+03 3.23700928e+03 3.26235791e+03 3.28299658e+03 3.31691870e+03 3.35462720e+03 4.58537158e+03 5.27490381e+03 4.87151270e+03 4.45787354e+03 3.47312817e+03 3.50556274e+03 3.52119434e+03 3.55557007e+03 4.84129248e+03 5.54336279e+03 5.19717676e+03 4.76471045e+03 3.67117725e+03 3.69600244e+03 3.72383130e+03 3.74953027e+03 3.76900952e+03 3.79185107e+03 3.82346826e+03 3.83576929e+03 3.85283057e+03 3.87604761e+03 3.91290234e+03 3.92764429e+03 3.94329224e+03 3.97396875e+03 3.99716211e+03 4.00876270e+03 4.03243042e+03 4.05764014e+03 4.08092310e+03 4.09601318e+03 4.11376221e+03 4.13761084e+03 4.15019189e+03 4.17256787e+03 4.18947949e+03 4.20878809e+03 4.22817188e+03 4.23837402e+03 4.26094775e+03 4.28491162e+03 4.30073242e+03 4.31565771e+03 4.32892480e+03 4.34870166e+03 4.36619531e+03 4.37681885e+03 4.39448193e+03 4.40767432e+03 4.42776660e+03 4.44078906e+03 4.45159473e+03 4.46656104e+03 4.47409277e+03 4.48871191e+03 4.50682178e+03 4.51796484e+03 4.52994238e+03 4.53554199e+03 4.55290430e+03 4.56421777e+03 4.57538232e+03 4.58856934e+03 4.59029785e+03 4.60488965e+03 4.61468506e+03 4.61968896e+03 4.63420068e+03 4.64268115e+03 4.64678760e+03 4.65448975e+03 4.66284619e+03 4.66996582e+03 4.67953760e+03 4.68616846e+03 4.69144385e+03 4.69419971e+03 4.70012109e+03 4.70715137e+03 4.70951758e+03 4.71394775e+03 4.71781152e+03 4.72251709e+03 4.72591260e+03 4.72935547e+03 4.73163818e+03 4.73344775e+03 4.73561377e+03 4.73679248e+03 4.73781104e+03 4.73901709e+03 4.73948145e+03 4.73929053e+03 4.73891211e+03 4.73806152e+03 4.73743555e+03 4.73675879e+03 4.73476660e+03 4.73251562e+03 4.72905908e+03 4.72547998e+03 4.72410156e+03 4.72085645e+03 4.71710254e+03 4.71236426e+03 4.70819873e+03 4.70453027e+03 4.69900781e+03 4.68945264e+03 4.68705127e+03 4.68094629e+03 4.67209814e+03 4.66884082e+03 4.66126221e+03 4.65309424e+03 4.64092578e+03 4.63418115e+03 4.62932910e+03 4.61856348e+03 4.60638379e+03 4.59792969e+03 4.58886426e+03 4.58072461e+03 4.56984814e+03 4.55473438e+03 4.54390039e+03 4.53313672e+03 4.52158447e+03 4.50949561e+03 4.49925537e+03 4.48567920e+03 4.46932178e+03 4.45452441e+03 4.44258887e+03 4.43023389e+03 4.41415869e+03 4.39887988e+03 4.38379541e+03 4.36522217e+03 4.34760010e+03 8.76429297e+03 5.27685625e+04 6506250. 738526272. 738526272. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -53495308. -53495308. -53495308. 0. 75041488. 75041488. 75041488. 0. 0. 0. 0. -26482576. 9348197. 9348197. 40649656. -23070948. 14036040. -11888827. 9.74740332e+03 2.89818574e+04 1.94458438e+04 6.22444287e+03 5.21565186e+03 4.68814697e+03 5.33138379e+03 1.22522539e+04 5.76427383e+04 2.32624609e+04 1.05632090e+04 6.28067285e+03 1.68392406e+05 5.34437148e+04 2120214. -11808881. -4.98544150e+06 -4.98544150e+06 4689231. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 132531296. 3.65589875e+06 -17650024. 4.03451733e+03 3.39786963e+03 2.43389111e+03 2.40108081e+03 2.37508618e+03 2.34081665e+03 2.31300269e+03 2.28634888e+03 2.25926099e+03 2.23054053e+03 2.20238110e+03 2.16849121e+03 2.13766431e+03 2.11432642e+03 2.08357739e+03 2.05241846e+03 2.02969080e+03 1.99675732e+03 1.96742810e+03 1.94073206e+03 1.91330359e+03 1.88639453e+03 1.85994922e+03 1.82813867e+03 1.80137976e+03 1.77187549e+03 1.74230200e+03 1.71514270e+03 1.69064551e+03 1.66045105e+03 1.63322180e+03 1.60499475e+03 1.57933008e+03 1.55247778e+03 1.52421240e+03 1.49795801e+03 1.46576501e+03 1.44406250e+03 1.41964111e+03 1.39371399e+03 1.36406421e+03 1.33786633e+03 1.30940186e+03 1.28732617e+03 1.26390112e+03 1.23697095e+03 1.21139673e+03 1.18562219e+03 1.15982666e+03 1.13486560e+03 1.11404980e+03 1.08443518e+03 1.06135620e+03 1.04197021e+03 1.01730780e+03 9.92508423e+02 9.69276611e+02 9.47418884e+02 9.23740051e+02 8.98751648e+02 8.77289734e+02 8.56902710e+02 8.32296387e+02 8.11237793e+02 7.92234924e+02 7.69692932e+02 7.47470337e+02 7.27332581e+02 7.06789795e+02 6.88325012e+02 6.67026794e+02 6.46467224e+02 6.26964294e+02 6.08448181e+02 5.89858032e+02 5.70558533e+02 5.51654114e+02 5.34079895e+02 5.16721619e+02 4.98807526e+02 4.81787201e+02 4.64617218e+02 4.47890442e+02 4.31789795e+02 4.15333832e+02 3.99394684e+02 3.83869904e+02 3.69429169e+02 3.53481873e+02 3.39218719e+02 3.25235657e+02 3.10724243e+02 2.97156738e+02 2.83469696e+02 2.70421539e+02 2.57817169e+02 2.45266846e+02 2.33447556e+02 2.21580933e+02 2.10113312e+02 1.99188736e+02 1.87882965e+02 1.77265579e+02 1.67639084e+02 1.57905914e+02 1.48175400e+02 1.39064789e+02 1.30372421e+02 1.21622833e+02 1.13374939e+02 1.05662117e+02 9.82892227e+01 9.12107086e+01 8.44737015e+01 7.80754700e+01 7.19929123e+01 6.62396927e+01 6.08618240e+01 5.59849663e+01 5.13280869e+01 4.69824448e+01 4.30045967e+01 3.93922615e+01 3.61414833e+01 3.31923981e+01 3.06987495e+01 2.85673695e+01 2.66879082e+01 2.51293755e+01 2.39725704e+01 2.31827717e+01 2.27587051e+01 2.26885834e+01 2.29705219e+01 2.35523491e+01 2.44778137e+01 2.57143726e+01 2.73964310e+01 2.94390736e+01 3.18488426e+01 3.45882416e+01 3.77188873e+01 4.12182732e+01 4.50026550e+01 4.91843681e+01 5.37325211e+01 5.86343689e+01 6.38217392e+01 6.93464737e+01 7.53117599e+01 8.15618973e+01 8.81460953e+01 9.51141281e+01 1.02382271e+02 1.09893661e+02 1.18075417e+02 1.26458290e+02 1.34942368e+02 1.44235519e+02 1.53800629e+02 1.63463654e+02 1.73316391e+02 1.83616608e+02 1.94486496e+02 2.05344940e+02 2.16539963e+02 2.28543365e+02 2.40394409e+02 2.52457092e+02 2.65600800e+02 2.78188019e+02 2.91263763e+02 3.04952728e+02 3.18522675e+02 3.33162415e+02 3.47576050e+02 3.62086273e+02 3.77191223e+02 3.93276184e+02 4.09440796e+02 4.25244598e+02 4.40758362e+02 4.56926727e+02 4.73795837e+02 4.92066406e+02 5.09823669e+02 5.27958130e+02 5.44598206e+02 5.62318848e+02 5.82276855e+02 6.00296143e+02 6.19762512e+02 6.40454712e+02 6.59664612e+02 6.77204102e+02 6.97809631e+02 7.21221924e+02 7.40090698e+02 7.60412964e+02 7.82314575e+02 8.02085999e+02 8.25681641e+02 8.45964661e+02 8.69303650e+02 8.91851135e+02 9.12771667e+02 9.37635620e+02 9.59760559e+02 9.82891663e+02 1.00353461e+03 1.02887952e+03 1.05604126e+03 1.07636743e+03 1.09997668e+03 1.12495752e+03 1.15059985e+03 1.17826819e+03 1.20212903e+03 1.22297485e+03 1.25306934e+03 1.27735474e+03 1.30075085e+03 1.33073889e+03 1.35627271e+03 1.38296729e+03 1.40466528e+03 1.43173950e+03 1.46259717e+03 1.48255933e+03 1.51112390e+03 1.53797778e+03 1.56402112e+03 1.59436487e+03 1.62535889e+03 1.65280334e+03 1.67522510e+03 1.70168726e+03 1.73457568e+03 1.75830103e+03 1.78788818e+03 1.81816895e+03 1.84492822e+03 1.87509277e+03 1.89840125e+03 1.92672229e+03 1.96391113e+03 1.99195996e+03 2.01263965e+03 2.04556763e+03 2.06938843e+03 2.10479712e+03 2.13712524e+03 2.15486597e+03 2.18128345e+03 2.21739600e+03 2.24819922e+03 2.27617334e+03 2.30183618e+03 2.33431250e+03 2.36414111e+03 2.39245020e+03 2.41374243e+03 2.44759351e+03 2.48102808e+03 3.45244580e+03 4.06988696e+03 -35036080. -2.45909575e+06 3.38884750e+06 3.62862250e+05 1.10928234e+05 2.39520450e+06 -56639260. 14276983. 14276983. 14276983. 0. 0. 0. 0. -36641172. -8562571. -8562571. -84675128. 0. 0. 0. -20316736. -26278846. 2.82984023e+04 -24054880. -18345768. 99279912. 99279912. 99279912. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -39095648. -39095648. 544219968. 166190192. 166190192. 0. 0. 0. 0. 0. 0. 0. -144617136. -144617136. -144617136. 0. 0. 0. 0. 0. 126457112. 126457112. 126457112. 0. 0. 0. 0. 0. 0. 180662240. 2.02849516e+05 -6.51240625e+05 -2.45161328e+05 1.34160264e+04 7.94281152e+03 4.60271387e+03 4.40449951e+03 4.42106006e+03 4.43399951e+03 4.44699170e+03 4.46239990e+03 4.47327393e+03 4.48917041e+03 4.50493945e+03 4.51426855e+03 4.52715576e+03 4.53754980e+03 4.55052051e+03 4.56054932e+03 4.57326318e+03 4.58625586e+03 4.59049658e+03 4.60241455e+03 4.61353613e+03 4.62221631e+03 4.62994189e+03 4.63925391e+03 4.64635107e+03 4.65325488e+03 4.66220264e+03 4.66999121e+03 4.67743604e+03 4.68415674e+03 4.68944287e+03 4.69382275e+03 4.69974268e+03 4.70540479e+03 4.70781738e+03 4.71289111e+03 4.71761328e+03 4.72111182e+03 4.72563770e+03 4.72865039e+03 4.73032764e+03 4.73217139e+03 4.73454102e+03 4.73616797e+03 4.73677979e+03 4.73755664e+03 4.73794873e+03 4.73790332e+03 4.73760742e+03 4.73698926e+03 4.73609131e+03 4.73508398e+03 4.73283008e+03 4.73060400e+03 4.72813672e+03 4.72529639e+03 4.72293066e+03 4.71937256e+03 4.71589795e+03 4.71098730e+03 4.70614746e+03 4.70295215e+03 4.69665332e+03 4.68874023e+03 4.68571484e+03 4.67871289e+03 4.67127100e+03 4.66614893e+03 4.65785400e+03 4.64960059e+03 4.63946240e+03 4.63708984e+03 4.63002832e+03 4.61707129e+03 4.60604053e+03 4.59434863e+03 4.58709961e+03 4.58152441e+03 4.56958984e+03 4.55675537e+03 4.53983740e+03 4.52988916e+03 4.52360986e+03 4.50478906e+03 4.49807764e+03 4.48745898e+03 4.46698340e+03 4.45218408e+03 4.44420654e+03 4.42988184e+03 4.41070898e+03 4.39676953e+03 4.37945020e+03 4.37278711e+03 4.35555664e+03 4.34017334e+03 4.31965039e+03 4.29653027e+03 4.28236865e+03 4.27058447e+03 4.25957373e+03 4.24132959e+03 4.21727783e+03 4.19095312e+03 4.17596680e+03 4.16026074e+03 4.13830859e+03 4.13119189e+03 4104. 4.07283496e+03 4.06029883e+03 4.05456226e+03 4.02566968e+03 3.99477124e+03 3.97276196e+03 3.95961182e+03 3.94553931e+03 3.91969946e+03 3.88809668e+03 3.85735449e+03 3.84225903e+03 3.83398804e+03 3.80982910e+03 3.78330225e+03 3.75181616e+03 3.72383936e+03 3.71163086e+03 3.69131006e+03 3.64763379e+03 3.62884009e+03 3.61171143e+03 3.58656787e+03 3.56201880e+03 3.53101440e+03 3.51252368e+03 3.48278564e+03 3.45294360e+03 3.43860400e+03 3.41143457e+03 3.37503394e+03 3.34793066e+03 3.32622583e+03 3.30592993e+03 3.26875659e+03 3.31058838e+03 3.23951270e+03 3.19223584e+03 3.16382764e+03 3.13958765e+03 3.11379517e+03 3.09048120e+03 3.04905249e+03 3.01851953e+03 3.03912549e+03 2.98134619e+03 2.94658130e+03 2.91407397e+03 2.88742578e+03 2.85702759e+03 2.83273755e+03 2.80861914e+03 2.77405420e+03 2.73735718e+03 2.70787256e+03 3.76654395e+03 4.82322070e+03 3.92121167e+03 1.58304434e+04 8767292. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 37879708. 37879708. 37879708. 0. 0. 0. 13197298. 13197298. 13197298. 0. 0. 0. 0. 0. 0. 0. 0. 15663976. 5686405. 3.02746625e+06 5.44845625e+05 1350043. -16546613. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.62457438e+05 -1.62457438e+05 -1.62457438e+05 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. 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. 0. 0. 0. 0. 0. 0. 0. 34001748. 34001748. 15767952. -17023598. -17023598. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_1.xml ================================================ 16 1024
f
284785024. 1.95432861e+02 6.29854889e+01 9.18014603e+01 1.20709114e+02 1.49189713e+02 1.77700348e+02 2.06200241e+02 2.35170425e+02 2.64392029e+02 2.92628510e+02 3.21212769e+02 3.50008667e+02 3.78228546e+02 4.06057831e+02 4.33839264e+02 4.62713562e+02 4.90480927e+02 5.17944397e+02 5.46215759e+02 5.74618835e+02 6.02697144e+02 6.30011597e+02 6.57736755e+02 6.84587036e+02 7.11476318e+02 7.39668335e+02 7.67654724e+02 7.95045959e+02 8.20750000e+02 8.47892883e+02 8.74420593e+02 8.99625427e+02 9.27485352e+02 9.53609314e+02 9.79599426e+02 1.00652313e+03 1.03250061e+03 1.05838245e+03 1.08388293e+03 1.10753735e+03 1.13309058e+03 1.15849036e+03 1.18439209e+03 1.20842822e+03 1.23200146e+03 1.25906873e+03 1.28247485e+03 1.30199231e+03 1.32777380e+03 1.35549719e+03 1.37676221e+03 1.39910596e+03 1.42089294e+03 1.44230798e+03 1.46611731e+03 1.49487952e+03 1.51389429e+03 1.53008777e+03 1.55342163e+03 1.57869568e+03 1.60079407e+03 1.61882336e+03 1.63977563e+03 1.65639014e+03 1.67763391e+03 1.70408130e+03 1.72056323e+03 1.73530701e+03 1.75289612e+03 1.77657935e+03 1.80139539e+03 1.81166895e+03 1.82212866e+03 1.84460876e+03 1.87255396e+03 1.88835852e+03 1.89816284e+03 1.92299353e+03 1.93829724e+03 1.94423987e+03 1.96705029e+03 1.98733801e+03 1.99804797e+03 2.00451392e+03 2.02736768e+03 2.04166467e+03 2.05637915e+03 4.20299121e+03 6.71109131e+03 3.07650723e+04 -5031298. 87245592. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9525159. -4.84672219e+05 -1.49197031e+04 3.19313135e+03 2.96795679e+03 2.28987744e+03 2.29303223e+03 2.29016235e+03 2.29580518e+03 2.29797070e+03 2.31151270e+03 2.32068018e+03 2.32901904e+03 2.32306396e+03 2.32733276e+03 2.32942554e+03 2.32356445e+03 2.34633081e+03 2.34131201e+03 2.33791577e+03 2.35293188e+03 2.34068555e+03 2.33296851e+03 2.33583008e+03 2.34293481e+03 2.34064868e+03 2.33901733e+03 2.34291577e+03 2.32840137e+03 2.33187964e+03 2.33635132e+03 2.31570752e+03 2.32884351e+03 2.33214819e+03 2.31693506e+03 2.31949365e+03 2.31860107e+03 2.31113330e+03 2.29891406e+03 2.29894922e+03 2.29229126e+03 2.27208472e+03 2.27838232e+03 2.26720215e+03 2.25971045e+03 2.26024316e+03 2.24309229e+03 2.24285083e+03 2.22927808e+03 2.21128418e+03 2.20495068e+03 2.19876978e+03 2.19455811e+03 2.19080664e+03 2.16996948e+03 2.16431055e+03 2.15038940e+03 2.13010669e+03 2.12410425e+03 2.11790063e+03 2.10503979e+03 2.08931128e+03 2.07605493e+03 2.06621240e+03 2.05215308e+03 2.03159424e+03 2.02199829e+03 2.00547888e+03 1.97579907e+03 1.97069434e+03 1.96326257e+03 1.94370618e+03 1.93188464e+03 1.90820435e+03 1.89320605e+03 1.88181653e+03 1.85726721e+03 1.83783179e+03 1.82207800e+03 1.81318494e+03 1.78832861e+03 1.76446948e+03 1.74860681e+03 1.72860449e+03 1.70743872e+03 1.69286804e+03 1.67919421e+03 1.65054089e+03 1.63142969e+03 1.61258948e+03 1.58393701e+03 1.56456702e+03 1.54717517e+03 1.52728906e+03 1.50798608e+03 1.48404553e+03 1.45434167e+03 1.43452686e+03 1.41592554e+03 1.38620874e+03 1.36721411e+03 1.34842114e+03 1.31974707e+03 1.29227441e+03 1.27116711e+03 1.24728137e+03 1.22272827e+03 1.20070056e+03 1.17363025e+03 1.14864722e+03 1.12526245e+03 1.09873413e+03 1.07339282e+03 1.04913013e+03 1.02079004e+03 9.95536194e+02 9.69676941e+02 9.41820496e+02 9.16836182e+02 8.91439392e+02 8.64598938e+02 8.37361023e+02 8.10737793e+02 7.83542603e+02 7.54927795e+02 7.28622864e+02 7.01655518e+02 6.74596924e+02 6.47079468e+02 6.18959290e+02 5.91170227e+02 5.63690735e+02 5.36034790e+02 5.07319397e+02 4.78913116e+02 4.51323883e+02 4.23177032e+02 3.95084747e+02 3.66510986e+02 3.37955902e+02 3.09499969e+02 2.81270660e+02 2.52576843e+02 2.23730637e+02 1.95376892e+02 1.66797195e+02 1.38019241e+02 1.09511101e+02 8.07657776e+01 5.18959846e+01 2.32885551e+01 -5.44077063e+00 -3.42425194e+01 -6.27470398e+01 -9.15402298e+01 -1.20374550e+02 -1.48999893e+02 -1.77895905e+02 -2.06331253e+02 -2.34654297e+02 -2.63577789e+02 -2.91999237e+02 -3.20405396e+02 -3.49283081e+02 -3.77644623e+02 -4.05312958e+02 -4.33395813e+02 -4.62441132e+02 -4.90291809e+02 -5.17451172e+02 -5.45800659e+02 -5.74446228e+02 -6.02041138e+02 -6.29474121e+02 -6.57438110e+02 -6.84389771e+02 -7.11156799e+02 -7.39224243e+02 -7.67498413e+02 -7.94568481e+02 -8.20807190e+02 -8.47949097e+02 -8.74220764e+02 -8.99330872e+02 -9.27104980e+02 -9.53669617e+02 -9.79382141e+02 -1.00577191e+03 -1.03209229e+03 -1.05835461e+03 -1.08317700e+03 -1.10795251e+03 -1.13249255e+03 -1.15811243e+03 -1.18466248e+03 -1.20821570e+03 -1.23153455e+03 -1.25961780e+03 -1.28200635e+03 -1.29931458e+03 -1.32662097e+03 -1.35378955e+03 -1.37812573e+03 -1.40000757e+03 -1.41913379e+03 -1.44221692e+03 -1.46611145e+03 -1.49521692e+03 -1.51412390e+03 -1.52946057e+03 -1.55193555e+03 -1.57633667e+03 -1.60013538e+03 -1.61883594e+03 -1.63948560e+03 -1.65547778e+03 -1.67675806e+03 -1.70700989e+03 -1.72188135e+03 -1.73279700e+03 -1.75237170e+03 -1.77720447e+03 -1.79956128e+03 -1.81180530e+03 -1.81976721e+03 -1.84477661e+03 -1.87441101e+03 -1.88764331e+03 -1.89581506e+03 -1.92289001e+03 -1.93748157e+03 -1.94313538e+03 -1.96483691e+03 -1.98506653e+03 -1.99469958e+03 -1.99967725e+03 -2.02927441e+03 -2.04628589e+03 -2.04258398e+03 -2.06076538e+03 -2.08114160e+03 -2.10010938e+03 -2.11174561e+03 -2.11129419e+03 -2.12592578e+03 -2.14889453e+03 -2.15633179e+03 -2.16379004e+03 -2.17496582e+03 -2.18207739e+03 -2.18874194e+03 -2.21010132e+03 -2.21699146e+03 -2.22191577e+03 -2.23236426e+03 -2.24553735e+03 -2.25308716e+03 -2.25857471e+03 -2.26957300e+03 -2.26166968e+03 -2.28269897e+03 -2.29836890e+03 -2.29069067e+03 -2.28975342e+03 -2.29130103e+03 -2.30443750e+03 -2.31425366e+03 -2.31711792e+03 -2.32840552e+03 -2.32173389e+03 -2.32754980e+03 -2.32433057e+03 -2.32105396e+03 -2.34436255e+03 -2.33967017e+03 -2.33210449e+03 -2.35282495e+03 -2.33702612e+03 -2.33163940e+03 -2.34102368e+03 -2.33828247e+03 -2.33863354e+03 -2.33381641e+03 -2.33903003e+03 -2.33171899e+03 -2.33009009e+03 -2.33195728e+03 -2.32413208e+03 -2.33161597e+03 -2.33008154e+03 -2.31403687e+03 -2.31286865e+03 -2.31300195e+03 -2.30204150e+03 -2.29296411e+03 -2.29946411e+03 -2.28780347e+03 -2.26808154e+03 -2.28458398e+03 -2.27179932e+03 -2.25651050e+03 -2.25920312e+03 -2.24972168e+03 -2.24320728e+03 -2.22633496e+03 -2.21001367e+03 -2.21025049e+03 -2.20366113e+03 -2.19584521e+03 -2.18785376e+03 -2.16725586e+03 -2.16261475e+03 -2.15283472e+03 -2.13018701e+03 -2.12155127e+03 -2.11488013e+03 -2.10456836e+03 -2.09243848e+03 -2.07615576e+03 -2.06044604e+03 -2.04623938e+03 -2.03369788e+03 -2.02050464e+03 -2.00546497e+03 -1.97811890e+03 -1.97138428e+03 -1.96324792e+03 -1.94240686e+03 -1.93282202e+03 -1.91016919e+03 -1.89000378e+03 -1.88047778e+03 -1.85828137e+03 -1.83977942e+03 -1.82485779e+03 -1.80987756e+03 -1.78746313e+03 -1.76697241e+03 -1.74759277e+03 -1.72758350e+03 -1.70705322e+03 -1.69184521e+03 -1.67771045e+03 -1.64867847e+03 -1.63154041e+03 -1.61323425e+03 -1.58421484e+03 -1.56342407e+03 -1.54543835e+03 -1.52798535e+03 -1.50781274e+03 -1.48237598e+03 -1.45464221e+03 -1.43391370e+03 -1.41489758e+03 -1.38685022e+03 -1.36487097e+03 -1.34736963e+03 -1.32136377e+03 -1.29257141e+03 -1.27215466e+03 -1.24664929e+03 -1.22171960e+03 -1.20110779e+03 -1.17375354e+03 -1.14850513e+03 -1.12600024e+03 -1.09721228e+03 -1.07324451e+03 -1.05008386e+03 -1.02069275e+03 -9.95302856e+02 -9.69212708e+02 -9.42047119e+02 -9.17456970e+02 -8.91481323e+02 -8.64505737e+02 -8.37192505e+02 -8.10889343e+02 -7.83603516e+02 -7.55657043e+02 -7.29004333e+02 -7.01407715e+02 -6.74583374e+02 -6.47019653e+02 -6.19242432e+02 -5.91405334e+02 -5.63755493e+02 -5.36006714e+02 -5.07339691e+02 -4.79145538e+02 -4.51351959e+02 -4.23304840e+02 -3.95310242e+02 -3.66807678e+02 -3.38134827e+02 -3.09275970e+02 -2.81038422e+02 -2.52758453e+02 -2.23996002e+02 -1.95432037e+02 -1.66790833e+02 -1.38051666e+02 -1.09411659e+02 -8.06931000e+01 -5.18052025e+01 -2.30837517e+01 5.51049280e+00 3.42149391e+01 6.28963814e+01 9.16426010e+01 1.20069847e+02 1.48705826e+02 1.77687775e+02 2.06199142e+02 2.34830154e+02 2.63494446e+02 2.91739471e+02 3.20311737e+02 3.48924042e+02 3.77270294e+02 4.05244141e+02 4.33509064e+02 4.62519287e+02 4.90270599e+02 5.17623474e+02 5.45730225e+02 5.73895203e+02 6.02051331e+02 6.29666565e+02 6.57642883e+02 6.84296936e+02 7.10777161e+02 7.39152283e+02 7.67171875e+02 7.94185425e+02 8.20566223e+02 8.47949829e+02 8.74243347e+02 8.99596252e+02 9.26768921e+02 9.52608398e+02 9.78622681e+02 1.00624097e+03 1.03248914e+03 1.05791528e+03 1.08293860e+03 1.10762341e+03 1.13269824e+03 1.15817224e+03 1.18468005e+03 1.20839795e+03 1.23222803e+03 1.25907056e+03 1.28108020e+03 1.30134338e+03 1.32867371e+03 1.35344568e+03 1.37616675e+03 1.39867224e+03 1.42122693e+03 1.44359827e+03 1.46613416e+03 1.49423767e+03 1.51298376e+03 1.52965759e+03 1.55376318e+03 1.57614893e+03 1.60074878e+03 1.62001245e+03 1.63821960e+03 1.65543188e+03 1.67766809e+03 1.70306836e+03 1.72072595e+03 1.73535181e+03 1.75372131e+03 1.77466187e+03 1.79933398e+03 1.80979114e+03 1.82104968e+03 1.84728296e+03 1.87303101e+03 1.88583997e+03 1.89484717e+03 1.92181274e+03 1.93966870e+03 1.94653442e+03 1.96542261e+03 1.98631824e+03 1.99404297e+03 2.00239954e+03 2.02873364e+03 2.04520020e+03 2.04845776e+03 2.06366284e+03 2.08205884e+03 2.09816870e+03 2.11187476e+03 2.11348242e+03 2.12708984e+03 2.14649316e+03 2.15419531e+03 2.16559229e+03 2.17513574e+03 2.18604053e+03 2.19179004e+03 2.20146216e+03 2.21737402e+03 2.22694775e+03 2.23518506e+03 2.24234790e+03 2.24902661e+03 2.25955908e+03 2.26950708e+03 2.26099194e+03 2.27882397e+03 2.29923169e+03 2.29087573e+03 2.29295825e+03 2.29264746e+03 2.30426147e+03 2.31067041e+03 2.32084985e+03 2.33166992e+03 2.31736353e+03 2.32578467e+03 2.33155151e+03 2.32302710e+03 2.34931372e+03 2.33773633e+03 2.33583789e+03 2.34971875e+03 2.34157129e+03 2.33509204e+03 2.33971411e+03 2.33694751e+03 2.34437598e+03 2.33018042e+03 2.34062842e+03 2.33429028e+03 2.33278101e+03 2.33252783e+03 2.31821729e+03 2.33743799e+03 2.32993213e+03 2.31482690e+03 2.31862939e+03 2.31131274e+03 2.29901001e+03 2.29890479e+03 2.30120752e+03 2.28829419e+03 2.26687183e+03 2.28105835e+03 2.27047900e+03 2.25592700e+03 2.25950000e+03 2.24650977e+03 2.24415845e+03 2.22833228e+03 2.21370117e+03 2.21296606e+03 2.20135547e+03 2.19323022e+03 2.18682544e+03 2.17023071e+03 2.16083374e+03 2.14780127e+03 2.13500757e+03 2.12423535e+03 2.11340503e+03 2.10359595e+03 2.09083618e+03 2.07620215e+03 2.06159277e+03 2.04808472e+03 2.03275952e+03 2.02069250e+03 2.00593896e+03 1.98043958e+03 1.97115015e+03 1.96291553e+03 1.94264233e+03 1.93176990e+03 1.90863428e+03 1.89056506e+03 1.87992590e+03 1.85893115e+03 1.83979443e+03 1.82484644e+03 1.80877881e+03 1.78932532e+03 1.76616064e+03 1.74861975e+03 1.72907031e+03 1.70646729e+03 1.69257825e+03 1.67938635e+03 1.64889734e+03 1.63074878e+03 1.61382202e+03 1.58495886e+03 1.56255444e+03 1.54575598e+03 1.52770667e+03 1.50804578e+03 1.48346423e+03 1.45473547e+03 1.43434448e+03 1.41548474e+03 1.38678430e+03 1.36593848e+03 1.34754260e+03 1.32073108e+03 1.29225867e+03 1.27169568e+03 1.24689941e+03 1.22265894e+03 1.20163599e+03 1.17332019e+03 1.14723718e+03 1.12599036e+03 1.09780859e+03 1.07301611e+03 1.05036926e+03 1.02065027e+03 9.95178833e+02 9.69671204e+02 9.42557129e+02 9.16921936e+02 8.91635559e+02 8.64299316e+02 8.37712341e+02 8.11420959e+02 7.83408936e+02 7.55233582e+02 7.28775513e+02 7.01476257e+02 6.74684326e+02 6.47007263e+02 6.19120361e+02 5.91200623e+02 5.63527893e+02 5.36022644e+02 5.07439209e+02 4.79190735e+02 4.51267120e+02 4.23050629e+02 3.95235046e+02 3.66644867e+02 3.38082245e+02 3.09568481e+02 2.81186981e+02 2.52601883e+02 2.23854523e+02 1.95479874e+02 1.66884537e+02 1.38088959e+02 1.09460800e+02 8.07380142e+01 5.20404816e+01 2.34678345e+01 -5.41654778e+00 -3.41813240e+01 -6.27225990e+01 -9.15807114e+01 -1.20339981e+02 -1.48931931e+02 -1.77833847e+02 -2.06351669e+02 -2.34733917e+02 -2.63423035e+02 -2.91946686e+02 -3.20360260e+02 -3.49056488e+02 -3.77426147e+02 -4.05124268e+02 -4.33470551e+02 -4.62324768e+02 -4.90166840e+02 -5.17818359e+02 -5.45955933e+02 -5.74239502e+02 -6.02381165e+02 -6.29472107e+02 -6.57079407e+02 -6.84682373e+02 -7.11456909e+02 -7.39110962e+02 -7.67436768e+02 -7.94722351e+02 -8.20776855e+02 -8.47754211e+02 -8.74116943e+02 -8.99402405e+02 -9.27106873e+02 -9.53837646e+02 -9.78836670e+02 -1.00548755e+03 -1.03207776e+03 -1.05876331e+03 -1.08391418e+03 -1.10688403e+03 -1.13179126e+03 -1.15854260e+03 -1.18515137e+03 -1.20800134e+03 -1.23071082e+03 -1.25814844e+03 -1.28118799e+03 -1.30061609e+03 -1.32746545e+03 -1.35406042e+03 -1.37766614e+03 -1.39907874e+03 -1.42006824e+03 -1.44274243e+03 -1.46594177e+03 -1.49453381e+03 -1.51375696e+03 -1.52917273e+03 -1.55336206e+03 -1.57588416e+03 -1.60050964e+03 -1.61990381e+03 -1.63839270e+03 -1.65549255e+03 -1.67657288e+03 -1.70340051e+03 -1.72137109e+03 -1.73443408e+03 -1.75386023e+03 -1.77696582e+03 -1.79951929e+03 -1.81193835e+03 -1.82083398e+03 -1.84629773e+03 -1.87403650e+03 -1.88722583e+03 -1.89457629e+03 -1.92185095e+03 -1.93900549e+03 -1.94245837e+03 -1.96883203e+03 -1.98607336e+03 -1.99553687e+03 -1.99969641e+03 -2.02794678e+03 -2.04546021e+03 -2.04430029e+03 -2.06361230e+03 -2.08270410e+03 -2.09739502e+03 -2.11045703e+03 -2.11691333e+03 -2.12960083e+03 -2.14666724e+03 -2.15602490e+03 -2.16411743e+03 -2.17256763e+03 -2.18229932e+03 -2.19373730e+03 -2.20785522e+03 -2.21529517e+03 -2.22137378e+03 -2.23613281e+03 -2.24993237e+03 -2.24911841e+03 -2.25853394e+03 -2.26775781e+03 -2.26103833e+03 -2.28516309e+03 -2.29407837e+03 -2.29165405e+03 -2.29216504e+03 -2.29431177e+03 -2.30691431e+03 -2.31362817e+03 -2.31425684e+03 -2.32960693e+03 -2.32042505e+03 -2.32478125e+03 -2.32962598e+03 -2.32161108e+03 -2.34805054e+03 -2.33769019e+03 -2.33310083e+03 -2.35062427e+03 -2.34110913e+03 -2.33527563e+03 -2.33767554e+03 -2.33921436e+03 -2.34179785e+03 -2.33239136e+03 -2.33951660e+03 -2.33391040e+03 -2.33388940e+03 -2.33554248e+03 -2.33768726e+03 -2.34869141e+03 -2.33062817e+03 -2.31054468e+03 -2.31285498e+03 -2.30659180e+03 -2.29487036e+03 -2.29691357e+03 -2.29371118e+03 -2.28905322e+03 -2.27989136e+03 -2.94027588e+03 -3.15777271e+03 -1.09785262e+06 -13551030. 0. 0. 0. 0. -109199712. -109199712. -109199712. 0. 0. 0. -162924736. -1.08207662e+06 2.32011680e+04 -6.38318359e+03 -4.70059033e+03 -2.20315479e+03 -2.15126611e+03 -2.17555322e+03 -2.16357275e+03 -2.06469385e+03 -2.02372412e+03 -2.00353992e+03 -1.97955933e+03 -1.97325378e+03 -1.96287488e+03 -1.94580383e+03 -1.93365918e+03 -1.90962866e+03 -1.89267212e+03 -1.87959143e+03 -1.85558008e+03 -1.84023157e+03 -1.81968799e+03 -1.80044580e+03 -1.78306543e+03 -1.76503442e+03 -1.74912708e+03 -1.73719531e+03 -1.72738855e+03 -1.70568408e+03 -1.67733374e+03 -1.64743872e+03 -1.62939734e+03 -1.61905676e+03 -1.58931787e+03 -1.56455127e+03 -1.54646082e+03 -1.52834583e+03 -1.50738293e+03 -1.48359778e+03 -1.45501074e+03 -1.43363733e+03 -1.41603992e+03 -1.38731433e+03 -1.36702917e+03 -1.34760547e+03 -1.32058081e+03 -1.29358594e+03 -1.27168237e+03 -1.24736841e+03 -1.22293164e+03 -1.20128979e+03 -1.17388892e+03 -1.14910071e+03 -1.12626306e+03 -1.09717590e+03 -1.07397961e+03 -1.05067505e+03 -1.02050806e+03 -9.95630737e+02 -9.69472412e+02 -9.42035278e+02 -9.17673767e+02 -8.91476624e+02 -8.64560791e+02 -8.37910217e+02 -8.11374512e+02 -7.84022339e+02 -7.55475281e+02 -7.28809570e+02 -7.01973755e+02 -6.75369568e+02 -6.47419922e+02 -6.19312744e+02 -5.91780762e+02 -5.64437683e+02 -5.36360535e+02 -5.07619751e+02 -4.79503510e+02 -4.51767548e+02 -4.23840149e+02 -3.95545288e+02 -3.66967133e+02 -3.38901001e+02 -3.10635132e+02 -2.81478271e+02 -2.52238434e+02 -2.23937500e+02 -1.95543289e+02 -1.66691544e+02 -1.38192657e+02 -1.10092041e+02 -8.08524933e+01 -5.15744934e+01 -1.27508583e+02 3.28981094e+05 1.78583054e+02 5.89298096e+01 8.77151184e+01 1.16331268e+02 1.44854370e+02 1.73582672e+02 2.02174286e+02 2.30668228e+02 2.59145142e+02 2.87630463e+02 3.16265869e+02 3.44763489e+02 3.72886261e+02 4.01032166e+02 4.29096710e+02 4.57361664e+02 4.85456848e+02 5.13348022e+02 5.41086731e+02 5.69068298e+02 5.97190979e+02 6.24492981e+02 6.52092041e+02 6.79521545e+02 7.06233032e+02 7.33910522e+02 7.61985962e+02 7.88945435e+02 8.15075806e+02 8.42240784e+02 8.68719360e+02 8.94876343e+02 9.21787964e+02 9.47943298e+02 9.73356628e+02 9.99731018e+02 1.02571191e+03 1.05336914e+03 1.07791260e+03 1.10080383e+03 1.12568591e+03 1.15267786e+03 1.17891833e+03 1.20214856e+03 1.22698865e+03 1.25260095e+03 1.27597864e+03 1.29535327e+03 1.32282361e+03 1.34857324e+03 1.36915088e+03 1.39296570e+03 1.41495337e+03 1.43558923e+03 1.46191296e+03 1.48574133e+03 1.50584595e+03 1.52722180e+03 1.54775989e+03 1.57022852e+03 1.59140686e+03 1.60766687e+03 1.63353503e+03 1.65086328e+03 1.66848071e+03 1.69740369e+03 1.71366357e+03 1.72965857e+03 1.75169189e+03 1.76924048e+03 1.78966846e+03 1.80699146e+03 1.82117419e+03 1.84038721e+03 1.86393958e+03 1.87789429e+03 1.88854089e+03 1.91405298e+03 1.93017566e+03 1.94048889e+03 1.95868835e+03 1.97810938e+03 1.99232166e+03 2.00003406e+03 2.59381274e+03 2.76969409e+03 3.09177856e+03 5.18687305e+03 6.71767383e+03 3.08321602e+04 -10396943. 174491184. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -159086048. 2.56197324e+04 5.22370508e+03 3.34361304e+03 3.09722681e+03 2.94969800e+03 2.28119727e+03 2.28891406e+03 2.28588086e+03 2.28788208e+03 2.29043872e+03 2.30456519e+03 2.31716797e+03 2.31906860e+03 2.31179004e+03 2.32103516e+03 2.32339478e+03 2.32030493e+03 2.33278516e+03 2.33378662e+03 2.32961670e+03 2.33794995e+03 2.33550122e+03 2.33506445e+03 2.33676807e+03 2.33345703e+03 2.33557617e+03 2.33560425e+03 2.33307251e+03 2.32320264e+03 2.33114697e+03 2.33066260e+03 2.31485449e+03 2.32180859e+03 2.32148999e+03 2.30977539e+03 2.31496753e+03 2.30588281e+03 2.30354468e+03 2.30001074e+03 2.29364917e+03 2.28030981e+03 2.27127539e+03 2.27608862e+03 2.26265332e+03 2.25599829e+03 2.25264502e+03 2.24398047e+03 2.23443774e+03 2.22274683e+03 2.20956470e+03 2.20705225e+03 2.19237061e+03 2.18490137e+03 2.18514380e+03 2.17074951e+03 2.15829517e+03 2.14030762e+03 2.13027319e+03 2.12421948e+03 2.11245898e+03 2.09469092e+03 2.08305542e+03 2.07641357e+03 2.05719751e+03 2.04583350e+03 2.03391833e+03 2.02034009e+03 1.99769116e+03 1.97775366e+03 1.97053796e+03 1.95976379e+03 1.94207275e+03 1.92590210e+03 1.90826941e+03 1.89095508e+03 1.87656763e+03 1.85806104e+03 1.83733911e+03 1.82028992e+03 1.80804260e+03 1.78643481e+03 1.76408362e+03 1.74879126e+03 1.72843457e+03 1.70700305e+03 1.68960950e+03 1.67526147e+03 1.64999536e+03 1.62900659e+03 1.61013708e+03 1.58653040e+03 1.56619958e+03 1.54450037e+03 1.52240625e+03 1.50579736e+03 1.48177161e+03 1.45395325e+03 1.43622363e+03 1.41532263e+03 1.38849634e+03 1.36369031e+03 1.34697729e+03 1.31972632e+03 1.29289502e+03 1.27320288e+03 1.24797766e+03 1.22288672e+03 1.19968213e+03 1.17483521e+03 1.14989966e+03 1.12407263e+03 1.09854932e+03 1.07378809e+03 1.05003186e+03 1.02295911e+03 9.95738098e+02 9.70603882e+02 9.43976562e+02 9.18521179e+02 8.92407837e+02 8.65211060e+02 8.39214294e+02 8.12134155e+02 7.84856140e+02 7.57545532e+02 7.30821960e+02 7.03628235e+02 6.76443542e+02 6.49006470e+02 6.21142090e+02 5.93531006e+02 5.65952271e+02 5.38312988e+02 5.09859741e+02 4.81582489e+02 4.53986420e+02 4.26002655e+02 3.97836273e+02 3.69405701e+02 3.40949921e+02 3.12481842e+02 2.84297791e+02 2.55765717e+02 2.27117462e+02 1.98750397e+02 1.70165390e+02 1.41542465e+02 1.13027153e+02 8.43542938e+01 5.56659203e+01 2.70599651e+01 -1.60541809e+00 -3.02783394e+01 -5.88557091e+01 -8.75257034e+01 -1.16210831e+02 -1.44767136e+02 -1.73434280e+02 -2.01980484e+02 -2.30401367e+02 -2.59011993e+02 -2.87380951e+02 -3.15701263e+02 -3.44354065e+02 -3.72699860e+02 -4.00720734e+02 -4.28887360e+02 -4.57337311e+02 -4.85184235e+02 -5.12843567e+02 -5.40812256e+02 -5.69251953e+02 -5.96754150e+02 -6.23990784e+02 -6.51958862e+02 -6.79219604e+02 -7.06135803e+02 -7.33646667e+02 -7.61439392e+02 -7.88577087e+02 -8.15034668e+02 -8.41947144e+02 -8.68686646e+02 -8.94675110e+02 -9.21548767e+02 -9.47700867e+02 -9.73432556e+02 -9.99278687e+02 -1.02547766e+03 -1.05292834e+03 -1.07687964e+03 -1.10136401e+03 -1.12515210e+03 -1.15192578e+03 -1.17824573e+03 -1.20122852e+03 -1.22683801e+03 -1.25299585e+03 -1.27424158e+03 -1.29399341e+03 -1.32129907e+03 -1.34682788e+03 -1.36896643e+03 -1.39328552e+03 -1.41386902e+03 -1.43594617e+03 -1.46117310e+03 -1.48506165e+03 -1.50673425e+03 -1.52720142e+03 -1.54517615e+03 -1.56950696e+03 -1.59075977e+03 -1.60645752e+03 -1.63238135e+03 -1.65131860e+03 -1.66757654e+03 -1.69626538e+03 -1.71390186e+03 -1.72767822e+03 -1.75092798e+03 -1.76951086e+03 -1.78817761e+03 -1.80761865e+03 -1.81870593e+03 -1.83695959e+03 -1.86451123e+03 -1.87812427e+03 -1.88738440e+03 -1.91483374e+03 -1.92864783e+03 -1.94045020e+03 -1.95658374e+03 -1.97421448e+03 -1.98893384e+03 -1.99794617e+03 -2.01905750e+03 -2.03769629e+03 -2.04384680e+03 -2.05396338e+03 -2.07391553e+03 -2.09187817e+03 -2.09799927e+03 -2.10582568e+03 -2.12340845e+03 -2.13768408e+03 -2.14741187e+03 -2.15857300e+03 -2.16762085e+03 -2.17820801e+03 -2.19081787e+03 -2.19757764e+03 -2.20689160e+03 -2.21981787e+03 -2.22480615e+03 -2.23530786e+03 -2.24773584e+03 -2.25377344e+03 -2.25636499e+03 -2.25805664e+03 -2.27692310e+03 -2.28096851e+03 -2.28278931e+03 -2.28736035e+03 -2.28858496e+03 -2.29616504e+03 -2.30601270e+03 -2.31307324e+03 -2.31787769e+03 -2.31127148e+03 -2.31537451e+03 -2.32340088e+03 -2.32134448e+03 -2.32977539e+03 -2.33410938e+03 -2.33119580e+03 -2.33712646e+03 -2.33398877e+03 -2.33483789e+03 -2.33405273e+03 -2.33332324e+03 -2.33529321e+03 -2.32859302e+03 -2.33349805e+03 -2.32918774e+03 -2.32791187e+03 -2.32792163e+03 -2.32073364e+03 -2.32534131e+03 -2.31401880e+03 -2.31014062e+03 -2.31258838e+03 -2.30600977e+03 -2.30299414e+03 -2.29708105e+03 -2.29465112e+03 -2.27719971e+03 -2.26547046e+03 -2.27471948e+03 -2.25804736e+03 -2.25136816e+03 -2.25697119e+03 -2.24315527e+03 -2.23552515e+03 -2.21861841e+03 -2.20727588e+03 -2.21009937e+03 -2.19928223e+03 -2.18466699e+03 -2.18658350e+03 -2.16861987e+03 -2.15502808e+03 -2.14242676e+03 -2.12951978e+03 -2.12508936e+03 -2.11185034e+03 -2.09305420e+03 -2.08643213e+03 -2.07540771e+03 -2.05398438e+03 -2.04121252e+03 -2.03493591e+03 -2.01692407e+03 -1.99880872e+03 -1.97992200e+03 -1.97109827e+03 -1.95960632e+03 -1.94206287e+03 -1.92576306e+03 -1.90655798e+03 -1.88743286e+03 -1.87664026e+03 -1.85578748e+03 -1.83731738e+03 -1.82264343e+03 -1.80535974e+03 -1.78626355e+03 -1.76595813e+03 -1.74635120e+03 -1.72769922e+03 -1.70740808e+03 -1.68899683e+03 -1.67447375e+03 -1.65014722e+03 -1.62901086e+03 -1.60943274e+03 -1.58643335e+03 -1.56622498e+03 -1.54557214e+03 -1.52196973e+03 -1.50392944e+03 -1.48073669e+03 -1.45471069e+03 -1.43582849e+03 -1.41466492e+03 -1.38768274e+03 -1.36408643e+03 -1.34614258e+03 -1.31999268e+03 -1.29276880e+03 -1.27365820e+03 -1.24825586e+03 -1.22220654e+03 -1.19956409e+03 -1.17465906e+03 -1.14961243e+03 -1.12460388e+03 -1.09744446e+03 -1.07380261e+03 -1.05052979e+03 -1.02266699e+03 -9.95534119e+02 -9.69645813e+02 -9.44119812e+02 -9.18665771e+02 -8.92445190e+02 -8.65271057e+02 -8.39177490e+02 -8.12123047e+02 -7.84867188e+02 -7.57688965e+02 -7.30752563e+02 -7.03253967e+02 -6.76285461e+02 -6.48980591e+02 -6.21354919e+02 -5.93688232e+02 -5.65896729e+02 -5.38151611e+02 -5.09800995e+02 -4.81737030e+02 -4.53881317e+02 -4.25943573e+02 -3.97910950e+02 -3.69507751e+02 -3.41033630e+02 -3.12423553e+02 -2.84187347e+02 -2.55818787e+02 -2.27203598e+02 -1.98760620e+02 -1.70170349e+02 -1.41552078e+02 -1.12998528e+02 -8.43260422e+01 -5.56528473e+01 -2.70232544e+01 1.61431360e+00 3.02653828e+01 5.88652611e+01 8.75109711e+01 1.16101517e+02 1.44677200e+02 1.73370682e+02 2.01911392e+02 2.30409454e+02 2.58958954e+02 2.87356049e+02 3.15712677e+02 3.44247406e+02 3.72567535e+02 4.00659149e+02 4.28841034e+02 4.57207214e+02 4.85153687e+02 5.13005676e+02 5.40772583e+02 5.68710205e+02 5.96888855e+02 6.24191040e+02 6.51914246e+02 6.79208923e+02 7.05918274e+02 7.33582031e+02 7.61735535e+02 7.88468933e+02 8.14651245e+02 8.41831299e+02 8.68366028e+02 8.95033936e+02 9.21307861e+02 9.47241394e+02 9.73269531e+02 9.99643005e+02 1.02523804e+03 1.05260205e+03 1.07755701e+03 1.10070142e+03 1.12535266e+03 1.15277185e+03 1.17822327e+03 1.20158289e+03 1.22603625e+03 1.25259412e+03 1.27451062e+03 1.29448633e+03 1.32220532e+03 1.34705774e+03 1.36854016e+03 1.39156165e+03 1.41522925e+03 1.43609436e+03 1.46110657e+03 1.48514929e+03 1.50500439e+03 1.52556470e+03 1.54603662e+03 1.57049841e+03 1.59228467e+03 1.60887793e+03 1.63267871e+03 1.65080017e+03 1.67007129e+03 1.69503845e+03 1.71276965e+03 1.73012744e+03 1.75183508e+03 1.76703406e+03 1.78837561e+03 1.80389417e+03 1.81983850e+03 1.84170178e+03 1.86480371e+03 1.87665442e+03 1.88733691e+03 1.91294495e+03 1.93180725e+03 1.94197437e+03 1.95690942e+03 1.97575500e+03 1.98796228e+03 1.99718213e+03 2.01865576e+03 2.03604834e+03 2.04695496e+03 2.05518188e+03 2.07419458e+03 2.09209497e+03 2.09773291e+03 2.10843848e+03 2.12497949e+03 2.13680396e+03 2.14571167e+03 2.16189746e+03 2.16585669e+03 2.17727930e+03 2.19121167e+03 2.19447681e+03 2.21016479e+03 2.22422681e+03 2.22401172e+03 2.23650977e+03 2.24643628e+03 2.25276001e+03 2.25660815e+03 2.25579932e+03 2.27268384e+03 2.28455444e+03 2.29077246e+03 2.28798560e+03 2.29024438e+03 2.29330859e+03 2.29938745e+03 2.31958740e+03 2.32138892e+03 2.30951465e+03 2.32142236e+03 2.32530835e+03 2.32389771e+03 2.32967627e+03 2.32659888e+03 2.33188525e+03 2.33409546e+03 2.33383374e+03 2.32789478e+03 2.33515918e+03 2.33612280e+03 2.33881885e+03 2.32824561e+03 2.32866113e+03 2.32566455e+03 2.33180884e+03 2.33079614e+03 2.31853467e+03 2.32516797e+03 2.31853516e+03 2.30782764e+03 2.31873706e+03 2.30124194e+03 2.29860938e+03 2.30121704e+03 2.29221704e+03 2.27820361e+03 2.27361401e+03 2.27444580e+03 2.26244507e+03 2.24924023e+03 2.25447412e+03 2.24364795e+03 2.23915308e+03 2.22364087e+03 2.20821973e+03 2.21097925e+03 2.19566504e+03 2.18552246e+03 2.18380640e+03 2.17075977e+03 2.15411719e+03 2.14119556e+03 2.13209131e+03 2.12552661e+03 2.11076343e+03 2.09643652e+03 2.08502466e+03 2.07433496e+03 2.05531787e+03 2.04386902e+03 2.03450903e+03 2.01883044e+03 1.99715308e+03 1.97968127e+03 1.96917102e+03 1.95961035e+03 1.94178320e+03 1.92536047e+03 1.90634485e+03 1.88959766e+03 1.87671582e+03 1.85740063e+03 1.83787891e+03 1.82201172e+03 1.80443359e+03 1.78728259e+03 1.76514185e+03 1.74747925e+03 1.72757996e+03 1.70697534e+03 1.68884143e+03 1.67462012e+03 1.64882153e+03 1.62782007e+03 1.60966064e+03 1.58729993e+03 1.56542749e+03 1.54469373e+03 1.52173621e+03 1.50415979e+03 1.48167151e+03 1.45481018e+03 1.43558630e+03 1.41362854e+03 1.38773169e+03 1.36495984e+03 1.34641687e+03 1.31983472e+03 1.29326257e+03 1.27330347e+03 1.24805969e+03 1.22253906e+03 1.19968420e+03 1.17427722e+03 1.14902307e+03 1.12472852e+03 1.09783728e+03 1.07337549e+03 1.05117346e+03 1.02305920e+03 9.95107910e+02 9.70022827e+02 9.44361511e+02 9.18230530e+02 8.92516113e+02 8.65317566e+02 8.39418152e+02 8.12528320e+02 7.84713013e+02 7.57451721e+02 7.30669983e+02 7.03481995e+02 6.76468323e+02 6.48990356e+02 6.21306519e+02 5.93453003e+02 5.65880859e+02 5.38301514e+02 5.09889679e+02 4.81754425e+02 4.53892212e+02 4.25815216e+02 3.97866516e+02 3.69526154e+02 3.41015839e+02 3.12461121e+02 2.84175995e+02 2.55781448e+02 2.27170593e+02 1.98742722e+02 1.70190704e+02 1.41577454e+02 1.13040245e+02 8.43742981e+01 5.57089462e+01 2.71198578e+01 -1.57965565e+00 -3.02571735e+01 -5.88146667e+01 -8.74958420e+01 -1.16179169e+02 -1.44743729e+02 -1.73400375e+02 -2.01951233e+02 -2.30412262e+02 -2.58951263e+02 -2.87370941e+02 -3.15766388e+02 -3.44308411e+02 -3.72616882e+02 -4.00598022e+02 -4.28874969e+02 -4.57233612e+02 -4.85157898e+02 -5.13156006e+02 -5.40949524e+02 -5.68857361e+02 -5.96886963e+02 -6.24026611e+02 -6.51657410e+02 -6.79365906e+02 -7.06149048e+02 -7.33609985e+02 -7.61929016e+02 -7.88543823e+02 -8.14993225e+02 -8.41709717e+02 -8.68484009e+02 -8.94704712e+02 -9.21516235e+02 -9.48037109e+02 -9.72938477e+02 -9.98868042e+02 -1.02533240e+03 -1.05337061e+03 -1.07782275e+03 -1.10070337e+03 -1.12479431e+03 -1.15287927e+03 -1.17929541e+03 -1.20118591e+03 -1.22595068e+03 -1.25232568e+03 -1.27416980e+03 -1.29376282e+03 -1.32158801e+03 -1.34751074e+03 -1.36864038e+03 -1.39260876e+03 -1.41487524e+03 -1.43658301e+03 -1.46139331e+03 -1.48552832e+03 -1.50654053e+03 -1.52583484e+03 -1.54664172e+03 -1.56917090e+03 -1.59092664e+03 -1.60887378e+03 -1.63255518e+03 -1.65110266e+03 -1.66737622e+03 -1.69520251e+03 -1.71340369e+03 -1.72823438e+03 -1.75181458e+03 -1.76942346e+03 -1.78892664e+03 -1.80678711e+03 -1.82062646e+03 -1.83935132e+03 -1.86421753e+03 -1.87688855e+03 -1.88736902e+03 -1.91487305e+03 -1.93034937e+03 -1.94166040e+03 -1.95610229e+03 -1.97547485e+03 -1.98948230e+03 -1.99975781e+03 -2.02055249e+03 -2.03489539e+03 -2.04682153e+03 -2.05667871e+03 -2.07513843e+03 -2.08994287e+03 -2.09638892e+03 -2.10772144e+03 -2.12332666e+03 -2.13679077e+03 -2.14868237e+03 -2.16054639e+03 -2.16341553e+03 -2.17685474e+03 -2.19199731e+03 -2.19311841e+03 -2.20679468e+03 -2.22040479e+03 -2.22523364e+03 -2.23511719e+03 -2.24879297e+03 -2.25212036e+03 -2.25394409e+03 -2.26130493e+03 -2.27478247e+03 -2.28097681e+03 -2.28434521e+03 -2.28647852e+03 -2.28923340e+03 -2.29890820e+03 -2.30260522e+03 -2.31446240e+03 -2.31746533e+03 -2.31424219e+03 -2.32211743e+03 -2.32130273e+03 -2.32087378e+03 -2.33557178e+03 -2.33557764e+03 -2.33014722e+03 -2.33347241e+03 -2.33696289e+03 -2.33578906e+03 -2.33590259e+03 -2.33099023e+03 -2.33551025e+03 -2.33257227e+03 -2.33624072e+03 -2.32892310e+03 -2.32887036e+03 -2.32971411e+03 -2.32029248e+03 -2.32200220e+03 -2.31504688e+03 -2.30667896e+03 -2.31196753e+03 -2.30042285e+03 -2.29453833e+03 -2.29101196e+03 -2.28534766e+03 -2.27789551e+03 -2.27196387e+03 -2.90395532e+03 -2.99875415e+03 -5.19703418e+03 -6.39966113e+03 -67023336. -2.95307725e+06 0. 0. -109199712. -109199712. -109199712. 0. 0. 0. -162924736. -1.08207662e+06 2.32011680e+04 -6.36718262e+03 -5.47721338e+03 -3.23086475e+03 -3.02160620e+03 -2.11283691e+03 -2.05979541e+03 -2.04467773e+03 -2.02686462e+03 -2.00496680e+03 -1.98152698e+03 -1.96992261e+03 -1.95868787e+03 -1.94154443e+03 -1.92717798e+03 -1.90544421e+03 -1.89257715e+03 -1.87784045e+03 -1.85517041e+03 -1.83965833e+03 -1.81836719e+03 -1.80130579e+03 -1.78299756e+03 -1.76436169e+03 -1.74603345e+03 -1.72764844e+03 -1.71049951e+03 -1.68998401e+03 -1.67295496e+03 -1.64948779e+03 -1.62720886e+03 -1.61073486e+03 -1.59102014e+03 -1.57170691e+03 -1.54617175e+03 -1.52360864e+03 -1.50552454e+03 -1.48003027e+03 -1.45503125e+03 -1.43658337e+03 -1.41607166e+03 -1.38820337e+03 -1.36462585e+03 -1.34657092e+03 -1.32114990e+03 -1.29293005e+03 -1.27289429e+03 -1.24841870e+03 -1.22329004e+03 -1.20005017e+03 -1.17471716e+03 -1.14921594e+03 -1.12495813e+03 -1.09782043e+03 -1.07456311e+03 -1.05149731e+03 -1.02285858e+03 -9.96071289e+02 -9.70053711e+02 -9.44146729e+02 -9.19502441e+02 -8.92655029e+02 -8.65175415e+02 -8.39534607e+02 -8.12443848e+02 -7.85246948e+02 -7.57953918e+02 -7.30860107e+02 -7.03714844e+02 -6.76855896e+02 -6.49178528e+02 -6.21341858e+02 -5.93852722e+02 -5.66351685e+02 -5.38354858e+02 -5.09992035e+02 -4.82052063e+02 -4.54195007e+02 -4.26194092e+02 -3.98069000e+02 -3.69694366e+02 -3.41300690e+02 -3.12392029e+02 -2.84288849e+02 -2.56146454e+02 -2.27467163e+02 -1.99019730e+02 -1.70247131e+02 -1.41525543e+02 -1.12444664e+02 -8.31861420e+01 -5.56676636e+01 -1.39985352e+02 2.24530094e+05 1.48884506e+02 5.13182678e+01 7.94213486e+01 1.07239540e+02 1.35280136e+02 1.63994156e+02 1.92395737e+02 2.19736725e+02 2.47842407e+02 2.76062164e+02 3.03992889e+02 3.32328522e+02 3.60197906e+02 3.87949677e+02 4.15822998e+02 4.43482971e+02 4.71173157e+02 4.98917877e+02 5.25836853e+02 5.53344299e+02 5.81165955e+02 6.07927673e+02 6.35643005e+02 6.62685791e+02 6.88246338e+02 7.16003235e+02 7.44136353e+02 7.69716614e+02 7.95301331e+02 8.22322388e+02 8.49672241e+02 8.75604797e+02 9.00974060e+02 9.25859375e+02 9.51571960e+02 9.78226868e+02 1.00377545e+03 1.03023633e+03 1.05433044e+03 1.07795471e+03 1.10309180e+03 1.12796558e+03 1.15270386e+03 1.17839795e+03 1.20154871e+03 1.22496704e+03 1.25072559e+03 1.27072412e+03 1.29438892e+03 1.32133582e+03 1.34320776e+03 1.36673987e+03 1.38700842e+03 1.40782166e+03 1.43348511e+03 1.45632776e+03 1.47731543e+03 1.49785657e+03 1.51709143e+03 1.54170203e+03 1.56197864e+03 1.57662012e+03 1.59992786e+03 1.62255444e+03 1.63874292e+03 1.66174292e+03 1.68243518e+03 1.69959033e+03 1.71735571e+03 1.73857983e+03 1.75718811e+03 1.77622876e+03 1.79037512e+03 1.80701111e+03 1.82782654e+03 1.84196362e+03 1.86143701e+03 1.87650354e+03 1.89410022e+03 1.90821289e+03 1.92171899e+03 1.94225110e+03 2.51369189e+03 2.62777686e+03 4.69760059e+03 3.34227319e+03 6.12988623e+03 2.30895547e+04 -181367584. 174491184. 174491184. 9073104. -948973952. -948973952. 0. 0. 0. 0. 0. 0. 7.97435950e+06 -19440566. 2.59315503e+03 6.06676416e+03 5.15198291e+03 2.87234766e+03 2.21900586e+03 2.22848633e+03 2.23519434e+03 2.24358081e+03 2.24779468e+03 2.25092139e+03 2.26741357e+03 2.26277344e+03 2.26232812e+03 2.27996753e+03 2.27949219e+03 2.28012524e+03 2.28815381e+03 2.28711865e+03 2.28474634e+03 2.29160645e+03 2.29305762e+03 2.29253882e+03 2.29415283e+03 2.29596216e+03 2.30164502e+03 2.29675195e+03 2.29689062e+03 2.30189771e+03 2.29379150e+03 2.29539160e+03 2.29990771e+03 2.29102856e+03 2.28977637e+03 2.28964209e+03 2.28650293e+03 2.28422974e+03 2.28206592e+03 2.27611353e+03 2.26408936e+03 2.26668164e+03 2.26641016e+03 2.25382959e+03 2.24426660e+03 2.24334644e+03 2.24350293e+03 2.22629004e+03 2.22254224e+03 2.21673901e+03 2.21501562e+03 2.20056909e+03 2.18625732e+03 2.18124731e+03 2.17930933e+03 2.16278931e+03 2.14898047e+03 2.14807910e+03 2.14323975e+03 2.12563330e+03 2.11057349e+03 2.10252856e+03 2.09494971e+03 2.08027490e+03 2.06383130e+03 2.05299023e+03 2.04350830e+03 2.02565369e+03 2.01527283e+03 2.00946021e+03 1.98885388e+03 1.97074438e+03 1.95661609e+03 1.94504358e+03 1.93115259e+03 1.91690955e+03 1.89613623e+03 1.88030859e+03 1.86808704e+03 1.84972083e+03 1.83607556e+03 1.81650513e+03 1.79112305e+03 1.78102917e+03 1.76549731e+03 1.73951733e+03 1.72350623e+03 1.70991724e+03 1.68668604e+03 1.66482214e+03 1.65064758e+03 1.62988452e+03 1.60781421e+03 1.58885022e+03 1.56810608e+03 1.54760718e+03 1.52678479e+03 1.50283740e+03 1.48630859e+03 1.46322534e+03 1.43633276e+03 1.41889380e+03 1.39854114e+03 1.37158386e+03 1.34745361e+03 1.32900549e+03 1.30424902e+03 1.27947534e+03 1.25865137e+03 1.23413147e+03 1.20827368e+03 1.18593591e+03 1.16283557e+03 1.13914734e+03 1.11246753e+03 1.08524768e+03 1.06220618e+03 1.04003845e+03 1.01312250e+03 9.86229980e+02 9.60739990e+02 9.35114746e+02 9.10718384e+02 8.84518738e+02 8.57679443e+02 8.32742676e+02 8.05819519e+02 7.78354126e+02 7.52067749e+02 7.25674072e+02 6.99277954e+02 6.72725159e+02 6.45053650e+02 6.18105286e+02 5.91057922e+02 5.63423340e+02 5.36299988e+02 5.08271912e+02 4.80376251e+02 4.53552002e+02 4.26087311e+02 3.98213623e+02 3.70302216e+02 3.42327301e+02 3.14232208e+02 2.86427399e+02 2.58490204e+02 2.30339722e+02 2.02347382e+02 1.74222382e+02 1.46060181e+02 1.17962662e+02 8.97624893e+01 6.15480766e+01 3.33812065e+01 5.18099594e+00 -2.30502949e+01 -5.12009239e+01 -7.93978043e+01 -1.07625626e+02 -1.35719055e+02 -1.63943802e+02 -1.92032288e+02 -2.20044724e+02 -2.48286591e+02 -2.76199829e+02 -3.03994781e+02 -3.32166718e+02 -3.60175140e+02 -3.87740234e+02 -4.15749268e+02 -4.43512360e+02 -4.71039581e+02 -4.98485718e+02 -5.25611938e+02 -5.53685608e+02 -5.80715698e+02 -6.07279297e+02 -6.35576355e+02 -6.62579468e+02 -6.88323303e+02 -7.15778870e+02 -7.43381897e+02 -7.69245056e+02 -7.95258484e+02 -8.22382324e+02 -8.49495605e+02 -8.75239441e+02 -9.00864441e+02 -9.25621033e+02 -9.50949585e+02 -9.77705261e+02 -1.00404706e+03 -1.02996985e+03 -1.05387903e+03 -1.07861255e+03 -1.10136157e+03 -1.12801135e+03 -1.15422363e+03 -1.17716333e+03 -1.20081714e+03 -1.22550208e+03 -1.24936035e+03 -1.26849524e+03 -1.29427478e+03 -1.31930078e+03 -1.34197607e+03 -1.36627441e+03 -1.38600049e+03 -1.40869360e+03 -1.43284583e+03 -1.45510925e+03 -1.47785107e+03 -1.49825244e+03 -1.51615442e+03 -1.53907739e+03 -1.56028430e+03 -1.57777820e+03 -1.60074438e+03 -1.62320386e+03 -1.63826807e+03 -1.66007446e+03 -1.68162378e+03 -1.69930090e+03 -1.71828003e+03 -1.73919885e+03 -1.75591199e+03 -1.77581360e+03 -1.78837854e+03 -1.80475208e+03 -1.82875208e+03 -1.83964331e+03 -1.85904065e+03 -1.87707983e+03 -1.88998010e+03 -1.91058752e+03 -1.92205798e+03 -1.93730066e+03 -1.95085791e+03 -1.96799084e+03 -1.98394751e+03 -1.99948254e+03 -2.01218384e+03 -2.02214368e+03 -2.03811829e+03 -2.05458545e+03 -2.06122388e+03 -2.07195581e+03 -2.08545654e+03 -2.09462500e+03 -2.11040381e+03 -2.12382227e+03 -2.12876953e+03 -2.14170825e+03 -2.15411743e+03 -2.15930737e+03 -2.17377563e+03 -2.18633960e+03 -2.18909961e+03 -2.19879712e+03 -2.20048682e+03 -2.21066968e+03 -2.21988794e+03 -2.23083081e+03 -2.24068091e+03 -2.23816846e+03 -2.24680249e+03 -2.25171729e+03 -2.25902319e+03 -2.26097485e+03 -2.26381079e+03 -2.27609717e+03 -2.27552759e+03 -2.27899609e+03 -2.28353979e+03 -2.28286377e+03 -2.28503149e+03 -2.29324731e+03 -2.29291406e+03 -2.29023950e+03 -2.29111743e+03 -2.29754126e+03 -2.30588452e+03 -2.30229907e+03 -2.29538281e+03 -2.29556689e+03 -2.29577661e+03 -2.29909473e+03 -2.29551196e+03 -2.28441553e+03 -2.28709888e+03 -2.29249707e+03 -2.28453687e+03 -2.28115674e+03 -2.28592725e+03 -2.27468384e+03 -2.26405591e+03 -2.26455908e+03 -2.26250073e+03 -2.25191968e+03 -2.24478149e+03 -2.24384424e+03 -2.24473755e+03 -2.22808691e+03 -2.22420044e+03 -2.21848242e+03 -2.21265771e+03 -2.19898169e+03 -2.18452686e+03 -2.18114087e+03 -2.18144067e+03 -2.16921240e+03 -2.15159082e+03 -2.15073486e+03 -2.14066357e+03 -2.12096997e+03 -2.10842725e+03 -2.10077979e+03 -2.09423413e+03 -2.08006665e+03 -2.06538525e+03 -2.05191699e+03 -2.04281909e+03 -2.02525818e+03 -2.01618835e+03 -2.00802332e+03 -1.98900085e+03 -1.96707458e+03 -1.95588916e+03 -1.94404236e+03 -1.93158728e+03 -1.91821838e+03 -1.89534656e+03 -1.88147778e+03 -1.86555591e+03 -1.84968945e+03 -1.83531055e+03 -1.81475598e+03 -1.79188171e+03 -1.77834985e+03 -1.76424158e+03 -1.74093396e+03 -1.72197070e+03 -1.70931335e+03 -1.68848523e+03 -1.66558533e+03 -1.64986499e+03 -1.62903247e+03 -1.60711792e+03 -1.58927966e+03 -1.56805823e+03 -1.54773584e+03 -1.52539209e+03 -1.50324243e+03 -1.48466760e+03 -1.46172827e+03 -1.43766626e+03 -1.41942505e+03 -1.39814197e+03 -1.37157947e+03 -1.34740247e+03 -1.32964124e+03 -1.30462256e+03 -1.27844617e+03 -1.25865161e+03 -1.23379871e+03 -1.20799792e+03 -1.18636438e+03 -1.16230957e+03 -1.13854749e+03 -1.11258423e+03 -1.08509326e+03 -1.06269556e+03 -1.03977344e+03 -1.01259747e+03 -9.85445496e+02 -9.60161560e+02 -9.35966919e+02 -9.11153137e+02 -8.84241638e+02 -8.57710327e+02 -8.32752991e+02 -8.05804688e+02 -7.78345093e+02 -7.51919373e+02 -7.25631042e+02 -6.99191589e+02 -6.72440247e+02 -6.45008484e+02 -6.18245728e+02 -5.90854675e+02 -5.63290100e+02 -5.36346924e+02 -5.08113220e+02 -4.80566711e+02 -4.53497009e+02 -4.25970245e+02 -3.98214722e+02 -3.70358032e+02 -3.42344513e+02 -3.14117432e+02 -2.86306305e+02 -2.58522858e+02 -2.30341827e+02 -2.02310928e+02 -1.74209198e+02 -1.46043716e+02 -1.17926155e+02 -8.97385025e+01 -6.15521889e+01 -3.33583183e+01 -5.14777279e+00 2.30435753e+01 5.12092018e+01 7.94205933e+01 1.07598412e+02 1.35683319e+02 1.63930542e+02 1.92038162e+02 2.20082153e+02 2.48248749e+02 2.76189056e+02 3.04033142e+02 3.32108185e+02 3.60084778e+02 3.87770844e+02 4.15691620e+02 4.43294617e+02 4.70903809e+02 4.98779144e+02 5.25695679e+02 5.53068054e+02 5.80906372e+02 6.07694092e+02 6.35394287e+02 6.62546753e+02 6.88109375e+02 7.15713745e+02 7.43889160e+02 7.69593506e+02 7.94901978e+02 8.21900452e+02 8.49393921e+02 8.75669983e+02 9.00927307e+02 9.24978394e+02 9.51417419e+02 9.78365173e+02 1.00369440e+03 1.02956482e+03 1.05368384e+03 1.07783765e+03 1.10267566e+03 1.12826440e+03 1.15293408e+03 1.17766077e+03 1.20178564e+03 1.22528516e+03 1.24893591e+03 1.26959253e+03 1.29534595e+03 1.32042957e+03 1.34316907e+03 1.36531726e+03 1.38685779e+03 1.40897729e+03 1.43321704e+03 1.45546814e+03 1.47638171e+03 1.49632581e+03 1.51625635e+03 1.54104492e+03 1.56237134e+03 1.57889160e+03 1.60109155e+03 1.62184412e+03 1.63852295e+03 1.66126794e+03 1.68240820e+03 1.69924719e+03 1.71807361e+03 1.73494312e+03 1.75611841e+03 1.77448669e+03 1.78894226e+03 1.80820703e+03 1.82656934e+03 1.84020984e+03 1.85709656e+03 1.87804980e+03 1.89378552e+03 1.90990796e+03 1.92306128e+03 1.93884644e+03 1.95352417e+03 1.96622778e+03 1.98522693e+03 2.00131580e+03 2.01341174e+03 2.01759521e+03 2.03688293e+03 2.05835522e+03 2.06177759e+03 2.07218311e+03 2.08909717e+03 2.09274854e+03 2.10805151e+03 2.12763745e+03 2.12647192e+03 2.14095117e+03 2.15544141e+03 2.15606177e+03 2.17458350e+03 2.18512036e+03 2.19322144e+03 2.20074756e+03 2.19852930e+03 2.20991870e+03 2.21783618e+03 2.22683911e+03 2.23950122e+03 2.24405933e+03 2.24944482e+03 2.25232861e+03 2.26086646e+03 2.25828491e+03 2.26325049e+03 2.28108423e+03 2.27955786e+03 2.27581396e+03 2.28528442e+03 2.29038330e+03 2.28556909e+03 2.28862427e+03 2.29246899e+03 2.29180396e+03 2.29055029e+03 2.29672852e+03 2.30070605e+03 2.29785620e+03 2.29628857e+03 2.30395068e+03 2.29165723e+03 2.29599243e+03 2.29933496e+03 2.28787280e+03 2.28907202e+03 2.28687500e+03 2.28890698e+03 2.28216919e+03 2.27726294e+03 2.28181934e+03 2.26006665e+03 2.26448535e+03 2.26738477e+03 2.25130298e+03 2.24225708e+03 2.24368945e+03 2.24332422e+03 2.22799902e+03 2.22082129e+03 2.21548828e+03 2.21224121e+03 2.20141162e+03 2.18551978e+03 2.18075488e+03 2.18004419e+03 2.16568457e+03 2.15205566e+03 2.14972070e+03 2.14284253e+03 2.12359741e+03 2.10853979e+03 2.10416992e+03 2.09535034e+03 2.07809204e+03 2.06480444e+03 2.05356543e+03 2.04372021e+03 2.02584814e+03 2.01544104e+03 2.00628943e+03 1.98967542e+03 1.96729846e+03 1.95657727e+03 1.94359021e+03 1.92998340e+03 1.91549365e+03 1.89610864e+03 1.87845312e+03 1.86518994e+03 1.85186755e+03 1.83518188e+03 1.81460400e+03 1.79354187e+03 1.77974878e+03 1.76465234e+03 1.74111780e+03 1.72224780e+03 1.70934717e+03 1.68627234e+03 1.66478467e+03 1.65073438e+03 1.62769580e+03 1.60779004e+03 1.59002344e+03 1.56844763e+03 1.54692126e+03 1.52626770e+03 1.50331567e+03 1.48675610e+03 1.46299084e+03 1.43694153e+03 1.41916479e+03 1.39766382e+03 1.37142969e+03 1.34880457e+03 1.32973438e+03 1.30477344e+03 1.27874548e+03 1.25936377e+03 1.23423877e+03 1.20797375e+03 1.18583337e+03 1.16227332e+03 1.13788940e+03 1.11288330e+03 1.08602429e+03 1.06208215e+03 1.04035413e+03 1.01281128e+03 9.85951721e+02 9.60502319e+02 9.35346130e+02 9.10749268e+02 8.84635132e+02 8.57800720e+02 8.32885986e+02 8.06082886e+02 7.78183228e+02 7.51597595e+02 7.25591064e+02 6.99480530e+02 6.72638000e+02 6.44917969e+02 6.18165588e+02 5.90656860e+02 5.63323914e+02 5.36473389e+02 5.08298035e+02 4.80555023e+02 4.53467377e+02 4.25880341e+02 3.98191803e+02 3.70377014e+02 3.42345306e+02 3.14224304e+02 2.86360291e+02 2.58478943e+02 2.30313538e+02 2.02318695e+02 1.74227295e+02 1.46091309e+02 1.18005898e+02 8.97952423e+01 6.15793800e+01 3.34473953e+01 5.21751547e+00 -2.30162258e+01 -5.11606903e+01 -7.93708115e+01 -1.07571510e+02 -1.35676254e+02 -1.63904495e+02 -1.92050018e+02 -2.20068161e+02 -2.48204300e+02 -2.76209106e+02 -3.04093872e+02 -3.32181976e+02 -3.60092834e+02 -3.87628937e+02 -4.15653473e+02 -4.43414551e+02 -4.70952026e+02 -4.98735382e+02 -5.25769592e+02 -5.53386963e+02 -5.80750916e+02 -6.07449829e+02 -6.35360718e+02 -6.62740967e+02 -6.88359497e+02 -7.15743164e+02 -7.43777710e+02 -7.69456726e+02 -7.95201782e+02 -8.21926758e+02 -8.49300781e+02 -8.75161743e+02 -9.00715881e+02 -9.25841431e+02 -9.51236572e+02 -9.77383850e+02 -1.00383630e+03 -1.03035596e+03 -1.05448865e+03 -1.07810999e+03 -1.10146680e+03 -1.12816187e+03 -1.15452393e+03 -1.17696509e+03 -1.20104041e+03 -1.22578406e+03 -1.24911267e+03 -1.26936072e+03 -1.29501306e+03 -1.31958411e+03 -1.34224207e+03 -1.36615063e+03 -1.38624866e+03 -1.40844031e+03 -1.43263049e+03 -1.45628760e+03 -1.47747766e+03 -1.49754419e+03 -1.51742249e+03 -1.54016602e+03 -1.56101245e+03 -1.57823645e+03 -1.60135913e+03 -1.62293018e+03 -1.63699023e+03 -1.66123938e+03 -1.68384363e+03 -1.69847253e+03 -1.71730591e+03 -1.73804980e+03 -1.75615698e+03 -1.77511597e+03 -1.78824634e+03 -1.80526501e+03 -1.82876465e+03 -1.84016357e+03 -1.85883350e+03 -1.87667102e+03 -1.89254199e+03 -1.90938940e+03 -1.92244482e+03 -1.93892371e+03 -1.95321680e+03 -1.96833008e+03 -1.98480151e+03 -1.99826587e+03 -2.01016541e+03 -2.02203125e+03 -2.03826013e+03 -2.05287915e+03 -2.06339990e+03 -2.07270312e+03 -2.08705664e+03 -2.09636890e+03 -2.11223340e+03 -2.12584814e+03 -2.12781519e+03 -2.14145215e+03 -2.15503589e+03 -2.15742383e+03 -2.17513989e+03 -2.18284619e+03 -2.18990723e+03 -2.20323291e+03 -2.20408521e+03 -2.21066479e+03 -2.21745215e+03 -2.22689331e+03 -2.24101196e+03 -2.23985620e+03 -2.25048242e+03 -2.24891187e+03 -2.26162476e+03 -2.26240674e+03 -2.26252393e+03 -2.27633643e+03 -2.28118848e+03 -2.27758276e+03 -2.28369824e+03 -2.28708813e+03 -2.28955347e+03 -2.29637036e+03 -2.29540527e+03 -2.29359473e+03 -2.28697632e+03 -2.29525635e+03 -2.30777539e+03 -2.29835327e+03 -2.29790698e+03 -2.29970483e+03 -2.28812573e+03 -2.29779053e+03 -2.29642773e+03 -2.28794531e+03 -2.28710107e+03 -2.28820410e+03 -2.28393384e+03 -2.28016772e+03 -2.27327441e+03 -2.27151294e+03 -2.26139893e+03 -2.25966113e+03 -2.26180542e+03 -2.24970142e+03 -2.24450293e+03 -2.24152515e+03 -2.23985669e+03 -2.22651221e+03 -2.84367554e+03 -2.97026782e+03 -5.14618262e+03 -6.50709424e+03 4580439. -100211816. 0. 0. 0. 313247168. 313247168. 313247168. 0. 0. 0. -44713372. 5275728. -8.08604053e+03 -5.53631836e+03 -3.21002393e+03 -3.00021509e+03 -2.73910034e+03 -1.99234668e+03 -1.97303821e+03 -1.95235327e+03 -1.94074597e+03 -1.93205408e+03 -1.91535010e+03 -1.89583630e+03 -1.87690723e+03 -1.86665027e+03 -1.85245959e+03 -1.83110706e+03 -1.81093091e+03 -1.79028613e+03 -1.77554211e+03 -1.76296716e+03 -1.74073938e+03 -1.72078894e+03 -1.70788208e+03 -1.69029724e+03 -1.66658118e+03 -1.64985034e+03 -1.62784302e+03 -1.60949866e+03 -1.59017078e+03 -1.57035217e+03 -1.55684607e+03 -1.53072913e+03 -1.50506567e+03 -1.48786316e+03 -1.46173511e+03 -1.43618701e+03 -1.41940796e+03 -1.39815625e+03 -1.37190820e+03 -1.34775293e+03 -1.32983972e+03 -1.30533398e+03 -1.27910791e+03 -1.25791565e+03 -1.23494287e+03 -1.20915308e+03 -1.18703125e+03 -1.16311292e+03 -1.13894226e+03 -1.11204834e+03 -1.08511072e+03 -1.06382007e+03 -1.04077136e+03 -1.01266162e+03 -9.86297180e+02 -9.60802429e+02 -9.35872009e+02 -9.11732117e+02 -8.84641052e+02 -8.57950378e+02 -8.33050110e+02 -8.06030029e+02 -7.78743713e+02 -7.52209167e+02 -7.25938538e+02 -6.99557495e+02 -6.73022461e+02 -6.45271851e+02 -6.18277710e+02 -5.90648010e+02 -5.63382935e+02 -5.36403564e+02 -5.08158844e+02 -4.80647400e+02 -4.53385498e+02 -4.25921112e+02 -3.98487701e+02 -3.69766510e+02 -3.41288116e+02 -3.13569092e+02 -2.86213959e+02 -2.58696289e+02 -2.30512192e+02 -2.02444778e+02 -1.74191483e+02 -1.45915237e+02 -1.17287880e+02 -8.86127625e+01 -6.13481941e+01 -1.57073364e+02 3.12323125e+04 1.67648071e+02 5.58630562e+01 8.35931625e+01 1.11080856e+02 1.38830963e+02 1.67104721e+02 1.95114304e+02 2.22181580e+02 2.49850723e+02 2.77733215e+02 3.05248169e+02 3.33066650e+02 3.60460876e+02 3.87961731e+02 4.15521301e+02 4.42296844e+02 4.69388428e+02 4.96678192e+02 5.23393494e+02 5.51170654e+02 5.78474792e+02 6.05094727e+02 6.32180176e+02 6.58713013e+02 6.85138489e+02 7.11818237e+02 7.38381104e+02 7.63912415e+02 7.89627869e+02 8.16265442e+02 8.43109497e+02 8.68283386e+02 8.93953979e+02 9.18693909e+02 9.43430115e+02 9.69198059e+02 9.94624634e+02 1.02058051e+03 1.04498425e+03 1.06819678e+03 1.09283789e+03 1.11758789e+03 1.14185938e+03 1.16739783e+03 1.18970496e+03 1.21196436e+03 1.23825793e+03 1.25769128e+03 1.28206250e+03 1.30708997e+03 1.32672253e+03 1.35175159e+03 1.37353015e+03 1.39289343e+03 1.41980139e+03 1.43819531e+03 1.45913660e+03 1.48557947e+03 1.50317004e+03 1.52167859e+03 1.54130469e+03 1.55768640e+03 1.58279858e+03 1.60602832e+03 1.61828564e+03 1.64070935e+03 1.66318567e+03 1.68200732e+03 1.69993933e+03 1.71515881e+03 1.73485669e+03 1.75408704e+03 1.77115747e+03 1.78547571e+03 1.80267786e+03 1.81873950e+03 1.84033826e+03 1.85213892e+03 1.86766052e+03 1.88339478e+03 2.47779541e+03 2.63529053e+03 4.54525781e+03 5.48046582e+03 29678704. 10822057. 5.37770650e+06 5.37770650e+06 0. 13341798. 13341798. 58420816. -948973952. -948973952. 0. 0. 0. 0. 102847440. 4.01055325e+06 6.28301416e+03 5.11424854e+03 3.21847632e+03 2.88630615e+03 2.77304248e+03 2.18289355e+03 2.18767896e+03 2.19895557e+03 2.20632227e+03 2.21097998e+03 2.21922485e+03 2.22400415e+03 2.23416626e+03 2.22810840e+03 2.23377808e+03 2.25506641e+03 2.24724707e+03 2.24362915e+03 2.25436353e+03 2.26056055e+03 2.25984741e+03 2.25734521e+03 2.26373389e+03 2.25916748e+03 2.25452930e+03 2.26719678e+03 2.27635376e+03 2.26939795e+03 2.26492920e+03 2.27415967e+03 2.26809009e+03 2.26411133e+03 2.26533765e+03 2.26214233e+03 2.26231519e+03 2.25475220e+03 2.25116577e+03 2.25211328e+03 2.24633765e+03 2.24569946e+03 2.23085571e+03 2.23219653e+03 2.23866187e+03 2.22216602e+03 2.21520703e+03 2.21493750e+03 2.20451733e+03 2.19365503e+03 2.19216260e+03 2.18470459e+03 2.17632422e+03 2.16690527e+03 2.15716113e+03 2.15768799e+03 2.14698535e+03 2.13087036e+03 2.11938379e+03 2.11641699e+03 2.11172998e+03 2.08844189e+03 2.07937817e+03 2.07667627e+03 2.06748926e+03 2.04659705e+03 2.03222961e+03 2.02554565e+03 2.01330090e+03 1.99595117e+03 1.98321448e+03 1.97722986e+03 1.95944641e+03 1.93956018e+03 1.93037732e+03 1.91456311e+03 1.89699561e+03 1.88987170e+03 1.86548120e+03 1.85000781e+03 1.83911072e+03 1.81982703e+03 1.80757642e+03 1.78754529e+03 1.76607434e+03 1.74949170e+03 1.73584766e+03 1.71294409e+03 1.69731689e+03 1.68367139e+03 1.66026648e+03 1.63861499e+03 1.61986804e+03 1.60330664e+03 1.58164539e+03 1.56236365e+03 1.54573108e+03 1.52360620e+03 1.49997046e+03 1.47506506e+03 1.45915344e+03 1.43733301e+03 1.41477942e+03 1.39675354e+03 1.37455884e+03 1.34914453e+03 1.32294568e+03 1.30546765e+03 1.28160437e+03 1.25771838e+03 1.23735352e+03 1.21270996e+03 1.18685388e+03 1.16399023e+03 1.14204932e+03 1.11891748e+03 1.09190503e+03 1.06585413e+03 1.04315906e+03 1.02064453e+03 9.94370728e+02 9.67495422e+02 9.42475159e+02 9.17248047e+02 8.92592285e+02 8.67198608e+02 8.40869019e+02 8.15142090e+02 7.89284973e+02 7.62760864e+02 7.37221069e+02 7.10510986e+02 6.83895874e+02 6.57376892e+02 6.30541321e+02 6.04137939e+02 5.77366272e+02 5.50003601e+02 5.23086304e+02 4.95961273e+02 4.68462738e+02 4.41722229e+02 4.14545166e+02 3.87000397e+02 3.59528900e+02 3.32023956e+02 3.04393219e+02 2.76804932e+02 2.49260559e+02 2.21597305e+02 1.93963181e+02 1.66188232e+02 1.38436646e+02 1.10706871e+02 8.28955841e+01 5.50885391e+01 2.72902336e+01 -5.26037514e-01 -2.83582916e+01 -5.61356163e+01 -8.39505005e+01 -1.11757942e+02 -1.39453674e+02 -1.67233292e+02 -1.94950119e+02 -2.22652725e+02 -2.50448593e+02 -2.77954681e+02 -3.05342255e+02 -3.33000397e+02 -3.60530304e+02 -3.87984375e+02 -4.15710602e+02 -4.42642548e+02 -4.69807831e+02 -4.97290588e+02 -5.24049988e+02 -5.51385925e+02 -5.77942444e+02 -6.04353882e+02 -6.31922607e+02 -6.58444458e+02 -6.85144531e+02 -7.11515930e+02 -7.37792114e+02 -7.63602600e+02 -7.89380188e+02 -8.16042358e+02 -8.43186157e+02 -8.68500366e+02 -8.93757141e+02 -9.18295837e+02 -9.43068176e+02 -9.69003052e+02 -9.94433960e+02 -1.02067957e+03 -1.04454761e+03 -1.06918750e+03 -1.09137476e+03 -1.11729578e+03 -1.14291357e+03 -1.16510046e+03 -1.19045166e+03 -1.21335938e+03 -1.23644397e+03 -1.25677869e+03 -1.28228540e+03 -1.30470532e+03 -1.32511951e+03 -1.35195593e+03 -1.37274365e+03 -1.39421741e+03 -1.41924365e+03 -1.43616541e+03 -1.45971985e+03 -1.48675732e+03 -1.50263794e+03 -1.52016455e+03 -1.54194238e+03 -1.55835730e+03 -1.58249658e+03 -1.60666687e+03 -1.61870984e+03 -1.63905017e+03 -1.66313025e+03 -1.68135156e+03 -1.69905029e+03 -1.71572559e+03 -1.73336731e+03 -1.75455493e+03 -1.77243176e+03 -1.78451233e+03 -1.80216748e+03 -1.81864819e+03 -1.83818982e+03 -1.85026392e+03 -1.86666028e+03 -1.88718127e+03 -1.89669080e+03 -1.91078564e+03 -1.93047205e+03 -1.94703198e+03 -1.95923547e+03 -1.97388257e+03 -1.99103955e+03 -1.99584912e+03 -2.01222241e+03 -2.02822021e+03 -2.03211792e+03 -2.04615283e+03 -2.06284277e+03 -2.06763037e+03 -2.08271973e+03 -2.09617896e+03 -2.09719873e+03 -2.11512085e+03 -2.13263965e+03 -2.13049902e+03 -2.14367261e+03 -2.15475366e+03 -2.15990552e+03 -2.17215845e+03 -2.17625586e+03 -2.18285229e+03 -2.18881177e+03 -2.20534717e+03 -2.20463525e+03 -2.20390210e+03 -2.22308521e+03 -2.22474487e+03 -2.22901587e+03 -2.23154810e+03 -2.23664404e+03 -2.24994556e+03 -2.24446411e+03 -2.24180615e+03 -2.24871265e+03 -2.26377563e+03 -2.26238770e+03 -2.25054785e+03 -2.26256738e+03 -2.25722510e+03 -2.25166260e+03 -2.26676978e+03 -2.27897485e+03 -2.26784399e+03 -2.26234888e+03 -2.26364282e+03 -2.26952295e+03 -2.26926733e+03 -2.26676099e+03 -2.25825366e+03 -2.25671729e+03 -2.25438623e+03 -2.25023608e+03 -2.24661084e+03 -2.24945435e+03 -2.24519751e+03 -2.22527295e+03 -2.23129932e+03 -2.23655151e+03 -2.22185181e+03 -2.21205005e+03 -2.21320117e+03 -2.20652490e+03 -2.19390967e+03 -2.19266602e+03 -2.18210986e+03 -2.18056201e+03 -2.16814209e+03 -2.15729834e+03 -2.15326343e+03 -2.14832397e+03 -2.13481860e+03 -2.11517212e+03 -2.11195630e+03 -2.10888330e+03 -2.08933984e+03 -2.07836719e+03 -2.07471411e+03 -2.06809424e+03 -2.04793274e+03 -2.02874927e+03 -2.02334790e+03 -2.01479895e+03 -1.99232166e+03 -1.98170386e+03 -1.97816748e+03 -1.95826721e+03 -1.93825403e+03 -1.92864966e+03 -1.91415356e+03 -1.89813464e+03 -1.88931494e+03 -1.86609521e+03 -1.84904443e+03 -1.83808032e+03 -1.82117517e+03 -1.80639490e+03 -1.78688428e+03 -1.76515027e+03 -1.74758606e+03 -1.73691687e+03 -1.71441040e+03 -1.69463660e+03 -1.68190881e+03 -1.66092151e+03 -1.63848926e+03 -1.61968005e+03 -1.60274451e+03 -1.58131543e+03 -1.56285559e+03 -1.54594849e+03 -1.52308838e+03 -1.50034253e+03 -1.47433508e+03 -1.45806152e+03 -1.43685706e+03 -1.41486255e+03 -1.39839014e+03 -1.37370178e+03 -1.34788843e+03 -1.32427661e+03 -1.30601074e+03 -1.28189514e+03 -1.25608875e+03 -1.23603931e+03 -1.21243896e+03 -1.18725635e+03 -1.16450500e+03 -1.14138477e+03 -1.11791895e+03 -1.09223535e+03 -1.06608789e+03 -1.04258044e+03 -1.01965540e+03 -9.94476074e+02 -9.66655396e+02 -9.42501770e+02 -9.18434387e+02 -8.92471008e+02 -8.66931335e+02 -8.41053650e+02 -8.15460083e+02 -7.89077209e+02 -7.62610168e+02 -7.36994385e+02 -7.10382202e+02 -6.83938171e+02 -6.57194275e+02 -6.30500793e+02 -6.04297302e+02 -5.77018555e+02 -5.49852112e+02 -5.23250183e+02 -4.95882080e+02 -4.68601379e+02 -4.41670929e+02 -4.14402161e+02 -3.86956421e+02 -3.59556519e+02 -3.32037781e+02 -3.04323486e+02 -2.76729279e+02 -2.49304199e+02 -2.21605820e+02 -1.93948257e+02 -1.66191498e+02 -1.38435547e+02 -1.10703278e+02 -8.28843231e+01 -5.51028214e+01 -2.73175335e+01 5.28168678e-01 2.83373299e+01 5.60822716e+01 8.39045486e+01 1.11708206e+02 1.39403122e+02 1.67213562e+02 1.94944687e+02 2.22637772e+02 2.50413025e+02 2.77931427e+02 3.05316895e+02 3.32912048e+02 3.60457153e+02 3.87984344e+02 4.15628632e+02 4.42431732e+02 4.69668884e+02 4.97582336e+02 5.24182007e+02 5.50908386e+02 5.77969116e+02 6.04580139e+02 6.31673706e+02 6.58398132e+02 6.84914307e+02 7.11450073e+02 7.38040710e+02 7.63647644e+02 7.89260010e+02 8.15654785e+02 8.42761230e+02 8.68384033e+02 8.93763916e+02 9.18212769e+02 9.43601074e+02 9.69424744e+02 9.94199646e+02 1.01977338e+03 1.04442993e+03 1.06866235e+03 1.09266724e+03 1.11757666e+03 1.14157837e+03 1.16624744e+03 1.18942297e+03 1.21186963e+03 1.23668811e+03 1.25664062e+03 1.28154761e+03 1.30723315e+03 1.32702185e+03 1.35089539e+03 1.37268188e+03 1.39335120e+03 1.42042285e+03 1.43761377e+03 1.45897229e+03 1.48462366e+03 1.50075903e+03 1.52091406e+03 1.54142896e+03 1.55778479e+03 1.58251733e+03 1.60716174e+03 1.61818140e+03 1.63988721e+03 1.66255212e+03 1.68133545e+03 1.69841382e+03 1.71361536e+03 1.73443787e+03 1.75375574e+03 1.77163074e+03 1.78741833e+03 1.80259045e+03 1.81903564e+03 1.83592334e+03 1.85075256e+03 1.86826306e+03 1.88703735e+03 1.89790344e+03 1.91596960e+03 1.93012024e+03 1.94364136e+03 1.95850220e+03 1.97614404e+03 1.99036829e+03 1.99374646e+03 2.01264294e+03 2.03119910e+03 2.03246338e+03 2.04639819e+03 2.06501538e+03 2.06520850e+03 2.08056372e+03 2.09845166e+03 2.09986670e+03 2.11523584e+03 2.13183594e+03 2.13252002e+03 2.14355518e+03 2.15560571e+03 2.15895093e+03 2.16536694e+03 2.17249048e+03 2.18357251e+03 2.18688721e+03 2.20015112e+03 2.20328760e+03 2.20869287e+03 2.22197021e+03 2.22460498e+03 2.23143677e+03 2.22602612e+03 2.23343555e+03 2.25519360e+03 2.24638062e+03 2.24101587e+03 2.25163550e+03 2.26040601e+03 2.26057812e+03 2.25196948e+03 2.25868579e+03 2.26495923e+03 2.25475513e+03 2.26690527e+03 2.27207764e+03 2.27055493e+03 2.26312573e+03 2.27073560e+03 2.26375635e+03 2.26102588e+03 2.26715210e+03 2.26806934e+03 2.26126660e+03 2.25034106e+03 2.24965088e+03 2.24698389e+03 2.24503247e+03 2.24412866e+03 2.23053247e+03 2.23056738e+03 2.23675439e+03 2.22405566e+03 2.21338696e+03 2.21207202e+03 2.20810547e+03 2.19742480e+03 2.18980811e+03 2.18405151e+03 2.17942310e+03 2.17051074e+03 2.15859839e+03 2.15484180e+03 2.14987500e+03 2.13429639e+03 2.11699438e+03 2.11177173e+03 2.10865918e+03 2.09159839e+03 2.07650195e+03 2.07627075e+03 2.06645288e+03 2.04750525e+03 2.03042114e+03 2.02398364e+03 2.01383081e+03 1.99470471e+03 1.98440784e+03 1.97686633e+03 1.95808105e+03 1.93932666e+03 1.93086011e+03 1.91421423e+03 1.89652563e+03 1.88978662e+03 1.86634131e+03 1.84918420e+03 1.83806934e+03 1.82052100e+03 1.80585803e+03 1.78786743e+03 1.76487463e+03 1.74908618e+03 1.73550195e+03 1.71341870e+03 1.69489844e+03 1.68175220e+03 1.66086414e+03 1.64087585e+03 1.62033801e+03 1.60245764e+03 1.58199060e+03 1.56245337e+03 1.54472644e+03 1.52214734e+03 1.50053125e+03 1.47554260e+03 1.45940186e+03 1.43693628e+03 1.41352209e+03 1.39731262e+03 1.37341150e+03 1.34865149e+03 1.32448364e+03 1.30576770e+03 1.28147192e+03 1.25700684e+03 1.23731360e+03 1.21188745e+03 1.18686499e+03 1.16462280e+03 1.14130981e+03 1.11751672e+03 1.09227185e+03 1.06653955e+03 1.04259937e+03 1.02030060e+03 9.94324585e+02 9.67025635e+02 9.42134277e+02 9.17822083e+02 8.92707764e+02 8.66969910e+02 8.40942017e+02 8.15361023e+02 7.89075073e+02 7.62580017e+02 7.36738342e+02 7.10296143e+02 6.84004517e+02 6.57254761e+02 6.30392700e+02 6.04287903e+02 5.77050232e+02 5.49974365e+02 5.23312744e+02 4.95967651e+02 4.68556152e+02 4.41688263e+02 4.14440125e+02 3.86946625e+02 3.59551544e+02 3.32015228e+02 3.04398102e+02 2.76809265e+02 2.49300171e+02 2.21597733e+02 1.93944199e+02 1.66182266e+02 1.38462250e+02 1.10769279e+02 8.29342499e+01 5.51251068e+01 2.73602428e+01 -4.92171824e-01 -2.83133869e+01 -5.60514030e+01 -8.38604126e+01 -1.11669876e+02 -1.39403366e+02 -1.67215668e+02 -1.95011108e+02 -2.22690720e+02 -2.50370285e+02 -2.77923004e+02 -3.05373169e+02 -3.33017456e+02 -3.60494080e+02 -3.87889343e+02 -4.15538086e+02 -4.42588623e+02 -4.69908783e+02 -4.97439270e+02 -5.24183105e+02 -5.51385864e+02 -5.77861145e+02 -6.04506470e+02 -6.32000427e+02 -6.58495789e+02 -6.84910400e+02 -7.11525574e+02 -7.38211731e+02 -7.63952209e+02 -7.89477722e+02 -8.16010986e+02 -8.42779846e+02 -8.68047729e+02 -8.93921448e+02 -9.18823425e+02 -9.43488892e+02 -9.68724915e+02 -9.94518005e+02 -1.02069049e+03 -1.04517969e+03 -1.06867810e+03 -1.09136377e+03 -1.11755066e+03 -1.14285864e+03 -1.16503516e+03 -1.18896692e+03 -1.21370398e+03 -1.23699121e+03 -1.25652686e+03 -1.28233362e+03 -1.30590356e+03 -1.32616968e+03 -1.35188464e+03 -1.37295435e+03 -1.39365356e+03 -1.42019153e+03 -1.43750085e+03 -1.45866272e+03 -1.48595667e+03 -1.50093774e+03 -1.52102771e+03 -1.54214490e+03 -1.55790063e+03 -1.58237329e+03 -1.60649524e+03 -1.61956653e+03 -1.63991064e+03 -1.66356921e+03 -1.68003345e+03 -1.69896545e+03 -1.71566187e+03 -1.73442700e+03 -1.75352966e+03 -1.77197192e+03 -1.78556445e+03 -1.80288318e+03 -1.81990259e+03 -1.83955164e+03 -1.85182678e+03 -1.86818762e+03 -1.88735730e+03 -1.89540149e+03 -1.91411011e+03 -1.93027698e+03 -1.94710791e+03 -1.95717322e+03 -1.97366980e+03 -1.99059253e+03 -1.99533154e+03 -2.01300708e+03 -2.02922778e+03 -2.03348621e+03 -2.04744006e+03 -2.06254175e+03 -2.06673438e+03 -2.08295386e+03 -2.09611353e+03 -2.10159302e+03 -2.11503564e+03 -2.13249780e+03 -2.13017407e+03 -2.14220532e+03 -2.15097510e+03 -2.16182788e+03 -2.17056177e+03 -2.17410107e+03 -2.18338745e+03 -2.19165137e+03 -2.20548584e+03 -2.20655688e+03 -2.20629102e+03 -2.22375952e+03 -2.22157812e+03 -2.23152466e+03 -2.22959863e+03 -2.23311450e+03 -2.25089893e+03 -2.24467090e+03 -2.24007104e+03 -2.25530396e+03 -2.26141040e+03 -2.26165527e+03 -2.25431519e+03 -2.26008569e+03 -2.25961597e+03 -2.25284595e+03 -2.26841992e+03 -2.27502856e+03 -2.27103711e+03 -2.26666333e+03 -2.26551099e+03 -2.26523633e+03 -2.26058154e+03 -2.26776855e+03 -2.26337256e+03 -2.26079810e+03 -2.25255469e+03 -2.25060059e+03 -2.24928589e+03 -2.24536816e+03 -2.24295947e+03 -2.23146680e+03 -2.22653076e+03 -2.23205493e+03 -2.21925977e+03 -2.21198120e+03 -2.20914722e+03 -2.20529810e+03 -2.19606885e+03 -2.18877515e+03 -2.18468481e+03 -2.83426221e+03 -3.04165405e+03 -5.16631836e+03 -6.42406396e+03 -35367252. 13371977. 0. 313247168. 313247168. 313247168. 0. 0. -26495768. -26495768. -26495768. -112293200. -9462262. -1.39351426e+04 -5.82771094e+03 -5.03037256e+03 -2.80639062e+03 -2.62071484e+03 -1.93843701e+03 -1.91983911e+03 -1.90380481e+03 -1.88823950e+03 -1.86582263e+03 -1.85133093e+03 -1.84166821e+03 -1.82123572e+03 -1.80531885e+03 -1.78732324e+03 -1.76612439e+03 -1.74975354e+03 -1.73381177e+03 -1.71387451e+03 -1.69295032e+03 -1.67886877e+03 -1.66124707e+03 -1.64137158e+03 -1.62254211e+03 -1.60300098e+03 -1.58151086e+03 -1.56064404e+03 -1.54272375e+03 -1.52651929e+03 -1.50381689e+03 -1.47944080e+03 -1.46022546e+03 -1.43588770e+03 -1.41534277e+03 -1.39792749e+03 -1.37359583e+03 -1.34924915e+03 -1.32394824e+03 -1.30658691e+03 -1.28224622e+03 -1.25495068e+03 -1.23614551e+03 -1.21300256e+03 -1.18838391e+03 -1.16533350e+03 -1.14079199e+03 -1.11782922e+03 -1.09185193e+03 -1.06660291e+03 -1.04359570e+03 -1.02041699e+03 -9.94272766e+02 -9.67648499e+02 -9.42699158e+02 -9.17801270e+02 -8.93291199e+02 -8.66440918e+02 -8.40258240e+02 -8.15873108e+02 -7.89229614e+02 -7.62532227e+02 -7.36810120e+02 -7.10408875e+02 -6.84109375e+02 -6.57681274e+02 -6.30633972e+02 -6.04489746e+02 -5.77100708e+02 -5.49846008e+02 -5.23344910e+02 -4.95829803e+02 -4.68626587e+02 -4.41626953e+02 -4.14474976e+02 -3.87254517e+02 -3.59237305e+02 -3.31338226e+02 -3.04021606e+02 -2.76985596e+02 -2.49706131e+02 -2.21915253e+02 -1.94248306e+02 -1.66356201e+02 -1.38457291e+02 -1.10265488e+02 -8.21267700e+01 -5.51945992e+01 -1.38326523e+02 1.09747508e+05 1.75697388e+02 4.29269600e+01 6.21981392e+01 1.72900681e+02 2.14276428e+02 2.58012482e+02 3.00836365e+02 3.38621918e+02 3.80103485e+02 4.22177917e+02 4.62498566e+02 5.04819305e+02 5.49298157e+02 5.34971069e+02 4.13937256e+02 4.42078796e+02 4.68038574e+02 4.94488708e+02 5.21081360e+02 5.48764709e+02 5.75588806e+02 6.02147095e+02 6.28652100e+02 6.54780701e+02 6.81294983e+02 7.07559021e+02 7.33414062e+02 7.59181946e+02 7.85104370e+02 8.11486572e+02 8.38059509e+02 8.62325500e+02 8.87681335e+02 9.12118286e+02 9.37066895e+02 9.62757446e+02 9.87582703e+02 1.01293408e+03 1.03758191e+03 1.06154504e+03 1.08514941e+03 1.10937720e+03 1.13346301e+03 1.15780054e+03 1.18224670e+03 1.20417505e+03 1.22783911e+03 1.24895996e+03 1.27251294e+03 1.29667236e+03 1.31734094e+03 1.34001111e+03 1.36147351e+03 1.38438806e+03 1.40764893e+03 1.42854724e+03 1.44705469e+03 1.47057861e+03 1.49121423e+03 1.51076440e+03 1.53029053e+03 1.54845825e+03 1.57003210e+03 1.59229431e+03 1.60845459e+03 1.62886035e+03 1.65091614e+03 1.66659082e+03 1.68370837e+03 1.70149792e+03 1.72164355e+03 1.74011389e+03 1.75394531e+03 1.77114221e+03 1.78820752e+03 1.80466394e+03 1.82390723e+03 1.83405066e+03 1.84888647e+03 2.42571460e+03 4.44642529e+03 5.53179297e+03 -2931310. 118345432. 0. 5.37770650e+06 5.37770650e+06 5.37770650e+06 0. 13341798. 13341798. 58420816. -948973952. -70596080. -38501324. -38501324. 0. 59017032. 2.41368164e+04 5.04653711e+03 2.93191870e+03 2.77904932e+03 2.14198438e+03 2.15245215e+03 2.15374976e+03 2.16069189e+03 2.17495312e+03 2.17989478e+03 2.19045117e+03 2.19797534e+03 2.19975122e+03 2.20481836e+03 2.20978345e+03 2.21261060e+03 2.21523389e+03 2.22399194e+03 2.22578833e+03 2.22575000e+03 2.23400952e+03 2.23909351e+03 2.23882642e+03 2.23846533e+03 2.23858203e+03 2.24052222e+03 2.24044897e+03 2.24413501e+03 2.24916699e+03 2.24395215e+03 2.24469238e+03 2.25271826e+03 2.23930786e+03 2.24341870e+03 2.24148975e+03 2.23755151e+03 2.23877808e+03 2.23823364e+03 2.23421045e+03 2.22814453e+03 2.22758569e+03 2.22166113e+03 2.21397510e+03 2.21389795e+03 2.21072827e+03 2.19890771e+03 2.19312646e+03 2.19280493e+03 2.18357056e+03 2.17892334e+03 2.17050635e+03 2.16325635e+03 2.16055200e+03 2.14621777e+03 2.13958838e+03 2.13474194e+03 2.12240308e+03 2.11236743e+03 2.09981641e+03 2.09390015e+03 2.08353442e+03 2.06907300e+03 2.06123096e+03 2.05623315e+03 2.04632446e+03 2.02704822e+03 2.01438525e+03 2.00931226e+03 1.99204688e+03 1.97438208e+03 1.96283057e+03 1.95519116e+03 1.93962927e+03 1.92225061e+03 1.91316846e+03 1.89459741e+03 1.88054199e+03 1.86989673e+03 1.84887585e+03 1.83195789e+03 1.81762305e+03 1.80126453e+03 1.78716016e+03 1.76851953e+03 1.75192310e+03 1.73607446e+03 1.71692371e+03 1.69625598e+03 1.67704199e+03 1.66302380e+03 1.64438257e+03 1.62476233e+03 1.60443872e+03 1.58700134e+03 1.56553235e+03 1.54677600e+03 1.52835608e+03 1.50566968e+03 1.48462354e+03 1.46312671e+03 1.44408948e+03 1.42259705e+03 1.40140930e+03 1.38182410e+03 1.35780298e+03 1.33410657e+03 1.31186304e+03 1.29038916e+03 1.26819458e+03 1.24543103e+03 1.22382556e+03 1.19932629e+03 1.17525500e+03 1.15159021e+03 1.12871509e+03 1.10564844e+03 1.07972400e+03 1.05525647e+03 1.03134363e+03 1.00829974e+03 9.82780579e+02 9.57268616e+02 9.32103943e+02 9.06345947e+02 8.81899353e+02 8.57205383e+02 8.31878845e+02 8.05217346e+02 7.79597168e+02 7.53782593e+02 7.27980896e+02 7.01686096e+02 6.75328247e+02 6.48949402e+02 6.22676453e+02 5.96326965e+02 5.69589172e+02 5.42716248e+02 5.15937317e+02 4.89380920e+02 4.62214722e+02 4.35286499e+02 4.08278137e+02 3.80997864e+02 3.53930542e+02 3.26621857e+02 2.99340881e+02 2.71956665e+02 2.44588654e+02 2.17254440e+02 1.89807816e+02 1.62265106e+02 1.34787613e+02 1.07293388e+02 7.97377319e+01 5.21882324e+01 2.46302776e+01 -2.92454386e+00 -3.05047493e+01 -5.80534668e+01 -8.56058350e+01 -1.13124382e+02 -1.40568420e+02 -1.68105865e+02 -1.95547043e+02 -2.23036560e+02 -2.50572922e+02 -2.77873138e+02 -3.05051178e+02 -3.32323669e+02 -3.59670502e+02 -3.86973785e+02 -4.14245972e+02 -4.40883453e+02 -4.67930969e+02 -4.94963654e+02 -5.21662903e+02 -5.48773499e+02 -5.74923035e+02 -6.01531433e+02 -6.28501038e+02 -6.54742004e+02 -6.81288452e+02 -7.07484131e+02 -7.33340149e+02 -7.59150452e+02 -7.84712097e+02 -8.10819824e+02 -8.37774048e+02 -8.62589600e+02 -8.87278442e+02 -9.12030640e+02 -9.37256897e+02 -9.62739990e+02 -9.87640259e+02 -1.01277740e+03 -1.03753735e+03 -1.06109338e+03 -1.08423901e+03 -1.10968469e+03 -1.13348047e+03 -1.15765125e+03 -1.18174597e+03 -1.20367725e+03 -1.22755615e+03 -1.24885168e+03 -1.27270154e+03 -1.29428381e+03 -1.31647192e+03 -1.33947241e+03 -1.36243140e+03 -1.38530908e+03 -1.40654712e+03 -1.42691528e+03 -1.44772034e+03 -1.47124829e+03 -1.49113977e+03 -1.51005811e+03 -1.53079700e+03 -1.54894983e+03 -1.56898108e+03 -1.59125098e+03 -1.61017981e+03 -1.62817468e+03 -1.64929102e+03 -1.66682678e+03 -1.68314172e+03 -1.70177576e+03 -1.72064673e+03 -1.74098547e+03 -1.75276013e+03 -1.77089929e+03 -1.78906897e+03 -1.80223865e+03 -1.82426428e+03 -1.83632312e+03 -1.85042419e+03 -1.87097314e+03 -1.88284717e+03 -1.89605713e+03 -1.91075256e+03 -1.92919739e+03 -1.94092432e+03 -1.95636975e+03 -1.97181592e+03 -1.98054114e+03 -1.99429028e+03 -2.00774219e+03 -2.01738708e+03 -2.03082153e+03 -2.04390601e+03 -2.05178394e+03 -2.06326953e+03 -2.07515039e+03 -2.08390210e+03 -2.09783716e+03 -2.10759204e+03 -2.11417358e+03 -2.12365991e+03 -2.12829541e+03 -2.14130225e+03 -2.15625000e+03 -2.15054077e+03 -2.16619727e+03 -2.17824927e+03 -2.17929272e+03 -2.18244263e+03 -2.19462720e+03 -2.20400562e+03 -2.20239062e+03 -2.20762036e+03 -2206. -2.22063477e+03 -2.22697485e+03 -2.22467017e+03 -2.22217163e+03 -2.22743433e+03 -2.24210132e+03 -2.23785571e+03 -2.23134424e+03 -2.23592627e+03 -2.24130225e+03 -2.23915308e+03 -2.24251880e+03 -2.25185107e+03 -2.24758887e+03 -2.24041504e+03 -2.24731250e+03 -2.24326416e+03 -2.24801343e+03 -2.24548755e+03 -2.23744873e+03 -2.23516187e+03 -2.23918628e+03 -2.22854785e+03 -2.22560156e+03 -2.22675757e+03 -2.21989282e+03 -2.21054541e+03 -2.21056567e+03 -2.21138062e+03 -2.20239575e+03 -2.19270020e+03 -2.19311304e+03 -2.18466089e+03 -2.17693384e+03 -2.16907251e+03 -2.16235840e+03 -2.16169312e+03 -2.14799829e+03 -2.13691235e+03 -2.13755859e+03 -2.12490161e+03 -2.11123022e+03 -2.09869873e+03 -2.09372925e+03 -2.08725952e+03 -2.07112842e+03 -2.06471143e+03 -2.05812305e+03 -2.04177661e+03 -2.02517542e+03 -2.01277759e+03 -2.00855994e+03 -1.99574927e+03 -1.97376416e+03 -1.96089038e+03 -1.95772363e+03 -1.94158362e+03 -1.92120557e+03 -1.91126648e+03 -1.89437500e+03 -1.88140686e+03 -1.87128381e+03 -1.84815295e+03 -1.83199219e+03 -1.81824951e+03 -1.80063940e+03 -1.78678723e+03 -1.76975842e+03 -1.75003357e+03 -1.73252234e+03 -1.71841760e+03 -1.69824390e+03 -1.67724133e+03 -1.66173718e+03 -1.64381763e+03 -1.62472937e+03 -1.60423047e+03 -1.58637964e+03 -1.56518347e+03 -1.54656372e+03 -1.52870728e+03 -1.50677356e+03 -1.48423718e+03 -1.46268237e+03 -1.44281921e+03 -1.42207153e+03 -1.40314893e+03 -1.38148682e+03 -1.35673730e+03 -1.33458105e+03 -1.31191553e+03 -1.29047498e+03 -1.26801416e+03 -1.24446582e+03 -1.22256018e+03 -1.19902332e+03 -1.17583850e+03 -1.15103149e+03 -1.12866589e+03 -1.10611218e+03 -1.07938562e+03 -1.05462207e+03 -1.03153174e+03 -1.00748547e+03 -9.82728699e+02 -9.56880066e+02 -9.32268005e+02 -9.07118774e+02 -8.81555603e+02 -8.57040771e+02 -8.31947021e+02 -8.05317017e+02 -7.79429382e+02 -7.53627075e+02 -7.27795410e+02 -7.01723389e+02 -6.75635864e+02 -6.49079651e+02 -6.22512695e+02 -5.96315552e+02 -5.69334167e+02 -5.42600220e+02 -5.16055237e+02 -4.89312561e+02 -4.62266449e+02 -4.35279572e+02 -4.08197632e+02 -3.80968414e+02 -3.53914124e+02 -3.26657837e+02 -2.99324677e+02 -2.71899414e+02 -2.44607590e+02 -2.17257431e+02 -1.89817688e+02 -1.62311615e+02 -1.34804352e+02 -1.07301765e+02 -7.97615280e+01 -5.22188759e+01 -2.46747665e+01 2.89399838e+00 3.04516907e+01 5.79644127e+01 8.55270996e+01 1.13060150e+02 1.40531555e+02 1.68088898e+02 1.95528687e+02 2.23029434e+02 2.50502197e+02 2.77774658e+02 3.05002106e+02 3.32250458e+02 3.59523804e+02 3.86845886e+02 4.14237274e+02 4.40749237e+02 4.67690643e+02 4.95138855e+02 5.21672302e+02 5.48407349e+02 5.75230164e+02 6.01664062e+02 6.28099976e+02 6.54582336e+02 6.81181213e+02 7.07285278e+02 7.33137451e+02 7.59066528e+02 7.84467834e+02 8.10846191e+02 8.37697571e+02 8.62328735e+02 8.87322266e+02 9.11566711e+02 9.37248779e+02 9.62868835e+02 9.87643005e+02 1.01295142e+03 1.03700745e+03 1.06126587e+03 1.08476489e+03 1.10902563e+03 1.13325806e+03 1.15756824e+03 1.18086829e+03 1.20395947e+03 1.22687097e+03 1.24817090e+03 1.27225818e+03 1.29604773e+03 1.31742334e+03 1.33931848e+03 1.36141211e+03 1.38399939e+03 1.40725793e+03 1.42857898e+03 1.44742896e+03 1.46970068e+03 1.49017920e+03 1.50833875e+03 1.52951074e+03 1.54865479e+03 1.56915918e+03 1.59041846e+03 1.60877710e+03 1.62969031e+03 1.64948364e+03 1.66608862e+03 1.68311121e+03 1.69992065e+03 1.72175085e+03 1.74161328e+03 1.75348315e+03 1.77101367e+03 1.78656750e+03 1.80286804e+03 1.82389795e+03 1.83726160e+03 1.85157471e+03 1.87002112e+03 1.88104517e+03 1.89756519e+03 1.91253357e+03 1.92874280e+03 1.94028625e+03 1.95741907e+03 1.97268420e+03 1.97675818e+03 1.99550940e+03 2.01137561e+03 2.01707092e+03 2.03219153e+03 2.04712195e+03 2.05332202e+03 2.06326562e+03 2.07454077e+03 2.08115723e+03 2.09507690e+03 2.11190527e+03 2.11385425e+03 2.12353418e+03 2.13028076e+03 2.14282397e+03 2.15565698e+03 2.15309937e+03 2.16365405e+03 2.17462695e+03 2.17933472e+03 2.18334863e+03 2.19687915e+03 2.19814673e+03 2.20427222e+03 2.20540430e+03 2.20893799e+03 2.21926392e+03 2.22871021e+03 2.22195776e+03 2.22150195e+03 2.23125513e+03 2.24291992e+03 2.23770068e+03 2.23365381e+03 2.23545190e+03 2.23799951e+03 2.23924414e+03 2.24160303e+03 2.24923096e+03 2.24291089e+03 2.24186328e+03 2.24887085e+03 2.24443506e+03 2.24424390e+03 2.24520996e+03 2.24107178e+03 2.23951782e+03 2.23273877e+03 2.22791040e+03 2.22426099e+03 2.22556738e+03 2.22259131e+03 2.21197534e+03 2.20895215e+03 2.20937402e+03 2.20095752e+03 2.19718823e+03 2.19000659e+03 2.18538110e+03 2.17895605e+03 2.16677515e+03 2.15992480e+03 2.15990942e+03 2.14701587e+03 2.14032446e+03 2.13410181e+03 2.12395142e+03 2.11129175e+03 2.09991211e+03 2.09407617e+03 2.08391528e+03 2.06998193e+03 2.06063281e+03 2.05479761e+03 2.04578870e+03 2.02337708e+03 2.01572083e+03 2.00692175e+03 1.99305994e+03 1.97465979e+03 1.96285986e+03 1.95749146e+03 1.93943237e+03 1.92142578e+03 1.91013477e+03 1.89636890e+03 1.88166772e+03 1.87002905e+03 1.84859082e+03 1.83054150e+03 1.81890710e+03 1.80143140e+03 1.78609045e+03 1.76838708e+03 1.75060083e+03 1.73633948e+03 1.71725208e+03 1.69561902e+03 1.67803857e+03 1.66146228e+03 1.64311633e+03 1.62616370e+03 1.60550720e+03 1.58518982e+03 1.56516907e+03 1.54776721e+03 1.52757788e+03 1.50469568e+03 1.48441943e+03 1.46428064e+03 1.44301367e+03 1.42140405e+03 1.40192310e+03 1.38180444e+03 1.35641284e+03 1.33490833e+03 1.31303833e+03 1.29037463e+03 1.26832874e+03 1.24556067e+03 1.22217542e+03 1.19934558e+03 1.17564526e+03 1.15190662e+03 1.12796057e+03 1.10510535e+03 1.08006909e+03 1.05549243e+03 1.03160400e+03 1.00817963e+03 9.82833435e+02 9.56851257e+02 9.32156006e+02 9.06788940e+02 8.81858276e+02 8.57184387e+02 8.31805908e+02 8.05242249e+02 7.79562073e+02 7.53664001e+02 7.27944519e+02 7.01671509e+02 6.75404236e+02 6.48733826e+02 6.22504028e+02 5.96493835e+02 5.69403198e+02 5.42608032e+02 5.16142334e+02 4.89437805e+02 4.62264923e+02 4.35309174e+02 4.08282501e+02 3.80957916e+02 3.53867737e+02 3.26645844e+02 2.99395111e+02 2.71991577e+02 2.44633545e+02 2.17288681e+02 1.89832062e+02 1.62309860e+02 1.34823532e+02 1.07340675e+02 7.97822647e+01 5.22578964e+01 2.47309475e+01 -2.89486742e+00 -3.04419308e+01 -5.79525414e+01 -8.55119629e+01 -1.13018906e+02 -1.40544739e+02 -1.68119232e+02 -1.95584763e+02 -2.23033844e+02 -2.50440735e+02 -2.77764801e+02 -3.05024017e+02 -3.32298676e+02 -3.59553375e+02 -3.86829620e+02 -4.14089478e+02 -4.40815765e+02 -468. -4.95056488e+02 -5.21695801e+02 -5.48734619e+02 -5.74863647e+02 -6.01497498e+02 -6.28581299e+02 -6.54674255e+02 -6.81123901e+02 -7.07456238e+02 -7.33544922e+02 -7.59377808e+02 -7.84581726e+02 -8.10918396e+02 -8.37676025e+02 -8.62285767e+02 -8.87613831e+02 -9.11993591e+02 -9.37229919e+02 -9.62984924e+02 -9.87622253e+02 -1.01288092e+03 -1.03747876e+03 -1.06091223e+03 -1.08433374e+03 -1.10930432e+03 -1.13360754e+03 -1.15789343e+03 -1.18180212e+03 -1.20432837e+03 -1.22770569e+03 -1.24922998e+03 -1.27288989e+03 -1.29475073e+03 -1.31568262e+03 -1.33977661e+03 -1.36232629e+03 -1.38462598e+03 -1.40620325e+03 -1.42750354e+03 -1.44682239e+03 -1.47049890e+03 -1.49116724e+03 -1.50935046e+03 -1.53064099e+03 -1.54815271e+03 -1.56880090e+03 -1.59236426e+03 -1.60956042e+03 -1.62853467e+03 -1.64952637e+03 -1.66651270e+03 -1.68363245e+03 -1.70160461e+03 -1.71975317e+03 -1.74040332e+03 -1.75488232e+03 -1.77126709e+03 -1.78746472e+03 -1.80267078e+03 -1.82607019e+03 -1.83670300e+03 -1.85111194e+03 -1.87087891e+03 -1.88244043e+03 -1.89749561e+03 -1.91375427e+03 -1.92921753e+03 -1.94034692e+03 -1.95782568e+03 -1.97169653e+03 -1.98031067e+03 -1.99353210e+03 -2.01002686e+03 -2.01927710e+03 -2.03094202e+03 -2.04498389e+03 -2.05327515e+03 -2.06531836e+03 -2.07444629e+03 -2.08388184e+03 -2.09466553e+03 -2.11202466e+03 -2.11725635e+03 -2.12488696e+03 -2.13026270e+03 -2.14459424e+03 -2.15431934e+03 -2.14807007e+03 -2.16509888e+03 -2.17681250e+03 -2.18286646e+03 -2.18285254e+03 -2.19553564e+03 -2.20263477e+03 -2.20448657e+03 -2.20851392e+03 -2.20957104e+03 -2.21800024e+03 -2.22279102e+03 -2.22433374e+03 -2.22075049e+03 -2.23285596e+03 -2.24226782e+03 -2.23994238e+03 -2.23761841e+03 -2.23907520e+03 -2.23729077e+03 -2.24015259e+03 -2.24018799e+03 -2.25392554e+03 -2.24567212e+03 -2.24720264e+03 -2.25127661e+03 -2.24259106e+03 -2.24403076e+03 -2.24687573e+03 -2.24047461e+03 -2.23842285e+03 -2.23719458e+03 -2.22853589e+03 -2.23022729e+03 -2.22686572e+03 -2.22134302e+03 -2.21264307e+03 -2.21171216e+03 -2.20931543e+03 -2.20037085e+03 -2.19213379e+03 -2.18735522e+03 -2.18583765e+03 -2.17647290e+03 -2.16630005e+03 -2.16450537e+03 -2.15711035e+03 -2.14800781e+03 -2.75225269e+03 -2.85655127e+03 -5.13265820e+03 -5.69057520e+03 8.06064350e+06 -14210346. 313247168. 313247168. -6.37134750e+05 -6.37134750e+05 -14678920. -26495768. -26495768. 0. 0. 0. 66376160. 8495527. -5.67254590e+03 -5.01184180e+03 -2.94945605e+03 -2.77274927e+03 -2.50023511e+03 -1.87556189e+03 -1.85485364e+03 -1.83186145e+03 -1.81601587e+03 -1.80470996e+03 -1.79056360e+03 -1.77121912e+03 -1.75289050e+03 -1.73407166e+03 -1.71637732e+03 -1.69674451e+03 -1.67598767e+03 -1.66145825e+03 -1.64434009e+03 -1.62366455e+03 -1.60343262e+03 -1.58639514e+03 -1.56589429e+03 -1.54825183e+03 -1.53022595e+03 -1.50607593e+03 -1.48582727e+03 -1.46478845e+03 -1.44289087e+03 -1.42281055e+03 -1.40433740e+03 -1.38029297e+03 -1.35728455e+03 -1.33595044e+03 -1.31267456e+03 -1.29012439e+03 -1.26807617e+03 -1.24459375e+03 -1.22266809e+03 -1.20014026e+03 -1.17599292e+03 -1.15169397e+03 -1.12893018e+03 -1.10510571e+03 -1.07997705e+03 -1.05489551e+03 -1.03201428e+03 -1.00823328e+03 -9.82780701e+02 -9.57065735e+02 -9.32224121e+02 -9.07249878e+02 -8.82324036e+02 -8.56721130e+02 -8.31663513e+02 -8.05788818e+02 -7.79547058e+02 -7.53418762e+02 -7.27694885e+02 -7.01602295e+02 -6.75799133e+02 -6.49313721e+02 -6.22482117e+02 -5.96488586e+02 -5.69426331e+02 -5.42393188e+02 -5.16023071e+02 -4.89231598e+02 -4.62241577e+02 -4.35464722e+02 -4.07640259e+02 -5.20790894e+02 -3.52969849e+02 -4.88941162e+02 -4.58323120e+02 -3.22619568e+02 -2.88789764e+02 -2.17765823e+02 -1.89935089e+02 -1.61756485e+02 -1.34591064e+02 -1.07457153e+02 -7.98144836e+01 -5.19618340e+01 -1.28905792e+02 451912608. 2.44351593e+02 2.35944881e+01 -2.33366337e+01 4.62254120e+02 4.13660980e+02 3.64820526e+02 403951. -1.06677445e+05 8.79583740e+02 7.12618408e+02 4.50810059e+02 4.91542328e+02 4.41998840e+02 4.72296753e+02 4.08224762e+02 4.36139008e+02 4.62314545e+02 4.88662933e+02 5.15279907e+02 5.42420349e+02 5.69014648e+02 5.95491089e+02 6.21640564e+02 6.47782288e+02 6.74145386e+02 7.00231384e+02 7.25763000e+02 7.51710144e+02 7.77299805e+02 8.03296631e+02 8.30177307e+02 8.54136047e+02 8.78539795e+02 9.03249573e+02 9.28461853e+02 9.53886108e+02 9.78015686e+02 1.00432623e+03 1.02939734e+03 1.05132996e+03 1.07483459e+03 1.10061914e+03 1.12417419e+03 1.14607178e+03 1.17047729e+03 1.19509070e+03 1.21725708e+03 1.23914551e+03 1.26093567e+03 1.28441577e+03 1.30634534e+03 1.32873401e+03 1.35172559e+03 1.37172742e+03 1.39420947e+03 1.41464331e+03 1.43617578e+03 1.45866162e+03 1.47818970e+03 1.49715662e+03 1.51950256e+03 1.53775281e+03 1.55719031e+03 1.57842908e+03 1.59440894e+03 1.61500623e+03 1.63630823e+03 1.65539038e+03 1.67071497e+03 1.68604871e+03 1.70755518e+03 1.72455579e+03 1.73979944e+03 1.75913586e+03 1.77282764e+03 1.79023706e+03 2.35734204e+03 2.54632788e+03 2.76781763e+03 4.67883545e+03 2.49676152e+04 -23354014. 0. 0. -65236368. -65236368. -65236368. 0. 0. 13341798. 13341798. 13341798. 0. -38501324. -38501324. -16758791. -19630806. 6.20288672e+03 4.95314014e+03 2.72312183e+03 2.10696802e+03 2.11639868e+03 2.12826416e+03 2.13442017e+03 2.14160864e+03 2.14553491e+03 2.16005078e+03 2.16144604e+03 2.16836084e+03 2.18370947e+03 2.18518384e+03 2.18454541e+03 2.19330298e+03 2.19469751e+03 2.20060498e+03 2.20819800e+03 2.20787769e+03 2.20821362e+03 2.21368604e+03 2.22455908e+03 2.22274878e+03 2.22147510e+03 2.22151929e+03 2.22706055e+03 2.22898438e+03 2.22624292e+03 2.22596631e+03 2.23078198e+03 2.23277686e+03 2.22658472e+03 2.23128979e+03 2.22853296e+03 2.22715039e+03 2.22540308e+03 2.22177148e+03 2.22176050e+03 2.21559766e+03 2.21492334e+03 2.21484839e+03 2.20515283e+03 2.20347095e+03 2.19785767e+03 2.19656494e+03 2.18839258e+03 2.18295117e+03 2.17196533e+03 2.16915649e+03 2.16949268e+03 2.15518994e+03 2.14767456e+03 2.14764355e+03 2.13157129e+03 2.12520410e+03 2.11977368e+03 2.10969678e+03 2.09578125e+03 2.08928369e+03 2.08304980e+03 2.06768408e+03 2.05488135e+03 2.05231299e+03 2.04480530e+03 2.03016150e+03 2.01064001e+03 2.00715491e+03 1.99648376e+03 1.98110596e+03 1.96678833e+03 1.95132214e+03 1.93881836e+03 1.92854468e+03 1.90951660e+03 1.89233044e+03 1.88342249e+03 1.87379150e+03 1.85791797e+03 1.83913135e+03 1.82236792e+03 1.80619995e+03 1.79179114e+03 1.77611328e+03 1.75476318e+03 1.74326904e+03 1.72400378e+03 1.70401270e+03 1.68771350e+03 1.66932788e+03 1.65377991e+03 1.63497583e+03 1.61539624e+03 1.59443445e+03 1.57709009e+03 1.55659766e+03 1.53820007e+03 1.51948877e+03 1.49745264e+03 1.47628308e+03 1.45736804e+03 1.43575916e+03 1.41428210e+03 1.39353735e+03 1.37210889e+03 1.35019409e+03 1.32928210e+03 1.30615662e+03 1.28289258e+03 1.26170618e+03 1.23934937e+03 1.21566077e+03 1.19299622e+03 1.17091016e+03 1.14768066e+03 1.12245667e+03 1.09811609e+03 1.07449023e+03 1.05114490e+03 1.02660107e+03 1.00316449e+03 9.78428101e+02 9.53137634e+02 9.27979736e+02 9.02931824e+02 8.78192627e+02 8.53523682e+02 8.28552185e+02 8.02162781e+02 7.77064270e+02 7.51178162e+02 7.25070190e+02 6.99346191e+02 6.73436340e+02 6.46956116e+02 6.20720215e+02 5.94531982e+02 5.67918152e+02 5.41639160e+02 5.14976501e+02 4.88556885e+02 4.61810822e+02 4.34756653e+02 4.07779419e+02 3.80858093e+02 3.54066620e+02 3.26995392e+02 2.99974579e+02 2.72692474e+02 2.45451904e+02 2.18376740e+02 1.91090286e+02 1.63727936e+02 1.36440948e+02 1.09130859e+02 8.17726822e+01 5.44117966e+01 2.70508671e+01 -3.10839415e-01 -2.77015953e+01 -5.50628204e+01 -8.24190292e+01 -1.09750214e+02 -1.37021271e+02 -1.64354294e+02 -1.91609283e+02 -2.18958923e+02 -2.46240021e+02 -2.73359589e+02 -3.00399902e+02 -3.27407227e+02 -3.54646515e+02 -3.81815094e+02 -4.08715210e+02 -4.35303192e+02 -4.62021698e+02 -4.88937012e+02 -5.15838623e+02 -5.42238708e+02 -5.68508240e+02 -5.95265442e+02 -6.21615234e+02 -6.47518921e+02 -6.74020691e+02 -7.00175537e+02 -7.25829468e+02 -7.51791626e+02 -7.76812500e+02 -8.02999939e+02 -8.29202637e+02 -8.53610718e+02 -8.78763733e+02 -9.03727295e+02 -9.28685120e+02 -9.53862427e+02 -9.78398682e+02 -1.00365210e+03 -1.02799268e+03 -1.05144690e+03 -1.07586523e+03 -1.09975940e+03 -1.12351025e+03 -1.14680945e+03 -1.17087561e+03 -1.19351807e+03 -1.21711816e+03 -1.24040674e+03 -1.26136108e+03 -1.28338428e+03 -1.30535413e+03 -1.32834314e+03 -1.35237317e+03 -1.37316162e+03 -1.39335889e+03 -1.41415771e+03 -1.43602966e+03 -1.45844971e+03 -1.47715576e+03 -1.49692053e+03 -1.51848987e+03 -1.53761340e+03 -1.55751758e+03 -1.57782568e+03 -1.59498828e+03 -1.61508911e+03 -1.63730530e+03 -1.65544568e+03 -1.67014001e+03 -1.68752771e+03 -1.70707031e+03 -1.72273999e+03 -1.74063953e+03 -1.75931262e+03 -1.77339636e+03 -1.79048901e+03 -1.81070215e+03 -1.82505750e+03 -1.84033533e+03 -1.85156445e+03 -1.86533521e+03 -1.88693640e+03 -1.89763391e+03 -1.91713342e+03 -1.92900366e+03 -1.94217346e+03 -1.95938269e+03 -1.96777954e+03 -1.98027893e+03 -1.99093164e+03 -1.99872925e+03 -2.01532019e+03 -2.03144043e+03 -2.04141553e+03 -2.04939038e+03 -2.05400513e+03 -2.07308545e+03 -2.08206494e+03 -2.09417310e+03 -2.10292920e+03 -2.10443286e+03 -2.11388818e+03 -2.12609375e+03 -2.14151904e+03 -2.14309180e+03 -2.14881494e+03 -2.16333813e+03 -2.15967676e+03 -2.16493774e+03 -2.18730493e+03 -2.18744165e+03 -2.18405176e+03 -2.18952539e+03 -2.19152002e+03 -2.20064795e+03 -2.20966943e+03 -2.21313989e+03 -2.20924219e+03 -2.21374463e+03 -2.22415356e+03 -2.22647266e+03 -2.21780908e+03 -2.22038721e+03 -2.22746826e+03 -2.23019702e+03 -2.22921216e+03 -2.22661865e+03 -2.23247876e+03 -2.23219995e+03 -2.22401416e+03 -2.23120166e+03 -2.22778271e+03 -2.22940747e+03 -2.22511743e+03 -2.22083350e+03 -2.21550049e+03 -2.21535645e+03 -2.20946045e+03 -2.20878516e+03 -2.20459448e+03 -2.20006592e+03 -2.19926709e+03 -2.19663696e+03 -2.18807520e+03 -2.18439380e+03 -2.16657446e+03 -2.16883057e+03 -2.16991943e+03 -2.15398413e+03 -2.14865259e+03 -2.14487524e+03 -2.13403247e+03 -2.12528638e+03 -2.12060815e+03 -2.10771045e+03 -2.09960791e+03 -2.08446021e+03 -2.08209351e+03 -2.07115430e+03 -2.05526001e+03 -2.05240015e+03 -2.04199023e+03 -2.02966663e+03 -2.01178613e+03 -1.99777246e+03 -1.99770374e+03 -1.98522131e+03 -1.96159778e+03 -1.95042224e+03 -1.94438464e+03 -1.92642529e+03 -1.90994751e+03 -1.89390198e+03 -1.88144897e+03 -1.87454736e+03 -1.85685327e+03 -1.84090027e+03 -1.82154773e+03 -1.80675342e+03 -1.79203333e+03 -1.77458057e+03 -1.75709998e+03 -1.74204016e+03 -1.72219824e+03 -1.70546094e+03 -1.69092383e+03 -1.66951416e+03 -1.65336548e+03 -1.63317957e+03 -1.61543884e+03 -1.59386145e+03 -1.57565845e+03 -1.55678687e+03 -1.53837524e+03 -1.52016895e+03 -1.49731592e+03 -1.47563281e+03 -1.45706396e+03 -1.43540393e+03 -1.41369397e+03 -1.39334265e+03 -1.37198560e+03 -1.35058704e+03 -1.32845654e+03 -1.30658215e+03 -1.28473376e+03 -1.26079724e+03 -1.23788086e+03 -1.21515613e+03 -1.19298828e+03 -1.17024792e+03 -1.14722583e+03 -1.12226477e+03 -1.09823584e+03 -1.07564258e+03 -1.05117847e+03 -1.02592188e+03 -1.00316272e+03 -9.78632996e+02 -9.52970825e+02 -9.28053833e+02 -9.03102966e+02 -8.77952026e+02 -8.53689270e+02 -8.28197021e+02 -8.02281677e+02 -7.77255737e+02 -7.51000122e+02 -7.24833374e+02 -6.99370972e+02 -6.73661804e+02 -6.47121216e+02 -6.20533691e+02 -5.94371094e+02 -5.68052795e+02 -5.41624146e+02 -5.14796997e+02 -4.88553314e+02 -4.61884094e+02 -4.34709412e+02 -4.07715729e+02 -3.80829468e+02 -3.54035217e+02 -3.26977356e+02 -2.99959625e+02 -2.72662842e+02 -2.45480301e+02 -2.18387375e+02 -1.91086136e+02 -1.63720947e+02 -1.36405884e+02 -1.09125023e+02 -8.17699509e+01 -5.44011040e+01 -2.70493183e+01 3.11311841e-01 2.76693916e+01 5.50104065e+01 8.23824387e+01 1.09722466e+02 1.37030029e+02 1.64381973e+02 1.91625153e+02 2.18962738e+02 2.46190170e+02 2.73315948e+02 3.00404388e+02 3.27369476e+02 3.54596466e+02 3.81750580e+02 4.08701599e+02 4.35367004e+02 4.61909210e+02 4.88796753e+02 5.15715149e+02 5.42218750e+02 5.68864746e+02 5.95339600e+02 6.21450867e+02 6.47529541e+02 6.73837402e+02 7.00045227e+02 7.25828308e+02 7.51812073e+02 7.76854980e+02 8.02543518e+02 8.29545410e+02 8.53927429e+02 8.78160706e+02 9.02725281e+02 9.29062622e+02 9.54194885e+02 9.78046448e+02 1.00388934e+03 1.02860193e+03 1.05154285e+03 1.07456201e+03 1.10021338e+03 1.12493457e+03 1.14518005e+03 1.16933704e+03 1.19478223e+03 1.21703894e+03 1.23874377e+03 1.26113794e+03 1.28430322e+03 1.30648718e+03 1.32879297e+03 1.35150244e+03 1.37218188e+03 1.39404785e+03 1.41498938e+03 1.43581995e+03 1.45908667e+03 1.47720508e+03 1.49696692e+03 1.51682678e+03 1.53739587e+03 1.55816003e+03 1.57797009e+03 1.59523669e+03 1.61490271e+03 1.63607593e+03 1.65444775e+03 1.67100952e+03 1.68603528e+03 1.70746509e+03 1.72430737e+03 1.73996826e+03 1.75946301e+03 1.77192847e+03 1.79102258e+03 1.80859509e+03 1.82386719e+03 1.83828296e+03 1.85049207e+03 1.86923193e+03 1.88708801e+03 1.89967273e+03 1.91552148e+03 1.92665649e+03 1.94071521e+03 1.95647205e+03 1.96381995e+03 1.98155029e+03 1.99654456e+03 1.99719617e+03 2.01517468e+03 2.03296130e+03 2.03999451e+03 2.04916016e+03 2.05345337e+03 2.06840356e+03 2.08202979e+03 2.09506006e+03 2.10113599e+03 2.10440527e+03 2.11378198e+03 2.12616089e+03 2.13904980e+03 2.14160913e+03 2.14920044e+03 2.16209277e+03 2.16296802e+03 2.16627222e+03 2.18336084e+03 2.18440820e+03 2.18517700e+03 2.19359448e+03 2.19103125e+03 2.20197510e+03 2.21189502e+03 2.21011035e+03 2.20834106e+03 2.21401367e+03 2.22726855e+03 2.22542310e+03 2.21857690e+03 2.22126025e+03 2.22928467e+03 2.23013965e+03 2.22977173e+03 2.22834448e+03 2.23012354e+03 2.22726758e+03 2.22733667e+03 2.23074316e+03 2.22863159e+03 2.22684497e+03 2.22640918e+03 2.22145996e+03 2.22056396e+03 2.21300073e+03 2.21253979e+03 2.21057617e+03 2.20646167e+03 2.19705835e+03 2.19795215e+03 2.19005737e+03 2.18821167e+03 2.18431616e+03 2.16929614e+03 2.16740015e+03 2.16900781e+03 2.15284399e+03 2.14690332e+03 2.14414917e+03 2.13171338e+03 2.12817773e+03 2.12344287e+03 2.10605200e+03 2.09825806e+03 2.08937793e+03 2.08153711e+03 2.07115747e+03 2.05612012e+03 2.05085645e+03 2.04364539e+03 2.02569666e+03 2.01525354e+03 2.00347839e+03 1.99846021e+03 1.98225964e+03 1.96261780e+03 1.95241309e+03 1.94248926e+03 1.92795190e+03 1.91059058e+03 1.89238562e+03 1.88479724e+03 1.87484387e+03 1.85744128e+03 1.83916882e+03 1.82209888e+03 1.80532568e+03 1.79217578e+03 1.77582739e+03 1.75614966e+03 1.74350989e+03 1.72417175e+03 1.70455103e+03 1.68896167e+03 1.66936963e+03 1.65350635e+03 1.63240479e+03 1.61539954e+03 1.59394409e+03 1.57482532e+03 1.55637012e+03 1.53859241e+03 1.51972778e+03 1.49757495e+03 1.47639551e+03 1.45713123e+03 1.43522180e+03 1.41263013e+03 1.39368591e+03 1.37216016e+03 1.34965820e+03 1.32879382e+03 1.30780725e+03 1.28405615e+03 1.26061206e+03 1.23891809e+03 1.21482629e+03 1.19213879e+03 1.17059326e+03 1.14774805e+03 1.12170752e+03 1.09788037e+03 1.07479224e+03 1.05108582e+03 1.02695239e+03 1.00337274e+03 9.78322571e+02 9.52857300e+02 9.27903015e+02 9.02752380e+02 8.78078674e+02 8.53647522e+02 8.28418213e+02 8.02226990e+02 7.76998230e+02 7.51158386e+02 7.24884094e+02 6.99274780e+02 6.73492981e+02 6.46872803e+02 6.20597107e+02 5.94437317e+02 5.67940552e+02 5.41607910e+02 5.14953369e+02 4.88609344e+02 4.61824890e+02 4.34759369e+02 4.07779755e+02 3.80833099e+02 3.53996063e+02 3.26958588e+02 2.99955170e+02 2.72705902e+02 2.45477493e+02 2.18387634e+02 1.91091461e+02 1.63744858e+02 1.36448517e+02 1.09145485e+02 8.17839203e+01 5.44461555e+01 2.70987511e+01 -3.19083124e-01 -2.76701832e+01 -5.50028725e+01 -8.23789825e+01 -1.09709991e+02 -1.37053101e+02 -1.64405762e+02 -1.91642151e+02 -2.18960388e+02 -2.46157806e+02 -2.73283295e+02 -3.00402466e+02 -3.27408173e+02 -3.54585876e+02 -3.81731995e+02 -4.08613464e+02 -4.35280701e+02 -4.62058014e+02 -4.88920990e+02 -5.15791870e+02 -5.42259644e+02 -5.68576233e+02 -5.95279968e+02 -6.21644226e+02 -6.47436462e+02 -6.73893982e+02 -7.00136169e+02 -7.26028503e+02 -7.51679077e+02 -7.76818909e+02 -8.03034607e+02 -8.29434265e+02 -8.53906616e+02 -8.78633179e+02 -9.03101624e+02 -9.28643127e+02 -9.54135803e+02 -9.78167908e+02 -1.00367468e+03 -1.02809106e+03 -1.05111194e+03 -1.07506116e+03 -1.09989319e+03 -1.12324158e+03 -1.14687000e+03 -1.17058228e+03 -1.19375537e+03 -1.21750452e+03 -1.23987097e+03 -1.26186731e+03 -1.28298059e+03 -1.30542883e+03 -1.32956116e+03 -1.35215918e+03 -1.37279980e+03 -1.39373267e+03 -1.41332849e+03 -1.43590356e+03 -1.46005054e+03 -1.47742468e+03 -1.49693933e+03 -1.51815234e+03 -1.53802710e+03 -1.55723572e+03 -1.57854919e+03 -1.59419458e+03 -1.61500684e+03 -1.63693176e+03 -1.65412964e+03 -1.67102197e+03 -1.68619751e+03 -1.70566870e+03 -1.72397803e+03 -1.74134851e+03 -1.75859814e+03 -1.77175513e+03 -1.78997559e+03 -1.81152185e+03 -1.82436157e+03 -1.83868909e+03 -1.85099646e+03 -1.86695203e+03 -1.88747498e+03 -1.89857312e+03 -1.91377502e+03 -1.92686682e+03 -1.94391260e+03 -1.96043567e+03 -1.96700256e+03 -1.97821741e+03 -1.99123450e+03 -2.00168347e+03 -2.01467773e+03 -2.02927356e+03 -2.04054614e+03 -2.04817163e+03 -2.05606104e+03 -2.06919824e+03 -2.08273828e+03 -2.09308667e+03 -2.10057983e+03 -2.10687549e+03 -2.11044653e+03 -2.12929150e+03 -2.13831812e+03 -2.14018652e+03 -2.15000635e+03 -2.16266162e+03 -2.16416528e+03 -2.16184814e+03 -2.18215869e+03 -2.18632617e+03 -2.18435449e+03 -2.18929980e+03 -2.19532080e+03 -2.20471582e+03 -2.21159888e+03 -2.20994287e+03 -2.20938135e+03 -2.21335400e+03 -2.22449316e+03 -2.22618457e+03 -2.22094775e+03 -2.22451587e+03 -2.22615698e+03 -2.22953101e+03 -2.22922217e+03 -2.22739453e+03 -2.23281177e+03 -2.22863379e+03 -2.22968506e+03 -2.23128906e+03 -2.22575244e+03 -2.22747412e+03 -2.22554980e+03 -2.22402661e+03 -2.21868994e+03 -2.21771582e+03 -2.21200439e+03 -2.21141235e+03 -2.20476807e+03 -2.20066748e+03 -2.20198145e+03 -2.19401733e+03 -2.18779468e+03 -2.18620215e+03 -2.17048950e+03 -2.16870752e+03 -2.16703027e+03 -2.15303320e+03 -2.14933643e+03 -2.14581885e+03 -2.13510010e+03 -2.12186768e+03 -2.11778613e+03 -2.73516235e+03 -2.79100830e+03 -4.86475684e+03 -2.50525859e+04 7.77735450e+06 0. -6.37134750e+05 -6.37134750e+05 -14678920. -26495768. -26495768. 0. 0. 0. 0. 0. 4.85868050e+06 -7.34674875e+05 -7.55014453e+03 -6.48494775e+03 -4.70074902e+03 -2.79461694e+03 -2.55505420e+03 -2.33254590e+03 -1.81139172e+03 -1.79226990e+03 -1.77531348e+03 -1.75625793e+03 -1.74185828e+03 -1.72215332e+03 -1.70310144e+03 -1.69117688e+03 -1.67250281e+03 -1.65420178e+03 -1.63545776e+03 -1.61703223e+03 -1.59395532e+03 -1.57702148e+03 -1.55761841e+03 -1.53826099e+03 -1.51947607e+03 -1.49729956e+03 -1.47600842e+03 -1.45710620e+03 -1.43516187e+03 -1.41327844e+03 -1.39430652e+03 -1.37172681e+03 -1.35020691e+03 -1.32928308e+03 -1.30829993e+03 -1.28366211e+03 -1.26114990e+03 -1.23856934e+03 -1.21582166e+03 -1.19343164e+03 -1.17070398e+03 -1.14672961e+03 -1.12319177e+03 -1.09857544e+03 -1.07524866e+03 -1.05130212e+03 -1.02626196e+03 -1.00379797e+03 -9.78733032e+02 -9.52904602e+02 -9.27609924e+02 -9.03118713e+02 -8.78265381e+02 -8.52996765e+02 -8.27985901e+02 -8.02420959e+02 -7.77056702e+02 -7.50618225e+02 -7.24589050e+02 -6.99161560e+02 -6.73691101e+02 -6.47309387e+02 -6.20350464e+02 -5.94577454e+02 -5.68210266e+02 -5.41481628e+02 -5.14974976e+02 -4.88644104e+02 -4.62070557e+02 -4.35611450e+02 -4.07241272e+02 -7.79689819e+02 -5.38582397e+02 -9.85347778e+02 -1.17351672e+03 -5.67183167e+02 -4.89362854e+02 -3.31381622e+02 -2.22224808e+02 -2.45001556e+02 -2.25133224e+02 -1.64659683e+02 -1.22921494e+02 -8.01329727e+01 -2.02355988e+02 -1412612608. -13139850. -13139850. -1129175168. -277667808. -277667808. -277667808. 0. 0. -870164800. 3.62835767e+03 7.58924561e+02 4.89532837e+02 4.74846130e+02 4.91140350e+02 4.06874878e+02 4.34712738e+02 4.61025726e+02 4.87169708e+02 5.13582458e+02 5.40286072e+02 5.66911499e+02 5.92591858e+02 6.19022034e+02 6.45781738e+02 6.71034180e+02 6.96881531e+02 7.22867065e+02 7.48274963e+02 7.74341614e+02 7.99907654e+02 8.25823792e+02 8.51050537e+02 8.74570923e+02 8.99582397e+02 9.24934265e+02 9.49776245e+02 9.74155396e+02 9.99602722e+02 1.02383130e+03 1.04676917e+03 1.07104529e+03 1.09508069e+03 1.11872107e+03 1.14049524e+03 1.16555432e+03 1.18995605e+03 1.20992419e+03 1.23296643e+03 1.25582629e+03 1.28001965e+03 1.30171143e+03 1.32213757e+03 1.34513257e+03 1.36667383e+03 1.38644067e+03 1.40884167e+03 1.42961890e+03 1.45009814e+03 1.47045752e+03 1.49181860e+03 1.51366272e+03 1.53353381e+03 1.54891919e+03 1.56937024e+03 1.59128662e+03 1.60995447e+03 1.62551794e+03 1.64458008e+03 1.66732288e+03 1.67848291e+03 1.69854626e+03 1.71999341e+03 1.73055579e+03 1.75132532e+03 2.29929297e+03 2.47569678e+03 4.40069580e+03 6.13766260e+03 2.71402207e+04 20486864. 74596248. 0. -441762368. -441762368. -4.24307302e+09 -65236368. -65236368. 0. 0. 0. 0. 0. 0. -15470623. 2.44816973e+04 3.35657007e+03 4.92493115e+03 2.82141479e+03 2.68501367e+03 2.08826831e+03 2.09732837e+03 2.11230737e+03 2.11974487e+03 2.12652881e+03 2.13135449e+03 2.13725171e+03 2.14799609e+03 2.15588965e+03 2.15693286e+03 2.16661938e+03 2.17058105e+03 2.17372607e+03 2.18664038e+03 2.18558374e+03 2.19160034e+03 2.19900195e+03 2.19869653e+03 2.19820093e+03 2.20723120e+03 2.20912012e+03 2.21314990e+03 2.21718506e+03 2.21220532e+03 2.21646997e+03 2.22192822e+03 2.21511279e+03 2.21410913e+03 2.22022021e+03 2.21981152e+03 2.21783398e+03 2.21733643e+03 2.22298535e+03 2.22007690e+03 2.20674585e+03 2.21540503e+03 2.21256079e+03 2.19960205e+03 2.19955054e+03 2.20030469e+03 2.19530640e+03 2.19466553e+03 2.18730225e+03 2.18090405e+03 2.17428784e+03 2.17371240e+03 2.16061768e+03 2.15725903e+03 2.15922192e+03 2.14236670e+03 2.13929541e+03 2.13617896e+03 2.12417676e+03 2.11003687e+03 2.10012305e+03 2.10249927e+03 2.09112329e+03 2.07812427e+03 2.06916797e+03 2.05939844e+03 2.05038867e+03 2.04338184e+03 2.03400073e+03 2.01476965e+03 2.00754822e+03 1.99864954e+03 1.98873340e+03 1.97246826e+03 1.95733325e+03 1.94091516e+03 1.92970374e+03 1.91876978e+03 1.89912305e+03 1.88282178e+03 1.87548047e+03 1.86504626e+03 1.85064490e+03 1.83068848e+03 1.81395154e+03 1.79666589e+03 1.78319104e+03 1.76763379e+03 1.74567578e+03 1.73345105e+03 1.71600183e+03 1.69819434e+03 1.68270203e+03 1.65989612e+03 1.64397009e+03 1.62779004e+03 1.60636426e+03 1.58692542e+03 1.56876599e+03 1.54893335e+03 1.53064111e+03 1.51044800e+03 1.48953516e+03 1.46995361e+03 1.45151599e+03 1.42817651e+03 1.40709229e+03 1.38633923e+03 1.36450208e+03 1.34348206e+03 1.32354260e+03 1.30028345e+03 1.27628796e+03 1.25507788e+03 1.23381506e+03 1.21060327e+03 1.18665173e+03 1.16408923e+03 1.14106421e+03 1.11729736e+03 1.09337878e+03 1.06938428e+03 1.04565515e+03 1.02152643e+03 9.97717346e+02 9.73798035e+02 9.48416016e+02 9.22932922e+02 8.98644897e+02 8.73926758e+02 8.49138184e+02 8.23466003e+02 7.98312073e+02 7.73131958e+02 7.46760071e+02 7.21386597e+02 6.95628906e+02 6.69933838e+02 6.43830566e+02 6.17267822e+02 5.91347534e+02 5.64916992e+02 5.38764526e+02 5.12217224e+02 4.85527008e+02 4.59146912e+02 4.32325226e+02 4.05372498e+02 3.78658630e+02 3.51932892e+02 3.24983093e+02 2.98102142e+02 2.70981628e+02 2.43877808e+02 2.16903046e+02 1.89722641e+02 1.62507080e+02 1.35331085e+02 1.08147514e+02 8.09294891e+01 5.36995277e+01 2.64678707e+01 -7.72602618e-01 -2.80262260e+01 -5.52605095e+01 -8.24822693e+01 -1.09690102e+02 -1.36848907e+02 -1.64062439e+02 -1.91212326e+02 -2.18379456e+02 -2.45493118e+02 -2.72558228e+02 -2.99506409e+02 -3.26355255e+02 -3.53458801e+02 -3.80422638e+02 -4.07035614e+02 -4.33744232e+02 -4.60496155e+02 -4.87035492e+02 -5.13821045e+02 -5.40101501e+02 -5.66481750e+02 -5.93001099e+02 -6.19244141e+02 -6.45327271e+02 -6.71002136e+02 -6.97024414e+02 -7.23013733e+02 -7.48808105e+02 -7.73818970e+02 -7.99223572e+02 -8.25586426e+02 -8.50503784e+02 -8.75127014e+02 -8.99948914e+02 -9.25494385e+02 -9.49843750e+02 -9.73795654e+02 -9.99052124e+02 -1.02383197e+03 -1.04718201e+03 -1.07046936e+03 -1.09465393e+03 -1.11901050e+03 -1.14205151e+03 -1.16541235e+03 -1.18801233e+03 -1.21096936e+03 -1.23437524e+03 -1.25611145e+03 -1.27903210e+03 -1.30156982e+03 -1.32164807e+03 -1.34562354e+03 -1.36803748e+03 -1.38690576e+03 -1.40809888e+03 -1.43020154e+03 -1.45091418e+03 -1.47070093e+03 -1.49121997e+03 -1.51229968e+03 -1.53129541e+03 -1.54941577e+03 -1.57037683e+03 -1.58866821e+03 -1.60792151e+03 -1.62807019e+03 -1.64465649e+03 -1.66688013e+03 -1.68089197e+03 -1.69578699e+03 -1.71812488e+03 -1.73262708e+03 -1.75153394e+03 -1.76481836e+03 -1.77878125e+03 -1.80169922e+03 -1.82030835e+03 -1.83159204e+03 -1.84180310e+03 -1.85786023e+03 -1.87779309e+03 -1.88848999e+03 -1.90642847e+03 -1.91932556e+03 -1.93323499e+03 -1.95224817e+03 -1.95966309e+03 -1.97250916e+03 -1.98154590e+03 -1.98856995e+03 -2.00613171e+03 -2.01647375e+03 -2.02920825e+03 -2.03706628e+03 -2.04332764e+03 -2.06286060e+03 -2.07322852e+03 -2.08060840e+03 -2.09275684e+03 -2.09546338e+03 -2.11098633e+03 -2.12094458e+03 -2.12421338e+03 -2.12881494e+03 -2.13596313e+03 -2.15135181e+03 -2.15372144e+03 -2.15198926e+03 -2.16859570e+03 -2.17483472e+03 -2.17770410e+03 -2.18644678e+03 -2.18677368e+03 -2.18896899e+03 -2.20350659e+03 -2.19826074e+03 -2.19825171e+03 -2.20528418e+03 -2.21499414e+03 -2.21503003e+03 -2.21189844e+03 -2.21474878e+03 -2.21863403e+03 -2.21951392e+03 -2.21461011e+03 -2.21770264e+03 -2.21985596e+03 -2.21648755e+03 -2.21897021e+03 -2.22057056e+03 -2.22779834e+03 -2.21784863e+03 -2.20824146e+03 -2.21390039e+03 -2.21088867e+03 -2.19989087e+03 -2.19915210e+03 -2.19909839e+03 -2.19564258e+03 -2.19623145e+03 -2.18338574e+03 -2.18307520e+03 -2.17432471e+03 -2.17516455e+03 -2.16007910e+03 -2.15572119e+03 -2.16073804e+03 -2.14733740e+03 -2.14186865e+03 -2.13630615e+03 -2.12396362e+03 -2.11214868e+03 -2.10438135e+03 -2.10251685e+03 -2.09226807e+03 -2.07508301e+03 -2.06933740e+03 -2.06212329e+03 -2.04979370e+03 -2.04210693e+03 -2.03114246e+03 -2.01503394e+03 -2.00248047e+03 -1.99444922e+03 -1.98900989e+03 -1.97421826e+03 -1.95481799e+03 -1.94072437e+03 -1.93472498e+03 -1.91862512e+03 -1.89920996e+03 -1.88353955e+03 -1.87344409e+03 -1.86648230e+03 -1.84783118e+03 -1.83174146e+03 -1.81421680e+03 -1.79505457e+03 -1.78165967e+03 -1.76893860e+03 -1.75043042e+03 -1.73270544e+03 -1.71439575e+03 -1.69633557e+03 -1.68299133e+03 -1.66032776e+03 -1.64215662e+03 -1.62632275e+03 -1.60672070e+03 -1.58768384e+03 -1.56794824e+03 -1.54981433e+03 -1.53051721e+03 -1.51099072e+03 -1.48974109e+03 -1.46934753e+03 -1.45217993e+03 -1.42793604e+03 -1.40663025e+03 -1.38726038e+03 -1.36420776e+03 -1.34336975e+03 -1.32318152e+03 -1.29916699e+03 -1.27590942e+03 -1.25426733e+03 -1.23353284e+03 -1.21067578e+03 -1.18699353e+03 -1.16367725e+03 -1.14058911e+03 -1.11714722e+03 -1.09395764e+03 -1.06919153e+03 -1.04547278e+03 -1.02165839e+03 -9.96994324e+02 -9.73000854e+02 -9.48610596e+02 -9.23387939e+02 -8.98301086e+02 -8.73685730e+02 -8.49376892e+02 -8.23360352e+02 -7.98319336e+02 -7.73197693e+02 -7.46527405e+02 -7.21090271e+02 -6.95649536e+02 -6.70059021e+02 -6.44111084e+02 -6.17096680e+02 -5.91023010e+02 -5.65345825e+02 -5.38817444e+02 -5.11758118e+02 -4.85448914e+02 -4.59230743e+02 -4.32280304e+02 -4.05379456e+02 -3.78709595e+02 -3.51915375e+02 -3.24954224e+02 -2.98066559e+02 -2.70947632e+02 -2.43907425e+02 -2.16913147e+02 -1.89718155e+02 -1.62496490e+02 -1.35288681e+02 -1.08146790e+02 -8.09260941e+01 -5.36806755e+01 -2.64584160e+01 7.75526464e-01 2.80090046e+01 5.52334404e+01 8.24734802e+01 1.09688004e+02 1.36865524e+02 1.64074371e+02 1.91222122e+02 2.18411819e+02 2.45479172e+02 2.72537018e+02 2.99501129e+02 3.26351471e+02 3.53432281e+02 3.80422607e+02 4.07083740e+02 4.33840820e+02 4.60497772e+02 4.86757996e+02 5.13308228e+02 5.40279480e+02 5.67079346e+02 5.92708984e+02 6.19124084e+02 6.45606812e+02 6.70671326e+02 6.96901611e+02 7.23294739e+02 7.48545837e+02 7.73806702e+02 7.99346558e+02 8.25683777e+02 8.50666443e+02 8.74364990e+02 8.99702820e+02 9.25353699e+02 9.49702087e+02 9.73951965e+02 9.99819885e+02 1.02424536e+03 1.04707617e+03 1.07072937e+03 1.09422937e+03 1.11953662e+03 1.14100134e+03 1.16506555e+03 1.18924402e+03 1.21037329e+03 1.23397241e+03 1.25633630e+03 1.27852661e+03 1.30112097e+03 1.32252380e+03 1.34494836e+03 1.36680176e+03 1.38712427e+03 1.40831042e+03 1.42971680e+03 1.45155713e+03 1.47146362e+03 1.49080676e+03 1.51279260e+03 1.53181519e+03 1.54885486e+03 1.57012988e+03 1.58866980e+03 1.60813928e+03 1.62710266e+03 1.64406921e+03 1.66642053e+03 1.67886206e+03 1.69639050e+03 1.71932349e+03 1.73184387e+03 1.75180615e+03 1.76629956e+03 1.77935815e+03 1.79986072e+03 1.81972021e+03 1.83029773e+03 1.84149719e+03 1.86224915e+03 1.87897717e+03 1.89047925e+03 1.90825903e+03 1.91963794e+03 1.93336914e+03 1.94933435e+03 1.95585266e+03 1.97455225e+03 1.98517126e+03 1.99007275e+03 2.00729810e+03 2.01726782e+03 2.03070349e+03 2.03911670e+03 2.04612805e+03 2.06133423e+03 2.06908472e+03 2.07796875e+03 2.09151807e+03 2.09818872e+03 2.10596582e+03 2.11537256e+03 2.13044165e+03 2.13030591e+03 2.13686133e+03 2.15178320e+03 2.15554712e+03 2.15329443e+03 2.16664429e+03 2.17341650e+03 2.17441675e+03 2.18436914e+03 2.18356616e+03 2.19352271e+03 2.20017358e+03 2.19859814e+03 2.19707031e+03 2.20263477e+03 2.20980273e+03 2.21854224e+03 2.21350659e+03 2.21535474e+03 2.21524780e+03 2.21901831e+03 2.21162378e+03 2.21504565e+03 2.22240381e+03 2.21489136e+03 2.21710986e+03 2.21831079e+03 2.22428442e+03 2.22112866e+03 2.20643726e+03 2.21091431e+03 2.21154590e+03 2.20360303e+03 2.19735693e+03 2.19977710e+03 2.19524341e+03 2.19114478e+03 2.18876660e+03 2.18142090e+03 2.17563354e+03 2.17322729e+03 2.16122339e+03 2.15795630e+03 2.15805200e+03 2.14612671e+03 2.13918872e+03 2.13703271e+03 2.12171069e+03 2.10821704e+03 2.10998755e+03 2.10240771e+03 2.08856689e+03 2.07662256e+03 2.07169556e+03 2.06158374e+03 2.04856348e+03 2.04492224e+03 2.03232056e+03 2.01553381e+03 2.00440942e+03 1.99325806e+03 1.98915210e+03 1.97542188e+03 1.95273657e+03 1.94160205e+03 1.93409155e+03 1.91817053e+03 1.90004370e+03 1.88451758e+03 1.87470422e+03 1.86684631e+03 1.84768018e+03 1.83027783e+03 1.81523022e+03 1.79501733e+03 1.78134399e+03 1.76758618e+03 1.74730554e+03 1.73362891e+03 1.71479395e+03 1.69715601e+03 1.68276843e+03 1.66143774e+03 1.64379907e+03 1.62708374e+03 1.60611572e+03 1.58476562e+03 1.56842505e+03 1.54984167e+03 1.53121167e+03 1.51194128e+03 1.48959583e+03 1.46939478e+03 1.45235498e+03 1.42868970e+03 1.40467395e+03 1.38637231e+03 1.36333850e+03 1.34236548e+03 1.32292261e+03 1.30017358e+03 1.27597998e+03 1.25473022e+03 1.23430701e+03 1.20984705e+03 1.18688647e+03 1.16458838e+03 1.14089221e+03 1.11650305e+03 1.09283496e+03 1.06928467e+03 1.04591602e+03 1.02174390e+03 1.31534326e+03 9.73616089e+02 1.21522803e+03 9.23281494e+02 8.98586609e+02 1.15264575e+03 8.49003052e+02 1.05500549e+03 7.98508789e+02 7.73190002e+02 7.46759033e+02 7.20874573e+02 6.95633362e+02 6.70060974e+02 6.43807861e+02 6.17354004e+02 5.91047729e+02 5.64997864e+02 5.38839966e+02 5.11958313e+02 4.85523682e+02 4.59187592e+02 4.32347992e+02 4.05403381e+02 3.78661407e+02 3.51902435e+02 3.24916840e+02 2.98034821e+02 2.70993042e+02 2.43907104e+02 2.16894119e+02 1.89724762e+02 1.62538498e+02 1.35323471e+02 1.08152512e+02 8.09337997e+01 5.37011871e+01 2.65036259e+01 -7.56641626e-01 -2.80251255e+01 -5.52501602e+01 -8.24713364e+01 -1.09677269e+02 -1.36874374e+02 -1.64090149e+02 -1.91214432e+02 -2.18381439e+02 -2.45449554e+02 -2.72502991e+02 -2.99504333e+02 -3.26358521e+02 -3.53416473e+02 -3.80335876e+02 -4.07022614e+02 -4.33778320e+02 -4.60440552e+02 -4.87029449e+02 -5.13718201e+02 -5.40075073e+02 -5.66552979e+02 -5.92886169e+02 -6.19352356e+02 -6.45455688e+02 -6.70661987e+02 -6.97056030e+02 -7.23247131e+02 -7.48352661e+02 -7.73539856e+02 -7.99449829e+02 -8.25916260e+02 -8.51008667e+02 -8.74810974e+02 -8.99560791e+02 -9.25219238e+02 -9.50605530e+02 -9.73804993e+02 -9.98844116e+02 -1.02364386e+03 -1.04658728e+03 -1.07063074e+03 -1.09440344e+03 -1.11857520e+03 -1.14212366e+03 -1.16538806e+03 -1.18806140e+03 -1.21075061e+03 -1.23411511e+03 -1.25591272e+03 -1.27906250e+03 -1.30056091e+03 -1.32182446e+03 -1.34522253e+03 -1.36739758e+03 -1.38735718e+03 -1.40861316e+03 -1.42952930e+03 -1.45059863e+03 -1.47081055e+03 -1.49149512e+03 -1.51251416e+03 -1.53188330e+03 -1.55037622e+03 -1.56891052e+03 -1.58947888e+03 -1.60860034e+03 -1.62650867e+03 -1.64574207e+03 -1.66760022e+03 -1.67923438e+03 -1.69625867e+03 -1.71917676e+03 -1.73390100e+03 -1.75212158e+03 -1.76610449e+03 -1.77853711e+03 -1.80150208e+03 -1.81940564e+03 -1.83081775e+03 -1.84005566e+03 -1.85803601e+03 -1.87866858e+03 -1.88993896e+03 -1.90612341e+03 -1.91934985e+03 -1.93439783e+03 -1.95138867e+03 -1.95900549e+03 -1.97118127e+03 -1.98018640e+03 -1.99175610e+03 -2.00822253e+03 -2.01867395e+03 -2.02852368e+03 -2.04101831e+03 -2.04747754e+03 -2.06338086e+03 -2.07354956e+03 -2.07910059e+03 -2.09220190e+03 -2.09487109e+03 -2.10594043e+03 -2.12029834e+03 -2.12707227e+03 -2.12917212e+03 -2.13485864e+03 -2.15182007e+03 -2.15758130e+03 -2.15141431e+03 -2.16729980e+03 -2.17565527e+03 -2.17778638e+03 -2.18416748e+03 -2.18798413e+03 -2.18934399e+03 -2.19975317e+03 -2.19789844e+03 -2.19734863e+03 -2.20495312e+03 -2.20780420e+03 -2.21587329e+03 -2.21499268e+03 -2.21301636e+03 -2.22061182e+03 -2.22088184e+03 -2.21406738e+03 -2.21585962e+03 -2.21999194e+03 -2.21643018e+03 -2.22080249e+03 -2.21808765e+03 -2.22933643e+03 -2.22201196e+03 -2.20795117e+03 -2.21619141e+03 -2.21114453e+03 -2.20096558e+03 -2.20048022e+03 -2.20303369e+03 -2.19376294e+03 -2.19149512e+03 -2.18901514e+03 -2.18306909e+03 -2.17425879e+03 -2.17249390e+03 -2.16297827e+03 -2.15624048e+03 -2.16299316e+03 -2.14529053e+03 -2.13998315e+03 -2.13936060e+03 -2.11975391e+03 -2.11163721e+03 -2.10337500e+03 -2.10086475e+03 -2.09220410e+03 -2.68749219e+03 -4.94430078e+03 -6.14532178e+03 -17523394. 10544034. -6.37134750e+05 -6.37134750e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 11674563. -1.54203238e+06 -7.05707373e+03 -5.95485254e+03 -4.48313867e+03 -2.35781396e+03 -1.78243311e+03 -1.76529456e+03 -1.74725134e+03 -1.73243066e+03 -1.71555310e+03 -1.69594495e+03 -1.68247388e+03 -1.66261218e+03 -1.64594751e+03 -1.62748132e+03 -1.60759888e+03 -1.58541418e+03 -1.56730347e+03 -1.54962244e+03 -1.53080920e+03 -1.51262488e+03 -1.49021521e+03 -1.46925098e+03 -1.45117041e+03 -1.42805151e+03 -1.40765320e+03 -1.38736230e+03 -1.36367102e+03 -1.34330615e+03 -1.32265015e+03 -1.29984912e+03 -1.27591602e+03 -1.25376245e+03 -1.23407458e+03 -1.21142456e+03 -1.18741858e+03 -1.16380664e+03 -1.13973938e+03 -1.11754285e+03 -1.09322302e+03 -1.06895508e+03 -1.04596130e+03 -1.02149847e+03 -9.97632629e+02 -9.73199463e+02 -9.48704468e+02 -9.23514160e+02 -8.98818054e+02 -8.74103271e+02 -8.49158142e+02 -8.23231384e+02 -7.98177917e+02 -7.73108582e+02 -7.46508850e+02 -7.21351135e+02 -6.95578552e+02 -6.69993896e+02 -6.44153931e+02 -6.17165649e+02 -5.91195984e+02 -5.65400818e+02 -5.38801147e+02 -5.12076172e+02 -4.85644379e+02 -4.59299805e+02 -4.32717804e+02 -4.05345734e+02 -1.57012109e+03 -1.06117712e+03 266354944. 266354944. 261679568. 3.52158450e+06 -4.73813555e+04 -3.90154388e+02 -4.82586304e+02 -5.79229736e+02 -7.83469219e+04 -1.15726826e+04 3.89611125e+06 -2.65623725e+06 0. 0. -1902562432. 62493520. 1.36884265e+03 -1279582080. -277667808. 0. 0. -870164800. 3.62835767e+03 7.58924561e+02 4.89532837e+02 4.99484558e+02 4.99634705e+02 4.05959839e+02 4.32928253e+02 4.59707977e+02 4.85990692e+02 5.12343018e+02 5.39042236e+02 5.65378052e+02 5.91111206e+02 6.17674377e+02 6.44180969e+02 6.69605896e+02 6.95354370e+02 7.21401550e+02 7.46841858e+02 7.72406128e+02 7.97860657e+02 8.23112732e+02 8.48625122e+02 8.72771240e+02 8.98080444e+02 9.23489258e+02 9.48045288e+02 9.72339050e+02 9.96758850e+02 1.02121698e+03 1.04418945e+03 1.06933948e+03 1.09349060e+03 1.11668848e+03 1.13850256e+03 1.16132593e+03 1.18576245e+03 1.20769531e+03 1.23061023e+03 1.25403955e+03 1.27760632e+03 1.29915808e+03 1.32032764e+03 1.34257715e+03 1.36267163e+03 1.38346387e+03 1.40480310e+03 1.42781311e+03 1.44845923e+03 1.46743762e+03 1.48830359e+03 1.50910291e+03 1.52786560e+03 1.54732373e+03 1.56736731e+03 1.58594690e+03 1.60369641e+03 1.62098865e+03 1.64449207e+03 1.66409119e+03 1.67377917e+03 1.69515491e+03 1.71395435e+03 2.23884253e+03 2.38724976e+03 4.24414014e+03 5.62919336e+03 11322082. 13851109. -16776671. -16776671. 0. 0. -441762368. -441762368. -4.24307302e+09 -65236368. -65236368. 0. 0. 0. 0. 37017584. 6405148. 6.12401562e+03 4.89557959e+03 2.81424390e+03 2.67463794e+03 2.06791797e+03 2.07350049e+03 2.08193384e+03 2.09597412e+03 2.10764331e+03 2.11098462e+03 2.11918799e+03 2.13454004e+03 2.13245386e+03 2.14238086e+03 2.15192163e+03 2.15408179e+03 2.16427051e+03 2.16905786e+03 2.17162891e+03 2.17729980e+03 2.17859375e+03 2.18345142e+03 2.19667456e+03 2.19067651e+03 2.19817236e+03 2.20198438e+03 2.20054810e+03 2.20907373e+03 2.21372510e+03 2.20833984e+03 2.21059033e+03 2.21834180e+03 2.21033252e+03 2.21343457e+03 2.21626270e+03 2.21759888e+03 2.21325464e+03 2.21370850e+03 2.21530884e+03 2.21225317e+03 2.20733667e+03 2.20983447e+03 2.20470459e+03 2.19585034e+03 2.19814233e+03 2.19823682e+03 2.18972314e+03 2.18809595e+03 2.18596240e+03 2.17786816e+03 2.17242627e+03 2.16893677e+03 2.15687231e+03 2.15509985e+03 2.15471362e+03 2.14090796e+03 2.13665552e+03 2.12970532e+03 2.12077563e+03 2.10617065e+03 2.09792407e+03 2.09797559e+03 2.08452441e+03 2.07226123e+03 2.06575464e+03 2.06039307e+03 2.04274011e+03 2.03874487e+03 2.02534302e+03 2.01068982e+03 2.00347876e+03 1.99461292e+03 1.98133997e+03 1.96603882e+03 1.95522363e+03 1.94031689e+03 1.92487549e+03 1.91223218e+03 1.89612524e+03 1.88398718e+03 1.87179492e+03 1.85861816e+03 1.84364905e+03 1.83007361e+03 1.81175708e+03 1.79433154e+03 1.78197095e+03 1.76235400e+03 1.74369580e+03 1.73060571e+03 1.70947913e+03 1.69386133e+03 1.68023291e+03 1.65903320e+03 1.64155371e+03 1.62349841e+03 1.60448633e+03 1.58073523e+03 1.56535266e+03 1.54789990e+03 1.52673889e+03 1.50856226e+03 1.48702344e+03 1.46615662e+03 1.44733728e+03 1.42659070e+03 1.40509131e+03 1.38304712e+03 1.36065002e+03 1.34174792e+03 1.31998279e+03 1.29753918e+03 1.27544739e+03 1.25276550e+03 1.22970044e+03 1.20785315e+03 1.18463562e+03 1.16069775e+03 1.13827026e+03 1.11536890e+03 1.09184399e+03 1.06754016e+03 1.04364624e+03 1.02009534e+03 9.96049377e+02 9.71147095e+02 9.47175842e+02 9.21886169e+02 8.96541504e+02 8.72178223e+02 8.47873962e+02 8.22009155e+02 7.96856506e+02 7.71825195e+02 7.45395081e+02 7.20280090e+02 6.94327026e+02 6.68419006e+02 6.42837830e+02 6.16110168e+02 5.90137756e+02 5.64326111e+02 5.37837097e+02 5.11299896e+02 4.84368103e+02 4.58269073e+02 4.31660278e+02 4.04749023e+02 3.78215302e+02 3.51362946e+02 3.24421631e+02 2.97653931e+02 2.70568726e+02 2.43557938e+02 2.16608795e+02 1.89471527e+02 1.62361710e+02 1.35224396e+02 1.08090408e+02 8.09346466e+01 5.37555656e+01 2.65750484e+01 -6.10849380e-01 -2.77982788e+01 -5.49756165e+01 -8.21461639e+01 -1.09304039e+02 -1.36435349e+02 -1.63587265e+02 -1.90690811e+02 -2.17763321e+02 -2.44802902e+02 -2.71830261e+02 -2.98774414e+02 -3.25595825e+02 -3.52534882e+02 -3.79375824e+02 -4.05988190e+02 -4.32725800e+02 -4.59323425e+02 -4.85985931e+02 -5.12607666e+02 -5.38674927e+02 -5.65181641e+02 -5.91673279e+02 -6.17910339e+02 -6.43703613e+02 -8.60459595e+02 -9.34748474e+02 -1.08279590e+03 -1.12158899e+03 -1.15862292e+03 -1.19681055e+03 -1.23552063e+03 -1.27313538e+03 -1.31026758e+03 -1.34843787e+03 -1.38601843e+03 -1.42266956e+03 -1.45783557e+03 -1.49535986e+03 -1.53265881e+03 -1.56772681e+03 -1.60241785e+03 -1.63864526e+03 -1.55080200e+03 -1.70928906e+03 -1.57712341e+03 -1.77926514e+03 -1.66655933e+03 -1.61416748e+03 -1.25386682e+03 -1.27640271e+03 -1.29757471e+03 -1.32056897e+03 -1.34240601e+03 -1.36371899e+03 -1.38482080e+03 -1.40446887e+03 -1.42751306e+03 -1.44886890e+03 -1.46724121e+03 -1.48722827e+03 -1.50783301e+03 -1.52675073e+03 -1.54712158e+03 -1.56949878e+03 -1.58446350e+03 -1.60397876e+03 -1.62367603e+03 -1.64386035e+03 -1.66461694e+03 -1.67764648e+03 -1.69185181e+03 -1.71254565e+03 -1.73119373e+03 -1.74632727e+03 -1.76009229e+03 -1.77781567e+03 -1.79733594e+03 -1.81439929e+03 -1.83006006e+03 -1.83764038e+03 -1.85215820e+03 -1.87378564e+03 -1.88856433e+03 -1.90107007e+03 -1.91469116e+03 -1.92984692e+03 -1.94728345e+03 -1.95527136e+03 -1.96677893e+03 -1.97643872e+03 -1.98702051e+03 -2.00552576e+03 -2.01437720e+03 -2.02713000e+03 -2.03462305e+03 -2.04608142e+03 -2.05867017e+03 -2.06806079e+03 -2.08252148e+03 -2.08506543e+03 -2.09112964e+03 -2.10711426e+03 -2.11183472e+03 -2.12007910e+03 -2.12851465e+03 -2.13189282e+03 -2.14237305e+03 -2.15140845e+03 -2.15215991e+03 -2.16358643e+03 -2.16977417e+03 -2.17205811e+03 -2.18052051e+03 -2.17978052e+03 -2.18297290e+03 -2.19800928e+03 -2.19201660e+03 -2.19832422e+03 -2.20206909e+03 -2.20180713e+03 -2.20745166e+03 -2.21016016e+03 -2.20748584e+03 -2.21009937e+03 -2.21507471e+03 -2.21253613e+03 -2.21489551e+03 -2.21868408e+03 -2.21173560e+03 -2.21146240e+03 -2.21444312e+03 -2.21828467e+03 -2.21135864e+03 -2.21078589e+03 -2.20989648e+03 -2.20619702e+03 -2.20005298e+03 -2.20015918e+03 -2.19997925e+03 -2.19090381e+03 -2.18565112e+03 -2.18331128e+03 -2.17743506e+03 -2.16913428e+03 -2.16971606e+03 -2.15572729e+03 -2.15133618e+03 -2.15857983e+03 -2.14479443e+03 -2.13713672e+03 -2.13052490e+03 -2.12079834e+03 -2.10612646e+03 -2.09959351e+03 -2.09993848e+03 -2.08563257e+03 -2.06890039e+03 -2.06568408e+03 -2.06257080e+03 -2.04299780e+03 -2.03767651e+03 -2.02316345e+03 -2.00912012e+03 -1.99961743e+03 -1.99321033e+03 -1.98179980e+03 -1.96828674e+03 -1.95294458e+03 -1.94104736e+03 -1.92774622e+03 -1.91290857e+03 -1.89816296e+03 -1.88288501e+03 -1.87217383e+03 -1.85807935e+03 -1.84240344e+03 -1.82844531e+03 -1.81084326e+03 -1.79255615e+03 -1.78078882e+03 -1.76600366e+03 -1.74769714e+03 -1.72947937e+03 -1.70993726e+03 -1.69469177e+03 -1.67907458e+03 -1.65857495e+03 -1.64117468e+03 -1.62310339e+03 -1.60382239e+03 -1.58142334e+03 -1.56356018e+03 -1.54832666e+03 -1.52880872e+03 -1.50908472e+03 -1.48681934e+03 -1.46547424e+03 -1.44840454e+03 -1.42633203e+03 -1.40257507e+03 -1.38217175e+03 -1.36099512e+03 -1.34298499e+03 -1.31985645e+03 -1.29641553e+03 -1.27547693e+03 -1.25185010e+03 -1.22896472e+03 -1.20909241e+03 -1.18546936e+03 -1.16072668e+03 -1.13845557e+03 -1.11535034e+03 -1.09192761e+03 -1.06727808e+03 -1.04368750e+03 -1.01995807e+03 -9.95330017e+02 -9.71031921e+02 -9.47208862e+02 -9.22479065e+02 -8.96788818e+02 -8.71959473e+02 -8.47705505e+02 -8.21763916e+02 -7.96891968e+02 -7.71789185e+02 -7.45319702e+02 -7.20179077e+02 -6.94497742e+02 -6.68399353e+02 -6.42857422e+02 -6.16059204e+02 -5.90055237e+02 -5.64750977e+02 -5.37870972e+02 -5.10863281e+02 -4.84376251e+02 -4.58345947e+02 -4.31639313e+02 -4.04695435e+02 -3.78272797e+02 -3.51411224e+02 -3.24426819e+02 -2.97580231e+02 -2.70543152e+02 -2.43603287e+02 -2.16595230e+02 -1.89472519e+02 -1.62373932e+02 -1.35204147e+02 -1.08087631e+02 -8.09299698e+01 -5.37484055e+01 -2.65728741e+01 6.11835778e-01 2.77960835e+01 5.49724960e+01 8.21502686e+01 1.09312782e+02 1.36437973e+02 1.63570496e+02 1.90705383e+02 2.17809845e+02 2.44783813e+02 2.71860657e+02 2.98811981e+02 3.25588684e+02 3.52562134e+02 3.79399475e+02 4.05924377e+02 4.32862000e+02 4.59615784e+02 4.85594025e+02 5.12136475e+02 5.39190613e+02 5.65596375e+02 5.91075500e+02 6.17560852e+02 6.44228027e+02 6.69589783e+02 6.95447876e+02 7.21354919e+02 7.46605774e+02 7.72624695e+02 7.97697266e+02 8.22772705e+02 8.48611511e+02 8.72597534e+02 8.98427612e+02 9.23084106e+02 9.47851746e+02 9.72765320e+02 9.96367004e+02 1.02093500e+03 1.04459009e+03 1.06858459e+03 1.09338428e+03 1.11635376e+03 1.13890454e+03 1.16271765e+03 1.18596362e+03 1.20802197e+03 1.23126624e+03 1.25408044e+03 1.27640857e+03 1.29934241e+03 1.32039661e+03 1.34250317e+03 1.36376807e+03 1.38496472e+03 1.40323718e+03 1.42730786e+03 1.45029883e+03 1.46820886e+03 1.48711743e+03 1.50915564e+03 1.52638330e+03 1.54678711e+03 1.56827966e+03 1.58466968e+03 1.60227917e+03 1.62363013e+03 1.64402661e+03 1.66469141e+03 1.67674353e+03 1.69377417e+03 1.71317700e+03 1.73105872e+03 1.74556702e+03 1.76012903e+03 1.78050732e+03 1.79507373e+03 1.81404980e+03 1.82869556e+03 1.83743701e+03 1.85652588e+03 1.87663818e+03 1.88693420e+03 1.89835632e+03 1.91308374e+03 1.93158093e+03 1.94709888e+03 1.95239453e+03 1.96918420e+03 1.97567993e+03 1.98771350e+03 2.00322913e+03 2.01276917e+03 2.02998901e+03 2.03692737e+03 2.04499512e+03 2.05548853e+03 2.06901611e+03 2.07768433e+03 2.08605688e+03 2.09589746e+03 2.09910254e+03 2.10579102e+03 2.12163867e+03 2.13190967e+03 2.13454883e+03 2.14265161e+03 2.15219922e+03 2.15064526e+03 2.16189209e+03 2.17012744e+03 2.17180396e+03 2.18148145e+03 2.17810229e+03 2.18256348e+03 2.19447534e+03 2.19449658e+03 2.20122632e+03 2.19836084e+03 2.20204980e+03 2.21080225e+03 2.21322827e+03 2.20929224e+03 2.21199585e+03 2.21733105e+03 2.21123901e+03 2.20935107e+03 2.21905640e+03 2.21532520e+03 2.21216699e+03 2.21415234e+03 2.21662085e+03 2.21301270e+03 2.20711646e+03 2.20696436e+03 2.20397607e+03 2.19806665e+03 2.19754810e+03 2.19575537e+03 2.19392407e+03 2.18488867e+03 2.18140576e+03 2.18117920e+03 2.17203345e+03 2.16779053e+03 2.15597388e+03 2.15281641e+03 2.15581299e+03 2.14511841e+03 2.13364966e+03 2.13044897e+03 2.11910913e+03 2.10866943e+03 2.10514453e+03 2.09980322e+03 2.08432007e+03 2.07194800e+03 2.06611377e+03 2.05864746e+03 2.04480615e+03 2.03564661e+03 2.02590088e+03 2.00961108e+03 2.00535718e+03 1.99183081e+03 1.98134973e+03 1.96745032e+03 1.95161816e+03 1.94208435e+03 1.92801880e+03 1.91456299e+03 1.89662317e+03 1.88276392e+03 1.87309265e+03 1.85756226e+03 1.84148352e+03 1.82878430e+03 1.81239221e+03 1.79166174e+03 1.77890686e+03 1.76542456e+03 1.74739050e+03 1.72800781e+03 1.70935803e+03 1.69469983e+03 1.67929602e+03 1.65794141e+03 1.64193188e+03 1.62342627e+03 1.60300342e+03 1.58052100e+03 1.56421753e+03 1.54878284e+03 1.52874292e+03 1.50882471e+03 1.48556897e+03 1.46656726e+03 1.44797583e+03 1.42597327e+03 1.40255566e+03 1.38297693e+03 1.36059680e+03 1.34187732e+03 1.32073291e+03 1.29701025e+03 1.27455359e+03 1.25245520e+03 1.23032800e+03 1.20726355e+03 1.18441467e+03 1.16176038e+03 1.13884924e+03 1.11435486e+03 1.09047327e+03 1.06733044e+03 1.04441223e+03 1.01975116e+03 1.96233606e+03 1.36517847e+03 2.23108862e+03 1.38170178e+03 1.34577344e+03 2.12655005e+03 1.27021423e+03 1.93248975e+03 1.19594824e+03 1.15766321e+03 1.11790320e+03 9.67156372e+02 1.04131274e+03 6.69059631e+02 8.32718872e+02 6.16607910e+02 5.90020264e+02 5.64290222e+02 5.38004517e+02 5.11129913e+02 4.84478973e+02 4.58291779e+02 4.31708984e+02 4.04793335e+02 3.78108002e+02 3.51344879e+02 3.24424957e+02 2.97564575e+02 2.70570465e+02 2.43606659e+02 2.16583694e+02 1.89470917e+02 1.62375336e+02 1.35220016e+02 1.08089447e+02 8.09376068e+01 5.37555542e+01 2.65806503e+01 -6.06983364e-01 -2.77939205e+01 -5.49705124e+01 -8.21482544e+01 -1.09302139e+02 -1.36437988e+02 -1.63577164e+02 -1.90687424e+02 -2.17777832e+02 -2.44793472e+02 -2.71808502e+02 -2.98772125e+02 -3.25631622e+02 -3.52613892e+02 -3.79322571e+02 -4.05906372e+02 -4.32795288e+02 -4.59468628e+02 -4.85929810e+02 -5.12427307e+02 -5.38763916e+02 -5.65372498e+02 -5.91467224e+02 -6.17815186e+02 -6.44015869e+02 -6.69468018e+02 -6.95446411e+02 -7.21624512e+02 -7.46727417e+02 -7.71921021e+02 -7.97575012e+02 -8.23349609e+02 -8.48823547e+02 -8.73135742e+02 -8.97997314e+02 -9.23001099e+02 -9.48042114e+02 -9.72364807e+02 -9.96673706e+02 -1.02114478e+03 -1.04470166e+03 -1.06862585e+03 -1.09236646e+03 -1.11609045e+03 -1.14006494e+03 -1.16279541e+03 -1.18593811e+03 -1.20806213e+03 -1.23092749e+03 -1.25437952e+03 -1.27627808e+03 -1.29726514e+03 -1.32044238e+03 -1.34165027e+03 -1.36366821e+03 -1.38545459e+03 -1.40403894e+03 -1.42730408e+03 -1.44900159e+03 -1.46706775e+03 -1.48738464e+03 -1.50821130e+03 -1.52789929e+03 -1.54719739e+03 -1.56702112e+03 -1.58561902e+03 -1.60183459e+03 -1.62178235e+03 -1.64383191e+03 -1.66437024e+03 -1.67549023e+03 -1.69182153e+03 -1.71373572e+03 -1.73192285e+03 -1.74612524e+03 -1.75944958e+03 -1.77956775e+03 -1.79620264e+03 -1.81583899e+03 -1.83001184e+03 -1.83781140e+03 -1.85251062e+03 -1.87409204e+03 -1.88715271e+03 -1.90142407e+03 -1.91527026e+03 -1.93090735e+03 -1.94723730e+03 -1.95515686e+03 -1.97023608e+03 -1.97639026e+03 -1.98576245e+03 -2.00526233e+03 -2.01386914e+03 -2.02436304e+03 -2.03741174e+03 -2.04521289e+03 -2.05854858e+03 -2.06717676e+03 -2.07923169e+03 -2.08595581e+03 -2.09063281e+03 -2.10154932e+03 -2.11009058e+03 -2.12078394e+03 -2.12740967e+03 -2.13269702e+03 -2.14095142e+03 -2.15547021e+03 -2.15153052e+03 -2.15950293e+03 -2.16942188e+03 -2.17657104e+03 -2.18318311e+03 -2.18038379e+03 -2.18152661e+03 -2.19477124e+03 -2.19532446e+03 -2.19972656e+03 -2.20010034e+03 -2.20248462e+03 -2.20979272e+03 -2.21051050e+03 -2.21026709e+03 -2.20992065e+03 -2.21956104e+03 -2.21292725e+03 -2.21284985e+03 -2.22100049e+03 -2.21215479e+03 -2.21293140e+03 -2.21450586e+03 -2.21538232e+03 -2.21240698e+03 -2.20920532e+03 -2.20889355e+03 -2.21053198e+03 -2.19870557e+03 -2.19564697e+03 -2.19586963e+03 -2.18786890e+03 -2.18368213e+03 -2.18669751e+03 -2.18037109e+03 -2.16729053e+03 -2.16537524e+03 -2.15722339e+03 -2.15145068e+03 -2.15642749e+03 -2.14518970e+03 -2.13410229e+03 -2.77321924e+03 -2.87858057e+03 -3.15422510e+03 -3.14916992e+03 -3.14564819e+03 -3.12732959e+03 -2.85185449e+03 -4.12871387e+03 -2.79946387e+03 -4.81843018e+03 -6.24364258e+03 -18128130. 88474184. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 171338688. -2.02805156e+04 -3.84576025e+03 -1.77796338e+03 -2.29434351e+03 -1.74567798e+03 -1.72979175e+03 -1.71018115e+03 -1.69534265e+03 -1.67814465e+03 -1.65884399e+03 -1.64313806e+03 -1.62411768e+03 -1.60433411e+03 -1.58071936e+03 -1.56497729e+03 -1.54817480e+03 -1.52772327e+03 -1.50898450e+03 -1.48603735e+03 -1.46661975e+03 -1.44772363e+03 -1.42576416e+03 -1.40431628e+03 -1.38405469e+03 -1.36190625e+03 -1.34256604e+03 -1.32021997e+03 -1.29714551e+03 -1.27561523e+03 -1.25132300e+03 -1.22950977e+03 -1.20858411e+03 -1.18590808e+03 -1.16062524e+03 -1.13768030e+03 -1.11571204e+03 -1.09187988e+03 -1.06770642e+03 -1.04407605e+03 -1.01972089e+03 -9.94951233e+02 -9.70845215e+02 -9.47050049e+02 -9.22686829e+02 -8.96916199e+02 -8.72247009e+02 -8.47295959e+02 -8.21446899e+02 -7.96757751e+02 -7.71703003e+02 -7.45290405e+02 -7.20345032e+02 -6.94278015e+02 -6.68420288e+02 -6.42989441e+02 -6.16079468e+02 -5.90022095e+02 -5.64547241e+02 -5.37919006e+02 -5.11231812e+02 -4.84520782e+02 -4.58152985e+02 -4.31713165e+02 -4.04911621e+02 -1.56674475e+03 -71669544. 0. 0. 0. 0. 0. -175946656. -175946656. -175946656. 0. 0. 0. 0. 0. 0. -1902562432. 62493520. 7.42814148e+02 9.49458191e+02 -1.32815531e+05 1363231488. 0. 0. -213172112. -10469757. 1.11851260e+04 1.08911243e+03 9.14049866e+02 6.08906311e+02 6.49096558e+02 6.29466797e+02 7.28507385e+02 5.12675049e+02 8.08685974e+02 7.78093140e+02 8.86215515e+02 9.26282532e+02 9.65988342e+02 1.00446332e+03 1.04268823e+03 1.08123010e+03 1.11895972e+03 1.15843909e+03 1.19727307e+03 1.23334497e+03 1.27197363e+03 1.30978125e+03 1.34764563e+03 1.38396118e+03 1.30097083e+03 1.45922253e+03 1.37391235e+03 1.52927271e+03 1.56723730e+03 1.60476917e+03 1.63719946e+03 1.67227454e+03 1.71130371e+03 1.74382251e+03 1.77723120e+03 1.80940881e+03 1.84420630e+03 1.88195984e+03 1.91656995e+03 1.94651770e+03 1.97836462e+03 2.01188452e+03 2.04588538e+03 1.89245776e+03 1.82477795e+03 1.42773389e+03 1.44765332e+03 1.46823413e+03 1.49050452e+03 1.50952881e+03 1.52901794e+03 1.54814502e+03 1.56911108e+03 1.58953601e+03 1.60581531e+03 1.62089343e+03 1.64405786e+03 1.66559558e+03 2.18245337e+03 2.33417603e+03 2.57201489e+03 4.16782568e+03 5.30026172e+03 -7.82585850e+06 40975212. 0. -16776671. -16776671. -16776671. 0. 0. -441762368. -441762368. -441762368. 0. 0. 0. 0. 0. 21716978. 2.41047578e+04 4.86560107e+03 2.78892944e+03 2.65547192e+03 2.05033130e+03 2.05839136e+03 2.06771313e+03 2.07903320e+03 2.70743188e+03 2.87577441e+03 3.16249365e+03 3.16492383e+03 3.17481909e+03 3.19658862e+03 3.19654028e+03 2.92627051e+03 2.80000439e+03 2.15749829e+03 2.16246680e+03 2.16877124e+03 2.17714648e+03 2.18312061e+03 2.18049707e+03 2.18643066e+03 2.19225659e+03 2.19551245e+03 2.19969287e+03 2.20911670e+03 2.20453857e+03 2.20677979e+03 2.21396289e+03 2.20967432e+03 2.21065308e+03 2.21541455e+03 2.20777075e+03 2.22000610e+03 2.21677100e+03 2.21463110e+03 2.21317822e+03 2.21790601e+03 2.21570117e+03 2.21435864e+03 2.20354810e+03 2.20947314e+03 2.20863940e+03 2.20169702e+03 2.19800391e+03 2.19556445e+03 2.19439062e+03 2.18852271e+03 2.18318115e+03 2.18043872e+03 2.17444922e+03 2.16838452e+03 2.15880688e+03 2.15836865e+03 2.15406079e+03 2.14351758e+03 2.13772974e+03 2.13021094e+03 2.11922827e+03 2.11425708e+03 2.10116602e+03 2.09694312e+03 2.09237573e+03 2.07653735e+03 2.06591138e+03 2.06069922e+03 2.04954565e+03 2.03498999e+03 2.02571448e+03 2.00788806e+03 2.00349341e+03 1.99595251e+03 1.98156726e+03 1.96835193e+03 1.95303845e+03 1.93789905e+03 1.92697668e+03 1.91297180e+03 1.89766980e+03 1.88607166e+03 1.87232275e+03 1.85679993e+03 1.84374707e+03 1.82763855e+03 1.81211328e+03 1.79528992e+03 1.78162817e+03 1.76629016e+03 1.74533850e+03 1.72835413e+03 1.71184863e+03 1.69623425e+03 1.68140088e+03 1.65985083e+03 1.64021875e+03 1.62457190e+03 1.60679675e+03 1.58521179e+03 1.56552258e+03 1.54939282e+03 1.52800891e+03 1.50838123e+03 1.48978210e+03 1.46688257e+03 1.44599866e+03 1.42753943e+03 1.40598096e+03 1.38371252e+03 1.36408130e+03 1.34274927e+03 1.31890405e+03 1.29705847e+03 1.27703796e+03 1.25372485e+03 1.22961047e+03 1.20876160e+03 1.18566333e+03 1.16159387e+03 1.13833765e+03 1.11616150e+03 1.09365186e+03 1.06800476e+03 1.04323474e+03 1.02034174e+03 9.96749878e+02 9.71509521e+02 9.47665100e+02 9.23192932e+02 8.96517700e+02 8.72134460e+02 8.48415955e+02 8.22798279e+02 7.96776917e+02 7.71726318e+02 7.46352600e+02 7.20928040e+02 6.94582214e+02 6.68553833e+02 6.43025635e+02 6.16573730e+02 5.90727417e+02 5.64339905e+02 5.37724854e+02 5.11649506e+02 4.84775818e+02 4.58190308e+02 4.31790924e+02 4.05072205e+02 3.78425903e+02 3.51479340e+02 3.24390656e+02 2.97654480e+02 2.70639893e+02 2.43602997e+02 2.16613907e+02 1.89448685e+02 1.62359497e+02 1.35172775e+02 1.08022102e+02 8.08565521e+01 5.36589813e+01 2.64701309e+01 -7.30367303e-01 -2.79394360e+01 -5.51457024e+01 -8.23450241e+01 -1.09521454e+02 -1.36675003e+02 -1.63804321e+02 -1.90970459e+02 -2.18074432e+02 -2.45055862e+02 -2.72102966e+02 -2.99147339e+02 -3.26132904e+02 -3.53101593e+02 -3.79675476e+02 -4.06321442e+02 -4.33194122e+02 -4.59891449e+02 -4.86436584e+02 -6.67532593e+02 -7.49862366e+02 -7.74730225e+02 -7.67812561e+02 -6.18206665e+02 -6.44392029e+02 -8.20131653e+02 -8.54304993e+02 -1.08288989e+03 -1.12211987e+03 -1.16017004e+03 -1.19732410e+03 -1.23643811e+03 -1.27446838e+03 -1.31139575e+03 -1.35020801e+03 -1.38785913e+03 -1.42385486e+03 -1.45889807e+03 -1.49469849e+03 -1.53274963e+03 -1.57114099e+03 -1.60524231e+03 -1.63896216e+03 -1.38807104e+03 -1.71072766e+03 -1.43021765e+03 -1.78083264e+03 -1.50139795e+03 -1.52311218e+03 -1.25532922e+03 -1.27850806e+03 -1.29867883e+03 -1.32012646e+03 -1.34255957e+03 -1.36492798e+03 -1.38494165e+03 -1.40651843e+03 -1.42890674e+03 -1.44864905e+03 -1.46856531e+03 -1.49035474e+03 -1.50918567e+03 -1.52615955e+03 -1.54752832e+03 -1.56979236e+03 -1.58770691e+03 -1.60490186e+03 -1.62582007e+03 -1.64308398e+03 -1.66542126e+03 -1.67905408e+03 -1.69302271e+03 -1.71578992e+03 -1.73169128e+03 -1.74442749e+03 -1.76217700e+03 -1.77941150e+03 -1.79786377e+03 -1.81646033e+03 -1.82771216e+03 -1.83993237e+03 -1.85755115e+03 -1.87507629e+03 -1.88980750e+03 -1.89924939e+03 -1.91535120e+03 -1.93198560e+03 -1.94684985e+03 -1.95758301e+03 -1.96631921e+03 -1.97644287e+03 -1.99239099e+03 -2.00663684e+03 -2.01103625e+03 -2.02754565e+03 -2.03662805e+03 -2.04873364e+03 -2.06149976e+03 -2.06797192e+03 -2.08145996e+03 -2.08405054e+03 -2.09593628e+03 -2.10755103e+03 -2.11198779e+03 -2.11826538e+03 -2.12610767e+03 -2.13723779e+03 -2.14816846e+03 -2.15478760e+03 -2.15318481e+03 -2.16291309e+03 -2.17162988e+03 -2.17381421e+03 -2.18178125e+03 -2.18086719e+03 -2.18650000e+03 -2.19736475e+03 -2.19507129e+03 -2.20239697e+03 -2.20514233e+03 -2.20199976e+03 -2.20736646e+03 -2.21275635e+03 -2.20699365e+03 -2.21399780e+03 -2.22061768e+03 -2.21144482e+03 -2.21997876e+03 -2.21940503e+03 -2.20955835e+03 -2.21557544e+03 -2.21842456e+03 -2.21930078e+03 -2.21449561e+03 -2.20413892e+03 -2.20979468e+03 -2.20973926e+03 -2.20184497e+03 -2.19985474e+03 -2.19427588e+03 -2.19571484e+03 -2.19350806e+03 -2.18310742e+03 -2.18111646e+03 -2.17498950e+03 -2.17247461e+03 -2.16155176e+03 -2.15787207e+03 -2.15185278e+03 -2.14266626e+03 -2.13652417e+03 -2.12932104e+03 -2.11840991e+03 -2.11343555e+03 -2.10274878e+03 -2.09768311e+03 -2.08318701e+03 -2.07477686e+03 -2.07063306e+03 -2.06329272e+03 -2.04712732e+03 -2.03609631e+03 -2.02610352e+03 -2.00656287e+03 -2.00267065e+03 -1.99588489e+03 -1.97815845e+03 -1.96826392e+03 -1.95538342e+03 -1.94096204e+03 -1.92718909e+03 -1.91471667e+03 -1.89808887e+03 -1.88701965e+03 -1.87214917e+03 -1.85674182e+03 -1.84311096e+03 -1.82717834e+03 -1.81277161e+03 -1.79428064e+03 -1.77960498e+03 -1.76893591e+03 -1.74849609e+03 -1.72758655e+03 -1.71106848e+03 -1.69636694e+03 -1.67930774e+03 -1.65979993e+03 -1.64161731e+03 -1.62215002e+03 -1.60571631e+03 -1.58561462e+03 -1.56489148e+03 -1.54925513e+03 -1.52837158e+03 -1.50836987e+03 -1.48937244e+03 -1.46567883e+03 -1.44748767e+03 -1.42765613e+03 -1.40541638e+03 -1.38386951e+03 -1.36365601e+03 -1.34282446e+03 -1.31942236e+03 -1.29564685e+03 -1.27646875e+03 -1.25348584e+03 -1.22958411e+03 -1.20978516e+03 -1.18590503e+03 -1.16108972e+03 -1.13891125e+03 -1.11572876e+03 -1.09297864e+03 -1.06815393e+03 -1.04360608e+03 -1.02009875e+03 -9.96232178e+02 -9.71477234e+02 -9.47665527e+02 -9.23764709e+02 -8.96842346e+02 -8.72063538e+02 -8.48246399e+02 -8.22491455e+02 -7.96763611e+02 -7.71674622e+02 -7.46342773e+02 -7.21030945e+02 -6.94786804e+02 -6.68317505e+02 -6.42820496e+02 -6.16598755e+02 -5.90582336e+02 -5.64587585e+02 -5.37748657e+02 -5.11414093e+02 -4.84857391e+02 -4.58282471e+02 -4.31774048e+02 -4.05065369e+02 -3.78337555e+02 -3.51387268e+02 -3.24449036e+02 -2.97628906e+02 -2.70556366e+02 -2.43614670e+02 -2.16563019e+02 -1.89436707e+02 -1.62383896e+02 -1.35191391e+02 -1.08008263e+02 -8.08463974e+01 -5.36664619e+01 -2.64581318e+01 7.49764740e-01 2.79578800e+01 5.51578331e+01 8.23485794e+01 1.09526512e+02 1.36664780e+02 1.63787231e+02 1.90970505e+02 2.18091934e+02 2.45045349e+02 2.72118896e+02 2.99175049e+02 3.26077942e+02 3.52838318e+02 3.79609528e+02 4.06375488e+02 4.33204315e+02 4.60107941e+02 4.86266449e+02 5.12625732e+02 5.39580017e+02 5.65798462e+02 5.91693481e+02 6.18051147e+02 6.44553650e+02 6.70377502e+02 6.95996338e+02 7.21323242e+02 7.47097534e+02 7.73465088e+02 7.99011597e+02 8.23640137e+02 8.48523560e+02 8.73957092e+02 9.00066162e+02 9.23731262e+02 9.48349548e+02 9.74014404e+02 9.96439209e+02 1.02066449e+03 1.04597058e+03 1.06978271e+03 1.09312170e+03 1.11675391e+03 1.14007068e+03 1.16294739e+03 1.18700659e+03 1.20890625e+03 1.23269824e+03 1.25606409e+03 1.27841833e+03 1.29818982e+03 1.32034753e+03 1.34238184e+03 1.36382996e+03 1.38608606e+03 1.40584570e+03 1.42870532e+03 1.44931812e+03 1.46902698e+03 1.49004224e+03 1.50910181e+03 1.52862610e+03 1.54779272e+03 1.56953650e+03 1.58741577e+03 1.60419812e+03 1.62521973e+03 1.64304370e+03 1.66363403e+03 1.67919592e+03 1.69333765e+03 1.71633472e+03 1.73265930e+03 1.74383862e+03 1.76112476e+03 1.78193567e+03 1.79621680e+03 1.81632166e+03 1.82793298e+03 1.83986145e+03 1.85833984e+03 1.87710425e+03 1.88884363e+03 1.89918530e+03 1.91528430e+03 1.93340576e+03 1.94599890e+03 1.95728015e+03 1.96888867e+03 1.97550574e+03 1.99182751e+03 2.00279480e+03 2.01079993e+03 2.02911829e+03 2.03561829e+03 2.04703284e+03 2.05945337e+03 2.06949219e+03 2.08003174e+03 2.08323096e+03 2.09985596e+03 2.10401392e+03 2.11113794e+03 2.12037231e+03 2.12709521e+03 2.13697998e+03 2.14740308e+03 2.15468115e+03 2.15261841e+03 2.16177344e+03 2.17554858e+03 2.17415894e+03 2.17887280e+03 2.18075122e+03 2.18783545e+03 2.19605640e+03 2.19477808e+03 2.20063379e+03 2.20597241e+03 2.20633350e+03 2.21177612e+03 2.21414209e+03 2.20786035e+03 2.21039771e+03 2.21981641e+03 2.20978198e+03 2.21773315e+03 2.21719189e+03 2.21033447e+03 2.21831274e+03 2.21906226e+03 2.22150415e+03 2.21335791e+03 2.20933252e+03 2.20736987e+03 2.20963306e+03 2.20271826e+03 2.20045288e+03 2.19600537e+03 2.19734131e+03 2.18916162e+03 2.18057568e+03 2.18256079e+03 2.17211279e+03 2.17063647e+03 2.16108740e+03 2.15649292e+03 2.15093384e+03 2.14424927e+03 2.13610913e+03 2.12695288e+03 2.12230054e+03 2.11447095e+03 2.10644800e+03 2.09859180e+03 2.08554712e+03 2.07542139e+03 2.07077710e+03 2.06289600e+03 2.04665930e+03 2.03605151e+03 2.02668872e+03 2.01099670e+03 2.00547461e+03 1.99398279e+03 1.98062903e+03 1.96801099e+03 1.95380469e+03 1.94114307e+03 1.92966589e+03 1.91331982e+03 1.89833325e+03 1.88622021e+03 1.87315686e+03 1.85801147e+03 1.84129858e+03 1.82616174e+03 1.81425378e+03 1.79472791e+03 1.78009338e+03 1.76785901e+03 1.74800281e+03 1.72661169e+03 1.71052271e+03 1.69687317e+03 1.67898926e+03 1.65971252e+03 1.64088843e+03 1.62328503e+03 1.60732007e+03 1.58532751e+03 1.56512463e+03 1.54893213e+03 1.52991260e+03 1.50816772e+03 1.48837891e+03 1.46727759e+03 1.44678918e+03 1.42771289e+03 1.40565405e+03 1.38397229e+03 1.36327759e+03 1.34253149e+03 1.32017871e+03 1.29681543e+03 1.27558582e+03 1.25245117e+03 1.23037061e+03 1.20899622e+03 1.18579480e+03 1.16222461e+03 1.13867480e+03 1.11525854e+03 1.09224927e+03 1.06808423e+03 1.04413196e+03 1.02072009e+03 1.96012085e+03 1.21326440e+03 2.25202441e+03 1.38484326e+03 1.34741211e+03 2.12511841e+03 1.27234790e+03 1.95134460e+03 1.19516187e+03 1.15815234e+03 1.11995337e+03 8.86275940e+02 1.04232922e+03 6.69380859e+02 7.88507935e+02 6.17081360e+02 5.90219055e+02 5.64676392e+02 5.38697144e+02 5.11371063e+02 4.84744263e+02 4.58314606e+02 4.31973083e+02 4.04778839e+02 3.77707489e+02 3.51622223e+02 3.25552521e+02 2.97798645e+02 2.70688171e+02 2.43704895e+02 2.16616547e+02 1.89452408e+02 1.62354279e+02 1.35181000e+02 1.08024879e+02 8.08687286e+01 5.36750870e+01 2.64618797e+01 -7.40734994e-01 -2.79464493e+01 -5.51533890e+01 -8.23463135e+01 -1.09509232e+02 -1.36659653e+02 -1.63810593e+02 -1.90976974e+02 -2.18055222e+02 -2.45060989e+02 -2.72108582e+02 -2.99100861e+02 -3.26114624e+02 -3.52944427e+02 -3.79599091e+02 -4.06372772e+02 -4.33211700e+02 -4.60002441e+02 -4.86503754e+02 -5.12810303e+02 -5.39253357e+02 -5.65750671e+02 -5.91954651e+02 -6.18314392e+02 -6.44434875e+02 -6.70240967e+02 -6.95998291e+02 -7.21679626e+02 -7.47469543e+02 -7.72720459e+02 -7.98460571e+02 -8.24184692e+02 -8.49133301e+02 -8.74017944e+02 -8.99111267e+02 -9.23937012e+02 -9.48674377e+02 -9.73393921e+02 -9.96504883e+02 -1.02111151e+03 -1.04522974e+03 -1.06953369e+03 -1.09329785e+03 -1.11721643e+03 -1.14048682e+03 -1.16293091e+03 -1.18740967e+03 -1.20933508e+03 -1.23147302e+03 -1.25566418e+03 -1.27868408e+03 -1.29853442e+03 -1.31939636e+03 -1.34213379e+03 -1.36538464e+03 -1.38663513e+03 -1.40671545e+03 -1.42821716e+03 -1.44880017e+03 -1.46949243e+03 -1.49034875e+03 -1.50791309e+03 -1.52868018e+03 -1.54798547e+03 -1.56913647e+03 -1.58852222e+03 -1.60504590e+03 -1.62289783e+03 -1.64426965e+03 -1.66627429e+03 -1.67768567e+03 -1.69214978e+03 -1.71694751e+03 -1.73392297e+03 -1.74446924e+03 -1.76120496e+03 -1.78008740e+03 -1.79764014e+03 -1.81811304e+03 -1.82909766e+03 -1.83979675e+03 -1.85605835e+03 -1.87464258e+03 -1.88743079e+03 -1.90077490e+03 -1.91856873e+03 -1.93368127e+03 -1.94577014e+03 -1.95497070e+03 -1.96928638e+03 -1.97867761e+03 -1.98997595e+03 -2.00311462e+03 -2.01284302e+03 -2.02918567e+03 -2.03774524e+03 -2.04873877e+03 -2.06246069e+03 -2.06664014e+03 -2.07885645e+03 -2.08691870e+03 -2.09535571e+03 -2.10689893e+03 -2.11364282e+03 -2.11937988e+03 -2.12695386e+03 -2.13729224e+03 -2.14698096e+03 -2.15459302e+03 -2.15124585e+03 -2.16004639e+03 -2.17140625e+03 -2.17456689e+03 -2.18011841e+03 -2.17975415e+03 -2.18672070e+03 -2.19427905e+03 -2.19783130e+03 -2.20032520e+03 -2.20425708e+03 -2.20406836e+03 -2.20688550e+03 -2.21612964e+03 -2.21096533e+03 -2.21387573e+03 -2.21946729e+03 -2.21031128e+03 -2.21656519e+03 -2.21925220e+03 -2.21298315e+03 -2.21452124e+03 -2.21845093e+03 -2.21905225e+03 -2.20857568e+03 -2.20905127e+03 -2.21379443e+03 -2.21146875e+03 -2.20952271e+03 -2.20203101e+03 -2.22454028e+03 -2.84964893e+03 -2.99676929e+03 -3.27645508e+03 -3.26306226e+03 -3.25454053e+03 -3.24566138e+03 -3.23712402e+03 -3.23060571e+03 -3.23471021e+03 -3.21933057e+03 -2.88383179e+03 -3.36364868e+03 -2.62322754e+03 -3.16432788e+03 -3.15153125e+03 -3.15123462e+03 -3.13543286e+03 -2.56919751e+03 -2.55118896e+03 -2.06053613e+03 -2.64391382e+03 -3.72614819e+03 -4.65591309e+03 19407244. 279000192. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 21756550. -2.16771660e+04 -2.66791772e+03 -4.23068115e+03 -2.61774512e+03 -2.59090015e+03 -2.56671729e+03 -2.31827856e+03 -2.18403174e+03 -1.65885266e+03 -1.64167773e+03 -1.62526904e+03 -1.60707483e+03 -1.58489966e+03 -1.56655261e+03 -1.54814380e+03 -1.52821643e+03 -1.50725391e+03 -1.48825427e+03 -1.46828918e+03 -1.44872314e+03 -1.42642737e+03 -1.40638757e+03 -1.38588477e+03 -1.36183984e+03 -1.34276733e+03 -1.31992639e+03 -1.29634521e+03 -1.27670703e+03 -1.25253821e+03 -1.23028186e+03 -1.21024854e+03 -1.18628589e+03 -1.16109924e+03 -1.13840234e+03 -1.11575867e+03 -1.09319678e+03 -1.06804285e+03 -1.04336853e+03 -1.02094611e+03 -9.96079224e+02 -9.70829651e+02 -9.47667542e+02 -9.23857910e+02 -8.97177124e+02 -8.72203308e+02 -8.48246399e+02 -8.21965088e+02 -7.96670349e+02 -7.71610046e+02 -7.45945618e+02 -7.21074280e+02 -6.94753662e+02 -6.68410522e+02 -6.43073547e+02 -6.16476562e+02 -5.90348999e+02 -7.32685120e+02 -7.36053711e+02 -7.66309204e+02 -7.26072815e+02 -6.86270447e+02 -6.46930786e+02 -6.06838806e+02 -2.34702612e+03 -53939496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.13973955e+10 -4.13973955e+10 0. 0. -1902562432. 62493520. 7.42814148e+02 9.49458191e+02 -1.32815531e+05 1363231488. 0. 0. 0. 0. 0. 78695328. 4.78086377e+03 1.25155994e+03 1.00568297e+05 1.33432825e+03 1.45584314e+03 7.67990662e+02 1.61779724e+03 1.76463550e+03 -7.07308828e+04 1.11749043e+04 5.13124750e+05 1.12385250e+06 4.85116162e+03 -6767677. -3.25245875e+06 -4455400. -6.04277188e+04 -1.02061188e+05 3.74550820e+04 2.50021094e+04 2.68218506e+03 2.76640991e+03 1.55418835e+03 2.91888257e+03 3.04016016e+03 -6.78794385e+03 2.44756875e+06 -1.24192375e+05 1.90291075e+06 2.65176050e+06 2.70202402e+04 3.30324336e+04 4.93684570e+04 -4.07970219e+05 -6.96909668e+02 2.89168188e+05 -6.94491211e+03 -2174376. 11124295. -2.34356203e+05 -1.03287262e+06 4.10743555e+03 3.36078052e+03 2.14369385e+03 2.17388989e+03 2.20351660e+03 2.04391199e+03 1.95755725e+03 1.53276318e+03 1.55337415e+03 1.57366455e+03 2.07385767e+03 2.22172925e+03 2.43692358e+03 2.47188452e+03 2.49517847e+03 4.05918408e+03 5.21976123e+03 1.98602031e+05 2.98070550e+06 200202848. 0. 0. 0. -16776671. -16776671. -16776671. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -15384775. 1.13265693e+04 2.64067944e+03 2.03292847e+03 2.04532422e+03 2.05572949e+03 2.06382935e+03 2.07577686e+03 2.08390527e+03 2.57585986e+03 2.59995142e+03 3.17211646e+03 3.17868994e+03 3.19302124e+03 3.20806665e+03 3.21724023e+03 2.65267261e+03 2.65515552e+03 2.16357104e+03 2.17059644e+03 2.17624756e+03 2.18005518e+03 2.18432153e+03 2.19085059e+03 2.19425024e+03 2.20132397e+03 2.20513379e+03 2.21175244e+03 2.21010571e+03 2.20948438e+03 2.21330640e+03 2.22169897e+03 2.21518970e+03 2.22063257e+03 2.22389819e+03 2.22212256e+03 2.22145361e+03 2.22586401e+03 2.22227905e+03 2.22606738e+03 2.22160498e+03 2.21467627e+03 2.21768677e+03 2.21941064e+03 2.21674536e+03 2.21587769e+03 2.20875586e+03 2.20539771e+03 2.20529150e+03 2.19692993e+03 2.19309424e+03 2.19607056e+03 2.19025610e+03 2.17850439e+03 2.17333032e+03 2.16712183e+03 2.16334497e+03 2.15861084e+03 2.14982837e+03 2.14307568e+03 2.13682861e+03 2.12460571e+03 2.12125000e+03 2.11220337e+03 2.10229175e+03 2.09114526e+03 2.08245361e+03 2.07412012e+03 2.06865332e+03 2.05298120e+03 2.04171313e+03 2.03290527e+03 2.01980298e+03 2.01051550e+03 2.00279175e+03 1.98488965e+03 1.97438220e+03 1.96136536e+03 1.94505505e+03 1.93636584e+03 1.91986096e+03 1.90391016e+03 1.89628455e+03 1.87791956e+03 1.86237830e+03 1.85010901e+03 1.83215320e+03 1.81967944e+03 1.80139343e+03 1.78703088e+03 1.76927917e+03 1.75180359e+03 1.73530249e+03 1.71882471e+03 1.70319409e+03 1.68349805e+03 1.66534009e+03 1.64563782e+03 1.63127771e+03 1.61257019e+03 1.58903711e+03 1.57151868e+03 1.55254749e+03 1.53148157e+03 1.51333521e+03 1.49429126e+03 1.47221460e+03 1.45254102e+03 1.43233118e+03 1.41046448e+03 1.38839380e+03 1.36759485e+03 1.34745801e+03 1.32294409e+03 1.30062927e+03 1.28182214e+03 1.25784924e+03 1.23430200e+03 1.21221167e+03 1.18986816e+03 1.16652234e+03 1.14224890e+03 1.11960669e+03 1.09664844e+03 1.07174194e+03 1.04706067e+03 1.02349225e+03 9.99315002e+02 9.75006348e+02 9.51248169e+02 9.26422058e+02 8.99594360e+02 8.75006836e+02 8.50794312e+02 8.25727783e+02 7.99602295e+02 7.74657043e+02 7.49003052e+02 7.22911133e+02 6.97240234e+02 6.70934387e+02 6.44812683e+02 6.18750000e+02 5.92799316e+02 5.66226440e+02 5.39616150e+02 5.13601013e+02 4.86836731e+02 4.59817566e+02 4.33150696e+02 4.06622986e+02 3.79772278e+02 3.52747070e+02 3.25618103e+02 2.98714935e+02 2.71698730e+02 2.44557037e+02 2.17436356e+02 1.90250336e+02 1.63076904e+02 1.35760269e+02 1.08528641e+02 8.12780991e+01 5.39943390e+01 2.67301292e+01 -5.60953915e-01 -2.78525715e+01 -5.51723366e+01 -8.24700851e+01 -1.09725998e+02 -1.36967514e+02 -1.64161224e+02 -1.91431061e+02 -2.18637390e+02 -2.45662308e+02 -2.72810760e+02 -3.00000946e+02 -3.27151489e+02 -3.54295685e+02 -3.80781403e+02 -4.07534088e+02 -4.34386932e+02 -4.61093719e+02 -4.87962219e+02 -6.29764465e+02 -6.65290344e+02 -7.05285278e+02 -7.34568848e+02 -6.19824219e+02 -6.45916809e+02 -8.57399231e+02 -9.29976990e+02 -1.08734167e+03 -1.12646301e+03 -1.16492761e+03 -1.97324622e+03 -2.61223779e+03 -2.42626611e+03 -2.02962305e+03 -1.35613855e+03 -1.39104871e+03 -1.42883862e+03 -1.46486426e+03 -1.50141589e+03 -1.53908557e+03 -1.57652039e+03 -1.61199902e+03 -1.64755200e+03 -1.56640417e+03 -1.71969507e+03 -1.57005273e+03 -1.78673840e+03 -1.69986230e+03 -1.62265417e+03 -1.25887427e+03 -1.28191272e+03 -1.30254700e+03 -1.32464014e+03 -1.34701562e+03 -1.36761902e+03 -1.38971350e+03 -1.41222583e+03 -1.43322412e+03 -1.45372217e+03 -1.47169043e+03 -1.49471875e+03 -1.51383838e+03 -1.53230200e+03 -1.55407788e+03 -1.57304968e+03 -1.59296313e+03 -1.61014172e+03 -1.62868774e+03 -1.65057727e+03 -1.66868774e+03 -1.68651367e+03 -1.70019775e+03 -1.71823169e+03 -1.73870691e+03 -1.75057715e+03 -1.76901807e+03 -1.78584106e+03 -1.80083630e+03 -1.82201489e+03 -1.83370654e+03 -1.84781409e+03 -1.86311902e+03 -1.88198376e+03 -1.89546155e+03 -1.90724561e+03 -1.92285437e+03 -1.93423840e+03 -1.95183484e+03 -1.96337000e+03 -1.96890295e+03 -1.97908411e+03 -1.99880164e+03 -2.01056348e+03 -2.01736816e+03 -2.03324646e+03 -2.04493018e+03 -2.05854565e+03 -2.06713428e+03 -2.07456055e+03 -2.08825415e+03 -2.09268652e+03 -2.10171313e+03 -2.10823120e+03 -2.11633472e+03 -2.12814526e+03 -2.13214746e+03 -2.14158179e+03 -2.15154907e+03 -2.15414355e+03 -2.16405396e+03 -2.17256592e+03 -2.18078809e+03 -2.18012476e+03 -2.18508496e+03 -2.18835107e+03 -2.19284009e+03 -2.20152637e+03 -2.20734204e+03 -2.21385376e+03 -2.21218970e+03 -2.21095166e+03 -2.21633984e+03 -2.21998779e+03 -2.21629346e+03 -2.21821484e+03 -2.22695972e+03 -2.22704419e+03 -2.22623511e+03 -2.21907031e+03 -2.22445337e+03 -2.22255786e+03 -2.22559204e+03 -2.22074048e+03 -2.21696899e+03 -2.21719800e+03 -2.21493628e+03 -2.21445483e+03 -2.21302393e+03 -2.21047339e+03 -2.20525854e+03 -2.19749341e+03 -2.19388013e+03 -2.19480908e+03 -2.19147217e+03 -2.18121631e+03 -2.17528540e+03 -2.16418677e+03 -2.16516138e+03 -2.15757007e+03 -2.14916382e+03 -2.14734521e+03 -2.13769556e+03 -2.12695728e+03 -2.12082520e+03 -2.11820581e+03 -2.10515894e+03 -2.08567017e+03 -2.07848462e+03 -2.08097852e+03 -2.07005396e+03 -2.05681665e+03 -2.04376086e+03 -2.02882715e+03 -2.01651038e+03 -2.00730383e+03 -2.00408960e+03 -1.98425781e+03 -1.97366003e+03 -1.96195911e+03 -1.94678223e+03 -1.93472986e+03 -1.92078040e+03 -1.90681042e+03 -1.89358960e+03 -1.87767236e+03 -1.86590503e+03 -1.84929150e+03 -1.83139441e+03 -1.81896094e+03 -1.80082190e+03 -1.78722485e+03 -1.77130701e+03 -1.75371521e+03 -1.73393579e+03 -1.71663342e+03 -1.70226819e+03 -1.68183264e+03 -1.66684180e+03 -1.64731079e+03 -1.62827966e+03 -1.61180225e+03 -1.59023242e+03 -1.57144971e+03 -1.55314307e+03 -1.53325134e+03 -1.51366919e+03 -1.49337280e+03 -1.47117773e+03 -1.45340869e+03 -1.43269434e+03 -1.41102295e+03 -1.38908813e+03 -1.36666162e+03 -1.34696460e+03 -1.32334045e+03 -1.30069604e+03 -1.28169446e+03 -1.25775513e+03 -1.23395422e+03 -1.21245447e+03 -1.19020752e+03 -1.16618811e+03 -1.14215979e+03 -1.11979761e+03 -1.09659680e+03 -1.07142932e+03 -1.04739233e+03 -1.02314276e+03 -9.99469238e+02 -9.74898010e+02 -9.51070679e+02 -9.26337585e+02 -8.99976562e+02 -8.75132812e+02 -8.50367615e+02 -8.25421814e+02 -7.99730103e+02 -7.74691345e+02 -7.48924377e+02 -7.23087708e+02 -6.97433167e+02 -6.70934082e+02 -6.44502930e+02 -6.18646362e+02 -5.92729919e+02 -5.66375427e+02 -5.39627563e+02 -5.13394226e+02 -4.86777954e+02 -4.59840363e+02 -4.33233032e+02 -4.06652588e+02 -3.79628876e+02 -3.52590607e+02 -3.25634705e+02 -2.98693817e+02 -2.71620514e+02 -2.44471481e+02 -2.17328186e+02 -1.90190018e+02 -1.63104446e+02 -1.35840958e+02 -1.08499847e+02 -8.12617111e+01 -5.40138283e+01 -2.67077904e+01 5.94026148e-01 2.78989735e+01 5.51816483e+01 8.24534760e+01 1.09733673e+02 1.36951889e+02 1.64147003e+02 1.91422974e+02 2.18628677e+02 2.45654007e+02 2.72794800e+02 2.99974457e+02 3.26930511e+02 3.53820831e+02 3.80665924e+02 4.07530823e+02 4.34372894e+02 4.61264008e+02 4.87853577e+02 5.14300781e+02 5.40988831e+02 5.67190674e+02 5.93441345e+02 6.19798767e+02 6.46248169e+02 6.72658386e+02 6.98064453e+02 7.23271973e+02 7.49967957e+02 7.76113220e+02 8.00720093e+02 8.26697205e+02 8.52008850e+02 8.76166199e+02 9.01108521e+02 9.26517700e+02 9.51523682e+02 9.76490173e+02 1.00033325e+03 1.02419238e+03 1.04869202e+03 1.07278113e+03 1.09729871e+03 1.12013269e+03 1.14317566e+03 1.16683313e+03 1.19046814e+03 1.21241150e+03 1.23632947e+03 1.26015735e+03 1.28203003e+03 1.30281885e+03 1.32543762e+03 1.34696289e+03 1.36746008e+03 1.38973962e+03 1.41052332e+03 1.43241809e+03 1.45288416e+03 1.47114929e+03 1.49426135e+03 1.51323230e+03 1.53471338e+03 1.55394165e+03 1.57256543e+03 1.59198267e+03 1.60830408e+03 1.62980713e+03 1.65287317e+03 1.66917273e+03 1.68629614e+03 1.70031213e+03 1.71712817e+03 1.74077820e+03 1.74911646e+03 1.76893030e+03 1.78824512e+03 1.79876343e+03 1.82088196e+03 1.83548145e+03 1.84687146e+03 1.86443872e+03 1.87976245e+03 1.89197668e+03 1.90568420e+03 1.92225476e+03 1.93544641e+03 1.95329248e+03 1.96533606e+03 1.96981946e+03 1.98117383e+03 2.00116492e+03 2.01008508e+03 2.01875830e+03 2.03498254e+03 2.04597278e+03 2.05737134e+03 2.06447583e+03 2.07703491e+03 2.08862427e+03 2.09228369e+03 2.10545068e+03 2.10892578e+03 2.11915723e+03 2.12722363e+03 2.13491626e+03 2.14373218e+03 2.15388330e+03 2.15538599e+03 2.16151733e+03 2.17097363e+03 2.17617822e+03 2.18078467e+03 2.18656787e+03 2.18863208e+03 2.19377954e+03 2.19917529e+03 2.20371362e+03 2.20865820e+03 2.21443237e+03 2.21582788e+03 2.21320312e+03 2.21600879e+03 2.21584961e+03 2.22031616e+03 2.22598999e+03 2.22528003e+03 2.22416528e+03 2.21892090e+03 2.22328540e+03 2.22272656e+03 2.22515796e+03 2.22366846e+03 2.21991162e+03 2.21769897e+03 2.21745068e+03 2.20750757e+03 2.21177759e+03 2.20853174e+03 2.20416113e+03 2.20141504e+03 2.19086841e+03 2.18937793e+03 2.18792944e+03 2.18250732e+03 2.17843945e+03 2.16747998e+03 2.16603735e+03 2.15862451e+03 2.14711279e+03 2.14607788e+03 2.14038525e+03 2.12466235e+03 2.12071094e+03 2.11518799e+03 2.10089111e+03 2.09049414e+03 2.08136694e+03 2.08007788e+03 2.07037280e+03 2.05539697e+03 2.04014050e+03 2.03269128e+03 2.01447986e+03 2.01105029e+03 2.00445837e+03 1.98532300e+03 1.97385315e+03 1.96244897e+03 1.94565845e+03 1.93697058e+03 1.92096655e+03 1.90346826e+03 1.89601831e+03 1.87995691e+03 1.86476367e+03 1.84837378e+03 1.83225696e+03 1.81984082e+03 1.80114636e+03 1.78779065e+03 1.77188416e+03 1.75353809e+03 1.73325903e+03 1.71735364e+03 1.70378821e+03 1.68254736e+03 1.66593994e+03 1.64583728e+03 1.62938513e+03 1.61325293e+03 1.59074451e+03 1.57147375e+03 1.55147424e+03 1.53231958e+03 1.51316626e+03 1.49325830e+03 1.47219275e+03 1.45246472e+03 1.43250818e+03 1.41074597e+03 1.38928186e+03 1.36749048e+03 1.34738159e+03 1.32395764e+03 1.30101123e+03 1.28160278e+03 1.25686682e+03 1.23443420e+03 1.21188318e+03 1.18878198e+03 1.16653284e+03 1.14235645e+03 1.11948792e+03 1.09613867e+03 1.07130603e+03 1.04731274e+03 1.02338361e+03 1.31873022e+03 1.37332825e+03 1.42710938e+03 1.39004504e+03 1.35233752e+03 1.31390564e+03 1.27575037e+03 1.24036304e+03 1.20308618e+03 1.16278076e+03 1.12542700e+03 9.72536865e+02 1.04749536e+03 6.72198425e+02 8.21345825e+02 6.17613770e+02 5.91065369e+02 5.68769653e+02 5.42110840e+02 5.13499268e+02 4.86818329e+02 4.60119476e+02 4.33684387e+02 4.06044128e+02 3.78241516e+02 3.53072083e+02 3.27468384e+02 2.99112030e+02 2.71884186e+02 2.44692047e+02 2.17463776e+02 1.90217163e+02 1.63048630e+02 1.35789612e+02 1.08535912e+02 8.12872314e+01 5.40074615e+01 2.67369938e+01 -5.66824257e-01 -2.79066067e+01 -5.52157516e+01 -8.24759064e+01 -1.09703598e+02 -1.36954346e+02 -1.64188965e+02 -1.91437317e+02 -2.18568878e+02 -2.45655350e+02 -2.72834412e+02 -2.99915039e+02 -3.26965332e+02 -3.53904968e+02 -3.80722107e+02 -4.07651733e+02 -4.34417603e+02 -4.61162354e+02 -4.87803741e+02 -5.14365417e+02 -5.40841675e+02 -5.67358398e+02 -5.93670044e+02 -6.20000061e+02 -6.46242126e+02 -6.72450073e+02 -6.98110962e+02 -7.23797302e+02 -7.49954224e+02 -7.75595520e+02 -8.00808044e+02 -8.27023010e+02 -8.52177979e+02 -8.76459106e+02 -9.01025635e+02 -9.26456787e+02 -9.51407532e+02 -9.76669128e+02 -1.00083191e+03 -1.02472766e+03 -1.04835437e+03 -1.07200427e+03 -1.09704956e+03 -1.12058984e+03 -1.14470386e+03 -1.16739087e+03 -1.18969019e+03 -1.21268042e+03 -1.23630591e+03 -1.25946326e+03 -1.28247327e+03 -1.30282849e+03 -1.32425684e+03 -1.34632666e+03 -1.36924670e+03 -1.39130591e+03 -1.41053174e+03 -1.43248669e+03 -1.45437708e+03 -1.47335168e+03 -1.49463159e+03 -1.51276978e+03 -1.53331238e+03 -1.55368555e+03 -1.57372363e+03 -1.59230615e+03 -1.60839185e+03 -1.62817590e+03 -1.65168201e+03 -1.66952551e+03 -1.68424597e+03 -1.69988440e+03 -1.71874597e+03 -1.74125818e+03 -1.75044116e+03 -1.76898706e+03 -1.78755603e+03 -1.79985132e+03 -1.82296631e+03 -1.83463647e+03 -1.84654956e+03 -1.86516504e+03 -1.88133630e+03 -1.89376990e+03 -1.90691418e+03 -1.92371643e+03 -1.93604150e+03 -1.95031250e+03 -1.96221228e+03 -1.97216199e+03 -1.98603613e+03 -2.00135571e+03 -2.00723962e+03 -2.02081848e+03 -2.03375378e+03 -2.04250098e+03 -2.05758081e+03 -2.06663940e+03 -2.07468945e+03 -2.09106787e+03 -2.09251099e+03 -2.10590698e+03 -2.10819287e+03 -2.11917188e+03 -2.13199487e+03 -2.13211108e+03 -2.14275244e+03 -2.15242480e+03 -2.15566235e+03 -2.16277173e+03 -2.17236475e+03 -2.18056567e+03 -2.18313086e+03 -2.18405908e+03 -2.18587036e+03 -2.19040894e+03 -2.19682520e+03 -2.20367334e+03 -2.21111572e+03 -2.21347656e+03 -2.21020386e+03 -2.21784351e+03 -2.22100977e+03 -2.21545654e+03 -2.21873438e+03 -2.22428931e+03 -2.22058789e+03 -2.22539575e+03 -2.22107153e+03 -2.21981982e+03 -2.22694312e+03 -2.22472192e+03 -2.22513965e+03 -2.21309717e+03 -2.21791211e+03 -2.21402100e+03 -2.21058325e+03 -2.21247095e+03 -2.21592700e+03 -2.22936963e+03 -2.69822461e+03 -2.70760938e+03 -3.30251538e+03 -3.28646997e+03 -3.27204834e+03 -3.25592139e+03 -3.24824414e+03 -3.24840820e+03 -3.23966333e+03 -3.22467847e+03 -2.65152441e+03 -3.37799927e+03 -2.93826343e+03 -3.18407324e+03 -3.17758521e+03 -3.16366650e+03 -3.14446387e+03 -2.83923633e+03 -2.69216016e+03 -2.06621313e+03 -2.05600659e+03 -2.51544312e+03 -2.61993677e+03 -5.02783350e+03 -2.07924727e+04 -35040284. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -202182896. -202182896. 13671897. 16994008. -4.75091650e+03 -5.63930508e+04 18262880. -5.17098584e+03 -4.10052246e+03 -2.49703882e+03 -2.46242627e+03 -2.43907153e+03 -2.41225586e+03 -2.18540381e+03 -2.04462402e+03 -1.55399500e+03 -1.53262305e+03 -1.51333228e+03 -1.49311365e+03 -1.47201501e+03 -1.88156519e+03 -1.95061963e+03 -2.10993604e+03 -2.08113013e+03 -2.04374084e+03 -2.01485730e+03 -1.98220728e+03 -1.94820117e+03 -1.91839136e+03 -1.88006995e+03 -1.84601367e+03 -1.81363196e+03 -1.78094043e+03 -1.74261938e+03 -1.70746460e+03 -1.67538110e+03 -1.64168298e+03 -1.60221216e+03 -1.45225183e+03 -1.53320483e+03 -1.36069312e+03 -1.45711731e+03 -1.42154077e+03 -1.38673071e+03 -1.34685571e+03 -1.30907751e+03 -1.27314514e+03 -1.23488428e+03 -1.19585901e+03 -1.15809509e+03 -1.12030664e+03 -1.08204175e+03 -1.04324377e+03 -1.00362396e+03 -9.65731384e+02 -9.25235596e+02 -8.85806213e+02 -1.32862805e+03 -1.55492920e+03 1.75568875e+06 8790920. 2.54955609e+05 1.07665984e+05 5.96893516e+04 -9049348. -616686720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.13973955e+10 -4.13973955e+10 0. 0. 0. 0. -440064992. -1.32815531e+05 -1.32815531e+05 1363231488. 0. 600903360. 8.76235062e+05 2.79726825e+06 -5.40771350e+06 51167944. 1.98555546e+10 1.98555546e+10 0. -248096720. -248096720. -9491195. -31841854. -31841854. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56744288. 56744288. 29543500. -35303540. -35303540. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 450898272. 450898272. 450898272. 0. 0. 2446779. 1.65293730e+04 8.27129004e+03 2.16370874e+03 3.49545215e+03 2.22276538e+03 1.85708667e+03 1.87289429e+03 1.54212146e+03 2.02824292e+03 2.16867334e+03 3.87303735e+03 4.99316895e+03 3.07393250e+05 -3.45545703e+04 -2.33892562e+05 1.18978338e+06 23614176. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.85282150e+06 -1.07543688e+06 -1.67580188e+05 5.53391797e+03 3.94562207e+03 2.03377954e+03 2.04521851e+03 2.05220557e+03 2.06536914e+03 2.07937427e+03 2.08755054e+03 2.09530225e+03 2.72983618e+03 2.89100928e+03 3.19594604e+03 3.20216919e+03 3.21539893e+03 3.23675586e+03 3.24411401e+03 2.98453882e+03 2.83456958e+03 2.17727979e+03 2.18483203e+03 2.18620166e+03 2.19197339e+03 2.20040332e+03 2.20531787e+03 2.20978174e+03 2.21395557e+03 2.21438696e+03 2.21854932e+03 2.22305566e+03 2.22881885e+03 2.22994019e+03 2.23400928e+03 2.23010059e+03 2.23176855e+03 2.23634082e+03 2.23590234e+03 2.23831860e+03 2.23751807e+03 2.23757471e+03 2.23632764e+03 2.23626245e+03 2.23621924e+03 2.24049292e+03 2.23363354e+03 2.22869849e+03 2.22007202e+03 2.22464990e+03 2.22171680e+03 2.21422974e+03 2.20961865e+03 2.20748022e+03 2.20025195e+03 2.20150537e+03 2.19814014e+03 2.18666089e+03 2.17546338e+03 2.17628516e+03 2.17279150e+03 2.16137256e+03 2.15961816e+03 2.14694458e+03 2.13882275e+03 2.13134839e+03 2.12256714e+03 2.11569556e+03 2.10506470e+03 2.09675977e+03 2.08617334e+03 2.07544653e+03 2.06831714e+03 2.05255273e+03 2.04366064e+03 2.03513196e+03 2.01904114e+03 2.01178857e+03 2.00079419e+03 1.98588525e+03 1.97117590e+03 1.95731470e+03 1.94418042e+03 1.93161938e+03 1.91961609e+03 1.90164160e+03 1.88776892e+03 1.87595557e+03 1.86041028e+03 1.84171057e+03 1.82769690e+03 1.81061841e+03 1.79800549e+03 1.78212207e+03 1.76254663e+03 1.74320667e+03 1.72699585e+03 1.71440283e+03 1.69265674e+03 1.67378162e+03 1.65687305e+03 1.63978845e+03 1.62021130e+03 1.60007703e+03 1.58166589e+03 1.56024280e+03 1.54129431e+03 1.52290930e+03 1.50199072e+03 1.48082471e+03 1.45923376e+03 1.44013684e+03 1.41899011e+03 1.39589417e+03 1.37548352e+03 1.35393030e+03 1.33054114e+03 1.30852112e+03 1.28713220e+03 1.26505640e+03 1.24234863e+03 1.21908484e+03 1.19525513e+03 1.17229688e+03 1.14928076e+03 1.12559241e+03 1.10188440e+03 1.07775952e+03 1.05353516e+03 1.02777124e+03 1.00425897e+03 9.81258728e+02 9.55482178e+02 9.30921631e+02 9.05201965e+02 8.80003418e+02 8.55005493e+02 8.29639099e+02 8.04419739e+02 7.78655701e+02 7.52432068e+02 7.26638123e+02 7.00805359e+02 6.74643372e+02 6.48014587e+02 6.21803284e+02 5.95923523e+02 5.68868958e+02 5.42377319e+02 5.16195068e+02 4.89311676e+02 4.62065216e+02 4.35278625e+02 4.08519592e+02 3.81378448e+02 3.54462646e+02 3.27119263e+02 2.99946075e+02 2.72847961e+02 2.45527634e+02 2.18254852e+02 1.90937637e+02 1.63574448e+02 1.36131622e+02 1.08750977e+02 8.13402786e+01 5.38635025e+01 2.64317169e+01 -1.00372088e+00 -2.84409447e+01 -5.59179802e+01 -8.33753815e+01 -1.10797935e+02 -1.38190750e+02 -1.65547302e+02 -1.92975891e+02 -2.20293961e+02 -2.47478485e+02 -2.74793793e+02 -3.02106506e+02 -3.29536530e+02 -3.57074219e+02 -3.83295685e+02 -4.10167999e+02 -4.37224976e+02 -4.63832581e+02 -4.91336823e+02 -6.43181946e+02 -6.89648499e+02 -8.20235962e+02 -7.98526306e+02 -6.24163086e+02 -6.49780640e+02 -6.76359253e+02 -7.03062378e+02 -7.28920410e+02 -7.53676270e+02 -7.79385193e+02 -9.90197449e+02 -1.02591602e+03 -1.06084326e+03 -1.08800635e+03 -9.07780884e+02 -9.32098267e+02 -9.57002197e+02 -9.81697937e+02 -1.00620160e+03 -1.35007104e+03 -1.46491577e+03 -1.61199902e+03 -1.64755200e+03 -1.51506580e+03 -1.47451196e+03 -1.17391345e+03 -1.19628955e+03 -1.22043823e+03 -1.24322485e+03 -1.26587549e+03 -1.28947058e+03 -1.31090686e+03 -1.33335352e+03 -1.35483325e+03 -1.37602673e+03 -1.39954297e+03 -1.42060364e+03 -1.44100098e+03 -1.46338782e+03 -1.48265381e+03 -1.50251721e+03 -1.52236963e+03 -1.54456458e+03 -1.56251453e+03 -1.58165137e+03 -1.60278491e+03 -1.62096594e+03 -1.63795789e+03 -1.65812048e+03 -1.67895923e+03 -1.69731250e+03 -1.71054382e+03 -1.72907043e+03 -1.75055042e+03 -1.76396362e+03 -1.77917944e+03 -1.79400574e+03 -1.81147424e+03 -1.83404395e+03 -1.84184717e+03 -1.85402795e+03 -1.87693884e+03 -1.89651331e+03 -1.90875061e+03 -1.91754285e+03 -1.93395239e+03 -1.94644763e+03 -1.96192358e+03 -1.97517126e+03 -1.97938721e+03 -1.99576514e+03 -2.01291187e+03 -2.02230884e+03 -2.03288062e+03 -2.04729993e+03 -2.05564355e+03 -2.06805005e+03 -2.08315649e+03 -2.08910986e+03 -2.09805835e+03 -2.10792358e+03 -2.11583887e+03 -2.12154468e+03 -2.12827759e+03 -2.14389648e+03 -2.14998853e+03 -2.15615894e+03 -2.16432788e+03 -2.16803223e+03 -2.17732642e+03 -2.18512109e+03 -2.18866553e+03 -2.19296973e+03 -2.20188110e+03 -2.20408228e+03 -2.20858691e+03 -2.21537402e+03 -2.21452051e+03 -2.21958228e+03 -2.22379614e+03 -2.23115601e+03 -2.22919263e+03 -2.23189478e+03 -2.22902344e+03 -2.23146069e+03 -2.24022729e+03 -2.23616895e+03 -2.23692065e+03 -2.23321265e+03 -2.23137695e+03 -2.23404395e+03 -2.23679468e+03 -2.24291699e+03 -2.23622168e+03 -2.23374292e+03 -2.22901001e+03 -2.22328296e+03 -2.22378613e+03 -2.22559937e+03 -2.21619360e+03 -2.20911255e+03 -2.20318750e+03 -2.20215674e+03 -2.20063452e+03 -2.19865869e+03 -2.18859912e+03 -2.17532715e+03 -2.17854932e+03 -2.17037842e+03 -2.16404004e+03 -2.15911035e+03 -2.14332959e+03 -2.13910913e+03 -2.13473682e+03 -2.12690845e+03 -2.11557129e+03 -2.10032104e+03 -2.09834399e+03 -2.09191382e+03 -2.07501147e+03 -2.07015674e+03 -2.05354834e+03 -2.04246460e+03 -2.03435059e+03 -2.01951880e+03 -2.01210547e+03 -2.00035205e+03 -1.98378528e+03 -1.97131555e+03 -1.95979236e+03 -1.94211926e+03 -1.92972107e+03 -1.92114465e+03 -1.90460547e+03 -1.88486096e+03 -1.87590857e+03 -1.86131738e+03 -1.84141956e+03 -1.82950427e+03 -1.81028943e+03 -1.79645264e+03 -1.78134558e+03 -1.76227930e+03 -1.74294690e+03 -1.72630518e+03 -1.71546533e+03 -1.69283142e+03 -1.67416162e+03 -1.65735925e+03 -1.63889221e+03 -1.61988062e+03 -1.59932764e+03 -1.58042896e+03 -1.55983972e+03 -1.54195483e+03 -1.52334814e+03 -1.50149658e+03 -1.47952991e+03 -1.45932031e+03 -1.44072046e+03 -1.41896277e+03 -1.39577002e+03 -1.37509106e+03 -1.35271497e+03 -1.33028247e+03 -1.30893518e+03 -1.28703772e+03 -1.26468884e+03 -1.24276709e+03 -1.21920349e+03 -1.19466760e+03 -1.17214050e+03 -1.14975830e+03 -1.12524438e+03 -1.10138879e+03 -1.07829553e+03 -1.05364185e+03 -1.02850134e+03 -1.00429285e+03 -9.80042725e+02 -9.55337524e+02 -9.31015930e+02 -9.05756714e+02 -8.80103699e+02 -8.54313660e+02 -8.29246399e+02 -8.04619446e+02 -7.78593750e+02 -7.52385620e+02 -7.26710693e+02 -7.00815125e+02 -6.74567810e+02 -6.47737366e+02 -6.21799744e+02 -5.95703735e+02 -5.68709473e+02 -5.42409912e+02 -5.16035034e+02 -4.89367188e+02 -4.62180786e+02 -4.35148315e+02 -4.08514404e+02 -3.81287994e+02 -3.54213623e+02 -3.27094086e+02 -2.99898926e+02 -2.72770874e+02 -2.45421127e+02 -2.18085037e+02 -1.90823029e+02 -1.63633133e+02 -1.36230179e+02 -1.08671631e+02 -8.12954330e+01 -5.39020767e+01 -2.64295998e+01 1.02025104e+00 2.84416599e+01 5.58845558e+01 8.33424301e+01 1.10794083e+02 1.38164581e+02 1.65515762e+02 1.92963745e+02 2.20331940e+02 2.47525681e+02 2.74807922e+02 3.02145294e+02 3.29255463e+02 3.56117371e+02 3.83165070e+02 4.10455719e+02 4.37202667e+02 4.64224243e+02 4.91426697e+02 5.17734924e+02 5.44207886e+02 5.70691833e+02 5.97622925e+02 6.24146301e+02 6.49993530e+02 6.76108215e+02 7.02470276e+02 7.28796143e+02 7.54753967e+02 7.80262451e+02 8.05694336e+02 8.31763672e+02 8.57234497e+02 8.81329102e+02 9.06766479e+02 9.33140808e+02 9.57393005e+02 9.81600159e+02 1.00537622e+03 1.03094971e+03 1.05567200e+03 1.07964075e+03 1.10245386e+03 1.12711914e+03 1.15087634e+03 1.17467236e+03 1.19667822e+03 1.22019360e+03 1.24526697e+03 1.26612683e+03 1.28841003e+03 1.31120251e+03 1.33313782e+03 1.35473706e+03 1.37484961e+03 1.39963416e+03 1.42045374e+03 1.44086877e+03 1.46434717e+03 1.48214563e+03 1.50166357e+03 1.52155273e+03 1.54527051e+03 1.56241614e+03 1.58046875e+03 1.60351062e+03 1.62012720e+03 1.63926196e+03 1.65927222e+03 1.67728320e+03 1.69291785e+03 1.70951196e+03 1.72937622e+03 1.75111292e+03 1.76295264e+03 1.78008191e+03 1.79488794e+03 1.81056421e+03 1.83072485e+03 1.84244495e+03 1.85807410e+03 1.87548267e+03 1.89326074e+03 1.90591309e+03 1.91257263e+03 1.93119995e+03 1.94798914e+03 1.96290942e+03 1.97704980e+03 1.98206360e+03 1.99652808e+03 2.01196179e+03 2.02006628e+03 2.03764624e+03 2.04689539e+03 2.05015454e+03 2.06650928e+03 2.08204834e+03 2.08764819e+03 2.09305469e+03 2.10637769e+03 2.11817896e+03 2.12041919e+03 2.12897412e+03 2.13811890e+03 2.14719385e+03 2.15979932e+03 2.17043018e+03 2.16641187e+03 2.17639062e+03 2.18630444e+03 2.19044971e+03 2.18987427e+03 2.19845142e+03 2.20729004e+03 2.20422021e+03 2.21214136e+03 2.21957910e+03 2.22013745e+03 2.22982642e+03 2.22800977e+03 2.22534790e+03 2.22445923e+03 2.22460181e+03 2.23186768e+03 2.23729419e+03 2.23483618e+03 2.24086206e+03 2.23061670e+03 2.22811841e+03 2.23641895e+03 2.23655347e+03 2.23906372e+03 2.23875244e+03 2.23346143e+03 2.22583594e+03 2.21472852e+03 2.22413525e+03 2.22940845e+03 2.21894800e+03 2.20708374e+03 2.20215405e+03 2.20509937e+03 2.20460522e+03 2.19687036e+03 2.18194141e+03 2.17570776e+03 2.18204370e+03 2.17105298e+03 2.15976855e+03 2.15970093e+03 2.14763672e+03 2.13716016e+03 2.13263110e+03 2.12174756e+03 2.11494116e+03 2.10353052e+03 2.09565796e+03 2.09060107e+03 2.07289380e+03 2.06830811e+03 2.05249585e+03 2.04335547e+03 2.03088696e+03 2.01659167e+03 2.01315308e+03 1.99802539e+03 1.98604932e+03 1.97429919e+03 1.95695264e+03 1.94573975e+03 1.93071619e+03 1.91805518e+03 1.90648633e+03 1.88701990e+03 1.87791187e+03 1.85976196e+03 1.84063916e+03 1.82835718e+03 1.80980225e+03 1.79887280e+03 1.78022473e+03 1.76180005e+03 1.74186182e+03 1.72591577e+03 1.71503784e+03 1.69279395e+03 1.67337878e+03 1.65566418e+03 1.64067322e+03 1.62070276e+03 1.60044214e+03 1.58103467e+03 1.56021399e+03 1.54174561e+03 1.52261011e+03 1.50172351e+03 1.47989844e+03 1.46025549e+03 1.43998755e+03 1.41873645e+03 1.39737329e+03 1.37547168e+03 1.35370483e+03 1.33076819e+03 1.30841064e+03 1.28737134e+03 1.26426465e+03 1.24221289e+03 1.21886816e+03 1.19553284e+03 1.17333411e+03 1.14828650e+03 1.12507654e+03 1.10125537e+03 1.07759265e+03 1.05365930e+03 1.02879028e+03 1.00478668e+03 9.80551392e+02 9.54925049e+02 9.30269287e+02 9.05267334e+02 8.79712402e+02 8.54594727e+02 8.28833679e+02 8.03984558e+02 9.91018066e+02 7.52608154e+02 9.61388977e+02 7.00536194e+02 6.74791382e+02 6.48296326e+02 6.19878601e+02 5.93683533e+02 5.71686768e+02 5.45346191e+02 5.16165039e+02 4.89345428e+02 4.62468140e+02 4.35597168e+02 4.07583832e+02 3.79452271e+02 3.55029144e+02 3.29375702e+02 3.00340637e+02 2.73005768e+02 2.45617035e+02 2.18317627e+02 1.90925201e+02 1.63556137e+02 1.36130127e+02 1.08725365e+02 8.13182449e+01 5.38751335e+01 2.64488392e+01 -1.03410292e+00 -2.85028458e+01 -5.59561501e+01 -8.33882751e+01 -1.10769913e+02 -1.38168488e+02 -1.65548965e+02 -1.92984772e+02 -2.20266525e+02 -2.47502380e+02 -2.74847504e+02 -3.02044342e+02 -3.29282745e+02 -3.56328735e+02 -3.83310059e+02 -4.10549713e+02 -4.37322906e+02 -4.64141388e+02 -4.91171783e+02 -5.17810425e+02 -5.44298401e+02 -5.70873352e+02 -5.97580139e+02 -6.24215271e+02 -6.50349731e+02 -6.76370483e+02 -7.02544800e+02 -7.28895264e+02 -7.54811584e+02 -7.80538635e+02 -8.05476440e+02 -8.31765381e+02 -8.57545105e+02 -8.81441162e+02 -9.07408325e+02 -9.33050903e+02 -9.57614990e+02 -9.81895813e+02 -1.00521466e+03 -1.03075525e+03 -1.05525818e+03 -1.07934521e+03 -1.10360901e+03 -1.12777844e+03 -1.15120947e+03 -1.17456372e+03 -1.19637585e+03 -1.22027869e+03 -1.24467444e+03 -1.26689075e+03 -1.28918066e+03 -1.31150024e+03 -1.33238135e+03 -1.35393274e+03 -1.37573926e+03 -1.39999805e+03 -1.42065198e+03 -1.43995117e+03 -1.46300610e+03 -1.48418628e+03 -1.50110840e+03 -1.52084814e+03 -1.54557861e+03 -1.56245032e+03 -1.58080823e+03 -1.60261975e+03 -1.61996533e+03 -1.63874109e+03 -1.65982068e+03 -1.67874585e+03 -1.69482349e+03 -1.70997791e+03 -1.72872339e+03 -1.75093689e+03 -1.76382874e+03 -1.78061096e+03 -1.79583545e+03 -1.81113794e+03 -1.83511963e+03 -1.84114966e+03 -1.85530261e+03 -1.87647778e+03 -1.89597461e+03 -1.90715674e+03 -1.91852148e+03 -1.93388416e+03 -1.94553503e+03 -1.96295447e+03 -1.97686548e+03 -1.98125012e+03 -1.99791284e+03 -2.01234741e+03 -2.02106604e+03 -2.03305212e+03 -2.04472607e+03 -2.05230200e+03 -2.06793335e+03 -2.08129712e+03 -2.08786011e+03 -2.09696924e+03 -2.10335449e+03 -2.11656177e+03 -2.12512671e+03 -2.13001465e+03 -2.14123267e+03 -2.14840405e+03 -2.15740991e+03 -2.16500073e+03 -2.16722070e+03 -2.17627197e+03 -2.18460229e+03 -2.19033813e+03 -2.19234912e+03 -2.19604590e+03 -2.20652441e+03 -2.20617920e+03 -2.21622363e+03 -2.21615332e+03 -2.21671924e+03 -2.22622876e+03 -2.22640625e+03 -2.22459570e+03 -2.22933252e+03 -2.22850342e+03 -2.23557007e+03 -2.23603931e+03 -2.23257935e+03 -2.24069751e+03 -2.23542578e+03 -2.23004370e+03 -2.23476587e+03 -2.23918555e+03 -2.24283398e+03 -2.23740894e+03 -2.23436108e+03 -2.22377539e+03 -2.21867139e+03 -2.22884106e+03 -2.22731055e+03 -2.23791040e+03 -2.87056470e+03 -3.03513721e+03 -3.31324243e+03 -3.30754639e+03 -3.31146997e+03 -3.28107251e+03 -3.27101440e+03 -3.27812793e+03 -3.26690845e+03 -3.25416309e+03 -2.97126611e+03 -2.78773633e+03 -2.13943579e+03 -2.12980713e+03 -2.12336841e+03 -2.11796826e+03 -2.10468408e+03 -2.09631128e+03 -2.08759473e+03 -2.07371582e+03 -2.06956665e+03 -2.67721631e+03 -2.04451111e+03 -3.06770410e+03 -4.70054883e+03 -5.24385791e+03 78626312. 26853954. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -276179360. 145225200. -4.57853086e+04 -3.04418281e+05 1.77717703e+05 -26484924. -4.46698096e+03 -3.11018091e+03 -1.56411743e+03 -1.54201294e+03 -1.52184338e+03 -1.50167639e+03 -1.48102747e+03 -1.80527856e+03 -1.78649353e+03 -3.37867310e+03 -4.12410596e+03 4.11211219e+05 7.70348359e+04 8.40772656e+03 -9.01833500e+05 -5.75281250e+05 -3.76036750e+06 8.19045875e+05 3.00403650e+06 2.76606975e+06 9.05897562e+05 1.68298730e+04 -4.59950375e+05 -6.38205062e+05 -1.10392125e+05 -3.25888428e+03 -3.06891479e+03 -2.89282300e+03 2.54757850e+06 1.16044711e+05 -4.14282148e+04 -2.89089844e+05 -1.92614062e+05 -7.46513812e+05 8.68969438e+05 1.90919238e+06 1.22375550e+06 3.44573312e+05 9.17822461e+03 -1.23286641e+04 3.37621055e+04 -1470457. 1.49452314e+04 1.03502168e+04 -13612294. 109072912. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.13973955e+10 -4.13973955e+10 0. 0. 1756571136. 1756571136. 1756571136. 0. 0. 0. 0. 600903360. 8.76235062e+05 2.79726825e+06 -5.40771350e+06 51167944. 1.98555546e+10 1.98555546e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56744288. 56744288. 56744288. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 450898272. 450898272. 450898272. 0. 0. 2446779. -136878880. -136878880. -30320120. -7663983. -6.40101172e+04 4.72408789e+03 3.78954370e+03 2.32200195e+03 3.76435352e+03 4.76128125e+03 2427053. 299625088. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -72765856. 4.01671475e+06 6.18389893e+03 4.86306689e+03 3.03076465e+03 2.76123169e+03 2.64436523e+03 2.05276733e+03 2.06321289e+03 2.06868945e+03 2.07796436e+03 2.09319971e+03 2.10766699e+03 2.10740283e+03 2.12121826e+03 2.13366821e+03 2.14222241e+03 2.14546558e+03 2.15618823e+03 2.16911133e+03 2.17326782e+03 2.17791284e+03 2.18637012e+03 2.19821460e+03 2.20601270e+03 2.20237231e+03 2.20572266e+03 2.22048804e+03 2.22497534e+03 2.22597803e+03 2.23241406e+03 2.23400439e+03 2.23350732e+03 2.23838354e+03 2.24672241e+03 2.24346973e+03 2.24859399e+03 2.24746240e+03 2.24888647e+03 2.25003784e+03 2.25575928e+03 2.25235205e+03 2.25493188e+03 2.25530981e+03 2.25577246e+03 2.25173413e+03 2.25406958e+03 2.25235156e+03 2.24885352e+03 2.24235132e+03 2.24009790e+03 2.23907617e+03 2.24068018e+03 2.23580566e+03 2.22436768e+03 2.22317310e+03 2.21935059e+03 2.21626782e+03 2.21687695e+03 2.20537329e+03 2.19289355e+03 2.19259570e+03 2.18933691e+03 2.18177344e+03 2.18247656e+03 2.16396436e+03 2.15562842e+03 2.14713281e+03 2.14012622e+03 2.13821045e+03 2.12025073e+03 2.11456445e+03 2.10821753e+03 2.09191479e+03 2.08451416e+03 2.06940332e+03 2.06474487e+03 2.05227002e+03 2.03693787e+03 2.02637268e+03 2.01428528e+03 2.00049255e+03 1.98820166e+03 1.97638074e+03 1.96177893e+03 1.94586072e+03 1.93635437e+03 1.91947717e+03 1.90200488e+03 1.89184534e+03 1.87794385e+03 1.86134619e+03 1.84277856e+03 1.82493750e+03 1.81456763e+03 1.79608813e+03 1.77884912e+03 1.75943921e+03 1.74414160e+03 1.72775195e+03 1.70497339e+03 1.68929077e+03 1.67125891e+03 1.65472668e+03 1.63350195e+03 1.61264551e+03 1.59688818e+03 1.57420312e+03 1.55469299e+03 1.53777087e+03 1.51503284e+03 1.49422534e+03 1.47465222e+03 1.45254431e+03 1.43124353e+03 1.40965588e+03 1.38802039e+03 1.36632507e+03 1.34369470e+03 1.32039819e+03 1.29914758e+03 1.27737244e+03 1.25474512e+03 1.23052295e+03 1.20639954e+03 1.18344629e+03 1.16056873e+03 1.13621460e+03 1.11227917e+03 1.08899976e+03 1.06404138e+03 1.03871106e+03 1.01353235e+03 9.90484741e+02 9.65652588e+02 9.40092834e+02 9.14352234e+02 8.89621338e+02 8.64338745e+02 8.37936584e+02 8.12767212e+02 7.86377991e+02 7.60010498e+02 7.34529236e+02 7.08400269e+02 6.82044983e+02 6.55294434e+02 6.28736389e+02 6.02551270e+02 5.75544922e+02 5.49079834e+02 5.22115356e+02 4.95149261e+02 4.68058441e+02 4.40822845e+02 4.13754852e+02 3.86466125e+02 3.59385437e+02 3.31849091e+02 3.04392059e+02 2.77069061e+02 2.49524078e+02 2.22033463e+02 1.94567032e+02 1.66944260e+02 1.39268890e+02 1.11688690e+02 8.40302963e+01 5.63468513e+01 2.87197456e+01 1.05561173e+00 -2.66048946e+01 -5.43227844e+01 -8.20461884e+01 -1.09689346e+02 -1.37268997e+02 -1.64871628e+02 -1.92473831e+02 -2.19974442e+02 -2.47495270e+02 -2.74981384e+02 -3.02441406e+02 -3.29856720e+02 -3.57230499e+02 -3.84470642e+02 -4.11827911e+02 -4.39025970e+02 -4.65894379e+02 -4.93428802e+02 -5.20839722e+02 -5.47897339e+02 -5.73825256e+02 -5.99852722e+02 -6.26727112e+02 -6.53575012e+02 -6.80363342e+02 -7.06521423e+02 -7.33027222e+02 -7.58217224e+02 -7.83962158e+02 -1.02821460e+03 -1.09644421e+03 -1.25362769e+03 -1.20210388e+03 -1.21436694e+03 -1.30892969e+03 -1.43911694e+03 -1.47677002e+03 -1.33160376e+03 -1.57982043e+03 -1.29331848e+03 -1.63067810e+03 -1.66798389e+03 -1.42305029e+03 -1.44477698e+03 -1.18234998e+03 -1.20451160e+03 -1.22878088e+03 -1.25143811e+03 -1.68284460e+03 -1.82951367e+03 -1.97349329e+03 -2.00780371e+03 -2.03841821e+03 -1.83943274e+03 -1.78067639e+03 -1.42888574e+03 -1.44913440e+03 -1.47350452e+03 -1.49354297e+03 -1.51162268e+03 -1.53414136e+03 -1.55695776e+03 -1.57411572e+03 -1.59192651e+03 -1.61209937e+03 -1.63319922e+03 -1.64888733e+03 -1.67046973e+03 -1.69116052e+03 -1.70961780e+03 -1.72437842e+03 -1.74008374e+03 -1.76426758e+03 -1.78041370e+03 -1.79214307e+03 -1.80659253e+03 -1.82409778e+03 -1.84669153e+03 -1.85849573e+03 -1.86879468e+03 -1.88923877e+03 -1.90867004e+03 -1.92070312e+03 -1.93522302e+03 -1.94553284e+03 -1.95849146e+03 -1.97890454e+03 -1.99106958e+03 -1.99558313e+03 -2.01635925e+03 -2.02934448e+03 -2.03680115e+03 -2.05294141e+03 -2.06058594e+03 -2.06945996e+03 -2.08330127e+03 -2.09597461e+03 -2.10210181e+03 -2.10533057e+03 -2.12071387e+03 -2.13567578e+03 -2.14046118e+03 -2.14381982e+03 -2.15605859e+03 -2.17116772e+03 -2.17173901e+03 -2.17923462e+03 -2.18773242e+03 -2.19859399e+03 -2.20483032e+03 -2.20518262e+03 -2.20875513e+03 -2.21601685e+03 -2.22302393e+03 -2.22751294e+03 -2.23423389e+03 -2.23548364e+03 -2.23470166e+03 -2.24107544e+03 -2.24566309e+03 -2.24929175e+03 -2.24418115e+03 -2.24880371e+03 -2.25054248e+03 -2.25553125e+03 -2.26013330e+03 -2.25452271e+03 -2.25242383e+03 -2.25504761e+03 -2.25016431e+03 -2.24824585e+03 -2.25319360e+03 -2.25596533e+03 -2.25100830e+03 -2.24182739e+03 -2.24108643e+03 -2.23892505e+03 -2.24471802e+03 -2.23430713e+03 -2.22431006e+03 -2.22164429e+03 -2.22137817e+03 -2.21929932e+03 -2.21638452e+03 -2.20081714e+03 -2.19476709e+03 -2.19793213e+03 -2.18702319e+03 -2.18490576e+03 -2.17723364e+03 -2.15893506e+03 -2.15663794e+03 -2.14893921e+03 -2.13974658e+03 -2.13489526e+03 -2.11925391e+03 -2.11758350e+03 -2.10473999e+03 -2.08973267e+03 -2.08884985e+03 -2.07184058e+03 -2.06207471e+03 -2.05377417e+03 -2.03921777e+03 -2.02741760e+03 -2.01373950e+03 -2.00109119e+03 -1.98833386e+03 -1.97622620e+03 -1.96307971e+03 -1.94575537e+03 -1.93901575e+03 -1.92162268e+03 -1.89883899e+03 -1.89221912e+03 -1.87842029e+03 -1.85868384e+03 -1.84281909e+03 -1.82544092e+03 -1.81533569e+03 -1.79500806e+03 -1.78014038e+03 -1.75997827e+03 -1.74142432e+03 -1.72875916e+03 -1.70469836e+03 -1.68957983e+03 -1.67274280e+03 -1.65612976e+03 -1.63341199e+03 -1.61227002e+03 -1.59648193e+03 -1.57447644e+03 -1.55603748e+03 -1.53744946e+03 -1.51467346e+03 -1.49267969e+03 -1.47307959e+03 -1.45244043e+03 -1.42984741e+03 -1.40924622e+03 -1.38745667e+03 -1.36610669e+03 -1.34399329e+03 -1.32131140e+03 -1.29958740e+03 -1.27631738e+03 -1.25398743e+03 -1.23087939e+03 -1.20690735e+03 -1.18362073e+03 -1.16040479e+03 -1.13645789e+03 -1.11166895e+03 -1.08839880e+03 -1.06390051e+03 -1.03868726e+03 -1.01333978e+03 -9.88946655e+02 -9.65108459e+02 -9.39875854e+02 -9.14574402e+02 -8.89677734e+02 -8.63849792e+02 -8.37842041e+02 -8.12578125e+02 -7.86209534e+02 -7.60401489e+02 -7.34564453e+02 -7.08237915e+02 -6.82003174e+02 -6.54918274e+02 -6.28557495e+02 -6.02426392e+02 -5.75703918e+02 -5.48826233e+02 -5.21716125e+02 -4.95154327e+02 -4.68063568e+02 -4.40624390e+02 -4.13639038e+02 -3.86362854e+02 -3.59212555e+02 -3.31843384e+02 -3.04244019e+02 -2.76980682e+02 -2.49437988e+02 -2.21747910e+02 -1.94362381e+02 -1.67077820e+02 -1.39392365e+02 -1.11553375e+02 -8.40102768e+01 -5.63657646e+01 -2.86529655e+01 -1.06707489e+00 2.66342659e+01 5.43290367e+01 8.19292145e+01 1.09668945e+02 1.37294983e+02 1.64803024e+02 1.92460266e+02 2.20038788e+02 2.47513321e+02 2.74950928e+02 3.02509216e+02 3.29926910e+02 3.56997253e+02 3.84341003e+02 4.11786957e+02 4.38767303e+02 4.65877106e+02 4.93174896e+02 5.19837524e+02 5.46739380e+02 5.73751587e+02 6.00487793e+02 6.27107483e+02 6.53555969e+02 6.79794617e+02 7.06134766e+02 7.32549866e+02 7.58667175e+02 7.84214294e+02 8.10452881e+02 8.36663086e+02 8.62339355e+02 8.86650391e+02 9.11560974e+02 9.38439514e+02 9.63662048e+02 9.87375916e+02 1.01257739e+03 1.03751733e+03 1.06270557e+03 1.08748657e+03 1.10937524e+03 1.13322607e+03 1.16014758e+03 1.18324792e+03 1.20457947e+03 1.22731250e+03 1.25081250e+03 1.27517432e+03 1.29882007e+03 1.32086157e+03 1.34146338e+03 1.36386377e+03 1.38545142e+03 1.40789880e+03 1.42953870e+03 1.45004883e+03 1.47254919e+03 1.49380139e+03 1.51277942e+03 1.53321948e+03 1.55503357e+03 1.57306934e+03 1.59254919e+03 1.61544092e+03 1.63246326e+03 1.65004297e+03 1.66923962e+03 1.68871667e+03 1.70692920e+03 1.72491345e+03 1.74256543e+03 1.76494214e+03 1.78021277e+03 1.79153198e+03 1.80649597e+03 1.82299097e+03 1.84598071e+03 1.86139905e+03 1.86985815e+03 1.88573132e+03 1.90563953e+03 1.91958643e+03 1.93210242e+03 1.94440039e+03 1.95692163e+03 1.97678931e+03 1.99102551e+03 1.99606799e+03 2.01262195e+03 2.02842493e+03 2.03552551e+03 2.04966870e+03 2.06424902e+03 2.06997388e+03 2.08176392e+03 2.09645117e+03 2.09868604e+03 2.10714795e+03 2.12209668e+03 2.13172803e+03 2.14344873e+03 2.14347705e+03 2.15750757e+03 2.16665356e+03 2.17044263e+03 2.18292822e+03 2.18615747e+03 2.19380786e+03 2.20500830e+03 2.20621387e+03 2.20644458e+03 2.21468555e+03 2.22068115e+03 2.22608423e+03 2.23272217e+03 2.23725146e+03 2.23802417e+03 2.24653955e+03 2.24771973e+03 2.24305884e+03 2.24636914e+03 2.24811157e+03 2.25195093e+03 2.25141943e+03 2.25902588e+03 2.25066821e+03 2.24985620e+03 2.26094189e+03 2.24944067e+03 2.24631738e+03 2.25500146e+03 2.25634937e+03 2.25374438e+03 2.24251562e+03 2.23739307e+03 2.24560156e+03 2.24487598e+03 2.23906641e+03 2.22842700e+03 2.21837524e+03 2.22188379e+03 2.22332056e+03 2.21888257e+03 2.19923877e+03 2.19198340e+03 2.19714526e+03 2.18804199e+03 2.17900415e+03 2.18167041e+03 2.16363550e+03 2.15297534e+03 2.14772144e+03 2.13922632e+03 2.13379883e+03 2.11823096e+03 2.11880029e+03 2.10506348e+03 2.08958691e+03 2.08390112e+03 2.06957935e+03 2.06088428e+03 2.05196216e+03 2.03767871e+03 2.02848560e+03 2.01252026e+03 2.00218506e+03 1.99056311e+03 1.97673596e+03 1.96394128e+03 1.94680725e+03 1.93621289e+03 1.92445435e+03 1.90192126e+03 1.89328870e+03 1.87935925e+03 1.85869434e+03 1.84278027e+03 1.82473901e+03 1.81708569e+03 1.79564148e+03 1.77635400e+03 1.75999731e+03 1.74193701e+03 1.72798206e+03 1.70585901e+03 1.68767493e+03 1.67138000e+03 1.65542419e+03 1.63273804e+03 1.61215173e+03 1.59655090e+03 1.57360229e+03 1.55563025e+03 1.53655151e+03 1.51336169e+03 1.49358215e+03 1.47483130e+03 1.45116406e+03 1.42917773e+03 1.40895996e+03 1.38327673e+03 1.76591406e+03 1.80404199e+03 1.96530945e+03 1.93458057e+03 1.90183850e+03 1.72654126e+03 1.60538184e+03 1.20764746e+03 1.18405017e+03 1.15920349e+03 1.13585071e+03 1.11141809e+03 1.08830835e+03 1.06544482e+03 1.03891199e+03 1.30100928e+03 9.98020203e+02 1.43608618e+03 1.18461267e+03 1.26836243e+03 1.16770093e+03 8.63487122e+02 8.37172119e+02 8.13368103e+02 9.63802429e+02 7.60670715e+02 9.09217712e+02 7.08324585e+02 6.82309387e+02 6.55343140e+02 6.25372681e+02 6.00564514e+02 5.78740173e+02 5.50650757e+02 5.22537354e+02 4.95409058e+02 4.68469940e+02 4.41138855e+02 4.13818268e+02 3.86563660e+02 3.59296051e+02 3.31853485e+02 3.04436768e+02 2.77022614e+02 2.49534164e+02 2.22101318e+02 1.94515015e+02 1.66912170e+02 1.39301071e+02 1.11671913e+02 8.40239487e+01 5.63553581e+01 2.86972694e+01 9.87595320e-01 -2.66867981e+01 -5.43444519e+01 -8.20078430e+01 -1.09634491e+02 -1.37252518e+02 -1.64847656e+02 -1.92470642e+02 -2.20009918e+02 -2.47522964e+02 -2.75010132e+02 -3.02425751e+02 -3.29872437e+02 -3.57227783e+02 -3.84441559e+02 -4.11721741e+02 -4.38806488e+02 -4.65779297e+02 -4.93094971e+02 -5.20050049e+02 -5.46825500e+02 -5.73792969e+02 -6.00455627e+02 -6.27117554e+02 -6.53913513e+02 -6.79869385e+02 -7.06240051e+02 -7.32972229e+02 -7.58713013e+02 -7.84417419e+02 -8.10320251e+02 -8.36596863e+02 -8.62550354e+02 -8.86949280e+02 -9.12527527e+02 -9.38835693e+02 -9.63605530e+02 -9.87773682e+02 -1.01169128e+03 -1.03796826e+03 -1.06262732e+03 -1.08708118e+03 -1.10996472e+03 -1.13339575e+03 -1.16003625e+03 -1.18342798e+03 -1.20446326e+03 -1.22650891e+03 -1.25137231e+03 -1.27523096e+03 -1.29855579e+03 -1.32101294e+03 -1.34235510e+03 -1.36446765e+03 -1.38579626e+03 -1.40778284e+03 -1.42923840e+03 -1.44986487e+03 -1.47291370e+03 -1.49324670e+03 -1.51264307e+03 -1.53233691e+03 -1.55570959e+03 -1.57391858e+03 -1.59171814e+03 -1.61439282e+03 -1.63275378e+03 -1.64864978e+03 -1.66947766e+03 -1.69148169e+03 -1.70913208e+03 -1.72483191e+03 -1.73991638e+03 -1.76377112e+03 -1.77982947e+03 -1.79307690e+03 -1.80619409e+03 -1.82363062e+03 -1.84579382e+03 -1.85759375e+03 -1.86980383e+03 -1.88970789e+03 -1.90754980e+03 -1.92132397e+03 -1.93485449e+03 -1.94491504e+03 -1.95818054e+03 -1.97701990e+03 -1.99106653e+03 -1.99621753e+03 -2.01576038e+03 -2.02980066e+03 -2.03558142e+03 -2.05056348e+03 -2.06071338e+03 -2.06781177e+03 -2.08021655e+03 -2.09796875e+03 -2.10245801e+03 -2.10768530e+03 -2.12153003e+03 -2.13832715e+03 -2.14261890e+03 -2.14320483e+03 -2.15562085e+03 -2.17008301e+03 -2.17304053e+03 -2.18087573e+03 -2.18752075e+03 -2.19600854e+03 -2.20326123e+03 -2.19933252e+03 -2.20658276e+03 -2.21427856e+03 -2.22349585e+03 -2.22657642e+03 -2.22967676e+03 -2.23663965e+03 -2.23415479e+03 -2.24295630e+03 -2.24608423e+03 -2.24379541e+03 -2.24738647e+03 -2.24932129e+03 -2.25148633e+03 -2.25137622e+03 -2.25903296e+03 -2.25498584e+03 -2.25222852e+03 -2.25599634e+03 -2.25281982e+03 -2.24951440e+03 -2.25912549e+03 -2.25828613e+03 -2.25065625e+03 -2.24036377e+03 -2.23736108e+03 -2.24274243e+03 -2.24618188e+03 -2.23817310e+03 -2.22518701e+03 -2.21917773e+03 -2.22299463e+03 -2.22226221e+03 -2.21961523e+03 -2.20166626e+03 -2.19610278e+03 -2.19758325e+03 -2.18886328e+03 -2.18070996e+03 -2.17607520e+03 -2.16061523e+03 -2.15522217e+03 -2.14681055e+03 -2.13979834e+03 -2.13652563e+03 -2.12161084e+03 -2.11711719e+03 -2.10406470e+03 -2.09254468e+03 -2.08730737e+03 -2.06836011e+03 -2.05809595e+03 -2.04752979e+03 -2.65432300e+03 -2.74274390e+03 -4.68492041e+03 -5.68373877e+03 -3.77649750e+06 47587496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 39352692. 39352692. 39352692. 0. 0. 1616350208. -6.36276709e+03 -1.58056580e+03 -1.55615637e+03 -1.97015747e+03 -2.03089221e+03 -2.03868616e+03 -3.48094214e+03 -2.80388403e+03 3.13707650e+06 3.33217625e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -38021184. -38021184. -38021184. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1756571136. 1756571136. 1756571136. 0. 0. 0. 0. 600903360. 8.76235062e+05 2.79726825e+06 -5.40771350e+06 898915648. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56842832. -9061306. 4.23295820e+04 -4.08843450e+06 -7.87497950e+06 9165844. -6.03958312e+05 24072544. -4.96676594e+05 -5.74153047e+04 15365739. -32527410. -228333616. -228333616. 0. 0. 0. 0. 0. 0. 0. 450898272. 450898272. 450898272. 0. 0. 2446779. -136878880. -136878880. -30320120. -7663983. -6.40101172e+04 -1.15830867e+05 -1.28067775e+06 -2.85391125e+05 13485562. -46676344. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -11337912. 1.21159980e+04 2.80575415e+03 2.65775391e+03 2.03449512e+03 2.05041724e+03 2.05819360e+03 2.07419214e+03 2.08499658e+03 2.09019238e+03 2.10329834e+03 2.11855688e+03 2.12850391e+03 2.13350464e+03 2.14749146e+03 2.79798804e+03 2.94684497e+03 2.95989844e+03 2.81639038e+03 2.18991772e+03 2.19880151e+03 2.20438550e+03 2.20878442e+03 2.21974243e+03 2.23096460e+03 2.22863550e+03 2.22920190e+03 2.24078320e+03 2.24901978e+03 2.25361182e+03 2.25425854e+03 2.25462085e+03 2.26360083e+03 2.26696216e+03 2.26761816e+03 2.27183472e+03 2.27073901e+03 2.93896558e+03 3.08434497e+03 3.39336621e+03 3.39522949e+03 3.39810107e+03 3.13435303e+03 2.96584741e+03 2.27658252e+03 2.28088452e+03 2.27817285e+03 2.27449023e+03 2.26928369e+03 2.27410327e+03 2.27135620e+03 2.27015796e+03 2.26200830e+03 2.25729492e+03 2.25487427e+03 2.24991626e+03 2.24303442e+03 2.24359204e+03 2.24599243e+03 2.23189014e+03 2.22027832e+03 2.22045239e+03 2.20879272e+03 2.21003687e+03 2.20279150e+03 2.18848901e+03 2.18220410e+03 2.17035791e+03 2.16210352e+03 2.16005762e+03 2.14775122e+03 2.14344727e+03 2.13194556e+03 2.11779395e+03 2.10713257e+03 2.09378979e+03 2.08288696e+03 2.07513110e+03 2.06500244e+03 2.04571240e+03 2.03737769e+03 2.02695959e+03 2.01193506e+03 2.00302930e+03 1.98327026e+03 1.97129846e+03 1.96189722e+03 1.94215186e+03 1.92557361e+03 1.91227185e+03 1.90141638e+03 1.88252612e+03 1.86265601e+03 1.84831042e+03 1.83293250e+03 1.81780408e+03 1.80270410e+03 1.78046887e+03 1.76527417e+03 1.74728674e+03 1.72641028e+03 1.71103479e+03 1.69316589e+03 1.67461462e+03 1.65087415e+03 1.63069141e+03 1.61554028e+03 1.59531750e+03 1.57526111e+03 1.55636841e+03 1.53507056e+03 1.51050452e+03 1.49109155e+03 1.47260413e+03 1.44864062e+03 1.42812280e+03 1.40511060e+03 1.38256360e+03 1.36017859e+03 1.33732263e+03 1.31505493e+03 1.29438708e+03 1.27007166e+03 1.24524524e+03 1.22192090e+03 1.19815051e+03 1.17539758e+03 1.15036975e+03 1.12628394e+03 1.10287952e+03 1.07692773e+03 1.05235718e+03 1.02776135e+03 1.00293549e+03 9.77039917e+02 9.52467712e+02 9.27040405e+02 9.00931946e+02 8.75202393e+02 8.49175964e+02 8.23872681e+02 7.97044067e+02 7.70559143e+02 7.44327637e+02 7.18174194e+02 6.91393738e+02 6.64293884e+02 6.37857849e+02 6.11325867e+02 5.83602844e+02 5.56979187e+02 5.29622375e+02 5.02191528e+02 4.75148651e+02 4.47674988e+02 4.20066010e+02 3.92602478e+02 3.65242004e+02 3.37344177e+02 3.09659698e+02 2.82001129e+02 2.54099579e+02 2.26264175e+02 1.98483215e+02 1.70584122e+02 1.42621521e+02 1.14713509e+02 8.67010117e+01 5.87526245e+01 3.08539848e+01 2.80174899e+00 -2.52161312e+01 -5.31956673e+01 -8.12320633e+01 -1.09214188e+02 -1.37099838e+02 -1.64984329e+02 -1.92843155e+02 -2.20700546e+02 -2.48597672e+02 -2.76345856e+02 -3.04097687e+02 -3.31917938e+02 -3.59600433e+02 -3.87075287e+02 -4.14727081e+02 -4.42333740e+02 -4.69324341e+02 -4.96909088e+02 -5.24459351e+02 -5.51549255e+02 -5.78636475e+02 -6.05698120e+02 -6.32504456e+02 -6.59490479e+02 -6.86657654e+02 -7.13460632e+02 -7.39748474e+02 -7.65664734e+02 -7.91610107e+02 -8.18134888e+02 -8.44205750e+02 -8.70277954e+02 -8.96666992e+02 -1.13775122e+03 -1.17380457e+03 -1.45940320e+03 -1.49711963e+03 -1.25903003e+03 -1.59994189e+03 -1.39636084e+03 -2.80397363e+03 -3.73853809e+03 -3.74497534e+03 -2.93735962e+03 -1.77463879e+03 -1.63920435e+03 -1.59147668e+03 -1.26425415e+03 -1.59098523e+03 -1.62672498e+03 -2.00244141e+03 -2.03863037e+03 -2.06742383e+03 -1.72314966e+03 -1.74530945e+03 -1.44485107e+03 -1.92565894e+03 -2.03558191e+03 -2.24620654e+03 -2.27089624e+03 -2.30388403e+03 -2.33920898e+03 -2.36811328e+03 -2.39210767e+03 -2.42212817e+03 -2.20117334e+03 -2.13715845e+03 -1.68582263e+03 -1.70852795e+03 -1.72663330e+03 -1.74164038e+03 -1.76048120e+03 -1.78019727e+03 -1.79704529e+03 -1.81088940e+03 -1.82503125e+03 -1.84418860e+03 -1.86465881e+03 -1.87798303e+03 -1.89072424e+03 -1.90888391e+03 -1.92331091e+03 -1.93632983e+03 -1.95215125e+03 -1.96750842e+03 -1.97592969e+03 -1.99995984e+03 -2.01310608e+03 -2.01939368e+03 -2.03851831e+03 -2.05058423e+03 -2.05843677e+03 -2.07609497e+03 -2.08549023e+03 -2.08840552e+03 -2.10429248e+03 -2.11942383e+03 -2.12531616e+03 -2.12935278e+03 -2.14508252e+03 -2.15603662e+03 -2.16430884e+03 -2.16752637e+03 -2.17969385e+03 -2.19183032e+03 -2.19931323e+03 -2.20176147e+03 -2.21177905e+03 -2.22134082e+03 -2.22932080e+03 -2.22878760e+03 -2.23292749e+03 -2.24278979e+03 -2.24699268e+03 -2.25399414e+03 -2.25679736e+03 -2.26106274e+03 -2.26410596e+03 -2.26534009e+03 -2.27090088e+03 -2.27398486e+03 -2.27643774e+03 -2.27785205e+03 -2.27965649e+03 -2.28195825e+03 -2.28007349e+03 -2.27626172e+03 -2.28334033e+03 -2.27853760e+03 -2.28134009e+03 -2.27754736e+03 -2.27566357e+03 -2.27700952e+03 -2.27705273e+03 -2.27231055e+03 -2.26842456e+03 -2.26908765e+03 -2.26846021e+03 -2.26006519e+03 -2.25142529e+03 -2.24772070e+03 -2.24773608e+03 -2.24572778e+03 -2.24206030e+03 -2.22757104e+03 -2.21804053e+03 -2.22510303e+03 -2.21440112e+03 -2.21347437e+03 -2.19821240e+03 -2.18058423e+03 -2.18723950e+03 -2.17436279e+03 -2.15866187e+03 -2.15831006e+03 -2.14796729e+03 -2.14350171e+03 -2.12955884e+03 -2.11297949e+03 -2.10677759e+03 -2.09481909e+03 -2.08458960e+03 -2.07813379e+03 -2.06267432e+03 -2.04439661e+03 -2.03840894e+03 -2.02755237e+03 -2.00897107e+03 -2.00420703e+03 -1.98524805e+03 -1.97097754e+03 -1.96396802e+03 -1.94279883e+03 -1.92648279e+03 -1.91147058e+03 -1.89839819e+03 -1.88156592e+03 -1.86497681e+03 -1.84992676e+03 -1.83462878e+03 -1.81644348e+03 -1.80090771e+03 -1.78085596e+03 -1.76277246e+03 -1.74942139e+03 -1.72642822e+03 -1.70759644e+03 -1.69374011e+03 -1.67640662e+03 -1.65009277e+03 -1.63017371e+03 -1.61557739e+03 -1.59643591e+03 -1.57597302e+03 -1.55699939e+03 -1.53647217e+03 -1.50829236e+03 -1.48883093e+03 -1.47120117e+03 -1.44920703e+03 -1.42756885e+03 -1.40434412e+03 -1.38151624e+03 -1.35911487e+03 -1.33845410e+03 -1.31662085e+03 -1.29247351e+03 -1.27042212e+03 -1.24608105e+03 -1.22245081e+03 -1.19795959e+03 -1.17445203e+03 -1.15034509e+03 -1.12622888e+03 -1.10200293e+03 -1.07692517e+03 -1.05274133e+03 -1.02683765e+03 -1.00153528e+03 -9.76589966e+02 -9.52455139e+02 -9.27234009e+02 -9.00860779e+02 -8.74821472e+02 -8.49374207e+02 -8.23602356e+02 -7.96521240e+02 -7.70975525e+02 -7.44427734e+02 -7.17645752e+02 -6.91089233e+02 -6.63895264e+02 -6.37623596e+02 -6.11180298e+02 -5.83927490e+02 -5.56711060e+02 -5.29254822e+02 -5.02353180e+02 -4.75212799e+02 -4.47380402e+02 -4.19859283e+02 -3.92364685e+02 -3.64976471e+02 -3.37394165e+02 -3.09471558e+02 -2.81886261e+02 -2.54124847e+02 -2.25950562e+02 -1.98208328e+02 -1.70779922e+02 -1.42770416e+02 -1.14587982e+02 -8.67027740e+01 -5.87169991e+01 -3.07247372e+01 -2.84793687e+00 2.51216316e+01 5.31647530e+01 8.11038437e+01 1.09128799e+02 1.37101334e+02 1.64926071e+02 1.92845551e+02 2.20769775e+02 2.48573761e+02 2.76211029e+02 3.04103546e+02 3.32026733e+02 3.59316437e+02 3.86952820e+02 4.14694427e+02 4.42036102e+02 4.69476013e+02 4.96861877e+02 5.24016174e+02 5.51463135e+02 5.78694702e+02 6.05481079e+02 6.32156250e+02 6.59429993e+02 6.85809143e+02 7.12225281e+02 7.39033630e+02 7.65723816e+02 7.91474060e+02 8.18011841e+02 8.44378235e+02 8.70186829e+02 8.95346375e+02 9.20851562e+02 9.48030151e+02 9.73436218e+02 9.96062561e+02 1.02103534e+03 1.04832324e+03 1.07397034e+03 1.09712524e+03 1.12001697e+03 1.14516223e+03 1.17084851e+03 1.19518127e+03 1.21711121e+03 1.24074463e+03 1.26406189e+03 1.28687805e+03 1.31160889e+03 1.33515588e+03 1.35464172e+03 1.37865173e+03 1.40084546e+03 1.42209448e+03 1.44496960e+03 1.46619226e+03 1.48722778e+03 1.50880469e+03 1.52931042e+03 1.55096277e+03 1.56978967e+03 1.58894653e+03 1.60976257e+03 1.62975464e+03 1.64979773e+03 1.66888647e+03 1.68540442e+03 1.70657971e+03 1.72634753e+03 1.74523206e+03 1.76293884e+03 1.77869775e+03 1.79897363e+03 1.81161279e+03 1.82602686e+03 1.84582825e+03 1.86371594e+03 1.88010046e+03 1.89152808e+03 1.90881372e+03 1.92990625e+03 1.94421460e+03 1.94903821e+03 1.96387793e+03 1.98022729e+03 1.99681958e+03 2.00864575e+03 2.02310352e+03 2.03540552e+03 2.04448389e+03 2.05966064e+03 2.07647534e+03 2.09150635e+03 2.09152954e+03 2.09952856e+03 2.11898584e+03 2.12156079e+03 2.13382886e+03 2.14491992e+03 2.15025122e+03 2.16564600e+03 2.17058813e+03 2.18077368e+03 2.19323120e+03 2.19505640e+03 2.20643848e+03 2.21034058e+03 2.21571216e+03 2.22842358e+03 2.22747583e+03 2.23274438e+03 2.24335693e+03 2.24311475e+03 2.25508130e+03 2.25758057e+03 2.25370776e+03 2.26600684e+03 2.27289746e+03 2.26382642e+03 2.26952246e+03 2.27886230e+03 2.27670142e+03 2.27259033e+03 2.27659814e+03 2.28581201e+03 2.27453931e+03 2.27775317e+03 2.27653760e+03 2.27803296e+03 2.28000879e+03 2.27885181e+03 2.28314160e+03 2.27442358e+03 2.26756982e+03 2.26603589e+03 2.27382886e+03 2.26683398e+03 2.26640503e+03 2.25396167e+03 2.24899536e+03 2.24318970e+03 2.24581396e+03 2.24759912e+03 2.22522607e+03 2.21655737e+03 2.22272168e+03 2.21590063e+03 2.20845654e+03 2.20055542e+03 2.18436646e+03 2.18247290e+03 2.17185962e+03 2.16464209e+03 2.15965137e+03 2.14742407e+03 2.14589917e+03 2.13037720e+03 2.11090405e+03 2.10841528e+03 2.09379639e+03 2.08306421e+03 2.07784692e+03 2.06340430e+03 2.04963818e+03 2.03656226e+03 2.02648083e+03 2.01140552e+03 2.00200842e+03 1.98623535e+03 1.96891907e+03 1.96018982e+03 1.94551855e+03 1.92506506e+03 1.91353845e+03 1.89898108e+03 1.88138354e+03 1.86515283e+03 1.84770776e+03 1.83647534e+03 1.81472070e+03 1.79744470e+03 1.78092554e+03 1.76336316e+03 1.74687817e+03 1.72578845e+03 1.70802502e+03 1.69044922e+03 2.13695581e+03 2.19322290e+03 2.42883057e+03 2.40601489e+03 2.37619336e+03 2.34883691e+03 2.31889600e+03 2.28438110e+03 2.25236230e+03 2.22175342e+03 2.06270605e+03 1.89981506e+03 1.42650806e+03 1.40045447e+03 1.71728479e+03 1.70586304e+03 2.00875659e+03 1.97267932e+03 1.94075769e+03 1.55290613e+03 1.52083350e+03 1.54910217e+03 1.57886218e+03 1.75014343e+03 1.62452185e+03 1.67443359e+03 1.44384253e+03 1.54047778e+03 1.40005981e+03 1.27809277e+03 9.92879272e+02 1.46537134e+03 1.24672205e+03 1.13150745e+03 1.09879944e+03 8.76022888e+02 8.47703735e+02 8.23891296e+02 1.08313806e+03 7.70287415e+02 9.32697571e+02 7.18206665e+02 6.92044800e+02 6.64707764e+02 6.38187134e+02 6.11411011e+02 5.83813965e+02 5.56862061e+02 5.29738708e+02 5.02326385e+02 4.75092010e+02 4.47551086e+02 4.20068451e+02 3.92667267e+02 3.65096222e+02 3.37308929e+02 3.09661194e+02 2.81988922e+02 2.54103333e+02 2.26340866e+02 1.98480469e+02 1.70543182e+02 1.42622604e+02 1.14680595e+02 8.67386932e+01 5.87598419e+01 3.07630157e+01 2.76512384e+00 -2.52137661e+01 -5.31556168e+01 -8.11101913e+01 -1.09087189e+02 -1.37061264e+02 -1.64948471e+02 -1.92815155e+02 -2.20746323e+02 -2.48585495e+02 -2.76305603e+02 -3.04040192e+02 -3.31891144e+02 -3.59538147e+02 -3.86993896e+02 -4.14639709e+02 -4.42052948e+02 -4.69369324e+02 -4.97022186e+02 -5.24112610e+02 -5.51193787e+02 -5.78785767e+02 -6.05685486e+02 -6.32548340e+02 -6.59250793e+02 -6.85648621e+02 -7.12773254e+02 -7.39820923e+02 -7.65986633e+02 -7.91405090e+02 -8.17622803e+02 -8.44264465e+02 -8.70169800e+02 -8.95845215e+02 -9.21841003e+02 -9.48132446e+02 -9.73145264e+02 -9.96687317e+02 -1.02100116e+03 -1.04813281e+03 -1.07404016e+03 -1.09788855e+03 -1.12076465e+03 -1.14495959e+03 -1.17031409e+03 -1.19484570e+03 -1.21780505e+03 -1.23952124e+03 -1.26384265e+03 -1.28771094e+03 -1.31164795e+03 -1.33430322e+03 -1.35591455e+03 -1.37908643e+03 -1.40023792e+03 -1.42090320e+03 -1.44557935e+03 -1.46800098e+03 -1.48715723e+03 -1.51027917e+03 -1.52802649e+03 -1.54962622e+03 -1.57127258e+03 -1.59094299e+03 -1.61003027e+03 -1.62853064e+03 -1.64879810e+03 -1.66717358e+03 -1.68688171e+03 -1.70808777e+03 -1.72712622e+03 -1.74506836e+03 -1.76104565e+03 -1.77929639e+03 -1.79922107e+03 -1.81320483e+03 -1.82770105e+03 -1.84489197e+03 -1.86353845e+03 -1.87928931e+03 -1.89238318e+03 -1.90989624e+03 -1.92875879e+03 -1.94304431e+03 -1.95432800e+03 -1.96807715e+03 -1.98245349e+03 -1.99469348e+03 -2.01056958e+03 -2.02250842e+03 -2.03783948e+03 -2.05041064e+03 -2.05727734e+03 -2.07434985e+03 -2.08370117e+03 -2.09237231e+03 -2.10052930e+03 -2.11733984e+03 -2.12781934e+03 -2.13079077e+03 -2.14569604e+03 -2.16032788e+03 -2.16598926e+03 -2.16469189e+03 -2.17835742e+03 -2.19928979e+03 -2.20014478e+03 -2.19907275e+03 -2.20956152e+03 -2.22507544e+03 -2.22548291e+03 -2.22313403e+03 -2.23099146e+03 -2.23998438e+03 -2.24978296e+03 -2.24645850e+03 -2.25519165e+03 -2.25931396e+03 -2.25895190e+03 -2.26826733e+03 -2.27216040e+03 -2.26889893e+03 -2.27684180e+03 -2.27389600e+03 -2.27066992e+03 -2.27030737e+03 -2.94222852e+03 -3.04927588e+03 -3.39635522e+03 -3.39490405e+03 -3.12686841e+03 -2.95631421e+03 -2.28219629e+03 -2.28237012e+03 -2.27427173e+03 -2.26721143e+03 -2.26530005e+03 -2.26847900e+03 -2.26784839e+03 -2.26515283e+03 -2.25479321e+03 -2.24458984e+03 -2.24174463e+03 -2.24485986e+03 -2.24242163e+03 -2.22846826e+03 -2.22391626e+03 -2.22135083e+03 -2.21445459e+03 -2.21064795e+03 -2.81625000e+03 -2.17763843e+03 -2.84388794e+03 -2.17678394e+03 -2.16720044e+03 -2.16428882e+03 -2.15000195e+03 -2.14124780e+03 -2.12857739e+03 -2.11423975e+03 -2.10646558e+03 -2.09794458e+03 -2.08562939e+03 -2.07347729e+03 -2.05931323e+03 -2.04266675e+03 -2.59416113e+03 -3.63737305e+03 -2.59005332e+04 47587496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 39352692. 39352692. 39352692. 0. 0. 121625240. -9.71063184e+03 -2.41228271e+03 -2.35248389e+03 -3.55202197e+03 -4.20363379e+03 -4.69745703e+03 -4.41428418e+03 -4.17922949e+03 3.13707650e+06 3.33217625e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -5.96269466e+09 -5.96269466e+09 -5.96269466e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1756571136. 1756571136. 1756571136. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 97407352. 97407352. 97407352. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56842832. -9061306. 4.23295820e+04 -4.08843450e+06 -7.87497950e+06 9165844. -6.03958312e+05 24072544. 2.56564624e+03 3.05400781e+03 1.32874258e+04 2.63230078e+03 1.26457705e+04 1.26457705e+04 4599262. -15852164. -15852164. 15629822. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -11337912. 1.21159980e+04 3.02888843e+03 3.04899048e+03 3.06744287e+03 2.82742920e+03 2.69296021e+03 2.10181567e+03 2.11570459e+03 2.12260132e+03 2.13529150e+03 2.14979224e+03 2.80374854e+03 2.97521606e+03 3.23117651e+03 5.22584570e+03 6.59361768e+03 6.37274365e+03 5.16440771e+03 3.30160327e+03 3.31327466e+03 3.31691406e+03 3.32894556e+03 3.34469751e+03 3.35309863e+03 3.36039722e+03 3.09372827e+03 2.94652588e+03 2.28179590e+03 2.28467456e+03 2.29101514e+03 2.28572412e+03 2.29327124e+03 2.29488379e+03 2.97592358e+03 3.13639209e+03 3.42534302e+03 5.49523828e+03 6.84105176e+03 1.75894938e+06 -336485280. -4060228. 6.84614062e+03 5.49850098e+03 3.43789746e+03 3.43031201e+03 3.43616040e+03 3.43170630e+03 3.41540479e+03 3.42161523e+03 3.42471094e+03 3.16403369e+03 2.98130054e+03 2.29052075e+03 2.28847021e+03 2.27723560e+03 2.27539062e+03 2.27258228e+03 2.27160352e+03 2.26473022e+03 2.25376758e+03 2.24921460e+03 2.23687964e+03 2.23711963e+03 2.23563965e+03 2.22206348e+03 2.21318311e+03 2.19948804e+03 2.18852539e+03 2.18635278e+03 2.18029663e+03 2.17553931e+03 2.16260913e+03 2.14639038e+03 2.13225830e+03 2.12413940e+03 2.11531616e+03 2.10268311e+03 2.08981055e+03 2.07269824e+03 2.06139966e+03 2.05268433e+03 2.04070801e+03 2.02738647e+03 2.01043188e+03 1.99387012e+03 1.98283008e+03 1.96699365e+03 1.95171814e+03 1.93424585e+03 1.92498950e+03 1.90955579e+03 1.88785864e+03 1.87259180e+03 1.85724646e+03 1.84089539e+03 1.82477051e+03 1.80035779e+03 1.78562170e+03 1.76909058e+03 1.74661218e+03 1.73079639e+03 1.71397400e+03 1.69494531e+03 1.67041260e+03 1.64909387e+03 1.63457642e+03 1.61555725e+03 1.59162415e+03 1.57235352e+03 1.55362378e+03 1.52880212e+03 1.51000183e+03 1.48859412e+03 1.46481787e+03 1.44463635e+03 1.42095068e+03 1.39819116e+03 1.37510547e+03 1.35167346e+03 1.33037476e+03 1.30800146e+03 1.28320581e+03 1.25899194e+03 1.23559753e+03 1.21211169e+03 1.18694226e+03 1.16284045e+03 1.13820337e+03 1.11376648e+03 1.08849292e+03 1.06271851e+03 1.03775732e+03 1.01254419e+03 9.86213379e+02 9.61242859e+02 9.35425659e+02 9.08963318e+02 8.82943970e+02 8.56809204e+02 8.30770874e+02 8.03475037e+02 7.76789856e+02 7.50133240e+02 7.23392395e+02 6.96518250e+02 6.68980530e+02 6.42041260e+02 6.15030762e+02 5.87195923e+02 5.59843689e+02 5.32297363e+02 5.04704193e+02 4.76932648e+02 4.48901642e+02 4.21073944e+02 3.93379852e+02 3.65338135e+02 3.37156281e+02 3.09116943e+02 2.81042450e+02 2.52805389e+02 2.24556137e+02 1.96363571e+02 1.68067596e+02 1.39708923e+02 1.11372528e+02 8.29497147e+01 5.45820084e+01 2.63122940e+01 -2.08592868e+00 -3.05075073e+01 -5.88745422e+01 -8.72792587e+01 -1.15685127e+02 -1.43969177e+02 -1.72208542e+02 -2.00429276e+02 -2.28700027e+02 -2.57060486e+02 -2.85107239e+02 -3.13202179e+02 -3.41504700e+02 -3.69550232e+02 -3.97460602e+02 -4.25436768e+02 -4.53181915e+02 -4.80830048e+02 -5.08717041e+02 -5.36668884e+02 -5.64103943e+02 -5.91601990e+02 -6.19042725e+02 -6.45737000e+02 -6.73117676e+02 -7.00785706e+02 -7.27426331e+02 -7.54020935e+02 -7.81434875e+02 -8.08025757e+02 -8.34352600e+02 -8.61532104e+02 -8.88296387e+02 -9.14743164e+02 -1.17742969e+03 -1.25101550e+03 -1.49992896e+03 -1.54460852e+03 -1.53399866e+03 -1.44704138e+03 -1.09212183e+03 -1.37560120e+03 -1.41204944e+03 -1.75097070e+03 -1.78767004e+03 -1.82371094e+03 -1.52685095e+03 -1.55098743e+03 -1.68938684e+03 -2.35516528e+03 -3.59785645e+03 -2709321. 4.09013550e+06 -1.33954062e+06 -4.64328271e+03 -3.70280518e+03 -2.22649438e+03 -3.67737793e+03 -4.43357715e+03 1.56695531e+05 5.75551050e+06 12527755. -3.47561925e+06 -2.42373375e+06 16720325. -4.62836035e+03 -3.72385522e+03 -2.54519604e+03 -2.53815625e+03 -2.17362891e+03 -2.60075000e+03 -2.26023535e+03 -2.65293042e+03 -2.68594214e+03 -2.70790918e+03 -2.72998169e+03 -2.32376904e+03 -2.31800122e+03 -2.38297412e+03 -1.89602466e+03 -2.86022021e+03 -1.94066980e+03 -2.45837915e+03 -1.95394336e+03 -1.97615564e+03 -2.00656458e+03 -1.99923120e+03 -2.01892859e+03 -2.03690369e+03 -2.04030066e+03 -2.05844629e+03 -2.07152148e+03 -2.07950000e+03 -2.09809717e+03 -2.10570093e+03 -2.11598291e+03 -2.12812012e+03 -2.74025684e+03 -2.17894800e+03 -2.65416821e+03 -2.92489551e+03 -2.79476831e+03 -3.26603979e+03 -3.26926392e+03 -3.28299805e+03 -3.29802490e+03 -3.31260010e+03 -3.32270898e+03 -3.33104297e+03 -3.34768018e+03 -3.35659985e+03 -3.35998120e+03 -3.35956079e+03 -3.38405444e+03 -3.38229517e+03 -3.38813257e+03 -3.40848779e+03 -3.39974951e+03 -3.40754834e+03 -3.41398389e+03 -3.41937402e+03 -3.14574707e+03 -2.98730225e+03 -2.30897705e+03 -2.31121240e+03 -2.31171509e+03 -2.31446240e+03 -2.30915796e+03 -2.31560767e+03 -2.31336499e+03 -2.31334399e+03 -2.30625122e+03 -2.30878076e+03 -2.30813135e+03 -2.30486499e+03 -2.30382324e+03 -2.30315869e+03 -2.30123779e+03 -2.29363940e+03 -2.28984009e+03 -2.28669580e+03 -2.28104810e+03 -2.27448511e+03 -2.27229297e+03 -2.27266235e+03 -2.26106689e+03 -2.25188257e+03 -2.25172290e+03 -2.24691333e+03 -2.23974878e+03 -2.22346069e+03 -2.21849561e+03 -2.21683789e+03 -2.19932739e+03 -2.18933057e+03 -2.18450659e+03 -2.17907788e+03 -2.16996631e+03 -2.15924878e+03 -2.14513330e+03 -2.12946606e+03 -2.12167114e+03 -2.11547192e+03 -2.10316821e+03 -2.09010132e+03 -2.07259155e+03 -2.06010278e+03 -2.05300098e+03 -2.04086548e+03 -2.02682483e+03 -2.01131970e+03 -1.99813135e+03 -1.98283862e+03 -1.96764453e+03 -1.95256873e+03 -1.93342676e+03 -1.92199841e+03 -1.90828162e+03 -1.89017346e+03 -1.87348877e+03 -1.85598315e+03 -1.83902722e+03 -1.82253003e+03 -1.80083630e+03 -1.78426941e+03 -1.77050391e+03 -1.74738965e+03 -1.72870300e+03 -1.71555798e+03 -1.69514197e+03 -1.66969836e+03 -1.64881824e+03 -1.63453027e+03 -1.61713916e+03 -1.59168445e+03 -1.57158984e+03 -1.55389526e+03 -1.52702075e+03 -1.50787073e+03 -1.48716309e+03 -1.46407300e+03 -1.44556006e+03 -1.42011755e+03 -1.39799402e+03 -1.37491516e+03 -1.35156055e+03 -1.33136621e+03 -1.30687000e+03 -1.28288269e+03 -1.25824744e+03 -1.23599524e+03 -1.21193555e+03 -1.18630969e+03 -1.16239648e+03 -1.13885193e+03 -1.11257471e+03 -1.08761755e+03 -1.06271509e+03 -1.03719067e+03 -1.01219293e+03 -9.86398621e+02 -9.61216797e+02 -9.35271545e+02 -9.08953979e+02 -8.82916138e+02 -8.56810059e+02 -8.29751953e+02 -8.03277832e+02 -7.77474609e+02 -7.49958313e+02 -7.23338013e+02 -6.96384338e+02 -6.68401978e+02 -6.41397705e+02 -6.14708252e+02 -5.87525269e+02 -5.59769470e+02 -5.31999329e+02 -5.04520569e+02 -4.76865021e+02 -4.48953979e+02 -4.20950500e+02 -3.93087463e+02 -3.65187347e+02 -3.37214569e+02 -3.09018982e+02 -2.80923309e+02 -2.52770279e+02 -2.24189667e+02 -1.96062241e+02 -1.68275208e+02 -1.39850708e+02 -1.11306572e+02 -8.29924316e+01 -5.45728607e+01 -2.62052937e+01 2.06107879e+00 3.05162239e+01 5.90652466e+01 8.72987747e+01 1.15634079e+02 1.43994171e+02 1.72176590e+02 2.00458221e+02 2.28642838e+02 2.56867920e+02 2.84869415e+02 3.13086212e+02 3.41552368e+02 3.69384949e+02 3.97373901e+02 4.25196106e+02 4.53080963e+02 4.80984985e+02 5.08510345e+02 5.36233582e+02 5.64196899e+02 5.91607483e+02 6.18364685e+02 6.45509521e+02 6.73280334e+02 7.00276428e+02 7.26573975e+02 7.53626587e+02 7.81418091e+02 8.07100281e+02 8.34053650e+02 8.61577881e+02 8.86532959e+02 9.12130676e+02 9.37911621e+02 9.65427673e+02 9.91356567e+02 1.01530878e+03 1.04075549e+03 1.06718945e+03 1.09266870e+03 1.11648035e+03 1.14054028e+03 1.16658752e+03 1.19101416e+03 1.21459985e+03 1.23954810e+03 1.26278174e+03 1.28492615e+03 1.30842200e+03 1.33464978e+03 1.35582935e+03 1.37780945e+03 1.40488965e+03 1.42714990e+03 1.44412830e+03 1.46777625e+03 1.49098181e+03 1.50860730e+03 1.53339111e+03 1.55771704e+03 1.57766174e+03 1.59288477e+03 1.61468726e+03 1.63957800e+03 1.65659595e+03 1.67541345e+03 1.69614758e+03 1.71366992e+03 1.73441602e+03 1.75251648e+03 1.77223718e+03 1.79020813e+03 1.80614661e+03 1.82619739e+03 1.84102600e+03 1.85755298e+03 1.87249548e+03 1.89153149e+03 1.91341321e+03 1.92084241e+03 1.93466565e+03 1.95478040e+03 1.97187561e+03 1.98549438e+03 1.99753455e+03 2.00711316e+03 2.02760938e+03 2.04091394e+03 2.05187622e+03 2.06836353e+03 2.07873145e+03 2.09301489e+03 2.10186890e+03 2.11850391e+03 2.12937915e+03 2.13240405e+03 2.14680200e+03 2.15400269e+03 2.16929810e+03 2.17890698e+03 2.18173315e+03 2.20173755e+03 2.20492041e+03 2.21038330e+03 2.22678003e+03 2.22484790e+03 2.23863745e+03 2.24213379e+03 2.24784033e+03 2.26117822e+03 2.26095337e+03 2.26762549e+03 2.27864014e+03 2.27545093e+03 2.28488916e+03 2.29099341e+03 2.28551978e+03 2.30038721e+03 2.30453857e+03 2.29111670e+03 2.30559253e+03 2.30836475e+03 2.30780542e+03 2.30508081e+03 2.30737256e+03 2.31658813e+03 2.30870264e+03 2.31171680e+03 2.31230273e+03 2.31457642e+03 2.31026367e+03 2.30469580e+03 2.30854834e+03 2.30402417e+03 2.30110156e+03 2.30318164e+03 2.30213672e+03 2.29133496e+03 2.94655884e+03 3.09449097e+03 3.12018604e+03 3.38428027e+03 3.06859302e+03 3.36817651e+03 3.36084351e+03 3.34308350e+03 3.34219287e+03 2.88404785e+03 2.94964209e+03 2.76547217e+03 2.93180566e+03 3.28792017e+03 3.26860913e+03 3.25492603e+03 2.80409497e+03 2.77531299e+03 2.25158057e+03 2.67092041e+03 2.88346021e+03 2.76364404e+03 3.15235913e+03 2.67893408e+03 3.12337891e+03 3.11020044e+03 3.08858276e+03 3.06509424e+03 3.04969067e+03 3.02946973e+03 3.00656958e+03 2.99191040e+03 2.96483252e+03 2.94955151e+03 2.92664160e+03 2.89576660e+03 2.88053589e+03 2.86007544e+03 2.83276489e+03 2.64621167e+03 2.78415039e+03 2.49211011e+03 2.73268164e+03 2.70566992e+03 2.68191797e+03 2.65404150e+03 2.62627026e+03 2.59625293e+03 2.57085962e+03 2.53786963e+03 3.92899829e+03 4.67043555e+03 8938099. -1.57937125e+06 -6148026. 32735108. 10627369. 4.81653857e+03 4.52127930e+03 4.21414062e+03 4.58296582e+03 3.50547168e+03 2.14498755e+03 2.10342676e+03 3.39568091e+03 4.46488086e+03 8022168. -7.99636750e+05 4.14360150e+06 3.45027344e+03 2.25451733e+03 2.04443823e+03 1.53958215e+03 1.78223706e+03 1.42657166e+03 1.70793274e+03 1.38598206e+03 1.33215344e+03 1.29831812e+03 1.40403198e+03 1.00940289e+03 1.49081946e+03 1.45190723e+03 1.21366956e+03 1.14127283e+03 8.83514099e+02 8.56875854e+02 8.31021423e+02 8.03906982e+02 7.76984009e+02 7.50247864e+02 7.23473206e+02 6.96612976e+02 6.68913940e+02 6.41818604e+02 6.14807434e+02 5.87368530e+02 5.59853210e+02 5.32289734e+02 5.04584381e+02 4.76866058e+02 4.48899048e+02 4.21164734e+02 3.93398438e+02 3.65212585e+02 3.37087311e+02 3.09129791e+02 2.81022491e+02 2.52728302e+02 2.24586182e+02 1.96329956e+02 1.67928314e+02 1.39517380e+02 1.11156853e+02 8.29353027e+01 5.46287766e+01 2.62375450e+01 -2.13752270e+00 -3.05150433e+01 -5.89105301e+01 -8.72395401e+01 -1.15488853e+02 -1.43881668e+02 -1.72212021e+02 -2.00403030e+02 -2.28790009e+02 -2.57007629e+02 -2.85012421e+02 -3.13223236e+02 -3.41411682e+02 -3.69494598e+02 -3.97447327e+02 -4.25200714e+02 -4.52942291e+02 -4.80841858e+02 -5.08619385e+02 -5.36275085e+02 -5.63709656e+02 -5.91631714e+02 -6.18727600e+02 -6.45545593e+02 -6.73360596e+02 -7.00479553e+02 -7.27318787e+02 -7.54250977e+02 -7.81161499e+02 -8.07283630e+02 -8.34364319e+02 -8.61309265e+02 -8.86616882e+02 -9.12766296e+02 -9.38294922e+02 -9.65378784e+02 -9.90755981e+02 -1.01516364e+03 -1.04074634e+03 -1.06750476e+03 -1.09215674e+03 -1.11684070e+03 -1.14163123e+03 -1.16577197e+03 -1.19062170e+03 -1.21528552e+03 -1.24011230e+03 -1.26236133e+03 -1.28556787e+03 -1.30977722e+03 -1.33452307e+03 -1.35619385e+03 -1.37891821e+03 -1.40474023e+03 -1.42584692e+03 -1.44439722e+03 -1.46727271e+03 -1.49139636e+03 -1.50975854e+03 -1.53325403e+03 -1.55705396e+03 -1.57531531e+03 -1.59243066e+03 -1.61686865e+03 -1.64094934e+03 -1.65585754e+03 -1.67421423e+03 -1.69424158e+03 -1.71636853e+03 -1.73613904e+03 -1.75339661e+03 -1.76916833e+03 -1.78587158e+03 -1.80579834e+03 -1.82777185e+03 -1.84197803e+03 -1.85952197e+03 -1.87246680e+03 -1.88918457e+03 -1.91254248e+03 -1.92280933e+03 -1.93750403e+03 -1.95677563e+03 -1.97177893e+03 -1.98601294e+03 -1.99843201e+03 -2.01018530e+03 -2.02635242e+03 -2.04148560e+03 -2.05294409e+03 -2.07010596e+03 -2.08102710e+03 -2.08970654e+03 -2.10340161e+03 -2.11588330e+03 -2.12486621e+03 -2.13450049e+03 -2.14868506e+03 -2.16086499e+03 -2.16323486e+03 -2.17544409e+03 -2.19338916e+03 -2.19783813e+03 -2.19896899e+03 -2.20921436e+03 -2.22364575e+03 -2.23191772e+03 -2.23119238e+03 -2.24308252e+03 -2.25155225e+03 -2.25688354e+03 -2.26049438e+03 -2.26890039e+03 -2.27825684e+03 -2.27848730e+03 -2.27925024e+03 -2.28976196e+03 -2.28874146e+03 -2.29558765e+03 -2.29425342e+03 -2.95171436e+03 -3.08783569e+03 -3.43031982e+03 -3.42537524e+03 -3.42794238e+03 -3.44241895e+03 -5.62988232e+03 -6.80213623e+03 7251580. -5.94573850e+06 -6.82733545e+03 -5.47066016e+03 -3.43675439e+03 -3.43612744e+03 -3.41745435e+03 -3.42431030e+03 -3.42224854e+03 -3.42170654e+03 -3.40362158e+03 -3.40582886e+03 -3.40505640e+03 -3.38259375e+03 -3.38046631e+03 -3.38065625e+03 -3.36213574e+03 -3.35659375e+03 -3.11281641e+03 -3.34562622e+03 -3.06379126e+03 -3.33260889e+03 -5.14354980e+03 -3.31963550e+03 -5.36637646e+03 -3.27796289e+03 -3.28007495e+03 -3.26749243e+03 -3.24234448e+03 -2.96885205e+03 -2.80685571e+03 -2.14463818e+03 -2.12903271e+03 -2.70594995e+03 -2.80449463e+03 -3.12123608e+03 -3.10176880e+03 -3.08574243e+03 -3.06067041e+03 -5.12305469e+03 -2.59005332e+04 47587496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 65827508. 65827508. 65827508. 0. 0. 0. 0. 39352692. 39352692. 39352692. 0. 0. 167188768. 1.57215516e+05 1.56048094e+05 5.00752688e+05 -30789696. -180564048. 59365920. 59365920. 59365920. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -5.96269466e+09 -5.96269466e+09 -5.96269466e+09 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. -1148540160. -1148540160. -1148540160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 97407352. 97407352. 97407352. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56842832. -9061306. 4.23295820e+04 -4.08843450e+06 -7.87497950e+06 9165844. -6.03958312e+05 24072544. 2.56564624e+03 3.05400781e+03 1.32874258e+04 2.63230078e+03 1.26457705e+04 1.26457705e+04 4599262. -15852164. -15852164. 15629822. 0. 0. 0. 0. 52656932. 52656932. 52656932. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.59553946e+09 -9.59553946e+09 -9.59553946e+09 0. 0. 0. 0. 0. 0. 0. 57413476. 57413476. 57413476. 0. -62066840. -4.26740850e+06 -5.61096625e+05 -4.03358350e+06 -4288934. 6.10870117e+03 4.94918945e+03 3.17017285e+03 3.19311108e+03 3.20731250e+03 3.22461377e+03 3.23752612e+03 5.26953223e+03 6.73159180e+03 -391842. -2.21696375e+06 49885892. 22989846. 2.71288066e+04 6.82337939e+03 -1.46942388e+06 -2.90954175e+06 -2.81085025e+06 6.69694434e+03 6.76585156e+03 6.83541113e+03 6.73208691e+03 5.45143311e+03 3.44016675e+03 3.44908472e+03 3.45250562e+03 3.44709155e+03 3.46145947e+03 3.46494043e+03 3.51174756e+03 5.46047119e+03 7.06627539e+03 2.68821875e+04 -590017856. -70963840. 0. 0. 5781835. 2.75129590e+04 6.90360059e+03 9259268. 10327478. 3.72993075e+06 -12592060. -5334756. -1.64789150e+06 6.95781885e+03 5.54572949e+03 3.45238477e+03 3.19669043e+03 3.02098071e+03 2.31333423e+03 2.30624976e+03 2.30866577e+03 2.29660400e+03 2.28933374e+03 2.28873047e+03 2.27902173e+03 2.27337842e+03 2.26738745e+03 2.25732544e+03 2.25066748e+03 2.23231396e+03 2.22603564e+03 2.22084155e+03 2.21160107e+03 2.20637036e+03 2.19516675e+03 2.18297656e+03 2.16632471e+03 2.16013354e+03 2.14738354e+03 2.73752222e+03 2.84679932e+03 2.91754492e+03 2.73515210e+03 2.08423877e+03 2.07261768e+03 2.05966431e+03 2.04384375e+03 2.59292505e+03 2.69199194e+03 2.77985254e+03 2.60004492e+03 1.96609253e+03 1.95256970e+03 1.93573633e+03 1.91914661e+03 1.90350208e+03 1.88334961e+03 1.86939954e+03 1.85205066e+03 1.83028723e+03 1.81204895e+03 1.79902539e+03 1.77540894e+03 1.75556604e+03 1.74109937e+03 1.72195581e+03 1.69587183e+03 1.67670728e+03 1.65996277e+03 1.64004163e+03 1.61719983e+03 1.59402637e+03 1.57439380e+03 1.55230469e+03 1.53244836e+03 1.50962036e+03 1.48729272e+03 1.46630249e+03 1.44218628e+03 1.41922961e+03 1.39689197e+03 1.37231262e+03 1.34945508e+03 1.32651672e+03 1.30173291e+03 1.27676990e+03 1.25318652e+03 1.22891626e+03 1.20360034e+03 1.17918457e+03 1.15339136e+03 1.12823047e+03 1.10318799e+03 1.07738293e+03 1.05179785e+03 1.02576880e+03 9.99529663e+02 9.73906006e+02 9.47341370e+02 9.20822876e+02 8.93759521e+02 8.67339417e+02 8.41111023e+02 8.13257202e+02 7.86182373e+02 7.59023560e+02 7.31624512e+02 7.04144226e+02 6.76498352e+02 6.48920288e+02 6.21354431e+02 5.92967651e+02 5.65198792e+02 5.37438904e+02 5.09050903e+02 4.80935791e+02 4.52566895e+02 4.24064423e+02 3.95778259e+02 3.67278259e+02 3.38685974e+02 3.10008575e+02 2.81439270e+02 2.52833145e+02 2.24121841e+02 1.95349823e+02 1.66626297e+02 1.37839630e+02 1.08933258e+02 8.00047760e+01 5.11726570e+01 2.23582344e+01 -6.54443359e+00 -3.54342804e+01 -6.42705994e+01 -9.30728760e+01 -1.22016220e+02 -1.50847244e+02 -1.79496796e+02 -2.08154114e+02 -2.36930511e+02 -2.65762482e+02 -2.94341064e+02 -3.22938446e+02 -3.51674591e+02 -3.80215332e+02 -4.08658356e+02 -4.37121094e+02 -4.65075348e+02 -4.93439423e+02 -5.21653503e+02 -5.49913147e+02 -5.78126648e+02 -6.05958923e+02 -6.33658508e+02 -6.61120300e+02 -6.88998230e+02 -7.17026978e+02 -7.44164307e+02 -7.70865295e+02 -7.98676147e+02 -8.26140503e+02 -8.52699768e+02 -8.79409058e+02 -9.05868958e+02 -9.32990845e+02 -9.59665588e+02 -9.85742554e+02 -1.01189539e+03 -1.03934229e+03 -1.06611133e+03 -1.09053357e+03 -1.11477429e+03 -1.43803284e+03 -1.52315796e+03 -1.80323694e+03 -1.84628491e+03 -1.88548071e+03 -1.82969604e+03 -1.73443750e+03 -1.61441711e+03 -2.70581177e+03 -2.04781287e+03 -4.07645776e+03 -4.34063135e+03 -1.33954062e+06 -3.47125150e+06 2.63552575e+06 -3.05270527e+04 -1854187392. -580577792. 0. 0. 0. 0. 0. 0. -24429536. -2.62390273e+04 -6.41618018e+03 2.43736344e+05 -2.31522290e+03 -3.82898706e+03 -4.48371387e+03 1.39156512e+06 6.70083359e+04 4.87315742e+04 1.01824838e+06 -2.85703027e+03 -3.48668237e+03 -4.42014844e+03 -2.67499854e+03 -5.86628320e+03 -3.60176392e+03 -4.38136475e+03 -2.95885449e+03 -3.03016382e+03 -3.15529736e+03 -2.93793433e+03 -3.04693481e+03 -2.82145557e+03 -3.05606543e+03 -3.09920630e+03 -3.08430347e+03 -3.10474023e+03 -3.16047583e+03 -3.14464209e+03 -3.14784326e+03 -3.17161157e+03 -5.15792822e+03 -3.48190674e+03 -4.67436523e+03 -6.53557861e+03 -6.62009375e+03 -1.82259216e+03 3.52783750e+04 3.70415969e+05 9.35385500e+05 6.75113250e+05 -3.33018875e+06 -11395548. -5445226. -3.30332375e+06 -15649554. 2.53144825e+06 5673026. 2.95737575e+06 -2.18753325e+06 -2.11194350e+06 -2.52454375e+06 -6.17774650e+06 -6.03427250e+06 4377010. -6.88578564e+03 -5.51746143e+03 -3.48058447e+03 -3.22389795e+03 -3.04967725e+03 -2.35170239e+03 -2.34913501e+03 -2.35145337e+03 -2.34983447e+03 -2.35056567e+03 -2.34972144e+03 -2.34689209e+03 -2.34362646e+03 -2.34880493e+03 -2.34105640e+03 -2.33694824e+03 -2.33934814e+03 -2.33188354e+03 -2.32733057e+03 -2.32450854e+03 -2.32477490e+03 -2.31242236e+03 -2.30799048e+03 -2.30374609e+03 -2.29738574e+03 -2.29252710e+03 -2.28576855e+03 -2.28116528e+03 -2.27398145e+03 -2.26090015e+03 -2.25585254e+03 -2.25131641e+03 -2.23485913e+03 -2.22652173e+03 -2.22110132e+03 -2.21403491e+03 -2.20473901e+03 -2.19548022e+03 -2.18099292e+03 -2.16494556e+03 -2.15845923e+03 -2.15000781e+03 -2.13934375e+03 -2.12439355e+03 -2.10407324e+03 -2.09464478e+03 -2.08278467e+03 -2.07337354e+03 -2.05904004e+03 -2.04211060e+03 -2.02994556e+03 -2.01669470e+03 -1.99646350e+03 -1.98737280e+03 -1.96388110e+03 -1.94867322e+03 -1.93695081e+03 -1.92128894e+03 -1.90436523e+03 -1.88529126e+03 -1.86756946e+03 -1.85246960e+03 -1.83060022e+03 -1.81303552e+03 -1.79775867e+03 -1.77319629e+03 -1.75467102e+03 -1.74109131e+03 -1.72064893e+03 -1.69408594e+03 -1.67547229e+03 -1.65857336e+03 -1.64081104e+03 -1.61571484e+03 -1.59477075e+03 -1.57591040e+03 -1.55181262e+03 -1.53167065e+03 -1.50888367e+03 -1.48611731e+03 -1.46581665e+03 -1.44262939e+03 -1.41849280e+03 -1.39551001e+03 -1.37212683e+03 -1.35032800e+03 -1.32544556e+03 -1.30136987e+03 -1.27638245e+03 -1.25286633e+03 -1.22811121e+03 -1.20128882e+03 -1.17809753e+03 -1.15503467e+03 -1.12819531e+03 -1.10251587e+03 -1.07705542e+03 -1.05122827e+03 -1.02540674e+03 -9.98848877e+02 -9.74189148e+02 -9.47676880e+02 -9.20891724e+02 -8.93690125e+02 -8.67041626e+02 -8.40337097e+02 -8.13320312e+02 -7.86486023e+02 -7.58699829e+02 -7.31642578e+02 -7.04179138e+02 -6.75798950e+02 -6.48246521e+02 -6.21060425e+02 -5.93162415e+02 -5.65062073e+02 -5.37268921e+02 -5.08880096e+02 -4.80781616e+02 -4.52534149e+02 -4.23934052e+02 -3.95607910e+02 -3.67132019e+02 -3.38711273e+02 -3.10039581e+02 -2.81458862e+02 -2.52699356e+02 -2.23720856e+02 -1.95076309e+02 -1.66826813e+02 -1.38019836e+02 -1.08974586e+02 -8.00697250e+01 -5.11573639e+01 -2.23559570e+01 6.51964808e+00 3.53153381e+01 6.43034592e+01 9.32433395e+01 1.21978043e+02 1.50724976e+02 1.79483383e+02 2.08228943e+02 2.36826767e+02 2.65549500e+02 2.94214447e+02 3.22811676e+02 3.51524933e+02 3.80108612e+02 4.08558258e+02 4.36841858e+02 4.65075623e+02 4.93551361e+02 5.21535095e+02 5.49563782e+02 5.77999023e+02 6.05717590e+02 6.33121521e+02 6.60789185e+02 6.88992249e+02 7.16654785e+02 7.43554077e+02 7.71043884e+02 7.98825500e+02 8.25190002e+02 8.51672974e+02 8.79701965e+02 9.06175171e+02 9.31818970e+02 9.58930176e+02 9.85836975e+02 1.01114868e+03 1.03720129e+03 1.06243872e+03 1.08918091e+03 1.11498132e+03 1.13852478e+03 1.16455261e+03 1.19083154e+03 1.21372070e+03 1.23850354e+03 1.26459033e+03 1.28895337e+03 1.31305005e+03 1.33572729e+03 1.35834863e+03 1.38172192e+03 1.40575427e+03 1.43052979e+03 1.45413098e+03 1.47370349e+03 1.49621570e+03 1.52069873e+03 1.53965723e+03 1.56184863e+03 1.58667908e+03 1.60797839e+03 1.62422510e+03 1.64523608e+03 1.66820569e+03 1.68461047e+03 1.70569360e+03 1.72885303e+03 1.74832080e+03 1.76947888e+03 1.78496130e+03 1.80366956e+03 1.82021887e+03 1.83596545e+03 1.86226038e+03 1.87639294e+03 1.89079626e+03 1.90978442e+03 1.92662158e+03 1.94350537e+03 1.95934338e+03 1.97379773e+03 1.99216602e+03 2.00679919e+03 2.02187354e+03 2.03559607e+03 2.04987622e+03 2.06359277e+03 2.07540601e+03 2.09216895e+03 2.10622925e+03 2.11491821e+03 2.13180762e+03 2.14213745e+03 2.15540723e+03 2.16473511e+03 2.17016382e+03 2.18767847e+03 2.19265942e+03 2.20783252e+03 2.21803442e+03 2.22578516e+03 2.23816455e+03 2.24390771e+03 2.25240576e+03 2.26224683e+03 2.26793701e+03 2.27492554e+03 2.28469507e+03 2.28798413e+03 2.29738281e+03 2.29777979e+03 2.31111694e+03 2.32073193e+03 2.31850269e+03 2.32579639e+03 2.32869043e+03 2.32767432e+03 2.34009692e+03 2.34505469e+03 2.33472900e+03 2.34206860e+03 2.34895654e+03 2.34774072e+03 2.34763184e+03 2.34925879e+03 2.35291382e+03 2.35215015e+03 2.35026465e+03 2.34712939e+03 2.34798706e+03 2.35103979e+03 3.02445557e+03 3.18011841e+03 3.47802930e+03 3.46656201e+03 3.46962158e+03 3.46438257e+03 3.45773730e+03 5.46764404e+03 6.77019043e+03 6.88260986e+03 6.81960889e+03 6.71754834e+03 3677637. -2.34194475e+06 3.27807350e+06 6509584. 6.60681689e+03 6.56586035e+03 4.74224561e+03 6.44782910e+03 -1.76684088e+06 -7.42877625e+05 -7932172. 6.66804004e+03 5.96591260e+03 4.26974023e+03 4.60379932e+03 6.23550146e+03 6.69064600e+03 6.06582812e+03 5.16035303e+03 -2163883. 2.62551975e+06 3.72254175e+06 -6.94293850e+06 11656459. 3.97845075e+06 48792808. 7891997. 2.16948650e+06 13087206. 2198327. -2.10630450e+06 -2.57436725e+06 5.86615039e+03 5.70397412e+03 3.02306982e+03 5.59279980e+03 5.28900537e+03 -1.46582150e+06 -3.09293875e+05 -3.87215688e+05 -8051897. -8.00264250e+05 14379382. -3.49918550e+06 5.13379688e+03 2.02597988e+04 11207521. 0. 0. 0. 0. 0. 44492012. 44492012. 44492012. -72030592. 9.97101375e+05 -6.57345438e+05 -14141556. -3.50874250e+06 -1.53858712e+06 4.23289404e+03 3.28192578e+03 1.98918933e+03 1.95387891e+03 1.56451843e+03 2.01126721e+03 1.90020532e+03 1.81689429e+03 1.53177124e+03 1.74521729e+03 1.63407190e+03 1.43682959e+03 1.35466760e+03 1.05266809e+03 1.02614929e+03 1.00021887e+03 9.73636536e+02 9.47154968e+02 9.20717590e+02 8.93546814e+02 8.67134949e+02 8.40820435e+02 8.13287598e+02 7.85626709e+02 7.58614014e+02 7.31588135e+02 7.04033997e+02 6.76417480e+02 6.48568298e+02 6.21042175e+02 5.93009460e+02 5.65050293e+02 5.37132507e+02 5.09009308e+02 4.80767456e+02 4.52304657e+02 4.24057434e+02 3.95750122e+02 3.67194794e+02 3.38568878e+02 3.09941528e+02 2.81430817e+02 2.52822388e+02 2.24142883e+02 1.95427521e+02 1.66499710e+02 1.37472733e+02 1.08660271e+02 8.00150452e+01 5.11625175e+01 2.22773705e+01 -6.49232769e+00 -3.53549423e+01 -6.43162689e+01 -9.31001358e+01 -1.21881310e+02 -1.50650162e+02 -1.79429337e+02 -2.08272385e+02 -2.37021545e+02 -2.65631897e+02 -2.94239624e+02 -3.22963989e+02 -3.51555176e+02 -3.80080902e+02 -4.08608704e+02 -4.37002594e+02 -4.65081024e+02 -4.93417206e+02 -5.21513306e+02 -5.49504517e+02 -5.77406372e+02 -6.05747925e+02 -6.33091431e+02 -6.60583862e+02 -6.88981812e+02 -7.16788513e+02 -7.44183350e+02 -7.70984131e+02 -7.98188049e+02 -8.25410095e+02 -8.52488098e+02 -8.79655151e+02 -9.06244812e+02 -9.32328796e+02 -9.58743591e+02 -9.85706726e+02 -1.01139520e+03 -1.03706262e+03 -1.06346704e+03 -1.08926001e+03 -1.11445435e+03 -1.13916272e+03 -1.16566882e+03 -1.19034351e+03 -1.21371643e+03 -1.23909644e+03 -1.26482202e+03 -1.28832983e+03 -1.31272070e+03 -1.33639136e+03 -1.35922974e+03 -1.38146460e+03 -1.40582935e+03 -1.43167749e+03 -1.45389819e+03 -1.47331567e+03 -1.49560266e+03 -1.52033484e+03 -1.54128296e+03 -1.56229346e+03 -1.58533667e+03 -1.60631519e+03 -1.62534033e+03 -1.64720337e+03 -1.66901929e+03 -1.68727368e+03 -1.70718689e+03 -1.72772900e+03 -1.74910474e+03 -1.76767004e+03 -1.78524976e+03 -1.80223132e+03 -1.81902466e+03 -1.83669226e+03 -1.86231482e+03 -1.87669690e+03 -1.89356201e+03 -1.90955115e+03 -1.92243066e+03 -1.94526135e+03 -1.96011536e+03 -1.97209937e+03 -1.99265234e+03 -2.00733313e+03 -2.02164502e+03 -2.03608264e+03 -2.04865430e+03 -2.06102002e+03 -2.07816797e+03 -2.09113013e+03 -2.10622803e+03 -2.11930981e+03 -2.12798755e+03 -2.13876758e+03 -2.15172290e+03 -2.17290308e+03 -2.17572778e+03 -2.18332788e+03 -2.19713037e+03 -2.20590747e+03 -2.21595020e+03 -2.23092871e+03 -2.23394678e+03 -2.24266504e+03 -2.25799536e+03 -2.26725317e+03 -2.26580200e+03 -2.26731812e+03 -2.28125244e+03 -2.29181787e+03 -2.29312720e+03 -2.30059302e+03 -2.30674512e+03 -2.31757031e+03 -2.31722876e+03 -2.32227661e+03 -2.32883252e+03 -3.06791504e+03 -3.34238623e+03 -3.23122583e+03 -4.92461084e+03 -6.02004004e+03 -1.64175950e+06 4.99586328e+04 -9.50212734e+04 -1.21712212e+06 35454856. -58404156. 0. 0. -26178324. 34462728. -2.36224175e+06 3200939. -1.22354938e+06 4970106. -3.56316475e+06 3237833. 1.04753425e+06 2.47510350e+06 -6.87426465e+03 -6.84357471e+03 -6.79470166e+03 -1.94623425e+06 -15369731. 4.64857350e+06 -6.72361133e+03 -6.73390283e+03 -6.73960498e+03 -1.46942373e+04 -17000164. 7.17727950e+06 31945958. -7.42524297e+04 -5.12252109e+04 -6.01128711e+04 3.17039750e+05 -6.79809131e+03 -5.29005811e+03 -3.22099634e+03 -3.20309424e+03 -4.99264404e+03 -6.09011084e+03 -10627519. -127286680. 1.10639250e+06 -1.76170312e+04 -1176500096. 47787000. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 65827508. 65827508. 65827508. 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. 0. 0. 0. 0. 0. 0. 0. -5.96269466e+09 -5.96269466e+09 -5.96269466e+09 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. -1148540160. -1148540160. 227358048. -207423008. -207423008. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 48703676. 48703676. 48703676. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 686052736. 686052736. 686052736. 633803904. -1.03958412e+06 -1.03958412e+06 2299631. -7926082. -7926082. 7814911. 0. 0. 0. 0. 52656932. 52656932. 52656932. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.59553946e+09 -9.59553946e+09 -9.59553946e+09 0. 0. 0. 0. 0. 0. 0. 57413476. 57413476. 57413476. 0. 0. 0. 0. 0. 0. 60152944. 2.80611450e+06 752185. -7.50683438e+05 6.71608950e+06 9.07518812e+05 -6.12390562e+05 10448964. 1.87643588e+06 0. 0. 0. -11961193. -11961193. -11961193. 0. 0. 0. 252966864. 252966864. 252966864. 50112816. 3.24799850e+06 -8.32370688e+05 -1.25575050e+06 2.95835125e+06 -3.82455175e+06 -2.60324050e+06 -14548975. 9.50044141e+03 -2721977. -21102690. -70963840. -70963840. -70963840. 0. 0. 22417482. 22417482. 22417482. 0. 0. 0. 0. 0. 0. -19208278. -1.47539338e+06 -4927072. 3.51176221e+03 3.11243945e+03 2.32175635e+03 2.31632837e+03 2.31396924e+03 2.30228223e+03 2.29343848e+03 2.29429810e+03 2.28634106e+03 2.27989673e+03 2.27182178e+03 2.25779712e+03 2.25497266e+03 2.23907788e+03 2.23219751e+03 2.22500708e+03 2.22168872e+03 2.21049048e+03 2.19753247e+03 2.18544824e+03 2.16973291e+03 2.16346558e+03 2.15962061e+03 2.79296509e+03 3.02616846e+03 3.25890649e+03 2.83350146e+03 2.08847583e+03 2.07917334e+03 2.05963477e+03 2.05112109e+03 2.63404346e+03 2.83230835e+03 3.12670850e+03 2.71357910e+03 1.96935168e+03 1.95412048e+03 1.94126428e+03 1.92533215e+03 1.90623181e+03 1.88885791e+03 1.87574084e+03 1.85287964e+03 1.83205249e+03 1.81412903e+03 1.80204749e+03 1.77935657e+03 1.75734204e+03 1.74283386e+03 1.72445288e+03 1.70049231e+03 1.68093970e+03 1.66205115e+03 1.64301611e+03 1.62022559e+03 1.59412048e+03 1.57453162e+03 1.55882275e+03 1.53812000e+03 1.51084363e+03 1.48924512e+03 1.46701282e+03 1.44129517e+03 1.41998535e+03 1.39928772e+03 1.37578125e+03 1.35170776e+03 1.32659070e+03 1.30361475e+03 1.27983679e+03 1.25401575e+03 1.23013843e+03 1.20439722e+03 1.18129297e+03 1.15571741e+03 1.12941821e+03 1.10466602e+03 1.07733325e+03 1.05213025e+03 1.02766711e+03 1.00096606e+03 9.74799011e+02 9.46945435e+02 9.21576782e+02 8.94678101e+02 8.68062073e+02 8.41661316e+02 8.12861328e+02 7.85943237e+02 7.59064453e+02 7.31247559e+02 7.03954407e+02 6.76437927e+02 6.48892700e+02 6.20876465e+02 5.92112976e+02 5.64198792e+02 5.36965515e+02 5.08664459e+02 4.80248596e+02 4.51533508e+02 4.23121613e+02 3.95007812e+02 3.66462891e+02 3.37659790e+02 3.08646973e+02 2.79947784e+02 2.51334763e+02 2.22754745e+02 1.93892258e+02 1.65210175e+02 1.36363647e+02 1.07210823e+02 7.81317368e+01 4.88248329e+01 1.99063377e+01 -8.54184246e+00 -3.75047493e+01 -6.63914108e+01 -9.50658493e+01 -1.24607841e+02 -1.53626770e+02 -1.82015091e+02 -2.10586044e+02 -2.39401718e+02 -2.68477875e+02 -2.96937469e+02 -3.25438812e+02 -3.54691803e+02 -3.83227386e+02 -4.11895996e+02 -4.40566467e+02 -4.67812561e+02 -4.96616730e+02 -5.25270935e+02 -5.53347168e+02 -5.81746033e+02 -6.09766235e+02 -6.37661560e+02 -6.64258240e+02 -6.92523621e+02 -7.20999878e+02 -7.47858154e+02 -7.74653564e+02 -8.02199036e+02 -8.30072144e+02 -8.56900330e+02 -8.83982361e+02 -9.10269958e+02 -9.36686584e+02 -9.63589111e+02 -9.90096497e+02 -1.01624438e+03 -1.04284680e+03 -1.06863318e+03 -1.09360547e+03 -1.11906458e+03 -1.14529907e+03 -1.17178320e+03 -1.19899695e+03 -1.22968286e+03 -1.25608362e+03 -1.27805640e+03 -1.29950293e+03 -2.48563770e+03 -1.51530078e+04 -9010884. -130615248. -130615248. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 23040304. 23040304. 23040304. 0. -39482064. -39482064. -39482064. 0. 0. 0. 0. 14429323. 3798009. 3798009. -1.30055950e+06 -2.17141312e+05 -16082913. 4766087. -3.45306689e+03 -3.85083125e+04 -7.63238721e+03 -3.40574194e+03 -3.12001636e+03 -2.92591992e+03 -2.55949854e+03 -1.48569941e+04 1.88688086e+04 9.17934863e+03 -5.08012031e+04 5.31478271e+03 7.42778281e+04 3.05907051e+04 4986671. 5.81408550e+06 3.82488475e+06 3.82488475e+06 18667696. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -19612156. 3.45346650e+06 -14699291. -3.51815820e+03 -3.13237451e+03 -2.35761865e+03 -2.35306152e+03 -2.35661938e+03 -2.35151392e+03 -2.35244336e+03 -2.35442480e+03 -2.35561084e+03 -2.35464233e+03 -2.35384668e+03 -2.34636353e+03 -2.34164282e+03 -2.34443433e+03 -2.33857495e+03 -2.33195166e+03 -2.33474756e+03 -2.32484985e+03 -2.31905005e+03 -2.31602539e+03 -2.31167505e+03 -2.30718359e+03 -2.30287817e+03 -2.29216382e+03 -2.28698267e+03 -2.27770386e+03 -2.26784888e+03 -2.26063550e+03 -2.25688257e+03 -2.24470776e+03 -2.23595874e+03 -2.22604004e+03 -2.21860425e+03 -2.20897241e+03 -2.19646021e+03 -2.18682520e+03 -2.16790063e+03 -2.16399438e+03 -2.15524805e+03 -2.14321118e+03 -2.12511084e+03 -2.11348706e+03 -2.09723047e+03 -2.08910010e+03 -2.07779370e+03 -2.06107251e+03 -2.04746289e+03 -2.03264050e+03 -2.01628662e+03 -1.99998987e+03 -1.99181873e+03 -1.96658752e+03 -1.95181287e+03 -1.94415332e+03 -1.92544617e+03 -1.90583105e+03 -1.88883289e+03 -1.87403772e+03 -1.85459229e+03 -1.83165967e+03 -1.81553796e+03 -1.80107849e+03 -1.77685205e+03 -1.75870129e+03 -1.74400842e+03 -1.72266138e+03 -1.69896790e+03 -1.67943591e+03 -1.66061169e+03 -1.64400842e+03 -1.61959827e+03 -1.59623108e+03 -1.57608447e+03 -1.55556238e+03 -1.53386890e+03 -1.51093262e+03 -1.48753918e+03 -1.46568530e+03 -1.44465381e+03 -1.42114600e+03 -1.39811914e+03 -1.37447119e+03 -1.35083557e+03 -1.32769177e+03 -1.30243555e+03 -1.27784326e+03 -1.25313696e+03 -1.23100854e+03 -1.20275110e+03 -1.17896912e+03 -1.15612366e+03 -1.12893262e+03 -1.10377014e+03 -1.07745203e+03 -1.05179407e+03 -1.02625977e+03 -1.00006116e+03 -9.75300293e+02 -9.47799805e+02 -9.21483276e+02 -8.95335754e+02 -8.66821777e+02 -8.39692444e+02 -8.14024475e+02 -7.86930115e+02 -7.58495117e+02 -7.31427490e+02 -7.04543152e+02 -6.75736877e+02 -6.47521851e+02 -6.20030640e+02 -5.92561462e+02 -5.64631348e+02 -5.36612488e+02 -5.08434113e+02 -4.80049744e+02 -4.51510315e+02 -4.23034546e+02 -3.95172363e+02 -3.66509094e+02 -3.37539917e+02 -3.08808960e+02 -2.80128510e+02 -2.50992081e+02 -2.21599945e+02 -1.93215958e+02 -1.65888992e+02 -1.36972015e+02 -1.07327972e+02 -7.83256454e+01 -4.92270851e+01 -2.03653946e+01 8.65098095e+00 3.75394478e+01 6.72203674e+01 9.62798462e+01 1.24505753e+02 1.53219391e+02 1.81997360e+02 2.10861832e+02 2.39332474e+02 2.68328033e+02 2.97277283e+02 3.25610413e+02 3.54253876e+02 3.83056854e+02 4.11836975e+02 4.39973938e+02 4.68112915e+02 4.96800751e+02 5.25013611e+02 5.52884094e+02 5.81244324e+02 6.09013916e+02 6.36179321e+02 6.64512939e+02 6.92241333e+02 7.19363953e+02 7.47544983e+02 7.75774963e+02 8.02948669e+02 8.29190979e+02 8.56176575e+02 8.84127319e+02 9.10196838e+02 9.36065552e+02 9.64031799e+02 9.89776123e+02 1.01507129e+03 1.04337830e+03 1.06759900e+03 1.09266101e+03 1.11874109e+03 1.14313354e+03 1.16997131e+03 1.19463354e+03 1.21825537e+03 1.24296680e+03 1.26958179e+03 1.29541895e+03 1.31874561e+03 1.34026721e+03 1.36237048e+03 1.38594617e+03 1.41257397e+03 1.43652637e+03 1.46078223e+03 1.47941821e+03 1.50038501e+03 1.52588281e+03 1.54549292e+03 1.56801990e+03 1.59312048e+03 1.61349829e+03 1.62860034e+03 1.65011267e+03 1.67786389e+03 1.69402454e+03 1.71288855e+03 1.73414319e+03 1.75004749e+03 1.77358423e+03 1.78900891e+03 1.81021167e+03 1.82933032e+03 1.84425220e+03 1.86630798e+03 1.88210852e+03 1.89956726e+03 1.91127185e+03 1.93100220e+03 1.95360681e+03 1.96327734e+03 1.97791895e+03 1.99396375e+03 2.01046985e+03 2.03071472e+03 2.04388367e+03 2.05094556e+03 2.07310352e+03 2.08484570e+03 2.09448804e+03 2.11402539e+03 2.12619751e+03 2.13919214e+03 2.14463770e+03 2.15838403e+03 2.17444043e+03 2.17605151e+03 2.19015967e+03 2.19991113e+03 2.20863892e+03 2.22368384e+03 2.23804883e+03 2.24589600e+03 2.24767456e+03 2.25405981e+03 2.26892163e+03 2.27170654e+03 2.28185352e+03 2.29123022e+03 2.29620874e+03 2.30502490e+03 2.30469604e+03 2.31042627e+03 2.32631982e+03 2.33023291e+03 2.32596069e+03 2.33569458e+03 2.33375854e+03 2.34517383e+03 2.35245166e+03 2.34285620e+03 2.34291431e+03 2.35199561e+03 2.35515894e+03 2.35504541e+03 2.35335645e+03 2.35895215e+03 2.35958691e+03 2.35878394e+03 2.35038574e+03 2.35397827e+03 2.35789307e+03 3.12088965e+03 3.48009863e+03 35872792. 2.75527425e+06 -3.99701775e+06 -3.08058656e+05 -1.16373688e+05 -4992041. 12470356. 7.53821125e+05 7.53821125e+05 7.53821125e+05 0. 0. 0. 0. -3.62708850e+06 -7630294. -7630294. -53648068. 0. 0. 0. 7401231. -33817648. 2.29699609e+04 -18538562. 6.13422650e+06 114210176. 114210176. 114210176. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 42326792. 42326792. 226276272. 92098648. 92098648. 0. 0. 0. 0. 0. 0. 0. -75963720. -75963720. -75963720. 0. 0. 0. 0. 0. 22246006. 22246006. 22246006. 0. 0. 0. 0. 0. 0. 53038192. -7.49783750e+05 3.64848075e+06 1.38852250e+06 3.54093140e+03 2.20867651e+03 1.35831299e+03 1.20767493e+03 1.18108118e+03 1.15554553e+03 1.12967981e+03 1.10445068e+03 1.07819800e+03 1.05306824e+03 1.02779041e+03 1.00072906e+03 9.74446472e+02 9.47414856e+02 9.21101074e+02 8.94130981e+02 8.67203857e+02 8.40910156e+02 8.12768250e+02 7.85644714e+02 7.58627075e+02 7.31236633e+02 7.04067749e+02 6.76702332e+02 6.48203857e+02 6.20170654e+02 5.92569031e+02 5.64361633e+02 5.36461853e+02 5.08562469e+02 4.80092285e+02 4.51450165e+02 4.23173889e+02 3.94808167e+02 3.66260254e+02 3.37516907e+02 3.08560516e+02 2.79836670e+02 2.51389893e+02 2.22975784e+02 1.94296356e+02 1.64874466e+02 1.34766281e+02 1.05802307e+02 7.79212418e+01 4.91213226e+01 2.01697464e+01 -8.39560223e+00 -3.74640999e+01 -6.69624939e+01 -9.56008835e+01 -1.23979240e+02 -1.52638489e+02 -1.81781204e+02 -2.11142792e+02 -2.40093124e+02 -2.68271759e+02 -2.96595551e+02 -3.25826477e+02 -3.54451569e+02 -3.83120209e+02 -4.12127930e+02 -4.40359283e+02 -4.68343536e+02 -4.96872284e+02 -5.24858826e+02 -5.52890076e+02 -5.80429626e+02 -6.08569763e+02 -6.35479492e+02 -6.62635071e+02 -6.92645752e+02 -7.20967957e+02 -7.47681274e+02 -7.74603210e+02 -8.01636536e+02 -8.29493591e+02 -8.57475220e+02 -8.83980957e+02 -9.10152100e+02 -9.35504395e+02 -9.62522461e+02 -9.89794800e+02 -1.01479120e+03 -1.04258398e+03 -1.06901074e+03 -1.09288293e+03 -1.11815320e+03 -1.14493384e+03 -1.17119543e+03 -1.19442957e+03 -1.21831042e+03 -1.24283960e+03 -1.27076318e+03 -1.29483411e+03 -1.31766797e+03 -1.34048840e+03 -1.36289282e+03 -1.38659387e+03 -1.41173425e+03 -1.43690137e+03 -1.45966687e+03 -1.48040552e+03 -1.49958020e+03 -1.52311060e+03 -1.54681360e+03 -1.56761572e+03 -1.59354932e+03 -1.61165552e+03 -1.62836023e+03 -1.65265527e+03 -1.67964966e+03 -1.69595264e+03 -1.71118469e+03 -1.73201282e+03 -1.75505920e+03 -1.77408887e+03 -1.79083545e+03 -1.80742419e+03 -1.82211279e+03 -1.84433228e+03 -1.86902527e+03 -1.88585156e+03 -1.90117578e+03 -1.91387610e+03 -1.92873169e+03 -1.95116833e+03 -1.96944958e+03 -1.97458252e+03 -1.99342236e+03 -2.01278125e+03 -2.02748987e+03 -2.04253442e+03 -2.05349097e+03 -2.07132056e+03 -2.08297998e+03 -2.09357056e+03 -2.11350439e+03 -2.12570923e+03 -2.13315039e+03 -2.14656470e+03 -2.16168115e+03 -2.20437183e+03 -2.18452319e+03 -2.19492944e+03 -2.19992896e+03 -2.21007983e+03 -2.22165967e+03 -2.23770703e+03 -2.24443579e+03 -2.25097559e+03 -2.27684863e+03 -2.27043164e+03 -2.27218799e+03 -2.27443701e+03 -2.28795923e+03 -2.29384009e+03 -2.30215405e+03 -2.30689307e+03 -2.31562964e+03 -2.32491455e+03 -2.32581909e+03 -2.33904126e+03 -2.34251245e+03 -3.49501367e+03 -4.76380420e+03 -3.31626929e+03 -1.38738311e+04 -7.97247850e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6473363. -6473363. -6473363. 0. 0. 0. -41674648. -41674648. -41674648. 0. 0. 0. 0. 0. 0. 0. 0. -18113776. 3.04154075e+06 1.88154050e+06 3.30333906e+05 6.81579312e+05 19489578. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 32913754. 32913754. 32913754. 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. 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. 0. 0. 0. 0. 0. 0. 0. -574270080. -574270080. -116224808. -207423008. -207423008. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_2.xml ================================================ 16 1024
f
3.64280150e+06 1.27991173e+02 8.44696579e+01 8.47647324e+01 8.50740433e+01 8.53444061e+01 8.56367416e+01 8.61333084e+01 8.65810471e+01 8.70222473e+01 8.70815735e+01 8.73020554e+01 8.75481949e+01 8.76806488e+01 8.78692551e+01 8.80321655e+01 8.84458313e+01 8.86664047e+01 8.89416962e+01 8.93561707e+01 8.97175217e+01 8.99293442e+01 9.01003036e+01 9.03093567e+01 9.05606689e+01 9.08422852e+01 9.12613449e+01 9.15640717e+01 9.17246246e+01 9.18645401e+01 9.21271591e+01 9.24270096e+01 9.24322968e+01 9.29039078e+01 9.33397217e+01 9.38845749e+01 9.43726501e+01 9.46433640e+01 9.48895264e+01 9.52222519e+01 9.53925858e+01 9.53695984e+01 9.54900360e+01 9.58032608e+01 9.61595612e+01 9.61688614e+01 9.67740479e+01 9.67512360e+01 9.66316452e+01 9.69784393e+01 9.73929977e+01 9.74912415e+01 9.76443558e+01 9.77815552e+01 9.76877136e+01 9.80987167e+01 9.86889343e+01 9.89437790e+01 9.91350250e+01 9.97230301e+01 1.00009529e+02 9.98187256e+01 9.92857361e+01 9.94010925e+01 9.90777893e+01 9.95848694e+01 9.96450272e+01 9.92380676e+01 9.93816528e+01 9.99204178e+01 9.99618912e+01 1.00302147e+02 1.00427536e+02 1.01075638e+02 1.01166916e+02 1.01993874e+02 1.02511444e+02 1.01988586e+02 1.01617607e+02 1.01290474e+02 1.02076599e+02 1.02085487e+02 1.01974144e+02 1.01028053e+02 1.00864120e+02 1.08783104e+02 8.51793976e+01 1.04329033e+02 -2.40378571e+02 -8.76062012e+02 6.90583057e+03 -7.67390438e+05 -561579264. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -25443220. 1.54065350e+06 1.01571344e+05 -3.46078094e+02 -1.29819153e+02 1.08687538e+02 1.05481277e+02 9.78236465e+01 5.14425392e+01 4.89636688e+01 8.26068573e+01 9.73199615e+01 1.12451263e+02 1.04816833e+02 1.02786278e+02 1.02903175e+02 1.02516556e+02 1.02292740e+02 1.01846497e+02 1.00768333e+02 1.01009560e+02 9.97623215e+01 9.98872910e+01 9.95718002e+01 1.00093140e+02 1.12939575e+02 1.30382599e+02 1.40611008e+02 1.19884026e+02 9.67085266e+01 1.02476410e+02 1.04921791e+02 9.58908997e+01 7.78678284e+01 7.17543335e+01 7.18816452e+01 8.35729828e+01 9.54866867e+01 1.00996399e+02 1.09061630e+02 1.18085419e+02 1.12366898e+02 1.10442764e+02 1.16341614e+02 1.15269814e+02 1.14449402e+02 9.56050873e+01 8.37894821e+01 8.65342865e+01 9.24448547e+01 9.61770782e+01 9.73400192e+01 9.66548843e+01 9.53593216e+01 9.47915344e+01 9.21320267e+01 8.99360657e+01 8.71039352e+01 8.60089188e+01 8.30250092e+01 8.20607224e+01 8.78899536e+01 9.27140503e+01 9.22689743e+01 9.35724258e+01 9.71577377e+01 9.78062592e+01 9.78459091e+01 9.55465622e+01 9.45184097e+01 9.31638565e+01 9.15809860e+01 9.11193314e+01 9.11525803e+01 9.01858063e+01 8.98365326e+01 8.78774338e+01 8.76250534e+01 8.77059250e+01 8.87563629e+01 8.89375916e+01 8.89366302e+01 8.91318359e+01 8.86542664e+01 8.79247589e+01 8.75771408e+01 8.76256561e+01 8.71711731e+01 8.65442047e+01 8.65652618e+01 8.62749252e+01 8.63054428e+01 8.62298431e+01 8.47474823e+01 8.36681519e+01 8.25493393e+01 8.36885071e+01 8.38488312e+01 8.42586060e+01 8.42325974e+01 8.23318863e+01 8.15673141e+01 8.01493607e+01 8.06783600e+01 8.11321259e+01 8.16812820e+01 8.10693359e+01 8.04833298e+01 7.99505539e+01 7.80772400e+01 7.77926636e+01 7.72336426e+01 7.67566223e+01 7.66759872e+01 7.67569199e+01 7.70154495e+01 7.68747482e+01 7.62163544e+01 7.63050537e+01 7.58014526e+01 7.48196716e+01 7.40755310e+01 7.31814423e+01 7.34199829e+01 7.40312576e+01 7.34053879e+01 7.29850616e+01 7.18348694e+01 7.09751968e+01 7.01319580e+01 6.98448563e+01 6.93401108e+01 6.92110748e+01 6.88212967e+01 6.87426605e+01 6.81024170e+01 6.75423660e+01 6.67018280e+01 6.67091751e+01 6.61504898e+01 6.53152084e+01 6.46595459e+01 6.44926147e+01 6.46791382e+01 6.37130241e+01 6.28846359e+01 6.27784462e+01 6.17681885e+01 6.13358765e+01 6.14421959e+01 6.05128517e+01 6.00242729e+01 5.98279610e+01 5.84821205e+01 5.83185272e+01 5.82993774e+01 5.76431503e+01 5.78169785e+01 5.67301826e+01 5.55489998e+01 5.59043846e+01 5.52195015e+01 5.47198143e+01 5.46209564e+01 5.38544197e+01 5.27336655e+01 5.18185539e+01 5.19216499e+01 5.10722885e+01 5.00907974e+01 4.99424019e+01 4.96222572e+01 4.90098763e+01 4.88319855e+01 4.81165504e+01 4.71696777e+01 4.60139847e+01 4.58799171e+01 4.61322479e+01 4.53272705e+01 4.49206429e+01 4.46769524e+01 4.35167961e+01 4.16816254e+01 4.14783936e+01 4.09453316e+01 4.14903641e+01 4.16217957e+01 4.05066528e+01 3.94687119e+01 3.98530273e+01 3.93226357e+01 3.75562439e+01 3.71406555e+01 3.63973160e+01 3.54331818e+01 3.50071983e+01 3.52219582e+01 3.47764015e+01 3.36234779e+01 3.29646111e+01 3.33154678e+01 3.18555508e+01 3.04276810e+01 2.93055725e+01 2.92194328e+01 2.97737808e+01 2.97380276e+01 2.92988148e+01 2.86879234e+01 2.87293549e+01 2.87688808e+01 2.81202469e+01 2.57612095e+01 2.43971291e+01 2.30488682e+01 2.37071648e+01 2.37238636e+01 2.25236568e+01 2.02867870e+01 2.07866631e+01 2.07314491e+01 2.03708115e+01 1.78964653e+01 1.86007004e+01 1.92021961e+01 2.08191032e+01 1.98677807e+01 1.74148293e+01 1.64392204e+01 1.55470629e+01 1.53667707e+01 1.43722992e+01 1.45834436e+01 1.39418125e+01 1.29648600e+01 1.19206200e+01 1.07152309e+01 9.09480667e+00 9.63907337e+00 1.02064390e+01 1.00804319e+01 8.47177124e+00 6.88603687e+00 7.89105368e+00 8.78597736e+00 7.03485298e+00 5.88527012e+00 4.03007698e+00 4.19723988e+00 4.58845758e+00 4.92302799e+00 2.97697544e+00 1.87031770e+00 1.23867464e+00 6.01673424e-01 3.02442878e-01 9.52385664e-02 -3.38144839e-01 -2.58628774e+00 -4.08318043e+00 -4.74851036e+00 -5.64291143e+00 -6.00724745e+00 -6.92090511e+00 -7.02932549e+00 -7.40517139e+00 -6.90544987e+00 -6.90801954e+00 -8.38777065e+00 -9.62357140e+00 -9.88830185e+00 -1.03344965e+01 -1.09153061e+01 -1.21100101e+01 -1.30671263e+01 -1.32067728e+01 -1.46362553e+01 -1.50413303e+01 -1.55911856e+01 -1.64216824e+01 -1.67791252e+01 -1.71181145e+01 -1.79284267e+01 -1.82160454e+01 -1.84551830e+01 -1.78756237e+01 -1.89291668e+01 -1.95365086e+01 -2.15390434e+01 -2.27071972e+01 -2.34658737e+01 -2.35246353e+01 -2.44897938e+01 -2.43033276e+01 -2.41844215e+01 -2.46756191e+01 -2.62343903e+01 -2.67779198e+01 -2.71765919e+01 -2.87512531e+01 -2.94542847e+01 -3.07593307e+01 -2.98576698e+01 -3.05288773e+01 -3.04071503e+01 -3.09638081e+01 -3.16243153e+01 -3.23936768e+01 -3.37734566e+01 -3.37466202e+01 -3.47982712e+01 -3.58664856e+01 -3.67700844e+01 -3.62862358e+01 -3.71984940e+01 -3.73468742e+01 -3.81749268e+01 -3.78454666e+01 -3.86370201e+01 -4.00845413e+01 -4.07322578e+01 -4.14557648e+01 -4.13388596e+01 -4.18774452e+01 -4.17799835e+01 -4.30449638e+01 -4.39761429e+01 -4.45472641e+01 -4.45654755e+01 -4.54307556e+01 -4.62424431e+01 -4.75060425e+01 -4.84630699e+01 -4.87867050e+01 -4.87111740e+01 -4.87197800e+01 -4.87729530e+01 -4.94365196e+01 -5.02740898e+01 -5.10359039e+01 -5.14979286e+01 -5.18527832e+01 -5.24982262e+01 -5.31258926e+01 -5.31872787e+01 -5.38214645e+01 -5.41240082e+01 -5.46436729e+01 -5.57159042e+01 -5.64925232e+01 -5.71250992e+01 -5.70290184e+01 -5.70810890e+01 -5.76641006e+01 -5.83306541e+01 -5.93294716e+01 -5.97614479e+01 -6.06627045e+01 -6.08967590e+01 -6.11339149e+01 -6.13450661e+01 -6.17892723e+01 -6.24075317e+01 -6.31880798e+01 -6.39513016e+01 -6.41837692e+01 -6.46089554e+01 -6.51233139e+01 -6.56264877e+01 -6.61248779e+01 -6.65960007e+01 -6.69244995e+01 -6.72474136e+01 -6.74397354e+01 -6.81197205e+01 -6.87241135e+01 -6.90625687e+01 -6.95698471e+01 -7.01529083e+01 -7.05054245e+01 -7.08796310e+01 -7.13501434e+01 -7.19747620e+01 -7.23360443e+01 -7.26769333e+01 -7.31624527e+01 -7.37461395e+01 -7.40981293e+01 -7.44848785e+01 -7.48850479e+01 -7.53426971e+01 -7.57911682e+01 -7.62581406e+01 -7.66663208e+01 -7.70402985e+01 -7.73225555e+01 -7.77496872e+01 -7.82024689e+01 -7.86371460e+01 -7.90210114e+01 -7.94275513e+01 -7.97645874e+01 -8.01514359e+01 -8.05453720e+01 -8.09949036e+01 -8.14009857e+01 -8.17899933e+01 -8.21729660e+01 -8.25733566e+01 -8.29023819e+01 -8.31888962e+01 -8.35287933e+01 -8.38640518e+01 -8.41878967e+01 -8.44907303e+01 -8.48477936e+01 -8.51037292e+01 -8.54376144e+01 -8.57615814e+01 -8.60362244e+01 -8.64021454e+01 -8.67133331e+01 -8.71207199e+01 -8.73613739e+01 -8.75999908e+01 -8.79742813e+01 -8.83168564e+01 -8.86044388e+01 -8.89751968e+01 -8.92355270e+01 -8.93418198e+01 -8.94373474e+01 -8.98640137e+01 -9.02491684e+01 -9.04287033e+01 -9.09689865e+01 -9.13878479e+01 -9.14906387e+01 -9.13097000e+01 -9.15067902e+01 -9.18793030e+01 -9.23962860e+01 -9.30968170e+01 -9.33243713e+01 -9.34416656e+01 -9.37507629e+01 -9.39870605e+01 -9.39904404e+01 -9.42521973e+01 -9.41492004e+01 -9.43244629e+01 -9.49361267e+01 -9.55394592e+01 -9.57753143e+01 -9.57961807e+01 -9.61017532e+01 -9.64368362e+01 -9.62844849e+01 -9.60153580e+01 -9.60228577e+01 -9.63570023e+01 -9.70242157e+01 -9.72518158e+01 -9.75438843e+01 -9.75904999e+01 -9.82062149e+01 -9.82764511e+01 -9.82743988e+01 -9.83803406e+01 -9.85247421e+01 -9.76903687e+01 -9.82927551e+01 -9.85599976e+01 -9.83893356e+01 -9.79035645e+01 -9.86091843e+01 -9.90167923e+01 -9.94983673e+01 -9.83269653e+01 -9.86418381e+01 -9.98746643e+01 -1.00580620e+02 -1.00732513e+02 -1.00328705e+02 -1.00485718e+02 -1.00314278e+02 -1.00394440e+02 -1.00969337e+02 -1.01096123e+02 -1.00555740e+02 -1.00324463e+02 -1.00368240e+02 -1.00611534e+02 -1.01279175e+02 -1.02306129e+02 -1.02521790e+02 -1.01659508e+02 -1.01296059e+02 -1.01434631e+02 -1.01428665e+02 -1.02413696e+02 -1.03537903e+02 -1.03821228e+02 -1.02479530e+02 -1.02634140e+02 -1.03578789e+02 -1.04308395e+02 -1.04411789e+02 -1.03635849e+02 -1.02933594e+02 -1.01944946e+02 -1.01951042e+02 -1.02537155e+02 -1.02960472e+02 -1.02465103e+02 -1.01410492e+02 -1.01404518e+02 -1.01307220e+02 -1.01107018e+02 -1.00639305e+02 -1.00978439e+02 -1.01287178e+02 -1.02817345e+02 -1.03255791e+02 -1.03218903e+02 -1.01682304e+02 -1.01973854e+02 -1.02720413e+02 -1.02604767e+02 -1.01158043e+02 -9.99484024e+01 -1.00436539e+02 -9.96869202e+01 -1.00931763e+02 -1.01287430e+02 -1.01460693e+02 -1.00724335e+02 -1.01139244e+02 -1.00872086e+02 -1.00065369e+02 -9.94776077e+01 -1.00997810e+02 -1.01650665e+02 -1.00678581e+02 -9.82123795e+01 -9.80902328e+01 -9.85478058e+01 -9.96485748e+01 -9.98266907e+01 -1.00663574e+02 -1.00786469e+02 -1.00618370e+02 -9.86463623e+01 -9.86105194e+01 -9.82026596e+01 -9.65943222e+01 -9.79279175e+01 -9.63915482e+01 -9.75305557e+01 -9.67804947e+01 -9.76018143e+01 -9.69614182e+01 -9.61758194e+01 -9.63918839e+01 -9.56801224e+01 -9.49399490e+01 -9.49641266e+01 -9.49543533e+01 -9.32787476e+01 -9.44957199e+01 -9.46944046e+01 -9.54996490e+01 -9.48214264e+01 -9.56659012e+01 -9.55112076e+01 -9.40580902e+01 -9.30684204e+01 -9.19666290e+01 -9.28525238e+01 -9.20724945e+01 -9.24277267e+01 -9.21100082e+01 -9.09845505e+01 -9.01230087e+01 -9.11994858e+01 -9.10622330e+01 -8.98160172e+01 -8.78166580e+01 -8.73383255e+01 -8.71476593e+01 -8.81836929e+01 -8.87262802e+01 -8.86751099e+01 -8.83546677e+01 -8.77790833e+01 -8.72934265e+01 -8.68102417e+01 -8.69927444e+01 -8.68693619e+01 -8.68254318e+01 -8.69759369e+01 -8.57543488e+01 -8.57740707e+01 -8.57791138e+01 -8.41388245e+01 -8.32259140e+01 -8.13537140e+01 -8.18901978e+01 -8.27312241e+01 -8.36128082e+01 -8.35915222e+01 -8.15918961e+01 -8.14987106e+01 -7.98603210e+01 -8.04992523e+01 -8.01300888e+01 -8.05418320e+01 -8.01764069e+01 -7.94211807e+01 -7.95029907e+01 -7.76845551e+01 -7.72504425e+01 -7.74455414e+01 -7.70417099e+01 -7.63312454e+01 -7.55108566e+01 -7.62305298e+01 -7.66621628e+01 -7.55162125e+01 -7.54947128e+01 -7.50044861e+01 -7.46570129e+01 -7.39932251e+01 -7.27765656e+01 -7.19721298e+01 -7.29346695e+01 -7.32025681e+01 -7.23676987e+01 -7.09758759e+01 -7.07331467e+01 -7.04517975e+01 -7.00594940e+01 -6.92943649e+01 -6.85580444e+01 -6.83973999e+01 -6.84747772e+01 -6.75945663e+01 -6.73701172e+01 -6.61577377e+01 -6.64771271e+01 -6.57976990e+01 -6.50755005e+01 -6.45533905e+01 -6.44524002e+01 -6.43419037e+01 -6.31112556e+01 -6.25173950e+01 -6.25246582e+01 -6.19646835e+01 -6.14518509e+01 -6.08600273e+01 -5.97896957e+01 -5.99278679e+01 -5.95817337e+01 -5.83817062e+01 -5.84707375e+01 -5.81535912e+01 -5.73663902e+01 -5.76114006e+01 -5.68875275e+01 -5.56836548e+01 -5.53783646e+01 -5.49801331e+01 -5.41113510e+01 -5.38825798e+01 -5.34126091e+01 -5.21282578e+01 -5.19803963e+01 -5.19734612e+01 -5.09046631e+01 -5.01401978e+01 -5.01265144e+01 -5.01427956e+01 -4.93910561e+01 -4.87764893e+01 -4.78822556e+01 -4.68535767e+01 -4.58042145e+01 -4.56489029e+01 -4.57930260e+01 -4.54360046e+01 -4.52802200e+01 -4.43505516e+01 -4.30882988e+01 -4.15341988e+01 -4.17992363e+01 -4.15178108e+01 -4.16907539e+01 -4.15415688e+01 -4.00219078e+01 -3.93821983e+01 -3.94973183e+01 -3.85471268e+01 -3.74240799e+01 -3.60492210e+01 -3.57498856e+01 -3.63106422e+01 -3.49098930e+01 -3.44765244e+01 -3.37995300e+01 -3.27254333e+01 -3.18698006e+01 -3.16450310e+01 -3.11904049e+01 -3.01907215e+01 -2.93800392e+01 -2.94773102e+01 -2.95875893e+01 -2.91629753e+01 -2.88076305e+01 -2.78476887e+01 -2.82900734e+01 -2.82745056e+01 -2.72249603e+01 -2.52296085e+01 -2.43217754e+01 -2.24321785e+01 -2.29625359e+01 -2.25737667e+01 -2.21022606e+01 -2.05457573e+01 -2.11404686e+01 -2.00198803e+01 -1.99729424e+01 -1.77323055e+01 -1.82342987e+01 -1.92683506e+01 -2.09329643e+01 -1.96870422e+01 -1.69443455e+01 -1.73077736e+01 -1.62086792e+01 -1.50076180e+01 -1.50377264e+01 -1.39001446e+01 -1.23705664e+01 -1.26663914e+01 -1.14421844e+01 -1.04239464e+01 -1.04831543e+01 -1.09104509e+01 -1.12093897e+01 -1.04799843e+01 -9.11992455e+00 -8.31233406e+00 -7.45384359e+00 -7.63131857e+00 -6.27352428e+00 -5.53714800e+00 -3.56341529e+00 -3.74826431e+00 -3.48422146e+00 -4.00232124e+00 -2.80839109e+00 -1.30869687e+00 -6.98546886e-01 2.56751627e-01 9.57647383e-01 4.45736676e-01 8.90078604e-01 2.98652053e+00 3.89793563e+00 4.99851465e+00 5.71999550e+00 6.36621046e+00 7.14974213e+00 7.91072941e+00 8.69351959e+00 8.06792450e+00 7.98865891e+00 8.03369713e+00 9.17541313e+00 9.62670708e+00 1.06761856e+01 1.09661388e+01 1.24052191e+01 1.40553780e+01 1.38565550e+01 1.55361052e+01 1.53676882e+01 1.61885338e+01 1.66399136e+01 1.72048111e+01 1.75251732e+01 1.85527611e+01 1.92535381e+01 1.63722324e+01 -4.19666290e+00 -4.36721573e+01 -3.14853592e+01 1.34153118e+01 2.50882874e+01 2.57503281e+01 2.41516590e+01 2.32471447e+01 2.44004135e+01 2.78056870e+01 4.38929138e+01 2.87627296e+01 -2.14067047e+02 -4.45435516e+02 -6.67891250e+06 134192872. 0. 0. 0. 0. 41271896. 41271896. 41271896. 0. 0. 0. -10370003. -1.81799725e+06 7.94732812e+04 -1.27769043e+03 -5.63828857e+02 -1.16991432e+02 -8.66778870e+01 -1.32107025e+02 -1.29604233e+02 -4.26925774e+01 2.52731152e+01 3.97091751e+01 4.24025612e+01 4.27663345e+01 4.40927658e+01 4.50034790e+01 4.56086922e+01 4.57309914e+01 4.64374390e+01 4.47022095e+01 2.96729908e+01 1.33577509e+01 2.65191593e+01 4.35019264e+01 4.87458992e+01 5.05704613e+01 5.34047661e+01 6.69044800e+01 9.30553818e+01 9.07052994e+01 6.24456673e+01 3.89019852e+01 4.98687553e+01 6.88014069e+01 6.16951485e+01 5.44916763e+01 5.31815834e+01 5.38902245e+01 5.60386391e+01 5.74456520e+01 5.77346954e+01 5.82169113e+01 5.83026924e+01 5.89063911e+01 5.98735580e+01 6.01070328e+01 6.09591904e+01 6.13405113e+01 6.17805634e+01 6.19567947e+01 6.24233055e+01 6.32399101e+01 6.37558174e+01 6.44118576e+01 6.48775864e+01 6.54358673e+01 6.59001236e+01 6.63818741e+01 6.67748718e+01 6.72087250e+01 6.74547653e+01 6.80204544e+01 6.82848129e+01 6.87223816e+01 6.93661118e+01 6.99531403e+01 7.06484680e+01 7.11770782e+01 7.13796463e+01 7.17632446e+01 7.22504578e+01 7.29375687e+01 7.34748077e+01 7.40197372e+01 7.44657516e+01 7.49655762e+01 7.53797073e+01 7.57810440e+01 7.62100143e+01 7.67690353e+01 7.73268814e+01 7.78060226e+01 7.82743683e+01 7.88995209e+01 7.96022797e+01 7.99628067e+01 8.02287064e+01 8.06560211e+01 8.10963058e+01 8.14984436e+01 8.19150772e+01 8.23924255e+01 8.27598801e+01 8.30542755e+01 8.20723114e+01 3.21845605e+03 4.20871811e+01 2.74759159e+01 2.77400494e+01 2.79917068e+01 2.82386456e+01 2.85035896e+01 2.87459469e+01 2.89779606e+01 2.92555237e+01 2.95264263e+01 2.98439693e+01 3.00491734e+01 3.02643108e+01 3.05293961e+01 3.07670593e+01 3.10293617e+01 3.12664032e+01 3.14906845e+01 3.17079220e+01 3.19835072e+01 3.22532425e+01 3.24871063e+01 3.27293129e+01 3.29850845e+01 3.32050285e+01 3.34783325e+01 3.37307205e+01 3.39743347e+01 3.42044525e+01 3.45176506e+01 3.47129860e+01 3.48858757e+01 3.50589371e+01 3.53625565e+01 3.56615334e+01 3.60116043e+01 3.62042351e+01 3.64559402e+01 3.66428413e+01 3.68239479e+01 3.70227013e+01 3.72848511e+01 3.76399384e+01 3.78189926e+01 3.80531616e+01 3.83146057e+01 3.84992142e+01 3.86480141e+01 3.89629135e+01 3.91728134e+01 3.93575630e+01 3.95427971e+01 3.97862740e+01 3.99160042e+01 4.02056732e+01 4.05888481e+01 4.07231750e+01 4.10002594e+01 4.10646629e+01 4.12386208e+01 4.13982277e+01 4.16047745e+01 4.19682770e+01 4.19679604e+01 4.21588745e+01 4.26516418e+01 4.28268967e+01 4.29668732e+01 4.31017952e+01 4.30320206e+01 4.33490944e+01 4.36466904e+01 4.36525192e+01 4.36206284e+01 4.39419594e+01 4.45413895e+01 4.44792290e+01 4.49254837e+01 4.46542511e+01 4.50962448e+01 4.48505898e+01 4.51750603e+01 4.82075386e+01 4.65820923e+01 -4.77655640e+01 -1.19169968e+02 1.37150955e+02 -3.30839661e+02 -8.64732056e+02 7.00750732e+03 -1.58558975e+06 -1123158528. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 159610656. -2.11236572e+03 -3.57046051e+02 1.06564392e+02 -1.62736969e+02 -7.84421310e+01 5.46455231e+01 5.34223785e+01 4.68444519e+01 3.81398125e+01 4.09137497e+01 4.12539902e+01 4.72182770e+01 5.42756271e+01 5.12305984e+01 5.09740677e+01 5.01804199e+01 4.99670601e+01 5.05918770e+01 5.05822601e+01 5.10350723e+01 5.13052902e+01 5.17989502e+01 5.15939064e+01 5.10122414e+01 5.09557152e+01 5.55279617e+01 5.96755829e+01 6.01321716e+01 5.51305084e+01 5.08999825e+01 5.14679031e+01 5.09124222e+01 4.77730637e+01 4.33232346e+01 4.22502251e+01 4.29001732e+01 4.76623917e+01 5.23014717e+01 5.39356079e+01 5.59855042e+01 5.81625481e+01 5.65820541e+01 5.62727203e+01 5.70500565e+01 5.67520180e+01 5.56525345e+01 5.01216812e+01 4.68401985e+01 4.86330032e+01 5.06495209e+01 5.18269615e+01 5.19068718e+01 5.21652603e+01 5.23523178e+01 5.21018105e+01 5.12811356e+01 5.10230980e+01 5.04884224e+01 4.98890190e+01 4.83375053e+01 4.89852982e+01 5.13189964e+01 5.32273407e+01 5.30011673e+01 5.38556786e+01 5.46248856e+01 5.46090546e+01 5.42269745e+01 5.36377716e+01 5.29302177e+01 5.23407555e+01 5.17716599e+01 5.23696251e+01 5.19417801e+01 5.24701576e+01 5.15919456e+01 5.14252548e+01 5.06092606e+01 5.10849495e+01 5.18246117e+01 5.24423256e+01 5.24744072e+01 5.21695518e+01 5.15523529e+01 5.07031784e+01 5.10186577e+01 5.16663895e+01 5.17195930e+01 5.18154221e+01 5.20191498e+01 5.17834091e+01 5.12096214e+01 5.07641106e+01 5.10459061e+01 5.11798363e+01 5.14509315e+01 5.14409676e+01 5.18821449e+01 5.14311447e+01 5.12307816e+01 5.07844925e+01 5.09979744e+01 5.08043633e+01 5.06718521e+01 5.07102470e+01 5.05615730e+01 5.07463036e+01 5.07575760e+01 5.06855469e+01 4.99272652e+01 4.99409637e+01 4.99764977e+01 5.02358818e+01 5.00443115e+01 4.98456039e+01 4.98899078e+01 5.01621437e+01 4.99698219e+01 4.98460808e+01 4.97032471e+01 4.97377777e+01 4.94291687e+01 4.93145180e+01 4.92182808e+01 4.94125557e+01 4.91715317e+01 4.90239372e+01 4.86725540e+01 4.85723915e+01 4.81374435e+01 4.79793663e+01 4.77482948e+01 4.78282890e+01 4.77005005e+01 4.77585602e+01 4.75111809e+01 4.73705101e+01 4.70832710e+01 4.71140633e+01 4.69639664e+01 4.67759933e+01 4.65871506e+01 4.65276756e+01 4.65007133e+01 4.62327232e+01 4.60769005e+01 4.59774399e+01 4.56442528e+01 4.55678482e+01 4.55841637e+01 4.52817192e+01 4.51731796e+01 4.50955353e+01 4.46575089e+01 4.46357994e+01 4.46544189e+01 4.43540306e+01 4.43407059e+01 4.41641884e+01 4.38108673e+01 4.37297058e+01 4.34381638e+01 4.33290253e+01 4.33403854e+01 4.31914101e+01 4.30589447e+01 4.27144241e+01 4.25583572e+01 4.20628281e+01 4.18351097e+01 4.15879097e+01 4.14814987e+01 4.13051071e+01 4.11792908e+01 4.09426918e+01 4.07110062e+01 4.01587219e+01 4.00042229e+01 4.00481262e+01 3.99833565e+01 3.97934875e+01 4.00034447e+01 3.95142632e+01 3.89478035e+01 3.82698174e+01 3.82063484e+01 3.82664261e+01 3.85879364e+01 3.81082611e+01 3.78880730e+01 3.76797333e+01 3.73587494e+01 3.70004807e+01 3.67990112e+01 3.67332802e+01 3.61792564e+01 3.61216812e+01 3.60511284e+01 3.58345680e+01 3.53619804e+01 3.49752922e+01 3.49049606e+01 3.47615471e+01 3.45089073e+01 3.41656342e+01 3.36752625e+01 3.36864395e+01 3.39388542e+01 3.36516304e+01 3.34794731e+01 3.25281792e+01 3.24205055e+01 3.24412308e+01 3.18932266e+01 3.19414043e+01 3.11333942e+01 3.13957787e+01 3.19530678e+01 3.20278015e+01 3.10271320e+01 3.05751266e+01 3.00899887e+01 3.03047028e+01 2.97038879e+01 2.89826279e+01 2.82731075e+01 2.87500248e+01 2.93376141e+01 2.83446388e+01 2.89953079e+01 2.80977478e+01 2.83509064e+01 2.77531624e+01 2.82284222e+01 2.83103981e+01 2.69979057e+01 2.65259266e+01 2.57459164e+01 2.54305229e+01 2.46776543e+01 2.42285271e+01 2.42666435e+01 2.41187840e+01 2.39957390e+01 2.43228951e+01 2.45645370e+01 2.42040195e+01 2.39085007e+01 2.32403278e+01 2.29909821e+01 2.27163029e+01 2.23717747e+01 2.16006927e+01 2.12662983e+01 2.04315910e+01 2.00473347e+01 2.00883865e+01 2.02789860e+01 2.04474335e+01 1.91432037e+01 1.90291576e+01 1.87775764e+01 1.92534866e+01 1.89550343e+01 1.75343246e+01 1.73630199e+01 1.68926601e+01 1.71513901e+01 1.72834225e+01 1.65237312e+01 1.67503281e+01 1.57699957e+01 1.52854080e+01 1.51842432e+01 1.48315048e+01 1.48787851e+01 1.48476267e+01 1.49313049e+01 1.45362167e+01 1.33812504e+01 1.30020666e+01 1.27814531e+01 1.22395496e+01 1.17392120e+01 1.10127878e+01 1.10853119e+01 1.08718405e+01 1.03712244e+01 1.01504354e+01 1.01485176e+01 9.82820034e+00 9.40837097e+00 9.08320808e+00 8.90529156e+00 8.55580330e+00 8.24988079e+00 8.10324669e+00 7.49738312e+00 7.15177298e+00 6.85140610e+00 6.73851538e+00 6.03380156e+00 5.32751322e+00 5.48489189e+00 5.38696432e+00 5.34153795e+00 4.92444611e+00 4.36161423e+00 4.13025331e+00 3.97524834e+00 3.60185838e+00 2.88941813e+00 2.67384005e+00 2.39861012e+00 2.22501445e+00 1.27728784e+00 1.58309877e+00 1.49984467e+00 1.66613948e+00 1.10095704e+00 5.72471082e-01 -5.54857627e-02 -5.56951344e-01 -7.87792265e-01 -9.44272280e-01 -1.24794245e+00 -1.88167465e+00 -2.36211371e+00 -2.32449436e+00 -2.55792713e+00 -2.63442492e+00 -3.44074655e+00 -3.99894524e+00 -4.64990854e+00 -4.66982889e+00 -4.60464621e+00 -4.65444136e+00 -4.86881781e+00 -5.34935331e+00 -5.94180012e+00 -6.53846216e+00 -6.79322815e+00 -6.91491365e+00 -7.28311682e+00 -7.52908802e+00 -7.69434023e+00 -8.04936886e+00 -8.54314995e+00 -9.01117420e+00 -9.27015305e+00 -9.52491379e+00 -9.55434227e+00 -9.86705875e+00 -1.00026922e+01 -1.05620394e+01 -1.09739485e+01 -1.13676710e+01 -1.15953913e+01 -1.19597464e+01 -1.21988268e+01 -1.24550371e+01 -1.27513266e+01 -1.30196543e+01 -1.33250637e+01 -1.37149525e+01 -1.41310759e+01 -1.43592806e+01 -1.46087475e+01 -1.48096485e+01 -1.51593781e+01 -1.55357256e+01 -1.58413677e+01 -1.60789585e+01 -1.63471718e+01 -1.65722370e+01 -1.69225273e+01 -1.72273540e+01 -1.75502911e+01 -1.78601990e+01 -1.82088165e+01 -1.84401913e+01 -1.87155704e+01 -1.90195103e+01 -1.93874378e+01 -1.96650028e+01 -1.99603214e+01 -2.02732334e+01 -2.06073723e+01 -2.08617039e+01 -2.11618347e+01 -2.14331398e+01 -2.17436752e+01 -2.20317593e+01 -2.23331070e+01 -2.26157951e+01 -2.28971710e+01 -2.31498833e+01 -2.34518452e+01 -2.37542133e+01 -2.40438766e+01 -2.43320637e+01 -2.46127453e+01 -2.48901806e+01 -2.51705284e+01 -2.54530754e+01 -2.57450409e+01 -2.60339985e+01 -2.63191071e+01 -2.65966187e+01 -2.68780537e+01 -2.71543465e+01 -2.74153938e+01 -2.76805401e+01 -2.79499836e+01 -2.82207165e+01 -2.84913445e+01 -2.87631435e+01 -2.90097790e+01 -2.92679005e+01 -2.95389938e+01 -2.98036709e+01 -3.00718193e+01 -3.03264141e+01 -3.06073589e+01 -3.08433819e+01 -3.10801010e+01 -3.13224468e+01 -3.15760326e+01 -3.18388100e+01 -3.21146088e+01 -3.23541870e+01 -3.25643158e+01 -3.27519226e+01 -3.30186157e+01 -3.33102570e+01 -3.35133247e+01 -3.38185654e+01 -3.41842232e+01 -3.43420296e+01 -3.44481544e+01 -3.46191483e+01 -3.49115601e+01 -3.51814880e+01 -3.55343323e+01 -3.57701607e+01 -3.60411835e+01 -3.62532616e+01 -3.64495316e+01 -3.66463318e+01 -3.69171371e+01 -3.70573273e+01 -3.72546806e+01 -3.76399879e+01 -3.78977852e+01 -3.80819016e+01 -3.82219849e+01 -3.84995117e+01 -3.87632332e+01 -3.88609161e+01 -3.89554176e+01 -3.92316551e+01 -3.94310722e+01 -3.97543030e+01 -4.00872154e+01 -4.01558189e+01 -4.04424782e+01 -4.04408836e+01 -4.05512619e+01 -4.07005386e+01 -4.10398331e+01 -4.14403915e+01 -4.13785782e+01 -4.17019768e+01 -4.21605721e+01 -4.24296722e+01 -4.24218559e+01 -4.26025314e+01 -4.26120071e+01 -4.29755936e+01 -4.29433670e+01 -4.28967476e+01 -4.31163559e+01 -4.34101448e+01 -4.38776131e+01 -4.38477058e+01 -4.43587723e+01 -4.43450356e+01 -4.46263275e+01 -4.47293129e+01 -4.50551071e+01 -4.51646500e+01 -4.48937111e+01 -4.51721573e+01 -4.52176285e+01 -4.55605392e+01 -4.56411743e+01 -4.59143982e+01 -4.58463783e+01 -4.59666557e+01 -4.60472145e+01 -4.63298988e+01 -4.68002357e+01 -4.75446053e+01 -4.76493149e+01 -4.73903313e+01 -4.73702393e+01 -4.78158302e+01 -4.79745216e+01 -4.81834488e+01 -4.81827240e+01 -4.77036324e+01 -4.76806068e+01 -4.79365578e+01 -4.83648987e+01 -4.89091682e+01 -4.85048180e+01 -4.87161827e+01 -4.89314919e+01 -4.93309326e+01 -4.93240929e+01 -4.85277138e+01 -4.88242760e+01 -4.90896378e+01 -5.00342293e+01 -5.06650467e+01 -5.03370628e+01 -5.05515289e+01 -4.98054962e+01 -4.98641968e+01 -5.02800941e+01 -4.99620552e+01 -5.03063583e+01 -5.06300316e+01 -5.11995811e+01 -5.15265465e+01 -5.12059364e+01 -5.12427139e+01 -5.10106468e+01 -5.08443604e+01 -5.06783485e+01 -4.99243507e+01 -5.01969872e+01 -5.02597542e+01 -5.08249893e+01 -5.09608269e+01 -5.12547874e+01 -5.13114548e+01 -5.14424706e+01 -5.16827202e+01 -5.18799667e+01 -5.19032745e+01 -5.19316444e+01 -5.21781998e+01 -5.15377274e+01 -5.16066170e+01 -5.13757019e+01 -5.16062737e+01 -5.17799835e+01 -5.13015556e+01 -5.16252136e+01 -5.20764885e+01 -5.21503983e+01 -5.19721909e+01 -5.15134506e+01 -5.22251511e+01 -5.23720894e+01 -5.20473061e+01 -5.17104721e+01 -5.21505547e+01 -5.20449409e+01 -5.22670860e+01 -5.17092476e+01 -5.26687508e+01 -5.28725204e+01 -5.36505051e+01 -5.32084732e+01 -5.30806541e+01 -5.25614128e+01 -5.21190033e+01 -5.22429466e+01 -5.22845612e+01 -5.23443565e+01 -5.20442467e+01 -5.17621422e+01 -5.22461319e+01 -5.22513924e+01 -5.27655678e+01 -5.18330574e+01 -5.13766747e+01 -5.08583641e+01 -5.11045761e+01 -5.18153725e+01 -5.24871216e+01 -5.24629173e+01 -5.22201157e+01 -5.15063362e+01 -5.07747688e+01 -5.08932228e+01 -5.14874153e+01 -5.16632690e+01 -5.17441521e+01 -5.18958130e+01 -5.17029495e+01 -5.10322380e+01 -5.05359268e+01 -5.06258583e+01 -5.07457237e+01 -5.11000061e+01 -5.10035744e+01 -5.15377731e+01 -5.11970024e+01 -5.11229630e+01 -5.06556358e+01 -5.08717422e+01 -5.04426956e+01 -5.04998512e+01 -5.04869957e+01 -5.02524185e+01 -5.02868385e+01 -5.04840317e+01 -5.03698769e+01 -4.95978088e+01 -4.97142410e+01 -4.99944382e+01 -5.01462669e+01 -4.98118782e+01 -4.94843826e+01 -4.96124496e+01 -4.99734001e+01 -4.96541290e+01 -4.96266518e+01 -4.96281586e+01 -4.95445633e+01 -4.91801338e+01 -4.91137619e+01 -4.87775803e+01 -4.91745224e+01 -4.91049767e+01 -4.88016701e+01 -4.84158783e+01 -4.83036957e+01 -4.80891571e+01 -4.80849075e+01 -4.78002014e+01 -4.76281166e+01 -4.75544128e+01 -4.76816521e+01 -4.73847885e+01 -4.72886810e+01 -4.68853531e+01 -4.69344406e+01 -4.68439560e+01 -4.68440857e+01 -4.65988922e+01 -4.64875221e+01 -4.64432983e+01 -4.61105309e+01 -4.59347191e+01 -4.58371124e+01 -4.55777245e+01 -4.54802475e+01 -4.53974915e+01 -4.50248909e+01 -4.50652847e+01 -4.50086327e+01 -4.44869080e+01 -4.45121193e+01 -4.45213547e+01 -4.42555046e+01 -4.42258186e+01 -4.40929565e+01 -4.37937164e+01 -4.36379089e+01 -4.33676033e+01 -4.31045952e+01 -4.32039146e+01 -4.31053505e+01 -4.28072968e+01 -4.25722961e+01 -4.24541817e+01 -4.21397552e+01 -4.19667053e+01 -4.15931320e+01 -4.13969688e+01 -4.12894516e+01 -4.11686287e+01 -4.07747383e+01 -4.04284286e+01 -4.00176811e+01 -3.99234695e+01 -3.99073448e+01 -3.97661400e+01 -3.99052773e+01 -3.97687149e+01 -3.91460609e+01 -3.86946182e+01 -3.83241310e+01 -3.85237617e+01 -3.83540764e+01 -3.84771080e+01 -3.80418243e+01 -3.79827118e+01 -3.76338348e+01 -3.73064041e+01 -3.70689125e+01 -3.66343498e+01 -3.66660881e+01 -3.65036240e+01 -3.63908844e+01 -3.59630280e+01 -3.55566978e+01 -3.50577660e+01 -3.48699532e+01 -3.45976219e+01 -3.43130951e+01 -3.41445656e+01 -3.40148239e+01 -3.39136391e+01 -3.37721519e+01 -3.39537506e+01 -3.33732300e+01 -3.32156258e+01 -3.25606079e+01 -3.23308258e+01 -3.22278442e+01 -3.17774849e+01 -3.18617687e+01 -3.10789967e+01 -3.10528145e+01 -3.14323559e+01 -3.18686218e+01 -3.09235344e+01 -3.05830917e+01 -2.97198143e+01 -3.01147976e+01 -2.95999222e+01 -2.90242729e+01 -2.84713669e+01 -2.88138847e+01 -2.92328262e+01 -2.81566200e+01 -2.89185123e+01 -2.80455246e+01 -2.81506557e+01 -2.76608829e+01 -2.81418629e+01 -2.78272724e+01 -2.67611599e+01 -2.63316040e+01 -2.54942455e+01 -2.55422478e+01 -2.48849907e+01 -2.46972542e+01 -2.46746273e+01 -2.42670593e+01 -2.40763798e+01 -2.39796638e+01 -2.41814079e+01 -2.42121830e+01 -2.36037731e+01 -2.28316479e+01 -2.23400879e+01 -2.22339954e+01 -2.19579048e+01 -2.15192509e+01 -2.09451790e+01 -2.01530800e+01 -1.98166695e+01 -1.99231358e+01 -2.00406399e+01 -2.01531754e+01 -1.93611221e+01 -1.92061462e+01 -1.87412167e+01 -1.89095364e+01 -1.87027817e+01 -1.73822880e+01 -1.71253090e+01 -1.66129379e+01 -1.71893215e+01 -1.72649918e+01 -1.68200417e+01 -1.69484367e+01 -1.55448017e+01 -1.48663626e+01 -1.50014486e+01 -1.45894051e+01 -1.48110485e+01 -1.47864227e+01 -1.49593706e+01 -1.44997759e+01 -1.33552761e+01 -1.30552635e+01 -1.28067026e+01 -1.23415165e+01 -1.16535797e+01 -1.08199644e+01 -1.19959984e+01 -1.88417492e+01 -2.43259506e+01 -1.75613403e+01 -1.80156250e+01 -1.66298866e+01 -9.01520824e+00 -8.85804367e+00 -8.70572567e+00 -8.18649292e+00 -6.75570107e+00 -8.67412627e-01 -6.81558132e+00 -1.37798065e+02 -2.04119431e+02 -4.10134308e+02 -1.10476147e+03 -266767888. 105182784. 0. 0. 41271896. 41271896. 41271896. 0. 0. 0. -10370003. -1.81799725e+06 7.94732812e+04 -1.18621973e+03 -6.16771362e+02 -3.40557678e+02 -2.38883942e+02 -6.02879829e+01 -2.31003304e+01 -2.77447472e+01 -2.08345299e+01 -9.09373188e+00 -9.82702672e-01 7.64430642e-01 1.81850541e+00 2.68915296e+00 2.59946203e+00 2.89279461e+00 2.93234301e+00 2.53934288e+00 -2.95249867e+00 -8.18999577e+00 -2.45264244e+00 4.49514961e+00 6.31502151e+00 6.61777973e+00 5.97518444e+00 8.13003540e+00 1.38828459e+01 1.34075317e+01 7.13618517e+00 2.99461269e+00 5.66473818e+00 9.86581039e+00 1.50210009e+01 2.07709866e+01 1.16834688e+01 4.08952188e+00 7.32618237e+00 8.91412926e+00 9.80611992e+00 1.02412319e+01 1.07372274e+01 1.11215448e+01 1.15207577e+01 1.16866531e+01 1.20402098e+01 1.23722782e+01 1.26598606e+01 1.28942833e+01 1.31961079e+01 1.36085367e+01 1.39642210e+01 1.43182535e+01 1.45695782e+01 1.48698521e+01 1.50908899e+01 1.54785175e+01 1.58464499e+01 1.61031876e+01 1.63016357e+01 1.66656055e+01 1.69623623e+01 1.72744808e+01 1.75432396e+01 1.78939590e+01 1.82341404e+01 1.85660553e+01 1.87768250e+01 1.90792885e+01 1.93959026e+01 1.97675381e+01 2.00907097e+01 2.04697170e+01 2.07774734e+01 2.11265736e+01 2.13677998e+01 2.16666908e+01 2.19784698e+01 2.23040276e+01 2.25930176e+01 2.28858013e+01 2.32169399e+01 2.35164547e+01 2.35287132e+01 2.38142376e+01 2.41536446e+01 2.45837288e+01 2.49459133e+01 2.52562714e+01 2.54973392e+01 2.54763813e+01 2.52751598e+01 2.54126911e+01 2.44634972e+01 7.01441345e+02 3.21153908e+01 2.12633438e+01 2.14191265e+01 2.16253033e+01 2.19456196e+01 2.22462902e+01 2.23853188e+01 2.24149742e+01 2.26495266e+01 2.31159534e+01 2.33363075e+01 2.37144833e+01 2.38561802e+01 2.39991055e+01 2.40533981e+01 2.41404705e+01 2.42013187e+01 2.42510548e+01 2.42733822e+01 2.43581219e+01 2.44328365e+01 2.44796906e+01 2.46142693e+01 2.46631126e+01 2.46557751e+01 2.47140083e+01 2.47939854e+01 2.48897648e+01 2.48909302e+01 2.50027676e+01 2.50670605e+01 2.50949383e+01 2.50784473e+01 2.51254234e+01 2.51345253e+01 2.52581387e+01 2.53400955e+01 2.54015179e+01 2.53566322e+01 2.53867760e+01 2.54302692e+01 2.54293919e+01 2.55595627e+01 2.55803757e+01 2.55852909e+01 2.56013794e+01 2.56616592e+01 2.57494888e+01 2.57867680e+01 2.58446178e+01 2.58676720e+01 2.60645771e+01 2.61038895e+01 2.61124763e+01 2.59282703e+01 2.59549084e+01 2.59814720e+01 2.60656910e+01 2.59272728e+01 2.59193897e+01 2.59911575e+01 2.63428764e+01 2.64682446e+01 2.64872150e+01 2.63057861e+01 2.63325806e+01 2.63289452e+01 2.63519993e+01 2.62313194e+01 2.61425571e+01 2.61840534e+01 2.63857937e+01 2.60274220e+01 2.57152786e+01 2.58432007e+01 2.59905071e+01 2.60504608e+01 2.62321339e+01 2.59696007e+01 2.65588684e+01 2.91113834e+01 2.56466732e+01 -6.90757294e+01 -1.25415230e+02 -2.68781769e+02 2.31371292e+02 7.41960831e+01 -8.13489197e+02 396830720. -1123158528. -1123158528. 1841341. 401538080. 401538080. 0. 0. 0. 0. 0. 0. -460605760. 42401352. 2.25080176e+04 -9.81433228e+02 -4.67140869e+02 -1.05246834e+02 2.32337437e+01 2.45464783e+01 2.77052746e+01 2.62109337e+01 2.35984974e+01 2.31309605e+01 1.40641470e+01 1.99675350e+01 2.84205227e+01 2.80426292e+01 2.68616657e+01 2.64910870e+01 2.66711769e+01 2.59771633e+01 2.56184464e+01 2.56719856e+01 2.56395435e+01 2.62386436e+01 2.66544647e+01 2.70863457e+01 2.66305695e+01 2.62897358e+01 2.56536541e+01 2.56466141e+01 2.67419567e+01 2.80758686e+01 2.57188320e+01 2.32192192e+01 2.34570808e+01 2.42468643e+01 2.46228390e+01 2.47994347e+01 2.48387070e+01 2.46154137e+01 2.55474014e+01 2.55269928e+01 2.52981319e+01 2.56056232e+01 2.67438030e+01 2.54493885e+01 2.45512390e+01 2.39857502e+01 2.49357758e+01 2.48677483e+01 2.50308781e+01 2.51774921e+01 2.51917152e+01 2.46767387e+01 2.37902203e+01 2.30296326e+01 2.34234657e+01 2.36904736e+01 2.41427231e+01 2.42230053e+01 2.47245502e+01 2.47327557e+01 2.39710541e+01 2.36303596e+01 2.33348846e+01 2.37658405e+01 2.39951973e+01 2.40844460e+01 2.42433987e+01 2.35806332e+01 2.37199230e+01 2.30638962e+01 2.25103283e+01 2.11698704e+01 2.12111034e+01 2.15120754e+01 2.21939278e+01 2.18488560e+01 2.25107136e+01 2.23602009e+01 2.24963722e+01 2.18587742e+01 2.15855541e+01 2.17493725e+01 2.15876369e+01 2.14009609e+01 2.09891510e+01 2.09209709e+01 2.04052067e+01 2.02566948e+01 2.08347969e+01 2.10942192e+01 2.13609447e+01 2.07856636e+01 2.04413986e+01 1.96503830e+01 1.94065628e+01 2.03046722e+01 2.07303123e+01 2.09481869e+01 2.01196804e+01 1.95036259e+01 1.89566536e+01 1.87722492e+01 1.95936871e+01 1.95670528e+01 2.03533840e+01 1.97278347e+01 1.91623459e+01 1.83023815e+01 1.84436970e+01 1.90284214e+01 1.91469059e+01 1.86654778e+01 1.84006844e+01 1.84051418e+01 1.88010883e+01 1.85638351e+01 1.83530827e+01 1.77386150e+01 1.77358322e+01 1.75596981e+01 1.73817101e+01 1.71904774e+01 1.75622692e+01 1.73212624e+01 1.74131317e+01 1.72622833e+01 1.69047890e+01 1.64680252e+01 1.64063568e+01 1.64464130e+01 1.64914551e+01 1.62007809e+01 1.58557367e+01 1.58435659e+01 1.57758827e+01 1.58008757e+01 1.57517662e+01 1.54123783e+01 1.52177753e+01 1.49077463e+01 1.48877687e+01 1.47868767e+01 1.46851635e+01 1.45772486e+01 1.44155893e+01 1.42732496e+01 1.41273184e+01 1.40144062e+01 1.39481115e+01 1.37453232e+01 1.36112890e+01 1.35673208e+01 1.33241653e+01 1.31726933e+01 1.31749353e+01 1.28123560e+01 1.27103319e+01 1.27428131e+01 1.24467363e+01 1.24360647e+01 1.22004042e+01 1.19885015e+01 1.20411797e+01 1.18519421e+01 1.15875416e+01 1.15849991e+01 1.15387907e+01 1.13576269e+01 1.13006735e+01 1.10926991e+01 1.08768539e+01 1.07279835e+01 1.04084501e+01 1.02058735e+01 1.00888748e+01 9.95769119e+00 9.86583233e+00 9.77279663e+00 9.35133266e+00 9.19005013e+00 9.39425373e+00 9.43212700e+00 8.99865150e+00 9.19160652e+00 8.89862728e+00 8.90372276e+00 8.24064255e+00 7.99607658e+00 7.80401850e+00 8.03312874e+00 7.88608980e+00 7.92277670e+00 7.42232990e+00 7.37181044e+00 7.14467096e+00 7.08563709e+00 7.06237984e+00 6.63583374e+00 6.79720068e+00 6.34794188e+00 6.41677618e+00 6.14289999e+00 5.65542603e+00 5.79908276e+00 5.94731617e+00 6.08413076e+00 5.80942440e+00 5.30059719e+00 4.69792318e+00 4.62315845e+00 4.89641762e+00 4.61320066e+00 3.49049473e+00 3.36438870e+00 3.65049314e+00 4.05888319e+00 4.17348909e+00 4.14565134e+00 3.49275064e+00 3.36206746e+00 3.56578183e+00 3.56471920e+00 2.72765851e+00 2.75860643e+00 2.63059330e+00 2.50427556e+00 1.00780904e+00 -4.00593728e-02 -1.95282832e-01 2.34530836e-01 3.83367956e-01 1.20149887e+00 1.12804019e+00 1.20582986e+00 -8.13823845e-03 1.54639512e-01 5.92398524e-01 2.47939184e-01 4.98596042e-01 9.49244276e-02 2.44144008e-01 -9.53875601e-01 -1.40533543e+00 -1.29324675e+00 -5.12845397e-01 -1.11402833e+00 -1.47907650e+00 -1.99774647e+00 -1.36617494e+00 -1.38193536e+00 -1.16722190e+00 -1.80401921e+00 -1.98173416e+00 -2.78163958e+00 -3.01129532e+00 -2.74321818e+00 -3.29794002e+00 -3.37960196e+00 -3.59823155e+00 -3.05667877e+00 -2.54901409e+00 -3.13947010e+00 -2.87480021e+00 -3.11163068e+00 -2.54617476e+00 -3.11442542e+00 -3.93696713e+00 -4.11051893e+00 -4.64008808e+00 -4.73906422e+00 -5.12591839e+00 -4.95730782e+00 -4.55022478e+00 -5.28184748e+00 -5.84943581e+00 -6.10989285e+00 -6.05291796e+00 -5.45770836e+00 -5.03860092e+00 -4.61258602e+00 -5.49184847e+00 -6.35013056e+00 -6.57447767e+00 -6.49678230e+00 -6.79746675e+00 -6.93743181e+00 -7.71751785e+00 -8.00001907e+00 -8.53705502e+00 -8.54180241e+00 -8.74628067e+00 -8.75772095e+00 -8.81570530e+00 -9.35192204e+00 -9.09453297e+00 -8.88563633e+00 -8.97017097e+00 -9.12885857e+00 -8.82445526e+00 -9.31174660e+00 -9.65589905e+00 -1.03691158e+01 -9.60928535e+00 -1.01763344e+01 -9.89561749e+00 -1.00879364e+01 -9.91742325e+00 -1.04998360e+01 -1.11349430e+01 -1.19339495e+01 -1.14488859e+01 -1.12608299e+01 -1.10273304e+01 -1.12282219e+01 -1.11665859e+01 -1.13660183e+01 -1.20701036e+01 -1.26983404e+01 -1.26592703e+01 -1.24703455e+01 -1.24982243e+01 -1.25353136e+01 -1.23741903e+01 -1.27801437e+01 -1.27299595e+01 -1.31075058e+01 -1.35234041e+01 -1.39536324e+01 -1.42761345e+01 -1.41698904e+01 -1.41476173e+01 -1.43921595e+01 -1.42532415e+01 -1.44774075e+01 -1.44525537e+01 -1.47388325e+01 -1.48840961e+01 -1.49155521e+01 -1.50711479e+01 -1.52909060e+01 -1.55019598e+01 -1.56141195e+01 -1.59685907e+01 -1.60636463e+01 -1.59177637e+01 -1.60195789e+01 -1.60078621e+01 -1.62855301e+01 -1.64925880e+01 -1.68819370e+01 -1.70663853e+01 -1.69083271e+01 -1.67558231e+01 -1.66694946e+01 -1.70470486e+01 -1.73715324e+01 -1.76688042e+01 -1.77519035e+01 -1.76883430e+01 -1.77724876e+01 -1.76833000e+01 -1.78563938e+01 -1.80436287e+01 -1.83442917e+01 -1.84138603e+01 -1.84255238e+01 -1.85145397e+01 -1.86819477e+01 -1.87326584e+01 -1.88140430e+01 -1.87387600e+01 -1.89405060e+01 -1.90433731e+01 -1.92214394e+01 -1.93744049e+01 -1.95067635e+01 -1.96086655e+01 -1.96943817e+01 -1.97530804e+01 -1.98876858e+01 -1.99643345e+01 -2.01110611e+01 -2.02051926e+01 -2.03171062e+01 -2.04208469e+01 -2.05189667e+01 -2.05915108e+01 -2.06853676e+01 -2.08196354e+01 -2.09226799e+01 -2.10024014e+01 -2.11018963e+01 -2.11995144e+01 -2.13206215e+01 -2.13946171e+01 -2.14851799e+01 -2.15739918e+01 -2.16524525e+01 -2.17211342e+01 -2.18324051e+01 -2.19376774e+01 -2.20102921e+01 -2.20990238e+01 -2.21870995e+01 -2.22738705e+01 -2.23618412e+01 -2.24463062e+01 -2.25358620e+01 -2.26266346e+01 -2.27183781e+01 -2.28003559e+01 -2.28813324e+01 -2.29662800e+01 -2.30425777e+01 -2.31118584e+01 -2.31953506e+01 -2.32684135e+01 -2.33390179e+01 -2.34189930e+01 -2.34784756e+01 -2.35415649e+01 -2.36248989e+01 -2.37037239e+01 -2.37758160e+01 -2.38441620e+01 -2.39165020e+01 -2.39667377e+01 -2.40226460e+01 -2.40533409e+01 -2.41177940e+01 -2.41883907e+01 -2.42494755e+01 -2.43571510e+01 -2.44172001e+01 -2.43758621e+01 -2.44387417e+01 -2.45371571e+01 -2.46025372e+01 -2.46765461e+01 -2.48666630e+01 -2.48856831e+01 -2.48387985e+01 -2.48312817e+01 -2.48673210e+01 -2.48594761e+01 -2.49628086e+01 -2.50516663e+01 -2.51397953e+01 -2.51779938e+01 -2.52196426e+01 -2.52483902e+01 -2.52974148e+01 -2.53446369e+01 -2.53723907e+01 -2.54663811e+01 -2.54539318e+01 -2.55374546e+01 -2.56595173e+01 -2.56338406e+01 -2.58048401e+01 -2.57807140e+01 -2.57927437e+01 -2.57916012e+01 -2.57934246e+01 -2.57228565e+01 -2.57073860e+01 -2.56674614e+01 -2.57176685e+01 -2.55099564e+01 -2.55090771e+01 -2.55859928e+01 -2.60854969e+01 -2.63258133e+01 -2.63519478e+01 -2.61322002e+01 -2.62211266e+01 -2.62293110e+01 -2.63048344e+01 -2.61665001e+01 -2.60963860e+01 -2.60205269e+01 -2.58070011e+01 -2.54579220e+01 -2.52484226e+01 -2.53324432e+01 -2.54423122e+01 -2.55526524e+01 -2.59978237e+01 -2.60427494e+01 -2.61657124e+01 -2.60004063e+01 -2.61830444e+01 -2.63353691e+01 -2.60732422e+01 -2.61670151e+01 -2.62500839e+01 -2.63015175e+01 -2.58312778e+01 -2.56440697e+01 -2.57498817e+01 -2.61618042e+01 -2.61976070e+01 -2.60028248e+01 -2.56096401e+01 -2.60568161e+01 -2.62247295e+01 -2.63937130e+01 -2.63629494e+01 -2.60671539e+01 -2.57749195e+01 -2.56806030e+01 -2.61024208e+01 -2.60204258e+01 -2.62766151e+01 -2.61124020e+01 -2.63963184e+01 -2.67966499e+01 -2.63319092e+01 -2.65288334e+01 -2.62241116e+01 -2.65439873e+01 -2.61411057e+01 -2.56211872e+01 -2.56466484e+01 -2.56392078e+01 -2.57659187e+01 -2.58788128e+01 -2.57102757e+01 -2.59920483e+01 -2.55278282e+01 -2.54194469e+01 -2.52608509e+01 -2.51639290e+01 -2.59449253e+01 -2.62873058e+01 -2.69097252e+01 -2.63184528e+01 -2.62375240e+01 -2.58392296e+01 -2.56021252e+01 -2.51112728e+01 -2.55117855e+01 -2.49653606e+01 -2.44969730e+01 -2.40312881e+01 -2.44002647e+01 -2.45689735e+01 -2.46428623e+01 -2.48414249e+01 -2.44330292e+01 -2.49752998e+01 -2.49982224e+01 -2.47597961e+01 -2.48675861e+01 -2.52936783e+01 -2.46940765e+01 -2.45956135e+01 -2.37439156e+01 -2.44389286e+01 -2.43993092e+01 -2.45918427e+01 -2.44273548e+01 -2.48241253e+01 -2.42231483e+01 -2.35643654e+01 -2.29329681e+01 -2.39635448e+01 -2.40340557e+01 -2.41142941e+01 -2.41065807e+01 -2.45366192e+01 -2.44955273e+01 -2.37759418e+01 -2.32066631e+01 -2.29166660e+01 -2.30578060e+01 -2.32217083e+01 -2.33175354e+01 -2.40060482e+01 -2.35948105e+01 -2.35633411e+01 -2.30348892e+01 -2.23984394e+01 -2.15979481e+01 -2.16868801e+01 -2.20461979e+01 -2.21812897e+01 -2.17356033e+01 -2.20085468e+01 -2.19264355e+01 -2.18619766e+01 -2.17607212e+01 -2.15666027e+01 -2.17016506e+01 -2.16414566e+01 -2.14051819e+01 -2.12746735e+01 -2.12978020e+01 -2.05895290e+01 -2.02895584e+01 -2.08267822e+01 -2.09089699e+01 -2.09331112e+01 -2.06043072e+01 -2.01962299e+01 -1.95359955e+01 -1.93453083e+01 -2.01459179e+01 -2.06014061e+01 -2.08869724e+01 -2.01229935e+01 -1.93283691e+01 -1.88441086e+01 -1.87659187e+01 -1.93696690e+01 -1.94901066e+01 -2.00100994e+01 -1.95034046e+01 -1.88567352e+01 -1.78111973e+01 -1.81681290e+01 -1.86361122e+01 -1.89716663e+01 -1.82859058e+01 -1.80480595e+01 -1.82111111e+01 -1.87506466e+01 -1.80541267e+01 -1.79705219e+01 -1.78648357e+01 -1.77364597e+01 -1.74840164e+01 -1.73865528e+01 -1.75793781e+01 -1.73457699e+01 -1.70621681e+01 -1.72314167e+01 -1.70899391e+01 -1.69048100e+01 -1.63991585e+01 -1.63793716e+01 -1.64804440e+01 -1.66247215e+01 -1.64619617e+01 -1.61416550e+01 -1.59707537e+01 -1.55604610e+01 -1.56029711e+01 -1.57446222e+01 -1.52989607e+01 -1.51483822e+01 -1.48023376e+01 -1.48307619e+01 -1.47752972e+01 -1.46235819e+01 -1.46271820e+01 -1.45160599e+01 -1.44455280e+01 -1.40951958e+01 -1.39417639e+01 -1.37794247e+01 -1.34965363e+01 -1.34255972e+01 -1.33970881e+01 -1.29802027e+01 -1.29815207e+01 -1.29981060e+01 -1.25993853e+01 -1.25699110e+01 -1.24631681e+01 -1.21863079e+01 -1.22939930e+01 -1.23118849e+01 -1.19165859e+01 -1.18233814e+01 -1.19279337e+01 -1.14970093e+01 -1.14842653e+01 -1.15022631e+01 -1.11113434e+01 -1.10757265e+01 -1.09344225e+01 -1.08039684e+01 -1.07171669e+01 -1.02989826e+01 -1.01957884e+01 -1.00067883e+01 -9.83235931e+00 -9.91965961e+00 -9.68891525e+00 -9.09502506e+00 -9.03375912e+00 -8.90816784e+00 -8.90039253e+00 -8.90859795e+00 -8.99458885e+00 -8.70618153e+00 -8.43236065e+00 -8.16021347e+00 -8.26510525e+00 -7.98692846e+00 -8.01843834e+00 -7.85539007e+00 -7.88409996e+00 -7.31005096e+00 -7.15332985e+00 -7.03342152e+00 -6.67007065e+00 -6.65038347e+00 -6.67258978e+00 -6.70457029e+00 -6.00173044e+00 -5.92023611e+00 -5.68692636e+00 -5.31086540e+00 -5.33280516e+00 -5.61946106e+00 -5.89954138e+00 -5.35987759e+00 -4.99149275e+00 -4.37526560e+00 -4.32848358e+00 -4.30487394e+00 -4.33423138e+00 -3.38641953e+00 -3.19600034e+00 -3.37901855e+00 -4.00707197e+00 -4.19838190e+00 -4.30953121e+00 -3.38339305e+00 -3.06633186e+00 -3.33249378e+00 -3.43117571e+00 -2.76719189e+00 -2.30523205e+00 -2.18898511e+00 -2.22050953e+00 -1.03824031e+00 -1.37495250e-01 -1.98726788e-01 -3.73382479e-01 6.52749315e-02 -9.08018887e-01 -1.03101003e+00 -9.83244181e-01 -8.48002210e-02 -2.68637657e-01 -5.43655753e-01 -1.68149248e-01 -2.41701782e-01 3.02710205e-01 9.03429389e-02 1.02671254e+00 1.28547478e+00 1.18341935e+00 1.10295725e+00 1.48904407e+00 1.51125455e+00 2.01832199e+00 1.51891744e+00 1.74595368e+00 1.40569651e+00 2.11164761e+00 2.35065198e+00 3.02745771e+00 3.06176686e+00 3.09385562e+00 3.54168487e+00 3.12520528e+00 3.29417467e+00 2.91127133e+00 2.64202213e+00 3.01998806e+00 2.81914735e+00 3.65826917e+00 3.37352443e+00 3.88488603e+00 4.43647909e+00 4.76252031e+00 5.15157747e+00 4.92718267e+00 5.00040483e+00 4.97511530e+00 4.74863386e+00 5.70567751e+00 6.28807974e+00 6.43492079e+00 6.54604912e+00 5.75844717e+00 5.19997406e+00 4.63726330e+00 5.49357271e+00 6.22368002e+00 6.99757719e+00 7.18630791e+00 7.71106577e+00 7.64719343e+00 7.77090406e+00 7.76820850e+00 8.48419571e+00 2.80336952e+00 1.95373809e+00 1.46658659e+00 3.04191422e+00 4.56867361e+00 4.14630270e+00 9.86151123e+00 9.96104336e+00 1.00244932e+01 9.71148491e+00 1.06752234e+01 1.42958937e+01 1.37867584e+01 -1.12151024e+02 -1.92547943e+02 -4.00247711e+02 -1.18183887e+03 12580737. -126164672. 0. 0. 0. 4.97597850e+09 4.97597850e+09 4.97597850e+09 0. 0. 0. 51098584. 4.43151150e+06 -1.98542590e+03 -6.61543091e+02 -1.65770493e+02 -2.54349426e+02 -1.60209915e+02 -5.91024017e+00 -8.37418175e+00 -2.33665490e+00 6.67927122e+00 1.17617369e+01 8.62431335e+00 9.35392284e+00 1.27822857e+01 1.31935682e+01 1.32722845e+01 1.17310848e+01 5.19060135e+00 6.28563929e+00 1.43931208e+01 1.65855312e+01 1.66679058e+01 1.56169376e+01 1.68279324e+01 1.93383980e+01 1.81066093e+01 1.49981842e+01 1.33194618e+01 1.86890030e+01 1.82308884e+01 1.92602215e+01 2.55710468e+01 1.90630875e+01 1.52642918e+01 1.89413853e+01 1.64846115e+01 1.50866499e+01 1.65732079e+01 1.73857021e+01 1.77857876e+01 1.77984200e+01 1.78351974e+01 1.77030296e+01 1.80476475e+01 1.82617455e+01 1.85105305e+01 1.85553417e+01 1.86262360e+01 1.86857510e+01 1.87759819e+01 1.88816338e+01 1.89872017e+01 1.89707508e+01 1.91913300e+01 1.93446407e+01 1.94603825e+01 1.96384296e+01 1.98249187e+01 2.00198307e+01 2.00848579e+01 2.00428162e+01 2.01286087e+01 2.02392063e+01 2.03852539e+01 2.04688416e+01 2.06051998e+01 2.07354965e+01 2.08121471e+01 2.09222126e+01 2.09775887e+01 2.07580376e+01 2.07836933e+01 2.08030453e+01 2.07890015e+01 2.07955379e+01 2.06888428e+01 2.06648254e+01 2.09003830e+01 2.04862061e+01 2.00719433e+01 1.99116993e+01 2.00408916e+01 2.02261219e+01 2.03172817e+01 2.04072609e+01 2.04674282e+01 2.05293331e+01 2.05284538e+01 2.05505772e+01 2.07149448e+01 2.04821529e+01 3.11084961e+02 2.77322044e+01 1.79973660e+01 1.82851734e+01 1.85327454e+01 1.88119411e+01 1.91937428e+01 1.95446148e+01 1.96383457e+01 1.98443642e+01 2.01669540e+01 2.04175625e+01 2.07842407e+01 2.10428524e+01 2.13498230e+01 2.16335583e+01 2.18860722e+01 2.21565647e+01 2.26027985e+01 2.33162060e+01 2.41103859e+01 2.46183834e+01 2.47766705e+01 2.49508247e+01 2.50485077e+01 2.51659279e+01 2.53183060e+01 2.55340462e+01 2.57700958e+01 2.60350342e+01 2.61909885e+01 2.64844704e+01 2.67152557e+01 2.70011711e+01 2.72242851e+01 2.74479485e+01 2.76417656e+01 2.79031601e+01 2.81756897e+01 2.84727459e+01 2.87107258e+01 2.87472038e+01 2.89618587e+01 2.91126232e+01 2.94889507e+01 2.96002502e+01 2.97936459e+01 2.99713383e+01 3.01171894e+01 3.02908611e+01 3.05684013e+01 3.07934666e+01 3.12187023e+01 3.13482914e+01 3.14656639e+01 3.16251450e+01 3.17505894e+01 3.20578423e+01 3.23799706e+01 3.25235291e+01 3.28239517e+01 3.31147079e+01 3.33572960e+01 3.34792252e+01 3.35261116e+01 3.36476326e+01 3.38369026e+01 3.39282799e+01 3.39513855e+01 3.43068962e+01 3.44040947e+01 3.47183151e+01 3.50022011e+01 3.51726189e+01 3.54986954e+01 3.58739433e+01 3.57284927e+01 3.57581520e+01 3.51172485e+01 3.45410461e+01 2.99179020e+01 -5.89632530e+01 -1.26620552e+02 -3.04828064e+02 -8.16039246e+02 -132549216. 3.83057350e+06 -157534928. -157534928. 0. -131372528. -131372528. -20722990. 401538080. 401538080. 0. 0. 0. 0. -1167919104. -20580638. -1.05170459e+03 -3.37784943e+02 1.01461098e+02 -1.53163391e+02 -7.87236099e+01 4.14086227e+01 3.91117668e+01 3.57043915e+01 3.97849846e+01 4.11133766e+01 3.93298988e+01 3.87013855e+01 3.91704597e+01 4.29257851e+01 4.25476532e+01 4.21430168e+01 4.16586952e+01 4.23173218e+01 4.23425789e+01 4.27124214e+01 4.25071754e+01 4.26438942e+01 4.29570732e+01 4.30191803e+01 4.31108971e+01 4.29310875e+01 4.34385796e+01 4.35771523e+01 4.37256470e+01 4.40140381e+01 4.39189606e+01 4.37432556e+01 4.39977989e+01 4.43020554e+01 4.44809532e+01 4.46477242e+01 4.48209991e+01 4.48325958e+01 4.45796127e+01 4.49916077e+01 4.54177475e+01 4.56594124e+01 4.59542351e+01 4.60814972e+01 4.54121819e+01 4.56985550e+01 4.57195587e+01 4.55979843e+01 4.55296021e+01 4.56099358e+01 4.59170647e+01 4.64563446e+01 4.59382935e+01 4.54108582e+01 4.54352646e+01 4.51692581e+01 4.49951477e+01 4.46676674e+01 4.55727158e+01 4.57754517e+01 4.57315254e+01 4.61249619e+01 4.67992287e+01 4.74091988e+01 4.65782776e+01 4.64028015e+01 4.58421631e+01 4.57399025e+01 4.57923622e+01 4.63626938e+01 4.66135521e+01 4.65136490e+01 4.61979523e+01 4.62345848e+01 4.65255966e+01 4.66947441e+01 4.60790062e+01 4.64595032e+01 4.62677536e+01 4.68099403e+01 4.63876076e+01 4.68708191e+01 4.62068100e+01 4.63789444e+01 4.59696159e+01 4.64523468e+01 4.63751717e+01 4.70356750e+01 4.70344543e+01 4.67422180e+01 4.66243019e+01 4.64777908e+01 4.69280014e+01 4.64293365e+01 4.64692535e+01 4.65171700e+01 4.66322060e+01 4.65919533e+01 4.67139359e+01 4.62345772e+01 4.62747993e+01 4.60641365e+01 4.63735504e+01 4.64305038e+01 4.65355759e+01 4.61734734e+01 4.59332390e+01 4.63433609e+01 4.65592155e+01 4.67919388e+01 4.64089890e+01 4.59595833e+01 4.59351692e+01 4.61370010e+01 4.58710556e+01 4.55021515e+01 4.49407043e+01 4.55287819e+01 4.57715797e+01 4.56237297e+01 4.53774567e+01 4.51644554e+01 4.55040779e+01 4.52369270e+01 4.50023575e+01 4.49514351e+01 4.50514183e+01 4.51644974e+01 4.46083946e+01 4.46195412e+01 4.45794868e+01 4.48747444e+01 4.50075073e+01 4.49092026e+01 4.47421722e+01 4.50136986e+01 4.48178520e+01 4.47574997e+01 4.44315681e+01 4.41688232e+01 4.41837845e+01 4.40632858e+01 4.40936928e+01 4.39019127e+01 4.37414665e+01 4.37303696e+01 4.35941124e+01 4.33553696e+01 4.31543159e+01 4.31825790e+01 4.30330887e+01 4.29691696e+01 4.28560295e+01 4.27472687e+01 4.26340103e+01 4.25479469e+01 4.25596542e+01 4.22896614e+01 4.22664146e+01 4.22157707e+01 4.18984070e+01 4.17087250e+01 4.15237274e+01 4.14809990e+01 4.14789810e+01 4.13418922e+01 4.12072945e+01 4.09965439e+01 4.07994499e+01 4.06509323e+01 4.07952309e+01 4.04964790e+01 4.03311348e+01 4.01854286e+01 4.00688820e+01 3.98295708e+01 3.97747078e+01 3.95749283e+01 3.95834808e+01 3.94625626e+01 3.94733086e+01 3.89338608e+01 3.90527992e+01 3.88015823e+01 3.85368538e+01 3.80966644e+01 3.84489288e+01 3.83967857e+01 3.84650421e+01 3.78360100e+01 3.77701836e+01 3.75295296e+01 3.77924080e+01 3.77615700e+01 3.76238632e+01 3.72570877e+01 3.64393158e+01 3.65534401e+01 3.60072365e+01 3.59889755e+01 3.59610329e+01 3.59507027e+01 3.54583549e+01 3.48158875e+01 3.44512978e+01 3.46112213e+01 3.47916298e+01 3.49812393e+01 3.43201981e+01 3.40358429e+01 3.38232307e+01 3.35284920e+01 3.37276230e+01 3.38938637e+01 3.30812263e+01 3.33124886e+01 3.32368622e+01 3.24873543e+01 3.22277832e+01 3.24102516e+01 3.17398548e+01 3.11210709e+01 3.08127098e+01 3.04328384e+01 3.05462513e+01 3.04783516e+01 3.04932766e+01 3.01985779e+01 3.02051144e+01 3.02400875e+01 3.03914661e+01 2.96655483e+01 2.95210419e+01 2.80351601e+01 2.84168282e+01 2.84872475e+01 2.86746349e+01 2.82386169e+01 2.74395981e+01 2.78421612e+01 2.75621796e+01 2.72771111e+01 2.71044064e+01 2.68496113e+01 2.72538948e+01 2.64339333e+01 2.63632889e+01 2.54380341e+01 2.54545383e+01 2.45194511e+01 2.46320400e+01 2.43065662e+01 2.40774212e+01 2.40246391e+01 2.40428562e+01 2.35337639e+01 2.32413197e+01 2.35960693e+01 2.39169884e+01 2.40268536e+01 2.34605331e+01 2.32326908e+01 2.21607513e+01 2.22818985e+01 2.18952789e+01 2.13590546e+01 2.06875725e+01 1.97170429e+01 2.04229145e+01 2.00652409e+01 2.01117477e+01 1.94961319e+01 1.88430882e+01 1.92796936e+01 1.88406391e+01 1.90323277e+01 1.80565205e+01 1.77695541e+01 1.83527565e+01 1.80985107e+01 1.78365574e+01 1.71109524e+01 1.69880943e+01 1.65399227e+01 1.63906765e+01 1.60584526e+01 1.58634377e+01 1.61138744e+01 1.57682915e+01 1.52713165e+01 1.46348219e+01 1.47245531e+01 1.44425240e+01 1.38738823e+01 1.35989008e+01 1.35609417e+01 1.32495499e+01 1.33373404e+01 1.37111597e+01 1.34836779e+01 1.30008049e+01 1.24426699e+01 1.19659328e+01 1.12894926e+01 1.08800421e+01 1.09187517e+01 1.12173119e+01 1.11752033e+01 1.01988621e+01 9.24178982e+00 9.18560219e+00 8.79228115e+00 8.73092270e+00 8.25531197e+00 8.77051926e+00 8.54253387e+00 7.80305815e+00 7.28466177e+00 7.01033115e+00 7.10483503e+00 6.53313828e+00 6.19879627e+00 5.54872656e+00 5.22592783e+00 5.07990980e+00 5.27187252e+00 5.09020805e+00 4.65698671e+00 4.21069622e+00 4.01037407e+00 3.94514489e+00 3.61509299e+00 2.90886211e+00 2.65006876e+00 2.30778313e+00 2.33185673e+00 1.90477169e+00 1.73438859e+00 1.16891205e+00 1.03560102e+00 6.34859502e-01 4.87623483e-01 8.02651700e-03 5.92552647e-02 -2.90920526e-01 -6.55882478e-01 -8.21223736e-01 -1.05116200e+00 -1.07655942e+00 -1.56983674e+00 -1.99604428e+00 -2.25683951e+00 -2.51876497e+00 -2.83876801e+00 -3.01565146e+00 -3.33443141e+00 -3.49638510e+00 -3.81405854e+00 -4.07921362e+00 -4.37069511e+00 -4.68674517e+00 -5.06856632e+00 -5.48923826e+00 -5.67838573e+00 -5.84998608e+00 -6.06578970e+00 -6.39162350e+00 -6.75905752e+00 -6.97422361e+00 -7.24360895e+00 -7.60293245e+00 -8.04531384e+00 -8.28516579e+00 -8.44612217e+00 -8.67057514e+00 -9.03717422e+00 -9.40306759e+00 -9.63918304e+00 -9.85541630e+00 -1.01469002e+01 -1.04654665e+01 -1.07114153e+01 -1.09529152e+01 -1.12223577e+01 -1.15754728e+01 -1.18083639e+01 -1.21028938e+01 -1.23343296e+01 -1.25987177e+01 -1.28315897e+01 -1.31102037e+01 -1.33457203e+01 -1.36321554e+01 -1.39476433e+01 -1.42427902e+01 -1.45246878e+01 -1.47774105e+01 -1.50212746e+01 -1.52757406e+01 -1.55529108e+01 -1.58317480e+01 -1.61070709e+01 -1.63828735e+01 -1.66424522e+01 -1.69080486e+01 -1.71710472e+01 -1.74330425e+01 -1.76983662e+01 -1.79599934e+01 -1.82228184e+01 -1.84870701e+01 -1.87470970e+01 -1.90105381e+01 -1.92674751e+01 -1.95325947e+01 -1.97967091e+01 -2.00490971e+01 -2.03160744e+01 -2.05707207e+01 -2.08195305e+01 -2.10799942e+01 -2.13157063e+01 -2.15594406e+01 -2.18247757e+01 -2.20808430e+01 -2.23381672e+01 -2.25999813e+01 -2.28404408e+01 -2.30867157e+01 -2.33562317e+01 -2.35705700e+01 -2.37879791e+01 -2.40662918e+01 -2.42919388e+01 -2.45595360e+01 -2.48062401e+01 -2.49868412e+01 -2.51754341e+01 -2.54395733e+01 -2.56942444e+01 -2.59946709e+01 -2.61942749e+01 -2.64535160e+01 -2.66037045e+01 -2.69135456e+01 -2.71282787e+01 -2.73218231e+01 -2.75378056e+01 -2.77881107e+01 -2.80731258e+01 -2.83484688e+01 -2.85750923e+01 -2.87004070e+01 -2.89169827e+01 -2.90362682e+01 -2.93965931e+01 -2.95524406e+01 -2.97477989e+01 -2.99870167e+01 -3.01459637e+01 -3.03179970e+01 -3.06592083e+01 -3.08458519e+01 -3.11017437e+01 -3.12646885e+01 -3.13606319e+01 -3.15905266e+01 -3.16914845e+01 -3.20200691e+01 -3.22738686e+01 -3.24121056e+01 -3.26266289e+01 -3.30375290e+01 -3.33772926e+01 -3.34700699e+01 -3.34776344e+01 -3.34794960e+01 -3.36914711e+01 -3.39111595e+01 -3.40222130e+01 -3.44269524e+01 -3.45189400e+01 -3.47387085e+01 -3.46692467e+01 -3.49812965e+01 -3.54004822e+01 -3.56508446e+01 -3.55749207e+01 -3.56798172e+01 -3.55623970e+01 -3.59535179e+01 -3.63864899e+01 -3.68030128e+01 -3.69272537e+01 -3.68735504e+01 -3.69684258e+01 -3.70368767e+01 -3.74709587e+01 -3.76543007e+01 -3.77445984e+01 -3.81152229e+01 -3.81923561e+01 -3.82922440e+01 -3.83454323e+01 -3.85408249e+01 -3.83194313e+01 -3.84663734e+01 -3.89267426e+01 -3.90256844e+01 -3.94177399e+01 -3.92838516e+01 -3.93051758e+01 -3.97071037e+01 -4.01198349e+01 -4.05222511e+01 -4.07336349e+01 -4.08815956e+01 -4.13317680e+01 -4.06273041e+01 -4.08377800e+01 -4.06288033e+01 -4.05465050e+01 -4.05505104e+01 -4.03961182e+01 -4.14502296e+01 -4.12365608e+01 -4.13647041e+01 -4.13768730e+01 -4.11057320e+01 -4.18199348e+01 -4.18972588e+01 -4.25970078e+01 -4.22993813e+01 -4.22750130e+01 -4.27473030e+01 -4.31376686e+01 -4.30842934e+01 -4.30155869e+01 -4.32432823e+01 -4.32462845e+01 -4.33044891e+01 -4.34947777e+01 -4.35532761e+01 -4.40727425e+01 -4.39987030e+01 -4.36438217e+01 -4.36065483e+01 -4.40028992e+01 -4.42168427e+01 -4.39580154e+01 -4.38078651e+01 -4.39677238e+01 -4.44735718e+01 -4.51417542e+01 -4.57519302e+01 -4.60439453e+01 -4.57676544e+01 -4.57009964e+01 -4.57171898e+01 -4.52333832e+01 -4.45171661e+01 -4.53850594e+01 -4.57106628e+01 -4.61105156e+01 -4.54773941e+01 -4.50128593e+01 -4.53319016e+01 -4.54687958e+01 -4.57381554e+01 -4.54025536e+01 -4.59672279e+01 -4.61467171e+01 -4.56627007e+01 -4.59405785e+01 -4.61188545e+01 -4.66061401e+01 -4.58323708e+01 -4.57081566e+01 -4.52928467e+01 -4.52423630e+01 -4.56630707e+01 -4.64890862e+01 -4.66127930e+01 -4.64703064e+01 -4.62069740e+01 -4.59692116e+01 -4.62863693e+01 -4.64450760e+01 -4.58545570e+01 -4.57986031e+01 -4.55438919e+01 -4.60850677e+01 -4.59368935e+01 -4.64759712e+01 -4.58867760e+01 -4.60093155e+01 -4.59457207e+01 -4.63987312e+01 -4.62098465e+01 -4.68536491e+01 -4.67676735e+01 -4.65919991e+01 -4.67522812e+01 -4.64963799e+01 -4.67012024e+01 -4.63838730e+01 -4.62627487e+01 -4.65442238e+01 -4.66023827e+01 -4.66362305e+01 -4.65871162e+01 -4.64272003e+01 -4.65526199e+01 -4.61268196e+01 -4.59373932e+01 -4.58781128e+01 -4.59898186e+01 -4.60008659e+01 -4.55923691e+01 -4.57363586e+01 -4.59417877e+01 -4.62303123e+01 -4.60598755e+01 -4.57279892e+01 -4.57322044e+01 -4.56456375e+01 -4.56645737e+01 -4.54350395e+01 -4.52855377e+01 -4.53418388e+01 -4.55729980e+01 -4.55394249e+01 -4.51754723e+01 -4.50003471e+01 -4.52744179e+01 -4.53907509e+01 -4.49317207e+01 -4.49872513e+01 -4.52031136e+01 -4.52550812e+01 -4.47049789e+01 -4.44760857e+01 -4.45752029e+01 -4.50366821e+01 -4.51148987e+01 -4.51336174e+01 -4.49595184e+01 -4.48739471e+01 -4.45329018e+01 -4.45329933e+01 -4.43767357e+01 -4.40695610e+01 -4.39832306e+01 -4.38390083e+01 -4.38801613e+01 -4.39289322e+01 -4.36317749e+01 -4.34786682e+01 -4.33646049e+01 -4.34026299e+01 -4.31451721e+01 -4.31777534e+01 -4.28301773e+01 -4.25291214e+01 -4.25970268e+01 -4.25113068e+01 -4.21887169e+01 -4.23412209e+01 -4.22891388e+01 -4.17682610e+01 -4.17126923e+01 -4.16918831e+01 -4.15322342e+01 -4.16455650e+01 -4.19169235e+01 -4.15800476e+01 -4.12952995e+01 -4.12182808e+01 -4.08005905e+01 -4.07375412e+01 -4.08263016e+01 -4.03722763e+01 -4.05507584e+01 -4.03424835e+01 -4.03470383e+01 -4.04434891e+01 -4.02005234e+01 -4.00594330e+01 -3.99967995e+01 -3.96095734e+01 -3.97727737e+01 -3.96410789e+01 -3.92219887e+01 -3.91325645e+01 -3.89767685e+01 -3.86498032e+01 -3.89680481e+01 -3.84879684e+01 -3.85812683e+01 -3.81287346e+01 -3.85345459e+01 -3.84402695e+01 -3.82785149e+01 -3.79126205e+01 -3.81539612e+01 -3.77530785e+01 -3.74954033e+01 -3.71774673e+01 -3.65362892e+01 -3.63962059e+01 -3.57826233e+01 -3.60626640e+01 -3.58117256e+01 -3.55879898e+01 -3.50373344e+01 -3.46536751e+01 -3.43139801e+01 -3.43944283e+01 -3.43160400e+01 -3.46676292e+01 -3.40076370e+01 -3.34393806e+01 -3.33602982e+01 -3.33347397e+01 -3.35966263e+01 -3.38308678e+01 -3.28688049e+01 -3.30077095e+01 -3.30473633e+01 -3.27237434e+01 -3.24020042e+01 -3.23154335e+01 -3.15838337e+01 -3.09892120e+01 -3.07931099e+01 -3.05832253e+01 -3.06835995e+01 -3.02856560e+01 -3.03873920e+01 -3.00780602e+01 -3.00019436e+01 -2.99404984e+01 -3.02784634e+01 -2.95568428e+01 -2.91184921e+01 -2.78745499e+01 -2.86386471e+01 -2.85249195e+01 -2.85953255e+01 -2.82428665e+01 -2.75807552e+01 -2.78396225e+01 -2.73195419e+01 -2.71703968e+01 -2.70350876e+01 -2.67749977e+01 -2.71624947e+01 -2.65072002e+01 -2.60126610e+01 -2.51665230e+01 -2.51204967e+01 -2.44454536e+01 -2.45210361e+01 -2.45151558e+01 -2.42633743e+01 -2.43198795e+01 -2.39323368e+01 -2.33838825e+01 -2.30864029e+01 -2.32271767e+01 -2.37992363e+01 -2.39203014e+01 -2.36543465e+01 -2.36057014e+01 -2.23390598e+01 -2.23459606e+01 -2.18626156e+01 -2.07458401e+01 -2.02195930e+01 -1.94999161e+01 -2.03332233e+01 -1.98056660e+01 -1.95635071e+01 -1.91449051e+01 -1.85321884e+01 -1.92581158e+01 -1.88530636e+01 -1.88573360e+01 -1.79844761e+01 -1.79128780e+01 -1.84534016e+01 -1.83049297e+01 -1.77870712e+01 -1.71629906e+01 -1.70949707e+01 -1.67794456e+01 -1.64645958e+01 -1.58050480e+01 -1.53402557e+01 -1.52731771e+01 -1.53771534e+01 -1.53344784e+01 -1.47950773e+01 -1.44792795e+01 -1.40160608e+01 -2.09306011e+01 -2.07606277e+01 -1.89577312e+01 -1.82531452e+01 -1.50559111e+01 -1.53159142e+01 -1.21355896e+01 -1.31194534e+01 -1.28037262e+01 -1.09575958e+01 -1.04078970e+01 -5.09951019e+00 -5.09917736e+00 -1.46977921e+02 -2.63215790e+02 -6.16302246e+02 -1.42701758e+03 -147235568. 203670320. 0. 4.97597850e+09 4.97597850e+09 4.97597850e+09 0. 0. 122415200. 122415200. 122415200. 2.63395686e+09 -4587961. -8.12564258e+03 -8.40789307e+02 -4.81444336e+02 -2.44250290e+02 -1.67187119e+02 -2.78908310e+01 -2.11145306e+01 -1.33568230e+01 -1.36346140e+01 -6.50661325e+00 1.04184322e+01 1.22491579e+01 -8.93771744e+00 -1.46328754e+01 -1.02983961e+01 -5.56642914e+00 -9.65466142e-01 -1.11100510e-01 -2.36035854e-01 -8.21050763e-01 -6.78058743e-01 2.27790236e+00 1.08713865e+01 1.04906244e+01 2.01864624e+00 7.18928623e+00 3.85360062e-01 1.39311826e+00 1.14173899e+01 5.33066893e+00 1.36696410e+00 2.56383681e+00 -1.45599976e-01 1.23490632e+00 4.52641487e+00 3.79638886e+00 3.83405113e+00 4.34922171e+00 4.85029745e+00 5.32557917e+00 5.67324972e+00 5.89414597e+00 6.07782936e+00 6.38408995e+00 6.77412176e+00 7.00348616e+00 7.24972486e+00 7.62191153e+00 8.06162071e+00 8.33492374e+00 8.55481434e+00 8.81301308e+00 9.07377052e+00 9.44651413e+00 8.92975807e+00 9.22263336e+00 9.14893723e+00 8.88407135e+00 9.55887318e+00 1.00582838e+01 1.03071947e+01 1.05751953e+01 1.08220844e+01 1.10757771e+01 1.13456326e+01 1.16436520e+01 1.18759985e+01 1.19814215e+01 1.22875824e+01 1.26491480e+01 1.28836241e+01 1.32269058e+01 1.34021463e+01 1.36873569e+01 1.40949306e+01 1.40347662e+01 1.40780926e+01 1.45706625e+01 1.51043453e+01 1.55134478e+01 1.56500950e+01 1.58639603e+01 1.60317497e+01 1.62442055e+01 1.65198669e+01 1.69804420e+01 1.74360485e+01 1.68478279e+01 1.55511316e+03 2.46903553e+01 1.79500885e+01 2.54685516e+01 7.04370193e+01 6.97455978e+01 7.04070129e+01 7.15304871e+01 7.03043823e+01 7.00294037e+01 6.93468399e+01 6.90119019e+01 6.93804779e+01 6.79865799e+01 4.64459190e+01 2.08457928e+01 2.19758148e+01 2.12822475e+01 2.12348442e+01 2.15595245e+01 2.22152653e+01 2.27723236e+01 2.31361561e+01 2.34156876e+01 2.36962833e+01 2.40366821e+01 2.44077663e+01 2.48451385e+01 2.52322865e+01 2.57458897e+01 2.60482864e+01 2.63029346e+01 2.65090981e+01 2.68375568e+01 2.72314911e+01 2.76251831e+01 2.80190239e+01 2.84130630e+01 2.87494183e+01 2.90959320e+01 2.94160881e+01 2.97725677e+01 3.00693626e+01 3.04871502e+01 3.09783077e+01 3.12987328e+01 3.14823589e+01 3.17651024e+01 3.20085487e+01 3.24023666e+01 3.25274734e+01 3.29717598e+01 3.34041443e+01 3.37746429e+01 3.41117287e+01 3.45688133e+01 3.48086166e+01 3.52759552e+01 3.56760902e+01 3.62136345e+01 3.63753014e+01 3.66440315e+01 3.66323280e+01 3.69863777e+01 3.73493156e+01 3.77627602e+01 3.79986725e+01 3.81273232e+01 3.85327454e+01 3.87934418e+01 3.90679703e+01 3.93530159e+01 3.99843369e+01 4.02778587e+01 4.06199760e+01 4.08908501e+01 4.08670883e+01 3.96965065e+01 3.51432381e+01 3.55437965e+01 -6.40726929e+01 -3.34749390e+02 -8.77164001e+02 7928168. 80773872. 0. -157534928. -157534928. -157534928. 0. -131372528. -131372528. -20722990. 401538080. -15627365. 67967792. 67967792. 0. -331316192. -2.04296375e+03 -4.33591736e+02 -1.66586243e+02 -7.11846542e+01 4.44316635e+01 5.08487358e+01 5.05145378e+01 4.59138336e+01 4.43850784e+01 4.77660255e+01 5.37051468e+01 5.07742386e+01 4.80394592e+01 5.16065102e+01 5.19956207e+01 5.15352898e+01 5.16707954e+01 5.15431557e+01 5.21692085e+01 5.23183174e+01 5.27305031e+01 5.28487968e+01 5.32569275e+01 5.35321007e+01 5.35866737e+01 5.34226723e+01 5.31633949e+01 5.31258278e+01 5.39338646e+01 5.44240799e+01 5.49972916e+01 5.56175232e+01 5.55165863e+01 5.56987610e+01 5.54923515e+01 5.55915680e+01 5.59903526e+01 5.60136185e+01 5.64559708e+01 5.72855110e+01 5.81883888e+01 5.86712494e+01 5.78464508e+01 5.75785561e+01 5.68980484e+01 5.71701775e+01 5.67064362e+01 5.76647224e+01 5.79025574e+01 5.87238846e+01 5.89733086e+01 5.90124474e+01 5.93077965e+01 5.88721237e+01 5.89836655e+01 5.91699486e+01 5.92529984e+01 5.96977158e+01 5.89193993e+01 5.91308937e+01 5.91516571e+01 5.95960159e+01 5.97503700e+01 6.03127136e+01 6.08612823e+01 6.15503693e+01 6.19217339e+01 6.19901123e+01 6.15417099e+01 6.11566811e+01 6.15188751e+01 6.18288078e+01 6.14225693e+01 6.15647049e+01 6.21801758e+01 6.29280472e+01 6.26307716e+01 6.26165390e+01 6.21257629e+01 6.23344498e+01 6.23463478e+01 6.24607239e+01 6.29313622e+01 6.34052048e+01 6.32836342e+01 6.29743423e+01 6.28571320e+01 6.28377953e+01 6.30349426e+01 6.35979195e+01 6.42976303e+01 6.42844009e+01 6.32942276e+01 6.32381096e+01 6.32629890e+01 6.36321220e+01 6.39619217e+01 6.42035141e+01 6.42503586e+01 6.34685440e+01 6.37331696e+01 6.34537506e+01 6.40362320e+01 6.45559464e+01 6.49819412e+01 6.49560852e+01 6.42824707e+01 6.41198273e+01 6.39507256e+01 6.42155304e+01 6.45417557e+01 6.45772629e+01 6.42537155e+01 6.36380997e+01 6.37828064e+01 6.41936722e+01 6.43021545e+01 6.41949921e+01 6.39142075e+01 6.41300583e+01 6.44258575e+01 6.47588120e+01 6.43684082e+01 6.41675491e+01 6.42774048e+01 6.44692993e+01 6.42783585e+01 6.42080154e+01 6.41532135e+01 6.41825943e+01 6.40995941e+01 6.41936035e+01 6.39177055e+01 6.41741562e+01 6.42698746e+01 6.41080399e+01 6.38710442e+01 6.40859222e+01 6.41796875e+01 6.40721817e+01 6.36740990e+01 6.36189804e+01 6.36118622e+01 6.36242523e+01 6.37497101e+01 6.38170280e+01 6.34373779e+01 6.34773483e+01 6.33868675e+01 6.31165695e+01 6.31500702e+01 6.32718468e+01 6.29701195e+01 6.29568405e+01 6.29127579e+01 6.27978477e+01 6.27803421e+01 6.26484756e+01 6.27263412e+01 6.26157722e+01 6.25284500e+01 6.23098030e+01 6.19176712e+01 6.18010483e+01 6.16668282e+01 6.17483673e+01 6.20180054e+01 6.20166359e+01 6.16508636e+01 6.13093796e+01 6.14129868e+01 6.13026314e+01 6.10523872e+01 6.08383179e+01 6.08871117e+01 6.06580238e+01 6.04258995e+01 6.03472939e+01 6.00655746e+01 6.01893539e+01 6.01975288e+01 6.01376991e+01 6.02667007e+01 5.97196999e+01 5.96875420e+01 5.94439735e+01 5.91879196e+01 5.88094482e+01 5.89642448e+01 5.86866341e+01 5.86828613e+01 5.82873306e+01 5.84502983e+01 5.81137238e+01 5.83763504e+01 5.79349403e+01 5.77814560e+01 5.74813652e+01 5.69800682e+01 5.74644585e+01 5.72978516e+01 5.68465118e+01 5.70437050e+01 5.69827766e+01 5.63623352e+01 5.52335014e+01 5.50441933e+01 5.45957260e+01 5.49591026e+01 5.47628555e+01 5.44159698e+01 5.43814812e+01 5.46557922e+01 5.44070015e+01 5.43157005e+01 5.41874733e+01 5.43581200e+01 5.41255112e+01 5.36612473e+01 5.20371742e+01 5.19365730e+01 5.21019516e+01 5.23825111e+01 5.19220581e+01 5.14450645e+01 5.09603500e+01 5.07332726e+01 5.08195534e+01 5.09543076e+01 5.10749359e+01 5.08170280e+01 5.08118248e+01 5.05438232e+01 5.01072159e+01 5.01244240e+01 4.91440468e+01 4.85641327e+01 4.86466255e+01 4.87123413e+01 4.87370567e+01 4.79250526e+01 4.76310768e+01 4.69005966e+01 4.65810013e+01 4.62859116e+01 4.59947701e+01 4.56271896e+01 4.55770645e+01 4.51766281e+01 4.51348152e+01 4.44486008e+01 4.38030243e+01 4.32821617e+01 4.31877136e+01 4.29543877e+01 4.28596535e+01 4.27873802e+01 4.26742020e+01 4.23907127e+01 4.20106506e+01 4.22847939e+01 4.20437584e+01 4.13963966e+01 4.07975006e+01 3.99046516e+01 3.97097931e+01 3.95360909e+01 3.97362366e+01 3.88806763e+01 3.83114128e+01 3.85416031e+01 3.78185730e+01 3.81602783e+01 3.72749062e+01 3.73870468e+01 3.70329132e+01 3.68465385e+01 3.64830627e+01 3.58088913e+01 3.55810280e+01 3.55375557e+01 3.52149048e+01 3.42290764e+01 3.37758179e+01 3.39330368e+01 3.40694733e+01 3.36514320e+01 3.31517639e+01 3.28967972e+01 3.24676514e+01 3.22267380e+01 3.16111870e+01 3.14127541e+01 3.08238354e+01 3.05214539e+01 3.05869865e+01 3.10320187e+01 3.10379601e+01 2.99214649e+01 2.94207916e+01 2.87698631e+01 2.86233368e+01 2.74861889e+01 2.73001862e+01 2.69429054e+01 2.72316017e+01 2.65032635e+01 2.62611580e+01 2.61305351e+01 2.54647484e+01 2.47546768e+01 2.47148514e+01 2.42079430e+01 2.45288925e+01 2.36051540e+01 2.34291859e+01 2.29265480e+01 2.27716370e+01 2.22190304e+01 2.18221455e+01 2.13349934e+01 2.13334122e+01 2.10899315e+01 2.06641941e+01 2.00057392e+01 1.93094616e+01 1.90411472e+01 1.89128838e+01 1.83399715e+01 1.77698479e+01 1.77602882e+01 1.74990978e+01 1.70956001e+01 1.65871754e+01 1.59753141e+01 1.57047186e+01 1.53531876e+01 1.51885414e+01 1.49826727e+01 1.47433329e+01 1.40799141e+01 1.35895548e+01 1.31557045e+01 1.27081070e+01 1.23223314e+01 1.20903997e+01 1.18986921e+01 1.14603920e+01 1.07731762e+01 1.03438892e+01 1.00147276e+01 9.81912327e+00 9.51660442e+00 9.15674591e+00 8.68066788e+00 8.00610161e+00 7.69025612e+00 7.12199831e+00 6.92457819e+00 6.60199451e+00 6.30097103e+00 5.87626457e+00 5.37223053e+00 4.99663734e+00 4.56919718e+00 4.11263227e+00 3.73230672e+00 3.30746317e+00 2.91203761e+00 2.48256588e+00 2.12361646e+00 1.80218017e+00 1.39608991e+00 1.01128876e+00 5.61470509e-01 2.34874308e-01 -1.65350169e-01 -6.16008341e-01 -1.04670727e+00 -1.34305155e+00 -1.68858695e+00 -2.06675625e+00 -2.49748850e+00 -2.88492584e+00 -3.29097056e+00 -3.67763352e+00 -4.10048580e+00 -4.43198109e+00 -4.86104822e+00 -5.27226114e+00 -5.67890310e+00 -6.03513098e+00 -6.41809273e+00 -6.77478266e+00 -7.17496395e+00 -7.58003521e+00 -7.99057293e+00 -8.38882828e+00 -8.76535511e+00 -9.12914085e+00 -9.51774502e+00 -9.90171337e+00 -1.03223658e+01 -1.07145348e+01 -1.10977612e+01 -1.14799089e+01 -1.18707342e+01 -1.22598143e+01 -1.26420908e+01 -1.30211105e+01 -1.34114494e+01 -1.37936382e+01 -1.41774187e+01 -1.45560198e+01 -1.49425678e+01 -1.53233471e+01 -1.57115154e+01 -1.60968246e+01 -1.64762688e+01 -1.68644104e+01 -1.72443352e+01 -1.76290741e+01 -1.80129108e+01 -1.83702812e+01 -1.87408562e+01 -1.91253433e+01 -1.95193996e+01 -1.98903542e+01 -2.02667332e+01 -2.06096096e+01 -2.09865036e+01 -2.13990593e+01 -2.17683086e+01 -2.21372986e+01 -2.25184803e+01 -2.28460159e+01 -2.31996002e+01 -2.35623035e+01 -2.39271717e+01 -2.42410641e+01 -2.46228237e+01 -2.49680920e+01 -2.53340378e+01 -2.56363983e+01 -2.60138588e+01 -2.62953262e+01 -2.66985493e+01 -2.70460186e+01 -2.74280891e+01 -2.78521996e+01 -2.82528954e+01 -2.85522671e+01 -2.88391914e+01 -2.90802059e+01 -2.95068035e+01 -2.98412151e+01 -3.02233906e+01 -3.07228470e+01 -3.10028305e+01 -3.12744465e+01 -3.16490250e+01 -3.18904495e+01 -3.22771072e+01 -3.24759293e+01 -3.28875237e+01 -3.32253380e+01 -3.36479988e+01 -3.40308800e+01 -3.45147324e+01 -3.47939262e+01 -3.52268562e+01 -3.56064911e+01 -3.61133118e+01 -3.62175484e+01 -3.65595245e+01 -3.66315002e+01 -3.68568459e+01 -3.71145706e+01 -3.75014076e+01 -3.78767128e+01 -3.81342125e+01 -3.85241318e+01 -3.87609634e+01 -3.90368500e+01 -3.93627930e+01 -3.98276672e+01 -4.02077522e+01 -4.06138268e+01 -4.08191299e+01 -4.11321945e+01 -4.16046371e+01 -4.17529106e+01 -4.18901939e+01 -4.23214607e+01 -4.25507927e+01 -4.28359909e+01 -4.29861870e+01 -4.32150269e+01 -4.33728828e+01 -4.37363396e+01 -4.43776855e+01 -4.46004333e+01 -4.51015434e+01 -4.53741226e+01 -4.53321075e+01 -4.55716209e+01 -4.57096748e+01 -4.56992912e+01 -4.59381752e+01 -4.63710175e+01 -4.66702690e+01 -4.69461403e+01 -4.74379349e+01 -4.76786385e+01 -4.81675453e+01 -4.84335136e+01 -4.90391846e+01 -4.91853714e+01 -4.91208153e+01 -4.92623558e+01 -4.90825882e+01 -4.93741035e+01 -4.94035759e+01 -5.01643715e+01 -5.01541138e+01 -5.04572716e+01 -5.11763077e+01 -5.10183067e+01 -5.15311394e+01 -5.15571442e+01 -5.20442467e+01 -5.23086815e+01 -5.27510643e+01 -5.30377350e+01 -5.31634903e+01 -5.33063622e+01 -5.34831009e+01 -5.34008255e+01 -5.29775467e+01 -5.32810707e+01 -5.41871338e+01 -5.45004883e+01 -5.47188492e+01 -5.50004387e+01 -5.52890091e+01 -5.52365112e+01 -5.52595100e+01 -5.52397003e+01 -5.59274902e+01 -5.56530952e+01 -5.59056015e+01 -5.67063637e+01 -5.77670059e+01 -5.83573570e+01 -5.75553093e+01 -5.75928841e+01 -5.73546028e+01 -5.76328278e+01 -5.69917030e+01 -5.72460289e+01 -5.76898384e+01 -5.82909050e+01 -5.78229179e+01 -5.82099571e+01 -5.83481979e+01 -5.81924400e+01 -5.85801582e+01 -5.90991974e+01 -5.91619797e+01 -5.99258232e+01 -5.96304131e+01 -5.99958649e+01 -5.97943802e+01 -6.01886330e+01 -5.99422340e+01 -6.02474632e+01 -6.04096489e+01 -6.06956367e+01 -6.11832771e+01 -6.12097359e+01 -6.08924789e+01 -6.04556885e+01 -6.10120926e+01 -6.16070099e+01 -6.11974831e+01 -6.12915421e+01 -6.20446892e+01 -6.23726845e+01 -6.20581322e+01 -6.18847237e+01 -6.15127411e+01 -6.18998528e+01 -6.19533195e+01 -6.21419106e+01 -6.27637596e+01 -6.31846619e+01 -6.29423065e+01 -6.28531609e+01 -6.30326500e+01 -6.29436646e+01 -6.29185829e+01 -6.31388931e+01 -6.35659103e+01 -6.39531784e+01 -6.33624992e+01 -6.29036179e+01 -6.30918579e+01 -6.37661972e+01 -6.41102829e+01 -6.40222549e+01 -6.40741806e+01 -6.36176186e+01 -6.39426193e+01 -6.34687309e+01 -6.37341156e+01 -6.36332207e+01 -6.41319427e+01 -6.42179565e+01 -6.38577499e+01 -6.37643700e+01 -6.35272446e+01 -6.36013412e+01 -6.37543755e+01 -6.40387039e+01 -6.40375595e+01 -6.35174332e+01 -6.36545372e+01 -6.37185287e+01 -6.37994156e+01 -6.40121841e+01 -6.41398849e+01 -6.40302277e+01 -6.40037231e+01 -6.40489578e+01 -6.37408600e+01 -6.40719299e+01 -6.41726532e+01 -6.44493179e+01 -6.43564606e+01 -6.41874619e+01 -6.40464172e+01 -6.40606232e+01 -6.39568710e+01 -6.40000687e+01 -6.39508591e+01 -6.39744492e+01 -6.37734070e+01 -6.40334473e+01 -6.40100555e+01 -6.40365906e+01 -6.38871994e+01 -6.38312569e+01 -6.35462494e+01 -6.32913017e+01 -6.33499908e+01 -6.35892296e+01 -6.37094231e+01 -6.35536728e+01 -6.31013298e+01 -6.30851860e+01 -6.29565582e+01 -6.29428673e+01 -6.28506470e+01 -6.28485680e+01 -6.26576385e+01 -6.25676765e+01 -6.25683899e+01 -6.22422409e+01 -6.19728775e+01 -6.24556046e+01 -6.22667122e+01 -6.18524551e+01 -6.18398705e+01 -6.15535507e+01 -6.16519508e+01 -6.19541893e+01 -6.19847183e+01 -6.15729713e+01 -6.13036003e+01 -6.14375191e+01 -6.11035652e+01 -6.07929916e+01 -6.09785423e+01 -6.06390457e+01 -6.06875076e+01 -6.05339851e+01 -6.05423355e+01 -6.06583252e+01 -6.05996475e+01 -6.06630936e+01 -6.00673180e+01 -5.97134132e+01 -5.98429909e+01 -5.98365822e+01 -5.95630722e+01 -5.93400116e+01 -5.95793152e+01 -5.92891235e+01 -5.94369659e+01 -5.92178802e+01 -5.90177002e+01 -5.84423103e+01 -5.84845352e+01 -5.86408081e+01 -5.85737152e+01 -5.84441109e+01 -5.84857559e+01 -5.79270592e+01 -5.75629921e+01 -5.68757362e+01 -5.68612480e+01 -5.69495239e+01 -5.71425667e+01 -5.71391869e+01 -5.68472481e+01 -5.64307289e+01 -5.60055542e+01 -5.53088455e+01 -5.48190651e+01 -5.42245941e+01 -5.43245392e+01 -5.43101387e+01 -5.42430840e+01 -5.40433006e+01 -5.44123268e+01 -5.41130257e+01 -5.40363121e+01 -5.40935860e+01 -5.38664360e+01 -5.34623947e+01 -5.34060364e+01 -5.20723381e+01 -5.19744148e+01 -5.19453468e+01 -5.21585045e+01 -5.18199234e+01 -5.14487572e+01 -5.13038826e+01 -5.08989525e+01 -5.07723045e+01 -5.08420105e+01 -5.08960571e+01 -5.07020950e+01 -5.03468781e+01 -5.00759087e+01 -4.99816093e+01 -4.97502174e+01 -4.88961143e+01 -4.86641312e+01 -4.86592484e+01 -4.84971123e+01 -4.82422104e+01 -4.75122528e+01 -4.73280220e+01 -4.65428925e+01 -4.64575996e+01 -4.61488533e+01 -4.56175728e+01 -4.51791725e+01 -4.55403633e+01 -4.49081078e+01 -4.46080322e+01 -4.40701866e+01 -4.35493507e+01 -4.33201218e+01 -4.30916443e+01 -4.27793579e+01 -4.27219124e+01 -4.26277351e+01 -4.22483406e+01 -4.20521126e+01 -4.16492805e+01 -4.20647507e+01 -4.17046051e+01 -4.12135315e+01 -4.07783470e+01 -4.00076790e+01 -4.01301117e+01 -3.96110764e+01 -3.95378532e+01 -3.86396408e+01 -3.83192902e+01 -3.84864731e+01 -3.76256371e+01 -3.76536102e+01 -3.67243919e+01 -3.69960785e+01 -3.69237251e+01 -3.69746437e+01 -3.65460739e+01 -3.61579742e+01 -3.58481483e+01 -3.57795448e+01 -3.50995636e+01 -3.40931244e+01 -3.35398140e+01 -3.39389572e+01 -3.38811188e+01 -3.39290466e+01 -3.37170486e+01 -3.30123825e+01 -3.19162102e+01 -3.16954746e+01 -3.17283058e+01 -3.14625072e+01 -3.05869007e+01 -3.02747631e+01 -3.04849930e+01 -3.08401909e+01 -3.67662697e+01 -3.56350822e+01 -3.20719948e+01 -3.08797035e+01 -2.72790833e+01 -2.79296761e+01 -2.75106392e+01 -2.67936134e+01 -2.74911518e+01 -2.49309902e+01 -2.19921608e+01 -2.11260777e+01 -2.76985130e+01 -1.65669922e+02 -2.48627502e+02 -5.81767029e+02 -1.05193652e+03 -12222066. 3.02385425e+06 4.97597850e+09 4.97597850e+09 150547056. 150547056. 5.68310050e+06 122415200. 122415200. 0. 0. 0. 311827328. -32326390. -9.39594971e+02 -5.90506470e+02 -1.22653885e+02 -2.64849060e+02 -1.51814621e+02 -3.13606300e+01 -2.57775040e+01 -5.59173059e+00 -4.22132349e+00 -2.29379482e+01 -2.83364143e+01 -2.01021290e+01 -1.55722694e+01 -1.45166283e+01 -1.33136950e+01 -1.31898422e+01 -1.03815718e+01 -7.13519573e+00 -7.89271164e+00 -1.77799106e+00 -3.00205445e+00 -1.25825911e+01 -7.53811312e+00 -1.28778305e+01 -1.65731850e+01 -8.25728321e+00 -4.59737778e+00 -2.69500542e+00 -5.72428656e+00 -9.75848770e+00 -8.87535572e+00 -5.84686947e+00 -6.68883419e+00 -6.51310015e+00 -5.85411501e+00 -5.34393215e+00 -4.75838614e+00 -4.19228935e+00 -3.69139624e+00 -3.25370932e+00 -2.90406632e+00 -2.47726202e+00 -2.09026194e+00 -1.71002173e+00 -1.21223187e+00 -8.45237792e-01 -4.01680857e-01 1.74508183e-04 3.84425581e-01 7.40838528e-01 1.13072121e+00 7.33344793e-01 1.26509976e+00 1.65342176e+00 1.71395612e+00 2.76859379e+00 3.40718055e+00 3.71298623e+00 4.06330347e+00 4.36074495e+00 4.73053503e+00 5.15386486e+00 5.62765932e+00 5.93233681e+00 6.15256357e+00 6.66635990e+00 7.36670494e+00 7.87100887e+00 8.60092926e+00 9.69860649e+00 8.79309654e+00 3.08600979e+01 1.30036507e+01 1.90244560e+01 4.97356834e+01 2.22510600e+00 3.14088082e+00 1.17297525e+01 1.20020323e+01 1.21039429e+01 1.23984737e+01 1.28882256e+01 1.32967033e+01 1.36213102e+01 1.25109816e+01 3673053. 7.73604126e+01 6.34864845e+01 1.15741493e+02 6.55968552e+01 2.72791195e+01 -3.02648234e+00 -141602224. -39718708. 1.06986275e+02 5.01466179e+01 1.40962276e+01 1.44503307e+01 1.34427519e+01 1.29000683e+01 1.36858969e+01 1.50596676e+01 1.42844524e+01 1.38525133e+01 1.38708153e+01 1.43020830e+01 1.47515621e+01 1.50696917e+01 1.52142649e+01 1.53958597e+01 1.55179529e+01 1.57210255e+01 1.58918419e+01 1.60584412e+01 1.63715515e+01 1.66465626e+01 1.68183632e+01 1.69873028e+01 1.71697445e+01 1.74321880e+01 1.76275101e+01 1.77941494e+01 1.79597378e+01 1.80811939e+01 1.81299992e+01 1.83866997e+01 1.88044243e+01 1.89617081e+01 1.90722408e+01 1.93222542e+01 1.96789150e+01 1.98607960e+01 2.00213394e+01 2.01642456e+01 2.03595047e+01 2.05093136e+01 2.07447681e+01 2.07834091e+01 2.10231781e+01 2.12432957e+01 2.13735638e+01 2.16074486e+01 2.18269062e+01 2.20561466e+01 2.23311768e+01 2.24751072e+01 2.24859085e+01 2.24965897e+01 2.26643276e+01 2.29343204e+01 2.31530628e+01 2.33681374e+01 2.36250324e+01 2.39046040e+01 2.39327927e+01 2.40070763e+01 2.41462212e+01 2.44842319e+01 2.46014099e+01 2.44401398e+01 2.36413803e+01 2.11184959e+01 -7.53366394e+01 -1.62968216e+02 2.32155457e+01 -4.66908325e+02 -2.50502368e+03 136875168. 0. 0. -494129408. -494129408. -494129408. 0. 0. -131372528. -131372528. -131372528. 0. 67967792. 67967792. -7165310. 782688000. -1.13916626e+03 -4.42375092e+02 -9.26796646e+01 2.76170750e+01 3.25322723e+01 2.66013622e+01 2.61177368e+01 2.91854877e+01 2.87012768e+01 2.80526524e+01 2.91181889e+01 3.07885189e+01 3.13110352e+01 3.14403152e+01 3.14008980e+01 3.09306202e+01 3.07838764e+01 3.06409607e+01 3.14115086e+01 3.16214485e+01 3.11371021e+01 3.13039627e+01 3.14316139e+01 3.20733452e+01 3.16096210e+01 3.13233490e+01 3.09756546e+01 3.08964481e+01 3.05910835e+01 3.13480835e+01 3.16545372e+01 3.23604622e+01 3.20792770e+01 3.22335396e+01 3.24436302e+01 3.26889610e+01 3.31586800e+01 3.35685768e+01 3.34636078e+01 3.36863823e+01 3.34361382e+01 3.34609184e+01 3.30236053e+01 3.34405289e+01 3.30671844e+01 3.30663986e+01 3.29421196e+01 3.34995041e+01 3.40880051e+01 3.41226616e+01 3.44632645e+01 3.46060677e+01 3.46638451e+01 3.42277832e+01 3.38230629e+01 3.41554565e+01 3.51354370e+01 3.49987030e+01 3.47933197e+01 3.43803635e+01 3.47320099e+01 3.47567902e+01 3.50601463e+01 3.55364380e+01 3.60266151e+01 3.61376839e+01 3.60770111e+01 3.59360237e+01 3.60433311e+01 3.64035187e+01 3.63624840e+01 3.59447861e+01 3.56038361e+01 3.55971031e+01 3.60273438e+01 3.62723885e+01 3.64006805e+01 3.62577744e+01 3.64997063e+01 3.61004143e+01 3.61952438e+01 3.59927483e+01 3.61513443e+01 3.60540848e+01 3.62766533e+01 3.63789902e+01 3.64276047e+01 3.63787766e+01 3.62960777e+01 3.59004326e+01 3.56546745e+01 3.56575623e+01 3.58491707e+01 3.60309219e+01 3.68026009e+01 3.69392586e+01 3.70208778e+01 3.67721786e+01 3.68981934e+01 3.71964569e+01 3.69278870e+01 3.68423271e+01 3.63695831e+01 3.65763206e+01 3.67670250e+01 3.75427895e+01 3.73156395e+01 3.69893417e+01 3.69765930e+01 3.68632126e+01 3.66354332e+01 3.65509682e+01 3.66609879e+01 3.67273483e+01 3.65148697e+01 3.65360031e+01 3.68993073e+01 3.70593338e+01 3.72495079e+01 3.71630249e+01 3.71581268e+01 3.69963989e+01 3.72019424e+01 3.68924026e+01 3.66159630e+01 3.64519310e+01 3.67473106e+01 3.69607468e+01 3.70176010e+01 3.66517258e+01 3.62097282e+01 3.67754402e+01 3.69508934e+01 3.64214935e+01 3.63441124e+01 3.66272049e+01 3.63951797e+01 3.61376839e+01 3.59658546e+01 3.60108948e+01 3.63173180e+01 3.61633644e+01 3.61716614e+01 3.60866585e+01 3.59430847e+01 3.59647255e+01 3.62252769e+01 3.59006004e+01 3.57535782e+01 3.58280220e+01 3.55582542e+01 3.56387177e+01 3.58299370e+01 3.55993690e+01 3.55798759e+01 3.55587273e+01 3.55162354e+01 3.54434853e+01 3.52826843e+01 3.54680405e+01 3.53827019e+01 3.52097778e+01 3.50919495e+01 3.45799179e+01 3.43296890e+01 3.43839607e+01 3.45819092e+01 3.49471664e+01 3.49079323e+01 3.44397163e+01 3.41035614e+01 3.44843674e+01 3.45345459e+01 3.41886940e+01 3.41281776e+01 3.40208588e+01 3.36230621e+01 3.34979820e+01 3.35945969e+01 3.33675041e+01 3.38268242e+01 3.36095047e+01 3.35620537e+01 3.39138298e+01 3.40015907e+01 3.36378670e+01 3.31500359e+01 3.24675064e+01 3.27678680e+01 3.28056908e+01 3.25612907e+01 3.24313545e+01 3.27158089e+01 3.28350601e+01 3.25818443e+01 3.26074104e+01 3.23497734e+01 3.19641933e+01 3.18159885e+01 3.18358231e+01 3.22583656e+01 3.19060440e+01 3.15094490e+01 3.18345203e+01 3.20377045e+01 3.17052002e+01 3.07898121e+01 3.05307426e+01 3.06132736e+01 3.08211365e+01 3.05341320e+01 3.01810551e+01 3.00425186e+01 3.02336540e+01 3.01297131e+01 2.99919415e+01 2.96356163e+01 2.99801903e+01 3.00389194e+01 2.96106415e+01 2.87913666e+01 2.87937012e+01 2.88713779e+01 2.89670048e+01 2.89628963e+01 2.88725624e+01 2.85093708e+01 2.79969902e+01 2.80668163e+01 2.80450401e+01 2.85314960e+01 2.82885303e+01 2.77143822e+01 2.68705502e+01 2.69152470e+01 2.71954117e+01 2.69632854e+01 2.65569286e+01 2.63035431e+01 2.58345108e+01 2.58455181e+01 2.57148705e+01 2.56482468e+01 2.59838066e+01 2.57325573e+01 2.55468464e+01 2.47329788e+01 2.39603138e+01 2.42831383e+01 2.46245422e+01 2.49344902e+01 2.47303448e+01 2.44917526e+01 2.42469273e+01 2.41443920e+01 2.42875652e+01 2.39608097e+01 2.35421562e+01 2.32379780e+01 2.32329674e+01 2.28918419e+01 2.25149403e+01 2.19746914e+01 2.17718391e+01 2.15793724e+01 2.15460052e+01 2.14975166e+01 2.11500549e+01 2.14914703e+01 2.14485703e+01 2.18582478e+01 2.10624409e+01 2.06080360e+01 2.02177219e+01 2.07130032e+01 2.08075752e+01 1.99812832e+01 1.99590607e+01 1.97094212e+01 1.98979626e+01 1.87950478e+01 1.81238842e+01 1.78099670e+01 1.75547733e+01 1.71029434e+01 1.71300068e+01 1.73522530e+01 1.76214123e+01 1.71663704e+01 1.74777641e+01 1.72437096e+01 1.72719879e+01 1.70458050e+01 1.72290974e+01 1.65761299e+01 1.64071789e+01 1.56912193e+01 1.54399700e+01 1.49061737e+01 1.50138044e+01 1.45820713e+01 1.40278702e+01 1.38630896e+01 1.37565613e+01 1.39974174e+01 1.37925434e+01 1.41294079e+01 1.35777617e+01 1.32658501e+01 1.27931433e+01 1.24275446e+01 1.25499363e+01 1.30934553e+01 1.24036798e+01 1.23523474e+01 1.19046898e+01 1.20390072e+01 1.15980225e+01 1.11725264e+01 1.13317089e+01 1.12392015e+01 1.09358988e+01 1.05924520e+01 1.02464781e+01 1.01940002e+01 9.75187111e+00 9.51037502e+00 9.30679703e+00 9.03595924e+00 8.77396679e+00 8.79404831e+00 8.67101383e+00 8.51070404e+00 8.14146900e+00 7.97583675e+00 7.49458933e+00 7.26228094e+00 6.83230448e+00 6.95297337e+00 6.79287386e+00 6.57864952e+00 6.28777885e+00 6.03713226e+00 5.80501080e+00 5.45869541e+00 5.04959345e+00 4.63317347e+00 4.34696913e+00 4.25222492e+00 4.15339851e+00 4.21764517e+00 3.92601299e+00 3.75057626e+00 3.53388524e+00 3.38513780e+00 3.20700765e+00 2.77001095e+00 2.55190802e+00 2.13828135e+00 2.07299042e+00 1.96310318e+00 1.85213065e+00 1.57895339e+00 1.25474036e+00 1.01930034e+00 7.68988073e-01 5.60157359e-01 2.34901875e-01 5.82632497e-02 -1.58641011e-01 -3.21513593e-01 -6.45429730e-01 -7.66750574e-01 -9.40986633e-01 -1.11695766e+00 -1.37612212e+00 -1.55727291e+00 -1.90877664e+00 -2.18265533e+00 -2.39304018e+00 -2.51855350e+00 -2.79770327e+00 -3.03388810e+00 -3.17060852e+00 -3.44859886e+00 -3.74486136e+00 -3.98725700e+00 -4.15711737e+00 -4.34351826e+00 -4.58665943e+00 -4.86737680e+00 -5.13669014e+00 -5.35043240e+00 -5.55138111e+00 -5.78226089e+00 -6.00203800e+00 -6.18159008e+00 -6.42130566e+00 -6.64468050e+00 -6.86157084e+00 -7.07374096e+00 -7.30572796e+00 -7.51365137e+00 -7.75464630e+00 -7.97965908e+00 -8.23210049e+00 -8.46095181e+00 -8.67667580e+00 -8.87213612e+00 -9.08075047e+00 -9.29898643e+00 -9.51380634e+00 -9.72699928e+00 -9.93739986e+00 -1.01543322e+01 -1.03726826e+01 -1.05901613e+01 -1.08088150e+01 -1.10261154e+01 -1.12417746e+01 -1.14569464e+01 -1.16708145e+01 -1.18926611e+01 -1.21061888e+01 -1.23057814e+01 -1.25191746e+01 -1.27416763e+01 -1.29619989e+01 -1.31664085e+01 -1.33719082e+01 -1.36022835e+01 -1.37687397e+01 -1.39400454e+01 -1.42424831e+01 -1.44672403e+01 -1.46633825e+01 -1.48392334e+01 -1.49776382e+01 -1.52218370e+01 -1.54450493e+01 -1.56961880e+01 -1.58966684e+01 -1.60405235e+01 -1.61765919e+01 -1.64261990e+01 -1.65580750e+01 -1.67837486e+01 -1.70285549e+01 -1.72287674e+01 -1.74514999e+01 -1.76400394e+01 -1.78852882e+01 -1.81259956e+01 -1.81872253e+01 -1.82162571e+01 -1.85373325e+01 -1.87562275e+01 -1.89536781e+01 -1.92028198e+01 -1.94592800e+01 -1.96919441e+01 -1.98933258e+01 -1.99575768e+01 -2.00936413e+01 -2.02729454e+01 -2.05096169e+01 -2.06365242e+01 -2.07545986e+01 -2.09855442e+01 -2.12808552e+01 -2.15941238e+01 -2.17892036e+01 -2.20314846e+01 -2.22248707e+01 -2.23900318e+01 -2.23997593e+01 -2.24872494e+01 -2.26119766e+01 -2.26020412e+01 -2.29147892e+01 -2.33606262e+01 -2.36713505e+01 -2.41013718e+01 -2.39813023e+01 -2.36329117e+01 -2.38747177e+01 -2.45051270e+01 -2.47219372e+01 -2.46163883e+01 -2.45835629e+01 -2.46697178e+01 -2.52130680e+01 -2.54074364e+01 -2.55050983e+01 -2.55996456e+01 -2.57346153e+01 -2.57279625e+01 -2.59345570e+01 -2.61026402e+01 -2.64382229e+01 -2.65106773e+01 -2.65952721e+01 -2.65071621e+01 -2.64423294e+01 -2.69496784e+01 -2.72959137e+01 -2.78517189e+01 -2.79017067e+01 -2.78435631e+01 -2.77394466e+01 -2.79342365e+01 -2.82432518e+01 -2.85855503e+01 -2.88610687e+01 -2.88032417e+01 -2.88794899e+01 -2.92145786e+01 -2.94497662e+01 -2.91933002e+01 -2.91816311e+01 -2.91975842e+01 -2.92344303e+01 -2.92326298e+01 -2.95374336e+01 -3.01576691e+01 -3.05156746e+01 -3.08288422e+01 -3.05358105e+01 -3.06070442e+01 -3.06089058e+01 -3.14916973e+01 -3.14293461e+01 -3.11842537e+01 -3.13832588e+01 -3.15548878e+01 -3.22389145e+01 -3.14451027e+01 -3.09892845e+01 -3.06301155e+01 -3.06126957e+01 -3.07623634e+01 -3.15925617e+01 -3.17615471e+01 -3.21238861e+01 -3.20004005e+01 -3.26719551e+01 -3.26854858e+01 -3.28187141e+01 -3.29131470e+01 -3.36059875e+01 -3.32015305e+01 -3.31595535e+01 -3.31086159e+01 -3.30304642e+01 -3.29152946e+01 -3.32718086e+01 -3.34145012e+01 -3.31040573e+01 -3.32397690e+01 -3.32582207e+01 -3.36998825e+01 -3.39489288e+01 -3.43402023e+01 -3.40218964e+01 -3.38100052e+01 -3.36138268e+01 -3.34074783e+01 -3.41868553e+01 -3.51763191e+01 -3.48344269e+01 -3.48385239e+01 -3.48642502e+01 -3.53779526e+01 -3.54235077e+01 -3.51647758e+01 -3.53067703e+01 -3.56640816e+01 -3.57321281e+01 -3.57687798e+01 -3.56856804e+01 -3.58393707e+01 -3.57165794e+01 -3.56006622e+01 -3.55283775e+01 -3.55657310e+01 -3.54851074e+01 -3.59148903e+01 -3.62845917e+01 -3.64586983e+01 -3.63284416e+01 -3.64294548e+01 -3.58273849e+01 -3.59616814e+01 -3.55154572e+01 -3.58192863e+01 -3.59858589e+01 -3.62785454e+01 -3.64280319e+01 -3.67311592e+01 -3.67208672e+01 -3.64158211e+01 -3.58554878e+01 -3.53255272e+01 -3.49917450e+01 -3.54850540e+01 -3.61587296e+01 -3.66928215e+01 -3.67935104e+01 -3.66319313e+01 -3.64914169e+01 -3.65607491e+01 -3.67972298e+01 -3.66527519e+01 -3.68512230e+01 -3.64352913e+01 -3.64771347e+01 -3.65422859e+01 -3.70025826e+01 -3.68347092e+01 -3.66748428e+01 -3.67219276e+01 -3.65551186e+01 -3.61855888e+01 -3.57731552e+01 -3.61401176e+01 -3.64432373e+01 -3.67362442e+01 -3.65146370e+01 -3.66360626e+01 -3.67612762e+01 -3.69422989e+01 -3.70302353e+01 -3.70037270e+01 -3.66042633e+01 -3.65977402e+01 -3.66510391e+01 -3.68887215e+01 -3.66349258e+01 -3.67736702e+01 -3.72138252e+01 -3.69578247e+01 -3.64603844e+01 -3.61937828e+01 -3.67446938e+01 -3.67905426e+01 -3.66306801e+01 -3.61674347e+01 -3.59859009e+01 -3.61508064e+01 -3.62296562e+01 -3.59516907e+01 -3.59053192e+01 -3.61106606e+01 -3.60423508e+01 -3.60716743e+01 -3.58891029e+01 -3.60866890e+01 -3.61387177e+01 -3.61085243e+01 -3.58620033e+01 -3.55198975e+01 -3.53804855e+01 -3.54323196e+01 -3.55704918e+01 -3.55377808e+01 -3.53900452e+01 -3.53545074e+01 -3.54139023e+01 -3.50943260e+01 -3.48760757e+01 -3.54047890e+01 -3.51279221e+01 -3.47105637e+01 -3.47934914e+01 -3.46768684e+01 -3.48822174e+01 -3.50099297e+01 -3.49293022e+01 -3.46386566e+01 -3.43228149e+01 -3.43083153e+01 -3.42449417e+01 -3.41360779e+01 -3.40764313e+01 -3.40707779e+01 -3.39938927e+01 -3.38990135e+01 -3.37134171e+01 -3.37071915e+01 -3.42274399e+01 -3.41535072e+01 -3.34587402e+01 -3.34036446e+01 -3.31444740e+01 -3.34745789e+01 -3.34740219e+01 -3.35691833e+01 -3.36259460e+01 -3.31205482e+01 -3.27809601e+01 -3.32699356e+01 -3.30515785e+01 -3.27368279e+01 -3.23481102e+01 -3.29006233e+01 -3.27938271e+01 -3.26296158e+01 -3.25135040e+01 -3.20988197e+01 -3.16165810e+01 -3.15266285e+01 -3.16635609e+01 -3.16838837e+01 -3.15188160e+01 -3.15184326e+01 -3.15414219e+01 -3.16177635e+01 -3.13404961e+01 -3.07046947e+01 -3.04230137e+01 -3.01151772e+01 -3.05700817e+01 -3.01757870e+01 -2.98322163e+01 -2.97562981e+01 -3.00795536e+01 -2.98271790e+01 -2.95139408e+01 -2.93457642e+01 -2.93055878e+01 -2.93572655e+01 -2.92348804e+01 -2.86978436e+01 -2.86772308e+01 -2.87080498e+01 -2.85968838e+01 -2.85153141e+01 -2.83863506e+01 -2.84110775e+01 -2.80082436e+01 -2.79880409e+01 -2.80093250e+01 -2.81260204e+01 -2.78563824e+01 -2.73733463e+01 -2.66343708e+01 -2.68789482e+01 -2.71210384e+01 -2.69071217e+01 -2.64466629e+01 -2.61357956e+01 -2.58131199e+01 -2.57293663e+01 -2.54860058e+01 -2.52705803e+01 -2.53065834e+01 -2.54175053e+01 -2.52228489e+01 -2.42628078e+01 -2.33555527e+01 -2.39920998e+01 -2.47925701e+01 -2.48854027e+01 -2.44276123e+01 -2.41103745e+01 -2.38076763e+01 -2.37370605e+01 -2.35629444e+01 -2.36093884e+01 -2.34103260e+01 -2.29930153e+01 -2.27562752e+01 -2.25468712e+01 -2.24589901e+01 -2.20214977e+01 -2.16028099e+01 -2.13508358e+01 -2.14015980e+01 -2.17158966e+01 -2.13494797e+01 -2.12320442e+01 -2.09527607e+01 -2.12888184e+01 -2.06463928e+01 -2.03938751e+01 -2.00791779e+01 -2.03950996e+01 -2.01551800e+01 -1.98504601e+01 -1.99432945e+01 -1.96396275e+01 -1.99655819e+01 -1.89178410e+01 -1.83990383e+01 -1.77883644e+01 -1.72311745e+01 -1.69586468e+01 -1.72126808e+01 -1.72893982e+01 -1.74058704e+01 -1.72377262e+01 -1.72348003e+01 -1.67157078e+01 -1.68859901e+01 -1.70892391e+01 -1.72084408e+01 -1.62673893e+01 -1.60471783e+01 -1.55697784e+01 -1.53263283e+01 -1.46893082e+01 -1.47006073e+01 -1.74466534e+01 -1.65785618e+01 -1.29739799e+01 -1.41459246e+01 -1.39609556e+01 -1.32907686e+01 -1.43172894e+01 -1.22223663e+01 -9.97094631e+00 -1.16512766e+01 -1.33346243e+01 -1.08499556e+01 -1.05454645e+01 -1.48216064e+02 -1.99181274e+02 -4.34404327e+02 -2.46269824e+03 560128384. 0. 150547056. 150547056. 5.68310050e+06 122415200. 122415200. 0. 0. 0. 0. 0. -126059192. -71584032. -6.31877979e+03 -1.38713684e+03 -5.50055725e+02 -3.13691883e+01 -2.10277451e+02 -9.75711594e+01 -3.15437055e+00 -1.64319534e+01 -2.05077324e+01 -1.20934200e+01 -6.76314735e+00 -5.90669346e+00 -4.81183243e+00 -5.18570900e+00 -2.99170327e+00 -2.86813021e-01 -1.51133144e+00 2.89848948e+00 1.04795790e+00 -7.91038656e+00 -6.33122826e+00 -7.14499331e+00 -7.25687361e+00 -2.47822666e+00 -1.72514188e+00 -2.14195156e+00 -3.71937394e+00 -3.51248121e+00 -9.27938282e-01 1.05480216e-01 -1.81067204e+00 -1.94012761e+00 -1.66315567e+00 -1.42982614e+00 -1.00115943e+00 -5.77359378e-01 -8.35400298e-02 1.75607219e-01 2.79924423e-01 3.54273319e-01 6.00571990e-01 8.26947153e-01 1.14774716e+00 1.34786677e+00 1.63709319e+00 1.92308724e+00 2.13377357e+00 2.25946975e+00 2.45807076e+00 1.97645056e+00 2.48657823e+00 2.93243957e+00 2.89250016e+00 3.90776730e+00 4.36762667e+00 4.55928898e+00 4.69613218e+00 4.84753704e+00 5.04768467e+00 5.38872862e+00 5.69900513e+00 5.85860348e+00 6.01588011e+00 6.27811098e+00 6.64935160e+00 6.97938013e+00 7.50857782e+00 8.47982883e+00 6.66293192e+00 4.09284897e+01 5.32978363e+01 1.01649307e+02 2.98434052e+02 4.57936287e+00 1.63960648e+01 4.58266258e+01 4.06594276e+00 1.68453941e+01 3.08416862e+01 4.54298706e+01 4.60997505e+01 4.61721268e+01 4.49262428e+01 31273378. 105598960. 105598960. 270841728. -126840040. -126840040. -126840040. 0. 0. 476654848. 3.90038361e+02 9.38689804e+01 2.08252506e+01 -1.74435673e+01 -8.94463062e+00 9.18114948e+00 1.07395515e+01 1.05826635e+01 1.05590429e+01 1.05947676e+01 1.07334909e+01 1.10756426e+01 1.13531570e+01 1.15877962e+01 1.18959179e+01 1.20078878e+01 1.21701803e+01 1.23569460e+01 1.26597395e+01 1.29951324e+01 1.32731094e+01 1.35304432e+01 1.38836842e+01 1.42092714e+01 1.43741798e+01 1.45374908e+01 1.46405106e+01 1.48830376e+01 1.50855322e+01 1.53801451e+01 1.57772627e+01 1.60045738e+01 1.61931324e+01 1.63148441e+01 1.61939831e+01 1.64171467e+01 1.71394501e+01 1.74767151e+01 1.83327808e+01 1.85286121e+01 1.81831379e+01 1.83980980e+01 1.86076851e+01 1.89688587e+01 1.90677681e+01 1.91705799e+01 1.94702320e+01 1.96238842e+01 1.98112774e+01 1.98693657e+01 2.02874718e+01 2.05162563e+01 2.08125381e+01 2.10026817e+01 2.11677856e+01 2.14042072e+01 2.15012512e+01 2.20804176e+01 2.23155365e+01 2.23790016e+01 2.24441223e+01 2.27170410e+01 2.29479122e+01 2.23065624e+01 2.24241123e+01 -7.08526840e+01 -1.50839661e+02 -3.87111023e+02 -1.20433459e+03 -6.49290977e+04 -144773488. 162565248. 0. -251944816. -251944816. 1742333568. -494129408. -494129408. 0. 0. 0. 0. 0. 0. -1.74448953e+05 1.52849902e+03 2.56537231e+02 -4.12032654e+02 -1.73033569e+02 -8.68375168e+01 2.93207932e+01 2.79401798e+01 3.03904152e+01 2.96285191e+01 2.94076633e+01 2.94493332e+01 2.97423820e+01 2.89824581e+01 2.99467487e+01 3.10683136e+01 3.09691734e+01 3.12612591e+01 3.12343807e+01 3.12508183e+01 3.10719624e+01 3.11004066e+01 3.12544575e+01 3.13257713e+01 3.16449738e+01 3.21233444e+01 3.23085861e+01 3.21930008e+01 3.24680634e+01 3.25519028e+01 3.27671394e+01 3.30648804e+01 3.32756195e+01 3.34374847e+01 3.35715027e+01 3.36423340e+01 3.37502441e+01 3.38686752e+01 3.41372032e+01 3.40439529e+01 3.39135437e+01 3.40364227e+01 3.48789177e+01 3.47308998e+01 3.53617516e+01 3.53609657e+01 3.52110710e+01 3.53686905e+01 3.55666580e+01 3.64717445e+01 3.66674614e+01 3.68842354e+01 3.65301437e+01 3.64664803e+01 3.63462219e+01 3.60047379e+01 3.56475372e+01 3.62936211e+01 3.65230141e+01 3.72674026e+01 3.73956833e+01 3.81194572e+01 3.71561699e+01 3.71257896e+01 3.75590286e+01 3.77927513e+01 3.75283203e+01 3.73483467e+01 3.80970306e+01 3.85685883e+01 3.88376694e+01 3.85371552e+01 3.83998795e+01 3.87676811e+01 3.86883545e+01 3.86259842e+01 3.91133423e+01 3.94707909e+01 3.91597023e+01 3.90442848e+01 3.93444633e+01 3.99631958e+01 3.97991409e+01 3.97579536e+01 3.95059700e+01 3.98536263e+01 3.97866669e+01 3.94173775e+01 3.89417572e+01 3.96229782e+01 4.02318344e+01 4.03454552e+01 4.03156128e+01 3.96823692e+01 3.99237328e+01 3.99656639e+01 3.97390518e+01 4.03437042e+01 4.09267654e+01 4.12245445e+01 4.04585533e+01 4.00206642e+01 4.08604889e+01 4.15643196e+01 4.16405144e+01 4.04433136e+01 4.07489014e+01 4.06717491e+01 4.10961037e+01 4.12778969e+01 4.11422005e+01 4.12262039e+01 4.12876778e+01 4.13728981e+01 4.12613144e+01 4.14703903e+01 4.16407242e+01 4.15255203e+01 4.16449623e+01 4.21244431e+01 4.21553726e+01 4.18959503e+01 4.16371117e+01 4.15398598e+01 4.17436600e+01 4.18618431e+01 4.21013107e+01 4.18687897e+01 4.15160370e+01 4.16611137e+01 4.17027664e+01 4.18064461e+01 4.19673462e+01 4.18182182e+01 4.12929955e+01 4.23142166e+01 4.22947540e+01 4.16000404e+01 4.16737137e+01 4.21552353e+01 4.22363167e+01 4.18194160e+01 4.15284233e+01 4.15901871e+01 4.19313431e+01 4.19103012e+01 4.18875351e+01 4.21302795e+01 4.19086647e+01 4.18336601e+01 4.19494743e+01 4.16148911e+01 4.14511986e+01 4.16628304e+01 4.15379105e+01 4.16228867e+01 4.18966141e+01 4.17828751e+01 4.16703339e+01 4.17314186e+01 4.16584778e+01 4.15304108e+01 4.14642525e+01 4.16802635e+01 4.16168709e+01 4.12732086e+01 4.12657700e+01 4.08023415e+01 4.07434654e+01 4.09993858e+01 4.08509979e+01 4.12138786e+01 4.12190285e+01 4.05335083e+01 4.04831848e+01 4.08277435e+01 4.09015160e+01 4.07540665e+01 4.08069267e+01 4.04571381e+01 4.00977364e+01 4.02090950e+01 3.99976425e+01 4.01700401e+01 4.06297455e+01 4.04838905e+01 4.04188194e+01 4.08915138e+01 4.04859886e+01 4.00961533e+01 3.98435669e+01 3.96097488e+01 3.95611649e+01 3.96739616e+01 3.98841248e+01 3.98714142e+01 3.97911720e+01 3.95264664e+01 3.92354507e+01 3.93085403e+01 3.93906174e+01 3.96455612e+01 3.92911568e+01 3.92332993e+01 3.95444870e+01 3.91181641e+01 3.82799683e+01 3.83225288e+01 3.87198257e+01 3.84963150e+01 3.86828880e+01 3.83941383e+01 3.84579353e+01 3.82487106e+01 3.78880348e+01 3.75990143e+01 3.70535545e+01 3.69516678e+01 3.72592735e+01 3.72442780e+01 3.69785767e+01 3.64298477e+01 3.66379433e+01 3.62440529e+01 3.64435387e+01 3.63296013e+01 3.59767265e+01 3.59702377e+01 3.59780083e+01 3.62559242e+01 3.60369492e+01 3.57506714e+01 3.55083313e+01 3.51671715e+01 3.56084518e+01 3.48567848e+01 3.48769760e+01 3.45816307e+01 3.46453934e+01 3.46274757e+01 3.40227852e+01 3.38494186e+01 3.37874069e+01 3.44889183e+01 3.44035187e+01 3.36741982e+01 3.35890999e+01 3.36434822e+01 3.34695282e+01 3.30591698e+01 3.27557716e+01 3.27082100e+01 3.22789993e+01 3.16122169e+01 3.16296024e+01 3.19894352e+01 3.27341003e+01 3.27660103e+01 3.21923409e+01 3.17402534e+01 3.15558167e+01 3.10722313e+01 3.13764439e+01 3.11084709e+01 3.06605854e+01 3.02268715e+01 2.96693535e+01 2.98331566e+01 2.97501316e+01 2.96512089e+01 2.90744629e+01 2.87620983e+01 2.87988033e+01 2.93355694e+01 2.88619156e+01 2.83428993e+01 2.77345524e+01 2.75105839e+01 2.72178249e+01 2.70762234e+01 2.71930561e+01 2.73595943e+01 2.73167229e+01 2.70915241e+01 2.67272739e+01 2.63101368e+01 2.61963482e+01 2.58909626e+01 2.55433369e+01 2.54599380e+01 2.55039940e+01 2.51589375e+01 2.53300037e+01 2.50865574e+01 2.48845043e+01 2.43289948e+01 2.41599751e+01 2.37835007e+01 2.40427761e+01 2.34214706e+01 2.33460636e+01 2.28047390e+01 2.28646393e+01 2.27359314e+01 2.18735561e+01 2.21414433e+01 2.22735195e+01 2.23310032e+01 2.19723434e+01 2.17240696e+01 2.12785702e+01 2.05640240e+01 1.99935970e+01 2.01805401e+01 1.97758045e+01 2.00775242e+01 1.99697170e+01 2.01652164e+01 1.94104252e+01 1.91172981e+01 1.90490208e+01 1.91355267e+01 1.81773815e+01 1.79269753e+01 1.81798782e+01 1.75834408e+01 1.73016109e+01 1.68106747e+01 1.65889587e+01 1.63756428e+01 1.60594997e+01 1.59164257e+01 1.59448719e+01 1.59667568e+01 1.57344656e+01 1.53572626e+01 1.51335793e+01 1.51198769e+01 1.47543411e+01 1.45260515e+01 1.40930748e+01 1.39041224e+01 1.36418352e+01 1.33351240e+01 1.27354460e+01 1.26706867e+01 1.26023893e+01 1.23905954e+01 1.21726618e+01 1.16701612e+01 1.13797712e+01 1.11179867e+01 1.08101072e+01 1.07147284e+01 1.05283766e+01 1.03419456e+01 1.01190872e+01 9.74295998e+00 9.50929260e+00 9.08335018e+00 8.92434025e+00 8.63104534e+00 8.52900314e+00 8.39941692e+00 8.23596287e+00 7.80182362e+00 7.49119234e+00 7.35002089e+00 7.07536888e+00 6.87725639e+00 6.72366714e+00 6.45068932e+00 6.17653608e+00 5.84725857e+00 5.60078239e+00 5.35210371e+00 5.03394318e+00 4.77193546e+00 4.40237045e+00 4.19528484e+00 4.04125881e+00 3.79041028e+00 3.52582288e+00 3.25313354e+00 2.98116255e+00 2.67382050e+00 2.39923906e+00 2.22853303e+00 1.94808793e+00 1.74316692e+00 1.47357082e+00 1.20927405e+00 9.28696632e-01 6.89597070e-01 4.51839179e-01 1.71917900e-01 -9.98251960e-02 -3.26480597e-01 -6.32462919e-01 -9.01085377e-01 -1.11082089e+00 -1.37337220e+00 -1.63382339e+00 -1.89290297e+00 -2.16077137e+00 -2.41586447e+00 -2.66563463e+00 -2.93111515e+00 -3.19442034e+00 -3.49686170e+00 -3.76393294e+00 -3.99568725e+00 -4.21213531e+00 -4.45718193e+00 -4.73590517e+00 -4.98634243e+00 -5.23760080e+00 -5.49255085e+00 -5.74878645e+00 -6.00354099e+00 -6.25724983e+00 -6.51375389e+00 -6.77025270e+00 -7.02495718e+00 -7.28200102e+00 -7.53770304e+00 -7.79479742e+00 -8.05821800e+00 -8.27953339e+00 -8.48940659e+00 -8.81408787e+00 -9.07899475e+00 -9.28458023e+00 -9.53984165e+00 -9.84166241e+00 -1.00414467e+01 -1.02228842e+01 -1.05115738e+01 -1.07808046e+01 -1.10862284e+01 -1.12987862e+01 -1.15341187e+01 -1.18269453e+01 -1.20757914e+01 -1.23168583e+01 -1.25090046e+01 -1.27601023e+01 -1.30074987e+01 -1.33120308e+01 -1.34976044e+01 -1.39391050e+01 -1.42536182e+01 -1.42856312e+01 -1.44224186e+01 -1.45881672e+01 -1.49541941e+01 -1.53482141e+01 -1.56792269e+01 -1.58222980e+01 -1.59515438e+01 -1.62170639e+01 -1.64607716e+01 -1.66782322e+01 -1.68146839e+01 -1.71105251e+01 -1.74498577e+01 -1.77469902e+01 -1.78978786e+01 -1.80749359e+01 -1.82922688e+01 -1.84959221e+01 -1.87884178e+01 -1.89229279e+01 -1.90846558e+01 -1.93884773e+01 -1.96569576e+01 -1.98647804e+01 -1.98397655e+01 -2.01324520e+01 -2.03534584e+01 -2.08577976e+01 -2.10507221e+01 -2.11484947e+01 -2.14455357e+01 -2.17747250e+01 -2.22244091e+01 -2.26124115e+01 -2.27368946e+01 -2.24895802e+01 -2.27912216e+01 -2.35198383e+01 -2.34040184e+01 -2.33944244e+01 -2.35000782e+01 -2.37603741e+01 -2.41191635e+01 -2.44081211e+01 -2.44896355e+01 -2.46006489e+01 -2.52998066e+01 -2.54168930e+01 -2.54252224e+01 -2.54118958e+01 -2.57189102e+01 -2.60995178e+01 -2.59850864e+01 -2.60656204e+01 -2.63709908e+01 -2.65352440e+01 -2.67475834e+01 -2.72221909e+01 -2.74602299e+01 -2.78877125e+01 -2.81007671e+01 -2.81590462e+01 -2.79491367e+01 -2.82590866e+01 -2.84280205e+01 -2.90531902e+01 -2.90130539e+01 -2.89193153e+01 -2.93335953e+01 -2.97210007e+01 -3.00881138e+01 -3.00715408e+01 -2.98631744e+01 -2.95483208e+01 -2.99473095e+01 -3.04495506e+01 -3.13140945e+01 -3.09475670e+01 -3.07935905e+01 -3.10283699e+01 -3.12970104e+01 -3.16143894e+01 -3.14164104e+01 -3.15890121e+01 -3.19709625e+01 -3.22392426e+01 -3.26472054e+01 -3.25591812e+01 -3.26091881e+01 -3.25236511e+01 -3.26447258e+01 -3.31051979e+01 -3.38153114e+01 -3.39361076e+01 -3.35310631e+01 -3.37547150e+01 -3.39730530e+01 -3.42772331e+01 -3.40436096e+01 -3.39825325e+01 -3.39720345e+01 -3.45493965e+01 -3.44984741e+01 -3.50166283e+01 -3.48314247e+01 -3.48557663e+01 -3.53462410e+01 -3.55320702e+01 -3.61069260e+01 -3.62659340e+01 -3.64927177e+01 -3.65045128e+01 -3.66570129e+01 -3.64596596e+01 -3.60447617e+01 -3.57286644e+01 -3.63245811e+01 -3.62661552e+01 -3.68967018e+01 -3.69305191e+01 -3.76417847e+01 -3.73208122e+01 -3.77347603e+01 -3.81190109e+01 -3.82854233e+01 -3.79218292e+01 -3.73889999e+01 -3.75725746e+01 -3.79357681e+01 -3.81759186e+01 -3.82864647e+01 -3.87446709e+01 -3.89188385e+01 -3.85307426e+01 -3.85280418e+01 -3.86753807e+01 -3.91808510e+01 -3.93544426e+01 -3.91357651e+01 -3.92807770e+01 -3.97290916e+01 -3.98014870e+01 -3.96971970e+01 -3.94007874e+01 -3.96451073e+01 -3.94200974e+01 -3.92892151e+01 -3.89006424e+01 -3.94708061e+01 -4.02223358e+01 -4.03707581e+01 -4.04454384e+01 -3.98649635e+01 -3.95678253e+01 -3.98435936e+01 -4.00598412e+01 -4.02840195e+01 -4.05378799e+01 -4.11047668e+01 -4.10032539e+01 -4.03529167e+01 -4.04142723e+01 -4.00889511e+01 -4.01108284e+01 -4.03028450e+01 -4.11263390e+01 -4.08706207e+01 -4.11327286e+01 -4.06856613e+01 -4.06353874e+01 -4.11483803e+01 -4.12082825e+01 -4.12796364e+01 -4.06886139e+01 -3.82693214e+01 -3.88928032e+01 -4.11384048e+01 -4.23698311e+01 -4.29949036e+01 -4.19398193e+01 -4.11228104e+01 -4.12660141e+01 -3.97351494e+01 1.64729614e+02 -4.26349716e+01 -2.70377045e+02 -4.34670792e+01 -4.60173836e+01 1.62735672e+02 -4.03361702e+01 -2.71173279e+02 -4.00100212e+01 -4.07522621e+01 -4.22294579e+01 -4.25230179e+01 -4.24905510e+01 -4.27728615e+01 -4.30329933e+01 -4.36771851e+01 -4.40111847e+01 -4.26237526e+01 -4.16479988e+01 -4.18750153e+01 -4.14578285e+01 -4.16033592e+01 -4.21535645e+01 -4.18044434e+01 -4.18264771e+01 -4.20542984e+01 -4.22461052e+01 -4.18879089e+01 -4.12526779e+01 -4.13011208e+01 -4.18710327e+01 -4.16600342e+01 -4.10862236e+01 -4.17320557e+01 -4.16038322e+01 -4.17031479e+01 -4.16612015e+01 -4.08020782e+01 -4.11989784e+01 -4.17467651e+01 -4.15230789e+01 -4.11930885e+01 -4.11155624e+01 -4.13948250e+01 -4.14673500e+01 -4.11702728e+01 -4.09223442e+01 -4.08141327e+01 -4.08591881e+01 -4.09086800e+01 -4.09265823e+01 -4.05433044e+01 -4.04500465e+01 -4.03558197e+01 -4.05460739e+01 -4.04095039e+01 -4.01842957e+01 -4.06656342e+01 -4.05680084e+01 -4.03048363e+01 -4.06573372e+01 -4.06153717e+01 -4.04813766e+01 -4.03069649e+01 -3.99287186e+01 -3.99125519e+01 -3.99170036e+01 -3.94363327e+01 -3.97991867e+01 -4.03262825e+01 -4.03831596e+01 -4.02032776e+01 -4.00750809e+01 -3.97019386e+01 -3.88595200e+01 -3.88437042e+01 -3.87596130e+01 -3.92058754e+01 -3.89244270e+01 -3.88196373e+01 -3.84815331e+01 -3.78181648e+01 -3.78242950e+01 -3.74890251e+01 -3.80150375e+01 -3.81058998e+01 -3.83713531e+01 -3.85159340e+01 -3.82605362e+01 -3.82554893e+01 -3.75968018e+01 -3.77078972e+01 -3.72496872e+01 -3.69524879e+01 -3.67483215e+01 -3.65460472e+01 -3.62146606e+01 -3.56064224e+01 -3.63518562e+01 -3.64286308e+01 -3.66434441e+01 -3.66536064e+01 -3.62167625e+01 -3.53246346e+01 -3.48300591e+01 -3.53355827e+01 -3.57336922e+01 -3.55907097e+01 -3.57701225e+01 -3.52681427e+01 -3.52777977e+01 -3.46258125e+01 -3.48082848e+01 -3.44461594e+01 -3.47059708e+01 -3.46744957e+01 -3.36824417e+01 -3.33884621e+01 -3.34704552e+01 -3.42398453e+01 -3.42612762e+01 -3.38458977e+01 -3.34723587e+01 -3.32415352e+01 -3.31499062e+01 -3.28863258e+01 -3.23740730e+01 -3.21497078e+01 -3.20453529e+01 -3.19939327e+01 -3.19614372e+01 -3.18722782e+01 -3.21111221e+01 -3.24156151e+01 -3.23130951e+01 -3.15217705e+01 -3.13386421e+01 -3.08669910e+01 -3.11811047e+01 -3.09056168e+01 -2.94670830e+01 -2.94648914e+01 -3.03241367e+01 -3.09266319e+01 -3.04109974e+01 -2.94022942e+01 -2.90703068e+01 -2.89291668e+01 -2.88076668e+01 -2.91904964e+01 -2.83752117e+01 -2.80545216e+01 -2.78225613e+01 -2.76090412e+01 -2.71197796e+01 -2.66614170e+01 -2.69777203e+01 -2.71882401e+01 -2.68805008e+01 -2.67142696e+01 -2.67576771e+01 -2.65248699e+01 -2.65129910e+01 -2.50038395e+01 -2.49250813e+01 -2.57382469e+01 -2.54205036e+01 -2.60784531e+01 -2.60647984e+01 -2.46268005e+01 -2.44176579e+01 -2.42157745e+01 -2.40193996e+01 -2.35058041e+01 -2.36280766e+01 -2.22830029e+01 -2.25899811e+01 -2.30984936e+01 -2.32914219e+01 -2.30492306e+01 -2.20148106e+01 -2.22468414e+01 -2.21197491e+01 -2.14994068e+01 -2.07677174e+01 -2.12581043e+01 -2.16811275e+01 -2.08358746e+01 -2.00306072e+01 -2.00745125e+01 -1.91508808e+01 -1.88551273e+01 -1.66711197e+01 -2.06449375e+01 -1.25375347e+01 -1.41808212e+02 -5.22686401e+02 -1.30341089e+03 -395095872. -2.08441438e+06 150547056. 150547056. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -105002672. -45696220. -7.60661230e+03 -1.23495618e+03 -4.69576111e+02 -1.28836945e+02 -1.49427404e+01 -1.61329823e+01 -1.50531435e+01 -1.37369776e+01 -1.30395155e+01 -1.21398163e+01 -1.24426651e+01 -1.06495123e+01 -8.07132149e+00 -1.07589455e+01 -1.16896181e+01 -1.08552942e+01 -1.16729717e+01 -1.07539654e+01 -1.00850334e+01 -9.37411785e+00 -9.06386185e+00 -9.23526192e+00 -9.70753288e+00 -9.26931667e+00 -8.88287735e+00 -8.43232250e+00 -8.07389450e+00 -7.49499226e+00 -6.97466135e+00 -7.19069862e+00 -7.43671417e+00 -7.20764589e+00 -6.84945297e+00 -6.35901213e+00 -6.02539444e+00 -5.83509350e+00 -5.58409595e+00 -5.39170551e+00 -4.96200037e+00 -4.72446346e+00 -4.34898901e+00 -4.00272274e+00 -3.76396227e+00 -3.68277454e+00 -3.57554960e+00 -3.28883934e+00 -3.07340884e+00 -2.75151896e+00 -2.40658259e+00 -2.19517350e+00 -1.95131767e+00 -1.69787514e+00 -1.42522860e+00 -1.23841596e+00 -1.01716089e+00 -7.37912357e-01 -4.09632802e-01 -1.58668920e-01 8.98334682e-02 2.56226212e-01 6.29652560e-01 1.06878304e+00 1.38026214e+00 1.87002873e+00 2.68144250e+00 1.14795685e+00 -1.04134369e+01 1.03192497e+02 69258424. 69258424. -254580928. -102906360. 3.47857219e+05 3.79364657e+00 6.21549873e+01 1.63007690e+02 1.55875050e+06 571887. 58337280. -34182836. 0. 0. 959236352. -633417088. -1.63658600e+02 97526872. -126840040. 0. 0. 476654848. 3.90038361e+02 9.38689804e+01 2.08252506e+01 4.11961212e+01 2.55270042e+01 4.67332602e+00 5.54556370e+00 5.87579393e+00 6.03918791e+00 5.91783810e+00 5.86380672e+00 6.19683647e+00 6.57866812e+00 6.80210876e+00 7.03426695e+00 7.27197599e+00 7.55796099e+00 7.92074919e+00 8.15750122e+00 8.36485100e+00 8.41308880e+00 8.60043430e+00 8.84862614e+00 9.21725845e+00 9.85096550e+00 1.00852175e+01 9.79568386e+00 9.92978954e+00 1.02155094e+01 1.03864079e+01 1.08544235e+01 1.10971937e+01 1.12619257e+01 1.14494152e+01 1.01455402e+01 1.02010460e+01 1.20803614e+01 1.26939011e+01 1.42529936e+01 1.50640154e+01 1.39137678e+01 1.36038361e+01 1.38958607e+01 1.42172527e+01 1.42784529e+01 1.44508762e+01 1.45490112e+01 1.47820635e+01 1.50087290e+01 1.54490452e+01 1.56792870e+01 1.58685503e+01 1.58371506e+01 1.63198051e+01 1.64711742e+01 1.64965572e+01 1.67311840e+01 1.70963631e+01 1.71363602e+01 1.69670944e+01 1.67713776e+01 1.66564865e+01 1.67489395e+01 -7.37938614e+01 -1.41247299e+02 -3.41167969e+02 -1.01370770e+03 -40371856. 2631699. 900671936. 900671936. 0. 0. -251944816. -251944816. 1742333568. -494129408. -494129408. 0. 0. 0. 0. 206530640. -266227296. -1.20688904e+03 -4.55784943e+02 -1.82065674e+02 -9.34383469e+01 2.32483349e+01 2.33227501e+01 2.44514275e+01 2.46283760e+01 2.41469193e+01 2.40380402e+01 2.47630444e+01 2.54811306e+01 2.59328976e+01 2.60182362e+01 2.57678967e+01 2.59085312e+01 2.59394150e+01 2.57524586e+01 2.58476715e+01 2.61002350e+01 2.61082745e+01 2.66421318e+01 2.69549255e+01 2.73733311e+01 2.72732849e+01 2.70387917e+01 2.73231716e+01 2.77712021e+01 2.81405964e+01 2.82337875e+01 2.81422672e+01 2.86078491e+01 2.87848072e+01 2.86665726e+01 2.87619839e+01 2.84841938e+01 2.85926132e+01 2.89547482e+01 2.96597786e+01 3.03520718e+01 3.06271172e+01 3.08555546e+01 3.05344543e+01 3.04493160e+01 3.05964241e+01 3.13306580e+01 3.15567455e+01 3.13015823e+01 3.15056343e+01 3.10657425e+01 3.13062992e+01 3.18594379e+01 3.16829529e+01 3.19854279e+01 3.20527954e+01 3.20186081e+01 3.23252945e+01 3.27985992e+01 3.32217178e+01 3.29624062e+01 3.21562157e+01 3.21236877e+01 3.23606033e+01 3.29493866e+01 3.33501244e+01 3.34972610e+01 3.31323318e+01 3.33028488e+01 3.38083572e+01 3.42636948e+01 3.41496353e+01 3.44531136e+01 3.45829849e+01 3.52166061e+01 3.59379463e+01 3.58244209e+01 3.53839226e+01 3.54958611e+01 3.48630028e+01 3.43008575e+01 3.36133308e+01 3.39627151e+01 3.49678764e+01 3.59133797e+01 3.60430603e+01 3.60051918e+01 3.59691582e+01 3.59954185e+01 3.60997276e+01 3.61790771e+01 3.56395988e+01 3.58759232e+01 3.60654411e+01 3.66489105e+01 3.70442696e+01 3.73981781e+01 3.71488152e+01 3.67224045e+01 3.67046051e+01 3.70805054e+01 3.53355637e+01 3.53743591e+01 3.79162598e+01 3.92664413e+01 3.85756302e+01 3.74117165e+01 3.71250381e+01 3.69913101e+01 3.76846962e+01 3.79956322e+01 3.81639671e+01 3.77693214e+01 3.78962975e+01 3.75289879e+01 3.77374458e+01 3.78439598e+01 3.79131699e+01 3.76545753e+01 3.83411484e+01 3.91892700e+01 3.85014954e+01 3.82395325e+01 3.79756813e+01 3.81889420e+01 3.83852119e+01 3.87667503e+01 3.88188515e+01 3.88261833e+01 3.83881721e+01 3.88316078e+01 3.89985580e+01 3.84922829e+01 3.87035828e+01 3.85991669e+01 3.81194000e+01 3.91947823e+01 3.95245781e+01 3.88924980e+01 3.89220009e+01 3.92223854e+01 3.91258965e+01 3.89995003e+01 3.90808945e+01 3.90545807e+01 3.91987762e+01 3.92363663e+01 3.90032959e+01 3.93024979e+01 3.94737434e+01 3.91759186e+01 3.93157463e+01 3.92666740e+01 3.91657600e+01 3.92758865e+01 3.92780685e+01 3.94020271e+01 3.95881004e+01 3.93073654e+01 3.93381310e+01 3.93804131e+01 3.94900665e+01 3.95708771e+01 3.94859467e+01 3.95771332e+01 3.93275642e+01 3.87910233e+01 3.90201263e+01 3.89068489e+01 3.90583687e+01 3.92657928e+01 3.87294693e+01 3.90668221e+01 3.90157890e+01 3.80684319e+01 3.82444954e+01 3.83750000e+01 3.87441902e+01 3.90268173e+01 3.76704865e+01 3.50531158e+01 3.89212151e+01 4.06896057e+01 3.44296265e+01 3.58573532e+01 4.33323593e+01 4.40490723e+01 3.90597267e+01 -1.67575836e+02 -3.14550842e+02 7.01551208e+01 6.91927872e+01 6.93638000e+01 6.88755722e+01 6.81767349e+01 6.85584259e+01 6.94297409e+01 7.05397873e+01 6.95985718e+01 6.77554703e+01 6.75360107e+01 6.88085556e+01 7.01567993e+01 6.80144958e+01 6.87165146e+01 6.97433167e+01 4.20080261e+02 5.86112823e+01 -3.07257904e+02 6.63323059e+01 4.16598175e+02 2.68338287e+02 4.40958710e+01 3.83542442e+01 3.70580521e+01 3.69210167e+01 3.64992371e+01 3.65689964e+01 3.70153580e+01 3.66493263e+01 3.69007416e+01 3.68611450e+01 3.68807449e+01 3.63923988e+01 3.58040581e+01 3.60180779e+01 3.66845016e+01 3.59458923e+01 3.56424980e+01 3.57331467e+01 3.58060875e+01 3.57856102e+01 3.55849190e+01 3.51686935e+01 3.49867096e+01 3.45939140e+01 3.48413734e+01 3.48338547e+01 3.51156960e+01 3.51481819e+01 3.48061523e+01 3.50037651e+01 3.48790016e+01 3.42998886e+01 3.39881706e+01 3.39688492e+01 3.37749329e+01 3.37479935e+01 3.33101425e+01 3.37398415e+01 3.37248764e+01 3.38245201e+01 3.40598793e+01 3.40504189e+01 3.30767479e+01 3.28876076e+01 3.22012138e+01 3.30711594e+01 3.25607033e+01 3.15047932e+01 3.13677082e+01 3.11861362e+01 3.22002831e+01 3.17912273e+01 3.07755260e+01 3.08970699e+01 3.06895123e+01 3.14838505e+01 3.14843006e+01 3.11421242e+01 3.09213104e+01 3.06421032e+01 3.05016575e+01 3.04538460e+01 2.98188381e+01 2.95640240e+01 2.95646496e+01 2.92377663e+01 2.95106850e+01 2.92421837e+01 2.94520779e+01 2.90932293e+01 2.83150253e+01 2.81623116e+01 2.87172394e+01 2.85203094e+01 2.79778385e+01 2.78327808e+01 2.81296730e+01 2.78912735e+01 2.72912731e+01 2.72878475e+01 2.65078259e+01 2.63972111e+01 2.61757431e+01 2.63138790e+01 2.66241608e+01 2.67252121e+01 2.65098495e+01 2.59170666e+01 2.54169178e+01 2.45510082e+01 2.48322315e+01 2.57955894e+01 2.55492840e+01 2.47847729e+01 2.43133602e+01 2.42434711e+01 2.42027454e+01 2.37651825e+01 2.37790642e+01 2.34363441e+01 2.29906158e+01 2.29603157e+01 2.31720085e+01 2.27999763e+01 2.22839298e+01 2.17274551e+01 2.16758556e+01 2.14668560e+01 2.13491344e+01 2.11911640e+01 2.08135319e+01 1.96445885e+01 1.98616371e+01 2.08577003e+01 2.02770252e+01 1.96149406e+01 1.94042225e+01 1.91543541e+01 1.94596405e+01 1.93141327e+01 1.91918201e+01 1.85113773e+01 1.84858475e+01 1.81567822e+01 1.77683372e+01 1.73608055e+01 1.71741238e+01 1.73135223e+01 1.76621819e+01 1.74011955e+01 1.71043720e+01 1.67564602e+01 1.65868111e+01 1.62382202e+01 1.60746918e+01 1.55604134e+01 1.54504976e+01 1.53079910e+01 1.52335691e+01 1.50857172e+01 1.49851675e+01 1.47667122e+01 1.43517866e+01 1.38598194e+01 1.37116880e+01 1.34598818e+01 1.32896500e+01 1.30571547e+01 1.27533646e+01 1.26279516e+01 1.24002647e+01 1.20544939e+01 1.18336105e+01 1.16404238e+01 1.14081268e+01 1.12177048e+01 1.09527817e+01 1.06976347e+01 1.04521570e+01 1.02431469e+01 1.01184273e+01 9.69539833e+00 9.35783005e+00 9.19524574e+00 9.10572243e+00 8.78595829e+00 8.52939701e+00 8.36116791e+00 8.20823669e+00 7.88608265e+00 7.73324680e+00 7.44325352e+00 7.17085218e+00 6.93115759e+00 6.76553297e+00 6.54722214e+00 6.25049019e+00 5.98675823e+00 5.72351551e+00 5.51530313e+00 5.35410929e+00 5.06826925e+00 4.82581139e+00 4.62403774e+00 4.35247564e+00 4.07109118e+00 3.86660242e+00 3.54555774e+00 3.31984830e+00 3.13712716e+00 2.88687062e+00 2.67659593e+00 2.43210053e+00 2.12325048e+00 1.89646947e+00 1.69842494e+00 1.45099545e+00 1.20088065e+00 8.84531856e-01 6.41454935e-01 4.58760113e-01 2.69044638e-01 2.70265043e-02 -2.57709354e-01 -4.89503682e-01 -7.24698126e-01 -9.70420003e-01 -1.21262634e+00 -1.45386541e+00 -1.69371033e+00 -1.93480563e+00 -2.18095541e+00 -2.42652583e+00 -2.67279410e+00 -2.91960120e+00 -3.14677525e+00 -3.40967178e+00 -3.64024711e+00 -3.83998585e+00 -4.13406372e+00 -4.38115788e+00 -4.58807945e+00 -4.83479786e+00 -5.13248968e+00 -5.31732988e+00 -5.49332094e+00 -5.75908852e+00 -6.00926542e+00 -6.29420328e+00 -6.50257683e+00 -6.76534891e+00 -7.01599407e+00 -7.25800037e+00 -7.42876530e+00 -7.66593361e+00 -7.93271208e+00 -8.18933296e+00 -8.37656403e+00 -8.50634003e+00 -8.91521358e+00 -9.21116638e+00 -9.26543331e+00 -9.41313362e+00 -9.64005756e+00 -9.93289757e+00 -1.02307863e+01 -1.05903997e+01 -1.07783470e+01 -1.09706411e+01 -1.11901379e+01 -1.14692364e+01 -1.16901007e+01 -1.18966360e+01 -1.20292511e+01 -1.23839750e+01 -1.26723175e+01 -1.29142265e+01 -1.29512205e+01 -1.31752987e+01 -1.33126049e+01 -1.37424698e+01 -1.39821587e+01 -1.42943497e+01 -1.43749466e+01 -1.47283058e+01 -1.49480877e+01 -1.53986330e+01 -1.53631649e+01 -1.53546972e+01 -1.57998209e+01 -1.62195415e+01 -1.62696629e+01 -1.64735317e+01 -1.67946720e+01 -1.69414043e+01 -1.75027981e+01 -1.77198181e+01 -1.73429680e+01 -1.74644642e+01 -1.80488796e+01 -1.82897434e+01 -1.79268265e+01 -1.83642120e+01 -1.89036789e+01 -1.91741848e+01 -2.00457020e+01 -1.99684696e+01 -1.97923374e+01 -2.00014973e+01 -2.02398300e+01 -2.03432274e+01 -2.02661114e+01 -2.06238995e+01 -2.13873692e+01 -2.13991890e+01 -2.16079159e+01 -2.20302391e+01 -2.20242004e+01 -2.21506462e+01 -2.24877586e+01 -2.26769409e+01 -2.32417164e+01 -2.27593040e+01 -2.28810501e+01 -2.32076836e+01 -2.29678516e+01 -2.31075363e+01 -2.31610088e+01 -2.33120041e+01 -2.38974342e+01 -2.44639492e+01 -2.47375336e+01 -2.51199818e+01 -2.54187450e+01 -2.49922028e+01 -2.49572849e+01 -2.53508244e+01 -2.58532867e+01 -2.58464088e+01 -2.60250397e+01 -2.61462097e+01 -2.61471691e+01 -2.67198811e+01 -2.70314121e+01 -2.75638065e+01 -2.72503815e+01 -2.68615952e+01 -2.71796532e+01 -2.79372368e+01 -2.79418869e+01 -2.81597824e+01 -2.77584305e+01 -2.82447491e+01 -2.93275070e+01 -2.98859749e+01 -2.98166084e+01 -2.87651043e+01 -2.89500198e+01 -2.88938828e+01 -2.93028297e+01 -2.97187099e+01 -3.01585274e+01 -3.03363571e+01 -3.01093540e+01 -3.02445164e+01 -3.02330246e+01 -3.10251846e+01 -3.06998425e+01 -3.05922928e+01 -3.09203072e+01 -3.13224716e+01 -3.15370216e+01 -3.17164440e+01 -3.12814198e+01 -3.16889629e+01 -3.18376694e+01 -3.20110207e+01 -3.20087738e+01 -3.26740723e+01 -3.30685616e+01 -3.28195724e+01 -3.25998077e+01 -3.31999130e+01 -3.32978859e+01 -3.31908531e+01 -3.32387962e+01 -3.33820419e+01 -3.31116371e+01 -3.29580193e+01 -3.36524048e+01 -3.37363129e+01 -3.35089951e+01 -3.40018654e+01 -3.44820671e+01 -3.50113373e+01 -3.47395210e+01 -3.47781487e+01 -3.46391182e+01 -3.48550949e+01 -3.46188698e+01 -3.43669739e+01 -3.43732605e+01 -3.45115891e+01 -3.51481056e+01 -3.60285606e+01 -3.61658859e+01 -3.65375328e+01 -3.58046913e+01 -3.60434113e+01 -3.56037483e+01 -3.58503151e+01 -3.54059715e+01 -3.58953171e+01 -3.61497803e+01 -3.63084755e+01 -3.68075905e+01 -3.80314789e+01 -3.79804497e+01 -3.64335709e+01 -3.60561028e+01 -3.71882477e+01 -3.78071175e+01 -3.74459534e+01 -3.73612404e+01 -3.75227966e+01 -3.67779541e+01 -3.71670532e+01 -3.74088783e+01 -3.70381851e+01 -3.70608292e+01 -3.68540764e+01 -3.71050186e+01 -3.73355484e+01 -3.72891922e+01 -3.72108383e+01 -3.63900604e+01 -3.29283409e+01 -3.22605362e+01 -3.65007706e+01 -3.61958466e+01 -3.80539513e+01 -4.04123573e+01 -3.97058868e+01 -3.87293091e+01 -3.57999496e+01 3.03991272e+02 3.52041626e+02 -1.00674530e+03 -8.51693115e+01 -1.00922485e+02 7.42011230e+02 -6.93387909e+01 -9.92864014e+02 -6.18669167e+01 -6.75986481e+01 -7.78958054e+01 -4.43946228e+02 -6.64782562e+01 -5.77962112e+01 -2.89244354e+02 -5.32514877e+01 -4.51196632e+01 -4.04240875e+01 -3.90589447e+01 -3.97297745e+01 -3.80890427e+01 -3.86112213e+01 -4.15730743e+01 -4.10393372e+01 -3.93547592e+01 -3.81182175e+01 -4.03252869e+01 -4.18307495e+01 -4.02100525e+01 -3.96861420e+01 -3.99605408e+01 -3.96051826e+01 -3.91266518e+01 -3.96127739e+01 -3.94041481e+01 -3.96222420e+01 -3.98125153e+01 -3.91316185e+01 -3.93127174e+01 -3.93849945e+01 -3.91217728e+01 -3.90657272e+01 -3.92173691e+01 -3.94039192e+01 -3.91344452e+01 -3.91426048e+01 -3.91710968e+01 -3.91175461e+01 -3.90553665e+01 -3.91594620e+01 -3.94850426e+01 -3.89451180e+01 -3.87897453e+01 -3.88991776e+01 -3.90433235e+01 -3.88059502e+01 -3.86622391e+01 -3.89976730e+01 -3.88429604e+01 -3.91929512e+01 -3.96148567e+01 -3.90061493e+01 -3.87717094e+01 -3.87743149e+01 -3.84252701e+01 -3.84637070e+01 -3.82982864e+01 -3.81587067e+01 -3.88728752e+01 -3.92603455e+01 -3.88838425e+01 -3.79920502e+01 -3.78164139e+01 -3.84418373e+01 -3.78615417e+01 -3.72658844e+01 -3.71889877e+01 -3.73837204e+01 -3.76306686e+01 -3.79843369e+01 -3.75498009e+01 -3.77517891e+01 -3.75150070e+01 -3.73356209e+01 -3.74494705e+01 -3.74035378e+01 -3.74443512e+01 -3.77242966e+01 -3.69425774e+01 -3.66735878e+01 -3.69742813e+01 -3.75510521e+01 -3.71931190e+01 -3.70187492e+01 -3.67369118e+01 -3.68404045e+01 -3.60132675e+01 -3.51373291e+01 -3.64293137e+01 -3.76036644e+01 -3.65509262e+01 -3.67986984e+01 -3.62472572e+01 -3.55013733e+01 -3.49575806e+01 -3.40249405e+01 -3.43774071e+01 -3.56449318e+01 -3.65445175e+01 -3.62979469e+01 -3.43712769e+01 -3.44472504e+01 -3.45043602e+01 -3.47858353e+01 -3.51246643e+01 -3.48606110e+01 -3.47506828e+01 -3.45341568e+01 -3.41151199e+01 -3.38725166e+01 -3.40647469e+01 -3.39579887e+01 -3.37842751e+01 -3.35448685e+01 -3.34922066e+01 -3.35252266e+01 -3.37900925e+01 -3.38892746e+01 -3.37791443e+01 -3.29571991e+01 -3.32236176e+01 -3.27120514e+01 -3.28103752e+01 -3.21797981e+01 -3.15804882e+01 -3.15970268e+01 -3.12304535e+01 -3.17011395e+01 -3.12615967e+01 -2.93795891e+01 -2.82499180e+01 -2.95149574e+01 -3.15269260e+01 -3.34477081e+01 -3.31504326e+01 -3.09371166e+01 -3.09760666e+01 -3.06858349e+01 -3.05268192e+01 -2.98716202e+01 -2.95383625e+01 -2.93087254e+01 -2.90207195e+01 -2.93002815e+01 -2.90099792e+01 -2.92137432e+01 -2.89063969e+01 -2.82247524e+01 -2.79642010e+01 -2.84917831e+01 -2.82424545e+01 -2.81226273e+01 -2.78971138e+01 -2.72911968e+01 -2.69686489e+01 -2.73871212e+01 -2.70812263e+01 -2.72688751e+01 -2.70404644e+01 -2.55667896e+01 -2.60287704e+01 -2.64401016e+01 -2.67387810e+01 -2.63919334e+01 -2.56345291e+01 -2.43451519e+01 -2.39397221e+01 -2.51246910e+01 -2.58116741e+01 -2.55656738e+01 -2.47339725e+01 -2.42034149e+01 -2.38315487e+01 -2.38110046e+01 -2.31775360e+01 -2.25196762e+01 -2.28778133e+01 -2.27066116e+01 -1.52765827e+01 1.10468422e+02 1.94383774e+02 -3.14118137e+01 -2.96102219e+01 -2.69078236e+01 -2.56059494e+01 -2.45595901e+02 -4.60329193e+02 -2.38173767e+02 -5.00457550e+02 -1.39911597e+03 -82093344. -940311552. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -394538816. -1.22758972e+03 -1.18090912e+02 -1.34021254e+01 -1.22470840e+02 -1.67233028e+01 -1.78213863e+01 -1.61944008e+01 -1.58454065e+01 -1.57052889e+01 -1.58546286e+01 -1.57196169e+01 -1.53373423e+01 -1.48783989e+01 -1.43281450e+01 -1.38722248e+01 -1.34229374e+01 -1.31384258e+01 -1.23735008e+01 -1.25421686e+01 -1.30421352e+01 -1.29516449e+01 -1.27023802e+01 -1.22358112e+01 -1.17330561e+01 -1.13547745e+01 -1.09009104e+01 -1.08237257e+01 -1.08287201e+01 -1.09400244e+01 -1.06766119e+01 -1.02437925e+01 -9.92210960e+00 -9.42638397e+00 -9.29987812e+00 -9.10969639e+00 -9.08664608e+00 -8.72226906e+00 -8.56923103e+00 -8.27837181e+00 -8.07040882e+00 -7.73493862e+00 -7.60960436e+00 -7.33928585e+00 -7.15833998e+00 -7.04133463e+00 -6.81411934e+00 -6.52211094e+00 -6.20306158e+00 -6.01809788e+00 -5.73632908e+00 -5.46936321e+00 -5.24610662e+00 -4.99728394e+00 -4.75359774e+00 -4.48497868e+00 -4.25527000e+00 -3.99588609e+00 -3.83958030e+00 -3.54555845e+00 -3.20641041e+00 -2.91667151e+00 -2.46120381e+00 -1.87060440e+00 -2.36099553e+00 -1.34165182e+01 -6.41923875e+05 0. 0. 0. 0. 0. 298558336. 298558336. 298558336. 0. 0. 0. 0. 0. 0. 959236352. -633417088. 1.46480194e+02 1.87256088e+02 -60026796. 1067954432. 0. 0. 1529941248. 2.47631411e+09 2.26314922e+05 1.95126923e+02 7.94991608e+01 -3.69399071e-01 1.04110897e+00 4.23949509e+01 2.76101589e+00 1.44141805e+00 1.88813972e+00 -4.79336472e+01 2.06559253e+00 1.95221639e+00 2.04710317e+00 2.35244823e+00 3.12360168e+00 4.19602871e+00 4.38578081e+00 4.58566141e+00 4.10911655e+00 3.96647859e+00 3.51690722e+00 4.18967867e+00 7.50599432e+00 8.27525520e+00 9.03525925e+01 7.25111723e+00 -8.23483658e+01 5.96261120e+00 7.34112358e+00 7.39870548e+00 6.93317747e+00 6.68093157e+00 -2.75456047e+00 -3.27707314e+00 7.57633543e+00 9.28272915e+00 1.74977398e+01 2.17136993e+01 1.41083374e+01 1.14422483e+01 1.18013010e+01 1.07503405e+01 1.04135962e+01 1.38983734e+02 8.76781082e+01 8.56047916e+00 8.92687702e+00 9.31001282e+00 9.45020580e+00 9.34978962e+00 9.10442352e+00 9.65241241e+00 9.94464588e+00 9.78730583e+00 9.53877735e+00 9.55876350e+00 1.00552759e+01 1.03128614e+01 -8.04088135e+01 -1.50652954e+02 8.31542683e+00 -3.77478333e+02 -9.78183289e+02 268139424. 860920768. 0. 900671936. 900671936. 900671936. 0. 0. -251944816. -251944816. -251944816. 0. 0. 0. 0. 0. -94990984. -2.25556494e+03 -4.70753845e+02 -1.93723007e+02 -1.03351906e+02 1.63434486e+01 1.70426254e+01 1.64952011e+01 1.66252365e+01 -1.07757179e+02 -2.02283295e+02 2.12029285e+01 2.09314327e+01 2.38193893e+01 2.63039417e+01 2.87840691e+01 2.59294373e+02 1.64020508e+02 1.89875164e+01 1.24188747e+01 1.83950939e+01 2.49313793e+01 2.04987659e+01 1.97547512e+01 1.91950569e+01 1.96929836e+01 1.97434006e+01 1.95792503e+01 1.94194221e+01 1.96976719e+01 2.00982456e+01 2.00747299e+01 2.01151867e+01 2.00761013e+01 2.02178688e+01 2.00573063e+01 2.06051712e+01 2.07221680e+01 2.06294231e+01 2.07459049e+01 2.09593716e+01 2.17135544e+01 2.23260632e+01 2.28219090e+01 2.29485836e+01 2.29770489e+01 2.26680565e+01 2.23369427e+01 2.21404552e+01 2.23803654e+01 2.28207951e+01 2.35244045e+01 2.33107014e+01 2.29123383e+01 2.35801220e+01 2.39655056e+01 2.38893623e+01 2.41169071e+01 2.47570248e+01 2.56385937e+01 2.52736931e+01 2.55182190e+01 2.47502174e+01 2.44802647e+01 2.38267117e+01 2.48012486e+01 2.52448311e+01 2.50207214e+01 2.52192974e+01 2.54134960e+01 2.63385372e+01 2.69817276e+01 2.72315407e+01 2.70366821e+01 2.67638588e+01 2.69841290e+01 2.74237137e+01 2.82500515e+01 2.80183640e+01 2.77157497e+01 2.73448105e+01 2.69321156e+01 2.68466511e+01 2.66190853e+01 2.69276829e+01 2.74514523e+01 2.79283981e+01 2.80233440e+01 2.79249821e+01 2.82141628e+01 2.82855892e+01 2.84254627e+01 2.87384319e+01 2.84211922e+01 2.86329498e+01 2.85359039e+01 2.85047379e+01 2.85977516e+01 2.87110558e+01 2.89560604e+01 2.86443119e+01 2.88525524e+01 2.89020023e+01 2.62696972e+01 2.62174206e+01 3.12818642e+01 3.26370201e+01 3.12092876e+01 3.02978191e+01 2.99182434e+01 2.94986610e+01 3.02306480e+01 3.02533112e+01 3.03029575e+01 3.04498329e+01 3.05278130e+01 3.02389927e+01 3.01552410e+01 3.04523373e+01 3.08955154e+01 3.06597919e+01 3.09815331e+01 3.13608456e+01 3.15828857e+01 3.16012745e+01 3.15850830e+01 3.17197876e+01 3.18530159e+01 3.15913544e+01 3.13875656e+01 3.16222115e+01 3.16092167e+01 3.16130486e+01 3.22191658e+01 3.19551468e+01 3.21373024e+01 3.14300194e+01 3.06105099e+01 3.22437859e+01 3.33036232e+01 3.20828819e+01 3.18874683e+01 3.22238388e+01 3.24892349e+01 3.23899879e+01 3.28418732e+01 3.27440758e+01 3.25087967e+01 3.24750900e+01 3.22851028e+01 3.27289810e+01 3.29466095e+01 3.28306389e+01 3.27979469e+01 3.27973824e+01 3.29028130e+01 3.28536644e+01 3.29419174e+01 3.30391884e+01 3.32089081e+01 3.29060669e+01 3.28984299e+01 3.29814911e+01 3.30789795e+01 3.34011612e+01 3.35548935e+01 3.33928223e+01 3.30696449e+01 3.27855530e+01 3.29056511e+01 3.28411179e+01 3.31762848e+01 3.32553673e+01 3.25503731e+01 3.29410172e+01 3.31142044e+01 3.21361580e+01 2.93599968e+01 2.44816608e+01 3.45642509e+01 3.80821190e+01 3.42649422e+01 3.37945976e+01 3.33859444e+01 -1.80071976e+02 -3.63056122e+02 4.31369629e+02 2.68723724e+02 3.31934776e+01 4.08411217e+01 4.41908340e+01 4.45927162e+01 5.06147652e+01 5.06876564e+01 4.99678192e+01 4.85570641e+01 4.81654854e+01 4.92178650e+01 4.92283669e+01 4.90140610e+01 4.93632164e+01 4.93631134e+01 4.92749710e+01 4.94132500e+01 4.92073174e+01 4.94669800e+01 4.94685974e+01 4.93149910e+01 4.35419769e+01 4.81931763e+01 3.75039368e+01 4.96555939e+01 3.39969482e+01 4.02790413e+01 3.87838173e+01 3.31166992e+01 3.23752098e+01 3.26546021e+01 3.17726898e+01 3.22944756e+01 3.26424904e+01 3.26416855e+01 3.20784874e+01 3.20094070e+01 3.25351677e+01 3.26416435e+01 3.17687988e+01 3.19673290e+01 3.28808327e+01 3.21642380e+01 3.17369041e+01 3.19381638e+01 3.16444321e+01 3.13119793e+01 3.17305508e+01 3.09585304e+01 3.18645248e+01 3.14151173e+01 3.16571465e+01 3.14888840e+01 3.14686794e+01 3.12912712e+01 3.12420330e+01 3.14923248e+01 3.15022717e+01 3.10368538e+01 3.07386513e+01 2.95117722e+01 2.96273766e+01 2.98187981e+01 2.99250183e+01 3.02585258e+01 3.02987251e+01 3.01063728e+01 2.98722363e+01 3.00844536e+01 3.04820595e+01 3.06244335e+01 2.97460003e+01 2.99676971e+01 2.98644428e+01 2.91934223e+01 2.92347870e+01 2.89248657e+01 2.97300282e+01 2.89283524e+01 2.80746765e+01 2.84949627e+01 2.81389389e+01 2.82273827e+01 2.81419735e+01 2.77260017e+01 2.74727135e+01 2.72419109e+01 2.78393612e+01 2.81098099e+01 2.76357594e+01 2.80813980e+01 2.79835567e+01 2.80145988e+01 2.74732609e+01 2.79744091e+01 2.77141972e+01 2.76256847e+01 2.68715382e+01 2.63439407e+01 2.67061062e+01 2.64738159e+01 2.61339016e+01 2.61623497e+01 2.64697933e+01 2.57253036e+01 2.56809235e+01 2.57599144e+01 2.52850704e+01 2.50586720e+01 2.47737160e+01 2.51192017e+01 2.53991394e+01 2.53636665e+01 2.52699852e+01 2.51089344e+01 2.46206760e+01 2.35266418e+01 2.30296917e+01 2.41872501e+01 2.50531368e+01 2.44254284e+01 2.39304066e+01 2.34203358e+01 2.32029991e+01 2.31621990e+01 2.29142265e+01 2.27895679e+01 2.29801350e+01 2.34453278e+01 2.32439060e+01 2.31242390e+01 2.21633682e+01 2.20947094e+01 2.15783234e+01 2.19697418e+01 2.18697395e+01 2.14842834e+01 2.09051094e+01 1.96611767e+01 2.02769547e+01 2.19337940e+01 2.11658630e+01 2.00977383e+01 1.97893887e+01 1.97610588e+01 2.02665997e+01 2.04432735e+01 1.99576550e+01 1.93597832e+01 1.93178940e+01 1.91261806e+01 1.89612427e+01 1.86608124e+01 1.85138969e+01 1.84884758e+01 1.84768581e+01 1.82415390e+01 1.79273872e+01 1.77669640e+01 1.77400990e+01 1.75798931e+01 1.75485725e+01 1.73020897e+01 1.71495361e+01 1.69733143e+01 1.65902958e+01 1.63272629e+01 1.60835800e+01 1.60882778e+01 1.57577114e+01 1.56120033e+01 1.54377832e+01 1.52933111e+01 1.49730988e+01 1.48422394e+01 1.47011700e+01 1.47819939e+01 1.46340647e+01 1.43855333e+01 1.41371222e+01 1.39700508e+01 1.38761501e+01 1.37106581e+01 1.33968601e+01 1.31144886e+01 1.27903662e+01 1.27228699e+01 1.27136831e+01 1.25803623e+01 1.21957016e+01 1.20162306e+01 1.19594355e+01 1.19158306e+01 1.16190233e+01 1.15466118e+01 1.13884048e+01 1.10618982e+01 1.07391872e+01 1.04537916e+01 1.02631531e+01 1.01397657e+01 1.00032978e+01 9.91623878e+00 9.65179348e+00 9.41530514e+00 9.07314491e+00 8.89758492e+00 8.81576729e+00 8.61798382e+00 8.36804295e+00 8.15936184e+00 7.92102814e+00 7.73442507e+00 7.67057037e+00 7.47288036e+00 7.19732332e+00 7.00490046e+00 6.77762699e+00 6.60807419e+00 6.40315199e+00 6.10215902e+00 5.92302418e+00 5.80827141e+00 5.59891510e+00 5.39249229e+00 5.10812807e+00 4.91152525e+00 4.77144670e+00 4.62273026e+00 4.42106962e+00 4.17197037e+00 3.97874379e+00 3.78594828e+00 3.57921576e+00 3.37617493e+00 3.17502499e+00 2.97553730e+00 2.77071977e+00 2.56211710e+00 2.35669851e+00 2.14973783e+00 1.94637775e+00 1.76774693e+00 1.52822280e+00 1.32308805e+00 1.16591561e+00 8.82473946e-01 6.72030449e-01 4.86198992e-01 2.63489366e-01 9.19863731e-02 -1.03492707e-01 -2.24713221e-01 -3.70098561e-01 -7.25254834e-01 -9.43220913e-01 -1.03800571e+00 -1.25199604e+00 -1.55773723e+00 -1.78331757e+00 -1.95448327e+00 -2.19418216e+00 -2.34027696e+00 -2.60002303e+00 -2.69489789e+00 -2.85333323e+00 -3.09830308e+00 -3.28592801e+00 -3.54397321e+00 -3.68521595e+00 -3.91947126e+00 -4.11129045e+00 -4.34761381e+00 -4.52411079e+00 -4.77534199e+00 -5.00097322e+00 -5.20953465e+00 -5.31452560e+00 -5.51827908e+00 -5.91839170e+00 -6.20160866e+00 -6.23359013e+00 -6.28956795e+00 -6.27812338e+00 -6.58463240e+00 -6.87315464e+00 -7.12482834e+00 -7.32252550e+00 -7.65810585e+00 -7.93306684e+00 -8.18003368e+00 -8.28343296e+00 -8.48766899e+00 -8.80683613e+00 -8.85557270e+00 -8.80795097e+00 -9.05609417e+00 -9.56764030e+00 -9.76604557e+00 -1.00194197e+01 -1.01491079e+01 -1.02422428e+01 -1.03583164e+01 -1.07548113e+01 -1.08090677e+01 -1.09466248e+01 -1.10977764e+01 -1.15396929e+01 -1.10847816e+01 -1.14911718e+01 -1.19075317e+01 -1.23741989e+01 -1.30407639e+01 -1.29194746e+01 -1.26046629e+01 -1.27151508e+01 -1.25796785e+01 -1.28479004e+01 -1.27163906e+01 -1.32749119e+01 -1.40286064e+01 -1.37421837e+01 -1.40293274e+01 -1.43817997e+01 -1.42670546e+01 -1.48476725e+01 -1.54319324e+01 -1.56067257e+01 -1.57295866e+01 -1.54327660e+01 -1.61751690e+01 -1.66514587e+01 -1.61802597e+01 -1.59036627e+01 -1.55427084e+01 -1.58442802e+01 -1.67874889e+01 -1.69670811e+01 -1.64268246e+01 -1.66717930e+01 -1.70205021e+01 -1.69123192e+01 -1.68648758e+01 -1.78771725e+01 -1.80335846e+01 -1.80945625e+01 -1.88125401e+01 -1.87381191e+01 -1.89264317e+01 -1.86981869e+01 -1.94989529e+01 -1.98122902e+01 -1.96154041e+01 -1.93692131e+01 -1.95393200e+01 -1.98944550e+01 -1.98628082e+01 -2.02216034e+01 -1.95566559e+01 -2.02554703e+01 -2.09572086e+01 -2.16541309e+01 -2.16809177e+01 -2.09764614e+01 -2.13403015e+01 -2.11331005e+01 -2.17979622e+01 -2.20648346e+01 -2.22796803e+01 -2.24739456e+01 -2.29263840e+01 -2.25982742e+01 -2.18592892e+01 -2.21942272e+01 -2.22469864e+01 -2.27679920e+01 -2.33510208e+01 -2.34640446e+01 -2.30816231e+01 -2.29345818e+01 -2.32011013e+01 -2.33476639e+01 -2.36091709e+01 -2.43061352e+01 -2.48853283e+01 -2.44775391e+01 -2.56350269e+01 -2.48509407e+01 -2.53689651e+01 -2.53393402e+01 -2.55110111e+01 -2.52827244e+01 -2.48580322e+01 -2.49045277e+01 -2.46985893e+01 -2.54874706e+01 -2.62876530e+01 -2.64716396e+01 -2.61891346e+01 -2.63113194e+01 -2.67123756e+01 -2.65744324e+01 -2.69351082e+01 -2.68860607e+01 -2.69180984e+01 -2.71720371e+01 -2.70536861e+01 -2.73340530e+01 -2.73169518e+01 -2.75488548e+01 -2.75213051e+01 -2.77195663e+01 -2.80342693e+01 -2.79311295e+01 -2.74108276e+01 -2.77876568e+01 -2.82887402e+01 -2.83706188e+01 -2.86753025e+01 -2.88939190e+01 -2.85803833e+01 -2.77550182e+01 -2.80957451e+01 -2.93125782e+01 -2.89819603e+01 -2.77906704e+01 -2.83626690e+01 -2.96789341e+01 -3.03811264e+01 -2.97127323e+01 -2.94951611e+01 -2.97383327e+01 -2.93982944e+01 -3.00653877e+01 -3.05130329e+01 -2.94337654e+01 -2.95785294e+01 -2.93998165e+01 -2.99156837e+01 -2.98486080e+01 -2.95929432e+01 -2.95895481e+01 -2.89439964e+01 -2.56680202e+01 -2.51546211e+01 -2.93559208e+01 -2.91306324e+01 -3.05817623e+01 -3.30715027e+01 -3.27045937e+01 -3.21105652e+01 -2.90451126e+01 -4.29388641e+02 -7.25832291e+01 3.57666870e+02 -4.95800629e+01 -5.41086044e+01 -5.18304443e+02 -4.60051422e+01 3.63426666e+02 -4.51999092e+01 -4.63802834e+01 -4.87195053e+01 -1.65526543e+01 -4.94922523e+01 -4.37757797e+01 -3.76752586e+01 -4.16432457e+01 -2.44145622e+01 -3.69283524e+01 -4.54597511e+01 -3.20766258e+01 -3.12555771e+01 -3.08836937e+01 -3.53922234e+01 -2.55054169e+01 -8.79603863e+00 -3.91059265e+01 -5.61542625e+01 -3.91825104e+01 -3.59972382e+01 -3.35720253e+01 -3.36011086e+01 -3.31138535e+01 -3.27507706e+01 -3.32249794e+01 -3.29241943e+01 -3.32673988e+01 -3.35736809e+01 -3.30707474e+01 -3.31470261e+01 -3.31109619e+01 -3.27915077e+01 -3.28429108e+01 -3.32519379e+01 -3.33363533e+01 -3.30040283e+01 -3.29334602e+01 -3.32265205e+01 -3.34875374e+01 -3.32751846e+01 -3.33549995e+01 -3.34973526e+01 -3.31590347e+01 -3.30103798e+01 -3.31814766e+01 -3.32598419e+01 -3.32005539e+01 -3.30835838e+01 -3.34153481e+01 -3.32253418e+01 -3.37423820e+01 -3.38951874e+01 -3.31147003e+01 -3.32268639e+01 -3.33141861e+01 -3.35294495e+01 -3.36549530e+01 -3.32848015e+01 -3.29846573e+01 -3.31735497e+01 -3.34595947e+01 -3.30928421e+01 -3.21013527e+01 -3.25004158e+01 -3.33533783e+01 -3.29090080e+01 -3.20106583e+01 -3.24351082e+01 -3.24712753e+01 -3.27663307e+01 -3.31756973e+01 -3.28388405e+01 -3.22108688e+01 -3.23607826e+01 -3.38905373e+01 -3.45144691e+01 -3.26987686e+01 -3.21629143e+01 -3.22187462e+01 -3.20663605e+01 -3.17854748e+01 -3.28534889e+01 -3.29133339e+01 -3.26313057e+01 -3.29181137e+01 -3.35016212e+01 -3.23941269e+01 -3.13058090e+01 -2.95097351e+01 -3.22920685e+01 -3.41291237e+01 -3.26636963e+01 -3.29724770e+01 -3.21995087e+01 -3.19360447e+01 -3.16252460e+01 -3.02331657e+01 -2.84766846e+01 -3.01771622e+01 -3.41613007e+01 -3.46598778e+01 -3.11858349e+01 -3.14714565e+01 -3.10172863e+01 -3.10463104e+01 -3.10654736e+01 -3.11614819e+01 -3.11743221e+01 -3.13957367e+01 -3.09335766e+01 -3.04574471e+01 -2.96125374e+01 -2.95604420e+01 -2.95186329e+01 -2.96790981e+01 -2.97902794e+01 -3.01997147e+01 -2.98398170e+01 -2.95295906e+01 -2.97259617e+01 -3.02642784e+01 -3.07407646e+01 -3.04635143e+01 -2.98429298e+01 -2.90912457e+01 -2.91211624e+01 -2.96393871e+01 -2.91538620e+01 -2.89825268e+01 -2.82542191e+01 -2.67246075e+01 -2.47158356e+01 -2.57666798e+01 -2.82945061e+01 -3.13348255e+01 -3.09739342e+01 -2.74378071e+01 -2.74082661e+01 -2.79680347e+01 -2.78775158e+01 -2.74432907e+01 -2.77929478e+01 -2.76846905e+01 -2.79929218e+01 -2.73298397e+01 -2.77541618e+01 -2.74329357e+01 -2.71695633e+01 -2.63348331e+01 -2.62317963e+01 -2.65343971e+01 -2.63091354e+01 -2.62588387e+01 -2.61718464e+01 -2.52620430e+01 -2.46315899e+01 -2.54396038e+01 -2.53574448e+01 -2.60110531e+01 -2.58714447e+01 -2.42819443e+01 -2.43226223e+01 -2.44205246e+01 -2.32674408e+01 -1.21118422e+01 -7.12546682e+00 2.51209297e+01 -4.56901627e+01 -8.04238510e+01 1.15337921e+02 2.14697464e+02 -3.34469681e+01 -3.09103985e+01 -2.87076588e+01 -2.92661667e+01 -2.91545277e+01 -2.57906876e+01 -2.99748478e+01 -2.93877583e+01 -2.48968826e+02 -1.84028946e+02 -3.51120071e+01 -3.16681919e+01 -3.26285286e+01 -3.10797863e+01 -3.08576679e+01 -2.71333218e+01 -2.51755829e+01 -1.88704014e+01 -1.41399857e+02 -1.27183655e+02 -4.51889465e+02 5103758. 1761492736. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.63312250e+05 1.79006458e+03 3.42631197e+00 -4.39401459e+02 -2.59819641e+01 -3.41271210e+01 -2.72256260e+01 -1.86482590e+02 -1.19168861e+02 -2.06879101e+01 -1.74969826e+01 -1.67144775e+01 -1.62240906e+01 -1.58152351e+01 -1.53444910e+01 -1.53897285e+01 -1.53187189e+01 -1.46227312e+01 -1.48092890e+01 -1.52676382e+01 -1.48804970e+01 -1.46254749e+01 -1.43258610e+01 -1.39876490e+01 -1.37458277e+01 -1.37324181e+01 -1.37926073e+01 -1.36726389e+01 -1.35944309e+01 -1.30011539e+01 -1.25415430e+01 -1.22485638e+01 -1.19994736e+01 -1.18039198e+01 -1.20123358e+01 -1.22887926e+01 -1.20533886e+01 -1.17905626e+01 -1.15161171e+01 -1.12607813e+01 -1.08757029e+01 -1.04284115e+01 -1.03869610e+01 -1.04475145e+01 -1.04561052e+01 -1.01990366e+01 -9.87315083e+00 -9.55897808e+00 -9.28066921e+00 -8.95270252e+00 -8.67894363e+00 -8.77421188e+00 -8.73119164e+00 -8.39728832e+00 -8.33554077e+00 -7.66889811e+00 -7.54999399e+00 1.98040752e+01 3.78113594e+01 -8.83159351e+00 -8.45214176e+00 -7.46554136e+00 -6.09336758e+00 -6.50901413e+00 -2.12087097e+01 -3.64481469e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 925190592. 925190592. 0. 0. 959236352. -633417088. 1.46480194e+02 1.87256088e+02 -60026796. 1067954432. 0. 0. 0. 0. 0. 6.39481562e+05 -1.71663483e+02 -1.03577393e+02 -11128080. 2.14339020e+02 -1.88998890e+01 -1.41094532e+01 -2.55037861e+01 -3.26224060e+02 -9022259. -1.87770238e+06 -24245522. -59340668. -2.00184088e+06 -304432768. -149923120. -208280656. -6060239. -35977732. -3.43879125e+06 -2749376. 2.38334732e+02 1.46230860e+01 -7.68729248e+01 -1.04665489e+01 -5.06271820e+02 -7.62163050e+06 209971808. -26514462. -689611712. -388341984. -2.23484656e+05 -2.64305312e+05 -5457362. -53045072. -6.64739375e+04 2566595. -1.73135062e+05 -78739992. 385426400. -12829301. -108533608. 7.52542053e+02 3.13843689e+02 -5.16733110e-01 8.00445735e-01 2.23842621e+00 1.47374634e+02 9.07102814e+01 4.69243145e+00 7.63315010e+00 8.12548923e+00 -7.84711227e+01 -1.47530533e+02 -5.78252649e+00 -1.56272376e+00 -2.47727156e-01 -3.79142548e+02 -9.97466614e+02 -7393042. -239200816. 1430286848. 0. 0. 0. 900671936. 900671936. 900671936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.47125438e+05 -3.90548492e+02 -1.06125473e+02 1.36364164e+01 1.51580105e+01 1.44347792e+01 1.38913164e+01 1.35430489e+01 1.38823528e+01 1.99349461e+01 2.12932358e+01 2.65179119e+01 2.46623745e+01 2.51567116e+01 2.69562950e+01 2.78921223e+01 1.99264412e+01 2.12833805e+01 1.70743675e+01 1.13552961e+01 1.83027172e+01 2.41786251e+01 1.95965881e+01 1.80627403e+01 1.72715816e+01 1.71059513e+01 1.71004124e+01 1.79416409e+01 1.86636410e+01 1.85373516e+01 1.83568134e+01 1.88586426e+01 1.89716492e+01 1.88561649e+01 1.87378826e+01 1.85445557e+01 1.95709476e+01 2.02728004e+01 1.99121189e+01 2.05817547e+01 2.10644569e+01 2.13451881e+01 2.13564453e+01 2.10042305e+01 2.07835960e+01 2.15122280e+01 2.17571716e+01 2.18820343e+01 2.18390503e+01 2.19099979e+01 2.17777424e+01 2.21012688e+01 2.23419647e+01 2.32338524e+01 2.39933586e+01 2.38033943e+01 2.37160225e+01 2.44115334e+01 2.45929985e+01 2.39077930e+01 2.37068176e+01 2.38750858e+01 2.47159595e+01 2.50782814e+01 2.47469711e+01 2.50722504e+01 2.50817528e+01 2.53091526e+01 2.55928860e+01 2.57816086e+01 2.61441536e+01 2.62518692e+01 2.66804771e+01 2.68071442e+01 2.65111065e+01 2.65814838e+01 2.65449123e+01 2.75482635e+01 2.83284607e+01 2.86714287e+01 2.83847599e+01 2.78967342e+01 2.84269733e+01 2.86396599e+01 2.85784016e+01 2.85203133e+01 2.78438358e+01 2.86016808e+01 2.89125519e+01 2.87034302e+01 2.85799332e+01 2.89554977e+01 3.01765785e+01 2.93384991e+01 2.94764252e+01 2.94322433e+01 2.98228168e+01 3.00582409e+01 3.00094872e+01 3.05948811e+01 3.00409946e+01 3.00615978e+01 2.98479691e+01 2.66451569e+01 2.71873894e+01 3.37168274e+01 3.47887688e+01 3.22500458e+01 3.10370045e+01 3.10160217e+01 3.15942688e+01 3.19040413e+01 3.16780300e+01 3.12839642e+01 3.20939445e+01 3.25541496e+01 3.30479584e+01 3.25342674e+01 3.26328926e+01 3.27937393e+01 3.26890678e+01 3.27185287e+01 3.26473389e+01 3.29623375e+01 3.31712379e+01 3.28891869e+01 3.29979439e+01 3.37493439e+01 3.39659729e+01 3.41086159e+01 3.41127930e+01 3.40904541e+01 3.39621658e+01 3.39941864e+01 3.43651161e+01 3.44493752e+01 3.44215050e+01 3.30863152e+01 3.46995277e+01 3.63794937e+01 3.45858841e+01 3.46546669e+01 3.50607033e+01 3.54197769e+01 3.52957458e+01 3.53841629e+01 3.54507446e+01 3.54392662e+01 3.52819786e+01 3.47722588e+01 3.50689583e+01 3.55192375e+01 3.57032585e+01 3.56624260e+01 3.56571007e+01 3.59948425e+01 3.60784874e+01 3.60228691e+01 3.63041344e+01 3.62741318e+01 3.58414688e+01 3.60053825e+01 3.60929451e+01 3.62140274e+01 3.65948944e+01 3.66554832e+01 3.67123871e+01 3.61844864e+01 3.59190979e+01 3.63365631e+01 3.62966919e+01 3.65601959e+01 3.65339088e+01 3.61335754e+01 3.64533501e+01 3.64655685e+01 3.55486298e+01 3.27239380e+01 2.81328735e+01 3.78780251e+01 4.12026482e+01 3.67029343e+01 3.64245796e+01 3.42706032e+01 3.49634743e+01 1.87107620e+01 5.48177261e+01 6.25949783e+01 4.13874283e+01 4.44489632e+01 2.72258362e+02 4.36578247e+02 6.85969009e+01 6.88546066e+01 6.89934998e+01 -7.75778442e+02 -2.05465454e+03 2.37255933e+03 9.63846741e+02 4.75575790e+01 1.00438942e+02 7.73241425e+01 7.91872177e+01 7.50349121e+01 6.46203842e+01 6.49879837e+01 6.51135483e+01 6.53932495e+01 -3.19198212e+02 5.70571060e+01 4.22980255e+02 6.39907150e+01 -3.15087616e+02 -1.59792679e+02 4.40687561e+01 3.82990341e+01 3.72495956e+01 3.72659912e+01 3.67077637e+01 3.67253227e+01 3.65871506e+01 3.69327431e+01 3.65688591e+01 3.68190804e+01 3.69375954e+01 3.71466026e+01 3.62869186e+01 3.61562233e+01 3.65597343e+01 3.63912430e+01 3.61105003e+01 3.58259315e+01 3.51281090e+01 3.56541138e+01 3.66359291e+01 3.61110764e+01 3.64240952e+01 3.66818924e+01 3.63914413e+01 3.63473930e+01 3.55147705e+01 3.57268257e+01 3.55571480e+01 3.56888504e+01 3.53968391e+01 3.62639580e+01 3.64665451e+01 3.56302757e+01 3.51720009e+01 3.49145164e+01 3.48588676e+01 3.49931984e+01 3.51392021e+01 3.52667542e+01 3.50001717e+01 3.46324310e+01 3.46472359e+01 3.46208572e+01 3.44273643e+01 3.46154594e+01 3.53660164e+01 3.48720932e+01 3.43744621e+01 3.43208961e+01 3.51963692e+01 3.51451302e+01 3.46241608e+01 3.44134445e+01 3.41326561e+01 3.38127823e+01 3.32807541e+01 3.28898544e+01 3.30287514e+01 3.28181305e+01 3.33270836e+01 3.37023773e+01 3.37360001e+01 3.32821693e+01 3.30816345e+01 3.26849480e+01 3.25608864e+01 3.24086952e+01 3.17960892e+01 3.26868362e+01 3.25080605e+01 3.23176270e+01 3.14171791e+01 3.21657829e+01 3.13883324e+01 3.16953964e+01 3.14064770e+01 3.16177521e+01 3.14865932e+01 3.14864407e+01 3.15331497e+01 3.14632835e+01 3.12561512e+01 3.09525185e+01 3.00746727e+01 2.92248497e+01 2.91166801e+01 3.02503548e+01 3.01994991e+01 2.97719135e+01 2.87562904e+01 2.94813156e+01 3.02720203e+01 2.95439262e+01 2.91884155e+01 2.91161556e+01 2.90177078e+01 2.90131378e+01 2.89477425e+01 2.88112316e+01 2.87467442e+01 2.82865257e+01 2.79681644e+01 2.77124424e+01 2.77775078e+01 2.81859035e+01 2.79613819e+01 2.76081715e+01 2.71969967e+01 2.74301434e+01 2.71300945e+01 2.60956364e+01 2.56198101e+01 2.69146461e+01 2.66517410e+01 2.53350220e+01 2.49209023e+01 2.51510906e+01 2.54497433e+01 2.59852276e+01 2.57505875e+01 2.51837769e+01 2.54447765e+01 2.50623150e+01 2.48600769e+01 2.47359066e+01 2.45528679e+01 2.41722145e+01 2.37701130e+01 2.35890083e+01 2.32192669e+01 2.32391415e+01 2.33878746e+01 2.30991764e+01 2.29918194e+01 2.26761379e+01 2.26716576e+01 2.24212151e+01 2.21018791e+01 2.20858078e+01 2.17860794e+01 2.16596146e+01 2.11328182e+01 2.09116020e+01 2.07402058e+01 2.06698532e+01 2.06440086e+01 2.05574379e+01 2.01214600e+01 1.99119282e+01 1.97952843e+01 1.96411381e+01 1.95564137e+01 1.93035526e+01 1.92886353e+01 1.90345802e+01 1.88375721e+01 1.87821064e+01 1.86392365e+01 1.82466679e+01 1.81147308e+01 1.79053078e+01 1.76002712e+01 1.73299370e+01 1.72093220e+01 1.71310081e+01 1.67323437e+01 1.66111794e+01 1.64196987e+01 1.62406750e+01 1.60458145e+01 1.56962395e+01 1.54622145e+01 1.54271708e+01 1.53532295e+01 1.51511803e+01 1.48524170e+01 1.45989790e+01 1.42897921e+01 1.40988960e+01 1.40306187e+01 1.38130713e+01 1.34990549e+01 1.31955853e+01 1.29483509e+01 1.29205713e+01 1.27863474e+01 1.24098263e+01 1.21332121e+01 1.19803162e+01 1.17532692e+01 1.15861130e+01 1.13834429e+01 1.10529366e+01 1.08288326e+01 1.06648788e+01 1.04439459e+01 1.02190866e+01 9.91422081e+00 9.69292927e+00 9.53905106e+00 9.37126160e+00 9.15166950e+00 8.87988091e+00 8.66237068e+00 8.44822788e+00 8.22325802e+00 7.99883699e+00 7.77497530e+00 7.54817009e+00 7.31701851e+00 7.09189367e+00 6.85569191e+00 6.62452173e+00 6.40890265e+00 6.19977379e+00 5.94701242e+00 5.72569323e+00 5.51321507e+00 5.22822428e+00 4.99933910e+00 4.78241682e+00 4.55026817e+00 4.34967375e+00 4.12676239e+00 3.97846723e+00 3.76557922e+00 3.40191650e+00 3.16326332e+00 3.04000139e+00 2.77718759e+00 2.50149465e+00 2.35768032e+00 2.17103148e+00 1.87189484e+00 1.66499650e+00 1.23604453e+00 1.16359258e+00 1.08212447e+00 6.85714245e-01 5.33709884e-01 2.52680808e-01 3.65386084e-02 -2.25514874e-01 -5.31650066e-01 -9.36568618e-01 -1.03259802e+00 -1.08870959e+00 -1.36049640e+00 -1.70370674e+00 -1.87307823e+00 -2.00682735e+00 -2.10777116e+00 -2.42077947e+00 -2.66700125e+00 -3.02086234e+00 -3.16187716e+00 -3.48468924e+00 -3.67922020e+00 -3.91088963e+00 -4.07491541e+00 -4.34011650e+00 -4.46643162e+00 -4.63734627e+00 -4.89150667e+00 -5.31612015e+00 -5.57658052e+00 -5.69417429e+00 -5.62170839e+00 -5.90683222e+00 -6.48416853e+00 -6.76928282e+00 -6.53684187e+00 -6.83959818e+00 -7.27793980e+00 -7.63757992e+00 -7.90400505e+00 -8.13862419e+00 -8.28957081e+00 -8.83143139e+00 -9.08252907e+00 -8.36983013e+00 -8.18821621e+00 -8.71670914e+00 -9.29071522e+00 -9.89320850e+00 -9.63252163e+00 -9.68421555e+00 -1.02198591e+01 -1.05850735e+01 -1.08008671e+01 -1.05890150e+01 -1.08797312e+01 -1.13343735e+01 -1.11959743e+01 -1.16338425e+01 -1.21230078e+01 -1.20290661e+01 -1.22098007e+01 -1.25722256e+01 -1.29862995e+01 -1.32800732e+01 -1.33511314e+01 -1.40301695e+01 -1.40578938e+01 -1.37640963e+01 -1.39047127e+01 -1.43559151e+01 -1.47016935e+01 -1.52516603e+01 -1.55805225e+01 -1.48937168e+01 -1.50132008e+01 -1.52289085e+01 -1.53981180e+01 -1.53521948e+01 -1.64013882e+01 -1.66789036e+01 -1.70547791e+01 -1.71823654e+01 -1.69286079e+01 -1.71485748e+01 -1.72893906e+01 -1.77413158e+01 -1.79309902e+01 -1.82004986e+01 -1.79578686e+01 -1.84065762e+01 -1.78672142e+01 -1.87441483e+01 -1.87183170e+01 -1.85822010e+01 -1.87901821e+01 -2.05067348e+01 -2.08005314e+01 -2.04998932e+01 -2.05304794e+01 -2.10761414e+01 -2.10484810e+01 -2.11773415e+01 -2.04916039e+01 -1.99176579e+01 -2.01847897e+01 -2.16166420e+01 -2.15854988e+01 -2.15408821e+01 -2.15564671e+01 -2.18121243e+01 -2.19774017e+01 -2.24574661e+01 -2.22028103e+01 -2.22561512e+01 -2.26726036e+01 -2.34186802e+01 -2.35571346e+01 -2.41092339e+01 -2.43135509e+01 -2.40019951e+01 -2.31568222e+01 -2.37812443e+01 -2.42493038e+01 -2.51644783e+01 -2.51169205e+01 -2.51579685e+01 -2.51326103e+01 -2.57414284e+01 -2.60096474e+01 -2.57780952e+01 -2.56485310e+01 -2.54063568e+01 -2.53215599e+01 -2.55586853e+01 -2.61691360e+01 -2.66402760e+01 -2.64453659e+01 -2.69136391e+01 -2.75126591e+01 -2.79453144e+01 -2.86916656e+01 -2.80282917e+01 -2.85590820e+01 -2.87422943e+01 -2.85075073e+01 -2.81219482e+01 -2.74065361e+01 -2.81306553e+01 -2.82030258e+01 -2.78351078e+01 -2.83982105e+01 -2.89635468e+01 -2.94216671e+01 -2.98496819e+01 -3.04797001e+01 -3.01560268e+01 -2.91564713e+01 -2.99871540e+01 -3.05966702e+01 -2.97268867e+01 -2.91618347e+01 -3.03694363e+01 -3.11542416e+01 -3.12755680e+01 -3.12136993e+01 -3.13395004e+01 -3.10789928e+01 -3.05840034e+01 -3.09017124e+01 -3.14129105e+01 -3.15775280e+01 -3.14197655e+01 -3.13967361e+01 -3.14244804e+01 -3.21880493e+01 -3.27311287e+01 -3.26736412e+01 -3.19783382e+01 -3.05148544e+01 -2.95001183e+01 -3.13672180e+01 -3.02091045e+01 -3.04544563e+01 -3.39645119e+01 -3.44061317e+01 -3.39363251e+01 -3.21676369e+01 -2.60406952e+02 -4.22027649e+02 -3.88915100e+01 -3.54815521e+01 -3.66327782e+01 -3.58860779e+01 -1.50822315e+01 -5.09450493e+01 -6.94753113e+01 -3.75272789e+01 -4.79963074e+01 3.36537598e+02 -5.19942894e+01 -4.57096176e+01 1.73028976e+02 -2.00628395e+01 -1.30040312e+01 -6.14640236e+01 -5.92097778e+01 -3.76937675e+01 -3.70691605e+01 -3.64750023e+01 -3.94264374e+01 -2.88769321e+01 -1.38078098e+01 -4.08118324e+01 -5.60748024e+01 -4.16094704e+01 -3.93307648e+01 -3.68160362e+01 -3.61798210e+01 -3.58860779e+01 -3.59980354e+01 -3.61029053e+01 -3.60366516e+01 -3.61984253e+01 -3.63779869e+01 -3.66825256e+01 -3.65517044e+01 -3.58358727e+01 -3.54905052e+01 -3.58339996e+01 -3.65867538e+01 -3.66064987e+01 -3.63358345e+01 -3.63582039e+01 -3.67753181e+01 -3.70104218e+01 -3.67358513e+01 -3.66904526e+01 -3.68239899e+01 -3.68457146e+01 -3.71350517e+01 -3.73320160e+01 -3.68636818e+01 -3.67415237e+01 -3.70207558e+01 -3.79378700e+01 -3.78290367e+01 -3.79761734e+01 -3.75874329e+01 -3.72904472e+01 -3.74618797e+01 -3.73483467e+01 -3.71969528e+01 -3.74863396e+01 -3.70959244e+01 -3.72691879e+01 -3.76083717e+01 -3.76037865e+01 -3.73706207e+01 -3.64589539e+01 -3.66032906e+01 -3.75155411e+01 -3.70950241e+01 -3.69920082e+01 -3.73816185e+01 -3.74134865e+01 -3.71344948e+01 -3.73035927e+01 -3.73361931e+01 -3.62337685e+01 -3.63418922e+01 -3.78586235e+01 -3.79485512e+01 -3.65031128e+01 -3.72550926e+01 -3.79071808e+01 -3.70625153e+01 -3.63900871e+01 -3.72552872e+01 -3.72452354e+01 -3.64566879e+01 -3.65983238e+01 -3.74302406e+01 -3.69604301e+01 -3.61725044e+01 -3.41644707e+01 -3.82072601e+01 -3.96725960e+01 -3.65603561e+01 -3.63544655e+01 -3.63034897e+01 -3.63201447e+01 -3.63005219e+01 -3.42594223e+01 -3.27129135e+01 -3.48193398e+01 -4.01097565e+01 -4.02604561e+01 -3.69949226e+01 -3.66591721e+01 -3.59001045e+01 -3.49135971e+01 -3.52581024e+01 -3.52277985e+01 -3.52063408e+01 -3.51752625e+01 -3.57538834e+01 -3.61949844e+01 -3.59299126e+01 -3.49655037e+01 -3.44076462e+01 -3.42373085e+01 -3.44980278e+01 -3.50380898e+01 -3.47083244e+01 -3.41336098e+01 -3.43723412e+01 -3.50245094e+01 -3.49501152e+01 -3.50099487e+01 -3.43893089e+01 -3.38969765e+01 -3.41887894e+01 -3.45453758e+01 -3.43885994e+01 -3.46232758e+01 -3.48916702e+01 -3.36758842e+01 -3.03430405e+01 -3.15227375e+01 -3.49358864e+01 -3.71945267e+01 -3.58805618e+01 -3.31290131e+01 -3.29785461e+01 -3.34714470e+01 -3.33354416e+01 -3.33835411e+01 -3.30681038e+01 -3.29922333e+01 -3.28593750e+01 -3.26459084e+01 -3.23440552e+01 -3.18299236e+01 -3.24206429e+01 -3.19543056e+01 -3.19731579e+01 -3.12522678e+01 -3.20118484e+01 -3.14791126e+01 -3.17397327e+01 -3.13647137e+01 -3.11386051e+01 -3.11129322e+01 -3.11391182e+01 -3.11862545e+01 -3.13739414e+01 -3.09001446e+01 -3.02359219e+01 -2.91540203e+01 -2.71161022e+01 -1.63080006e+01 -1.37055588e+01 5.73133039e+00 -4.58261948e+01 -7.44590149e+01 -3.54500809e+01 -3.64386787e+01 -4.14989433e+01 -4.10885963e+01 -4.03808136e+01 -3.99423599e+01 -3.95304832e+01 -3.83456726e+01 -3.97206497e+01 -3.90832939e+01 -2.33816071e+01 -1.78960251e+02 -2.65930267e+02 -6.14863548e+01 -6.74243164e+01 -6.26135826e+01 -6.37824593e+01 1.69945007e+02 8.99418335e+01 -2.42288666e+01 -1.89916286e+01 -3.07808399e+01 -1.34733582e+02 -4.14251862e+02 -1.58748853e+03 -204983264. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -241726160. -241726160. -75617416. -113941664. -3.84233945e+04 -7.21223125e+05 966734528. -1.13379578e+03 -4.85968933e+02 -6.82629852e+01 -4.93319054e+01 -4.58989639e+01 -4.35877151e+01 -1.81913284e+02 -1.13101929e+02 -2.15345345e+01 -2.22510796e+01 -2.06807728e+01 -2.04684639e+01 -1.98521843e+01 5.42768974e+01 1.04918625e+02 -3.94105301e+01 -3.88174782e+01 -3.81596222e+01 -3.94005089e+01 -4.06966782e+01 -4.12843552e+01 -4.05433693e+01 -3.87614136e+01 -3.65107765e+01 -3.55619125e+01 -3.51415939e+01 -3.45849380e+01 -3.68179436e+01 -3.94100761e+01 -3.90247650e+01 -3.75541267e+01 -1.18154457e+02 -2.40379295e+01 6.64123840e+01 -3.32817001e+01 -3.38381577e+01 -3.51200943e+01 -3.58481560e+01 -3.49131889e+01 -3.37526398e+01 -3.26948128e+01 -3.19659119e+01 -3.17098904e+01 -3.10044060e+01 -3.23702583e+01 -3.28209152e+01 -3.17861805e+01 -3.24410439e+01 -2.91316166e+01 -2.93714561e+01 7.76713333e+01 2.21939133e+02 -157344304. -568543936. -8861726. -1.80331962e+06 -1.12493912e+06 336935776. 58122560. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 925190592. 925190592. 0. 0. 0. 0. -1466635776. -60026796. -60026796. 1067954432. 0. 53502272. 90715280. 295344000. -572696704. -16985452. -1228782848. -1228782848. 0. -1203652096. -1203652096. -62323532. 714537216. 714537216. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70341464. -70341464. -10072857. 411714016. 411714016. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70665224. -70665224. -70665224. 0. 0. -205965712. -5.80657288e+02 -6.65602478e+02 -6.99031830e+00 1.75483322e+02 9.14113998e+00 3.70619512e+00 1.78666580e+00 -9.89564121e-01 -8.16190948e+01 -1.46559097e+02 -3.68661407e+02 -9.54258911e+02 -10850295. -2.55366250e+06 -8.07003150e+06 75077776. 325799392. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -227256832. -26704650. -2.22729675e+06 -5.83973877e+02 -1.83644958e+02 6.44443846e+00 7.40738010e+00 7.88725328e+00 7.58552170e+00 7.39152145e+00 7.54716825e+00 8.17973042e+00 1.36310287e+02 2.23043869e+02 -1.84495544e+01 -2.62709484e+01 -2.48006248e+01 -2.16477318e+01 -1.99345818e+01 -2.22683945e+02 -1.21895210e+02 9.92907524e+00 5.41948795e+00 1.15707970e+01 1.69205685e+01 1.32060547e+01 1.16474934e+01 1.07307968e+01 1.06272812e+01 1.06839218e+01 1.14621773e+01 1.18430958e+01 1.14930429e+01 1.16975632e+01 1.19995937e+01 1.20188541e+01 1.24323683e+01 1.22139502e+01 1.16460571e+01 1.29488163e+01 1.35365705e+01 1.25793476e+01 1.32030716e+01 1.41434116e+01 1.48436155e+01 1.47754059e+01 1.43881254e+01 1.46072512e+01 1.47262506e+01 1.55554848e+01 1.52109737e+01 1.51792660e+01 1.54434872e+01 1.51991835e+01 1.53976250e+01 1.48898277e+01 1.56030502e+01 1.67676010e+01 1.69873714e+01 1.71657391e+01 1.76543140e+01 1.71016998e+01 1.62597485e+01 1.66986504e+01 1.72455902e+01 1.79350510e+01 1.76944275e+01 1.74733009e+01 1.74744320e+01 1.79974709e+01 1.88442955e+01 1.90771732e+01 1.95905190e+01 1.97284832e+01 1.95274677e+01 1.96246319e+01 1.95185375e+01 1.96370869e+01 1.99293156e+01 2.01561317e+01 2.02777348e+01 2.06709423e+01 2.14519577e+01 2.06138020e+01 2.09662380e+01 2.05658913e+01 2.08105640e+01 2.10904808e+01 2.14972229e+01 2.15196114e+01 2.21134758e+01 2.24362164e+01 2.21330070e+01 2.17504654e+01 2.26984310e+01 2.33572483e+01 2.23719349e+01 2.25653725e+01 2.30492649e+01 2.37381172e+01 2.34062176e+01 2.31785603e+01 2.35612392e+01 2.44694366e+01 2.43893356e+01 2.40340347e+01 1.94828796e+01 1.97470970e+01 2.51755733e+01 2.81088009e+01 2.67313309e+01 2.46408501e+01 2.43351326e+01 2.49727535e+01 2.57793980e+01 2.59053612e+01 2.56660118e+01 2.52754650e+01 2.55220909e+01 2.58140965e+01 2.57386036e+01 2.57969837e+01 2.59187717e+01 2.61373463e+01 2.62955265e+01 2.64378490e+01 2.64288235e+01 2.66531200e+01 2.64210377e+01 2.65963039e+01 2.69945755e+01 2.75464249e+01 2.78459988e+01 2.77016907e+01 2.77118549e+01 2.75597343e+01 2.77630463e+01 2.80135841e+01 2.80567322e+01 2.82141495e+01 2.65047226e+01 2.83624039e+01 3.03107014e+01 2.86069221e+01 2.85838547e+01 2.89699001e+01 2.90204105e+01 2.89050236e+01 2.88456879e+01 2.91340446e+01 2.94123707e+01 2.93211441e+01 2.91561127e+01 2.94620628e+01 2.96730843e+01 3.00738716e+01 2.99941368e+01 2.98885555e+01 3.02352753e+01 3.03028450e+01 3.03145447e+01 3.05867329e+01 3.05066833e+01 3.05081520e+01 3.07671337e+01 3.08017616e+01 3.05904179e+01 3.07892990e+01 3.10017414e+01 3.12004261e+01 3.09040890e+01 3.08007145e+01 3.10302238e+01 3.10160637e+01 3.11760082e+01 3.12434196e+01 3.13924141e+01 3.15753288e+01 3.16025410e+01 3.12513313e+01 2.84148865e+01 2.40337849e+01 3.33827591e+01 3.63540039e+01 3.34711800e+01 3.53050728e+01 2.92732391e+01 2.48914581e+02 3.69391907e+02 -3.08688782e+02 -1.62190567e+02 3.07158031e+01 3.80644455e+01 3.17130547e+01 2.57572784e+01 2.63134766e+01 4.56737671e+01 4.71246986e+01 3.80213127e+01 3.73066139e+01 3.92990036e+01 3.14566154e+01 3.05558796e+01 3.85332527e+01 3.54264259e+01 3.57890358e+01 3.38567848e+01 -1.75125259e+02 -3.23871704e+02 6.51135483e+01 6.53932495e+01 4.21133850e+02 2.59519043e+02 3.47048149e+01 4.24645538e+01 3.82312164e+01 3.59786072e+01 3.48918457e+01 3.37226868e+01 3.38073158e+01 3.35983658e+01 3.32074928e+01 3.25780182e+01 3.29050255e+01 3.30746613e+01 3.29765930e+01 3.28045883e+01 3.29371948e+01 3.30602150e+01 3.25207596e+01 3.23912926e+01 3.24156914e+01 3.26055031e+01 3.21170235e+01 3.26246796e+01 3.23965645e+01 3.33967781e+01 3.41555138e+01 3.28543587e+01 3.29799042e+01 3.31695824e+01 3.27336731e+01 3.28751717e+01 3.24437408e+01 3.25505905e+01 3.28566246e+01 3.32623215e+01 3.27891502e+01 3.36717720e+01 3.36973457e+01 3.31343307e+01 3.29393349e+01 3.31902847e+01 3.28364830e+01 3.30772858e+01 3.31400757e+01 3.33508873e+01 3.31054955e+01 3.25289497e+01 3.24986229e+01 3.24564018e+01 3.17500916e+01 3.14062939e+01 3.17351913e+01 3.20402145e+01 3.16492462e+01 3.20663757e+01 3.34226990e+01 3.37679062e+01 3.31864891e+01 3.23013115e+01 3.25925026e+01 3.32348137e+01 3.28419266e+01 3.26150131e+01 3.24159317e+01 3.26938629e+01 3.18670063e+01 3.22783928e+01 3.19529133e+01 3.17724228e+01 3.21089020e+01 3.17766895e+01 3.18461514e+01 3.11065121e+01 3.05771828e+01 3.10300579e+01 3.14385071e+01 3.15466232e+01 3.14676704e+01 3.13968182e+01 3.11128674e+01 3.08157482e+01 3.07555332e+01 3.10539780e+01 3.12646141e+01 3.06101780e+01 3.02856407e+01 3.04112606e+01 3.05825539e+01 3.05701599e+01 3.02471924e+01 2.95073166e+01 2.92915955e+01 2.98032074e+01 3.02740536e+01 2.98691673e+01 2.87050114e+01 2.93182945e+01 3.02332134e+01 3.00672398e+01 2.92098675e+01 2.92308025e+01 2.90995064e+01 2.92884064e+01 2.97005043e+01 2.93525085e+01 2.89424725e+01 2.84654617e+01 2.83397503e+01 2.82645588e+01 2.86064968e+01 2.83314018e+01 2.85654583e+01 2.77489605e+01 2.74607315e+01 2.76675072e+01 2.79576874e+01 2.77455482e+01 2.67944832e+01 2.80180454e+01 2.78418694e+01 2.62856255e+01 2.60550556e+01 2.63067455e+01 2.66981106e+01 2.71857090e+01 2.69788971e+01 2.64170399e+01 2.59974403e+01 2.59999657e+01 2.54412937e+01 2.53180428e+01 2.54892178e+01 2.54943066e+01 2.55163441e+01 2.54526234e+01 2.50444145e+01 2.50885105e+01 2.51044903e+01 2.49533787e+01 2.45124912e+01 2.41587944e+01 2.43929043e+01 2.42808762e+01 2.41993256e+01 2.39938164e+01 2.38252430e+01 2.35987282e+01 2.34918365e+01 2.34396343e+01 2.33270454e+01 2.28756752e+01 2.27851868e+01 2.24452324e+01 2.22544003e+01 2.19440880e+01 2.18874874e+01 2.21465950e+01 2.19586792e+01 2.18769741e+01 2.21141624e+01 2.19102306e+01 2.13900051e+01 2.12463837e+01 2.11133614e+01 2.08303833e+01 2.05685234e+01 2.03726883e+01 2.03255444e+01 2.00264301e+01 2.00053768e+01 2.00281620e+01 1.98135509e+01 1.97325497e+01 1.95226536e+01 1.90502987e+01 1.90282364e+01 1.90192795e+01 1.87775211e+01 1.88360596e+01 1.85965977e+01 1.83462105e+01 1.82301025e+01 1.81045609e+01 1.78224506e+01 1.75994415e+01 1.75680389e+01 1.72264996e+01 1.70512161e+01 1.68376369e+01 1.66220951e+01 1.66284904e+01 1.65228367e+01 1.61288548e+01 1.58730745e+01 1.58244362e+01 1.57010450e+01 1.54040766e+01 1.52539244e+01 1.50820580e+01 1.49006701e+01 1.47178135e+01 1.45269995e+01 1.43655767e+01 1.40880957e+01 1.38694525e+01 1.37275743e+01 1.36045370e+01 1.34284430e+01 1.31904097e+01 1.30096598e+01 1.28260403e+01 1.26332579e+01 1.24403410e+01 1.22236967e+01 1.20058470e+01 1.17971087e+01 1.16063080e+01 1.14111338e+01 1.12117538e+01 1.10284958e+01 1.08778086e+01 1.06904125e+01 1.04918156e+01 1.03265219e+01 1.00580006e+01 9.85554600e+00 9.69318676e+00 9.43827438e+00 9.26106167e+00 9.13046265e+00 9.05056286e+00 8.84375381e+00 8.46467495e+00 8.29689026e+00 8.22022629e+00 7.97564363e+00 7.70236158e+00 7.55596304e+00 7.42089939e+00 7.18524790e+00 6.99408102e+00 6.62247133e+00 6.56826162e+00 6.51649046e+00 5.96788311e+00 5.83754730e+00 5.77359009e+00 5.53991318e+00 5.42143488e+00 5.14561558e+00 4.79648161e+00 4.60510445e+00 4.63179398e+00 4.39751816e+00 4.13560247e+00 3.85946321e+00 3.74422884e+00 3.71869731e+00 3.51887560e+00 3.13632154e+00 2.83411956e+00 2.59307075e+00 2.44072413e+00 2.28460622e+00 2.20930362e+00 2.07482934e+00 1.72777319e+00 1.60901177e+00 1.40782332e+00 1.19433486e+00 9.35638368e-01 1.03232110e+00 7.60445833e-01 3.31168324e-01 2.40065694e-01 1.95481889e-02 -4.70559329e-01 -1.26131386e-01 -2.53637344e-01 -7.14982212e-01 -1.23279440e+00 -1.63833272e+00 -1.81326532e+00 -1.78324687e+00 -1.98859489e+00 -2.15152216e+00 -2.18633842e+00 -2.02945209e+00 -2.34734058e+00 -2.87712216e+00 -3.19428730e+00 -3.10595822e+00 -3.39546490e+00 -3.75344396e+00 -4.14364719e+00 -4.20302582e+00 -4.32761860e+00 -4.60655975e+00 -4.86286020e+00 -4.88606501e+00 -5.29782772e+00 -5.78426313e+00 -5.62323713e+00 -5.61949539e+00 -6.19919300e+00 -6.07032585e+00 -5.69443703e+00 -5.84424353e+00 -6.56632137e+00 -6.66092682e+00 -6.77759886e+00 -7.38841820e+00 -7.91490650e+00 -8.03687191e+00 -8.00993252e+00 -8.89504051e+00 -9.15639400e+00 -9.09666538e+00 -9.21983242e+00 -9.21413422e+00 -9.53664970e+00 -9.14121056e+00 -9.49191189e+00 -9.82127666e+00 -1.04045467e+01 -1.03393393e+01 -1.04246302e+01 -1.05921354e+01 -1.08415470e+01 -1.15870533e+01 -1.12295027e+01 -1.08194742e+01 -1.12508144e+01 -1.15920162e+01 -1.22065029e+01 -1.21130543e+01 -1.16149464e+01 -1.22443151e+01 -1.36526155e+01 -1.35572357e+01 -1.32122040e+01 -1.34163923e+01 -1.36367874e+01 -1.42293224e+01 -1.45680723e+01 -1.41009674e+01 -1.33385067e+01 -1.34010344e+01 -1.47010345e+01 -1.52130318e+01 -1.45780439e+01 -1.50880537e+01 -1.53340816e+01 -1.53085079e+01 -1.62741241e+01 -1.56761847e+01 -1.58257475e+01 -1.58599443e+01 -1.63623943e+01 -1.73820248e+01 -1.69600716e+01 -1.68683510e+01 -1.62965889e+01 -1.64375229e+01 -1.69189911e+01 -1.80606670e+01 -1.82060356e+01 -1.86678829e+01 -1.80118103e+01 -1.79480419e+01 -1.88779945e+01 -1.94827995e+01 -2.01135921e+01 -1.98783321e+01 -1.99271088e+01 -1.96391125e+01 -1.91051750e+01 -1.96328373e+01 -2.03583622e+01 -2.05795269e+01 -2.08550549e+01 -2.05813007e+01 -2.08583908e+01 -2.04452515e+01 -2.09138889e+01 -2.02775402e+01 -2.07441807e+01 -2.11709328e+01 -2.17287407e+01 -2.16918964e+01 -2.20647659e+01 -2.20277901e+01 -2.19834309e+01 -2.22925358e+01 -2.27055721e+01 -2.23276176e+01 -2.24106598e+01 -2.31231689e+01 -2.29486237e+01 -2.25528793e+01 -2.35063572e+01 -2.42068233e+01 -2.28313866e+01 -2.32035198e+01 -2.46528549e+01 -2.48956203e+01 -2.42021122e+01 -2.41332684e+01 -2.39002457e+01 -2.42065105e+01 -2.40410786e+01 -2.45913429e+01 -2.48227501e+01 -2.49377136e+01 -2.53278561e+01 -2.52186260e+01 -2.47715950e+01 -2.47689896e+01 -2.49784203e+01 -2.55577354e+01 -2.57495537e+01 -2.49544811e+01 -2.50289955e+01 -2.55181923e+01 -2.51653156e+01 -2.32813663e+01 -1.93785305e+01 -2.92657566e+01 -3.38061752e+01 -2.61494598e+01 -2.65878944e+01 -2.72519493e+01 -2.69181347e+01 -2.63071480e+01 -2.63430290e+01 -2.61178055e+01 -2.27651119e+01 -2.24151592e+01 -3.19226074e+01 1.86300629e+02 -2.79688892e+01 -2.65803436e+02 -2.96199684e+01 -3.04325771e+01 -2.96081886e+01 -4.74122810e+00 -6.44202662e+00 -5.10723572e+01 -5.15653305e+01 -3.17399635e+01 -3.19542885e+01 -3.10070019e+01 -3.16538219e+01 -2.15859299e+01 -9.42442989e+00 -3.60405083e+01 -4.88939667e+01 -3.35126762e+01 -3.21960297e+01 -3.07077522e+01 -3.07371597e+01 -3.04905014e+01 -3.03754711e+01 -3.04522800e+01 -3.04501438e+01 -3.05971546e+01 -3.07053909e+01 -3.09531498e+01 -3.06952896e+01 -3.05737038e+01 -3.05052319e+01 -3.06354008e+01 -3.13329697e+01 -3.12963257e+01 -3.12059650e+01 -3.11430931e+01 -3.14365387e+01 -3.16874466e+01 -3.15826321e+01 -3.15161018e+01 -3.14915905e+01 -3.16401825e+01 -3.21471786e+01 -3.21125679e+01 -3.20394592e+01 -3.17090015e+01 -3.20262718e+01 -3.27675743e+01 -3.29152870e+01 -3.28111534e+01 -3.23062630e+01 -3.23980103e+01 -3.26169662e+01 -3.27432213e+01 -3.26637039e+01 -3.26357040e+01 -3.28072548e+01 -3.27328911e+01 -3.28843765e+01 -3.30289268e+01 -3.32520828e+01 -3.30287399e+01 -3.29097900e+01 -3.34085159e+01 -3.30853348e+01 -3.30806961e+01 -3.29435463e+01 -3.32369194e+01 -3.30238419e+01 -3.26749229e+01 -3.21403770e+01 -3.13423901e+01 -3.26793137e+01 -3.46743126e+01 -3.34890442e+01 -3.25883522e+01 -3.27304306e+01 -3.32406845e+01 -3.30810356e+01 -3.28763733e+01 -3.32174339e+01 -3.32647095e+01 -3.27862930e+01 -3.28956070e+01 -3.31624336e+01 -3.30049629e+01 -3.18601933e+01 -3.11263599e+01 -3.47592239e+01 -3.53643532e+01 -3.29713135e+01 -3.24324303e+01 -3.22625504e+01 -3.23360519e+01 -3.30963478e+01 -3.18637848e+01 -3.04554920e+01 -3.20928802e+01 -3.69807663e+01 -3.67680664e+01 -3.34750824e+01 -3.26883240e+01 -3.24978294e+01 -3.24597435e+01 -3.25214996e+01 -3.26613045e+01 -3.26796150e+01 -3.26790848e+01 -3.31641655e+01 -3.34327126e+01 -3.35923119e+01 -3.31015930e+01 -3.29909019e+01 -3.22867508e+01 -3.26898003e+01 -3.32751160e+01 -3.32137833e+01 -3.25994186e+01 -3.24026489e+01 -3.27321930e+01 -3.27398376e+01 -3.25326118e+01 -3.15617409e+01 -3.08197041e+01 -3.13380375e+01 -3.19948425e+01 -3.24095459e+01 -3.28642921e+01 -3.32473946e+01 -3.31925049e+01 -2.82477131e+01 -2.88216972e+01 -3.45076561e+01 -3.66979599e+01 -3.54419403e+01 -3.25326576e+01 -3.29637947e+01 -3.19517746e+01 -3.18494511e+01 -3.13920498e+01 -3.17221584e+01 -3.20117874e+01 -3.17712040e+01 -3.15338669e+01 -3.09019470e+01 -3.10919304e+01 -3.11504841e+01 -3.07669411e+01 -3.08914318e+01 -3.09741077e+01 -3.14242134e+01 -3.10314579e+01 -3.09817123e+01 -3.10140114e+01 -3.09461517e+01 -3.08661404e+01 -3.05636177e+01 -3.04163094e+01 -3.02422256e+01 -3.02670593e+01 -3.01015720e+01 -2.94028702e+01 -2.72155285e+01 -1.65433464e+01 -1.42985773e+01 -5.59816420e-01 -4.00240440e+01 -6.48920670e+01 -1.82821182e+02 -2.95000244e+02 -7.26476822e+01 -7.10308380e+01 -6.94620819e+01 -6.94562531e+01 -6.87305603e+01 -6.89102936e+01 -6.81868134e+01 -6.82239456e+01 1.89842590e+02 9.68763580e+01 -2.79054432e+01 -2.78557777e+01 -2.86745453e+01 -2.80115814e+01 -2.80448589e+01 -2.83360329e+01 -2.76448898e+01 -2.70897121e+01 -2.38020515e+01 -1.53358688e+02 -1.51736660e+01 -6.17336130e+00 -4.43279724e+02 -7.69356262e+02 -73065304. -282787552. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.88663375e+06 537763584. -2.80449688e+05 -25487672. -26622898. 1524076928. -5.63489746e+02 -2.05911682e+02 -3.25462074e+01 -2.75856724e+01 -2.50930882e+01 -2.33785038e+01 -2.15723896e+01 -2.34474316e+01 -2.35216293e+01 1.13129181e+02 3.17784546e+02 -14852270. -15363801. -48945672. 319367808. 122173928. 245470608. -30091450. -75174488. -65227220. -18303046. -1.17719025e+06 -25161532. -59384724. -22739106. -6.31336426e+02 -8.87923431e+01 3.90599091e+02 -54442540. -5.28924250e+06 -141424928. -39146092. -32037836. 169315216. -55147896. -65490856. -37612512. -7689055. -9.78784312e+05 -2210088. -4.86473350e+06 -71174624. -2.80197875e+05 -2.37283328e+05 -301843296. -110606600. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 925190592. 925190592. 0. 0. 129619688. 129619688. 129619688. 0. 0. 0. 0. 53502272. 90715280. 295344000. -572696704. -16985452. -1228782848. -1228782848. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70341464. -70341464. -70341464. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70665224. -70665224. -70665224. 0. 0. -205965712. -233591728. -233591728. 94530224. -26735972. -3.36577344e+05 -9.60596863e+02 -4.03147888e+02 -4.47293777e+01 -3.66818237e+02 -9.10290466e+02 -747123008. -13897377. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -251897856. 208069440. -1.22746875e+03 -4.39827820e+02 6.02682161e+00 -1.79762283e+02 -9.80351791e+01 1.28017149e+01 1.36373482e+01 1.40349922e+01 1.47414837e+01 1.50803175e+01 1.46775379e+01 1.47961960e+01 1.52848473e+01 1.64146347e+01 1.65535088e+01 1.54012432e+01 1.60156307e+01 1.67834053e+01 1.72293358e+01 1.78644867e+01 1.77194252e+01 1.75862980e+01 1.91197529e+01 1.93993111e+01 1.93544064e+01 1.99271584e+01 1.98585072e+01 1.97340584e+01 2.03552246e+01 2.01890106e+01 2.06678219e+01 2.12159061e+01 2.09503975e+01 2.11764641e+01 2.14380894e+01 2.13538322e+01 2.20796089e+01 2.20894623e+01 2.21938934e+01 2.35727005e+01 2.44116745e+01 2.42074394e+01 2.45910053e+01 2.48008461e+01 2.49353638e+01 2.49272823e+01 2.53410873e+01 2.64038963e+01 2.58835049e+01 2.56458626e+01 2.64376888e+01 2.66833496e+01 2.62038326e+01 2.66412735e+01 2.70376167e+01 2.78711891e+01 2.81515484e+01 2.85985718e+01 2.77879562e+01 2.76682720e+01 2.87074490e+01 2.88840790e+01 2.90285645e+01 2.96251183e+01 3.00447178e+01 3.02309647e+01 3.04848537e+01 3.09549999e+01 3.09635658e+01 3.08597775e+01 3.09485321e+01 3.13029842e+01 3.23298149e+01 3.31826820e+01 3.38225403e+01 3.41694183e+01 3.37399826e+01 3.40503235e+01 3.39751778e+01 3.47803078e+01 3.48539505e+01 3.49271622e+01 3.47453308e+01 3.42632790e+01 3.48073845e+01 3.53549461e+01 3.57150764e+01 3.66022530e+01 3.66719322e+01 3.62842407e+01 3.65463486e+01 3.72149734e+01 3.73454018e+01 3.74118080e+01 3.78664169e+01 3.81207352e+01 3.80430527e+01 3.85313950e+01 3.85863190e+01 3.91055412e+01 3.81585121e+01 3.88335266e+01 3.91203499e+01 4.02918396e+01 4.05115852e+01 4.00632133e+01 3.71969948e+01 3.61741295e+01 3.91915512e+01 4.43298302e+01 4.48295631e+01 4.15453300e+01 4.09534607e+01 4.14189911e+01 4.22020798e+01 4.18945045e+01 4.20624008e+01 4.22020073e+01 4.25683212e+01 4.24792786e+01 4.25349197e+01 4.29905663e+01 4.36491356e+01 4.33771667e+01 4.33315582e+01 4.35752258e+01 4.39275742e+01 4.41550674e+01 4.42795372e+01 4.44504051e+01 4.42538338e+01 4.49161453e+01 4.50952034e+01 4.48236465e+01 4.52329826e+01 4.53356285e+01 4.56236382e+01 4.54268265e+01 4.57134628e+01 4.58913116e+01 4.43124886e+01 4.59777298e+01 4.79014015e+01 4.66935997e+01 4.68227615e+01 4.70067863e+01 4.70718536e+01 4.69589233e+01 4.72778931e+01 4.77728729e+01 4.82501221e+01 4.82578850e+01 4.79804497e+01 4.84194527e+01 4.84468117e+01 4.86606445e+01 4.85675430e+01 4.85665359e+01 4.88848839e+01 4.89916344e+01 4.91192665e+01 4.95301552e+01 4.94806099e+01 4.93872833e+01 4.97230339e+01 4.96670303e+01 4.96401596e+01 5.00186996e+01 5.01764717e+01 5.03634453e+01 5.00436554e+01 4.96878281e+01 4.99727249e+01 5.02661591e+01 5.03227234e+01 5.04948158e+01 5.10018044e+01 5.08935699e+01 5.07045822e+01 5.10884018e+01 5.12320595e+01 5.10050201e+01 5.12127266e+01 5.12905197e+01 5.03983231e+01 5.01858635e+01 4.80019379e+01 4.47463913e+01 4.03900566e+01 5.18774452e+01 6.25550919e+01 5.45752029e+01 5.02812119e+01 4.89733391e+01 4.44162636e+01 4.54038277e+01 6.36509666e+01 6.59474945e+01 2.94856049e+02 4.60452118e+02 -3.37351685e+02 -1.85371155e+02 -1.59504013e+02 -2.79558777e+02 6.31352577e+01 6.42499695e+01 4.29731934e+02 3.07336639e+02 6.36864243e+01 7.72405701e+01 7.73182983e+01 5.70730057e+01 5.36819000e+01 5.46205750e+01 6.20111465e+01 5.74061623e+01 5.43792419e+01 -1.48117661e+02 -3.03414703e+02 5.69423294e+01 5.73162117e+01 5.66143188e+01 4.23549896e+02 2.64326508e+02 4.09102631e+01 6.14740486e+01 6.20140266e+01 5.96186028e+01 5.54830284e+01 5.38831291e+01 5.33681374e+01 5.36014366e+01 5.32051582e+01 5.25475655e+01 5.22750320e+01 5.21596031e+01 5.26650162e+01 5.31086311e+01 5.27214813e+01 5.22783890e+01 5.18423424e+01 5.16768684e+01 5.18780899e+01 5.20183563e+01 5.17232933e+01 5.21530228e+01 5.25248604e+01 5.20978127e+01 5.19616394e+01 5.12547226e+01 5.12835007e+01 5.15672150e+01 5.17638245e+01 5.18506279e+01 5.18623047e+01 5.23114243e+01 5.21151886e+01 5.17559013e+01 5.13612671e+01 5.12195396e+01 5.12494392e+01 5.03955116e+01 5.01076889e+01 5.01208382e+01 5.08378296e+01 5.04411850e+01 5.09681664e+01 5.16185722e+01 5.19236832e+01 5.11860771e+01 5.04710464e+01 5.00932732e+01 5.04344101e+01 5.08575096e+01 5.01279068e+01 4.98141136e+01 4.95482368e+01 4.90687218e+01 4.92871780e+01 4.94348145e+01 4.94953232e+01 4.93716621e+01 4.95052071e+01 4.88894691e+01 4.86475067e+01 4.80094719e+01 4.80409050e+01 4.88091736e+01 4.84777565e+01 4.88387756e+01 4.80634232e+01 4.79029922e+01 4.71312256e+01 4.71193619e+01 4.75516357e+01 4.80760574e+01 4.71258049e+01 4.65331421e+01 4.57542763e+01 4.62620659e+01 4.63097076e+01 4.69639702e+01 4.65251274e+01 4.63732948e+01 4.60567856e+01 4.61412048e+01 4.61893044e+01 4.51739922e+01 4.49957771e+01 4.59323845e+01 4.55413437e+01 4.56612587e+01 4.52645836e+01 4.47867661e+01 4.43400307e+01 4.41142044e+01 4.35653610e+01 4.36656342e+01 4.37130318e+01 4.34391327e+01 4.32735672e+01 4.30384293e+01 4.31234322e+01 4.34591942e+01 4.28308640e+01 4.25225105e+01 4.17643127e+01 4.16693497e+01 4.16199341e+01 4.11799583e+01 4.23656540e+01 4.26279984e+01 4.11445808e+01 4.06629066e+01 4.01992378e+01 4.07253418e+01 4.09266396e+01 4.07174873e+01 3.97995110e+01 3.90245285e+01 3.89641571e+01 3.86861725e+01 3.81514130e+01 3.85529518e+01 3.87221947e+01 3.85634880e+01 3.80182228e+01 3.75346870e+01 3.75116730e+01 3.74016151e+01 3.72223320e+01 3.67283745e+01 3.65324974e+01 3.67071838e+01 3.64004173e+01 3.61510048e+01 3.55974197e+01 3.54942894e+01 3.51428146e+01 3.51030731e+01 3.49041290e+01 3.45983925e+01 3.42135353e+01 3.37748184e+01 3.33071327e+01 3.30737305e+01 3.29493103e+01 3.29827766e+01 3.29183846e+01 3.24116287e+01 3.20788727e+01 3.22383690e+01 3.21760178e+01 3.16493340e+01 3.12776260e+01 3.09928875e+01 3.06650639e+01 3.04291496e+01 3.01802120e+01 2.99141827e+01 2.94428368e+01 2.91753235e+01 2.90180473e+01 2.88182659e+01 2.87947350e+01 2.85601826e+01 2.78481827e+01 2.74740887e+01 2.72187443e+01 2.70013847e+01 2.70823078e+01 2.68433895e+01 2.64520512e+01 2.61541290e+01 2.59879990e+01 2.56200390e+01 2.53058357e+01 2.50983410e+01 2.46202278e+01 2.43690357e+01 2.40039082e+01 2.36649628e+01 2.36580715e+01 2.33846703e+01 2.28482037e+01 2.24751644e+01 2.23193150e+01 2.20592670e+01 2.16443958e+01 2.13765907e+01 2.11304340e+01 2.08500214e+01 2.05318451e+01 2.02273998e+01 1.99595909e+01 1.95809841e+01 1.92374306e+01 1.89491482e+01 1.87270737e+01 1.84085732e+01 1.80679398e+01 1.77730083e+01 1.74725742e+01 1.71613102e+01 1.68534355e+01 1.65499496e+01 1.62590504e+01 1.59475565e+01 1.56463566e+01 1.53431644e+01 1.50282631e+01 1.47299929e+01 1.44380627e+01 1.41250381e+01 1.37133570e+01 1.34324932e+01 1.31261415e+01 1.27945652e+01 1.24550867e+01 1.20611706e+01 1.18155470e+01 1.15960646e+01 1.13352604e+01 1.10339718e+01 1.06525116e+01 1.03721695e+01 1.00550795e+01 9.75817871e+00 9.41318321e+00 9.12247944e+00 8.77647781e+00 8.42978001e+00 8.07689190e+00 7.59576035e+00 7.45006990e+00 7.26254940e+00 6.77810574e+00 6.45370102e+00 6.16975927e+00 5.79393959e+00 5.52878475e+00 5.23975563e+00 4.76902819e+00 4.49506903e+00 4.42844009e+00 3.94934511e+00 3.59489512e+00 3.20007801e+00 2.96951270e+00 2.67345738e+00 2.42528200e+00 2.12319899e+00 1.78680849e+00 1.32439971e+00 1.01506662e+00 7.12820888e-01 4.21283811e-01 7.87377581e-02 -1.27089128e-01 -5.24716079e-01 -7.94420302e-01 -1.30527914e+00 -1.73432994e+00 -1.87349451e+00 -1.83055389e+00 -2.48876786e+00 -2.96632457e+00 -3.52842307e+00 -3.92271852e+00 -3.65056133e+00 -3.64649820e+00 -4.17189121e+00 -4.88830328e+00 -5.47989321e+00 -6.01164865e+00 -6.08144426e+00 -6.04207230e+00 -6.16230583e+00 -6.38778782e+00 -6.74696493e+00 -7.26909304e+00 -8.12197113e+00 -8.25049973e+00 -8.28355598e+00 -8.30765343e+00 -8.80451393e+00 -9.40487099e+00 -9.52733040e+00 -9.80534935e+00 -1.01398554e+01 -1.06332731e+01 -1.10924530e+01 -1.13879681e+01 -1.17413092e+01 -1.20768709e+01 -1.23740034e+01 -1.26480103e+01 -1.27753019e+01 -1.27128401e+01 -1.27184381e+01 -1.32715197e+01 -1.39958763e+01 -1.46653214e+01 -1.48070517e+01 -1.54563036e+01 -1.58344812e+01 -1.59212608e+01 -1.60695534e+01 -1.60905037e+01 -1.69935818e+01 -1.72197342e+01 -1.72579269e+01 -1.72077217e+01 -1.72018356e+01 -1.77067394e+01 -1.83002472e+01 -1.86236000e+01 -1.90041046e+01 -1.97331295e+01 -1.95996838e+01 -1.99327526e+01 -2.05369129e+01 -2.05816612e+01 -2.10635548e+01 -2.13745823e+01 -2.22247696e+01 -2.20281830e+01 -2.21230202e+01 -2.13076744e+01 -2.19062233e+01 -2.33271961e+01 -2.37071304e+01 -2.33297138e+01 -2.35450287e+01 -2.27062588e+01 -2.35536652e+01 -2.39139996e+01 -2.52392159e+01 -2.55930386e+01 -2.62190609e+01 -2.61282387e+01 -2.56945839e+01 -2.59761944e+01 -2.68859997e+01 -2.66837730e+01 -2.66712570e+01 -2.76432838e+01 -2.86650505e+01 -2.84061165e+01 -2.80228691e+01 -2.77005520e+01 -2.82872505e+01 -2.84451160e+01 -2.86885757e+01 -2.88763103e+01 -2.92697754e+01 -2.94238701e+01 -3.03856773e+01 -3.09259071e+01 -3.18396339e+01 -3.14702568e+01 -3.19451504e+01 -3.14866333e+01 -3.14478626e+01 -3.20134277e+01 -3.27817917e+01 -3.39579620e+01 -3.44401131e+01 -3.36604805e+01 -3.41621132e+01 -3.45324135e+01 -3.50577011e+01 -3.49164238e+01 -3.48780022e+01 -3.48561020e+01 -3.44520073e+01 -3.48361015e+01 -3.48997917e+01 -3.49810104e+01 -3.61431007e+01 -3.67907944e+01 -3.66539192e+01 -3.64496689e+01 -3.65372391e+01 -3.69146461e+01 -3.71694679e+01 -3.75347214e+01 -3.75552063e+01 -3.78586082e+01 -3.85056953e+01 -3.82685013e+01 -3.77707596e+01 -3.81683083e+01 -3.91687317e+01 -3.73733749e+01 -3.82455673e+01 -4.02381477e+01 -4.02768593e+01 -3.99015274e+01 -3.93466492e+01 -3.95411873e+01 -4.01395378e+01 -4.02411766e+01 -3.90896835e+01 -3.48285408e+01 -3.90873795e+01 -2.90207157e+01 1.80665604e+02 3.24767090e+02 -1.51548357e+01 -1.39367237e+01 -1.55423994e+01 -4.13589142e+02 -2.69274628e+02 -4.46276131e+01 -4.32793694e+01 -4.24275169e+01 -4.11008339e+01 -3.80728760e+01 -4.76928253e+01 -5.20064316e+01 -4.44186440e+01 1.66160065e+02 1.70960037e+02 -4.27558060e+01 2.21867783e+02 -4.21016296e+02 -2.76040710e+02 -4.56412849e+01 -4.16719246e+01 -5.10033836e+01 -6.33962059e+01 -4.66676941e+01 -5.86511078e+01 -4.78196983e+01 -4.83970299e+01 -4.76504860e+01 -2.67396431e+01 -3.67867432e+01 -6.35844765e+01 -5.67815666e+01 -5.06892548e+01 -5.02405777e+01 -5.02807388e+01 -4.96686554e+01 -4.89008369e+01 -4.87255936e+01 -4.87416229e+01 -4.85098076e+01 -4.84656219e+01 -4.86088524e+01 -4.90566444e+01 -4.95253983e+01 -4.93357887e+01 -4.93123741e+01 -4.95516396e+01 -4.96227379e+01 -4.96656418e+01 -4.97185364e+01 -4.98731346e+01 -4.96927567e+01 -4.97609520e+01 -4.98806419e+01 -4.99653969e+01 -5.04114838e+01 -5.04514465e+01 -5.04182129e+01 -5.04883804e+01 -5.06220932e+01 -5.07947960e+01 -5.08460159e+01 -5.08504257e+01 -5.09602127e+01 -5.10856552e+01 -5.12751236e+01 -5.16190186e+01 -5.19680557e+01 -5.17849350e+01 -5.16520386e+01 -5.19182930e+01 -5.22705154e+01 -5.15442009e+01 -5.14026566e+01 -5.14747467e+01 -5.17303505e+01 -5.18998528e+01 -5.20259705e+01 -5.17368317e+01 -5.21725121e+01 -5.26132736e+01 -5.24517250e+01 -5.22997475e+01 -5.19247398e+01 -5.21320801e+01 -5.24008980e+01 -5.26421051e+01 -5.24480667e+01 -5.21294441e+01 -5.21209183e+01 -5.24026184e+01 -5.24821777e+01 -5.23364258e+01 -5.15684814e+01 -5.10154686e+01 -5.29158249e+01 -5.42187576e+01 -5.28946762e+01 -5.21467896e+01 -5.24737625e+01 -5.26471977e+01 -5.22896538e+01 -5.25035057e+01 -5.26595726e+01 -5.28038902e+01 -5.24405937e+01 -5.25066223e+01 -5.24338531e+01 -5.27854080e+01 -5.11554680e+01 -5.13187370e+01 -5.43656883e+01 -5.42542152e+01 -5.27151184e+01 -5.34316635e+01 -5.26715622e+01 -5.19722862e+01 -5.17641716e+01 -4.97512321e+01 -4.99691734e+01 -5.26145096e+01 -5.62985344e+01 -5.56071014e+01 -5.21049690e+01 -5.14166107e+01 -5.12723732e+01 -5.16663475e+01 -5.20687065e+01 -5.25638428e+01 -5.21013718e+01 -5.17600441e+01 -5.16491623e+01 -5.15034332e+01 -5.16971207e+01 -5.16667366e+01 -5.19939728e+01 -5.20412292e+01 -5.19274597e+01 -5.23791618e+01 -5.22766571e+01 -5.16867256e+01 -5.13752060e+01 -5.16914253e+01 -5.19601822e+01 -5.14021645e+01 -5.05953178e+01 -4.97918167e+01 -5.04715767e+01 -5.07449036e+01 -5.10637512e+01 -5.07720642e+01 -5.12339249e+01 -5.10839195e+01 -4.64589348e+01 -4.64649582e+01 -5.26773415e+01 -5.44291115e+01 -5.18016281e+01 -5.00003395e+01 -4.98753281e+01 -4.94588432e+01 -4.91426620e+01 -4.88643341e+01 -4.93861732e+01 -4.94548874e+01 -4.94488258e+01 -4.87000046e+01 -4.85102425e+01 -4.84743423e+01 -4.82344513e+01 -4.86292877e+01 -4.83836975e+01 -4.87818756e+01 -4.82226143e+01 -4.78650246e+01 -4.77571602e+01 -4.79872704e+01 -4.79998283e+01 -4.78473701e+01 -4.73688240e+01 -4.70491905e+01 -4.61681366e+01 -4.65286484e+01 -4.64759407e+01 -4.71316071e+01 -4.67930107e+01 -4.67696342e+01 -4.60718155e+01 -4.58023758e+01 -4.57645111e+01 -4.58144073e+01 -4.51682854e+01 -4.53376694e+01 -4.59223557e+01 -4.57462273e+01 -4.47874107e+01 -4.45668678e+01 -4.40081787e+01 -4.38650627e+01 -4.34665070e+01 -4.34599380e+01 -4.31291809e+01 -4.34059258e+01 -4.35014305e+01 -4.30418663e+01 -4.29102058e+01 -4.34211006e+01 -4.33204231e+01 -4.24644928e+01 -4.18657532e+01 -4.19914856e+01 -4.15514755e+01 -4.06863594e+01 -3.90714111e+01 -2.46459541e+01 -1.53424271e+02 -2.14895828e+02 -4.77194763e+02 -1.04395325e+03 7469192. -44941720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5267423. 5267423. 5267423. 0. 0. 20586100. -1.26065559e+02 -4.70261688e+01 -4.11275749e+01 3.66540680e+01 8.38761215e+01 -1.80844543e+02 -2.50737656e+02 -8.16253586e+01 -35165424. -59987064. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 399658688. 399658688. 399658688. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 129619688. 129619688. 129619688. 0. 0. 0. 0. 53502272. 90715280. 295344000. -572696704. -974818688. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.07369719e+05 24424656. -2.39277094e+05 -78548992. -111749376. 151267904. -21269158. 4.41671731e+09 -21567020. -7.12624250e+06 -547796352. 113355000. -364349472. -364349472. 0. 0. 0. 0. 0. 0. 0. -70665224. -70665224. -70665224. 0. 0. -205965712. -233591728. -233591728. 94530224. -26735972. -3.36577344e+05 -1691978. -35712672. -3441318. 113085688. 29294388. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.35006703e+05 3.66021004e+01 -1.89564972e+02 -9.48055115e+01 1.69678440e+01 1.78595276e+01 1.68671799e+01 1.60000229e+01 1.56726952e+01 1.52373447e+01 1.58169012e+01 1.63843555e+01 1.55943813e+01 1.58106709e+01 1.75686703e+01 -1.04325249e+02 -2.01232346e+02 2.45654434e+02 1.56083984e+02 1.67079315e+01 1.88116817e+01 2.02708340e+01 1.95986252e+01 2.00841675e+01 2.16834335e+01 2.17501774e+01 2.20658379e+01 2.29428024e+01 2.28126259e+01 2.28271027e+01 2.33599339e+01 2.35305119e+01 2.44465332e+01 2.48725700e+01 2.47233715e+01 2.51993160e+01 2.31953049e+01 -1.20055283e+02 -2.30652084e+02 1.88644104e+01 1.87190304e+01 2.52747746e+01 3.09514069e+02 1.98863754e+02 2.88477993e+01 2.85152454e+01 2.94884338e+01 3.00544395e+01 3.04251156e+01 3.13319378e+01 3.08990135e+01 3.08518887e+01 3.15144272e+01 3.23953171e+01 3.23606682e+01 3.24012985e+01 3.26579132e+01 3.37500076e+01 3.43305855e+01 3.45652122e+01 3.36506500e+01 3.39587746e+01 3.44167671e+01 3.57578773e+01 3.59012260e+01 3.52458611e+01 3.55715103e+01 3.56594353e+01 3.66797676e+01 3.70714798e+01 3.75063286e+01 3.79352036e+01 3.78883018e+01 3.77752228e+01 3.79824486e+01 3.80689011e+01 3.92552567e+01 3.93457794e+01 3.98841095e+01 3.99174652e+01 4.09163971e+01 4.18431625e+01 4.16536369e+01 4.19773331e+01 4.17346191e+01 4.26175232e+01 4.23694763e+01 4.25794678e+01 4.28475342e+01 4.32419395e+01 4.34906464e+01 4.35648956e+01 4.39013367e+01 4.43360786e+01 4.45542412e+01 4.50780602e+01 4.52905159e+01 4.50747147e+01 4.55092773e+01 4.59352722e+01 4.60955391e+01 4.61573143e+01 4.61303482e+01 4.61175957e+01 4.65074883e+01 4.75372887e+01 4.82554169e+01 4.78168869e+01 4.68919716e+01 4.53373070e+01 4.72614861e+01 5.31036453e+01 5.35221710e+01 4.99359169e+01 4.89892616e+01 4.96457596e+01 5.01188889e+01 4.99420128e+01 5.00933952e+01 5.05605888e+01 5.12106972e+01 5.16768341e+01 5.16398735e+01 5.22195244e+01 5.23902664e+01 5.18865356e+01 5.19426041e+01 5.23878593e+01 5.29702759e+01 5.30886345e+01 5.34167633e+01 5.30677414e+01 5.30482063e+01 5.34659424e+01 5.39379768e+01 5.39425964e+01 5.40441971e+01 5.44160233e+01 5.50463943e+01 5.55311203e+01 5.57849617e+01 5.56430855e+01 5.44534111e+01 5.55340042e+01 5.71819458e+01 5.64028511e+01 5.64933052e+01 5.69595337e+01 5.69409714e+01 5.66812897e+01 5.70621071e+01 5.74241524e+01 5.76035118e+01 5.77666206e+01 5.78052216e+01 5.80566864e+01 5.83347931e+01 5.86357574e+01 5.86040344e+01 5.87481232e+01 5.88176804e+01 5.88235779e+01 5.90387650e+01 5.94534264e+01 5.95833931e+01 5.95820694e+01 5.98462944e+01 5.96847725e+01 5.99550591e+01 6.05413628e+01 6.02985001e+01 6.02413979e+01 6.03540268e+01 6.01317024e+01 6.02213783e+01 6.06152496e+01 6.09255066e+01 6.12409439e+01 6.15776558e+01 6.12550163e+01 6.11500473e+01 6.17411346e+01 6.17971344e+01 6.17544975e+01 6.17154274e+01 6.19450760e+01 6.19277725e+01 6.21507988e+01 6.20339622e+01 6.22415810e+01 6.19459190e+01 6.15437698e+01 6.16248512e+01 6.13437271e+01 6.10380516e+01 5.89112129e+01 5.32343407e+01 5.42014542e+01 7.12691116e+01 7.38866806e+01 6.16336174e+01 5.82364426e+01 5.31676865e+01 5.23127899e+01 8.64674759e+01 9.30579529e+01 9.06960907e+01 8.50200043e+01 6.82292175e+01 3.40574585e+02 4.95314148e+02 -8.50772156e+02 -2.25424316e+03 -1.78546814e+03 -6.37186096e+02 1.27459625e+02 4.64642975e+02 3.00562164e+02 6.60698776e+01 7.82429886e+01 7.81727600e+01 9.28376923e+01 9.30202484e+01 9.20346909e+01 7.64806671e+01 5.94416084e+01 3.11041527e+01 -1.43811020e+02 -2.57886932e+02 1.79335968e+02 1.53172577e+02 1.42726044e+02 1.37175491e+02 1.39299927e+02 1.36487457e+02 1.33559189e+02 4.54366455e+02 3.03638641e+02 7.23547974e+01 7.16006622e+01 7.23250122e+01 7.00094223e+01 6.84396973e+01 6.45867844e+01 6.65168991e+01 7.00016556e+01 6.44767456e+01 6.22220955e+01 6.65476913e+01 6.61047745e+01 5.89919777e+01 5.69164581e+01 5.26460991e+01 3.65236206e+01 6.98682327e+01 9.36867676e+01 5.75982132e+01 8.75048981e+01 9.28471527e+01 7.47087936e+01 7.59455872e+01 6.64679108e+01 6.74143066e+01 6.15265465e+01 6.58172073e+01 6.59694672e+01 6.39687080e+01 6.53688202e+01 6.37383919e+01 6.09349861e+01 6.36574593e+01 6.13614998e+01 5.75361977e+01 6.18291473e+01 6.46878052e+01 6.36947021e+01 6.32725601e+01 6.23434410e+01 6.19716339e+01 6.17943192e+01 6.17846909e+01 6.16098595e+01 6.07119789e+01 6.02990799e+01 6.02921906e+01 6.04080696e+01 6.02595139e+01 5.99442482e+01 5.97791481e+01 5.96363792e+01 5.96824989e+01 5.95030251e+01 5.87090530e+01 5.83548317e+01 5.80511208e+01 5.75263596e+01 5.74061241e+01 5.78252563e+01 5.76490021e+01 5.71726494e+01 5.66992531e+01 5.62845268e+01 5.61414337e+01 5.65668488e+01 5.69369736e+01 5.67712288e+01 5.59853935e+01 5.56692963e+01 5.57428246e+01 5.51417885e+01 5.51112900e+01 5.59679909e+01 5.50732727e+01 5.46551933e+01 5.45686607e+01 5.43682976e+01 5.41213799e+01 5.40822449e+01 5.35803833e+01 5.38968277e+01 5.36984940e+01 5.28098831e+01 5.27247314e+01 5.21987000e+01 5.23283806e+01 5.23430634e+01 5.21284943e+01 5.20731125e+01 5.14110107e+01 5.09391861e+01 5.05807648e+01 4.99897346e+01 5.06084137e+01 5.07112846e+01 5.00949440e+01 4.91530533e+01 4.92043381e+01 4.97864456e+01 4.96897736e+01 4.96136398e+01 4.86472740e+01 4.82335205e+01 4.82113533e+01 4.80351105e+01 4.72810974e+01 4.69232140e+01 4.70350876e+01 4.71965637e+01 4.65893402e+01 4.59959984e+01 4.56574783e+01 4.54601479e+01 4.53689766e+01 4.49819298e+01 4.46269035e+01 4.44059563e+01 4.42287979e+01 4.39461098e+01 4.38179207e+01 4.33303299e+01 4.29530602e+01 4.27027626e+01 4.25084648e+01 4.21073112e+01 4.18102913e+01 4.16247330e+01 4.14835739e+01 4.09446297e+01 4.05354195e+01 4.04657478e+01 4.03192101e+01 3.97644234e+01 3.91547241e+01 3.92011528e+01 3.92168579e+01 3.88738556e+01 3.85946426e+01 3.81253128e+01 3.76693153e+01 3.73970184e+01 3.69739609e+01 3.65646667e+01 3.60457611e+01 3.57189293e+01 3.53764076e+01 3.50235367e+01 3.51592789e+01 3.49039955e+01 3.41644173e+01 3.36250763e+01 3.34189606e+01 3.32382011e+01 3.31957550e+01 3.27152481e+01 3.22843361e+01 3.20433197e+01 3.17783947e+01 3.13066845e+01 3.10745201e+01 3.07512493e+01 3.01672363e+01 2.98123283e+01 2.94888210e+01 2.92261505e+01 2.91253090e+01 2.87798843e+01 2.83290043e+01 2.78716869e+01 2.76333561e+01 2.73281803e+01 2.68697681e+01 2.64664555e+01 2.61121635e+01 2.57946548e+01 2.54104996e+01 2.50387993e+01 2.46958103e+01 2.43184853e+01 2.39087009e+01 2.35529022e+01 2.32841244e+01 2.28988094e+01 2.24848156e+01 2.21290474e+01 2.17623978e+01 2.14103699e+01 2.10494804e+01 2.06974125e+01 2.03531876e+01 2.00010548e+01 1.96442795e+01 1.92871723e+01 1.88996964e+01 1.85253105e+01 1.81420078e+01 1.77105618e+01 1.71743469e+01 1.68303661e+01 1.65408669e+01 1.61193428e+01 1.57058125e+01 1.52956486e+01 1.50657673e+01 1.47767200e+01 1.44097052e+01 1.39830017e+01 1.35199318e+01 1.31182518e+01 1.27389278e+01 1.23146133e+01 1.19293890e+01 1.15949144e+01 1.12253284e+01 1.07812872e+01 1.04053907e+01 9.95407200e+00 9.61499023e+00 9.20227146e+00 8.72795963e+00 8.38465405e+00 8.03417110e+00 7.59192419e+00 7.16722584e+00 6.84395885e+00 6.33040524e+00 5.91188383e+00 5.62781715e+00 5.20698214e+00 4.73867750e+00 4.50411081e+00 4.23590088e+00 3.67538786e+00 3.31178975e+00 2.89758301e+00 2.51802802e+00 1.98562956e+00 1.65199423e+00 1.24230349e+00 8.80967915e-01 4.45056826e-01 3.12455267e-01 -5.12908213e-02 -4.02569801e-01 -9.13485169e-01 -1.53340125e+00 -1.99277318e+00 -2.21506739e+00 -2.68999505e+00 -3.01052761e+00 -2.96130180e+00 -3.72245479e+00 -4.12822580e+00 -4.97067881e+00 -5.36156702e+00 -5.67223740e+00 -5.83475685e+00 -5.95906687e+00 -6.39222670e+00 -6.85356903e+00 -7.55115747e+00 -8.14091396e+00 -8.18366718e+00 -8.42940140e+00 -8.98598671e+00 -9.32232189e+00 -9.53843880e+00 -9.92378902e+00 -1.05282154e+01 -1.11776505e+01 -1.11781502e+01 -1.13183632e+01 -1.13041258e+01 -1.17714157e+01 -1.25947866e+01 -1.31569328e+01 -1.34431276e+01 -1.38511267e+01 -1.39834051e+01 -1.46830940e+01 -1.50914497e+01 -1.55926266e+01 -1.56260128e+01 -1.57041807e+01 -1.64671898e+01 -1.67632904e+01 -1.66945305e+01 -1.70963516e+01 -1.74296932e+01 -1.85143204e+01 -1.84272976e+01 -1.83904266e+01 -1.87908573e+01 -1.93471127e+01 -2.01409054e+01 -2.04821091e+01 -2.10973377e+01 -2.16956882e+01 -2.28048954e+01 -2.25060139e+01 -2.24119625e+01 -2.24329853e+01 -2.28462181e+01 -2.32150269e+01 -2.35323563e+01 -2.41957073e+01 -2.47532578e+01 -2.49679623e+01 -2.55578880e+01 -2.58676662e+01 -2.53187237e+01 -2.54211693e+01 -2.65785236e+01 -2.76117611e+01 -2.72184410e+01 -2.72893524e+01 -2.80310421e+01 -2.75892353e+01 -2.82773876e+01 -2.87097931e+01 -2.98215313e+01 -3.08191891e+01 -3.09878578e+01 -3.03952484e+01 -2.99543304e+01 -3.08041496e+01 -3.20694199e+01 -3.19432888e+01 -3.18515949e+01 -3.13728638e+01 -3.23402824e+01 -3.33370972e+01 -3.37964821e+01 -3.40130539e+01 -3.45530586e+01 -3.50473366e+01 -3.52934608e+01 -3.53324699e+01 -3.47357712e+01 -3.44240417e+01 -3.50524864e+01 -3.67872314e+01 -3.69212303e+01 -3.74086914e+01 -3.84611168e+01 -3.82653923e+01 -3.77144928e+01 -3.79950294e+01 -3.81388931e+01 -3.89969788e+01 -3.96525040e+01 -3.96594238e+01 -4.01765327e+01 -4.06262093e+01 -4.05532608e+01 -4.05238419e+01 -4.16155663e+01 -4.13621216e+01 -4.20173302e+01 -4.23851471e+01 -4.30196838e+01 -4.27669258e+01 -4.35296669e+01 -4.37754822e+01 -4.41262398e+01 -4.39396553e+01 -4.38618126e+01 -4.42449493e+01 -4.36801834e+01 -4.51745071e+01 -4.56376152e+01 -4.53340645e+01 -4.55980873e+01 -4.45819321e+01 -4.36335526e+01 -4.06544533e+01 1.47509903e+02 2.87353790e+02 -6.47209396e+01 -7.21512222e+01 -7.14772644e+01 -7.16659088e+01 -7.22596741e+01 -7.47185974e+01 -7.70800705e+01 -7.39545517e+01 -4.34020447e+02 -2.71756165e+02 -4.85715256e+01 -3.82218437e+01 -6.67831650e+01 -8.55292511e+01 -7.97691269e+01 -7.95282135e+01 -7.98851929e+01 -6.14438820e+01 -6.39606285e+01 1.42217178e+02 2.90517548e+02 -7.96689377e+01 -4.29456940e+02 -6.72157898e+01 2.73221283e+02 -4.59122345e+02 -2.92549530e+02 -7.27546844e+01 5.37778854e+01 -7.72216415e+01 -1.78522232e+02 -6.31431084e+01 -6.78844299e+01 -5.96285629e+01 -5.02863197e+01 -5.68220482e+01 -2.93875519e+02 -5.39210815e+01 1.47938370e+02 -5.64980164e+01 -5.84008217e+01 -5.82552757e+01 -5.86589928e+01 -5.80189056e+01 -5.72461472e+01 -5.72644196e+01 -5.76053619e+01 -5.76606331e+01 -5.78829880e+01 -5.80539818e+01 -5.81441116e+01 -5.83689690e+01 -5.84253006e+01 -5.86475220e+01 -5.87124443e+01 -5.88161774e+01 -5.91182785e+01 -5.95578156e+01 -5.95258255e+01 -5.94827003e+01 -5.96794548e+01 -5.97737617e+01 -5.99705162e+01 -6.00631790e+01 -6.00868568e+01 -6.01343880e+01 -6.02867432e+01 -6.06089859e+01 -6.08626671e+01 -6.10288048e+01 -6.08785744e+01 -6.09676590e+01 -6.14539452e+01 -6.13464966e+01 -6.12987518e+01 -6.13621101e+01 -6.18804054e+01 -6.19991646e+01 -6.20279007e+01 -6.17544594e+01 -6.21231079e+01 -6.28347244e+01 -6.26652718e+01 -6.24684105e+01 -6.33339157e+01 -6.35057030e+01 -6.20645409e+01 -6.24008064e+01 -6.28680077e+01 -6.28180656e+01 -6.29063950e+01 -6.28811378e+01 -6.27348404e+01 -6.28929710e+01 -6.35025787e+01 -6.30871773e+01 -6.32639351e+01 -6.28694649e+01 -6.29300728e+01 -6.33020554e+01 -6.35020027e+01 -6.39146538e+01 -6.35382957e+01 -6.34857750e+01 -6.35597000e+01 -6.35861816e+01 -6.37732964e+01 -6.28072624e+01 -6.27066498e+01 -6.46165619e+01 -6.47384949e+01 -6.37774315e+01 -6.39329033e+01 -6.39250298e+01 -6.41924057e+01 -6.37784462e+01 -6.40424957e+01 -6.39717827e+01 -6.41745529e+01 -6.37676888e+01 -6.36077957e+01 -6.38590317e+01 -6.38964691e+01 -6.21535568e+01 -6.26252289e+01 -6.65370331e+01 -6.59712982e+01 -6.39920578e+01 -6.36207428e+01 -6.31071167e+01 -6.29143181e+01 -6.41290131e+01 -6.20028191e+01 -6.16707306e+01 -6.42697220e+01 -6.68951187e+01 -6.64202194e+01 -6.41939621e+01 -6.40563049e+01 -6.41160202e+01 -6.38301849e+01 -6.33836098e+01 -6.37102089e+01 -6.31638565e+01 -6.33296890e+01 -6.32834244e+01 -6.29964638e+01 -6.31288643e+01 -6.27902374e+01 -6.29598312e+01 -6.27619743e+01 -6.24469452e+01 -6.26295929e+01 -6.24636192e+01 -6.25759010e+01 -6.29435921e+01 -6.25229149e+01 -6.27293205e+01 -6.28039551e+01 -6.28900337e+01 -6.21567841e+01 -6.18466415e+01 -6.20315208e+01 -6.20359268e+01 -6.11774597e+01 -6.08355141e+01 -6.05930061e+01 -5.73431282e+01 -5.70323524e+01 -6.29370346e+01 -6.35378609e+01 -6.07829475e+01 -6.00826950e+01 -6.01758347e+01 -6.07048836e+01 -6.03771248e+01 -6.01362648e+01 -5.96376152e+01 -5.91188278e+01 -5.90717201e+01 -5.89813232e+01 -5.92981567e+01 -5.92406006e+01 -5.90152168e+01 -5.95329094e+01 -5.95384941e+01 -5.93032722e+01 -5.86227226e+01 -5.53903503e+01 -4.84046707e+01 -4.25165253e+01 9.38274002e+01 1.73910980e+02 -1.32984161e+02 -1.33484558e+02 -3.58237274e+02 -2.30340637e+02 -5.69164276e+01 -5.76216240e+01 -5.77844353e+01 -5.74290810e+01 -5.67721405e+01 -5.66625366e+01 -5.63064537e+01 -5.62106285e+01 -5.59478455e+01 -5.55017662e+01 -5.51721649e+01 -5.53143959e+01 -5.49963951e+01 -5.48816338e+01 -5.33330040e+01 -5.27288628e+01 -5.31566696e+01 -6.09338913e+01 5.92836456e+01 -3.42409706e+01 -2.19724854e+02 -6.34663925e+01 -6.54918900e+01 -6.40149841e+01 -5.58914833e+01 -5.37524681e+01 -5.27057114e+01 -5.22870331e+01 -5.15720863e+01 -5.09703064e+01 -5.03288918e+01 -4.93935165e+01 -4.68501472e+01 -3.15527000e+01 -1.49405533e+02 -1.55136459e+02 2.46388525e+03 -44941720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5267423. 5267423. 5267423. 0. 0. 2.16375850e+06 -4.10028046e+02 -1.79196915e+02 -1.55042816e+02 1.63289398e+02 6.03803833e+02 -1.08552429e+03 -2.06701477e+02 5.45942078e+02 -35165424. -59987064. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.84576538e+09 2.84576538e+09 2.84576538e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 129619688. 129619688. 129619688. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 827010048. 827010048. 827010048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.07369719e+05 24424656. -2.39277094e+05 -78548992. -111749376. 151267904. -21269158. 4.41671731e+09 2.20673447e+02 -1.63034760e+02 -1.14014429e+03 1.54054276e+02 7.88498108e+02 7.88498108e+02 -12231849. -268952864. -268952864. -138468800. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.35006703e+05 3.66021004e+01 -3.04770012e+01 -2.53635464e+01 -2.46902714e+01 1.95140182e+02 1.17678528e+02 -1.96944129e+00 -1.76279771e+00 -2.18375182e+00 -2.37525725e+00 -1.60839248e+00 -1.28389984e+02 -2.32368942e+02 -3.76721458e+01 -5.67499390e+02 -1.44151184e+03 1.17456921e+03 4.75732422e+02 -4.68002510e+01 -3.65120811e+01 -3.33094521e+01 -3.52084007e+01 -3.13951778e+01 -2.80118141e+01 -2.92296066e+01 2.41652863e+02 1.49049179e+02 3.00835061e+00 3.31758070e+00 3.64882588e+00 3.86870933e+00 4.19772053e+00 4.76934004e+00 -1.41063522e+02 -2.55352554e+02 -3.51697083e+01 -6.47273376e+02 -1.64463586e+03 15776011. -2.84588621e+09 -31432704. 1.52168213e+03 6.41616699e+02 -1.02324924e+01 -1.75388107e+01 -1.47421103e+01 -1.32954550e+01 -1.14308062e+01 -9.66950226e+00 -1.02628603e+01 2.95636780e+02 1.82271576e+02 1.14183578e+01 1.19244423e+01 1.15807734e+01 1.20084686e+01 1.20111456e+01 1.28242750e+01 1.28445148e+01 1.24966259e+01 1.29332638e+01 1.27698746e+01 1.33604803e+01 1.34650230e+01 1.31047735e+01 1.34324427e+01 1.41997223e+01 1.43633165e+01 1.45436449e+01 1.48656902e+01 1.57330332e+01 1.58648205e+01 1.62875595e+01 1.63027363e+01 1.63985176e+01 1.61370335e+01 1.58003960e+01 1.66069202e+01 1.66094532e+01 1.73096333e+01 1.72612019e+01 1.76257324e+01 1.74726028e+01 1.81644306e+01 1.85033379e+01 1.96048260e+01 1.96045856e+01 1.93015003e+01 1.85397930e+01 1.91449757e+01 2.07817955e+01 2.01340694e+01 2.02445679e+01 2.00869904e+01 2.07791443e+01 2.10313892e+01 2.10174503e+01 2.20963097e+01 2.20105171e+01 2.19307079e+01 2.17664547e+01 2.25778866e+01 2.27404900e+01 2.29983826e+01 2.31104164e+01 2.36100292e+01 2.39101543e+01 2.40566483e+01 2.05290432e+01 2.12187881e+01 2.92684383e+01 2.95217819e+01 2.48920174e+01 2.46127949e+01 2.52417603e+01 2.57373009e+01 2.58765564e+01 2.58486118e+01 2.60215588e+01 2.62055798e+01 2.69012794e+01 2.68360100e+01 2.70682621e+01 2.69137039e+01 2.71245117e+01 2.74804268e+01 2.82325897e+01 2.83951454e+01 2.80529861e+01 2.85995102e+01 2.85138512e+01 2.87660046e+01 2.94275951e+01 2.93447933e+01 2.92984962e+01 2.95244274e+01 2.96380711e+01 3.01116333e+01 3.05285625e+01 3.07481918e+01 3.05785160e+01 2.98241062e+01 3.07712936e+01 3.20058937e+01 3.13411598e+01 3.14950619e+01 3.23391991e+01 3.24456291e+01 3.19053421e+01 3.22119713e+01 3.26167183e+01 3.26369438e+01 3.24664421e+01 3.25787125e+01 3.28678360e+01 3.34544220e+01 3.35308838e+01 3.36641388e+01 3.39009209e+01 3.40761757e+01 3.42470131e+01 3.44323540e+01 3.47785301e+01 3.49342728e+01 3.49044952e+01 3.50434189e+01 3.49198074e+01 3.50551987e+01 3.56939964e+01 3.57604713e+01 3.57089729e+01 3.58722000e+01 3.58623199e+01 3.58377190e+01 3.61766052e+01 3.66200523e+01 3.68772354e+01 3.70168610e+01 3.67586441e+01 3.70954895e+01 3.76186752e+01 3.73746758e+01 3.76209335e+01 3.75678978e+01 3.75007744e+01 3.80786591e+01 3.81908798e+01 3.81391830e+01 3.81722565e+01 3.84007111e+01 3.81591606e+01 3.83213577e+01 3.89874229e+01 3.88648453e+01 3.87939606e+01 3.90297852e+01 3.91119194e+01 3.89806938e+01 3.88961792e+01 3.85279350e+01 3.48792534e+01 2.92943363e+01 2.93511944e+01 2.55785019e+02 4.16347351e+02 4.83152618e+01 2.56820965e+01 -3.21671783e+02 -1.67298996e+02 3.52145500e+01 6.12372017e+01 6.56279449e+01 5.44602242e+01 4.86482315e+01 4.67726517e+01 4.70194168e+01 5.10020218e+01 -1.60613098e+02 -3.56667557e+01 2.34033936e+03 -13435681. 20299972. -6.55823250e+06 -1.90993933e+03 -7.54764160e+02 -9.15332565e+01 -7.12440308e+02 -1.72064172e+03 1.53453675e+06 42231520. 85671848. -22628356. -15605513. 106922120. 2.16762402e+03 8.26772522e+02 -2.78632183e+01 1.50015717e+02 4.21651733e+02 1.35280045e+02 -1.62602844e+02 1.28708160e+02 1.05345566e+02 1.17168999e+02 1.40415054e+02 3.67193451e+02 2.91173248e+02 -1.12493645e+02 1.18759399e+02 6.82102585e+01 -9.87838840e+00 3.39752441e+02 4.62372246e+01 2.47007790e+01 1.73353073e+02 8.54232330e+01 5.05654755e+01 1.13663399e+02 6.87599106e+01 4.63747177e+01 7.31030655e+01 7.03125916e+01 4.33835068e+01 5.68878822e+01 7.26452026e+01 6.61198273e+01 -1.24046967e+02 1.39444214e+02 1.38588501e+02 -2.15609344e+02 -1.47490280e+02 8.44692612e+01 1.14854538e+02 1.34638412e+02 1.28581024e+02 1.26705910e+02 1.21274712e+02 1.20943794e+02 1.19563759e+02 1.19379700e+02 1.19313354e+02 1.17987045e+02 1.18207848e+02 1.16587662e+02 1.16492599e+02 1.16076378e+02 1.17812599e+02 1.17241890e+02 1.16223862e+02 1.18169617e+02 3.55155212e+02 2.22458633e+02 4.54038277e+01 4.56688766e+01 4.50027084e+01 4.48282433e+01 4.46914062e+01 4.49939804e+01 4.46827660e+01 4.48928413e+01 4.37831688e+01 4.34305878e+01 4.25684471e+01 4.23286247e+01 4.21805038e+01 4.23191490e+01 4.24761429e+01 4.24792023e+01 4.16785088e+01 4.19586678e+01 4.23174438e+01 4.20189018e+01 4.15152779e+01 4.20168953e+01 4.19996567e+01 4.18760452e+01 4.16559906e+01 4.12837639e+01 4.14964447e+01 4.12754326e+01 4.13514786e+01 4.13976517e+01 4.10746841e+01 4.08555450e+01 4.07048035e+01 4.06211395e+01 4.08136444e+01 4.08336983e+01 4.08884506e+01 4.06187553e+01 4.02322235e+01 4.01448364e+01 3.99808235e+01 4.02465782e+01 3.89207687e+01 3.90220909e+01 3.90234184e+01 3.98917580e+01 3.97060966e+01 3.90117798e+01 3.83469849e+01 3.89348488e+01 3.93415527e+01 3.85579872e+01 3.81939964e+01 3.86051750e+01 3.91315956e+01 3.84572525e+01 3.81723976e+01 3.78788071e+01 3.77379570e+01 3.77492065e+01 3.76842537e+01 3.76069908e+01 3.74568672e+01 3.74015694e+01 3.73741913e+01 3.74891281e+01 3.69459839e+01 3.68776627e+01 3.68832817e+01 3.66327057e+01 3.64167824e+01 3.61111259e+01 3.58706169e+01 3.57755318e+01 3.54848442e+01 3.56935692e+01 3.54756775e+01 3.52347717e+01 3.50805397e+01 3.49450264e+01 3.49017525e+01 3.47971992e+01 3.45790100e+01 3.45090065e+01 3.44085503e+01 3.40432816e+01 3.38858795e+01 3.37771530e+01 3.35681763e+01 3.33648453e+01 3.31989861e+01 3.27580490e+01 3.25355682e+01 3.26664734e+01 3.24384804e+01 3.22363930e+01 3.20170975e+01 3.17788906e+01 3.16377449e+01 3.14873581e+01 3.12909107e+01 3.11969051e+01 3.09882221e+01 3.06302090e+01 3.05898495e+01 3.04721222e+01 3.01824417e+01 2.99344540e+01 2.97259617e+01 2.94036865e+01 2.92258511e+01 2.92332630e+01 2.90733318e+01 2.88295803e+01 2.86217384e+01 2.84218864e+01 2.82113228e+01 2.80245533e+01 2.78128586e+01 2.76130562e+01 2.73869610e+01 2.71324444e+01 2.69219360e+01 2.67112312e+01 2.65025635e+01 2.62314129e+01 2.60541897e+01 2.59366398e+01 2.57182312e+01 2.54581985e+01 2.52544193e+01 2.50236111e+01 2.48177853e+01 2.46118259e+01 2.43847332e+01 2.41953945e+01 2.40014515e+01 2.38219604e+01 2.36189709e+01 2.33614788e+01 2.31465778e+01 2.29223385e+01 2.26895199e+01 2.24577141e+01 2.22893066e+01 2.21452255e+01 2.18050003e+01 2.15481739e+01 2.13650246e+01 2.12608414e+01 2.09944324e+01 2.07087288e+01 2.04588013e+01 2.01953411e+01 1.98778095e+01 1.95676956e+01 1.93617878e+01 1.91063213e+01 1.87559185e+01 1.85091438e+01 1.83072815e+01 1.81730671e+01 1.79406528e+01 1.76705818e+01 1.73957310e+01 1.70276375e+01 1.68106232e+01 1.66951599e+01 1.64535732e+01 1.62196827e+01 1.59874439e+01 1.57403097e+01 1.55061188e+01 1.51526756e+01 1.49720678e+01 1.46808815e+01 1.45878935e+01 1.42723436e+01 1.37796812e+01 1.34192762e+01 1.33152218e+01 1.31431656e+01 1.29764318e+01 1.25396957e+01 1.22528467e+01 1.19126253e+01 1.17595882e+01 1.16326704e+01 1.14736423e+01 1.11900721e+01 1.08656559e+01 1.04052734e+01 1.02271423e+01 1.01459103e+01 9.83884144e+00 9.64224815e+00 9.45717239e+00 9.27943325e+00 9.04560375e+00 8.77692986e+00 8.37486458e+00 8.23866749e+00 7.97764874e+00 7.60381937e+00 7.09356594e+00 6.91527700e+00 6.61834335e+00 5.98714924e+00 5.86685562e+00 5.97935247e+00 5.98736191e+00 5.56846666e+00 5.03917360e+00 4.69377804e+00 4.23183537e+00 3.97037339e+00 3.62719893e+00 3.42855978e+00 3.51543283e+00 3.45431781e+00 3.02608252e+00 2.60199142e+00 2.28945661e+00 1.99524772e+00 1.95838523e+00 2.28729343e+00 1.70293939e+00 8.97551596e-01 1.00827861e+00 9.14840877e-01 2.67847329e-01 1.21908568e-01 -1.37645483e-01 -9.10049200e-01 -8.66366684e-01 -1.01160836e+00 -1.29175770e+00 -1.89066684e+00 -1.63620353e+00 -1.90829599e+00 -2.28764009e+00 -2.73939681e+00 -2.82409286e+00 -3.28787947e+00 -4.17947006e+00 -4.67683125e+00 -4.23388338e+00 -3.55493665e+00 -3.83782959e+00 -4.60984182e+00 -5.39561415e+00 -5.42587852e+00 -5.28314066e+00 -5.09118032e+00 -5.85848856e+00 -5.90046549e+00 -5.70002890e+00 -5.47193861e+00 -6.72802401e+00 -7.93929195e+00 -6.89471483e+00 -7.22802687e+00 -7.29895782e+00 -8.01389408e+00 -8.18049335e+00 -8.68786526e+00 -8.58603096e+00 -8.93348217e+00 -8.90836430e+00 -9.06990051e+00 -8.55187893e+00 -1.00386429e+01 1.49688644e+02 2.74124878e+02 -2.96579224e+02 -1.56671534e+01 2.80452240e+02 5.10051823e+00 3.00311327e+00 1.83760178e+00 8.58780146e-01 -2.37967865e+02 -2.60187958e+02 1.07068466e+02 2.89828369e+02 6.01551104e+00 3.45290256e+00 -2.04742002e+00 -2.46264755e+02 -2.17397598e+02 -1.45672150e+02 8.71711960e+01 2.98306244e+02 -2.70016632e+02 -1.59129658e+01 2.56887817e+02 -5.23271132e+00 -8.05215740e+00 -9.96669292e+00 -1.29585075e+01 -8.70129776e+00 -7.99863243e+00 -1.08417244e+01 -1.07843256e+01 -1.13552742e+01 -1.45908728e+01 -1.50392284e+01 -1.51237411e+01 -1.53373919e+01 -1.48233662e+01 -1.81429482e+01 -3.70464172e+02 -3.18722992e+01 3.17465057e+02 -1.36397381e+01 -2.11426201e+01 -2.36225491e+01 -2.05314522e+01 -1.90508289e+01 -1.24170818e+01 -6.91020584e+00 1.70482407e+01 8.65575623e+02 2.24622656e+03 -58943888. 10050929. 39429684. -211116608. -68663712. -1.92913257e+03 -6.78539886e+01 1.86394482e+03 -2.02631775e+03 -7.91483459e+02 -2.80696545e+01 1.93760433e+01 -7.50926392e+02 -1.91465698e+03 -39524472. 3952981. -20429162. 2.03764795e+03 -3.20528374e+01 -3.44768036e+02 -1.16572212e+02 -4.75953026e+01 -4.25211639e+01 -4.69937096e+01 -3.20847282e+01 -3.10040245e+01 -3.69794998e+01 -2.58793335e+02 6.07570038e+01 -4.34479141e+01 -3.66975861e+02 3.33851837e+02 1.72822525e+02 -3.52928619e+01 -3.18163242e+01 -3.23016815e+01 -3.19747181e+01 -3.18251781e+01 -3.14954243e+01 -3.13772812e+01 -3.19374485e+01 -3.17883759e+01 -3.18868103e+01 -3.22317924e+01 -3.23871040e+01 -3.25086441e+01 -3.26440430e+01 -3.25715981e+01 -3.27476997e+01 -3.29589424e+01 -3.31786232e+01 -3.34965439e+01 -3.35522804e+01 -3.37751579e+01 -3.40227852e+01 -3.40873604e+01 -3.40756531e+01 -3.45367813e+01 -3.46998482e+01 -3.44915771e+01 -3.41437035e+01 -3.41464462e+01 -3.49167252e+01 -3.53232765e+01 -3.53793144e+01 -3.55317917e+01 -3.56660385e+01 -3.56778183e+01 -3.59970322e+01 -3.67113228e+01 -3.65240440e+01 -3.64188766e+01 -3.69594498e+01 -3.66134033e+01 -3.68408546e+01 -3.73183479e+01 -3.73979530e+01 -3.75356941e+01 -3.75937767e+01 -3.73809090e+01 -3.80185852e+01 -3.87122040e+01 -3.83682098e+01 -3.83222504e+01 -3.91071701e+01 -3.93932915e+01 -3.84950676e+01 -3.92932205e+01 -3.98915482e+01 -3.92851906e+01 -3.91453323e+01 -3.91455460e+01 -3.90301056e+01 -3.90686417e+01 -3.97666702e+01 -3.96294785e+01 -3.97613907e+01 -3.96549988e+01 -4.00003891e+01 -4.01151314e+01 -4.04475365e+01 -4.08314247e+01 -4.03766022e+01 -4.03333817e+01 -4.01010361e+01 -4.06282196e+01 -4.06791420e+01 -3.95766449e+01 -3.96195488e+01 -4.19435081e+01 -4.21911736e+01 -4.15478058e+01 -4.11373787e+01 -4.12353401e+01 -4.10173302e+01 -4.10456696e+01 -4.19067192e+01 -4.23362923e+01 -4.19449387e+01 -4.22145996e+01 -4.18461533e+01 -4.18079262e+01 -4.18783684e+01 -4.11420326e+01 -4.13665733e+01 -4.41614609e+01 -4.40013885e+01 -4.23971214e+01 -4.20677299e+01 -4.12519951e+01 -4.13486137e+01 -4.22112350e+01 -4.08289948e+01 -4.07009430e+01 -4.40457420e+01 -4.54180374e+01 -4.45700607e+01 -4.34353027e+01 -4.40085831e+01 -4.42344322e+01 -4.35753212e+01 -4.31764412e+01 -4.31462631e+01 -4.30512390e+01 -4.31691551e+01 -4.33613243e+01 -4.34468918e+01 -4.35821571e+01 -4.36848297e+01 -4.37818413e+01 -4.35100288e+01 -4.31437225e+01 -4.25706749e+01 -4.22226181e+01 -4.25902138e+01 -4.33960648e+01 -4.33150520e+01 -4.24920540e+01 -4.19317360e+01 -4.23961945e+01 -3.88680916e+01 -4.48638954e+01 -4.95567207e+01 -4.42740440e+01 -4.44357910e+01 -4.22611580e+01 -4.12497139e+01 -3.98418312e+01 -4.02838173e+01 -4.32936707e+01 -4.59570236e+01 -4.64391098e+01 -4.50278511e+01 -4.33221779e+01 -4.30895271e+01 -4.32761688e+01 -4.32811050e+01 -4.25105247e+01 -4.26884537e+01 -4.23443756e+01 -4.28060532e+01 -4.20327644e+01 -2.73987961e+01 -2.29701767e+01 -4.15511627e+01 1.09902451e+02 2.03544266e+02 -1.13126122e+02 -9.61658783e+01 -5.05916481e+01 -1.80056036e+00 6.62097046e+02 1.67002246e+03 -59429016. 49697208. -1.84115576e+03 -7.95197571e+02 -1.17316238e+02 -1.17862854e+02 -1.17958382e+02 -1.17180962e+02 -1.18170135e+02 -1.20910614e+02 -1.17530098e+02 -1.15509872e+02 -1.17396172e+02 -1.16494583e+02 -1.18702049e+02 -1.18152885e+02 -1.17134567e+02 -1.17379143e+02 -3.06287720e+02 -6.19310379e+01 1.78648636e+02 -1.58090927e+02 3.23510925e+02 1.98158340e+01 -9.17100647e+02 -1.93424133e+02 -2.02785995e+02 -1.90827164e+02 -1.39173508e+02 -3.01005859e+02 -1.94012573e+02 -4.77550583e+01 -4.73817635e+01 6.77174072e+01 1.33611618e+02 -1.11809357e+02 -1.08095360e+02 -9.72745209e+01 -4.51486816e+01 4.73297150e+02 2.46388525e+03 -44941720. 0. 0. 0. 0. 0. 0. 0. 0. 0. -115607928. -115607928. -115607928. 0. 0. 0. 0. 5267423. 5267423. 5267423. 0. 0. -71735328. -23928980. -3406612. -4228635. 202364224. 2.47866525e+06 56524316. 56524316. 56524316. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.84576538e+09 2.84576538e+09 2.84576538e+09 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. -666764. -666764. -666764. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 827010048. 827010048. 827010048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.07369719e+05 24424656. -2.39277094e+05 -78548992. -111749376. 151267904. -21269158. 4.41671731e+09 2.20673447e+02 -1.63034760e+02 -1.14014429e+03 1.54054276e+02 7.88498108e+02 7.88498108e+02 -12231849. -268952864. -268952864. -138468800. 0. 0. 0. 0. -83195784. -83195784. -83195784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.37004093e+10 1.37004093e+10 1.37004093e+10 0. 0. 0. 0. 0. 0. 0. -34077768. -34077768. -34077768. 0. -10514144. -17545476. -2.79007550e+06 -25635526. -26739002. 1.02032019e+03 3.89515411e+02 -7.39746475e+01 -7.46735916e+01 -7.68372879e+01 -7.86006851e+01 -7.33606873e+01 -6.01756165e+02 -1.47772717e+03 -2.98586175e+06 -12729093. 63542612. 1.06678703e+05 -1.22569470e+03 -6.69753235e+02 -13349513. -22836150. -22664062. 6.36880798e+02 -5.30100393e+00 -6.89350464e+02 1.23553357e+03 4.98287048e+02 -6.07977333e+01 -6.18691101e+01 -6.13935738e+01 -6.19596443e+01 -6.11101875e+01 -5.73801689e+01 7.22831488e+00 -5.63033142e+02 -1.52012732e+03 4.13009229e+03 -62663220. -451043616. 0. 0. 3.07015898e+04 -1.37256934e+03 -7.50779602e+02 64374604. 68517808. 23372388. -78004272. -33526550. -10244756. 1.51712573e+03 6.14404663e+02 -3.73119850e+01 2.73566620e+02 1.62074280e+02 -4.36900949e+00 -4.16818714e+00 -3.83959866e+00 -3.64483118e+00 -3.57781005e+00 -3.46573400e+00 -3.89025474e+00 -4.01576424e+00 -3.48731065e+00 -2.75059533e+00 -2.29222679e+00 -1.82051599e+00 -1.22886217e+00 -1.36151385e+00 -1.86752987e+00 -1.13027930e+00 -8.29907000e-01 -4.44318026e-01 -8.16547930e-01 1.07745521e-01 6.90607950e-02 -1.80646729e+02 -3.18708771e+02 3.11135406e+02 1.84146881e+02 -8.12908709e-01 2.05187023e-01 6.29622340e-01 1.16956973e+00 -1.84530869e+02 -3.23088928e+02 3.25428223e+02 1.93957504e+02 1.41084182e+00 2.03749394e+00 2.87493777e+00 2.65070677e+00 2.53088379e+00 2.76169991e+00 3.15096068e+00 3.46202278e+00 3.69677591e+00 4.19655609e+00 4.21740103e+00 4.20055676e+00 4.16259289e+00 5.14205170e+00 5.74149990e+00 5.62766171e+00 5.16983271e+00 5.02941132e+00 5.54803038e+00 5.79766464e+00 1.94089270e+00 2.41495562e+00 1.13475475e+01 1.13584070e+01 6.50917292e+00 6.84263468e+00 6.99534035e+00 7.49726057e+00 7.75610304e+00 8.03595924e+00 8.08189964e+00 8.56540871e+00 8.93415928e+00 9.03764915e+00 9.04151535e+00 9.18316555e+00 9.38799858e+00 9.33167839e+00 9.81177807e+00 1.00038347e+01 9.82417965e+00 1.01491423e+01 1.04690132e+01 1.07221928e+01 1.11109152e+01 1.06753454e+01 1.09797421e+01 1.11382513e+01 1.16665726e+01 1.17835665e+01 1.19099350e+01 1.21243372e+01 1.24047108e+01 1.21566458e+01 1.25580349e+01 1.31549826e+01 1.29074402e+01 1.29466648e+01 1.35695238e+01 1.40063562e+01 1.35610085e+01 1.39710093e+01 1.44816542e+01 1.44886618e+01 1.43679571e+01 1.45654507e+01 1.47391129e+01 1.53491430e+01 1.56005602e+01 1.55603819e+01 1.53557205e+01 1.55118732e+01 1.59207239e+01 1.62972813e+01 1.64400940e+01 1.67928181e+01 1.70346336e+01 1.69119854e+01 1.67646046e+01 1.70118351e+01 1.73759899e+01 1.74062920e+01 1.74789906e+01 1.77304115e+01 1.81208363e+01 1.79227295e+01 1.80009842e+01 1.86805763e+01 1.91405182e+01 1.91626282e+01 1.90247669e+01 1.93746967e+01 1.96967545e+01 1.93454094e+01 1.94852543e+01 1.97247486e+01 1.98146954e+01 2.06236210e+01 2.05947113e+01 2.04962578e+01 2.03961563e+01 2.06988335e+01 2.08439274e+01 2.09957008e+01 2.13856506e+01 2.13807716e+01 2.13475819e+01 2.18435802e+01 2.21846657e+01 2.23473206e+01 2.18483791e+01 2.23587532e+01 2.22353973e+01 2.21392288e+01 2.22923603e+01 2.22012882e+01 2.21603355e+01 2.12524757e+01 1.77100277e+01 1.41376371e+01 1.59434910e+01 1.91710396e+01 2.31338272e+02 3.86390656e+02 3.00783215e+01 8.46143913e+00 2.13992906e+00 -3.10778900e+02 -1.73871506e+02 3.99962616e+01 -3.13270691e+02 9.20403957e+00 6.69730835e+01 -1.01447235e+03 -6.55823250e+06 -16958520. 12791272. -6.79396250e+04 -3.28821043e+09 1286979328. 0. 0. 0. 0. 0. 0. 1.30834039e+05 -5.28457129e+03 -2.30604565e+03 1.70111875e+06 2.75257871e+04 1.04385625e+04 -2.47194531e+03 8725150. 3.56173219e+05 2.93528719e+05 7204792. 1.61686758e+04 5.88054736e+03 -1.28408289e+03 2.45184912e+03 -3.08579163e+02 -1.76908850e+03 2.16780566e+03 2.00047932e+01 -1.26806847e+02 8.36442627e+02 4.51114258e+02 3.71893387e+01 -2.45420776e+02 2.81399811e+02 8.17815857e+01 4.18280640e+02 3.75017548e+02 5.15382080e+01 2.22252182e+02 4.39072662e+02 3.61731567e+02 -9.86434265e+02 8.13414062e+02 -2.03623238e+01 -1.54215491e+03 -5.62981934e+03 1.83804043e+04 2.32922109e+05 3.01157925e+06 6.93725450e+06 5031631. -21863326. -75404464. -35423736. -21104908. -99831448. 16442697. 37194280. 19366362. -14024411. -13602573. -16643721. -41303472. -39452952. 29793738. 1.98684851e+03 8.31286621e+02 1.14808388e+02 3.45793579e+02 2.07207825e+02 3.48982887e+01 3.55619812e+01 3.51373177e+01 3.47464027e+01 3.46165466e+01 3.42367363e+01 3.38229294e+01 3.32017899e+01 3.27072601e+01 3.26108589e+01 3.26111031e+01 3.29245987e+01 3.30238342e+01 3.25265198e+01 3.23683586e+01 3.30111809e+01 3.30242653e+01 3.29601784e+01 3.30795364e+01 3.33145409e+01 3.31825409e+01 3.28482170e+01 3.29362411e+01 3.31134605e+01 3.32687302e+01 3.35253067e+01 3.32758064e+01 3.31582069e+01 3.30868340e+01 3.26925659e+01 3.26886635e+01 3.30056381e+01 3.33528061e+01 3.33067284e+01 3.31276779e+01 3.30323143e+01 3.30452156e+01 3.36477890e+01 3.38019333e+01 3.27546425e+01 3.22150345e+01 3.27735634e+01 3.37192650e+01 3.35469589e+01 3.28614426e+01 3.24954300e+01 3.24950066e+01 3.29202652e+01 3.27990837e+01 3.26379242e+01 3.29787865e+01 3.27772751e+01 3.27165489e+01 3.27434769e+01 3.27526550e+01 3.26599083e+01 3.26877975e+01 3.26883354e+01 3.24812851e+01 3.25901527e+01 3.23723755e+01 3.25926781e+01 3.28705444e+01 3.23829117e+01 3.25859756e+01 3.28222618e+01 3.21716309e+01 3.22516899e+01 3.21212997e+01 3.21586952e+01 3.20770760e+01 3.23789673e+01 3.24901199e+01 3.19303017e+01 3.18885021e+01 3.22885666e+01 3.21968193e+01 3.19608784e+01 3.19892368e+01 3.19012051e+01 3.17664948e+01 3.19437752e+01 3.18696594e+01 3.18317184e+01 3.18665390e+01 3.18299427e+01 3.17933750e+01 3.16901093e+01 3.14265099e+01 3.13468533e+01 3.13746719e+01 3.12826271e+01 3.11624660e+01 3.12337494e+01 3.08748360e+01 3.08091259e+01 3.09998512e+01 3.08935738e+01 3.08582821e+01 3.06552639e+01 3.04294434e+01 3.05807400e+01 3.05943642e+01 3.04657860e+01 3.03179169e+01 3.02031746e+01 2.98851776e+01 2.97572250e+01 2.98169670e+01 2.97592773e+01 2.96896305e+01 2.96006451e+01 2.95044575e+01 2.93983536e+01 2.93160076e+01 2.92052040e+01 2.91436157e+01 2.90313797e+01 2.89197617e+01 2.88168755e+01 2.87271862e+01 2.86430321e+01 2.85167961e+01 2.84506550e+01 2.83934059e+01 2.82680187e+01 2.81240044e+01 2.79951077e+01 2.78775673e+01 2.77616138e+01 2.76564445e+01 2.75616322e+01 2.74637260e+01 2.73615742e+01 2.72288208e+01 2.71083965e+01 2.69909611e+01 2.68775101e+01 2.67548695e+01 2.66479435e+01 2.65700474e+01 2.64946766e+01 2.63961868e+01 2.62321110e+01 2.60790787e+01 2.59561005e+01 2.58290710e+01 2.56961212e+01 2.55558567e+01 2.54478683e+01 2.52821255e+01 2.51264267e+01 2.49635029e+01 2.49380455e+01 2.47720203e+01 2.45453930e+01 2.44207649e+01 2.43536110e+01 2.42884178e+01 2.41699829e+01 2.39915695e+01 2.38745556e+01 2.36926556e+01 2.35970993e+01 2.35649300e+01 2.34134808e+01 2.31995792e+01 2.30688190e+01 2.30775700e+01 2.29678574e+01 2.27350864e+01 2.24970016e+01 2.23352871e+01 2.23366356e+01 2.21225281e+01 2.17850780e+01 2.16296177e+01 2.15334988e+01 2.14350033e+01 2.13086910e+01 2.10844994e+01 2.09422359e+01 2.06486530e+01 2.05200005e+01 2.03391056e+01 2.01309624e+01 1.99083633e+01 1.98296967e+01 1.97602158e+01 1.96160679e+01 1.94939613e+01 1.91630001e+01 1.90211201e+01 1.87034035e+01 1.87337017e+01 1.85660858e+01 1.87188740e+01 1.86114578e+01 1.83049049e+01 1.79858952e+01 1.77053070e+01 1.76441364e+01 1.73990593e+01 1.72920818e+01 1.71793423e+01 1.70749302e+01 1.66689358e+01 1.63163662e+01 1.64762592e+01 1.62965946e+01 1.60776463e+01 1.55472221e+01 1.55535727e+01 1.56341677e+01 1.54833050e+01 1.53636637e+01 1.51353579e+01 1.48018293e+01 1.46472759e+01 1.42925959e+01 1.41875629e+01 1.40059261e+01 1.43169947e+01 1.36946297e+01 1.32092447e+01 1.35877943e+01 1.31549778e+01 1.26390257e+01 1.28179665e+01 1.23142767e+01 1.18753052e+01 1.18664980e+01 1.25909433e+01 1.24766903e+01 1.22057457e+01 1.18744240e+01 1.12884235e+01 1.11844912e+01 1.12286949e+01 1.13397789e+01 1.10969992e+01 1.12072754e+01 1.06663275e+01 1.07328777e+01 1.06949358e+01 1.02414465e+01 9.75706577e+00 9.67500973e+00 9.33740902e+00 9.06136513e+00 9.26072311e+00 9.03904057e+00 9.23546791e+00 9.19223785e+00 9.82645512e+00 9.41252327e+00 8.72203064e+00 9.02194309e+00 9.01608467e+00 9.96049213e+00 1.03770304e+01 9.14159393e+00 1.70292465e+02 2.98781891e+02 5.13360748e+01 4.89606705e+01 4.92693138e+01 5.59909134e+01 4.62471619e+01 7.31869324e+02 1.83942908e+03 -1.59024780e+03 9.08367844e+01 1.89662231e+03 -23122738. 14405515. -19734686. -39558160. -4.42443262e+03 -2.07320166e+03 3.45190491e+02 2.83890894e+03 11987811. 4707957. 45217728. -5.32257031e+03 -2.98631250e+03 -1.14201562e+03 1.41625580e+02 1.92183105e+03 -4.95306104e+03 1.62798865e+03 9.62789648e+03 12315628. -14723673. -20675858. 38457684. -66907044. -22299516. -264832592. -43710028. -11902365. -71351032. -11939257. 11385853. 13902528. -9.31626404e+02 -2.30793953e+01 2.99069489e+02 1.85537071e+01 1.89177515e+03 8424259. 1.66917975e+06 2.01748162e+06 43006188. 4308214. -81371176. 21135692. -8.97173340e+02 -1.92294238e+03 -1.06283844e+05 0. 0. 0. 0. 0. 220810304. 220810304. 220810304. 317480928. -4638865. 3.20085875e+06 70386928. 17422840. 7.57477750e+06 -1.05256421e+03 -4.42664368e+02 -1.85820770e+01 -1.86734486e+01 5.12692566e+01 -2.18604126e+02 -4.49075043e+02 1.20383179e+00 3.47186340e+02 -1.19249516e+01 -3.63795776e+02 3.50250183e+02 1.91523865e+02 -1.67251377e+01 -1.24731684e+01 -1.27444906e+01 -1.29805803e+01 -1.23838844e+01 -1.21997814e+01 -1.22719202e+01 -1.16261444e+01 -1.22186699e+01 -1.26886349e+01 -1.21734867e+01 -1.20028715e+01 -1.23855038e+01 -1.34501762e+01 -1.38497610e+01 -1.32701044e+01 -1.37558680e+01 -1.37325096e+01 -1.36293850e+01 -1.40832376e+01 -1.45866108e+01 -1.46156082e+01 -1.45042181e+01 -1.48828993e+01 -1.52970047e+01 -1.56074953e+01 -1.55711880e+01 -1.53302364e+01 -1.56194801e+01 -1.61372414e+01 -1.65494862e+01 -1.68260517e+01 -1.64641304e+01 -1.57198610e+01 -1.59080000e+01 -1.68511906e+01 -1.70049305e+01 -1.70596142e+01 -1.75866261e+01 -1.77368183e+01 -1.74700642e+01 -1.78865871e+01 -1.82944145e+01 -1.85935898e+01 -1.87102737e+01 -1.85510960e+01 -1.87409000e+01 -1.91986332e+01 -1.93620358e+01 -1.92731800e+01 -1.94894104e+01 -1.95485592e+01 -1.93549576e+01 -1.95457916e+01 -2.00668201e+01 -2.03004990e+01 -2.04230213e+01 -2.12733135e+01 -2.25137787e+01 -2.10324306e+01 -2.22015324e+01 -2.31894073e+01 -2.17659149e+01 -2.15777359e+01 -2.18583927e+01 -2.22720203e+01 -2.24480152e+01 -2.22314224e+01 -2.23592339e+01 -2.22509136e+01 -2.25569973e+01 -2.30479527e+01 -2.30856380e+01 -2.35132103e+01 -2.35927238e+01 -2.32169094e+01 -2.31549244e+01 -2.32439423e+01 -2.37075539e+01 -2.39464664e+01 -2.27485123e+01 -2.31986160e+01 -2.54480419e+01 -2.50676918e+01 -2.41770897e+01 -2.40074139e+01 -2.49592190e+01 -2.47596722e+01 -2.46526814e+01 -2.53487415e+01 -2.55764160e+01 -2.56877956e+01 -2.59884033e+01 -2.55702209e+01 -2.60589619e+01 -2.64881210e+01 -2.55507469e+01 -2.56725368e+01 -2.70032578e+01 -2.75436134e+01 -2.65794563e+01 -2.71850929e+01 -2.61942692e+01 -2.63064156e+01 -2.64776115e+01 -2.49442806e+01 -2.53002758e+01 -2.95190086e+01 -3.04479904e+01 -2.83085918e+01 -2.77054405e+01 -2.74687176e+01 -2.77623177e+01 -2.78581448e+01 -2.85503712e+01 -2.84509983e+01 -2.82832375e+01 -2.82404881e+01 -2.80594063e+01 -2.84169788e+01 -2.87052536e+01 -2.91311226e+01 -2.91779060e+01 -2.92584629e+01 -2.90581093e+01 -2.90230064e+01 -2.81433220e+01 -2.85620842e+01 -2.94269257e+01 -2.93130341e+01 -2.81141624e+01 -2.71567497e+01 -2.68632412e+01 -2.23171782e+00 -2.04261475e+01 -6.30690308e+01 -4.42984238e+01 -3.09313469e+01 -2.97878494e+01 -2.69383450e+01 -2.88008881e+01 -3.47566757e+01 -9.21301651e+00 -1.93742256e+01 -5.63158379e+01 -4.21409111e+01 -3.23049889e+01 -3.08815727e+01 -3.04234657e+01 -3.01544838e+01 -3.01989059e+01 -3.02045135e+01 -2.90292511e+01 -1.41191015e+01 -1.47476130e+01 1.65665527e+02 3.30993835e+02 -3.64636688e+02 6.17842734e-01 6.44303833e+02 10024523. -2.44863016e+05 2.15142844e+05 2146934. -58086164. 39575756. 0. 0. -103955936. -222783152. 15557502. -21983256. 8456586. -34927728. 25890376. -26664872. -8.03527750e+06 -17299162. -7.59685974e+02 -7.00985947e+01 5.84635864e+02 13938259. 107401880. -33064630. -1.45431079e+03 -1.47726166e+02 1.05703467e+03 -9.65457812e+04 -44564748. -9351756. 289626656. -1.60200650e+06 -2.62890781e+05 -2.98479562e+05 -8.15493750e+06 -2.01004626e+03 -8.57117981e+02 -1.64862686e+02 -1.64160065e+02 3.78464447e+02 1.10174390e+03 81256752. 822987520. -5735278. 2.28421641e+04 1496791424. 11049033. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -115607928. -115607928. -115607928. 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. 0. 0. 0. 0. 0. 0. 0. 2.84576538e+09 2.84576538e+09 2.84576538e+09 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. -666764. -666764. 68852944. 90862584. 90862584. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 413505024. 413505024. 413505024. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2016075008. 2016075008. 2016075008. 170807072. -15098876. -15098876. -6.11592450e+06 -134476432. -134476432. -69234400. 0. 0. 0. 0. -83195784. -83195784. -83195784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.37004093e+10 1.37004093e+10 1.37004093e+10 0. 0. 0. 0. 0. 0. 0. -34077768. -34077768. -34077768. 0. 0. 0. 0. 0. 0. 25364174. 19846232. 5.33365150e+06 -5.25354150e+06 49221932. 7.20719050e+06 -4158076. 61596048. -29585664. 0. 0. 0. 62839560. 62839560. 62839560. 0. 0. 0. 87957592. 87957592. 87957592. -20787226. 20504132. -6147997. -9263180. 18891632. -24703874. -16713144. -84602568. 9.84972168e+03 -3.40544025e+06 227931424. -451043616. -451043616. -451043616. 0. 0. 181617968. 181617968. 181617968. 0. 0. 0. 0. 0. 0. -20934184. -7.73959450e+06 -25146050. 6.77502563e+02 2.98876160e+02 -4.52314301e+01 -4.47393951e+01 -4.38425713e+01 -4.34705353e+01 -4.47435722e+01 -4.46938095e+01 -4.52886925e+01 -4.51417389e+01 -4.40136185e+01 -4.32230759e+01 -4.24148788e+01 -4.14837379e+01 -3.86230431e+01 -3.94411964e+01 -3.95496597e+01 -3.83093987e+01 -3.71861725e+01 -3.78151474e+01 -3.93428917e+01 -3.81506195e+01 -3.60175781e+01 -4.50463562e+02 -9.96929810e+02 7.85921814e+02 3.45885590e+02 -3.52693596e+01 -3.42136421e+01 -3.33777046e+01 -3.17410545e+01 -4.56110565e+02 -1.00507825e+03 8.38606079e+02 3.71123810e+02 -3.51464615e+01 -3.34228439e+01 -2.82925644e+01 -2.90447769e+01 -2.90025101e+01 -2.84491177e+01 -2.74862328e+01 -2.67919292e+01 -2.67570820e+01 -2.63971138e+01 -2.70684147e+01 -2.83014240e+01 -2.84194508e+01 -2.52096977e+01 -2.32090492e+01 -2.27204533e+01 -2.44076786e+01 -2.53187675e+01 -2.33888283e+01 -2.24804058e+01 -3.66627731e+01 -3.57226562e+01 -5.40075684e+00 -5.26642704e+00 -2.07722111e+01 -1.88544159e+01 -1.87549515e+01 -1.94021969e+01 -1.90088711e+01 -1.74170208e+01 -1.57822256e+01 -1.48002720e+01 -1.53786783e+01 -1.50828762e+01 -1.46826277e+01 -1.40649605e+01 -1.34083233e+01 -1.45671663e+01 -1.26181383e+01 -1.23057108e+01 -1.23201313e+01 -1.02285995e+01 -1.06065807e+01 -9.24287128e+00 -7.70241499e+00 -8.17469120e+00 -7.09490490e+00 -6.98455381e+00 -6.56153202e+00 -6.80312204e+00 -5.70031977e+00 -4.84283972e+00 -4.98700762e+00 -6.44738865e+00 -4.36411572e+00 -2.70572019e+00 -4.47439241e+00 -3.31814933e+00 2.06632778e-01 2.33341619e-01 -2.68670535e+00 -1.64410377e+00 1.03245234e+00 1.20983315e+00 1.61623645e+00 1.96772385e+00 2.36492419e+00 3.71264076e+00 4.99072409e+00 4.77750778e+00 4.01442146e+00 4.33356476e+00 5.36795282e+00 6.60069466e+00 7.04765224e+00 8.28660774e+00 8.90895462e+00 8.51959038e+00 8.44585705e+00 7.52693892e+00 8.12261486e+00 1.05049343e+01 1.09341030e+01 1.16205215e+01 1.31068010e+01 1.13105946e+01 1.13206997e+01 1.36183519e+01 1.49838753e+01 1.53046923e+01 1.50323219e+01 1.66311893e+01 1.78699226e+01 1.59219904e+01 1.67331657e+01 1.71149940e+01 1.67769051e+01 2.01466923e+01 2.02207184e+01 1.93343983e+01 1.92185917e+01 2.02948093e+01 2.06347198e+01 2.09687538e+01 2.38217239e+01 2.31223068e+01 2.26186619e+01 2.45001411e+01 2.54548607e+01 2.57146950e+01 2.41831951e+01 2.69540863e+01 2.66850796e+01 2.59486809e+01 2.75990391e+01 2.72566586e+01 2.74948235e+01 2.83387833e+01 2.88120918e+01 2.91547565e+01 2.96433964e+01 2.93565941e+01 2.85721607e+01 2.62264481e+01 1.72838593e+01 -3.91573381e+00 -9.69700432e+00 -3.42059231e+00 5.32974052e+00 6.43768127e+02 3.83839453e+03 -22825018. 365558432. 365558432. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.24441250e+05 -1.24441250e+05 -1.24441250e+05 0. -20913630. -20913630. -20913630. 0. 0. 0. 0. 3.38632575e+06 35442572. 35442572. 81324912. -49938220. -33809280. -7.36222950e+06 7.96469531e+03 -8.58625234e+04 1.38130078e+04 9.01472107e+02 -7.59350357e+01 -3.82745056e+02 2.58013696e+03 -2.68209629e+04 2.03430438e+05 8.81154141e+04 -1.61054922e+05 3.44566602e+04 6.76877250e+05 2.40620750e+05 23148164. -7.99474250e+06 1.12205662e+06 1.12205662e+06 82945920. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 305395488. 20144728. -91475640. 9.84107788e+02 4.51022339e+02 7.72898331e+01 8.06920700e+01 7.94553452e+01 7.81508713e+01 7.71956863e+01 7.57801819e+01 7.44654922e+01 7.33560791e+01 7.24279556e+01 7.16682968e+01 7.12190628e+01 7.18756714e+01 7.24676819e+01 7.26264954e+01 7.26175308e+01 7.35821762e+01 7.37376404e+01 7.38003006e+01 7.40004578e+01 7.50841675e+01 7.61217957e+01 7.52997055e+01 7.53873825e+01 7.57383194e+01 7.60130768e+01 7.64498138e+01 7.61767502e+01 7.64353638e+01 7.69443130e+01 7.59084778e+01 7.62171936e+01 7.66135406e+01 7.75957336e+01 7.76383972e+01 7.73964157e+01 7.76068115e+01 7.83955536e+01 8.00693359e+01 8.09790878e+01 7.86152878e+01 7.70618744e+01 7.88839111e+01 8.16287003e+01 8.22374649e+01 8.01428757e+01 7.85088120e+01 7.85146408e+01 7.98857880e+01 7.90286636e+01 7.87256699e+01 7.99991837e+01 8.00378876e+01 8.07058716e+01 8.12075958e+01 8.12590561e+01 8.10977631e+01 8.13370667e+01 8.15273819e+01 8.13650589e+01 8.11377487e+01 8.06883316e+01 8.15868454e+01 8.31434250e+01 8.14298401e+01 8.29954758e+01 8.43577347e+01 8.20701065e+01 8.27095108e+01 8.32751465e+01 8.35849533e+01 8.19510345e+01 8.30778275e+01 8.42725525e+01 8.33020630e+01 8.30167160e+01 8.42553024e+01 8.40176392e+01 8.35663071e+01 8.44506378e+01 8.42630692e+01 8.43547211e+01 8.48962402e+01 8.51841507e+01 8.53154984e+01 8.57509232e+01 8.61948090e+01 8.61097488e+01 8.63318710e+01 8.54545288e+01 8.54873276e+01 8.57532578e+01 8.53250275e+01 8.53300095e+01 8.55722275e+01 8.52559738e+01 8.51768951e+01 8.58047714e+01 8.56512680e+01 8.60863800e+01 8.54930878e+01 8.51176758e+01 8.61318130e+01 8.63916016e+01 8.61710358e+01 8.60830917e+01 8.61442261e+01 8.57495880e+01 8.55466232e+01 8.56373749e+01 8.56665649e+01 8.56968994e+01 8.57154007e+01 8.57439346e+01 8.57017136e+01 8.56176987e+01 8.55769196e+01 8.58829269e+01 8.59394226e+01 8.59062576e+01 8.58518906e+01 8.58194885e+01 8.59089050e+01 8.58293610e+01 8.59440002e+01 8.59451370e+01 8.57865601e+01 8.55528336e+01 8.54348907e+01 8.53582687e+01 8.53105240e+01 8.52571487e+01 8.51891403e+01 8.48800583e+01 8.45388412e+01 8.41089630e+01 8.39751205e+01 8.38557510e+01 8.37651062e+01 8.36466675e+01 8.35634918e+01 8.35275497e+01 8.33777542e+01 8.33050385e+01 8.32215729e+01 8.31292038e+01 8.29869232e+01 8.27869263e+01 8.26921844e+01 8.25166931e+01 8.24109497e+01 8.21921310e+01 8.20368042e+01 8.17742615e+01 8.20908051e+01 8.21397552e+01 8.15881348e+01 8.21018524e+01 8.22426605e+01 8.20839081e+01 8.19314957e+01 8.16399612e+01 8.14393082e+01 8.12318420e+01 8.11287231e+01 8.10768509e+01 8.08767776e+01 8.05547638e+01 8.03474808e+01 8.02820892e+01 8.00149307e+01 7.97586060e+01 7.93434601e+01 7.92020950e+01 7.90250320e+01 7.89685898e+01 7.86977921e+01 7.86674500e+01 7.83977966e+01 7.82298965e+01 7.77975540e+01 7.78469772e+01 7.74889526e+01 7.72266998e+01 7.69732056e+01 7.63848038e+01 7.61863708e+01 7.57623138e+01 7.61514359e+01 7.60636215e+01 7.59990692e+01 7.54576950e+01 7.48426437e+01 7.45857925e+01 7.48805695e+01 7.46450043e+01 7.41085205e+01 7.35468063e+01 7.35945740e+01 7.32259293e+01 7.30604630e+01 7.28874283e+01 7.29093094e+01 7.22166367e+01 7.16779251e+01 7.15564117e+01 7.13194122e+01 7.05304947e+01 7.00624390e+01 7.04274139e+01 7.04053802e+01 6.92906418e+01 6.91717987e+01 6.98862610e+01 7.07221909e+01 7.00235367e+01 6.87884369e+01 6.82781830e+01 6.78986359e+01 6.74067001e+01 6.71651535e+01 6.74338760e+01 6.68032455e+01 6.71272736e+01 6.57977371e+01 6.35738716e+01 6.71701965e+01 6.56379166e+01 6.38104439e+01 6.46774216e+01 6.42119980e+01 6.21470184e+01 6.22956009e+01 6.46545410e+01 6.42887955e+01 6.50009308e+01 6.48949280e+01 6.34769859e+01 6.18347855e+01 6.27407150e+01 6.24565964e+01 6.20823402e+01 6.22563095e+01 6.17635002e+01 6.14423599e+01 6.22807045e+01 6.11125031e+01 5.96816559e+01 6.01696777e+01 5.92711258e+01 5.86834602e+01 5.89850998e+01 5.83850517e+01 6.04896660e+01 6.19734764e+01 6.32134972e+01 6.14180183e+01 5.79571953e+01 5.93673058e+01 5.95784302e+01 6.07528915e+01 6.20643578e+01 6.01444359e+01 4.33482300e+02 9.58003296e+02 -200468768. -14770068. 20946910. 1.88610912e+06 6.42720312e+05 21349338. -186212848. 34441660. 34441660. 34441660. 0. 0. 0. 0. -88268144. 3.82991575e+06 3.82991575e+06 -34977040. 0. 0. 0. -81082712. 57678516. -1.21039131e+04 6.99405650e+06 -61604996. -185440256. -185440256. -185440256. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -189898464. -189898464. 177319392. -27032950. -27032950. 0. 0. 0. 0. 0. 0. 0. 41697316. 41697316. 41697316. 0. 0. 0. 0. 0. 110405152. 110405152. 110405152. 0. 0. 0. 0. 0. 0. 12185555. 2.67072650e+06 -12652946. -4.81303950e+06 1.33047485e+03 2.17989853e+02 -2.44896881e+02 -3.83721054e-01 6.99219322e+00 6.58529472e+00 7.16097498e+00 7.30943203e+00 6.77343893e+00 6.27141380e+00 5.74603701e+00 6.09814310e+00 6.23046684e+00 6.87922525e+00 6.60079241e+00 6.23929739e+00 7.44093418e+00 6.11193371e+00 5.51808119e+00 6.03341818e+00 5.34315777e+00 4.30431175e+00 1.69251800e+00 5.11000276e-01 2.16956067e+00 1.83383191e+00 7.21837521e-01 1.10598385e+00 4.84383106e-03 -1.59623194e+00 -1.76913595e+00 -1.75239694e+00 -2.65884423e+00 -3.47415709e+00 -4.70372200e+00 -4.49912119e+00 -3.71224523e+00 -4.19740391e+00 -5.59871674e+00 -7.52818918e+00 -8.73953056e+00 -7.15947866e+00 -2.96544552e+00 -3.22263169e+00 -7.67686319e+00 -8.66341877e+00 -9.10407639e+00 -1.10147114e+01 -1.10167656e+01 -9.37466812e+00 -1.09523287e+01 -1.34833469e+01 -1.47862740e+01 -1.42053509e+01 -1.27156210e+01 -1.26452007e+01 -1.55320883e+01 -1.75401745e+01 -1.60699482e+01 -1.64059601e+01 -1.64761047e+01 -1.56943598e+01 -1.67014046e+01 -1.78624363e+01 -1.87071648e+01 -1.99019623e+01 -2.05356903e+01 -2.39354630e+01 -2.34217911e+01 -2.73443165e+01 -2.91316948e+01 -2.43154984e+01 -2.31403122e+01 -2.42290134e+01 -2.54112568e+01 -2.54620361e+01 -2.51450939e+01 -2.53969059e+01 -2.64925594e+01 -2.78490067e+01 -2.88163815e+01 -2.86045990e+01 -3.02406330e+01 -2.97584324e+01 -2.87551441e+01 -2.93533287e+01 -3.01636028e+01 -3.05525036e+01 -3.14414196e+01 -2.80482655e+01 -3.04969025e+01 -3.54109116e+01 -3.40967484e+01 -3.13110428e+01 -3.10453815e+01 -3.68313522e+01 -3.65307121e+01 -3.42029572e+01 -3.70260963e+01 -3.72093048e+01 -3.80129929e+01 -3.83047447e+01 -3.80912209e+01 -3.98549843e+01 -4.01075287e+01 -3.85297241e+01 -3.84420013e+01 -3.99120255e+01 -4.11471977e+01 -4.08365326e+01 -3.97048683e+01 -3.87798386e+01 -4.11366844e+01 -4.32725372e+01 -3.86485481e+01 -3.93601418e+01 -5.23103523e+01 -5.41715546e+01 -4.66754723e+01 -4.61442947e+01 -4.47100449e+01 -4.59765701e+01 -4.71205711e+01 -4.86674423e+01 -4.97480774e+01 -4.87918129e+01 -4.94769821e+01 -4.94895210e+01 -5.04269485e+01 -4.99985542e+01 -5.05427170e+01 -5.10409164e+01 -5.08925705e+01 -5.11639214e+01 -5.22233467e+01 -5.10786285e+01 -5.22150993e+01 -5.32823219e+01 -5.31657219e+01 -4.87687988e+01 -4.32525139e+01 -4.27976990e+01 4.25811920e+01 -3.41036224e+01 -1.82972137e+02 -1.05833824e+02 -6.26632423e+01 -5.49444618e+01 -4.19562302e+01 -5.34904175e+01 -7.03846970e+01 1.31728153e+01 -2.51165924e+01 -1.55712357e+02 -1.02492195e+02 -6.79526901e+01 -6.06757622e+01 -5.90889282e+01 -5.83275490e+01 -5.95711746e+01 -5.90476189e+01 -5.66241913e+01 -1.22815695e+01 -1.28688707e+01 5.70885620e+02 1.45224109e+03 -6.45025635e+02 -1.38390137e+03 -3.27780898e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -84203840. -84203840. -84203840. 0. 0. 0. 60923704. 60923704. 60923704. 0. 0. 0. 0. 0. 0. 0. 0. -11231910. -26436280. -14682468. -2.62304425e+06 -6.18916750e+06 12952885. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -57803964. -57803964. -57803964. 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. 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. 0. 0. 0. 0. 0. 0. 0. -333382. -333382. -35197244. 90862584. 90862584. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_3.xml ================================================ 16 1024
f
284785024. 1.95432861e+02 6.29854889e+01 9.18014603e+01 1.20709114e+02 1.49189713e+02 1.77700348e+02 2.06200241e+02 2.35170425e+02 2.64392029e+02 2.92628510e+02 3.21212769e+02 3.50008667e+02 3.78228546e+02 4.06057831e+02 4.33839264e+02 4.62713562e+02 4.90480927e+02 5.17944397e+02 5.46215759e+02 5.74618835e+02 6.02697144e+02 6.30011597e+02 6.57736755e+02 6.84587036e+02 7.11476318e+02 7.39668335e+02 7.67654724e+02 7.95045959e+02 8.20750000e+02 8.47892883e+02 8.74420593e+02 8.99625427e+02 9.27485352e+02 9.53609314e+02 9.79599426e+02 1.00652313e+03 1.03250061e+03 1.05838245e+03 1.08388293e+03 1.10753735e+03 1.13309058e+03 1.15849036e+03 1.18439209e+03 1.20842822e+03 1.23200146e+03 1.25906873e+03 1.28247485e+03 1.30199231e+03 1.32777380e+03 1.35549719e+03 1.37676221e+03 1.39910596e+03 1.42089294e+03 1.44230798e+03 1.46611731e+03 1.49487952e+03 1.51389429e+03 1.53008777e+03 1.55342163e+03 1.57869568e+03 1.60079407e+03 1.61882336e+03 1.63977563e+03 1.65639014e+03 1.67763391e+03 1.70408130e+03 1.72056323e+03 1.73530701e+03 1.75289612e+03 1.77657935e+03 1.80139539e+03 1.81166895e+03 1.82212866e+03 1.84460876e+03 1.87255396e+03 1.88835852e+03 1.89816284e+03 1.92299353e+03 1.93829724e+03 1.94423987e+03 1.96705029e+03 1.98733801e+03 1.99804797e+03 2.00451392e+03 2.02736768e+03 2.04166467e+03 2.05637915e+03 4.20299121e+03 6.71109131e+03 3.07650723e+04 -5031298. 87245592. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9525159. -4.84672219e+05 -1.49197031e+04 3.19313135e+03 2.96795679e+03 2.28987744e+03 2.29303223e+03 2.29016235e+03 2.29580518e+03 2.29797070e+03 2.31151270e+03 2.32068018e+03 2.32901904e+03 2.32306396e+03 2.32733276e+03 2.32942554e+03 2.32356445e+03 2.34633081e+03 2.34131201e+03 2.33791577e+03 2.35293188e+03 2.34068555e+03 2.33296851e+03 2.33583008e+03 2.34293481e+03 2.34064868e+03 2.33901733e+03 2.34291577e+03 2.32840137e+03 2.33187964e+03 2.33635132e+03 2.31570752e+03 2.32884351e+03 2.33214819e+03 2.31693506e+03 2.31949365e+03 2.31860107e+03 2.31113330e+03 2.29891406e+03 2.29894922e+03 2.29229126e+03 2.27208472e+03 2.27838232e+03 2.26720215e+03 2.25971045e+03 2.26024316e+03 2.24309229e+03 2.24285083e+03 2.22927808e+03 2.21128418e+03 2.20495068e+03 2.19876978e+03 2.19455811e+03 2.19080664e+03 2.16996948e+03 2.16431055e+03 2.15038940e+03 2.13010669e+03 2.12410425e+03 2.11790063e+03 2.10503979e+03 2.08931128e+03 2.07605493e+03 2.06621240e+03 2.05215308e+03 2.03159424e+03 2.02199829e+03 2.00547888e+03 1.97579907e+03 1.97069434e+03 1.96326257e+03 1.94370618e+03 1.93188464e+03 1.90820435e+03 1.89320605e+03 1.88181653e+03 1.85726721e+03 1.83783179e+03 1.82207800e+03 1.81318494e+03 1.78832861e+03 1.76446948e+03 1.74860681e+03 1.72860449e+03 1.70743872e+03 1.69286804e+03 1.67919421e+03 1.65054089e+03 1.63142969e+03 1.61258948e+03 1.58393701e+03 1.56456702e+03 1.54717517e+03 1.52728906e+03 1.50798608e+03 1.48404553e+03 1.45434167e+03 1.43452686e+03 1.41592554e+03 1.38620874e+03 1.36721411e+03 1.34842114e+03 1.31974707e+03 1.29227441e+03 1.27116711e+03 1.24728137e+03 1.22272827e+03 1.20070056e+03 1.17363025e+03 1.14864722e+03 1.12526245e+03 1.09873413e+03 1.07339282e+03 1.04913013e+03 1.02079004e+03 9.95536194e+02 9.69676941e+02 9.41820496e+02 9.16836182e+02 8.91439392e+02 8.64598938e+02 8.37361023e+02 8.10737793e+02 7.83542603e+02 7.54927795e+02 7.28622864e+02 7.01655518e+02 6.74596924e+02 6.47079468e+02 6.18959290e+02 5.91170227e+02 5.63690735e+02 5.36034790e+02 5.07319397e+02 4.78913116e+02 4.51323883e+02 4.23177032e+02 3.95084747e+02 3.66510986e+02 3.37955902e+02 3.09499969e+02 2.81270660e+02 2.52576843e+02 2.23730637e+02 1.95376892e+02 1.66797195e+02 1.38019241e+02 1.09511101e+02 8.07657776e+01 5.18959846e+01 2.32885551e+01 -5.44077063e+00 -3.42425194e+01 -6.27470398e+01 -9.15402298e+01 -1.20374550e+02 -1.48999893e+02 -1.77895905e+02 -2.06331253e+02 -2.34654297e+02 -2.63577789e+02 -2.91999237e+02 -3.20405396e+02 -3.49283081e+02 -3.77644623e+02 -4.05312958e+02 -4.33395813e+02 -4.62441132e+02 -4.90291809e+02 -5.17451172e+02 -5.45800659e+02 -5.74446228e+02 -6.02041138e+02 -6.29474121e+02 -6.57438110e+02 -6.84389771e+02 -7.11156799e+02 -7.39224243e+02 -7.67498413e+02 -7.94568481e+02 -8.20807190e+02 -8.47949097e+02 -8.74220764e+02 -8.99330872e+02 -9.27104980e+02 -9.53669617e+02 -9.79382141e+02 -1.00577191e+03 -1.03209229e+03 -1.05835461e+03 -1.08317700e+03 -1.10795251e+03 -1.13249255e+03 -1.15811243e+03 -1.18466248e+03 -1.20821570e+03 -1.23153455e+03 -1.25961780e+03 -1.28200635e+03 -1.29931458e+03 -1.32662097e+03 -1.35378955e+03 -1.37812573e+03 -1.40000757e+03 -1.41913379e+03 -1.44221692e+03 -1.46611145e+03 -1.49521692e+03 -1.51412390e+03 -1.52946057e+03 -1.55193555e+03 -1.57633667e+03 -1.60013538e+03 -1.61883594e+03 -1.63948560e+03 -1.65547778e+03 -1.67675806e+03 -1.70700989e+03 -1.72188135e+03 -1.73279700e+03 -1.75237170e+03 -1.77720447e+03 -1.79956128e+03 -1.81180530e+03 -1.81976721e+03 -1.84477661e+03 -1.87441101e+03 -1.88764331e+03 -1.89581506e+03 -1.92289001e+03 -1.93748157e+03 -1.94313538e+03 -1.96483691e+03 -1.98506653e+03 -1.99469958e+03 -1.99967725e+03 -2.02927441e+03 -2.04628589e+03 -2.04258398e+03 -2.06076538e+03 -2.08114160e+03 -2.10010938e+03 -2.11174561e+03 -2.11129419e+03 -2.12592578e+03 -2.14889453e+03 -2.15633179e+03 -2.16379004e+03 -2.17496582e+03 -2.18207739e+03 -2.18874194e+03 -2.21010132e+03 -2.21699146e+03 -2.22191577e+03 -2.23236426e+03 -2.24553735e+03 -2.25308716e+03 -2.25857471e+03 -2.26957300e+03 -2.26166968e+03 -2.28269897e+03 -2.29836890e+03 -2.29069067e+03 -2.28975342e+03 -2.29130103e+03 -2.30443750e+03 -2.31425366e+03 -2.31711792e+03 -2.32840552e+03 -2.32173389e+03 -2.32754980e+03 -2.32433057e+03 -2.32105396e+03 -2.34436255e+03 -2.33967017e+03 -2.33210449e+03 -2.35282495e+03 -2.33702612e+03 -2.33163940e+03 -2.34102368e+03 -2.33828247e+03 -2.33863354e+03 -2.33381641e+03 -2.33903003e+03 -2.33171899e+03 -2.33009009e+03 -2.33195728e+03 -2.32413208e+03 -2.33161597e+03 -2.33008154e+03 -2.31403687e+03 -2.31286865e+03 -2.31300195e+03 -2.30204150e+03 -2.29296411e+03 -2.29946411e+03 -2.28780347e+03 -2.26808154e+03 -2.28458398e+03 -2.27179932e+03 -2.25651050e+03 -2.25920312e+03 -2.24972168e+03 -2.24320728e+03 -2.22633496e+03 -2.21001367e+03 -2.21025049e+03 -2.20366113e+03 -2.19584521e+03 -2.18785376e+03 -2.16725586e+03 -2.16261475e+03 -2.15283472e+03 -2.13018701e+03 -2.12155127e+03 -2.11488013e+03 -2.10456836e+03 -2.09243848e+03 -2.07615576e+03 -2.06044604e+03 -2.04623938e+03 -2.03369788e+03 -2.02050464e+03 -2.00546497e+03 -1.97811890e+03 -1.97138428e+03 -1.96324792e+03 -1.94240686e+03 -1.93282202e+03 -1.91016919e+03 -1.89000378e+03 -1.88047778e+03 -1.85828137e+03 -1.83977942e+03 -1.82485779e+03 -1.80987756e+03 -1.78746313e+03 -1.76697241e+03 -1.74759277e+03 -1.72758350e+03 -1.70705322e+03 -1.69184521e+03 -1.67771045e+03 -1.64867847e+03 -1.63154041e+03 -1.61323425e+03 -1.58421484e+03 -1.56342407e+03 -1.54543835e+03 -1.52798535e+03 -1.50781274e+03 -1.48237598e+03 -1.45464221e+03 -1.43391370e+03 -1.41489758e+03 -1.38685022e+03 -1.36487097e+03 -1.34736963e+03 -1.32136377e+03 -1.29257141e+03 -1.27215466e+03 -1.24664929e+03 -1.22171960e+03 -1.20110779e+03 -1.17375354e+03 -1.14850513e+03 -1.12600024e+03 -1.09721228e+03 -1.07324451e+03 -1.05008386e+03 -1.02069275e+03 -9.95302856e+02 -9.69212708e+02 -9.42047119e+02 -9.17456970e+02 -8.91481323e+02 -8.64505737e+02 -8.37192505e+02 -8.10889343e+02 -7.83603516e+02 -7.55657043e+02 -7.29004333e+02 -7.01407715e+02 -6.74583374e+02 -6.47019653e+02 -6.19242432e+02 -5.91405334e+02 -5.63755493e+02 -5.36006714e+02 -5.07339691e+02 -4.79145538e+02 -4.51351959e+02 -4.23304840e+02 -3.95310242e+02 -3.66807678e+02 -3.38134827e+02 -3.09275970e+02 -2.81038422e+02 -2.52758453e+02 -2.23996002e+02 -1.95432037e+02 -1.66790833e+02 -1.38051666e+02 -1.09411659e+02 -8.06931000e+01 -5.18052025e+01 -2.30837517e+01 5.51049280e+00 3.42149391e+01 6.28963814e+01 9.16426010e+01 1.20069847e+02 1.48705826e+02 1.77687775e+02 2.06199142e+02 2.34830154e+02 2.63494446e+02 2.91739471e+02 3.20311737e+02 3.48924042e+02 3.77270294e+02 4.05244141e+02 4.33509064e+02 4.62519287e+02 4.90270599e+02 5.17623474e+02 5.45730225e+02 5.73895203e+02 6.02051331e+02 6.29666565e+02 6.57642883e+02 6.84296936e+02 7.10777161e+02 7.39152283e+02 7.67171875e+02 7.94185425e+02 8.20566223e+02 8.47949829e+02 8.74243347e+02 8.99596252e+02 9.26768921e+02 9.52608398e+02 9.78622681e+02 1.00624097e+03 1.03248914e+03 1.05791528e+03 1.08293860e+03 1.10762341e+03 1.13269824e+03 1.15817224e+03 1.18468005e+03 1.20839795e+03 1.23222803e+03 1.25907056e+03 1.28108020e+03 1.30134338e+03 1.32867371e+03 1.35344568e+03 1.37616675e+03 1.39867224e+03 1.42122693e+03 1.44359827e+03 1.46613416e+03 1.49423767e+03 1.51298376e+03 1.52965759e+03 1.55376318e+03 1.57614893e+03 1.60074878e+03 1.62001245e+03 1.63821960e+03 1.65543188e+03 1.67766809e+03 1.70306836e+03 1.72072595e+03 1.73535181e+03 1.75372131e+03 1.77466187e+03 1.79933398e+03 1.80979114e+03 1.82104968e+03 1.84728296e+03 1.87303101e+03 1.88583997e+03 1.89484717e+03 1.92181274e+03 1.93966870e+03 1.94653442e+03 1.96542261e+03 1.98631824e+03 1.99404297e+03 2.00239954e+03 2.02873364e+03 2.04520020e+03 2.04845776e+03 2.06366284e+03 2.08205884e+03 2.09816870e+03 2.11187476e+03 2.11348242e+03 2.12708984e+03 2.14649316e+03 2.15419531e+03 2.16559229e+03 2.17513574e+03 2.18604053e+03 2.19179004e+03 2.20146216e+03 2.21737402e+03 2.22694775e+03 2.23518506e+03 2.24234790e+03 2.24902661e+03 2.25955908e+03 2.26950708e+03 2.26099194e+03 2.27882397e+03 2.29923169e+03 2.29087573e+03 2.29295825e+03 2.29264746e+03 2.30426147e+03 2.31067041e+03 2.32084985e+03 2.33166992e+03 2.31736353e+03 2.32578467e+03 2.33155151e+03 2.32302710e+03 2.34931372e+03 2.33773633e+03 2.33583789e+03 2.34971875e+03 2.34157129e+03 2.33509204e+03 2.33971411e+03 2.33694751e+03 2.34437598e+03 2.33018042e+03 2.34062842e+03 2.33429028e+03 2.33278101e+03 2.33252783e+03 2.31821729e+03 2.33743799e+03 2.32993213e+03 2.31482690e+03 2.31862939e+03 2.31131274e+03 2.29901001e+03 2.29890479e+03 2.30120752e+03 2.28829419e+03 2.26687183e+03 2.28105835e+03 2.27047900e+03 2.25592700e+03 2.25950000e+03 2.24650977e+03 2.24415845e+03 2.22833228e+03 2.21370117e+03 2.21296606e+03 2.20135547e+03 2.19323022e+03 2.18682544e+03 2.17023071e+03 2.16083374e+03 2.14780127e+03 2.13500757e+03 2.12423535e+03 2.11340503e+03 2.10359595e+03 2.09083618e+03 2.07620215e+03 2.06159277e+03 2.04808472e+03 2.03275952e+03 2.02069250e+03 2.00593896e+03 1.98043958e+03 1.97115015e+03 1.96291553e+03 1.94264233e+03 1.93176990e+03 1.90863428e+03 1.89056506e+03 1.87992590e+03 1.85893115e+03 1.83979443e+03 1.82484644e+03 1.80877881e+03 1.78932532e+03 1.76616064e+03 1.74861975e+03 1.72907031e+03 1.70646729e+03 1.69257825e+03 1.67938635e+03 1.64889734e+03 1.63074878e+03 1.61382202e+03 1.58495886e+03 1.56255444e+03 1.54575598e+03 1.52770667e+03 1.50804578e+03 1.48346423e+03 1.45473547e+03 1.43434448e+03 1.41548474e+03 1.38678430e+03 1.36593848e+03 1.34754260e+03 1.32073108e+03 1.29225867e+03 1.27169568e+03 1.24689941e+03 1.22265894e+03 1.20163599e+03 1.17332019e+03 1.14723718e+03 1.12599036e+03 1.09780859e+03 1.07301611e+03 1.05036926e+03 1.02065027e+03 9.95178833e+02 9.69671204e+02 9.42557129e+02 9.16921936e+02 8.91635559e+02 8.64299316e+02 8.37712341e+02 8.11420959e+02 7.83408936e+02 7.55233582e+02 7.28775513e+02 7.01476257e+02 6.74684326e+02 6.47007263e+02 6.19120361e+02 5.91200623e+02 5.63527893e+02 5.36022644e+02 5.07439209e+02 4.79190735e+02 4.51267120e+02 4.23050629e+02 3.95235046e+02 3.66644867e+02 3.38082245e+02 3.09568481e+02 2.81186981e+02 2.52601883e+02 2.23854523e+02 1.95479874e+02 1.66884537e+02 1.38088959e+02 1.09460800e+02 8.07380142e+01 5.20404816e+01 2.34678345e+01 -5.41654778e+00 -3.41813240e+01 -6.27225990e+01 -9.15807114e+01 -1.20339981e+02 -1.48931931e+02 -1.77833847e+02 -2.06351669e+02 -2.34733917e+02 -2.63423035e+02 -2.91946686e+02 -3.20360260e+02 -3.49056488e+02 -3.77426147e+02 -4.05124268e+02 -4.33470551e+02 -4.62324768e+02 -4.90166840e+02 -5.17818359e+02 -5.45955933e+02 -5.74239502e+02 -6.02381165e+02 -6.29472107e+02 -6.57079407e+02 -6.84682373e+02 -7.11456909e+02 -7.39110962e+02 -7.67436768e+02 -7.94722351e+02 -8.20776855e+02 -8.47754211e+02 -8.74116943e+02 -8.99402405e+02 -9.27106873e+02 -9.53837646e+02 -9.78836670e+02 -1.00548755e+03 -1.03207776e+03 -1.05876331e+03 -1.08391418e+03 -1.10688403e+03 -1.13179126e+03 -1.15854260e+03 -1.18515137e+03 -1.20800134e+03 -1.23071082e+03 -1.25814844e+03 -1.28118799e+03 -1.30061609e+03 -1.32746545e+03 -1.35406042e+03 -1.37766614e+03 -1.39907874e+03 -1.42006824e+03 -1.44274243e+03 -1.46594177e+03 -1.49453381e+03 -1.51375696e+03 -1.52917273e+03 -1.55336206e+03 -1.57588416e+03 -1.60050964e+03 -1.61990381e+03 -1.63839270e+03 -1.65549255e+03 -1.67657288e+03 -1.70340051e+03 -1.72137109e+03 -1.73443408e+03 -1.75386023e+03 -1.77696582e+03 -1.79951929e+03 -1.81193835e+03 -1.82083398e+03 -1.84629773e+03 -1.87403650e+03 -1.88722583e+03 -1.89457629e+03 -1.92185095e+03 -1.93900549e+03 -1.94245837e+03 -1.96883203e+03 -1.98607336e+03 -1.99553687e+03 -1.99969641e+03 -2.02794678e+03 -2.04546021e+03 -2.04430029e+03 -2.06361230e+03 -2.08270410e+03 -2.09739502e+03 -2.11045703e+03 -2.11691333e+03 -2.12960083e+03 -2.14666724e+03 -2.15602490e+03 -2.16411743e+03 -2.17256763e+03 -2.18229932e+03 -2.19373730e+03 -2.20785522e+03 -2.21529517e+03 -2.22137378e+03 -2.23613281e+03 -2.24993237e+03 -2.24911841e+03 -2.25853394e+03 -2.26775781e+03 -2.26103833e+03 -2.28516309e+03 -2.29407837e+03 -2.29165405e+03 -2.29216504e+03 -2.29431177e+03 -2.30691431e+03 -2.31362817e+03 -2.31425684e+03 -2.32960693e+03 -2.32042505e+03 -2.32478125e+03 -2.32962598e+03 -2.32161108e+03 -2.34805054e+03 -2.33769019e+03 -2.33310083e+03 -2.35062427e+03 -2.34110913e+03 -2.33527563e+03 -2.33767554e+03 -2.33921436e+03 -2.34179785e+03 -2.33239136e+03 -2.33951660e+03 -2.33391040e+03 -2.33388940e+03 -2.33554248e+03 -2.33768726e+03 -2.34869141e+03 -2.33062817e+03 -2.31054468e+03 -2.31285498e+03 -2.30659180e+03 -2.29487036e+03 -2.29691357e+03 -2.29371118e+03 -2.28905322e+03 -2.27989136e+03 -2.94027588e+03 -3.15777271e+03 -1.09785262e+06 -13551030. 0. 0. 0. 0. -109199712. -109199712. -109199712. 0. 0. 0. -162924736. -1.08207662e+06 2.32011680e+04 -6.38318359e+03 -4.70059033e+03 -2.20315479e+03 -2.15126611e+03 -2.17555322e+03 -2.16357275e+03 -2.06469385e+03 -2.02372412e+03 -2.00353992e+03 -1.97955933e+03 -1.97325378e+03 -1.96287488e+03 -1.94580383e+03 -1.93365918e+03 -1.90962866e+03 -1.89267212e+03 -1.87959143e+03 -1.85558008e+03 -1.84023157e+03 -1.81968799e+03 -1.80044580e+03 -1.78306543e+03 -1.76503442e+03 -1.74912708e+03 -1.73719531e+03 -1.72738855e+03 -1.70568408e+03 -1.67733374e+03 -1.64743872e+03 -1.62939734e+03 -1.61905676e+03 -1.58931787e+03 -1.56455127e+03 -1.54646082e+03 -1.52834583e+03 -1.50738293e+03 -1.48359778e+03 -1.45501074e+03 -1.43363733e+03 -1.41603992e+03 -1.38731433e+03 -1.36702917e+03 -1.34760547e+03 -1.32058081e+03 -1.29358594e+03 -1.27168237e+03 -1.24736841e+03 -1.22293164e+03 -1.20128979e+03 -1.17388892e+03 -1.14910071e+03 -1.12626306e+03 -1.09717590e+03 -1.07397961e+03 -1.05067505e+03 -1.02050806e+03 -9.95630737e+02 -9.69472412e+02 -9.42035278e+02 -9.17673767e+02 -8.91476624e+02 -8.64560791e+02 -8.37910217e+02 -8.11374512e+02 -7.84022339e+02 -7.55475281e+02 -7.28809570e+02 -7.01973755e+02 -6.75369568e+02 -6.47419922e+02 -6.19312744e+02 -5.91780762e+02 -5.64437683e+02 -5.36360535e+02 -5.07619751e+02 -4.79503510e+02 -4.51767548e+02 -4.23840149e+02 -3.95545288e+02 -3.66967133e+02 -3.38901001e+02 -3.10635132e+02 -2.81478271e+02 -2.52238434e+02 -2.23937500e+02 -1.95543289e+02 -1.66691544e+02 -1.38192657e+02 -1.10092041e+02 -8.08524933e+01 -5.15744934e+01 -1.27508583e+02 3.28981094e+05 1.78583054e+02 5.89298096e+01 8.77151184e+01 1.16331268e+02 1.44854370e+02 1.73582672e+02 2.02174286e+02 2.30668228e+02 2.59145142e+02 2.87630463e+02 3.16265869e+02 3.44763489e+02 3.72886261e+02 4.01032166e+02 4.29096710e+02 4.57361664e+02 4.85456848e+02 5.13348022e+02 5.41086731e+02 5.69068298e+02 5.97190979e+02 6.24492981e+02 6.52092041e+02 6.79521545e+02 7.06233032e+02 7.33910522e+02 7.61985962e+02 7.88945435e+02 8.15075806e+02 8.42240784e+02 8.68719360e+02 8.94876343e+02 9.21787964e+02 9.47943298e+02 9.73356628e+02 9.99731018e+02 1.02571191e+03 1.05336914e+03 1.07791260e+03 1.10080383e+03 1.12568591e+03 1.15267786e+03 1.17891833e+03 1.20214856e+03 1.22698865e+03 1.25260095e+03 1.27597864e+03 1.29535327e+03 1.32282361e+03 1.34857324e+03 1.36915088e+03 1.39296570e+03 1.41495337e+03 1.43558923e+03 1.46191296e+03 1.48574133e+03 1.50584595e+03 1.52722180e+03 1.54775989e+03 1.57022852e+03 1.59140686e+03 1.60766687e+03 1.63353503e+03 1.65086328e+03 1.66848071e+03 1.69740369e+03 1.71366357e+03 1.72965857e+03 1.75169189e+03 1.76924048e+03 1.78966846e+03 1.80699146e+03 1.82117419e+03 1.84038721e+03 1.86393958e+03 1.87789429e+03 1.88854089e+03 1.91405298e+03 1.93017566e+03 1.94048889e+03 1.95868835e+03 1.97810938e+03 1.99232166e+03 2.00003406e+03 2.59381274e+03 2.76969409e+03 3.09177856e+03 5.18687305e+03 6.71767383e+03 3.08321602e+04 -10396943. 174491184. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -159086048. 2.56197324e+04 5.22370508e+03 3.34361304e+03 3.09722681e+03 2.94969800e+03 2.28119727e+03 2.28891406e+03 2.28588086e+03 2.28788208e+03 2.29043872e+03 2.30456519e+03 2.31716797e+03 2.31906860e+03 2.31179004e+03 2.32103516e+03 2.32339478e+03 2.32030493e+03 2.33278516e+03 2.33378662e+03 2.32961670e+03 2.33794995e+03 2.33550122e+03 2.33506445e+03 2.33676807e+03 2.33345703e+03 2.33557617e+03 2.33560425e+03 2.33307251e+03 2.32320264e+03 2.33114697e+03 2.33066260e+03 2.31485449e+03 2.32180859e+03 2.32148999e+03 2.30977539e+03 2.31496753e+03 2.30588281e+03 2.30354468e+03 2.30001074e+03 2.29364917e+03 2.28030981e+03 2.27127539e+03 2.27608862e+03 2.26265332e+03 2.25599829e+03 2.25264502e+03 2.24398047e+03 2.23443774e+03 2.22274683e+03 2.20956470e+03 2.20705225e+03 2.19237061e+03 2.18490137e+03 2.18514380e+03 2.17074951e+03 2.15829517e+03 2.14030762e+03 2.13027319e+03 2.12421948e+03 2.11245898e+03 2.09469092e+03 2.08305542e+03 2.07641357e+03 2.05719751e+03 2.04583350e+03 2.03391833e+03 2.02034009e+03 1.99769116e+03 1.97775366e+03 1.97053796e+03 1.95976379e+03 1.94207275e+03 1.92590210e+03 1.90826941e+03 1.89095508e+03 1.87656763e+03 1.85806104e+03 1.83733911e+03 1.82028992e+03 1.80804260e+03 1.78643481e+03 1.76408362e+03 1.74879126e+03 1.72843457e+03 1.70700305e+03 1.68960950e+03 1.67526147e+03 1.64999536e+03 1.62900659e+03 1.61013708e+03 1.58653040e+03 1.56619958e+03 1.54450037e+03 1.52240625e+03 1.50579736e+03 1.48177161e+03 1.45395325e+03 1.43622363e+03 1.41532263e+03 1.38849634e+03 1.36369031e+03 1.34697729e+03 1.31972632e+03 1.29289502e+03 1.27320288e+03 1.24797766e+03 1.22288672e+03 1.19968213e+03 1.17483521e+03 1.14989966e+03 1.12407263e+03 1.09854932e+03 1.07378809e+03 1.05003186e+03 1.02295911e+03 9.95738098e+02 9.70603882e+02 9.43976562e+02 9.18521179e+02 8.92407837e+02 8.65211060e+02 8.39214294e+02 8.12134155e+02 7.84856140e+02 7.57545532e+02 7.30821960e+02 7.03628235e+02 6.76443542e+02 6.49006470e+02 6.21142090e+02 5.93531006e+02 5.65952271e+02 5.38312988e+02 5.09859741e+02 4.81582489e+02 4.53986420e+02 4.26002655e+02 3.97836273e+02 3.69405701e+02 3.40949921e+02 3.12481842e+02 2.84297791e+02 2.55765717e+02 2.27117462e+02 1.98750397e+02 1.70165390e+02 1.41542465e+02 1.13027153e+02 8.43542938e+01 5.56659203e+01 2.70599651e+01 -1.60541809e+00 -3.02783394e+01 -5.88557091e+01 -8.75257034e+01 -1.16210831e+02 -1.44767136e+02 -1.73434280e+02 -2.01980484e+02 -2.30401367e+02 -2.59011993e+02 -2.87380951e+02 -3.15701263e+02 -3.44354065e+02 -3.72699860e+02 -4.00720734e+02 -4.28887360e+02 -4.57337311e+02 -4.85184235e+02 -5.12843567e+02 -5.40812256e+02 -5.69251953e+02 -5.96754150e+02 -6.23990784e+02 -6.51958862e+02 -6.79219604e+02 -7.06135803e+02 -7.33646667e+02 -7.61439392e+02 -7.88577087e+02 -8.15034668e+02 -8.41947144e+02 -8.68686646e+02 -8.94675110e+02 -9.21548767e+02 -9.47700867e+02 -9.73432556e+02 -9.99278687e+02 -1.02547766e+03 -1.05292834e+03 -1.07687964e+03 -1.10136401e+03 -1.12515210e+03 -1.15192578e+03 -1.17824573e+03 -1.20122852e+03 -1.22683801e+03 -1.25299585e+03 -1.27424158e+03 -1.29399341e+03 -1.32129907e+03 -1.34682788e+03 -1.36896643e+03 -1.39328552e+03 -1.41386902e+03 -1.43594617e+03 -1.46117310e+03 -1.48506165e+03 -1.50673425e+03 -1.52720142e+03 -1.54517615e+03 -1.56950696e+03 -1.59075977e+03 -1.60645752e+03 -1.63238135e+03 -1.65131860e+03 -1.66757654e+03 -1.69626538e+03 -1.71390186e+03 -1.72767822e+03 -1.75092798e+03 -1.76951086e+03 -1.78817761e+03 -1.80761865e+03 -1.81870593e+03 -1.83695959e+03 -1.86451123e+03 -1.87812427e+03 -1.88738440e+03 -1.91483374e+03 -1.92864783e+03 -1.94045020e+03 -1.95658374e+03 -1.97421448e+03 -1.98893384e+03 -1.99794617e+03 -2.01905750e+03 -2.03769629e+03 -2.04384680e+03 -2.05396338e+03 -2.07391553e+03 -2.09187817e+03 -2.09799927e+03 -2.10582568e+03 -2.12340845e+03 -2.13768408e+03 -2.14741187e+03 -2.15857300e+03 -2.16762085e+03 -2.17820801e+03 -2.19081787e+03 -2.19757764e+03 -2.20689160e+03 -2.21981787e+03 -2.22480615e+03 -2.23530786e+03 -2.24773584e+03 -2.25377344e+03 -2.25636499e+03 -2.25805664e+03 -2.27692310e+03 -2.28096851e+03 -2.28278931e+03 -2.28736035e+03 -2.28858496e+03 -2.29616504e+03 -2.30601270e+03 -2.31307324e+03 -2.31787769e+03 -2.31127148e+03 -2.31537451e+03 -2.32340088e+03 -2.32134448e+03 -2.32977539e+03 -2.33410938e+03 -2.33119580e+03 -2.33712646e+03 -2.33398877e+03 -2.33483789e+03 -2.33405273e+03 -2.33332324e+03 -2.33529321e+03 -2.32859302e+03 -2.33349805e+03 -2.32918774e+03 -2.32791187e+03 -2.32792163e+03 -2.32073364e+03 -2.32534131e+03 -2.31401880e+03 -2.31014062e+03 -2.31258838e+03 -2.30600977e+03 -2.30299414e+03 -2.29708105e+03 -2.29465112e+03 -2.27719971e+03 -2.26547046e+03 -2.27471948e+03 -2.25804736e+03 -2.25136816e+03 -2.25697119e+03 -2.24315527e+03 -2.23552515e+03 -2.21861841e+03 -2.20727588e+03 -2.21009937e+03 -2.19928223e+03 -2.18466699e+03 -2.18658350e+03 -2.16861987e+03 -2.15502808e+03 -2.14242676e+03 -2.12951978e+03 -2.12508936e+03 -2.11185034e+03 -2.09305420e+03 -2.08643213e+03 -2.07540771e+03 -2.05398438e+03 -2.04121252e+03 -2.03493591e+03 -2.01692407e+03 -1.99880872e+03 -1.97992200e+03 -1.97109827e+03 -1.95960632e+03 -1.94206287e+03 -1.92576306e+03 -1.90655798e+03 -1.88743286e+03 -1.87664026e+03 -1.85578748e+03 -1.83731738e+03 -1.82264343e+03 -1.80535974e+03 -1.78626355e+03 -1.76595813e+03 -1.74635120e+03 -1.72769922e+03 -1.70740808e+03 -1.68899683e+03 -1.67447375e+03 -1.65014722e+03 -1.62901086e+03 -1.60943274e+03 -1.58643335e+03 -1.56622498e+03 -1.54557214e+03 -1.52196973e+03 -1.50392944e+03 -1.48073669e+03 -1.45471069e+03 -1.43582849e+03 -1.41466492e+03 -1.38768274e+03 -1.36408643e+03 -1.34614258e+03 -1.31999268e+03 -1.29276880e+03 -1.27365820e+03 -1.24825586e+03 -1.22220654e+03 -1.19956409e+03 -1.17465906e+03 -1.14961243e+03 -1.12460388e+03 -1.09744446e+03 -1.07380261e+03 -1.05052979e+03 -1.02266699e+03 -9.95534119e+02 -9.69645813e+02 -9.44119812e+02 -9.18665771e+02 -8.92445190e+02 -8.65271057e+02 -8.39177490e+02 -8.12123047e+02 -7.84867188e+02 -7.57688965e+02 -7.30752563e+02 -7.03253967e+02 -6.76285461e+02 -6.48980591e+02 -6.21354919e+02 -5.93688232e+02 -5.65896729e+02 -5.38151611e+02 -5.09800995e+02 -4.81737030e+02 -4.53881317e+02 -4.25943573e+02 -3.97910950e+02 -3.69507751e+02 -3.41033630e+02 -3.12423553e+02 -2.84187347e+02 -2.55818787e+02 -2.27203598e+02 -1.98760620e+02 -1.70170349e+02 -1.41552078e+02 -1.12998528e+02 -8.43260422e+01 -5.56528473e+01 -2.70232544e+01 1.61431360e+00 3.02653828e+01 5.88652611e+01 8.75109711e+01 1.16101517e+02 1.44677200e+02 1.73370682e+02 2.01911392e+02 2.30409454e+02 2.58958954e+02 2.87356049e+02 3.15712677e+02 3.44247406e+02 3.72567535e+02 4.00659149e+02 4.28841034e+02 4.57207214e+02 4.85153687e+02 5.13005676e+02 5.40772583e+02 5.68710205e+02 5.96888855e+02 6.24191040e+02 6.51914246e+02 6.79208923e+02 7.05918274e+02 7.33582031e+02 7.61735535e+02 7.88468933e+02 8.14651245e+02 8.41831299e+02 8.68366028e+02 8.95033936e+02 9.21307861e+02 9.47241394e+02 9.73269531e+02 9.99643005e+02 1.02523804e+03 1.05260205e+03 1.07755701e+03 1.10070142e+03 1.12535266e+03 1.15277185e+03 1.17822327e+03 1.20158289e+03 1.22603625e+03 1.25259412e+03 1.27451062e+03 1.29448633e+03 1.32220532e+03 1.34705774e+03 1.36854016e+03 1.39156165e+03 1.41522925e+03 1.43609436e+03 1.46110657e+03 1.48514929e+03 1.50500439e+03 1.52556470e+03 1.54603662e+03 1.57049841e+03 1.59228467e+03 1.60887793e+03 1.63267871e+03 1.65080017e+03 1.67007129e+03 1.69503845e+03 1.71276965e+03 1.73012744e+03 1.75183508e+03 1.76703406e+03 1.78837561e+03 1.80389417e+03 1.81983850e+03 1.84170178e+03 1.86480371e+03 1.87665442e+03 1.88733691e+03 1.91294495e+03 1.93180725e+03 1.94197437e+03 1.95690942e+03 1.97575500e+03 1.98796228e+03 1.99718213e+03 2.01865576e+03 2.03604834e+03 2.04695496e+03 2.05518188e+03 2.07419458e+03 2.09209497e+03 2.09773291e+03 2.10843848e+03 2.12497949e+03 2.13680396e+03 2.14571167e+03 2.16189746e+03 2.16585669e+03 2.17727930e+03 2.19121167e+03 2.19447681e+03 2.21016479e+03 2.22422681e+03 2.22401172e+03 2.23650977e+03 2.24643628e+03 2.25276001e+03 2.25660815e+03 2.25579932e+03 2.27268384e+03 2.28455444e+03 2.29077246e+03 2.28798560e+03 2.29024438e+03 2.29330859e+03 2.29938745e+03 2.31958740e+03 2.32138892e+03 2.30951465e+03 2.32142236e+03 2.32530835e+03 2.32389771e+03 2.32967627e+03 2.32659888e+03 2.33188525e+03 2.33409546e+03 2.33383374e+03 2.32789478e+03 2.33515918e+03 2.33612280e+03 2.33881885e+03 2.32824561e+03 2.32866113e+03 2.32566455e+03 2.33180884e+03 2.33079614e+03 2.31853467e+03 2.32516797e+03 2.31853516e+03 2.30782764e+03 2.31873706e+03 2.30124194e+03 2.29860938e+03 2.30121704e+03 2.29221704e+03 2.27820361e+03 2.27361401e+03 2.27444580e+03 2.26244507e+03 2.24924023e+03 2.25447412e+03 2.24364795e+03 2.23915308e+03 2.22364087e+03 2.20821973e+03 2.21097925e+03 2.19566504e+03 2.18552246e+03 2.18380640e+03 2.17075977e+03 2.15411719e+03 2.14119556e+03 2.13209131e+03 2.12552661e+03 2.11076343e+03 2.09643652e+03 2.08502466e+03 2.07433496e+03 2.05531787e+03 2.04386902e+03 2.03450903e+03 2.01883044e+03 1.99715308e+03 1.97968127e+03 1.96917102e+03 1.95961035e+03 1.94178320e+03 1.92536047e+03 1.90634485e+03 1.88959766e+03 1.87671582e+03 1.85740063e+03 1.83787891e+03 1.82201172e+03 1.80443359e+03 1.78728259e+03 1.76514185e+03 1.74747925e+03 1.72757996e+03 1.70697534e+03 1.68884143e+03 1.67462012e+03 1.64882153e+03 1.62782007e+03 1.60966064e+03 1.58729993e+03 1.56542749e+03 1.54469373e+03 1.52173621e+03 1.50415979e+03 1.48167151e+03 1.45481018e+03 1.43558630e+03 1.41362854e+03 1.38773169e+03 1.36495984e+03 1.34641687e+03 1.31983472e+03 1.29326257e+03 1.27330347e+03 1.24805969e+03 1.22253906e+03 1.19968420e+03 1.17427722e+03 1.14902307e+03 1.12472852e+03 1.09783728e+03 1.07337549e+03 1.05117346e+03 1.02305920e+03 9.95107910e+02 9.70022827e+02 9.44361511e+02 9.18230530e+02 8.92516113e+02 8.65317566e+02 8.39418152e+02 8.12528320e+02 7.84713013e+02 7.57451721e+02 7.30669983e+02 7.03481995e+02 6.76468323e+02 6.48990356e+02 6.21306519e+02 5.93453003e+02 5.65880859e+02 5.38301514e+02 5.09889679e+02 4.81754425e+02 4.53892212e+02 4.25815216e+02 3.97866516e+02 3.69526154e+02 3.41015839e+02 3.12461121e+02 2.84175995e+02 2.55781448e+02 2.27170593e+02 1.98742722e+02 1.70190704e+02 1.41577454e+02 1.13040245e+02 8.43742981e+01 5.57089462e+01 2.71198578e+01 -1.57965565e+00 -3.02571735e+01 -5.88146667e+01 -8.74958420e+01 -1.16179169e+02 -1.44743729e+02 -1.73400375e+02 -2.01951233e+02 -2.30412262e+02 -2.58951263e+02 -2.87370941e+02 -3.15766388e+02 -3.44308411e+02 -3.72616882e+02 -4.00598022e+02 -4.28874969e+02 -4.57233612e+02 -4.85157898e+02 -5.13156006e+02 -5.40949524e+02 -5.68857361e+02 -5.96886963e+02 -6.24026611e+02 -6.51657410e+02 -6.79365906e+02 -7.06149048e+02 -7.33609985e+02 -7.61929016e+02 -7.88543823e+02 -8.14993225e+02 -8.41709717e+02 -8.68484009e+02 -8.94704712e+02 -9.21516235e+02 -9.48037109e+02 -9.72938477e+02 -9.98868042e+02 -1.02533240e+03 -1.05337061e+03 -1.07782275e+03 -1.10070337e+03 -1.12479431e+03 -1.15287927e+03 -1.17929541e+03 -1.20118591e+03 -1.22595068e+03 -1.25232568e+03 -1.27416980e+03 -1.29376282e+03 -1.32158801e+03 -1.34751074e+03 -1.36864038e+03 -1.39260876e+03 -1.41487524e+03 -1.43658301e+03 -1.46139331e+03 -1.48552832e+03 -1.50654053e+03 -1.52583484e+03 -1.54664172e+03 -1.56917090e+03 -1.59092664e+03 -1.60887378e+03 -1.63255518e+03 -1.65110266e+03 -1.66737622e+03 -1.69520251e+03 -1.71340369e+03 -1.72823438e+03 -1.75181458e+03 -1.76942346e+03 -1.78892664e+03 -1.80678711e+03 -1.82062646e+03 -1.83935132e+03 -1.86421753e+03 -1.87688855e+03 -1.88736902e+03 -1.91487305e+03 -1.93034937e+03 -1.94166040e+03 -1.95610229e+03 -1.97547485e+03 -1.98948230e+03 -1.99975781e+03 -2.02055249e+03 -2.03489539e+03 -2.04682153e+03 -2.05667871e+03 -2.07513843e+03 -2.08994287e+03 -2.09638892e+03 -2.10772144e+03 -2.12332666e+03 -2.13679077e+03 -2.14868237e+03 -2.16054639e+03 -2.16341553e+03 -2.17685474e+03 -2.19199731e+03 -2.19311841e+03 -2.20679468e+03 -2.22040479e+03 -2.22523364e+03 -2.23511719e+03 -2.24879297e+03 -2.25212036e+03 -2.25394409e+03 -2.26130493e+03 -2.27478247e+03 -2.28097681e+03 -2.28434521e+03 -2.28647852e+03 -2.28923340e+03 -2.29890820e+03 -2.30260522e+03 -2.31446240e+03 -2.31746533e+03 -2.31424219e+03 -2.32211743e+03 -2.32130273e+03 -2.32087378e+03 -2.33557178e+03 -2.33557764e+03 -2.33014722e+03 -2.33347241e+03 -2.33696289e+03 -2.33578906e+03 -2.33590259e+03 -2.33099023e+03 -2.33551025e+03 -2.33257227e+03 -2.33624072e+03 -2.32892310e+03 -2.32887036e+03 -2.32971411e+03 -2.32029248e+03 -2.32200220e+03 -2.31504688e+03 -2.30667896e+03 -2.31196753e+03 -2.30042285e+03 -2.29453833e+03 -2.29101196e+03 -2.28534766e+03 -2.27789551e+03 -2.27196387e+03 -2.90395532e+03 -2.99875415e+03 -5.19703418e+03 -6.39966113e+03 -67023336. -2.95307725e+06 0. 0. -109199712. -109199712. -109199712. 0. 0. 0. -162924736. -1.08207662e+06 2.32011680e+04 -6.36718262e+03 -5.47721338e+03 -3.23086475e+03 -3.02160620e+03 -2.11283691e+03 -2.05979541e+03 -2.04467773e+03 -2.02686462e+03 -2.00496680e+03 -1.98152698e+03 -1.96992261e+03 -1.95868787e+03 -1.94154443e+03 -1.92717798e+03 -1.90544421e+03 -1.89257715e+03 -1.87784045e+03 -1.85517041e+03 -1.83965833e+03 -1.81836719e+03 -1.80130579e+03 -1.78299756e+03 -1.76436169e+03 -1.74603345e+03 -1.72764844e+03 -1.71049951e+03 -1.68998401e+03 -1.67295496e+03 -1.64948779e+03 -1.62720886e+03 -1.61073486e+03 -1.59102014e+03 -1.57170691e+03 -1.54617175e+03 -1.52360864e+03 -1.50552454e+03 -1.48003027e+03 -1.45503125e+03 -1.43658337e+03 -1.41607166e+03 -1.38820337e+03 -1.36462585e+03 -1.34657092e+03 -1.32114990e+03 -1.29293005e+03 -1.27289429e+03 -1.24841870e+03 -1.22329004e+03 -1.20005017e+03 -1.17471716e+03 -1.14921594e+03 -1.12495813e+03 -1.09782043e+03 -1.07456311e+03 -1.05149731e+03 -1.02285858e+03 -9.96071289e+02 -9.70053711e+02 -9.44146729e+02 -9.19502441e+02 -8.92655029e+02 -8.65175415e+02 -8.39534607e+02 -8.12443848e+02 -7.85246948e+02 -7.57953918e+02 -7.30860107e+02 -7.03714844e+02 -6.76855896e+02 -6.49178528e+02 -6.21341858e+02 -5.93852722e+02 -5.66351685e+02 -5.38354858e+02 -5.09992035e+02 -4.82052063e+02 -4.54195007e+02 -4.26194092e+02 -3.98069000e+02 -3.69694366e+02 -3.41300690e+02 -3.12392029e+02 -2.84288849e+02 -2.56146454e+02 -2.27467163e+02 -1.99019730e+02 -1.70247131e+02 -1.41525543e+02 -1.12444664e+02 -8.31861420e+01 -5.56676636e+01 -1.39985352e+02 2.24530094e+05 1.48884506e+02 5.13182678e+01 7.94213486e+01 1.07239540e+02 1.35280136e+02 1.63994156e+02 1.92395737e+02 2.19736725e+02 2.47842407e+02 2.76062164e+02 3.03992889e+02 3.32328522e+02 3.60197906e+02 3.87949677e+02 4.15822998e+02 4.43482971e+02 4.71173157e+02 4.98917877e+02 5.25836853e+02 5.53344299e+02 5.81165955e+02 6.07927673e+02 6.35643005e+02 6.62685791e+02 6.88246338e+02 7.16003235e+02 7.44136353e+02 7.69716614e+02 7.95301331e+02 8.22322388e+02 8.49672241e+02 8.75604797e+02 9.00974060e+02 9.25859375e+02 9.51571960e+02 9.78226868e+02 1.00377545e+03 1.03023633e+03 1.05433044e+03 1.07795471e+03 1.10309180e+03 1.12796558e+03 1.15270386e+03 1.17839795e+03 1.20154871e+03 1.22496704e+03 1.25072559e+03 1.27072412e+03 1.29438892e+03 1.32133582e+03 1.34320776e+03 1.36673987e+03 1.38700842e+03 1.40782166e+03 1.43348511e+03 1.45632776e+03 1.47731543e+03 1.49785657e+03 1.51709143e+03 1.54170203e+03 1.56197864e+03 1.57662012e+03 1.59992786e+03 1.62255444e+03 1.63874292e+03 1.66174292e+03 1.68243518e+03 1.69959033e+03 1.71735571e+03 1.73857983e+03 1.75718811e+03 1.77622876e+03 1.79037512e+03 1.80701111e+03 1.82782654e+03 1.84196362e+03 1.86143701e+03 1.87650354e+03 1.89410022e+03 1.90821289e+03 1.92171899e+03 1.94225110e+03 2.51369189e+03 2.62777686e+03 4.69760059e+03 3.34227319e+03 6.12988623e+03 2.30895547e+04 -181367584. 174491184. 174491184. 9073104. -948973952. -948973952. 0. 0. 0. 0. 0. 0. 7.97435950e+06 -19440566. 2.59315503e+03 6.06676416e+03 5.15198291e+03 2.87234766e+03 2.21900586e+03 2.22848633e+03 2.23519434e+03 2.24358081e+03 2.24779468e+03 2.25092139e+03 2.26741357e+03 2.26277344e+03 2.26232812e+03 2.27996753e+03 2.27949219e+03 2.28012524e+03 2.28815381e+03 2.28711865e+03 2.28474634e+03 2.29160645e+03 2.29305762e+03 2.29253882e+03 2.29415283e+03 2.29596216e+03 2.30164502e+03 2.29675195e+03 2.29689062e+03 2.30189771e+03 2.29379150e+03 2.29539160e+03 2.29990771e+03 2.29102856e+03 2.28977637e+03 2.28964209e+03 2.28650293e+03 2.28422974e+03 2.28206592e+03 2.27611353e+03 2.26408936e+03 2.26668164e+03 2.26641016e+03 2.25382959e+03 2.24426660e+03 2.24334644e+03 2.24350293e+03 2.22629004e+03 2.22254224e+03 2.21673901e+03 2.21501562e+03 2.20056909e+03 2.18625732e+03 2.18124731e+03 2.17930933e+03 2.16278931e+03 2.14898047e+03 2.14807910e+03 2.14323975e+03 2.12563330e+03 2.11057349e+03 2.10252856e+03 2.09494971e+03 2.08027490e+03 2.06383130e+03 2.05299023e+03 2.04350830e+03 2.02565369e+03 2.01527283e+03 2.00946021e+03 1.98885388e+03 1.97074438e+03 1.95661609e+03 1.94504358e+03 1.93115259e+03 1.91690955e+03 1.89613623e+03 1.88030859e+03 1.86808704e+03 1.84972083e+03 1.83607556e+03 1.81650513e+03 1.79112305e+03 1.78102917e+03 1.76549731e+03 1.73951733e+03 1.72350623e+03 1.70991724e+03 1.68668604e+03 1.66482214e+03 1.65064758e+03 1.62988452e+03 1.60781421e+03 1.58885022e+03 1.56810608e+03 1.54760718e+03 1.52678479e+03 1.50283740e+03 1.48630859e+03 1.46322534e+03 1.43633276e+03 1.41889380e+03 1.39854114e+03 1.37158386e+03 1.34745361e+03 1.32900549e+03 1.30424902e+03 1.27947534e+03 1.25865137e+03 1.23413147e+03 1.20827368e+03 1.18593591e+03 1.16283557e+03 1.13914734e+03 1.11246753e+03 1.08524768e+03 1.06220618e+03 1.04003845e+03 1.01312250e+03 9.86229980e+02 9.60739990e+02 9.35114746e+02 9.10718384e+02 8.84518738e+02 8.57679443e+02 8.32742676e+02 8.05819519e+02 7.78354126e+02 7.52067749e+02 7.25674072e+02 6.99277954e+02 6.72725159e+02 6.45053650e+02 6.18105286e+02 5.91057922e+02 5.63423340e+02 5.36299988e+02 5.08271912e+02 4.80376251e+02 4.53552002e+02 4.26087311e+02 3.98213623e+02 3.70302216e+02 3.42327301e+02 3.14232208e+02 2.86427399e+02 2.58490204e+02 2.30339722e+02 2.02347382e+02 1.74222382e+02 1.46060181e+02 1.17962662e+02 8.97624893e+01 6.15480766e+01 3.33812065e+01 5.18099594e+00 -2.30502949e+01 -5.12009239e+01 -7.93978043e+01 -1.07625626e+02 -1.35719055e+02 -1.63943802e+02 -1.92032288e+02 -2.20044724e+02 -2.48286591e+02 -2.76199829e+02 -3.03994781e+02 -3.32166718e+02 -3.60175140e+02 -3.87740234e+02 -4.15749268e+02 -4.43512360e+02 -4.71039581e+02 -4.98485718e+02 -5.25611938e+02 -5.53685608e+02 -5.80715698e+02 -6.07279297e+02 -6.35576355e+02 -6.62579468e+02 -6.88323303e+02 -7.15778870e+02 -7.43381897e+02 -7.69245056e+02 -7.95258484e+02 -8.22382324e+02 -8.49495605e+02 -8.75239441e+02 -9.00864441e+02 -9.25621033e+02 -9.50949585e+02 -9.77705261e+02 -1.00404706e+03 -1.02996985e+03 -1.05387903e+03 -1.07861255e+03 -1.10136157e+03 -1.12801135e+03 -1.15422363e+03 -1.17716333e+03 -1.20081714e+03 -1.22550208e+03 -1.24936035e+03 -1.26849524e+03 -1.29427478e+03 -1.31930078e+03 -1.34197607e+03 -1.36627441e+03 -1.38600049e+03 -1.40869360e+03 -1.43284583e+03 -1.45510925e+03 -1.47785107e+03 -1.49825244e+03 -1.51615442e+03 -1.53907739e+03 -1.56028430e+03 -1.57777820e+03 -1.60074438e+03 -1.62320386e+03 -1.63826807e+03 -1.66007446e+03 -1.68162378e+03 -1.69930090e+03 -1.71828003e+03 -1.73919885e+03 -1.75591199e+03 -1.77581360e+03 -1.78837854e+03 -1.80475208e+03 -1.82875208e+03 -1.83964331e+03 -1.85904065e+03 -1.87707983e+03 -1.88998010e+03 -1.91058752e+03 -1.92205798e+03 -1.93730066e+03 -1.95085791e+03 -1.96799084e+03 -1.98394751e+03 -1.99948254e+03 -2.01218384e+03 -2.02214368e+03 -2.03811829e+03 -2.05458545e+03 -2.06122388e+03 -2.07195581e+03 -2.08545654e+03 -2.09462500e+03 -2.11040381e+03 -2.12382227e+03 -2.12876953e+03 -2.14170825e+03 -2.15411743e+03 -2.15930737e+03 -2.17377563e+03 -2.18633960e+03 -2.18909961e+03 -2.19879712e+03 -2.20048682e+03 -2.21066968e+03 -2.21988794e+03 -2.23083081e+03 -2.24068091e+03 -2.23816846e+03 -2.24680249e+03 -2.25171729e+03 -2.25902319e+03 -2.26097485e+03 -2.26381079e+03 -2.27609717e+03 -2.27552759e+03 -2.27899609e+03 -2.28353979e+03 -2.28286377e+03 -2.28503149e+03 -2.29324731e+03 -2.29291406e+03 -2.29023950e+03 -2.29111743e+03 -2.29754126e+03 -2.30588452e+03 -2.30229907e+03 -2.29538281e+03 -2.29556689e+03 -2.29577661e+03 -2.29909473e+03 -2.29551196e+03 -2.28441553e+03 -2.28709888e+03 -2.29249707e+03 -2.28453687e+03 -2.28115674e+03 -2.28592725e+03 -2.27468384e+03 -2.26405591e+03 -2.26455908e+03 -2.26250073e+03 -2.25191968e+03 -2.24478149e+03 -2.24384424e+03 -2.24473755e+03 -2.22808691e+03 -2.22420044e+03 -2.21848242e+03 -2.21265771e+03 -2.19898169e+03 -2.18452686e+03 -2.18114087e+03 -2.18144067e+03 -2.16921240e+03 -2.15159082e+03 -2.15073486e+03 -2.14066357e+03 -2.12096997e+03 -2.10842725e+03 -2.10077979e+03 -2.09423413e+03 -2.08006665e+03 -2.06538525e+03 -2.05191699e+03 -2.04281909e+03 -2.02525818e+03 -2.01618835e+03 -2.00802332e+03 -1.98900085e+03 -1.96707458e+03 -1.95588916e+03 -1.94404236e+03 -1.93158728e+03 -1.91821838e+03 -1.89534656e+03 -1.88147778e+03 -1.86555591e+03 -1.84968945e+03 -1.83531055e+03 -1.81475598e+03 -1.79188171e+03 -1.77834985e+03 -1.76424158e+03 -1.74093396e+03 -1.72197070e+03 -1.70931335e+03 -1.68848523e+03 -1.66558533e+03 -1.64986499e+03 -1.62903247e+03 -1.60711792e+03 -1.58927966e+03 -1.56805823e+03 -1.54773584e+03 -1.52539209e+03 -1.50324243e+03 -1.48466760e+03 -1.46172827e+03 -1.43766626e+03 -1.41942505e+03 -1.39814197e+03 -1.37157947e+03 -1.34740247e+03 -1.32964124e+03 -1.30462256e+03 -1.27844617e+03 -1.25865161e+03 -1.23379871e+03 -1.20799792e+03 -1.18636438e+03 -1.16230957e+03 -1.13854749e+03 -1.11258423e+03 -1.08509326e+03 -1.06269556e+03 -1.03977344e+03 -1.01259747e+03 -9.85445496e+02 -9.60161560e+02 -9.35966919e+02 -9.11153137e+02 -8.84241638e+02 -8.57710327e+02 -8.32752991e+02 -8.05804688e+02 -7.78345093e+02 -7.51919373e+02 -7.25631042e+02 -6.99191589e+02 -6.72440247e+02 -6.45008484e+02 -6.18245728e+02 -5.90854675e+02 -5.63290100e+02 -5.36346924e+02 -5.08113220e+02 -4.80566711e+02 -4.53497009e+02 -4.25970245e+02 -3.98214722e+02 -3.70358032e+02 -3.42344513e+02 -3.14117432e+02 -2.86306305e+02 -2.58522858e+02 -2.30341827e+02 -2.02310928e+02 -1.74209198e+02 -1.46043716e+02 -1.17926155e+02 -8.97385025e+01 -6.15521889e+01 -3.33583183e+01 -5.14777279e+00 2.30435753e+01 5.12092018e+01 7.94205933e+01 1.07598412e+02 1.35683319e+02 1.63930542e+02 1.92038162e+02 2.20082153e+02 2.48248749e+02 2.76189056e+02 3.04033142e+02 3.32108185e+02 3.60084778e+02 3.87770844e+02 4.15691620e+02 4.43294617e+02 4.70903809e+02 4.98779144e+02 5.25695679e+02 5.53068054e+02 5.80906372e+02 6.07694092e+02 6.35394287e+02 6.62546753e+02 6.88109375e+02 7.15713745e+02 7.43889160e+02 7.69593506e+02 7.94901978e+02 8.21900452e+02 8.49393921e+02 8.75669983e+02 9.00927307e+02 9.24978394e+02 9.51417419e+02 9.78365173e+02 1.00369440e+03 1.02956482e+03 1.05368384e+03 1.07783765e+03 1.10267566e+03 1.12826440e+03 1.15293408e+03 1.17766077e+03 1.20178564e+03 1.22528516e+03 1.24893591e+03 1.26959253e+03 1.29534595e+03 1.32042957e+03 1.34316907e+03 1.36531726e+03 1.38685779e+03 1.40897729e+03 1.43321704e+03 1.45546814e+03 1.47638171e+03 1.49632581e+03 1.51625635e+03 1.54104492e+03 1.56237134e+03 1.57889160e+03 1.60109155e+03 1.62184412e+03 1.63852295e+03 1.66126794e+03 1.68240820e+03 1.69924719e+03 1.71807361e+03 1.73494312e+03 1.75611841e+03 1.77448669e+03 1.78894226e+03 1.80820703e+03 1.82656934e+03 1.84020984e+03 1.85709656e+03 1.87804980e+03 1.89378552e+03 1.90990796e+03 1.92306128e+03 1.93884644e+03 1.95352417e+03 1.96622778e+03 1.98522693e+03 2.00131580e+03 2.01341174e+03 2.01759521e+03 2.03688293e+03 2.05835522e+03 2.06177759e+03 2.07218311e+03 2.08909717e+03 2.09274854e+03 2.10805151e+03 2.12763745e+03 2.12647192e+03 2.14095117e+03 2.15544141e+03 2.15606177e+03 2.17458350e+03 2.18512036e+03 2.19322144e+03 2.20074756e+03 2.19852930e+03 2.20991870e+03 2.21783618e+03 2.22683911e+03 2.23950122e+03 2.24405933e+03 2.24944482e+03 2.25232861e+03 2.26086646e+03 2.25828491e+03 2.26325049e+03 2.28108423e+03 2.27955786e+03 2.27581396e+03 2.28528442e+03 2.29038330e+03 2.28556909e+03 2.28862427e+03 2.29246899e+03 2.29180396e+03 2.29055029e+03 2.29672852e+03 2.30070605e+03 2.29785620e+03 2.29628857e+03 2.30395068e+03 2.29165723e+03 2.29599243e+03 2.29933496e+03 2.28787280e+03 2.28907202e+03 2.28687500e+03 2.28890698e+03 2.28216919e+03 2.27726294e+03 2.28181934e+03 2.26006665e+03 2.26448535e+03 2.26738477e+03 2.25130298e+03 2.24225708e+03 2.24368945e+03 2.24332422e+03 2.22799902e+03 2.22082129e+03 2.21548828e+03 2.21224121e+03 2.20141162e+03 2.18551978e+03 2.18075488e+03 2.18004419e+03 2.16568457e+03 2.15205566e+03 2.14972070e+03 2.14284253e+03 2.12359741e+03 2.10853979e+03 2.10416992e+03 2.09535034e+03 2.07809204e+03 2.06480444e+03 2.05356543e+03 2.04372021e+03 2.02584814e+03 2.01544104e+03 2.00628943e+03 1.98967542e+03 1.96729846e+03 1.95657727e+03 1.94359021e+03 1.92998340e+03 1.91549365e+03 1.89610864e+03 1.87845312e+03 1.86518994e+03 1.85186755e+03 1.83518188e+03 1.81460400e+03 1.79354187e+03 1.77974878e+03 1.76465234e+03 1.74111780e+03 1.72224780e+03 1.70934717e+03 1.68627234e+03 1.66478467e+03 1.65073438e+03 1.62769580e+03 1.60779004e+03 1.59002344e+03 1.56844763e+03 1.54692126e+03 1.52626770e+03 1.50331567e+03 1.48675610e+03 1.46299084e+03 1.43694153e+03 1.41916479e+03 1.39766382e+03 1.37142969e+03 1.34880457e+03 1.32973438e+03 1.30477344e+03 1.27874548e+03 1.25936377e+03 1.23423877e+03 1.20797375e+03 1.18583337e+03 1.16227332e+03 1.13788940e+03 1.11288330e+03 1.08602429e+03 1.06208215e+03 1.04035413e+03 1.01281128e+03 9.85951721e+02 9.60502319e+02 9.35346130e+02 9.10749268e+02 8.84635132e+02 8.57800720e+02 8.32885986e+02 8.06082886e+02 7.78183228e+02 7.51597595e+02 7.25591064e+02 6.99480530e+02 6.72638000e+02 6.44917969e+02 6.18165588e+02 5.90656860e+02 5.63323914e+02 5.36473389e+02 5.08298035e+02 4.80555023e+02 4.53467377e+02 4.25880341e+02 3.98191803e+02 3.70377014e+02 3.42345306e+02 3.14224304e+02 2.86360291e+02 2.58478943e+02 2.30313538e+02 2.02318695e+02 1.74227295e+02 1.46091309e+02 1.18005898e+02 8.97952423e+01 6.15793800e+01 3.34473953e+01 5.21751547e+00 -2.30162258e+01 -5.11606903e+01 -7.93708115e+01 -1.07571510e+02 -1.35676254e+02 -1.63904495e+02 -1.92050018e+02 -2.20068161e+02 -2.48204300e+02 -2.76209106e+02 -3.04093872e+02 -3.32181976e+02 -3.60092834e+02 -3.87628937e+02 -4.15653473e+02 -4.43414551e+02 -4.70952026e+02 -4.98735382e+02 -5.25769592e+02 -5.53386963e+02 -5.80750916e+02 -6.07449829e+02 -6.35360718e+02 -6.62740967e+02 -6.88359497e+02 -7.15743164e+02 -7.43777710e+02 -7.69456726e+02 -7.95201782e+02 -8.21926758e+02 -8.49300781e+02 -8.75161743e+02 -9.00715881e+02 -9.25841431e+02 -9.51236572e+02 -9.77383850e+02 -1.00383630e+03 -1.03035596e+03 -1.05448865e+03 -1.07810999e+03 -1.10146680e+03 -1.12816187e+03 -1.15452393e+03 -1.17696509e+03 -1.20104041e+03 -1.22578406e+03 -1.24911267e+03 -1.26936072e+03 -1.29501306e+03 -1.31958411e+03 -1.34224207e+03 -1.36615063e+03 -1.38624866e+03 -1.40844031e+03 -1.43263049e+03 -1.45628760e+03 -1.47747766e+03 -1.49754419e+03 -1.51742249e+03 -1.54016602e+03 -1.56101245e+03 -1.57823645e+03 -1.60135913e+03 -1.62293018e+03 -1.63699023e+03 -1.66123938e+03 -1.68384363e+03 -1.69847253e+03 -1.71730591e+03 -1.73804980e+03 -1.75615698e+03 -1.77511597e+03 -1.78824634e+03 -1.80526501e+03 -1.82876465e+03 -1.84016357e+03 -1.85883350e+03 -1.87667102e+03 -1.89254199e+03 -1.90938940e+03 -1.92244482e+03 -1.93892371e+03 -1.95321680e+03 -1.96833008e+03 -1.98480151e+03 -1.99826587e+03 -2.01016541e+03 -2.02203125e+03 -2.03826013e+03 -2.05287915e+03 -2.06339990e+03 -2.07270312e+03 -2.08705664e+03 -2.09636890e+03 -2.11223340e+03 -2.12584814e+03 -2.12781519e+03 -2.14145215e+03 -2.15503589e+03 -2.15742383e+03 -2.17513989e+03 -2.18284619e+03 -2.18990723e+03 -2.20323291e+03 -2.20408521e+03 -2.21066479e+03 -2.21745215e+03 -2.22689331e+03 -2.24101196e+03 -2.23985620e+03 -2.25048242e+03 -2.24891187e+03 -2.26162476e+03 -2.26240674e+03 -2.26252393e+03 -2.27633643e+03 -2.28118848e+03 -2.27758276e+03 -2.28369824e+03 -2.28708813e+03 -2.28955347e+03 -2.29637036e+03 -2.29540527e+03 -2.29359473e+03 -2.28697632e+03 -2.29525635e+03 -2.30777539e+03 -2.29835327e+03 -2.29790698e+03 -2.29970483e+03 -2.28812573e+03 -2.29779053e+03 -2.29642773e+03 -2.28794531e+03 -2.28710107e+03 -2.28820410e+03 -2.28393384e+03 -2.28016772e+03 -2.27327441e+03 -2.27151294e+03 -2.26139893e+03 -2.25966113e+03 -2.26180542e+03 -2.24970142e+03 -2.24450293e+03 -2.24152515e+03 -2.23985669e+03 -2.22651221e+03 -2.84367554e+03 -2.97026782e+03 -5.14618262e+03 -6.50709424e+03 4580439. -100211816. 0. 0. 0. 313247168. 313247168. 313247168. 0. 0. 0. -44713372. 5275728. -8.08604053e+03 -5.53631836e+03 -3.21002393e+03 -3.00021509e+03 -2.73910034e+03 -1.99234668e+03 -1.97303821e+03 -1.95235327e+03 -1.94074597e+03 -1.93205408e+03 -1.91535010e+03 -1.89583630e+03 -1.87690723e+03 -1.86665027e+03 -1.85245959e+03 -1.83110706e+03 -1.81093091e+03 -1.79028613e+03 -1.77554211e+03 -1.76296716e+03 -1.74073938e+03 -1.72078894e+03 -1.70788208e+03 -1.69029724e+03 -1.66658118e+03 -1.64985034e+03 -1.62784302e+03 -1.60949866e+03 -1.59017078e+03 -1.57035217e+03 -1.55684607e+03 -1.53072913e+03 -1.50506567e+03 -1.48786316e+03 -1.46173511e+03 -1.43618701e+03 -1.41940796e+03 -1.39815625e+03 -1.37190820e+03 -1.34775293e+03 -1.32983972e+03 -1.30533398e+03 -1.27910791e+03 -1.25791565e+03 -1.23494287e+03 -1.20915308e+03 -1.18703125e+03 -1.16311292e+03 -1.13894226e+03 -1.11204834e+03 -1.08511072e+03 -1.06382007e+03 -1.04077136e+03 -1.01266162e+03 -9.86297180e+02 -9.60802429e+02 -9.35872009e+02 -9.11732117e+02 -8.84641052e+02 -8.57950378e+02 -8.33050110e+02 -8.06030029e+02 -7.78743713e+02 -7.52209167e+02 -7.25938538e+02 -6.99557495e+02 -6.73022461e+02 -6.45271851e+02 -6.18277710e+02 -5.90648010e+02 -5.63382935e+02 -5.36403564e+02 -5.08158844e+02 -4.80647400e+02 -4.53385498e+02 -4.25921112e+02 -3.98487701e+02 -3.69766510e+02 -3.41288116e+02 -3.13569092e+02 -2.86213959e+02 -2.58696289e+02 -2.30512192e+02 -2.02444778e+02 -1.74191483e+02 -1.45915237e+02 -1.17287880e+02 -8.86127625e+01 -6.13481941e+01 -1.57073364e+02 3.12323125e+04 1.67648071e+02 5.58630562e+01 8.35931625e+01 1.11080856e+02 1.38830963e+02 1.67104721e+02 1.95114304e+02 2.22181580e+02 2.49850723e+02 2.77733215e+02 3.05248169e+02 3.33066650e+02 3.60460876e+02 3.87961731e+02 4.15521301e+02 4.42296844e+02 4.69388428e+02 4.96678192e+02 5.23393494e+02 5.51170654e+02 5.78474792e+02 6.05094727e+02 6.32180176e+02 6.58713013e+02 6.85138489e+02 7.11818237e+02 7.38381104e+02 7.63912415e+02 7.89627869e+02 8.16265442e+02 8.43109497e+02 8.68283386e+02 8.93953979e+02 9.18693909e+02 9.43430115e+02 9.69198059e+02 9.94624634e+02 1.02058051e+03 1.04498425e+03 1.06819678e+03 1.09283789e+03 1.11758789e+03 1.14185938e+03 1.16739783e+03 1.18970496e+03 1.21196436e+03 1.23825793e+03 1.25769128e+03 1.28206250e+03 1.30708997e+03 1.32672253e+03 1.35175159e+03 1.37353015e+03 1.39289343e+03 1.41980139e+03 1.43819531e+03 1.45913660e+03 1.48557947e+03 1.50317004e+03 1.52167859e+03 1.54130469e+03 1.55768640e+03 1.58279858e+03 1.60602832e+03 1.61828564e+03 1.64070935e+03 1.66318567e+03 1.68200732e+03 1.69993933e+03 1.71515881e+03 1.73485669e+03 1.75408704e+03 1.77115747e+03 1.78547571e+03 1.80267786e+03 1.81873950e+03 1.84033826e+03 1.85213892e+03 1.86766052e+03 1.88339478e+03 2.47779541e+03 2.63529053e+03 4.54525781e+03 5.48046582e+03 29678704. 10822057. 5.37770650e+06 5.37770650e+06 0. 13341798. 13341798. 58420816. -948973952. -948973952. 0. 0. 0. 0. 102847440. 4.01055325e+06 6.28301416e+03 5.11424854e+03 3.21847632e+03 2.88630615e+03 2.77304248e+03 2.18289355e+03 2.18767896e+03 2.19895557e+03 2.20632227e+03 2.21097998e+03 2.21922485e+03 2.22400415e+03 2.23416626e+03 2.22810840e+03 2.23377808e+03 2.25506641e+03 2.24724707e+03 2.24362915e+03 2.25436353e+03 2.26056055e+03 2.25984741e+03 2.25734521e+03 2.26373389e+03 2.25916748e+03 2.25452930e+03 2.26719678e+03 2.27635376e+03 2.26939795e+03 2.26492920e+03 2.27415967e+03 2.26809009e+03 2.26411133e+03 2.26533765e+03 2.26214233e+03 2.26231519e+03 2.25475220e+03 2.25116577e+03 2.25211328e+03 2.24633765e+03 2.24569946e+03 2.23085571e+03 2.23219653e+03 2.23866187e+03 2.22216602e+03 2.21520703e+03 2.21493750e+03 2.20451733e+03 2.19365503e+03 2.19216260e+03 2.18470459e+03 2.17632422e+03 2.16690527e+03 2.15716113e+03 2.15768799e+03 2.14698535e+03 2.13087036e+03 2.11938379e+03 2.11641699e+03 2.11172998e+03 2.08844189e+03 2.07937817e+03 2.07667627e+03 2.06748926e+03 2.04659705e+03 2.03222961e+03 2.02554565e+03 2.01330090e+03 1.99595117e+03 1.98321448e+03 1.97722986e+03 1.95944641e+03 1.93956018e+03 1.93037732e+03 1.91456311e+03 1.89699561e+03 1.88987170e+03 1.86548120e+03 1.85000781e+03 1.83911072e+03 1.81982703e+03 1.80757642e+03 1.78754529e+03 1.76607434e+03 1.74949170e+03 1.73584766e+03 1.71294409e+03 1.69731689e+03 1.68367139e+03 1.66026648e+03 1.63861499e+03 1.61986804e+03 1.60330664e+03 1.58164539e+03 1.56236365e+03 1.54573108e+03 1.52360620e+03 1.49997046e+03 1.47506506e+03 1.45915344e+03 1.43733301e+03 1.41477942e+03 1.39675354e+03 1.37455884e+03 1.34914453e+03 1.32294568e+03 1.30546765e+03 1.28160437e+03 1.25771838e+03 1.23735352e+03 1.21270996e+03 1.18685388e+03 1.16399023e+03 1.14204932e+03 1.11891748e+03 1.09190503e+03 1.06585413e+03 1.04315906e+03 1.02064453e+03 9.94370728e+02 9.67495422e+02 9.42475159e+02 9.17248047e+02 8.92592285e+02 8.67198608e+02 8.40869019e+02 8.15142090e+02 7.89284973e+02 7.62760864e+02 7.37221069e+02 7.10510986e+02 6.83895874e+02 6.57376892e+02 6.30541321e+02 6.04137939e+02 5.77366272e+02 5.50003601e+02 5.23086304e+02 4.95961273e+02 4.68462738e+02 4.41722229e+02 4.14545166e+02 3.87000397e+02 3.59528900e+02 3.32023956e+02 3.04393219e+02 2.76804932e+02 2.49260559e+02 2.21597305e+02 1.93963181e+02 1.66188232e+02 1.38436646e+02 1.10706871e+02 8.28955841e+01 5.50885391e+01 2.72902336e+01 -5.26037514e-01 -2.83582916e+01 -5.61356163e+01 -8.39505005e+01 -1.11757942e+02 -1.39453674e+02 -1.67233292e+02 -1.94950119e+02 -2.22652725e+02 -2.50448593e+02 -2.77954681e+02 -3.05342255e+02 -3.33000397e+02 -3.60530304e+02 -3.87984375e+02 -4.15710602e+02 -4.42642548e+02 -4.69807831e+02 -4.97290588e+02 -5.24049988e+02 -5.51385925e+02 -5.77942444e+02 -6.04353882e+02 -6.31922607e+02 -6.58444458e+02 -6.85144531e+02 -7.11515930e+02 -7.37792114e+02 -7.63602600e+02 -7.89380188e+02 -8.16042358e+02 -8.43186157e+02 -8.68500366e+02 -8.93757141e+02 -9.18295837e+02 -9.43068176e+02 -9.69003052e+02 -9.94433960e+02 -1.02067957e+03 -1.04454761e+03 -1.06918750e+03 -1.09137476e+03 -1.11729578e+03 -1.14291357e+03 -1.16510046e+03 -1.19045166e+03 -1.21335938e+03 -1.23644397e+03 -1.25677869e+03 -1.28228540e+03 -1.30470532e+03 -1.32511951e+03 -1.35195593e+03 -1.37274365e+03 -1.39421741e+03 -1.41924365e+03 -1.43616541e+03 -1.45971985e+03 -1.48675732e+03 -1.50263794e+03 -1.52016455e+03 -1.54194238e+03 -1.55835730e+03 -1.58249658e+03 -1.60666687e+03 -1.61870984e+03 -1.63905017e+03 -1.66313025e+03 -1.68135156e+03 -1.69905029e+03 -1.71572559e+03 -1.73336731e+03 -1.75455493e+03 -1.77243176e+03 -1.78451233e+03 -1.80216748e+03 -1.81864819e+03 -1.83818982e+03 -1.85026392e+03 -1.86666028e+03 -1.88718127e+03 -1.89669080e+03 -1.91078564e+03 -1.93047205e+03 -1.94703198e+03 -1.95923547e+03 -1.97388257e+03 -1.99103955e+03 -1.99584912e+03 -2.01222241e+03 -2.02822021e+03 -2.03211792e+03 -2.04615283e+03 -2.06284277e+03 -2.06763037e+03 -2.08271973e+03 -2.09617896e+03 -2.09719873e+03 -2.11512085e+03 -2.13263965e+03 -2.13049902e+03 -2.14367261e+03 -2.15475366e+03 -2.15990552e+03 -2.17215845e+03 -2.17625586e+03 -2.18285229e+03 -2.18881177e+03 -2.20534717e+03 -2.20463525e+03 -2.20390210e+03 -2.22308521e+03 -2.22474487e+03 -2.22901587e+03 -2.23154810e+03 -2.23664404e+03 -2.24994556e+03 -2.24446411e+03 -2.24180615e+03 -2.24871265e+03 -2.26377563e+03 -2.26238770e+03 -2.25054785e+03 -2.26256738e+03 -2.25722510e+03 -2.25166260e+03 -2.26676978e+03 -2.27897485e+03 -2.26784399e+03 -2.26234888e+03 -2.26364282e+03 -2.26952295e+03 -2.26926733e+03 -2.26676099e+03 -2.25825366e+03 -2.25671729e+03 -2.25438623e+03 -2.25023608e+03 -2.24661084e+03 -2.24945435e+03 -2.24519751e+03 -2.22527295e+03 -2.23129932e+03 -2.23655151e+03 -2.22185181e+03 -2.21205005e+03 -2.21320117e+03 -2.20652490e+03 -2.19390967e+03 -2.19266602e+03 -2.18210986e+03 -2.18056201e+03 -2.16814209e+03 -2.15729834e+03 -2.15326343e+03 -2.14832397e+03 -2.13481860e+03 -2.11517212e+03 -2.11195630e+03 -2.10888330e+03 -2.08933984e+03 -2.07836719e+03 -2.07471411e+03 -2.06809424e+03 -2.04793274e+03 -2.02874927e+03 -2.02334790e+03 -2.01479895e+03 -1.99232166e+03 -1.98170386e+03 -1.97816748e+03 -1.95826721e+03 -1.93825403e+03 -1.92864966e+03 -1.91415356e+03 -1.89813464e+03 -1.88931494e+03 -1.86609521e+03 -1.84904443e+03 -1.83808032e+03 -1.82117517e+03 -1.80639490e+03 -1.78688428e+03 -1.76515027e+03 -1.74758606e+03 -1.73691687e+03 -1.71441040e+03 -1.69463660e+03 -1.68190881e+03 -1.66092151e+03 -1.63848926e+03 -1.61968005e+03 -1.60274451e+03 -1.58131543e+03 -1.56285559e+03 -1.54594849e+03 -1.52308838e+03 -1.50034253e+03 -1.47433508e+03 -1.45806152e+03 -1.43685706e+03 -1.41486255e+03 -1.39839014e+03 -1.37370178e+03 -1.34788843e+03 -1.32427661e+03 -1.30601074e+03 -1.28189514e+03 -1.25608875e+03 -1.23603931e+03 -1.21243896e+03 -1.18725635e+03 -1.16450500e+03 -1.14138477e+03 -1.11791895e+03 -1.09223535e+03 -1.06608789e+03 -1.04258044e+03 -1.01965540e+03 -9.94476074e+02 -9.66655396e+02 -9.42501770e+02 -9.18434387e+02 -8.92471008e+02 -8.66931335e+02 -8.41053650e+02 -8.15460083e+02 -7.89077209e+02 -7.62610168e+02 -7.36994385e+02 -7.10382202e+02 -6.83938171e+02 -6.57194275e+02 -6.30500793e+02 -6.04297302e+02 -5.77018555e+02 -5.49852112e+02 -5.23250183e+02 -4.95882080e+02 -4.68601379e+02 -4.41670929e+02 -4.14402161e+02 -3.86956421e+02 -3.59556519e+02 -3.32037781e+02 -3.04323486e+02 -2.76729279e+02 -2.49304199e+02 -2.21605820e+02 -1.93948257e+02 -1.66191498e+02 -1.38435547e+02 -1.10703278e+02 -8.28843231e+01 -5.51028214e+01 -2.73175335e+01 5.28168678e-01 2.83373299e+01 5.60822716e+01 8.39045486e+01 1.11708206e+02 1.39403122e+02 1.67213562e+02 1.94944687e+02 2.22637772e+02 2.50413025e+02 2.77931427e+02 3.05316895e+02 3.32912048e+02 3.60457153e+02 3.87984344e+02 4.15628632e+02 4.42431732e+02 4.69668884e+02 4.97582336e+02 5.24182007e+02 5.50908386e+02 5.77969116e+02 6.04580139e+02 6.31673706e+02 6.58398132e+02 6.84914307e+02 7.11450073e+02 7.38040710e+02 7.63647644e+02 7.89260010e+02 8.15654785e+02 8.42761230e+02 8.68384033e+02 8.93763916e+02 9.18212769e+02 9.43601074e+02 9.69424744e+02 9.94199646e+02 1.01977338e+03 1.04442993e+03 1.06866235e+03 1.09266724e+03 1.11757666e+03 1.14157837e+03 1.16624744e+03 1.18942297e+03 1.21186963e+03 1.23668811e+03 1.25664062e+03 1.28154761e+03 1.30723315e+03 1.32702185e+03 1.35089539e+03 1.37268188e+03 1.39335120e+03 1.42042285e+03 1.43761377e+03 1.45897229e+03 1.48462366e+03 1.50075903e+03 1.52091406e+03 1.54142896e+03 1.55778479e+03 1.58251733e+03 1.60716174e+03 1.61818140e+03 1.63988721e+03 1.66255212e+03 1.68133545e+03 1.69841382e+03 1.71361536e+03 1.73443787e+03 1.75375574e+03 1.77163074e+03 1.78741833e+03 1.80259045e+03 1.81903564e+03 1.83592334e+03 1.85075256e+03 1.86826306e+03 1.88703735e+03 1.89790344e+03 1.91596960e+03 1.93012024e+03 1.94364136e+03 1.95850220e+03 1.97614404e+03 1.99036829e+03 1.99374646e+03 2.01264294e+03 2.03119910e+03 2.03246338e+03 2.04639819e+03 2.06501538e+03 2.06520850e+03 2.08056372e+03 2.09845166e+03 2.09986670e+03 2.11523584e+03 2.13183594e+03 2.13252002e+03 2.14355518e+03 2.15560571e+03 2.15895093e+03 2.16536694e+03 2.17249048e+03 2.18357251e+03 2.18688721e+03 2.20015112e+03 2.20328760e+03 2.20869287e+03 2.22197021e+03 2.22460498e+03 2.23143677e+03 2.22602612e+03 2.23343555e+03 2.25519360e+03 2.24638062e+03 2.24101587e+03 2.25163550e+03 2.26040601e+03 2.26057812e+03 2.25196948e+03 2.25868579e+03 2.26495923e+03 2.25475513e+03 2.26690527e+03 2.27207764e+03 2.27055493e+03 2.26312573e+03 2.27073560e+03 2.26375635e+03 2.26102588e+03 2.26715210e+03 2.26806934e+03 2.26126660e+03 2.25034106e+03 2.24965088e+03 2.24698389e+03 2.24503247e+03 2.24412866e+03 2.23053247e+03 2.23056738e+03 2.23675439e+03 2.22405566e+03 2.21338696e+03 2.21207202e+03 2.20810547e+03 2.19742480e+03 2.18980811e+03 2.18405151e+03 2.17942310e+03 2.17051074e+03 2.15859839e+03 2.15484180e+03 2.14987500e+03 2.13429639e+03 2.11699438e+03 2.11177173e+03 2.10865918e+03 2.09159839e+03 2.07650195e+03 2.07627075e+03 2.06645288e+03 2.04750525e+03 2.03042114e+03 2.02398364e+03 2.01383081e+03 1.99470471e+03 1.98440784e+03 1.97686633e+03 1.95808105e+03 1.93932666e+03 1.93086011e+03 1.91421423e+03 1.89652563e+03 1.88978662e+03 1.86634131e+03 1.84918420e+03 1.83806934e+03 1.82052100e+03 1.80585803e+03 1.78786743e+03 1.76487463e+03 1.74908618e+03 1.73550195e+03 1.71341870e+03 1.69489844e+03 1.68175220e+03 1.66086414e+03 1.64087585e+03 1.62033801e+03 1.60245764e+03 1.58199060e+03 1.56245337e+03 1.54472644e+03 1.52214734e+03 1.50053125e+03 1.47554260e+03 1.45940186e+03 1.43693628e+03 1.41352209e+03 1.39731262e+03 1.37341150e+03 1.34865149e+03 1.32448364e+03 1.30576770e+03 1.28147192e+03 1.25700684e+03 1.23731360e+03 1.21188745e+03 1.18686499e+03 1.16462280e+03 1.14130981e+03 1.11751672e+03 1.09227185e+03 1.06653955e+03 1.04259937e+03 1.02030060e+03 9.94324585e+02 9.67025635e+02 9.42134277e+02 9.17822083e+02 8.92707764e+02 8.66969910e+02 8.40942017e+02 8.15361023e+02 7.89075073e+02 7.62580017e+02 7.36738342e+02 7.10296143e+02 6.84004517e+02 6.57254761e+02 6.30392700e+02 6.04287903e+02 5.77050232e+02 5.49974365e+02 5.23312744e+02 4.95967651e+02 4.68556152e+02 4.41688263e+02 4.14440125e+02 3.86946625e+02 3.59551544e+02 3.32015228e+02 3.04398102e+02 2.76809265e+02 2.49300171e+02 2.21597733e+02 1.93944199e+02 1.66182266e+02 1.38462250e+02 1.10769279e+02 8.29342499e+01 5.51251068e+01 2.73602428e+01 -4.92171824e-01 -2.83133869e+01 -5.60514030e+01 -8.38604126e+01 -1.11669876e+02 -1.39403366e+02 -1.67215668e+02 -1.95011108e+02 -2.22690720e+02 -2.50370285e+02 -2.77923004e+02 -3.05373169e+02 -3.33017456e+02 -3.60494080e+02 -3.87889343e+02 -4.15538086e+02 -4.42588623e+02 -4.69908783e+02 -4.97439270e+02 -5.24183105e+02 -5.51385864e+02 -5.77861145e+02 -6.04506470e+02 -6.32000427e+02 -6.58495789e+02 -6.84910400e+02 -7.11525574e+02 -7.38211731e+02 -7.63952209e+02 -7.89477722e+02 -8.16010986e+02 -8.42779846e+02 -8.68047729e+02 -8.93921448e+02 -9.18823425e+02 -9.43488892e+02 -9.68724915e+02 -9.94518005e+02 -1.02069049e+03 -1.04517969e+03 -1.06867810e+03 -1.09136377e+03 -1.11755066e+03 -1.14285864e+03 -1.16503516e+03 -1.18896692e+03 -1.21370398e+03 -1.23699121e+03 -1.25652686e+03 -1.28233362e+03 -1.30590356e+03 -1.32616968e+03 -1.35188464e+03 -1.37295435e+03 -1.39365356e+03 -1.42019153e+03 -1.43750085e+03 -1.45866272e+03 -1.48595667e+03 -1.50093774e+03 -1.52102771e+03 -1.54214490e+03 -1.55790063e+03 -1.58237329e+03 -1.60649524e+03 -1.61956653e+03 -1.63991064e+03 -1.66356921e+03 -1.68003345e+03 -1.69896545e+03 -1.71566187e+03 -1.73442700e+03 -1.75352966e+03 -1.77197192e+03 -1.78556445e+03 -1.80288318e+03 -1.81990259e+03 -1.83955164e+03 -1.85182678e+03 -1.86818762e+03 -1.88735730e+03 -1.89540149e+03 -1.91411011e+03 -1.93027698e+03 -1.94710791e+03 -1.95717322e+03 -1.97366980e+03 -1.99059253e+03 -1.99533154e+03 -2.01300708e+03 -2.02922778e+03 -2.03348621e+03 -2.04744006e+03 -2.06254175e+03 -2.06673438e+03 -2.08295386e+03 -2.09611353e+03 -2.10159302e+03 -2.11503564e+03 -2.13249780e+03 -2.13017407e+03 -2.14220532e+03 -2.15097510e+03 -2.16182788e+03 -2.17056177e+03 -2.17410107e+03 -2.18338745e+03 -2.19165137e+03 -2.20548584e+03 -2.20655688e+03 -2.20629102e+03 -2.22375952e+03 -2.22157812e+03 -2.23152466e+03 -2.22959863e+03 -2.23311450e+03 -2.25089893e+03 -2.24467090e+03 -2.24007104e+03 -2.25530396e+03 -2.26141040e+03 -2.26165527e+03 -2.25431519e+03 -2.26008569e+03 -2.25961597e+03 -2.25284595e+03 -2.26841992e+03 -2.27502856e+03 -2.27103711e+03 -2.26666333e+03 -2.26551099e+03 -2.26523633e+03 -2.26058154e+03 -2.26776855e+03 -2.26337256e+03 -2.26079810e+03 -2.25255469e+03 -2.25060059e+03 -2.24928589e+03 -2.24536816e+03 -2.24295947e+03 -2.23146680e+03 -2.22653076e+03 -2.23205493e+03 -2.21925977e+03 -2.21198120e+03 -2.20914722e+03 -2.20529810e+03 -2.19606885e+03 -2.18877515e+03 -2.18468481e+03 -2.83426221e+03 -3.04165405e+03 -5.16631836e+03 -6.42406396e+03 -35367252. 13371977. 0. 313247168. 313247168. 313247168. 0. 0. -26495768. -26495768. -26495768. -112293200. -9462262. -1.39351426e+04 -5.82771094e+03 -5.03037256e+03 -2.80639062e+03 -2.62071484e+03 -1.93843701e+03 -1.91983911e+03 -1.90380481e+03 -1.88823950e+03 -1.86582263e+03 -1.85133093e+03 -1.84166821e+03 -1.82123572e+03 -1.80531885e+03 -1.78732324e+03 -1.76612439e+03 -1.74975354e+03 -1.73381177e+03 -1.71387451e+03 -1.69295032e+03 -1.67886877e+03 -1.66124707e+03 -1.64137158e+03 -1.62254211e+03 -1.60300098e+03 -1.58151086e+03 -1.56064404e+03 -1.54272375e+03 -1.52651929e+03 -1.50381689e+03 -1.47944080e+03 -1.46022546e+03 -1.43588770e+03 -1.41534277e+03 -1.39792749e+03 -1.37359583e+03 -1.34924915e+03 -1.32394824e+03 -1.30658691e+03 -1.28224622e+03 -1.25495068e+03 -1.23614551e+03 -1.21300256e+03 -1.18838391e+03 -1.16533350e+03 -1.14079199e+03 -1.11782922e+03 -1.09185193e+03 -1.06660291e+03 -1.04359570e+03 -1.02041699e+03 -9.94272766e+02 -9.67648499e+02 -9.42699158e+02 -9.17801270e+02 -8.93291199e+02 -8.66440918e+02 -8.40258240e+02 -8.15873108e+02 -7.89229614e+02 -7.62532227e+02 -7.36810120e+02 -7.10408875e+02 -6.84109375e+02 -6.57681274e+02 -6.30633972e+02 -6.04489746e+02 -5.77100708e+02 -5.49846008e+02 -5.23344910e+02 -4.95829803e+02 -4.68626587e+02 -4.41626953e+02 -4.14474976e+02 -3.87254517e+02 -3.59237305e+02 -3.31338226e+02 -3.04021606e+02 -2.76985596e+02 -2.49706131e+02 -2.21915253e+02 -1.94248306e+02 -1.66356201e+02 -1.38457291e+02 -1.10265488e+02 -8.21267700e+01 -5.51945992e+01 -1.38326523e+02 1.09747508e+05 1.75697388e+02 4.29269600e+01 6.21981392e+01 1.72900681e+02 2.14276428e+02 2.58012482e+02 3.00836365e+02 3.38621918e+02 3.80103485e+02 4.22177917e+02 4.62498566e+02 5.04819305e+02 5.49298157e+02 5.34971069e+02 4.13937256e+02 4.42078796e+02 4.68038574e+02 4.94488708e+02 5.21081360e+02 5.48764709e+02 5.75588806e+02 6.02147095e+02 6.28652100e+02 6.54780701e+02 6.81294983e+02 7.07559021e+02 7.33414062e+02 7.59181946e+02 7.85104370e+02 8.11486572e+02 8.38059509e+02 8.62325500e+02 8.87681335e+02 9.12118286e+02 9.37066895e+02 9.62757446e+02 9.87582703e+02 1.01293408e+03 1.03758191e+03 1.06154504e+03 1.08514941e+03 1.10937720e+03 1.13346301e+03 1.15780054e+03 1.18224670e+03 1.20417505e+03 1.22783911e+03 1.24895996e+03 1.27251294e+03 1.29667236e+03 1.31734094e+03 1.34001111e+03 1.36147351e+03 1.38438806e+03 1.40764893e+03 1.42854724e+03 1.44705469e+03 1.47057861e+03 1.49121423e+03 1.51076440e+03 1.53029053e+03 1.54845825e+03 1.57003210e+03 1.59229431e+03 1.60845459e+03 1.62886035e+03 1.65091614e+03 1.66659082e+03 1.68370837e+03 1.70149792e+03 1.72164355e+03 1.74011389e+03 1.75394531e+03 1.77114221e+03 1.78820752e+03 1.80466394e+03 1.82390723e+03 1.83405066e+03 1.84888647e+03 2.42571460e+03 4.44642529e+03 5.53179297e+03 -2931310. 118345432. 0. 5.37770650e+06 5.37770650e+06 5.37770650e+06 0. 13341798. 13341798. 58420816. -948973952. -70596080. -38501324. -38501324. 0. 59017032. 2.41368164e+04 5.04653711e+03 2.93191870e+03 2.77904932e+03 2.14198438e+03 2.15245215e+03 2.15374976e+03 2.16069189e+03 2.17495312e+03 2.17989478e+03 2.19045117e+03 2.19797534e+03 2.19975122e+03 2.20481836e+03 2.20978345e+03 2.21261060e+03 2.21523389e+03 2.22399194e+03 2.22578833e+03 2.22575000e+03 2.23400952e+03 2.23909351e+03 2.23882642e+03 2.23846533e+03 2.23858203e+03 2.24052222e+03 2.24044897e+03 2.24413501e+03 2.24916699e+03 2.24395215e+03 2.24469238e+03 2.25271826e+03 2.23930786e+03 2.24341870e+03 2.24148975e+03 2.23755151e+03 2.23877808e+03 2.23823364e+03 2.23421045e+03 2.22814453e+03 2.22758569e+03 2.22166113e+03 2.21397510e+03 2.21389795e+03 2.21072827e+03 2.19890771e+03 2.19312646e+03 2.19280493e+03 2.18357056e+03 2.17892334e+03 2.17050635e+03 2.16325635e+03 2.16055200e+03 2.14621777e+03 2.13958838e+03 2.13474194e+03 2.12240308e+03 2.11236743e+03 2.09981641e+03 2.09390015e+03 2.08353442e+03 2.06907300e+03 2.06123096e+03 2.05623315e+03 2.04632446e+03 2.02704822e+03 2.01438525e+03 2.00931226e+03 1.99204688e+03 1.97438208e+03 1.96283057e+03 1.95519116e+03 1.93962927e+03 1.92225061e+03 1.91316846e+03 1.89459741e+03 1.88054199e+03 1.86989673e+03 1.84887585e+03 1.83195789e+03 1.81762305e+03 1.80126453e+03 1.78716016e+03 1.76851953e+03 1.75192310e+03 1.73607446e+03 1.71692371e+03 1.69625598e+03 1.67704199e+03 1.66302380e+03 1.64438257e+03 1.62476233e+03 1.60443872e+03 1.58700134e+03 1.56553235e+03 1.54677600e+03 1.52835608e+03 1.50566968e+03 1.48462354e+03 1.46312671e+03 1.44408948e+03 1.42259705e+03 1.40140930e+03 1.38182410e+03 1.35780298e+03 1.33410657e+03 1.31186304e+03 1.29038916e+03 1.26819458e+03 1.24543103e+03 1.22382556e+03 1.19932629e+03 1.17525500e+03 1.15159021e+03 1.12871509e+03 1.10564844e+03 1.07972400e+03 1.05525647e+03 1.03134363e+03 1.00829974e+03 9.82780579e+02 9.57268616e+02 9.32103943e+02 9.06345947e+02 8.81899353e+02 8.57205383e+02 8.31878845e+02 8.05217346e+02 7.79597168e+02 7.53782593e+02 7.27980896e+02 7.01686096e+02 6.75328247e+02 6.48949402e+02 6.22676453e+02 5.96326965e+02 5.69589172e+02 5.42716248e+02 5.15937317e+02 4.89380920e+02 4.62214722e+02 4.35286499e+02 4.08278137e+02 3.80997864e+02 3.53930542e+02 3.26621857e+02 2.99340881e+02 2.71956665e+02 2.44588654e+02 2.17254440e+02 1.89807816e+02 1.62265106e+02 1.34787613e+02 1.07293388e+02 7.97377319e+01 5.21882324e+01 2.46302776e+01 -2.92454386e+00 -3.05047493e+01 -5.80534668e+01 -8.56058350e+01 -1.13124382e+02 -1.40568420e+02 -1.68105865e+02 -1.95547043e+02 -2.23036560e+02 -2.50572922e+02 -2.77873138e+02 -3.05051178e+02 -3.32323669e+02 -3.59670502e+02 -3.86973785e+02 -4.14245972e+02 -4.40883453e+02 -4.67930969e+02 -4.94963654e+02 -5.21662903e+02 -5.48773499e+02 -5.74923035e+02 -6.01531433e+02 -6.28501038e+02 -6.54742004e+02 -6.81288452e+02 -7.07484131e+02 -7.33340149e+02 -7.59150452e+02 -7.84712097e+02 -8.10819824e+02 -8.37774048e+02 -8.62589600e+02 -8.87278442e+02 -9.12030640e+02 -9.37256897e+02 -9.62739990e+02 -9.87640259e+02 -1.01277740e+03 -1.03753735e+03 -1.06109338e+03 -1.08423901e+03 -1.10968469e+03 -1.13348047e+03 -1.15765125e+03 -1.18174597e+03 -1.20367725e+03 -1.22755615e+03 -1.24885168e+03 -1.27270154e+03 -1.29428381e+03 -1.31647192e+03 -1.33947241e+03 -1.36243140e+03 -1.38530908e+03 -1.40654712e+03 -1.42691528e+03 -1.44772034e+03 -1.47124829e+03 -1.49113977e+03 -1.51005811e+03 -1.53079700e+03 -1.54894983e+03 -1.56898108e+03 -1.59125098e+03 -1.61017981e+03 -1.62817468e+03 -1.64929102e+03 -1.66682678e+03 -1.68314172e+03 -1.70177576e+03 -1.72064673e+03 -1.74098547e+03 -1.75276013e+03 -1.77089929e+03 -1.78906897e+03 -1.80223865e+03 -1.82426428e+03 -1.83632312e+03 -1.85042419e+03 -1.87097314e+03 -1.88284717e+03 -1.89605713e+03 -1.91075256e+03 -1.92919739e+03 -1.94092432e+03 -1.95636975e+03 -1.97181592e+03 -1.98054114e+03 -1.99429028e+03 -2.00774219e+03 -2.01738708e+03 -2.03082153e+03 -2.04390601e+03 -2.05178394e+03 -2.06326953e+03 -2.07515039e+03 -2.08390210e+03 -2.09783716e+03 -2.10759204e+03 -2.11417358e+03 -2.12365991e+03 -2.12829541e+03 -2.14130225e+03 -2.15625000e+03 -2.15054077e+03 -2.16619727e+03 -2.17824927e+03 -2.17929272e+03 -2.18244263e+03 -2.19462720e+03 -2.20400562e+03 -2.20239062e+03 -2.20762036e+03 -2206. -2.22063477e+03 -2.22697485e+03 -2.22467017e+03 -2.22217163e+03 -2.22743433e+03 -2.24210132e+03 -2.23785571e+03 -2.23134424e+03 -2.23592627e+03 -2.24130225e+03 -2.23915308e+03 -2.24251880e+03 -2.25185107e+03 -2.24758887e+03 -2.24041504e+03 -2.24731250e+03 -2.24326416e+03 -2.24801343e+03 -2.24548755e+03 -2.23744873e+03 -2.23516187e+03 -2.23918628e+03 -2.22854785e+03 -2.22560156e+03 -2.22675757e+03 -2.21989282e+03 -2.21054541e+03 -2.21056567e+03 -2.21138062e+03 -2.20239575e+03 -2.19270020e+03 -2.19311304e+03 -2.18466089e+03 -2.17693384e+03 -2.16907251e+03 -2.16235840e+03 -2.16169312e+03 -2.14799829e+03 -2.13691235e+03 -2.13755859e+03 -2.12490161e+03 -2.11123022e+03 -2.09869873e+03 -2.09372925e+03 -2.08725952e+03 -2.07112842e+03 -2.06471143e+03 -2.05812305e+03 -2.04177661e+03 -2.02517542e+03 -2.01277759e+03 -2.00855994e+03 -1.99574927e+03 -1.97376416e+03 -1.96089038e+03 -1.95772363e+03 -1.94158362e+03 -1.92120557e+03 -1.91126648e+03 -1.89437500e+03 -1.88140686e+03 -1.87128381e+03 -1.84815295e+03 -1.83199219e+03 -1.81824951e+03 -1.80063940e+03 -1.78678723e+03 -1.76975842e+03 -1.75003357e+03 -1.73252234e+03 -1.71841760e+03 -1.69824390e+03 -1.67724133e+03 -1.66173718e+03 -1.64381763e+03 -1.62472937e+03 -1.60423047e+03 -1.58637964e+03 -1.56518347e+03 -1.54656372e+03 -1.52870728e+03 -1.50677356e+03 -1.48423718e+03 -1.46268237e+03 -1.44281921e+03 -1.42207153e+03 -1.40314893e+03 -1.38148682e+03 -1.35673730e+03 -1.33458105e+03 -1.31191553e+03 -1.29047498e+03 -1.26801416e+03 -1.24446582e+03 -1.22256018e+03 -1.19902332e+03 -1.17583850e+03 -1.15103149e+03 -1.12866589e+03 -1.10611218e+03 -1.07938562e+03 -1.05462207e+03 -1.03153174e+03 -1.00748547e+03 -9.82728699e+02 -9.56880066e+02 -9.32268005e+02 -9.07118774e+02 -8.81555603e+02 -8.57040771e+02 -8.31947021e+02 -8.05317017e+02 -7.79429382e+02 -7.53627075e+02 -7.27795410e+02 -7.01723389e+02 -6.75635864e+02 -6.49079651e+02 -6.22512695e+02 -5.96315552e+02 -5.69334167e+02 -5.42600220e+02 -5.16055237e+02 -4.89312561e+02 -4.62266449e+02 -4.35279572e+02 -4.08197632e+02 -3.80968414e+02 -3.53914124e+02 -3.26657837e+02 -2.99324677e+02 -2.71899414e+02 -2.44607590e+02 -2.17257431e+02 -1.89817688e+02 -1.62311615e+02 -1.34804352e+02 -1.07301765e+02 -7.97615280e+01 -5.22188759e+01 -2.46747665e+01 2.89399838e+00 3.04516907e+01 5.79644127e+01 8.55270996e+01 1.13060150e+02 1.40531555e+02 1.68088898e+02 1.95528687e+02 2.23029434e+02 2.50502197e+02 2.77774658e+02 3.05002106e+02 3.32250458e+02 3.59523804e+02 3.86845886e+02 4.14237274e+02 4.40749237e+02 4.67690643e+02 4.95138855e+02 5.21672302e+02 5.48407349e+02 5.75230164e+02 6.01664062e+02 6.28099976e+02 6.54582336e+02 6.81181213e+02 7.07285278e+02 7.33137451e+02 7.59066528e+02 7.84467834e+02 8.10846191e+02 8.37697571e+02 8.62328735e+02 8.87322266e+02 9.11566711e+02 9.37248779e+02 9.62868835e+02 9.87643005e+02 1.01295142e+03 1.03700745e+03 1.06126587e+03 1.08476489e+03 1.10902563e+03 1.13325806e+03 1.15756824e+03 1.18086829e+03 1.20395947e+03 1.22687097e+03 1.24817090e+03 1.27225818e+03 1.29604773e+03 1.31742334e+03 1.33931848e+03 1.36141211e+03 1.38399939e+03 1.40725793e+03 1.42857898e+03 1.44742896e+03 1.46970068e+03 1.49017920e+03 1.50833875e+03 1.52951074e+03 1.54865479e+03 1.56915918e+03 1.59041846e+03 1.60877710e+03 1.62969031e+03 1.64948364e+03 1.66608862e+03 1.68311121e+03 1.69992065e+03 1.72175085e+03 1.74161328e+03 1.75348315e+03 1.77101367e+03 1.78656750e+03 1.80286804e+03 1.82389795e+03 1.83726160e+03 1.85157471e+03 1.87002112e+03 1.88104517e+03 1.89756519e+03 1.91253357e+03 1.92874280e+03 1.94028625e+03 1.95741907e+03 1.97268420e+03 1.97675818e+03 1.99550940e+03 2.01137561e+03 2.01707092e+03 2.03219153e+03 2.04712195e+03 2.05332202e+03 2.06326562e+03 2.07454077e+03 2.08115723e+03 2.09507690e+03 2.11190527e+03 2.11385425e+03 2.12353418e+03 2.13028076e+03 2.14282397e+03 2.15565698e+03 2.15309937e+03 2.16365405e+03 2.17462695e+03 2.17933472e+03 2.18334863e+03 2.19687915e+03 2.19814673e+03 2.20427222e+03 2.20540430e+03 2.20893799e+03 2.21926392e+03 2.22871021e+03 2.22195776e+03 2.22150195e+03 2.23125513e+03 2.24291992e+03 2.23770068e+03 2.23365381e+03 2.23545190e+03 2.23799951e+03 2.23924414e+03 2.24160303e+03 2.24923096e+03 2.24291089e+03 2.24186328e+03 2.24887085e+03 2.24443506e+03 2.24424390e+03 2.24520996e+03 2.24107178e+03 2.23951782e+03 2.23273877e+03 2.22791040e+03 2.22426099e+03 2.22556738e+03 2.22259131e+03 2.21197534e+03 2.20895215e+03 2.20937402e+03 2.20095752e+03 2.19718823e+03 2.19000659e+03 2.18538110e+03 2.17895605e+03 2.16677515e+03 2.15992480e+03 2.15990942e+03 2.14701587e+03 2.14032446e+03 2.13410181e+03 2.12395142e+03 2.11129175e+03 2.09991211e+03 2.09407617e+03 2.08391528e+03 2.06998193e+03 2.06063281e+03 2.05479761e+03 2.04578870e+03 2.02337708e+03 2.01572083e+03 2.00692175e+03 1.99305994e+03 1.97465979e+03 1.96285986e+03 1.95749146e+03 1.93943237e+03 1.92142578e+03 1.91013477e+03 1.89636890e+03 1.88166772e+03 1.87002905e+03 1.84859082e+03 1.83054150e+03 1.81890710e+03 1.80143140e+03 1.78609045e+03 1.76838708e+03 1.75060083e+03 1.73633948e+03 1.71725208e+03 1.69561902e+03 1.67803857e+03 1.66146228e+03 1.64311633e+03 1.62616370e+03 1.60550720e+03 1.58518982e+03 1.56516907e+03 1.54776721e+03 1.52757788e+03 1.50469568e+03 1.48441943e+03 1.46428064e+03 1.44301367e+03 1.42140405e+03 1.40192310e+03 1.38180444e+03 1.35641284e+03 1.33490833e+03 1.31303833e+03 1.29037463e+03 1.26832874e+03 1.24556067e+03 1.22217542e+03 1.19934558e+03 1.17564526e+03 1.15190662e+03 1.12796057e+03 1.10510535e+03 1.08006909e+03 1.05549243e+03 1.03160400e+03 1.00817963e+03 9.82833435e+02 9.56851257e+02 9.32156006e+02 9.06788940e+02 8.81858276e+02 8.57184387e+02 8.31805908e+02 8.05242249e+02 7.79562073e+02 7.53664001e+02 7.27944519e+02 7.01671509e+02 6.75404236e+02 6.48733826e+02 6.22504028e+02 5.96493835e+02 5.69403198e+02 5.42608032e+02 5.16142334e+02 4.89437805e+02 4.62264923e+02 4.35309174e+02 4.08282501e+02 3.80957916e+02 3.53867737e+02 3.26645844e+02 2.99395111e+02 2.71991577e+02 2.44633545e+02 2.17288681e+02 1.89832062e+02 1.62309860e+02 1.34823532e+02 1.07340675e+02 7.97822647e+01 5.22578964e+01 2.47309475e+01 -2.89486742e+00 -3.04419308e+01 -5.79525414e+01 -8.55119629e+01 -1.13018906e+02 -1.40544739e+02 -1.68119232e+02 -1.95584763e+02 -2.23033844e+02 -2.50440735e+02 -2.77764801e+02 -3.05024017e+02 -3.32298676e+02 -3.59553375e+02 -3.86829620e+02 -4.14089478e+02 -4.40815765e+02 -468. -4.95056488e+02 -5.21695801e+02 -5.48734619e+02 -5.74863647e+02 -6.01497498e+02 -6.28581299e+02 -6.54674255e+02 -6.81123901e+02 -7.07456238e+02 -7.33544922e+02 -7.59377808e+02 -7.84581726e+02 -8.10918396e+02 -8.37676025e+02 -8.62285767e+02 -8.87613831e+02 -9.11993591e+02 -9.37229919e+02 -9.62984924e+02 -9.87622253e+02 -1.01288092e+03 -1.03747876e+03 -1.06091223e+03 -1.08433374e+03 -1.10930432e+03 -1.13360754e+03 -1.15789343e+03 -1.18180212e+03 -1.20432837e+03 -1.22770569e+03 -1.24922998e+03 -1.27288989e+03 -1.29475073e+03 -1.31568262e+03 -1.33977661e+03 -1.36232629e+03 -1.38462598e+03 -1.40620325e+03 -1.42750354e+03 -1.44682239e+03 -1.47049890e+03 -1.49116724e+03 -1.50935046e+03 -1.53064099e+03 -1.54815271e+03 -1.56880090e+03 -1.59236426e+03 -1.60956042e+03 -1.62853467e+03 -1.64952637e+03 -1.66651270e+03 -1.68363245e+03 -1.70160461e+03 -1.71975317e+03 -1.74040332e+03 -1.75488232e+03 -1.77126709e+03 -1.78746472e+03 -1.80267078e+03 -1.82607019e+03 -1.83670300e+03 -1.85111194e+03 -1.87087891e+03 -1.88244043e+03 -1.89749561e+03 -1.91375427e+03 -1.92921753e+03 -1.94034692e+03 -1.95782568e+03 -1.97169653e+03 -1.98031067e+03 -1.99353210e+03 -2.01002686e+03 -2.01927710e+03 -2.03094202e+03 -2.04498389e+03 -2.05327515e+03 -2.06531836e+03 -2.07444629e+03 -2.08388184e+03 -2.09466553e+03 -2.11202466e+03 -2.11725635e+03 -2.12488696e+03 -2.13026270e+03 -2.14459424e+03 -2.15431934e+03 -2.14807007e+03 -2.16509888e+03 -2.17681250e+03 -2.18286646e+03 -2.18285254e+03 -2.19553564e+03 -2.20263477e+03 -2.20448657e+03 -2.20851392e+03 -2.20957104e+03 -2.21800024e+03 -2.22279102e+03 -2.22433374e+03 -2.22075049e+03 -2.23285596e+03 -2.24226782e+03 -2.23994238e+03 -2.23761841e+03 -2.23907520e+03 -2.23729077e+03 -2.24015259e+03 -2.24018799e+03 -2.25392554e+03 -2.24567212e+03 -2.24720264e+03 -2.25127661e+03 -2.24259106e+03 -2.24403076e+03 -2.24687573e+03 -2.24047461e+03 -2.23842285e+03 -2.23719458e+03 -2.22853589e+03 -2.23022729e+03 -2.22686572e+03 -2.22134302e+03 -2.21264307e+03 -2.21171216e+03 -2.20931543e+03 -2.20037085e+03 -2.19213379e+03 -2.18735522e+03 -2.18583765e+03 -2.17647290e+03 -2.16630005e+03 -2.16450537e+03 -2.15711035e+03 -2.14800781e+03 -2.75225269e+03 -2.85655127e+03 -5.13265820e+03 -5.69057520e+03 8.06064350e+06 -14210346. 313247168. 313247168. -6.37134750e+05 -6.37134750e+05 -14678920. -26495768. -26495768. 0. 0. 0. 66376160. 8495527. -5.67254590e+03 -5.01184180e+03 -2.94945605e+03 -2.77274927e+03 -2.50023511e+03 -1.87556189e+03 -1.85485364e+03 -1.83186145e+03 -1.81601587e+03 -1.80470996e+03 -1.79056360e+03 -1.77121912e+03 -1.75289050e+03 -1.73407166e+03 -1.71637732e+03 -1.69674451e+03 -1.67598767e+03 -1.66145825e+03 -1.64434009e+03 -1.62366455e+03 -1.60343262e+03 -1.58639514e+03 -1.56589429e+03 -1.54825183e+03 -1.53022595e+03 -1.50607593e+03 -1.48582727e+03 -1.46478845e+03 -1.44289087e+03 -1.42281055e+03 -1.40433740e+03 -1.38029297e+03 -1.35728455e+03 -1.33595044e+03 -1.31267456e+03 -1.29012439e+03 -1.26807617e+03 -1.24459375e+03 -1.22266809e+03 -1.20014026e+03 -1.17599292e+03 -1.15169397e+03 -1.12893018e+03 -1.10510571e+03 -1.07997705e+03 -1.05489551e+03 -1.03201428e+03 -1.00823328e+03 -9.82780701e+02 -9.57065735e+02 -9.32224121e+02 -9.07249878e+02 -8.82324036e+02 -8.56721130e+02 -8.31663513e+02 -8.05788818e+02 -7.79547058e+02 -7.53418762e+02 -7.27694885e+02 -7.01602295e+02 -6.75799133e+02 -6.49313721e+02 -6.22482117e+02 -5.96488586e+02 -5.69426331e+02 -5.42393188e+02 -5.16023071e+02 -4.89231598e+02 -4.62241577e+02 -4.35464722e+02 -4.07640259e+02 -5.20790894e+02 -3.52969849e+02 -4.88941162e+02 -4.58323120e+02 -3.22619568e+02 -2.88789764e+02 -2.17765823e+02 -1.89935089e+02 -1.61756485e+02 -1.34591064e+02 -1.07457153e+02 -7.98144836e+01 -5.19618340e+01 -1.28905792e+02 451912608. 2.44351593e+02 2.35944881e+01 -2.33366337e+01 4.62254120e+02 4.13660980e+02 3.64820526e+02 403951. -1.06677445e+05 8.79583740e+02 7.12618408e+02 4.50810059e+02 4.91542328e+02 4.41998840e+02 4.72296753e+02 4.08224762e+02 4.36139008e+02 4.62314545e+02 4.88662933e+02 5.15279907e+02 5.42420349e+02 5.69014648e+02 5.95491089e+02 6.21640564e+02 6.47782288e+02 6.74145386e+02 7.00231384e+02 7.25763000e+02 7.51710144e+02 7.77299805e+02 8.03296631e+02 8.30177307e+02 8.54136047e+02 8.78539795e+02 9.03249573e+02 9.28461853e+02 9.53886108e+02 9.78015686e+02 1.00432623e+03 1.02939734e+03 1.05132996e+03 1.07483459e+03 1.10061914e+03 1.12417419e+03 1.14607178e+03 1.17047729e+03 1.19509070e+03 1.21725708e+03 1.23914551e+03 1.26093567e+03 1.28441577e+03 1.30634534e+03 1.32873401e+03 1.35172559e+03 1.37172742e+03 1.39420947e+03 1.41464331e+03 1.43617578e+03 1.45866162e+03 1.47818970e+03 1.49715662e+03 1.51950256e+03 1.53775281e+03 1.55719031e+03 1.57842908e+03 1.59440894e+03 1.61500623e+03 1.63630823e+03 1.65539038e+03 1.67071497e+03 1.68604871e+03 1.70755518e+03 1.72455579e+03 1.73979944e+03 1.75913586e+03 1.77282764e+03 1.79023706e+03 2.35734204e+03 2.54632788e+03 2.76781763e+03 4.67883545e+03 2.49676152e+04 -23354014. 0. 0. -65236368. -65236368. -65236368. 0. 0. 13341798. 13341798. 13341798. 0. -38501324. -38501324. -16758791. -19630806. 6.20288672e+03 4.95314014e+03 2.72312183e+03 2.10696802e+03 2.11639868e+03 2.12826416e+03 2.13442017e+03 2.14160864e+03 2.14553491e+03 2.16005078e+03 2.16144604e+03 2.16836084e+03 2.18370947e+03 2.18518384e+03 2.18454541e+03 2.19330298e+03 2.19469751e+03 2.20060498e+03 2.20819800e+03 2.20787769e+03 2.20821362e+03 2.21368604e+03 2.22455908e+03 2.22274878e+03 2.22147510e+03 2.22151929e+03 2.22706055e+03 2.22898438e+03 2.22624292e+03 2.22596631e+03 2.23078198e+03 2.23277686e+03 2.22658472e+03 2.23128979e+03 2.22853296e+03 2.22715039e+03 2.22540308e+03 2.22177148e+03 2.22176050e+03 2.21559766e+03 2.21492334e+03 2.21484839e+03 2.20515283e+03 2.20347095e+03 2.19785767e+03 2.19656494e+03 2.18839258e+03 2.18295117e+03 2.17196533e+03 2.16915649e+03 2.16949268e+03 2.15518994e+03 2.14767456e+03 2.14764355e+03 2.13157129e+03 2.12520410e+03 2.11977368e+03 2.10969678e+03 2.09578125e+03 2.08928369e+03 2.08304980e+03 2.06768408e+03 2.05488135e+03 2.05231299e+03 2.04480530e+03 2.03016150e+03 2.01064001e+03 2.00715491e+03 1.99648376e+03 1.98110596e+03 1.96678833e+03 1.95132214e+03 1.93881836e+03 1.92854468e+03 1.90951660e+03 1.89233044e+03 1.88342249e+03 1.87379150e+03 1.85791797e+03 1.83913135e+03 1.82236792e+03 1.80619995e+03 1.79179114e+03 1.77611328e+03 1.75476318e+03 1.74326904e+03 1.72400378e+03 1.70401270e+03 1.68771350e+03 1.66932788e+03 1.65377991e+03 1.63497583e+03 1.61539624e+03 1.59443445e+03 1.57709009e+03 1.55659766e+03 1.53820007e+03 1.51948877e+03 1.49745264e+03 1.47628308e+03 1.45736804e+03 1.43575916e+03 1.41428210e+03 1.39353735e+03 1.37210889e+03 1.35019409e+03 1.32928210e+03 1.30615662e+03 1.28289258e+03 1.26170618e+03 1.23934937e+03 1.21566077e+03 1.19299622e+03 1.17091016e+03 1.14768066e+03 1.12245667e+03 1.09811609e+03 1.07449023e+03 1.05114490e+03 1.02660107e+03 1.00316449e+03 9.78428101e+02 9.53137634e+02 9.27979736e+02 9.02931824e+02 8.78192627e+02 8.53523682e+02 8.28552185e+02 8.02162781e+02 7.77064270e+02 7.51178162e+02 7.25070190e+02 6.99346191e+02 6.73436340e+02 6.46956116e+02 6.20720215e+02 5.94531982e+02 5.67918152e+02 5.41639160e+02 5.14976501e+02 4.88556885e+02 4.61810822e+02 4.34756653e+02 4.07779419e+02 3.80858093e+02 3.54066620e+02 3.26995392e+02 2.99974579e+02 2.72692474e+02 2.45451904e+02 2.18376740e+02 1.91090286e+02 1.63727936e+02 1.36440948e+02 1.09130859e+02 8.17726822e+01 5.44117966e+01 2.70508671e+01 -3.10839415e-01 -2.77015953e+01 -5.50628204e+01 -8.24190292e+01 -1.09750214e+02 -1.37021271e+02 -1.64354294e+02 -1.91609283e+02 -2.18958923e+02 -2.46240021e+02 -2.73359589e+02 -3.00399902e+02 -3.27407227e+02 -3.54646515e+02 -3.81815094e+02 -4.08715210e+02 -4.35303192e+02 -4.62021698e+02 -4.88937012e+02 -5.15838623e+02 -5.42238708e+02 -5.68508240e+02 -5.95265442e+02 -6.21615234e+02 -6.47518921e+02 -6.74020691e+02 -7.00175537e+02 -7.25829468e+02 -7.51791626e+02 -7.76812500e+02 -8.02999939e+02 -8.29202637e+02 -8.53610718e+02 -8.78763733e+02 -9.03727295e+02 -9.28685120e+02 -9.53862427e+02 -9.78398682e+02 -1.00365210e+03 -1.02799268e+03 -1.05144690e+03 -1.07586523e+03 -1.09975940e+03 -1.12351025e+03 -1.14680945e+03 -1.17087561e+03 -1.19351807e+03 -1.21711816e+03 -1.24040674e+03 -1.26136108e+03 -1.28338428e+03 -1.30535413e+03 -1.32834314e+03 -1.35237317e+03 -1.37316162e+03 -1.39335889e+03 -1.41415771e+03 -1.43602966e+03 -1.45844971e+03 -1.47715576e+03 -1.49692053e+03 -1.51848987e+03 -1.53761340e+03 -1.55751758e+03 -1.57782568e+03 -1.59498828e+03 -1.61508911e+03 -1.63730530e+03 -1.65544568e+03 -1.67014001e+03 -1.68752771e+03 -1.70707031e+03 -1.72273999e+03 -1.74063953e+03 -1.75931262e+03 -1.77339636e+03 -1.79048901e+03 -1.81070215e+03 -1.82505750e+03 -1.84033533e+03 -1.85156445e+03 -1.86533521e+03 -1.88693640e+03 -1.89763391e+03 -1.91713342e+03 -1.92900366e+03 -1.94217346e+03 -1.95938269e+03 -1.96777954e+03 -1.98027893e+03 -1.99093164e+03 -1.99872925e+03 -2.01532019e+03 -2.03144043e+03 -2.04141553e+03 -2.04939038e+03 -2.05400513e+03 -2.07308545e+03 -2.08206494e+03 -2.09417310e+03 -2.10292920e+03 -2.10443286e+03 -2.11388818e+03 -2.12609375e+03 -2.14151904e+03 -2.14309180e+03 -2.14881494e+03 -2.16333813e+03 -2.15967676e+03 -2.16493774e+03 -2.18730493e+03 -2.18744165e+03 -2.18405176e+03 -2.18952539e+03 -2.19152002e+03 -2.20064795e+03 -2.20966943e+03 -2.21313989e+03 -2.20924219e+03 -2.21374463e+03 -2.22415356e+03 -2.22647266e+03 -2.21780908e+03 -2.22038721e+03 -2.22746826e+03 -2.23019702e+03 -2.22921216e+03 -2.22661865e+03 -2.23247876e+03 -2.23219995e+03 -2.22401416e+03 -2.23120166e+03 -2.22778271e+03 -2.22940747e+03 -2.22511743e+03 -2.22083350e+03 -2.21550049e+03 -2.21535645e+03 -2.20946045e+03 -2.20878516e+03 -2.20459448e+03 -2.20006592e+03 -2.19926709e+03 -2.19663696e+03 -2.18807520e+03 -2.18439380e+03 -2.16657446e+03 -2.16883057e+03 -2.16991943e+03 -2.15398413e+03 -2.14865259e+03 -2.14487524e+03 -2.13403247e+03 -2.12528638e+03 -2.12060815e+03 -2.10771045e+03 -2.09960791e+03 -2.08446021e+03 -2.08209351e+03 -2.07115430e+03 -2.05526001e+03 -2.05240015e+03 -2.04199023e+03 -2.02966663e+03 -2.01178613e+03 -1.99777246e+03 -1.99770374e+03 -1.98522131e+03 -1.96159778e+03 -1.95042224e+03 -1.94438464e+03 -1.92642529e+03 -1.90994751e+03 -1.89390198e+03 -1.88144897e+03 -1.87454736e+03 -1.85685327e+03 -1.84090027e+03 -1.82154773e+03 -1.80675342e+03 -1.79203333e+03 -1.77458057e+03 -1.75709998e+03 -1.74204016e+03 -1.72219824e+03 -1.70546094e+03 -1.69092383e+03 -1.66951416e+03 -1.65336548e+03 -1.63317957e+03 -1.61543884e+03 -1.59386145e+03 -1.57565845e+03 -1.55678687e+03 -1.53837524e+03 -1.52016895e+03 -1.49731592e+03 -1.47563281e+03 -1.45706396e+03 -1.43540393e+03 -1.41369397e+03 -1.39334265e+03 -1.37198560e+03 -1.35058704e+03 -1.32845654e+03 -1.30658215e+03 -1.28473376e+03 -1.26079724e+03 -1.23788086e+03 -1.21515613e+03 -1.19298828e+03 -1.17024792e+03 -1.14722583e+03 -1.12226477e+03 -1.09823584e+03 -1.07564258e+03 -1.05117847e+03 -1.02592188e+03 -1.00316272e+03 -9.78632996e+02 -9.52970825e+02 -9.28053833e+02 -9.03102966e+02 -8.77952026e+02 -8.53689270e+02 -8.28197021e+02 -8.02281677e+02 -7.77255737e+02 -7.51000122e+02 -7.24833374e+02 -6.99370972e+02 -6.73661804e+02 -6.47121216e+02 -6.20533691e+02 -5.94371094e+02 -5.68052795e+02 -5.41624146e+02 -5.14796997e+02 -4.88553314e+02 -4.61884094e+02 -4.34709412e+02 -4.07715729e+02 -3.80829468e+02 -3.54035217e+02 -3.26977356e+02 -2.99959625e+02 -2.72662842e+02 -2.45480301e+02 -2.18387375e+02 -1.91086136e+02 -1.63720947e+02 -1.36405884e+02 -1.09125023e+02 -8.17699509e+01 -5.44011040e+01 -2.70493183e+01 3.11311841e-01 2.76693916e+01 5.50104065e+01 8.23824387e+01 1.09722466e+02 1.37030029e+02 1.64381973e+02 1.91625153e+02 2.18962738e+02 2.46190170e+02 2.73315948e+02 3.00404388e+02 3.27369476e+02 3.54596466e+02 3.81750580e+02 4.08701599e+02 4.35367004e+02 4.61909210e+02 4.88796753e+02 5.15715149e+02 5.42218750e+02 5.68864746e+02 5.95339600e+02 6.21450867e+02 6.47529541e+02 6.73837402e+02 7.00045227e+02 7.25828308e+02 7.51812073e+02 7.76854980e+02 8.02543518e+02 8.29545410e+02 8.53927429e+02 8.78160706e+02 9.02725281e+02 9.29062622e+02 9.54194885e+02 9.78046448e+02 1.00388934e+03 1.02860193e+03 1.05154285e+03 1.07456201e+03 1.10021338e+03 1.12493457e+03 1.14518005e+03 1.16933704e+03 1.19478223e+03 1.21703894e+03 1.23874377e+03 1.26113794e+03 1.28430322e+03 1.30648718e+03 1.32879297e+03 1.35150244e+03 1.37218188e+03 1.39404785e+03 1.41498938e+03 1.43581995e+03 1.45908667e+03 1.47720508e+03 1.49696692e+03 1.51682678e+03 1.53739587e+03 1.55816003e+03 1.57797009e+03 1.59523669e+03 1.61490271e+03 1.63607593e+03 1.65444775e+03 1.67100952e+03 1.68603528e+03 1.70746509e+03 1.72430737e+03 1.73996826e+03 1.75946301e+03 1.77192847e+03 1.79102258e+03 1.80859509e+03 1.82386719e+03 1.83828296e+03 1.85049207e+03 1.86923193e+03 1.88708801e+03 1.89967273e+03 1.91552148e+03 1.92665649e+03 1.94071521e+03 1.95647205e+03 1.96381995e+03 1.98155029e+03 1.99654456e+03 1.99719617e+03 2.01517468e+03 2.03296130e+03 2.03999451e+03 2.04916016e+03 2.05345337e+03 2.06840356e+03 2.08202979e+03 2.09506006e+03 2.10113599e+03 2.10440527e+03 2.11378198e+03 2.12616089e+03 2.13904980e+03 2.14160913e+03 2.14920044e+03 2.16209277e+03 2.16296802e+03 2.16627222e+03 2.18336084e+03 2.18440820e+03 2.18517700e+03 2.19359448e+03 2.19103125e+03 2.20197510e+03 2.21189502e+03 2.21011035e+03 2.20834106e+03 2.21401367e+03 2.22726855e+03 2.22542310e+03 2.21857690e+03 2.22126025e+03 2.22928467e+03 2.23013965e+03 2.22977173e+03 2.22834448e+03 2.23012354e+03 2.22726758e+03 2.22733667e+03 2.23074316e+03 2.22863159e+03 2.22684497e+03 2.22640918e+03 2.22145996e+03 2.22056396e+03 2.21300073e+03 2.21253979e+03 2.21057617e+03 2.20646167e+03 2.19705835e+03 2.19795215e+03 2.19005737e+03 2.18821167e+03 2.18431616e+03 2.16929614e+03 2.16740015e+03 2.16900781e+03 2.15284399e+03 2.14690332e+03 2.14414917e+03 2.13171338e+03 2.12817773e+03 2.12344287e+03 2.10605200e+03 2.09825806e+03 2.08937793e+03 2.08153711e+03 2.07115747e+03 2.05612012e+03 2.05085645e+03 2.04364539e+03 2.02569666e+03 2.01525354e+03 2.00347839e+03 1.99846021e+03 1.98225964e+03 1.96261780e+03 1.95241309e+03 1.94248926e+03 1.92795190e+03 1.91059058e+03 1.89238562e+03 1.88479724e+03 1.87484387e+03 1.85744128e+03 1.83916882e+03 1.82209888e+03 1.80532568e+03 1.79217578e+03 1.77582739e+03 1.75614966e+03 1.74350989e+03 1.72417175e+03 1.70455103e+03 1.68896167e+03 1.66936963e+03 1.65350635e+03 1.63240479e+03 1.61539954e+03 1.59394409e+03 1.57482532e+03 1.55637012e+03 1.53859241e+03 1.51972778e+03 1.49757495e+03 1.47639551e+03 1.45713123e+03 1.43522180e+03 1.41263013e+03 1.39368591e+03 1.37216016e+03 1.34965820e+03 1.32879382e+03 1.30780725e+03 1.28405615e+03 1.26061206e+03 1.23891809e+03 1.21482629e+03 1.19213879e+03 1.17059326e+03 1.14774805e+03 1.12170752e+03 1.09788037e+03 1.07479224e+03 1.05108582e+03 1.02695239e+03 1.00337274e+03 9.78322571e+02 9.52857300e+02 9.27903015e+02 9.02752380e+02 8.78078674e+02 8.53647522e+02 8.28418213e+02 8.02226990e+02 7.76998230e+02 7.51158386e+02 7.24884094e+02 6.99274780e+02 6.73492981e+02 6.46872803e+02 6.20597107e+02 5.94437317e+02 5.67940552e+02 5.41607910e+02 5.14953369e+02 4.88609344e+02 4.61824890e+02 4.34759369e+02 4.07779755e+02 3.80833099e+02 3.53996063e+02 3.26958588e+02 2.99955170e+02 2.72705902e+02 2.45477493e+02 2.18387634e+02 1.91091461e+02 1.63744858e+02 1.36448517e+02 1.09145485e+02 8.17839203e+01 5.44461555e+01 2.70987511e+01 -3.19083124e-01 -2.76701832e+01 -5.50028725e+01 -8.23789825e+01 -1.09709991e+02 -1.37053101e+02 -1.64405762e+02 -1.91642151e+02 -2.18960388e+02 -2.46157806e+02 -2.73283295e+02 -3.00402466e+02 -3.27408173e+02 -3.54585876e+02 -3.81731995e+02 -4.08613464e+02 -4.35280701e+02 -4.62058014e+02 -4.88920990e+02 -5.15791870e+02 -5.42259644e+02 -5.68576233e+02 -5.95279968e+02 -6.21644226e+02 -6.47436462e+02 -6.73893982e+02 -7.00136169e+02 -7.26028503e+02 -7.51679077e+02 -7.76818909e+02 -8.03034607e+02 -8.29434265e+02 -8.53906616e+02 -8.78633179e+02 -9.03101624e+02 -9.28643127e+02 -9.54135803e+02 -9.78167908e+02 -1.00367468e+03 -1.02809106e+03 -1.05111194e+03 -1.07506116e+03 -1.09989319e+03 -1.12324158e+03 -1.14687000e+03 -1.17058228e+03 -1.19375537e+03 -1.21750452e+03 -1.23987097e+03 -1.26186731e+03 -1.28298059e+03 -1.30542883e+03 -1.32956116e+03 -1.35215918e+03 -1.37279980e+03 -1.39373267e+03 -1.41332849e+03 -1.43590356e+03 -1.46005054e+03 -1.47742468e+03 -1.49693933e+03 -1.51815234e+03 -1.53802710e+03 -1.55723572e+03 -1.57854919e+03 -1.59419458e+03 -1.61500684e+03 -1.63693176e+03 -1.65412964e+03 -1.67102197e+03 -1.68619751e+03 -1.70566870e+03 -1.72397803e+03 -1.74134851e+03 -1.75859814e+03 -1.77175513e+03 -1.78997559e+03 -1.81152185e+03 -1.82436157e+03 -1.83868909e+03 -1.85099646e+03 -1.86695203e+03 -1.88747498e+03 -1.89857312e+03 -1.91377502e+03 -1.92686682e+03 -1.94391260e+03 -1.96043567e+03 -1.96700256e+03 -1.97821741e+03 -1.99123450e+03 -2.00168347e+03 -2.01467773e+03 -2.02927356e+03 -2.04054614e+03 -2.04817163e+03 -2.05606104e+03 -2.06919824e+03 -2.08273828e+03 -2.09308667e+03 -2.10057983e+03 -2.10687549e+03 -2.11044653e+03 -2.12929150e+03 -2.13831812e+03 -2.14018652e+03 -2.15000635e+03 -2.16266162e+03 -2.16416528e+03 -2.16184814e+03 -2.18215869e+03 -2.18632617e+03 -2.18435449e+03 -2.18929980e+03 -2.19532080e+03 -2.20471582e+03 -2.21159888e+03 -2.20994287e+03 -2.20938135e+03 -2.21335400e+03 -2.22449316e+03 -2.22618457e+03 -2.22094775e+03 -2.22451587e+03 -2.22615698e+03 -2.22953101e+03 -2.22922217e+03 -2.22739453e+03 -2.23281177e+03 -2.22863379e+03 -2.22968506e+03 -2.23128906e+03 -2.22575244e+03 -2.22747412e+03 -2.22554980e+03 -2.22402661e+03 -2.21868994e+03 -2.21771582e+03 -2.21200439e+03 -2.21141235e+03 -2.20476807e+03 -2.20066748e+03 -2.20198145e+03 -2.19401733e+03 -2.18779468e+03 -2.18620215e+03 -2.17048950e+03 -2.16870752e+03 -2.16703027e+03 -2.15303320e+03 -2.14933643e+03 -2.14581885e+03 -2.13510010e+03 -2.12186768e+03 -2.11778613e+03 -2.73516235e+03 -2.79100830e+03 -4.86475684e+03 -2.50525859e+04 7.77735450e+06 0. -6.37134750e+05 -6.37134750e+05 -14678920. -26495768. -26495768. 0. 0. 0. 0. 0. 4.85868050e+06 -7.34674875e+05 -7.55014453e+03 -6.48494775e+03 -4.70074902e+03 -2.79461694e+03 -2.55505420e+03 -2.33254590e+03 -1.81139172e+03 -1.79226990e+03 -1.77531348e+03 -1.75625793e+03 -1.74185828e+03 -1.72215332e+03 -1.70310144e+03 -1.69117688e+03 -1.67250281e+03 -1.65420178e+03 -1.63545776e+03 -1.61703223e+03 -1.59395532e+03 -1.57702148e+03 -1.55761841e+03 -1.53826099e+03 -1.51947607e+03 -1.49729956e+03 -1.47600842e+03 -1.45710620e+03 -1.43516187e+03 -1.41327844e+03 -1.39430652e+03 -1.37172681e+03 -1.35020691e+03 -1.32928308e+03 -1.30829993e+03 -1.28366211e+03 -1.26114990e+03 -1.23856934e+03 -1.21582166e+03 -1.19343164e+03 -1.17070398e+03 -1.14672961e+03 -1.12319177e+03 -1.09857544e+03 -1.07524866e+03 -1.05130212e+03 -1.02626196e+03 -1.00379797e+03 -9.78733032e+02 -9.52904602e+02 -9.27609924e+02 -9.03118713e+02 -8.78265381e+02 -8.52996765e+02 -8.27985901e+02 -8.02420959e+02 -7.77056702e+02 -7.50618225e+02 -7.24589050e+02 -6.99161560e+02 -6.73691101e+02 -6.47309387e+02 -6.20350464e+02 -5.94577454e+02 -5.68210266e+02 -5.41481628e+02 -5.14974976e+02 -4.88644104e+02 -4.62070557e+02 -4.35611450e+02 -4.07241272e+02 -7.79689819e+02 -5.38582397e+02 -9.85347778e+02 -1.17351672e+03 -5.67183167e+02 -4.89362854e+02 -3.31381622e+02 -2.22224808e+02 -2.45001556e+02 -2.25133224e+02 -1.64659683e+02 -1.22921494e+02 -8.01329727e+01 -2.02355988e+02 -1412612608. -13139850. -13139850. -1129175168. -277667808. -277667808. -277667808. 0. 0. -870164800. 3.62835767e+03 7.58924561e+02 4.89532837e+02 4.74846130e+02 4.91140350e+02 4.06874878e+02 4.34712738e+02 4.61025726e+02 4.87169708e+02 5.13582458e+02 5.40286072e+02 5.66911499e+02 5.92591858e+02 6.19022034e+02 6.45781738e+02 6.71034180e+02 6.96881531e+02 7.22867065e+02 7.48274963e+02 7.74341614e+02 7.99907654e+02 8.25823792e+02 8.51050537e+02 8.74570923e+02 8.99582397e+02 9.24934265e+02 9.49776245e+02 9.74155396e+02 9.99602722e+02 1.02383130e+03 1.04676917e+03 1.07104529e+03 1.09508069e+03 1.11872107e+03 1.14049524e+03 1.16555432e+03 1.18995605e+03 1.20992419e+03 1.23296643e+03 1.25582629e+03 1.28001965e+03 1.30171143e+03 1.32213757e+03 1.34513257e+03 1.36667383e+03 1.38644067e+03 1.40884167e+03 1.42961890e+03 1.45009814e+03 1.47045752e+03 1.49181860e+03 1.51366272e+03 1.53353381e+03 1.54891919e+03 1.56937024e+03 1.59128662e+03 1.60995447e+03 1.62551794e+03 1.64458008e+03 1.66732288e+03 1.67848291e+03 1.69854626e+03 1.71999341e+03 1.73055579e+03 1.75132532e+03 2.29929297e+03 2.47569678e+03 4.40069580e+03 6.13766260e+03 2.71402207e+04 20486864. 74596248. 0. -441762368. -441762368. -4.24307302e+09 -65236368. -65236368. 0. 0. 0. 0. 0. 0. -15470623. 2.44816973e+04 3.35657007e+03 4.92493115e+03 2.82141479e+03 2.68501367e+03 2.08826831e+03 2.09732837e+03 2.11230737e+03 2.11974487e+03 2.12652881e+03 2.13135449e+03 2.13725171e+03 2.14799609e+03 2.15588965e+03 2.15693286e+03 2.16661938e+03 2.17058105e+03 2.17372607e+03 2.18664038e+03 2.18558374e+03 2.19160034e+03 2.19900195e+03 2.19869653e+03 2.19820093e+03 2.20723120e+03 2.20912012e+03 2.21314990e+03 2.21718506e+03 2.21220532e+03 2.21646997e+03 2.22192822e+03 2.21511279e+03 2.21410913e+03 2.22022021e+03 2.21981152e+03 2.21783398e+03 2.21733643e+03 2.22298535e+03 2.22007690e+03 2.20674585e+03 2.21540503e+03 2.21256079e+03 2.19960205e+03 2.19955054e+03 2.20030469e+03 2.19530640e+03 2.19466553e+03 2.18730225e+03 2.18090405e+03 2.17428784e+03 2.17371240e+03 2.16061768e+03 2.15725903e+03 2.15922192e+03 2.14236670e+03 2.13929541e+03 2.13617896e+03 2.12417676e+03 2.11003687e+03 2.10012305e+03 2.10249927e+03 2.09112329e+03 2.07812427e+03 2.06916797e+03 2.05939844e+03 2.05038867e+03 2.04338184e+03 2.03400073e+03 2.01476965e+03 2.00754822e+03 1.99864954e+03 1.98873340e+03 1.97246826e+03 1.95733325e+03 1.94091516e+03 1.92970374e+03 1.91876978e+03 1.89912305e+03 1.88282178e+03 1.87548047e+03 1.86504626e+03 1.85064490e+03 1.83068848e+03 1.81395154e+03 1.79666589e+03 1.78319104e+03 1.76763379e+03 1.74567578e+03 1.73345105e+03 1.71600183e+03 1.69819434e+03 1.68270203e+03 1.65989612e+03 1.64397009e+03 1.62779004e+03 1.60636426e+03 1.58692542e+03 1.56876599e+03 1.54893335e+03 1.53064111e+03 1.51044800e+03 1.48953516e+03 1.46995361e+03 1.45151599e+03 1.42817651e+03 1.40709229e+03 1.38633923e+03 1.36450208e+03 1.34348206e+03 1.32354260e+03 1.30028345e+03 1.27628796e+03 1.25507788e+03 1.23381506e+03 1.21060327e+03 1.18665173e+03 1.16408923e+03 1.14106421e+03 1.11729736e+03 1.09337878e+03 1.06938428e+03 1.04565515e+03 1.02152643e+03 9.97717346e+02 9.73798035e+02 9.48416016e+02 9.22932922e+02 8.98644897e+02 8.73926758e+02 8.49138184e+02 8.23466003e+02 7.98312073e+02 7.73131958e+02 7.46760071e+02 7.21386597e+02 6.95628906e+02 6.69933838e+02 6.43830566e+02 6.17267822e+02 5.91347534e+02 5.64916992e+02 5.38764526e+02 5.12217224e+02 4.85527008e+02 4.59146912e+02 4.32325226e+02 4.05372498e+02 3.78658630e+02 3.51932892e+02 3.24983093e+02 2.98102142e+02 2.70981628e+02 2.43877808e+02 2.16903046e+02 1.89722641e+02 1.62507080e+02 1.35331085e+02 1.08147514e+02 8.09294891e+01 5.36995277e+01 2.64678707e+01 -7.72602618e-01 -2.80262260e+01 -5.52605095e+01 -8.24822693e+01 -1.09690102e+02 -1.36848907e+02 -1.64062439e+02 -1.91212326e+02 -2.18379456e+02 -2.45493118e+02 -2.72558228e+02 -2.99506409e+02 -3.26355255e+02 -3.53458801e+02 -3.80422638e+02 -4.07035614e+02 -4.33744232e+02 -4.60496155e+02 -4.87035492e+02 -5.13821045e+02 -5.40101501e+02 -5.66481750e+02 -5.93001099e+02 -6.19244141e+02 -6.45327271e+02 -6.71002136e+02 -6.97024414e+02 -7.23013733e+02 -7.48808105e+02 -7.73818970e+02 -7.99223572e+02 -8.25586426e+02 -8.50503784e+02 -8.75127014e+02 -8.99948914e+02 -9.25494385e+02 -9.49843750e+02 -9.73795654e+02 -9.99052124e+02 -1.02383197e+03 -1.04718201e+03 -1.07046936e+03 -1.09465393e+03 -1.11901050e+03 -1.14205151e+03 -1.16541235e+03 -1.18801233e+03 -1.21096936e+03 -1.23437524e+03 -1.25611145e+03 -1.27903210e+03 -1.30156982e+03 -1.32164807e+03 -1.34562354e+03 -1.36803748e+03 -1.38690576e+03 -1.40809888e+03 -1.43020154e+03 -1.45091418e+03 -1.47070093e+03 -1.49121997e+03 -1.51229968e+03 -1.53129541e+03 -1.54941577e+03 -1.57037683e+03 -1.58866821e+03 -1.60792151e+03 -1.62807019e+03 -1.64465649e+03 -1.66688013e+03 -1.68089197e+03 -1.69578699e+03 -1.71812488e+03 -1.73262708e+03 -1.75153394e+03 -1.76481836e+03 -1.77878125e+03 -1.80169922e+03 -1.82030835e+03 -1.83159204e+03 -1.84180310e+03 -1.85786023e+03 -1.87779309e+03 -1.88848999e+03 -1.90642847e+03 -1.91932556e+03 -1.93323499e+03 -1.95224817e+03 -1.95966309e+03 -1.97250916e+03 -1.98154590e+03 -1.98856995e+03 -2.00613171e+03 -2.01647375e+03 -2.02920825e+03 -2.03706628e+03 -2.04332764e+03 -2.06286060e+03 -2.07322852e+03 -2.08060840e+03 -2.09275684e+03 -2.09546338e+03 -2.11098633e+03 -2.12094458e+03 -2.12421338e+03 -2.12881494e+03 -2.13596313e+03 -2.15135181e+03 -2.15372144e+03 -2.15198926e+03 -2.16859570e+03 -2.17483472e+03 -2.17770410e+03 -2.18644678e+03 -2.18677368e+03 -2.18896899e+03 -2.20350659e+03 -2.19826074e+03 -2.19825171e+03 -2.20528418e+03 -2.21499414e+03 -2.21503003e+03 -2.21189844e+03 -2.21474878e+03 -2.21863403e+03 -2.21951392e+03 -2.21461011e+03 -2.21770264e+03 -2.21985596e+03 -2.21648755e+03 -2.21897021e+03 -2.22057056e+03 -2.22779834e+03 -2.21784863e+03 -2.20824146e+03 -2.21390039e+03 -2.21088867e+03 -2.19989087e+03 -2.19915210e+03 -2.19909839e+03 -2.19564258e+03 -2.19623145e+03 -2.18338574e+03 -2.18307520e+03 -2.17432471e+03 -2.17516455e+03 -2.16007910e+03 -2.15572119e+03 -2.16073804e+03 -2.14733740e+03 -2.14186865e+03 -2.13630615e+03 -2.12396362e+03 -2.11214868e+03 -2.10438135e+03 -2.10251685e+03 -2.09226807e+03 -2.07508301e+03 -2.06933740e+03 -2.06212329e+03 -2.04979370e+03 -2.04210693e+03 -2.03114246e+03 -2.01503394e+03 -2.00248047e+03 -1.99444922e+03 -1.98900989e+03 -1.97421826e+03 -1.95481799e+03 -1.94072437e+03 -1.93472498e+03 -1.91862512e+03 -1.89920996e+03 -1.88353955e+03 -1.87344409e+03 -1.86648230e+03 -1.84783118e+03 -1.83174146e+03 -1.81421680e+03 -1.79505457e+03 -1.78165967e+03 -1.76893860e+03 -1.75043042e+03 -1.73270544e+03 -1.71439575e+03 -1.69633557e+03 -1.68299133e+03 -1.66032776e+03 -1.64215662e+03 -1.62632275e+03 -1.60672070e+03 -1.58768384e+03 -1.56794824e+03 -1.54981433e+03 -1.53051721e+03 -1.51099072e+03 -1.48974109e+03 -1.46934753e+03 -1.45217993e+03 -1.42793604e+03 -1.40663025e+03 -1.38726038e+03 -1.36420776e+03 -1.34336975e+03 -1.32318152e+03 -1.29916699e+03 -1.27590942e+03 -1.25426733e+03 -1.23353284e+03 -1.21067578e+03 -1.18699353e+03 -1.16367725e+03 -1.14058911e+03 -1.11714722e+03 -1.09395764e+03 -1.06919153e+03 -1.04547278e+03 -1.02165839e+03 -9.96994324e+02 -9.73000854e+02 -9.48610596e+02 -9.23387939e+02 -8.98301086e+02 -8.73685730e+02 -8.49376892e+02 -8.23360352e+02 -7.98319336e+02 -7.73197693e+02 -7.46527405e+02 -7.21090271e+02 -6.95649536e+02 -6.70059021e+02 -6.44111084e+02 -6.17096680e+02 -5.91023010e+02 -5.65345825e+02 -5.38817444e+02 -5.11758118e+02 -4.85448914e+02 -4.59230743e+02 -4.32280304e+02 -4.05379456e+02 -3.78709595e+02 -3.51915375e+02 -3.24954224e+02 -2.98066559e+02 -2.70947632e+02 -2.43907425e+02 -2.16913147e+02 -1.89718155e+02 -1.62496490e+02 -1.35288681e+02 -1.08146790e+02 -8.09260941e+01 -5.36806755e+01 -2.64584160e+01 7.75526464e-01 2.80090046e+01 5.52334404e+01 8.24734802e+01 1.09688004e+02 1.36865524e+02 1.64074371e+02 1.91222122e+02 2.18411819e+02 2.45479172e+02 2.72537018e+02 2.99501129e+02 3.26351471e+02 3.53432281e+02 3.80422607e+02 4.07083740e+02 4.33840820e+02 4.60497772e+02 4.86757996e+02 5.13308228e+02 5.40279480e+02 5.67079346e+02 5.92708984e+02 6.19124084e+02 6.45606812e+02 6.70671326e+02 6.96901611e+02 7.23294739e+02 7.48545837e+02 7.73806702e+02 7.99346558e+02 8.25683777e+02 8.50666443e+02 8.74364990e+02 8.99702820e+02 9.25353699e+02 9.49702087e+02 9.73951965e+02 9.99819885e+02 1.02424536e+03 1.04707617e+03 1.07072937e+03 1.09422937e+03 1.11953662e+03 1.14100134e+03 1.16506555e+03 1.18924402e+03 1.21037329e+03 1.23397241e+03 1.25633630e+03 1.27852661e+03 1.30112097e+03 1.32252380e+03 1.34494836e+03 1.36680176e+03 1.38712427e+03 1.40831042e+03 1.42971680e+03 1.45155713e+03 1.47146362e+03 1.49080676e+03 1.51279260e+03 1.53181519e+03 1.54885486e+03 1.57012988e+03 1.58866980e+03 1.60813928e+03 1.62710266e+03 1.64406921e+03 1.66642053e+03 1.67886206e+03 1.69639050e+03 1.71932349e+03 1.73184387e+03 1.75180615e+03 1.76629956e+03 1.77935815e+03 1.79986072e+03 1.81972021e+03 1.83029773e+03 1.84149719e+03 1.86224915e+03 1.87897717e+03 1.89047925e+03 1.90825903e+03 1.91963794e+03 1.93336914e+03 1.94933435e+03 1.95585266e+03 1.97455225e+03 1.98517126e+03 1.99007275e+03 2.00729810e+03 2.01726782e+03 2.03070349e+03 2.03911670e+03 2.04612805e+03 2.06133423e+03 2.06908472e+03 2.07796875e+03 2.09151807e+03 2.09818872e+03 2.10596582e+03 2.11537256e+03 2.13044165e+03 2.13030591e+03 2.13686133e+03 2.15178320e+03 2.15554712e+03 2.15329443e+03 2.16664429e+03 2.17341650e+03 2.17441675e+03 2.18436914e+03 2.18356616e+03 2.19352271e+03 2.20017358e+03 2.19859814e+03 2.19707031e+03 2.20263477e+03 2.20980273e+03 2.21854224e+03 2.21350659e+03 2.21535474e+03 2.21524780e+03 2.21901831e+03 2.21162378e+03 2.21504565e+03 2.22240381e+03 2.21489136e+03 2.21710986e+03 2.21831079e+03 2.22428442e+03 2.22112866e+03 2.20643726e+03 2.21091431e+03 2.21154590e+03 2.20360303e+03 2.19735693e+03 2.19977710e+03 2.19524341e+03 2.19114478e+03 2.18876660e+03 2.18142090e+03 2.17563354e+03 2.17322729e+03 2.16122339e+03 2.15795630e+03 2.15805200e+03 2.14612671e+03 2.13918872e+03 2.13703271e+03 2.12171069e+03 2.10821704e+03 2.10998755e+03 2.10240771e+03 2.08856689e+03 2.07662256e+03 2.07169556e+03 2.06158374e+03 2.04856348e+03 2.04492224e+03 2.03232056e+03 2.01553381e+03 2.00440942e+03 1.99325806e+03 1.98915210e+03 1.97542188e+03 1.95273657e+03 1.94160205e+03 1.93409155e+03 1.91817053e+03 1.90004370e+03 1.88451758e+03 1.87470422e+03 1.86684631e+03 1.84768018e+03 1.83027783e+03 1.81523022e+03 1.79501733e+03 1.78134399e+03 1.76758618e+03 1.74730554e+03 1.73362891e+03 1.71479395e+03 1.69715601e+03 1.68276843e+03 1.66143774e+03 1.64379907e+03 1.62708374e+03 1.60611572e+03 1.58476562e+03 1.56842505e+03 1.54984167e+03 1.53121167e+03 1.51194128e+03 1.48959583e+03 1.46939478e+03 1.45235498e+03 1.42868970e+03 1.40467395e+03 1.38637231e+03 1.36333850e+03 1.34236548e+03 1.32292261e+03 1.30017358e+03 1.27597998e+03 1.25473022e+03 1.23430701e+03 1.20984705e+03 1.18688647e+03 1.16458838e+03 1.14089221e+03 1.11650305e+03 1.09283496e+03 1.06928467e+03 1.04591602e+03 1.02174390e+03 1.31534326e+03 9.73616089e+02 1.21522803e+03 9.23281494e+02 8.98586609e+02 1.15264575e+03 8.49003052e+02 1.05500549e+03 7.98508789e+02 7.73190002e+02 7.46759033e+02 7.20874573e+02 6.95633362e+02 6.70060974e+02 6.43807861e+02 6.17354004e+02 5.91047729e+02 5.64997864e+02 5.38839966e+02 5.11958313e+02 4.85523682e+02 4.59187592e+02 4.32347992e+02 4.05403381e+02 3.78661407e+02 3.51902435e+02 3.24916840e+02 2.98034821e+02 2.70993042e+02 2.43907104e+02 2.16894119e+02 1.89724762e+02 1.62538498e+02 1.35323471e+02 1.08152512e+02 8.09337997e+01 5.37011871e+01 2.65036259e+01 -7.56641626e-01 -2.80251255e+01 -5.52501602e+01 -8.24713364e+01 -1.09677269e+02 -1.36874374e+02 -1.64090149e+02 -1.91214432e+02 -2.18381439e+02 -2.45449554e+02 -2.72502991e+02 -2.99504333e+02 -3.26358521e+02 -3.53416473e+02 -3.80335876e+02 -4.07022614e+02 -4.33778320e+02 -4.60440552e+02 -4.87029449e+02 -5.13718201e+02 -5.40075073e+02 -5.66552979e+02 -5.92886169e+02 -6.19352356e+02 -6.45455688e+02 -6.70661987e+02 -6.97056030e+02 -7.23247131e+02 -7.48352661e+02 -7.73539856e+02 -7.99449829e+02 -8.25916260e+02 -8.51008667e+02 -8.74810974e+02 -8.99560791e+02 -9.25219238e+02 -9.50605530e+02 -9.73804993e+02 -9.98844116e+02 -1.02364386e+03 -1.04658728e+03 -1.07063074e+03 -1.09440344e+03 -1.11857520e+03 -1.14212366e+03 -1.16538806e+03 -1.18806140e+03 -1.21075061e+03 -1.23411511e+03 -1.25591272e+03 -1.27906250e+03 -1.30056091e+03 -1.32182446e+03 -1.34522253e+03 -1.36739758e+03 -1.38735718e+03 -1.40861316e+03 -1.42952930e+03 -1.45059863e+03 -1.47081055e+03 -1.49149512e+03 -1.51251416e+03 -1.53188330e+03 -1.55037622e+03 -1.56891052e+03 -1.58947888e+03 -1.60860034e+03 -1.62650867e+03 -1.64574207e+03 -1.66760022e+03 -1.67923438e+03 -1.69625867e+03 -1.71917676e+03 -1.73390100e+03 -1.75212158e+03 -1.76610449e+03 -1.77853711e+03 -1.80150208e+03 -1.81940564e+03 -1.83081775e+03 -1.84005566e+03 -1.85803601e+03 -1.87866858e+03 -1.88993896e+03 -1.90612341e+03 -1.91934985e+03 -1.93439783e+03 -1.95138867e+03 -1.95900549e+03 -1.97118127e+03 -1.98018640e+03 -1.99175610e+03 -2.00822253e+03 -2.01867395e+03 -2.02852368e+03 -2.04101831e+03 -2.04747754e+03 -2.06338086e+03 -2.07354956e+03 -2.07910059e+03 -2.09220190e+03 -2.09487109e+03 -2.10594043e+03 -2.12029834e+03 -2.12707227e+03 -2.12917212e+03 -2.13485864e+03 -2.15182007e+03 -2.15758130e+03 -2.15141431e+03 -2.16729980e+03 -2.17565527e+03 -2.17778638e+03 -2.18416748e+03 -2.18798413e+03 -2.18934399e+03 -2.19975317e+03 -2.19789844e+03 -2.19734863e+03 -2.20495312e+03 -2.20780420e+03 -2.21587329e+03 -2.21499268e+03 -2.21301636e+03 -2.22061182e+03 -2.22088184e+03 -2.21406738e+03 -2.21585962e+03 -2.21999194e+03 -2.21643018e+03 -2.22080249e+03 -2.21808765e+03 -2.22933643e+03 -2.22201196e+03 -2.20795117e+03 -2.21619141e+03 -2.21114453e+03 -2.20096558e+03 -2.20048022e+03 -2.20303369e+03 -2.19376294e+03 -2.19149512e+03 -2.18901514e+03 -2.18306909e+03 -2.17425879e+03 -2.17249390e+03 -2.16297827e+03 -2.15624048e+03 -2.16299316e+03 -2.14529053e+03 -2.13998315e+03 -2.13936060e+03 -2.11975391e+03 -2.11163721e+03 -2.10337500e+03 -2.10086475e+03 -2.09220410e+03 -2.68749219e+03 -4.94430078e+03 -6.14532178e+03 -17523394. 10544034. -6.37134750e+05 -6.37134750e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 11674563. -1.54203238e+06 -7.05707373e+03 -5.95485254e+03 -4.48313867e+03 -2.35781396e+03 -1.78243311e+03 -1.76529456e+03 -1.74725134e+03 -1.73243066e+03 -1.71555310e+03 -1.69594495e+03 -1.68247388e+03 -1.66261218e+03 -1.64594751e+03 -1.62748132e+03 -1.60759888e+03 -1.58541418e+03 -1.56730347e+03 -1.54962244e+03 -1.53080920e+03 -1.51262488e+03 -1.49021521e+03 -1.46925098e+03 -1.45117041e+03 -1.42805151e+03 -1.40765320e+03 -1.38736230e+03 -1.36367102e+03 -1.34330615e+03 -1.32265015e+03 -1.29984912e+03 -1.27591602e+03 -1.25376245e+03 -1.23407458e+03 -1.21142456e+03 -1.18741858e+03 -1.16380664e+03 -1.13973938e+03 -1.11754285e+03 -1.09322302e+03 -1.06895508e+03 -1.04596130e+03 -1.02149847e+03 -9.97632629e+02 -9.73199463e+02 -9.48704468e+02 -9.23514160e+02 -8.98818054e+02 -8.74103271e+02 -8.49158142e+02 -8.23231384e+02 -7.98177917e+02 -7.73108582e+02 -7.46508850e+02 -7.21351135e+02 -6.95578552e+02 -6.69993896e+02 -6.44153931e+02 -6.17165649e+02 -5.91195984e+02 -5.65400818e+02 -5.38801147e+02 -5.12076172e+02 -4.85644379e+02 -4.59299805e+02 -4.32717804e+02 -4.05345734e+02 -1.57012109e+03 -1.06117712e+03 266354944. 266354944. 261679568. 3.52158450e+06 -4.73813555e+04 -3.90154388e+02 -4.82586304e+02 -5.79229736e+02 -7.83469219e+04 -1.15726826e+04 3.89611125e+06 -2.65623725e+06 0. 0. -1902562432. 62493520. 1.36884265e+03 -1279582080. -277667808. 0. 0. -870164800. 3.62835767e+03 7.58924561e+02 4.89532837e+02 4.99484558e+02 4.99634705e+02 4.05959839e+02 4.32928253e+02 4.59707977e+02 4.85990692e+02 5.12343018e+02 5.39042236e+02 5.65378052e+02 5.91111206e+02 6.17674377e+02 6.44180969e+02 6.69605896e+02 6.95354370e+02 7.21401550e+02 7.46841858e+02 7.72406128e+02 7.97860657e+02 8.23112732e+02 8.48625122e+02 8.72771240e+02 8.98080444e+02 9.23489258e+02 9.48045288e+02 9.72339050e+02 9.96758850e+02 1.02121698e+03 1.04418945e+03 1.06933948e+03 1.09349060e+03 1.11668848e+03 1.13850256e+03 1.16132593e+03 1.18576245e+03 1.20769531e+03 1.23061023e+03 1.25403955e+03 1.27760632e+03 1.29915808e+03 1.32032764e+03 1.34257715e+03 1.36267163e+03 1.38346387e+03 1.40480310e+03 1.42781311e+03 1.44845923e+03 1.46743762e+03 1.48830359e+03 1.50910291e+03 1.52786560e+03 1.54732373e+03 1.56736731e+03 1.58594690e+03 1.60369641e+03 1.62098865e+03 1.64449207e+03 1.66409119e+03 1.67377917e+03 1.69515491e+03 1.71395435e+03 2.23884253e+03 2.38724976e+03 4.24414014e+03 5.62919336e+03 11322082. 13851109. -16776671. -16776671. 0. 0. -441762368. -441762368. -4.24307302e+09 -65236368. -65236368. 0. 0. 0. 0. 37017584. 6405148. 6.12401562e+03 4.89557959e+03 2.81424390e+03 2.67463794e+03 2.06791797e+03 2.07350049e+03 2.08193384e+03 2.09597412e+03 2.10764331e+03 2.11098462e+03 2.11918799e+03 2.13454004e+03 2.13245386e+03 2.14238086e+03 2.15192163e+03 2.15408179e+03 2.16427051e+03 2.16905786e+03 2.17162891e+03 2.17729980e+03 2.17859375e+03 2.18345142e+03 2.19667456e+03 2.19067651e+03 2.19817236e+03 2.20198438e+03 2.20054810e+03 2.20907373e+03 2.21372510e+03 2.20833984e+03 2.21059033e+03 2.21834180e+03 2.21033252e+03 2.21343457e+03 2.21626270e+03 2.21759888e+03 2.21325464e+03 2.21370850e+03 2.21530884e+03 2.21225317e+03 2.20733667e+03 2.20983447e+03 2.20470459e+03 2.19585034e+03 2.19814233e+03 2.19823682e+03 2.18972314e+03 2.18809595e+03 2.18596240e+03 2.17786816e+03 2.17242627e+03 2.16893677e+03 2.15687231e+03 2.15509985e+03 2.15471362e+03 2.14090796e+03 2.13665552e+03 2.12970532e+03 2.12077563e+03 2.10617065e+03 2.09792407e+03 2.09797559e+03 2.08452441e+03 2.07226123e+03 2.06575464e+03 2.06039307e+03 2.04274011e+03 2.03874487e+03 2.02534302e+03 2.01068982e+03 2.00347876e+03 1.99461292e+03 1.98133997e+03 1.96603882e+03 1.95522363e+03 1.94031689e+03 1.92487549e+03 1.91223218e+03 1.89612524e+03 1.88398718e+03 1.87179492e+03 1.85861816e+03 1.84364905e+03 1.83007361e+03 1.81175708e+03 1.79433154e+03 1.78197095e+03 1.76235400e+03 1.74369580e+03 1.73060571e+03 1.70947913e+03 1.69386133e+03 1.68023291e+03 1.65903320e+03 1.64155371e+03 1.62349841e+03 1.60448633e+03 1.58073523e+03 1.56535266e+03 1.54789990e+03 1.52673889e+03 1.50856226e+03 1.48702344e+03 1.46615662e+03 1.44733728e+03 1.42659070e+03 1.40509131e+03 1.38304712e+03 1.36065002e+03 1.34174792e+03 1.31998279e+03 1.29753918e+03 1.27544739e+03 1.25276550e+03 1.22970044e+03 1.20785315e+03 1.18463562e+03 1.16069775e+03 1.13827026e+03 1.11536890e+03 1.09184399e+03 1.06754016e+03 1.04364624e+03 1.02009534e+03 9.96049377e+02 9.71147095e+02 9.47175842e+02 9.21886169e+02 8.96541504e+02 8.72178223e+02 8.47873962e+02 8.22009155e+02 7.96856506e+02 7.71825195e+02 7.45395081e+02 7.20280090e+02 6.94327026e+02 6.68419006e+02 6.42837830e+02 6.16110168e+02 5.90137756e+02 5.64326111e+02 5.37837097e+02 5.11299896e+02 4.84368103e+02 4.58269073e+02 4.31660278e+02 4.04749023e+02 3.78215302e+02 3.51362946e+02 3.24421631e+02 2.97653931e+02 2.70568726e+02 2.43557938e+02 2.16608795e+02 1.89471527e+02 1.62361710e+02 1.35224396e+02 1.08090408e+02 8.09346466e+01 5.37555656e+01 2.65750484e+01 -6.10849380e-01 -2.77982788e+01 -5.49756165e+01 -8.21461639e+01 -1.09304039e+02 -1.36435349e+02 -1.63587265e+02 -1.90690811e+02 -2.17763321e+02 -2.44802902e+02 -2.71830261e+02 -2.98774414e+02 -3.25595825e+02 -3.52534882e+02 -3.79375824e+02 -4.05988190e+02 -4.32725800e+02 -4.59323425e+02 -4.85985931e+02 -5.12607666e+02 -5.38674927e+02 -5.65181641e+02 -5.91673279e+02 -6.17910339e+02 -6.43703613e+02 -8.60459595e+02 -9.34748474e+02 -1.08279590e+03 -1.12158899e+03 -1.15862292e+03 -1.19681055e+03 -1.23552063e+03 -1.27313538e+03 -1.31026758e+03 -1.34843787e+03 -1.38601843e+03 -1.42266956e+03 -1.45783557e+03 -1.49535986e+03 -1.53265881e+03 -1.56772681e+03 -1.60241785e+03 -1.63864526e+03 -1.55080200e+03 -1.70928906e+03 -1.57712341e+03 -1.77926514e+03 -1.66655933e+03 -1.61416748e+03 -1.25386682e+03 -1.27640271e+03 -1.29757471e+03 -1.32056897e+03 -1.34240601e+03 -1.36371899e+03 -1.38482080e+03 -1.40446887e+03 -1.42751306e+03 -1.44886890e+03 -1.46724121e+03 -1.48722827e+03 -1.50783301e+03 -1.52675073e+03 -1.54712158e+03 -1.56949878e+03 -1.58446350e+03 -1.60397876e+03 -1.62367603e+03 -1.64386035e+03 -1.66461694e+03 -1.67764648e+03 -1.69185181e+03 -1.71254565e+03 -1.73119373e+03 -1.74632727e+03 -1.76009229e+03 -1.77781567e+03 -1.79733594e+03 -1.81439929e+03 -1.83006006e+03 -1.83764038e+03 -1.85215820e+03 -1.87378564e+03 -1.88856433e+03 -1.90107007e+03 -1.91469116e+03 -1.92984692e+03 -1.94728345e+03 -1.95527136e+03 -1.96677893e+03 -1.97643872e+03 -1.98702051e+03 -2.00552576e+03 -2.01437720e+03 -2.02713000e+03 -2.03462305e+03 -2.04608142e+03 -2.05867017e+03 -2.06806079e+03 -2.08252148e+03 -2.08506543e+03 -2.09112964e+03 -2.10711426e+03 -2.11183472e+03 -2.12007910e+03 -2.12851465e+03 -2.13189282e+03 -2.14237305e+03 -2.15140845e+03 -2.15215991e+03 -2.16358643e+03 -2.16977417e+03 -2.17205811e+03 -2.18052051e+03 -2.17978052e+03 -2.18297290e+03 -2.19800928e+03 -2.19201660e+03 -2.19832422e+03 -2.20206909e+03 -2.20180713e+03 -2.20745166e+03 -2.21016016e+03 -2.20748584e+03 -2.21009937e+03 -2.21507471e+03 -2.21253613e+03 -2.21489551e+03 -2.21868408e+03 -2.21173560e+03 -2.21146240e+03 -2.21444312e+03 -2.21828467e+03 -2.21135864e+03 -2.21078589e+03 -2.20989648e+03 -2.20619702e+03 -2.20005298e+03 -2.20015918e+03 -2.19997925e+03 -2.19090381e+03 -2.18565112e+03 -2.18331128e+03 -2.17743506e+03 -2.16913428e+03 -2.16971606e+03 -2.15572729e+03 -2.15133618e+03 -2.15857983e+03 -2.14479443e+03 -2.13713672e+03 -2.13052490e+03 -2.12079834e+03 -2.10612646e+03 -2.09959351e+03 -2.09993848e+03 -2.08563257e+03 -2.06890039e+03 -2.06568408e+03 -2.06257080e+03 -2.04299780e+03 -2.03767651e+03 -2.02316345e+03 -2.00912012e+03 -1.99961743e+03 -1.99321033e+03 -1.98179980e+03 -1.96828674e+03 -1.95294458e+03 -1.94104736e+03 -1.92774622e+03 -1.91290857e+03 -1.89816296e+03 -1.88288501e+03 -1.87217383e+03 -1.85807935e+03 -1.84240344e+03 -1.82844531e+03 -1.81084326e+03 -1.79255615e+03 -1.78078882e+03 -1.76600366e+03 -1.74769714e+03 -1.72947937e+03 -1.70993726e+03 -1.69469177e+03 -1.67907458e+03 -1.65857495e+03 -1.64117468e+03 -1.62310339e+03 -1.60382239e+03 -1.58142334e+03 -1.56356018e+03 -1.54832666e+03 -1.52880872e+03 -1.50908472e+03 -1.48681934e+03 -1.46547424e+03 -1.44840454e+03 -1.42633203e+03 -1.40257507e+03 -1.38217175e+03 -1.36099512e+03 -1.34298499e+03 -1.31985645e+03 -1.29641553e+03 -1.27547693e+03 -1.25185010e+03 -1.22896472e+03 -1.20909241e+03 -1.18546936e+03 -1.16072668e+03 -1.13845557e+03 -1.11535034e+03 -1.09192761e+03 -1.06727808e+03 -1.04368750e+03 -1.01995807e+03 -9.95330017e+02 -9.71031921e+02 -9.47208862e+02 -9.22479065e+02 -8.96788818e+02 -8.71959473e+02 -8.47705505e+02 -8.21763916e+02 -7.96891968e+02 -7.71789185e+02 -7.45319702e+02 -7.20179077e+02 -6.94497742e+02 -6.68399353e+02 -6.42857422e+02 -6.16059204e+02 -5.90055237e+02 -5.64750977e+02 -5.37870972e+02 -5.10863281e+02 -4.84376251e+02 -4.58345947e+02 -4.31639313e+02 -4.04695435e+02 -3.78272797e+02 -3.51411224e+02 -3.24426819e+02 -2.97580231e+02 -2.70543152e+02 -2.43603287e+02 -2.16595230e+02 -1.89472519e+02 -1.62373932e+02 -1.35204147e+02 -1.08087631e+02 -8.09299698e+01 -5.37484055e+01 -2.65728741e+01 6.11835778e-01 2.77960835e+01 5.49724960e+01 8.21502686e+01 1.09312782e+02 1.36437973e+02 1.63570496e+02 1.90705383e+02 2.17809845e+02 2.44783813e+02 2.71860657e+02 2.98811981e+02 3.25588684e+02 3.52562134e+02 3.79399475e+02 4.05924377e+02 4.32862000e+02 4.59615784e+02 4.85594025e+02 5.12136475e+02 5.39190613e+02 5.65596375e+02 5.91075500e+02 6.17560852e+02 6.44228027e+02 6.69589783e+02 6.95447876e+02 7.21354919e+02 7.46605774e+02 7.72624695e+02 7.97697266e+02 8.22772705e+02 8.48611511e+02 8.72597534e+02 8.98427612e+02 9.23084106e+02 9.47851746e+02 9.72765320e+02 9.96367004e+02 1.02093500e+03 1.04459009e+03 1.06858459e+03 1.09338428e+03 1.11635376e+03 1.13890454e+03 1.16271765e+03 1.18596362e+03 1.20802197e+03 1.23126624e+03 1.25408044e+03 1.27640857e+03 1.29934241e+03 1.32039661e+03 1.34250317e+03 1.36376807e+03 1.38496472e+03 1.40323718e+03 1.42730786e+03 1.45029883e+03 1.46820886e+03 1.48711743e+03 1.50915564e+03 1.52638330e+03 1.54678711e+03 1.56827966e+03 1.58466968e+03 1.60227917e+03 1.62363013e+03 1.64402661e+03 1.66469141e+03 1.67674353e+03 1.69377417e+03 1.71317700e+03 1.73105872e+03 1.74556702e+03 1.76012903e+03 1.78050732e+03 1.79507373e+03 1.81404980e+03 1.82869556e+03 1.83743701e+03 1.85652588e+03 1.87663818e+03 1.88693420e+03 1.89835632e+03 1.91308374e+03 1.93158093e+03 1.94709888e+03 1.95239453e+03 1.96918420e+03 1.97567993e+03 1.98771350e+03 2.00322913e+03 2.01276917e+03 2.02998901e+03 2.03692737e+03 2.04499512e+03 2.05548853e+03 2.06901611e+03 2.07768433e+03 2.08605688e+03 2.09589746e+03 2.09910254e+03 2.10579102e+03 2.12163867e+03 2.13190967e+03 2.13454883e+03 2.14265161e+03 2.15219922e+03 2.15064526e+03 2.16189209e+03 2.17012744e+03 2.17180396e+03 2.18148145e+03 2.17810229e+03 2.18256348e+03 2.19447534e+03 2.19449658e+03 2.20122632e+03 2.19836084e+03 2.20204980e+03 2.21080225e+03 2.21322827e+03 2.20929224e+03 2.21199585e+03 2.21733105e+03 2.21123901e+03 2.20935107e+03 2.21905640e+03 2.21532520e+03 2.21216699e+03 2.21415234e+03 2.21662085e+03 2.21301270e+03 2.20711646e+03 2.20696436e+03 2.20397607e+03 2.19806665e+03 2.19754810e+03 2.19575537e+03 2.19392407e+03 2.18488867e+03 2.18140576e+03 2.18117920e+03 2.17203345e+03 2.16779053e+03 2.15597388e+03 2.15281641e+03 2.15581299e+03 2.14511841e+03 2.13364966e+03 2.13044897e+03 2.11910913e+03 2.10866943e+03 2.10514453e+03 2.09980322e+03 2.08432007e+03 2.07194800e+03 2.06611377e+03 2.05864746e+03 2.04480615e+03 2.03564661e+03 2.02590088e+03 2.00961108e+03 2.00535718e+03 1.99183081e+03 1.98134973e+03 1.96745032e+03 1.95161816e+03 1.94208435e+03 1.92801880e+03 1.91456299e+03 1.89662317e+03 1.88276392e+03 1.87309265e+03 1.85756226e+03 1.84148352e+03 1.82878430e+03 1.81239221e+03 1.79166174e+03 1.77890686e+03 1.76542456e+03 1.74739050e+03 1.72800781e+03 1.70935803e+03 1.69469983e+03 1.67929602e+03 1.65794141e+03 1.64193188e+03 1.62342627e+03 1.60300342e+03 1.58052100e+03 1.56421753e+03 1.54878284e+03 1.52874292e+03 1.50882471e+03 1.48556897e+03 1.46656726e+03 1.44797583e+03 1.42597327e+03 1.40255566e+03 1.38297693e+03 1.36059680e+03 1.34187732e+03 1.32073291e+03 1.29701025e+03 1.27455359e+03 1.25245520e+03 1.23032800e+03 1.20726355e+03 1.18441467e+03 1.16176038e+03 1.13884924e+03 1.11435486e+03 1.09047327e+03 1.06733044e+03 1.04441223e+03 1.01975116e+03 1.96233606e+03 1.36517847e+03 2.23108862e+03 1.38170178e+03 1.34577344e+03 2.12655005e+03 1.27021423e+03 1.93248975e+03 1.19594824e+03 1.15766321e+03 1.11790320e+03 9.67156372e+02 1.04131274e+03 6.69059631e+02 8.32718872e+02 6.16607910e+02 5.90020264e+02 5.64290222e+02 5.38004517e+02 5.11129913e+02 4.84478973e+02 4.58291779e+02 4.31708984e+02 4.04793335e+02 3.78108002e+02 3.51344879e+02 3.24424957e+02 2.97564575e+02 2.70570465e+02 2.43606659e+02 2.16583694e+02 1.89470917e+02 1.62375336e+02 1.35220016e+02 1.08089447e+02 8.09376068e+01 5.37555542e+01 2.65806503e+01 -6.06983364e-01 -2.77939205e+01 -5.49705124e+01 -8.21482544e+01 -1.09302139e+02 -1.36437988e+02 -1.63577164e+02 -1.90687424e+02 -2.17777832e+02 -2.44793472e+02 -2.71808502e+02 -2.98772125e+02 -3.25631622e+02 -3.52613892e+02 -3.79322571e+02 -4.05906372e+02 -4.32795288e+02 -4.59468628e+02 -4.85929810e+02 -5.12427307e+02 -5.38763916e+02 -5.65372498e+02 -5.91467224e+02 -6.17815186e+02 -6.44015869e+02 -6.69468018e+02 -6.95446411e+02 -7.21624512e+02 -7.46727417e+02 -7.71921021e+02 -7.97575012e+02 -8.23349609e+02 -8.48823547e+02 -8.73135742e+02 -8.97997314e+02 -9.23001099e+02 -9.48042114e+02 -9.72364807e+02 -9.96673706e+02 -1.02114478e+03 -1.04470166e+03 -1.06862585e+03 -1.09236646e+03 -1.11609045e+03 -1.14006494e+03 -1.16279541e+03 -1.18593811e+03 -1.20806213e+03 -1.23092749e+03 -1.25437952e+03 -1.27627808e+03 -1.29726514e+03 -1.32044238e+03 -1.34165027e+03 -1.36366821e+03 -1.38545459e+03 -1.40403894e+03 -1.42730408e+03 -1.44900159e+03 -1.46706775e+03 -1.48738464e+03 -1.50821130e+03 -1.52789929e+03 -1.54719739e+03 -1.56702112e+03 -1.58561902e+03 -1.60183459e+03 -1.62178235e+03 -1.64383191e+03 -1.66437024e+03 -1.67549023e+03 -1.69182153e+03 -1.71373572e+03 -1.73192285e+03 -1.74612524e+03 -1.75944958e+03 -1.77956775e+03 -1.79620264e+03 -1.81583899e+03 -1.83001184e+03 -1.83781140e+03 -1.85251062e+03 -1.87409204e+03 -1.88715271e+03 -1.90142407e+03 -1.91527026e+03 -1.93090735e+03 -1.94723730e+03 -1.95515686e+03 -1.97023608e+03 -1.97639026e+03 -1.98576245e+03 -2.00526233e+03 -2.01386914e+03 -2.02436304e+03 -2.03741174e+03 -2.04521289e+03 -2.05854858e+03 -2.06717676e+03 -2.07923169e+03 -2.08595581e+03 -2.09063281e+03 -2.10154932e+03 -2.11009058e+03 -2.12078394e+03 -2.12740967e+03 -2.13269702e+03 -2.14095142e+03 -2.15547021e+03 -2.15153052e+03 -2.15950293e+03 -2.16942188e+03 -2.17657104e+03 -2.18318311e+03 -2.18038379e+03 -2.18152661e+03 -2.19477124e+03 -2.19532446e+03 -2.19972656e+03 -2.20010034e+03 -2.20248462e+03 -2.20979272e+03 -2.21051050e+03 -2.21026709e+03 -2.20992065e+03 -2.21956104e+03 -2.21292725e+03 -2.21284985e+03 -2.22100049e+03 -2.21215479e+03 -2.21293140e+03 -2.21450586e+03 -2.21538232e+03 -2.21240698e+03 -2.20920532e+03 -2.20889355e+03 -2.21053198e+03 -2.19870557e+03 -2.19564697e+03 -2.19586963e+03 -2.18786890e+03 -2.18368213e+03 -2.18669751e+03 -2.18037109e+03 -2.16729053e+03 -2.16537524e+03 -2.15722339e+03 -2.15145068e+03 -2.15642749e+03 -2.14518970e+03 -2.13410229e+03 -2.77321924e+03 -2.87858057e+03 -3.15422510e+03 -3.14916992e+03 -3.14564819e+03 -3.12732959e+03 -2.85185449e+03 -4.12871387e+03 -2.79946387e+03 -4.81843018e+03 -6.24364258e+03 -18128130. 88474184. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 171338688. -2.02805156e+04 -3.84576025e+03 -1.77796338e+03 -2.29434351e+03 -1.74567798e+03 -1.72979175e+03 -1.71018115e+03 -1.69534265e+03 -1.67814465e+03 -1.65884399e+03 -1.64313806e+03 -1.62411768e+03 -1.60433411e+03 -1.58071936e+03 -1.56497729e+03 -1.54817480e+03 -1.52772327e+03 -1.50898450e+03 -1.48603735e+03 -1.46661975e+03 -1.44772363e+03 -1.42576416e+03 -1.40431628e+03 -1.38405469e+03 -1.36190625e+03 -1.34256604e+03 -1.32021997e+03 -1.29714551e+03 -1.27561523e+03 -1.25132300e+03 -1.22950977e+03 -1.20858411e+03 -1.18590808e+03 -1.16062524e+03 -1.13768030e+03 -1.11571204e+03 -1.09187988e+03 -1.06770642e+03 -1.04407605e+03 -1.01972089e+03 -9.94951233e+02 -9.70845215e+02 -9.47050049e+02 -9.22686829e+02 -8.96916199e+02 -8.72247009e+02 -8.47295959e+02 -8.21446899e+02 -7.96757751e+02 -7.71703003e+02 -7.45290405e+02 -7.20345032e+02 -6.94278015e+02 -6.68420288e+02 -6.42989441e+02 -6.16079468e+02 -5.90022095e+02 -5.64547241e+02 -5.37919006e+02 -5.11231812e+02 -4.84520782e+02 -4.58152985e+02 -4.31713165e+02 -4.04911621e+02 -1.56674475e+03 -71669544. 0. 0. 0. 0. 0. -175946656. -175946656. -175946656. 0. 0. 0. 0. 0. 0. -1902562432. 62493520. 7.42814148e+02 9.49458191e+02 -1.32815531e+05 1363231488. 0. 0. -213172112. -10469757. 1.11851260e+04 1.08911243e+03 9.14049866e+02 6.08906311e+02 6.49096558e+02 6.29466797e+02 7.28507385e+02 5.12675049e+02 8.08685974e+02 7.78093140e+02 8.86215515e+02 9.26282532e+02 9.65988342e+02 1.00446332e+03 1.04268823e+03 1.08123010e+03 1.11895972e+03 1.15843909e+03 1.19727307e+03 1.23334497e+03 1.27197363e+03 1.30978125e+03 1.34764563e+03 1.38396118e+03 1.30097083e+03 1.45922253e+03 1.37391235e+03 1.52927271e+03 1.56723730e+03 1.60476917e+03 1.63719946e+03 1.67227454e+03 1.71130371e+03 1.74382251e+03 1.77723120e+03 1.80940881e+03 1.84420630e+03 1.88195984e+03 1.91656995e+03 1.94651770e+03 1.97836462e+03 2.01188452e+03 2.04588538e+03 1.89245776e+03 1.82477795e+03 1.42773389e+03 1.44765332e+03 1.46823413e+03 1.49050452e+03 1.50952881e+03 1.52901794e+03 1.54814502e+03 1.56911108e+03 1.58953601e+03 1.60581531e+03 1.62089343e+03 1.64405786e+03 1.66559558e+03 2.18245337e+03 2.33417603e+03 2.57201489e+03 4.16782568e+03 5.30026172e+03 -7.82585850e+06 40975212. 0. -16776671. -16776671. -16776671. 0. 0. -441762368. -441762368. -441762368. 0. 0. 0. 0. 0. 21716978. 2.41047578e+04 4.86560107e+03 2.78892944e+03 2.65547192e+03 2.05033130e+03 2.05839136e+03 2.06771313e+03 2.07903320e+03 2.70743188e+03 2.87577441e+03 3.16249365e+03 3.16492383e+03 3.17481909e+03 3.19658862e+03 3.19654028e+03 2.92627051e+03 2.80000439e+03 2.15749829e+03 2.16246680e+03 2.16877124e+03 2.17714648e+03 2.18312061e+03 2.18049707e+03 2.18643066e+03 2.19225659e+03 2.19551245e+03 2.19969287e+03 2.20911670e+03 2.20453857e+03 2.20677979e+03 2.21396289e+03 2.20967432e+03 2.21065308e+03 2.21541455e+03 2.20777075e+03 2.22000610e+03 2.21677100e+03 2.21463110e+03 2.21317822e+03 2.21790601e+03 2.21570117e+03 2.21435864e+03 2.20354810e+03 2.20947314e+03 2.20863940e+03 2.20169702e+03 2.19800391e+03 2.19556445e+03 2.19439062e+03 2.18852271e+03 2.18318115e+03 2.18043872e+03 2.17444922e+03 2.16838452e+03 2.15880688e+03 2.15836865e+03 2.15406079e+03 2.14351758e+03 2.13772974e+03 2.13021094e+03 2.11922827e+03 2.11425708e+03 2.10116602e+03 2.09694312e+03 2.09237573e+03 2.07653735e+03 2.06591138e+03 2.06069922e+03 2.04954565e+03 2.03498999e+03 2.02571448e+03 2.00788806e+03 2.00349341e+03 1.99595251e+03 1.98156726e+03 1.96835193e+03 1.95303845e+03 1.93789905e+03 1.92697668e+03 1.91297180e+03 1.89766980e+03 1.88607166e+03 1.87232275e+03 1.85679993e+03 1.84374707e+03 1.82763855e+03 1.81211328e+03 1.79528992e+03 1.78162817e+03 1.76629016e+03 1.74533850e+03 1.72835413e+03 1.71184863e+03 1.69623425e+03 1.68140088e+03 1.65985083e+03 1.64021875e+03 1.62457190e+03 1.60679675e+03 1.58521179e+03 1.56552258e+03 1.54939282e+03 1.52800891e+03 1.50838123e+03 1.48978210e+03 1.46688257e+03 1.44599866e+03 1.42753943e+03 1.40598096e+03 1.38371252e+03 1.36408130e+03 1.34274927e+03 1.31890405e+03 1.29705847e+03 1.27703796e+03 1.25372485e+03 1.22961047e+03 1.20876160e+03 1.18566333e+03 1.16159387e+03 1.13833765e+03 1.11616150e+03 1.09365186e+03 1.06800476e+03 1.04323474e+03 1.02034174e+03 9.96749878e+02 9.71509521e+02 9.47665100e+02 9.23192932e+02 8.96517700e+02 8.72134460e+02 8.48415955e+02 8.22798279e+02 7.96776917e+02 7.71726318e+02 7.46352600e+02 7.20928040e+02 6.94582214e+02 6.68553833e+02 6.43025635e+02 6.16573730e+02 5.90727417e+02 5.64339905e+02 5.37724854e+02 5.11649506e+02 4.84775818e+02 4.58190308e+02 4.31790924e+02 4.05072205e+02 3.78425903e+02 3.51479340e+02 3.24390656e+02 2.97654480e+02 2.70639893e+02 2.43602997e+02 2.16613907e+02 1.89448685e+02 1.62359497e+02 1.35172775e+02 1.08022102e+02 8.08565521e+01 5.36589813e+01 2.64701309e+01 -7.30367303e-01 -2.79394360e+01 -5.51457024e+01 -8.23450241e+01 -1.09521454e+02 -1.36675003e+02 -1.63804321e+02 -1.90970459e+02 -2.18074432e+02 -2.45055862e+02 -2.72102966e+02 -2.99147339e+02 -3.26132904e+02 -3.53101593e+02 -3.79675476e+02 -4.06321442e+02 -4.33194122e+02 -4.59891449e+02 -4.86436584e+02 -6.67532593e+02 -7.49862366e+02 -7.74730225e+02 -7.67812561e+02 -6.18206665e+02 -6.44392029e+02 -8.20131653e+02 -8.54304993e+02 -1.08288989e+03 -1.12211987e+03 -1.16017004e+03 -1.19732410e+03 -1.23643811e+03 -1.27446838e+03 -1.31139575e+03 -1.35020801e+03 -1.38785913e+03 -1.42385486e+03 -1.45889807e+03 -1.49469849e+03 -1.53274963e+03 -1.57114099e+03 -1.60524231e+03 -1.63896216e+03 -1.38807104e+03 -1.71072766e+03 -1.43021765e+03 -1.78083264e+03 -1.50139795e+03 -1.52311218e+03 -1.25532922e+03 -1.27850806e+03 -1.29867883e+03 -1.32012646e+03 -1.34255957e+03 -1.36492798e+03 -1.38494165e+03 -1.40651843e+03 -1.42890674e+03 -1.44864905e+03 -1.46856531e+03 -1.49035474e+03 -1.50918567e+03 -1.52615955e+03 -1.54752832e+03 -1.56979236e+03 -1.58770691e+03 -1.60490186e+03 -1.62582007e+03 -1.64308398e+03 -1.66542126e+03 -1.67905408e+03 -1.69302271e+03 -1.71578992e+03 -1.73169128e+03 -1.74442749e+03 -1.76217700e+03 -1.77941150e+03 -1.79786377e+03 -1.81646033e+03 -1.82771216e+03 -1.83993237e+03 -1.85755115e+03 -1.87507629e+03 -1.88980750e+03 -1.89924939e+03 -1.91535120e+03 -1.93198560e+03 -1.94684985e+03 -1.95758301e+03 -1.96631921e+03 -1.97644287e+03 -1.99239099e+03 -2.00663684e+03 -2.01103625e+03 -2.02754565e+03 -2.03662805e+03 -2.04873364e+03 -2.06149976e+03 -2.06797192e+03 -2.08145996e+03 -2.08405054e+03 -2.09593628e+03 -2.10755103e+03 -2.11198779e+03 -2.11826538e+03 -2.12610767e+03 -2.13723779e+03 -2.14816846e+03 -2.15478760e+03 -2.15318481e+03 -2.16291309e+03 -2.17162988e+03 -2.17381421e+03 -2.18178125e+03 -2.18086719e+03 -2.18650000e+03 -2.19736475e+03 -2.19507129e+03 -2.20239697e+03 -2.20514233e+03 -2.20199976e+03 -2.20736646e+03 -2.21275635e+03 -2.20699365e+03 -2.21399780e+03 -2.22061768e+03 -2.21144482e+03 -2.21997876e+03 -2.21940503e+03 -2.20955835e+03 -2.21557544e+03 -2.21842456e+03 -2.21930078e+03 -2.21449561e+03 -2.20413892e+03 -2.20979468e+03 -2.20973926e+03 -2.20184497e+03 -2.19985474e+03 -2.19427588e+03 -2.19571484e+03 -2.19350806e+03 -2.18310742e+03 -2.18111646e+03 -2.17498950e+03 -2.17247461e+03 -2.16155176e+03 -2.15787207e+03 -2.15185278e+03 -2.14266626e+03 -2.13652417e+03 -2.12932104e+03 -2.11840991e+03 -2.11343555e+03 -2.10274878e+03 -2.09768311e+03 -2.08318701e+03 -2.07477686e+03 -2.07063306e+03 -2.06329272e+03 -2.04712732e+03 -2.03609631e+03 -2.02610352e+03 -2.00656287e+03 -2.00267065e+03 -1.99588489e+03 -1.97815845e+03 -1.96826392e+03 -1.95538342e+03 -1.94096204e+03 -1.92718909e+03 -1.91471667e+03 -1.89808887e+03 -1.88701965e+03 -1.87214917e+03 -1.85674182e+03 -1.84311096e+03 -1.82717834e+03 -1.81277161e+03 -1.79428064e+03 -1.77960498e+03 -1.76893591e+03 -1.74849609e+03 -1.72758655e+03 -1.71106848e+03 -1.69636694e+03 -1.67930774e+03 -1.65979993e+03 -1.64161731e+03 -1.62215002e+03 -1.60571631e+03 -1.58561462e+03 -1.56489148e+03 -1.54925513e+03 -1.52837158e+03 -1.50836987e+03 -1.48937244e+03 -1.46567883e+03 -1.44748767e+03 -1.42765613e+03 -1.40541638e+03 -1.38386951e+03 -1.36365601e+03 -1.34282446e+03 -1.31942236e+03 -1.29564685e+03 -1.27646875e+03 -1.25348584e+03 -1.22958411e+03 -1.20978516e+03 -1.18590503e+03 -1.16108972e+03 -1.13891125e+03 -1.11572876e+03 -1.09297864e+03 -1.06815393e+03 -1.04360608e+03 -1.02009875e+03 -9.96232178e+02 -9.71477234e+02 -9.47665527e+02 -9.23764709e+02 -8.96842346e+02 -8.72063538e+02 -8.48246399e+02 -8.22491455e+02 -7.96763611e+02 -7.71674622e+02 -7.46342773e+02 -7.21030945e+02 -6.94786804e+02 -6.68317505e+02 -6.42820496e+02 -6.16598755e+02 -5.90582336e+02 -5.64587585e+02 -5.37748657e+02 -5.11414093e+02 -4.84857391e+02 -4.58282471e+02 -4.31774048e+02 -4.05065369e+02 -3.78337555e+02 -3.51387268e+02 -3.24449036e+02 -2.97628906e+02 -2.70556366e+02 -2.43614670e+02 -2.16563019e+02 -1.89436707e+02 -1.62383896e+02 -1.35191391e+02 -1.08008263e+02 -8.08463974e+01 -5.36664619e+01 -2.64581318e+01 7.49764740e-01 2.79578800e+01 5.51578331e+01 8.23485794e+01 1.09526512e+02 1.36664780e+02 1.63787231e+02 1.90970505e+02 2.18091934e+02 2.45045349e+02 2.72118896e+02 2.99175049e+02 3.26077942e+02 3.52838318e+02 3.79609528e+02 4.06375488e+02 4.33204315e+02 4.60107941e+02 4.86266449e+02 5.12625732e+02 5.39580017e+02 5.65798462e+02 5.91693481e+02 6.18051147e+02 6.44553650e+02 6.70377502e+02 6.95996338e+02 7.21323242e+02 7.47097534e+02 7.73465088e+02 7.99011597e+02 8.23640137e+02 8.48523560e+02 8.73957092e+02 9.00066162e+02 9.23731262e+02 9.48349548e+02 9.74014404e+02 9.96439209e+02 1.02066449e+03 1.04597058e+03 1.06978271e+03 1.09312170e+03 1.11675391e+03 1.14007068e+03 1.16294739e+03 1.18700659e+03 1.20890625e+03 1.23269824e+03 1.25606409e+03 1.27841833e+03 1.29818982e+03 1.32034753e+03 1.34238184e+03 1.36382996e+03 1.38608606e+03 1.40584570e+03 1.42870532e+03 1.44931812e+03 1.46902698e+03 1.49004224e+03 1.50910181e+03 1.52862610e+03 1.54779272e+03 1.56953650e+03 1.58741577e+03 1.60419812e+03 1.62521973e+03 1.64304370e+03 1.66363403e+03 1.67919592e+03 1.69333765e+03 1.71633472e+03 1.73265930e+03 1.74383862e+03 1.76112476e+03 1.78193567e+03 1.79621680e+03 1.81632166e+03 1.82793298e+03 1.83986145e+03 1.85833984e+03 1.87710425e+03 1.88884363e+03 1.89918530e+03 1.91528430e+03 1.93340576e+03 1.94599890e+03 1.95728015e+03 1.96888867e+03 1.97550574e+03 1.99182751e+03 2.00279480e+03 2.01079993e+03 2.02911829e+03 2.03561829e+03 2.04703284e+03 2.05945337e+03 2.06949219e+03 2.08003174e+03 2.08323096e+03 2.09985596e+03 2.10401392e+03 2.11113794e+03 2.12037231e+03 2.12709521e+03 2.13697998e+03 2.14740308e+03 2.15468115e+03 2.15261841e+03 2.16177344e+03 2.17554858e+03 2.17415894e+03 2.17887280e+03 2.18075122e+03 2.18783545e+03 2.19605640e+03 2.19477808e+03 2.20063379e+03 2.20597241e+03 2.20633350e+03 2.21177612e+03 2.21414209e+03 2.20786035e+03 2.21039771e+03 2.21981641e+03 2.20978198e+03 2.21773315e+03 2.21719189e+03 2.21033447e+03 2.21831274e+03 2.21906226e+03 2.22150415e+03 2.21335791e+03 2.20933252e+03 2.20736987e+03 2.20963306e+03 2.20271826e+03 2.20045288e+03 2.19600537e+03 2.19734131e+03 2.18916162e+03 2.18057568e+03 2.18256079e+03 2.17211279e+03 2.17063647e+03 2.16108740e+03 2.15649292e+03 2.15093384e+03 2.14424927e+03 2.13610913e+03 2.12695288e+03 2.12230054e+03 2.11447095e+03 2.10644800e+03 2.09859180e+03 2.08554712e+03 2.07542139e+03 2.07077710e+03 2.06289600e+03 2.04665930e+03 2.03605151e+03 2.02668872e+03 2.01099670e+03 2.00547461e+03 1.99398279e+03 1.98062903e+03 1.96801099e+03 1.95380469e+03 1.94114307e+03 1.92966589e+03 1.91331982e+03 1.89833325e+03 1.88622021e+03 1.87315686e+03 1.85801147e+03 1.84129858e+03 1.82616174e+03 1.81425378e+03 1.79472791e+03 1.78009338e+03 1.76785901e+03 1.74800281e+03 1.72661169e+03 1.71052271e+03 1.69687317e+03 1.67898926e+03 1.65971252e+03 1.64088843e+03 1.62328503e+03 1.60732007e+03 1.58532751e+03 1.56512463e+03 1.54893213e+03 1.52991260e+03 1.50816772e+03 1.48837891e+03 1.46727759e+03 1.44678918e+03 1.42771289e+03 1.40565405e+03 1.38397229e+03 1.36327759e+03 1.34253149e+03 1.32017871e+03 1.29681543e+03 1.27558582e+03 1.25245117e+03 1.23037061e+03 1.20899622e+03 1.18579480e+03 1.16222461e+03 1.13867480e+03 1.11525854e+03 1.09224927e+03 1.06808423e+03 1.04413196e+03 1.02072009e+03 1.96012085e+03 1.21326440e+03 2.25202441e+03 1.38484326e+03 1.34741211e+03 2.12511841e+03 1.27234790e+03 1.95134460e+03 1.19516187e+03 1.15815234e+03 1.11995337e+03 8.86275940e+02 1.04232922e+03 6.69380859e+02 7.88507935e+02 6.17081360e+02 5.90219055e+02 5.64676392e+02 5.38697144e+02 5.11371063e+02 4.84744263e+02 4.58314606e+02 4.31973083e+02 4.04778839e+02 3.77707489e+02 3.51622223e+02 3.25552521e+02 2.97798645e+02 2.70688171e+02 2.43704895e+02 2.16616547e+02 1.89452408e+02 1.62354279e+02 1.35181000e+02 1.08024879e+02 8.08687286e+01 5.36750870e+01 2.64618797e+01 -7.40734994e-01 -2.79464493e+01 -5.51533890e+01 -8.23463135e+01 -1.09509232e+02 -1.36659653e+02 -1.63810593e+02 -1.90976974e+02 -2.18055222e+02 -2.45060989e+02 -2.72108582e+02 -2.99100861e+02 -3.26114624e+02 -3.52944427e+02 -3.79599091e+02 -4.06372772e+02 -4.33211700e+02 -4.60002441e+02 -4.86503754e+02 -5.12810303e+02 -5.39253357e+02 -5.65750671e+02 -5.91954651e+02 -6.18314392e+02 -6.44434875e+02 -6.70240967e+02 -6.95998291e+02 -7.21679626e+02 -7.47469543e+02 -7.72720459e+02 -7.98460571e+02 -8.24184692e+02 -8.49133301e+02 -8.74017944e+02 -8.99111267e+02 -9.23937012e+02 -9.48674377e+02 -9.73393921e+02 -9.96504883e+02 -1.02111151e+03 -1.04522974e+03 -1.06953369e+03 -1.09329785e+03 -1.11721643e+03 -1.14048682e+03 -1.16293091e+03 -1.18740967e+03 -1.20933508e+03 -1.23147302e+03 -1.25566418e+03 -1.27868408e+03 -1.29853442e+03 -1.31939636e+03 -1.34213379e+03 -1.36538464e+03 -1.38663513e+03 -1.40671545e+03 -1.42821716e+03 -1.44880017e+03 -1.46949243e+03 -1.49034875e+03 -1.50791309e+03 -1.52868018e+03 -1.54798547e+03 -1.56913647e+03 -1.58852222e+03 -1.60504590e+03 -1.62289783e+03 -1.64426965e+03 -1.66627429e+03 -1.67768567e+03 -1.69214978e+03 -1.71694751e+03 -1.73392297e+03 -1.74446924e+03 -1.76120496e+03 -1.78008740e+03 -1.79764014e+03 -1.81811304e+03 -1.82909766e+03 -1.83979675e+03 -1.85605835e+03 -1.87464258e+03 -1.88743079e+03 -1.90077490e+03 -1.91856873e+03 -1.93368127e+03 -1.94577014e+03 -1.95497070e+03 -1.96928638e+03 -1.97867761e+03 -1.98997595e+03 -2.00311462e+03 -2.01284302e+03 -2.02918567e+03 -2.03774524e+03 -2.04873877e+03 -2.06246069e+03 -2.06664014e+03 -2.07885645e+03 -2.08691870e+03 -2.09535571e+03 -2.10689893e+03 -2.11364282e+03 -2.11937988e+03 -2.12695386e+03 -2.13729224e+03 -2.14698096e+03 -2.15459302e+03 -2.15124585e+03 -2.16004639e+03 -2.17140625e+03 -2.17456689e+03 -2.18011841e+03 -2.17975415e+03 -2.18672070e+03 -2.19427905e+03 -2.19783130e+03 -2.20032520e+03 -2.20425708e+03 -2.20406836e+03 -2.20688550e+03 -2.21612964e+03 -2.21096533e+03 -2.21387573e+03 -2.21946729e+03 -2.21031128e+03 -2.21656519e+03 -2.21925220e+03 -2.21298315e+03 -2.21452124e+03 -2.21845093e+03 -2.21905225e+03 -2.20857568e+03 -2.20905127e+03 -2.21379443e+03 -2.21146875e+03 -2.20952271e+03 -2.20203101e+03 -2.22454028e+03 -2.84964893e+03 -2.99676929e+03 -3.27645508e+03 -3.26306226e+03 -3.25454053e+03 -3.24566138e+03 -3.23712402e+03 -3.23060571e+03 -3.23471021e+03 -3.21933057e+03 -2.88383179e+03 -3.36364868e+03 -2.62322754e+03 -3.16432788e+03 -3.15153125e+03 -3.15123462e+03 -3.13543286e+03 -2.56919751e+03 -2.55118896e+03 -2.06053613e+03 -2.64391382e+03 -3.72614819e+03 -4.65591309e+03 19407244. 279000192. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 21756550. -2.16771660e+04 -2.66791772e+03 -4.23068115e+03 -2.61774512e+03 -2.59090015e+03 -2.56671729e+03 -2.31827856e+03 -2.18403174e+03 -1.65885266e+03 -1.64167773e+03 -1.62526904e+03 -1.60707483e+03 -1.58489966e+03 -1.56655261e+03 -1.54814380e+03 -1.52821643e+03 -1.50725391e+03 -1.48825427e+03 -1.46828918e+03 -1.44872314e+03 -1.42642737e+03 -1.40638757e+03 -1.38588477e+03 -1.36183984e+03 -1.34276733e+03 -1.31992639e+03 -1.29634521e+03 -1.27670703e+03 -1.25253821e+03 -1.23028186e+03 -1.21024854e+03 -1.18628589e+03 -1.16109924e+03 -1.13840234e+03 -1.11575867e+03 -1.09319678e+03 -1.06804285e+03 -1.04336853e+03 -1.02094611e+03 -9.96079224e+02 -9.70829651e+02 -9.47667542e+02 -9.23857910e+02 -8.97177124e+02 -8.72203308e+02 -8.48246399e+02 -8.21965088e+02 -7.96670349e+02 -7.71610046e+02 -7.45945618e+02 -7.21074280e+02 -6.94753662e+02 -6.68410522e+02 -6.43073547e+02 -6.16476562e+02 -5.90348999e+02 -7.32685120e+02 -7.36053711e+02 -7.66309204e+02 -7.26072815e+02 -6.86270447e+02 -6.46930786e+02 -6.06838806e+02 -2.34702612e+03 -53939496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.13973955e+10 -4.13973955e+10 0. 0. -1902562432. 62493520. 7.42814148e+02 9.49458191e+02 -1.32815531e+05 1363231488. 0. 0. 0. 0. 0. 78695328. 4.78086377e+03 1.25155994e+03 1.00568297e+05 1.33432825e+03 1.45584314e+03 7.67990662e+02 1.61779724e+03 1.76463550e+03 -7.07308828e+04 1.11749043e+04 5.13124750e+05 1.12385250e+06 4.85116162e+03 -6767677. -3.25245875e+06 -4455400. -6.04277188e+04 -1.02061188e+05 3.74550820e+04 2.50021094e+04 2.68218506e+03 2.76640991e+03 1.55418835e+03 2.91888257e+03 3.04016016e+03 -6.78794385e+03 2.44756875e+06 -1.24192375e+05 1.90291075e+06 2.65176050e+06 2.70202402e+04 3.30324336e+04 4.93684570e+04 -4.07970219e+05 -6.96909668e+02 2.89168188e+05 -6.94491211e+03 -2174376. 11124295. -2.34356203e+05 -1.03287262e+06 4.10743555e+03 3.36078052e+03 2.14369385e+03 2.17388989e+03 2.20351660e+03 2.04391199e+03 1.95755725e+03 1.53276318e+03 1.55337415e+03 1.57366455e+03 2.07385767e+03 2.22172925e+03 2.43692358e+03 2.47188452e+03 2.49517847e+03 4.05918408e+03 5.21976123e+03 1.98602031e+05 2.98070550e+06 200202848. 0. 0. 0. -16776671. -16776671. -16776671. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -15384775. 1.13265693e+04 2.64067944e+03 2.03292847e+03 2.04532422e+03 2.05572949e+03 2.06382935e+03 2.07577686e+03 2.08390527e+03 2.57585986e+03 2.59995142e+03 3.17211646e+03 3.17868994e+03 3.19302124e+03 3.20806665e+03 3.21724023e+03 2.65267261e+03 2.65515552e+03 2.16357104e+03 2.17059644e+03 2.17624756e+03 2.18005518e+03 2.18432153e+03 2.19085059e+03 2.19425024e+03 2.20132397e+03 2.20513379e+03 2.21175244e+03 2.21010571e+03 2.20948438e+03 2.21330640e+03 2.22169897e+03 2.21518970e+03 2.22063257e+03 2.22389819e+03 2.22212256e+03 2.22145361e+03 2.22586401e+03 2.22227905e+03 2.22606738e+03 2.22160498e+03 2.21467627e+03 2.21768677e+03 2.21941064e+03 2.21674536e+03 2.21587769e+03 2.20875586e+03 2.20539771e+03 2.20529150e+03 2.19692993e+03 2.19309424e+03 2.19607056e+03 2.19025610e+03 2.17850439e+03 2.17333032e+03 2.16712183e+03 2.16334497e+03 2.15861084e+03 2.14982837e+03 2.14307568e+03 2.13682861e+03 2.12460571e+03 2.12125000e+03 2.11220337e+03 2.10229175e+03 2.09114526e+03 2.08245361e+03 2.07412012e+03 2.06865332e+03 2.05298120e+03 2.04171313e+03 2.03290527e+03 2.01980298e+03 2.01051550e+03 2.00279175e+03 1.98488965e+03 1.97438220e+03 1.96136536e+03 1.94505505e+03 1.93636584e+03 1.91986096e+03 1.90391016e+03 1.89628455e+03 1.87791956e+03 1.86237830e+03 1.85010901e+03 1.83215320e+03 1.81967944e+03 1.80139343e+03 1.78703088e+03 1.76927917e+03 1.75180359e+03 1.73530249e+03 1.71882471e+03 1.70319409e+03 1.68349805e+03 1.66534009e+03 1.64563782e+03 1.63127771e+03 1.61257019e+03 1.58903711e+03 1.57151868e+03 1.55254749e+03 1.53148157e+03 1.51333521e+03 1.49429126e+03 1.47221460e+03 1.45254102e+03 1.43233118e+03 1.41046448e+03 1.38839380e+03 1.36759485e+03 1.34745801e+03 1.32294409e+03 1.30062927e+03 1.28182214e+03 1.25784924e+03 1.23430200e+03 1.21221167e+03 1.18986816e+03 1.16652234e+03 1.14224890e+03 1.11960669e+03 1.09664844e+03 1.07174194e+03 1.04706067e+03 1.02349225e+03 9.99315002e+02 9.75006348e+02 9.51248169e+02 9.26422058e+02 8.99594360e+02 8.75006836e+02 8.50794312e+02 8.25727783e+02 7.99602295e+02 7.74657043e+02 7.49003052e+02 7.22911133e+02 6.97240234e+02 6.70934387e+02 6.44812683e+02 6.18750000e+02 5.92799316e+02 5.66226440e+02 5.39616150e+02 5.13601013e+02 4.86836731e+02 4.59817566e+02 4.33150696e+02 4.06622986e+02 3.79772278e+02 3.52747070e+02 3.25618103e+02 2.98714935e+02 2.71698730e+02 2.44557037e+02 2.17436356e+02 1.90250336e+02 1.63076904e+02 1.35760269e+02 1.08528641e+02 8.12780991e+01 5.39943390e+01 2.67301292e+01 -5.60953915e-01 -2.78525715e+01 -5.51723366e+01 -8.24700851e+01 -1.09725998e+02 -1.36967514e+02 -1.64161224e+02 -1.91431061e+02 -2.18637390e+02 -2.45662308e+02 -2.72810760e+02 -3.00000946e+02 -3.27151489e+02 -3.54295685e+02 -3.80781403e+02 -4.07534088e+02 -4.34386932e+02 -4.61093719e+02 -4.87962219e+02 -6.29764465e+02 -6.65290344e+02 -7.05285278e+02 -7.34568848e+02 -6.19824219e+02 -6.45916809e+02 -8.57399231e+02 -9.29976990e+02 -1.08734167e+03 -1.12646301e+03 -1.16492761e+03 -1.97324622e+03 -2.61223779e+03 -2.42626611e+03 -2.02962305e+03 -1.35613855e+03 -1.39104871e+03 -1.42883862e+03 -1.46486426e+03 -1.50141589e+03 -1.53908557e+03 -1.57652039e+03 -1.61199902e+03 -1.64755200e+03 -1.56640417e+03 -1.71969507e+03 -1.57005273e+03 -1.78673840e+03 -1.69986230e+03 -1.62265417e+03 -1.25887427e+03 -1.28191272e+03 -1.30254700e+03 -1.32464014e+03 -1.34701562e+03 -1.36761902e+03 -1.38971350e+03 -1.41222583e+03 -1.43322412e+03 -1.45372217e+03 -1.47169043e+03 -1.49471875e+03 -1.51383838e+03 -1.53230200e+03 -1.55407788e+03 -1.57304968e+03 -1.59296313e+03 -1.61014172e+03 -1.62868774e+03 -1.65057727e+03 -1.66868774e+03 -1.68651367e+03 -1.70019775e+03 -1.71823169e+03 -1.73870691e+03 -1.75057715e+03 -1.76901807e+03 -1.78584106e+03 -1.80083630e+03 -1.82201489e+03 -1.83370654e+03 -1.84781409e+03 -1.86311902e+03 -1.88198376e+03 -1.89546155e+03 -1.90724561e+03 -1.92285437e+03 -1.93423840e+03 -1.95183484e+03 -1.96337000e+03 -1.96890295e+03 -1.97908411e+03 -1.99880164e+03 -2.01056348e+03 -2.01736816e+03 -2.03324646e+03 -2.04493018e+03 -2.05854565e+03 -2.06713428e+03 -2.07456055e+03 -2.08825415e+03 -2.09268652e+03 -2.10171313e+03 -2.10823120e+03 -2.11633472e+03 -2.12814526e+03 -2.13214746e+03 -2.14158179e+03 -2.15154907e+03 -2.15414355e+03 -2.16405396e+03 -2.17256592e+03 -2.18078809e+03 -2.18012476e+03 -2.18508496e+03 -2.18835107e+03 -2.19284009e+03 -2.20152637e+03 -2.20734204e+03 -2.21385376e+03 -2.21218970e+03 -2.21095166e+03 -2.21633984e+03 -2.21998779e+03 -2.21629346e+03 -2.21821484e+03 -2.22695972e+03 -2.22704419e+03 -2.22623511e+03 -2.21907031e+03 -2.22445337e+03 -2.22255786e+03 -2.22559204e+03 -2.22074048e+03 -2.21696899e+03 -2.21719800e+03 -2.21493628e+03 -2.21445483e+03 -2.21302393e+03 -2.21047339e+03 -2.20525854e+03 -2.19749341e+03 -2.19388013e+03 -2.19480908e+03 -2.19147217e+03 -2.18121631e+03 -2.17528540e+03 -2.16418677e+03 -2.16516138e+03 -2.15757007e+03 -2.14916382e+03 -2.14734521e+03 -2.13769556e+03 -2.12695728e+03 -2.12082520e+03 -2.11820581e+03 -2.10515894e+03 -2.08567017e+03 -2.07848462e+03 -2.08097852e+03 -2.07005396e+03 -2.05681665e+03 -2.04376086e+03 -2.02882715e+03 -2.01651038e+03 -2.00730383e+03 -2.00408960e+03 -1.98425781e+03 -1.97366003e+03 -1.96195911e+03 -1.94678223e+03 -1.93472986e+03 -1.92078040e+03 -1.90681042e+03 -1.89358960e+03 -1.87767236e+03 -1.86590503e+03 -1.84929150e+03 -1.83139441e+03 -1.81896094e+03 -1.80082190e+03 -1.78722485e+03 -1.77130701e+03 -1.75371521e+03 -1.73393579e+03 -1.71663342e+03 -1.70226819e+03 -1.68183264e+03 -1.66684180e+03 -1.64731079e+03 -1.62827966e+03 -1.61180225e+03 -1.59023242e+03 -1.57144971e+03 -1.55314307e+03 -1.53325134e+03 -1.51366919e+03 -1.49337280e+03 -1.47117773e+03 -1.45340869e+03 -1.43269434e+03 -1.41102295e+03 -1.38908813e+03 -1.36666162e+03 -1.34696460e+03 -1.32334045e+03 -1.30069604e+03 -1.28169446e+03 -1.25775513e+03 -1.23395422e+03 -1.21245447e+03 -1.19020752e+03 -1.16618811e+03 -1.14215979e+03 -1.11979761e+03 -1.09659680e+03 -1.07142932e+03 -1.04739233e+03 -1.02314276e+03 -9.99469238e+02 -9.74898010e+02 -9.51070679e+02 -9.26337585e+02 -8.99976562e+02 -8.75132812e+02 -8.50367615e+02 -8.25421814e+02 -7.99730103e+02 -7.74691345e+02 -7.48924377e+02 -7.23087708e+02 -6.97433167e+02 -6.70934082e+02 -6.44502930e+02 -6.18646362e+02 -5.92729919e+02 -5.66375427e+02 -5.39627563e+02 -5.13394226e+02 -4.86777954e+02 -4.59840363e+02 -4.33233032e+02 -4.06652588e+02 -3.79628876e+02 -3.52590607e+02 -3.25634705e+02 -2.98693817e+02 -2.71620514e+02 -2.44471481e+02 -2.17328186e+02 -1.90190018e+02 -1.63104446e+02 -1.35840958e+02 -1.08499847e+02 -8.12617111e+01 -5.40138283e+01 -2.67077904e+01 5.94026148e-01 2.78989735e+01 5.51816483e+01 8.24534760e+01 1.09733673e+02 1.36951889e+02 1.64147003e+02 1.91422974e+02 2.18628677e+02 2.45654007e+02 2.72794800e+02 2.99974457e+02 3.26930511e+02 3.53820831e+02 3.80665924e+02 4.07530823e+02 4.34372894e+02 4.61264008e+02 4.87853577e+02 5.14300781e+02 5.40988831e+02 5.67190674e+02 5.93441345e+02 6.19798767e+02 6.46248169e+02 6.72658386e+02 6.98064453e+02 7.23271973e+02 7.49967957e+02 7.76113220e+02 8.00720093e+02 8.26697205e+02 8.52008850e+02 8.76166199e+02 9.01108521e+02 9.26517700e+02 9.51523682e+02 9.76490173e+02 1.00033325e+03 1.02419238e+03 1.04869202e+03 1.07278113e+03 1.09729871e+03 1.12013269e+03 1.14317566e+03 1.16683313e+03 1.19046814e+03 1.21241150e+03 1.23632947e+03 1.26015735e+03 1.28203003e+03 1.30281885e+03 1.32543762e+03 1.34696289e+03 1.36746008e+03 1.38973962e+03 1.41052332e+03 1.43241809e+03 1.45288416e+03 1.47114929e+03 1.49426135e+03 1.51323230e+03 1.53471338e+03 1.55394165e+03 1.57256543e+03 1.59198267e+03 1.60830408e+03 1.62980713e+03 1.65287317e+03 1.66917273e+03 1.68629614e+03 1.70031213e+03 1.71712817e+03 1.74077820e+03 1.74911646e+03 1.76893030e+03 1.78824512e+03 1.79876343e+03 1.82088196e+03 1.83548145e+03 1.84687146e+03 1.86443872e+03 1.87976245e+03 1.89197668e+03 1.90568420e+03 1.92225476e+03 1.93544641e+03 1.95329248e+03 1.96533606e+03 1.96981946e+03 1.98117383e+03 2.00116492e+03 2.01008508e+03 2.01875830e+03 2.03498254e+03 2.04597278e+03 2.05737134e+03 2.06447583e+03 2.07703491e+03 2.08862427e+03 2.09228369e+03 2.10545068e+03 2.10892578e+03 2.11915723e+03 2.12722363e+03 2.13491626e+03 2.14373218e+03 2.15388330e+03 2.15538599e+03 2.16151733e+03 2.17097363e+03 2.17617822e+03 2.18078467e+03 2.18656787e+03 2.18863208e+03 2.19377954e+03 2.19917529e+03 2.20371362e+03 2.20865820e+03 2.21443237e+03 2.21582788e+03 2.21320312e+03 2.21600879e+03 2.21584961e+03 2.22031616e+03 2.22598999e+03 2.22528003e+03 2.22416528e+03 2.21892090e+03 2.22328540e+03 2.22272656e+03 2.22515796e+03 2.22366846e+03 2.21991162e+03 2.21769897e+03 2.21745068e+03 2.20750757e+03 2.21177759e+03 2.20853174e+03 2.20416113e+03 2.20141504e+03 2.19086841e+03 2.18937793e+03 2.18792944e+03 2.18250732e+03 2.17843945e+03 2.16747998e+03 2.16603735e+03 2.15862451e+03 2.14711279e+03 2.14607788e+03 2.14038525e+03 2.12466235e+03 2.12071094e+03 2.11518799e+03 2.10089111e+03 2.09049414e+03 2.08136694e+03 2.08007788e+03 2.07037280e+03 2.05539697e+03 2.04014050e+03 2.03269128e+03 2.01447986e+03 2.01105029e+03 2.00445837e+03 1.98532300e+03 1.97385315e+03 1.96244897e+03 1.94565845e+03 1.93697058e+03 1.92096655e+03 1.90346826e+03 1.89601831e+03 1.87995691e+03 1.86476367e+03 1.84837378e+03 1.83225696e+03 1.81984082e+03 1.80114636e+03 1.78779065e+03 1.77188416e+03 1.75353809e+03 1.73325903e+03 1.71735364e+03 1.70378821e+03 1.68254736e+03 1.66593994e+03 1.64583728e+03 1.62938513e+03 1.61325293e+03 1.59074451e+03 1.57147375e+03 1.55147424e+03 1.53231958e+03 1.51316626e+03 1.49325830e+03 1.47219275e+03 1.45246472e+03 1.43250818e+03 1.41074597e+03 1.38928186e+03 1.36749048e+03 1.34738159e+03 1.32395764e+03 1.30101123e+03 1.28160278e+03 1.25686682e+03 1.23443420e+03 1.21188318e+03 1.18878198e+03 1.16653284e+03 1.14235645e+03 1.11948792e+03 1.09613867e+03 1.07130603e+03 1.04731274e+03 1.02338361e+03 1.31873022e+03 1.37332825e+03 1.42710938e+03 1.39004504e+03 1.35233752e+03 1.31390564e+03 1.27575037e+03 1.24036304e+03 1.20308618e+03 1.16278076e+03 1.12542700e+03 9.72536865e+02 1.04749536e+03 6.72198425e+02 8.21345825e+02 6.17613770e+02 5.91065369e+02 5.68769653e+02 5.42110840e+02 5.13499268e+02 4.86818329e+02 4.60119476e+02 4.33684387e+02 4.06044128e+02 3.78241516e+02 3.53072083e+02 3.27468384e+02 2.99112030e+02 2.71884186e+02 2.44692047e+02 2.17463776e+02 1.90217163e+02 1.63048630e+02 1.35789612e+02 1.08535912e+02 8.12872314e+01 5.40074615e+01 2.67369938e+01 -5.66824257e-01 -2.79066067e+01 -5.52157516e+01 -8.24759064e+01 -1.09703598e+02 -1.36954346e+02 -1.64188965e+02 -1.91437317e+02 -2.18568878e+02 -2.45655350e+02 -2.72834412e+02 -2.99915039e+02 -3.26965332e+02 -3.53904968e+02 -3.80722107e+02 -4.07651733e+02 -4.34417603e+02 -4.61162354e+02 -4.87803741e+02 -5.14365417e+02 -5.40841675e+02 -5.67358398e+02 -5.93670044e+02 -6.20000061e+02 -6.46242126e+02 -6.72450073e+02 -6.98110962e+02 -7.23797302e+02 -7.49954224e+02 -7.75595520e+02 -8.00808044e+02 -8.27023010e+02 -8.52177979e+02 -8.76459106e+02 -9.01025635e+02 -9.26456787e+02 -9.51407532e+02 -9.76669128e+02 -1.00083191e+03 -1.02472766e+03 -1.04835437e+03 -1.07200427e+03 -1.09704956e+03 -1.12058984e+03 -1.14470386e+03 -1.16739087e+03 -1.18969019e+03 -1.21268042e+03 -1.23630591e+03 -1.25946326e+03 -1.28247327e+03 -1.30282849e+03 -1.32425684e+03 -1.34632666e+03 -1.36924670e+03 -1.39130591e+03 -1.41053174e+03 -1.43248669e+03 -1.45437708e+03 -1.47335168e+03 -1.49463159e+03 -1.51276978e+03 -1.53331238e+03 -1.55368555e+03 -1.57372363e+03 -1.59230615e+03 -1.60839185e+03 -1.62817590e+03 -1.65168201e+03 -1.66952551e+03 -1.68424597e+03 -1.69988440e+03 -1.71874597e+03 -1.74125818e+03 -1.75044116e+03 -1.76898706e+03 -1.78755603e+03 -1.79985132e+03 -1.82296631e+03 -1.83463647e+03 -1.84654956e+03 -1.86516504e+03 -1.88133630e+03 -1.89376990e+03 -1.90691418e+03 -1.92371643e+03 -1.93604150e+03 -1.95031250e+03 -1.96221228e+03 -1.97216199e+03 -1.98603613e+03 -2.00135571e+03 -2.00723962e+03 -2.02081848e+03 -2.03375378e+03 -2.04250098e+03 -2.05758081e+03 -2.06663940e+03 -2.07468945e+03 -2.09106787e+03 -2.09251099e+03 -2.10590698e+03 -2.10819287e+03 -2.11917188e+03 -2.13199487e+03 -2.13211108e+03 -2.14275244e+03 -2.15242480e+03 -2.15566235e+03 -2.16277173e+03 -2.17236475e+03 -2.18056567e+03 -2.18313086e+03 -2.18405908e+03 -2.18587036e+03 -2.19040894e+03 -2.19682520e+03 -2.20367334e+03 -2.21111572e+03 -2.21347656e+03 -2.21020386e+03 -2.21784351e+03 -2.22100977e+03 -2.21545654e+03 -2.21873438e+03 -2.22428931e+03 -2.22058789e+03 -2.22539575e+03 -2.22107153e+03 -2.21981982e+03 -2.22694312e+03 -2.22472192e+03 -2.22513965e+03 -2.21309717e+03 -2.21791211e+03 -2.21402100e+03 -2.21058325e+03 -2.21247095e+03 -2.21592700e+03 -2.22936963e+03 -2.69822461e+03 -2.70760938e+03 -3.30251538e+03 -3.28646997e+03 -3.27204834e+03 -3.25592139e+03 -3.24824414e+03 -3.24840820e+03 -3.23966333e+03 -3.22467847e+03 -2.65152441e+03 -3.37799927e+03 -2.93826343e+03 -3.18407324e+03 -3.17758521e+03 -3.16366650e+03 -3.14446387e+03 -2.83923633e+03 -2.69216016e+03 -2.06621313e+03 -2.05600659e+03 -2.51544312e+03 -2.61993677e+03 -5.02783350e+03 -2.07924727e+04 -35040284. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -202182896. -202182896. 13671897. 16994008. -4.75091650e+03 -5.63930508e+04 18262880. -5.17098584e+03 -4.10052246e+03 -2.49703882e+03 -2.46242627e+03 -2.43907153e+03 -2.41225586e+03 -2.18540381e+03 -2.04462402e+03 -1.55399500e+03 -1.53262305e+03 -1.51333228e+03 -1.49311365e+03 -1.47201501e+03 -1.88156519e+03 -1.95061963e+03 -2.10993604e+03 -2.08113013e+03 -2.04374084e+03 -2.01485730e+03 -1.98220728e+03 -1.94820117e+03 -1.91839136e+03 -1.88006995e+03 -1.84601367e+03 -1.81363196e+03 -1.78094043e+03 -1.74261938e+03 -1.70746460e+03 -1.67538110e+03 -1.64168298e+03 -1.60221216e+03 -1.45225183e+03 -1.53320483e+03 -1.36069312e+03 -1.45711731e+03 -1.42154077e+03 -1.38673071e+03 -1.34685571e+03 -1.30907751e+03 -1.27314514e+03 -1.23488428e+03 -1.19585901e+03 -1.15809509e+03 -1.12030664e+03 -1.08204175e+03 -1.04324377e+03 -1.00362396e+03 -9.65731384e+02 -9.25235596e+02 -8.85806213e+02 -1.32862805e+03 -1.55492920e+03 1.75568875e+06 8790920. 2.54955609e+05 1.07665984e+05 5.96893516e+04 -9049348. -616686720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.13973955e+10 -4.13973955e+10 0. 0. 0. 0. -440064992. -1.32815531e+05 -1.32815531e+05 1363231488. 0. 600903360. 8.76235062e+05 2.79726825e+06 -5.40771350e+06 51167944. 1.98555546e+10 1.98555546e+10 0. -248096720. -248096720. -9491195. -31841854. -31841854. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56744288. 56744288. 29543500. -35303540. -35303540. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 450898272. 450898272. 450898272. 0. 0. 2446779. 1.65293730e+04 8.27129004e+03 2.16370874e+03 3.49545215e+03 2.22276538e+03 1.85708667e+03 1.87289429e+03 1.54212146e+03 2.02824292e+03 2.16867334e+03 3.87303735e+03 4.99316895e+03 3.07393250e+05 -3.45545703e+04 -2.33892562e+05 1.18978338e+06 23614176. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 6.85282150e+06 -1.07543688e+06 -1.67580188e+05 5.53391797e+03 3.94562207e+03 2.03377954e+03 2.04521851e+03 2.05220557e+03 2.06536914e+03 2.07937427e+03 2.08755054e+03 2.09530225e+03 2.72983618e+03 2.89100928e+03 3.19594604e+03 3.20216919e+03 3.21539893e+03 3.23675586e+03 3.24411401e+03 2.98453882e+03 2.83456958e+03 2.17727979e+03 2.18483203e+03 2.18620166e+03 2.19197339e+03 2.20040332e+03 2.20531787e+03 2.20978174e+03 2.21395557e+03 2.21438696e+03 2.21854932e+03 2.22305566e+03 2.22881885e+03 2.22994019e+03 2.23400928e+03 2.23010059e+03 2.23176855e+03 2.23634082e+03 2.23590234e+03 2.23831860e+03 2.23751807e+03 2.23757471e+03 2.23632764e+03 2.23626245e+03 2.23621924e+03 2.24049292e+03 2.23363354e+03 2.22869849e+03 2.22007202e+03 2.22464990e+03 2.22171680e+03 2.21422974e+03 2.20961865e+03 2.20748022e+03 2.20025195e+03 2.20150537e+03 2.19814014e+03 2.18666089e+03 2.17546338e+03 2.17628516e+03 2.17279150e+03 2.16137256e+03 2.15961816e+03 2.14694458e+03 2.13882275e+03 2.13134839e+03 2.12256714e+03 2.11569556e+03 2.10506470e+03 2.09675977e+03 2.08617334e+03 2.07544653e+03 2.06831714e+03 2.05255273e+03 2.04366064e+03 2.03513196e+03 2.01904114e+03 2.01178857e+03 2.00079419e+03 1.98588525e+03 1.97117590e+03 1.95731470e+03 1.94418042e+03 1.93161938e+03 1.91961609e+03 1.90164160e+03 1.88776892e+03 1.87595557e+03 1.86041028e+03 1.84171057e+03 1.82769690e+03 1.81061841e+03 1.79800549e+03 1.78212207e+03 1.76254663e+03 1.74320667e+03 1.72699585e+03 1.71440283e+03 1.69265674e+03 1.67378162e+03 1.65687305e+03 1.63978845e+03 1.62021130e+03 1.60007703e+03 1.58166589e+03 1.56024280e+03 1.54129431e+03 1.52290930e+03 1.50199072e+03 1.48082471e+03 1.45923376e+03 1.44013684e+03 1.41899011e+03 1.39589417e+03 1.37548352e+03 1.35393030e+03 1.33054114e+03 1.30852112e+03 1.28713220e+03 1.26505640e+03 1.24234863e+03 1.21908484e+03 1.19525513e+03 1.17229688e+03 1.14928076e+03 1.12559241e+03 1.10188440e+03 1.07775952e+03 1.05353516e+03 1.02777124e+03 1.00425897e+03 9.81258728e+02 9.55482178e+02 9.30921631e+02 9.05201965e+02 8.80003418e+02 8.55005493e+02 8.29639099e+02 8.04419739e+02 7.78655701e+02 7.52432068e+02 7.26638123e+02 7.00805359e+02 6.74643372e+02 6.48014587e+02 6.21803284e+02 5.95923523e+02 5.68868958e+02 5.42377319e+02 5.16195068e+02 4.89311676e+02 4.62065216e+02 4.35278625e+02 4.08519592e+02 3.81378448e+02 3.54462646e+02 3.27119263e+02 2.99946075e+02 2.72847961e+02 2.45527634e+02 2.18254852e+02 1.90937637e+02 1.63574448e+02 1.36131622e+02 1.08750977e+02 8.13402786e+01 5.38635025e+01 2.64317169e+01 -1.00372088e+00 -2.84409447e+01 -5.59179802e+01 -8.33753815e+01 -1.10797935e+02 -1.38190750e+02 -1.65547302e+02 -1.92975891e+02 -2.20293961e+02 -2.47478485e+02 -2.74793793e+02 -3.02106506e+02 -3.29536530e+02 -3.57074219e+02 -3.83295685e+02 -4.10167999e+02 -4.37224976e+02 -4.63832581e+02 -4.91336823e+02 -6.43181946e+02 -6.89648499e+02 -8.20235962e+02 -7.98526306e+02 -6.24163086e+02 -6.49780640e+02 -6.76359253e+02 -7.03062378e+02 -7.28920410e+02 -7.53676270e+02 -7.79385193e+02 -9.90197449e+02 -1.02591602e+03 -1.06084326e+03 -1.08800635e+03 -9.07780884e+02 -9.32098267e+02 -9.57002197e+02 -9.81697937e+02 -1.00620160e+03 -1.35007104e+03 -1.46491577e+03 -1.61199902e+03 -1.64755200e+03 -1.51506580e+03 -1.47451196e+03 -1.17391345e+03 -1.19628955e+03 -1.22043823e+03 -1.24322485e+03 -1.26587549e+03 -1.28947058e+03 -1.31090686e+03 -1.33335352e+03 -1.35483325e+03 -1.37602673e+03 -1.39954297e+03 -1.42060364e+03 -1.44100098e+03 -1.46338782e+03 -1.48265381e+03 -1.50251721e+03 -1.52236963e+03 -1.54456458e+03 -1.56251453e+03 -1.58165137e+03 -1.60278491e+03 -1.62096594e+03 -1.63795789e+03 -1.65812048e+03 -1.67895923e+03 -1.69731250e+03 -1.71054382e+03 -1.72907043e+03 -1.75055042e+03 -1.76396362e+03 -1.77917944e+03 -1.79400574e+03 -1.81147424e+03 -1.83404395e+03 -1.84184717e+03 -1.85402795e+03 -1.87693884e+03 -1.89651331e+03 -1.90875061e+03 -1.91754285e+03 -1.93395239e+03 -1.94644763e+03 -1.96192358e+03 -1.97517126e+03 -1.97938721e+03 -1.99576514e+03 -2.01291187e+03 -2.02230884e+03 -2.03288062e+03 -2.04729993e+03 -2.05564355e+03 -2.06805005e+03 -2.08315649e+03 -2.08910986e+03 -2.09805835e+03 -2.10792358e+03 -2.11583887e+03 -2.12154468e+03 -2.12827759e+03 -2.14389648e+03 -2.14998853e+03 -2.15615894e+03 -2.16432788e+03 -2.16803223e+03 -2.17732642e+03 -2.18512109e+03 -2.18866553e+03 -2.19296973e+03 -2.20188110e+03 -2.20408228e+03 -2.20858691e+03 -2.21537402e+03 -2.21452051e+03 -2.21958228e+03 -2.22379614e+03 -2.23115601e+03 -2.22919263e+03 -2.23189478e+03 -2.22902344e+03 -2.23146069e+03 -2.24022729e+03 -2.23616895e+03 -2.23692065e+03 -2.23321265e+03 -2.23137695e+03 -2.23404395e+03 -2.23679468e+03 -2.24291699e+03 -2.23622168e+03 -2.23374292e+03 -2.22901001e+03 -2.22328296e+03 -2.22378613e+03 -2.22559937e+03 -2.21619360e+03 -2.20911255e+03 -2.20318750e+03 -2.20215674e+03 -2.20063452e+03 -2.19865869e+03 -2.18859912e+03 -2.17532715e+03 -2.17854932e+03 -2.17037842e+03 -2.16404004e+03 -2.15911035e+03 -2.14332959e+03 -2.13910913e+03 -2.13473682e+03 -2.12690845e+03 -2.11557129e+03 -2.10032104e+03 -2.09834399e+03 -2.09191382e+03 -2.07501147e+03 -2.07015674e+03 -2.05354834e+03 -2.04246460e+03 -2.03435059e+03 -2.01951880e+03 -2.01210547e+03 -2.00035205e+03 -1.98378528e+03 -1.97131555e+03 -1.95979236e+03 -1.94211926e+03 -1.92972107e+03 -1.92114465e+03 -1.90460547e+03 -1.88486096e+03 -1.87590857e+03 -1.86131738e+03 -1.84141956e+03 -1.82950427e+03 -1.81028943e+03 -1.79645264e+03 -1.78134558e+03 -1.76227930e+03 -1.74294690e+03 -1.72630518e+03 -1.71546533e+03 -1.69283142e+03 -1.67416162e+03 -1.65735925e+03 -1.63889221e+03 -1.61988062e+03 -1.59932764e+03 -1.58042896e+03 -1.55983972e+03 -1.54195483e+03 -1.52334814e+03 -1.50149658e+03 -1.47952991e+03 -1.45932031e+03 -1.44072046e+03 -1.41896277e+03 -1.39577002e+03 -1.37509106e+03 -1.35271497e+03 -1.33028247e+03 -1.30893518e+03 -1.28703772e+03 -1.26468884e+03 -1.24276709e+03 -1.21920349e+03 -1.19466760e+03 -1.17214050e+03 -1.14975830e+03 -1.12524438e+03 -1.10138879e+03 -1.07829553e+03 -1.05364185e+03 -1.02850134e+03 -1.00429285e+03 -9.80042725e+02 -9.55337524e+02 -9.31015930e+02 -9.05756714e+02 -8.80103699e+02 -8.54313660e+02 -8.29246399e+02 -8.04619446e+02 -7.78593750e+02 -7.52385620e+02 -7.26710693e+02 -7.00815125e+02 -6.74567810e+02 -6.47737366e+02 -6.21799744e+02 -5.95703735e+02 -5.68709473e+02 -5.42409912e+02 -5.16035034e+02 -4.89367188e+02 -4.62180786e+02 -4.35148315e+02 -4.08514404e+02 -3.81287994e+02 -3.54213623e+02 -3.27094086e+02 -2.99898926e+02 -2.72770874e+02 -2.45421127e+02 -2.18085037e+02 -1.90823029e+02 -1.63633133e+02 -1.36230179e+02 -1.08671631e+02 -8.12954330e+01 -5.39020767e+01 -2.64295998e+01 1.02025104e+00 2.84416599e+01 5.58845558e+01 8.33424301e+01 1.10794083e+02 1.38164581e+02 1.65515762e+02 1.92963745e+02 2.20331940e+02 2.47525681e+02 2.74807922e+02 3.02145294e+02 3.29255463e+02 3.56117371e+02 3.83165070e+02 4.10455719e+02 4.37202667e+02 4.64224243e+02 4.91426697e+02 5.17734924e+02 5.44207886e+02 5.70691833e+02 5.97622925e+02 6.24146301e+02 6.49993530e+02 6.76108215e+02 7.02470276e+02 7.28796143e+02 7.54753967e+02 7.80262451e+02 8.05694336e+02 8.31763672e+02 8.57234497e+02 8.81329102e+02 9.06766479e+02 9.33140808e+02 9.57393005e+02 9.81600159e+02 1.00537622e+03 1.03094971e+03 1.05567200e+03 1.07964075e+03 1.10245386e+03 1.12711914e+03 1.15087634e+03 1.17467236e+03 1.19667822e+03 1.22019360e+03 1.24526697e+03 1.26612683e+03 1.28841003e+03 1.31120251e+03 1.33313782e+03 1.35473706e+03 1.37484961e+03 1.39963416e+03 1.42045374e+03 1.44086877e+03 1.46434717e+03 1.48214563e+03 1.50166357e+03 1.52155273e+03 1.54527051e+03 1.56241614e+03 1.58046875e+03 1.60351062e+03 1.62012720e+03 1.63926196e+03 1.65927222e+03 1.67728320e+03 1.69291785e+03 1.70951196e+03 1.72937622e+03 1.75111292e+03 1.76295264e+03 1.78008191e+03 1.79488794e+03 1.81056421e+03 1.83072485e+03 1.84244495e+03 1.85807410e+03 1.87548267e+03 1.89326074e+03 1.90591309e+03 1.91257263e+03 1.93119995e+03 1.94798914e+03 1.96290942e+03 1.97704980e+03 1.98206360e+03 1.99652808e+03 2.01196179e+03 2.02006628e+03 2.03764624e+03 2.04689539e+03 2.05015454e+03 2.06650928e+03 2.08204834e+03 2.08764819e+03 2.09305469e+03 2.10637769e+03 2.11817896e+03 2.12041919e+03 2.12897412e+03 2.13811890e+03 2.14719385e+03 2.15979932e+03 2.17043018e+03 2.16641187e+03 2.17639062e+03 2.18630444e+03 2.19044971e+03 2.18987427e+03 2.19845142e+03 2.20729004e+03 2.20422021e+03 2.21214136e+03 2.21957910e+03 2.22013745e+03 2.22982642e+03 2.22800977e+03 2.22534790e+03 2.22445923e+03 2.22460181e+03 2.23186768e+03 2.23729419e+03 2.23483618e+03 2.24086206e+03 2.23061670e+03 2.22811841e+03 2.23641895e+03 2.23655347e+03 2.23906372e+03 2.23875244e+03 2.23346143e+03 2.22583594e+03 2.21472852e+03 2.22413525e+03 2.22940845e+03 2.21894800e+03 2.20708374e+03 2.20215405e+03 2.20509937e+03 2.20460522e+03 2.19687036e+03 2.18194141e+03 2.17570776e+03 2.18204370e+03 2.17105298e+03 2.15976855e+03 2.15970093e+03 2.14763672e+03 2.13716016e+03 2.13263110e+03 2.12174756e+03 2.11494116e+03 2.10353052e+03 2.09565796e+03 2.09060107e+03 2.07289380e+03 2.06830811e+03 2.05249585e+03 2.04335547e+03 2.03088696e+03 2.01659167e+03 2.01315308e+03 1.99802539e+03 1.98604932e+03 1.97429919e+03 1.95695264e+03 1.94573975e+03 1.93071619e+03 1.91805518e+03 1.90648633e+03 1.88701990e+03 1.87791187e+03 1.85976196e+03 1.84063916e+03 1.82835718e+03 1.80980225e+03 1.79887280e+03 1.78022473e+03 1.76180005e+03 1.74186182e+03 1.72591577e+03 1.71503784e+03 1.69279395e+03 1.67337878e+03 1.65566418e+03 1.64067322e+03 1.62070276e+03 1.60044214e+03 1.58103467e+03 1.56021399e+03 1.54174561e+03 1.52261011e+03 1.50172351e+03 1.47989844e+03 1.46025549e+03 1.43998755e+03 1.41873645e+03 1.39737329e+03 1.37547168e+03 1.35370483e+03 1.33076819e+03 1.30841064e+03 1.28737134e+03 1.26426465e+03 1.24221289e+03 1.21886816e+03 1.19553284e+03 1.17333411e+03 1.14828650e+03 1.12507654e+03 1.10125537e+03 1.07759265e+03 1.05365930e+03 1.02879028e+03 1.00478668e+03 9.80551392e+02 9.54925049e+02 9.30269287e+02 9.05267334e+02 8.79712402e+02 8.54594727e+02 8.28833679e+02 8.03984558e+02 9.91018066e+02 7.52608154e+02 9.61388977e+02 7.00536194e+02 6.74791382e+02 6.48296326e+02 6.19878601e+02 5.93683533e+02 5.71686768e+02 5.45346191e+02 5.16165039e+02 4.89345428e+02 4.62468140e+02 4.35597168e+02 4.07583832e+02 3.79452271e+02 3.55029144e+02 3.29375702e+02 3.00340637e+02 2.73005768e+02 2.45617035e+02 2.18317627e+02 1.90925201e+02 1.63556137e+02 1.36130127e+02 1.08725365e+02 8.13182449e+01 5.38751335e+01 2.64488392e+01 -1.03410292e+00 -2.85028458e+01 -5.59561501e+01 -8.33882751e+01 -1.10769913e+02 -1.38168488e+02 -1.65548965e+02 -1.92984772e+02 -2.20266525e+02 -2.47502380e+02 -2.74847504e+02 -3.02044342e+02 -3.29282745e+02 -3.56328735e+02 -3.83310059e+02 -4.10549713e+02 -4.37322906e+02 -4.64141388e+02 -4.91171783e+02 -5.17810425e+02 -5.44298401e+02 -5.70873352e+02 -5.97580139e+02 -6.24215271e+02 -6.50349731e+02 -6.76370483e+02 -7.02544800e+02 -7.28895264e+02 -7.54811584e+02 -7.80538635e+02 -8.05476440e+02 -8.31765381e+02 -8.57545105e+02 -8.81441162e+02 -9.07408325e+02 -9.33050903e+02 -9.57614990e+02 -9.81895813e+02 -1.00521466e+03 -1.03075525e+03 -1.05525818e+03 -1.07934521e+03 -1.10360901e+03 -1.12777844e+03 -1.15120947e+03 -1.17456372e+03 -1.19637585e+03 -1.22027869e+03 -1.24467444e+03 -1.26689075e+03 -1.28918066e+03 -1.31150024e+03 -1.33238135e+03 -1.35393274e+03 -1.37573926e+03 -1.39999805e+03 -1.42065198e+03 -1.43995117e+03 -1.46300610e+03 -1.48418628e+03 -1.50110840e+03 -1.52084814e+03 -1.54557861e+03 -1.56245032e+03 -1.58080823e+03 -1.60261975e+03 -1.61996533e+03 -1.63874109e+03 -1.65982068e+03 -1.67874585e+03 -1.69482349e+03 -1.70997791e+03 -1.72872339e+03 -1.75093689e+03 -1.76382874e+03 -1.78061096e+03 -1.79583545e+03 -1.81113794e+03 -1.83511963e+03 -1.84114966e+03 -1.85530261e+03 -1.87647778e+03 -1.89597461e+03 -1.90715674e+03 -1.91852148e+03 -1.93388416e+03 -1.94553503e+03 -1.96295447e+03 -1.97686548e+03 -1.98125012e+03 -1.99791284e+03 -2.01234741e+03 -2.02106604e+03 -2.03305212e+03 -2.04472607e+03 -2.05230200e+03 -2.06793335e+03 -2.08129712e+03 -2.08786011e+03 -2.09696924e+03 -2.10335449e+03 -2.11656177e+03 -2.12512671e+03 -2.13001465e+03 -2.14123267e+03 -2.14840405e+03 -2.15740991e+03 -2.16500073e+03 -2.16722070e+03 -2.17627197e+03 -2.18460229e+03 -2.19033813e+03 -2.19234912e+03 -2.19604590e+03 -2.20652441e+03 -2.20617920e+03 -2.21622363e+03 -2.21615332e+03 -2.21671924e+03 -2.22622876e+03 -2.22640625e+03 -2.22459570e+03 -2.22933252e+03 -2.22850342e+03 -2.23557007e+03 -2.23603931e+03 -2.23257935e+03 -2.24069751e+03 -2.23542578e+03 -2.23004370e+03 -2.23476587e+03 -2.23918555e+03 -2.24283398e+03 -2.23740894e+03 -2.23436108e+03 -2.22377539e+03 -2.21867139e+03 -2.22884106e+03 -2.22731055e+03 -2.23791040e+03 -2.87056470e+03 -3.03513721e+03 -3.31324243e+03 -3.30754639e+03 -3.31146997e+03 -3.28107251e+03 -3.27101440e+03 -3.27812793e+03 -3.26690845e+03 -3.25416309e+03 -2.97126611e+03 -2.78773633e+03 -2.13943579e+03 -2.12980713e+03 -2.12336841e+03 -2.11796826e+03 -2.10468408e+03 -2.09631128e+03 -2.08759473e+03 -2.07371582e+03 -2.06956665e+03 -2.67721631e+03 -2.04451111e+03 -3.06770410e+03 -4.70054883e+03 -5.24385791e+03 78626312. 26853954. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -276179360. 145225200. -4.57853086e+04 -3.04418281e+05 1.77717703e+05 -26484924. -4.46698096e+03 -3.11018091e+03 -1.56411743e+03 -1.54201294e+03 -1.52184338e+03 -1.50167639e+03 -1.48102747e+03 -1.80527856e+03 -1.78649353e+03 -3.37867310e+03 -4.12410596e+03 4.11211219e+05 7.70348359e+04 8.40772656e+03 -9.01833500e+05 -5.75281250e+05 -3.76036750e+06 8.19045875e+05 3.00403650e+06 2.76606975e+06 9.05897562e+05 1.68298730e+04 -4.59950375e+05 -6.38205062e+05 -1.10392125e+05 -3.25888428e+03 -3.06891479e+03 -2.89282300e+03 2.54757850e+06 1.16044711e+05 -4.14282148e+04 -2.89089844e+05 -1.92614062e+05 -7.46513812e+05 8.68969438e+05 1.90919238e+06 1.22375550e+06 3.44573312e+05 9.17822461e+03 -1.23286641e+04 3.37621055e+04 -1470457. 1.49452314e+04 1.03502168e+04 -13612294. 109072912. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -4.13973955e+10 -4.13973955e+10 0. 0. 1756571136. 1756571136. 1756571136. 0. 0. 0. 0. 600903360. 8.76235062e+05 2.79726825e+06 -5.40771350e+06 51167944. 1.98555546e+10 1.98555546e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56744288. 56744288. 56744288. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 450898272. 450898272. 450898272. 0. 0. 2446779. -136878880. -136878880. -30320120. -7663983. -6.40101172e+04 4.72408789e+03 3.78954370e+03 2.32200195e+03 3.76435352e+03 4.76128125e+03 2427053. 299625088. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -72765856. 4.01671475e+06 6.18389893e+03 4.86306689e+03 3.03076465e+03 2.76123169e+03 2.64436523e+03 2.05276733e+03 2.06321289e+03 2.06868945e+03 2.07796436e+03 2.09319971e+03 2.10766699e+03 2.10740283e+03 2.12121826e+03 2.13366821e+03 2.14222241e+03 2.14546558e+03 2.15618823e+03 2.16911133e+03 2.17326782e+03 2.17791284e+03 2.18637012e+03 2.19821460e+03 2.20601270e+03 2.20237231e+03 2.20572266e+03 2.22048804e+03 2.22497534e+03 2.22597803e+03 2.23241406e+03 2.23400439e+03 2.23350732e+03 2.23838354e+03 2.24672241e+03 2.24346973e+03 2.24859399e+03 2.24746240e+03 2.24888647e+03 2.25003784e+03 2.25575928e+03 2.25235205e+03 2.25493188e+03 2.25530981e+03 2.25577246e+03 2.25173413e+03 2.25406958e+03 2.25235156e+03 2.24885352e+03 2.24235132e+03 2.24009790e+03 2.23907617e+03 2.24068018e+03 2.23580566e+03 2.22436768e+03 2.22317310e+03 2.21935059e+03 2.21626782e+03 2.21687695e+03 2.20537329e+03 2.19289355e+03 2.19259570e+03 2.18933691e+03 2.18177344e+03 2.18247656e+03 2.16396436e+03 2.15562842e+03 2.14713281e+03 2.14012622e+03 2.13821045e+03 2.12025073e+03 2.11456445e+03 2.10821753e+03 2.09191479e+03 2.08451416e+03 2.06940332e+03 2.06474487e+03 2.05227002e+03 2.03693787e+03 2.02637268e+03 2.01428528e+03 2.00049255e+03 1.98820166e+03 1.97638074e+03 1.96177893e+03 1.94586072e+03 1.93635437e+03 1.91947717e+03 1.90200488e+03 1.89184534e+03 1.87794385e+03 1.86134619e+03 1.84277856e+03 1.82493750e+03 1.81456763e+03 1.79608813e+03 1.77884912e+03 1.75943921e+03 1.74414160e+03 1.72775195e+03 1.70497339e+03 1.68929077e+03 1.67125891e+03 1.65472668e+03 1.63350195e+03 1.61264551e+03 1.59688818e+03 1.57420312e+03 1.55469299e+03 1.53777087e+03 1.51503284e+03 1.49422534e+03 1.47465222e+03 1.45254431e+03 1.43124353e+03 1.40965588e+03 1.38802039e+03 1.36632507e+03 1.34369470e+03 1.32039819e+03 1.29914758e+03 1.27737244e+03 1.25474512e+03 1.23052295e+03 1.20639954e+03 1.18344629e+03 1.16056873e+03 1.13621460e+03 1.11227917e+03 1.08899976e+03 1.06404138e+03 1.03871106e+03 1.01353235e+03 9.90484741e+02 9.65652588e+02 9.40092834e+02 9.14352234e+02 8.89621338e+02 8.64338745e+02 8.37936584e+02 8.12767212e+02 7.86377991e+02 7.60010498e+02 7.34529236e+02 7.08400269e+02 6.82044983e+02 6.55294434e+02 6.28736389e+02 6.02551270e+02 5.75544922e+02 5.49079834e+02 5.22115356e+02 4.95149261e+02 4.68058441e+02 4.40822845e+02 4.13754852e+02 3.86466125e+02 3.59385437e+02 3.31849091e+02 3.04392059e+02 2.77069061e+02 2.49524078e+02 2.22033463e+02 1.94567032e+02 1.66944260e+02 1.39268890e+02 1.11688690e+02 8.40302963e+01 5.63468513e+01 2.87197456e+01 1.05561173e+00 -2.66048946e+01 -5.43227844e+01 -8.20461884e+01 -1.09689346e+02 -1.37268997e+02 -1.64871628e+02 -1.92473831e+02 -2.19974442e+02 -2.47495270e+02 -2.74981384e+02 -3.02441406e+02 -3.29856720e+02 -3.57230499e+02 -3.84470642e+02 -4.11827911e+02 -4.39025970e+02 -4.65894379e+02 -4.93428802e+02 -5.20839722e+02 -5.47897339e+02 -5.73825256e+02 -5.99852722e+02 -6.26727112e+02 -6.53575012e+02 -6.80363342e+02 -7.06521423e+02 -7.33027222e+02 -7.58217224e+02 -7.83962158e+02 -1.02821460e+03 -1.09644421e+03 -1.25362769e+03 -1.20210388e+03 -1.21436694e+03 -1.30892969e+03 -1.43911694e+03 -1.47677002e+03 -1.33160376e+03 -1.57982043e+03 -1.29331848e+03 -1.63067810e+03 -1.66798389e+03 -1.42305029e+03 -1.44477698e+03 -1.18234998e+03 -1.20451160e+03 -1.22878088e+03 -1.25143811e+03 -1.68284460e+03 -1.82951367e+03 -1.97349329e+03 -2.00780371e+03 -2.03841821e+03 -1.83943274e+03 -1.78067639e+03 -1.42888574e+03 -1.44913440e+03 -1.47350452e+03 -1.49354297e+03 -1.51162268e+03 -1.53414136e+03 -1.55695776e+03 -1.57411572e+03 -1.59192651e+03 -1.61209937e+03 -1.63319922e+03 -1.64888733e+03 -1.67046973e+03 -1.69116052e+03 -1.70961780e+03 -1.72437842e+03 -1.74008374e+03 -1.76426758e+03 -1.78041370e+03 -1.79214307e+03 -1.80659253e+03 -1.82409778e+03 -1.84669153e+03 -1.85849573e+03 -1.86879468e+03 -1.88923877e+03 -1.90867004e+03 -1.92070312e+03 -1.93522302e+03 -1.94553284e+03 -1.95849146e+03 -1.97890454e+03 -1.99106958e+03 -1.99558313e+03 -2.01635925e+03 -2.02934448e+03 -2.03680115e+03 -2.05294141e+03 -2.06058594e+03 -2.06945996e+03 -2.08330127e+03 -2.09597461e+03 -2.10210181e+03 -2.10533057e+03 -2.12071387e+03 -2.13567578e+03 -2.14046118e+03 -2.14381982e+03 -2.15605859e+03 -2.17116772e+03 -2.17173901e+03 -2.17923462e+03 -2.18773242e+03 -2.19859399e+03 -2.20483032e+03 -2.20518262e+03 -2.20875513e+03 -2.21601685e+03 -2.22302393e+03 -2.22751294e+03 -2.23423389e+03 -2.23548364e+03 -2.23470166e+03 -2.24107544e+03 -2.24566309e+03 -2.24929175e+03 -2.24418115e+03 -2.24880371e+03 -2.25054248e+03 -2.25553125e+03 -2.26013330e+03 -2.25452271e+03 -2.25242383e+03 -2.25504761e+03 -2.25016431e+03 -2.24824585e+03 -2.25319360e+03 -2.25596533e+03 -2.25100830e+03 -2.24182739e+03 -2.24108643e+03 -2.23892505e+03 -2.24471802e+03 -2.23430713e+03 -2.22431006e+03 -2.22164429e+03 -2.22137817e+03 -2.21929932e+03 -2.21638452e+03 -2.20081714e+03 -2.19476709e+03 -2.19793213e+03 -2.18702319e+03 -2.18490576e+03 -2.17723364e+03 -2.15893506e+03 -2.15663794e+03 -2.14893921e+03 -2.13974658e+03 -2.13489526e+03 -2.11925391e+03 -2.11758350e+03 -2.10473999e+03 -2.08973267e+03 -2.08884985e+03 -2.07184058e+03 -2.06207471e+03 -2.05377417e+03 -2.03921777e+03 -2.02741760e+03 -2.01373950e+03 -2.00109119e+03 -1.98833386e+03 -1.97622620e+03 -1.96307971e+03 -1.94575537e+03 -1.93901575e+03 -1.92162268e+03 -1.89883899e+03 -1.89221912e+03 -1.87842029e+03 -1.85868384e+03 -1.84281909e+03 -1.82544092e+03 -1.81533569e+03 -1.79500806e+03 -1.78014038e+03 -1.75997827e+03 -1.74142432e+03 -1.72875916e+03 -1.70469836e+03 -1.68957983e+03 -1.67274280e+03 -1.65612976e+03 -1.63341199e+03 -1.61227002e+03 -1.59648193e+03 -1.57447644e+03 -1.55603748e+03 -1.53744946e+03 -1.51467346e+03 -1.49267969e+03 -1.47307959e+03 -1.45244043e+03 -1.42984741e+03 -1.40924622e+03 -1.38745667e+03 -1.36610669e+03 -1.34399329e+03 -1.32131140e+03 -1.29958740e+03 -1.27631738e+03 -1.25398743e+03 -1.23087939e+03 -1.20690735e+03 -1.18362073e+03 -1.16040479e+03 -1.13645789e+03 -1.11166895e+03 -1.08839880e+03 -1.06390051e+03 -1.03868726e+03 -1.01333978e+03 -9.88946655e+02 -9.65108459e+02 -9.39875854e+02 -9.14574402e+02 -8.89677734e+02 -8.63849792e+02 -8.37842041e+02 -8.12578125e+02 -7.86209534e+02 -7.60401489e+02 -7.34564453e+02 -7.08237915e+02 -6.82003174e+02 -6.54918274e+02 -6.28557495e+02 -6.02426392e+02 -5.75703918e+02 -5.48826233e+02 -5.21716125e+02 -4.95154327e+02 -4.68063568e+02 -4.40624390e+02 -4.13639038e+02 -3.86362854e+02 -3.59212555e+02 -3.31843384e+02 -3.04244019e+02 -2.76980682e+02 -2.49437988e+02 -2.21747910e+02 -1.94362381e+02 -1.67077820e+02 -1.39392365e+02 -1.11553375e+02 -8.40102768e+01 -5.63657646e+01 -2.86529655e+01 -1.06707489e+00 2.66342659e+01 5.43290367e+01 8.19292145e+01 1.09668945e+02 1.37294983e+02 1.64803024e+02 1.92460266e+02 2.20038788e+02 2.47513321e+02 2.74950928e+02 3.02509216e+02 3.29926910e+02 3.56997253e+02 3.84341003e+02 4.11786957e+02 4.38767303e+02 4.65877106e+02 4.93174896e+02 5.19837524e+02 5.46739380e+02 5.73751587e+02 6.00487793e+02 6.27107483e+02 6.53555969e+02 6.79794617e+02 7.06134766e+02 7.32549866e+02 7.58667175e+02 7.84214294e+02 8.10452881e+02 8.36663086e+02 8.62339355e+02 8.86650391e+02 9.11560974e+02 9.38439514e+02 9.63662048e+02 9.87375916e+02 1.01257739e+03 1.03751733e+03 1.06270557e+03 1.08748657e+03 1.10937524e+03 1.13322607e+03 1.16014758e+03 1.18324792e+03 1.20457947e+03 1.22731250e+03 1.25081250e+03 1.27517432e+03 1.29882007e+03 1.32086157e+03 1.34146338e+03 1.36386377e+03 1.38545142e+03 1.40789880e+03 1.42953870e+03 1.45004883e+03 1.47254919e+03 1.49380139e+03 1.51277942e+03 1.53321948e+03 1.55503357e+03 1.57306934e+03 1.59254919e+03 1.61544092e+03 1.63246326e+03 1.65004297e+03 1.66923962e+03 1.68871667e+03 1.70692920e+03 1.72491345e+03 1.74256543e+03 1.76494214e+03 1.78021277e+03 1.79153198e+03 1.80649597e+03 1.82299097e+03 1.84598071e+03 1.86139905e+03 1.86985815e+03 1.88573132e+03 1.90563953e+03 1.91958643e+03 1.93210242e+03 1.94440039e+03 1.95692163e+03 1.97678931e+03 1.99102551e+03 1.99606799e+03 2.01262195e+03 2.02842493e+03 2.03552551e+03 2.04966870e+03 2.06424902e+03 2.06997388e+03 2.08176392e+03 2.09645117e+03 2.09868604e+03 2.10714795e+03 2.12209668e+03 2.13172803e+03 2.14344873e+03 2.14347705e+03 2.15750757e+03 2.16665356e+03 2.17044263e+03 2.18292822e+03 2.18615747e+03 2.19380786e+03 2.20500830e+03 2.20621387e+03 2.20644458e+03 2.21468555e+03 2.22068115e+03 2.22608423e+03 2.23272217e+03 2.23725146e+03 2.23802417e+03 2.24653955e+03 2.24771973e+03 2.24305884e+03 2.24636914e+03 2.24811157e+03 2.25195093e+03 2.25141943e+03 2.25902588e+03 2.25066821e+03 2.24985620e+03 2.26094189e+03 2.24944067e+03 2.24631738e+03 2.25500146e+03 2.25634937e+03 2.25374438e+03 2.24251562e+03 2.23739307e+03 2.24560156e+03 2.24487598e+03 2.23906641e+03 2.22842700e+03 2.21837524e+03 2.22188379e+03 2.22332056e+03 2.21888257e+03 2.19923877e+03 2.19198340e+03 2.19714526e+03 2.18804199e+03 2.17900415e+03 2.18167041e+03 2.16363550e+03 2.15297534e+03 2.14772144e+03 2.13922632e+03 2.13379883e+03 2.11823096e+03 2.11880029e+03 2.10506348e+03 2.08958691e+03 2.08390112e+03 2.06957935e+03 2.06088428e+03 2.05196216e+03 2.03767871e+03 2.02848560e+03 2.01252026e+03 2.00218506e+03 1.99056311e+03 1.97673596e+03 1.96394128e+03 1.94680725e+03 1.93621289e+03 1.92445435e+03 1.90192126e+03 1.89328870e+03 1.87935925e+03 1.85869434e+03 1.84278027e+03 1.82473901e+03 1.81708569e+03 1.79564148e+03 1.77635400e+03 1.75999731e+03 1.74193701e+03 1.72798206e+03 1.70585901e+03 1.68767493e+03 1.67138000e+03 1.65542419e+03 1.63273804e+03 1.61215173e+03 1.59655090e+03 1.57360229e+03 1.55563025e+03 1.53655151e+03 1.51336169e+03 1.49358215e+03 1.47483130e+03 1.45116406e+03 1.42917773e+03 1.40895996e+03 1.38327673e+03 1.76591406e+03 1.80404199e+03 1.96530945e+03 1.93458057e+03 1.90183850e+03 1.72654126e+03 1.60538184e+03 1.20764746e+03 1.18405017e+03 1.15920349e+03 1.13585071e+03 1.11141809e+03 1.08830835e+03 1.06544482e+03 1.03891199e+03 1.30100928e+03 9.98020203e+02 1.43608618e+03 1.18461267e+03 1.26836243e+03 1.16770093e+03 8.63487122e+02 8.37172119e+02 8.13368103e+02 9.63802429e+02 7.60670715e+02 9.09217712e+02 7.08324585e+02 6.82309387e+02 6.55343140e+02 6.25372681e+02 6.00564514e+02 5.78740173e+02 5.50650757e+02 5.22537354e+02 4.95409058e+02 4.68469940e+02 4.41138855e+02 4.13818268e+02 3.86563660e+02 3.59296051e+02 3.31853485e+02 3.04436768e+02 2.77022614e+02 2.49534164e+02 2.22101318e+02 1.94515015e+02 1.66912170e+02 1.39301071e+02 1.11671913e+02 8.40239487e+01 5.63553581e+01 2.86972694e+01 9.87595320e-01 -2.66867981e+01 -5.43444519e+01 -8.20078430e+01 -1.09634491e+02 -1.37252518e+02 -1.64847656e+02 -1.92470642e+02 -2.20009918e+02 -2.47522964e+02 -2.75010132e+02 -3.02425751e+02 -3.29872437e+02 -3.57227783e+02 -3.84441559e+02 -4.11721741e+02 -4.38806488e+02 -4.65779297e+02 -4.93094971e+02 -5.20050049e+02 -5.46825500e+02 -5.73792969e+02 -6.00455627e+02 -6.27117554e+02 -6.53913513e+02 -6.79869385e+02 -7.06240051e+02 -7.32972229e+02 -7.58713013e+02 -7.84417419e+02 -8.10320251e+02 -8.36596863e+02 -8.62550354e+02 -8.86949280e+02 -9.12527527e+02 -9.38835693e+02 -9.63605530e+02 -9.87773682e+02 -1.01169128e+03 -1.03796826e+03 -1.06262732e+03 -1.08708118e+03 -1.10996472e+03 -1.13339575e+03 -1.16003625e+03 -1.18342798e+03 -1.20446326e+03 -1.22650891e+03 -1.25137231e+03 -1.27523096e+03 -1.29855579e+03 -1.32101294e+03 -1.34235510e+03 -1.36446765e+03 -1.38579626e+03 -1.40778284e+03 -1.42923840e+03 -1.44986487e+03 -1.47291370e+03 -1.49324670e+03 -1.51264307e+03 -1.53233691e+03 -1.55570959e+03 -1.57391858e+03 -1.59171814e+03 -1.61439282e+03 -1.63275378e+03 -1.64864978e+03 -1.66947766e+03 -1.69148169e+03 -1.70913208e+03 -1.72483191e+03 -1.73991638e+03 -1.76377112e+03 -1.77982947e+03 -1.79307690e+03 -1.80619409e+03 -1.82363062e+03 -1.84579382e+03 -1.85759375e+03 -1.86980383e+03 -1.88970789e+03 -1.90754980e+03 -1.92132397e+03 -1.93485449e+03 -1.94491504e+03 -1.95818054e+03 -1.97701990e+03 -1.99106653e+03 -1.99621753e+03 -2.01576038e+03 -2.02980066e+03 -2.03558142e+03 -2.05056348e+03 -2.06071338e+03 -2.06781177e+03 -2.08021655e+03 -2.09796875e+03 -2.10245801e+03 -2.10768530e+03 -2.12153003e+03 -2.13832715e+03 -2.14261890e+03 -2.14320483e+03 -2.15562085e+03 -2.17008301e+03 -2.17304053e+03 -2.18087573e+03 -2.18752075e+03 -2.19600854e+03 -2.20326123e+03 -2.19933252e+03 -2.20658276e+03 -2.21427856e+03 -2.22349585e+03 -2.22657642e+03 -2.22967676e+03 -2.23663965e+03 -2.23415479e+03 -2.24295630e+03 -2.24608423e+03 -2.24379541e+03 -2.24738647e+03 -2.24932129e+03 -2.25148633e+03 -2.25137622e+03 -2.25903296e+03 -2.25498584e+03 -2.25222852e+03 -2.25599634e+03 -2.25281982e+03 -2.24951440e+03 -2.25912549e+03 -2.25828613e+03 -2.25065625e+03 -2.24036377e+03 -2.23736108e+03 -2.24274243e+03 -2.24618188e+03 -2.23817310e+03 -2.22518701e+03 -2.21917773e+03 -2.22299463e+03 -2.22226221e+03 -2.21961523e+03 -2.20166626e+03 -2.19610278e+03 -2.19758325e+03 -2.18886328e+03 -2.18070996e+03 -2.17607520e+03 -2.16061523e+03 -2.15522217e+03 -2.14681055e+03 -2.13979834e+03 -2.13652563e+03 -2.12161084e+03 -2.11711719e+03 -2.10406470e+03 -2.09254468e+03 -2.08730737e+03 -2.06836011e+03 -2.05809595e+03 -2.04752979e+03 -2.65432300e+03 -2.74274390e+03 -4.68492041e+03 -5.68373877e+03 -3.77649750e+06 47587496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 39352692. 39352692. 39352692. 0. 0. 1616350208. -6.36276709e+03 -1.58056580e+03 -1.55615637e+03 -1.97015747e+03 -2.03089221e+03 -2.03868616e+03 -3.48094214e+03 -2.80388403e+03 3.13707650e+06 3.33217625e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -38021184. -38021184. -38021184. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1756571136. 1756571136. 1756571136. 0. 0. 0. 0. 600903360. 8.76235062e+05 2.79726825e+06 -5.40771350e+06 898915648. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56842832. -9061306. 4.23295820e+04 -4.08843450e+06 -7.87497950e+06 9165844. -6.03958312e+05 24072544. -4.96676594e+05 -5.74153047e+04 15365739. -32527410. -228333616. -228333616. 0. 0. 0. 0. 0. 0. 0. 450898272. 450898272. 450898272. 0. 0. 2446779. -136878880. -136878880. -30320120. -7663983. -6.40101172e+04 -1.15830867e+05 -1.28067775e+06 -2.85391125e+05 13485562. -46676344. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -11337912. 1.21159980e+04 2.80575415e+03 2.65775391e+03 2.03449512e+03 2.05041724e+03 2.05819360e+03 2.07419214e+03 2.08499658e+03 2.09019238e+03 2.10329834e+03 2.11855688e+03 2.12850391e+03 2.13350464e+03 2.14749146e+03 2.79798804e+03 2.94684497e+03 2.95989844e+03 2.81639038e+03 2.18991772e+03 2.19880151e+03 2.20438550e+03 2.20878442e+03 2.21974243e+03 2.23096460e+03 2.22863550e+03 2.22920190e+03 2.24078320e+03 2.24901978e+03 2.25361182e+03 2.25425854e+03 2.25462085e+03 2.26360083e+03 2.26696216e+03 2.26761816e+03 2.27183472e+03 2.27073901e+03 2.93896558e+03 3.08434497e+03 3.39336621e+03 3.39522949e+03 3.39810107e+03 3.13435303e+03 2.96584741e+03 2.27658252e+03 2.28088452e+03 2.27817285e+03 2.27449023e+03 2.26928369e+03 2.27410327e+03 2.27135620e+03 2.27015796e+03 2.26200830e+03 2.25729492e+03 2.25487427e+03 2.24991626e+03 2.24303442e+03 2.24359204e+03 2.24599243e+03 2.23189014e+03 2.22027832e+03 2.22045239e+03 2.20879272e+03 2.21003687e+03 2.20279150e+03 2.18848901e+03 2.18220410e+03 2.17035791e+03 2.16210352e+03 2.16005762e+03 2.14775122e+03 2.14344727e+03 2.13194556e+03 2.11779395e+03 2.10713257e+03 2.09378979e+03 2.08288696e+03 2.07513110e+03 2.06500244e+03 2.04571240e+03 2.03737769e+03 2.02695959e+03 2.01193506e+03 2.00302930e+03 1.98327026e+03 1.97129846e+03 1.96189722e+03 1.94215186e+03 1.92557361e+03 1.91227185e+03 1.90141638e+03 1.88252612e+03 1.86265601e+03 1.84831042e+03 1.83293250e+03 1.81780408e+03 1.80270410e+03 1.78046887e+03 1.76527417e+03 1.74728674e+03 1.72641028e+03 1.71103479e+03 1.69316589e+03 1.67461462e+03 1.65087415e+03 1.63069141e+03 1.61554028e+03 1.59531750e+03 1.57526111e+03 1.55636841e+03 1.53507056e+03 1.51050452e+03 1.49109155e+03 1.47260413e+03 1.44864062e+03 1.42812280e+03 1.40511060e+03 1.38256360e+03 1.36017859e+03 1.33732263e+03 1.31505493e+03 1.29438708e+03 1.27007166e+03 1.24524524e+03 1.22192090e+03 1.19815051e+03 1.17539758e+03 1.15036975e+03 1.12628394e+03 1.10287952e+03 1.07692773e+03 1.05235718e+03 1.02776135e+03 1.00293549e+03 9.77039917e+02 9.52467712e+02 9.27040405e+02 9.00931946e+02 8.75202393e+02 8.49175964e+02 8.23872681e+02 7.97044067e+02 7.70559143e+02 7.44327637e+02 7.18174194e+02 6.91393738e+02 6.64293884e+02 6.37857849e+02 6.11325867e+02 5.83602844e+02 5.56979187e+02 5.29622375e+02 5.02191528e+02 4.75148651e+02 4.47674988e+02 4.20066010e+02 3.92602478e+02 3.65242004e+02 3.37344177e+02 3.09659698e+02 2.82001129e+02 2.54099579e+02 2.26264175e+02 1.98483215e+02 1.70584122e+02 1.42621521e+02 1.14713509e+02 8.67010117e+01 5.87526245e+01 3.08539848e+01 2.80174899e+00 -2.52161312e+01 -5.31956673e+01 -8.12320633e+01 -1.09214188e+02 -1.37099838e+02 -1.64984329e+02 -1.92843155e+02 -2.20700546e+02 -2.48597672e+02 -2.76345856e+02 -3.04097687e+02 -3.31917938e+02 -3.59600433e+02 -3.87075287e+02 -4.14727081e+02 -4.42333740e+02 -4.69324341e+02 -4.96909088e+02 -5.24459351e+02 -5.51549255e+02 -5.78636475e+02 -6.05698120e+02 -6.32504456e+02 -6.59490479e+02 -6.86657654e+02 -7.13460632e+02 -7.39748474e+02 -7.65664734e+02 -7.91610107e+02 -8.18134888e+02 -8.44205750e+02 -8.70277954e+02 -8.96666992e+02 -1.13775122e+03 -1.17380457e+03 -1.45940320e+03 -1.49711963e+03 -1.25903003e+03 -1.59994189e+03 -1.39636084e+03 -2.80397363e+03 -3.73853809e+03 -3.74497534e+03 -2.93735962e+03 -1.77463879e+03 -1.63920435e+03 -1.59147668e+03 -1.26425415e+03 -1.59098523e+03 -1.62672498e+03 -2.00244141e+03 -2.03863037e+03 -2.06742383e+03 -1.72314966e+03 -1.74530945e+03 -1.44485107e+03 -1.92565894e+03 -2.03558191e+03 -2.24620654e+03 -2.27089624e+03 -2.30388403e+03 -2.33920898e+03 -2.36811328e+03 -2.39210767e+03 -2.42212817e+03 -2.20117334e+03 -2.13715845e+03 -1.68582263e+03 -1.70852795e+03 -1.72663330e+03 -1.74164038e+03 -1.76048120e+03 -1.78019727e+03 -1.79704529e+03 -1.81088940e+03 -1.82503125e+03 -1.84418860e+03 -1.86465881e+03 -1.87798303e+03 -1.89072424e+03 -1.90888391e+03 -1.92331091e+03 -1.93632983e+03 -1.95215125e+03 -1.96750842e+03 -1.97592969e+03 -1.99995984e+03 -2.01310608e+03 -2.01939368e+03 -2.03851831e+03 -2.05058423e+03 -2.05843677e+03 -2.07609497e+03 -2.08549023e+03 -2.08840552e+03 -2.10429248e+03 -2.11942383e+03 -2.12531616e+03 -2.12935278e+03 -2.14508252e+03 -2.15603662e+03 -2.16430884e+03 -2.16752637e+03 -2.17969385e+03 -2.19183032e+03 -2.19931323e+03 -2.20176147e+03 -2.21177905e+03 -2.22134082e+03 -2.22932080e+03 -2.22878760e+03 -2.23292749e+03 -2.24278979e+03 -2.24699268e+03 -2.25399414e+03 -2.25679736e+03 -2.26106274e+03 -2.26410596e+03 -2.26534009e+03 -2.27090088e+03 -2.27398486e+03 -2.27643774e+03 -2.27785205e+03 -2.27965649e+03 -2.28195825e+03 -2.28007349e+03 -2.27626172e+03 -2.28334033e+03 -2.27853760e+03 -2.28134009e+03 -2.27754736e+03 -2.27566357e+03 -2.27700952e+03 -2.27705273e+03 -2.27231055e+03 -2.26842456e+03 -2.26908765e+03 -2.26846021e+03 -2.26006519e+03 -2.25142529e+03 -2.24772070e+03 -2.24773608e+03 -2.24572778e+03 -2.24206030e+03 -2.22757104e+03 -2.21804053e+03 -2.22510303e+03 -2.21440112e+03 -2.21347437e+03 -2.19821240e+03 -2.18058423e+03 -2.18723950e+03 -2.17436279e+03 -2.15866187e+03 -2.15831006e+03 -2.14796729e+03 -2.14350171e+03 -2.12955884e+03 -2.11297949e+03 -2.10677759e+03 -2.09481909e+03 -2.08458960e+03 -2.07813379e+03 -2.06267432e+03 -2.04439661e+03 -2.03840894e+03 -2.02755237e+03 -2.00897107e+03 -2.00420703e+03 -1.98524805e+03 -1.97097754e+03 -1.96396802e+03 -1.94279883e+03 -1.92648279e+03 -1.91147058e+03 -1.89839819e+03 -1.88156592e+03 -1.86497681e+03 -1.84992676e+03 -1.83462878e+03 -1.81644348e+03 -1.80090771e+03 -1.78085596e+03 -1.76277246e+03 -1.74942139e+03 -1.72642822e+03 -1.70759644e+03 -1.69374011e+03 -1.67640662e+03 -1.65009277e+03 -1.63017371e+03 -1.61557739e+03 -1.59643591e+03 -1.57597302e+03 -1.55699939e+03 -1.53647217e+03 -1.50829236e+03 -1.48883093e+03 -1.47120117e+03 -1.44920703e+03 -1.42756885e+03 -1.40434412e+03 -1.38151624e+03 -1.35911487e+03 -1.33845410e+03 -1.31662085e+03 -1.29247351e+03 -1.27042212e+03 -1.24608105e+03 -1.22245081e+03 -1.19795959e+03 -1.17445203e+03 -1.15034509e+03 -1.12622888e+03 -1.10200293e+03 -1.07692517e+03 -1.05274133e+03 -1.02683765e+03 -1.00153528e+03 -9.76589966e+02 -9.52455139e+02 -9.27234009e+02 -9.00860779e+02 -8.74821472e+02 -8.49374207e+02 -8.23602356e+02 -7.96521240e+02 -7.70975525e+02 -7.44427734e+02 -7.17645752e+02 -6.91089233e+02 -6.63895264e+02 -6.37623596e+02 -6.11180298e+02 -5.83927490e+02 -5.56711060e+02 -5.29254822e+02 -5.02353180e+02 -4.75212799e+02 -4.47380402e+02 -4.19859283e+02 -3.92364685e+02 -3.64976471e+02 -3.37394165e+02 -3.09471558e+02 -2.81886261e+02 -2.54124847e+02 -2.25950562e+02 -1.98208328e+02 -1.70779922e+02 -1.42770416e+02 -1.14587982e+02 -8.67027740e+01 -5.87169991e+01 -3.07247372e+01 -2.84793687e+00 2.51216316e+01 5.31647530e+01 8.11038437e+01 1.09128799e+02 1.37101334e+02 1.64926071e+02 1.92845551e+02 2.20769775e+02 2.48573761e+02 2.76211029e+02 3.04103546e+02 3.32026733e+02 3.59316437e+02 3.86952820e+02 4.14694427e+02 4.42036102e+02 4.69476013e+02 4.96861877e+02 5.24016174e+02 5.51463135e+02 5.78694702e+02 6.05481079e+02 6.32156250e+02 6.59429993e+02 6.85809143e+02 7.12225281e+02 7.39033630e+02 7.65723816e+02 7.91474060e+02 8.18011841e+02 8.44378235e+02 8.70186829e+02 8.95346375e+02 9.20851562e+02 9.48030151e+02 9.73436218e+02 9.96062561e+02 1.02103534e+03 1.04832324e+03 1.07397034e+03 1.09712524e+03 1.12001697e+03 1.14516223e+03 1.17084851e+03 1.19518127e+03 1.21711121e+03 1.24074463e+03 1.26406189e+03 1.28687805e+03 1.31160889e+03 1.33515588e+03 1.35464172e+03 1.37865173e+03 1.40084546e+03 1.42209448e+03 1.44496960e+03 1.46619226e+03 1.48722778e+03 1.50880469e+03 1.52931042e+03 1.55096277e+03 1.56978967e+03 1.58894653e+03 1.60976257e+03 1.62975464e+03 1.64979773e+03 1.66888647e+03 1.68540442e+03 1.70657971e+03 1.72634753e+03 1.74523206e+03 1.76293884e+03 1.77869775e+03 1.79897363e+03 1.81161279e+03 1.82602686e+03 1.84582825e+03 1.86371594e+03 1.88010046e+03 1.89152808e+03 1.90881372e+03 1.92990625e+03 1.94421460e+03 1.94903821e+03 1.96387793e+03 1.98022729e+03 1.99681958e+03 2.00864575e+03 2.02310352e+03 2.03540552e+03 2.04448389e+03 2.05966064e+03 2.07647534e+03 2.09150635e+03 2.09152954e+03 2.09952856e+03 2.11898584e+03 2.12156079e+03 2.13382886e+03 2.14491992e+03 2.15025122e+03 2.16564600e+03 2.17058813e+03 2.18077368e+03 2.19323120e+03 2.19505640e+03 2.20643848e+03 2.21034058e+03 2.21571216e+03 2.22842358e+03 2.22747583e+03 2.23274438e+03 2.24335693e+03 2.24311475e+03 2.25508130e+03 2.25758057e+03 2.25370776e+03 2.26600684e+03 2.27289746e+03 2.26382642e+03 2.26952246e+03 2.27886230e+03 2.27670142e+03 2.27259033e+03 2.27659814e+03 2.28581201e+03 2.27453931e+03 2.27775317e+03 2.27653760e+03 2.27803296e+03 2.28000879e+03 2.27885181e+03 2.28314160e+03 2.27442358e+03 2.26756982e+03 2.26603589e+03 2.27382886e+03 2.26683398e+03 2.26640503e+03 2.25396167e+03 2.24899536e+03 2.24318970e+03 2.24581396e+03 2.24759912e+03 2.22522607e+03 2.21655737e+03 2.22272168e+03 2.21590063e+03 2.20845654e+03 2.20055542e+03 2.18436646e+03 2.18247290e+03 2.17185962e+03 2.16464209e+03 2.15965137e+03 2.14742407e+03 2.14589917e+03 2.13037720e+03 2.11090405e+03 2.10841528e+03 2.09379639e+03 2.08306421e+03 2.07784692e+03 2.06340430e+03 2.04963818e+03 2.03656226e+03 2.02648083e+03 2.01140552e+03 2.00200842e+03 1.98623535e+03 1.96891907e+03 1.96018982e+03 1.94551855e+03 1.92506506e+03 1.91353845e+03 1.89898108e+03 1.88138354e+03 1.86515283e+03 1.84770776e+03 1.83647534e+03 1.81472070e+03 1.79744470e+03 1.78092554e+03 1.76336316e+03 1.74687817e+03 1.72578845e+03 1.70802502e+03 1.69044922e+03 2.13695581e+03 2.19322290e+03 2.42883057e+03 2.40601489e+03 2.37619336e+03 2.34883691e+03 2.31889600e+03 2.28438110e+03 2.25236230e+03 2.22175342e+03 2.06270605e+03 1.89981506e+03 1.42650806e+03 1.40045447e+03 1.71728479e+03 1.70586304e+03 2.00875659e+03 1.97267932e+03 1.94075769e+03 1.55290613e+03 1.52083350e+03 1.54910217e+03 1.57886218e+03 1.75014343e+03 1.62452185e+03 1.67443359e+03 1.44384253e+03 1.54047778e+03 1.40005981e+03 1.27809277e+03 9.92879272e+02 1.46537134e+03 1.24672205e+03 1.13150745e+03 1.09879944e+03 8.76022888e+02 8.47703735e+02 8.23891296e+02 1.08313806e+03 7.70287415e+02 9.32697571e+02 7.18206665e+02 6.92044800e+02 6.64707764e+02 6.38187134e+02 6.11411011e+02 5.83813965e+02 5.56862061e+02 5.29738708e+02 5.02326385e+02 4.75092010e+02 4.47551086e+02 4.20068451e+02 3.92667267e+02 3.65096222e+02 3.37308929e+02 3.09661194e+02 2.81988922e+02 2.54103333e+02 2.26340866e+02 1.98480469e+02 1.70543182e+02 1.42622604e+02 1.14680595e+02 8.67386932e+01 5.87598419e+01 3.07630157e+01 2.76512384e+00 -2.52137661e+01 -5.31556168e+01 -8.11101913e+01 -1.09087189e+02 -1.37061264e+02 -1.64948471e+02 -1.92815155e+02 -2.20746323e+02 -2.48585495e+02 -2.76305603e+02 -3.04040192e+02 -3.31891144e+02 -3.59538147e+02 -3.86993896e+02 -4.14639709e+02 -4.42052948e+02 -4.69369324e+02 -4.97022186e+02 -5.24112610e+02 -5.51193787e+02 -5.78785767e+02 -6.05685486e+02 -6.32548340e+02 -6.59250793e+02 -6.85648621e+02 -7.12773254e+02 -7.39820923e+02 -7.65986633e+02 -7.91405090e+02 -8.17622803e+02 -8.44264465e+02 -8.70169800e+02 -8.95845215e+02 -9.21841003e+02 -9.48132446e+02 -9.73145264e+02 -9.96687317e+02 -1.02100116e+03 -1.04813281e+03 -1.07404016e+03 -1.09788855e+03 -1.12076465e+03 -1.14495959e+03 -1.17031409e+03 -1.19484570e+03 -1.21780505e+03 -1.23952124e+03 -1.26384265e+03 -1.28771094e+03 -1.31164795e+03 -1.33430322e+03 -1.35591455e+03 -1.37908643e+03 -1.40023792e+03 -1.42090320e+03 -1.44557935e+03 -1.46800098e+03 -1.48715723e+03 -1.51027917e+03 -1.52802649e+03 -1.54962622e+03 -1.57127258e+03 -1.59094299e+03 -1.61003027e+03 -1.62853064e+03 -1.64879810e+03 -1.66717358e+03 -1.68688171e+03 -1.70808777e+03 -1.72712622e+03 -1.74506836e+03 -1.76104565e+03 -1.77929639e+03 -1.79922107e+03 -1.81320483e+03 -1.82770105e+03 -1.84489197e+03 -1.86353845e+03 -1.87928931e+03 -1.89238318e+03 -1.90989624e+03 -1.92875879e+03 -1.94304431e+03 -1.95432800e+03 -1.96807715e+03 -1.98245349e+03 -1.99469348e+03 -2.01056958e+03 -2.02250842e+03 -2.03783948e+03 -2.05041064e+03 -2.05727734e+03 -2.07434985e+03 -2.08370117e+03 -2.09237231e+03 -2.10052930e+03 -2.11733984e+03 -2.12781934e+03 -2.13079077e+03 -2.14569604e+03 -2.16032788e+03 -2.16598926e+03 -2.16469189e+03 -2.17835742e+03 -2.19928979e+03 -2.20014478e+03 -2.19907275e+03 -2.20956152e+03 -2.22507544e+03 -2.22548291e+03 -2.22313403e+03 -2.23099146e+03 -2.23998438e+03 -2.24978296e+03 -2.24645850e+03 -2.25519165e+03 -2.25931396e+03 -2.25895190e+03 -2.26826733e+03 -2.27216040e+03 -2.26889893e+03 -2.27684180e+03 -2.27389600e+03 -2.27066992e+03 -2.27030737e+03 -2.94222852e+03 -3.04927588e+03 -3.39635522e+03 -3.39490405e+03 -3.12686841e+03 -2.95631421e+03 -2.28219629e+03 -2.28237012e+03 -2.27427173e+03 -2.26721143e+03 -2.26530005e+03 -2.26847900e+03 -2.26784839e+03 -2.26515283e+03 -2.25479321e+03 -2.24458984e+03 -2.24174463e+03 -2.24485986e+03 -2.24242163e+03 -2.22846826e+03 -2.22391626e+03 -2.22135083e+03 -2.21445459e+03 -2.21064795e+03 -2.81625000e+03 -2.17763843e+03 -2.84388794e+03 -2.17678394e+03 -2.16720044e+03 -2.16428882e+03 -2.15000195e+03 -2.14124780e+03 -2.12857739e+03 -2.11423975e+03 -2.10646558e+03 -2.09794458e+03 -2.08562939e+03 -2.07347729e+03 -2.05931323e+03 -2.04266675e+03 -2.59416113e+03 -3.63737305e+03 -2.59005332e+04 47587496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 39352692. 39352692. 39352692. 0. 0. 121625240. -9.71063184e+03 -2.41228271e+03 -2.35248389e+03 -3.55202197e+03 -4.20363379e+03 -4.69745703e+03 -4.41428418e+03 -4.17922949e+03 3.13707650e+06 3.33217625e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -5.96269466e+09 -5.96269466e+09 -5.96269466e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1756571136. 1756571136. 1756571136. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 97407352. 97407352. 97407352. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56842832. -9061306. 4.23295820e+04 -4.08843450e+06 -7.87497950e+06 9165844. -6.03958312e+05 24072544. 2.56564624e+03 3.05400781e+03 1.32874258e+04 2.63230078e+03 1.26457705e+04 1.26457705e+04 4599262. -15852164. -15852164. 15629822. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -11337912. 1.21159980e+04 3.02888843e+03 3.04899048e+03 3.06744287e+03 2.82742920e+03 2.69296021e+03 2.10181567e+03 2.11570459e+03 2.12260132e+03 2.13529150e+03 2.14979224e+03 2.80374854e+03 2.97521606e+03 3.23117651e+03 5.22584570e+03 6.59361768e+03 6.37274365e+03 5.16440771e+03 3.30160327e+03 3.31327466e+03 3.31691406e+03 3.32894556e+03 3.34469751e+03 3.35309863e+03 3.36039722e+03 3.09372827e+03 2.94652588e+03 2.28179590e+03 2.28467456e+03 2.29101514e+03 2.28572412e+03 2.29327124e+03 2.29488379e+03 2.97592358e+03 3.13639209e+03 3.42534302e+03 5.49523828e+03 6.84105176e+03 1.75894938e+06 -336485280. -4060228. 6.84614062e+03 5.49850098e+03 3.43789746e+03 3.43031201e+03 3.43616040e+03 3.43170630e+03 3.41540479e+03 3.42161523e+03 3.42471094e+03 3.16403369e+03 2.98130054e+03 2.29052075e+03 2.28847021e+03 2.27723560e+03 2.27539062e+03 2.27258228e+03 2.27160352e+03 2.26473022e+03 2.25376758e+03 2.24921460e+03 2.23687964e+03 2.23711963e+03 2.23563965e+03 2.22206348e+03 2.21318311e+03 2.19948804e+03 2.18852539e+03 2.18635278e+03 2.18029663e+03 2.17553931e+03 2.16260913e+03 2.14639038e+03 2.13225830e+03 2.12413940e+03 2.11531616e+03 2.10268311e+03 2.08981055e+03 2.07269824e+03 2.06139966e+03 2.05268433e+03 2.04070801e+03 2.02738647e+03 2.01043188e+03 1.99387012e+03 1.98283008e+03 1.96699365e+03 1.95171814e+03 1.93424585e+03 1.92498950e+03 1.90955579e+03 1.88785864e+03 1.87259180e+03 1.85724646e+03 1.84089539e+03 1.82477051e+03 1.80035779e+03 1.78562170e+03 1.76909058e+03 1.74661218e+03 1.73079639e+03 1.71397400e+03 1.69494531e+03 1.67041260e+03 1.64909387e+03 1.63457642e+03 1.61555725e+03 1.59162415e+03 1.57235352e+03 1.55362378e+03 1.52880212e+03 1.51000183e+03 1.48859412e+03 1.46481787e+03 1.44463635e+03 1.42095068e+03 1.39819116e+03 1.37510547e+03 1.35167346e+03 1.33037476e+03 1.30800146e+03 1.28320581e+03 1.25899194e+03 1.23559753e+03 1.21211169e+03 1.18694226e+03 1.16284045e+03 1.13820337e+03 1.11376648e+03 1.08849292e+03 1.06271851e+03 1.03775732e+03 1.01254419e+03 9.86213379e+02 9.61242859e+02 9.35425659e+02 9.08963318e+02 8.82943970e+02 8.56809204e+02 8.30770874e+02 8.03475037e+02 7.76789856e+02 7.50133240e+02 7.23392395e+02 6.96518250e+02 6.68980530e+02 6.42041260e+02 6.15030762e+02 5.87195923e+02 5.59843689e+02 5.32297363e+02 5.04704193e+02 4.76932648e+02 4.48901642e+02 4.21073944e+02 3.93379852e+02 3.65338135e+02 3.37156281e+02 3.09116943e+02 2.81042450e+02 2.52805389e+02 2.24556137e+02 1.96363571e+02 1.68067596e+02 1.39708923e+02 1.11372528e+02 8.29497147e+01 5.45820084e+01 2.63122940e+01 -2.08592868e+00 -3.05075073e+01 -5.88745422e+01 -8.72792587e+01 -1.15685127e+02 -1.43969177e+02 -1.72208542e+02 -2.00429276e+02 -2.28700027e+02 -2.57060486e+02 -2.85107239e+02 -3.13202179e+02 -3.41504700e+02 -3.69550232e+02 -3.97460602e+02 -4.25436768e+02 -4.53181915e+02 -4.80830048e+02 -5.08717041e+02 -5.36668884e+02 -5.64103943e+02 -5.91601990e+02 -6.19042725e+02 -6.45737000e+02 -6.73117676e+02 -7.00785706e+02 -7.27426331e+02 -7.54020935e+02 -7.81434875e+02 -8.08025757e+02 -8.34352600e+02 -8.61532104e+02 -8.88296387e+02 -9.14743164e+02 -1.17742969e+03 -1.25101550e+03 -1.49992896e+03 -1.54460852e+03 -1.53399866e+03 -1.44704138e+03 -1.09212183e+03 -1.37560120e+03 -1.41204944e+03 -1.75097070e+03 -1.78767004e+03 -1.82371094e+03 -1.52685095e+03 -1.55098743e+03 -1.68938684e+03 -2.35516528e+03 -3.59785645e+03 -2709321. 4.09013550e+06 -1.33954062e+06 -4.64328271e+03 -3.70280518e+03 -2.22649438e+03 -3.67737793e+03 -4.43357715e+03 1.56695531e+05 5.75551050e+06 12527755. -3.47561925e+06 -2.42373375e+06 16720325. -4.62836035e+03 -3.72385522e+03 -2.54519604e+03 -2.53815625e+03 -2.17362891e+03 -2.60075000e+03 -2.26023535e+03 -2.65293042e+03 -2.68594214e+03 -2.70790918e+03 -2.72998169e+03 -2.32376904e+03 -2.31800122e+03 -2.38297412e+03 -1.89602466e+03 -2.86022021e+03 -1.94066980e+03 -2.45837915e+03 -1.95394336e+03 -1.97615564e+03 -2.00656458e+03 -1.99923120e+03 -2.01892859e+03 -2.03690369e+03 -2.04030066e+03 -2.05844629e+03 -2.07152148e+03 -2.07950000e+03 -2.09809717e+03 -2.10570093e+03 -2.11598291e+03 -2.12812012e+03 -2.74025684e+03 -2.17894800e+03 -2.65416821e+03 -2.92489551e+03 -2.79476831e+03 -3.26603979e+03 -3.26926392e+03 -3.28299805e+03 -3.29802490e+03 -3.31260010e+03 -3.32270898e+03 -3.33104297e+03 -3.34768018e+03 -3.35659985e+03 -3.35998120e+03 -3.35956079e+03 -3.38405444e+03 -3.38229517e+03 -3.38813257e+03 -3.40848779e+03 -3.39974951e+03 -3.40754834e+03 -3.41398389e+03 -3.41937402e+03 -3.14574707e+03 -2.98730225e+03 -2.30897705e+03 -2.31121240e+03 -2.31171509e+03 -2.31446240e+03 -2.30915796e+03 -2.31560767e+03 -2.31336499e+03 -2.31334399e+03 -2.30625122e+03 -2.30878076e+03 -2.30813135e+03 -2.30486499e+03 -2.30382324e+03 -2.30315869e+03 -2.30123779e+03 -2.29363940e+03 -2.28984009e+03 -2.28669580e+03 -2.28104810e+03 -2.27448511e+03 -2.27229297e+03 -2.27266235e+03 -2.26106689e+03 -2.25188257e+03 -2.25172290e+03 -2.24691333e+03 -2.23974878e+03 -2.22346069e+03 -2.21849561e+03 -2.21683789e+03 -2.19932739e+03 -2.18933057e+03 -2.18450659e+03 -2.17907788e+03 -2.16996631e+03 -2.15924878e+03 -2.14513330e+03 -2.12946606e+03 -2.12167114e+03 -2.11547192e+03 -2.10316821e+03 -2.09010132e+03 -2.07259155e+03 -2.06010278e+03 -2.05300098e+03 -2.04086548e+03 -2.02682483e+03 -2.01131970e+03 -1.99813135e+03 -1.98283862e+03 -1.96764453e+03 -1.95256873e+03 -1.93342676e+03 -1.92199841e+03 -1.90828162e+03 -1.89017346e+03 -1.87348877e+03 -1.85598315e+03 -1.83902722e+03 -1.82253003e+03 -1.80083630e+03 -1.78426941e+03 -1.77050391e+03 -1.74738965e+03 -1.72870300e+03 -1.71555798e+03 -1.69514197e+03 -1.66969836e+03 -1.64881824e+03 -1.63453027e+03 -1.61713916e+03 -1.59168445e+03 -1.57158984e+03 -1.55389526e+03 -1.52702075e+03 -1.50787073e+03 -1.48716309e+03 -1.46407300e+03 -1.44556006e+03 -1.42011755e+03 -1.39799402e+03 -1.37491516e+03 -1.35156055e+03 -1.33136621e+03 -1.30687000e+03 -1.28288269e+03 -1.25824744e+03 -1.23599524e+03 -1.21193555e+03 -1.18630969e+03 -1.16239648e+03 -1.13885193e+03 -1.11257471e+03 -1.08761755e+03 -1.06271509e+03 -1.03719067e+03 -1.01219293e+03 -9.86398621e+02 -9.61216797e+02 -9.35271545e+02 -9.08953979e+02 -8.82916138e+02 -8.56810059e+02 -8.29751953e+02 -8.03277832e+02 -7.77474609e+02 -7.49958313e+02 -7.23338013e+02 -6.96384338e+02 -6.68401978e+02 -6.41397705e+02 -6.14708252e+02 -5.87525269e+02 -5.59769470e+02 -5.31999329e+02 -5.04520569e+02 -4.76865021e+02 -4.48953979e+02 -4.20950500e+02 -3.93087463e+02 -3.65187347e+02 -3.37214569e+02 -3.09018982e+02 -2.80923309e+02 -2.52770279e+02 -2.24189667e+02 -1.96062241e+02 -1.68275208e+02 -1.39850708e+02 -1.11306572e+02 -8.29924316e+01 -5.45728607e+01 -2.62052937e+01 2.06107879e+00 3.05162239e+01 5.90652466e+01 8.72987747e+01 1.15634079e+02 1.43994171e+02 1.72176590e+02 2.00458221e+02 2.28642838e+02 2.56867920e+02 2.84869415e+02 3.13086212e+02 3.41552368e+02 3.69384949e+02 3.97373901e+02 4.25196106e+02 4.53080963e+02 4.80984985e+02 5.08510345e+02 5.36233582e+02 5.64196899e+02 5.91607483e+02 6.18364685e+02 6.45509521e+02 6.73280334e+02 7.00276428e+02 7.26573975e+02 7.53626587e+02 7.81418091e+02 8.07100281e+02 8.34053650e+02 8.61577881e+02 8.86532959e+02 9.12130676e+02 9.37911621e+02 9.65427673e+02 9.91356567e+02 1.01530878e+03 1.04075549e+03 1.06718945e+03 1.09266870e+03 1.11648035e+03 1.14054028e+03 1.16658752e+03 1.19101416e+03 1.21459985e+03 1.23954810e+03 1.26278174e+03 1.28492615e+03 1.30842200e+03 1.33464978e+03 1.35582935e+03 1.37780945e+03 1.40488965e+03 1.42714990e+03 1.44412830e+03 1.46777625e+03 1.49098181e+03 1.50860730e+03 1.53339111e+03 1.55771704e+03 1.57766174e+03 1.59288477e+03 1.61468726e+03 1.63957800e+03 1.65659595e+03 1.67541345e+03 1.69614758e+03 1.71366992e+03 1.73441602e+03 1.75251648e+03 1.77223718e+03 1.79020813e+03 1.80614661e+03 1.82619739e+03 1.84102600e+03 1.85755298e+03 1.87249548e+03 1.89153149e+03 1.91341321e+03 1.92084241e+03 1.93466565e+03 1.95478040e+03 1.97187561e+03 1.98549438e+03 1.99753455e+03 2.00711316e+03 2.02760938e+03 2.04091394e+03 2.05187622e+03 2.06836353e+03 2.07873145e+03 2.09301489e+03 2.10186890e+03 2.11850391e+03 2.12937915e+03 2.13240405e+03 2.14680200e+03 2.15400269e+03 2.16929810e+03 2.17890698e+03 2.18173315e+03 2.20173755e+03 2.20492041e+03 2.21038330e+03 2.22678003e+03 2.22484790e+03 2.23863745e+03 2.24213379e+03 2.24784033e+03 2.26117822e+03 2.26095337e+03 2.26762549e+03 2.27864014e+03 2.27545093e+03 2.28488916e+03 2.29099341e+03 2.28551978e+03 2.30038721e+03 2.30453857e+03 2.29111670e+03 2.30559253e+03 2.30836475e+03 2.30780542e+03 2.30508081e+03 2.30737256e+03 2.31658813e+03 2.30870264e+03 2.31171680e+03 2.31230273e+03 2.31457642e+03 2.31026367e+03 2.30469580e+03 2.30854834e+03 2.30402417e+03 2.30110156e+03 2.30318164e+03 2.30213672e+03 2.29133496e+03 2.94655884e+03 3.09449097e+03 3.12018604e+03 3.38428027e+03 3.06859302e+03 3.36817651e+03 3.36084351e+03 3.34308350e+03 3.34219287e+03 2.88404785e+03 2.94964209e+03 2.76547217e+03 2.93180566e+03 3.28792017e+03 3.26860913e+03 3.25492603e+03 2.80409497e+03 2.77531299e+03 2.25158057e+03 2.67092041e+03 2.88346021e+03 2.76364404e+03 3.15235913e+03 2.67893408e+03 3.12337891e+03 3.11020044e+03 3.08858276e+03 3.06509424e+03 3.04969067e+03 3.02946973e+03 3.00656958e+03 2.99191040e+03 2.96483252e+03 2.94955151e+03 2.92664160e+03 2.89576660e+03 2.88053589e+03 2.86007544e+03 2.83276489e+03 2.64621167e+03 2.78415039e+03 2.49211011e+03 2.73268164e+03 2.70566992e+03 2.68191797e+03 2.65404150e+03 2.62627026e+03 2.59625293e+03 2.57085962e+03 2.53786963e+03 3.92899829e+03 4.67043555e+03 8938099. -1.57937125e+06 -6148026. 32735108. 10627369. 4.81653857e+03 4.52127930e+03 4.21414062e+03 4.58296582e+03 3.50547168e+03 2.14498755e+03 2.10342676e+03 3.39568091e+03 4.46488086e+03 8022168. -7.99636750e+05 4.14360150e+06 3.45027344e+03 2.25451733e+03 2.04443823e+03 1.53958215e+03 1.78223706e+03 1.42657166e+03 1.70793274e+03 1.38598206e+03 1.33215344e+03 1.29831812e+03 1.40403198e+03 1.00940289e+03 1.49081946e+03 1.45190723e+03 1.21366956e+03 1.14127283e+03 8.83514099e+02 8.56875854e+02 8.31021423e+02 8.03906982e+02 7.76984009e+02 7.50247864e+02 7.23473206e+02 6.96612976e+02 6.68913940e+02 6.41818604e+02 6.14807434e+02 5.87368530e+02 5.59853210e+02 5.32289734e+02 5.04584381e+02 4.76866058e+02 4.48899048e+02 4.21164734e+02 3.93398438e+02 3.65212585e+02 3.37087311e+02 3.09129791e+02 2.81022491e+02 2.52728302e+02 2.24586182e+02 1.96329956e+02 1.67928314e+02 1.39517380e+02 1.11156853e+02 8.29353027e+01 5.46287766e+01 2.62375450e+01 -2.13752270e+00 -3.05150433e+01 -5.89105301e+01 -8.72395401e+01 -1.15488853e+02 -1.43881668e+02 -1.72212021e+02 -2.00403030e+02 -2.28790009e+02 -2.57007629e+02 -2.85012421e+02 -3.13223236e+02 -3.41411682e+02 -3.69494598e+02 -3.97447327e+02 -4.25200714e+02 -4.52942291e+02 -4.80841858e+02 -5.08619385e+02 -5.36275085e+02 -5.63709656e+02 -5.91631714e+02 -6.18727600e+02 -6.45545593e+02 -6.73360596e+02 -7.00479553e+02 -7.27318787e+02 -7.54250977e+02 -7.81161499e+02 -8.07283630e+02 -8.34364319e+02 -8.61309265e+02 -8.86616882e+02 -9.12766296e+02 -9.38294922e+02 -9.65378784e+02 -9.90755981e+02 -1.01516364e+03 -1.04074634e+03 -1.06750476e+03 -1.09215674e+03 -1.11684070e+03 -1.14163123e+03 -1.16577197e+03 -1.19062170e+03 -1.21528552e+03 -1.24011230e+03 -1.26236133e+03 -1.28556787e+03 -1.30977722e+03 -1.33452307e+03 -1.35619385e+03 -1.37891821e+03 -1.40474023e+03 -1.42584692e+03 -1.44439722e+03 -1.46727271e+03 -1.49139636e+03 -1.50975854e+03 -1.53325403e+03 -1.55705396e+03 -1.57531531e+03 -1.59243066e+03 -1.61686865e+03 -1.64094934e+03 -1.65585754e+03 -1.67421423e+03 -1.69424158e+03 -1.71636853e+03 -1.73613904e+03 -1.75339661e+03 -1.76916833e+03 -1.78587158e+03 -1.80579834e+03 -1.82777185e+03 -1.84197803e+03 -1.85952197e+03 -1.87246680e+03 -1.88918457e+03 -1.91254248e+03 -1.92280933e+03 -1.93750403e+03 -1.95677563e+03 -1.97177893e+03 -1.98601294e+03 -1.99843201e+03 -2.01018530e+03 -2.02635242e+03 -2.04148560e+03 -2.05294409e+03 -2.07010596e+03 -2.08102710e+03 -2.08970654e+03 -2.10340161e+03 -2.11588330e+03 -2.12486621e+03 -2.13450049e+03 -2.14868506e+03 -2.16086499e+03 -2.16323486e+03 -2.17544409e+03 -2.19338916e+03 -2.19783813e+03 -2.19896899e+03 -2.20921436e+03 -2.22364575e+03 -2.23191772e+03 -2.23119238e+03 -2.24308252e+03 -2.25155225e+03 -2.25688354e+03 -2.26049438e+03 -2.26890039e+03 -2.27825684e+03 -2.27848730e+03 -2.27925024e+03 -2.28976196e+03 -2.28874146e+03 -2.29558765e+03 -2.29425342e+03 -2.95171436e+03 -3.08783569e+03 -3.43031982e+03 -3.42537524e+03 -3.42794238e+03 -3.44241895e+03 -5.62988232e+03 -6.80213623e+03 7251580. -5.94573850e+06 -6.82733545e+03 -5.47066016e+03 -3.43675439e+03 -3.43612744e+03 -3.41745435e+03 -3.42431030e+03 -3.42224854e+03 -3.42170654e+03 -3.40362158e+03 -3.40582886e+03 -3.40505640e+03 -3.38259375e+03 -3.38046631e+03 -3.38065625e+03 -3.36213574e+03 -3.35659375e+03 -3.11281641e+03 -3.34562622e+03 -3.06379126e+03 -3.33260889e+03 -5.14354980e+03 -3.31963550e+03 -5.36637646e+03 -3.27796289e+03 -3.28007495e+03 -3.26749243e+03 -3.24234448e+03 -2.96885205e+03 -2.80685571e+03 -2.14463818e+03 -2.12903271e+03 -2.70594995e+03 -2.80449463e+03 -3.12123608e+03 -3.10176880e+03 -3.08574243e+03 -3.06067041e+03 -5.12305469e+03 -2.59005332e+04 47587496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 65827508. 65827508. 65827508. 0. 0. 0. 0. 39352692. 39352692. 39352692. 0. 0. 167188768. 1.57215516e+05 1.56048094e+05 5.00752688e+05 -30789696. -180564048. 59365920. 59365920. 59365920. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -5.96269466e+09 -5.96269466e+09 -5.96269466e+09 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. -1148540160. -1148540160. -1148540160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 97407352. 97407352. 97407352. 0. 0. 0. 0. 0. 0. 0. 0. 0. 56842832. -9061306. 4.23295820e+04 -4.08843450e+06 -7.87497950e+06 9165844. -6.03958312e+05 24072544. 2.56564624e+03 3.05400781e+03 1.32874258e+04 2.63230078e+03 1.26457705e+04 1.26457705e+04 4599262. -15852164. -15852164. 15629822. 0. 0. 0. 0. 52656932. 52656932. 52656932. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.59553946e+09 -9.59553946e+09 -9.59553946e+09 0. 0. 0. 0. 0. 0. 0. 57413476. 57413476. 57413476. 0. -62066840. -4.26740850e+06 -5.61096625e+05 -4.03358350e+06 -4288934. 6.10870117e+03 4.94918945e+03 3.17017285e+03 3.19311108e+03 3.20731250e+03 3.22461377e+03 3.23752612e+03 5.26953223e+03 6.73159180e+03 -391842. -2.21696375e+06 49885892. 22989846. 2.71288066e+04 6.82337939e+03 -1.46942388e+06 -2.90954175e+06 -2.81085025e+06 6.69694434e+03 6.76585156e+03 6.83541113e+03 6.73208691e+03 5.45143311e+03 3.44016675e+03 3.44908472e+03 3.45250562e+03 3.44709155e+03 3.46145947e+03 3.46494043e+03 3.51174756e+03 5.46047119e+03 7.06627539e+03 2.68821875e+04 -590017856. -70963840. 0. 0. 5781835. 2.75129590e+04 6.90360059e+03 9259268. 10327478. 3.72993075e+06 -12592060. -5334756. -1.64789150e+06 6.95781885e+03 5.54572949e+03 3.45238477e+03 3.19669043e+03 3.02098071e+03 2.31333423e+03 2.30624976e+03 2.30866577e+03 2.29660400e+03 2.28933374e+03 2.28873047e+03 2.27902173e+03 2.27337842e+03 2.26738745e+03 2.25732544e+03 2.25066748e+03 2.23231396e+03 2.22603564e+03 2.22084155e+03 2.21160107e+03 2.20637036e+03 2.19516675e+03 2.18297656e+03 2.16632471e+03 2.16013354e+03 2.14738354e+03 2.73752222e+03 2.84679932e+03 2.91754492e+03 2.73515210e+03 2.08423877e+03 2.07261768e+03 2.05966431e+03 2.04384375e+03 2.59292505e+03 2.69199194e+03 2.77985254e+03 2.60004492e+03 1.96609253e+03 1.95256970e+03 1.93573633e+03 1.91914661e+03 1.90350208e+03 1.88334961e+03 1.86939954e+03 1.85205066e+03 1.83028723e+03 1.81204895e+03 1.79902539e+03 1.77540894e+03 1.75556604e+03 1.74109937e+03 1.72195581e+03 1.69587183e+03 1.67670728e+03 1.65996277e+03 1.64004163e+03 1.61719983e+03 1.59402637e+03 1.57439380e+03 1.55230469e+03 1.53244836e+03 1.50962036e+03 1.48729272e+03 1.46630249e+03 1.44218628e+03 1.41922961e+03 1.39689197e+03 1.37231262e+03 1.34945508e+03 1.32651672e+03 1.30173291e+03 1.27676990e+03 1.25318652e+03 1.22891626e+03 1.20360034e+03 1.17918457e+03 1.15339136e+03 1.12823047e+03 1.10318799e+03 1.07738293e+03 1.05179785e+03 1.02576880e+03 9.99529663e+02 9.73906006e+02 9.47341370e+02 9.20822876e+02 8.93759521e+02 8.67339417e+02 8.41111023e+02 8.13257202e+02 7.86182373e+02 7.59023560e+02 7.31624512e+02 7.04144226e+02 6.76498352e+02 6.48920288e+02 6.21354431e+02 5.92967651e+02 5.65198792e+02 5.37438904e+02 5.09050903e+02 4.80935791e+02 4.52566895e+02 4.24064423e+02 3.95778259e+02 3.67278259e+02 3.38685974e+02 3.10008575e+02 2.81439270e+02 2.52833145e+02 2.24121841e+02 1.95349823e+02 1.66626297e+02 1.37839630e+02 1.08933258e+02 8.00047760e+01 5.11726570e+01 2.23582344e+01 -6.54443359e+00 -3.54342804e+01 -6.42705994e+01 -9.30728760e+01 -1.22016220e+02 -1.50847244e+02 -1.79496796e+02 -2.08154114e+02 -2.36930511e+02 -2.65762482e+02 -2.94341064e+02 -3.22938446e+02 -3.51674591e+02 -3.80215332e+02 -4.08658356e+02 -4.37121094e+02 -4.65075348e+02 -4.93439423e+02 -5.21653503e+02 -5.49913147e+02 -5.78126648e+02 -6.05958923e+02 -6.33658508e+02 -6.61120300e+02 -6.88998230e+02 -7.17026978e+02 -7.44164307e+02 -7.70865295e+02 -7.98676147e+02 -8.26140503e+02 -8.52699768e+02 -8.79409058e+02 -9.05868958e+02 -9.32990845e+02 -9.59665588e+02 -9.85742554e+02 -1.01189539e+03 -1.03934229e+03 -1.06611133e+03 -1.09053357e+03 -1.11477429e+03 -1.43803284e+03 -1.52315796e+03 -1.80323694e+03 -1.84628491e+03 -1.88548071e+03 -1.82969604e+03 -1.73443750e+03 -1.61441711e+03 -2.70581177e+03 -2.04781287e+03 -4.07645776e+03 -4.34063135e+03 -1.33954062e+06 -3.47125150e+06 2.63552575e+06 -3.05270527e+04 -1854187392. -580577792. 0. 0. 0. 0. 0. 0. -24429536. -2.62390273e+04 -6.41618018e+03 2.43736344e+05 -2.31522290e+03 -3.82898706e+03 -4.48371387e+03 1.39156512e+06 6.70083359e+04 4.87315742e+04 1.01824838e+06 -2.85703027e+03 -3.48668237e+03 -4.42014844e+03 -2.67499854e+03 -5.86628320e+03 -3.60176392e+03 -4.38136475e+03 -2.95885449e+03 -3.03016382e+03 -3.15529736e+03 -2.93793433e+03 -3.04693481e+03 -2.82145557e+03 -3.05606543e+03 -3.09920630e+03 -3.08430347e+03 -3.10474023e+03 -3.16047583e+03 -3.14464209e+03 -3.14784326e+03 -3.17161157e+03 -5.15792822e+03 -3.48190674e+03 -4.67436523e+03 -6.53557861e+03 -6.62009375e+03 -1.82259216e+03 3.52783750e+04 3.70415969e+05 9.35385500e+05 6.75113250e+05 -3.33018875e+06 -11395548. -5445226. -3.30332375e+06 -15649554. 2.53144825e+06 5673026. 2.95737575e+06 -2.18753325e+06 -2.11194350e+06 -2.52454375e+06 -6.17774650e+06 -6.03427250e+06 4377010. -6.88578564e+03 -5.51746143e+03 -3.48058447e+03 -3.22389795e+03 -3.04967725e+03 -2.35170239e+03 -2.34913501e+03 -2.35145337e+03 -2.34983447e+03 -2.35056567e+03 -2.34972144e+03 -2.34689209e+03 -2.34362646e+03 -2.34880493e+03 -2.34105640e+03 -2.33694824e+03 -2.33934814e+03 -2.33188354e+03 -2.32733057e+03 -2.32450854e+03 -2.32477490e+03 -2.31242236e+03 -2.30799048e+03 -2.30374609e+03 -2.29738574e+03 -2.29252710e+03 -2.28576855e+03 -2.28116528e+03 -2.27398145e+03 -2.26090015e+03 -2.25585254e+03 -2.25131641e+03 -2.23485913e+03 -2.22652173e+03 -2.22110132e+03 -2.21403491e+03 -2.20473901e+03 -2.19548022e+03 -2.18099292e+03 -2.16494556e+03 -2.15845923e+03 -2.15000781e+03 -2.13934375e+03 -2.12439355e+03 -2.10407324e+03 -2.09464478e+03 -2.08278467e+03 -2.07337354e+03 -2.05904004e+03 -2.04211060e+03 -2.02994556e+03 -2.01669470e+03 -1.99646350e+03 -1.98737280e+03 -1.96388110e+03 -1.94867322e+03 -1.93695081e+03 -1.92128894e+03 -1.90436523e+03 -1.88529126e+03 -1.86756946e+03 -1.85246960e+03 -1.83060022e+03 -1.81303552e+03 -1.79775867e+03 -1.77319629e+03 -1.75467102e+03 -1.74109131e+03 -1.72064893e+03 -1.69408594e+03 -1.67547229e+03 -1.65857336e+03 -1.64081104e+03 -1.61571484e+03 -1.59477075e+03 -1.57591040e+03 -1.55181262e+03 -1.53167065e+03 -1.50888367e+03 -1.48611731e+03 -1.46581665e+03 -1.44262939e+03 -1.41849280e+03 -1.39551001e+03 -1.37212683e+03 -1.35032800e+03 -1.32544556e+03 -1.30136987e+03 -1.27638245e+03 -1.25286633e+03 -1.22811121e+03 -1.20128882e+03 -1.17809753e+03 -1.15503467e+03 -1.12819531e+03 -1.10251587e+03 -1.07705542e+03 -1.05122827e+03 -1.02540674e+03 -9.98848877e+02 -9.74189148e+02 -9.47676880e+02 -9.20891724e+02 -8.93690125e+02 -8.67041626e+02 -8.40337097e+02 -8.13320312e+02 -7.86486023e+02 -7.58699829e+02 -7.31642578e+02 -7.04179138e+02 -6.75798950e+02 -6.48246521e+02 -6.21060425e+02 -5.93162415e+02 -5.65062073e+02 -5.37268921e+02 -5.08880096e+02 -4.80781616e+02 -4.52534149e+02 -4.23934052e+02 -3.95607910e+02 -3.67132019e+02 -3.38711273e+02 -3.10039581e+02 -2.81458862e+02 -2.52699356e+02 -2.23720856e+02 -1.95076309e+02 -1.66826813e+02 -1.38019836e+02 -1.08974586e+02 -8.00697250e+01 -5.11573639e+01 -2.23559570e+01 6.51964808e+00 3.53153381e+01 6.43034592e+01 9.32433395e+01 1.21978043e+02 1.50724976e+02 1.79483383e+02 2.08228943e+02 2.36826767e+02 2.65549500e+02 2.94214447e+02 3.22811676e+02 3.51524933e+02 3.80108612e+02 4.08558258e+02 4.36841858e+02 4.65075623e+02 4.93551361e+02 5.21535095e+02 5.49563782e+02 5.77999023e+02 6.05717590e+02 6.33121521e+02 6.60789185e+02 6.88992249e+02 7.16654785e+02 7.43554077e+02 7.71043884e+02 7.98825500e+02 8.25190002e+02 8.51672974e+02 8.79701965e+02 9.06175171e+02 9.31818970e+02 9.58930176e+02 9.85836975e+02 1.01114868e+03 1.03720129e+03 1.06243872e+03 1.08918091e+03 1.11498132e+03 1.13852478e+03 1.16455261e+03 1.19083154e+03 1.21372070e+03 1.23850354e+03 1.26459033e+03 1.28895337e+03 1.31305005e+03 1.33572729e+03 1.35834863e+03 1.38172192e+03 1.40575427e+03 1.43052979e+03 1.45413098e+03 1.47370349e+03 1.49621570e+03 1.52069873e+03 1.53965723e+03 1.56184863e+03 1.58667908e+03 1.60797839e+03 1.62422510e+03 1.64523608e+03 1.66820569e+03 1.68461047e+03 1.70569360e+03 1.72885303e+03 1.74832080e+03 1.76947888e+03 1.78496130e+03 1.80366956e+03 1.82021887e+03 1.83596545e+03 1.86226038e+03 1.87639294e+03 1.89079626e+03 1.90978442e+03 1.92662158e+03 1.94350537e+03 1.95934338e+03 1.97379773e+03 1.99216602e+03 2.00679919e+03 2.02187354e+03 2.03559607e+03 2.04987622e+03 2.06359277e+03 2.07540601e+03 2.09216895e+03 2.10622925e+03 2.11491821e+03 2.13180762e+03 2.14213745e+03 2.15540723e+03 2.16473511e+03 2.17016382e+03 2.18767847e+03 2.19265942e+03 2.20783252e+03 2.21803442e+03 2.22578516e+03 2.23816455e+03 2.24390771e+03 2.25240576e+03 2.26224683e+03 2.26793701e+03 2.27492554e+03 2.28469507e+03 2.28798413e+03 2.29738281e+03 2.29777979e+03 2.31111694e+03 2.32073193e+03 2.31850269e+03 2.32579639e+03 2.32869043e+03 2.32767432e+03 2.34009692e+03 2.34505469e+03 2.33472900e+03 2.34206860e+03 2.34895654e+03 2.34774072e+03 2.34763184e+03 2.34925879e+03 2.35291382e+03 2.35215015e+03 2.35026465e+03 2.34712939e+03 2.34798706e+03 2.35103979e+03 3.02445557e+03 3.18011841e+03 3.47802930e+03 3.46656201e+03 3.46962158e+03 3.46438257e+03 3.45773730e+03 5.46764404e+03 6.77019043e+03 6.88260986e+03 6.81960889e+03 6.71754834e+03 3677637. -2.34194475e+06 3.27807350e+06 6509584. 6.60681689e+03 6.56586035e+03 4.74224561e+03 6.44782910e+03 -1.76684088e+06 -7.42877625e+05 -7932172. 6.66804004e+03 5.96591260e+03 4.26974023e+03 4.60379932e+03 6.23550146e+03 6.69064600e+03 6.06582812e+03 5.16035303e+03 -2163883. 2.62551975e+06 3.72254175e+06 -6.94293850e+06 11656459. 3.97845075e+06 48792808. 7891997. 2.16948650e+06 13087206. 2198327. -2.10630450e+06 -2.57436725e+06 5.86615039e+03 5.70397412e+03 3.02306982e+03 5.59279980e+03 5.28900537e+03 -1.46582150e+06 -3.09293875e+05 -3.87215688e+05 -8051897. -8.00264250e+05 14379382. -3.49918550e+06 5.13379688e+03 2.02597988e+04 11207521. 0. 0. 0. 0. 0. 44492012. 44492012. 44492012. -72030592. 9.97101375e+05 -6.57345438e+05 -14141556. -3.50874250e+06 -1.53858712e+06 4.23289404e+03 3.28192578e+03 1.98918933e+03 1.95387891e+03 1.56451843e+03 2.01126721e+03 1.90020532e+03 1.81689429e+03 1.53177124e+03 1.74521729e+03 1.63407190e+03 1.43682959e+03 1.35466760e+03 1.05266809e+03 1.02614929e+03 1.00021887e+03 9.73636536e+02 9.47154968e+02 9.20717590e+02 8.93546814e+02 8.67134949e+02 8.40820435e+02 8.13287598e+02 7.85626709e+02 7.58614014e+02 7.31588135e+02 7.04033997e+02 6.76417480e+02 6.48568298e+02 6.21042175e+02 5.93009460e+02 5.65050293e+02 5.37132507e+02 5.09009308e+02 4.80767456e+02 4.52304657e+02 4.24057434e+02 3.95750122e+02 3.67194794e+02 3.38568878e+02 3.09941528e+02 2.81430817e+02 2.52822388e+02 2.24142883e+02 1.95427521e+02 1.66499710e+02 1.37472733e+02 1.08660271e+02 8.00150452e+01 5.11625175e+01 2.22773705e+01 -6.49232769e+00 -3.53549423e+01 -6.43162689e+01 -9.31001358e+01 -1.21881310e+02 -1.50650162e+02 -1.79429337e+02 -2.08272385e+02 -2.37021545e+02 -2.65631897e+02 -2.94239624e+02 -3.22963989e+02 -3.51555176e+02 -3.80080902e+02 -4.08608704e+02 -4.37002594e+02 -4.65081024e+02 -4.93417206e+02 -5.21513306e+02 -5.49504517e+02 -5.77406372e+02 -6.05747925e+02 -6.33091431e+02 -6.60583862e+02 -6.88981812e+02 -7.16788513e+02 -7.44183350e+02 -7.70984131e+02 -7.98188049e+02 -8.25410095e+02 -8.52488098e+02 -8.79655151e+02 -9.06244812e+02 -9.32328796e+02 -9.58743591e+02 -9.85706726e+02 -1.01139520e+03 -1.03706262e+03 -1.06346704e+03 -1.08926001e+03 -1.11445435e+03 -1.13916272e+03 -1.16566882e+03 -1.19034351e+03 -1.21371643e+03 -1.23909644e+03 -1.26482202e+03 -1.28832983e+03 -1.31272070e+03 -1.33639136e+03 -1.35922974e+03 -1.38146460e+03 -1.40582935e+03 -1.43167749e+03 -1.45389819e+03 -1.47331567e+03 -1.49560266e+03 -1.52033484e+03 -1.54128296e+03 -1.56229346e+03 -1.58533667e+03 -1.60631519e+03 -1.62534033e+03 -1.64720337e+03 -1.66901929e+03 -1.68727368e+03 -1.70718689e+03 -1.72772900e+03 -1.74910474e+03 -1.76767004e+03 -1.78524976e+03 -1.80223132e+03 -1.81902466e+03 -1.83669226e+03 -1.86231482e+03 -1.87669690e+03 -1.89356201e+03 -1.90955115e+03 -1.92243066e+03 -1.94526135e+03 -1.96011536e+03 -1.97209937e+03 -1.99265234e+03 -2.00733313e+03 -2.02164502e+03 -2.03608264e+03 -2.04865430e+03 -2.06102002e+03 -2.07816797e+03 -2.09113013e+03 -2.10622803e+03 -2.11930981e+03 -2.12798755e+03 -2.13876758e+03 -2.15172290e+03 -2.17290308e+03 -2.17572778e+03 -2.18332788e+03 -2.19713037e+03 -2.20590747e+03 -2.21595020e+03 -2.23092871e+03 -2.23394678e+03 -2.24266504e+03 -2.25799536e+03 -2.26725317e+03 -2.26580200e+03 -2.26731812e+03 -2.28125244e+03 -2.29181787e+03 -2.29312720e+03 -2.30059302e+03 -2.30674512e+03 -2.31757031e+03 -2.31722876e+03 -2.32227661e+03 -2.32883252e+03 -3.06791504e+03 -3.34238623e+03 -3.23122583e+03 -4.92461084e+03 -6.02004004e+03 -1.64175950e+06 4.99586328e+04 -9.50212734e+04 -1.21712212e+06 35454856. -58404156. 0. 0. -26178324. 34462728. -2.36224175e+06 3200939. -1.22354938e+06 4970106. -3.56316475e+06 3237833. 1.04753425e+06 2.47510350e+06 -6.87426465e+03 -6.84357471e+03 -6.79470166e+03 -1.94623425e+06 -15369731. 4.64857350e+06 -6.72361133e+03 -6.73390283e+03 -6.73960498e+03 -1.46942373e+04 -17000164. 7.17727950e+06 31945958. -7.42524297e+04 -5.12252109e+04 -6.01128711e+04 3.17039750e+05 -6.79809131e+03 -5.29005811e+03 -3.22099634e+03 -3.20309424e+03 -4.99264404e+03 -6.09011084e+03 -10627519. -127286680. 1.10639250e+06 -1.76170312e+04 -1176500096. 47787000. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 65827508. 65827508. 65827508. 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. 0. 0. 0. 0. 0. 0. 0. -5.96269466e+09 -5.96269466e+09 -5.96269466e+09 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. -1148540160. -1148540160. 227358048. -207423008. -207423008. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 48703676. 48703676. 48703676. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 686052736. 686052736. 686052736. 633803904. -1.03958412e+06 -1.03958412e+06 2299631. -7926082. -7926082. 7814911. 0. 0. 0. 0. 52656932. 52656932. 52656932. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.59553946e+09 -9.59553946e+09 -9.59553946e+09 0. 0. 0. 0. 0. 0. 0. 57413476. 57413476. 57413476. 0. 0. 0. 0. 0. 0. 60152944. 2.80611450e+06 752185. -7.50683438e+05 6.71608950e+06 9.07518812e+05 -6.12390562e+05 10448964. 1.87643588e+06 0. 0. 0. -11961193. -11961193. -11961193. 0. 0. 0. 252966864. 252966864. 252966864. 50112816. 3.24799850e+06 -8.32370688e+05 -1.25575050e+06 2.95835125e+06 -3.82455175e+06 -2.60324050e+06 -14548975. 9.50044141e+03 -2721977. -21102690. -70963840. -70963840. -70963840. 0. 0. 22417482. 22417482. 22417482. 0. 0. 0. 0. 0. 0. -19208278. -1.47539338e+06 -4927072. 3.51176221e+03 3.11243945e+03 2.32175635e+03 2.31632837e+03 2.31396924e+03 2.30228223e+03 2.29343848e+03 2.29429810e+03 2.28634106e+03 2.27989673e+03 2.27182178e+03 2.25779712e+03 2.25497266e+03 2.23907788e+03 2.23219751e+03 2.22500708e+03 2.22168872e+03 2.21049048e+03 2.19753247e+03 2.18544824e+03 2.16973291e+03 2.16346558e+03 2.15962061e+03 2.79296509e+03 3.02616846e+03 3.25890649e+03 2.83350146e+03 2.08847583e+03 2.07917334e+03 2.05963477e+03 2.05112109e+03 2.63404346e+03 2.83230835e+03 3.12670850e+03 2.71357910e+03 1.96935168e+03 1.95412048e+03 1.94126428e+03 1.92533215e+03 1.90623181e+03 1.88885791e+03 1.87574084e+03 1.85287964e+03 1.83205249e+03 1.81412903e+03 1.80204749e+03 1.77935657e+03 1.75734204e+03 1.74283386e+03 1.72445288e+03 1.70049231e+03 1.68093970e+03 1.66205115e+03 1.64301611e+03 1.62022559e+03 1.59412048e+03 1.57453162e+03 1.55882275e+03 1.53812000e+03 1.51084363e+03 1.48924512e+03 1.46701282e+03 1.44129517e+03 1.41998535e+03 1.39928772e+03 1.37578125e+03 1.35170776e+03 1.32659070e+03 1.30361475e+03 1.27983679e+03 1.25401575e+03 1.23013843e+03 1.20439722e+03 1.18129297e+03 1.15571741e+03 1.12941821e+03 1.10466602e+03 1.07733325e+03 1.05213025e+03 1.02766711e+03 1.00096606e+03 9.74799011e+02 9.46945435e+02 9.21576782e+02 8.94678101e+02 8.68062073e+02 8.41661316e+02 8.12861328e+02 7.85943237e+02 7.59064453e+02 7.31247559e+02 7.03954407e+02 6.76437927e+02 6.48892700e+02 6.20876465e+02 5.92112976e+02 5.64198792e+02 5.36965515e+02 5.08664459e+02 4.80248596e+02 4.51533508e+02 4.23121613e+02 3.95007812e+02 3.66462891e+02 3.37659790e+02 3.08646973e+02 2.79947784e+02 2.51334763e+02 2.22754745e+02 1.93892258e+02 1.65210175e+02 1.36363647e+02 1.07210823e+02 7.81317368e+01 4.88248329e+01 1.99063377e+01 -8.54184246e+00 -3.75047493e+01 -6.63914108e+01 -9.50658493e+01 -1.24607841e+02 -1.53626770e+02 -1.82015091e+02 -2.10586044e+02 -2.39401718e+02 -2.68477875e+02 -2.96937469e+02 -3.25438812e+02 -3.54691803e+02 -3.83227386e+02 -4.11895996e+02 -4.40566467e+02 -4.67812561e+02 -4.96616730e+02 -5.25270935e+02 -5.53347168e+02 -5.81746033e+02 -6.09766235e+02 -6.37661560e+02 -6.64258240e+02 -6.92523621e+02 -7.20999878e+02 -7.47858154e+02 -7.74653564e+02 -8.02199036e+02 -8.30072144e+02 -8.56900330e+02 -8.83982361e+02 -9.10269958e+02 -9.36686584e+02 -9.63589111e+02 -9.90096497e+02 -1.01624438e+03 -1.04284680e+03 -1.06863318e+03 -1.09360547e+03 -1.11906458e+03 -1.14529907e+03 -1.17178320e+03 -1.19899695e+03 -1.22968286e+03 -1.25608362e+03 -1.27805640e+03 -1.29950293e+03 -2.48563770e+03 -1.51530078e+04 -9010884. -130615248. -130615248. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 23040304. 23040304. 23040304. 0. -39482064. -39482064. -39482064. 0. 0. 0. 0. 14429323. 3798009. 3798009. -1.30055950e+06 -2.17141312e+05 -16082913. 4766087. -3.45306689e+03 -3.85083125e+04 -7.63238721e+03 -3.40574194e+03 -3.12001636e+03 -2.92591992e+03 -2.55949854e+03 -1.48569941e+04 1.88688086e+04 9.17934863e+03 -5.08012031e+04 5.31478271e+03 7.42778281e+04 3.05907051e+04 4986671. 5.81408550e+06 3.82488475e+06 3.82488475e+06 18667696. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -19612156. 3.45346650e+06 -14699291. -3.51815820e+03 -3.13237451e+03 -2.35761865e+03 -2.35306152e+03 -2.35661938e+03 -2.35151392e+03 -2.35244336e+03 -2.35442480e+03 -2.35561084e+03 -2.35464233e+03 -2.35384668e+03 -2.34636353e+03 -2.34164282e+03 -2.34443433e+03 -2.33857495e+03 -2.33195166e+03 -2.33474756e+03 -2.32484985e+03 -2.31905005e+03 -2.31602539e+03 -2.31167505e+03 -2.30718359e+03 -2.30287817e+03 -2.29216382e+03 -2.28698267e+03 -2.27770386e+03 -2.26784888e+03 -2.26063550e+03 -2.25688257e+03 -2.24470776e+03 -2.23595874e+03 -2.22604004e+03 -2.21860425e+03 -2.20897241e+03 -2.19646021e+03 -2.18682520e+03 -2.16790063e+03 -2.16399438e+03 -2.15524805e+03 -2.14321118e+03 -2.12511084e+03 -2.11348706e+03 -2.09723047e+03 -2.08910010e+03 -2.07779370e+03 -2.06107251e+03 -2.04746289e+03 -2.03264050e+03 -2.01628662e+03 -1.99998987e+03 -1.99181873e+03 -1.96658752e+03 -1.95181287e+03 -1.94415332e+03 -1.92544617e+03 -1.90583105e+03 -1.88883289e+03 -1.87403772e+03 -1.85459229e+03 -1.83165967e+03 -1.81553796e+03 -1.80107849e+03 -1.77685205e+03 -1.75870129e+03 -1.74400842e+03 -1.72266138e+03 -1.69896790e+03 -1.67943591e+03 -1.66061169e+03 -1.64400842e+03 -1.61959827e+03 -1.59623108e+03 -1.57608447e+03 -1.55556238e+03 -1.53386890e+03 -1.51093262e+03 -1.48753918e+03 -1.46568530e+03 -1.44465381e+03 -1.42114600e+03 -1.39811914e+03 -1.37447119e+03 -1.35083557e+03 -1.32769177e+03 -1.30243555e+03 -1.27784326e+03 -1.25313696e+03 -1.23100854e+03 -1.20275110e+03 -1.17896912e+03 -1.15612366e+03 -1.12893262e+03 -1.10377014e+03 -1.07745203e+03 -1.05179407e+03 -1.02625977e+03 -1.00006116e+03 -9.75300293e+02 -9.47799805e+02 -9.21483276e+02 -8.95335754e+02 -8.66821777e+02 -8.39692444e+02 -8.14024475e+02 -7.86930115e+02 -7.58495117e+02 -7.31427490e+02 -7.04543152e+02 -6.75736877e+02 -6.47521851e+02 -6.20030640e+02 -5.92561462e+02 -5.64631348e+02 -5.36612488e+02 -5.08434113e+02 -4.80049744e+02 -4.51510315e+02 -4.23034546e+02 -3.95172363e+02 -3.66509094e+02 -3.37539917e+02 -3.08808960e+02 -2.80128510e+02 -2.50992081e+02 -2.21599945e+02 -1.93215958e+02 -1.65888992e+02 -1.36972015e+02 -1.07327972e+02 -7.83256454e+01 -4.92270851e+01 -2.03653946e+01 8.65098095e+00 3.75394478e+01 6.72203674e+01 9.62798462e+01 1.24505753e+02 1.53219391e+02 1.81997360e+02 2.10861832e+02 2.39332474e+02 2.68328033e+02 2.97277283e+02 3.25610413e+02 3.54253876e+02 3.83056854e+02 4.11836975e+02 4.39973938e+02 4.68112915e+02 4.96800751e+02 5.25013611e+02 5.52884094e+02 5.81244324e+02 6.09013916e+02 6.36179321e+02 6.64512939e+02 6.92241333e+02 7.19363953e+02 7.47544983e+02 7.75774963e+02 8.02948669e+02 8.29190979e+02 8.56176575e+02 8.84127319e+02 9.10196838e+02 9.36065552e+02 9.64031799e+02 9.89776123e+02 1.01507129e+03 1.04337830e+03 1.06759900e+03 1.09266101e+03 1.11874109e+03 1.14313354e+03 1.16997131e+03 1.19463354e+03 1.21825537e+03 1.24296680e+03 1.26958179e+03 1.29541895e+03 1.31874561e+03 1.34026721e+03 1.36237048e+03 1.38594617e+03 1.41257397e+03 1.43652637e+03 1.46078223e+03 1.47941821e+03 1.50038501e+03 1.52588281e+03 1.54549292e+03 1.56801990e+03 1.59312048e+03 1.61349829e+03 1.62860034e+03 1.65011267e+03 1.67786389e+03 1.69402454e+03 1.71288855e+03 1.73414319e+03 1.75004749e+03 1.77358423e+03 1.78900891e+03 1.81021167e+03 1.82933032e+03 1.84425220e+03 1.86630798e+03 1.88210852e+03 1.89956726e+03 1.91127185e+03 1.93100220e+03 1.95360681e+03 1.96327734e+03 1.97791895e+03 1.99396375e+03 2.01046985e+03 2.03071472e+03 2.04388367e+03 2.05094556e+03 2.07310352e+03 2.08484570e+03 2.09448804e+03 2.11402539e+03 2.12619751e+03 2.13919214e+03 2.14463770e+03 2.15838403e+03 2.17444043e+03 2.17605151e+03 2.19015967e+03 2.19991113e+03 2.20863892e+03 2.22368384e+03 2.23804883e+03 2.24589600e+03 2.24767456e+03 2.25405981e+03 2.26892163e+03 2.27170654e+03 2.28185352e+03 2.29123022e+03 2.29620874e+03 2.30502490e+03 2.30469604e+03 2.31042627e+03 2.32631982e+03 2.33023291e+03 2.32596069e+03 2.33569458e+03 2.33375854e+03 2.34517383e+03 2.35245166e+03 2.34285620e+03 2.34291431e+03 2.35199561e+03 2.35515894e+03 2.35504541e+03 2.35335645e+03 2.35895215e+03 2.35958691e+03 2.35878394e+03 2.35038574e+03 2.35397827e+03 2.35789307e+03 3.12088965e+03 3.48009863e+03 35872792. 2.75527425e+06 -3.99701775e+06 -3.08058656e+05 -1.16373688e+05 -4992041. 12470356. 7.53821125e+05 7.53821125e+05 7.53821125e+05 0. 0. 0. 0. -3.62708850e+06 -7630294. -7630294. -53648068. 0. 0. 0. 7401231. -33817648. 2.29699609e+04 -18538562. 6.13422650e+06 114210176. 114210176. 114210176. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 42326792. 42326792. 226276272. 92098648. 92098648. 0. 0. 0. 0. 0. 0. 0. -75963720. -75963720. -75963720. 0. 0. 0. 0. 0. 22246006. 22246006. 22246006. 0. 0. 0. 0. 0. 0. 53038192. -7.49783750e+05 3.64848075e+06 1.38852250e+06 3.54093140e+03 2.20867651e+03 1.35831299e+03 1.20767493e+03 1.18108118e+03 1.15554553e+03 1.12967981e+03 1.10445068e+03 1.07819800e+03 1.05306824e+03 1.02779041e+03 1.00072906e+03 9.74446472e+02 9.47414856e+02 9.21101074e+02 8.94130981e+02 8.67203857e+02 8.40910156e+02 8.12768250e+02 7.85644714e+02 7.58627075e+02 7.31236633e+02 7.04067749e+02 6.76702332e+02 6.48203857e+02 6.20170654e+02 5.92569031e+02 5.64361633e+02 5.36461853e+02 5.08562469e+02 4.80092285e+02 4.51450165e+02 4.23173889e+02 3.94808167e+02 3.66260254e+02 3.37516907e+02 3.08560516e+02 2.79836670e+02 2.51389893e+02 2.22975784e+02 1.94296356e+02 1.64874466e+02 1.34766281e+02 1.05802307e+02 7.79212418e+01 4.91213226e+01 2.01697464e+01 -8.39560223e+00 -3.74640999e+01 -6.69624939e+01 -9.56008835e+01 -1.23979240e+02 -1.52638489e+02 -1.81781204e+02 -2.11142792e+02 -2.40093124e+02 -2.68271759e+02 -2.96595551e+02 -3.25826477e+02 -3.54451569e+02 -3.83120209e+02 -4.12127930e+02 -4.40359283e+02 -4.68343536e+02 -4.96872284e+02 -5.24858826e+02 -5.52890076e+02 -5.80429626e+02 -6.08569763e+02 -6.35479492e+02 -6.62635071e+02 -6.92645752e+02 -7.20967957e+02 -7.47681274e+02 -7.74603210e+02 -8.01636536e+02 -8.29493591e+02 -8.57475220e+02 -8.83980957e+02 -9.10152100e+02 -9.35504395e+02 -9.62522461e+02 -9.89794800e+02 -1.01479120e+03 -1.04258398e+03 -1.06901074e+03 -1.09288293e+03 -1.11815320e+03 -1.14493384e+03 -1.17119543e+03 -1.19442957e+03 -1.21831042e+03 -1.24283960e+03 -1.27076318e+03 -1.29483411e+03 -1.31766797e+03 -1.34048840e+03 -1.36289282e+03 -1.38659387e+03 -1.41173425e+03 -1.43690137e+03 -1.45966687e+03 -1.48040552e+03 -1.49958020e+03 -1.52311060e+03 -1.54681360e+03 -1.56761572e+03 -1.59354932e+03 -1.61165552e+03 -1.62836023e+03 -1.65265527e+03 -1.67964966e+03 -1.69595264e+03 -1.71118469e+03 -1.73201282e+03 -1.75505920e+03 -1.77408887e+03 -1.79083545e+03 -1.80742419e+03 -1.82211279e+03 -1.84433228e+03 -1.86902527e+03 -1.88585156e+03 -1.90117578e+03 -1.91387610e+03 -1.92873169e+03 -1.95116833e+03 -1.96944958e+03 -1.97458252e+03 -1.99342236e+03 -2.01278125e+03 -2.02748987e+03 -2.04253442e+03 -2.05349097e+03 -2.07132056e+03 -2.08297998e+03 -2.09357056e+03 -2.11350439e+03 -2.12570923e+03 -2.13315039e+03 -2.14656470e+03 -2.16168115e+03 -2.20437183e+03 -2.18452319e+03 -2.19492944e+03 -2.19992896e+03 -2.21007983e+03 -2.22165967e+03 -2.23770703e+03 -2.24443579e+03 -2.25097559e+03 -2.27684863e+03 -2.27043164e+03 -2.27218799e+03 -2.27443701e+03 -2.28795923e+03 -2.29384009e+03 -2.30215405e+03 -2.30689307e+03 -2.31562964e+03 -2.32491455e+03 -2.32581909e+03 -2.33904126e+03 -2.34251245e+03 -3.49501367e+03 -4.76380420e+03 -3.31626929e+03 -1.38738311e+04 -7.97247850e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6473363. -6473363. -6473363. 0. 0. 0. -41674648. -41674648. -41674648. 0. 0. 0. 0. 0. 0. 0. 0. -18113776. 3.04154075e+06 1.88154050e+06 3.30333906e+05 6.81579312e+05 19489578. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 32913754. 32913754. 32913754. 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. 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. 0. 0. 0. 0. 0. 0. 0. -574270080. -574270080. -116224808. -207423008. -207423008. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_4.xml ================================================ 16 1024
f
3.89828116e+10 1.88189297e+04 4.70337891e+03 4.70243896e+03 4.70202197e+03 4.69964404e+03 4.69907275e+03 4.69549805e+03 4.69128467e+03 4.68992090e+03 4.68620947e+03 4.68263770e+03 4.68147803e+03 4.67589893e+03 4.66666357e+03 4.65991211e+03 4.65995166e+03 4.65309619e+03 4.64302490e+03 4.63749512e+03 4.63308643e+03 4.62825439e+03 4.61879834e+03 4.61206445e+03 4.59931592e+03 4.58712988e+03 4.58306934e+03 4.57860205e+03 4.57129102e+03 4.55490869e+03 4.54608105e+03 4.53437646e+03 4.51815039e+03 4.51310498e+03 4.50033740e+03 4.48674658e+03 4.47797559e+03 4.46591016e+03 4.45396875e+03 4.44024854e+03 4.41995752e+03 4.40829102e+03 4.39589697e+03 4.38498779e+03 4.36732764e+03 4.34971191e+03 4.34282861e+03 4.32532812e+03 4.29532812e+03 4.28544629e+03 4.28175146e+03 4.25867383e+03 4.23936475e+03 4.21871143e+03 4.19795996e+03 4.18349951e+03 4.18286035e+03 4.15569482e+03 4.12153662e+03 4.10654541e+03 4.09733252e+03 4.08082690e+03 4.05487646e+03 4.03569434e+03 4.00688184e+03 3.98848975e+03 3.98331274e+03 3.95570508e+03 3.92397949e+03 3.89866797e+03 3.88794922e+03 3.87930835e+03 3.83984961e+03 3.80101025e+03 3.78840356e+03 3.78625293e+03 3.75989062e+03 3.72326270e+03 3.71636182e+03 3.69113062e+03 3.64758179e+03 3.63687036e+03 3.62166821e+03 3.59034448e+03 3.55121436e+03 3.53313062e+03 3.53024390e+03 3.48447290e+03 7.36476611e+03 1.20650146e+04 4.51143906e+04 -7.58353750e+06 -134334384. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 14195943. 3490674. 2.56359512e+04 4.39902051e+03 3.89618506e+03 2.86880713e+03 2.84054907e+03 2.80706567e+03 2.80456909e+03 2.77639111e+03 2.74097583e+03 2.70723950e+03 2.67514502e+03 2.64021021e+03 2.61386548e+03 2.58421777e+03 2.54646338e+03 2.54017822e+03 2.50414282e+03 2.47059106e+03 2.45615918e+03 2.41421777e+03 2.37703979e+03 2.35116772e+03 2.32961035e+03 2.29596411e+03 2.26231787e+03 2.23716675e+03 2.20396484e+03 2.18889282e+03 2.16573413e+03 2.12023560e+03 2.10769189e+03 2.08736816e+03 2.04699390e+03 2.02117896e+03 1.99091785e+03 1.95653589e+03 1.92154578e+03 1.89691052e+03 1.86720374e+03 1.83084619e+03 1.81530090e+03 1.78410718e+03 1.75787830e+03 1.73740576e+03 1.70668262e+03 1.68630688e+03 1.65275574e+03 1.61642993e+03 1.59009546e+03 1.56504907e+03 1.54220081e+03 1.52003931e+03 1.48634338e+03 1.46375342e+03 1.43576477e+03 1.40402295e+03 1.38146985e+03 1.35916272e+03 1.33251941e+03 1.30347131e+03 1.27683984e+03 1.25372266e+03 1.22819922e+03 1.19901453e+03 1.17729297e+03 1.15198401e+03 1.11989111e+03 1.10159863e+03 1.08216870e+03 1.05644775e+03 1.03504199e+03 1.00762482e+03 9.85287842e+02 9.64999634e+02 9.38670044e+02 9.15062561e+02 8.93568298e+02 8.75541992e+02 8.50357910e+02 8.26114624e+02 8.05878784e+02 7.84205566e+02 7.62383972e+02 7.43763367e+02 7.25762634e+02 7.01836975e+02 6.82307922e+02 6.63140869e+02 6.40460510e+02 6.21788574e+02 6.04213318e+02 5.86171509e+02 5.68619629e+02 5.49713501e+02 5.28901672e+02 5.12078857e+02 4.95951935e+02 4.76464813e+02 4.61080475e+02 4.45956207e+02 4.28102966e+02 4.10842316e+02 3.95892487e+02 3.80434723e+02 3.65240326e+02 3.51111481e+02 3.35927582e+02 3.21785248e+02 3.08297791e+02 2.94359314e+02 2.81068970e+02 2.68361420e+02 2.55018219e+02 2.42747742e+02 2.30710114e+02 2.18630920e+02 2.07478851e+02 1.96617966e+02 1.85853165e+02 1.75355240e+02 1.65326080e+02 1.55475372e+02 1.45716141e+02 1.36758499e+02 1.28036301e+02 1.19688255e+02 1.11602310e+02 1.03790230e+02 9.63499985e+01 8.93181305e+01 8.26002197e+01 7.61104126e+01 7.00031815e+01 6.43443832e+01 5.89824333e+01 5.39845314e+01 4.92783852e+01 4.49460449e+01 4.09755096e+01 3.73674736e+01 3.40779076e+01 3.11332893e+01 2.85880566e+01 2.63759212e+01 2.45031033e+01 2.29870548e+01 2.18130779e+01 2.09864330e+01 2.05270386e+01 2.04176636e+01 2.06671143e+01 2.12635403e+01 2.22263584e+01 2.35463467e+01 2.52123337e+01 2.72267494e+01 2.95780163e+01 3.22584572e+01 3.53550224e+01 3.87420197e+01 4.24921379e+01 4.66287270e+01 5.10802612e+01 5.58181229e+01 6.09390984e+01 6.65205917e+01 7.23142700e+01 7.83918152e+01 8.49729919e+01 9.19505768e+01 9.91408615e+01 1.06683891e+02 1.14618164e+02 1.22758278e+02 1.31207062e+02 1.40250427e+02 1.49698608e+02 1.59261139e+02 1.69052460e+02 1.79357330e+02 1.89813171e+02 2.00332184e+02 2.11824677e+02 2.23419006e+02 2.35256546e+02 2.47550674e+02 2.60103088e+02 2.73007812e+02 2.86024933e+02 2.99318634e+02 3.12814636e+02 3.27042816e+02 3.41854614e+02 3.56198242e+02 3.70840729e+02 3.87240814e+02 4.02302338e+02 4.16120911e+02 4.33319519e+02 4.50974823e+02 4.67950226e+02 4.84504608e+02 5.00498199e+02 5.18254639e+02 5.36708557e+02 5.57320312e+02 5.74639221e+02 5.90947144e+02 6.10288330e+02 6.30744568e+02 6.51262634e+02 6.69968079e+02 6.89872925e+02 7.08224792e+02 7.29296143e+02 7.54489136e+02 7.73370605e+02 7.90684692e+02 8.12444580e+02 8.36878418e+02 8.60553162e+02 8.79604736e+02 8.97335388e+02 9.23537659e+02 9.52623291e+02 9.73655334e+02 9.92206055e+02 1.02091980e+03 1.04363037e+03 1.06200110e+03 1.08913440e+03 1.11607959e+03 1.13743665e+03 1.15639941e+03 1.18959045e+03 1.21606384e+03 1.23066431e+03 1.25880444e+03 1.28869275e+03 1.31803491e+03 1.34299719e+03 1.36070410e+03 1.38868469e+03 1.42244104e+03 1.44600659e+03 1.46999463e+03 1.49664087e+03 1.52129907e+03 1.54599292e+03 1.58127295e+03 1.60634106e+03 1.63047852e+03 1.65902734e+03 1.68995129e+03 1.71720300e+03 1.74324536e+03 1.77378284e+03 1.78963416e+03 1.82844934e+03 1.86385266e+03 1.88086841e+03 1.90369495e+03 1.92864502e+03 1.96377368e+03 1.99650342e+03 2.02396619e+03 2.05893579e+03 2.07822705e+03 2.10881738e+03 2.13200635e+03 2.15525610e+03 2.20327905e+03 2.22569971e+03 2.24565161e+03 2.29318433e+03 2.30562183e+03 2.32862988e+03 2.36653979e+03 2.39266602e+03 2.42241870e+03 2.44722852e+03 2.48259717e+03 2.50545459e+03 2.53460010e+03 2.56829443e+03 2.59110938e+03 2.63134375e+03 2.66145996e+03 2.67579736e+03 2.70751270e+03 2.74147925e+03 2.76238452e+03 2.78629541e+03 2.82926758e+03 2.85041089e+03 2.86116528e+03 2.91798511e+03 2.93858350e+03 2.95543726e+03 2.99640723e+03 3.02154199e+03 3.05219214e+03 3.06830225e+03 3.08574927e+03 3.12600244e+03 3.15727344e+03 3.18709375e+03 3.21673584e+03 3.22917993e+03 3.26469775e+03 3.29301685e+03 3.30217773e+03 3.33396143e+03 3.36834204e+03 3.39799023e+03 3.42462720e+03 3.44569897e+03 3.46715625e+03 3.49084106e+03 3.51844409e+03 3.54515356e+03 3.56987427e+03 3.57241602e+03 3.61261108e+03 3.64967725e+03 3.66410962e+03 3.70021045e+03 3.71263477e+03 3.72900391e+03 3.76663745e+03 3.77906763e+03 3.79940479e+03 3.82816602e+03 3.85779492e+03 3.87204565e+03 3.89064624e+03 3.91118750e+03 3.93037915e+03 3.94863184e+03 3.97989746e+03 4.01451318e+03 4.01381152e+03 4.04174463e+03 4.06842456e+03 4.06761499e+03 4.08825269e+03 4.11629395e+03 4.14532910e+03 4.16817822e+03 4.17727002e+03 4.18142773e+03 4.20539453e+03 4.23373096e+03 4.23555859e+03 4.25499805e+03 4.29012842e+03 4.29803418e+03 4.29849219e+03 4.32676172e+03 4.33852832e+03 4.35182568e+03 4.38044287e+03 4.38474609e+03 4.39681934e+03 4.42168213e+03 4.42188721e+03 4.44092676e+03 4.46425537e+03 4.46154443e+03 4.47617432e+03 4.48844238e+03 4.49640088e+03 4.51760010e+03 4.53020166e+03 4.53822314e+03 4.54629932e+03 4.55878711e+03 4.56605420e+03 4.57178223e+03 4.58539160e+03 4.59274219e+03 4.60357812e+03 4.61204785e+03 4.61972412e+03 4.62537939e+03 4.63232178e+03 4.64244922e+03 4.64394482e+03 4.64919238e+03 4.65751953e+03 4.66449609e+03 4.67100830e+03 4.67394824e+03 4.67678369e+03 4.67977979e+03 4.68444580e+03 4.68782568e+03 4.68954883e+03 4.69340771e+03 4.69595508e+03 4.69744873e+03 4.70035400e+03 4.70057373e+03 4.70098926e+03 4.70194189e+03 4.70183838e+03 4.70170996e+03 4.70054150e+03 4.69975000e+03 4.69891455e+03 4.69647559e+03 4.69637695e+03 4.69260352e+03 4.68870410e+03 4.68717285e+03 4.68349121e+03 4.67985254e+03 4.67835107e+03 4.67367627e+03 4.66357178e+03 4.65804346e+03 4.65877002e+03 4.65109082e+03 4.64106689e+03 4.63534424e+03 4.63014404e+03 4.62565479e+03 4.61628906e+03 4.61067578e+03 4.59823926e+03 4.58536426e+03 4.58213232e+03 4.57716895e+03 4.56784131e+03 4.55307617e+03 4.54462891e+03 4.53303223e+03 4.51848486e+03 4.51144238e+03 4.49728613e+03 4.48387207e+03 4.47691309e+03 4.46589453e+03 4.45214551e+03 4.43647217e+03 4.42016846e+03 4.40656104e+03 4.39391357e+03 4.38697607e+03 4.36892871e+03 4.35049951e+03 4.34304004e+03 4.32023438e+03 4.29261230e+03 4.28806152e+03 4.27491992e+03 4.25681348e+03 4.23863428e+03 4.22057520e+03 4.20153955e+03 4.18279590e+03 4.18095215e+03 4.15305957e+03 4.12068359e+03 4.10781641e+03 4.09158472e+03 4.08138892e+03 4.05746729e+03 4.03131274e+03 4.00465796e+03 3.98854419e+03 3.98063403e+03 3.95551318e+03 3.92428857e+03 3.90043115e+03 3.88300635e+03 3.87391675e+03 3.83663232e+03 3.80004468e+03 3.79395850e+03 3.78740137e+03 3.75544458e+03 3.71714209e+03 3.71386035e+03 3.69332178e+03 3.65218140e+03 3.63359155e+03 3.61930835e+03 3.58196680e+03 3.54606738e+03 3.54210229e+03 3.52074438e+03 3.47688550e+03 3.45352490e+03 3.43638330e+03 3.41657715e+03 3.39277539e+03 3.34961548e+03 3.32616504e+03 3.31120337e+03 3.27844287e+03 3.25221362e+03 3.22459888e+03 3.19836206e+03 3.16451660e+03 3.13696753e+03 3.11893994e+03 3.09275977e+03 3.06500684e+03 3.03633740e+03 3.00686475e+03 2.98260620e+03 2.95793799e+03 2.91014844e+03 2.89700464e+03 2.88653931e+03 2.84048730e+03 2.80795581e+03 2.77309668e+03 2.75265308e+03 2.72626880e+03 2.70406543e+03 2.68329663e+03 2.63429590e+03 2.61231543e+03 2.58671729e+03 2.54561279e+03 2.54312646e+03 2.50040942e+03 2.46854541e+03 2.45289844e+03 2.41513257e+03 2.37887354e+03 2.35454395e+03 2.32321021e+03 2.30261572e+03 2.26084790e+03 2.24355664e+03 2.21061230e+03 2.18263892e+03 2.15545679e+03 2.11604614e+03 2.10790088e+03 2.07630273e+03 2.03784546e+03 2.01610559e+03 1.98486865e+03 1.95006592e+03 1.92579602e+03 1.90397437e+03 1.87001550e+03 1.83016089e+03 1.81873950e+03 1.78793286e+03 1.75478369e+03 1.73523657e+03 1.70405505e+03 1.68060144e+03 1.64792566e+03 1.61623535e+03 1.59530017e+03 1.56689319e+03 1.54110669e+03 1.51701196e+03 1.48627466e+03 1.46066321e+03 1.43296533e+03 1.40611975e+03 1.38040137e+03 1.35517432e+03 1.33083008e+03 1.30523059e+03 1.27857935e+03 1.25245300e+03 1.22757971e+03 1.20188782e+03 1.17850183e+03 1.15355518e+03 1.12320435e+03 1.10214478e+03 1.08203894e+03 1.05582263e+03 1.03497888e+03 1.00771027e+03 9.83675964e+02 9.63909973e+02 9.39347168e+02 9.15910156e+02 8.94824036e+02 8.73361206e+02 8.50682312e+02 8.26740234e+02 8.05798035e+02 7.84318604e+02 7.61839600e+02 7.43536560e+02 7.25724365e+02 7.00997009e+02 6.81799377e+02 6.63387817e+02 6.40702942e+02 6.20842712e+02 6.03503601e+02 5.86159302e+02 5.68450256e+02 5.49384766e+02 5.28990845e+02 5.11917389e+02 4.95667358e+02 4.76542877e+02 4.60567200e+02 4.45539856e+02 4.28277649e+02 4.10694427e+02 3.95976166e+02 3.80276520e+02 3.65183594e+02 3.51372406e+02 3.35796600e+02 3.21351288e+02 3.08416931e+02 2.93995117e+02 2.80814301e+02 2.68518341e+02 2.54912308e+02 2.42586838e+02 2.30613419e+02 2.18720520e+02 2.07441391e+02 1.96599411e+02 1.85689789e+02 1.75299789e+02 1.65343872e+02 1.55412201e+02 1.45730637e+02 1.36719528e+02 1.27972748e+02 1.19687569e+02 1.11555618e+02 1.03754089e+02 9.62916565e+01 8.92386703e+01 8.25593796e+01 7.60848160e+01 6.99992752e+01 6.43108749e+01 5.89399872e+01 5.39837151e+01 4.92642021e+01 4.49388809e+01 4.09624672e+01 3.73646355e+01 3.40788841e+01 3.11401463e+01 2.85838566e+01 2.63656139e+01 2.44866180e+01 2.29700336e+01 2.18038883e+01 2.09925842e+01 2.05321236e+01 2.04256229e+01 2.06789608e+01 2.12788143e+01 2.22358246e+01 2.35393009e+01 2.51931629e+01 2.72057266e+01 2.95556087e+01 3.22396507e+01 3.53104744e+01 3.87073021e+01 4.24504700e+01 4.65698624e+01 5.10312386e+01 5.57650986e+01 6.09309425e+01 6.64910202e+01 7.22813034e+01 7.84191971e+01 8.49820786e+01 9.19115372e+01 9.91583481e+01 1.06625053e+02 1.14496994e+02 1.22712463e+02 1.31165131e+02 1.40149689e+02 1.49606659e+02 1.59218338e+02 1.68980820e+02 1.79215622e+02 1.89690567e+02 2.00272018e+02 2.11788681e+02 2.23445068e+02 2.35111633e+02 2.47449860e+02 2.60045074e+02 2.73083496e+02 2.86175812e+02 2.99007019e+02 3.12643005e+02 3.27102905e+02 3.41955109e+02 3.56211578e+02 3.70618317e+02 3.86801331e+02 4.02067139e+02 4.16548676e+02 4.33632385e+02 4.51075378e+02 4.67893738e+02 4.84292755e+02 5.00904785e+02 5.18531738e+02 5.36714050e+02 5.57113159e+02 5.74572144e+02 5.90867249e+02 6.10884521e+02 6.30603333e+02 6.51386780e+02 6.70392151e+02 6.89470703e+02 7.08204590e+02 7.29168274e+02 7.52854004e+02 7.73139160e+02 7.91476990e+02 8.13182800e+02 8.36719482e+02 8.60540894e+02 8.79735046e+02 8.97887878e+02 9.24373352e+02 9.52503418e+02 9.73448792e+02 9.91520020e+02 1.02051294e+03 1.04451282e+03 1.06156140e+03 1.09137354e+03 1.11652319e+03 1.13767651e+03 1.15640710e+03 1.18880444e+03 1.21558960e+03 1.23197620e+03 1.26077490e+03 1.28984692e+03 1.31647620e+03 1.34238208e+03 1.36461719e+03 1.39106519e+03 1.42089575e+03 1.44577625e+03 1.47026831e+03 1.49503857e+03 1.52146204e+03 1.54932910e+03 1.57963135e+03 1.60524194e+03 1.63011328e+03 1.66180371e+03 1.69315942e+03 1.71411218e+03 1.74327747e+03 1.77247839e+03 1.78927039e+03 1.83070178e+03 1.86065527e+03 1.88195020e+03 1.90587170e+03 1.93137378e+03 1.96591479e+03 1.99594641e+03 2.02153467e+03 2.06003369e+03 2.07755957e+03 2.10687524e+03 2.13728296e+03 2.15610107e+03 2.20712231e+03 2.22423291e+03 2.24676831e+03 2.29138013e+03 2.30978174e+03 2.33257275e+03 2.36346338e+03 2.39399341e+03 2.42595898e+03 2.44606006e+03 2.48331006e+03 2.50778955e+03 2.54029248e+03 2.58502173e+03 2.63642627e+03 2.67579370e+03 2.66638330e+03 2.67087988e+03 2.70666919e+03 2.73401562e+03 2.75485083e+03 2.79119556e+03 2.82031299e+03 2.83929199e+03 2.87136890e+03 3.87529736e+03 4.39308887e+03 -1.01660125e+06 242900736. 0. 0. 0. 0. 108177760. 108177760. 108177760. 0. 0. 0. 308122944. 28710256. 1.08841516e+05 1.15344668e+04 8.14837158e+03 3.77578687e+03 3.73061206e+03 3.88530908e+03 3.88552734e+03 3.66276807e+03 3.56985718e+03 3.56970459e+03 3.57570312e+03 3.61617163e+03 3.64904590e+03 3.67053833e+03 3.70188281e+03 3.71167139e+03 3.73461328e+03 3.77001245e+03 3.80395337e+03 3.85323975e+03 3.85411304e+03 3.84757861e+03 3.86404688e+03 3.88537891e+03 3.91072925e+03 3.93300220e+03 3.94113599e+03 3.96063452e+03 4.00332031e+03 4.03495288e+03 4.04392407e+03 4.05707617e+03 4.06858228e+03 4.09198120e+03 4.12311230e+03 4.15152100e+03 4.16993750e+03 4.18204053e+03 4.18306592e+03 4.20424609e+03 4.23786279e+03 4.23776367e+03 4.26223242e+03 4.29194629e+03 4.29674121e+03 4.30291357e+03 4.32587988e+03 4.34184668e+03 4.35679785e+03 4.38118750e+03 4.38623193e+03 4.40050684e+03 4.42324512e+03 4.42184082e+03 4.44419580e+03 4.46677148e+03 4.46099072e+03 4.47798291e+03 4.49090967e+03 4.49660059e+03 4.51855908e+03 4.53123389e+03 4.53969287e+03 4.55001953e+03 4.56066748e+03 4.56831055e+03 4.57196533e+03 4.58514746e+03 4.59683350e+03 4.60885840e+03 4.61353613e+03 4.61689160e+03 4.62609082e+03 4.63659668e+03 4.64334814e+03 4.64468750e+03 4.65138135e+03 4.65916016e+03 4.66696191e+03 4.67341553e+03 4.67548047e+03 4.67874072e+03 4.68136572e+03 4.68728809e+03 4.69098047e+03 4.69194141e+03 4.69622803e+03 4.69910986e+03 4.70010693e+03 4.70252734e+03 4.70320508e+03 4.70408301e+03 1.41137246e+04 50754124. 1.87095723e+04 4.67734131e+03 4.67648486e+03 4.67592236e+03 4.67358887e+03 4.67283301e+03 4.67006934e+03 4.66607324e+03 4.66391992e+03 4.66038184e+03 4.65658301e+03 4.65465869e+03 4.64890918e+03 4.64264062e+03 4.63683008e+03 4.63262158e+03 4.62737207e+03 4.62068262e+03 4.61316309e+03 4.60716504e+03 4.60270459e+03 4.59268408e+03 4.58516113e+03 4.57661328e+03 4.56401562e+03 4.55778027e+03 4.55428418e+03 4.54423877e+03 4.52992920e+03 4.52129443e+03 4.51003467e+03 4.49765234e+03 4.48940186e+03 4.47705273e+03 4.46165283e+03 4.45083643e+03 4.43929199e+03 4.43501123e+03 4.41799854e+03 4.39484424e+03 4.38017041e+03 4.37375928e+03 4.36425781e+03 4.34445508e+03 4.33080127e+03 4.32006738e+03 4.30210449e+03 4.27130615e+03 4.26734424e+03 4.25806787e+03 4.23284375e+03 4.21817578e+03 4.19809570e+03 4.17475146e+03 4.16796143e+03 4.15394385e+03 4.13036572e+03 4.11045557e+03 4.08905811e+03 4.07295215e+03 4.05377368e+03 4.02247192e+03 4.01541211e+03 3.98804419e+03 3.96171631e+03 3.96203491e+03 3.93324683e+03 3.90450757e+03 3.88979736e+03 3.86567212e+03 3.84771777e+03 3.82339624e+03 3.79323584e+03 3.77403931e+03 3.76356152e+03 3.73359277e+03 3.69835449e+03 3.69210449e+03 3.66851221e+03 3.63369604e+03 3.61478320e+03 3.59783545e+03 3.56879077e+03 3.53282153e+03 4.61635303e+03 4.93767041e+03 5.24568164e+03 9.14215723e+03 1.21389814e+04 4.51960273e+04 -15671229. -268668768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -40962184. 3.50632930e+04 7.11278418e+03 4.36229297e+03 4.08003003e+03 3.79750098e+03 2.85258472e+03 2.82749072e+03 2.79211621e+03 2.76405518e+03 2.73173633e+03 2.71372144e+03 2.69193677e+03 2.65793994e+03 2.61851709e+03 2.59696045e+03 2.56811890e+03 2.53346606e+03 2.51581299e+03 2.48623120e+03 2.45139648e+03 2.43015112e+03 2.39789771e+03 2.36837793e+03 2.34147754e+03 2.30976562e+03 2.28244873e+03 2.25368359e+03 2.22410498e+03 2.18946558e+03 2.17162036e+03 2.14453540e+03 2.10408936e+03 2.08532227e+03 2.06036816e+03 2.02468567e+03 2.00370142e+03 1.96979834e+03 1.94230225e+03 1.91510547e+03 1.88588708e+03 1.85138293e+03 1.82174109e+03 1.80318994e+03 1.77014307e+03 1.74309460e+03 1.71898816e+03 1.69196704e+03 1.66398816e+03 1.63363354e+03 1.60266785e+03 1.58004663e+03 1.54931824e+03 1.52406177e+03 1.50444055e+03 1.47513599e+03 1.44763831e+03 1.41671460e+03 1.39148694e+03 1.36913965e+03 1.34355200e+03 1.31412842e+03 1.28870032e+03 1.26678748e+03 1.23794958e+03 1.21405627e+03 1.19019910e+03 1.16585461e+03 1.13672278e+03 1.10958423e+03 1.08990173e+03 1.06847998e+03 1.04361646e+03 1.01976385e+03 9.95635010e+02 9.71908325e+02 9.50212952e+02 9.26682617e+02 9.02512207e+02 8.80341003e+02 8.60773560e+02 8.37100586e+02 8.13563232e+02 7.93655273e+02 7.71833435e+02 7.49925903e+02 7.30012878e+02 7.11682922e+02 6.89137390e+02 6.68763733e+02 6.49579529e+02 6.28901062e+02 6.09908508e+02 5.90723328e+02 5.71672241e+02 5.55016235e+02 5.35949463e+02 5.15952148e+02 4.99830597e+02 4.83003601e+02 4.64502350e+02 4.47079102e+02 4.32560608e+02 4.15046753e+02 3.98055023e+02 3.83573120e+02 3.67785461e+02 3.52379486e+02 3.37870331e+02 3.23258636e+02 3.09021637e+02 2.94852936e+02 2.81117798e+02 2.67914581e+02 2.55325562e+02 2.42290375e+02 2.29573654e+02 2.17671600e+02 2.05815079e+02 1.94557480e+02 1.83509277e+02 1.72591644e+02 1.62275070e+02 1.52093597e+02 1.42231506e+02 1.32705734e+02 1.23648819e+02 1.14860031e+02 1.06431808e+02 9.83046570e+01 9.04818420e+01 8.30356598e+01 7.59490204e+01 6.91944580e+01 6.27011375e+01 5.65789604e+01 5.08876076e+01 4.55043449e+01 4.04580498e+01 3.57335434e+01 3.13648682e+01 2.73467522e+01 2.36995792e+01 2.03792648e+01 1.74078026e+01 1.48052282e+01 1.25414162e+01 1.06272869e+01 9.06866837e+00 7.85577869e+00 6.99429274e+00 6.48750210e+00 6.33130550e+00 6.52723742e+00 7.07310963e+00 7.97291470e+00 9.22538185e+00 1.08255901e+01 1.27825222e+01 1.50868425e+01 1.77325134e+01 2.07428341e+01 2.40882092e+01 2.77844582e+01 3.18584404e+01 3.62618065e+01 4.09895515e+01 4.60702629e+01 5.15342560e+01 5.72846375e+01 6.33752365e+01 6.98465500e+01 7.67314987e+01 8.38521805e+01 9.12927780e+01 9.91771469e+01 1.07316666e+02 1.15736900e+02 1.24615265e+02 1.33899918e+02 1.43432053e+02 1.53191864e+02 1.63404816e+02 1.73900406e+02 1.84594849e+02 1.95804886e+02 2.07258804e+02 2.18980011e+02 2.31090515e+02 2.43583801e+02 2.56742279e+02 2.69431763e+02 2.82581879e+02 2.95899658e+02 3.10340179e+02 3.25045044e+02 3.39167236e+02 3.54392365e+02 3.70135834e+02 3.84802917e+02 3.99323212e+02 4.16471802e+02 4.33485352e+02 4.49773773e+02 4.67112030e+02 4.83560028e+02 5.00830780e+02 5.19584534e+02 5.38270935e+02 5.56475159e+02 5.74600220e+02 5.92050598e+02 6.12324463e+02 6.31799805e+02 6.49370544e+02 6.71412292e+02 6.90926086e+02 7.09753845e+02 7.34215637e+02 7.54308044e+02 7.72903076e+02 7.96082214e+02 8.17541565e+02 8.39463623e+02 8.62010010e+02 8.80923157e+02 9.03572388e+02 9.31311218e+02 9.52592590e+02 9.71749756e+02 1.00075751e+03 1.02291986e+03 1.04448181e+03 1.06856335e+03 1.09397205e+03 1.11809998e+03 1.13914856e+03 1.16749475e+03 1.19481702e+03 1.21527661e+03 1.23828076e+03 1.26756323e+03 1.29617419e+03 1.31781641e+03 1.34080615e+03 1.37037561e+03 1.39824402e+03 1.42339575e+03 1.44985156e+03 1.47516553e+03 1.50193384e+03 1.53045190e+03 1.55525378e+03 1.58208228e+03 1.61194556e+03 1.63633215e+03 1.66516052e+03 1.69592004e+03 1.72230469e+03 1.74638733e+03 1.76969690e+03 1.80702759e+03 1.83310425e+03 1.85785144e+03 1.88497046e+03 1.90934607e+03 1.93965381e+03 1.97218665e+03 2.00297668e+03 2.03217188e+03 2.05146777e+03 2.08072046e+03 2.11355981e+03 2.13777563e+03 2.17205322e+03 2.20289795e+03 2.22740869e+03 2.26064062e+03 2.28557959e+03 2.31453149e+03 2.34198999e+03 2.37006982e+03 2.40131177e+03 2.42389209e+03 2.45881641e+03 2.48442407e+03 2.51384180e+03 2.54495654e+03 2.56844482e+03 2.60539478e+03 2.62507812e+03 2.65323413e+03 2.68902002e+03 2.71480591e+03 2.74517627e+03 2.77240259e+03 2.80418628e+03 2.81807764e+03 2.83888721e+03 2.88640601e+03 2.90173999e+03 2.93008179e+03 2.97459375e+03 2.99409424e+03 3.02250171e+03 3.03859595e+03 3.06246240e+03 3.10614746e+03 3.13124927e+03 3.15136499e+03 3.19572363e+03 3.21149121e+03 3.23365698e+03 3.25791821e+03 3.28197339e+03 3.31950684e+03 3.34332739e+03 3.35945190e+03 3.39507666e+03 3.42427515e+03 3.43615771e+03 3.46261279e+03 3.50047534e+03 3.51877808e+03 3.53734668e+03 3.55481909e+03 3.59051904e+03 3.62166943e+03 3.64221851e+03 3.66586694e+03 3.68407983e+03 3.70281079e+03 3.73747070e+03 3.75290039e+03 3.77320215e+03 3.80236426e+03 3.82666089e+03 3.84739746e+03 3.86564893e+03 3.88538770e+03 3.90739941e+03 3.92603760e+03 3.94975146e+03 3.98324683e+03 3.99366797e+03 4.01205054e+03 4.03480420e+03 4.04901660e+03 4.07038550e+03 4.09103076e+03 4.10458838e+03 4.13340186e+03 4.14915820e+03 4.15658203e+03 4.18501172e+03 4.20652197e+03 4.21142725e+03 4.22661279e+03 4.26015576e+03 4.26817383e+03 4.27300049e+03 4.30482031e+03 4.31604346e+03 4.32524658e+03 4.34668750e+03 4.36016455e+03 4.37330859e+03 4.38758984e+03 4.39374414e+03 4.41430762e+03 4.43652881e+03 4.43975146e+03 4.44642334e+03 4.45911572e+03 4.47374268e+03 4.48946191e+03 4.50124512e+03 4.50875146e+03 4.52206201e+03 4.53074902e+03 4.53829736e+03 4.54745947e+03 4.55808105e+03 4.56539941e+03 4.57574902e+03 4.58527441e+03 4.59270801e+03 4.59993701e+03 4.60619141e+03 4.61440137e+03 4.61700098e+03 4.62292236e+03 4.63042432e+03 4.63798389e+03 4.64449658e+03 4.64755420e+03 4.65020996e+03 4.65238184e+03 4.65790479e+03 4.66171143e+03 4.66299414e+03 4.66724561e+03 4.66946436e+03 4.67097461e+03 4.67406885e+03 4.67433203e+03 4.67466943e+03 4.67570508e+03 4.67570996e+03 4.67566113e+03 4.67452686e+03 4.67371094e+03 4.67309766e+03 4.67060205e+03 4.66991162e+03 4.66728516e+03 4.66362012e+03 4.66163672e+03 4.65830615e+03 4.65368506e+03 4.65161719e+03 4.64711426e+03 4.64011475e+03 4.63501172e+03 4.63154883e+03 4.62523438e+03 4.61841113e+03 4.61094922e+03 4.60496387e+03 4.60098438e+03 4.59040039e+03 4.58389014e+03 4.57496338e+03 4.56283252e+03 4.55646045e+03 4.55311084e+03 4.54202295e+03 4.52767578e+03 4.51880811e+03 4.50828662e+03 4.49896680e+03 4.48761084e+03 4.47418506e+03 4.46183203e+03 4.45096826e+03 4.43756006e+03 4.43191797e+03 4.41654688e+03 4.39434912e+03 4.37876709e+03 4.37397852e+03 4.36224219e+03 4.34288379e+03 4.32739258e+03 4.32001562e+03 4.29707764e+03 4.26844092e+03 4.26546924e+03 4.25322363e+03 4.23106396e+03 4.21412012e+03 4.19905029e+03 4.17617871e+03 4.16554688e+03 4.15226562e+03 4.12814062e+03 4.10602002e+03 4.08461865e+03 4.07388159e+03 4.05628442e+03 4.02559058e+03 4.01333203e+03 3.98800537e+03 3.96543457e+03 3.95646777e+03 3.93107275e+03 3.90564136e+03 3.89012671e+03 3.86068555e+03 3.84474292e+03 3.81700073e+03 3.79070630e+03 3.77671729e+03 3.76533032e+03 3.73125684e+03 3.69605688e+03 3.68994312e+03 3.67134204e+03 3.63634473e+03 3.61095557e+03 3.59291504e+03 3.56326831e+03 3.52911450e+03 3.51655347e+03 3.49719263e+03 3.46678516e+03 3.43253394e+03 3.41657300e+03 3.39916309e+03 3.36202783e+03 3.33357690e+03 3.31454297e+03 3.28826733e+03 3.25774268e+03 3.23901685e+03 3.20251489e+03 3.17740869e+03 3.15593433e+03 3.11964648e+03 3.10139258e+03 3.08113452e+03 3.04172949e+03 3.01994482e+03 2.99477539e+03 2.96508325e+03 2.93246484e+03 2.89478052e+03 2.87987354e+03 2.85873169e+03 2.83072656e+03 2.79218848e+03 2.76070312e+03 2.73008276e+03 2.70347095e+03 2.69334766e+03 2.66212329e+03 2.61613965e+03 2.59738354e+03 2.57020703e+03 2.53727271e+03 2.51240698e+03 2.47862744e+03 2.45390161e+03 2.42625415e+03 2.39628418e+03 2.36100879e+03 2.33968311e+03 2.31219751e+03 2.28682031e+03 2.24883569e+03 2.22193213e+03 2.19227710e+03 2.17125781e+03 2.14385107e+03 2.10637549e+03 2.08657422e+03 2.05506714e+03 2.02050769e+03 2.00513708e+03 1.96548633e+03 1.93901978e+03 1.91727258e+03 1.88616626e+03 1.85132056e+03 1.82475952e+03 1.80266589e+03 1.77079150e+03 1.73833936e+03 1.72044104e+03 1.69069714e+03 1.66591089e+03 1.63325037e+03 1.60122595e+03 1.58274744e+03 1.55167261e+03 1.52442432e+03 1.50345093e+03 1.47507874e+03 1.44468408e+03 1.41704260e+03 1.39238025e+03 1.36961060e+03 1.34202234e+03 1.31483801e+03 1.28997253e+03 1.26579529e+03 1.23710632e+03 1.21330701e+03 1.19109827e+03 1.16551575e+03 1.13678381e+03 1.11087866e+03 1.08921094e+03 1.06840027e+03 1.04341040e+03 1.01943610e+03 9.94529358e+02 9.71108765e+02 9.50194519e+02 9.26295288e+02 9.02686096e+02 8.81116211e+02 8.59005066e+02 8.37441040e+02 8.13996521e+02 7.93003479e+02 7.71401184e+02 7.49847107e+02 7.29638733e+02 7.11369080e+02 6.88592468e+02 6.68219360e+02 6.49340759e+02 6.29153259e+02 6.09569397e+02 5.90757812e+02 5.71399963e+02 5.54393799e+02 5.35886169e+02 5.16233948e+02 4.99577728e+02 4.82383423e+02 4.64196075e+02 4.47447021e+02 4.32340820e+02 4.15058624e+02 3.98132141e+02 3.83573456e+02 3.67787933e+02 3.52272034e+02 3.37854492e+02 3.23094177e+02 3.08776764e+02 2.95005310e+02 2.80902618e+02 2.67783600e+02 2.55575943e+02 2.42301651e+02 2.29413589e+02 2.17521530e+02 2.05882263e+02 1.94478897e+02 1.83504776e+02 1.72589798e+02 1.62293182e+02 1.52144806e+02 1.42195724e+02 1.32669678e+02 1.23597733e+02 1.14818542e+02 1.06420044e+02 9.82866364e+01 9.04821625e+01 8.29973068e+01 7.59136734e+01 6.91720886e+01 6.26842613e+01 5.65748672e+01 5.08570137e+01 4.54628868e+01 4.04409447e+01 3.57244263e+01 3.13512383e+01 2.73229370e+01 2.36709003e+01 2.03596992e+01 1.73888912e+01 1.47816296e+01 1.25171719e+01 1.06034994e+01 9.04633236e+00 7.83743525e+00 6.97867537e+00 6.47217464e+00 6.31570625e+00 6.51333141e+00 7.06065845e+00 7.96271706e+00 9.21632862e+00 1.08166695e+01 1.27736721e+01 1.50785837e+01 1.77281208e+01 2.07321110e+01 2.40807076e+01 2.77784271e+01 3.18457966e+01 3.62451935e+01 4.09647217e+01 4.60603561e+01 5.15188675e+01 5.72819214e+01 6.34078522e+01 6.98567581e+01 7.66761627e+01 8.38666992e+01 9.12943573e+01 9.91250916e+01 1.07321602e+02 1.15729973e+02 1.24603592e+02 1.33978333e+02 1.43420273e+02 1.53194763e+02 1.63354935e+02 1.73855484e+02 1.84606949e+02 1.95825821e+02 2.07370590e+02 2.18901382e+02 2.31015396e+02 2.43569016e+02 2.56872986e+02 2.69675751e+02 2.82431213e+02 2.95827179e+02 3.10587860e+02 3.25326263e+02 3.39177551e+02 3.54162354e+02 3.69939728e+02 3.84769257e+02 3.99241364e+02 4.16565002e+02 4.33687225e+02 4.49644287e+02 4.66870392e+02 4.83895386e+02 5.01080933e+02 5.19682800e+02 5.38453308e+02 5.56397461e+02 5.74087402e+02 5.92622070e+02 6.12198486e+02 6.31851562e+02 6.50323303e+02 6.71477600e+02 6.90834900e+02 7.09640381e+02 7.33716370e+02 7.54090027e+02 7.73151306e+02 7.96492676e+02 8.17472046e+02 8.39806702e+02 8.61632751e+02 8.81874451e+02 9.04785583e+02 9.31196411e+02 9.51981140e+02 9.71739380e+02 1.00079156e+03 1.02382635e+03 1.04512122e+03 1.06831433e+03 1.09467554e+03 1.11835474e+03 1.14015466e+03 1.16834485e+03 1.19317712e+03 1.21707544e+03 1.23996289e+03 1.26840918e+03 1.29508142e+03 1.31686963e+03 1.34204834e+03 1.37030212e+03 1.39763745e+03 1.42427649e+03 1.45114648e+03 1.47229224e+03 1.50092444e+03 1.53121973e+03 1.55209216e+03 1.58204749e+03 1.61235730e+03 1.63664783e+03 1.66504126e+03 1.69675024e+03 1.72107141e+03 1.74453357e+03 1.77233557e+03 1.80545276e+03 1.83317554e+03 1.85911072e+03 1.88427087e+03 1.90992737e+03 1.94197437e+03 1.96931323e+03 2.00427209e+03 2.03190063e+03 2.05425659e+03 2.08688037e+03 2.11169189e+03 2.13731641e+03 2.17746045e+03 2.20430420e+03 2.22649658e+03 2.25722021e+03 2.28857715e+03 2.31555225e+03 2.34391772e+03 2.36782617e+03 2.40162793e+03 2.42812256e+03 2.46174463e+03 2.48416016e+03 2.51535303e+03 2.55051416e+03 2.57445020e+03 2.60616309e+03 2.63043262e+03 2.65259741e+03 2.68821777e+03 2.70828760e+03 2.73521826e+03 2.76511572e+03 2.79232544e+03 2.81521948e+03 2.84618481e+03 3.73798120e+03 3.94395166e+03 6.95786230e+03 8.98147461e+03 -310405280. -40194164. 0. 0. 108177760. 108177760. 108177760. 0. 0. 0. 308122944. 28710256. 1.08841516e+05 1.15765820e+04 9.50111523e+03 5.59864160e+03 5.20467822e+03 3.59751538e+03 3.52509790e+03 3.55098730e+03 3.56020190e+03 3.55935034e+03 3.56035986e+03 3.58936279e+03 3.62040747e+03 3.64125220e+03 3.66857666e+03 3.68192090e+03 3.71283325e+03 3.74134717e+03 3.76051123e+03 3.79355542e+03 3.80285327e+03 3.81893530e+03 3.83942383e+03 3.86125635e+03 3.88502759e+03 3.90515991e+03 3.92274316e+03 3.94100537e+03 3.97647314e+03 3.99540625e+03 4.00758521e+03 4.03153979e+03 4.04776050e+03 4.06617090e+03 4.09368823e+03 4.12414453e+03 4.14461426e+03 4.14984326e+03 4.15853906e+03 4.18744775e+03 4.21098975e+03 4.21333887e+03 4.22858203e+03 4.26196045e+03 4.27237109e+03 4.27383301e+03 4.30256104e+03 4.31712891e+03 4.32946680e+03 4.34849609e+03 4.36056055e+03 4.37224365e+03 4.38929883e+03 4.39541162e+03 4.41745117e+03 4.44047949e+03 4.44048340e+03 4.44897900e+03 4.46140137e+03 4.47389160e+03 4.49321729e+03 4.50234619e+03 4.50869482e+03 4.52430811e+03 4.53268164e+03 4.54077002e+03 4.54958057e+03 4.55907910e+03 4.56857031e+03 4.57974316e+03 4.58644287e+03 4.59152881e+03 4.60041992e+03 4.60913770e+03 4.61575928e+03 4.61862305e+03 4.62521191e+03 4.63284814e+03 4.64024951e+03 4.64645850e+03 4.64931348e+03 4.65233252e+03 4.65548291e+03 4.66091699e+03 4.66375586e+03 4.66528125e+03 4.66973389e+03 4.67251172e+03 4.67390186e+03 4.67695264e+03 4.67777393e+03 4.67691406e+03 1.40250420e+04 44618304. 1.84033906e+04 4.60094678e+03 4.60027979e+03 4.60070898e+03 4.59835791e+03 4.59648730e+03 4.59424414e+03 4.59193604e+03 4.59021973e+03 4.58655518e+03 4.58194580e+03 4.57943994e+03 4.57486230e+03 4.56866357e+03 4.56560840e+03 4.55953809e+03 4.55433301e+03 4.55006104e+03 4.53912305e+03 4.53305273e+03 4.52993018e+03 4.51911328e+03 4.51486035e+03 4.50676416e+03 4.48982275e+03 4.48702930e+03 4.48626904e+03 4.47031689e+03 4.45575781e+03 4.44897949e+03 4.44431299e+03 4.43263428e+03 4.41878174e+03 4.40272949e+03 4.39128906e+03 4.38390234e+03 4.37204541e+03 4.36446826e+03 4.34753613e+03 4.32896631e+03 4.31685596e+03 4.30415332e+03 4.29086182e+03 4.28167041e+03 4.26355371e+03 4.24684131e+03 4.23837012e+03 4.21072070e+03 4.19595703e+03 4.19187793e+03 4.17200293e+03 4.15731055e+03 4.13338525e+03 4.11168848e+03 4.10474072e+03 4.08947119e+03 4.06936646e+03 4.04833423e+03 4.02460034e+03 4.01523169e+03 3.99465479e+03 3.95989722e+03 3.94770630e+03 3.93408472e+03 3.90550171e+03 3.89324756e+03 3.87579590e+03 3.85053857e+03 3.82726465e+03 3.81196021e+03 3.79104468e+03 3.77122119e+03 3.74194531e+03 3.71829736e+03 3.70309717e+03 3.67468140e+03 3.65738989e+03 3.63161743e+03 3.61154321e+03 3.58438159e+03 3.55468262e+03 3.54320337e+03 4.60473633e+03 4.80083643e+03 8.55912402e+03 5.62789648e+03 1.03981953e+04 3.96540312e+04 224527136. -268668768. -268668768. 13400340. -1510269440. -1510269440. 0. 0. 0. 0. 0. 0. 157643936. -64257964. 1.88190469e+04 8.64791895e+03 7.06675977e+03 3.84121704e+03 2.89262207e+03 2.86817041e+03 2.83955151e+03 2.81532983e+03 2.78648315e+03 2.75597290e+03 2.74461499e+03 2.70249023e+03 2.66524731e+03 2.65308472e+03 2.62037720e+03 2.58903125e+03 2.56621460e+03 2.53386353e+03 2.50039087e+03 2.47722144e+03 2.44853638e+03 2.41793042e+03 2.38999585e+03 2.36259619e+03 2.33974146e+03 2.30643433e+03 2.27867993e+03 2.25582739e+03 2.22025098e+03 2.19445483e+03 2.17259717e+03 2.13842871e+03 2.11101001e+03 2.08484692e+03 2.05641016e+03 2.02915881e+03 2.00236047e+03 1.97264917e+03 1.93784692e+03 1.91613782e+03 1.89227026e+03 1.85843591e+03 1.82735095e+03 1.80413196e+03 1.78191785e+03 1.74622729e+03 1.72122217e+03 1.69512390e+03 1.67239832e+03 1.64041553e+03 1.60901184e+03 1.58490295e+03 1.56334875e+03 1.53167749e+03 1.50216272e+03 1.48199463e+03 1.45930835e+03 1.42837756e+03 1.39949988e+03 1.37570435e+03 1.35260925e+03 1.32522571e+03 1.29709680e+03 1.27275269e+03 1.24958789e+03 1.22170044e+03 1.19866931e+03 1.17872144e+03 1.15034827e+03 1.12393140e+03 1.10013013e+03 1.07817834e+03 1.05509253e+03 1.03211462e+03 1.00595459e+03 9.82915283e+02 9.61948853e+02 9.38263184e+02 9.17269775e+02 8.93742859e+02 8.67739990e+02 8.49422668e+02 8.28828186e+02 8.03739380e+02 7.83636780e+02 7.64898499e+02 7.42246887e+02 7.20549622e+02 7.02423035e+02 6.81854736e+02 6.61115479e+02 6.42065735e+02 6.22623291e+02 6.03656738e+02 5.84861267e+02 5.65144409e+02 5.48581726e+02 5.29949463e+02 5.10419098e+02 4.94548370e+02 4.77973846e+02 4.59491760e+02 4.42262665e+02 4.27268982e+02 4.10541565e+02 3.94269348e+02 3.79533264e+02 3.64045624e+02 3.48469147e+02 3.34217743e+02 3.20112213e+02 3.06216797e+02 2.91866364e+02 2.77735413e+02 2.64989258e+02 2.52810776e+02 2.39831497e+02 2.27242111e+02 2.15291595e+02 2.03667145e+02 1.92642487e+02 1.81584839e+02 1.70728195e+02 1.60610184e+02 1.50445877e+02 1.40548935e+02 1.31213562e+02 1.22206360e+02 1.13527832e+02 1.05164085e+02 9.69784546e+01 8.92579193e+01 8.18669510e+01 7.47393112e+01 6.80214767e+01 6.15424881e+01 5.54312782e+01 4.97848892e+01 4.44122581e+01 3.93498230e+01 3.46255875e+01 3.02443733e+01 2.62009621e+01 2.25240078e+01 1.91845055e+01 1.61803627e+01 1.35302486e+01 1.12192583e+01 9.25181961e+00 7.63345432e+00 6.35790014e+00 5.42858696e+00 4.84658766e+00 4.61013508e+00 4.71892023e+00 5.17314005e+00 5.97324133e+00 7.12211704e+00 8.61226749e+00 1.04552889e+01 1.26377287e+01 1.51622410e+01 1.80455704e+01 2.12561131e+01 2.48031502e+01 2.87255383e+01 3.29839554e+01 3.75509415e+01 4.25029030e+01 4.77787170e+01 5.33750191e+01 5.93108826e+01 6.55498734e+01 7.22499237e+01 7.91725540e+01 8.63752670e+01 9.41606216e+01 1.02117889e+02 1.10218605e+02 1.18932518e+02 1.28035538e+02 1.37191513e+02 1.46694092e+02 1.56766922e+02 1.67172501e+02 1.77678345e+02 1.88471970e+02 1.99447845e+02 2.10880844e+02 2.22997055e+02 2.35356293e+02 2.47985062e+02 2.60452057e+02 2.73481079e+02 2.86342651e+02 3.00548889e+02 3.15014618e+02 3.28922455e+02 3.43398743e+02 3.58474487e+02 3.73697327e+02 3.87832062e+02 4.04287628e+02 4.20926605e+02 4.37169495e+02 4.54293793e+02 4.70224640e+02 4.87464691e+02 5.05553284e+02 5.23379517e+02 5.41754028e+02 5.59589294e+02 5.76751038e+02 5.96219971e+02 6.15423889e+02 6.33518433e+02 6.54106812e+02 6.74863708e+02 6.92840454e+02 7.14022705e+02 7.35498474e+02 7.55625916e+02 7.76583923e+02 7.98860474e+02 8.19548584e+02 8.42058899e+02 8.61303406e+02 8.82710571e+02 9.08308228e+02 9.27850159e+02 9.51938232e+02 9.75807190e+02 9.97234741e+02 1.02309186e+03 1.04427002e+03 1.06797119e+03 1.09112427e+03 1.11651599e+03 1.14169897e+03 1.16691943e+03 1.19092200e+03 1.21343970e+03 1.23998096e+03 1.26729993e+03 1.28900427e+03 1.31335132e+03 1.33982251e+03 1.36384485e+03 1.39267615e+03 1.42026477e+03 1.44256995e+03 1.47045349e+03 1.49843665e+03 1.52163525e+03 1.55178491e+03 1.58110046e+03 1.60351392e+03 1.63138879e+03 1.65362427e+03 1.68267517e+03 1.71139368e+03 1.74159937e+03 1.77153723e+03 1.79192334e+03 1.82165247e+03 1.84852930e+03 1.87762354e+03 1.90279639e+03 1.92889294e+03 1.96354529e+03 1.98742322e+03 2.01525659e+03 2.04445435e+03 2.06904956e+03 2.09654956e+03 2.13004834e+03 2.15608984e+03 2.18036255e+03 2.20827222e+03 2.24192114e+03 2.27754834e+03 2.30183960e+03 2.32320093e+03 2.35211548e+03 2.38129565e+03 2.41412646e+03 2.43992261e+03 2.45810229e+03 2.49129980e+03 2.52809766e+03 2.55052393e+03 2.57839526e+03 2.61588647e+03 2.63529956e+03 2.65587964e+03 2.68978052e+03 2.72101733e+03 2.74227539e+03 2.76820166e+03 2.80181226e+03 2.83828564e+03 2.85278052e+03 2.88442139e+03 2.91356201e+03 2.94328784e+03 2.96270557e+03 2.98142383e+03 3.01519653e+03 3.05457690e+03 3.07681616e+03 3.09222070e+03 3.13186841e+03 3.15867944e+03 3.17125757e+03 3.19485107e+03 3.22605371e+03 3.25917944e+03 3.28086157e+03 3.30240625e+03 3.32624023e+03 3.35742212e+03 3.37506421e+03 3.40727026e+03 3.44119580e+03 3.45719897e+03 3.46798022e+03 3.49785913e+03 3.52705127e+03 3.55563794e+03 3.58335986e+03 3.59353516e+03 3.62075586e+03 3.64476855e+03 3.66892261e+03 3.69667529e+03 3.71207910e+03 3.72299731e+03 3.75367480e+03 3.78361426e+03 3.79410034e+03 3.81420386e+03 3.84886206e+03 3.86541528e+03 3.87767603e+03 3.90725024e+03 3.92489966e+03 3.94029004e+03 3.96567651e+03 3.98312695e+03 4.00294556e+03 4.01812012e+03 4.03456299e+03 4.06096753e+03 4.07587329e+03 4.08702344e+03 4.11522607e+03 4.13519678e+03 4.14021094e+03 4.15269336e+03 4.18519434e+03 4.19582275e+03 4.20224268e+03 4.22992920e+03 4.24091797e+03 4.24930029e+03 4.27285059e+03 4.28803613e+03 4.30443701e+03 4.31323779e+03 4.31604150e+03 4.33989404e+03 4.36143555e+03 4.36592822e+03 4.37018604e+03 4.38302344e+03 4.40135254e+03 4.41758545e+03 4.42406738e+03 4.43277881e+03 4.44964600e+03 4.45673535e+03 4.46059521e+03 4.47087061e+03 4.48224463e+03 4.49326709e+03 4.50276611e+03 4.50840186e+03 4.51876221e+03 4.52454785e+03 4.52932471e+03 4.53986328e+03 4.53957129e+03 4.54546777e+03 4.55591455e+03 4.56330176e+03 4.56828369e+03 4.57231641e+03 4.57496484e+03 4.57564941e+03 4.58071826e+03 4.58691406e+03 4.58786865e+03 4.59133203e+03 4.59384082e+03 4.59557812e+03 4.59844775e+03 4.59876611e+03 4.59925586e+03 4.60039795e+03 4.60052051e+03 4.60058594e+03 4.59966016e+03 4.59882715e+03 4.59836865e+03 4.59547363e+03 4.59489502e+03 4.59278418e+03 4.58972266e+03 4.58844678e+03 4.58464551e+03 4.57936279e+03 4.57699707e+03 4.57357861e+03 4.56695312e+03 4.56370947e+03 4.55733887e+03 4.55185840e+03 4.54893359e+03 4.53798926e+03 4.53106787e+03 4.52802734e+03 4.51720459e+03 4.51318018e+03 4.50583447e+03 4.48920020e+03 4.48542773e+03 4.48494678e+03 4.46998828e+03 4.45343652e+03 4.44608887e+03 4.44257861e+03 4.43308057e+03 4.41861816e+03 4.39858496e+03 4.39064844e+03 4.38465576e+03 4.37180566e+03 4.36161768e+03 4.34457861e+03 4.32815967e+03 4.31497217e+03 4.30493408e+03 4.29162207e+03 4.27886768e+03 4.26402100e+03 4.24766504e+03 4.23194238e+03 4.20653027e+03 4.19873730e+03 4.18842871e+03 4.17141064e+03 4.15282227e+03 4.13285156e+03 4.11497803e+03 4.10371387e+03 4.08687817e+03 4.06671533e+03 4.04416260e+03 4.02243311e+03 4.01353076e+03 3.99565503e+03 3.96541919e+03 3.95027466e+03 3.93207935e+03 3.90475513e+03 3.89186108e+03 3.87544800e+03 3.84942920e+03 3.82855103e+03 3.80363330e+03 3.78850635e+03 3.76766187e+03 3.73907227e+03 3.72075586e+03 3.70060620e+03 3.67127026e+03 3.64886523e+03 3.63436646e+03 3.61038989e+03 3.58743091e+03 3.55952246e+03 3.53660107e+03 3.51200977e+03 3.48458472e+03 3.46834033e+03 3.44726562e+03 3.41965942e+03 3.37952466e+03 3.36491821e+03 3.35376733e+03 3.31339429e+03 3.28503784e+03 3.26740088e+03 3.22952441e+03 3.20961133e+03 3.19648169e+03 3.15259619e+03 3.13251538e+03 3.11272461e+03 3.07336475e+03 3.05975391e+03 3.03483374e+03 3.00714453e+03 2.97884912e+03 2.93808350e+03 2.91574951e+03 2.88904395e+03 2.86446240e+03 2.84451807e+03 2.81479590e+03 2.78625293e+03 2.75527563e+03 2.73161597e+03 2.69466431e+03 2.66721973e+03 2.65501978e+03 2.62058423e+03 2.58419482e+03 2.56301196e+03 2.53740723e+03 2.50114062e+03 2.47391235e+03 2.44784229e+03 2.41703076e+03 2.38614771e+03 2.36322314e+03 2.33865527e+03 2.30733569e+03 2.27780688e+03 2.25763037e+03 2.21836548e+03 2.19537622e+03 2.17189722e+03 2.13484644e+03 2.10999121e+03 2.08211597e+03 2.05843188e+03 2.02721545e+03 1.99800903e+03 1.97749976e+03 1.93442371e+03 1.91428955e+03 1.89308545e+03 1.85638635e+03 1.82587146e+03 1.80441138e+03 1.78162109e+03 1.74749207e+03 1.71986670e+03 1.69414392e+03 1.67027563e+03 1.64108105e+03 1.60844128e+03 1.58453699e+03 1.56382544e+03 1.53365881e+03 1.50413257e+03 1.48297522e+03 1.45893860e+03 1.42691956e+03 1.39807056e+03 1.37670947e+03 1.35280676e+03 1.32382166e+03 1.29769824e+03 1.27314612e+03 1.24977258e+03 1.22187073e+03 1.19875342e+03 1.17681116e+03 1.15078931e+03 1.12191736e+03 1.10006714e+03 1.07726355e+03 1.05434167e+03 1.03123242e+03 1.00588800e+03 9.81908142e+02 9.60472229e+02 9.39352844e+02 9.16855042e+02 8.92785095e+02 8.68876831e+02 8.48788086e+02 8.28398560e+02 8.04444275e+02 7.83007935e+02 7.64572876e+02 7.42009705e+02 7.20491455e+02 7.02421448e+02 6.80920959e+02 6.61102722e+02 6.42518311e+02 6.22744446e+02 6.03367798e+02 5.84633606e+02 5.65301697e+02 5.48721008e+02 5.29831665e+02 5.10593475e+02 4.94613739e+02 4.77644409e+02 4.59401764e+02 4.42679718e+02 4.27469788e+02 4.10693756e+02 3.94027100e+02 3.79734497e+02 3.64074646e+02 3.48369507e+02 3.34181885e+02 3.19941925e+02 3.05878052e+02 2.91970642e+02 2.77920868e+02 2.64943115e+02 2.52891785e+02 2.39757492e+02 2.27152344e+02 2.15217361e+02 2.03699448e+02 1.92627945e+02 1.81569839e+02 1.70737244e+02 1.60625519e+02 1.50482025e+02 1.40505173e+02 1.31112701e+02 1.22172707e+02 1.13537567e+02 1.05126846e+02 9.69310379e+01 8.92348557e+01 8.17818146e+01 7.46992035e+01 6.80233917e+01 6.15282288e+01 5.54291496e+01 4.97583160e+01 4.43721275e+01 3.93272781e+01 3.46086159e+01 3.02239799e+01 2.61807003e+01 2.24998646e+01 1.91625538e+01 1.61554317e+01 1.35063047e+01 1.11967821e+01 9.23280716e+00 7.61739683e+00 6.34376955e+00 5.41516066e+00 4.83601332e+00 4.60036898e+00 4.71198797e+00 5.16660547e+00 5.97016907e+00 7.12067556e+00 8.61554146e+00 1.04611235e+01 1.26481504e+01 1.51719646e+01 1.80494881e+01 2.12693272e+01 2.48194828e+01 2.87358913e+01 3.29873695e+01 3.75489235e+01 4.25019951e+01 4.77800980e+01 5.33791046e+01 5.93525772e+01 6.55810547e+01 7.22294006e+01 7.91934509e+01 8.64151459e+01 9.41541748e+01 1.02161934e+02 1.10240082e+02 1.18945755e+02 1.28110352e+02 1.37237198e+02 1.46711227e+02 1.56707092e+02 1.67158310e+02 1.77675781e+02 1.88469391e+02 1.99534470e+02 2.10973419e+02 2.22940323e+02 2.35315308e+02 2.48076538e+02 2.60592651e+02 2.73344482e+02 2.86364075e+02 3.00569183e+02 3.15075012e+02 3.28875275e+02 3.43461914e+02 3.58542328e+02 3.73598907e+02 3.88066895e+02 4.04491882e+02 4.20982452e+02 4.37233032e+02 4.54243805e+02 4.70282745e+02 4.87366058e+02 5.05465210e+02 5.23789734e+02 5.41584961e+02 5.59317444e+02 5.77230225e+02 5.96630493e+02 6.15688843e+02 6.33698914e+02 6.54362122e+02 6.74771179e+02 6.92302551e+02 7.14498413e+02 7.36445435e+02 7.55249634e+02 7.76154785e+02 7.98296631e+02 8.19625671e+02 8.41710388e+02 8.61253662e+02 8.82990967e+02 9.08371704e+02 9.28141296e+02 9.51801514e+02 9.75584290e+02 9.98590210e+02 1.02245129e+03 1.04451526e+03 1.06890222e+03 1.09245374e+03 1.11671863e+03 1.14217761e+03 1.16618481e+03 1.18971545e+03 1.21339160e+03 1.24011841e+03 1.26630322e+03 1.29031152e+03 1.31380762e+03 1.34088416e+03 1.36501611e+03 1.39389636e+03 1.42159473e+03 1.44192908e+03 1.47026843e+03 1.49905725e+03 1.52031909e+03 1.55279651e+03 1.57857629e+03 1.60411243e+03 1.63476599e+03 1.65642480e+03 1.68274231e+03 1.70954602e+03 1.73859363e+03 1.77184607e+03 1.79319177e+03 1.82449060e+03 1.84610400e+03 1.87970691e+03 1.90388916e+03 1.92772815e+03 1.96374817e+03 1.99242139e+03 2.01405298e+03 2.04459521e+03 2.07281006e+03 2.10061646e+03 2.13290210e+03 2.15834253e+03 2.18350903e+03 2.20429297e+03 2.23973193e+03 2.27945264e+03 2.29798340e+03 2.32565991e+03 2.35615723e+03 2.37313037e+03 2.41258032e+03 2.44091943e+03 2.46199780e+03 2.49134326e+03 2.52551294e+03 2.55271606e+03 2.58070386e+03 2.60447144e+03 2.63402222e+03 2.65495850e+03 2.68382178e+03 2.72004565e+03 2.73949609e+03 2.76773877e+03 2.79855298e+03 2.83022656e+03 2.84911938e+03 3.73105396e+03 3.98017773e+03 7.01379395e+03 9.25738965e+03 -22127728. 68511144. 0. 0. 0. 216867760. 216867760. 216867760. 0. 0. 0. 6382026. -14347127. 1.51728418e+04 9.76808594e+03 5.57431836e+03 5.30024902e+03 4.83901758e+03 3.48358472e+03 3.50043774e+03 3.50685083e+03 3.52819092e+03 3.55903882e+03 3.58212329e+03 3.59737256e+03 3.61189893e+03 3.64633105e+03 3.67403174e+03 3.68938599e+03 3.71224097e+03 3.72761768e+03 3.74872949e+03 3.77998535e+03 3.79286353e+03 3.81199097e+03 3.84454565e+03 3.86526050e+03 3.87628467e+03 3.90637109e+03 3.92375439e+03 3.94204224e+03 3.96480078e+03 3.98421631e+03 4.01230444e+03 4.02797095e+03 4.04208447e+03 4.06837793e+03 4.07896680e+03 4.08839600e+03 4.11766162e+03 4.13632764e+03 4.14146582e+03 4.15384424e+03 4.18597070e+03 4.19836084e+03 4.20430566e+03 4.22734033e+03 4.24486621e+03 4.25343311e+03 4.27512891e+03 4.29094336e+03 4.30612549e+03 4.31126025e+03 4.31617529e+03 4.34433301e+03 4.36542529e+03 4.36584131e+03 4.37385498e+03 4.38575049e+03 4.40052490e+03 4.41962842e+03 4.42546973e+03 4.43391602e+03 4.45136377e+03 4.45784033e+03 4.46273242e+03 4.47257617e+03 4.48398975e+03 4.49532324e+03 4.50646631e+03 4.50966699e+03 4.51842480e+03 4.52495898e+03 4.53157861e+03 4.54082129e+03 4.54124219e+03 4.54723779e+03 4.55761963e+03 4.56501025e+03 4.56945361e+03 4.57171973e+03 4.57504980e+03 4.57695166e+03 4.58200098e+03 4.58792480e+03 4.58945068e+03 4.59274463e+03 4.59527588e+03 4.59665576e+03 4.59821631e+03 4.59778174e+03 4.59963965e+03 1.38009268e+04 5.02994050e+06 1.80971582e+04 4.53402881e+03 4.53328711e+03 4.53210596e+03 4.53007422e+03 4.52943018e+03 4.52767383e+03 4.52418750e+03 4.52196240e+03 4.51907520e+03 4.51418604e+03 4.51177686e+03 4.50687842e+03 4.50258643e+03 4.50001318e+03 4.49087402e+03 4.48704199e+03 4.48408301e+03 4.47283643e+03 4.46861182e+03 4462. 4.45289551e+03 4.44742041e+03 4.43907568e+03 4.43047266e+03 4.42362744e+03 4.41603418e+03 4.40256152e+03 4.39058154e+03 4.38456641e+03 4.37916553e+03 4.36561230e+03 4.35482178e+03 4.34004199e+03 4.32580908e+03 4.31672314e+03 4.30620703e+03 4.29815039e+03 4.28375195e+03 4.26509375e+03 4.25311035e+03 4.24137500e+03 4.22824658e+03 4.21957275e+03 4.20001074e+03 4.18069434e+03 4.17558691e+03 4.14766113e+03 4.13661963e+03 4.12758057e+03 4.10198877e+03 4.09318091e+03 4.07516040e+03 4.05048779e+03 4.04801929e+03 4.02141138e+03 4.00231323e+03 3.99839429e+03 3.97109131e+03 3.94659546e+03 3.92549634e+03 3.89665918e+03 3.89022339e+03 3.87918604e+03 3842. 3.82943799e+03 3.81718066e+03 3.79683081e+03 3.77451074e+03 3.74683984e+03 3.72918774e+03 3.71081250e+03 3.68826611e+03 3.66028394e+03 3.63861523e+03 3.61535303e+03 3.60326660e+03 3.57269312e+03 3.54986938e+03 3.53074756e+03 4.64930127e+03 4.92790918e+03 8.48724707e+03 1.04890762e+04 -67371056. 16581188. 30564580. 30564580. 0. 49731296. 49731296. 101760248. -1510269440. -1510269440. 0. 0. 0. 0. -316577312. -75079136. 9.19293359e+03 7.21805127e+03 4.40284521e+03 3.96059668e+03 3.73315063e+03 2.87169873e+03 2.84262061e+03 2.82244214e+03 2.79498535e+03 2.76535938e+03 2.74165601e+03 2.71346777e+03 2.69184375e+03 2.65008716e+03 2.62419531e+03 2.61674902e+03 2.57576294e+03 2.53985010e+03 2.52073096e+03 2.49665845e+03 2.46544141e+03 2.43257764e+03 2.40962793e+03 2.37539185e+03 2.34158838e+03 2.32610547e+03 2.30700439e+03 2.27193604e+03 2.23985083e+03 2.22155933e+03 2.18868408e+03 2.15826538e+03 2.13306616e+03 2.10402197e+03 2.07848047e+03 2.04617322e+03 2.01789380e+03 1.99400623e+03 1.96454773e+03 1.93978613e+03 1.90312708e+03 1.88073938e+03 1.86283191e+03 1.82618103e+03 1.79795203e+03 1.77530701e+03 1.74488782e+03 1.71457166e+03 1.69190186e+03 1.66489807e+03 1.63750647e+03 1.60965613e+03 1.58208264e+03 1.56233789e+03 1.53464978e+03 1.50355469e+03 1.47610242e+03 1.45493103e+03 1.43264380e+03 1.39823950e+03 1.37380737e+03 1.35379736e+03 1.32977686e+03 1.29863184e+03 1.27222351e+03 1.25086462e+03 1.22641040e+03 1.19915967e+03 1.17504004e+03 1.15515527e+03 1.12871765e+03 1.10152295e+03 1.08077075e+03 1.05658313e+03 1.03177246e+03 1.01296307e+03 9.85299194e+02 9.62669556e+02 9.42756714e+02 9.18822021e+02 8.98853394e+02 8.75267273e+02 8.51460388e+02 8.30302856e+02 8.10897461e+02 7.87437317e+02 7.67728882e+02 7.49147278e+02 7.26620178e+02 7.05267090e+02 6.85501465e+02 6.66986572e+02 6.46638977e+02 6.27685486e+02 6.10067749e+02 5.90615234e+02 5.70940613e+02 5.51171448e+02 5.35094727e+02 5.17189026e+02 4.99353485e+02 4.83441315e+02 4.66387482e+02 4.48610870e+02 4.30954742e+02 4.16493927e+02 4.00307220e+02 3.84439667e+02 3.69980621e+02 3.54579437e+02 3.39215820e+02 3.25057434e+02 3.11461151e+02 2.97857513e+02 2.83594208e+02 2.69950684e+02 2.57497437e+02 2.45363266e+02 2.32679291e+02 2.20230438e+02 2.08551727e+02 1.97167374e+02 1.86223679e+02 1.75483963e+02 1.64898483e+02 1.54767853e+02 1.44945801e+02 1.35346619e+02 1.26277206e+02 1.17334724e+02 1.08753403e+02 1.00520531e+02 9.25867920e+01 8.50617065e+01 7.78257599e+01 7.08478241e+01 6.42770386e+01 5.80209198e+01 5.20704384e+01 4.65399513e+01 4.12989540e+01 3.63676453e+01 3.17832336e+01 2.75411987e+01 2.36302071e+01 2.00622425e+01 1.68378010e+01 1.39493628e+01 1.14032173e+01 9.19147968e+00 7.32304287e+00 5.79533005e+00 4.60727167e+00 3.76013041e+00 3.25512385e+00 3.09036613e+00 3.26742363e+00 3.78463173e+00 4.64387321e+00 5.84525681e+00 7.38372278e+00 9.26737690e+00 1.14900522e+01 1.40545349e+01 1.69651699e+01 2.01991196e+01 2.37654572e+01 2.76893845e+01 3.19470119e+01 3.65411987e+01 4.15068512e+01 4.67347298e+01 5.23251266e+01 5.82919579e+01 6.45218124e+01 7.11573486e+01 7.80443573e+01 8.52428284e+01 9.29469910e+01 1.00843750e+02 1.09113289e+02 1.17658882e+02 1.26546524e+02 1.35685287e+02 1.45154556e+02 1.55118240e+02 1.65547119e+02 1.75961288e+02 1.86704041e+02 1.97612946e+02 2.08918716e+02 2.20816376e+02 2.32962021e+02 2.45637665e+02 2.58087799e+02 2.71056274e+02 2.83724792e+02 2.97719330e+02 3.11968353e+02 3.25652191e+02 3.40551056e+02 3.55105438e+02 3.70025696e+02 3.84453461e+02 4.00791351e+02 4.16565765e+02 4.32024872e+02 4.49912872e+02 4.66118744e+02 4.82902710e+02 5.01262695e+02 5.17126404e+02 5.35697205e+02 5.55933716e+02 5.72315125e+02 5.89680115e+02 6.08991150e+02 6.26489502e+02 6.47432190e+02 6.68818481e+02 6.85456421e+02 7.05881226e+02 7.28307434e+02 7.48546448e+02 7.68923157e+02 7.89154053e+02 8.10158569e+02 8.33141357e+02 8.54957214e+02 8.74308533e+02 8.96698364e+02 9.18778442e+02 9.42796753e+02 9.63235168e+02 9.86380066e+02 1.01205579e+03 1.03220239e+03 1.05506299e+03 1.08132947e+03 1.10635938e+03 1.12921460e+03 1.15378296e+03 1.18020728e+03 1.19964221e+03 1.22636780e+03 1.25312085e+03 1.27283521e+03 1.29904199e+03 1.32744702e+03 1.34843494e+03 1.37655969e+03 1.40394507e+03 1.42334814e+03 1.45449963e+03 1.48586340e+03 1.50383130e+03 1.53285596e+03 1.56089783e+03 1.58496790e+03 1.61455920e+03 1.63835669e+03 1.66438489e+03 1.69012537e+03 1.72457031e+03 1.74589502e+03 1.76735962e+03 1.80511365e+03 1.82907178e+03 1.85573010e+03 1.88111902e+03 1.90901343e+03 1.94421826e+03 1.96356555e+03 1.98578906e+03 2.01659961e+03 2.05529980e+03 2.07932544e+03 2.09408350e+03 2.13142310e+03 2.15271118e+03 2.17395483e+03 2.21539575e+03 2.25474609e+03 2.27137842e+03 2.29386084e+03 2.32347217e+03 2.35822705e+03 2.38717627e+03 2.41394580e+03 2.43458228e+03 2.46291577e+03 2.49094849e+03 2.51719727e+03 2.54430347e+03 2.57916528e+03 2.60642285e+03 2.61562598e+03 2.65558643e+03 2.69535596e+03 2.71132129e+03 2.73335278e+03 2.76917944e+03 2.79573047e+03 2.81493188e+03 2.84913086e+03 2.87178052e+03 2.90671777e+03 2.92746875e+03 2.95025220e+03 2.98264819e+03 3.01461572e+03 3.03479712e+03 3.04657275e+03 3.08198291e+03 3.11861768e+03 3.13096631e+03 3.15609668e+03 3.19283179e+03 3.22568799e+03 3.23795093e+03 3.25151440e+03 3.28750464e+03 3.31881006e+03 3.32765845e+03 3.35651343e+03 3.39809766e+03 3.41191919e+03 3.42548145e+03 3.45768872e+03 3.48176196e+03 3.50345679e+03 3.53869116e+03 3.54718384e+03 3.56771899e+03 3.60038257e+03 3.62210278e+03 3.64810864e+03 3.66511621e+03 3.67746118e+03 3.69899536e+03 3.73536694e+03 3.74704395e+03 3.76449268e+03 3.79849756e+03 3.81403369e+03 3.82640820e+03 3.84764966e+03 3.87368384e+03 3.88952319e+03 3.91243921e+03 3.93983765e+03 3.95267383e+03 3.96599780e+03 3.97076978e+03 4.00205078e+03 4.02035889e+03 4.03685034e+03 4.06948364e+03 4.07880151e+03 4.08485156e+03 4.09757275e+03 4.12713184e+03 4.13878662e+03 4.14546582e+03 4.17145898e+03 4.18600635e+03 4.19510791e+03 4.21295654e+03 4.23026318e+03 4.24659082e+03 4.25468506e+03 4.26079102e+03 4.27822900e+03 4.29878369e+03 4.31028564e+03 4.30998486e+03 4.32610498e+03 4.34362598e+03 4.35277930e+03 4.36397949e+03 4.37376074e+03 4.38557520e+03 4.39357764e+03 4.40115869e+03 4.41360107e+03 4.42115088e+03 4.42966016e+03 4.43690430e+03 4.44462939e+03 4.45645264e+03 4.46054736e+03 4.46594922e+03 4.47586035e+03 4.47924805e+03 4.48379443e+03 4.49212402e+03 4.49816455e+03 4.50273535e+03 4.50803076e+03 4.51148193e+03 4.51272559e+03 4.51571045e+03 4.52183936e+03 4.52413232e+03 4.52723975e+03 4.52874316e+03 4.53049902e+03 4.53351807e+03 4.53372021e+03 4.53407715e+03 4.53518311e+03 4.53527539e+03 4.53520410e+03 4.53419824e+03 4.53354297e+03 4.53267578e+03 4.52975342e+03 4.52904785e+03 4.52712305e+03 4.52475781e+03 4.52337305e+03 4.51907910e+03 4.51290234e+03 4.50961621e+03 4.50597119e+03 4.50243408e+03 4.50030469e+03 4.48991602e+03 4.48442871e+03 4.48504785e+03 4.47458887e+03 4.46588965e+03 4.45968555e+03 4.45086670e+03 4.44554736e+03 4.43798486e+03 4.42976953e+03 4.42193408e+03 4.41430127e+03 4.40123730e+03 4.38852295e+03 4.38105469e+03 4.37725781e+03 4.36634375e+03 4.35395508e+03 4.33785352e+03 4.32677979e+03 4.31783301e+03 4.30445459e+03 4.29473584e+03 4.28152197e+03 4.26703662e+03 4.25233105e+03 4.24123828e+03 4.22720068e+03 4.21542529e+03 4.19898389e+03 4.18037451e+03 4.17018555e+03 4.14406152e+03 4.13481250e+03 4.12780176e+03 4.10276367e+03 4.09068384e+03 4.07267041e+03 4.05186768e+03 4.04975342e+03 4.01977271e+03 4.00185864e+03 3.99589795e+03 3.96479785e+03 3.94478613e+03 3.92585327e+03 3.89682227e+03 3.88946851e+03 3.88191260e+03 3.84185938e+03 3.82760278e+03 3.81568018e+03 3.79518848e+03 3.77095068e+03 3.74329468e+03 3.72819580e+03 3.71027808e+03 3.68931885e+03 3.66426343e+03 3.63853271e+03 3.61597095e+03 3.59453320e+03 3.56952148e+03 3.54974463e+03 3.53253687e+03 3.50088574e+03 3.48310913e+03 3.45857056e+03 3.43321924e+03 3.41055835e+03 3.39285327e+03 3.36962671e+03 3.32859131e+03 3.31380103e+03 3.29869580e+03 3.25585327e+03 3.23393164e+03 3.21948315e+03 3.17689600e+03 3.15797583e+03 3.14291577e+03 3.10364355e+03 3.08537671e+03 3.06921997e+03 3.03042871e+03 3.00668555e+03 2.98460571e+03 2.95088965e+03 2.92186401e+03 2.89421802e+03 2.87202905e+03 2.84034424e+03 2.82162891e+03 2.79030298e+03 2.76225830e+03 2.74426758e+03 2.71344336e+03 2.68775000e+03 2.64807227e+03 2.62406763e+03 2.61703491e+03 2.57483716e+03 2.53694092e+03 2.51770312e+03 2.49643115e+03 2.46620898e+03 2.42677612e+03 2.40419092e+03 2.38134180e+03 2.34171655e+03 2.32567993e+03 2.30259082e+03 2.27305688e+03 2.23803833e+03 2.21820435e+03 2.18445337e+03 2.15513013e+03 2.13467480e+03 2.10957788e+03 2.07759766e+03 2.04218848e+03 2.01654272e+03 1.98950403e+03 1.96343127e+03 1.93850122e+03 1.90292493e+03 1.87936719e+03 1.86118445e+03 1.82765002e+03 1.79631873e+03 1.77292310e+03 1.74765112e+03 1.71750635e+03 1.69016248e+03 1.66435803e+03 1.63979822e+03 1.61232568e+03 1.58314661e+03 1.56027588e+03 1.53666919e+03 1.50587146e+03 1.47427356e+03 1.45157202e+03 1.43043237e+03 1.40022058e+03 1.37182275e+03 1.35346497e+03 1.32910950e+03 1.29922961e+03 1.27110742e+03 1.24991565e+03 1.22673499e+03 1.19840796e+03 1.17570593e+03 1.15487415e+03 1.12788098e+03 1.10134241e+03 1.08099011e+03 1.05636206e+03 1.03148914e+03 1.01289008e+03 9.85729553e+02 9.62256592e+02 9.42249451e+02 9.19199402e+02 8.98003662e+02 8.75422485e+02 8.50872681e+02 8.30104126e+02 8.10702454e+02 7.87624939e+02 7.66614380e+02 7.48273560e+02 7.26869385e+02 7.06222046e+02 6.85665161e+02 6.66604919e+02 6.46767883e+02 6.27696411e+02 6.09658081e+02 5.90020935e+02 5.71130127e+02 5.51321594e+02 5.35165955e+02 5.17001404e+02 4.98859863e+02 4.83598541e+02 4.65992859e+02 4.48447662e+02 4.31456024e+02 4.16573090e+02 4.00259125e+02 3.84227905e+02 3.69977997e+02 3.54347198e+02 3.39219391e+02 3.25225891e+02 3.11251221e+02 2.97485931e+02 2.83676117e+02 2.70104370e+02 2.57324554e+02 2.45264801e+02 2.32652206e+02 2.20105209e+02 2.08464066e+02 1.97276321e+02 1.86235687e+02 1.75413010e+02 1.64893372e+02 1.54785812e+02 1.44880569e+02 1.35290161e+02 1.26170609e+02 1.17280266e+02 1.08745926e+02 1.00473679e+02 9.25391006e+01 8.50543747e+01 7.77571564e+01 7.08244324e+01 6.42872467e+01 5.80047226e+01 5.20607796e+01 4.65186844e+01 4.12731361e+01 3.63473740e+01 3.17682419e+01 2.75195656e+01 2.36112099e+01 2.00464916e+01 1.68267002e+01 1.39356871e+01 1.13895721e+01 9.17731094e+00 7.31023598e+00 5.78381634e+00 4.59446049e+00 3.74782348e+00 3.24377584e+00 3.07926536e+00 3.25708485e+00 3.77477288e+00 4.63677263e+00 5.83985710e+00 7.38221550e+00 9.26770878e+00 1.14946747e+01 1.40533924e+01 1.69555302e+01 2.01942577e+01 2.37655144e+01 2.76932945e+01 3.19537010e+01 3.65403175e+01 4.14992905e+01 4.67399673e+01 5.23491974e+01 5.83262482e+01 6.45512848e+01 7.11705475e+01 7.80439148e+01 8.52687683e+01 9.29658813e+01 1.00859673e+02 1.09073708e+02 1.17666336e+02 1.26610695e+02 1.35735382e+02 1.45175690e+02 1.55114471e+02 1.65458862e+02 1.75846085e+02 1.86719711e+02 1.97724213e+02 2.09006714e+02 2.20745453e+02 2.32971481e+02 2.45615250e+02 2.58211823e+02 2.70903656e+02 2.83704254e+02 2.97760803e+02 3.11923462e+02 3.25620026e+02 3.40109161e+02 3.55175079e+02 3.70155365e+02 3.84357574e+02 4.00787598e+02 4.16919159e+02 4.32322937e+02 4.49857269e+02 4.66157379e+02 4.82665802e+02 5.01558197e+02 5.17584473e+02 5.35297791e+02 5.55629028e+02 5.71657898e+02 5.89991821e+02 6.09058411e+02 6.26325073e+02 6.47394836e+02 6.68740784e+02 6.85800415e+02 7.06228088e+02 7.28482849e+02 7.47961060e+02 7.68885803e+02 7.89098877e+02 8.10632385e+02 8.32639465e+02 8.54715210e+02 8.74794617e+02 8.97046082e+02 9.19402161e+02 9.43457825e+02 9.64028992e+02 9.87202881e+02 1.01215692e+03 1.03150732e+03 1.05690015e+03 1.08124622e+03 1.10641064e+03 1.12801831e+03 1.15365869e+03 1.17995251e+03 1.19934509e+03 1.22686047e+03 1.25377832e+03 1.27367725e+03 1.29985425e+03 1.32724829e+03 1.34788196e+03 1.37673779e+03 1.40396375e+03 1.42637634e+03 1.45451233e+03 1.48578723e+03 1.50361584e+03 1.53183093e+03 1.55816199e+03 1.58639600e+03 1.61340491e+03 1.63681213e+03 1.66488550e+03 1.69236731e+03 1.72471667e+03 1.74743176e+03 1.76918762e+03 1.80560205e+03 1.82646472e+03 1.85782373e+03 1.87947180e+03 1.90595923e+03 1.94501794e+03 1.96374036e+03 1.98430933e+03 2.02253284e+03 2.05316846e+03 2.07867383e+03 2.09764722e+03 2.12915845e+03 2.15507275e+03 2.17513379e+03 2.21707446e+03 2.25093945e+03 2.27467188e+03 2.29827295e+03 2.32534814e+03 2.35369824e+03 2.37792480e+03 2.41499121e+03 2.44016016e+03 2.46745386e+03 2.48893726e+03 2.51755566e+03 2.54945996e+03 2.57689746e+03 2.60596338e+03 2.62490454e+03 2.65089209e+03 2.69079761e+03 2.70804761e+03 2.73354712e+03 2.76445410e+03 2.79402686e+03 2.81755420e+03 2.84222900e+03 2.87330347e+03 3.81647314e+03 4.18475928e+03 7.25093604e+03 9.34621973e+03 336821568. -212669440. 0. 216867760. 216867760. 216867760. 0. 0. -55283024. -55283024. -55283024. -110982232. 19596818. 3.30708945e+04 1.05857285e+04 9.04139062e+03 5.06165088e+03 4.74261035e+03 3.49190039e+03 3.50439941e+03 3.52049292e+03 3.54312109e+03 3.54874341e+03 3.56412158e+03 3.59925244e+03 3.62898853e+03 3.65598706e+03 3.67235229e+03 3.68277783e+03 3.70369287e+03 3.72834717e+03 3.74560767e+03 3.76145532e+03 3.79232935e+03 3.81349365e+03 3.82532837e+03 3.84821167e+03 3.87726782e+03 3.88746680e+03 3.91077197e+03 3.93323486e+03 3.94946362e+03 3.96950098e+03 3.98426904e+03 4.00784497e+03 4.02179053e+03 4.04117383e+03 4.06734277e+03 4.07960718e+03 4.09036719e+03 4.09746289e+03 4.12949023e+03 4.14031250e+03 4.14184131e+03 4.17184814e+03 4.18804248e+03 4.19918848e+03 4.21597217e+03 4.22808301e+03 4.24634912e+03 4.25332422e+03 4.26298926e+03 4.28241260e+03 4.30183887e+03 4.30915723e+03 4.31444043e+03 4.32704541e+03 4.34278271e+03 4.35818018e+03 4.36325244e+03 4.37318066e+03 4.38856152e+03 4.39382031e+03 4.40030664e+03 4.41263574e+03 4.42141113e+03 4.43106689e+03 4.44021289e+03 4.44525684e+03 4.45754980e+03 4.46235645e+03 4.46635693e+03 4.47622705e+03 4.47930225e+03 4.48394141e+03 4.49319434e+03 4.49990625e+03 4.50347021e+03 4.50767969e+03 4.51184814e+03 4.51375537e+03 4.51717969e+03 4.52074756e+03 4.52322021e+03 4.52649756e+03 4.52868506e+03 4.53083252e+03 4.53340625e+03 4.53402100e+03 4.53310645e+03 1.35609561e+04 16189381. 1.79406582e+04 5.81864697e+03 6.11268555e+03 6.75807471e+03 6.75579785e+03 6.75898682e+03 6.75871826e+03 6.74734473e+03 6.74452344e+03 6.74222803e+03 6.73405713e+03 6.73221143e+03 6.14552979e+03 5.80350879e+03 4.45604248e+03 4.45230127e+03 4.44506152e+03 4.43776074e+03 4.42907861e+03 4.42752051e+03 4.42004004e+03 4.41242578e+03 4.40533105e+03 4.39605908e+03 4.38943896e+03 4.38131494e+03 4.37076611e+03 4.36027783e+03 4.35043506e+03 4.34413232e+03 4.33909814e+03 4.32260156e+03 4.31179834e+03 4.29672461e+03 4.28459912e+03 4.27612744e+03 4.26408154e+03 4.25472656e+03 4.24264551e+03 4.22814209e+03 4.21255713e+03 4.19987500e+03 4.18675684e+03 4.17475098e+03 4.16365576e+03 4.14421680e+03 4.13104443e+03 4.10969922e+03 4.09666064e+03 4.08607178e+03 4.06441309e+03 4.04936841e+03 4.03110107e+03 4.01750708e+03 4.00501294e+03 3.98626099e+03 3.96107104e+03 3.95009961e+03 3.93141895e+03 3.91062280e+03 3.89005884e+03 3.86669507e+03 3.85192603e+03 3.83900098e+03 3.81164722e+03 3.79493945e+03 3.78233252e+03 3.75518213e+03 3.73187183e+03 3.71041895e+03 3.69443018e+03 3.67486353e+03 3.64608643e+03 3.62472998e+03 3.60345605e+03 3.58148975e+03 3.56601831e+03 3.53506006e+03 3.51118237e+03 4.60468018e+03 8.46518066e+03 1.07912783e+04 -43395772. 117013112. 0. 30564580. 30564580. 30564580. 0. 49731296. 49731296. 101760248. -1510269440. -103743984. -31861920. -31861920. 0. 128123184. 3.49991367e+04 7.28375391e+03 4.16210156e+03 3.87230884e+03 2.92483813e+03 2.89993115e+03 2.86499854e+03 2.83904688e+03 2.82209985e+03 2.79205737e+03 2.76901270e+03 2.74452979e+03 2.71316846e+03 2.68475708e+03 2.65737695e+03 2.62797949e+03 2.59860400e+03 2.57681006e+03 2.54706934e+03 2.51571069e+03 2.49403467e+03 2.46911304e+03 2.43858301e+03 2.40835815e+03 2.37907861e+03 2.35213184e+03 2.32343359e+03 2.29892017e+03 2.27591968e+03 2.24290186e+03 2.21626318e+03 2.19702319e+03 2.15734253e+03 2.13495923e+03 2.10714893e+03 2.07777856e+03 2.05347437e+03 2.02788220e+03 1.99939429e+03 1.96941199e+03 1.94463452e+03 1.91555103e+03 1.88550085e+03 1.86221045e+03 1.83664282e+03 1.80413379e+03 1.77708777e+03 1.75457886e+03 1.72533118e+03 1.70000073e+03 1.67212183e+03 1.64552637e+03 1.62265845e+03 1.59146533e+03 1.56633191e+03 1.54278601e+03 1.51416858e+03 1.48752979e+03 1.45960217e+03 1.43653870e+03 1.41072485e+03 1.38248364e+03 1.35903967e+03 1.33772119e+03 1.31347522e+03 1.28357239e+03 1.25830933e+03 1.23810645e+03 1.21074805e+03 1.18353564e+03 1.16029578e+03 1.13966711e+03 1.11477527e+03 1.08917529e+03 1.06856763e+03 1.04297034e+03 1.02031232e+03 9.99781921e+02 9.74068970e+02 9.50857056e+02 9.29333374e+02 9.07094849e+02 8.86297241e+02 8.63572205e+02 8.42243652e+02 8.21602173e+02 7.99729553e+02 7.77500061e+02 7.56293213e+02 7.37725464e+02 7.17410889e+02 6.97053894e+02 6.76798584e+02 6.58044067e+02 6.37943054e+02 6.19281311e+02 6.01074036e+02 5.81537170e+02 5.62997742e+02 5.44672058e+02 5.27544983e+02 5.09870453e+02 4.92609650e+02 4.76239166e+02 4.58681122e+02 4.41613495e+02 4.25398987e+02 4.09747711e+02 3.94195648e+02 3.78788605e+02 3.64061157e+02 3.48820831e+02 3.34067291e+02 3.19782227e+02 3.06024719e+02 2.92536346e+02 2.78643494e+02 2.65483887e+02 2.52804123e+02 2.40653473e+02 2.28242279e+02 2.16180847e+02 2.04556778e+02 1.93142426e+02 1.82335388e+02 1.71806366e+02 1.61491974e+02 1.51258621e+02 1.41562866e+02 1.32168076e+02 1.23114662e+02 1.14312668e+02 1.05847328e+02 9.77084351e+01 8.99256287e+01 8.24721451e+01 7.53054886e+01 6.84554291e+01 6.19583588e+01 5.58271332e+01 4.99675179e+01 4.44684448e+01 3.92973213e+01 3.44403992e+01 2.99393826e+01 2.57576427e+01 2.19206047e+01 1.84113464e+01 1.52429085e+01 1.24145880e+01 9.91633511e+00 7.75141478e+00 5.92984009e+00 4.44509459e+00 3.29778147e+00 2.48830771e+00 2.01696634e+00 1.88388228e+00 2.08909726e+00 2.63202524e+00 3.51295900e+00 4.73150730e+00 6.28638506e+00 8.18376160e+00 1.04160299e+01 1.29889736e+01 1.59038534e+01 1.91418095e+01 2.27069569e+01 2.66171093e+01 3.08751793e+01 3.54662476e+01 4.03925400e+01 4.55987930e+01 5.11853409e+01 5.71066360e+01 6.33288422e+01 6.99399796e+01 7.67680740e+01 8.39961472e+01 9.16115952e+01 9.94599152e+01 1.07693657e+02 1.16200249e+02 1.25000122e+02 1.34125931e+02 1.43545425e+02 1.53396790e+02 1.63763199e+02 1.74050888e+02 1.84650436e+02 1.95587631e+02 2.06973312e+02 2.18743469e+02 2.30738297e+02 2.43110168e+02 2.55741501e+02 2.68413330e+02 2.81301788e+02 2.95151154e+02 3.08892456e+02 3.23062469e+02 3.37580963e+02 3.51809357e+02 3.66914551e+02 3.81571594e+02 3.97368500e+02 4.12798889e+02 4.28776245e+02 4.45339600e+02 4.62224884e+02 4.79450653e+02 4.96467468e+02 5.13489380e+02 5.31001099e+02 5.49853821e+02 5.67721558e+02 5.85524536e+02 6.04349854e+02 6.22433044e+02 6.41669006e+02 6.62185181e+02 6.81678223e+02 7.01065552e+02 7.22129333e+02 7.41982971e+02 7.61626099e+02 7.82662476e+02 8.04155701e+02 8.26692993e+02 8.45488159e+02 8.67653320e+02 8.90181458e+02 9.10545044e+02 9.35735962e+02 9.56137634e+02 9.77906799e+02 1.00349066e+03 1.02478467e+03 1.04711145e+03 1.07051355e+03 1.09640869e+03 1.11882983e+03 1.14373523e+03 1.16902307e+03 1.19065540e+03 1.21560876e+03 1.24075513e+03 1.26386450e+03 1.28968176e+03 1.31559375e+03 1.33848145e+03 1.36405371e+03 1.39026831e+03 1.41473450e+03 1.44305798e+03 1.46890149e+03 1.49284094e+03 1.51912842e+03 1.54227161e+03 1.57184460e+03 1.60323352e+03 1.61955347e+03 1.65219214e+03 1.68251562e+03 1.70477441e+03 1.72894153e+03 1.76063147e+03 1.79038098e+03 1.81156519e+03 1.83874377e+03 1.86040027e+03 1.89620557e+03 1.92525586e+03 1.94728381e+03 1.96932898e+03 1.99852502e+03 2.03657703e+03 2.05784961e+03 2.07730981e+03 2.10736450e+03 2.13854321e+03 2.16279297e+03 2.19276147e+03 2.22907495e+03 2.25239111e+03 2.27290845e+03 2.30799707e+03 2.33230786e+03 2.36604590e+03 2.39259131e+03 2.41346777e+03 2.44087085e+03 2.47548730e+03 2.49434277e+03 2.52209058e+03 2.55495581e+03 2.57892065e+03 2.60001904e+03 2.63254346e+03 2.66646338e+03 2.68906787e+03 2.71081396e+03 2.74557397e+03 2.76965674e+03 2.79507520e+03 2.82041772e+03 2.84768384e+03 2.88338281e+03 2.90197144e+03 2.92423828e+03 2.96311304e+03 2.98392139e+03 3.00374292e+03 3.02507007e+03 3.05780444e+03 3.08878711e+03 3.10590674e+03 3.13773633e+03 3.16982642e+03 3.18723291e+03 3.20457666e+03 3.22870142e+03 3.26630811e+03 3.29038892e+03 3.29956250e+03 3.32421606e+03 3.36586621e+03 3.38562891e+03 3.39817700e+03 3.42965942e+03 3.44901685e+03 3.47569580e+03 3.50809985e+03 3.51643359e+03 3.53828613e+03 3.56514355e+03 3.58490381e+03 3.61244141e+03 3.63401489e+03 3.65006006e+03 3.67109814e+03 3.69973657e+03 3.71578760e+03 3.73020386e+03 3.75726904e+03 3.77936987e+03 3.79898462e+03 3.81542651e+03 3.83863989e+03 3.85423999e+03 3.87653101e+03 3.90114185e+03 3.91570142e+03 3.92881763e+03 3.94456396e+03 3.96551587e+03 3.98421509e+03 4.00880591e+03 4.02597217e+03 4.03440186e+03 4.05055884e+03 4.06540845e+03 4.08451904e+03 4.10079102e+03 4.11379102e+03 4.13267139e+03 4.14635645e+03 4.16165283e+03 4.17143164e+03 4.19047217e+03 4.20940674e+03 4.21269873e+03 4.22365430e+03 4.24160205e+03 4.25634131e+03 4.26838037e+03 4.27576270e+03 4.28897559e+03 4.30043750e+03 4.31016992e+03 4.32525391e+03 4.33782471e+03 4.34281445e+03 4.35189941e+03 4.36185254e+03 4.37186523e+03 4.38123096e+03 4.39042383e+03 4.39699463e+03 4.40374658e+03 4.41377246e+03 4.41825586e+03 4.42499365e+03 4.43336816e+03 4.44038330e+03 4.44500635e+03 4.45047852e+03 4.45564746e+03 4.45967041e+03 4.46582715e+03 4.46998535e+03 4.47263672e+03 4.47458594e+03 4.47926172e+03 4.48325244e+03 4.48547852e+03 4.48654834e+03 4.48840283e+03 4.49104541e+03 4.49148145e+03 4.49196143e+03 4.49289990e+03 4.49300244e+03 4.49285254e+03 4.49182666e+03 4.49138184e+03 4.49015234e+03 4.48753711e+03 4.48703711e+03 4.48408643e+03 4.48262842e+03 4.48065723e+03 4.47637793e+03 4.47149268e+03 4.46698486e+03 4.46300244e+03 4.46029980e+03 4.45835693e+03 4.44770068e+03 4.44169971e+03 4.44031152e+03 4.43130322e+03 4.42451172e+03 4.41861816e+03 4.41043896e+03 4.40247168e+03 4.39513037e+03 4.38879492e+03 4.37978125e+03 4.36926660e+03 4.35980176e+03 4.34760693e+03 4.34148730e+03 4.33768506e+03 4.32291211e+03 4.31010400e+03 4.29427686e+03 4.28562549e+03 4.27673584e+03 4.26445264e+03 4.25496631e+03 4.24054980e+03 4.22743457e+03 4.21132471e+03 4.19874854e+03 4.18627246e+03 4.17416797e+03 4.15908691e+03 4.14363623e+03 4.12779199e+03 4.10711768e+03 4.09586816e+03 4.08405518e+03 4.06469165e+03 4.04743091e+03 4.03102710e+03 4.01642627e+03 4.00392017e+03 3.98634302e+03 3.96215063e+03 3.94780835e+03 3.92879150e+03 3.90444604e+03 3.88811621e+03 3.86714575e+03 3.84983887e+03 3.83459448e+03 3.81256445e+03 3.79692407e+03 3.77899023e+03 3.75401221e+03 3.73053198e+03 3.70695337e+03 3.69462622e+03 3.67810254e+03 3.64513989e+03 3.62444678e+03 3.60015771e+03 3.57770483e+03 3.56481836e+03 3.53731128e+03 3.51211792e+03 3.49490967e+03 3.46427393e+03 3.44416724e+03 3.42158057e+03 3.40148730e+03 3.37349585e+03 3.35551807e+03 3.33440234e+03 3.29499561e+03 3.28042871e+03 3.26134033e+03 3.22621313e+03 3.20652393e+03 3.18675464e+03 3.15380225e+03 3.12695728e+03 3.10243237e+03 3.07133911e+03 3.05143384e+03 3.03584180e+03 2.99923853e+03 2.97401367e+03 2.94506177e+03 2.92440771e+03 2.90443555e+03 2.86417407e+03 2.84177979e+03 2.82027124e+03 2.79081982e+03 2.76093994e+03 2.74322461e+03 2.71062671e+03 2.68437500e+03 2.65228638e+03 2.62370752e+03 2.60335596e+03 2.58227637e+03 2.54269946e+03 2.51089429e+03 2.49093994e+03 2.47329810e+03 2.43737036e+03 2.40319580e+03 2.37574048e+03 2.34943994e+03 2.32218164e+03 2.29625830e+03 2.27591211e+03 2.24182642e+03 2.21348169e+03 2.19333057e+03 2.16229932e+03 2.13579492e+03 2.11067749e+03 2.08109570e+03 2.05416016e+03 2.02294287e+03 1.99382080e+03 1.96604150e+03 1.94291467e+03 1.91638367e+03 1.88382495e+03 1.85802393e+03 1.83542664e+03 1.80573364e+03 1.78031860e+03 1.75236475e+03 1.72676953e+03 1.70006409e+03 1.66935657e+03 1.64305090e+03 1.62225122e+03 1.59210352e+03 1.56688513e+03 1.54230151e+03 1.51525500e+03 1.48672266e+03 1.45957190e+03 1.43655139e+03 1.41089978e+03 1.38300720e+03 1.35859668e+03 1.33675671e+03 1.31314124e+03 1.28129224e+03 1.25918115e+03 1.23667126e+03 1.21139258e+03 1.18373547e+03 1.16033142e+03 1.14100598e+03 1.11466345e+03 1.08870886e+03 1.06685852e+03 1.04396082e+03 1.02093878e+03 9.99876343e+02 9.73933594e+02 9.50117798e+02 9.29986389e+02 9.07168884e+02 8.85748413e+02 8.63493103e+02 8.41600464e+02 8.21708496e+02 7.99846252e+02 7.77173950e+02 7.56721436e+02 7.37028015e+02 7.16868530e+02 6.97646423e+02 6.77219543e+02 6.57282776e+02 6.37777405e+02 6.19645569e+02 6.00735291e+02 5.81142639e+02 5.62901489e+02 5.45069763e+02 5.27116516e+02 5.09416199e+02 4.92777618e+02 4.76247101e+02 4.58221497e+02 4.41884552e+02 4.25774994e+02 4.09737457e+02 3.94235870e+02 3.78834015e+02 3.63580627e+02 3.48828247e+02 3.34168335e+02 3.19857117e+02 3.05805542e+02 2.92387848e+02 2.78728546e+02 2.65530518e+02 2.52843887e+02 2.40609802e+02 2.28248245e+02 2.16086975e+02 2.04566299e+02 1.93219772e+02 1.82311432e+02 1.71785355e+02 1.61459366e+02 1.51246338e+02 1.41540710e+02 1.32131500e+02 1.23092873e+02 1.14295029e+02 1.05839310e+02 9.76596909e+01 8.98899918e+01 8.24777069e+01 7.52606277e+01 6.84228668e+01 6.19652748e+01 5.58148804e+01 4.99525795e+01 4.44531937e+01 3.92798576e+01 3.44159088e+01 2.99123802e+01 2.57378922e+01 2.19023094e+01 1.83911152e+01 1.52236376e+01 1.23939238e+01 9.89705086e+00 7.73456335e+00 5.91226912e+00 4.42754078e+00 3.27846026e+00 2.47025871e+00 1.99910283e+00 1.86502612e+00 2.06929159e+00 2.61080360e+00 3.49232769e+00 4.70979023e+00 6.26601219e+00 8.16362095e+00 1.03952188e+01 1.29627113e+01 1.58674259e+01 1.91078033e+01 2.26788540e+01 2.65885086e+01 3.08403072e+01 3.54265633e+01 4.03554344e+01 4.55696983e+01 5.11689529e+01 5.70967140e+01 6.33129578e+01 6.99156342e+01 7.67342148e+01 8.39564819e+01 9.15892181e+01 9.94170685e+01 1.07629280e+02 1.16164597e+02 1.25008957e+02 1.34137665e+02 1.43501740e+02 1.53397903e+02 1.63719803e+02 1.73958145e+02 1.84686417e+02 1.95558884e+02 2.06940384e+02 2.18777664e+02 2.30710236e+02 2.43108261e+02 2.55695908e+02 2.68324585e+02 2.81299347e+02 2.95012939e+02 3.08901917e+02 3.23122131e+02 3.37574249e+02 3.51963867e+02 3.66933594e+02 3.81676971e+02 3.97405365e+02 4.12918091e+02 4.28481689e+02 4.45408112e+02 4.62168518e+02 4.79189087e+02 4.96322540e+02 5.13673584e+02 5.30651306e+02 5.49564148e+02 5.67704407e+02 5.85219482e+02 6.04278625e+02 6.22122314e+02 6.41601257e+02 6.62637451e+02 6.81403625e+02 7.01210449e+02 7.22229797e+02 7.41863037e+02 7.61858643e+02 7.82585388e+02 8.03740845e+02 8.26414917e+02 8.46508118e+02 8.67812134e+02 8.89370911e+02 9.10765686e+02 9.36642273e+02 9.56322693e+02 9.78284302e+02 1.00345392e+03 1.02456885e+03 1.04788525e+03 1.07217358e+03 1.09641504e+03 1.11848926e+03 1.14459143e+03 1.16896008e+03 1.19051050e+03 1.21513721e+03 1.24218359e+03 1.26503943e+03 1.28973218e+03 1.31627454e+03 1.33945728e+03 1.36543787e+03 1.38982239e+03 1.41473450e+03 1.44090503e+03 1.47199268e+03 1.49499597e+03 1.52000049e+03 1.54368408e+03 1.57425769e+03 1.60179700e+03 1.61771472e+03 1.65139563e+03 1.68146191e+03 1.70764026e+03 1.72929980e+03 1.76135266e+03 1.78926648e+03 1.81330896e+03 1.83950952e+03 1.86340027e+03 1.89392969e+03 1.92161340e+03 1.94698206e+03 1.96810632e+03 2.00343140e+03 2.03678259e+03 2.05985742e+03 2.08321094e+03 2.11039355e+03 2.13474097e+03 2.16376733e+03 2.19049268e+03 2.23116626e+03 2.25049683e+03 2.27985547e+03 2.31218359e+03 2.33166235e+03 2.36181689e+03 2.39403442e+03 2.41680811e+03 2.44449756e+03 2.47332129e+03 2.49435864e+03 2.52735669e+03 2.55510376e+03 2.58197974e+03 2.60396045e+03 2.63479517e+03 2.66474731e+03 2.68658374e+03 2.71053320e+03 2.73880713e+03 2.77148315e+03 2.79494702e+03 2.81678833e+03 2.84974072e+03 2.87624487e+03 2.90291309e+03 3.79627295e+03 4.01137744e+03 7.32424561e+03 8.32542188e+03 -9374074. 19763114. 216867760. 216867760. -38679024. -38679024. 21316162. -55283024. -55283024. 0. 0. 0. -773834048. -6.36935650e+06 1.05099238e+04 9.22962695e+03 5.37444141e+03 5.19119092e+03 4.69401221e+03 3.52467114e+03 3.53526831e+03 3.53402124e+03 3.55593530e+03 3.59807471e+03 3.62807715e+03 3.64045068e+03 3.65709790e+03 3.67510986e+03 3.69567017e+03 3.71304126e+03 3.72656396e+03 3.75402881e+03 3.77876074e+03 3.79076465e+03 3.80894946e+03 3.84160938e+03 3.85477393e+03 3.88385742e+03 3.91157837e+03 3.91400610e+03 3.93003857e+03 3.94543042e+03 3.96339307e+03 3.98829614e+03 4.01374121e+03 4.02158325e+03 4.03659863e+03 4.05567163e+03 4.06857617e+03 4.08408105e+03 4.10142725e+03 4.11446875e+03 4.13310205e+03 4.15022998e+03 4.16229785e+03 4.17391309e+03 4.19149902e+03 4.20558691e+03 4.21483691e+03 4.22468945e+03 4.24356689e+03 4.25936670e+03 4.26852637e+03 4.27675830e+03 4.28902539e+03 4.30314258e+03 4.31541064e+03 4.32510645e+03 4.33911475e+03 4.34593506e+03 4.35237354e+03 4.36088867e+03 4.37182910e+03 4.38118604e+03 4.39236084e+03 4.39931592e+03 4.40384082e+03 4.41570166e+03 4.42123975e+03 4.42502441e+03 4.43322900e+03 4.43980225e+03 4.44361426e+03 4.44750537e+03 4.46104199e+03 5.74049561e+03 4.46742139e+03 6.73962891e+03 6.05724023e+03 6.25957666e+03 5.88389014e+03 4.47771631e+03 4.48250635e+03 4.48876904e+03 4.48882129e+03 4.48857422e+03 4.48968213e+03 4.49184521e+03 1.34645596e+04 7.25708390e+10 2.68338750e+04 1.08213447e+04 1.35216025e+04 1.34393008e+04 1.34566689e+04 1.34688232e+04 3.82045605e+03 1.10129287e+04 1.34384502e+04 1.07065928e+04 6.66354297e+03 6.65860791e+03 5.47362598e+03 5.45005859e+03 4.42409570e+03 4.41895361e+03 4.41343115e+03 4.40682275e+03 4.40020215e+03 4.39645410e+03 4.38899658e+03 4.38195605e+03 4.37362207e+03 4.36538477e+03 4.35908154e+03 4.35092578e+03 4.33981104e+03 4.33158887e+03 4.32119824e+03 4.31356641e+03 4.31098340e+03 4.29349561e+03 4.27884521e+03 4.26596289e+03 4.25599951e+03 4.24727588e+03 4.23312305e+03 4.22872705e+03 4.21929541e+03 4.19714648e+03 4.18166846e+03 4.17562500e+03 4.16136475e+03 4.14124561e+03 4.13051807e+03 4.12085449e+03 4.10310400e+03 4.08484546e+03 4.06668530e+03 4.05434302e+03 4.03731396e+03 4.02221924e+03 4.00903125e+03 3.98734546e+03 3.97332788e+03 3.95370044e+03 3.93754370e+03 3.92423022e+03 3.90322534e+03 3.88127246e+03 3.86846729e+03 3.84552393e+03 3.82589551e+03 3.81090430e+03 3.78362109e+03 3.76771899e+03 3.75362866e+03 3.73468140e+03 3.70775708e+03 3.68134619e+03 3.66871338e+03 3.64652124e+03 3.62113916e+03 3.60469995e+03 3.57729785e+03 3.55851978e+03 4.66405176e+03 5.00381543e+03 5.28504004e+03 9.04658105e+03 4.77880469e+04 -71015168. 0. 0. -37418632. -37418632. -37418632. 0. 0. 49731296. 49731296. 49731296. 0. -31861920. -31861920. -23908462. 12419001. 9.19689551e+03 7.18582324e+03 3.88607178e+03 2.95384863e+03 2.92795264e+03 2.90781763e+03 2.87910742e+03 2.85148999e+03 2.82062451e+03 2.80401172e+03 2.77031958e+03 2.74404297e+03 2.72883618e+03 2.69662549e+03 2.66231738e+03 2.63989551e+03 2.60887354e+03 2.58360498e+03 2.56044897e+03 2.52854395e+03 2.49790771e+03 2.47334302e+03 2.45503564e+03 2.42294531e+03 2.39201392e+03 2.36286743e+03 2.33988940e+03 2.31335620e+03 2.28237744e+03 2.25418262e+03 2.23148999e+03 2.20618652e+03 2.17328101e+03 2.15131372e+03 2.12242969e+03 2.09520435e+03 2.06793994e+03 2.03928186e+03 2.01433032e+03 1.98410168e+03 1.95919653e+03 1.93506067e+03 1.90292078e+03 1.87797961e+03 1.85008887e+03 1.82612415e+03 1.79677148e+03 1.76997107e+03 1.73902344e+03 1.71505261e+03 1.69377344e+03 1.66143445e+03 1.63474548e+03 1.61407080e+03 1.58167358e+03 1.55681860e+03 1.53288782e+03 1.50600378e+03 1.47676758e+03 1.45313135e+03 1.42990552e+03 1.40077246e+03 1.37376514e+03 1.35388281e+03 1.33099243e+03 1.30381433e+03 1.27393127e+03 1.25456506e+03 1.23094055e+03 1.20475488e+03 1.17959558e+03 1.15413196e+03 1.13076758e+03 1.10899084e+03 1.08249548e+03 1.05745251e+03 1.03735901e+03 1.01715540e+03 9.93846191e+02 9.69381104e+02 9.46310120e+02 9.23913818e+02 9.02719849e+02 8.81224243e+02 8.57251831e+02 8.38447815e+02 8.16205139e+02 7.94005554e+02 7.73853210e+02 7.53097473e+02 7.33927551e+02 7.13628540e+02 6.93323303e+02 6.72780212e+02 6.54078796e+02 6.34422363e+02 6.15963684e+02 5.97706238e+02 5.78471436e+02 5.59914124e+02 5.42562988e+02 5.24530640e+02 5.06903748e+02 4.89852875e+02 4.72894226e+02 4.56088715e+02 4.39983032e+02 4.23484467e+02 4.07279663e+02 3.92070709e+02 3.76827393e+02 3.61515350e+02 3.46841064e+02 3.32663757e+02 3.18496582e+02 3.04115845e+02 2.90313446e+02 2.77043793e+02 2.64175293e+02 2.51347275e+02 2.39121063e+02 2.26919815e+02 2.14923706e+02 2.03307114e+02 1.92052734e+02 1.81195465e+02 1.70677383e+02 1.60430710e+02 1.50252029e+02 1.40659531e+02 1.31258575e+02 1.22143745e+02 1.13434830e+02 1.05040245e+02 9.68872604e+01 8.91045609e+01 8.16688919e+01 7.45124817e+01 6.77340775e+01 6.12410202e+01 5.51091614e+01 4.92793922e+01 4.37532692e+01 3.85729675e+01 3.37350197e+01 2.92416840e+01 2.50590553e+01 2.12198715e+01 1.76976223e+01 1.45147724e+01 1.16776066e+01 9.16374016e+00 6.98246908e+00 5.14127636e+00 3.63454795e+00 2.46245074e+00 1.62637222e+00 1.12632143e+00 9.62323308e-01 1.13421047e+00 1.64190090e+00 2.48527479e+00 3.66428995e+00 5.17679548e+00 7.02711535e+00 9.21168327e+00 1.17362967e+01 1.45953798e+01 1.77795315e+01 2.12926197e+01 2.51387119e+01 2.93424320e+01 3.38753662e+01 3.87189827e+01 4.38703690e+01 4.93683891e+01 5.52205238e+01 6.14116936e+01 6.78826981e+01 7.46677017e+01 8.18588409e+01 8.93250809e+01 9.70638657e+01 1.05232353e+02 1.13682587e+02 1.22381020e+02 1.31464767e+02 1.40716263e+02 1.50525772e+02 1.60678101e+02 1.70815048e+02 1.81432571e+02 1.92354218e+02 2.03606277e+02 2.15237595e+02 2.27067566e+02 2.39395416e+02 2.51843918e+02 2.64413116e+02 2.77561096e+02 2.90922974e+02 3.04563293e+02 3.18415649e+02 3.32832916e+02 3.47185516e+02 3.62133850e+02 3.77320404e+02 3.92141693e+02 4.07630127e+02 4.23436096e+02 4.39895996e+02 4.57048737e+02 4.73461090e+02 4.90001740e+02 5.07073303e+02 5.24859436e+02 5.43191162e+02 5.60499939e+02 5.78523010e+02 5.97565735e+02 6.15974548e+02 6.35054626e+02 6.54645508e+02 6.73265198e+02 6.93444336e+02 7.14891479e+02 7.34906067e+02 7.53701538e+02 7.74040771e+02 7.95709717e+02 8.15934448e+02 8.37507263e+02 8.59789001e+02 8.80154175e+02 9.02368042e+02 9.26528992e+02 9.48026428e+02 9.70315125e+02 9.90798462e+02 1.01291632e+03 1.03968237e+03 1.06080005e+03 1.08717053e+03 1.10961755e+03 1.13307703e+03 1.15926257e+03 1.18053223e+03 1.20456445e+03 1.22786047e+03 1.24970056e+03 1.27735144e+03 1.30509338e+03 1.32923108e+03 1.35239587e+03 1.37360986e+03 1.40486670e+03 1.42964880e+03 1.45691028e+03 1.48220361e+03 1.50269128e+03 1.52910657e+03 1.55787012e+03 1.58940674e+03 1.61104724e+03 1.63607288e+03 1.66817175e+03 1.68660352e+03 1.71218066e+03 1.75180127e+03 1.77403931e+03 1.79365820e+03 1.82070825e+03 1.84521460e+03 1.87605859e+03 1.90732336e+03 1.93414539e+03 1.95473108e+03 1.98308240e+03 2.01710571e+03 2.04425452e+03 2.06143848e+03 2.08933472e+03 2.12190039e+03 2.15072876e+03 2.17629346e+03 2.20063135e+03 2.23368750e+03 2.26103931e+03 2.28053687e+03 2.31621338e+03 2.34121680e+03 2.37189331e+03 2.39660474e+03 2.42165625e+03 2.44573267e+03 2.47593701e+03 2.49998486e+03 2.53032275e+03 2.55696948e+03 2.58364844e+03 2.61500415e+03 2.64457275e+03 2.66737769e+03 2.69644531e+03 2.70836572e+03 2.74552661e+03 2.78190015e+03 2.79661523e+03 2.82535962e+03 2.85652783e+03 2.87866846e+03 2.90398413e+03 2.93533936e+03 2.95540942e+03 2.98261987e+03 3.00002612e+03 3.03625317e+03 3.06035400e+03 3.07734546e+03 3.11433032e+03 3.14030688e+03 3.16359473e+03 3.17847168e+03 3.19958203e+03 3.24358716e+03 3.26793433e+03 3.27417261e+03 3.30130225e+03 3.33764624e+03 3.35392090e+03 3.37306128e+03 3.39317578e+03 3.42004517e+03 3.45746313e+03 3.47553418e+03 3.49698413e+03 3.51235767e+03 3.53666577e+03 3.56176538e+03 3.58163037e+03 3.60175269e+03 3.62710400e+03 3.64293188e+03 3.66551367e+03 3.69330518e+03 3.70633716e+03 3.73136792e+03 3.74768213e+03 3.77001245e+03 3.78369238e+03 3.80573364e+03 3.82639111e+03 3.84859863e+03 3.87176367e+03 3.88344824e+03 3.89834180e+03 3.92164551e+03 3.93718604e+03 3.95271289e+03 3.97262012e+03 3.99001685e+03 4.00763672e+03 4.02332129e+03 4.04004419e+03 4.05730981e+03 4.06824707e+03 4.08276367e+03 4.09810645e+03 4.11586426e+03 4.13202100e+03 4.14765869e+03 4.15638672e+03 4.16899170e+03 4.18738525e+03 4.19893799e+03 4.20741455e+03 4.22660449e+03 4.23860596e+03 4.24604150e+03 4.25712256e+03 4.26853271e+03 4.27904150e+03 4.29436523e+03 4.30421582e+03 4.31178857e+03 4.32444141e+03 4.33075781e+03 4.33793701e+03 4.34967188e+03 4.36016748e+03 4.36549365e+03 4.37065625e+03 4.37934277e+03 4.38735645e+03 4.39474268e+03 4.39923486e+03 4.40929443e+03 4.41575928e+03 4.41769287e+03 4.42165967e+03 4.42709521e+03 4.43386377e+03 4.43812305e+03 4.44277588e+03 4.44387451e+03 4.44651367e+03 4.45182129e+03 4.45408740e+03 4.45505176e+03 4.45667285e+03 4.45884326e+03 4.45973682e+03 4.46042529e+03 4.46124170e+03 4.46132129e+03 4.46113184e+03 4.46039990e+03 4.46006641e+03 4.45842432e+03 4.45635645e+03 4.45575488e+03 4.45253906e+03 4.45151758e+03 4.44876123e+03 4.44500098e+03 4.44064648e+03 4.43483496e+03 4.43289795e+03 4.43032861e+03 4.42560547e+03 4.41787354e+03 4.41014014e+03 4.40602197e+03 4.40157227e+03 4.39427490e+03 4.38857471e+03 4.38193604e+03 4.37313916e+03 4.36412988e+03 4.35708252e+03 4.34957275e+03 4.33990918e+03 4.33195752e+03 4.31893066e+03 4.30971973e+03 4.30794678e+03 4.29256299e+03 4.27697559e+03 4.26358301e+03 4.25883643e+03 4.24872510e+03 4.23322754e+03 4.22664600e+03 4.21574219e+03 4.19799365e+03 4.18071338e+03 4.17411035e+03 4.16411621e+03 4.13795850e+03 4.12652490e+03 4.11975879e+03 4.10228955e+03 4.08352979e+03 4.06739917e+03 4.05402441e+03 4.03778931e+03 4.02237427e+03 4.00845337e+03 3.98875708e+03 3.97284839e+03 3.95459424e+03 3.93651953e+03 3.92532959e+03 3.90064233e+03 3.88077344e+03 3.86161719e+03 3.84454102e+03 3.82821924e+03 3.80989185e+03 3.78564258e+03 3.76741821e+03 3.75300366e+03 3.73238770e+03 3.70830786e+03 3.68140063e+03 3.66855591e+03 3.64590771e+03 3.62135791e+03 3.60520288e+03 3.57499780e+03 3.55852808e+03 3.53908496e+03 3.51559741e+03 3.49084570e+03 3.46233716e+03 3.44637207e+03 3.42900342e+03 3.40228271e+03 3.38178784e+03 3.35324170e+03 3.33031250e+03 3.31053149e+03 3.27696851e+03 3.26109595e+03 3.24073560e+03 3.19762744e+03 3.18269824e+03 3.16765747e+03 3.13621484e+03 3.10846533e+03 3.07374561e+03 3.05530469e+03 3.03511914e+03 3.01430054e+03 2.98388232e+03 2.94992017e+03 2.92487451e+03 2.90429248e+03 2.88468457e+03 2.85144556e+03 2.82530127e+03 2.80641113e+03 2.77222461e+03 2.74158984e+03 2.72857886e+03 2.69579761e+03 2.66316479e+03 2.64027832e+03 2.60450464e+03 2.58518848e+03 2.56470508e+03 2.53111841e+03 2.49801929e+03 2.47366626e+03 2.45797681e+03 2.42581738e+03 2.38887744e+03 2.36259790e+03 2.34222705e+03 2.31456152e+03 2.28594604e+03 2.25653101e+03 2.23079028e+03 2.20073096e+03 2.17398755e+03 2.15069287e+03 2.12245923e+03 2.09487256e+03 2.06888232e+03 2.03897998e+03 2.01326086e+03 1.98181714e+03 1.95709534e+03 1.93134412e+03 1.90402441e+03 1.87249219e+03 1.85009253e+03 1.82065405e+03 1.79654749e+03 1.77105188e+03 1.73688525e+03 1.71364600e+03 1.69338379e+03 1.65965393e+03 1.63420215e+03 1.61146143e+03 1.58177161e+03 1.55896143e+03 1.53550928e+03 1.50338513e+03 1.47848987e+03 1.45313635e+03 1.42879822e+03 1.40305640e+03 1.37456165e+03 1.35291553e+03 1.33023572e+03 1.30094714e+03 1.27684875e+03 1.25224817e+03 1.23214209e+03 1.20547046e+03 1.17710779e+03 1.15477515e+03 1.13288440e+03 1.10863782e+03 1.08309473e+03 1.05746790e+03 1.03810120e+03 1.01770905e+03 9.93576965e+02 9.69393188e+02 9.46156799e+02 9.23464844e+02 9.02902649e+02 8.81061462e+02 8.57907288e+02 8.38542175e+02 8.16250183e+02 7.94220093e+02 7.74400146e+02 7.53098633e+02 7.33799866e+02 7.12510803e+02 6.93317749e+02 6.72545532e+02 6.53119446e+02 6.34310669e+02 6.16111328e+02 5.97789062e+02 5.78508728e+02 5.59949524e+02 5.42463623e+02 5.24314331e+02 5.06287628e+02 4.89884521e+02 4.72894135e+02 4.55901093e+02 4.39812653e+02 4.24009430e+02 4.07639343e+02 3.91725677e+02 3.76693634e+02 3.61271240e+02 3.46587372e+02 3.32563721e+02 3.18493896e+02 3.03897583e+02 2.90241577e+02 2.77113098e+02 2.64153748e+02 2.51423874e+02 2.39162476e+02 2.26892120e+02 2.14861038e+02 2.03283646e+02 1.91998062e+02 1.81157608e+02 1.70690201e+02 1.60389511e+02 1.50253799e+02 1.40639557e+02 1.31244339e+02 1.22101334e+02 1.13413857e+02 1.05034500e+02 9.68651657e+01 8.90821686e+01 8.16462097e+01 7.45017014e+01 6.77177200e+01 6.12267952e+01 5.51046944e+01 4.92700424e+01 4.37425079e+01 3.85627060e+01 3.37196312e+01 2.92225971e+01 2.50448151e+01 2.12067852e+01 1.76876965e+01 1.45059843e+01 1.16663113e+01 9.15165806e+00 6.97210455e+00 5.13067961e+00 3.62457323e+00 2.45207500e+00 1.61667597e+00 1.11650848e+00 9.51895118e-01 1.12349141e+00 1.62987936e+00 2.47301245e+00 3.65097761e+00 5.16579437e+00 7.01746225e+00 9.20026016e+00 1.17221909e+01 1.45741043e+01 1.77585831e+01 2.12774277e+01 2.51234550e+01 2.93186035e+01 3.38488693e+01 3.86925964e+01 4.38505745e+01 4.93545799e+01 5.52049828e+01 6.13990173e+01 6.78763657e+01 7.46628342e+01 8.18424454e+01 8.93111649e+01 9.70390167e+01 1.05196266e+02 1.13660805e+02 1.22405151e+02 1.31436310e+02 1.40713501e+02 1.50531296e+02 1.60716888e+02 1.70865707e+02 1.81392380e+02 1.92214615e+02 2.03586014e+02 2.15290573e+02 2.27003250e+02 2.39387894e+02 2.51853455e+02 2.64316437e+02 2.77344727e+02 2.90939026e+02 3.04477264e+02 3.18428772e+02 3.32741394e+02 3.47240814e+02 3.62235474e+02 3.77150696e+02 3.92289764e+02 4.07483826e+02 4.23446899e+02 4.40282227e+02 4.56959473e+02 4.73323181e+02 4.90122467e+02 5.06765533e+02 5.24797607e+02 5.43776978e+02 5.60579407e+02 5.78508301e+02 5.97421814e+02 6.16139343e+02 6.34936829e+02 6.54938782e+02 6.72916870e+02 6.93394104e+02 7.14714478e+02 7.34325195e+02 7.54103333e+02 7.73436218e+02 7.95066101e+02 8.16511658e+02 8.37836609e+02 8.59432068e+02 8.79338806e+02 9.02114868e+02 9.26951477e+02 9.47668030e+02 9.69453308e+02 9.90496155e+02 1.01380280e+03 1.03997998e+03 1.06131494e+03 1.08525427e+03 1.10836011e+03 1.13408191e+03 1.15987463e+03 1.18004944e+03 1.20328662e+03 1.22803833e+03 1.25155823e+03 1.27694397e+03 1.30368835e+03 1.32865076e+03 1.35157678e+03 1.37496753e+03 1.40219824e+03 1.43009583e+03 1.45615564e+03 1.48054297e+03 1.50440833e+03 1.52660779e+03 1.56021582e+03 1.58704858e+03 1.60886560e+03 1.63697852e+03 1.66765833e+03 1.69013123e+03 1.70976355e+03 1.74767090e+03 1.77310706e+03 1.79387341e+03 1.82049963e+03 1.84840112e+03 1.87951831e+03 1.90896912e+03 1.93131348e+03 1.95486328e+03 1.98275208e+03 2.01743201e+03 2.04402380e+03 2.06438892e+03 2.09326001e+03 2.12066431e+03 2.15006519e+03 2.17630493e+03 2.20142529e+03 2.23404028e+03 2.25743604e+03 2.28637939e+03 2.31630469e+03 2.33905029e+03 2.36982715e+03 2.39710986e+03 2.42516821e+03 2.44924487e+03 2.47855859e+03 2.50287085e+03 2.53333130e+03 2.55716016e+03 2.58432788e+03 2.61870215e+03 2.64187183e+03 2.66696143e+03 2.69882959e+03 2.71335596e+03 2.74541211e+03 2.77837158e+03 2.79527686e+03 2.82576807e+03 2.85763794e+03 2.88033716e+03 2.89907520e+03 2.93107983e+03 3.85413086e+03 3.99145410e+03 7.04923193e+03 3.65598594e+04 -38071796. 0. -38679024. -38679024. 21316162. -55283024. -55283024. 0. 0. 0. 0. 0. -85976472. -9.06919238e+03 4.33782227e+04 1.25047158e+04 8.95294043e+03 5.26174268e+03 4.94803223e+03 4.54022070e+03 3.54426001e+03 3.56553125e+03 3.58829468e+03 3.60236523e+03 3.62719385e+03 3.64305811e+03 3.66034570e+03 3.69406543e+03 3.71238403e+03 3.73156348e+03 3.75180835e+03 3.77017310e+03 3.78101587e+03 3.81069678e+03 3.82948120e+03 3.85014746e+03 3.87223511e+03 3.88311719e+03 3.89862158e+03 3.92150928e+03 3.93742383e+03 3.95266675e+03 3.97465137e+03 3.98775464e+03 4.00644165e+03 4.02610522e+03 4.04571924e+03 4.05436572e+03 4.06967261e+03 4.08512378e+03 4.10026904e+03 4.11723486e+03 4.13359766e+03 4.14594678e+03 4.15995947e+03 4.17030762e+03 4.18567969e+03 4.19925049e+03 4.20857178e+03 4.22890869e+03 4.23889502e+03 4.24587598e+03 4.25525684e+03 4.27005811e+03 4.28170557e+03 4.29193213e+03 4.30483594e+03 4.31281641e+03 4.32324072e+03 4.32859863e+03 4.33661719e+03 4.34864355e+03 4.36077637e+03 4.36698633e+03 4.36946143e+03 4.38115332e+03 4.38901074e+03 4.39382080e+03 4.40006250e+03 4.40854346e+03 4.41403613e+03 4.41768848e+03 4.42522607e+03 8.51489062e+03 6.17316504e+03 1.33943643e+04 1.33983301e+04 1.34027930e+04 1.07112666e+04 6.69401758e+03 6.10551367e+03 6.70267334e+03 6.08432178e+03 6.70557666e+03 6.70682617e+03 6.70914209e+03 2.01265879e+04 -9.70940744e+10 20115778. 20115778. -3.10117786e+10 -2.19149394e+10 -2.19149394e+10 -2.19149394e+10 0. 0. -3.37702236e+10 5.27990078e+04 1.05704189e+04 6.61321094e+03 6.03474512e+03 5.75646924e+03 4.40154834e+03 4.40095020e+03 4.39404785e+03 4.38509131e+03 4.37872852e+03 4.37468311e+03 4.36952344e+03 4.35769043e+03 4.35194873e+03 4.34841797e+03 4.33547510e+03 4.32680566e+03 4.31922510e+03 4.30837793e+03 4.30162061e+03 4.29241162e+03 4.28540186e+03 4.27489355e+03 4.25639111e+03 4.24585303e+03 4.23717334e+03 4.22647998e+03 4.21391943e+03 4.20629736e+03 4.19368457e+03 4.17616797e+03 4.16451562e+03 4.15223486e+03 4.13881494e+03 4.11909131e+03 4.11138965e+03 4.10113477e+03 4.07628223e+03 4.06199707e+03 4.04776392e+03 4.03833691e+03 4.02095679e+03 4.00014917e+03 3.98738623e+03 3.97070728e+03 3.94925830e+03 3.93562183e+03 3.91774536e+03 3.89943359e+03 3.88115381e+03 3.86572803e+03 3.85182861e+03 3.83315430e+03 3.80376392e+03 3.78730054e+03 3.77454199e+03 3.75436401e+03 3.72724463e+03 3.70867358e+03 3.69863208e+03 3.66322656e+03 3.64776514e+03 3.63533960e+03 3.60057129e+03 3.58726489e+03 4.67020850e+03 4.97686475e+03 8.78241699e+03 1.23241338e+04 1.05504859e+05 -111435208. 40116004. 0. -726943360. -726943360. -7.55927501e+09 -37418632. -37418632. 0. 0. 0. 0. 0. 0. -23453666. 3.68329258e+04 5.00346875e+03 7.28425049e+03 4.12364746e+03 3.86835498e+03 2.96428857e+03 2.93885034e+03 2.92151978e+03 2.89435474e+03 2.86662671e+03 2.83660278e+03 2.80838574e+03 2.78695947e+03 2.76190479e+03 2.72848462e+03 2.70647095e+03 2.67757715e+03 2.64810059e+03 2.63077905e+03 2.59695508e+03 2.57191870e+03 2.54877539e+03 2.51702661e+03 2.48549414e+03 2.46501929e+03 2.43688745e+03 2.41146533e+03 2.38631299e+03 2.35184497e+03 2.32759961e+03 2.30484277e+03 2.26972876e+03 2.24101831e+03 2.21978540e+03 2.19231812e+03 2.16364087e+03 2.13676221e+03 2.11607861e+03 2.08752954e+03 2.04964600e+03 2.03251831e+03 2.00501306e+03 1.96883936e+03 1.94458984e+03 1.92133606e+03 1.89339014e+03 1.86948987e+03 1.84018921e+03 1.81203308e+03 1.78409338e+03 1.76142419e+03 1.72896692e+03 1.70468567e+03 1.68483643e+03 1.65066406e+03 1.62751733e+03 1.60453796e+03 1.57524365e+03 1.54474084e+03 1.51776221e+03 1.49990869e+03 1.47256519e+03 1.44443359e+03 1.41944080e+03 1.39422949e+03 1.36987024e+03 1.34714990e+03 1.32312036e+03 1.29307983e+03 1.27111548e+03 1.24839380e+03 1.22532898e+03 1.19868262e+03 1.17311218e+03 1.14714270e+03 1.12458459e+03 1.10249097e+03 1.07576245e+03 1.05131543e+03 1.03215808e+03 1.01156030e+03 9.89129883e+02 9.64093506e+02 9.41119141e+02 9.18199585e+02 8.97564392e+02 8.76200134e+02 8.52025452e+02 8.32922302e+02 8.11602600e+02 7.90480347e+02 7.70748596e+02 7.48038696e+02 7.28757751e+02 7.09674805e+02 6.88646973e+02 6.68811035e+02 6.49842957e+02 6.30522217e+02 6.12179626e+02 5.93397522e+02 5.74649536e+02 5.56751831e+02 5.39618774e+02 5.21017883e+02 5.03569580e+02 4.86573029e+02 4.69525726e+02 4.53095612e+02 4.37357849e+02 4.20847382e+02 4.04452484e+02 3.89277527e+02 3.74411499e+02 3.59278473e+02 3.44269714e+02 3.30004517e+02 3.15934143e+02 3.01988403e+02 2.88344910e+02 2.75021271e+02 2.62101166e+02 2.49411469e+02 2.37130280e+02 2.25152176e+02 2.13170563e+02 2.01513489e+02 1.90454483e+02 1.79628784e+02 1.69122574e+02 1.58773499e+02 1.48861252e+02 1.39277069e+02 1.29818741e+02 1.20857666e+02 1.12172119e+02 1.03835571e+02 9.57630157e+01 8.79571762e+01 8.05802078e+01 7.34701385e+01 6.67293777e+01 6.02707596e+01 5.41299973e+01 4.83596992e+01 4.28767319e+01 3.77155113e+01 3.29130135e+01 2.84419041e+01 2.42861176e+01 2.04711399e+01 1.69733715e+01 1.38108654e+01 1.09902630e+01 8.49291039e+00 6.32868481e+00 4.50112963e+00 3.00742340e+00 1.84689999e+00 1.02064121e+00 5.28739691e-01 3.70947510e-01 5.47573090e-01 1.05837071e+00 1.90325260e+00 3.08224511e+00 4.59363031e+00 6.44118881e+00 8.62164402e+00 1.11364517e+01 1.39847355e+01 1.71638680e+01 2.06678963e+01 2.45000496e+01 2.86872692e+01 3.31980095e+01 3.80116501e+01 4.31676331e+01 4.86611824e+01 5.44660797e+01 6.06361961e+01 6.70800323e+01 7.38713150e+01 8.10182571e+01 8.84594879e+01 9.62132416e+01 1.04242477e+02 1.12651733e+02 1.21391525e+02 1.30435226e+02 1.39675766e+02 1.49318695e+02 1.59481583e+02 1.69704895e+02 1.80198029e+02 1.91061905e+02 2.02413864e+02 2.13840836e+02 2.25511932e+02 2.37819595e+02 2.50359055e+02 2.62875122e+02 2.75705994e+02 2.89104736e+02 3.02879761e+02 3.16630219e+02 3.30811127e+02 3.45117004e+02 3.59846680e+02 3.75057404e+02 3.90086090e+02 4.05819733e+02 4.21769501e+02 4.37245026e+02 4.54344086e+02 4.71264893e+02 4.87299194e+02 5.04473389e+02 5.22311890e+02 5.39977417e+02 5.57626587e+02 5.75894409e+02 5.94710571e+02 6.13054077e+02 6.31363464e+02 6.51157776e+02 6.70196167e+02 6.89965759e+02 7.10472961e+02 7.29747986e+02 7.51863525e+02 7.70629761e+02 7.90075439e+02 8.13364075e+02 8.33256653e+02 8.55616333e+02 8.75553101e+02 8.96133179e+02 9.21575500e+02 9.45204468e+02 9.65362061e+02 9.85245178e+02 1.00857074e+03 1.03436243e+03 1.05538940e+03 1.08080493e+03 1.10373706e+03 1.12755640e+03 1.15473169e+03 1.17538525e+03 1.19959900e+03 1.22180884e+03 1.24303516e+03 1.27120068e+03 1.29517847e+03 1.32103235e+03 1.34403284e+03 1.36622449e+03 1.39766174e+03 1.42331665e+03 1.44722241e+03 1.47482153e+03 1.49606067e+03 1.52676575e+03 1.55386194e+03 1.57634619e+03 1.60012512e+03 1.62610938e+03 1.65875696e+03 1.68173499e+03 1.70173621e+03 1.73660474e+03 1.76363977e+03 1.78819824e+03 1.81792786e+03 1.84099060e+03 1.86590698e+03 1.90173914e+03 1.92088049e+03 1.94481250e+03 1.97532483e+03 2.00864136e+03 2.03356689e+03 2.05583740e+03 2.08395093e+03 2.11342407e+03 2.14036719e+03 2.16202563e+03 2.19178784e+03 2.22103198e+03 2.24503687e+03 2.27534033e+03 2.30511133e+03 2.34113867e+03 2.35946411e+03 2.37830786e+03 2.41392065e+03 2.44055737e+03 2.45855005e+03 2.48830884e+03 2.51921973e+03 2.54663867e+03 2.57914380e+03 2.59610034e+03 2.62833398e+03 2.65075415e+03 2.68520264e+03 2.70030908e+03 2.72901611e+03 2.77011230e+03 2.78797192e+03 2.81638208e+03 2.84515747e+03 2.86513794e+03 2.88613428e+03 2.91290259e+03 2.94828735e+03 2.97226978e+03 2.98662964e+03 3.01774023e+03 3.04717480e+03 3.06927026e+03 3.09873633e+03 3.12369580e+03 3.14086646e+03 3.16386523e+03 3.19433911e+03 3.22953125e+03 3.24995996e+03 3.26297241e+03 3.28503076e+03 3.32128394e+03 3.34062842e+03 3.35434033e+03 3.37481250e+03 3.40569385e+03 3.44287549e+03 3.45891650e+03 3.47995044e+03 3.49855615e+03 3.51421680e+03 3.54149316e+03 3.57056958e+03 3.58832544e+03 3.60801001e+03 3.62681958e+03 3.64632300e+03 3.67645068e+03 3.68646411e+03 3.70669312e+03 3.73262061e+03 3.75028442e+03 3.76962500e+03 3.78760889e+03 3.80980249e+03 3.82952075e+03 3.84895850e+03 3.86436890e+03 3.88221191e+03 3.90912061e+03 3.91731689e+03 3.93374756e+03 3.95604541e+03 3.96814551e+03 3.98685205e+03 4.00798462e+03 4.01794409e+03 4.03034229e+03 4.04818921e+03 4.06945630e+03 4.08410815e+03 4.09624805e+03 4.10990430e+03 4.12475000e+03 4.13866699e+03 4.15383252e+03 4.16335889e+03 4.17712500e+03 4.19103027e+03 4.20180176e+03 4.21566357e+03 4.22818262e+03 4.23730322e+03 4.24727881e+03 4.25979443e+03 4.27429785e+03 4.28071484e+03 4.29227002e+03 4.30399316e+03 4.30721533e+03 4.31773877e+03 4.32867578e+03 4.33918701e+03 4.34785352e+03 4.34938721e+03 4.35767676e+03 4.36954688e+03 4.37513086e+03 4.37659814e+03 4.38486914e+03 4.39436426e+03 4.39728613e+03 4.40083252e+03 4.40715674e+03 4.41255811e+03 4.41627344e+03 4.42117969e+03 4.42307373e+03 4.42594824e+03 4.43067285e+03 4.43251709e+03 4.43403857e+03 4.43522705e+03 4.43711816e+03 4.43843604e+03 4.43922559e+03 4.43991113e+03 4.43998291e+03 4.43979297e+03 4.43898975e+03 4.43869189e+03 4.43720801e+03 4.43497314e+03 4.43386816e+03 4.43150879e+03 4.43030762e+03 4.42665039e+03 4.42397900e+03 4.42007373e+03 4.41396143e+03 4.41177588e+03 4.40898340e+03 4.40242090e+03 4.39713428e+03 4.39160742e+03 4.38283545e+03 4.37674316e+03 4.37449072e+03 4.37077686e+03 4.35868750e+03 4.35283105e+03 4.34745361e+03 4.33307227e+03 4.32674805e+03 4.32164209e+03 4.30994434e+03 4.29876953e+03 4.28944629e+03 4.28475879e+03 4.27291846e+03 4.25534570e+03 4.24652832e+03 4.23924121e+03 4.22624170e+03 4.21301904e+03 4.20704004e+03 4.19518848e+03 4.17741016e+03 4.16335400e+03 4149. 4.14174707e+03 4.12061670e+03 4.10939502e+03 4.09863672e+03 4.07774487e+03 4.06560132e+03 4.04973193e+03 4.03368604e+03 4.01918848e+03 4.00137866e+03 3.98693140e+03 3.97115137e+03 3.95127344e+03 3.93419263e+03 3.91804175e+03 3.90337964e+03 3.88388696e+03 3.86321606e+03 3.84971387e+03 3.82886182e+03 3.80362207e+03 3.78917676e+03 3.76834131e+03 3.75005005e+03 3.73084521e+03 3.70745605e+03 3.69656396e+03 3.66405786e+03 3.64311865e+03 3.63379321e+03 3.60300757e+03 3.58804419e+03 3.56213965e+03 3.53379175e+03 3.52053320e+03 3.50615723e+03 3.47426001e+03 3.44409546e+03 3.43198926e+03 3.41272803e+03 3.38434204e+03 3.36755078e+03 3.33966650e+03 3.31631519e+03 3.29709644e+03 3.26229688e+03 3.24814331e+03 3.22091919e+03 3.18495142e+03 3.16903564e+03 3.14196240e+03 3.12060815e+03 3.09186108e+03 3.06146191e+03 3.04365527e+03 3.01506274e+03 2.98853760e+03 2.96894507e+03 2.93996509e+03 2.91291235e+03 2.88840161e+03 2.87183813e+03 2.83512915e+03 2.80783350e+03 2.79179761e+03 2.76153296e+03 2.72399390e+03 2.70655127e+03 2.68105957e+03 2.64897412e+03 2.62808203e+03 2.59454590e+03 2.57414697e+03 2.55009302e+03 2.51691821e+03 2.48422852e+03 2.45990112e+03 2.43764355e+03 2.41730811e+03 2.38233398e+03 2.35518750e+03 2.32632812e+03 2.30186304e+03 2.26616431e+03 2.24194580e+03 2.22195215e+03 2.18746387e+03 2.16293262e+03 2.13768872e+03 2.11731177e+03 2.08851978e+03 2.04936230e+03 2.02840271e+03 2.00412134e+03 1.97244788e+03 1.94267346e+03 1.92091101e+03 1.89334448e+03 1.86647595e+03 1.84140173e+03 1.81246814e+03 1.78521204e+03 1.76104382e+03 1.72945166e+03 1.70522778e+03 1.68392236e+03 1.65356360e+03 1.62743213e+03 1.60517456e+03 1.57341248e+03 1.54341504e+03 1.52491687e+03 1.49987402e+03 1.47076868e+03 1.44336389e+03 1.42115259e+03 1.39568848e+03 1.36863464e+03 1.34816589e+03 1.32204675e+03 1.29359509e+03 1.26914685e+03 1.24501917e+03 1.22555908e+03 1.20045715e+03 1.17034265e+03 1.14753967e+03 1.12714648e+03 1.10215674e+03 1.07628040e+03 1.05226660e+03 1.03174194e+03 1.01255334e+03 9.87545776e+02 9.63877563e+02 9.41781006e+02 9.17357910e+02 8.96634521e+02 8.76173340e+02 8.52818298e+02 8.33010803e+02 8.11029114e+02 7.89992981e+02 7.70774109e+02 7.48728882e+02 7.28691040e+02 7.09370422e+02 6.88532837e+02 6.67897400e+02 6.49704224e+02 6.30888000e+02 6.12392944e+02 5.93974304e+02 5.74678101e+02 5.56563843e+02 5.39956665e+02 5.21206055e+02 5.02693909e+02 4.86576324e+02 4.69118958e+02 4.52723267e+02 4.37155304e+02 4.20809418e+02 4.04353149e+02 3.89170502e+02 3.74568787e+02 3.59101349e+02 3.44379974e+02 3.30158081e+02 3.15884064e+02 3.01768402e+02 2.88208008e+02 2.75009399e+02 2.62176239e+02 2.49494553e+02 3.16486053e+02 2.25265549e+02 2.69718414e+02 2.01583237e+02 1.90403427e+02 2.40209244e+02 1.69257370e+02 2.00495010e+02 1.48920166e+02 1.39304489e+02 1.29819672e+02 1.20777908e+02 1.12178566e+02 1.03852966e+02 9.57558136e+01 8.79626770e+01 8.05288391e+01 7.34749069e+01 6.67360764e+01 6.02368546e+01 5.41298523e+01 4.83633766e+01 4.28759193e+01 3.77179375e+01 3.29120560e+01 2.84374561e+01 2.42784996e+01 2.04636898e+01 1.69724140e+01 1.38116541e+01 1.09870367e+01 8.49081898e+00 6.32895470e+00 4.49888849e+00 3.00567985e+00 1.84481657e+00 1.01840508e+00 5.26882231e-01 3.69122535e-01 5.45873582e-01 1.05634987e+00 1.90074325e+00 3.07952523e+00 4.59270287e+00 6.44090605e+00 8.61942863e+00 1.11341314e+01 1.39785900e+01 1.71567650e+01 2.06661110e+01 2.44988918e+01 2.86796532e+01 3.31858940e+01 3.80061531e+01 4.31677017e+01 4.86529808e+01 5.44637947e+01 6.06244278e+01 6.70778732e+01 7.38787994e+01 8.09999542e+01 8.84718323e+01 9.62282867e+01 1.04181236e+02 1.12648285e+02 1.21424667e+02 1.30352722e+02 1.39620468e+02 1.49359695e+02 1.59546021e+02 1.69803818e+02 1.80129242e+02 1.90976669e+02 2.02350311e+02 2.14002380e+02 2.25503601e+02 2.37758270e+02 2.50304550e+02 2.62718414e+02 2.75738647e+02 2.89022583e+02 3.02743530e+02 3.16643066e+02 3.30792175e+02 3.45119293e+02 3.59774628e+02 3.74970856e+02 3.90023071e+02 4.05822662e+02 4.21439636e+02 4.37294800e+02 4.54206787e+02 4.71045044e+02 4.87455261e+02 5.04647430e+02 5.22053894e+02 5.39846924e+02 5.57652405e+02 5.75995911e+02 5.94798401e+02 6.13291992e+02 6.31757263e+02 6.50552795e+02 6.70520569e+02 6.90231506e+02 7.09774048e+02 7.30225769e+02 7.52186401e+02 7.69881165e+02 7.90303345e+02 8.13859497e+02 8.33865112e+02 8.55901855e+02 8.76188477e+02 8.96014160e+02 9.21480225e+02 9.44729736e+02 9.64947083e+02 9.84307678e+02 1.00866504e+03 1.03484253e+03 1.05620117e+03 1.08062671e+03 1.10373608e+03 1.12822498e+03 1.15421851e+03 1.17498145e+03 1.19877539e+03 1.22096606e+03 1.24503662e+03 1.27253442e+03 1.29658545e+03 1.32056787e+03 1.34662708e+03 1.36900085e+03 1.39800232e+03 1.42352869e+03 1.44616785e+03 1.47442786e+03 1.49563330e+03 1.52307910e+03 1.55336572e+03 1.57850439e+03 1.60044788e+03 1.62530688e+03 1.65911499e+03 1.68475000e+03 1.70129346e+03 1.73557080e+03 1.76430408e+03 1.78824731e+03 1.81602417e+03 1.84201270e+03 1.86623364e+03 1.89850342e+03 1.92055225e+03 1.94401172e+03 1.97503137e+03 2.00212329e+03 2.03434216e+03 2.05872681e+03 2.08234277e+03 2.11532715e+03 2.14163867e+03 2.16147095e+03 2.19000391e+03 2.22118555e+03 2.24506372e+03 2.27728857e+03 2.30252173e+03 2.34273511e+03 2.36390259e+03 2.37800732e+03 2.41641968e+03 2.44082861e+03 2.45968530e+03 2.48977344e+03 2.52376343e+03 2.54451001e+03 2.57362183e+03 2.60280151e+03 2.62833179e+03 2.65065771e+03 2.68185327e+03 2.70383618e+03 2.72964722e+03 2.77304175e+03 2.78535767e+03 2.81393311e+03 2.84923535e+03 2.85941577e+03 2.88531934e+03 2.91115527e+03 2.94606250e+03 2.97138916e+03 3.87417578e+03 7.22135645e+03 9.11361621e+03 44078104. -15727987. -38679024. -38679024. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -238509824. -5.71106250e+05 5.55787773e+04 1.17694131e+04 8.80162012e+03 4.65002832e+03 3.54332324e+03 3.56385156e+03 3.58237622e+03 3.60774585e+03 3.62942651e+03 3.64549658e+03 3.67547461e+03 3.69134546e+03 3.71439404e+03 3.73514600e+03 3.75252173e+03 3.76426025e+03 3.78637256e+03 3.80946436e+03 3.83022974e+03 3.85299780e+03 3.86544800e+03 3.88202466e+03 3.90672266e+03 3.91791479e+03 3.93678149e+03 3.95637085e+03 3.96653076e+03 3.98655322e+03 4.00618164e+03 4.02001367e+03 4.03057617e+03 4.04675854e+03 4.07132837e+03 4.08659131e+03 4.09763428e+03 4.11037109e+03 4.12170947e+03 4.14018506e+03 4.15105078e+03 4.16243994e+03 4.17909180e+03 4.19025732e+03 4.20429736e+03 4.21646387e+03 4.22868652e+03 4.23795410e+03 4.24983594e+03 4.26191553e+03 4.27320361e+03 4.28000781e+03 4.29153223e+03 4.30345850e+03 4.30706592e+03 4.31937549e+03 4.32843359e+03 4.33891162e+03 4.34812939e+03 4.34993457e+03 4.35907227e+03 4.37027686e+03 4.37511914e+03 4.37881396e+03 4.38564551e+03 4.39290088e+03 4.39643945e+03 4.40480566e+03 1.76627090e+04 1.20613740e+04 -841149056. -841149056. 2.93384730e+09 -1.40327725e+06 8.44561484e+04 1.31867832e+04 1.33715645e+04 1.31557500e+04 6.07088398e+04 1.61096289e+04 3.25122725e+06 -2.53036850e+06 0. 0. -1.39061035e+11 205564720. 5.44697188e+04 -4.73872753e+10 -2.19149394e+10 0. 0. -3.37702236e+10 5.27990078e+04 1.05704189e+04 6.61321094e+03 6.06850049e+03 5.70365332e+03 4.39197705e+03 4.38897461e+03 4.38482373e+03 4.37650098e+03 4.36949512e+03 4.36566162e+03 4.35882520e+03 4.34781787e+03 4.34339209e+03 4.33864600e+03 4.32700977e+03 4.31789307e+03 4.31091357e+03 4.30064600e+03 4.29151807e+03 4.28210059e+03 4.27193604e+03 4.26336621e+03 4.24831689e+03 4.23927490e+03 4.23098438e+03 4.21919385e+03 4.20650049e+03 4.19469580e+03 4.18336377e+03 4.16629688e+03 4.15829736e+03 4.14658496e+03 4.13162158e+03 4.11219482e+03 4.09672266e+03 4.08693018e+03 4.06899634e+03 4.05463940e+03 4.04233398e+03 4.03092285e+03 4.01332666e+03 3.99492603e+03 3.98010864e+03 3.95932788e+03 3.94097241e+03 3.92453613e+03 3.91297534e+03 3.89518604e+03 3.87329102e+03 3.85677026e+03 3.84035156e+03 3.81911865e+03 3.79995703e+03 3.78257617e+03 3.76199194e+03 3.73981226e+03 3.71695679e+03 3.70861353e+03 3.69158301e+03 3.65310547e+03 3.64062012e+03 3.62270459e+03 4.67418164e+03 4.91718945e+03 8.64654199e+03 1.14176143e+04 36263724. 26573638. 128097856. 128097856. 0. 0. -726943360. -726943360. -7.55927501e+09 -37418632. -37418632. 0. 0. 0. 0. 15684514. 3.34382825e+06 9.32095410e+03 7.38768848e+03 4.20271826e+03 3.94451172e+03 3.01335693e+03 2.98209546e+03 2.95533496e+03 2.93680908e+03 2.91519678e+03 2.88241187e+03 2.85667432e+03 2.84077661e+03 2.80201392e+03 2.77952002e+03 2.75673926e+03 2.72489795e+03 2.70352661e+03 2.67570337e+03 2.64552710e+03 2.61950073e+03 2.58857153e+03 2.56225562e+03 2.54595410e+03 2.50771875e+03 2.48537305e+03 2.45911450e+03 2.42737915e+03 2.40692944e+03 2.38249805e+03 2.34764453e+03 2.32133447e+03 2.30102197e+03 2.26474243e+03 2.24025220e+03 2.21575684e+03 2.19005811e+03 2.15910767e+03 2.13319263e+03 2.10867505e+03 2.08004028e+03 2.05003979e+03 2.02725098e+03 1.99778479e+03 1.96535986e+03 1.94325708e+03 1.91943054e+03 1.88845923e+03 1.86376807e+03 1.83893896e+03 1.80943274e+03 1.78249792e+03 1.75747046e+03 1.72586230e+03 1.70285486e+03 1.68117969e+03 1.64939575e+03 1.62533521e+03 1.59951672e+03 1.57255969e+03 1.54178259e+03 1.51606323e+03 1.49659058e+03 1.46778711e+03 1.44020532e+03 1.41695374e+03 1.39476404e+03 1.36461548e+03 1.34393860e+03 1.31734216e+03 1.29032104e+03 1.26840796e+03 1.24572632e+03 1.22061841e+03 1.19461279e+03 1.17167773e+03 1.14662280e+03 1.12162170e+03 1.09858582e+03 1.07390747e+03 1.05181506e+03 1.02999426e+03 1.00794202e+03 9.85234558e+02 9.63600281e+02 9.39804016e+02 9.16843201e+02 8.96784302e+02 8.73410034e+02 8.50872864e+02 8.31380981e+02 8.08354187e+02 7.88295410e+02 7.69440979e+02 7.47460327e+02 7.27501587e+02 7.07620300e+02 6.87653320e+02 6.66019470e+02 6.48254333e+02 6.29925049e+02 6.10434875e+02 5.92461243e+02 5.73489197e+02 5.55128357e+02 5.37878235e+02 5.20236816e+02 5.02655548e+02 4.85218445e+02 4.68001404e+02 4.52314331e+02 4.35978729e+02 4.19761047e+02 4.03988098e+02 3.88366241e+02 3.72962128e+02 3.58261597e+02 3.43484283e+02 3.28840179e+02 3.14953766e+02 3.01262787e+02 2.87737793e+02 2.74342743e+02 2.61389343e+02 2.48851852e+02 2.36523621e+02 2.24327484e+02 2.12681366e+02 2.01072021e+02 1.89793076e+02 1.79052475e+02 1.68652435e+02 1.58275162e+02 1.48372330e+02 1.38821152e+02 1.29356918e+02 1.20453209e+02 1.11741783e+02 1.03374908e+02 9.53887787e+01 8.75671692e+01 8.01902466e+01 7.31646423e+01 6.63839722e+01 5.99319649e+01 5.37701340e+01 4.80348091e+01 4.25767975e+01 3.74238396e+01 3.26391373e+01 2.81600761e+01 2.40078106e+01 2.02018280e+01 1.67076054e+01 1.35524426e+01 1.07337408e+01 8.23925877e+00 6.07994366e+00 4.25346518e+00 2.76073027e+00 1.60098827e+00 7.74417460e-01 2.81493604e-01 1.22138642e-01 2.96430022e-01 8.04249346e-01 1.64554834e+00 2.82032704e+00 4.32793427e+00 6.16995811e+00 8.34404469e+00 1.08501024e+01 1.36886024e+01 1.68599491e+01 2.03594151e+01 2.41841888e+01 2.83513126e+01 3.28448906e+01 3.76517944e+01 4.28018188e+01 4.82709427e+01 5.40868073e+01 6.02315674e+01 6.66339645e+01 7.34328308e+01 8.05739136e+01 8.80058746e+01 9.56995392e+01 1.32160614e+02 1.48746414e+02 1.81822571e+02 1.95394791e+02 2.09162720e+02 2.23629120e+02 2.38697739e+02 2.54064331e+02 2.69834076e+02 2.86320618e+02 3.03176208e+02 3.20324341e+02 3.37639984e+02 3.56006897e+02 3.74833862e+02 3.93589935e+02 4.12761169e+02 4.32826111e+02 4.22919617e+02 4.73532196e+02 4.43797058e+02 5.16917175e+02 4.98782623e+02 4.92409088e+02 3.89108246e+02 4.04681885e+02 4.20168182e+02 4.36580048e+02 4.52951904e+02 4.69477844e+02 4.86267365e+02 5.02865570e+02 5.21019409e+02 5.38907043e+02 5.56010071e+02 5.74041870e+02 5.92648010e+02 6.10926208e+02 6.30119934e+02 6.50483154e+02 6.68106506e+02 6.87958313e+02 7.08237244e+02 7.29072083e+02 7.50520996e+02 7.68810608e+02 7.87917053e+02 8.10383484e+02 8.32243103e+02 8.52748291e+02 8.72888184e+02 8.95317932e+02 9.19012451e+02 9.41817444e+02 9.64235596e+02 9.82686584e+02 1.00512219e+03 1.03179736e+03 1.05508472e+03 1.07742383e+03 1.10072192e+03 1.12523608e+03 1.15145569e+03 1.17241357e+03 1.19577563e+03 1.21833130e+03 1.24174573e+03 1.27049255e+03 1.29348669e+03 1.31931384e+03 1.34203931e+03 1.36767639e+03 1.39444653e+03 1.41938733e+03 1.44818542e+03 1.46901245e+03 1.49256311e+03 1.52357715e+03 1.54681018e+03 1.57293420e+03 1.59953735e+03 1.62264795e+03 1.65147192e+03 1.67958655e+03 1.70151855e+03 1.73223254e+03 1.75912671e+03 1.78316614e+03 1.81261658e+03 1.83474280e+03 1.86044177e+03 1.89666028e+03 1.91508496e+03 1.94449438e+03 1.97203101e+03 1.99627173e+03 2.02622180e+03 2.05382007e+03 2.07671973e+03 2.10488647e+03 2.13570117e+03 2.15960229e+03 2.18860303e+03 2.21941992e+03 2.23978784e+03 2.26717505e+03 2.29828198e+03 2.33070825e+03 2.35216431e+03 2.38066333e+03 2.40917944e+03 2.43495508e+03 2.45832080e+03 2.48899365e+03 2.51979370e+03 2.54070752e+03 2.56629077e+03 2.59561890e+03 2.62109399e+03 2.64393652e+03 2.67798291e+03 2.69439038e+03 2.72299878e+03 2.76690015e+03 2.78424219e+03 2.80977954e+03 2.83704419e+03 2.86046802e+03 2.87743408e+03 2.90575708e+03 2.94411450e+03 2.96233081e+03 2.97724414e+03 3.01190259e+03 3.04727051e+03 3.05857471e+03 3.09149976e+03 3.11089380e+03 3.13116528e+03 3.15884033e+03 3.19188110e+03 3.21734985e+03 3.23975635e+03 3.25940234e+03 3.28509985e+03 3.30877515e+03 3.33011548e+03 3.35191919e+03 3.37305835e+03 3.40277710e+03 3.42676489e+03 3.44818799e+03 3.47315332e+03 3.49153198e+03 3.50877295e+03 3.53919214e+03 3.56407300e+03 3.58219482e+03 3.60072583e+03 3.61676611e+03 3.64217676e+03 3.66729712e+03 3.68201416e+03 3.70391431e+03 3.72465894e+03 3.74296411e+03 3.75418628e+03 3.77640771e+03 3.80552856e+03 3.82458374e+03 3.84346387e+03 3.85613696e+03 3.87138550e+03 3.89836011e+03 3.91230322e+03 3.92174341e+03 3.94083350e+03 3.95808594e+03 3.98502148e+03 3.99726050e+03 4.00868091e+03 4.02819971e+03 4.03953833e+03 4.05351855e+03 4.07791626e+03 4.09012671e+03 4.09862402e+03 4.11618213e+03 4.13115723e+03 4.14527197e+03 4.15502734e+03 4.16917334e+03 4.18320264e+03 4.19381934e+03 4.20618213e+03 4.22095215e+03 4.23211133e+03 4.23907275e+03 4.25037256e+03 4.26490674e+03 4.27129688e+03 4.28348096e+03 4.29493701e+03 4.29898682e+03 4.31100195e+03 4.32019824e+03 4.32709619e+03 4.33799121e+03 4.34068604e+03 4.34908545e+03 4.36336816e+03 4.36586230e+03 4.36731885e+03 4.37341357e+03 4.38407129e+03 4.38890820e+03 4.39139062e+03 4.39986670e+03 4.40387598e+03 4.40658984e+03 4.41137939e+03 4.41371143e+03 4.41768994e+03 4.42116797e+03 4.42286426e+03 4.42545801e+03 4.42600244e+03 4.42788721e+03 4.42942871e+03 4.43010059e+03 4.43078076e+03 4.43086816e+03 4.43067139e+03 4.42986572e+03 4.42936670e+03 4.42814600e+03 4.42597119e+03 4.42434912e+03 4.42303809e+03 4.42124805e+03 4.41708203e+03 4.41524463e+03 4.41160596e+03 4.40575293e+03 4.40299170e+03 4.39881201e+03 4.39142285e+03 4.38881055e+03 4.38452490e+03 4.37341455e+03 4.36785693e+03 4.36675732e+03 4.36047314e+03 4.34763037e+03 4.34265088e+03 4.33900781e+03 4.32693701e+03 4.31856934e+03 4.31076074e+03 4.29940869e+03 4.29282373e+03 4.28126807e+03 4.27022021e+03 4.26328857e+03 4.24748340e+03 4.24108105e+03 4.22930615e+03 4.21841504e+03 4.20838525e+03 4.19308691e+03 4.18220264e+03 4.16793604e+03 4.15539844e+03 4.14619922e+03 4.13035645e+03 4.11340576e+03 4.10138037e+03 4.08763208e+03 4.07013843e+03 4.05701050e+03 4.04273804e+03 4.02728394e+03 4.01396094e+03 3.99521777e+03 3.97994971e+03 3.96256812e+03 3.94529712e+03 3.92020117e+03 3.91161865e+03 3.90016089e+03 3.87538110e+03 3.85376050e+03 3.84055566e+03 3.81542847e+03 3.79866772e+03 3.78481372e+03 3.75897339e+03 3.73650146e+03 3.72302856e+03 3.70755103e+03 3.69288940e+03 3.65956030e+03 3.63762622e+03 3.62101709e+03 3.60150464e+03 3.57534106e+03 3.54972852e+03 3.53610693e+03 3.51122534e+03 3.49527832e+03 3.47124780e+03 3.43654443e+03 3.42154712e+03 3.40856738e+03 3.37805518e+03 3.35008301e+03 3.32826831e+03 3.31325439e+03 3.29330005e+03 3.25651099e+03 3.23929541e+03 3.20548999e+03 3.18114673e+03 3.16258984e+03 3.13492603e+03 3.11948926e+03 3.08856030e+03 3.05979199e+03 3.03498901e+03 3.01496143e+03 2.98812671e+03 2.96124902e+03 2.93678662e+03 2.90341382e+03 2.87531543e+03 2.85995166e+03 2.83726538e+03 2.80476880e+03 2.77989233e+03 2.75712817e+03 2.72055835e+03 2.70054907e+03 2.67700830e+03 2.64574268e+03 2.62454004e+03 2.58798315e+03 2.56121045e+03 2.54340112e+03 2.51210620e+03 2.48884253e+03 2.45507227e+03 2.42903052e+03 2.40880103e+03 2.38196265e+03 2.34865869e+03 2.32282104e+03 2.29999707e+03 2.26567920e+03 2.23611816e+03 2.21855298e+03 2.18781958e+03 2.15804712e+03 2.13362134e+03 2.10993457e+03 2.08077026e+03 2.04985376e+03 2.02463538e+03 1.99714111e+03 1.96736353e+03 1.94274634e+03 1.91728210e+03 1.89209692e+03 1.86104614e+03 1.83510315e+03 1.81216724e+03 1.78216052e+03 1.75653528e+03 1.72515137e+03 1.70105701e+03 1.68204883e+03 1.65264331e+03 1.62305664e+03 1.60007446e+03 1.57131738e+03 1.54360950e+03 1.52128381e+03 1.49789661e+03 1.46764758e+03 1.43998865e+03 1.41720557e+03 1.39358459e+03 1.36600098e+03 1.34190540e+03 1.31771460e+03 1.28964111e+03 1.26960181e+03 1.24398303e+03 1.22061292e+03 1.19546387e+03 1.16951489e+03 1.14767090e+03 1.12345691e+03 1.09994214e+03 1.07420215e+03 1.05114453e+03 1.03071448e+03 1.00737488e+03 9.84079651e+02 9.62919922e+02 9.40131653e+02 9.15471130e+02 8.95234924e+02 8.74923706e+02 8.52682312e+02 8.30139709e+02 8.08304199e+02 7.88688049e+02 7.69017761e+02 7.46974854e+02 7.27673035e+02 7.07588013e+02 6.87014160e+02 6.65929565e+02 6.47783447e+02 6.30282410e+02 6.11228455e+02 5.92561523e+02 5.72936218e+02 5.55295105e+02 5.38127136e+02 5.20016907e+02 5.01747589e+02 4.85191772e+02 4.67981415e+02 4.52361298e+02 4.36230988e+02 4.19594055e+02 4.03708069e+02 3.88271454e+02 3.73156464e+02 3.58100647e+02 3.43434296e+02 3.29143311e+02 3.15120514e+02 3.00994019e+02 2.87370636e+02 2.74283661e+02 2.61578033e+02 2.48774170e+02 4.70980804e+02 3.19083069e+02 4.92131683e+02 3.01581818e+02 2.85009460e+02 4.45423676e+02 2.53231232e+02 3.64746796e+02 2.23034973e+02 2.08551865e+02 1.94289658e+02 1.59569305e+02 1.67621490e+02 1.03469147e+02 1.22385872e+02 8.76188507e+01 8.01663971e+01 7.31584244e+01 6.64045792e+01 5.99115334e+01 5.37840042e+01 4.80382805e+01 4.25800400e+01 3.74269829e+01 3.26304932e+01 2.81598511e+01 2.40077553e+01 2.01942883e+01 1.67069969e+01 1.35546894e+01 1.07319431e+01 8.23888016e+00 6.08033705e+00 4.25300694e+00 2.76042604e+00 1.60068202e+00 7.74050176e-01 2.81196475e-01 1.21801578e-01 2.96081334e-01 8.03864658e-01 1.64532542e+00 2.81997514e+00 4.32774401e+00 6.16920805e+00 8.34341335e+00 1.08505688e+01 1.36875772e+01 1.68580914e+01 2.03593349e+01 2.41869164e+01 2.83568916e+01 3.28391075e+01 3.76427612e+01 4.28086014e+01 4.82877274e+01 5.40778503e+01 6.02058601e+01 6.66477814e+01 7.34582596e+01 8.05368958e+01 8.79817047e+01 9.57423706e+01 1.03723160e+02 1.12116676e+02 1.20879128e+02 1.29795044e+02 1.39054947e+02 1.48733337e+02 1.58769516e+02 1.69085037e+02 1.79499130e+02 1.90357590e+02 2.01582199e+02 2.13149048e+02 2.24889481e+02 2.36959259e+02 2.49403549e+02 2.61957428e+02 2.74933990e+02 2.88196960e+02 3.01789032e+02 3.15787445e+02 3.29774475e+02 3.44211578e+02 3.58682678e+02 3.73703430e+02 3.89244324e+02 4.04635620e+02 4.20065216e+02 4.36536682e+02 4.52700195e+02 4.69462372e+02 4.86489746e+02 5.02712067e+02 5.20943298e+02 5.38954407e+02 5.55937744e+02 5.74102966e+02 5.92803284e+02 6.11385071e+02 6.30147034e+02 6.49454468e+02 6.68588928e+02 6.87032654e+02 7.07401978e+02 7.29052856e+02 7.50409729e+02 7.67830750e+02 7.87911621e+02 8.10947632e+02 8.32588684e+02 8.52647034e+02 8.72568726e+02 8.96202881e+02 9.18438660e+02 9.42565125e+02 9.64212463e+02 9.82777466e+02 1.00531512e+03 1.03196729e+03 1.05429846e+03 1.07762537e+03 1.10105420e+03 1.12585034e+03 1.15142676e+03 1.17234753e+03 1.19787720e+03 1.21829761e+03 1.24095496e+03 1.27032812e+03 1.29316504e+03 1.31751306e+03 1.34387341e+03 1.36709412e+03 1.39436084e+03 1.41877881e+03 1.44589270e+03 1.46963403e+03 1.49219470e+03 1.51953479e+03 1.54553113e+03 1.57347021e+03 1.59873181e+03 1.62328503e+03 1.65037988e+03 1.68275952e+03 1.70102283e+03 1.72896667e+03 1.75884766e+03 1.78687256e+03 1.81482556e+03 1.83524902e+03 1.85921008e+03 1.89386951e+03 1.91797559e+03 1.94573645e+03 1.97027417e+03 1.99689490e+03 2.02837891e+03 2.05415015e+03 2.07934180e+03 2.10472388e+03 2.14002295e+03 2.15998560e+03 2.18659473e+03 2.22174756e+03 2.24023364e+03 2.26869678e+03 2.29834351e+03 2.32766162e+03 2.35329126e+03 2.37897827e+03 2.40810083e+03 2.43974585e+03 2.45681250e+03 2.48389355e+03 2.51509961e+03 2.53719067e+03 2.56398120e+03 2.59964307e+03 2.62462964e+03 2.64169141e+03 2.67264282e+03 2.69625854e+03 2.72312744e+03 2.76411890e+03 2.78475830e+03 2.80563159e+03 3.68241260e+03 3.86514746e+03 4.31034814e+03 4.35926318e+03 4.41101123e+03 4.44265625e+03 4.12315479e+03 6.03084619e+03 4.12809277e+03 7.18142920e+03 9.38211328e+03 22916850. -193381408. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -208075552. 3.96340078e+04 7.55511816e+03 3.53344043e+03 4.64636768e+03 3.57811060e+03 3.60151221e+03 3.61733716e+03 3.64361377e+03 3.66530933e+03 3.68268677e+03 3.70842432e+03 3.72703076e+03 3.74417798e+03 3.75251172e+03 3.77981567e+03 3.80511938e+03 3.82183423e+03 3.84315820e+03 3.85409399e+03 3.87445581e+03 3.89658301e+03 3.91080225e+03 3.92665332e+03 3.94619214e+03 3.96069287e+03 3.98372339e+03 3.99832349e+03 4.01091675e+03 4.02865869e+03 4.03786938e+03 4.05533228e+03 4.07619092e+03 4.09161279e+03 4.09827734e+03 4.11339111e+03 4.13251074e+03 4.14510156e+03 4.15671436e+03 4.17073926e+03 4.18222998e+03 4.19222900e+03 4.20539160e+03 4.22027002e+03 4.23310547e+03 4.23972949e+03 4.25180469e+03 4.26286426e+03 4.26967725e+03 4.28283008e+03 4.29453564e+03 4.29888379e+03 4.31204004e+03 4.31889355e+03 4.32729248e+03 4.33891553e+03 4.34087207e+03 4.34890283e+03 4.36191406e+03 4.36639551e+03 4.37050879e+03 4.37462305e+03 4.38196387e+03 4.38897021e+03 4.39389941e+03 1.75933262e+04 833628736. 0. 0. 0. 0. 0. 9.61959014e+09 9.61959014e+09 9.61959014e+09 0. 0. 0. 0. 0. 0. -1.39061035e+11 205564720. 5.05868945e+04 5.33395703e+04 5.79706172e+04 3.47728282e+11 0. 0. -4.13566464e+09 4287712. 4.63349414e+04 1.33005176e+04 1.04844209e+04 6.58437500e+03 6.57946289e+03 6.00986523e+03 6.56044531e+03 4.37296777e+03 6.54714062e+03 5.99134326e+03 6.51700244e+03 6.51192871e+03 6.50453369e+03 6.48943115e+03 6.47354639e+03 6.46032422e+03 6.44257959e+03 6.43543066e+03 6.42461768e+03 6.39983203e+03 6.38885840e+03 6.37432861e+03 6.36101074e+03 6.34037646e+03 5.79286328e+03 6.31191504e+03 5.77758057e+03 6.26360400e+03 6.25248340e+03 6.23967480e+03 6.20754883e+03 6.18632666e+03 6.17890527e+03 6.14940430e+03 6.12476709e+03 6.09570166e+03 6.07660303e+03 6.06709570e+03 6.04676221e+03 6.01271045e+03 5.98552686e+03 5.96373682e+03 5.94385352e+03 5.39253223e+03 5.09868311e+03 3.91255273e+03 3.89284473e+03 3.87525513e+03 3.86234424e+03 3.84124854e+03 3.82173267e+03 3.80176782e+03 3.78660303e+03 3.77025903e+03 3.74447852e+03 3.71646973e+03 3.70737988e+03 3.69464209e+03 4.76182715e+03 5.01081104e+03 5.43557666e+03 8.68987598e+03 1.09049990e+04 -95029064. -151390144. 0. 128097856. 128097856. 128097856. 0. 0. -726943360. -726943360. -726943360. 0. 0. 0. 0. 0. -13582847. 3.73656367e+04 7.49295312e+03 4.25620850e+03 4.00936377e+03 3.06767432e+03 3.03923926e+03 3.01297266e+03 2.98995776e+03 3.84245776e+03 4.02816528e+03 4.37390869e+03 4.32118213e+03 4.27941260e+03 4.25400488e+03 4.20005811e+03 3.79735156e+03 3.58745874e+03 2.72919287e+03 2.70089380e+03 2.67526172e+03 2.65247925e+03 2.62650830e+03 2.59080493e+03 2.56569043e+03 2.54079688e+03 2.51321167e+03 2.48702686e+03 2.46699683e+03 2.43170972e+03 2.40437402e+03 2.38268481e+03 2.34898999e+03 2.32131665e+03 2.29789746e+03 2.26201538e+03 2.24682104e+03 2.21617920e+03 2.18704370e+03 2.15893506e+03 2.13715259e+03 2.10899805e+03 2.08200171e+03 2.04652539e+03 2.02692224e+03 2.00134021e+03 1.97058337e+03 1.94309412e+03 1.91704834e+03 1.89242859e+03 1.86408850e+03 1.83656982e+03 1.81151355e+03 1.78409009e+03 1.75698315e+03 1.72739417e+03 1.70542468e+03 1.68066455e+03 1.65140515e+03 1.62616614e+03 1.59989197e+03 1.57140808e+03 1.54767896e+03 1.51837402e+03 1.49580432e+03 1.47328394e+03 1.44316138e+03 1.41704382e+03 1.39495850e+03 1.36915723e+03 1.34147864e+03 1.31760645e+03 1.28854553e+03 1.26842834e+03 1.24656519e+03 1.22076611e+03 1.19603955e+03 1.17040540e+03 1.14522131e+03 1.12286328e+03 1.09902441e+03 1.07479236e+03 1.05298596e+03 1.03028613e+03 1.00695941e+03 9.85300110e+02 9.62334961e+02 9.40009949e+02 9.17343079e+02 8.96627563e+02 8.75371643e+02 8.51693970e+02 8.30317444e+02 8.09485535e+02 7.89412415e+02 7.69994690e+02 7.47848694e+02 7.26928528e+02 7.08102112e+02 6.88659363e+02 6.67924133e+02 6.48346680e+02 6.30558716e+02 6.10925476e+02 5.92374756e+02 5.74602844e+02 5.55477051e+02 5.37433777e+02 5.20621582e+02 5.03005310e+02 4.85482483e+02 4.69221710e+02 4.52694580e+02 4.35664185e+02 4.19643250e+02 4.04530670e+02 3.88700378e+02 3.72971985e+02 3.58569061e+02 3.43823639e+02 3.29133240e+02 3.15014923e+02 3.01523712e+02 2.88262939e+02 2.74512207e+02 2.61336609e+02 2.48961731e+02 2.36741989e+02 2.24462280e+02 2.12842331e+02 2.01410263e+02 1.89841354e+02 1.79097351e+02 1.68817017e+02 1.58483170e+02 1.48414871e+02 1.38857010e+02 1.29572235e+02 1.20621902e+02 1.11849625e+02 1.03456558e+02 9.54765778e+01 8.76956177e+01 8.03348083e+01 7.32310562e+01 6.64365463e+01 6.00394173e+01 5.38823738e+01 4.80941353e+01 4.26570053e+01 3.75232964e+01 3.27287674e+01 2.82413654e+01 2.40781040e+01 2.02749100e+01 1.67856998e+01 1.36295395e+01 1.08094196e+01 8.31477928e+00 6.15744925e+00 4.32996893e+00 2.83802080e+00 1.67939508e+00 8.54049027e-01 3.62608165e-01 2.04811543e-01 3.80864650e-01 8.90913963e-01 1.73473954e+00 2.91189241e+00 4.42226267e+00 6.26552486e+00 8.44424725e+00 1.09555578e+01 1.37927599e+01 1.69675388e+01 2.04784660e+01 2.43239059e+01 2.85081940e+01 3.29608383e+01 3.77641296e+01 4.29400330e+01 4.84252129e+01 5.42287750e+01 7.85590439e+01 9.29739761e+01 1.00595261e+02 1.04542015e+02 8.81373367e+01 9.58697739e+01 1.26502892e+02 1.37058899e+02 1.81512527e+02 1.95163132e+02 2.09118164e+02 2.23407074e+02 2.38559601e+02 2.54003265e+02 2.69730469e+02 2.86351227e+02 3.03234100e+02 3.20253448e+02 3.37548340e+02 3.55503601e+02 3.74504669e+02 3.94104950e+02 4.13137085e+02 4.32548615e+02 3.76755676e+02 4.73982056e+02 4.04427673e+02 5.17029541e+02 4.47407410e+02 4.63808990e+02 3.89608063e+02 4.05464813e+02 4.20650269e+02 4.36558624e+02 4.53140717e+02 4.70028351e+02 4.86439117e+02 5.03729675e+02 5.21663513e+02 5.38962402e+02 5.56644226e+02 5.75379639e+02 5.93322266e+02 6.10827637e+02 6.30415039e+02 6.50744751e+02 6.69617310e+02 6.88489441e+02 7.09311218e+02 7.28874023e+02 7.51026917e+02 7.69608887e+02 7.88600891e+02 8.12060852e+02 8.32620605e+02 8.51960693e+02 8.74064758e+02 8.96268311e+02 9.19431396e+02 9.43033936e+02 9.63147827e+02 9.84066223e+02 1.00820929e+03 1.03268201e+03 1.05594727e+03 1.07655603e+03 1.10126306e+03 1.12664258e+03 1.15135815e+03 1.17396436e+03 1.19566846e+03 1.21850586e+03 1.24526416e+03 1.27135388e+03 1.29151025e+03 1.31975647e+03 1.34353674e+03 1.36964246e+03 1.39654797e+03 1.41951245e+03 1.44760803e+03 1.46847681e+03 1.49619519e+03 1.52408362e+03 1.54711511e+03 1.57177283e+03 1.59792236e+03 1.62691431e+03 1.65614722e+03 1.68242236e+03 1.70251599e+03 1.73187231e+03 1.76083740e+03 1.78479907e+03 1.81385840e+03 1.83584351e+03 1.86364062e+03 1.89628381e+03 1.91793567e+03 1.94828638e+03 1.97499170e+03 1.99666345e+03 2.02634082e+03 2.05644312e+03 2.07648462e+03 2.10882642e+03 2.14125952e+03 2.15877856e+03 2.19385669e+03 2.22038037e+03 2.23781982e+03 2.27165479e+03 2.30266943e+03 2.33200879e+03 2.35570435e+03 2.37370264e+03 2.40927148e+03 2.43907935e+03 2.46054248e+03 2.48893750e+03 2.51356812e+03 2.54651880e+03 2.57569580e+03 2.59559180e+03 2.62578613e+03 2.65135425e+03 2.68166992e+03 2.70191748e+03 2.73151123e+03 2.75851221e+03 2.78172461e+03 2.80919312e+03 2.83567456e+03 2.85748633e+03 2.88770410e+03 2.91039917e+03 2.94125513e+03 2.95914771e+03 2.98596973e+03 3.01939429e+03 3.04862598e+03 3.06513940e+03 3.08943213e+03 3.11559009e+03 3.12743872e+03 3.16400659e+03 3.19652344e+03 3.21177783e+03 3.24000220e+03 3.26372461e+03 3.28524048e+03 3.30815308e+03 3.33359644e+03 3.35211182e+03 3.38078516e+03 3.40306592e+03 3.42463696e+03 3.44983911e+03 3.47106885e+03 3.49557373e+03 3.51252075e+03 3.53719604e+03 3.57035449e+03 3.58418115e+03 3.59714233e+03 3.61954102e+03 3.64616602e+03 3.66817578e+03 3.68513208e+03 3.70534375e+03 3.72292993e+03 3.74781689e+03 3.76456445e+03 3.78004492e+03 3.80822510e+03 3.82394141e+03 3.84210938e+03 3.86323169e+03 3.87237793e+03 3.89632690e+03 3.91637451e+03 3.93013940e+03 3.94609912e+03 3.96622705e+03 3.98494043e+03 3.99635352e+03 4.00679419e+03 4.03187061e+03 4.04541528e+03 4.05610522e+03 4.08075537e+03 4.09213354e+03 4.10050537e+03 4.11843115e+03 4.13310938e+03 4.14975830e+03 4.15899268e+03 4.16935596e+03 4.18430322e+03 4.19821680e+03 4.20877783e+03 4.22370898e+03 4.23874902e+03 4.24002686e+03 4.25156787e+03 4.26828516e+03 4.27578955e+03 4.28359131e+03 4.29526611e+03 4.30586133e+03 4.31691992e+03 4.32283838e+03 4.32752686e+03 4.33878711e+03 4.34563574e+03 4.35416113e+03 4.36314893e+03 4.36603857e+03 4.37336426e+03 4.37903955e+03 4.38489062e+03 4.39168311e+03 4.39689600e+03 4.40263037e+03 4.40567285e+03 4.40873145e+03 4.41419824e+03 4.41628467e+03 4.42139453e+03 4.42442236e+03 4.42532715e+03 4.42831006e+03 4.42859277e+03 4.43089160e+03 4.43249316e+03 4.43285303e+03 4.43363818e+03 4.43376855e+03 4.43359229e+03 4.43275488e+03 4.43216992e+03 4.43124268e+03 4.42895996e+03 4.42673438e+03 4.42621143e+03 4.42404297e+03 4.41966895e+03 4.41745264e+03 4.41480518e+03 4.41092725e+03 4.40516943e+03 4.39994873e+03 4.39511768e+03 4.39111084e+03 4.38807227e+03 4.37819238e+03 4.37078857e+03 4.36899463e+03 4.36118018e+03 4.35118799e+03 4.34516650e+03 4.34044678e+03 4.33133496e+03 4.32126416e+03 4.30990674e+03 4.30152881e+03 4.29683887e+03 4.28764551e+03 4.27401660e+03 4.26224219e+03 4.25350830e+03 4.24826074e+03 4.23171777e+03 4.22011377e+03 4.21329443e+03 4.19292725e+03 4.18062158e+03 4.17297900e+03 4.15962012e+03 4.14478613e+03 4.13138965e+03 4.11717969e+03 4.10183691e+03 4.09089380e+03 4.07276440e+03 4.06135352e+03 4.04872534e+03 4.03324268e+03 4.01005347e+03 3.99470337e+03 3.97922681e+03 3.96241553e+03 3.94818457e+03 3.92722485e+03 3.91517896e+03 3.89725537e+03 3.87730005e+03 3.86107690e+03 3.84010132e+03 3.82075659e+03 3.80090356e+03 3.78761719e+03 3.76527271e+03 3.74079785e+03 3.72649609e+03 3.70515210e+03 3.69038232e+03 3.66470386e+03 3.63647607e+03 3.62751270e+03 3.60469141e+03 3.57156812e+03 3.55152417e+03 3.53875122e+03 3.51332056e+03 3.49957764e+03 3.46968848e+03 3.44091650e+03 3.42472583e+03 3.40923145e+03 3.38130176e+03 3.35133203e+03 3.33192310e+03 3.31626245e+03 3.29127344e+03 3.26451074e+03 3.23866626e+03 3.20503735e+03 3.18759619e+03 3.16182056e+03 3.13178931e+03 3.11805029e+03 3.08642188e+03 3.06272778e+03 3.04077832e+03 3.01555127e+03 2.99137378e+03 2.95706763e+03 2.94217090e+03 2.91011719e+03 2.88255371e+03 2.85813672e+03 2.83073486e+03 2.80785791e+03 2.78592334e+03 2.76018018e+03 2.72296973e+03 2.70031812e+03 2.68359229e+03 2.64854224e+03 2.62131885e+03 2.59105859e+03 2.56731079e+03 2.54518433e+03 2.51238403e+03 2.48810815e+03 2.46348999e+03 2.43368701e+03 2.40980713e+03 2.38287573e+03 2.34706885e+03 2.32103223e+03 2.30248120e+03 2.26413330e+03 2.24459399e+03 2.21665820e+03 2.18283252e+03 2.16397144e+03 2.13828613e+03 2.11454126e+03 2.08106714e+03 2.05188770e+03 2.02498389e+03 2.00224768e+03 1.97150342e+03 1.94525464e+03 1.91744666e+03 1.89498315e+03 1.86464209e+03 1.83438489e+03 1.81328491e+03 1.78218469e+03 1.75879443e+03 1.72921143e+03 1.70394263e+03 1.67822705e+03 1.65196301e+03 1.62491943e+03 1.59742749e+03 1.57368652e+03 1.54784045e+03 1.52221814e+03 1.49702649e+03 1.46849792e+03 1.44238770e+03 1.42038281e+03 1.39645276e+03 1.36723059e+03 1.34217249e+03 1.31823889e+03 1.29053650e+03 1.26967310e+03 1.24532849e+03 1.22018164e+03 1.19581421e+03 1.17083813e+03 1.14712183e+03 1.12442432e+03 1.09923840e+03 1.07518274e+03 1.05308960e+03 1.03076782e+03 1.00763892e+03 9.84000427e+02 9.61556091e+02 9.41119690e+02 9.17055969e+02 8.95843445e+02 8.76142883e+02 8.53001831e+02 8.29485352e+02 8.08874207e+02 7.89719299e+02 7.68898682e+02 7.47779663e+02 7.27220520e+02 7.07551819e+02 6.88885925e+02 6.67965637e+02 6.48178101e+02 6.30383179e+02 6.11739136e+02 5.92338501e+02 5.74050171e+02 5.55599915e+02 5.37713440e+02 5.20686218e+02 5.02898193e+02 4.85575867e+02 4.68942078e+02 4.52616669e+02 4.36085480e+02 4.19565033e+02 4.04066376e+02 3.88300842e+02 3.73191650e+02 3.58596222e+02 3.43810913e+02 3.29295593e+02 3.15089752e+02 3.01270142e+02 2.87897614e+02 2.74532623e+02 2.61557129e+02 2.49029251e+02 4.71964996e+02 2.81957214e+02 4.99418976e+02 3.02073273e+02 2.85293121e+02 4.42211975e+02 2.53225677e+02 3.70341248e+02 2.22542801e+02 2.08319412e+02 1.94380905e+02 1.47351791e+02 1.67753174e+02 1.03627159e+02 1.16408920e+02 8.77948990e+01 8.02323151e+01 7.32881165e+01 6.65964050e+01 6.00039177e+01 5.38738556e+01 4.81012573e+01 4.26823463e+01 3.74781914e+01 3.26125298e+01 2.82648506e+01 2.42080154e+01 2.02959976e+01 1.67942829e+01 1.36367035e+01 1.08112907e+01 8.31589222e+00 6.15766668e+00 4.33129025e+00 2.83888531e+00 1.68075895e+00 8.55416059e-01 3.63519996e-01 2.05604538e-01 3.81633371e-01 8.91774058e-01 1.73550475e+00 2.91212368e+00 4.42232418e+00 6.26681376e+00 8.44580936e+00 1.09545403e+01 1.37931442e+01 1.69685822e+01 2.04742260e+01 2.43154736e+01 2.84780979e+01 3.29588928e+01 3.77821846e+01 4.29463692e+01 4.84413147e+01 5.42403641e+01 6.03485336e+01 6.68076172e+01 7.36057739e+01 8.07016296e+01 8.81563187e+01 9.59088516e+01 1.03947128e+02 1.12310104e+02 1.20993576e+02 1.30032135e+02 1.39309494e+02 1.49006271e+02 1.59037308e+02 1.69256775e+02 1.79798615e+02 1.90709366e+02 2.01895493e+02 2.13403931e+02 2.25247406e+02 2.37037979e+02 2.49515350e+02 2.62208984e+02 2.75283447e+02 2.88562073e+02 3.02217468e+02 3.16028442e+02 3.29926422e+02 3.44747986e+02 3.59184631e+02 3.73998474e+02 3.89771027e+02 4.05528717e+02 4.20607697e+02 4.36314484e+02 4.52988617e+02 4.70184631e+02 4.87033142e+02 5.03790619e+02 5.21408325e+02 5.39026489e+02 5.57026489e+02 5.75378479e+02 5.92791931e+02 6.11826721e+02 6.30598816e+02 6.50470032e+02 6.69955505e+02 6.88550293e+02 7.08049133e+02 7.29432800e+02 7.51426514e+02 7.68934448e+02 7.88154663e+02 8.12612854e+02 8.33693237e+02 8.51984863e+02 8.73588257e+02 8.96614746e+02 9.19322083e+02 9.43898071e+02 9.63879517e+02 9.83991699e+02 1.00740051e+03 1.03243811e+03 1.05462292e+03 1.07742969e+03 1.10311865e+03 1.12763452e+03 1.15071765e+03 1.17240466e+03 1.19747925e+03 1.21988123e+03 1.24374670e+03 1.26911487e+03 1.29265710e+03 1.32082654e+03 1.34428699e+03 1.36964563e+03 1.39718726e+03 1.41859155e+03 1.44581250e+03 1.47051245e+03 1.49580859e+03 1.52370068e+03 1.54838489e+03 1.57260022e+03 1.59847839e+03 1.62687524e+03 1.65523425e+03 1.68226685e+03 1.70098279e+03 1.72958887e+03 1.76066687e+03 1.78542480e+03 1.81247876e+03 1.83490283e+03 1.86383203e+03 1.89362854e+03 1.92035474e+03 1.94646326e+03 1.97421423e+03 1.99854651e+03 2.02590662e+03 2.05958276e+03 2.08021582e+03 2.10870874e+03 2.14019409e+03 2.15771436e+03 2.19049194e+03 2.22024341e+03 2.24126123e+03 2.27053979e+03 2.30270947e+03 2.33177173e+03 2.34944873e+03 2.37909082e+03 2.41420605e+03 2.44175659e+03 2.47109277e+03 2.49055347e+03 2.54585474e+03 3.30545752e+03 3.51991724e+03 3.89543921e+03 3.92822119e+03 3.96728809e+03 4.00634595e+03 4.04633350e+03 4.08943921e+03 4.14656396e+03 4.17945166e+03 3.79121338e+03 4.47255664e+03 3.53152930e+03 4.32364990e+03 4.36202148e+03 4.41859131e+03 4.45397266e+03 3.70443066e+03 3.72628149e+03 3.04470068e+03 3.94285474e+03 5.62129785e+03 7.09336572e+03 -29482316. -297753856. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -42588268. 4.26680156e+04 5.30320605e+03 8.55802344e+03 5.36584473e+03 5.39426074e+03 5.42927148e+03 4.98119141e+03 4.76920312e+03 3.68247681e+03 3.70533911e+03 3.73000562e+03 3.75095972e+03 3.76283228e+03 3.78406982e+03 3.80546533e+03 3.82350977e+03 3.83933398e+03 3.86035400e+03 3.87918604e+03 3.89962964e+03 3.91300952e+03 3.93287720e+03 3.95188550e+03 3.96098584e+03 3.98479810e+03 3.99786279e+03 4.00885376e+03 4.03247168e+03 4.04227051e+03 4.05844409e+03 4.08243726e+03 4.09359741e+03 4.10064453e+03 4.11657324e+03 4.13309912e+03 4.15052979e+03 4.15848486e+03 4.16841211e+03 4.18781543e+03 4.19764111e+03 4.20612354e+03 4.22378125e+03 4.23909863e+03 4.24143311e+03 4.25210986e+03 4.26828516e+03 4.27310645e+03 4.28318896e+03 4.29503662e+03 4.30380322e+03 4.31728857e+03 4.32258398e+03 4.32814893e+03 4.34030615e+03 4.34512451e+03 4.35272754e+03 5.66580371e+03 5.98283203e+03 6.55333350e+03 6.55796143e+03 6.56717383e+03 6.58202051e+03 6.58853564e+03 2.63616426e+04 627619648. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.08026942e+13 1.08026942e+13 0. 0. -1.39061035e+11 205564720. 5.05868945e+04 5.33395703e+04 5.79706172e+04 3.47728282e+11 0. 0. 0. 0. 0. 912400128. 5.28783203e+04 1.32341729e+04 4.64832539e+04 1.33270889e+04 1.31351943e+04 6.57067676e+03 1.30972354e+04 1.31449209e+04 3.62405547e+04 1.47510479e+04 3.81175344e+05 7.46074812e+05 1.30953604e+04 6.76890150e+06 3.17134450e+06 4.26678150e+06 3.94941641e+04 2.45513770e+04 2.52549160e+04 1.92551211e+04 1.27977324e+04 1.26775146e+04 6.84002002e+03 1.26268398e+04 1.25623564e+04 1.30190068e+04 -1.17520762e+06 3.62915000e+04 2.01572016e+05 6.40551688e+05 5.70930078e+04 6.95978750e+04 2.60497285e+04 1.50349703e+05 6.31112617e+04 3.85008975e+06 1.07017969e+05 3324031. -18014886. 2.20617547e+05 4.19440781e+05 1.18734424e+04 9.45788965e+03 5.87688184e+03 5.84823047e+03 5.81865527e+03 5.33641650e+03 5.00416162e+03 3.83135840e+03 3.81593311e+03 3.79896924e+03 4.89911035e+03 5.14611621e+03 5.58748779e+03 5.57512451e+03 5.53603760e+03 8.80642578e+03 1.10780127e+04 1.34568094e+05 1.11045950e+06 330957408. 0. 0. 0. 128097856. 128097856. 128097856. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -24287552. 1.76407871e+04 4.08327075e+03 3.12459277e+03 3.10207959e+03 3.07647827e+03 3.04782788e+03 3.02523242e+03 2.99750439e+03 3.66308887e+03 3.65056665e+03 4.38821777e+03 4.34066406e+03 4.30459277e+03 4.27010742e+03 4.22814844e+03 3.43572827e+03 3.39656641e+03 2.73751611e+03 2.71129541e+03 2.68527002e+03 2.65715967e+03 2.62875098e+03 2.60373047e+03 2.57541699e+03 2.55178052e+03 2.52469214e+03 2.50121851e+03 2.46874683e+03 2.43776538e+03 2.41202344e+03 2.39158521e+03 2.35542725e+03 2.33234717e+03 2.30722192e+03 2.27722998e+03 2.24885645e+03 2.22588257e+03 2.19516016e+03 2.17212036e+03 2.14134937e+03 2.10862231e+03 2.08568311e+03 2.06175024e+03 2.03406348e+03 2.00841882e+03 1.97743445e+03 1.95019312e+03 1.92610254e+03 1.89516406e+03 1.86848474e+03 1.84789722e+03 1.82018665e+03 1.78800806e+03 1.76159338e+03 1.73460693e+03 1.70989978e+03 1.68477478e+03 1.65681116e+03 1.63069824e+03 1.60533252e+03 1.57586035e+03 1.55332935e+03 1.52690149e+03 1.50016980e+03 1.47294946e+03 1.44778076e+03 1.42319568e+03 1.40086926e+03 1.37198218e+03 1.34642468e+03 1.32278760e+03 1.29670728e+03 1.27339771e+03 1.25134204e+03 1.22330334e+03 1.20017419e+03 1.17588501e+03 1.14997937e+03 1.12887939e+03 1.10351489e+03 1.07884546e+03 1.05922266e+03 1.03391724e+03 1.01052698e+03 9.89217163e+02 9.65194580e+02 9.44431824e+02 9.20974609e+02 8.99839966e+02 8.77335815e+02 8.55336914e+02 8.34174316e+02 8.13281677e+02 7.93142761e+02 7.71442383e+02 7.50813843e+02 7.29822632e+02 7.11514893e+02 6.91632629e+02 6.70024536e+02 6.51312073e+02 6.32314026e+02 6.12722656e+02 5.94735291e+02 5.76869934e+02 5.58032593e+02 5.40350281e+02 5.22830322e+02 5.05073212e+02 4.87603912e+02 4.70906982e+02 4.54749695e+02 4.37454193e+02 4.21268219e+02 4.06519257e+02 3.90463623e+02 3.74867523e+02 3.60061035e+02 3.45507751e+02 3.30991638e+02 3.16557098e+02 3.02909149e+02 2.89507629e+02 2.75929932e+02 2.62745331e+02 2.50180649e+02 2.37808655e+02 2.25729431e+02 2.14107285e+02 2.02572235e+02 1.90948853e+02 1.80139557e+02 1.69736755e+02 1.59497986e+02 1.49389832e+02 1.39835602e+02 1.30470261e+02 1.21400414e+02 1.12734779e+02 1.04267838e+02 9.61847916e+01 8.84483490e+01 8.10599136e+01 7.39171448e+01 6.71087265e+01 6.07063332e+01 5.45486526e+01 4.87003822e+01 4.32226028e+01 3.80975304e+01 3.32763596e+01 2.87745152e+01 2.45989571e+01 2.07758465e+01 1.72799835e+01 1.41107225e+01 1.12764463e+01 8.77544022e+00 6.60866594e+00 4.77109575e+00 3.27240133e+00 2.10761094e+00 1.27756166e+00 7.82957971e-01 6.23085558e-01 7.97717750e-01 1.30785692e+00 2.15248823e+00 3.33058858e+00 4.84340382e+00 6.68966436e+00 8.87424660e+00 1.13927383e+01 1.42339411e+01 1.74175396e+01 2.09426193e+01 2.48092041e+01 2.90199413e+01 3.34417152e+01 3.82483368e+01 4.34491119e+01 4.89384651e+01 5.48030319e+01 7.40455399e+01 8.24005814e+01 9.26698914e+01 1.00904694e+02 8.87004623e+01 9.64293518e+01 1.30511566e+02 1.45778702e+02 1.85308884e+02 1.98965408e+02 2.13012680e+02 3.82399445e+02 5.37393799e+02 4.61280304e+02 4.10127075e+02 2.91295013e+02 3.06692657e+02 3.24438141e+02 3.41896393e+02 3.60110352e+02 3.79244537e+02 3.98637360e+02 4.18047302e+02 4.37977295e+02 4.34109497e+02 4.77519196e+02 4.37064514e+02 5.21914612e+02 5.16003540e+02 4.99175690e+02 3.90968140e+02 4.06883972e+02 4.22258942e+02 4.38407745e+02 4.55003387e+02 4.71319946e+02 4.88484772e+02 5.06136108e+02 5.23599304e+02 5.41203308e+02 5.58182861e+02 5.77415527e+02 5.95514282e+02 6.13649963e+02 6.33445068e+02 6.52451904e+02 6.72193787e+02 6.91109253e+02 7.10947693e+02 7.32561768e+02 7.52839294e+02 7.73366333e+02 7.92285706e+02 8.13538635e+02 8.36334839e+02 8.55298889e+02 8.77815063e+02 8.99851196e+02 9.21298706e+02 9.46268799e+02 9.66668518e+02 9.88598999e+02 1.01152747e+03 1.03678845e+03 1.05942603e+03 1.08141724e+03 1.10590796e+03 1.12828918e+03 1.15463550e+03 1.17775537e+03 1.19756262e+03 1.22047852e+03 1.24962781e+03 1.27419470e+03 1.29592029e+03 1.32380200e+03 1.34930225e+03 1.37648792e+03 1.40067432e+03 1.42433154e+03 1.45260486e+03 1.47480273e+03 1.50055786e+03 1.52484314e+03 1.55057434e+03 1.57940723e+03 1.60277222e+03 1.63053772e+03 1.65905615e+03 1.68223767e+03 1.71141357e+03 1.73988293e+03 1.76850317e+03 1.79026135e+03 1.81688867e+03 1.84246228e+03 1.86935425e+03 1.90022192e+03 1.92902661e+03 1.95871277e+03 1.98154980e+03 2.00502246e+03 2.03488843e+03 2.06340796e+03 2.08551587e+03 2.11310229e+03 2.14766797e+03 2.17423413e+03 2.20026611e+03 2.22025220e+03 2.25310083e+03 2.27898682e+03 2.31027637e+03 2.33374219e+03 2.35863989e+03 2.38815356e+03 2.41526318e+03 2.44454272e+03 2.47327539e+03 2.50114746e+03 2.52640503e+03 2.54881445e+03 2.57632861e+03 2.60976025e+03 2.63848657e+03 2.65912720e+03 2.68532373e+03 2.70539575e+03 2.74091626e+03 2.76603369e+03 2.79035864e+03 2.82371997e+03 2.84712280e+03 2.86933325e+03 2.89801318e+03 2.93191650e+03 2.95181128e+03 2.96282568e+03 2.99150391e+03 3.03461206e+03 3.05871509e+03 3.07980811e+03 3.10134204e+03 3.11992456e+03 3.14306616e+03 3.17158154e+03 3.20997095e+03 3.22193726e+03 3.24911865e+03 3.27482861e+03 3.29519214e+03 3.32122974e+03 3.34421387e+03 3.36759961e+03 3.39264355e+03 3.41314673e+03 3.44157642e+03 3.46151050e+03 3.47923730e+03 3.50768457e+03 3.52551221e+03 3.55247266e+03 3.57519287e+03 3.59496509e+03 3.61045190e+03 3.63140210e+03 3.65889917e+03 3.67375562e+03 3.70085669e+03 3.71821753e+03 3.73700854e+03 3.76205688e+03 3.77563013e+03 3.79600806e+03 3.81788965e+03 3.83621265e+03 3.85560254e+03 3.87356030e+03 3.88698633e+03 3.91240527e+03 3.93030005e+03 3.94587744e+03 3.96095679e+03 3.97497095e+03 3.99715479e+03 4.00818701e+03 4.02231348e+03 4.04814844e+03 4.05882886e+03 4.07030542e+03 4.08955493e+03 4.10680762e+03 4.11833398e+03 4.13002588e+03 4.14798633e+03 4.16326807e+03 4.17163086e+03 4.18435742e+03 4.19663037e+03 4.21162451e+03 4.22325391e+03 4.23867480e+03 4.25038916e+03 4.25446729e+03 4.26595215e+03 4.27839502e+03 4.29052246e+03 4.29905029e+03 4.31154639e+03 4.32017090e+03 4.32839551e+03 4.33844922e+03 4.34376855e+03 4.34968262e+03 4.35967773e+03 4.36897656e+03 4.37572998e+03 4.38061719e+03 4.38971143e+03 4.39540576e+03 4.39872021e+03 4.40515088e+03 4.41255811e+03 4.41644580e+03 4.41945020e+03 4.42306787e+03 4.42801221e+03 4.43144629e+03 4.43544727e+03 4.43846973e+03 4.43988184e+03 4.44298633e+03 4.44349268e+03 4.44539014e+03 4.44715625e+03 4.44749561e+03 4.44815527e+03 4.44831836e+03 4.44811328e+03 4.44733105e+03 4.44655762e+03 4.44583545e+03 4.44381787e+03 4.44151270e+03 4.44070020e+03 4.43831934e+03 4.43381201e+03 4.43125244e+03 4.42937451e+03 4.42537061e+03 4.42006104e+03 4.41460352e+03 4.40992236e+03 4.40508789e+03 4.40113574e+03 4.39417920e+03 4.38677734e+03 4.38236963e+03 4.37380859e+03 4.36568164e+03 4.35910742e+03 4.35347998e+03 4.34736328e+03 4.33532324e+03 4.32287842e+03 4.31937500e+03 4.31318311e+03 4.29821094e+03 4.29100830e+03 4.28115723e+03 4.26556348e+03 4.25444727e+03 4.24568750e+03 4.23540430e+03 4.22527051e+03 4.21072119e+03 4.19635352e+03 4.18487793e+03 4.17233838e+03 4.16175049e+03 4.14499414e+03 4.12939697e+03 4.11636035e+03 4.10367139e+03 4.08548975e+03 4.07434863e+03 4.06294482e+03 4.04567944e+03 4.02534131e+03 4.01106616e+03 3.99373096e+03 3.97385059e+03 3.95939648e+03 3.94103125e+03 3.92613989e+03 3.90770288e+03 3.88374438e+03 3.87279370e+03 3.85130078e+03 3.83668799e+03 3.81682153e+03 3.79576147e+03 3.77673926e+03 3.75102393e+03 3.73775488e+03 3.72812378e+03 3.70346069e+03 3.68106177e+03 3.65226660e+03 3.63012744e+03 3.62243921e+03 3.58305371e+03 3.56781567e+03 3.55189795e+03 3.51899365e+03 3.50907275e+03 3.48463306e+03 3.45467578e+03 3.43671387e+03 3.41486182e+03 3.38769019e+03 3.36349780e+03 3.34472705e+03 3.32042163e+03 3.30422437e+03 3.27859131e+03 3.24089185e+03 3.21487793e+03 3.20312134e+03 3.17392236e+03 3.14480933e+03 3.12769678e+03 3.10275977e+03 3.07888354e+03 3.04882788e+03 3.02715186e+03 3.00435376e+03 2.97063867e+03 2.95073218e+03 2.91762061e+03 2.89422827e+03 2.86801440e+03 2.84177173e+03 2.81734375e+03 2.79493408e+03 2.76164209e+03 2.73484229e+03 2.71243066e+03 2.68505103e+03 2.65723511e+03 2.63115723e+03 2.60099854e+03 2.57487134e+03 2.54936377e+03 2.52317310e+03 2.49775977e+03 2.47351416e+03 2.44476196e+03 2.41190527e+03 2.38548755e+03 2.35613208e+03 2.33199927e+03 2.30941577e+03 2.28067114e+03 2.25175586e+03 2.21901001e+03 2.19624121e+03 2.16892139e+03 2.14479980e+03 2.11719995e+03 2.08775806e+03 2.06012378e+03 2.03470239e+03 2.00087695e+03 1.98015063e+03 1.95296155e+03 1.92512939e+03 1.89905603e+03 1.86663318e+03 1.84232751e+03 1.81826453e+03 1.79124426e+03 1.76566138e+03 1.73489026e+03 1.71203589e+03 1.68478455e+03 1.65472131e+03 1.63300208e+03 1.60798499e+03 1.57591089e+03 1.55292419e+03 1.52907471e+03 1.49921252e+03 1.47250977e+03 1.44704822e+03 1.42732251e+03 1.40208484e+03 1.37362512e+03 1.34539185e+03 1.32263330e+03 1.29324780e+03 1.27368982e+03 1.25237585e+03 1.22358679e+03 1.19986438e+03 1.17652234e+03 1.15031812e+03 1.12922046e+03 1.10418250e+03 1.07861963e+03 1.05909302e+03 1.03505200e+03 1.01182715e+03 9.88286621e+02 9.65238525e+02 9.44502686e+02 9.20824646e+02 9.00196228e+02 8.78626282e+02 8.56199707e+02 8.33181824e+02 8.12617798e+02 7.93458923e+02 7.71039917e+02 7.51068726e+02 7.29913330e+02 7.10712830e+02 6.91903809e+02 6.70725952e+02 6.51311279e+02 6.31923462e+02 6.13193604e+02 5.94789185e+02 5.76421143e+02 5.57936401e+02 5.40285889e+02 5.22896118e+02 5.05188049e+02 4.87920135e+02 4.70865387e+02 4.54723450e+02 4.37796234e+02 4.21400238e+02 4.06459320e+02 3.90155121e+02 3.74897125e+02 3.59917145e+02 3.45118256e+02 3.30952515e+02 3.16516663e+02 3.02810150e+02 2.89359314e+02 2.75811371e+02 2.62801941e+02 2.50118896e+02 3.18524353e+02 3.26405182e+02 3.23742035e+02 3.06436188e+02 2.89590912e+02 2.73071991e+02 2.56839111e+02 2.42483887e+02 2.27945251e+02 2.12529892e+02 1.98856323e+02 1.58216919e+02 1.69571899e+02 1.04684158e+02 1.19727821e+02 8.81296616e+01 8.06381226e+01 7.44666595e+01 6.75938644e+01 6.07031059e+01 5.45434189e+01 4.87213135e+01 4.32859192e+01 3.79876328e+01 3.29964333e+01 2.87900963e+01 2.47985649e+01 2.08135242e+01 1.72971401e+01 1.41173286e+01 1.12766047e+01 8.77159882e+00 6.60599327e+00 4.77172565e+00 3.27226233e+00 2.10818267e+00 1.27842331e+00 7.83959389e-01 6.24205112e-01 7.99221754e-01 1.30944371e+00 2.15294528e+00 3.33045411e+00 4.84387159e+00 6.69232702e+00 8.87595749e+00 1.13883638e+01 1.42334232e+01 1.74205475e+01 2.09362411e+01 2.47843742e+01 2.89594955e+01 3.34574356e+01 3.83001976e+01 4.34675369e+01 4.89654770e+01 5.47848282e+01 6.09244423e+01 6.73958664e+01 7.42061996e+01 8.13298569e+01 8.87908478e+01 9.65698929e+01 1.04682419e+02 1.13044838e+02 1.21739166e+02 1.30855637e+02 1.40213791e+02 1.49825607e+02 1.59967484e+02 1.70246414e+02 1.80687943e+02 1.91502945e+02 2.02825989e+02 2.14402740e+02 2.26382858e+02 2.38439682e+02 2.50767242e+02 2.63367523e+02 2.76293884e+02 2.89924347e+02 3.03517517e+02 3.17581238e+02 3.31558258e+02 3.45777100e+02 3.60558502e+02 3.75826050e+02 3.91294342e+02 4.07089783e+02 4.22367889e+02 4.38280884e+02 4.54760681e+02 4.71888367e+02 4.89045563e+02 5.05517639e+02 5.23324707e+02 5.41468994e+02 5.58884399e+02 5.77353210e+02 5.95002502e+02 6.14047607e+02 6.33294739e+02 6.52735535e+02 6.71912781e+02 6.90345154e+02 7.10752258e+02 7.33138245e+02 7.53266235e+02 7.72190308e+02 7.92013611e+02 8.13774719e+02 8.37554504e+02 8.55247620e+02 8.77818970e+02 9.00732239e+02 9.20807129e+02 9.46779724e+02 9.67167175e+02 9.87936035e+02 1.01264667e+03 1.03641675e+03 1.05849011e+03 1.08125195e+03 1.10642920e+03 1.12935730e+03 1.15373425e+03 1.17708374e+03 1.19958167e+03 1.22476465e+03 1.25119080e+03 1.27206140e+03 1.29810669e+03 1.32414014e+03 1.34776611e+03 1.37587732e+03 1.40033032e+03 1.42441675e+03 1.45459534e+03 1.47469360e+03 1.50360437e+03 1.52503809e+03 1.55279504e+03 1.58219360e+03 1.60250806e+03 1.63124951e+03 1.65972754e+03 1.68341528e+03 1.71038965e+03 1.73974902e+03 1.76834973e+03 1.79274817e+03 1.81603992e+03 1.84036157e+03 1.86727539e+03 1.89616809e+03 1.92581165e+03 1.95630420e+03 1.98274292e+03 2.00437036e+03 2.03628064e+03 2.06436572e+03 2.08471729e+03 2.11359106e+03 2.14509229e+03 2.16796533e+03 2.19946655e+03 2.22228613e+03 2.24843384e+03 2.28349634e+03 2.30940112e+03 2.33843066e+03 2.35460303e+03 2.38912573e+03 2.41553247e+03 2.44190112e+03 2.47613281e+03 2.50559277e+03 2.54914136e+03 3.12454907e+03 3.17378857e+03 3.92660156e+03 3.95649487e+03 3.98870459e+03 4.01912646e+03 4.06040527e+03 4.11223193e+03 4.15308789e+03 4.18660498e+03 3.49422070e+03 4.47850098e+03 3.92044971e+03 4.35356787e+03 4.39994531e+03 4.43862451e+03 4.46921533e+03 4.13396729e+03 3.95429565e+03 3.05348975e+03 3.07975415e+03 3.81045190e+03 4.00271313e+03 7.74210547e+03 3.22460996e+04 -6640961. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 443274400. 443274400. -40753804. -56341296. 1.10302012e+04 6.89578281e+04 -9129700. 1.09751162e+04 8.89683594e+03 5.53868213e+03 5.55689404e+03 5.59738232e+03 5.63041016e+03 5.15283887e+03 4.91775781e+03 3.81970654e+03 3.83398560e+03 3.85471753e+03 3.87290576e+03 3.88931958e+03 5.08853467e+03 5.39241602e+03 5.90087842e+03 5.93507178e+03 5.94516260e+03 5.97951221e+03 6.00341357e+03 6.02374512e+03 6.05848828e+03 6.06715283e+03 6.09017139e+03 6.11870508e+03 6.14668262e+03 6.15573682e+03 6.17443652e+03 6.20460645e+03 6.23129932e+03 6.23723633e+03 5.74177051e+03 6.28851074e+03 5.79736279e+03 6.31398535e+03 6.33631152e+03 6.36219580e+03 6.36547852e+03 6.38058936e+03 6.40566895e+03 6.41975000e+03 6.42988477e+03 6.44674512e+03 6.46495654e+03 6.47762891e+03 6.48887744e+03 6.49763281e+03 6.51490869e+03 6.52405762e+03 6.53320459e+03 1.04545547e+04 1.31236982e+04 7.83113062e+05 5452731. 3.28072250e+05 3.36800562e+05 1.70273109e+05 -10328691. 6.25512755e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.08026942e+13 1.08026942e+13 0. 0. 0. 0. -2.21101855e+10 5.79706172e+04 5.79706172e+04 3.47728282e+11 0. -483214752. -7.32938135e+03 -1.79575594e+05 4.26685156e+05 423949696. 2.10603246e+11 2.10603246e+11 0. -2.75760973e+09 -2.75760973e+09 33072232. 1523909504. 1523909504. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -127887808. -127887808. 116196616. 299319456. 299319456. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1150972544. 1150972544. 1150972544. 0. 0. -270507200. 4.58485625e+04 2.25362051e+04 5.92269629e+03 9.47893262e+03 5.87028857e+03 4.80123828e+03 4.75522803e+03 3.85450732e+03 4.94146631e+03 5.16733008e+03 9.05554004e+03 1.13138809e+04 1.16706555e+05 2.11751094e+04 1.40867422e+05 -2.55181125e+05 92724024. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 76953496. 3.78675156e+05 1.31907312e+05 8.60828516e+03 6.14423096e+03 3.16819360e+03 3.14365625e+03 3.11256055e+03 3.09094141e+03 3.07082495e+03 3.04250879e+03 3.01412769e+03 3.91471167e+03 4.11860938e+03 4.42610938e+03 4.37576270e+03 4.33796143e+03 4.31185352e+03 4.26729248e+03 3.81397339e+03 3.59762134e+03 2.75493237e+03 2.72891968e+03 2.69772852e+03 2.67217236e+03 2.64849854e+03 2.62124829e+03 2.59391724e+03 2.56671680e+03 2.53559229e+03 2.50922461e+03 2.48349194e+03 2.45932056e+03 2.43043677e+03 2.40511060e+03 2.37153467e+03 2.34436768e+03 2.32042676e+03 2.29156958e+03 2.26623779e+03 2.23786377e+03 2.21048438e+03 2.18236597e+03 2.15579175e+03 2.12951562e+03 2.10751880e+03 2.07535034e+03 2.04546704e+03 2.01259924e+03 1.99210620e+03 1.96500415e+03 1.93430994e+03 1.90651978e+03 1.88112769e+03 1.85179370e+03 1.82982007e+03 1.80440955e+03 1.77277283e+03 1.74170801e+03 1.72056860e+03 1.69629138e+03 1.66609924e+03 1.64363586e+03 1.61334070e+03 1.58684302e+03 1.56116235e+03 1.53478406e+03 1.51011499e+03 1.48311914e+03 1.45814294e+03 1.43193921e+03 1.40594873e+03 1.38272864e+03 1.35406653e+03 1.33026270e+03 1.30700781e+03 1.27924719e+03 1.25743384e+03 1.23358191e+03 1.20767529e+03 1.18223682e+03 1.15769348e+03 1.13393420e+03 1.11073462e+03 1.08824194e+03 1.06267944e+03 1.03979956e+03 1.01836609e+03 9.95236755e+02 9.70768677e+02 9.49140686e+02 9.26235657e+02 9.05898987e+02 8.84215942e+02 8.61141907e+02 8.38525330e+02 8.17676331e+02 7.98891968e+02 7.76203491e+02 7.55204590e+02 7.35363342e+02 7.15777588e+02 6.95461426e+02 6.75285706e+02 6.56116028e+02 6.36039490e+02 6.17127869e+02 5.98977905e+02 5.80384094e+02 5.61929321e+02 5.43482361e+02 5.26264343e+02 5.08697113e+02 4.90823395e+02 4.74231445e+02 4.57552399e+02 4.40584961e+02 4.24408936e+02 4.08790466e+02 3.93284271e+02 3.77906525e+02 3.62701538e+02 3.47673676e+02 3.33238617e+02 3.19118469e+02 3.05148193e+02 2.91505554e+02 2.78096619e+02 2.64987915e+02 2.51849701e+02 2.39606201e+02 2.27809067e+02 2.15701782e+02 2.04196579e+02 1.92780518e+02 1.81813019e+02 1.71227448e+02 1.60905670e+02 1.50941696e+02 1.41215637e+02 1.31712585e+02 1.22686729e+02 1.13988083e+02 1.05514061e+02 9.73333054e+01 8.95596008e+01 8.21608963e+01 7.49391174e+01 6.81302261e+01 6.16970329e+01 5.55166168e+01 4.96310501e+01 4.41308823e+01 3.89729881e+01 3.41160851e+01 2.96173496e+01 2.54177608e+01 2.15692749e+01 1.80645123e+01 1.48810930e+01 1.20366621e+01 9.52731323e+00 7.35122967e+00 5.50950909e+00 4.00739241e+00 2.84033394e+00 2.00908303e+00 1.51684093e+00 1.36158204e+00 1.54298139e+00 2.06115079e+00 2.91676760e+00 4.10786200e+00 5.63587570e+00 7.49812460e+00 9.69995975e+00 1.22329292e+01 1.50950108e+01 1.83024445e+01 2.18494320e+01 2.57500210e+01 2.99958458e+01 3.43851471e+01 3.92131691e+01 4.44861259e+01 4.99794960e+01 5.59984741e+01 7.43118744e+01 8.30939102e+01 1.15249458e+02 1.13983727e+02 9.01647110e+01 9.77683487e+01 1.06102203e+02 1.14793106e+02 1.23584671e+02 1.32147125e+02 1.41483459e+02 1.85215134e+02 1.98276810e+02 2.13625336e+02 2.26027344e+02 1.93790237e+02 2.04750687e+02 2.16421097e+02 2.28304001e+02 2.40536560e+02 3.35439026e+02 3.76589508e+02 4.18047302e+02 4.37977295e+02 4.03853516e+02 4.05407776e+02 3.34318573e+02 3.48363281e+02 3.63599518e+02 3.78734528e+02 3.94134033e+02 4.10180786e+02 4.25838959e+02 4.42169586e+02 4.58525238e+02 4.75124268e+02 4.92832642e+02 5.10034546e+02 5.27334534e+02 5.45713379e+02 5.63251709e+02 5.81345642e+02 5.99794006e+02 6.19493591e+02 6.37825256e+02 6.56955627e+02 6.77295776e+02 6.96684937e+02 7.15913879e+02 7.36803833e+02 7.58367432e+02 7.79263367e+02 7.98053650e+02 8.19620300e+02 8.42998352e+02 8.62796570e+02 8.83809570e+02 9.04926514e+02 9.27688965e+02 9.53451843e+02 9.71914246e+02 9.92867920e+02 1.01999615e+03 1.04576318e+03 1.06781250e+03 1.08818774e+03 1.11324695e+03 1.13636536e+03 1.16156299e+03 1.18579517e+03 1.20490698e+03 1.23175842e+03 1.25945154e+03 1.28264136e+03 1.30693762e+03 1.33404309e+03 1.35747986e+03 1.38392627e+03 1.41261963e+03 1.43537952e+03 1.46041956e+03 1.48652478e+03 1.51165759e+03 1.53554321e+03 1.56036084e+03 1.59205408e+03 1.61714941e+03 1.64259229e+03 1.66989197e+03 1.69402759e+03 1.72297180e+03 1.75098792e+03 1.77599084e+03 1.80191492e+03 1.83192798e+03 1.85677869e+03 1.88382214e+03 1.91328320e+03 1.93641980e+03 1.96493835e+03 1.99305408e+03 2.02443872e+03 2.04770129e+03 2.07557007e+03 2.09857227e+03 2.12687158e+03 2.16159863e+03 2.18426099e+03 2.21190649e+03 2.23559375e+03 2.26135498e+03 2.29201172e+03 2.32310742e+03 2.35822583e+03 2.38023413e+03 2.40709644e+03 2.43175293e+03 2.45549438e+03 2.48644067e+03 2.51944580e+03 2.54018481e+03 2.56352246e+03 2.58841724e+03 2.61961963e+03 2.65078418e+03 2.68166138e+03 2.70303369e+03 2.72054395e+03 2.75900659e+03 2.78364526e+03 2.81094507e+03 2.84049243e+03 2.85592017e+03 2.88701880e+03 2.91828076e+03 2.94534399e+03 2.96772827e+03 2.98509863e+03 3.02153711e+03 3.05199902e+03 3.06736084e+03 3.10101660e+03 3.11759424e+03 3.14217236e+03 3.17215088e+03 3.19235449e+03 3.22426953e+03 3.24952075e+03 3.26714453e+03 3.29176929e+03 3.31856323e+03 3.33534717e+03 3.36140918e+03 3.39448315e+03 3.41408105e+03 3.42794067e+03 3.46166772e+03 3.48556421e+03 3.49970239e+03 3.52942603e+03 3.54554175e+03 3.57229517e+03 3.59698828e+03 3.61403052e+03 3.63093018e+03 3.65365356e+03 3.68895386e+03 3.69942236e+03 3.71868750e+03 3.74259277e+03 3.76303491e+03 3.78265356e+03 3.79882373e+03 3.81924878e+03 3.83588159e+03 3.85979102e+03 3.88209277e+03 3.89664429e+03 3.91099536e+03 3.93042383e+03 3.95443018e+03 3.96991382e+03 3.98191895e+03 4.00133618e+03 4.01584839e+03 4.03085718e+03 4.04983057e+03 4.06715503e+03 4.08340894e+03 4.10160938e+03 4.11472070e+03 4.12467725e+03 4.14168799e+03 4.16003467e+03 4.17064453e+03 4.18388525e+03 4.20076562e+03 4.21166260e+03 4.22101611e+03 4.23501611e+03 4.24847021e+03 4.26024707e+03 4.27455566e+03 4.28421191e+03 4.29297412e+03 4.30135645e+03 4.31339697e+03 4.32815479e+03 4.33627246e+03 4.34339844e+03 4.35331152e+03 4.36345312e+03 4.37116455e+03 4.37543896e+03 4.38590723e+03 4.39449707e+03 4.39729053e+03 4.40760010e+03 4.41743945e+03 4.42339307e+03 4.42538818e+03 4.43053857e+03 4.43900684e+03 4.44145898e+03 4.44564404e+03 4.44969531e+03 4.45331836e+03 4.45765381e+03 4.46145020e+03 4.46442383e+03 4.46620947e+03 4.46902100e+03 4.46943750e+03 4.47138379e+03 4.47331641e+03 4.47358057e+03 4.47422949e+03 4.47441943e+03 4.47431055e+03 4.47348486e+03 4.47274170e+03 4.47221240e+03 4.46997998e+03 4.46759912e+03 4.46683789e+03 4.46369971e+03 4.45958838e+03 4.45739111e+03 4.45512305e+03 4.45174805e+03 4.44442529e+03 4.43955420e+03 4.43849316e+03 4.43086475e+03 4.42589551e+03 4.42247168e+03 4.41257422e+03 4.40588818e+03 4.39824023e+03 4.39374170e+03 4.38724951e+03 4.37664062e+03 4.36763379e+03 4.36052832e+03 4.35379199e+03 4.34506006e+03 4.33471240e+03 4.32330859e+03 4.31564453e+03 4.30641260e+03 4.28969043e+03 4.27981250e+03 4.27481494e+03 4.26018164e+03 4.24611377e+03 4.23079785e+03 4.22302539e+03 4.21160010e+03 4.19794873e+03 4.18027539e+03 4.16999072e+03 4.15635400e+03 4.14309570e+03 4.12412646e+03 4.11100488e+03 4.10313818e+03 4.08169727e+03 4.06518506e+03 4.05061523e+03 4.03363428e+03 4.01607031e+03 3.99471460e+03 3.98699878e+03 3.96823438e+03 3.94882104e+03 3.93800366e+03 3.91206958e+03 3.89140820e+03 3.87220850e+03 3.86270728e+03 3.83717017e+03 3.81455322e+03 3.80363989e+03 3.77812158e+03 3.75906641e+03 3.74232129e+03 3.72129980e+03 3.69532568e+03 3.67176001e+03 3.65565625e+03 3.64359546e+03 3.61128833e+03 3.59019165e+03 3.56496875e+03 3.54199854e+03 3.52790820e+03 3.49775024e+03 3.47559033e+03 3.45702075e+03 3.43939697e+03 3.41262695e+03 3.37574756e+03 3.36038354e+03 3.34198145e+03 3.32056592e+03 3.29822314e+03 3.26117798e+03 3.23988940e+03 3.22045068e+03 3.18983154e+03 3.17424902e+03 3.14587915e+03 3.10900732e+03 3.09248120e+03 3.07471631e+03 3.04263452e+03 3.01087817e+03 2.99080371e+03 2.96869678e+03 2.93357666e+03 2.90783081e+03 2.88305444e+03 2.85841455e+03 2.83875952e+03 2.81667725e+03 2.77613135e+03 2.75378394e+03 2.73173364e+03 2.70281372e+03 2.66855249e+03 2.64569995e+03 2.62339648e+03 2.58739111e+03 2.56465332e+03 2.54168604e+03 2.51098950e+03 2.49091064e+03 2.45843701e+03 2.42549756e+03 2.39492749e+03 2.36576050e+03 2.34437598e+03 2.32146313e+03 2.29081982e+03 2.26895776e+03 2.23097266e+03 2.20131494e+03 2.18252881e+03 2.15611475e+03 2.13222461e+03 2.10586328e+03 2.07513159e+03 2.04275635e+03 2.00780273e+03 1.99162646e+03 1.97174939e+03 1.93845337e+03 1.90436536e+03 1.87664148e+03 1.85599438e+03 1.83252917e+03 1.80345386e+03 1.76891174e+03 1.74187329e+03 1.72516357e+03 1.69489941e+03 1.66487134e+03 1.64372278e+03 1.61384863e+03 1.58559253e+03 1.56212695e+03 1.53425952e+03 1.50970996e+03 1.48210327e+03 1.45740051e+03 1.43500525e+03 1.40429626e+03 1.38279822e+03 1.35406812e+03 1.33012122e+03 1.30430737e+03 1.27768408e+03 1.25829639e+03 1.23192310e+03 1.20781494e+03 1.18415710e+03 1.15748376e+03 1.13481628e+03 1.11021423e+03 1.08736475e+03 1.06536719e+03 1.03939441e+03 1.01944879e+03 9.94917969e+02 9.70229370e+02 9.49483276e+02 9.25803223e+02 9.06333496e+02 8.83318665e+02 8.60790039e+02 8.37833008e+02 8.17175354e+02 7.99217957e+02 7.76262512e+02 7.54963623e+02 7.34832825e+02 7.16212341e+02 6.95641418e+02 6.75388916e+02 6.55879639e+02 6.36081055e+02 6.17530701e+02 5.99067688e+02 5.80246399e+02 5.61436646e+02 5.43766602e+02 5.26223816e+02 5.08642883e+02 4.91358826e+02 4.74229919e+02 4.57470520e+02 4.40645355e+02 4.24373535e+02 4.08863739e+02 3.93046692e+02 3.77881989e+02 3.62632355e+02 3.47755768e+02 3.33550598e+02 3.18853577e+02 3.04971130e+02 2.91216736e+02 2.78186371e+02 2.65263336e+02 2.52122116e+02 2.39759094e+02 2.27676468e+02 2.15588669e+02 2.04052322e+02 1.92790497e+02 1.81746750e+02 1.71065216e+02 1.60678558e+02 1.50969925e+02 1.76573441e+02 1.31969986e+02 1.65062729e+02 1.13959969e+02 1.05587532e+02 9.74026260e+01 8.89097519e+01 8.14503784e+01 7.54776611e+01 6.86947861e+01 6.17061462e+01 5.55307426e+01 4.96725273e+01 4.41756592e+01 3.87652626e+01 3.36489487e+01 2.95673313e+01 2.56110229e+01 2.15998878e+01 1.80825481e+01 1.48932400e+01 1.20467529e+01 9.53074741e+00 7.35393476e+00 5.51316881e+00 4.00991344e+00 2.84374595e+00 2.01418281e+00 1.52217662e+00 1.36648309e+00 1.54792273e+00 2.06516981e+00 2.91909361e+00 4.10755014e+00 5.63526058e+00 7.49944162e+00 9.70233917e+00 1.22348070e+01 1.51010447e+01 1.83131142e+01 2.18521175e+01 2.57303638e+01 2.99294949e+01 3.44566040e+01 3.93490181e+01 4.45359421e+01 5.00643692e+01 5.59467621e+01 6.21179619e+01 6.86137695e+01 7.54598083e+01 8.26649170e+01 9.01927795e+01 9.79830856e+01 1.06093941e+02 1.14567062e+02 1.23408676e+02 1.32511398e+02 1.41923676e+02 1.51520355e+02 1.61707596e+02 1.72137329e+02 1.82530548e+02 1.93681763e+02 2.05096222e+02 2.16629684e+02 2.28426422e+02 2.40331192e+02 2.53089981e+02 2.65953186e+02 2.79050781e+02 2.92541626e+02 3.06351990e+02 3.20240723e+02 3.34422211e+02 3.48592407e+02 3.63693420e+02 3.79259674e+02 3.94489929e+02 4.10100128e+02 4.26055389e+02 4.41858704e+02 4.58218750e+02 4.75022095e+02 4.92998779e+02 5.10057007e+02 5.26960266e+02 5.45619019e+02 5.63911133e+02 5.80733337e+02 5.99076538e+02 6.19880920e+02 6.37804321e+02 6.56623962e+02 6.77220825e+02 6.96236389e+02 7.16290100e+02 7.37701721e+02 7.58368286e+02 7.77910034e+02 7.97603699e+02 8.19454834e+02 8.43200684e+02 8.62764343e+02 8.84531189e+02 9.05860168e+02 9.27535156e+02 9.54053040e+02 9.71562744e+02 9.93587158e+02 1.01976740e+03 1.04543933e+03 1.06691907e+03 1.08876575e+03 1.11325305e+03 1.13586389e+03 1.16217053e+03 1.18682800e+03 1.20608044e+03 1.23308411e+03 1.25907080e+03 1.28182300e+03 1.30698889e+03 1.33235803e+03 1.35535046e+03 1.38391321e+03 1.41133923e+03 1.43450366e+03 1.45972192e+03 1.48335986e+03 1.51218347e+03 1.53849792e+03 1.56196594e+03 1.58994360e+03 1.61558899e+03 1.64327832e+03 1.67040833e+03 1.69337476e+03 1.72213513e+03 1.75062427e+03 1.77741309e+03 1.80141528e+03 1.82708337e+03 1.85884497e+03 1.88180811e+03 1.91404712e+03 1.93779114e+03 1.96238940e+03 1.99530737e+03 2.02019714e+03 2.04352673e+03 2.07318311e+03 2.09809448e+03 2.13076660e+03 2.15751440e+03 2.18076367e+03 2.21569775e+03 2.23781763e+03 2.25998047e+03 2.29277539e+03 2.32563110e+03 2.35818555e+03 2.38158691e+03 2.40803687e+03 2.42783691e+03 2.45248291e+03 2.49604395e+03 2.51894922e+03 2.55832544e+03 3.29939282e+03 3.51167480e+03 3.94710791e+03 3.98999487e+03 4.04523291e+03 4.05856274e+03 4.09741846e+03 4.15829590e+03 4.19687598e+03 4.23370996e+03 3.97383252e+03 3.75155005e+03 2.88740015e+03 2.91158521e+03 2.94024316e+03 2.97112305e+03 2.99109985e+03 3.01825684e+03 3.04557788e+03 3.06557227e+03 3.10103687e+03 4.02386938e+03 3.14961865e+03 4.79489746e+03 7.27381104e+03 8.14799365e+03 -165617680. -83804736. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 407533600. -206850224. 5.57249414e+04 5.90740820e+04 3.04096270e+04 -7565526. 1.04258857e+04 7.45488135e+03 3.84117822e+03 3.85700562e+03 3.87673584e+03 3.89645679e+03 3.91544214e+03 4.85108887e+03 4.89036182e+03 9.53010156e+03 1.19635088e+04 2.18563125e+05 1.86707695e+04 1.20546035e+04 -2.69417578e+04 -2.95396621e+04 -9.33260375e+05 4.06021750e+05 2.26856450e+06 2.24702875e+06 9.06289812e+05 1.82046562e+04 1.32045344e+05 1.13359758e+05 2.01842266e+04 1.24898330e+04 1.25928193e+04 1.27660264e+04 2.25778375e+06 5.81636094e+04 1.28978311e+04 4.48582500e+04 3.01240703e+04 -3.91294766e+04 2.39795156e+05 9.72348188e+05 7.07483375e+05 2.95719906e+05 1.51255566e+04 1.37427197e+04 1.72789629e+04 4.71990156e+05 3.16242305e+04 2.42179238e+04 9032737. 137416208. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.08026942e+13 1.08026942e+13 0. 0. 7.04949453e+10 7.04949453e+10 7.04949453e+10 0. 0. 0. 0. -483214752. -7.32938135e+03 -1.79575594e+05 4.26685156e+05 423949696. 2.10603246e+11 2.10603246e+11 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -127887808. -127887808. -127887808. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1150972544. 1150972544. 1150972544. 0. 0. -270507200. -1252513152. -1252513152. -37172496. 63499344. 2.22142484e+05 1.14635010e+04 9.32551074e+03 5.80366504e+03 9.04506738e+03 1.09971758e+04 1.17091273e+05 1072932416. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 37091552. -3.64057375e+05 9.73011914e+03 7.79456201e+03 4.94673193e+03 4.33639404e+03 4.12679736e+03 3.20182544e+03 3.17529932e+03 3.14147656e+03 3.11396533e+03 3.09549829e+03 3.07579956e+03 3.03532886e+03 3.01562109e+03 2.99443677e+03 2.96775635e+03 2.93372852e+03 2.91079199e+03 2.89109302e+03 2.85999634e+03 2.83004248e+03 2.80513574e+03 2.78483154e+03 2.76011743e+03 2.72126953e+03 2.69142432e+03 2.67585547e+03 2.64798169e+03 2.61638159e+03 2.59165894e+03 2.56148242e+03 2.52949487e+03 2.50396826e+03 2.48236206e+03 2.44845044e+03 2.42402832e+03 2.39314697e+03 2.36553345e+03 2.33781836e+03 2.31513135e+03 2.28369922e+03 2.25855078e+03 2.23129907e+03 2.20456421e+03 2.17377637e+03 2.14947192e+03 2.12159277e+03 2.09248926e+03 2.06108984e+03 2.03368872e+03 2.00777087e+03 1.98464563e+03 1.95602014e+03 1.92198450e+03 1.89728467e+03 1.87063281e+03 1.84499084e+03 1.82260742e+03 1.79067249e+03 1.75821936e+03 1.73593604e+03 1.71172327e+03 1.68439014e+03 1.66365747e+03 1.62876770e+03 1.60191541e+03 1.57524365e+03 1.55001489e+03 1.52873718e+03 1.49635608e+03 1.47297229e+03 1.44941772e+03 1.41945374e+03 1.39593262e+03 1.36760059e+03 1.34644714e+03 1.32047778e+03 1.29299158e+03 1.26894458e+03 1.24423767e+03 1.21891919e+03 1.19477649e+03 1.17125073e+03 1.14638904e+03 1.12110608e+03 1.09990356e+03 1.07486157e+03 1.04984888e+03 1.02922424e+03 1.00679822e+03 9.83244812e+02 9.59064575e+02 9.35668457e+02 9.16346130e+02 8.93255615e+02 8.71174377e+02 8.48365173e+02 8.27858582e+02 8.07172363e+02 7.83863892e+02 7.64175232e+02 7.43658020e+02 7.24240234e+02 7.03091370e+02 6.82524963e+02 6.64360291e+02 6.43630859e+02 6.24392700e+02 6.06618835e+02 5.87140442e+02 5.68885254e+02 5.51156433e+02 5.32621826e+02 5.14875916e+02 4.97424011e+02 4.80308899e+02 4.63457336e+02 4.46653809e+02 4.29981354e+02 4.14312836e+02 3.98787872e+02 3.83338409e+02 3.67769592e+02 3.52588043e+02 3.38046631e+02 3.23868347e+02 3.09630890e+02 2.95854004e+02 2.82575867e+02 2.69203766e+02 2.56086273e+02 2.43342697e+02 2.31465530e+02 2.19491806e+02 2.07684143e+02 1.96201355e+02 1.85262238e+02 1.74548462e+02 1.63945297e+02 1.53930359e+02 1.44026291e+02 1.34425232e+02 1.25396797e+02 1.16598557e+02 1.08034805e+02 9.97766037e+01 9.18906021e+01 8.43918457e+01 7.71204300e+01 7.02655945e+01 6.36913147e+01 5.74573288e+01 5.15409164e+01 4.59450455e+01 4.07139206e+01 3.57967110e+01 3.12387142e+01 2.69798088e+01 2.30690098e+01 1.95096474e+01 1.62750587e+01 1.33844948e+01 1.08354464e+01 8.61639214e+00 6.73463154e+00 5.19772768e+00 3.99733782e+00 3.13658142e+00 2.61449122e+00 2.42948532e+00 2.58579516e+00 3.08199453e+00 3.92121673e+00 5.09649754e+00 6.61119986e+00 8.46564388e+00 1.06587038e+01 1.31833105e+01 1.60540466e+01 1.92634373e+01 2.28063755e+01 2.66860523e+01 3.09061775e+01 3.54511375e+01 4.03471718e+01 4.55751839e+01 5.10987282e+01 5.70451508e+01 6.33258095e+01 6.98889847e+01 7.64579468e+01 8.34144440e+01 9.12176743e+01 9.92349930e+01 1.07506561e+02 1.16089798e+02 1.24954361e+02 1.33536514e+02 1.42916153e+02 1.87746948e+02 2.04290314e+02 2.68126984e+02 2.58445557e+02 2.65280945e+02 2.97760956e+02 3.30081421e+02 3.48197815e+02 3.09992279e+02 3.80479797e+02 3.24931610e+02 4.21298248e+02 4.41808472e+02 3.88220734e+02 4.03528229e+02 3.37057190e+02 3.51030151e+02 3.66450745e+02 3.81674133e+02 5.32170959e+02 5.97214783e+02 6.46536743e+02 6.71260681e+02 6.95314392e+02 6.21946533e+02 6.19314148e+02 5.14127502e+02 5.30419006e+02 5.49453125e+02 5.67398865e+02 5.85041504e+02 6.04629272e+02 6.24654236e+02 6.42706116e+02 6.61381226e+02 6.81388672e+02 7.02119873e+02 7.20840698e+02 7.42435547e+02 7.64017517e+02 7.84992920e+02 8.04606140e+02 8.24961548e+02 8.49696289e+02 8.70905090e+02 8.90250366e+02 9.11285400e+02 9.34132629e+02 9.59987549e+02 9.80643677e+02 1.00076337e+03 1.02670642e+03 1.05244971e+03 1.07442419e+03 1.09812866e+03 1.11976501e+03 1.14324792e+03 1.17142224e+03 1.19515991e+03 1.21457825e+03 1.24425134e+03 1.26949744e+03 1.29156104e+03 1.31957776e+03 1.34241357e+03 1.36631323e+03 1.39377527e+03 1.42094421e+03 1.44389856e+03 1.46509143e+03 1.49514038e+03 1.52543896e+03 1.54881140e+03 1.57137634e+03 1.60070349e+03 1.63258276e+03 1.65400391e+03 1.68092529e+03 1.70900269e+03 1.73932214e+03 1.76628149e+03 1.78879565e+03 1.81423376e+03 1.84305933e+03 1.87202612e+03 1.89932422e+03 1.92884705e+03 1.95401904e+03 1.97760254e+03 2.00771838e+03 2.03681885e+03 2.06527783e+03 2.08618726e+03 2.11633643e+03 2.14425781e+03 2.17551514e+03 2.20674927e+03 2.22829565e+03 2.25384351e+03 2.28440356e+03 2.30770239e+03 2.33405957e+03 2.36804883e+03 2.40006494e+03 2.42443018e+03 2.44440771e+03 2.47393140e+03 2.50216699e+03 2.53976392e+03 2.55960400e+03 2.57990283e+03 2.60873633e+03 2.64113867e+03 2.67166333e+03 2.70171973e+03 2.71659546e+03 2.74344141e+03 2.78225024e+03 2.80370850e+03 2.83657983e+03 2.86268115e+03 2.87503442e+03 2.90896826e+03 2.93608813e+03 2.96135767e+03 2.99299438e+03 3.01006421e+03 3.04725171e+03 3.06894312e+03 3.08740698e+03 3.12721753e+03 3.14336816e+03 3.17014819e+03 3.19999048e+03 3.22106616e+03 3.24640625e+03 3.26904639e+03 3.29325781e+03 3.31776489e+03 3.34389331e+03 3.36896802e+03 3.38706812e+03 3.42370532e+03 3.44204321e+03 3.45091187e+03 3.48908887e+03 3.51471582e+03 3.52956665e+03 3.55231128e+03 3.57237573e+03 3.60693140e+03 3.62158716e+03 3.64759326e+03 3.66328931e+03 3.68228857e+03 3.71404077e+03 3.72185278e+03 3.74944995e+03 3.77394922e+03 3.79903394e+03 3.81060498e+03 3.82571729e+03 3.85414062e+03 3.86795483e+03 3.89092432e+03 3.91405762e+03 3.92684912e+03 3.94164771e+03 3.96300195e+03 3.98175806e+03 3.99551709e+03 4.01570728e+03 4.03270557e+03 4.05073828e+03 4.06713281e+03 4.08270898e+03 4.10143408e+03 4.11548779e+03 4.13299707e+03 4.14817676e+03 4.16073730e+03 4.17602588e+03 4.19229102e+03 4.20592041e+03 4.21646680e+03 4.23324365e+03 4.24522168e+03 4.25498877e+03 4.26559668e+03 4.27980469e+03 4.29654541e+03 4.30736084e+03 4.31717725e+03 4.33042969e+03 4.34002051e+03 4.34862109e+03 4.36087256e+03 4.36827539e+03 4.37890234e+03 4.38927246e+03 4.39843115e+03 4.40733154e+03 4.41139648e+03 4.42047949e+03 4.42954346e+03 4.43664160e+03 4.44497754e+03 4.45012305e+03 4.45815527e+03 4.46302930e+03 4.46677393e+03 4.47356250e+03 4.47719043e+03 4.48314209e+03 4.48772070e+03 4.48883252e+03 4.49413818e+03 4.49828418e+03 4.49942188e+03 4.50298779e+03 4.50655664e+03 4.50660645e+03 4.50818359e+03 4.51012549e+03 4.51061084e+03 4.51123340e+03 4.51165186e+03 4.51136621e+03 4.51038965e+03 4.51018896e+03 4.50936426e+03 4.50697266e+03 4.50491504e+03 4.50354492e+03 4.49998145e+03 4.49672900e+03 4.49517236e+03 4.49194385e+03 4.48818066e+03 4.48188330e+03 4.47814648e+03 4.47633350e+03 4.46784668e+03 4.46147998e+03 4.45773535e+03 4.44899756e+03 4.44338428e+03 4.43787354e+03 4.43077832e+03 4.42308008e+03 4.41485596e+03 4.40526514e+03 4.39698145e+03 4.38941357e+03 4.38045361e+03 4.36930322e+03 4.36078906e+03 4.35255908e+03 4.34285352e+03 4.32627539e+03 4.31303760e+03 4.30949658e+03 4.29822412e+03 4.28080957e+03 4.27074756e+03 4.25926758e+03 4.24861475e+03 4.23742822e+03 4.21529590e+03 4.20120654e+03 4.19819727e+03 4.18176709e+03 4.15954297e+03 4.14275391e+03 4.12891797e+03 4.11833496e+03 4.10541504e+03 4.08776538e+03 4.06613428e+03 4.05039136e+03 4.03240112e+03 4.01747339e+03 4.00037378e+03 3.98080859e+03 3.96684790e+03 3.94951929e+03 3.92639233e+03 3.90817017e+03 3.89348828e+03 3.86984009e+03 3.85000366e+03 3.83798901e+03 3.81262183e+03 3.78943701e+03 3.77048389e+03 3.75233447e+03 3.73165674e+03 3.71047876e+03 3.68887256e+03 3.67755151e+03 3.65179565e+03 3.61860107e+03 3.59332349e+03 3.57165430e+03 3.56241382e+03 3.53874316e+03 3.50242993e+03 3.48068188e+03 3.46660986e+03 3.44175098e+03 3.41480444e+03 3.38791187e+03 3.36187427e+03 3.34865137e+03 3.32600757e+03 3.28858423e+03 3.27044702e+03 3.25126440e+03 3.21856079e+03 3.19727783e+03 3.17682520e+03 3.14320630e+03 3.11937744e+03 3.10017383e+03 3.06300439e+03 3.03520654e+03 3.01714429e+03 2.99170898e+03 2.96939282e+03 2.93136914e+03 2.91278003e+03 2.88810107e+03 2.85651025e+03 2.83658350e+03 2.80493115e+03 2.77935645e+03 2.75862769e+03 2.72584497e+03 2.69222803e+03 2.66874658e+03 2.64290991e+03 2.61649463e+03 2.59192456e+03 2.56530078e+03 2.53459473e+03 2.51306665e+03 2.48358691e+03 2.44828296e+03 2.42178271e+03 2.39401636e+03 2.36857812e+03 2.33920850e+03 2.31870508e+03 2.28203125e+03 2.25328857e+03 2.23673633e+03 2.19807324e+03 2.16837915e+03 2.15020581e+03 2.12544922e+03 2.09711792e+03 2.06125366e+03 2.03130164e+03 2.01361902e+03 1.98828796e+03 1.95893250e+03 1.92557971e+03 1.89323010e+03 1.87286926e+03 1.85100085e+03 1.82434912e+03 1.78567322e+03 1.75750208e+03 1.73962183e+03 1.71070605e+03 1.68225684e+03 1.66304590e+03 1.62849219e+03 1.59988977e+03 1.57570447e+03 1.54943091e+03 1.52571667e+03 1.49500586e+03 1.47604883e+03 1.44733777e+03 1.41791345e+03 1.39550708e+03 1.36769165e+03 1.34398242e+03 1.32033167e+03 1.29347473e+03 1.27029187e+03 1.24322009e+03 1.21997534e+03 1.19619507e+03 1.17144971e+03 1.14765369e+03 1.12165796e+03 1.09982715e+03 1.07759583e+03 1.04974231e+03 1.02997046e+03 1.00755945e+03 9.81883362e+02 9.59050659e+02 9.35507324e+02 9.17570190e+02 8.93012695e+02 8.69928955e+02 8.48575439e+02 8.26782715e+02 8.07261292e+02 7.84237305e+02 7.63359314e+02 7.43712830e+02 7.24570007e+02 7.02660583e+02 6.82199890e+02 6.64218201e+02 6.43423767e+02 6.24974182e+02 6.06391113e+02 5.86594055e+02 5.68479187e+02 5.51046265e+02 5.32079407e+02 5.13954346e+02 4.97219543e+02 4.78286926e+02 5.89618958e+02 5.86092529e+02 6.42229248e+02 6.19164368e+02 5.96060364e+02 5.40916687e+02 4.87041779e+02 3.53045471e+02 3.38253815e+02 3.23493408e+02 3.09468536e+02 2.95423462e+02 2.82540344e+02 2.69841003e+02 2.56160797e+02 3.06055878e+02 2.28077133e+02 3.28920563e+02 2.59094849e+02 2.81495728e+02 2.47983337e+02 1.74339111e+02 1.63617874e+02 1.54087036e+02 1.76828552e+02 1.34519531e+02 1.53864548e+02 1.16512291e+02 1.08039017e+02 9.97265778e+01 9.07831421e+01 8.36271439e+01 7.75124207e+01 7.04514542e+01 6.37035713e+01 5.74649277e+01 5.15881004e+01 4.59960289e+01 4.07362022e+01 3.58240204e+01 3.12487984e+01 2.69959297e+01 2.30872269e+01 1.95214386e+01 1.62940598e+01 1.34087305e+01 1.08493462e+01 8.63024616e+00 6.75186539e+00 5.21212959e+00 4.01143599e+00 3.14976907e+00 2.62865162e+00 2.44516420e+00 2.60232353e+00 3.09563661e+00 3.92977381e+00 5.10134268e+00 6.61553907e+00 8.46943760e+00 1.06629267e+01 1.31927357e+01 1.60606499e+01 1.92679482e+01 2.28095608e+01 2.66917267e+01 3.09068966e+01 3.54511375e+01 4.03370819e+01 4.55412407e+01 5.10770416e+01 5.69909706e+01 6.32046623e+01 6.97364120e+01 7.66530151e+01 8.38560181e+01 9.13934708e+01 9.92854843e+01 1.07394623e+02 1.15905350e+02 1.24829918e+02 1.33910446e+02 1.43319977e+02 1.53116333e+02 1.63324417e+02 1.73821228e+02 1.84326401e+02 1.95408279e+02 2.06993103e+02 2.18596634e+02 2.30403122e+02 2.42472977e+02 2.55439926e+02 2.68366547e+02 2.81588898e+02 2.94765533e+02 3.08402252e+02 3.23171478e+02 3.37411285e+02 3.51415863e+02 3.66008636e+02 3.81738892e+02 3.97524048e+02 4.13515045e+02 4.29546478e+02 4.45551270e+02 4.62146271e+02 4.78838837e+02 4.96073425e+02 5.13471008e+02 5.30881897e+02 5.49632568e+02 5.67623108e+02 5.85427673e+02 6.03853027e+02 6.24166565e+02 6.42625977e+02 6.61316589e+02 6.82384338e+02 7.01949585e+02 7.20891113e+02 7.42176208e+02 7.64200989e+02 7.84534912e+02 8.04599792e+02 8.24885010e+02 8.49493591e+02 8.70683655e+02 8.90759277e+02 9.11075073e+02 9.33876465e+02 9.59567200e+02 9.80211365e+02 1.00134460e+03 1.02696082e+03 1.05181250e+03 1.07478564e+03 1.09791956e+03 1.11941431e+03 1.14308313e+03 1.17032422e+03 1.19516541e+03 1.21498706e+03 1.24388635e+03 1.26974097e+03 1.29072180e+03 1.31795728e+03 1.34246387e+03 1.36527649e+03 1.39176404e+03 1.42227747e+03 1.44414697e+03 1.46684692e+03 1.49581616e+03 1.52736169e+03 1.55086279e+03 1.57136414e+03 1.60008606e+03 1.63131091e+03 1.65479163e+03 1.68219177e+03 1.70881860e+03 1.73724158e+03 1.76506274e+03 1.78413977e+03 1.81248401e+03 1.84161987e+03 1.87245642e+03 1.89857605e+03 1.92495288e+03 1.95498926e+03 1.97711890e+03 2.00945618e+03 2.03723425e+03 2.06024780e+03 2.08917603e+03 2.11686499e+03 2.14508691e+03 2.17139062e+03 2.20564307e+03 2.22884106e+03 2.25363770e+03 2.28529517e+03 2.31038135e+03 2.33534985e+03 2.37427051e+03 2.40249780e+03 2.42397534e+03 2.44271216e+03 2.46981299e+03 2.50652515e+03 2.54152124e+03 2.56386670e+03 2.58085864e+03 2.60595679e+03 2.64295728e+03 2.67519312e+03 2.70576294e+03 2.71766919e+03 2.74517090e+03 2.78184326e+03 2.80605664e+03 2.83114795e+03 2.86130054e+03 2.87726221e+03 2.90696484e+03 2.93315454e+03 2.96148120e+03 2.99525806e+03 3.01318750e+03 3.04653735e+03 3.06785986e+03 3.09139966e+03 3.12486792e+03 3.13818628e+03 3.16515430e+03 3.19650098e+03 4.14342139e+03 4.31632666e+03 7.42634131e+03 8.91489746e+03 18369958. -41010048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -18068684. -18068684. -18068684. 0. 0. -3.89905050e+09 1.54709180e+04 3.87470557e+03 3.88784912e+03 5.07899170e+03 5.37693066e+03 5.27719580e+03 9.16006641e+03 7.62935205e+03 2.57717075e+06 -526683936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 698272000. 698272000. 698272000. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.04949453e+10 7.04949453e+10 7.04949453e+10 0. 0. 0. 0. -483214752. -7.32938135e+03 -1.79575594e+05 4.26685156e+05 2122439680. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -44701892. -11784350. 4.02532617e+04 1.05387025e+06 2.77450125e+06 -2.71922950e+06 9.57533984e+04 -5.97140750e+05 6.80763594e+04 1.55582021e+04 1.98258450e+06 -32738190. -371431968. -371431968. 0. 0. 0. 0. 0. 0. 0. 1150972544. 1150972544. 1150972544. 0. 0. -270507200. -1252513152. -1252513152. -37172496. 63499344. 2.22142484e+05 8.49179688e+04 3.65215250e+05 2.30578734e+05 -16394580. 16006507. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -19182360. 2.03912891e+04 4.56959961e+03 4.31316357e+03 3.31149072e+03 3.29224048e+03 3.25945215e+03 3.24006006e+03 3.21309766e+03 3.17798120e+03 3.15572778e+03 3.13692554e+03 3.10996191e+03 3.07669336e+03 3.05725684e+03 3.88531982e+03 4.01182422e+03 4.13283789e+03 3.85109717e+03 2.92165332e+03 2.89710449e+03 2.86826587e+03 2.83746802e+03 2.81578345e+03 2.79500537e+03 2.75721436e+03 2.72357886e+03 2.70383911e+03 2.67994629e+03 2.65215161e+03 2.62027856e+03 2.58843018e+03 2.56694580e+03 2.53926245e+03 2.50878320e+03 2.48274683e+03 2.45064087e+03 3.09780859e+03 3.19111157e+03 3.53993457e+03 3.49852734e+03 3.46017798e+03 3.20358203e+03 2.97159717e+03 2.22808496e+03 2.20489624e+03 2.17563257e+03 2.14570703e+03 2.11470630e+03 2.09338062e+03 2.06512549e+03 2.03868860e+03 2.00656726e+03 1.97792175e+03 1.95141150e+03 1.92306702e+03 1.89350806e+03 1.87066406e+03 1.84948853e+03 1.81509070e+03 1.78298547e+03 1.76082202e+03 1.72969568e+03 1.70909082e+03 1.68201306e+03 1.64987048e+03 1.62427051e+03 1.59486340e+03 1.56860632e+03 1.54698755e+03 1.51840198e+03 1.49576343e+03 1.46837402e+03 1.43956885e+03 1.41352625e+03 1.38605383e+03 1.36068726e+03 1.33753406e+03 1.31321008e+03 1.28342969e+03 1.26095679e+03 1.23748535e+03 1.21143542e+03 1.18942627e+03 1.16130591e+03 1.13822754e+03 1.11676782e+03 1.08988049e+03 1.06514355e+03 1.04256067e+03 1.02159082e+03 9.96658081e+02 9.71636108e+02 9.49827209e+02 9.27798767e+02 9.06247681e+02 8.85001221e+02 8.60601440e+02 8.40003174e+02 8.18402954e+02 7.95812866e+02 7.76052368e+02 7.55492859e+02 7.34967529e+02 7.12593018e+02 6.92171570e+02 6.74153809e+02 6.54273315e+02 6.34745728e+02 6.15980164e+02 5.96869385e+02 5.77168701e+02 5.59364258e+02 5.41939880e+02 5.23058044e+02 5.05862152e+02 4.88126129e+02 4.70862030e+02 4.54015961e+02 4.37379944e+02 4.21281616e+02 4.06002350e+02 3.89900726e+02 3.74043152e+02 3.58955719e+02 3.44050293e+02 3.29797852e+02 3.15277527e+02 3.01365509e+02 2.87943268e+02 2.74228943e+02 2.61177917e+02 2.48475372e+02 2.36080292e+02 2.23785141e+02 2.12113708e+02 2.00595337e+02 1.89295776e+02 1.78422501e+02 1.67831207e+02 1.57706207e+02 1.47630020e+02 1.37922653e+02 1.28680588e+02 1.19804970e+02 1.11108803e+02 1.02727554e+02 9.47992172e+01 8.71806412e+01 7.97418289e+01 7.28028030e+01 6.61159973e+01 5.97638206e+01 5.37975121e+01 4.81298866e+01 4.27964935e+01 3.78187866e+01 3.31908455e+01 2.88593388e+01 2.48917522e+01 2.12665844e+01 1.79702091e+01 1.50231047e+01 1.24230270e+01 1.01584005e+01 8.23493290e+00 6.65902138e+00 5.42364740e+00 4.53147268e+00 3.98146462e+00 3.77372456e+00 3.91355896e+00 4.39839745e+00 5.22585154e+00 6.39411020e+00 7.90002203e+00 9.74833775e+00 1.19397812e+01 1.44761696e+01 1.73655548e+01 2.05884285e+01 2.41454258e+01 2.80563545e+01 3.23031197e+01 3.68762093e+01 4.18039284e+01 4.70752068e+01 5.26215363e+01 5.85790596e+01 6.48743362e+01 7.14670410e+01 7.84030991e+01 8.56631927e+01 9.32363052e+01 1.01175507e+02 1.09516075e+02 1.18189323e+02 1.26940704e+02 1.35628769e+02 1.45148285e+02 1.55611450e+02 1.65934952e+02 1.76652298e+02 1.87643799e+02 2.42642181e+02 2.57400635e+02 3.30698761e+02 3.49099915e+02 3.03717621e+02 3.84203766e+02 3.37994141e+02 7.98191406e+02 1.16086377e+03 1.14061523e+03 8.66307922e+02 5.11004883e+02 4.63476074e+02 4.65503601e+02 3.86257965e+02 4.94596771e+02 5.16409973e+02 6.50279663e+02 6.75797607e+02 6.99433655e+02 5.97102051e+02 6.17597229e+02 5.22089050e+02 7.19123779e+02 7.82900024e+02 8.58231750e+02 8.84547607e+02 9.13900085e+02 9.44541077e+02 9.72696045e+02 9.99702942e+02 1.02971497e+03 9.24026367e+02 9.19808044e+02 7.49742676e+02 7.72331543e+02 7.93099182e+02 8.13012329e+02 8.35018799e+02 8.58061890e+02 8.79539062e+02 8.99697144e+02 9.21184570e+02 9.45282837e+02 9.69790955e+02 9.91385681e+02 1.01373920e+03 1.03890039e+03 1.06277173e+03 1.08770996e+03 1.10889294e+03 1.13094360e+03 1.15593262e+03 1.18267188e+03 1.20630640e+03 1.22852747e+03 1.25708044e+03 1.28283850e+03 1.30520300e+03 1.33498267e+03 1.35855139e+03 1.37863171e+03 1.40793665e+03 1.43664343e+03 1.45989429e+03 1.48231128e+03 1.51244800e+03 1.54036841e+03 1.56699438e+03 1.58900183e+03 1.61807056e+03 1.64806323e+03 1.67486182e+03 1.69819153e+03 1.72765051e+03 1.75709717e+03 1.78567200e+03 1.80773230e+03 1.83401794e+03 1.86528418e+03 1.89213977e+03 1.92168091e+03 1.94804651e+03 1.97603284e+03 2.00327087e+03 2.02922034e+03 2.05936108e+03 2.08767163e+03 2.11589307e+03 2.14340674e+03 2.17160986e+03 2.20068726e+03 2.22596191e+03 2.24949927e+03 2.28434375e+03 2.30769531e+03 2.33908667e+03 2.36405127e+03 2.39122656e+03 2.42203296e+03 2.45186328e+03 2.47701099e+03 2.50356323e+03 2.53538916e+03 2.56607690e+03 2.58847046e+03 2.61063452e+03 2.63854712e+03 2.67181079e+03 2.70294043e+03 2.73236060e+03 2.74884399e+03 2.77164697e+03 2.81568384e+03 2.83778467e+03 2.87252051e+03 2.88912256e+03 2.90292944e+03 2.94927441e+03 2.96990747e+03 2.98651953e+03 3.02489160e+03 3.04973047e+03 3.08326880e+03 3.10377002e+03 3.12049390e+03 3.15288330e+03 3.17712769e+03 3.20376733e+03 3.23690283e+03 3.25670459e+03 3.27236157e+03 3.30761499e+03 3.33518213e+03 3.35056738e+03 3.38949536e+03 3.40526807e+03 3.42898706e+03 3.46569019e+03 3.47771631e+03 3.49903149e+03 3.52278906e+03 3.55021729e+03 3.57089111e+03 3.59287354e+03 3.61819702e+03 3.64326270e+03 3.66279688e+03 3.68794019e+03 3.70438037e+03 3.72513232e+03 3.75630835e+03 3.76696216e+03 3.78697217e+03 3.81842700e+03 3.84288525e+03 3.84675049e+03 3.86554248e+03 3.89748877e+03 3.91916333e+03 3.93784204e+03 3.96049829e+03 3.97953662e+03 3.97917700e+03 4.00184302e+03 4.02963037e+03 4.04595605e+03 4.06421313e+03 4.07832690e+03 4.09282129e+03 4.10896875e+03 4.13139746e+03 4.15053076e+03 4.16296631e+03 4.18256689e+03 4.19460547e+03 4.20962158e+03 4.22196045e+03 4.23824072e+03 4.25232617e+03 4.26676318e+03 4.28132861e+03 4.29159717e+03 4.30679688e+03 4.31658789e+03 4.32843213e+03 4.34118555e+03 4.35803955e+03 4.36998730e+03 4.37812988e+03 4.38800879e+03 4.40024609e+03 4.41182227e+03 4.41746338e+03 4.43077002e+03 4.43889453e+03 4.44752979e+03 4.45645605e+03 4.46143506e+03 4.47282275e+03 4.48230713e+03 4.48801074e+03 4.49545898e+03 4.50062207e+03 4.50860254e+03 4.51568506e+03 4.51876465e+03 4.52374170e+03 4.52819531e+03 4.53445801e+03 4.54005371e+03 4.54119629e+03 4.54637988e+03 4.55087500e+03 4.55035010e+03 4.55401855e+03 4.55898096e+03 4.55955078e+03 4.56068896e+03 4.56204053e+03 4.56266895e+03 4.56350586e+03 4.56401953e+03 4.56393018e+03 4.56271191e+03 4.56257129e+03 4.56181104e+03 4.55926318e+03 4.55742627e+03 4.55581982e+03 4.55188574e+03 4.54890869e+03 4.54793115e+03 4.54391211e+03 4.54026367e+03 4.53342578e+03 4.53053418e+03 4.52914551e+03 4.52025293e+03 4.51418018e+03 4.50806299e+03 4.50107080e+03 4.49721436e+03 4.49128027e+03 4.48215527e+03 4.47304932e+03 4.46816748e+03 4.45724023e+03 4.44723340e+03 4.44033740e+03 4.43246973e+03 4.42015381e+03 4.41193359e+03 4.40337744e+03 4.39257812e+03 4.37834668e+03 4.36632373e+03 4.36271240e+03 4.35110205e+03 4.32744043e+03 4.31508154e+03 4.31219238e+03 4.30231006e+03 4.28331738e+03 4.26404248e+03 4.25310791e+03 4.24442090e+03 4.23172803e+03 4.21053418e+03 4.19574023e+03 4.18015625e+03 4.16358057e+03 4.15305127e+03 4.13911621e+03 4.11308691e+03 4.10123096e+03 4.08377002e+03 4.06436182e+03 4.04983496e+03 4.03125293e+03 4.01266528e+03 3.99561182e+03 3.97575513e+03 3.95955249e+03 3.93631885e+03 3.91396484e+03 3.89687817e+03 3.87774219e+03 3.85948047e+03 3.83884009e+03 3.81269287e+03 3.79721606e+03 3.77880591e+03 3.75907275e+03 3.73714209e+03 3.71175146e+03 3.69590234e+03 3.66438403e+03 3.63713037e+03 3.62108301e+03 3.60139111e+03 3.57902271e+03 3.54781885e+03 3.52806372e+03 3.51548828e+03 3.49045312e+03 3.44918335e+03 3.42598413e+03 3.40595215e+03 3.38679028e+03 3.35972998e+03 3.33725024e+03 3.31160010e+03 3.28102563e+03 3.26080322e+03 3.24322729e+03 3.22309277e+03 3.18023462e+03 3.15002686e+03 3.13747534e+03 3.10015283e+03 3.07723462e+03 3.05306250e+03 3.02113647e+03 3.00387622e+03 2.97200122e+03 2.94768774e+03 2.92680518e+03 2.89226855e+03 2.87070801e+03 2.83960620e+03 2.81090698e+03 2.79169409e+03 2.75600269e+03 2.72790820e+03 2.70665723e+03 2.67277295e+03 2.65382739e+03 2.62403809e+03 2.58735669e+03 2.56955151e+03 2.54580444e+03 2.50462329e+03 2.48025122e+03 2.45995459e+03 2.42742285e+03 2.39343579e+03 2.36861060e+03 2.34933228e+03 2.30915698e+03 2.28417139e+03 2.25524634e+03 2.22906323e+03 2.20388379e+03 2.17595093e+03 2.15360791e+03 2.11940820e+03 2.08719702e+03 2.06008521e+03 2.04164929e+03 2.01057971e+03 1.98571570e+03 1.95049707e+03 1.92215723e+03 1.89337878e+03 1.87226062e+03 1.85065002e+03 1.80959387e+03 1.78009094e+03 1.76272168e+03 1.73537256e+03 1.70784607e+03 1.68028247e+03 1.64674146e+03 1.62433838e+03 1.59592200e+03 1.57053406e+03 1.54675464e+03 1.51823987e+03 1.49762219e+03 1.46743958e+03 1.43498242e+03 1.41444971e+03 1.38612378e+03 1.36084070e+03 1.33938611e+03 1.31227258e+03 1.28601306e+03 1.26053479e+03 1.23715967e+03 1.21110388e+03 1.18890942e+03 1.16311499e+03 1.13692896e+03 1.11594324e+03 1.09193762e+03 1.06499060e+03 1.04341711e+03 1.02045935e+03 9.96260437e+02 9.73066284e+02 9.49612671e+02 9.29687683e+02 9.04745789e+02 8.82589172e+02 8.61026794e+02 8.39229492e+02 8.18336914e+02 7.95558655e+02 7.74680359e+02 7.54100037e+02 9.23282288e+02 9.24391907e+02 1.03824780e+03 1.01174268e+03 9.82251404e+02 9.54343689e+02 9.25925171e+02 8.96379272e+02 8.68299011e+02 8.40936646e+02 7.81767517e+02 6.97455444e+02 5.05286713e+02 4.85774170e+02 5.85640991e+02 5.71463013e+02 6.55302429e+02 6.30210327e+02 6.06981567e+02 4.74294403e+02 4.54659576e+02 4.45387238e+02 4.38899750e+02 4.97722809e+02 4.60804138e+02 4.47244019e+02 3.64351776e+02 4.08047211e+02 3.55451843e+02 3.09403595e+02 2.28833282e+02 3.32835327e+02 2.81089233e+02 2.42784363e+02 2.29093750e+02 1.78635941e+02 1.67188538e+02 1.57562454e+02 2.08498428e+02 1.38845779e+02 1.54085541e+02 1.19678825e+02 1.11164284e+02 1.02776749e+02 9.48603516e+01 8.72163773e+01 7.97936096e+01 7.28117447e+01 6.61571274e+01 5.98060226e+01 5.38208656e+01 4.81464272e+01 4.28196259e+01 3.78448410e+01 3.31964722e+01 2.88773174e+01 2.49094162e+01 2.12818775e+01 1.79903812e+01 1.50526972e+01 1.24492464e+01 1.01851587e+01 8.26457405e+00 6.68681526e+00 5.45130491e+00 4.55861807e+00 4.00872993e+00 3.80315971e+00 3.94050360e+00 4.42063570e+00 5.24370337e+00 6.41145325e+00 7.92525578e+00 9.77826786e+00 1.19691925e+01 1.45092983e+01 1.73896790e+01 2.06086140e+01 2.41644096e+01 2.80766544e+01 3.23174477e+01 3.68926353e+01 4.18160667e+01 4.70565491e+01 5.26420135e+01 5.86126366e+01 6.48343430e+01 7.14115448e+01 7.84337006e+01 8.56797333e+01 9.32573547e+01 1.01166702e+02 1.09368607e+02 1.18030785e+02 1.27031197e+02 1.36220261e+02 1.45602173e+02 1.55502563e+02 1.65809036e+02 1.76338928e+02 1.87148163e+02 1.98357239e+02 2.09987930e+02 2.21673447e+02 2.33391434e+02 2.45602264e+02 2.58835541e+02 2.72130737e+02 2.85245056e+02 2.98493378e+02 3.12386688e+02 3.26846039e+02 3.41516724e+02 3.56137604e+02 3.70670593e+02 3.86325317e+02 4.02179840e+02 4.18441711e+02 4.34606689e+02 4.50787292e+02 4.67819427e+02 4.84544708e+02 5.01417145e+02 5.20025391e+02 5.38208679e+02 5.55651001e+02 5.74767761e+02 5.91933960e+02 6.11235718e+02 6.31027161e+02 6.50250671e+02 6.69585693e+02 6.88982483e+02 7.09355225e+02 7.29523621e+02 7.50472656e+02 7.72197815e+02 7.93309021e+02 8.14527832e+02 8.35328918e+02 8.57337952e+02 8.80504639e+02 9.01132202e+02 9.22345093e+02 9.45180420e+02 9.69210205e+02 9.92017700e+02 1.01376910e+03 1.03825403e+03 1.06381641e+03 1.08726025e+03 1.10928992e+03 1.13307397e+03 1.15758813e+03 1.18112268e+03 1.20721973e+03 1.23126050e+03 1.25768652e+03 1.28286560e+03 1.30469250e+03 1.33336621e+03 1.35744421e+03 1.38148462e+03 1.40545349e+03 1.43549902e+03 1.46168762e+03 1.48309924e+03 1.51311523e+03 1.54333594e+03 1.56795984e+03 1.58732605e+03 1.61698840e+03 1.65341113e+03 1.67565002e+03 1.69629980e+03 1.72605920e+03 1.76010181e+03 1.78270703e+03 1.80328113e+03 1.83252515e+03 1.86307996e+03 1.89465833e+03 1.91545850e+03 1.94681238e+03 1.97463196e+03 1.99887048e+03 2.03189258e+03 2.06057642e+03 2.08309009e+03 2.11637622e+03 2.14051318e+03 2.16568457e+03 2.19393481e+03 2.90751953e+03 3.06958862e+03 3.40134839e+03 3.44156396e+03 3.14779761e+03 3.03343848e+03 2.39807715e+03 2.42763062e+03 2.44877026e+03 2.47140186e+03 2.50002954e+03 2.53455078e+03 2.56532422e+03 2.59406836e+03 2.61437134e+03 2.63509595e+03 2.66476270e+03 2.70183179e+03 2.73283838e+03 2.74996973e+03 2.77954150e+03 2.81171875e+03 2.83846606e+03 2.86644702e+03 3.74205933e+03 2.90869482e+03 3.78559644e+03 2.97073486e+03 2.99433691e+03 3.02920728e+03 3.05132935e+03 3.07946948e+03 3.10189575e+03 3.12184839e+03 3.15201929e+03 3.18147632e+03 3.20555591e+03 3.23036206e+03 3.25306641e+03 3.27790479e+03 4.15495508e+03 5.92266748e+03 4.46602500e+04 -41010048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -18068684. -18068684. -18068684. 0. 0. -292792928. 2.34795410e+04 5.86798438e+03 5.86039600e+03 9.37218066e+03 1.18220801e+04 1.15749209e+04 1.18720244e+04 1.23243633e+04 2.57717075e+06 -526683936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.71605903e+10 4.71605903e+10 4.71605903e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.04949453e+10 7.04949453e+10 7.04949453e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1620073344. -1620073344. -1620073344. 0. 0. 0. 0. 0. 0. 0. 0. 0. -44701892. -11784350. 4.02532617e+04 1.05387025e+06 2.77450125e+06 -2.71922950e+06 9.57533984e+04 -5.97140750e+05 1.32988799e+04 1.31674062e+04 5.27937031e+04 1.20912363e+04 5.35358906e+04 5.35358906e+04 4861610. 3.99154725e+06 3.99154725e+06 156925280. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -19182360. 2.03912891e+04 5.07937695e+03 5.04417725e+03 5.00581348e+03 4.64874365e+03 4.32131543e+03 3.27692529e+03 3.25446338e+03 3.22134595e+03 3.19754810e+03 3.17721045e+03 4.02809790e+03 4.18153662e+03 4.60782959e+03 7.12924707e+03 8.62449219e+03 9.26116992e+03 7.18751904e+03 4.40684619e+03 4.37171924e+03 4.32274658e+03 4.28305029e+03 4.25052002e+03 4.20904297e+03 4.16482764e+03 3.86397046e+03 3.59972876e+03 2.71442529e+03 2.68440869e+03 2.65876660e+03 2.62008423e+03 2.59648022e+03 2.56656934e+03 3.24172900e+03 3.34799170e+03 3.70125903e+03 5.69701660e+03 6.81671924e+03 -1.44481850e+06 313130560. 4540783. 7.28337793e+03 5.61388086e+03 3.37456763e+03 3.32435742e+03 3.29018530e+03 3.24621167e+03 3.19182715e+03 3.15891113e+03 3.12287402e+03 2.90452954e+03 2.67770312e+03 2.00436682e+03 1.97800244e+03 1.94392590e+03 1.91840234e+03 1.89226233e+03 1.86814941e+03 1.83932776e+03 1.80755237e+03 1.78141553e+03 1.74941968e+03 1.72770837e+03 1.70479419e+03 1.67297693e+03 1.64519983e+03 1.61432690e+03 1.58574939e+03 1.56379419e+03 1.53939648e+03 1.51628845e+03 1.48772961e+03 1.45738416e+03 1.42878247e+03 1.40455542e+03 1.38011084e+03 1.35354492e+03 1.32735815e+03 1.29876282e+03 1.27425793e+03 1.25152930e+03 1.22719885e+03 1.20233276e+03 1.17581946e+03 1.14987439e+03 1.12751416e+03 1.10263220e+03 1.07837329e+03 1.05324011e+03 1.03304041e+03 1.00998071e+03 9.83724182e+02 9.61257629e+02 9.39053223e+02 9.16786865e+02 8.94911804e+02 8.69355286e+02 8.48926453e+02 8.27835083e+02 8.04379333e+02 7.84299500e+02 7.64188049e+02 7.43355225e+02 7.20518311e+02 6.99428589e+02 6.81555054e+02 6.62119446e+02 6.41041016e+02 6.21854980e+02 6.03584351e+02 5.83964722e+02 5.66278931e+02 5.47551697e+02 5.28698364e+02 5.11540649e+02 4.93500183e+02 4.76112823e+02 4.58947632e+02 4.42032227e+02 4.26143646e+02 4.10285309e+02 3.93980957e+02 3.78233582e+02 3.63050079e+02 3.48208618e+02 3.33251190e+02 3.18962524e+02 3.04840179e+02 2.91088379e+02 2.77520386e+02 2.64145416e+02 2.51330521e+02 2.38826706e+02 2.26375900e+02 2.14583038e+02 2.02954758e+02 1.91542007e+02 1.80581543e+02 1.69945511e+02 1.59660217e+02 1.49481232e+02 1.39737411e+02 1.30413589e+02 1.21431572e+02 1.12717194e+02 1.04280388e+02 9.62984009e+01 8.86238708e+01 8.11718826e+01 7.41580200e+01 6.74681244e+01 6.11087570e+01 5.50724678e+01 4.93670578e+01 4.40332451e+01 3.90651398e+01 3.44053917e+01 3.00858498e+01 2.61266098e+01 2.25120792e+01 1.92346954e+01 1.63047562e+01 1.37271318e+01 1.14890356e+01 9.59710693e+00 8.05327225e+00 6.85511875e+00 6.01290369e+00 5.52507257e+00 5.38652468e+00 5.59185553e+00 6.14011288e+00 7.03338623e+00 8.27672291e+00 9.86453724e+00 1.17994795e+01 1.40798931e+01 1.67148762e+01 1.97049084e+01 2.30168858e+01 2.66740971e+01 3.07120304e+01 3.50731201e+01 3.97793770e+01 4.48379059e+01 5.02109756e+01 5.59265556e+01 6.20185928e+01 6.84708023e+01 7.52029037e+01 8.23071899e+01 8.97408981e+01 9.74013138e+01 1.05527634e+02 1.14044739e+02 1.22742805e+02 1.31777374e+02 1.41311478e+02 1.51050674e+02 1.61092651e+02 1.71729126e+02 1.82637863e+02 1.93563873e+02 2.45848053e+02 2.64840027e+02 3.63115662e+02 3.83557129e+02 3.98360718e+02 3.74030304e+02 2.79665527e+02 3.57721344e+02 3.75958954e+02 4.79543671e+02 5.01729797e+02 5.24070557e+02 4.51008545e+02 4.68085205e+02 5.33376343e+02 7.45647522e+02 1.04478870e+03 -8004316. 12329798. -4436438. 1.81764331e+03 1.39388562e+03 8.27036621e+02 1.42054688e+03 1.82743799e+03 8.28039219e+04 6157901. 17915864. -6.29528550e+06 -4.65208550e+06 33926880. 1.83491943e+03 1.56771350e+03 1.14272668e+03 1.14553223e+03 9.70021362e+02 1.20643042e+03 1.09367310e+03 1.27368909e+03 1.31185815e+03 1.34159497e+03 1.37052576e+03 1.15941797e+03 1.17882996e+03 1.27228821e+03 1.00680396e+03 1.54772473e+03 1.07738525e+03 1.33852881e+03 1.10638733e+03 1.13701746e+03 1.14934998e+03 1.17184448e+03 1.20382654e+03 1.22264246e+03 1.24817822e+03 1.27990735e+03 1.30205322e+03 1.32509033e+03 1.35919299e+03 1.38056409e+03 1.40325439e+03 1.43092688e+03 1.89661316e+03 1.48959741e+03 1.84511475e+03 2.11708569e+03 2.04909351e+03 2.38597290e+03 2.41439941e+03 2.45217847e+03 2.49520068e+03 2.53802588e+03 2.57865088e+03 2.61766455e+03 2.66396753e+03 2.70454761e+03 2.74114990e+03 2.77533472e+03 2.83026709e+03 2.86430176e+03 2.90482251e+03 2.95852686e+03 2.98702661e+03 3.03090308e+03 3.07428638e+03 3.11654028e+03 2.83216528e+03 2.74526758e+03 2.17873730e+03 2.20761060e+03 2.23542725e+03 2.26565161e+03 2.28827563e+03 2.32275854e+03 2.34910205e+03 2.37786328e+03 2.40008008e+03 2.43241650e+03 2.46199268e+03 2.48892163e+03 2.51857739e+03 2.54893823e+03 2.57828613e+03 2.60162988e+03 2.62986597e+03 2.65881641e+03 2.68517065e+03 2.71101636e+03 2.74252661e+03 2.77718628e+03 2.79777783e+03 2.82159985e+03 2.85719653e+03 2.88739624e+03 2.91468945e+03 2.93050977e+03 2.96139575e+03 2.99721655e+03 3.01206177e+03 3.03734277e+03 3.07020386e+03 3.10261841e+03 3.13006421e+03 3.15560181e+03 3.17644751e+03 3.19537622e+03 3.22653833e+03 3.26046216e+03 3.28541162e+03 3.30921045e+03 3.32721753e+03 3.35266138e+03 3.38745093e+03 3.41376001e+03 3.43793896e+03 3.46028784e+03 3.48698657e+03 3.50944824e+03 3.53249927e+03 3.55705103e+03 3.57410962e+03 3.60518286e+03 3.63235474e+03 3.65252148e+03 3.67540771e+03 3.69701538e+03 3.71991260e+03 3.74396606e+03 3.75767334e+03 3.78236011e+03 3.81361865e+03 3.82492188e+03 3.84610742e+03 3.88001685e+03 3.89871655e+03 3.90532324e+03 3.92265503e+03 3.95654419e+03 3.98351025e+03 3.99096973e+03 4.01193872e+03 4.03943262e+03 4.04349878e+03 4.06746802e+03 4.08846265e+03 4.10321729e+03 4.13120117e+03 4.13959961e+03 4.15769238e+03 4.17349512e+03 4.18896143e+03 4.21449902e+03 4.22680957e+03 4.24160986e+03 4.25402490e+03 4.27470264e+03 4.28987109e+03 4.29969678e+03 4316. 4.33505713e+03 4.34328906e+03 4.35572266e+03 4.36999512e+03 4.38197559e+03 4.39653271e+03 4.40800342e+03 4.42215039e+03 4.43330518e+03 4.44317773e+03 4.45416699e+03 4.46597998e+03 4.47404199e+03 4.48342676e+03 4.49734326e+03 4.50290527e+03 4.51409424e+03 4.52334961e+03 4.52725928e+03 4.53670508e+03 4.54692822e+03 4.55558740e+03 4.56116553e+03 4.56617334e+03 4.57398047e+03 4.58087891e+03 4.58526172e+03 4.58926025e+03 4.59435547e+03 4.59983252e+03 4.60579004e+03 4.60812695e+03 4.61225195e+03 4.61604834e+03 4.61643652e+03 4.62025049e+03 4.62419238e+03 4.62521533e+03 4.62678711e+03 4.62745361e+03 4.62831152e+03 4.62922900e+03 4.62936768e+03 4.62913965e+03 4.62781934e+03 4.62770264e+03 4.62709033e+03 4.62428076e+03 4.62256641e+03 4.62024609e+03 4.61660254e+03 4.61438184e+03 4.61147754e+03 4.60648828e+03 4.60421387e+03 4.59966699e+03 4.59712695e+03 4.59075781e+03 4.58310449e+03 4.57853271e+03 4.57096436e+03 4.56517480e+03 4.56190527e+03 4.55516797e+03 4.54360449e+03 4.53448633e+03 4.53031201e+03 4.52210059e+03 4.50876807e+03 4.50039307e+03 4.49617188e+03 4.48098242e+03 4.47349756e+03 4.46909766e+03 4.45240771e+03 4.43858789e+03 4.42562109e+03 4.42156738e+03 4.41040283e+03 4.39101318e+03 4.37857861e+03 4.37048340e+03 4.35913184e+03 4.34095801e+03 4.32461914e+03 4.31541016e+03 4.30119043e+03 4.28479736e+03 4.27310840e+03 4.25517676e+03 4.23428662e+03 4.21826660e+03 4.21179102e+03 4.18939404e+03 4.17008936e+03 4.16588721e+03 4.14761426e+03 4.11473779e+03 4.10153223e+03 4.08728906e+03 4.05863501e+03 4.04893799e+03 4.03798633e+03 4.01632446e+03 3.98314746e+03 3.96682959e+03 3.95813257e+03 3.93093677e+03 3.90851245e+03 3.89101196e+03 3.86623071e+03 3.84918579e+03 3.82672803e+03 3.80829932e+03 3.78600464e+03 3.75998730e+03 3.74311157e+03 3.71545605e+03 3.69142920e+03 3.66475000e+03 3.64681274e+03 3.63453906e+03 3.59520508e+03 3.56845776e+03 3.55333374e+03 3.53304688e+03 3.50676929e+03 3.47792700e+03 3.44541748e+03 3.43213696e+03 3.40692163e+03 3.37816968e+03 3.35873511e+03 3.32960352e+03 3.30686035e+03 3.27650195e+03 3.25866016e+03 3.23168237e+03 3.19348853e+03 3.17297217e+03 3.14188110e+03 3.12297119e+03 3.09635425e+03 3.06023975e+03 3.04845044e+03 3.01385571e+03 2.98300830e+03 2.96667310e+03 2.92665381e+03 2.90766919e+03 2.87568262e+03 2.84680786e+03 2.82794775e+03 2.79272583e+03 2.76623535e+03 2.74489795e+03 2.70683594e+03 2.68452710e+03 2.65871826e+03 2.62002710e+03 2.60456885e+03 2.57716943e+03 2.53075049e+03 2.51570996e+03 2.48791797e+03 2.45688647e+03 2.42396948e+03 2.39716333e+03 2.37771826e+03 2.34044604e+03 2.31502783e+03 2.28738940e+03 2.26194531e+03 2.23024683e+03 2.19788818e+03 2.17460376e+03 2.14392505e+03 2.11499316e+03 2.09099365e+03 2.06431372e+03 2.02981396e+03 2.54262036e+03 2.61668286e+03 2.72590381e+03 2.85427173e+03 2.49921338e+03 2.78207886e+03 2.74203174e+03 2.69394775e+03 2.65979053e+03 2.30798828e+03 2.32772437e+03 2.09374976e+03 2.16074072e+03 2.45589697e+03 2.41107715e+03 2.37148022e+03 2.05449731e+03 1.99994495e+03 1.59585400e+03 1.82482751e+03 1.91237671e+03 1.89967566e+03 2.09262085e+03 1.72057251e+03 2.02286096e+03 1.98790747e+03 1.94799585e+03 1.90771497e+03 1.87194214e+03 1.83419971e+03 1.79581958e+03 1.76233899e+03 1.72227576e+03 1.68984155e+03 1.65321411e+03 1.61269812e+03 1.58129419e+03 1.54743494e+03 1.51089661e+03 1.41863550e+03 1.43006177e+03 1.22636292e+03 1.37296851e+03 1.33975317e+03 1.30807874e+03 1.27424854e+03 1.24131116e+03 1.20740881e+03 1.17648108e+03 1.14154321e+03 1.66484143e+03 1.87072522e+03 -15328017. 3.38997650e+06 12386042. -63375560. -20316870. 2.02888635e+03 1.73915344e+03 1.47068665e+03 1.84636902e+03 1.32349756e+03 7.68477173e+02 7.34351135e+02 1.21760022e+03 1.65150208e+03 -27340334. 2809608. -13924093. 9.59004944e+02 6.78165222e+02 6.18546936e+02 4.48198181e+02 4.98027008e+02 3.89185913e+02 4.54864044e+02 3.62018463e+02 3.36892151e+02 3.20442078e+02 3.52760834e+02 2.32291336e+02 3.38884277e+02 3.38867645e+02 2.48313293e+02 2.30248932e+02 1.80728577e+02 1.69912888e+02 1.59708282e+02 1.49583862e+02 1.39851624e+02 1.30481949e+02 1.21460052e+02 1.12787834e+02 1.04310440e+02 9.62796631e+01 8.86143875e+01 8.12320938e+01 7.41865387e+01 6.74829178e+01 6.11082878e+01 5.50862503e+01 4.93866806e+01 4.40589790e+01 3.90779533e+01 3.44069366e+01 3.00940266e+01 2.61390152e+01 2.25181370e+01 1.92329636e+01 1.63087711e+01 1.37217169e+01 1.14761705e+01 9.58883476e+00 8.06082821e+00 6.88464689e+00 6.04527760e+00 5.54678392e+00 5.39770985e+00 5.59610891e+00 6.14901209e+00 7.04817963e+00 8.28743267e+00 9.87811565e+00 1.18164358e+01 1.40956335e+01 1.67449226e+01 1.97248154e+01 2.30352230e+01 2.67069588e+01 3.07298126e+01 3.50973930e+01 3.98080177e+01 4.48360138e+01 5.02107010e+01 5.59738121e+01 6.20643044e+01 6.84664459e+01 7.51978455e+01 8.23629761e+01 8.97192917e+01 9.73843613e+01 1.05588676e+02 1.14030540e+02 1.22770851e+02 1.31876312e+02 1.41318344e+02 1.50948425e+02 1.61135300e+02 1.71643738e+02 1.82182755e+02 1.93216522e+02 2.04474518e+02 2.16409241e+02 2.28317764e+02 2.40389923e+02 2.53058395e+02 2.66377319e+02 2.79490570e+02 2.92981781e+02 3.06921295e+02 3.20965607e+02 3.35413849e+02 3.50280396e+02 3.65612549e+02 3.80525116e+02 3.96022217e+02 4.12196869e+02 4.28875488e+02 4.44870300e+02 4.61568909e+02 4.79733948e+02 4.96602692e+02 5.12960266e+02 5.31144104e+02 5.50140869e+02 5.67421814e+02 5.86888611e+02 6.06639282e+02 6.24853333e+02 6.43057007e+02 6.64435913e+02 6.86116272e+02 7.04231201e+02 7.24036926e+02 7.45120422e+02 7.67365906e+02 7.88555725e+02 8.09177246e+02 8.29675842e+02 8.50989807e+02 8.73976501e+02 8.98381592e+02 9.19425171e+02 9.42440735e+02 9.63420654e+02 9.86667358e+02 1.01374048e+03 1.03424084e+03 1.05743115e+03 1.08349817e+03 1.10756824e+03 1.13156128e+03 1.15490100e+03 1.17820081e+03 1.20445740e+03 1.23045862e+03 1.25447961e+03 1.28228516e+03 1.30672314e+03 1.33019543e+03 1.35716797e+03 1.38358447e+03 1.40879749e+03 1.43303052e+03 1.46084045e+03 1.48929358e+03 1.51045276e+03 1.53924194e+03 1.57236877e+03 1.59626343e+03 1.61765051e+03 1.64557910e+03 1.67707166e+03 1.70469592e+03 1.72602844e+03 1.75758423e+03 1.78658997e+03 1.81340271e+03 1.83918457e+03 1.86941003e+03 1.90059326e+03 1.92463464e+03 1.94918005e+03 1.98277161e+03 2.01058740e+03 2.04345520e+03 2.06375903e+03 2.72430908e+03 2.91029614e+03 3.20551221e+03 3.24530371e+03 3.30192358e+03 3.37515869e+03 5.73721094e+03 7.28597559e+03 7.18843750e+06 -5.62313350e+06 6.64172607e+03 5.53807080e+03 3.62803003e+03 3.67202393e+03 3.69712061e+03 3.75051831e+03 3.79417871e+03 3.83932422e+03 3.86724170e+03 3.91823071e+03 3.96544189e+03 3.98882739e+03 4.03559497e+03 4.08678735e+03 4.11592041e+03 4.16077686e+03 3.81255493e+03 4.24685596e+03 4.03398071e+03 4.32725537e+03 6.96634961e+03 4.51334375e+03 6.99648926e+03 4.48242969e+03 4.53043066e+03 4.57096582e+03 4.61421631e+03 4.17878369e+03 4.03784302e+03 3.17573145e+03 3.19474390e+03 4.17952979e+03 4.43226074e+03 4.88333838e+03 4.92139941e+03 4.96981299e+03 5.03291748e+03 8.81971875e+03 4.46602500e+04 -41010048. 0. 0. 0. 0. 0. 0. 0. 0. 0. -13921537. -13921537. -13921537. 0. 0. 0. 0. -18068684. -18068684. -18068684. 0. 0. -395754880. 5.41559023e+04 5.89275898e+04 4.70310156e+05 -39282656. 606139904. -305518912. -305518912. -305518912. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.71605903e+10 4.71605903e+10 4.71605903e+10 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. 2.48837550e+10 2.48837550e+10 2.48837550e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1620073344. -1620073344. -1620073344. 0. 0. 0. 0. 0. 0. 0. 0. 0. -44701892. -11784350. 4.02532617e+04 1.05387025e+06 2.77450125e+06 -2.71922950e+06 9.57533984e+04 -5.97140750e+05 1.32988799e+04 1.31674062e+04 5.27937031e+04 1.20912363e+04 5.35358906e+04 5.35358906e+04 4861610. 3.99154725e+06 3.99154725e+06 156925280. 0. 0. 0. 0. -56456332. -56456332. -56456332. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.02777436e+10 -1.02777436e+10 -1.02777436e+10 0. 0. 0. 0. 0. 0. 0. -18899010. -18899010. -18899010. 0. 38438892. 10712101. 9.47523812e+05 4.23141050e+06 4.64204150e+06 1.06078535e+04 8.13799170e+03 4.95494482e+03 4.92311475e+03 4.87729346e+03 4.83700732e+03 4.79467334e+03 7.41929834e+03 9.04027148e+03 3.33913594e+05 3.00511150e+06 650076480. 30910274. 3.56479492e+04 8.76955762e+03 9.07645500e+05 2.22007825e+06 2.05691238e+06 8.74865039e+03 8.44335938e+03 8.15025146e+03 8.81568750e+03 6.80774121e+03 4.10426611e+03 4.06437354e+03 4.01894507e+03 3.96326367e+03 3.93115552e+03 3.88827075e+03 3.91185010e+03 5.79685059e+03 7.17125195e+03 3.00912168e+04 -645750336. -46450972. 0. 0. 5.69585250e+06 2.65303633e+04 6.52029932e+03 -8551941. -10486358. -4.26142850e+06 14908794. 6131944. 1.96420325e+06 6.69552148e+03 5.09342871e+03 3.03543188e+03 2.83647217e+03 2.61766870e+03 1.94837292e+03 1.91844238e+03 1.89669751e+03 1.86340417e+03 1.83437585e+03 1.81095349e+03 1.78057532e+03 1.75381152e+03 1.72726685e+03 1.69805103e+03 1.67164868e+03 1.63703882e+03 1.61165063e+03 1.58717932e+03 1.56008911e+03 1.53640649e+03 1.50881970e+03 1.48094666e+03 1.45033459e+03 1.42729053e+03 1.40005505e+03 1.72976990e+03 1.75741919e+03 1.88208301e+03 1.71870789e+03 1.26961096e+03 1.24542102e+03 1.22065588e+03 1.19454919e+03 1.46631226e+03 1.48607275e+03 1.60723535e+03 1.46220264e+03 1.06997229e+03 1.04730371e+03 1.02322247e+03 9.99489258e+02 9.76589600e+02 9.51834045e+02 9.30545837e+02 9.07902893e+02 8.83477539e+02 8.61155579e+02 8.41536621e+02 8.17362976e+02 7.95300232e+02 7.76093262e+02 7.55098877e+02 7.31395813e+02 7.10995300e+02 6.91967834e+02 6.72046448e+02 6.51266663e+02 6.30311768e+02 6.11556091e+02 5.93074951e+02 5.74844910e+02 5.55391724e+02 5.36991821e+02 5.19390808e+02 5.01082428e+02 4.83510895e+02 4.66498199e+02 4.49088959e+02 4.32632385e+02 4.16487213e+02 4.00111847e+02 3.84036316e+02 3.68728577e+02 3.53569153e+02 3.38455902e+02 3.23987488e+02 3.09487274e+02 2.95484253e+02 2.81891388e+02 2.68463196e+02 2.55435181e+02 2.42663940e+02 2.30149841e+02 2.18167908e+02 2.06325363e+02 1.94870468e+02 1.83641541e+02 1.72900192e+02 1.62547897e+02 1.52256470e+02 1.42433441e+02 1.32981293e+02 1.23851929e+02 1.15030388e+02 1.06546165e+02 9.84444656e+01 9.06932449e+01 8.31567383e+01 7.60857544e+01 6.93648911e+01 6.29143600e+01 5.68418159e+01 5.11055908e+01 4.57092934e+01 4.06975288e+01 3.60100212e+01 3.16649952e+01 2.76698246e+01 2.40492973e+01 2.07828636e+01 1.78601608e+01 1.52858648e+01 1.30686054e+01 1.11998558e+01 9.68161392e+00 8.51908875e+00 7.71984100e+00 7.27274227e+00 7.17372322e+00 7.42887831e+00 8.03313732e+00 8.99350071e+00 1.03166399e+01 1.19946184e+01 1.40201206e+01 1.63957138e+01 1.91314106e+01 2.22244701e+01 2.56538925e+01 2.94368382e+01 3.36015739e+01 3.80938721e+01 4.29337273e+01 4.81292801e+01 5.36111908e+01 5.95098724e+01 6.57513504e+01 7.23577042e+01 7.92993469e+01 8.65500259e+01 9.41325302e+01 1.02027527e+02 1.10353333e+02 1.19063278e+02 1.27965233e+02 1.37149872e+02 1.46880692e+02 1.56941010e+02 1.67137512e+02 1.77745728e+02 1.88655365e+02 2.00040756e+02 2.11699646e+02 2.23575607e+02 2.35848923e+02 2.48853180e+02 2.61978333e+02 2.74550995e+02 2.87379150e+02 3.65305389e+02 3.90583130e+02 5.22733093e+02 5.47092407e+02 5.69457581e+02 5.76954163e+02 5.44294312e+02 4.97028259e+02 8.74750061e+02 6.63082825e+02 1.33917761e+03 1.53967566e+03 -4436438. -12040623. 10227595. 2.40591758e+04 1113239808. 131442632. 0. 0. 0. 0. 0. 0. 10521950. 1.20189346e+04 3.10819141e+03 2.04853328e+05 1.92317932e+03 3.38484180e+03 6.36792188e+03 1.48634038e+06 2.46949078e+05 1.03677594e+05 7.89249688e+05 2.34024829e+03 2.24469214e+03 3.56697876e+03 1.56471057e+03 3.63659595e+03 2.60730347e+03 2.34979346e+03 1.75745630e+03 1.82722693e+03 1.76823291e+03 1.66908545e+03 1.81648352e+03 1.74929736e+03 1.90614453e+03 1.99438477e+03 1.99096008e+03 2.03151233e+03 2.15518896e+03 2.15066187e+03 2.14716113e+03 2.20149463e+03 3.86135864e+03 2.31994800e+03 3.34396851e+03 4.99524072e+03 1.00641572e+04 -5330381. 7.35097812e+04 2.62274938e+05 7.59902062e+05 5.49361812e+05 -3.40045275e+06 -11494216. -5696656. -3.59326825e+06 -17197230. 2.70205675e+06 5893439. 3.09446550e+06 -2348334. -2242416. -2551901. -6099449. -6.24857850e+06 4209196. 5.94378613e+03 4.99012988e+03 3.30537964e+03 3.00539551e+03 2.90717554e+03 2.30790820e+03 2.33344800e+03 2.36454712e+03 2.39210889e+03 2.42233130e+03 2.45140210e+03 2.47874390e+03 2.50603320e+03 2.54274097e+03 2.56570874e+03 2.59290405e+03 2.62760400e+03 2.65169482e+03 2.67963940e+03 2.70979004e+03 2.74362964e+03 2.76319531e+03 2.79250659e+03 2.82232153e+03 2.84984766e+03 2.87977759e+03 2.90780713e+03 2.93872827e+03 2.96667358e+03 2.98721216e+03 3.01860571e+03 3.05145483e+03 3.06835254e+03 3.09661523e+03 3.12956274e+03 3.16041943e+03 3.18830469e+03 3.21657373e+03 3.23777759e+03 3.25696826e+03 3.29083350e+03 3.32210669e+03 3.34994604e+03 3.37174023e+03 3.38607397e+03 3.41784033e+03 3.44518335e+03 3.47672754e+03 3.50133081e+03 3.52232104e+03 3.55153979e+03 3.57905249e+03 3.59399072e+03 3.62991895e+03 3.63986938e+03 3.66486890e+03 3.69748975e+03 3.72292749e+03 3.74619092e+03 3.76552417e+03 3.78796899e+03 3.81602246e+03 3.83048608e+03 3.85443433e+03 3.88335522e+03 3.89297192e+03 3.91544067e+03 3.94941138e+03 3.96937280e+03 3.97428955e+03 3.99794800e+03 4.02758472e+03 4.05463135e+03 4.06414771e+03 4.08401050e+03 4.10989502e+03 4.12174121e+03 4.14472803e+03 4.16235840e+03 4.17936426e+03 4.20267578e+03 4.21915381e+03 4.23348535e+03 4.25112109e+03 4.26814990e+03 4.29071387e+03 4.30299072e+03 4.31877637e+03 4.33168457e+03 4.34969434e+03 4.36404346e+03 4.37119189e+03 4.39211523e+03 4.41458643e+03 4.42232080e+03 4.43434375e+03 4.44835156e+03 4.46127881e+03 4.47348291e+03 4.48488574e+03 4.50374756e+03 4.51334473e+03 4.52352930e+03 4.53180029e+03 4.54409668e+03 4.55669824e+03 4.56494580e+03 4.57587158e+03 4.58285791e+03 4.59475732e+03 4.60396777e+03 4.60917285e+03 4.61822314e+03 4.62802148e+03 4.63508105e+03 4.64089600e+03 4.64989551e+03 4.65411768e+03 4.66143555e+03 4.66734717e+03 4.67045898e+03 4.67534082e+03 4.68008643e+03 4.68656885e+03 4.68959033e+03 4.69363184e+03 4.69725049e+03 4.69901025e+03 4.70141406e+03 4.70460156e+03 4.70669434e+03 4.70807031e+03 4.70862305e+03 4.70965186e+03 4.71038867e+03 4.71039795e+03 4.71022363e+03 4.70904639e+03 4.70869580e+03 4.70813184e+03 4.70532080e+03 4.70346826e+03 4.70071875e+03 4.69670410e+03 4.69464551e+03 4.69168555e+03 4.68656641e+03 4.68342920e+03 4.68004541e+03 4.67602490e+03 4.66952393e+03 4.66306104e+03 4.65911670e+03 4.65128271e+03 4.64378760e+03 4.64083008e+03 4.63231641e+03 4.62191064e+03 4.61210938e+03 4.60795166e+03 4.60097119e+03 4.58873779e+03 4.57995605e+03 4.57328369e+03 4.55918018e+03 4.54674658e+03 4.54223584e+03 4.53053027e+03 4.51466797e+03 4.50590869e+03 4.49689209e+03 4.48135596e+03 4.46904395e+03 4.45302588e+03 4.44414209e+03 4.43212354e+03 4.41164355e+03 4.40088428e+03 4.39052539e+03 4.36893896e+03 4.35497021e+03 4.34530957e+03 4.32982080e+03 4.31383984e+03 4.29367969e+03 4.27410938e+03 4.25703662e+03 4.24271191e+03 4.23040967e+03 4.21502344e+03 4.18849219e+03 4.17081787e+03 4.15854248e+03 4.13161230e+03 4.11393213e+03 4.10329199e+03 4.08416309e+03 4.05244482e+03 4.03342065e+03 4.01880713e+03 3.98920630e+03 3.97059180e+03 3.95737915e+03 3.93625830e+03 3.91923071e+03 3.88999951e+03 3.86798608e+03 3.84192896e+03 3.81453589e+03 3.80912842e+03 3.77917603e+03 3.75064966e+03 3.73145166e+03 3.70782739e+03 3.68499585e+03 3.66057617e+03 3.63430835e+03 3.61500781e+03 3.58920874e+03 3.56472339e+03 3.53816577e+03 3.51301758e+03 3.48738086e+03 3.45880640e+03 3.43898193e+03 3.41475977e+03 3.38237744e+03 3.36299023e+03 3.33432349e+03 3.31047583e+03 3.28034937e+03 3.24538354e+03 3.22878662e+03 3.19363037e+03 3.17410010e+03 3.14762720e+03 3.11784351e+03 3.09438916e+03 3.06266626e+03 3.03517847e+03 3.00986670e+03 2.97952710e+03 2.95101294e+03 2.92630591e+03 2.89369482e+03 2.86931689e+03 2.83398389e+03 2.81520508e+03 2.79181201e+03 2.75465356e+03 2.72937769e+03 2.69927490e+03 2.66493604e+03 2.64633008e+03 2.61950366e+03 2.57598438e+03 2.55250415e+03 2.52861499e+03 2.49649902e+03 2.46569238e+03 2.43749731e+03 2.41183838e+03 2.38163159e+03 2.35079126e+03 2.31875513e+03 2.29126782e+03 2.26674927e+03 2.83345801e+03 2.91511743e+03 3.25044385e+03 3.20105713e+03 3.16442749e+03 3.11931860e+03 3.07777002e+03 4.63524316e+03 5.48162842e+03 6.32809766e+03 5.77519336e+03 5.23485693e+03 -4.13864525e+06 2.83471975e+06 -4.10453325e+06 -7.99086650e+06 8.12041992e+03 5.66129004e+03 3.67486230e+03 4.45135840e+03 1690847. 8.54719312e+05 11848295. 8.22320703e+03 5.50442871e+03 3.25414600e+03 3.19396411e+03 3.95989111e+03 6.62170752e+03 4.67664111e+03 3.07332935e+03 3271804. -4.06989025e+06 -5.99089150e+06 11431451. -16811432. -6201948. -86657752. -12903726. -3.64182150e+06 -22811052. -3.84598225e+06 3875017. 4743081. 3.25752148e+03 3.00589331e+03 1.53403198e+03 2.89188354e+03 2.49071680e+03 2.08880550e+06 6.27993812e+05 9.32451375e+05 15470711. 1534876. -21014038. 4.01521925e+06 2.36973999e+03 9.06548438e+03 4867995. 0. 0. 0. 0. 0. 38563576. 38563576. 38563576. -1.14343825e+06 -5.78278450e+06 2.82440925e+06 43663956. 11207011. 5.50931250e+06 1.45271106e+03 1.07307593e+03 6.21190918e+02 5.97150696e+02 4.62166260e+02 6.04228210e+02 5.83951233e+02 5.30966797e+02 3.99284637e+02 4.71020752e+02 4.58903015e+02 3.46509430e+02 3.23574921e+02 2.55739624e+02 2.42699341e+02 2.30334763e+02 2.18167801e+02 2.06338898e+02 1.94881180e+02 1.83645569e+02 1.72881180e+02 1.62542984e+02 1.52331528e+02 1.42404129e+02 1.32961014e+02 1.23881065e+02 1.15087830e+02 1.06610680e+02 9.84237671e+01 9.06772614e+01 8.32056351e+01 7.60969238e+01 6.93656235e+01 6.29570885e+01 5.68777771e+01 5.11272125e+01 4.57724037e+01 4.07551155e+01 3.60645638e+01 3.17119713e+01 2.77220783e+01 2.41044579e+01 2.08356323e+01 1.79075184e+01 1.53294849e+01 1.30935431e+01 1.12130957e+01 9.70021152e+00 8.55065346e+00 7.74417925e+00 7.29810667e+00 7.19788456e+00 7.45241785e+00 8.06149101e+00 9.02673721e+00 1.03498459e+01 1.20159273e+01 1.40428896e+01 1.64309177e+01 1.91697674e+01 2.22462616e+01 2.56679688e+01 2.94710846e+01 3.36112251e+01 3.81115723e+01 4.29636688e+01 4.81661224e+01 5.36789169e+01 5.95802193e+01 6.57982712e+01 7.23535080e+01 7.92183762e+01 8.65965805e+01 9.40703430e+01 1.01934090e+02 1.10358604e+02 1.19033417e+02 1.27982323e+02 1.37179031e+02 1.46806091e+02 1.56810944e+02 1.67131668e+02 1.77839111e+02 1.88760834e+02 1.99925018e+02 2.11527176e+02 2.23587784e+02 2.35741272e+02 2.48272934e+02 2.61318909e+02 2.74566620e+02 2.87993439e+02 3.01659637e+02 3.16241638e+02 3.30580078e+02 3.44785736e+02 3.60093536e+02 3.75917267e+02 3.91387329e+02 4.07377258e+02 4.23601501e+02 4.39901215e+02 4.56295349e+02 4.73763855e+02 4.92106537e+02 5.09572937e+02 5.26471313e+02 5.44641235e+02 5.64061829e+02 5.82571838e+02 6.01351196e+02 6.21154663e+02 6.40612061e+02 6.59800720e+02 6.80292358e+02 7.01307312e+02 7.21065186e+02 7.41854309e+02 7.63491577e+02 7.85633911e+02 8.06410461e+02 8.27490295e+02 8.49024292e+02 8.70621460e+02 8.92909546e+02 9.19373901e+02 9.40727661e+02 9.63555115e+02 9.86410767e+02 1.00800226e+03 1.03514832e+03 1.05848596e+03 1.08051147e+03 1.10758252e+03 1.13176416e+03 1.15614258e+03 1.18093701e+03 1.20505505e+03 1.22934094e+03 1.25698376e+03 1.28224414e+03 1.30909375e+03 1.33526233e+03 1.35921362e+03 1.38479358e+03 1.41202563e+03 1.45051917e+03 1.46851660e+03 1.48435791e+03 1.51657214e+03 1.54505603e+03 1.57264636e+03 1.60454541e+03 1.62706226e+03 1.65291565e+03 1.69212537e+03 1.71882715e+03 1.73117126e+03 1.75706641e+03 1.79242957e+03 1.82383679e+03 1.84802661e+03 1.87745239e+03 1.90609521e+03 1.93901343e+03 1.96335803e+03 1.99708057e+03 2.02829492e+03 2.75356445e+03 3.08499585e+03 2.83037305e+03 4.49574023e+03 5.73759668e+03 -1.96867325e+06 2.23053375e+05 2.94386156e+05 2.39538925e+06 -64881168. 50180392. 0. 0. -7983493. 37051760. -2.41017375e+06 3.07381650e+06 -1.12501875e+06 4.55874250e+06 -3.03596675e+06 2269566. 8.41041312e+05 2299423. 7.75161523e+03 8.06684766e+03 8.37404395e+03 -1688801. -14095813. 4.16594775e+06 7.95472217e+03 8.59387012e+03 9.27206738e+03 1.07293760e+04 11657493. -17559432. -10511812. 1.90684609e+04 2.92156152e+04 3.42575977e+04 6.53000820e+04 9.03254688e+03 7.42841602e+03 4.79985938e+03 4.83771045e+03 7.99020508e+03 1.03770391e+04 -8278052. -129237984. 1.70063388e+06 1.03043898e+05 3.92791654e+09 -15063129. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -13921537. -13921537. -13921537. 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. 0. 0. 0. 0. 0. 0. 0. 4.71605903e+10 4.71605903e+10 4.71605903e+10 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. 2.48837550e+10 2.48837550e+10 -1675834496. 6.14980915e+09 6.14980915e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -810036672. -810036672. -810036672. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -995181824. -995181824. -995181824. 3.68460902e+09 3.27804500e+05 3.27804500e+05 2430805. 1.99577362e+06 1.99577362e+06 78462640. 0. 0. 0. 0. -56456332. -56456332. -56456332. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.02777436e+10 -1.02777436e+10 -1.02777436e+10 0. 0. 0. 0. 0. 0. 0. -18899010. -18899010. -18899010. 0. 0. 0. 0. 0. 0. 41849560. -1.88696675e+06 -5.04635438e+05 5.34297812e+05 -4374275. -5.19519281e+05 4.58101156e+05 -9463985. -18352446. 0. 0. 0. 67229864. 67229864. 67229864. 0. 0. 0. 436850688. 436850688. 436850688. 38532592. -2599985. 5.37102625e+05 8.06582500e+05 -2358340. 3.01644575e+06 2078089. 13779957. 3.47747812e+04 -5568198. -96177024. -46450972. -46450972. -46450972. 0. 0. 28421382. 28421382. 28421382. 0. 0. 0. 0. 0. 0. -10984622. 1.80027438e+06 6.19420350e+06 3.31191064e+03 2.77707349e+03 1.97032556e+03 1.94184790e+03 1.91623621e+03 1.88316101e+03 1.85228894e+03 1.82979102e+03 1.80050793e+03 1.77305762e+03 1.74496021e+03 1.71269507e+03 1.68913184e+03 1.65632922e+03 1.63079187e+03 1.60454248e+03 1.58152637e+03 1.55373865e+03 1.52503540e+03 1.49693286e+03 1.46670996e+03 1.44366016e+03 1.42256970e+03 1.74176196e+03 1.80253845e+03 2.25162183e+03 1.84219556e+03 1.28669873e+03 1.26400598e+03 1.23546875e+03 1.21370349e+03 1.47163379e+03 1.51057947e+03 1.94956628e+03 1.58500073e+03 1.08593188e+03 1.06248987e+03 1.04106689e+03 1.01760986e+03 9.92929749e+02 9.69602478e+02 9.48734558e+02 9.23406433e+02 8.99373352e+02 8.77159973e+02 8.57834045e+02 8.33811646e+02 8.10625427e+02 7.91584473e+02 7.71053650e+02 7.48321533e+02 7.27570435e+02 7.07503967e+02 6.88054565e+02 6.67298706e+02 6.43922974e+02 6.25157166e+02 6.11442505e+02 5.92896179e+02 5.70713867e+02 5.52737427e+02 5.34713684e+02 5.15750000e+02 4.98705292e+02 4.82327606e+02 4.65412323e+02 4.48631958e+02 4.31727448e+02 4.15908264e+02 4.00174927e+02 3.84205780e+02 3.69131042e+02 3.53751129e+02 3.39720398e+02 3.25215210e+02 3.10884583e+02 2.97421631e+02 2.83540741e+02 2.70667114e+02 2.58330750e+02 2.45727142e+02 2.33693283e+02 2.21604614e+02 2.10418137e+02 1.99210953e+02 1.88482956e+02 1.78138428e+02 1.67655960e+02 1.57765976e+02 1.48440720e+02 1.39294693e+02 1.30445480e+02 1.21990135e+02 1.14012627e+02 1.06217293e+02 9.85406570e+01 9.14391403e+01 8.48119659e+01 7.83752518e+01 7.22881927e+01 6.65275116e+01 6.11458397e+01 5.61540184e+01 5.14590607e+01 4.70722733e+01 4.30528679e+01 3.94733391e+01 3.62646637e+01 3.33909721e+01 3.08420315e+01 2.86619091e+01 2.68007622e+01 2.53038139e+01 2.41745071e+01 2.33739491e+01 2.29073544e+01 2.27859707e+01 2.30697041e+01 2.37266140e+01 2.47265682e+01 2.61251068e+01 2.78514118e+01 2.99022427e+01 3.23029785e+01 3.50594902e+01 3.81888771e+01 4.16567841e+01 4.54758720e+01 4.97764206e+01 5.43022766e+01 5.91935387e+01 6.44465714e+01 6.98130569e+01 7.58060150e+01 8.21851807e+01 8.88246994e+01 9.58222122e+01 1.03104034e+02 1.10721512e+02 1.18441063e+02 1.26911209e+02 1.35807831e+02 1.44639572e+02 1.53877518e+02 1.63573944e+02 1.73799118e+02 1.83991882e+02 1.94728455e+02 2.05701096e+02 2.16895966e+02 2.28677917e+02 2.40699692e+02 2.52961853e+02 2.65712982e+02 2.78612793e+02 2.91657684e+02 3.05222778e+02 3.19383972e+02 3.34011719e+02 3.49450714e+02 3.66637360e+02 3.81641907e+02 3.94730072e+02 4.08208801e+02 7.28216064e+02 4.39188428e+03 12494607. 36285616. 36285616. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9923343. -9923343. -9923343. 0. 6563862. 6563862. 6563862. 0. 0. 0. 0. 8164381. 1.56184125e+06 1.56184125e+06 4.29502188e+04 17139928. 18430230. -1.91015550e+06 1.71296118e+03 5.48952305e+04 3.23776270e+03 1.88443872e+03 1.89195886e+03 1.85210681e+03 3.10884424e+03 2.10701133e+04 1.11769443e+04 1.03440869e+04 4.05493531e+05 5.46889258e+04 3.88390625e+04 2.56882402e+04 11906563. -2.86237425e+06 -2.93441125e+06 -2.93441125e+06 -16127327. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8764063. 3.31571550e+06 -12230095. 3.15771680e+03 2.94375220e+03 2.32903711e+03 2.35173413e+03 2.38453857e+03 2.40927539e+03 2.44031396e+03 2.47301587e+03 2.50510645e+03 2.53526953e+03 2.56589795e+03 2.58964209e+03 2.61659399e+03 2.65190161e+03 2.67786963e+03 2.70350562e+03 2.74041968e+03 2.76251636e+03 2.79001172e+03 2.82122168e+03 2.85108032e+03 2.88066968e+03 2.91093726e+03 2.93444556e+03 2.96487646e+03 2.99019385e+03 3.01511646e+03 3.04362891e+03 3.07777393e+03 3.10047607e+03 3.12811719e+03 3.15534570e+03 3.18575366e+03 3.21335352e+03 3.23665967e+03 3.26524634e+03 3.28054956e+03 3.31850024e+03 3.34900464e+03 3.37422021e+03 3.39066284e+03 3.42034839e+03 3.44216040e+03 3.47441968e+03 3.50144482e+03 3.52146973e+03 3.55006445e+03 3.57592676e+03 3.59812842e+03 3.61936670e+03 3.65810767e+03 3.66531030e+03 3.69035767e+03 3.73086328e+03 3.75011230e+03 3.76806348e+03 3.79181665e+03 3.82068237e+03 3.83991284e+03 3.85229224e+03 3.87960742e+03 3.91114673e+03 3.92251929e+03 3.94534253e+03 3.97557007e+03 3.99569482e+03 4.00587134e+03 4.02605420e+03 4.05426001e+03 4.08389453e+03 4.09459033e+03 4.10876416e+03 4.13436084e+03 4.15400488e+03 4.17054150e+03 4.18948633e+03 4.20625635e+03 4.22356104e+03 4.24681006e+03 4.26432568e+03 4.28082080e+03 4.29830469e+03 4.31514404e+03 4.33270605e+03 4.34439502e+03 4.35887354e+03 4.37287695e+03 4.39627393e+03 4.39991357e+03 4.41846240e+03 4.44401074e+03 4.45015283e+03 4.46312842e+03 4.47591943e+03 4.48949902e+03 4.50127734e+03 4.51501416e+03 4.53344043e+03 4.53742041e+03 4.55068701e+03 4.56356787e+03 4.56973535e+03 4.58203809e+03 4.59240771e+03 4.60298438e+03 4.61044971e+03 4.62256885e+03 4.63523633e+03 4.63917725e+03 4.64517480e+03 4.65217822e+03 4.66264795e+03 4.66994580e+03 4.67740674e+03 4.68343750e+03 4.68923926e+03 4.69414258e+03 4.69906934e+03 4.70381689e+03 4.70827295e+03 4.71361475e+03 4.71742188e+03 4.72130469e+03 4.72442773e+03 4.72760156e+03 4.73014941e+03 4.73239844e+03 4.73392871e+03 4.73555420e+03 4.73638672e+03 4.73743506e+03 4.73813721e+03 4.73810205e+03 4.73792139e+03 4.73685449e+03 4.73656445e+03 4.73585205e+03 4.73263770e+03 4.73070508e+03 4.72794336e+03 4.72358398e+03 4.72234326e+03 4.71903809e+03 4.71317773e+03 4.70956982e+03 4.70740918e+03 4.70438770e+03 4.69667334e+03 4.68949756e+03 4.68592188e+03 4.67990186e+03 4.67061719e+03 4.66688965e+03 4.65844727e+03 4.65005518e+03 4.63993896e+03 4.63153516e+03 4.62514404e+03 4.61650586e+03 4.61016211e+03 4.60001270e+03 4.58497705e+03 4.57537842e+03 4.57014258e+03 4.55572266e+03 4.54045508e+03 4.53525244e+03 4.52074658e+03 4.50540625e+03 4.50287402e+03 4.48221729e+03 4.46649268e+03 4.45499023e+03 4.43792676e+03 4.42965332e+03 4.41365479e+03 4.39394287e+03 4.37919385e+03 4.37049561e+03 4.36004102e+03 4.34127539e+03 4.31784082e+03 4.29553174e+03 4.27937695e+03 4.27252832e+03 4.25771680e+03 4.24477051e+03 4.21509131e+03 4.19316846e+03 4.18235205e+03 4.15692432e+03 4.13955957e+03 4.13003369e+03 4.10871729e+03 4.07421631e+03 4.05527148e+03 4.05246436e+03 4.02251099e+03 3.99948413e+03 3.98132397e+03 3.95200293e+03 3.93971167e+03 3.90988892e+03 3.89277783e+03 3.87244019e+03 3.84344971e+03 3.82900439e+03 3.80232373e+03 3.78010132e+03 3.74661182e+03 3.72818237e+03 3.71583252e+03 3.68054883e+03 3.65399292e+03 3.62947925e+03 3.60612549e+03 3.59116309e+03 3.56444824e+03 3.52693726e+03 3.51541406e+03 3.48676758e+03 3.45499658e+03 3.43929004e+03 3.41265161e+03 3.38660303e+03 3.35059692e+03 3.32871045e+03 3.30633521e+03 3.26621118e+03 3.24514453e+03 3.21628931e+03 3.18730664e+03 3.16899048e+03 3.14845020e+03 3.11776025e+03 3.08066235e+03 3.04974170e+03 3.03093774e+03 2.99718701e+03 2.97353467e+03 2.94769141e+03 2.91726685e+03 2.89203906e+03 2.85567139e+03 2.82753076e+03 2.81186084e+03 2.78130835e+03 2.74265430e+03 2.72085254e+03 2.68520605e+03 2.66564307e+03 2.64138013e+03 2.59839233e+03 2.56700171e+03 2.54455737e+03 2.51626050e+03 2.48481177e+03 2.45358350e+03 2.43091235e+03 2.40169214e+03 2.37172241e+03 2.33434668e+03 2.30934668e+03 2.28600293e+03 2.87736255e+03 3.06633032e+03 -36715064. -3.07122925e+06 4731206. 2.73577094e+05 1.37435094e+05 10544990. -68033392. -13456287. -13456287. -13456287. 0. 0. 0. 0. 16324905. -6799236. -6799236. -41306560. 0. 0. 0. 7699605. -43512684. 1.87243711e+04 -14287130. 16867090. -220500880. -220500880. -220500880. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 122133592. 122133592. 94081440. 42071804. 42071804. 0. 0. 0. 0. 0. 0. 0. -104661096. -104661096. -104661096. 0. 0. 0. 0. 0. 19281788. 19281788. 19281788. 0. 0. 0. 0. 0. 0. -5679472. 3.90570050e+06 -19989876. -7418246. 9.51935242e+02 6.29736267e+02 4.15631073e+02 3.54680817e+02 3.39242401e+02 3.24894135e+02 3.10776978e+02 2.97224609e+02 2.83849945e+02 2.71086212e+02 2.58616119e+02 2.45996033e+02 2.33847824e+02 2.21880219e+02 2.10437119e+02 1.99251999e+02 1.88385178e+02 1.78089508e+02 1.67790268e+02 1.57941330e+02 1.48595184e+02 1.39521591e+02 1.30839203e+02 1.22387840e+02 1.14035744e+02 1.06180878e+02 9.88336639e+01 9.17220154e+01 8.50937576e+01 7.87471466e+01 7.26714554e+01 6.69346771e+01 6.16565781e+01 5.66531754e+01 5.19677811e+01 4.75636253e+01 4.35743065e+01 3.99599419e+01 3.67364845e+01 3.38219643e+01 3.12757797e+01 2.90197983e+01 2.70444260e+01 2.54429226e+01 2.42693462e+01 2.34532433e+01 2.30691814e+01 2.29913979e+01 2.32748528e+01 2.38708973e+01 2.48384590e+01 2.62067356e+01 2.79246387e+01 3.00464821e+01 3.25093727e+01 3.52620659e+01 3.83066902e+01 4.16834793e+01 4.56416893e+01 4.98347015e+01 5.43942566e+01 5.93364601e+01 6.46058884e+01 7.01862488e+01 7.61872711e+01 8.24035339e+01 8.90046997e+01 9.56942062e+01 1.03091034e+02 1.10393120e+02 1.18272690e+02 1.27016335e+02 1.35846741e+02 1.44676407e+02 1.53849777e+02 1.63495651e+02 1.73645599e+02 1.84210983e+02 1.94792099e+02 2.05625290e+02 2.16655579e+02 2.28430923e+02 2.40567017e+02 2.52672455e+02 2.65835999e+02 2.78932312e+02 2.91749756e+02 3.05262421e+02 3.19485687e+02 3.34221710e+02 3.48074524e+02 3.62269104e+02 3.77494446e+02 3.94184967e+02 4.09883820e+02 4.25066864e+02 4.41110321e+02 4.57580017e+02 4.74344391e+02 4.92211517e+02 5.10317383e+02 5.28050781e+02 5.45463257e+02 5.62510620e+02 5.81606262e+02 6.01315613e+02 6.20163391e+02 6.41144714e+02 6.59473145e+02 6.77741516e+02 6.99500061e+02 7.22716736e+02 7.41458374e+02 7.60018066e+02 7.82263428e+02 8.05184265e+02 8.25214111e+02 8.45918579e+02 8.68156250e+02 8.88828125e+02 9.13566956e+02 9.39551208e+02 9.62070251e+02 9.84111816e+02 1.00520343e+03 1.02810193e+03 1.05508777e+03 1.08042310e+03 1.09880151e+03 1.12517261e+03 1.15207739e+03 1.17672778e+03 1.20203699e+03 1.22525232e+03 1.25269226e+03 1.27723682e+03 1.30099976e+03 1.33084802e+03 1.35664099e+03 1.38055212e+03 1.40882361e+03 1.43753699e+03 1.50589502e+03 1.49924622e+03 1.49392114e+03 1.52986682e+03 1.56414294e+03 1.59473987e+03 1.62994727e+03 1.65260095e+03 1.67306714e+03 1.73739233e+03 1.74765527e+03 1.74115222e+03 1.77425024e+03 1.81457495e+03 1.84395776e+03 1.87413550e+03 1.90167468e+03 1.93225183e+03 1.96429871e+03 1.99074390e+03 2.04515674e+03 2.08000732e+03 3.31497290e+03 4.80983154e+03 2.85670264e+03 1.22160078e+04 7249794. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 68573880. 68573880. 68573880. 0. 0. 0. 42910220. 42910220. 42910220. 0. 0. 0. 0. 0. 0. 0. 0. -16968902. 1.66262188e+06 1.17909638e+06 2.09918359e+05 3.79148219e+05 -2.04790812e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.96076850e+06 -6.96076850e+06 -6.96076850e+06 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. 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. 0. 0. 0. 0. 0. 0. 0. 1.24418775e+10 1.24418775e+10 856691200. 6.14980915e+09 6.14980915e+09 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_5.xml ================================================ 16 1024
f
498627904. 2.41588745e+02 5.92198944e+01 5.90848389e+01 5.92807770e+01 5.79948349e+01 5.66465187e+01 5.57279167e+01 5.69209290e+01 5.86400909e+01 5.69737587e+01 5.67713623e+01 5.68107910e+01 5.58918343e+01 5.47810936e+01 5.28905334e+01 5.29704056e+01 5.13272705e+01 5.00665436e+01 5.02461128e+01 5.05456009e+01 4.98336906e+01 4.86147728e+01 4.77962799e+01 4.70892715e+01 4.66116829e+01 4.65550385e+01 4.59910469e+01 4.50324402e+01 4.38789330e+01 4.34917679e+01 4.29626694e+01 4.10706978e+01 4.11935692e+01 4.08542824e+01 4.10242691e+01 4.10540924e+01 4.04658241e+01 3.97344360e+01 3.94233017e+01 3.86280136e+01 3.73208923e+01 3.64139862e+01 3.62406654e+01 3.61791916e+01 3.48244247e+01 3.55552330e+01 3.41890030e+01 3.27713737e+01 3.27497253e+01 3.28378143e+01 3.18889961e+01 3.10577564e+01 3.03442230e+01 2.89279881e+01 2.89092751e+01 2.94389191e+01 2.90093842e+01 2.85799961e+01 2.90512867e+01 2.88822021e+01 2.75046387e+01 2.53393803e+01 2.46700859e+01 2.30315628e+01 2.33881073e+01 2.26605816e+01 2.08106251e+01 2.01210575e+01 2.03338165e+01 1.93901081e+01 1.91250210e+01 1.85585194e+01 1.89785423e+01 1.82925816e+01 1.89370518e+01 1.91105118e+01 1.72210941e+01 1.56445189e+01 1.40186005e+01 1.45547686e+01 1.36918259e+01 1.26562662e+01 9.62047005e+00 8.10994816e+00 2.32663288e+01 -2.14831123e+01 2.20784283e+01 -5.83151794e+02 -1.77710010e+03 9.95683789e+03 -1.15692688e+06 631358784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -69586696. -10739157. -1.17796562e+05 -7.68343384e+02 -3.35646881e+02 1.05685730e+01 1.20289874e+00 -1.27404699e+01 -7.87353363e+01 -8.83537521e+01 -4.30294838e+01 -1.51111536e+01 6.98989058e+00 -5.72426701e+00 -9.15172291e+00 -9.53257656e+00 -1.03865042e+01 -1.10469398e+01 -1.20230865e+01 -1.35833921e+01 -1.37467670e+01 -1.53632174e+01 -1.56322708e+01 -1.63339214e+01 -1.64457474e+01 -7.79566622e+00 3.92904639e+00 7.53420305e+00 -1.56288233e+01 -4.09917641e+01 -3.92011871e+01 -3.82998466e+01 -4.28730621e+01 -5.02815857e+01 -4.55268478e+01 -3.65036621e+01 -2.22583237e+01 -1.14573002e+01 -9.66586399e+00 -7.05900526e+00 -4.90430689e+00 -1.48837376e+01 -2.22320156e+01 -2.32019157e+01 -2.93720169e+01 -3.33702736e+01 -4.65599518e+01 -5.08807640e+01 -4.36541710e+01 -3.64193268e+01 -3.28168335e+01 -3.20724030e+01 -3.29848137e+01 -3.42987976e+01 -3.51029549e+01 -3.71973763e+01 -3.87152634e+01 -4.02729568e+01 -4.01087723e+01 -4.02943993e+01 -3.90528336e+01 -3.44693108e+01 -3.16118374e+01 -3.25376205e+01 -3.27709732e+01 -3.23382339e+01 -3.41835747e+01 -3.64070473e+01 -3.93919945e+01 -4.10978546e+01 -4.24998245e+01 -4.38711929e+01 -4.45320282e+01 -4.49071503e+01 -4.57483292e+01 -4.63179474e+01 -4.77022934e+01 -4.82908211e+01 -4.86814842e+01 -4.86112289e+01 -4.89110489e+01 -4.93358307e+01 -4.96674652e+01 -5.03263664e+01 -5.10101166e+01 -5.15696106e+01 -5.19523849e+01 -5.25532875e+01 -5.32070236e+01 -5.36179237e+01 -5.41556244e+01 -5.45316086e+01 -5.49491501e+01 -5.59661674e+01 -5.67665901e+01 -5.75718994e+01 -5.74961319e+01 -5.78391953e+01 -5.80610619e+01 -5.84404640e+01 -5.94385300e+01 -6.00525093e+01 -6.09001999e+01 -6.10541840e+01 -6.12297401e+01 -6.13703575e+01 -6.18854790e+01 -6.24330978e+01 -6.29745331e+01 -6.39303932e+01 -6.44436417e+01 -6.50142212e+01 -6.55230560e+01 -6.59379120e+01 -6.62714157e+01 -6.65604858e+01 -6.69388046e+01 -6.74593582e+01 -6.78064041e+01 -6.83063431e+01 -6.89401550e+01 -6.95362396e+01 -7.01163559e+01 -7.04306870e+01 -7.06509781e+01 -7.10842743e+01 -7.15050507e+01 -7.20752563e+01 -7.25723724e+01 -7.30880966e+01 -7.34863434e+01 -7.39473267e+01 -7.43516541e+01 -7.47541122e+01 -7.51081390e+01 -7.55006714e+01 -7.59008713e+01 -7.63278885e+01 -7.66787643e+01 -7.70969009e+01 -7.75170670e+01 -7.79119797e+01 -7.82906799e+01 -7.86606293e+01 -7.91153641e+01 -7.95352554e+01 -7.99282074e+01 -8.02989502e+01 -8.06549530e+01 -8.09912720e+01 -8.13694839e+01 -8.17401581e+01 -8.21323395e+01 -8.25048599e+01 -8.29234619e+01 -8.33474884e+01 -8.37639160e+01 -8.41247025e+01 -8.44824600e+01 -8.47717667e+01 -8.51969604e+01 -8.54724274e+01 -8.57972870e+01 -8.61229324e+01 -8.64365005e+01 -8.67119370e+01 -8.69839859e+01 -8.73242950e+01 -8.75503464e+01 -8.78105621e+01 -8.81623459e+01 -8.85264893e+01 -8.88281097e+01 -8.92223892e+01 -8.94846954e+01 -8.97265549e+01 -8.99277573e+01 -9.02937775e+01 -9.07026520e+01 -9.09331970e+01 -9.12528000e+01 -9.15833511e+01 -9.17408295e+01 -9.16772614e+01 -9.19909744e+01 -9.22506027e+01 -9.27857132e+01 -9.31513290e+01 -9.31921310e+01 -9.32644806e+01 -9.37228317e+01 -9.39578629e+01 -9.38539886e+01 -9.41647949e+01 -9.43797455e+01 -9.45077057e+01 -9.47379379e+01 -9.51605301e+01 -9.53309860e+01 -9.53005676e+01 -9.54072800e+01 -9.59012146e+01 -9.57886200e+01 -9.57093964e+01 -9.57211761e+01 -9.61059494e+01 -9.67191772e+01 -9.71251907e+01 -9.73588486e+01 -9.75651932e+01 -9.80237198e+01 -9.85454330e+01 -9.87211151e+01 -9.82304153e+01 -9.80739136e+01 -9.78915329e+01 -9.85357895e+01 -9.89310913e+01 -9.88176270e+01 -9.82462463e+01 -9.88597870e+01 -9.92027740e+01 -9.93990326e+01 -9.85659256e+01 -9.93168793e+01 -1.00034401e+02 -1.01321030e+02 -1.01308006e+02 -1.00502991e+02 -1.00416176e+02 -1.00355705e+02 -1.00648598e+02 -1.00529488e+02 -1.01097244e+02 -1.01190216e+02 -1.01049507e+02 -1.00845840e+02 -1.00549843e+02 -1.00019943e+02 -1.00785866e+02 -1.01592506e+02 -1.01931953e+02 -1.01377815e+02 -1.00814400e+02 -1.01962280e+02 -1.03017899e+02 -1.02317528e+02 -1.01975174e+02 -1.01172356e+02 -1.01735397e+02 -1.02464516e+02 -1.03160492e+02 -1.02236244e+02 -1.01899681e+02 -1.01890945e+02 -1.01865479e+02 -1.02126251e+02 -1.02435280e+02 -1.02560059e+02 -1.01241783e+02 -1.00478523e+02 -1.00402054e+02 -1.00174034e+02 -1.00419250e+02 -1.00182777e+02 -1.00558311e+02 -1.00657288e+02 -1.01528481e+02 -1.02017151e+02 -1.01263802e+02 -1.00693657e+02 -1.00946632e+02 -1.00989822e+02 -1.00950783e+02 -1.00310974e+02 -9.98863144e+01 -1.00222626e+02 -9.93400726e+01 -9.94740524e+01 -9.94321976e+01 -9.91210251e+01 -9.92660675e+01 -9.94449234e+01 -9.91387329e+01 -9.93764801e+01 -9.97194366e+01 -1.00949356e+02 -1.00408539e+02 -1.00344345e+02 -9.87028122e+01 -9.79820633e+01 -9.77215958e+01 -9.82746353e+01 -9.77463074e+01 -9.86185074e+01 -9.93725128e+01 -9.94219818e+01 -9.80685120e+01 -9.80243454e+01 -9.80933762e+01 -9.66507568e+01 -9.62327271e+01 -9.50482864e+01 -9.67913818e+01 -9.63915100e+01 -9.70984802e+01 -9.68798599e+01 -9.66016006e+01 -9.61091995e+01 -9.47688141e+01 -9.54664841e+01 -9.46264801e+01 -9.36605530e+01 -9.29383545e+01 -9.43493271e+01 -9.36168137e+01 -9.40668106e+01 -9.33261032e+01 -9.44258347e+01 -9.37375183e+01 -9.19947739e+01 -9.16794739e+01 -9.11280060e+01 -9.21079865e+01 -9.18942871e+01 -9.29199600e+01 -9.14134598e+01 -9.04920883e+01 -9.02646332e+01 -9.10918198e+01 -9.03389435e+01 -8.96112823e+01 -8.79503250e+01 -8.68146286e+01 -8.69657440e+01 -8.79418106e+01 -8.87617035e+01 -8.96705704e+01 -8.92526932e+01 -8.84205704e+01 -8.74810486e+01 -8.72819138e+01 -8.73137207e+01 -8.66816483e+01 -8.60128784e+01 -8.67790298e+01 -8.61366119e+01 -8.62822952e+01 -8.59459381e+01 -8.41488037e+01 -8.30822372e+01 -8.24557419e+01 -8.37818832e+01 -8.48051758e+01 -8.41861267e+01 -8.33573532e+01 -8.16177902e+01 -8.13782196e+01 -7.97882004e+01 -8.00945435e+01 -8.05150070e+01 -8.09119186e+01 -8.06315155e+01 -7.98756638e+01 -7.85004425e+01 -7.71095657e+01 -7.76831436e+01 -7.75185089e+01 -7.70379639e+01 -7.67404709e+01 -7.62578812e+01 -7.58822937e+01 -7.57480392e+01 -7.59216614e+01 -7.66878891e+01 -7.53633499e+01 -7.41349030e+01 -7.40958481e+01 -7.31122055e+01 -7.19763794e+01 -7.23035507e+01 -7.25305710e+01 -7.21655350e+01 -7.06980591e+01 -7.04621506e+01 -7.04492798e+01 -6.93803177e+01 -6.81313553e+01 -6.86104965e+01 -6.85237045e+01 -6.82143402e+01 -6.74253845e+01 -6.68997269e+01 -6.57978516e+01 -6.53477936e+01 -6.55077820e+01 -6.63985825e+01 -6.51879501e+01 -6.36971626e+01 -6.37176781e+01 -6.33175278e+01 -6.28944206e+01 -6.26600113e+01 -6.21566200e+01 -6.16301765e+01 -6.18123398e+01 -6.13421974e+01 -6.03128090e+01 -5.97312050e+01 -5.90989456e+01 -5.87430153e+01 -5.71107521e+01 -5.65242348e+01 -5.70749550e+01 -5.62955513e+01 -5.61458168e+01 -5.57310181e+01 -5.41556702e+01 -5.39826469e+01 -5.34504623e+01 -5.28242760e+01 -5.26301651e+01 -5.23062630e+01 -5.27128563e+01 -5.13725395e+01 -4.96933250e+01 -4.93511391e+01 -4.91323853e+01 -4.86192513e+01 -4.86039696e+01 -4.82217522e+01 -4.65828209e+01 -4.49333572e+01 -4.51283531e+01 -4.50597038e+01 -4.39906960e+01 -4.44632149e+01 -4.47714119e+01 -4.32896767e+01 -4.07081413e+01 -3.97381020e+01 -3.94524040e+01 -3.96481514e+01 -4.08792267e+01 -4.04584656e+01 -3.95899124e+01 -3.93150787e+01 -3.87591133e+01 -3.75113029e+01 -3.71969452e+01 -3.52932014e+01 -3.43744087e+01 -3.48605728e+01 -3.53623657e+01 -3.45986137e+01 -3.34277534e+01 -3.31020966e+01 -3.31970367e+01 -3.18682232e+01 -3.02541180e+01 -2.92098465e+01 -2.91562481e+01 -2.99039421e+01 -2.95779476e+01 -2.91466637e+01 -2.81178112e+01 -2.84931087e+01 -2.75555000e+01 -2.64853230e+01 -2.59231853e+01 -2.54874802e+01 -2.28705330e+01 -2.34305973e+01 -2.31276245e+01 -2.17019062e+01 -1.97572365e+01 -2.04546432e+01 -2.05694103e+01 -2.06634579e+01 -1.71403904e+01 -1.66725864e+01 -1.81516552e+01 -1.86043110e+01 -1.80430965e+01 -1.64268627e+01 -1.59400654e+01 -1.47297611e+01 -1.39747639e+01 -1.41776152e+01 -1.35989008e+01 -1.18417606e+01 -1.07680216e+01 -1.01154470e+01 -9.77777958e+00 -1.00878859e+01 -1.10376682e+01 -1.07160769e+01 -8.49601364e+00 -7.03721952e+00 -6.41630554e+00 -5.57824373e+00 -6.30696344e+00 -7.20934963e+00 -6.99571514e+00 -4.50894165e+00 -4.24197483e+00 -5.05969334e+00 -5.48225689e+00 -5.02761650e+00 -3.39760852e+00 -1.91462803e+00 -3.94344851e-02 5.81553280e-01 5.03438592e-01 6.84091389e-01 1.89318347e+00 3.77886510e+00 4.29475880e+00 5.01238966e+00 5.81407595e+00 6.94742250e+00 7.22515106e+00 7.53749657e+00 6.44746065e+00 6.59184551e+00 7.31338024e+00 9.71605015e+00 9.99262047e+00 9.69691467e+00 1.03399782e+01 1.23093958e+01 1.40518131e+01 1.40338192e+01 1.54318676e+01 1.47746658e+01 1.49333944e+01 1.52177725e+01 1.64617805e+01 1.66134834e+01 1.74207745e+01 1.87009773e+01 1.98107548e+01 1.90035114e+01 1.88629360e+01 2.02307034e+01 2.28519630e+01 2.35631847e+01 2.35923252e+01 2.30760899e+01 2.32802868e+01 2.30262089e+01 2.33670902e+01 2.39302425e+01 2.59726238e+01 2.64190750e+01 2.71575661e+01 2.87830811e+01 2.81907654e+01 2.97873287e+01 2.93214417e+01 3.03245220e+01 3.01928997e+01 3.11547813e+01 3.21966629e+01 3.24830933e+01 3.34247437e+01 3.43692818e+01 3.48028145e+01 3.52370186e+01 3.67309494e+01 3.63974075e+01 3.67052078e+01 3.66601562e+01 3.75316277e+01 3.74869614e+01 3.79752502e+01 3.91995659e+01 4.01433220e+01 4.11938362e+01 4.11128311e+01 4.19931412e+01 4.22036705e+01 4.27910881e+01 4.37683640e+01 4.46228371e+01 4.44989166e+01 4.49508705e+01 4.59547119e+01 4.72971535e+01 4.79822884e+01 4.84899063e+01 4.84093246e+01 4.85063477e+01 4.89003563e+01 4.94384308e+01 5.00689316e+01 5.06626015e+01 5.12829437e+01 5.16054153e+01 5.20715790e+01 5.24619751e+01 5.27879372e+01 5.36477013e+01 5.40077438e+01 5.44147987e+01 5.54318237e+01 5.61412048e+01 5.72160797e+01 5.73970680e+01 5.75521698e+01 5.76324577e+01 5.80904045e+01 5.91538048e+01 5.96193085e+01 6.04894981e+01 6.05968666e+01 6.10300903e+01 6.12765350e+01 6.18193169e+01 6.25063095e+01 6.28599510e+01 6.37701912e+01 6.42409363e+01 6.45812073e+01 6.49591064e+01 6.54596329e+01 6.60402908e+01 6.63030624e+01 6.66175232e+01 6.72407150e+01 6.76325912e+01 6.81159363e+01 6.85684586e+01 6.90938339e+01 6.97313614e+01 7.03018265e+01 7.05281830e+01 7.08550873e+01 7.13876038e+01 7.20452194e+01 7.24542694e+01 7.28825989e+01 7.32677536e+01 7.37425079e+01 7.42256165e+01 7.46271515e+01 7.49995804e+01 7.54137955e+01 7.58015976e+01 7.62932739e+01 7.65974884e+01 7.70464249e+01 7.74617844e+01 7.79377060e+01 7.83051453e+01 7.86777267e+01 7.90928040e+01 7.94903564e+01 7.98613663e+01 8.02447510e+01 8.06295624e+01 8.10156937e+01 8.13885498e+01 8.17741699e+01 8.21811371e+01 8.25676422e+01 8.29582672e+01 8.33224182e+01 8.36932602e+01 8.40465851e+01 8.43864059e+01 8.46794281e+01 8.50481796e+01 8.53424149e+01 8.56353607e+01 8.59447479e+01 8.62957230e+01 8.65480957e+01 8.69075851e+01 8.72330246e+01 8.74505386e+01 8.77408600e+01 8.81094589e+01 8.84552383e+01 8.87118454e+01 8.89763947e+01 8.91878967e+01 8.93582077e+01 8.95637741e+01 8.99521255e+01 9.03641052e+01 9.06448975e+01 9.09780273e+01 9.11506119e+01 9.13202057e+01 9.13660889e+01 9.18292542e+01 9.21946640e+01 9.26558914e+01 9.29787064e+01 9.29467697e+01 9.31589508e+01 9.35921936e+01 9.37501907e+01 9.38492508e+01 9.39203491e+01 9.42241898e+01 9.47490997e+01 9.47328949e+01 9.50449524e+01 9.52900696e+01 9.53684845e+01 9.55396347e+01 9.58879242e+01 9.60545044e+01 9.59753418e+01 9.59863968e+01 9.63974991e+01 9.68821182e+01 9.71725616e+01 9.74963379e+01 9.75507202e+01 9.81239624e+01 9.85442810e+01 9.85148544e+01 9.81111450e+01 9.81102066e+01 9.76909790e+01 9.82430420e+01 9.84556808e+01 9.86429138e+01 9.83684464e+01 9.89950790e+01 9.88910751e+01 9.92921371e+01 9.86676254e+01 9.93336563e+01 1.00250061e+02 1.01426750e+02 1.01182350e+02 1.00155579e+02 1.00727135e+02 1.00502029e+02 1.00222557e+02 1.00683121e+02 1.00576035e+02 1.00246185e+02 1.00892509e+02 1.00589607e+02 1.00399895e+02 1.00885719e+02 1.01579224e+02 1.02178032e+02 1.02152954e+02 1.01842148e+02 1.01909981e+02 1.01932213e+02 1.02535149e+02 1.02089401e+02 1.02012680e+02 1.01067108e+02 1.01601120e+02 1.01903122e+02 1.02773125e+02 1.02426743e+02 1.01814240e+02 1.01835594e+02 1.01599052e+02 1.01569550e+02 1.02457207e+02 1.02639969e+02 1.01485954e+02 1.01294930e+02 1.00926964e+02 1.00911926e+02 1.00874130e+02 1.00737968e+02 1.00597687e+02 1.00410759e+02 1.01440216e+02 1.01997353e+02 1.02528397e+02 1.02070900e+02 1.02219742e+02 1.01774269e+02 1.02017616e+02 1.01233360e+02 1.00194550e+02 1.00907761e+02 9.97197647e+01 1.00329552e+02 9.99777374e+01 1.00013748e+02 9.99451675e+01 1.00104790e+02 9.95004044e+01 9.92271729e+01 1.03997246e+02 1.35961655e+02 1.83531555e+02 1.70248062e+02 1.11313782e+02 9.64988937e+01 9.65112228e+01 9.93195267e+01 1.01149918e+02 9.99554443e+01 9.50819397e+01 6.76489639e+01 8.74086838e+01 4.49950256e+02 9.55707214e+02 -6369800. 589390080. 0. 0. 0. 0. -98937536. -98937536. -98937536. 0. 0. 0. 107782896. 49361064. 2.63467188e+05 2.74379004e+03 1.21994507e+03 4.26417236e+02 4.10134766e+02 5.41735718e+02 4.84596436e+02 2.74385529e+02 1.29117065e+02 9.82903824e+01 9.31355743e+01 9.30727539e+01 9.13230667e+01 9.04809723e+01 9.02293549e+01 9.10111084e+01 9.09159317e+01 9.87394333e+01 1.42398636e+02 1.81408234e+02 1.52432312e+02 1.05558037e+02 9.19540100e+01 8.86027374e+01 8.35778503e+01 5.77794876e+01 3.29113483e-01 5.49322224e+00 7.10350037e+01 1.23827789e+02 9.72068024e+01 4.79392662e+01 6.82738647e+01 8.72273026e+01 9.16144638e+01 9.13142776e+01 8.69616928e+01 8.41729279e+01 8.43913422e+01 8.41602554e+01 8.49880905e+01 8.42278900e+01 8.22568512e+01 8.25729218e+01 8.11396027e+01 8.12638092e+01 8.11903610e+01 8.17370834e+01 8.12930756e+01 7.98467712e+01 7.94076996e+01 7.84824448e+01 7.81138229e+01 7.74914932e+01 7.71750946e+01 7.66633911e+01 7.63508911e+01 7.60795212e+01 7.67369995e+01 7.60109482e+01 7.64887085e+01 7.60572739e+01 7.49205704e+01 7.38997269e+01 7.24391632e+01 7.17786255e+01 7.30290756e+01 7.30131531e+01 7.23421631e+01 7.06391068e+01 6.96534576e+01 6.85179596e+01 6.81450195e+01 6.74316025e+01 6.75182037e+01 6.76231537e+01 6.75932617e+01 6.62983398e+01 6.55710373e+01 6.55832443e+01 6.50913239e+01 6.29046631e+01 6.12625465e+01 6.40048599e+01 6.63588104e+01 6.43022919e+01 6.32428055e+01 6.36494179e+01 6.23135223e+01 5.95341568e+01 6.10749016e+01 6.27780800e+01 1.81806641e+02 4.90310031e+05 1.80366623e+02 4.48109245e+01 4.52089500e+01 4.48731003e+01 4.43686256e+01 4.45678024e+01 4.45311165e+01 4.44010887e+01 4.39158287e+01 4.38412170e+01 4.45807457e+01 4.42671089e+01 4.36345711e+01 4.34542656e+01 4.29400711e+01 4.27935181e+01 4.24603004e+01 4.20613899e+01 4.15894470e+01 4.15915565e+01 4.15082741e+01 4.11499176e+01 4.09026489e+01 4.07251053e+01 4.03619537e+01 4.02251549e+01 4.00029488e+01 3.97704353e+01 3.95164948e+01 3.96822701e+01 3.92574577e+01 3.87136765e+01 3.82007866e+01 3.82396927e+01 3.82980003e+01 3.85760841e+01 3.81951714e+01 3.80172501e+01 3.75810318e+01 3.71423798e+01 3.67900467e+01 3.67044220e+01 3.69309998e+01 3.65701141e+01 3.63553467e+01 3.62461243e+01 3.58435783e+01 3.53715897e+01 3.54599533e+01 3.51809120e+01 3.48242264e+01 3.44373512e+01 3.42741432e+01 3.37831688e+01 3.37835770e+01 3.40174370e+01 3.35500336e+01 3.34713173e+01 3.28518600e+01 3.25320168e+01 3.22059174e+01 3.19919758e+01 3.21775932e+01 3.14569263e+01 3.11979332e+01 3.16387196e+01 3.13462505e+01 3.09819736e+01 3.06082172e+01 2.97688808e+01 2.97848778e+01 2.97487068e+01 2.91000652e+01 2.83966026e+01 2.84049492e+01 2.89723701e+01 2.82159634e+01 2.84509735e+01 2.72997589e+01 2.74557667e+01 2.62728214e+01 2.61018543e+01 3.18093529e+01 2.88315029e+01 -1.51121002e+02 -3.09821106e+02 2.10239277e+01 -8.20229309e+02 -1.89280566e+03 1.00091553e+04 -2.39030475e+06 1262717568. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -525940352. -3.28226978e+03 -6.93044922e+02 -2.20646667e+01 -2.86388031e+02 -1.53529480e+02 2.40896530e+01 2.13991508e+01 1.16580448e+01 1.66541100e-01 3.14567065e+00 5.59275818e+00 1.37162437e+01 2.20848694e+01 1.76028442e+01 1.67997036e+01 1.55049887e+01 1.48692322e+01 1.51471806e+01 1.47465124e+01 1.48425550e+01 1.47393799e+01 1.48717737e+01 1.42865238e+01 1.33328581e+01 1.28822794e+01 1.64688072e+01 1.92549076e+01 1.80524158e+01 1.21933317e+01 7.44974804e+00 7.65491009e+00 6.97783041e+00 4.49667549e+00 1.52024794e+00 1.89105761e+00 3.68513060e+00 8.25801754e+00 1.20312643e+01 1.26040735e+01 1.32539768e+01 1.37377195e+01 1.12308674e+01 9.75676537e+00 9.31605625e+00 8.04175854e+00 6.44709110e+00 2.12792730e+00 6.32063970e-02 1.90386295e+00 3.56438494e+00 4.28364420e+00 4.06466103e+00 3.90725994e+00 3.69856262e+00 3.19517732e+00 2.34559631e+00 1.92201793e+00 1.39970756e+00 9.38578129e-01 2.46896911e-02 5.28603196e-01 1.90058768e+00 2.79132533e+00 2.25153494e+00 2.30641794e+00 2.18694544e+00 1.52807701e+00 6.60932839e-01 -2.05309838e-01 -1.04047775e+00 -1.71803045e+00 -2.35928273e+00 -2.35625648e+00 -2.89181924e+00 -2.92465639e+00 -3.67526531e+00 -4.06465006e+00 -4.76855135e+00 -4.83689976e+00 -4.78018188e+00 -4.78917742e+00 -5.07528830e+00 -5.51661015e+00 -6.09425688e+00 -6.76420498e+00 -6.92495108e+00 -6.95165539e+00 -7.22491121e+00 -7.48049307e+00 -7.69346285e+00 -8.08646870e+00 -8.60237026e+00 -9.06846619e+00 -9.25016022e+00 -9.48512363e+00 -9.67112541e+00 -9.97195625e+00 -1.01259718e+01 -1.05776510e+01 -1.09383917e+01 -1.13637676e+01 -1.15818253e+01 -1.19257078e+01 -1.22525024e+01 -1.25246496e+01 -1.28495245e+01 -1.30790300e+01 -1.33596754e+01 -1.36701040e+01 -1.41689644e+01 -1.44531059e+01 -1.47302399e+01 -1.49525061e+01 -1.52889128e+01 -1.56187792e+01 -1.58905354e+01 -1.61111164e+01 -1.64349613e+01 -1.67385826e+01 -1.70522175e+01 -1.73310165e+01 -1.76822968e+01 -1.79854660e+01 -1.82887383e+01 -1.85361214e+01 -1.88587666e+01 -1.91644764e+01 -1.95013618e+01 -1.97933140e+01 -2.01352921e+01 -2.04316597e+01 -2.07455826e+01 -2.10168476e+01 -2.13084736e+01 -2.15774956e+01 -2.18775024e+01 -2.21689568e+01 -2.24732914e+01 -2.27473602e+01 -2.30396824e+01 -2.33265686e+01 -2.36103630e+01 -2.38874664e+01 -2.41730289e+01 -2.44710236e+01 -2.47575798e+01 -2.50395374e+01 -2.53224964e+01 -2.55991173e+01 -2.58723373e+01 -2.61530628e+01 -2.64308834e+01 -2.67093773e+01 -2.69819717e+01 -2.72611256e+01 -2.75396976e+01 -2.78145752e+01 -2.80950508e+01 -2.83732738e+01 -2.86314754e+01 -2.89062271e+01 -2.91631832e+01 -2.94343224e+01 -2.97167435e+01 -2.99920406e+01 -3.02624378e+01 -3.04930611e+01 -3.07415466e+01 -3.09590473e+01 -3.12206459e+01 -3.14688740e+01 -3.17346115e+01 -3.19831352e+01 -3.22557945e+01 -3.25038528e+01 -3.27551994e+01 -3.29389954e+01 -3.31878853e+01 -3.34643440e+01 -3.37372475e+01 -3.39929199e+01 -3.43352661e+01 -3.45218658e+01 -3.46744041e+01 -3.47926712e+01 -3.50560570e+01 -3.53554535e+01 -3.57070007e+01 -3.58696594e+01 -3.60891495e+01 -3.63227119e+01 -3.65287552e+01 -3.67253036e+01 -3.69700432e+01 -3.72561874e+01 -3.73992348e+01 -3.76715660e+01 -3.79320908e+01 -3.81506195e+01 -3.82911148e+01 -3.84544182e+01 -3.87243423e+01 -3.89645309e+01 -3.91703072e+01 -3.93403664e+01 -3.94595718e+01 -3.97533951e+01 -4.01400719e+01 -4.03301430e+01 -4.05700645e+01 -4.05076027e+01 -4.07727509e+01 -4.10759125e+01 -4.11627464e+01 -4.14756241e+01 -4.14357071e+01 -4.18327332e+01 -4.23741875e+01 -4.27193336e+01 -4.25870667e+01 -4.26878319e+01 -4.27655869e+01 -4.31689186e+01 -4.31794853e+01 -4.31310806e+01 -4.30921707e+01 -4.36461411e+01 -4.42678337e+01 -4.40756035e+01 -4.47293129e+01 -4.45705566e+01 -4.50213432e+01 -4.50086250e+01 -4.55933762e+01 -4.59693985e+01 -4.55515900e+01 -4.56016045e+01 -4.54644966e+01 -4.55993309e+01 -4.54569359e+01 -4.55021362e+01 -4.58531036e+01 -4.60952454e+01 -4.63517303e+01 -4.68957367e+01 -4.73997993e+01 -4.75055008e+01 -4.76529655e+01 -4.75433426e+01 -4.77100258e+01 -4.78583717e+01 -4.79603653e+01 -4.77616539e+01 -4.78626175e+01 -4.75876350e+01 -4.76368370e+01 -4.80146065e+01 -4.85087128e+01 -4.89930687e+01 -4.83287621e+01 -4.85895767e+01 -4.87449570e+01 -4.94917793e+01 -4.96174583e+01 -4.88020134e+01 -4.90189133e+01 -4.89825401e+01 -4.95774307e+01 -5.00734062e+01 -4.97827606e+01 -5.03581352e+01 -4.98450050e+01 -4.97760239e+01 -5.00693626e+01 -5.01177063e+01 -5.05494919e+01 -5.09090691e+01 -5.13898354e+01 -5.13986511e+01 -5.06451492e+01 -5.06638260e+01 -5.08415871e+01 -5.06793060e+01 -5.05462837e+01 -5.01625557e+01 -5.06355057e+01 -5.08059082e+01 -5.06641006e+01 -5.08308754e+01 -5.12500191e+01 -5.13010750e+01 -5.12372780e+01 -5.12902031e+01 -5.15163307e+01 -5.15334740e+01 -5.15982971e+01 -5.18557053e+01 -5.15361099e+01 -5.15409775e+01 -5.16136360e+01 -5.19197655e+01 -5.14400635e+01 -5.09501724e+01 -5.16153374e+01 -5.19434319e+01 -5.23471298e+01 -5.22417450e+01 -5.19198570e+01 -5.20671043e+01 -5.23260078e+01 -5.22677078e+01 -5.17051239e+01 -5.18833389e+01 -5.19745979e+01 -5.22137604e+01 -5.12431984e+01 -5.22372665e+01 -5.26096954e+01 -5.33910179e+01 -5.29861259e+01 -5.26477394e+01 -5.21280632e+01 -5.18096695e+01 -5.19588966e+01 -5.22336349e+01 -5.22678909e+01 -5.16741028e+01 -5.13551064e+01 -5.20016251e+01 -5.21612167e+01 -5.26379356e+01 -5.16796494e+01 -5.11888542e+01 -5.04822578e+01 -5.10435715e+01 -5.17957611e+01 -5.23347893e+01 -5.25727386e+01 -5.22304077e+01 -5.16186333e+01 -5.09390182e+01 -5.10441780e+01 -5.14639244e+01 -5.13014259e+01 -5.13983803e+01 -5.17241936e+01 -5.15620193e+01 -5.10529404e+01 -5.05594444e+01 -5.06200867e+01 -5.06943092e+01 -5.14267502e+01 -5.13907051e+01 -5.18757515e+01 -5.11086159e+01 -5.07470436e+01 -5.04066544e+01 -5.05729027e+01 -5.03150978e+01 -5.04640846e+01 -5.05581131e+01 -5.04981422e+01 -5.05491562e+01 -5.04851418e+01 -5.01027489e+01 -4.95918579e+01 -4.97872887e+01 -4.99362869e+01 -5.02931252e+01 -5.00446358e+01 -4.96511230e+01 -4.95539513e+01 -4.97186699e+01 -4.97601433e+01 -5.00229378e+01 -4.96589622e+01 -4.94760933e+01 -4.92131271e+01 -4.90236092e+01 -4.86384583e+01 -4.89049644e+01 -4.89301186e+01 -4.88006821e+01 -4.82359886e+01 -4.82353172e+01 -4.81305199e+01 -4.78554764e+01 -4.74334068e+01 -4.76217041e+01 -4.74411812e+01 -4.75512161e+01 -4.73100624e+01 -4.72177849e+01 -4.69003258e+01 -4.67284393e+01 -4.66799355e+01 -4.70018005e+01 -4.66537590e+01 -4.62407379e+01 -4.62221298e+01 -4.60463676e+01 -4.60069847e+01 -4.59336777e+01 -4.57419815e+01 -4.56766205e+01 -4.56339188e+01 -4.54341125e+01 -4.52152596e+01 -4.50539894e+01 -4.47187462e+01 -4.45965958e+01 -4.42270432e+01 -4.40340614e+01 -4.41516571e+01 -4.39476852e+01 -4.38419762e+01 -4.36895523e+01 -4.32534904e+01 -4.30944290e+01 -4.30516853e+01 -4.29152374e+01 -4.28084946e+01 -4.25898170e+01 -4.26164780e+01 -4.21493378e+01 -4.16969795e+01 -4.13689575e+01 -4.12363472e+01 -4.11832657e+01 -4.11805420e+01 -4.09135704e+01 -4.04313927e+01 -3.98115959e+01 -3.97409706e+01 -3.97987900e+01 -3.93929329e+01 -3.94503746e+01 -3.98904343e+01 -3.91812935e+01 -3.83032074e+01 -3.77451820e+01 -3.78431473e+01 -3.77964516e+01 -3.81177330e+01 -3.79194679e+01 -3.78754578e+01 -3.75712738e+01 -3.72193680e+01 -3.69020195e+01 -3.68694572e+01 -3.63188591e+01 -3.60339127e+01 -3.64028511e+01 -3.63128128e+01 -3.59132729e+01 -3.53747177e+01 -3.52982521e+01 -3.52141571e+01 -3.46540108e+01 -3.40992737e+01 -3.40853195e+01 -3.38432007e+01 -3.39484673e+01 -3.40557098e+01 -3.34191132e+01 -3.33898582e+01 -3.26175194e+01 -3.21569443e+01 -3.17942333e+01 -3.18908386e+01 -3.21431122e+01 -3.12770615e+01 -3.13234673e+01 -3.16619263e+01 -3.15334816e+01 -3.08564396e+01 -3.06109829e+01 -3.00046730e+01 -3.00909996e+01 -2.93390064e+01 -2.85738373e+01 -2.84115791e+01 -2.83851585e+01 -2.87106323e+01 -2.80378017e+01 -2.84162884e+01 -2.77878819e+01 -2.77198086e+01 -2.73272552e+01 -2.73449669e+01 -2.69700203e+01 -2.59460812e+01 -2.58745823e+01 -2.54063568e+01 -2.54316826e+01 -2.50115299e+01 -2.49268837e+01 -2.42788734e+01 -2.39581223e+01 -2.35576439e+01 -2.34812908e+01 -2.36880131e+01 -2.43001194e+01 -2.39477005e+01 -2.30675964e+01 -2.25613766e+01 -2.27098179e+01 -2.24265423e+01 -2.22226601e+01 -2.17452660e+01 -2.06412392e+01 -2.01408825e+01 -2.00189571e+01 -2.00997658e+01 -2.03327827e+01 -1.93414898e+01 -1.91609898e+01 -1.89751835e+01 -1.90017948e+01 -1.85258751e+01 -1.71155186e+01 -1.70193272e+01 -1.68802738e+01 -1.75256500e+01 -1.78046036e+01 -1.69877167e+01 -1.68026314e+01 -1.55719776e+01 -1.52342358e+01 -1.52774076e+01 -1.45297041e+01 -1.44930849e+01 -1.44174719e+01 -1.45974169e+01 -1.45281458e+01 -1.38187885e+01 -1.34656248e+01 -1.28479815e+01 -1.23030815e+01 -1.17702551e+01 -1.06846676e+01 -1.05567970e+01 -1.02261944e+01 -1.03669682e+01 -1.01283875e+01 -1.00362253e+01 -9.71504974e+00 -9.45014668e+00 -9.28812885e+00 -9.09733391e+00 -8.76484680e+00 -8.42929649e+00 -8.28222847e+00 -7.43535948e+00 -7.15223551e+00 -6.62459040e+00 -6.45628643e+00 -6.24961662e+00 -5.55082655e+00 -5.44917536e+00 -5.42174578e+00 -5.11003065e+00 -4.63028765e+00 -3.96716857e+00 -4.15681934e+00 -3.93394637e+00 -3.39166975e+00 -2.82437587e+00 -2.77810454e+00 -2.38289285e+00 -2.20803189e+00 -1.55127883e+00 -1.83239913e+00 -1.63551676e+00 -1.76743722e+00 -1.15931463e+00 -7.40579665e-01 -1.08327396e-01 4.69746232e-01 7.16850042e-01 1.00948107e+00 1.28423965e+00 1.75245941e+00 2.20108485e+00 2.23811221e+00 2.54617953e+00 2.59350753e+00 3.38562322e+00 3.91843939e+00 4.48466873e+00 4.67154741e+00 4.63364458e+00 4.61894464e+00 4.91968536e+00 5.31871748e+00 5.92262220e+00 6.53383350e+00 6.77943277e+00 6.81337595e+00 7.03193521e+00 7.29004908e+00 7.53694963e+00 7.91195774e+00 8.46671391e+00 8.93802166e+00 9.18937206e+00 9.43033314e+00 9.59525776e+00 9.91689205e+00 1.00218639e+01 1.04323425e+01 1.07675304e+01 1.12207632e+01 1.14511738e+01 1.18755550e+01 1.21501408e+01 1.24368849e+01 1.27972412e+01 1.30745687e+01 1.33207903e+01 1.36408577e+01 1.41476421e+01 1.44049149e+01 1.46161823e+01 1.48545828e+01 1.52194471e+01 1.55845337e+01 1.58370810e+01 1.60382004e+01 1.63902435e+01 1.66795635e+01 1.69568253e+01 1.72522106e+01 1.76068630e+01 1.79072838e+01 1.82494774e+01 1.84587803e+01 1.87577038e+01 1.90960884e+01 1.94464531e+01 1.97382393e+01 2.00519447e+01 2.03255424e+01 2.06461239e+01 2.09414749e+01 2.12345695e+01 2.14932823e+01 2.17980366e+01 2.20794392e+01 2.24008503e+01 2.26771355e+01 2.29692593e+01 2.32402344e+01 2.35310249e+01 2.38103752e+01 2.40908451e+01 2.43811150e+01 2.46588497e+01 2.49413128e+01 2.52334766e+01 2.55263100e+01 2.58096790e+01 2.60909214e+01 2.63687534e+01 2.66541538e+01 2.69340191e+01 2.72220383e+01 2.75058651e+01 2.77803364e+01 2.80627937e+01 2.83431110e+01 2.86104527e+01 2.88737736e+01 2.91332893e+01 2.93892479e+01 2.96761761e+01 2.99468765e+01 3.01977787e+01 3.04509754e+01 3.07123184e+01 3.09514027e+01 3.12085247e+01 3.14404144e+01 3.16984177e+01 3.19675922e+01 3.22360458e+01 3.24560432e+01 3.26784172e+01 3.28924942e+01 3.31568832e+01 3.34473000e+01 3.37077217e+01 3.40317612e+01 3.43027039e+01 3.44867020e+01 3.46872787e+01 3.48943405e+01 3.52141075e+01 3.54568558e+01 3.57564087e+01 3.59227562e+01 3.61811981e+01 3.63756065e+01 3.65718040e+01 3.67877960e+01 3.69460144e+01 3.72453613e+01 3.74795303e+01 3.77369766e+01 3.78960228e+01 3.80713844e+01 3.82120781e+01 3.84429779e+01 3.86453934e+01 3.88357773e+01 3.90620613e+01 3.93016472e+01 3.95595970e+01 3.98084831e+01 4.01737671e+01 4.02593842e+01 4.04924240e+01 4.05314255e+01 4.07333679e+01 4.09774017e+01 4.10945168e+01 4.14229584e+01 4.13967781e+01 4.16855469e+01 4.21569977e+01 4.26664467e+01 4.25514870e+01 4.26980667e+01 4.26140785e+01 4.31125946e+01 4.31791267e+01 4.32022705e+01 4.32368546e+01 4.37148285e+01 4.42477646e+01 4.40108452e+01 4.47258987e+01 4.45758781e+01 4.49515190e+01 4.49997139e+01 4.55872421e+01 4.57312737e+01 4.54495201e+01 4.55215149e+01 4.53561440e+01 4.57080116e+01 4.56407585e+01 4.58426819e+01 4.61459732e+01 4.62278099e+01 4.64635658e+01 4.67655678e+01 4.72496605e+01 4.76156387e+01 4.75485992e+01 4.73596840e+01 4.73621292e+01 4.76305313e+01 4.77863731e+01 4.78256493e+01 4.77631416e+01 4.75442963e+01 4.76449356e+01 4.80719833e+01 4.85010262e+01 4.89313965e+01 4.86577110e+01 4.88862076e+01 4.88872719e+01 4.94141846e+01 4.96230049e+01 4.88900566e+01 4.90398102e+01 4.89802780e+01 4.98457069e+01 5.02765961e+01 5.02549858e+01 5.07550201e+01 4.98754387e+01 4.96397285e+01 5.01527443e+01 5.01508331e+01 5.07373962e+01 5.10957527e+01 5.16451988e+01 5.15867958e+01 5.08365364e+01 5.09271660e+01 5.10672989e+01 5.09784966e+01 5.06509323e+01 5.01558647e+01 5.19949226e+01 6.12479362e+01 6.93582382e+01 6.38168411e+01 6.34509621e+01 6.09976006e+01 5.13305016e+01 5.16332474e+01 5.19545593e+01 5.17580719e+01 5.02376404e+01 4.19923363e+01 4.97051392e+01 2.27152893e+02 3.40565338e+02 7.39964783e+02 1.85993140e+03 -1236108928. -136547312. 0. 0. -98937536. -98937536. -98937536. 0. 0. 0. 107782896. 49361064. 2.63467188e+05 2.86556934e+03 1.42557263e+03 7.29259094e+02 5.02961182e+02 1.83942474e+02 1.17092186e+02 1.22467903e+02 1.02102211e+02 7.50737228e+01 5.76923676e+01 5.41813049e+01 5.24525185e+01 5.12733727e+01 5.19848671e+01 5.20324974e+01 5.26130753e+01 5.45253525e+01 6.80381775e+01 7.99459305e+01 6.87925034e+01 5.35921745e+01 5.08193741e+01 5.11699142e+01 5.31282654e+01 4.81993866e+01 3.34195671e+01 3.25698280e+01 4.62402382e+01 5.67753906e+01 5.13234901e+01 4.14278374e+01 3.14299698e+01 2.28703728e+01 5.19153519e+01 7.27911835e+01 6.05594978e+01 5.51415596e+01 5.27675476e+01 5.21409912e+01 5.14730301e+01 5.11547508e+01 5.07803841e+01 5.11312027e+01 5.09247093e+01 5.08134880e+01 5.08658485e+01 5.10465317e+01 5.09758949e+01 5.05220528e+01 5.02670364e+01 5.00120277e+01 5.00919456e+01 5.00552101e+01 5.02920494e+01 4.99116135e+01 4.95273590e+01 4.96843376e+01 5.00699463e+01 4.97331657e+01 4.97362442e+01 4.96479759e+01 4.97727928e+01 4.94136124e+01 4.90859375e+01 4.87971153e+01 4.92309151e+01 4.90877876e+01 4.88939629e+01 4.83249588e+01 4.80955849e+01 4.74638023e+01 4.73795891e+01 4.70125809e+01 4.73947792e+01 4.73509216e+01 4.71954765e+01 4.69554787e+01 4.70047264e+01 4.68991394e+01 4.64853935e+01 4.61607895e+01 4.79767609e+01 4.69671211e+01 4.52934952e+01 4.55392838e+01 4.53598213e+01 4.61188393e+01 4.63892059e+01 4.83512383e+01 5.07480774e+01 4.56660805e+01 1.29606369e+02 1.33100984e+05 5.39616814e+01 1.33902073e+01 1.27749176e+01 1.05951252e+01 9.90281010e+00 1.26235151e+01 1.38836794e+01 9.86278629e+00 9.61269665e+00 1.05530863e+01 1.04573736e+01 1.18136663e+01 1.16632500e+01 1.17562323e+01 1.12630396e+01 1.11900539e+01 1.10580177e+01 1.08201571e+01 1.03689127e+01 1.03618851e+01 1.02228289e+01 9.91390705e+00 1.02493534e+01 1.00156546e+01 9.38017178e+00 9.24159050e+00 9.27056122e+00 9.36320972e+00 8.90153408e+00 9.01155567e+00 8.93831825e+00 8.66336060e+00 8.20396519e+00 8.05763626e+00 7.74214172e+00 7.95010805e+00 7.93403864e+00 7.82194567e+00 7.29047060e+00 7.07787657e+00 6.91819525e+00 6.59043741e+00 6.75485897e+00 6.54678440e+00 6.27815151e+00 6.05446434e+00 5.97398758e+00 5.97526026e+00 5.82765532e+00 5.70309162e+00 5.48164463e+00 5.77245283e+00 5.60281134e+00 5.36104441e+00 4.59623575e+00 4.43641663e+00 4.27546406e+00 4.26280165e+00 3.66314387e+00 3.39923263e+00 3.35252929e+00 4.00854397e+00 4.10376692e+00 3.92229819e+00 3.27891278e+00 3.13866830e+00 2.93472815e+00 2.79825616e+00 2.32750463e+00 1.93600380e+00 1.83094537e+00 2.06926370e+00 1.12322593e+00 3.03412437e-01 4.04300570e-01 5.37846625e-01 4.67989028e-01 6.05625391e-01 -1.64629802e-01 7.70140469e-01 6.26422644e+00 -1.91560432e-01 -1.84940781e+02 -3.15485687e+02 -7.37170593e+02 3.07741974e+02 3.62243690e+01 -1.49504382e+03 -1157379584. 1262717568. 1262717568. 2.71939975e+06 92080408. 92080408. 0. 0. 0. 0. 0. 0. -550745792. 140042224. -5.73526055e+04 -1.66581177e+03 -7.06874634e+02 -1.87422485e+02 -8.99699783e+00 -8.27484417e+00 -4.76126051e+00 -7.24731731e+00 -1.07099590e+01 -1.17835617e+01 -2.12070503e+01 -1.27267752e+01 -1.83697331e+00 -2.64459133e+00 -4.33061123e+00 -4.92620945e+00 -4.86761236e+00 -5.78967285e+00 -6.31514454e+00 -6.37784958e+00 -6.52029800e+00 -6.00798798e+00 -5.70616865e+00 -5.39506483e+00 -5.98507738e+00 -6.45047760e+00 -7.19792795e+00 -7.32002115e+00 -6.50751162e+00 -5.65706825e+00 -8.18093681e+00 -1.05368834e+01 -1.00856056e+01 -9.27746201e+00 -8.96066380e+00 -8.88834190e+00 -8.92342091e+00 -9.18766689e+00 -8.47186375e+00 -8.60376740e+00 -8.91698742e+00 -8.82754993e+00 -8.11217976e+00 -9.30436611e+00 -1.01191788e+01 -1.05847282e+01 -9.91865349e+00 -1.00485220e+01 -1.00199261e+01 -1.00114937e+01 -1.00982389e+01 -1.05744791e+01 -1.13139019e+01 -1.19551325e+01 -1.17863321e+01 -1.17140598e+01 -1.15208912e+01 -1.15731230e+01 -1.13362179e+01 -1.14055576e+01 -1.19560881e+01 -1.22177610e+01 -1.24465113e+01 -1.22413826e+01 -1.21855316e+01 -1.22449760e+01 -1.22636700e+01 -1.27715816e+01 -1.27998295e+01 -1.32751904e+01 -1.36730146e+01 -1.44950399e+01 -1.45504208e+01 -1.44678402e+01 -1.41861115e+01 -1.44462404e+01 -1.41841831e+01 -1.43522434e+01 -1.43763685e+01 -1.47831297e+01 -1.49999695e+01 -1.50043192e+01 -1.51677713e+01 -1.53341427e+01 -1.56072779e+01 -1.57225399e+01 -1.60401573e+01 -1.61860867e+01 -1.60194988e+01 -1.59967413e+01 -1.59766855e+01 -1.63001213e+01 -1.65253658e+01 -1.69167919e+01 -1.70886879e+01 -1.68218040e+01 -1.67499237e+01 -1.67587738e+01 -1.71484547e+01 -1.74426899e+01 -1.77100067e+01 -1.78527527e+01 -1.76631908e+01 -1.77582664e+01 -1.75914154e+01 -1.78815460e+01 -1.81401386e+01 -1.84839306e+01 -1.85245686e+01 -1.84418602e+01 -1.84924965e+01 -1.86998215e+01 -1.88469257e+01 -1.89274921e+01 -1.89167061e+01 -1.90606709e+01 -1.91961823e+01 -1.94247093e+01 -1.95094700e+01 -1.96330814e+01 -1.97519112e+01 -1.98765259e+01 -1.98834743e+01 -2.00172539e+01 -2.00820808e+01 -2.01966648e+01 -2.03426685e+01 -2.04996910e+01 -2.05912437e+01 -2.06618690e+01 -2.07325840e+01 -2.08544636e+01 -2.09803066e+01 -2.10642929e+01 -2.11497784e+01 -2.12280045e+01 -2.13149738e+01 -2.14335499e+01 -2.15374851e+01 -2.16526871e+01 -2.17411957e+01 -2.18326702e+01 -2.19219418e+01 -2.20072174e+01 -2.20982628e+01 -2.21925068e+01 -2.22851868e+01 -2.23733482e+01 -2.24538860e+01 -2.25381947e+01 -2.26203632e+01 -2.27019100e+01 -2.27856426e+01 -2.28677559e+01 -2.29444618e+01 -2.30186443e+01 -2.30903454e+01 -2.31696148e+01 -2.32409210e+01 -2.33255672e+01 -2.33978233e+01 -2.34686737e+01 -2.35442867e+01 -2.36109562e+01 -2.36723480e+01 -2.37524052e+01 -2.38307629e+01 -2.38977509e+01 -2.39734764e+01 -2.40381660e+01 -2.40948124e+01 -2.41601601e+01 -2.42013206e+01 -2.42598305e+01 -2.43251534e+01 -2.43854675e+01 -2.44546299e+01 -2.45238037e+01 -2.45456562e+01 -2.46025105e+01 -2.47230415e+01 -2.48099270e+01 -2.48098278e+01 -2.49256840e+01 -2.49542160e+01 -2.50411930e+01 -2.49868927e+01 -2.50153236e+01 -2.50549660e+01 -2.51950226e+01 -2.52477493e+01 -2.53418026e+01 -2.53014107e+01 -2.53712311e+01 -2.53995075e+01 -2.54597492e+01 -2.55333157e+01 -2.54946098e+01 -2.56188221e+01 -2.55726013e+01 -2.56797829e+01 -2.56975842e+01 -2.56494560e+01 -2.57870522e+01 -2.59222050e+01 -2.60516052e+01 -2.60498180e+01 -2.59578972e+01 -2.58217754e+01 -2.58721638e+01 -2.60512924e+01 -2.60399590e+01 -2.57084007e+01 -2.57467670e+01 -2.59388657e+01 -2.61858959e+01 -2.63230247e+01 -2.64060745e+01 -2.62181759e+01 -2.62560272e+01 -2.64382381e+01 -2.65322475e+01 -2.62467804e+01 -2.63507175e+01 -2.63764935e+01 -2.64004726e+01 -2.57637329e+01 -2.53333454e+01 -2.53362312e+01 -2.56304207e+01 -2.57881794e+01 -2.62971363e+01 -2.63533535e+01 -2.64927921e+01 -2.59224834e+01 -2.60922203e+01 -2.64201622e+01 -2.63152409e+01 -2.65539532e+01 -2.64173393e+01 -2.66042747e+01 -2.59777985e+01 -2.57875271e+01 -2.59522781e+01 -2.65298233e+01 -2.62423840e+01 -2.60939102e+01 -2.58553276e+01 -2.63702068e+01 -2.64635010e+01 -2.67102280e+01 -2.63834858e+01 -2.63523941e+01 -2.58846302e+01 -2.58075542e+01 -2.60980320e+01 -2.57938061e+01 -2.58424702e+01 -2.57843628e+01 -2.63086033e+01 -2.68152752e+01 -2.64827538e+01 -2.67968540e+01 -2.67152271e+01 -2.72765388e+01 -2.69283085e+01 -2.63590794e+01 -2.63265476e+01 -2.59968624e+01 -2.60329723e+01 -2.58096313e+01 -2.60599079e+01 -2.65241108e+01 -2.59759274e+01 -2.55831833e+01 -2.54518356e+01 -2.56175385e+01 -2.62905273e+01 -2.68215542e+01 -2.73621387e+01 -2.66237564e+01 -2.58982239e+01 -2.57981224e+01 -2.60155182e+01 -2.58328724e+01 -2.58117332e+01 -2.50968475e+01 -2.49051323e+01 -2.44302216e+01 -2.45355835e+01 -2.44189110e+01 -2.45243416e+01 -2.45747700e+01 -2.40672340e+01 -2.44777603e+01 -2.48424053e+01 -2.48624821e+01 -2.47891426e+01 -2.52877159e+01 -2.48231659e+01 -2.45212040e+01 -2.37441216e+01 -2.48467903e+01 -2.42423801e+01 -2.47391930e+01 -2.46170197e+01 -2.49947872e+01 -2.43468113e+01 -2.36111202e+01 -2.26187572e+01 -2.34441948e+01 -2.38419228e+01 -2.43170547e+01 -2.41501865e+01 -2.43953896e+01 -2.42584896e+01 -2.33405094e+01 -2.25082417e+01 -2.27030373e+01 -2.31483326e+01 -2.32590237e+01 -2.33592587e+01 -2.37920418e+01 -2.32590008e+01 -2.35075569e+01 -2.30128937e+01 -2.24476223e+01 -2.18359604e+01 -2.14026051e+01 -2.17509193e+01 -2.19496021e+01 -2.16474476e+01 -2.20748386e+01 -2.18056965e+01 -2.20282421e+01 -2.16314850e+01 -2.15104408e+01 -2.16175385e+01 -2.14739857e+01 -2.11872406e+01 -2.09194260e+01 -2.08640480e+01 -2.02720356e+01 -2.02685165e+01 -2.08274403e+01 -2.07907848e+01 -2.10152988e+01 -2.05363483e+01 -2.02247791e+01 -1.94534359e+01 -1.91752071e+01 -1.97994041e+01 -2.04346542e+01 -2.09222431e+01 -2.01216087e+01 -1.94519520e+01 -1.88255806e+01 -1.88269558e+01 -1.92401180e+01 -1.92400188e+01 -1.97746468e+01 -1.95104141e+01 -1.91688557e+01 -1.84358006e+01 -1.84823551e+01 -1.87284584e+01 -1.86919823e+01 -1.83450642e+01 -1.84417210e+01 -1.84387684e+01 -1.90852470e+01 -1.85925541e+01 -1.85217991e+01 -1.81121712e+01 -1.78021278e+01 -1.75620937e+01 -1.74640713e+01 -1.74348049e+01 -1.75511875e+01 -1.72987118e+01 -1.73367462e+01 -1.69706306e+01 -1.68278255e+01 -1.65971107e+01 -1.64026318e+01 -1.62798061e+01 -1.63701954e+01 -1.63428822e+01 -1.59491024e+01 -1.57343702e+01 -1.56738052e+01 -1.55430899e+01 -1.54175596e+01 -1.50545425e+01 -1.50902166e+01 -1.49578352e+01 -1.47498264e+01 -1.47060127e+01 -1.49521027e+01 -1.46046448e+01 -1.42216625e+01 -1.42447662e+01 -1.40974607e+01 -1.39834862e+01 -1.39835186e+01 -1.38510189e+01 -1.36671915e+01 -1.35033960e+01 -1.34014158e+01 -1.33169079e+01 -1.31288471e+01 -1.28536968e+01 -1.28402033e+01 -1.26239204e+01 -1.22927113e+01 -1.24943266e+01 -1.22813473e+01 -1.20474710e+01 -1.20506468e+01 -1.16686583e+01 -1.14128227e+01 -1.14719095e+01 -1.14773245e+01 -1.14613400e+01 -1.13507328e+01 -1.11926289e+01 -1.08602753e+01 -1.06176519e+01 -1.01951275e+01 -1.00677662e+01 -1.00165215e+01 -9.89612865e+00 -1.00541525e+01 -9.87253094e+00 -9.05617332e+00 -8.95323563e+00 -9.03146839e+00 -8.92118645e+00 -8.87392044e+00 -9.44189453e+00 -9.08065891e+00 -8.43302059e+00 -8.04153538e+00 -7.89392376e+00 -7.55847168e+00 -7.69976950e+00 -7.72839451e+00 -7.72205210e+00 -7.52776814e+00 -7.35234880e+00 -7.11569786e+00 -6.94772387e+00 -6.81051445e+00 -6.63695526e+00 -6.71701241e+00 -6.38193464e+00 -6.39041138e+00 -6.51413774e+00 -6.19102335e+00 -6.45368910e+00 -6.08766222e+00 -5.84212923e+00 -5.57905245e+00 -5.34430981e+00 -4.90830946e+00 -4.63110018e+00 -4.31151390e+00 -4.22713614e+00 -3.47396922e+00 -3.25540328e+00 -3.25839305e+00 -4.27704334e+00 -4.62015533e+00 -4.39536572e+00 -3.61504269e+00 -3.58118033e+00 -3.39652610e+00 -3.38188481e+00 -2.89807200e+00 -2.54852772e+00 -2.18502903e+00 -1.56664681e+00 -6.94627166e-01 -1.50296152e-01 -1.81656614e-01 -2.39504337e-01 -2.96899199e-01 -9.92696524e-01 -9.22977269e-01 -9.88087237e-01 -5.12817800e-01 -6.95958138e-01 -8.19210052e-01 -2.12011456e-01 -2.22373337e-01 -2.02256233e-01 -1.17717929e-01 8.44854176e-01 1.30661154e+00 1.26765358e+00 7.33951092e-01 8.25791419e-01 1.27101719e+00 2.01154900e+00 1.46505606e+00 1.35938776e+00 1.26766551e+00 1.47504365e+00 2.07085419e+00 2.65120292e+00 2.92689013e+00 2.49462461e+00 2.75223398e+00 2.55656958e+00 2.91996813e+00 2.68613720e+00 2.31508160e+00 3.06980371e+00 2.97495031e+00 3.51188111e+00 3.26627135e+00 3.91478777e+00 4.67662096e+00 4.77108145e+00 4.90799475e+00 4.89481115e+00 4.89649391e+00 5.21585035e+00 5.01283169e+00 5.64126730e+00 5.86944962e+00 6.16194105e+00 6.38908958e+00 5.67779303e+00 5.43977690e+00 4.89825058e+00 5.61817169e+00 5.81404686e+00 6.34972715e+00 6.71303129e+00 7.31437492e+00 7.04030180e+00 7.66874695e+00 8.21564007e+00 8.75712585e+00 8.54203892e+00 8.50124550e+00 8.54743671e+00 8.46293354e+00 8.93129253e+00 8.57940102e+00 8.68832970e+00 9.00142097e+00 9.02846718e+00 8.79906654e+00 9.38977146e+00 9.57266140e+00 1.03420677e+01 9.91228008e+00 1.00527430e+01 1.00310450e+01 1.02799892e+01 1.01035604e+01 1.06483612e+01 1.12120628e+01 1.17487936e+01 1.11006126e+01 1.11377573e+01 1.11676550e+01 1.12818022e+01 1.11054182e+01 1.12444706e+01 1.18063316e+01 1.22574511e+01 1.25287428e+01 1.25221767e+01 1.25156088e+01 1.25594654e+01 1.22626123e+01 1.26020718e+01 1.27162886e+01 1.31036272e+01 1.35508881e+01 1.40781097e+01 1.41173458e+01 1.40146303e+01 1.40321569e+01 1.43582373e+01 1.43249121e+01 1.44712229e+01 1.46088467e+01 1.47477369e+01 1.49352541e+01 1.49590645e+01 1.50718565e+01 1.52619829e+01 1.53959703e+01 1.54663668e+01 1.58601933e+01 1.60610504e+01 1.59065123e+01 1.59531851e+01 1.60361538e+01 1.62673626e+01 1.65164089e+01 1.68645344e+01 1.70113926e+01 1.67826061e+01 1.66884537e+01 1.66595173e+01 1.70125179e+01 1.73656807e+01 1.76224785e+01 1.77380905e+01 1.76236897e+01 1.76661549e+01 1.75911217e+01 1.78458424e+01 1.81356144e+01 1.85274582e+01 1.85017033e+01 1.84497204e+01 1.84453220e+01 1.87202473e+01 1.88724957e+01 1.89217110e+01 1.88753834e+01 1.91290951e+01 1.92223587e+01 1.93300304e+01 1.94374256e+01 1.95820446e+01 1.96786861e+01 1.97113094e+01 1.98380222e+01 1.99809475e+01 2.00412617e+01 2.01416321e+01 2.02526226e+01 2.04177933e+01 2.04989967e+01 2.05574303e+01 2.06091175e+01 2.07147560e+01 2.08383350e+01 2.09473629e+01 2.10791969e+01 2.11608658e+01 2.12259712e+01 2.13592529e+01 2.14516335e+01 2.15672398e+01 2.16426849e+01 2.17381744e+01 2.18372021e+01 2.19209728e+01 2.20050507e+01 2.20879593e+01 2.21854267e+01 2.22733078e+01 2.23659668e+01 2.24633503e+01 2.25560970e+01 2.26410923e+01 2.27369709e+01 2.28242474e+01 2.29145069e+01 2.29914207e+01 2.30791740e+01 2.31697445e+01 2.32632771e+01 2.33606625e+01 2.34453297e+01 2.35105133e+01 2.35843258e+01 2.36724129e+01 2.37190304e+01 2.37970333e+01 2.38777122e+01 2.39308414e+01 2.40064602e+01 2.40846672e+01 2.41508713e+01 2.42249794e+01 2.42600346e+01 2.43337345e+01 2.44004135e+01 2.44635372e+01 2.45662785e+01 2.46190529e+01 2.46155205e+01 2.46897793e+01 2.47610531e+01 2.48531475e+01 2.49440327e+01 2.50425835e+01 2.50592670e+01 2.50886192e+01 2.51061935e+01 2.51991100e+01 2.51924782e+01 2.52563972e+01 2.52689552e+01 2.53329029e+01 2.52601261e+01 2.53086262e+01 2.53665218e+01 2.53551559e+01 2.54292603e+01 2.55204868e+01 2.56089935e+01 2.54871883e+01 2.55334244e+01 2.55486794e+01 2.55149822e+01 2.56103745e+01 2.57986317e+01 2.59904537e+01 2.59126625e+01 2.58779430e+01 2.57395859e+01 2.58059444e+01 2.58666821e+01 2.59594269e+01 2.56737232e+01 2.56761131e+01 2.58218594e+01 2.61569042e+01 2.63331299e+01 2.64826450e+01 2.61922226e+01 2.61478882e+01 2.63532352e+01 2.64842472e+01 2.62757969e+01 2.61541080e+01 2.61857433e+01 2.62808590e+01 2.57954617e+01 2.54428387e+01 2.55633698e+01 2.57402096e+01 2.56141090e+01 2.62251415e+01 2.63937340e+01 2.64614258e+01 2.60507717e+01 2.62314339e+01 2.64657116e+01 2.63443832e+01 2.64844341e+01 2.62705212e+01 2.64939556e+01 2.60366898e+01 2.59753494e+01 2.61345406e+01 2.62822304e+01 2.61431885e+01 2.62318611e+01 2.60022583e+01 2.64264088e+01 2.63790150e+01 2.67137280e+01 2.63352528e+01 2.62620544e+01 2.58849144e+01 2.59558163e+01 2.60361576e+01 2.58106785e+01 2.62163200e+01 2.61836433e+01 2.65648403e+01 2.68722305e+01 2.66858711e+01 2.69447556e+01 2.63872547e+01 2.67275448e+01 2.64342556e+01 2.60836697e+01 2.59167538e+01 2.56923313e+01 2.60016079e+01 2.60533695e+01 2.61899319e+01 2.65056210e+01 2.57622242e+01 2.53463593e+01 2.53218365e+01 2.53175049e+01 2.61615410e+01 2.68026428e+01 2.74650421e+01 2.67518616e+01 2.61429768e+01 2.54817657e+01 2.53992500e+01 2.49794788e+01 2.51791725e+01 2.51744766e+01 2.52965755e+01 2.46114922e+01 3.18383369e+01 3.41654625e+01 3.61652908e+01 3.48056717e+01 3.20986748e+01 3.17741356e+01 2.42640934e+01 2.43357906e+01 2.44072132e+01 2.48824406e+01 2.36215916e+01 1.83942432e+01 1.84729843e+01 1.90545746e+02 3.18846436e+02 7.12812073e+02 1.94963647e+03 -60530716. -258594160. 0. 0. 0. 2.47411738e+09 2.47411738e+09 2.47411738e+09 0. 0. 0. -131358120. -12028001. 4.35065283e+03 1.46256641e+03 5.33941772e+02 5.45680054e+02 3.58925232e+02 7.41854935e+01 7.70873184e+01 6.01129608e+01 3.92529106e+01 2.75622482e+01 3.16602802e+01 2.89503975e+01 2.14676437e+01 2.08135910e+01 2.09586182e+01 2.46894455e+01 3.95274925e+01 3.91885529e+01 2.37200165e+01 1.94804440e+01 1.93964939e+01 2.17340622e+01 1.85164051e+01 1.14168196e+01 1.27655106e+01 1.91769123e+01 2.41482182e+01 1.31150942e+01 1.46092892e+01 1.13477345e+01 -6.49850988e+00 1.16751995e+01 2.45378208e+01 1.82607880e+01 2.63004131e+01 2.95520515e+01 2.36303787e+01 2.06457844e+01 1.93320618e+01 1.94443588e+01 1.95641727e+01 2.02677307e+01 1.94517841e+01 1.90574379e+01 1.85247631e+01 1.86563396e+01 1.86693707e+01 1.87250996e+01 1.87060242e+01 1.86350384e+01 1.85844688e+01 1.89833965e+01 1.84495697e+01 1.81753025e+01 1.80776081e+01 1.76829166e+01 1.72349682e+01 1.67702160e+01 1.69123764e+01 1.75378418e+01 1.74897041e+01 1.72850456e+01 1.69161472e+01 1.68934097e+01 1.65474586e+01 1.62619743e+01 1.62422581e+01 1.60739384e+01 1.60490284e+01 1.73422718e+01 1.67568378e+01 1.60315170e+01 1.63292809e+01 1.60296097e+01 1.65494976e+01 1.62224522e+01 1.41600351e+01 1.75447330e+01 2.01132965e+01 1.82075844e+01 1.54975166e+01 1.36579990e+01 1.38160286e+01 1.37731895e+01 1.43954535e+01 1.48568964e+01 1.70976810e+01 1.93091736e+01 1.45700836e+01 3.74118271e+01 4.58789883e+04 1.63513412e+02 4.06479645e+01 4.01178818e+01 3.81305580e+01 3.80067368e+01 4.09712296e+01 4.25379372e+01 3.87195053e+01 3.84378624e+01 3.98074150e+01 3.97876472e+01 4.07799263e+01 4.03564987e+01 4.05100174e+01 4.02020988e+01 3.89685593e+01 3.67984161e+01 3.53347816e+01 3.62973175e+01 3.91325150e+01 4.09818649e+01 4.09114838e+01 4.09712639e+01 4.03520088e+01 3.96631699e+01 3.91562920e+01 3.89172325e+01 3.87539520e+01 3.87408600e+01 3.81612663e+01 3.83086357e+01 3.80871887e+01 3.81496544e+01 3.79402237e+01 3.77406311e+01 3.74018517e+01 3.73298569e+01 3.73096008e+01 3.73952751e+01 3.72619553e+01 3.63750725e+01 3.61712379e+01 3.57471581e+01 3.61320229e+01 3.56023445e+01 3.53588028e+01 3.50937881e+01 3.46964188e+01 3.43968582e+01 3.44037743e+01 3.42556496e+01 3.47148895e+01 3.42634811e+01 3.37877388e+01 3.34444237e+01 3.30177498e+01 3.31172142e+01 3.32543106e+01 3.29112892e+01 3.29718895e+01 3.29869614e+01 3.28771973e+01 3.24633255e+01 3.18886452e+01 3.15137005e+01 3.13030128e+01 3.08652973e+01 3.02772560e+01 3.04401779e+01 3.00462246e+01 3.01170006e+01 3.01277313e+01 2.98820190e+01 2.99559231e+01 3.01096916e+01 2.92096806e+01 2.86343002e+01 2.66834545e+01 2.46113968e+01 1.36623688e+01 -1.64745880e+02 -3.16849152e+02 -7.83515991e+02 -1.94551550e+03 301316256. 5868675. -70056360. -70056360. 0. -126921904. -126921904. -36096712. 92080408. 92080408. 0. 0. 0. 0. 2.22274099e+09 387926848. -1.78250574e+03 -6.21254761e+02 1.96401482e+01 -2.64170929e+02 -1.45902832e+02 2.13300667e+01 1.73550892e+01 1.28941689e+01 1.81362286e+01 1.99394512e+01 1.73462791e+01 1.68244267e+01 1.74962864e+01 2.19833488e+01 2.09935493e+01 2.00368137e+01 1.90513096e+01 1.93853149e+01 1.90043125e+01 1.90109386e+01 1.83964520e+01 1.81582260e+01 1.81005650e+01 1.77704792e+01 1.74759502e+01 1.69072247e+01 1.70408058e+01 1.67998638e+01 1.65859451e+01 1.64743767e+01 1.59835548e+01 1.54384756e+01 1.53345308e+01 1.52710075e+01 1.50422726e+01 1.48092937e+01 1.46014833e+01 1.42816124e+01 1.37262640e+01 1.37521381e+01 1.37605505e+01 1.36144400e+01 1.35090446e+01 1.32634888e+01 1.23748388e+01 1.22630033e+01 1.19477110e+01 1.15295324e+01 1.11532793e+01 1.08945637e+01 1.08046284e+01 1.08810101e+01 1.01842155e+01 9.48733234e+00 9.18875408e+00 8.67006302e+00 8.21802139e+00 7.65649843e+00 7.93594456e+00 7.72789717e+00 7.37048817e+00 7.31139851e+00 7.45036983e+00 7.54725552e+00 6.73870993e+00 6.34339571e+00 5.71419287e+00 5.37012005e+00 5.11310959e+00 5.15875006e+00 5.00947285e+00 4.65837049e+00 4.18460894e+00 3.90793943e+00 3.77226186e+00 3.57039118e+00 2.95700145e+00 2.87200713e+00 2.48984480e+00 2.47502947e+00 1.97051084e+00 1.91253412e+00 1.29765761e+00 1.08723390e+00 6.04283690e-01 5.39379776e-01 2.20225945e-01 2.28546724e-01 -5.44220395e-02 -4.62822825e-01 -7.94099092e-01 -1.14225984e+00 -1.24298918e+00 -1.72504961e+00 -1.98243690e+00 -2.23714304e+00 -2.46393776e+00 -2.75873256e+00 -2.99811387e+00 -3.45550394e+00 -3.71675873e+00 -4.05983210e+00 -4.22395515e+00 -4.47417927e+00 -4.71407461e+00 -5.10082388e+00 -5.45051241e+00 -5.59534121e+00 -5.79787493e+00 -5.99724579e+00 -6.37731171e+00 -6.78326845e+00 -7.06523180e+00 -7.29096413e+00 -7.63306236e+00 -8.00316906e+00 -8.41032600e+00 -8.53532600e+00 -8.74484825e+00 -9.03803349e+00 -9.35561562e+00 -9.66245651e+00 -9.86492157e+00 -1.01893263e+01 -1.05100527e+01 -1.07848215e+01 -1.10306797e+01 -1.12712517e+01 -1.16281204e+01 -1.18861465e+01 -1.21547441e+01 -1.23682327e+01 -1.26118345e+01 -1.28859167e+01 -1.31699619e+01 -1.33988581e+01 -1.36848116e+01 -1.39587746e+01 -1.42618237e+01 -1.45533800e+01 -1.48174667e+01 -1.50919428e+01 -1.53576527e+01 -1.56417036e+01 -1.59200449e+01 -1.61838779e+01 -1.64477997e+01 -1.67200737e+01 -1.69909115e+01 -1.72569656e+01 -1.75276031e+01 -1.77902279e+01 -1.80560207e+01 -1.83169155e+01 -1.85813828e+01 -1.88397369e+01 -1.91001091e+01 -1.93542385e+01 -1.96108932e+01 -1.98707371e+01 -2.01224365e+01 -2.03824120e+01 -2.06405544e+01 -2.09057808e+01 -2.11684151e+01 -2.14157639e+01 -2.16621094e+01 -2.18983212e+01 -2.21386890e+01 -2.23855381e+01 -2.26656685e+01 -2.29014950e+01 -2.31476116e+01 -2.33923244e+01 -2.36494560e+01 -2.38919315e+01 -2.41646233e+01 -2.43988457e+01 -2.46701012e+01 -2.49119549e+01 -2.51910419e+01 -2.53707199e+01 -2.56618671e+01 -2.58810844e+01 -2.60999031e+01 -2.62721272e+01 -2.66110783e+01 -2.68725796e+01 -2.71713352e+01 -2.73082829e+01 -2.75593700e+01 -2.77703781e+01 -2.80921345e+01 -2.83495712e+01 -2.85777569e+01 -2.87584114e+01 -2.88206387e+01 -2.91107979e+01 -2.92244759e+01 -2.94759560e+01 -2.97311573e+01 -2.99838905e+01 -3.01025429e+01 -3.01827393e+01 -3.03540802e+01 -3.06914616e+01 -3.10267277e+01 -3.13654079e+01 -3.14133644e+01 -3.15907707e+01 -3.17845707e+01 -3.19524059e+01 -3.22998466e+01 -3.26419449e+01 -3.26170006e+01 -3.29783096e+01 -3.32324257e+01 -3.32208710e+01 -3.34098816e+01 -3.37758904e+01 -3.37854309e+01 -3.38096771e+01 -3.39550323e+01 -3.40697823e+01 -3.44012642e+01 -3.46610565e+01 -3.49493675e+01 -3.50941124e+01 -3.53774834e+01 -3.56721230e+01 -3.60347824e+01 -3.59549866e+01 -3.61742744e+01 -3.56879272e+01 -3.61802979e+01 -3.65097198e+01 -3.69069481e+01 -3.69608574e+01 -3.68150749e+01 -3.73467064e+01 -3.74930153e+01 -3.76246300e+01 -3.78190613e+01 -3.79677925e+01 -3.85177383e+01 -3.83161163e+01 -3.85730896e+01 -3.82905006e+01 -3.86112213e+01 -3.83118286e+01 -3.86934052e+01 -3.87803764e+01 -3.89345703e+01 -3.92143707e+01 -3.95440712e+01 -3.95004692e+01 -3.95961571e+01 -4.01682510e+01 -4.07346115e+01 -4.11535263e+01 -4.10644684e+01 -4.12282906e+01 -4.07405281e+01 -4.11713333e+01 -4.12039795e+01 -4.11114807e+01 -4.08949203e+01 -4.04192924e+01 -4.13283997e+01 -4.13658218e+01 -4.17454224e+01 -4.15581207e+01 -4.13264427e+01 -4.20529480e+01 -4.20064049e+01 -4.25245018e+01 -4.19770546e+01 -4.20571823e+01 -4.29625359e+01 -4.30806274e+01 -4.31836052e+01 -4.28376350e+01 -4.30925903e+01 -4.30273590e+01 -4.32499428e+01 -4.32824478e+01 -4.34526634e+01 -4.40974541e+01 -4.41112900e+01 -4.39593239e+01 -4.36470337e+01 -4.41332436e+01 -4.42145042e+01 -4.39709854e+01 -4.40607338e+01 -4.44206085e+01 -4.44614296e+01 -4.49690857e+01 -4.58379326e+01 -4.59786758e+01 -4.58054695e+01 -4.55352173e+01 -4.53692284e+01 -4.49359779e+01 -4.48382225e+01 -4.53140450e+01 -4.61409569e+01 -4.65238647e+01 -4.56401672e+01 -4.47715302e+01 -4.51326141e+01 -4.50337753e+01 -4.53995819e+01 -4.51714935e+01 -4.63967590e+01 -4.65269165e+01 -4.58725243e+01 -4.55445824e+01 -4.55961151e+01 -4.62257652e+01 -4.58061752e+01 -4.57570076e+01 -4.51945343e+01 -4.51567001e+01 -4.54134674e+01 -4.62481613e+01 -4.64585190e+01 -4.62254524e+01 -4.59786148e+01 -4.61459999e+01 -4.65736961e+01 -4.65067596e+01 -4.57389755e+01 -4.58106461e+01 -4.57100868e+01 -4.63194923e+01 -4.60294037e+01 -4.62586021e+01 -4.56880836e+01 -4.60003090e+01 -4.57478294e+01 -4.60316353e+01 -4.56082954e+01 -4.63662834e+01 -4.62337379e+01 -4.60525284e+01 -4.63427582e+01 -4.64662132e+01 -4.70990639e+01 -4.65650063e+01 -4.61980782e+01 -4.62425804e+01 -4.63114319e+01 -4.62146225e+01 -4.64998245e+01 -4.63869057e+01 -4.67106552e+01 -4.66008568e+01 -4.66242142e+01 -4.65805321e+01 -4.64594650e+01 -4.61247139e+01 -4.56436996e+01 -4.59165230e+01 -4.62682381e+01 -4.64986725e+01 -4.63332100e+01 -4.59879723e+01 -4.61817474e+01 -4.61730804e+01 -4.58409920e+01 -4.51549873e+01 -4.52796364e+01 -4.57086296e+01 -4.58741798e+01 -4.54284286e+01 -4.49907761e+01 -4.51337166e+01 -4.53861465e+01 -4.52940674e+01 -4.50636597e+01 -4.51443024e+01 -4.52278214e+01 -4.51751289e+01 -4.46475220e+01 -4.48101196e+01 -4.45665016e+01 -4.47012024e+01 -4.46665230e+01 -4.48698807e+01 -4.47629204e+01 -4.49946098e+01 -4.48012962e+01 -4.43605881e+01 -4.40319977e+01 -4.38124962e+01 -4.39086609e+01 -4.41008949e+01 -4.41575432e+01 -4.38951378e+01 -4.37138634e+01 -4.35415573e+01 -4.33067932e+01 -4.32611961e+01 -4.31099281e+01 -4.30433235e+01 -4.29873314e+01 -4.29378433e+01 -4.28889999e+01 -4.26417313e+01 -4.24595375e+01 -4.25790253e+01 -4.24640884e+01 -4.20030098e+01 -4.20435600e+01 -4.19991150e+01 -4.16735687e+01 -4.17289429e+01 -4.15868340e+01 -4.14133034e+01 -4.15108871e+01 -4.10890694e+01 -4.07908096e+01 -4.08093414e+01 -4.07871666e+01 -4.07405396e+01 -4.07385139e+01 -4.04299736e+01 -4.02748985e+01 -4.03711433e+01 -4.00232773e+01 -3.96613312e+01 -3.97639923e+01 -3.94693604e+01 -3.95212326e+01 -3.94449081e+01 -3.89993248e+01 -3.85981789e+01 -3.86457100e+01 -3.85802078e+01 -3.87963753e+01 -3.84295807e+01 -3.84260139e+01 -3.78443832e+01 -3.81000862e+01 -3.78417168e+01 -3.75350342e+01 -3.73318748e+01 -3.72831154e+01 -3.73554344e+01 -3.73492165e+01 -3.71484337e+01 -3.65675163e+01 -3.63537636e+01 -3.58086929e+01 -3.61304550e+01 -3.57028275e+01 -3.54038277e+01 -3.52848892e+01 -3.49405441e+01 -3.46429787e+01 -3.48566170e+01 -3.45707207e+01 -3.45129318e+01 -3.41919975e+01 -3.36892395e+01 -3.35598526e+01 -3.30739059e+01 -3.32067413e+01 -3.31509247e+01 -3.27702026e+01 -3.26095467e+01 -3.29480667e+01 -3.31143761e+01 -3.26405754e+01 -3.19596024e+01 -3.12635727e+01 -3.11048183e+01 -3.09892082e+01 -3.06204700e+01 -3.08958492e+01 -3.04718666e+01 -3.03473759e+01 -2.96198215e+01 -2.96988258e+01 -2.99814072e+01 -2.98989868e+01 -2.91688671e+01 -2.88231869e+01 -2.80667362e+01 -2.82732906e+01 -2.85458717e+01 -2.87766628e+01 -2.84707966e+01 -2.78449421e+01 -2.74949474e+01 -2.71195068e+01 -2.73625278e+01 -2.71649132e+01 -2.67943993e+01 -2.68988380e+01 -2.65253086e+01 -2.61988850e+01 -2.58039017e+01 -2.56410503e+01 -2.48321533e+01 -2.45878162e+01 -2.48052826e+01 -2.44721794e+01 -2.45730057e+01 -2.39134960e+01 -2.34967766e+01 -2.36222839e+01 -2.37462234e+01 -2.38386688e+01 -2.36646976e+01 -2.34070492e+01 -2.35563889e+01 -2.21961823e+01 -2.20426121e+01 -2.13425064e+01 -2.08281708e+01 -2.04327679e+01 -1.98645306e+01 -2.07571411e+01 -2.01090660e+01 -1.98693333e+01 -1.94926052e+01 -1.87857952e+01 -1.92037354e+01 -1.88892555e+01 -1.92697945e+01 -1.85572491e+01 -1.81475677e+01 -1.82885857e+01 -1.83305340e+01 -1.79136162e+01 -1.74735928e+01 -1.73335819e+01 -1.69548054e+01 -1.66265030e+01 -1.64307785e+01 -1.61187134e+01 -1.62461624e+01 -1.58089075e+01 -1.51198959e+01 -1.47402630e+01 -1.47531586e+01 -1.45941610e+01 -1.40149641e+01 -1.35433493e+01 -1.33451490e+01 -1.34222870e+01 -1.36251783e+01 -1.37701578e+01 -1.36579800e+01 -1.30804853e+01 -1.26740885e+01 -1.23402586e+01 -1.16331940e+01 -1.07455730e+01 -1.10671597e+01 -1.09573641e+01 -1.09119711e+01 -1.01148767e+01 -9.46589851e+00 -9.39039707e+00 -9.18072128e+00 -9.04724216e+00 -8.50467777e+00 -8.57875729e+00 -8.38920212e+00 -7.75383139e+00 -7.61909008e+00 -7.42136192e+00 -7.40534735e+00 -6.60516644e+00 -6.21889162e+00 -5.67274523e+00 -5.34926796e+00 -5.30967331e+00 -5.49734020e+00 -5.27006292e+00 -4.88960695e+00 -4.44292307e+00 -4.00918102e+00 -3.88035297e+00 -3.65704489e+00 -3.03854775e+00 -2.70738220e+00 -2.27857065e+00 -2.25788569e+00 -1.88870883e+00 -1.86376727e+00 -1.29781103e+00 -1.07243967e+00 -7.62718379e-01 -6.76392794e-01 -2.96256065e-01 -2.84901142e-01 4.66391370e-02 4.06028658e-01 6.24840260e-01 1.01341903e+00 1.20950127e+00 1.61190474e+00 1.93246877e+00 2.10153604e+00 2.35905099e+00 2.62401819e+00 2.91376901e+00 3.23860645e+00 3.47072244e+00 3.90133786e+00 4.24883556e+00 4.54433823e+00 4.77812529e+00 5.04698896e+00 5.43843365e+00 5.66661644e+00 5.88631725e+00 6.08304024e+00 6.41188574e+00 6.76974869e+00 7.03977823e+00 7.32627439e+00 7.59148121e+00 7.92181730e+00 8.22412205e+00 8.46951866e+00 8.67472076e+00 8.95493698e+00 9.31051540e+00 9.61179924e+00 9.81685925e+00 1.00590048e+01 1.04147024e+01 1.06637793e+01 1.08806276e+01 1.11366196e+01 1.14948282e+01 1.17899160e+01 1.20289145e+01 1.22167540e+01 1.24737339e+01 1.27382774e+01 1.30284271e+01 1.33040190e+01 1.36095982e+01 1.38773546e+01 1.41625071e+01 1.44642382e+01 1.47413120e+01 1.50189934e+01 1.52767878e+01 1.55340214e+01 1.58222332e+01 1.61062050e+01 1.63857861e+01 1.66556549e+01 1.69321423e+01 1.71917057e+01 1.74634457e+01 1.77279606e+01 1.79889297e+01 1.82531357e+01 1.85213966e+01 1.87829113e+01 1.90473709e+01 1.93071728e+01 1.95813160e+01 1.98523293e+01 2.01218090e+01 2.03871479e+01 2.06529179e+01 2.08870773e+01 2.11339188e+01 2.13950176e+01 2.16454716e+01 2.19105339e+01 2.21928558e+01 2.24231606e+01 2.27054062e+01 2.29527626e+01 2.32172718e+01 2.34924793e+01 2.37264690e+01 2.39643459e+01 2.42148361e+01 2.44204407e+01 2.47076893e+01 2.49537296e+01 2.51538296e+01 2.53941784e+01 2.56157608e+01 2.58129025e+01 2.61193600e+01 2.62803860e+01 2.65338135e+01 2.66960144e+01 2.70402660e+01 2.72951622e+01 2.75304928e+01 2.77113323e+01 2.80250187e+01 2.81915932e+01 2.83974495e+01 2.86004925e+01 2.87138138e+01 2.89548149e+01 2.90482368e+01 2.93906517e+01 2.95837193e+01 2.97902241e+01 2.98964214e+01 3.00520573e+01 3.02241173e+01 3.05275612e+01 3.07780514e+01 3.11667423e+01 3.12198677e+01 3.13061981e+01 3.15537987e+01 3.18228512e+01 3.21908340e+01 3.25587273e+01 3.24790764e+01 3.28159180e+01 3.31250916e+01 3.32813568e+01 3.34385567e+01 3.36857414e+01 3.36546135e+01 3.36706657e+01 3.38587456e+01 3.40531616e+01 3.43915596e+01 3.44883308e+01 3.48134613e+01 3.49441032e+01 3.51983452e+01 3.54647408e+01 3.59303780e+01 3.58646889e+01 3.59342003e+01 3.55810204e+01 3.62785339e+01 3.65147629e+01 3.68537598e+01 3.69557724e+01 3.68906403e+01 3.73391075e+01 3.73532486e+01 3.75745010e+01 3.78116379e+01 3.79666710e+01 3.85267029e+01 3.84482956e+01 3.84614334e+01 3.82372704e+01 3.85108299e+01 3.83782310e+01 3.87294998e+01 3.90360260e+01 3.91860352e+01 3.95326157e+01 3.95740623e+01 3.94922600e+01 3.95988083e+01 4.00163269e+01 4.07526093e+01 4.11619034e+01 4.12876587e+01 4.15868149e+01 4.09560089e+01 4.12951622e+01 4.12454147e+01 4.06789131e+01 4.05764618e+01 4.03215485e+01 4.13466187e+01 4.12482262e+01 4.13717422e+01 4.13577957e+01 4.11760330e+01 4.21733131e+01 4.21608734e+01 4.25112839e+01 4.20609283e+01 4.23445816e+01 4.32014160e+01 4.34233932e+01 4.32839737e+01 4.30409698e+01 4.33334579e+01 4.33821564e+01 4.34332504e+01 4.31341972e+01 4.30345955e+01 4.33543892e+01 4.38616180e+01 4.42037926e+01 4.40000038e+01 4.40299416e+01 4.38707542e+01 5.28805885e+01 5.40295258e+01 5.33306427e+01 5.29437599e+01 4.91139832e+01 4.94705772e+01 4.56768494e+01 4.71993256e+01 4.70790672e+01 4.49705772e+01 4.45266724e+01 3.77007751e+01 3.82530594e+01 2.36340591e+02 4.16383270e+02 1.01263953e+03 2.31445728e+03 1403066240. -947091392. 0. 2.47411738e+09 2.47411738e+09 2.47411738e+09 0. 0. -440080640. -440080640. -440080640. -685678592. 9506764. 2.37407754e+04 1.85423694e+03 1.09285828e+03 5.17954834e+02 3.59482819e+02 9.55672379e+01 8.27731400e+01 6.61838150e+01 6.56103439e+01 5.19119377e+01 2.24408913e+01 2.23257046e+01 6.52679214e+01 7.41602859e+01 6.39741249e+01 5.49142151e+01 4.65832024e+01 4.49763336e+01 4.55927048e+01 4.76069221e+01 4.82640419e+01 4.30610008e+01 2.65177727e+01 3.10871143e+01 5.36858215e+01 4.10763397e+01 5.56421356e+01 4.97553062e+01 1.84932652e+01 3.33801117e+01 4.55314865e+01 4.60398407e+01 5.50148773e+01 5.27223740e+01 4.48190536e+01 4.87302971e+01 4.92733345e+01 4.81215324e+01 4.70989075e+01 4.63348923e+01 4.60498085e+01 4.62261772e+01 4.65454521e+01 4.64532204e+01 4.60246582e+01 4.61746635e+01 4.62786293e+01 4.59491577e+01 4.52875748e+01 4.52890854e+01 4.54525642e+01 4.54671555e+01 4.54625015e+01 4.49982109e+01 4.78764915e+01 4.71687317e+01 4.73650169e+01 4.92482910e+01 4.60037766e+01 4.45207443e+01 4.46808395e+01 4.47083397e+01 4.48253441e+01 4.48139038e+01 4.47233925e+01 4.43773575e+01 4.45923576e+01 4.57235718e+01 4.53427544e+01 4.44711075e+01 4.46910362e+01 4.39438782e+01 4.47224312e+01 4.44694786e+01 4.26159935e+01 4.59920311e+01 4.84673843e+01 4.60844307e+01 4.25293274e+01 4.04160347e+01 4.10435486e+01 4.10270233e+01 4.20133324e+01 4.29559059e+01 4.57430992e+01 4.78050423e+01 4.20400391e+01 1.19753632e+02 2.26145547e+05 2.42359940e+02 -1.43161804e+02 -2.91860138e+02 1.11807800e+02 1.11299927e+02 1.26570663e+02 1.35928070e+02 1.12581100e+02 1.13396988e+02 1.18254684e+02 1.13340607e+02 1.19948586e+02 4.54073700e+02 2.93957642e+02 6.00308189e+01 6.75492401e+01 6.03040962e+01 5.74977188e+01 5.76249924e+01 6.01052284e+01 6.16224174e+01 6.15676270e+01 6.08245049e+01 5.99983330e+01 5.95047607e+01 5.92250557e+01 5.92582817e+01 5.91072655e+01 5.98105583e+01 5.95411110e+01 5.90451813e+01 5.82309036e+01 5.79497643e+01 5.79271393e+01 5.78979187e+01 5.78604088e+01 5.78460693e+01 5.75920792e+01 5.73946877e+01 5.71185226e+01 5.69808197e+01 5.66363411e+01 5.67192879e+01 5.70613976e+01 5.67927818e+01 5.60565834e+01 5.56766624e+01 5.51634903e+01 5.51434326e+01 5.42819366e+01 5.44283409e+01 5.45397415e+01 5.44469070e+01 5.42501297e+01 5.43898735e+01 5.39260330e+01 5.40851212e+01 5.40490761e+01 5.43690796e+01 5.37041740e+01 5.33292084e+01 5.22528725e+01 5.21010551e+01 5.19710732e+01 5.19612885e+01 5.15361938e+01 5.08906021e+01 5.08796997e+01 5.05565453e+01 5.02566986e+01 4.99818382e+01 5.04228668e+01 5.01438370e+01 4.99516296e+01 4.95901184e+01 4.85653000e+01 4.49778252e+01 3.39505730e+01 3.23213615e+01 -1.68064835e+02 -7.11646729e+02 -2.13537085e+03 116564224. 292684096. 0. -70056360. -70056360. -70056360. 0. -126921904. -126921904. -36096712. 92080408. -22965170. -176459200. -176459200. 0. -291323936. -3.15922852e+03 -7.36492798e+02 -2.80058014e+02 -1.30441574e+02 3.47167358e+01 4.29266472e+01 4.14477654e+01 3.50104752e+01 3.28257828e+01 3.69484520e+01 4.37646065e+01 3.97072601e+01 3.59046898e+01 3.99939308e+01 3.98188705e+01 3.86113739e+01 3.81350250e+01 3.73800735e+01 3.75117950e+01 3.71032791e+01 3.69859123e+01 3.65454063e+01 3.64220352e+01 3.61523132e+01 3.56435356e+01 3.49084854e+01 3.40758667e+01 3.34770088e+01 3.37390480e+01 3.36754799e+01 3.37008934e+01 3.37679749e+01 3.31290016e+01 3.27566032e+01 3.20197601e+01 3.15865841e+01 3.14393444e+01 3.09615593e+01 3.08649216e+01 3.10955124e+01 3.13662434e+01 3.12536259e+01 3.00310593e+01 2.92981968e+01 2.82312241e+01 2.79604206e+01 2.70910149e+01 2.73703346e+01 2.70675125e+01 2.72262688e+01 2.69241581e+01 2.64619789e+01 2.61889153e+01 2.53895912e+01 2.49953480e+01 2.46652374e+01 2.42507572e+01 2.40915909e+01 2.30691109e+01 2.27454605e+01 2.23042088e+01 2.21444454e+01 2.17941723e+01 2.17001839e+01 2.15995960e+01 2.15759640e+01 2.13511734e+01 2.09375343e+01 2.02180176e+01 1.95485668e+01 1.93311615e+01 1.90757580e+01 1.83997307e+01 1.80277367e+01 1.79097843e+01 1.78585815e+01 1.72427769e+01 1.67964478e+01 1.60996513e+01 1.57704868e+01 1.53372068e+01 1.49638538e+01 1.47672663e+01 1.45683508e+01 1.40792656e+01 1.35086679e+01 1.30331182e+01 1.25990553e+01 1.22610188e+01 1.20878010e+01 1.19678211e+01 1.15354958e+01 1.06869860e+01 1.02474222e+01 9.84705162e+00 9.59215164e+00 9.31268215e+00 8.99650860e+00 8.59932995e+00 7.89347219e+00 7.57835770e+00 7.07119370e+00 6.86983585e+00 6.64024544e+00 6.37640238e+00 5.96425009e+00 5.34232092e+00 4.89106941e+00 4.43534040e+00 4.11586714e+00 3.80891466e+00 3.42026281e+00 2.92940354e+00 2.35498357e+00 1.99219120e+00 1.69863832e+00 1.33227384e+00 9.13810074e-01 4.52353925e-01 1.05939977e-01 -2.23590672e-01 -5.40583909e-01 -1.02118444e+00 -1.45998025e+00 -1.83774757e+00 -2.18881249e+00 -2.61252308e+00 -3.00433278e+00 -3.39979863e+00 -3.78602386e+00 -4.18849516e+00 -4.56265020e+00 -4.99169254e+00 -5.34488297e+00 -5.71606684e+00 -6.11724615e+00 -6.53467226e+00 -6.90416193e+00 -7.29100132e+00 -7.69780636e+00 -8.12615681e+00 -8.51730728e+00 -8.90070152e+00 -9.28462887e+00 -9.66149902e+00 -1.00431185e+01 -1.04591150e+01 -1.08454075e+01 -1.12420206e+01 -1.16408806e+01 -1.20220928e+01 -1.23946400e+01 -1.27864618e+01 -1.31722612e+01 -1.35639906e+01 -1.39504604e+01 -1.43360243e+01 -1.47216644e+01 -1.51074038e+01 -1.54890785e+01 -1.58690062e+01 -1.62474747e+01 -1.66287022e+01 -1.70213985e+01 -1.74142170e+01 -1.78107128e+01 -1.82114925e+01 -1.85929127e+01 -1.89520683e+01 -1.93215637e+01 -1.97198315e+01 -2.00960255e+01 -2.04568329e+01 -2.08269882e+01 -2.12312870e+01 -2.16058941e+01 -2.19824543e+01 -2.23720436e+01 -2.27371216e+01 -2.31540031e+01 -2.35475883e+01 -2.39155788e+01 -2.42987423e+01 -2.45792713e+01 -2.49487324e+01 -2.52988300e+01 -2.56510010e+01 -2.59782619e+01 -2.63982677e+01 -2.67333755e+01 -2.71262302e+01 -2.74416695e+01 -2.78714142e+01 -2.81829758e+01 -2.86250477e+01 -2.89114475e+01 -2.92655659e+01 -2.95898170e+01 -2.98514557e+01 -3.03674126e+01 -3.07125587e+01 -3.09817066e+01 -3.14357052e+01 -3.18075752e+01 -3.20137939e+01 -3.20684776e+01 -3.24110718e+01 -3.26733742e+01 -3.31853638e+01 -3.35205460e+01 -3.37999878e+01 -3.41981087e+01 -3.47059212e+01 -3.50229836e+01 -3.53975258e+01 -3.57571411e+01 -3.62305984e+01 -3.65433273e+01 -3.67737885e+01 -3.65400925e+01 -3.69177666e+01 -3.74012680e+01 -3.79386330e+01 -3.81516037e+01 -3.83545647e+01 -3.85503464e+01 -3.88657188e+01 -3.93258820e+01 -3.98172989e+01 -4.03056908e+01 -4.06100845e+01 -4.10330925e+01 -4.13245735e+01 -4.15390701e+01 -4.19823685e+01 -4.19137383e+01 -4.20379219e+01 -4.25144844e+01 -4.29852448e+01 -4.34385681e+01 -4.34308624e+01 -4.37109528e+01 -4.37385521e+01 -4.39915619e+01 -4.42556953e+01 -4.45253716e+01 -4.47483025e+01 -4.51648674e+01 -4.53687248e+01 -4.58013420e+01 -4.58211899e+01 -4.58486671e+01 -4.59529915e+01 -4.63412819e+01 -4.66439285e+01 -4.70380325e+01 -4.74611053e+01 -4.78586502e+01 -4.81359138e+01 -4.83315315e+01 -4.90087738e+01 -4.93082008e+01 -4.93033524e+01 -4.93217087e+01 -4.91142654e+01 -4.94456978e+01 -4.98036308e+01 -5.04597816e+01 -5.02613907e+01 -5.02807770e+01 -5.09608307e+01 -5.08485146e+01 -5.16402168e+01 -5.13820648e+01 -5.19877968e+01 -5.21879425e+01 -5.25336533e+01 -5.27182846e+01 -5.26084595e+01 -5.29217834e+01 -5.34086342e+01 -5.36390800e+01 -5.32160149e+01 -5.33049240e+01 -5.39993668e+01 -5.46812744e+01 -5.48082771e+01 -5.48435287e+01 -5.51325531e+01 -5.52308769e+01 -5.55317726e+01 -5.54247169e+01 -5.57686958e+01 -5.56781769e+01 -5.59100838e+01 -5.65570946e+01 -5.76556931e+01 -5.82661018e+01 -5.75610161e+01 -5.75648918e+01 -5.73831482e+01 -5.78123817e+01 -5.70128822e+01 -5.73750114e+01 -5.75328293e+01 -5.85280952e+01 -5.82272377e+01 -5.85503387e+01 -5.90189972e+01 -5.87675362e+01 -5.84337387e+01 -5.90226364e+01 -5.89644928e+01 -6.00923386e+01 -5.94524803e+01 -5.98829002e+01 -5.98393631e+01 -6.02989273e+01 -6.01563301e+01 -6.02355957e+01 -6.01805611e+01 -6.08938179e+01 -6.12353134e+01 -6.12808495e+01 -6.09351463e+01 -6.05107193e+01 -6.07977524e+01 -6.13281555e+01 -6.10982971e+01 -6.08598099e+01 -6.16192055e+01 -6.19384575e+01 -6.20024529e+01 -6.18649902e+01 -6.15250854e+01 -6.18375587e+01 -6.20065956e+01 -6.25418053e+01 -6.29962845e+01 -6.33847275e+01 -6.28980980e+01 -6.27641754e+01 -6.27439308e+01 -6.26937294e+01 -6.27799721e+01 -6.32155914e+01 -6.37522469e+01 -6.37221069e+01 -6.30997467e+01 -6.30788994e+01 -6.32996483e+01 -6.38476524e+01 -6.41364136e+01 -6.42700272e+01 -6.41060715e+01 -6.34035378e+01 -6.36641541e+01 -6.32196922e+01 -6.38148956e+01 -6.40615845e+01 -6.43856964e+01 -6.43341370e+01 -6.40421753e+01 -6.41232300e+01 -6.40427399e+01 -6.38575249e+01 -6.39251328e+01 -6.38304710e+01 -6.38239098e+01 -6.36932144e+01 -6.38137894e+01 -6.40875397e+01 -6.40401611e+01 -6.40872192e+01 -6.38662033e+01 -6.41658554e+01 -6.41473846e+01 -6.38879166e+01 -6.37020950e+01 -6.41299362e+01 -6.43658142e+01 -6.44322205e+01 -6.42264252e+01 -6.42206497e+01 -6.41186905e+01 -6.41200104e+01 -6.39141808e+01 -6.42541046e+01 -6.39933243e+01 -6.38275299e+01 -6.36940804e+01 -6.39266052e+01 -6.39597015e+01 -6.42000885e+01 -6.40794983e+01 -6.38990135e+01 -6.36470947e+01 -6.34830627e+01 -6.35113525e+01 -6.37146988e+01 -6.37005157e+01 -6.37629128e+01 -6.33411293e+01 -6.32320862e+01 -6.32519531e+01 -6.31892128e+01 -6.29590149e+01 -6.27906303e+01 -6.28283081e+01 -6.29123116e+01 -6.27392921e+01 -6.25998230e+01 -6.24917870e+01 -6.25034866e+01 -6.24207535e+01 -6.20460320e+01 -6.20696640e+01 -6.19852943e+01 -6.17989006e+01 -6.18597946e+01 -6.17520905e+01 -6.17616959e+01 -6.17745476e+01 -6.13654060e+01 -6.11320190e+01 -6.11471062e+01 -6.12501221e+01 -6.10940514e+01 -6.10030823e+01 -6.05816422e+01 -6.05147476e+01 -6.07616692e+01 -6.06297340e+01 -6.05162125e+01 -6.04988480e+01 -6.00908279e+01 -5.98827858e+01 -5.97511635e+01 -5.96564903e+01 -5.92578964e+01 -5.93036308e+01 -5.91048431e+01 -5.90101471e+01 -5.85485458e+01 -5.84993095e+01 -5.79644356e+01 -5.80430527e+01 -5.78272591e+01 -5.77673340e+01 -5.78850517e+01 -5.79141769e+01 -5.75301247e+01 -5.71021576e+01 -5.64965401e+01 -5.66242104e+01 -5.64002953e+01 -5.63642197e+01 -5.67467918e+01 -5.63283119e+01 -5.58862495e+01 -5.57918358e+01 -5.52555046e+01 -5.51811447e+01 -5.45072594e+01 -5.45146332e+01 -5.42912140e+01 -5.43429642e+01 -5.42711143e+01 -5.45043297e+01 -5.41434402e+01 -5.42117157e+01 -5.41265640e+01 -5.43740540e+01 -5.35790176e+01 -5.34010696e+01 -5.25505562e+01 -5.20885429e+01 -5.17257576e+01 -5.16768341e+01 -5.15981483e+01 -5.12406654e+01 -5.11872711e+01 -5.07870522e+01 -5.04750595e+01 -5.02710686e+01 -5.03667221e+01 -5.02827225e+01 -5.02430687e+01 -4.97980576e+01 -4.95809593e+01 -4.96738586e+01 -4.91244659e+01 -4.85628624e+01 -4.85651627e+01 -4.81954041e+01 -4.79159737e+01 -4.73933716e+01 -4.70164566e+01 -4.65316658e+01 -4.64100189e+01 -4.67474060e+01 -4.63637695e+01 -4.64368820e+01 -4.61378021e+01 -4.53466225e+01 -4.50129738e+01 -4.45226288e+01 -4.38036919e+01 -4.34710617e+01 -4.34189529e+01 -4.31657181e+01 -4.28889580e+01 -4.29284630e+01 -4.26019821e+01 -4.26187820e+01 -4.23269272e+01 -4.24953842e+01 -4.20346832e+01 -4.12984009e+01 -4.08451004e+01 -3.99837456e+01 -3.97282257e+01 -3.91454849e+01 -3.94812775e+01 -3.88697281e+01 -3.86531105e+01 -3.89333572e+01 -3.81558304e+01 -3.81741180e+01 -3.76219902e+01 -3.75968285e+01 -3.73159027e+01 -3.72313232e+01 -3.69716873e+01 -3.65288048e+01 -3.61134262e+01 -3.57368927e+01 -3.50911064e+01 -3.40933876e+01 -3.38523674e+01 -3.42223625e+01 -3.39740448e+01 -3.36361618e+01 -3.33586044e+01 -3.31021996e+01 -3.25191154e+01 -3.20178146e+01 -3.14876308e+01 -3.16174545e+01 -3.08564453e+01 -3.05711021e+01 -3.07651939e+01 -3.11718025e+01 -3.11600361e+01 -2.99520550e+01 -2.94823208e+01 -2.87884922e+01 -2.85294170e+01 -2.75229511e+01 -2.72408142e+01 -2.71058788e+01 -2.70932674e+01 -2.62493095e+01 -2.60671978e+01 -2.56931419e+01 -2.51063404e+01 -2.49168205e+01 -2.48187714e+01 -2.43884850e+01 -2.44581890e+01 -2.37775745e+01 -2.35622997e+01 -2.29615040e+01 -2.27741909e+01 -2.21605263e+01 -2.19073277e+01 -2.15545864e+01 -2.12739716e+01 -2.11195221e+01 -2.06760998e+01 -2.00311432e+01 -1.93246288e+01 -1.92128220e+01 -1.91096382e+01 -1.84233665e+01 -1.80271225e+01 -1.80103455e+01 -1.77526398e+01 -1.71473942e+01 -1.66212692e+01 -1.59940901e+01 -1.57718248e+01 -1.53773117e+01 -1.50461731e+01 -1.49252310e+01 -1.46943855e+01 -1.41459141e+01 -1.36763563e+01 -1.33330736e+01 -1.28688259e+01 -1.24353676e+01 -1.21099072e+01 -1.18686504e+01 -1.16005154e+01 -1.09232149e+01 -1.03145161e+01 -9.97855091e+00 -9.83555984e+00 -9.55294418e+00 -9.10537243e+00 -8.71240234e+00 -8.12727833e+00 -7.83339071e+00 -7.25245762e+00 -6.94009495e+00 -6.50016975e+00 -6.26476622e+00 -5.88746214e+00 -5.36300564e+00 -4.92810011e+00 -4.45347023e+00 -4.06928825e+00 -3.71048284e+00 -3.38602948e+00 -2.98681641e+00 -2.44521403e+00 -2.08573985e+00 -1.70853376e+00 -1.33274329e+00 -9.95314121e-01 -6.27647698e-01 -2.05344945e-01 1.97088465e-01 5.77293992e-01 1.03653073e+00 1.35315621e+00 1.73124886e+00 2.07395792e+00 2.48276424e+00 2.88888240e+00 3.29106188e+00 3.67740107e+00 4.08308125e+00 4.46135044e+00 4.85338974e+00 5.23639870e+00 5.65496540e+00 6.00426435e+00 6.39635324e+00 6.77914858e+00 7.18161583e+00 7.57500267e+00 7.98873901e+00 8.40224552e+00 8.78202820e+00 9.14165974e+00 9.51285744e+00 9.89909935e+00 1.03108921e+01 1.06932716e+01 1.10939980e+01 1.14879179e+01 1.18854704e+01 1.22728176e+01 1.26623783e+01 1.30469131e+01 1.34261427e+01 1.38208027e+01 1.42072220e+01 1.45889063e+01 1.49675150e+01 1.53428507e+01 1.57274189e+01 1.61012497e+01 1.64766293e+01 1.68627243e+01 1.72437172e+01 1.76110783e+01 1.79849949e+01 1.83785362e+01 1.87446079e+01 1.91098671e+01 1.95155487e+01 1.98743038e+01 2.02686291e+01 2.06392403e+01 2.10342407e+01 2.14401245e+01 2.18226700e+01 2.22169189e+01 2.25276604e+01 2.28733711e+01 2.32783661e+01 2.36544075e+01 2.39847202e+01 2.43274727e+01 2.47474613e+01 2.50811043e+01 2.54937820e+01 2.58486347e+01 2.62056599e+01 2.64760284e+01 2.68710232e+01 2.72875214e+01 2.76756725e+01 2.80451336e+01 2.84659557e+01 2.87338161e+01 2.90464344e+01 2.92683697e+01 2.96610966e+01 3.00786819e+01 3.05291653e+01 3.09303341e+01 3.12585640e+01 3.15406380e+01 3.18184624e+01 3.20038414e+01 3.22544403e+01 3.24612999e+01 3.28846512e+01 3.32751923e+01 3.36492958e+01 3.39833946e+01 3.45162697e+01 3.48133011e+01 3.52019806e+01 3.56407356e+01 3.59897423e+01 3.62539444e+01 3.66579895e+01 3.65346565e+01 3.68996201e+01 3.72852097e+01 3.77827034e+01 3.80540276e+01 3.83158798e+01 3.86767006e+01 3.89245796e+01 3.92872047e+01 3.97494011e+01 4.02072182e+01 4.05534325e+01 4.08073921e+01 4.11015167e+01 4.14823723e+01 4.17913399e+01 4.17739029e+01 4.20896835e+01 4.25352020e+01 4.28964958e+01 4.31986465e+01 4.32328262e+01 4.35730705e+01 4.35677567e+01 4.39575081e+01 4.42158203e+01 4.43446999e+01 4.45341148e+01 4.52112083e+01 4.52647476e+01 4.55195656e+01 4.56260033e+01 4.57430229e+01 4.60436172e+01 4.63406906e+01 4.65858345e+01 4.70104675e+01 4.74163551e+01 4.76193466e+01 4.79510002e+01 4.81311455e+01 4.89082069e+01 4.91153450e+01 4.92228012e+01 4.93707008e+01 4.92587814e+01 4.98387146e+01 4.99213486e+01 5.03540802e+01 5.01242943e+01 5.03524094e+01 5.09913864e+01 5.07643242e+01 5.12812080e+01 5.09789696e+01 5.17199402e+01 5.21722298e+01 5.27325401e+01 5.28620338e+01 5.30223732e+01 5.32523689e+01 5.37073097e+01 5.35868034e+01 5.31514359e+01 5.31456070e+01 5.40755386e+01 5.45685081e+01 5.51719818e+01 5.55194588e+01 5.53493347e+01 5.47529335e+01 5.50719070e+01 5.56614609e+01 5.59416771e+01 5.55469017e+01 5.57740593e+01 5.65849533e+01 5.75892792e+01 6.56077271e+01 6.55220718e+01 6.25065231e+01 6.16985970e+01 5.79457626e+01 5.94251633e+01 5.96439171e+01 5.94081459e+01 6.08868599e+01 5.80680199e+01 5.46839142e+01 5.37560196e+01 6.33834686e+01 2.59651001e+02 3.93572327e+02 9.44494385e+02 1.73604980e+03 14223753. -4.20534150e+06 2.47411738e+09 2.47411738e+09 -268468640. -268468640. -8252523. -440080640. -440080640. 0. 0. 0. -1970944384. 24324094. 1.99104712e+03 1.24891614e+03 3.63948700e+02 5.59324768e+02 3.29382324e+02 9.43870239e+01 8.48422928e+01 4.61865959e+01 4.33943329e+01 8.08640442e+01 9.22980499e+01 7.60308228e+01 6.70820465e+01 6.57597122e+01 6.41641464e+01 6.48717041e+01 6.00470276e+01 5.45679092e+01 5.78692322e+01 4.48808670e+01 4.81609535e+01 7.19712524e+01 5.92088470e+01 7.31511307e+01 8.38375397e+01 6.44540558e+01 5.51612701e+01 4.93825912e+01 5.67530174e+01 6.85110855e+01 6.77236328e+01 6.12367554e+01 6.55433273e+01 6.65520477e+01 6.58931656e+01 6.55485535e+01 6.48790741e+01 6.42526245e+01 6.38717079e+01 6.37059441e+01 6.38814812e+01 6.37579918e+01 6.37925949e+01 6.38568954e+01 6.35093002e+01 6.37087212e+01 6.36176147e+01 6.37045364e+01 6.37903442e+01 6.39782524e+01 6.39031296e+01 6.75011826e+01 6.67299347e+01 6.66475677e+01 6.84437943e+01 6.50276031e+01 6.37710457e+01 6.43252182e+01 6.45336685e+01 6.50092087e+01 6.49808731e+01 6.46285400e+01 6.39501762e+01 6.45880356e+01 6.63522263e+01 6.58986893e+01 6.41828690e+01 6.39620361e+01 6.25608940e+01 5.93438225e+01 7.21923752e+01 -1.25440010e+02 7.20785217e+01 1.22648987e+02 -2.80819427e+02 4.90485229e+02 3.09566589e+02 5.69628372e+01 6.12083588e+01 6.84980469e+01 6.51431808e+01 6.14894333e+01 6.24188004e+01 6.51792374e+01 1.89627029e+02 589828992. 1.67690140e+02 -8.38651794e+02 -2.18275293e+03 1.20691919e+03 1.04639908e+02 -9.99322449e+02 3.37814650e+06 -8.96873938e+05 1.24318970e+03 5.37965576e+02 5.20448380e+01 5.21254120e+01 3.45458145e+01 2.40274315e+01 3.01377316e+01 4.22838173e+01 3.46792526e+01 3.09185581e+01 3.08769302e+01 3.33899307e+01 3.51756783e+01 3.55219002e+01 3.46222496e+01 3.41508408e+01 3.34011993e+01 3.32509689e+01 3.29119453e+01 3.25840759e+01 3.30636673e+01 3.32783356e+01 3.29495354e+01 3.26693230e+01 3.25277748e+01 3.27731323e+01 3.26671562e+01 3.24105301e+01 3.21580925e+01 3.17054329e+01 3.09284248e+01 3.10031452e+01 3.17342720e+01 3.14963722e+01 3.10913773e+01 3.11967182e+01 3.16516705e+01 3.14861584e+01 3.12464447e+01 3.09649563e+01 3.08553486e+01 3.06139355e+01 3.06386223e+01 3.00739994e+01 3.01721649e+01 3.02054691e+01 2.99727840e+01 2.99843807e+01 2.99479828e+01 2.99400387e+01 3.00434933e+01 2.97987537e+01 2.92195911e+01 2.86550732e+01 2.84962482e+01 2.85854244e+01 2.85475616e+01 2.84939651e+01 2.85432854e+01 2.86443253e+01 2.81861553e+01 2.78291512e+01 2.76121159e+01 2.78089256e+01 2.75275211e+01 2.66429043e+01 2.43670578e+01 1.83173027e+01 -1.79993530e+02 -3.68625000e+02 -8.74532852e+01 -1.07150012e+03 -5.09439014e+03 105150272. 0. 0. -844416064. -844416064. -844416064. 0. 0. -126921904. -126921904. -126921904. 0. -176459200. -176459200. -10222370. -493076352. -1.78591321e+03 -6.70439453e+02 -1.53547165e+02 2.05908661e+01 2.70527725e+01 1.86707439e+01 1.79011955e+01 2.18645306e+01 2.08456326e+01 1.96689606e+01 2.07478600e+01 2.25827694e+01 2.29018745e+01 2.26727600e+01 2.22076607e+01 2.12483578e+01 2.07145844e+01 2.01999893e+01 2.07606697e+01 2.06626511e+01 1.97797394e+01 1.96410294e+01 1.94597759e+01 1.98376675e+01 1.90133381e+01 1.83938389e+01 1.77177429e+01 1.73287811e+01 1.67112293e+01 1.71819401e+01 1.71863079e+01 1.75729370e+01 1.69865303e+01 1.68306255e+01 1.67388611e+01 1.66784763e+01 1.68290691e+01 1.69196873e+01 1.65388870e+01 1.64490776e+01 1.59304171e+01 1.56628675e+01 1.49980879e+01 1.50734015e+01 1.44744673e+01 1.41906395e+01 1.38098831e+01 1.39889164e+01 1.41904478e+01 1.39415045e+01 1.39251356e+01 1.37516136e+01 1.35173016e+01 1.29159040e+01 1.23482809e+01 1.23262281e+01 1.27666588e+01 1.23959618e+01 1.19836521e+01 1.14324303e+01 1.14220848e+01 1.11874247e+01 1.11459589e+01 1.12127762e+01 1.12741194e+01 1.10782146e+01 1.07609625e+01 1.04027843e+01 1.02012167e+01 1.01626167e+01 9.88194370e+00 9.38342762e+00 8.93664455e+00 8.68232632e+00 8.67863274e+00 8.56218529e+00 8.38024426e+00 8.04382515e+00 7.91908026e+00 7.45462656e+00 7.25830030e+00 6.91196299e+00 6.75205898e+00 6.46563339e+00 6.33378172e+00 6.14196968e+00 5.91991806e+00 5.65175009e+00 5.36906147e+00 4.94657326e+00 4.59812975e+00 4.36297655e+00 4.21275854e+00 4.05842495e+00 4.14900589e+00 3.97165489e+00 3.77069998e+00 3.43156433e+00 3.24047923e+00 3.11384964e+00 2.77772999e+00 2.51182747e+00 2.10840034e+00 1.94821441e+00 1.78344989e+00 1.81673932e+00 1.51121831e+00 1.17757070e+00 9.46679354e-01 6.85332477e-01 3.87942374e-01 1.30460426e-01 -6.43163621e-02 -2.72324473e-01 -5.49709022e-01 -7.65612423e-01 -8.87021005e-01 -1.06934690e+00 -1.24308896e+00 -1.48737144e+00 -1.71300936e+00 -1.97371173e+00 -2.15168762e+00 -2.44273496e+00 -2.72667027e+00 -2.98028445e+00 -3.14007592e+00 -3.31768370e+00 -3.52753162e+00 -3.81738114e+00 -4.11387014e+00 -4.23793888e+00 -4.42885494e+00 -4.73286629e+00 -4.96496725e+00 -5.14279222e+00 -5.39120150e+00 -5.64329052e+00 -5.88231134e+00 -6.09462643e+00 -6.27297211e+00 -6.50343084e+00 -6.71646595e+00 -6.94078827e+00 -7.17021418e+00 -7.38274765e+00 -7.57316828e+00 -7.81074858e+00 -8.03495502e+00 -8.25481033e+00 -8.48718739e+00 -8.70194244e+00 -8.91009998e+00 -9.13047791e+00 -9.34439278e+00 -9.55723667e+00 -9.77146912e+00 -9.98637867e+00 -1.02042227e+01 -1.04213562e+01 -1.06381531e+01 -1.08536711e+01 -1.10712395e+01 -1.12811747e+01 -1.14917202e+01 -1.17164660e+01 -1.19402752e+01 -1.21765680e+01 -1.23937912e+01 -1.25912399e+01 -1.27945967e+01 -1.30450792e+01 -1.32648439e+01 -1.34485121e+01 -1.36610909e+01 -1.38678436e+01 -1.40428038e+01 -1.42463160e+01 -1.44776335e+01 -1.46657028e+01 -1.49374781e+01 -1.51154470e+01 -1.53176308e+01 -1.55808916e+01 -1.58074684e+01 -1.59613647e+01 -1.61002941e+01 -1.61986198e+01 -1.64745922e+01 -1.66997337e+01 -1.68772297e+01 -1.70727062e+01 -1.73516331e+01 -1.75957985e+01 -1.77614346e+01 -1.79950352e+01 -1.81607151e+01 -1.82898598e+01 -1.84771175e+01 -1.87030525e+01 -1.90424786e+01 -1.91701908e+01 -1.92889271e+01 -1.96055412e+01 -1.99022274e+01 -2.00340862e+01 -1.99871712e+01 -2.01279964e+01 -2.03760109e+01 -2.06667557e+01 -2.07973366e+01 -2.09083118e+01 -2.10881901e+01 -2.13886509e+01 -2.15809231e+01 -2.17575970e+01 -2.18490677e+01 -2.22098312e+01 -2.24713993e+01 -2.25441895e+01 -2.24528027e+01 -2.26814346e+01 -2.29423885e+01 -2.32111206e+01 -2.34414711e+01 -2.36357880e+01 -2.37122250e+01 -2.37170086e+01 -2.39827309e+01 -2.42133255e+01 -2.46856480e+01 -2.48150692e+01 -2.47813225e+01 -2.46073475e+01 -2.48713360e+01 -2.52569923e+01 -2.53848972e+01 -2.54166317e+01 -2.55250416e+01 -2.55152092e+01 -2.57669163e+01 -2.59399815e+01 -2.61492863e+01 -2.65901413e+01 -2.67000332e+01 -2.68456135e+01 -2.66154671e+01 -2.63926849e+01 -2.68386002e+01 -2.73053894e+01 -2.77641087e+01 -2.78950996e+01 -2.79993916e+01 -2.80983696e+01 -2.82934628e+01 -2.86553860e+01 -2.86970119e+01 -2.86726131e+01 -2.87286549e+01 -2.89988136e+01 -2.90239029e+01 -2.90152760e+01 -2.88796902e+01 -2.89912453e+01 -2.91116791e+01 -2.93575001e+01 -2.95950451e+01 -2.95956306e+01 -3.01455536e+01 -3.03961105e+01 -3.10212631e+01 -3.06517029e+01 -3.05566063e+01 -3.05102463e+01 -3.12245846e+01 -3.15978470e+01 -3.11647301e+01 -3.14378681e+01 -3.15090599e+01 -3.19797344e+01 -3.12575436e+01 -3.09213352e+01 -3.09159431e+01 -3.09654484e+01 -3.08191929e+01 -3.11352463e+01 -3.16491146e+01 -3.22227058e+01 -3.20646782e+01 -3.26968193e+01 -3.27655563e+01 -3.31135902e+01 -3.31920471e+01 -3.37164841e+01 -3.33242302e+01 -3.34613342e+01 -3.29814072e+01 -3.30228691e+01 -3.27338142e+01 -3.31874428e+01 -3.30076523e+01 -3.26680450e+01 -3.27969589e+01 -3.29986572e+01 -3.36364861e+01 -3.37141190e+01 -3.44873962e+01 -3.41298599e+01 -3.40832291e+01 -3.38157959e+01 -3.36789818e+01 -3.42018127e+01 -3.53146439e+01 -3.47272720e+01 -3.50282021e+01 -3.47696991e+01 -3.53493881e+01 -3.51030388e+01 -3.48813248e+01 -3.55308418e+01 -3.57952499e+01 -3.57143402e+01 -3.55804176e+01 -3.54331474e+01 -3.57649727e+01 -3.54752998e+01 -3.55067978e+01 -3.56020851e+01 -3.55655823e+01 -3.55436745e+01 -3.60192146e+01 -3.62440605e+01 -3.64183083e+01 -3.62095070e+01 -3.63760757e+01 -3.59316940e+01 -3.59475937e+01 -3.55731888e+01 -3.62901001e+01 -3.64612770e+01 -3.65264664e+01 -3.64290466e+01 -3.64172440e+01 -3.64415207e+01 -3.62133331e+01 -3.58343849e+01 -3.54260216e+01 -3.53019333e+01 -3.56147308e+01 -3.59240303e+01 -3.66418610e+01 -3.65149117e+01 -3.66691284e+01 -3.67178497e+01 -3.69363098e+01 -3.70885429e+01 -3.65486946e+01 -3.65922279e+01 -3.60876884e+01 -3.65561409e+01 -3.69065323e+01 -3.72688866e+01 -3.71479111e+01 -3.68603134e+01 -3.68427849e+01 -3.67721367e+01 -3.68344460e+01 -3.64892387e+01 -3.66436615e+01 -3.66553612e+01 -3.68817291e+01 -3.65242386e+01 -3.69263306e+01 -3.71156960e+01 -3.73080788e+01 -3.71606750e+01 -3.73462296e+01 -3.68123398e+01 -3.65859451e+01 -3.66313591e+01 -3.70492554e+01 -3.67665901e+01 -3.66735458e+01 -3.71223259e+01 -3.68461647e+01 -3.64708786e+01 -3.63454437e+01 -3.66323853e+01 -3.68452873e+01 -3.67245941e+01 -3.63120384e+01 -3.59723892e+01 -3.60121956e+01 -3.61829987e+01 -3.60673904e+01 -3.60311852e+01 -3.63218346e+01 -3.61108360e+01 -3.60579033e+01 -3.60881805e+01 -3.61694260e+01 -3.60028648e+01 -3.61296501e+01 -3.57864494e+01 -3.56585617e+01 -3.52840195e+01 -3.52717972e+01 -3.56124077e+01 -3.59452477e+01 -3.59181557e+01 -3.55449715e+01 -3.55444183e+01 -3.56257858e+01 -3.54707794e+01 -3.53186836e+01 -3.51403809e+01 -3.48389931e+01 -3.48807411e+01 -3.48838997e+01 -3.48085022e+01 -3.47782936e+01 -3.47377548e+01 -3.48725128e+01 -3.47667236e+01 -3.44192886e+01 -3.43182678e+01 -3.44056778e+01 -3.44608421e+01 -3.43480453e+01 -3.42261314e+01 -3.45315170e+01 -3.40197678e+01 -3.36049995e+01 -3.42025070e+01 -3.42684555e+01 -3.41579056e+01 -3.38752823e+01 -3.33229370e+01 -3.34758301e+01 -3.34936333e+01 -3.36821213e+01 -3.35654373e+01 -3.31387253e+01 -3.27088737e+01 -3.28926849e+01 -3.23741951e+01 -3.24127312e+01 -3.25376091e+01 -3.24977760e+01 -3.24584160e+01 -3.22591171e+01 -3.23180161e+01 -3.24258385e+01 -3.18093071e+01 -3.10758057e+01 -3.14610691e+01 -3.14370651e+01 -3.13423271e+01 -3.14347515e+01 -3.15488987e+01 -3.15778275e+01 -3.14913425e+01 -3.09433212e+01 -3.06387119e+01 -3.04824467e+01 -3.05083904e+01 -3.01913471e+01 -2.98588753e+01 -2.98569908e+01 -3.00561466e+01 -3.02958031e+01 -3.02103443e+01 -3.02302513e+01 -3.01189957e+01 -2.99304771e+01 -2.93512917e+01 -2.89973507e+01 -2.87434673e+01 -2.81573830e+01 -2.83449554e+01 -2.88258419e+01 -2.90012054e+01 -2.94696236e+01 -2.87036018e+01 -2.74184303e+01 -2.74093952e+01 -2.82378960e+01 -2.82194595e+01 -2.75133190e+01 -2.69550362e+01 -2.66133251e+01 -2.71874161e+01 -2.70644341e+01 -2.67842636e+01 -2.64968166e+01 -2.62896690e+01 -2.58289776e+01 -2.57558098e+01 -2.56145020e+01 -2.57601337e+01 -2.54505558e+01 -2.51647320e+01 -2.46028557e+01 -2.40894604e+01 -2.45092430e+01 -2.46500530e+01 -2.51157093e+01 -2.47818775e+01 -2.42880192e+01 -2.37342739e+01 -2.36398239e+01 -2.37148170e+01 -2.38319378e+01 -2.38472233e+01 -2.33808594e+01 -2.30993519e+01 -2.31835880e+01 -2.31308842e+01 -2.24293747e+01 -2.20725403e+01 -2.17569275e+01 -2.14562016e+01 -2.10844059e+01 -2.11033058e+01 -2.15242310e+01 -2.16226597e+01 -2.16583023e+01 -2.09591675e+01 -2.07022705e+01 -2.03718624e+01 -2.10677986e+01 -2.06642094e+01 -2.00586777e+01 -1.99511490e+01 -1.98124657e+01 -2.02276745e+01 -1.90393257e+01 -1.82265816e+01 -1.75292320e+01 -1.72001629e+01 -1.70521870e+01 -1.75964012e+01 -1.74784031e+01 -1.75499439e+01 -1.71397324e+01 -1.74897480e+01 -1.72031441e+01 -1.70313072e+01 -1.68265972e+01 -1.71673393e+01 -1.65012093e+01 -1.61665573e+01 -1.58260727e+01 -1.54683199e+01 -1.50848370e+01 -1.51130161e+01 -1.49580889e+01 -1.44248104e+01 -1.42628174e+01 -1.40023518e+01 -1.40834007e+01 -1.40082684e+01 -1.40411348e+01 -1.35228329e+01 -1.30918407e+01 -1.26789150e+01 -1.22629709e+01 -1.25753479e+01 -1.30255814e+01 -1.25090933e+01 -1.22429161e+01 -1.19913740e+01 -1.20762510e+01 -1.18360891e+01 -1.13965101e+01 -1.12264404e+01 -1.11961660e+01 -1.09749088e+01 -1.07376060e+01 -1.04257183e+01 -1.02639275e+01 -9.92979240e+00 -9.60348701e+00 -9.30292511e+00 -9.06856823e+00 -8.76691437e+00 -8.75735283e+00 -8.71143246e+00 -8.55644608e+00 -8.23638439e+00 -8.04332733e+00 -7.47781420e+00 -7.30726385e+00 -6.83764458e+00 -6.75366879e+00 -6.59557343e+00 -6.49688530e+00 -6.32451630e+00 -6.22458839e+00 -5.97450590e+00 -5.59417105e+00 -5.10330534e+00 -4.63455105e+00 -4.25861359e+00 -4.24256277e+00 -4.29745960e+00 -4.28355169e+00 -4.08509111e+00 -3.78054523e+00 -3.48748136e+00 -3.28027630e+00 -3.13423252e+00 -2.84351087e+00 -2.67873359e+00 -2.29350901e+00 -2.07829261e+00 -1.87225354e+00 -1.79949558e+00 -1.51303232e+00 -1.23069835e+00 -1.01698101e+00 -7.31792092e-01 -3.86918724e-01 -3.63935530e-02 8.02646279e-02 2.18189344e-01 3.65030915e-01 6.52460396e-01 8.44761848e-01 1.03726768e+00 1.21979094e+00 1.42651844e+00 1.65989983e+00 1.97751379e+00 2.20044088e+00 2.40768623e+00 2.57640886e+00 2.85129476e+00 3.04375124e+00 3.18056703e+00 3.45164680e+00 3.76604009e+00 4.02856350e+00 4.15082264e+00 4.36220694e+00 4.60648394e+00 4.89547491e+00 5.13237190e+00 5.32355738e+00 5.52924538e+00 5.78419018e+00 6.00758982e+00 6.19981241e+00 6.42192554e+00 6.63193655e+00 6.86321592e+00 7.05786896e+00 7.26875496e+00 7.48431349e+00 7.71935081e+00 7.95509005e+00 8.17959976e+00 8.39122295e+00 8.60132122e+00 8.82240963e+00 9.04381275e+00 9.26239777e+00 9.47176170e+00 9.68918133e+00 9.90219784e+00 1.01155062e+01 1.03295870e+01 1.05355453e+01 1.07444429e+01 1.09505224e+01 1.11653738e+01 1.13839302e+01 1.15975447e+01 1.18067465e+01 1.20107965e+01 1.22306633e+01 1.24373083e+01 1.26413403e+01 1.28462868e+01 1.30588636e+01 1.32663708e+01 1.34708939e+01 1.36762638e+01 1.38982887e+01 1.41807613e+01 1.43947277e+01 1.45289154e+01 1.47463779e+01 1.49311447e+01 1.51963902e+01 1.54108715e+01 1.56452951e+01 1.58750219e+01 1.60141754e+01 1.61743851e+01 1.64861889e+01 1.66662369e+01 1.68235168e+01 1.69645348e+01 1.73013477e+01 1.75030155e+01 1.76973782e+01 1.79053078e+01 1.80436287e+01 1.81580715e+01 1.83591633e+01 1.86171169e+01 1.88452587e+01 1.90298996e+01 1.92588787e+01 1.94972305e+01 1.97495937e+01 1.98971882e+01 1.99294891e+01 2.00675678e+01 2.01929607e+01 2.05633659e+01 2.06584187e+01 2.07658195e+01 2.09625454e+01 2.13022614e+01 2.14458408e+01 2.15670586e+01 2.17403355e+01 2.19598255e+01 2.22154121e+01 2.23992729e+01 2.24165344e+01 2.26324558e+01 2.28718224e+01 2.30568237e+01 2.32659225e+01 2.34548321e+01 2.37071056e+01 2.37589970e+01 2.39855690e+01 2.42376480e+01 2.45387955e+01 2.46535664e+01 2.46579189e+01 2.45303669e+01 2.48863182e+01 2.52483349e+01 2.53823147e+01 2.53890076e+01 2.54713154e+01 2.55415497e+01 2.57415676e+01 2.58498096e+01 2.59747696e+01 2.62401981e+01 2.65540886e+01 2.66875591e+01 2.63647003e+01 2.60599308e+01 2.66939201e+01 2.74413414e+01 2.77542915e+01 2.77195129e+01 2.77729759e+01 2.78348751e+01 2.80480709e+01 2.81913624e+01 2.84884338e+01 2.86172981e+01 2.85955582e+01 2.86939602e+01 2.88144054e+01 2.90190868e+01 2.89673843e+01 2.89252148e+01 2.90075378e+01 2.93193302e+01 2.98454819e+01 2.98384266e+01 3.00246563e+01 3.00754662e+01 3.06271210e+01 3.03780117e+01 3.04460926e+01 3.04625511e+01 3.10233650e+01 3.11067562e+01 3.11308289e+01 3.15056458e+01 3.15285034e+01 3.21287422e+01 3.14619942e+01 3.12724247e+01 3.09866199e+01 3.07448845e+01 3.07731667e+01 3.13190994e+01 3.16964531e+01 3.21175385e+01 3.22538033e+01 3.25611610e+01 3.23282509e+01 3.28150864e+01 3.33478508e+01 3.38012695e+01 3.30960770e+01 3.31770096e+01 3.29669266e+01 3.30184288e+01 3.26076241e+01 3.29457359e+01 3.67092857e+01 3.62064285e+01 3.23457909e+01 3.41882172e+01 3.43933945e+01 3.39861183e+01 3.56688194e+01 3.32168236e+01 3.03766708e+01 3.27390480e+01 3.53393822e+01 3.23687439e+01 3.25107880e+01 2.29917664e+02 3.12665283e+02 6.89369995e+02 3.68677319e+03 -324448992. 0. -268468640. -268468640. -8252523. -440080640. -440080640. 0. 0. 0. 0. 0. -299095488. -5035621. 1.15053344e+05 2.91747681e+03 1.21402759e+03 1.93025360e+02 4.57712067e+02 2.19550201e+02 2.75025101e+01 5.34834747e+01 6.35991936e+01 4.87213631e+01 3.87745361e+01 3.75465050e+01 3.57863960e+01 3.71507835e+01 3.28218002e+01 2.72034073e+01 3.01512127e+01 1.90660496e+01 2.25475636e+01 4.40558586e+01 4.10604973e+01 4.46996460e+01 4.63166313e+01 3.55697136e+01 3.39429817e+01 3.54135208e+01 4.01623688e+01 4.05237312e+01 3.37125435e+01 3.09948368e+01 3.68801422e+01 3.80891266e+01 3.81900215e+01 3.83442726e+01 3.77456627e+01 3.71016426e+01 3.62094154e+01 3.61096764e+01 3.65603180e+01 3.71156540e+01 3.70374107e+01 3.70053062e+01 3.66010132e+01 3.66909981e+01 3.64537010e+01 3.62734528e+01 3.64045639e+01 3.68906212e+01 3.69798775e+01 4.06183624e+01 3.95160980e+01 3.91208839e+01 4.09953270e+01 3.74405632e+01 3.62408562e+01 3.63370438e+01 3.67855682e+01 3.72013893e+01 3.73775787e+01 3.66169319e+01 3.60397949e+01 3.64563293e+01 3.68560181e+01 3.64215660e+01 3.50920029e+01 3.42290840e+01 3.17095814e+01 2.52627869e+01 4.56391411e+01 -2.91109741e+02 -3.62302948e+02 1.22114822e+02 -2.14127368e+03 2.24159814e+03 9.37617554e+02 2.32167091e+01 4.19520813e+02 6.82539825e+01 -3.14507812e+02 4.79597855e+01 5.39303780e+01 7.04701080e+01 1.80153992e+02 -1.06193347e+10 -161225136. -161225136. -9.24121805e+09 8.71484006e+09 8.71484006e+09 8.71484006e+09 0. 0. 2.56066335e+10 5.08697754e+03 1.01593292e+03 8.35211258e+01 -3.21685669e+02 -1.78295334e+02 3.77952919e+01 5.12217789e+01 4.61635170e+01 4.33054771e+01 4.11266403e+01 4.00021324e+01 4.05237923e+01 4.05722008e+01 4.04094963e+01 4.08134613e+01 3.99854240e+01 3.95037079e+01 3.91687813e+01 3.94830627e+01 3.98971481e+01 3.99095612e+01 3.97761726e+01 4.01585770e+01 4.04366608e+01 3.99933929e+01 3.95785942e+01 3.89115868e+01 3.88475914e+01 3.85951157e+01 3.87124405e+01 3.92386055e+01 3.90903931e+01 3.88029289e+01 3.82709656e+01 3.67692032e+01 3.65225754e+01 3.80059586e+01 3.82195663e+01 4.02782784e+01 4.01177444e+01 3.82689285e+01 3.80980530e+01 3.79167519e+01 3.81823959e+01 3.76753845e+01 3.71990547e+01 3.72879372e+01 3.69661751e+01 3.67380905e+01 3.61697235e+01 3.65660934e+01 3.64517784e+01 3.65128822e+01 3.62926178e+01 3.60273056e+01 3.59310112e+01 3.55167007e+01 3.62254257e+01 3.61247635e+01 3.56381874e+01 3.51482887e+01 3.51292877e+01 3.49830513e+01 3.29759102e+01 3.25470276e+01 -1.61941742e+02 -3.31951263e+02 -8.73748596e+02 -2.58746826e+03 -2.85450406e+05 788625088. 524555392. 0. -2.30841114e+09 -2.30841114e+09 3.10406579e+09 -844416064. -844416064. 0. 0. 0. 0. 0. 0. -2.64499344e+05 2.28154810e+03 3.68495483e+02 -6.37369873e+02 -2.66755646e+02 -1.36382675e+02 3.16316109e+01 2.92518120e+01 3.22753983e+01 3.07377052e+01 2.99849586e+01 2.96132641e+01 2.95971737e+01 2.82433662e+01 2.90977917e+01 3.01007156e+01 2.95185089e+01 2.94459419e+01 2.89911156e+01 2.86011925e+01 2.79883823e+01 2.76325951e+01 2.74252834e+01 2.71230202e+01 2.71044807e+01 2.72612152e+01 2.70888596e+01 2.65857983e+01 2.65097275e+01 2.62250462e+01 2.60820560e+01 2.60249252e+01 2.58764553e+01 2.56768742e+01 2.54500656e+01 2.51587982e+01 2.49043751e+01 2.46614552e+01 2.45663471e+01 2.41338387e+01 2.36727295e+01 2.34516773e+01 2.38804798e+01 2.34043407e+01 2.36210995e+01 2.32748127e+01 2.28028984e+01 2.25960159e+01 2.24262199e+01 2.28458672e+01 2.26731396e+01 2.25139942e+01 2.18958626e+01 2.15149632e+01 2.10939503e+01 2.05098228e+01 1.99235229e+01 2.01015720e+01 1.99583511e+01 2.01889477e+01 1.99609261e+01 2.01592445e+01 1.91627026e+01 1.88376751e+01 1.88328171e+01 1.86856213e+01 1.82052994e+01 1.77883873e+01 1.79810085e+01 1.79830475e+01 1.78484650e+01 1.73542042e+01 1.69664135e+01 1.68911572e+01 1.65452862e+01 1.62108307e+01 1.62041779e+01 1.61176510e+01 1.56514730e+01 1.52985058e+01 1.51763706e+01 1.52222862e+01 1.48377628e+01 1.45229807e+01 1.41015673e+01 1.39941034e+01 1.36765795e+01 1.32126455e+01 1.27049026e+01 1.27574472e+01 1.27640867e+01 1.25297318e+01 1.22305775e+01 1.16644192e+01 1.14984703e+01 1.12427330e+01 1.08705702e+01 1.08522549e+01 1.08178129e+01 1.06628456e+01 1.00647392e+01 9.60680866e+00 9.64600849e+00 9.65806103e+00 9.42798138e+00 8.73499489e+00 8.57154560e+00 8.27091503e+00 8.14382648e+00 7.93671227e+00 7.62373638e+00 7.38432598e+00 7.13694143e+00 6.89763021e+00 6.59839582e+00 6.39507151e+00 6.17821836e+00 5.87618494e+00 5.64315891e+00 5.51037169e+00 5.25878668e+00 4.93143559e+00 4.60306025e+00 4.31870222e+00 4.10847044e+00 3.87667584e+00 3.66826463e+00 3.35690379e+00 3.02301311e+00 2.79777527e+00 2.54666829e+00 2.30705690e+00 2.07611561e+00 1.78141713e+00 1.42557979e+00 1.33928120e+00 1.08209014e+00 7.21253872e-01 4.74103838e-01 2.84729600e-01 3.59392986e-02 -2.72445679e-01 -5.58761656e-01 -8.02812576e-01 -1.01719522e+00 -1.28062165e+00 -1.54277933e+00 -1.77649713e+00 -2.04767513e+00 -2.30273175e+00 -2.54832721e+00 -2.82588124e+00 -3.09156322e+00 -3.33212209e+00 -3.59279180e+00 -3.84235430e+00 -4.08746338e+00 -4.34555769e+00 -4.59979725e+00 -4.84929276e+00 -5.10251236e+00 -5.35703516e+00 -5.60926914e+00 -5.86287546e+00 -6.11497736e+00 -6.36608124e+00 -6.61956882e+00 -6.86173630e+00 -7.10751724e+00 -7.36928511e+00 -7.61415100e+00 -7.88975954e+00 -8.15003872e+00 -8.36229992e+00 -8.61124134e+00 -8.89211559e+00 -9.15354347e+00 -9.39682865e+00 -9.65473843e+00 -9.87572861e+00 -1.00914125e+01 -1.03601980e+01 -1.05883522e+01 -1.08630295e+01 -1.11765747e+01 -1.14160786e+01 -1.16696548e+01 -1.20092392e+01 -1.22073851e+01 -1.24029741e+01 -1.26203909e+01 -1.28364124e+01 -1.30898304e+01 -1.33752279e+01 -1.36844130e+01 -1.39445362e+01 -1.41870108e+01 -1.43864098e+01 -1.45801210e+01 -1.48601360e+01 -1.51422415e+01 -1.54683981e+01 -1.56424608e+01 -1.58883934e+01 -1.62324905e+01 -1.63802166e+01 -1.64193325e+01 -1.66944675e+01 -1.70831699e+01 -1.72835255e+01 -1.76097164e+01 -1.77844810e+01 -1.80727139e+01 -1.82772579e+01 -1.84304295e+01 -1.86074944e+01 -1.86905918e+01 -1.89254055e+01 -1.93049850e+01 -1.95738811e+01 -1.97480717e+01 -1.98133640e+01 -2.01651897e+01 -2.02883816e+01 -2.06415901e+01 -2.08701611e+01 -2.10005856e+01 -2.12764854e+01 -2.15621243e+01 -2.19618149e+01 -2.21481628e+01 -2.23004169e+01 -2.24728241e+01 -2.25927601e+01 -2.30822659e+01 -2.30061092e+01 -2.33021545e+01 -2.34421082e+01 -2.37598305e+01 -2.40351810e+01 -2.40077553e+01 -2.42030602e+01 -2.44593029e+01 -2.51317806e+01 -2.53833752e+01 -2.52747154e+01 -2.55220737e+01 -2.58494148e+01 -2.60467091e+01 -2.61025562e+01 -2.62180634e+01 -2.64865189e+01 -2.65232773e+01 -2.64074726e+01 -2.67199001e+01 -2.72551517e+01 -2.80460491e+01 -2.83819809e+01 -2.83154526e+01 -2.83293762e+01 -2.85192032e+01 -2.84936695e+01 -2.90154285e+01 -2.91380692e+01 -2.91347084e+01 -2.91368332e+01 -2.90413857e+01 -2.94823246e+01 -2.97416763e+01 -2.99904099e+01 -2.98686733e+01 -2.99465160e+01 -3.02998428e+01 -3.10595074e+01 -3.10048599e+01 -3.09083614e+01 -3.07317142e+01 -3.08734169e+01 -3.09566593e+01 -3.11662560e+01 -3.16058159e+01 -3.20951843e+01 -3.24067802e+01 -3.25513763e+01 -3.25646057e+01 -3.25220947e+01 -3.27649689e+01 -3.28260803e+01 -3.28448448e+01 -3.31190338e+01 -3.35219345e+01 -3.35367165e+01 -3.40759239e+01 -3.41960373e+01 -3.43570976e+01 -3.41434746e+01 -3.43339424e+01 -3.42984085e+01 -3.49645576e+01 -3.46599388e+01 -3.49708366e+01 -3.47537842e+01 -3.52109985e+01 -3.54451714e+01 -3.48055954e+01 -3.55217209e+01 -3.60853996e+01 -3.65674095e+01 -3.65356293e+01 -3.66375427e+01 -3.64828186e+01 -3.59747543e+01 -3.56396904e+01 -3.63042412e+01 -3.61844330e+01 -3.70282249e+01 -3.73227615e+01 -3.80408974e+01 -3.74196968e+01 -3.74422112e+01 -3.77942963e+01 -3.83723335e+01 -3.74245453e+01 -3.74977837e+01 -3.83518753e+01 -3.78809853e+01 -3.79164963e+01 -3.76274719e+01 -3.77572784e+01 -3.79030571e+01 -3.78718452e+01 -3.81303558e+01 -3.86853447e+01 -3.92385330e+01 -3.93540878e+01 -3.92081070e+01 -3.93333015e+01 -3.98457069e+01 -3.97145271e+01 -3.98321686e+01 -3.95548592e+01 -3.97400055e+01 -3.97855148e+01 -3.97422485e+01 -3.90957870e+01 -3.95410728e+01 -3.99908943e+01 -4.01408501e+01 -4.02774696e+01 -3.97813339e+01 -3.97497406e+01 -3.97795982e+01 -3.96988487e+01 -4.01162682e+01 -4.03293152e+01 -4.05497589e+01 -4.06849670e+01 -4.04305038e+01 -4.05382042e+01 -4.01403923e+01 -4.04388962e+01 -4.03745918e+01 -4.08343773e+01 -4.12323456e+01 -4.15401382e+01 -4.10529556e+01 -4.09181366e+01 -4.12994156e+01 -4.12817307e+01 -4.15047607e+01 -4.18753777e+01 -4.18483925e+01 -4.18190575e+01 -4.16113892e+01 -4.16939125e+01 -4.17727966e+01 -4.15771141e+01 -4.15858955e+01 -4.11579018e+01 -4.13687668e+01 -4.18078842e+01 -4.18557587e+01 -4.18496246e+01 -4.18113899e+01 -4.17624817e+01 -4.15272751e+01 -4.14321480e+01 -4.18761826e+01 -4.17644043e+01 -4.20736046e+01 -4.20243416e+01 -4.19984589e+01 -4.18600616e+01 -4.19800568e+01 -4.21110001e+01 -4.19577713e+01 -4.18412170e+01 -4.20638084e+01 -4.16840515e+01 -4.15862389e+01 -4.20162926e+01 -4.19651146e+01 -4.19462471e+01 -4.19598007e+01 -4.18628540e+01 -4.18724670e+01 -4.19300575e+01 -4.17586021e+01 -4.16278496e+01 -4.09680634e+01 -4.09072609e+01 -4.16350708e+01 -4.24359207e+01 -4.25589828e+01 -4.15586700e+01 -4.17049751e+01 -4.20378914e+01 -4.17496872e+01 -4.15679092e+01 -4.13854523e+01 -4.11731644e+01 -4.12200623e+01 -4.12811546e+01 -4.12715950e+01 -4.13428764e+01 -4.13358116e+01 -4.13555336e+01 -4.16100731e+01 -4.10064697e+01 -4.03239136e+01 -4.12946396e+01 -4.14792061e+01 -4.09704819e+01 -4.09476051e+01 -4.14162521e+01 -4.08313675e+01 -4.01574059e+01 -4.04069099e+01 -4.04869423e+01 -4.08250046e+01 -4.04426384e+01 -4.02480621e+01 -4.04547005e+01 -4.04142342e+01 -4.03249931e+01 -3.99417801e+01 -3.98639030e+01 -3.97736435e+01 -3.99818878e+01 -3.95724640e+01 -4.04731827e+01 -4.07105980e+01 -3.96149063e+01 -3.90468216e+01 -3.86385117e+01 -3.91058350e+01 -3.96678581e+01 -3.99369736e+01 -3.94399529e+01 -3.89082680e+01 -3.89148521e+01 -3.88395233e+01 -3.86602402e+01 -3.82012672e+01 -3.83089523e+01 -3.85596275e+01 -3.86563759e+01 -3.82683029e+01 -3.79748306e+01 -3.78114891e+01 -3.76137657e+01 -3.76882591e+01 -3.72933922e+01 -3.69827118e+01 -3.70755348e+01 -3.70673294e+01 -3.68931770e+01 -3.61027451e+01 -3.61560287e+01 -3.60215454e+01 -3.65967979e+01 -3.63833542e+01 -3.59528427e+01 -3.60052567e+01 -3.61393547e+01 -3.65346489e+01 -3.67817116e+01 -3.64291840e+01 -3.52757492e+01 -3.53270378e+01 -3.62714310e+01 -3.54221115e+01 -3.48110657e+01 -3.44429550e+01 -3.43908501e+01 -3.45353928e+01 -3.45556755e+01 -3.41775589e+01 -3.38580208e+01 -3.46150703e+01 -3.42924690e+01 -3.37786140e+01 -3.32182770e+01 -3.32268639e+01 -3.33579254e+01 -3.26609726e+01 -3.23061981e+01 -3.23262100e+01 -3.21107826e+01 -3.19730663e+01 -3.22505417e+01 -3.21475754e+01 -3.23332825e+01 -3.21865273e+01 -3.18110790e+01 -3.10451202e+01 -3.10502396e+01 -3.08485546e+01 -3.12951107e+01 -3.07880173e+01 -3.02184086e+01 -3.03524418e+01 -3.04501114e+01 -3.05128517e+01 -3.00671597e+01 -2.93747139e+01 -2.85562019e+01 -2.86532440e+01 -2.88793716e+01 -2.95442390e+01 -2.86896305e+01 -2.81038761e+01 -2.79866562e+01 -2.79098625e+01 -2.78867588e+01 -2.72710781e+01 -2.70846958e+01 -2.71300716e+01 -2.70473194e+01 -2.71139069e+01 -2.66426468e+01 -2.63257160e+01 -2.58586826e+01 -2.56133499e+01 -2.57141743e+01 -2.60840893e+01 -2.58537712e+01 -2.51056786e+01 -2.49740162e+01 -2.48332882e+01 -2.47742176e+01 -2.42030544e+01 -2.38019905e+01 -2.34486160e+01 -2.36348534e+01 -2.32487278e+01 -2.33685055e+01 -2.28662167e+01 -2.25505047e+01 -2.26421032e+01 -2.24681587e+01 -2.26165867e+01 -2.24103394e+01 -2.22576332e+01 -2.19340534e+01 -2.17256927e+01 -2.12463055e+01 -2.06039619e+01 -2.00445232e+01 -2.01795273e+01 -1.98198776e+01 -1.99707680e+01 -1.96809273e+01 -1.98802605e+01 -1.93421574e+01 -1.93213024e+01 -1.92705784e+01 -1.90696468e+01 -1.85136585e+01 -1.78562450e+01 -1.76748638e+01 -1.76113148e+01 -1.74634666e+01 -1.72369614e+01 -1.72252712e+01 -1.70394421e+01 -1.65104942e+01 -1.62131195e+01 -1.60039120e+01 -1.60051899e+01 -1.58131008e+01 -1.54019918e+01 -1.51907368e+01 -1.51459265e+01 -1.48928108e+01 -1.45485773e+01 -1.41034632e+01 -1.39446287e+01 -1.35465727e+01 -1.32021313e+01 -1.27330313e+01 -1.27323780e+01 -1.28096514e+01 -1.25920811e+01 -1.23407249e+01 -1.17886343e+01 -1.13746862e+01 -1.12215223e+01 -1.10469656e+01 -1.08695965e+01 -1.06922722e+01 -1.06465197e+01 -1.03364191e+01 -9.81655025e+00 -9.57391739e+00 -9.18029976e+00 -8.91468430e+00 -8.71689510e+00 -8.74006748e+00 -8.38061905e+00 -8.19588280e+00 -7.77108288e+00 -7.48660278e+00 -7.38694763e+00 -7.13515043e+00 -6.88712645e+00 -6.42657757e+00 -5.39202166e+00 -5.26195860e+00 -5.59520388e+00 -5.67888546e+00 -5.60798931e+00 -5.07699203e+00 -4.61127520e+00 -4.36956310e+00 -3.69795060e+00 4.76682930e+01 -1.72798681e+00 -5.17908249e+01 -3.50065494e+00 -3.83874059e+00 4.17092590e+01 -2.01380208e-01 -4.35453110e+01 -1.59346497e+00 -1.43735468e+00 -1.41559243e+00 -1.21567941e+00 -9.59989786e-01 -7.60522902e-01 -5.55925429e-01 -4.20102715e-01 -2.40776554e-01 1.74327701e-01 5.36314309e-01 7.58855462e-01 1.06205761e+00 1.30603111e+00 1.51263773e+00 1.80030727e+00 2.05361152e+00 2.29169607e+00 2.52652931e+00 2.80428457e+00 3.09851623e+00 3.35487413e+00 3.57353258e+00 3.83540869e+00 4.10785389e+00 4.34048462e+00 4.59676886e+00 4.84124041e+00 5.09136343e+00 5.34851694e+00 5.60430431e+00 5.85990858e+00 6.10804653e+00 6.35004234e+00 6.60100031e+00 6.86151314e+00 7.11897564e+00 7.36343002e+00 7.60670280e+00 7.85336018e+00 8.11194897e+00 8.36883450e+00 8.62434769e+00 8.84498692e+00 9.09253979e+00 9.34254742e+00 9.62007809e+00 9.86225796e+00 1.00917568e+01 1.04020185e+01 1.06495056e+01 1.08690166e+01 1.11648426e+01 1.14104280e+01 1.16487942e+01 1.18844175e+01 1.20821953e+01 1.23358173e+01 1.25939407e+01 1.27704477e+01 1.30968723e+01 1.34593134e+01 1.37316494e+01 1.39596758e+01 1.41964912e+01 1.43773441e+01 1.44503345e+01 1.47135010e+01 1.49643965e+01 1.53424826e+01 1.55380926e+01 1.57713270e+01 1.59466515e+01 1.60309830e+01 1.62966385e+01 1.64614296e+01 1.68734684e+01 1.71644936e+01 1.75115261e+01 1.78254337e+01 1.80134792e+01 1.82812996e+01 1.83324871e+01 1.86373482e+01 1.87488327e+01 1.89152241e+01 1.91132259e+01 1.93112450e+01 1.94659195e+01 1.95086708e+01 2.00680847e+01 2.03672924e+01 2.07223148e+01 2.09967690e+01 2.10913887e+01 2.10009861e+01 2.10726643e+01 2.15746040e+01 2.20309772e+01 2.22468243e+01 2.26011620e+01 2.26395721e+01 2.29151478e+01 2.28822536e+01 2.32522316e+01 2.33583546e+01 2.37737408e+01 2.40454922e+01 2.38205051e+01 2.39498425e+01 2.42769547e+01 2.49802608e+01 2.52847843e+01 2.53483810e+01 2.54313240e+01 2.55933170e+01 2.58362064e+01 2.59774303e+01 2.59669914e+01 2.61257172e+01 2.63582649e+01 2.66266232e+01 2.69077473e+01 2.71534328e+01 2.76145191e+01 2.81256657e+01 2.83723240e+01 2.81511726e+01 2.83358536e+01 2.83188057e+01 2.88502903e+01 2.89716206e+01 2.82773342e+01 2.86131268e+01 2.95899754e+01 3.03422489e+01 3.02580872e+01 2.97914181e+01 2.98606129e+01 3.00758190e+01 3.03033695e+01 3.09393330e+01 3.06046066e+01 3.06693134e+01 3.08078728e+01 3.09621601e+01 3.08763790e+01 3.08109741e+01 3.14219685e+01 3.19522839e+01 3.20199013e+01 3.22164001e+01 3.26051331e+01 3.27404480e+01 3.30836105e+01 3.20227623e+01 3.23265991e+01 3.35173264e+01 3.35611954e+01 3.45546150e+01 3.48791809e+01 3.37297821e+01 3.38770294e+01 3.40305557e+01 3.41898994e+01 3.40026512e+01 3.45104675e+01 3.34253235e+01 3.41836853e+01 3.51857796e+01 3.57637215e+01 3.58393784e+01 3.49725189e+01 3.56432381e+01 3.58854332e+01 3.55144272e+01 3.49822159e+01 3.59967155e+01 3.69653511e+01 3.63235435e+01 3.56957970e+01 3.61641121e+01 3.53205986e+01 3.53002472e+01 3.26040840e+01 3.86271896e+01 2.73136654e+01 2.15051712e+02 7.75827454e+02 1.96699170e+03 994388864. 3109245. -268468640. -268468640. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1172492288. -18423924. 2.28281750e+05 2.61072266e+03 9.50846008e+02 2.71584381e+02 4.27107468e+01 4.57873421e+01 4.42533302e+01 4.22492867e+01 4.14218979e+01 4.00929298e+01 4.13223572e+01 3.78144493e+01 3.22832565e+01 3.87663078e+01 4.14403763e+01 4.02080841e+01 4.28722038e+01 4.14325829e+01 4.05244675e+01 3.94404640e+01 3.93541412e+01 4.05346031e+01 4.25612030e+01 4.21451416e+01 4.18447304e+01 4.13432426e+01 4.10833511e+01 4.01673546e+01 3.94061546e+01 4.08888168e+01 4.25031128e+01 4.26348267e+01 4.23333511e+01 4.15986481e+01 4.13747826e+01 4.16557846e+01 4.17255821e+01 4.20079880e+01 4.14199791e+01 4.14959183e+01 4.10154114e+01 4.05963593e+01 4.06438446e+01 4.13808823e+01 4.20446167e+01 4.19423714e+01 4.21668701e+01 4.18871346e+01 4.14470520e+01 4.16382675e+01 4.16489716e+01 4.16351166e+01 4.15441895e+01 4.19934006e+01 4.22353249e+01 4.21609039e+01 4.17425423e+01 4.18285484e+01 4.19173698e+01 4.26154938e+01 4.17531509e+01 4.01548958e+01 3.95585899e+01 3.70798912e+01 3.07337532e+01 5.01037369e+01 2.14513184e+02 -9.96777954e+02 2.45936102e+09 2.45936102e+09 5.25647053e+09 42531004. -5.29378500e+05 2.24754468e+03 2.29510071e+02 -2.06356445e+03 -9.45902250e+05 -1.38574234e+05 48479208. -33083930. 0. 0. -2.51298161e+10 -2083047040. -6.46987598e+03 3.61175142e+09 8.71484006e+09 0. 0. 2.56066335e+10 5.08697754e+03 1.01593292e+03 8.35211258e+01 4.44362793e+02 2.64674072e+02 3.60257378e+01 4.25299072e+01 4.33082542e+01 4.25854607e+01 3.94424095e+01 3.70027084e+01 3.76980133e+01 3.87242508e+01 3.85605545e+01 3.84602623e+01 3.83635292e+01 3.86158524e+01 3.93313599e+01 3.93062325e+01 3.91133957e+01 3.80513039e+01 3.77605324e+01 3.77497253e+01 3.83387108e+01 4.01936798e+01 4.01527672e+01 3.77428169e+01 3.72600327e+01 3.74070663e+01 3.71051636e+01 3.79954071e+01 3.79700737e+01 3.76366653e+01 3.73852577e+01 3.16094379e+01 3.08726139e+01 3.64546623e+01 3.76702194e+01 4.20641098e+01 4.39080849e+01 3.94915695e+01 3.77728691e+01 3.79034042e+01 3.81040611e+01 3.75261116e+01 3.72789459e+01 3.68317032e+01 3.67681961e+01 3.66822548e+01 3.71646500e+01 3.70906525e+01 3.69129066e+01 3.61790848e+01 3.67297668e+01 3.64577370e+01 3.58964386e+01 3.58311729e+01 3.60700722e+01 3.55525055e+01 3.45786438e+01 3.35495529e+01 3.27136726e+01 3.23258133e+01 -1.59484573e+02 -3.01571320e+02 -7.41231567e+02 -2.13960303e+03 -129402768. 5.04896050e+06 2.73123584e+09 2.73123584e+09 0. 0. -2.30841114e+09 -2.30841114e+09 3.10406579e+09 -844416064. -844416064. 0. 0. 0. 0. -873056960. -137949360. -1.80614197e+03 -6.75039551e+02 -2.71924286e+02 -1.39398727e+02 3.15984669e+01 3.12796173e+01 3.24613152e+01 3.22817764e+01 3.11925297e+01 3.06295948e+01 3.12040615e+01 3.17623920e+01 3.19639416e+01 3.16804924e+01 3.09648743e+01 3.07488976e+01 3.03957558e+01 2.97774429e+01 2.95144958e+01 2.94428215e+01 2.90772095e+01 2.93325081e+01 2.93220596e+01 2.94296703e+01 2.89448318e+01 2.83179760e+01 2.82748089e+01 2.84068298e+01 2.84469891e+01 2.81873302e+01 2.77346592e+01 2.78651543e+01 2.76918240e+01 2.72207298e+01 2.69702930e+01 2.63535004e+01 2.61227360e+01 2.61392193e+01 2.64784431e+01 2.67976341e+01 2.67178898e+01 2.65947914e+01 2.59714184e+01 2.55690918e+01 2.53766842e+01 2.56965084e+01 2.55641346e+01 2.50197392e+01 2.48697643e+01 2.41845455e+01 2.40710373e+01 2.42089634e+01 2.37549782e+01 2.36856270e+01 2.34300270e+01 2.30989799e+01 2.30308075e+01 2.30837307e+01 2.30932827e+01 2.25967312e+01 2.17115860e+01 2.13937473e+01 2.12683296e+01 2.13861332e+01 2.13683987e+01 2.11756973e+01 2.06413097e+01 2.04698048e+01 2.05171089e+01 2.05277462e+01 2.01723194e+01 2.00796108e+01 1.98753872e+01 1.99771729e+01 2.01280251e+01 1.97743454e+01 1.92352962e+01 1.90179768e+01 1.83799667e+01 1.77905197e+01 1.71418476e+01 1.70688095e+01 1.73421383e+01 1.75713768e+01 1.73641281e+01 1.70710468e+01 1.67808514e+01 1.65220814e+01 1.63034229e+01 1.60716133e+01 1.55481396e+01 1.53937597e+01 1.52158184e+01 1.52144537e+01 1.51237211e+01 1.50111675e+01 1.46359472e+01 1.41901665e+01 1.39212837e+01 1.38144407e+01 1.28447905e+01 1.26006870e+01 1.33287516e+01 1.35892220e+01 1.30741472e+01 1.23906898e+01 1.20307169e+01 1.17287560e+01 1.17153435e+01 1.15661268e+01 1.13669825e+01 1.09830074e+01 1.07701139e+01 1.04031935e+01 1.02159233e+01 9.99610710e+00 9.76494694e+00 9.43974209e+00 9.38268757e+00 9.36162853e+00 8.92831230e+00 8.61274433e+00 8.29969406e+00 8.10690498e+00 7.90791178e+00 7.75021172e+00 7.51423597e+00 7.26848984e+00 6.92862892e+00 6.77630806e+00 6.56291676e+00 6.21878195e+00 6.01425934e+00 5.74937963e+00 5.41867495e+00 5.35879087e+00 5.16786814e+00 4.82759762e+00 4.58844233e+00 4.38844013e+00 4.13161898e+00 3.87321568e+00 3.64207792e+00 3.39699626e+00 3.17170978e+00 2.93336582e+00 2.66707444e+00 2.45413280e+00 2.22688293e+00 1.96199882e+00 1.73118293e+00 1.48608506e+00 1.23777270e+00 1.00348437e+00 7.61951029e-01 5.27806342e-01 2.94049531e-01 4.35833223e-02 -1.97060972e-01 -4.38497245e-01 -6.77681684e-01 -9.18082595e-01 -1.15805268e+00 -1.39905131e+00 -1.63812053e+00 -1.87205255e+00 -2.11816025e+00 -2.35798621e+00 -2.60206199e+00 -2.85237455e+00 -3.06825638e+00 -3.32784247e+00 -3.56854916e+00 -3.75107980e+00 -4.00684309e+00 -4.26435089e+00 -4.53870869e+00 -4.81146812e+00 -4.93051052e+00 -4.92239475e+00 -5.58073902e+00 -6.03902674e+00 -5.53335714e+00 -5.96653128e+00 -7.20627594e+00 -7.54173708e+00 -7.04964209e+00 2.34745331e+01 4.55182152e+01 -2.54108219e+01 -2.57084694e+01 -2.61881447e+01 -2.65758438e+01 -2.69222126e+01 -2.74760742e+01 -2.81068230e+01 -2.88004990e+01 -2.90509701e+01 -2.90897331e+01 -2.94857273e+01 -3.02431030e+01 -3.10386696e+01 -3.09569397e+01 -3.15709534e+01 -3.22697678e+01 -1.18824463e+02 -2.05608826e+01 8.20822144e+01 -3.32019386e+01 -1.29319565e+02 -8.41520309e+01 -1.49446754e+01 -1.33710232e+01 -1.32018652e+01 -1.34088840e+01 -1.35215178e+01 -1.37996559e+01 -1.42118073e+01 -1.43389206e+01 -1.46879110e+01 -1.49336967e+01 -1.52011080e+01 -1.52748814e+01 -1.53072414e+01 -1.56513500e+01 -1.61841793e+01 -1.61424294e+01 -1.62782860e+01 -1.65798779e+01 -1.68759289e+01 -1.71334476e+01 -1.73099880e+01 -1.73864594e+01 -1.75655632e+01 -1.76442833e+01 -1.80255299e+01 -1.82887554e+01 -1.86957664e+01 -1.89840298e+01 -1.90825310e+01 -1.94585228e+01 -1.96697922e+01 -1.96387596e+01 -1.97461853e+01 -2.00114250e+01 -2.01803322e+01 -2.04428177e+01 -2.04707870e+01 -2.09987125e+01 -2.12723446e+01 -2.16157818e+01 -2.20465927e+01 -2.23330402e+01 -2.20206337e+01 -2.21902008e+01 -2.20418949e+01 -2.28926849e+01 -2.28528500e+01 -2.24390030e+01 -2.26361313e+01 -2.28004608e+01 -2.37920132e+01 -2.38008537e+01 -2.33720627e+01 -2.37529163e+01 -2.38978062e+01 -2.47848110e+01 -2.50936909e+01 -2.51450672e+01 -2.52884560e+01 -2.53860989e+01 -2.55888844e+01 -2.58636723e+01 -2.56632710e+01 -2.57656536e+01 -2.60788269e+01 -2.61201458e+01 -2.66697941e+01 -2.67629070e+01 -2.72694950e+01 -2.72803822e+01 -2.69098492e+01 -2.70956154e+01 -2.79297256e+01 -2.80811920e+01 -2.79076366e+01 -2.81054306e+01 -2.87308369e+01 -2.88431358e+01 -2.85978584e+01 -2.89362907e+01 -2.84944859e+01 -2.87222633e+01 -2.88395195e+01 -2.93305683e+01 -3.00131416e+01 -3.04821491e+01 -3.06137352e+01 -3.03268299e+01 -3.01348763e+01 -2.95256329e+01 -3.02143726e+01 -3.16970119e+01 -3.17872200e+01 -3.12586079e+01 -3.10739250e+01 -3.13700695e+01 -3.17052631e+01 -3.15487232e+01 -3.19552708e+01 -3.19111538e+01 -3.17303619e+01 -3.20879135e+01 -3.27731667e+01 -3.26863174e+01 -3.23977776e+01 -3.20418663e+01 -3.23780632e+01 -3.24959869e+01 -3.27438507e+01 -3.29341507e+01 -3.27995453e+01 -3.14869671e+01 -3.22346153e+01 -3.41916046e+01 -3.37334900e+01 -3.31372757e+01 -3.32583847e+01 -3.33105431e+01 -3.42751160e+01 -3.44997063e+01 -3.47703209e+01 -3.40871849e+01 -3.45261230e+01 -3.44346619e+01 -3.42296753e+01 -3.39804268e+01 -3.41280441e+01 -3.48870049e+01 -3.60611343e+01 -3.60917320e+01 -3.60519485e+01 -3.59065590e+01 -3.61131020e+01 -3.59541588e+01 -3.61705513e+01 -3.56502800e+01 -3.59791298e+01 -3.62479401e+01 -3.66719170e+01 -3.69417267e+01 -3.73264771e+01 -3.74439125e+01 -3.70977364e+01 -3.65504799e+01 -3.68268929e+01 -3.68515053e+01 -3.70810547e+01 -3.71565514e+01 -3.70418892e+01 -3.73968086e+01 -3.74822121e+01 -3.72351723e+01 -3.73326302e+01 -3.75084267e+01 -3.75694466e+01 -3.77588844e+01 -3.77228165e+01 -3.77186966e+01 -3.77411156e+01 -3.78819618e+01 -3.82999802e+01 -3.77093925e+01 -3.73949928e+01 -3.77065468e+01 -3.82928543e+01 -3.80262375e+01 -3.79877548e+01 -3.82917709e+01 -3.86714897e+01 -3.83529968e+01 -3.87568703e+01 -3.85731316e+01 -3.84591179e+01 -3.84892502e+01 -3.88744316e+01 -3.90112381e+01 -3.87481956e+01 -3.86444244e+01 -3.85530548e+01 -3.87685242e+01 -3.92611351e+01 -3.89960594e+01 -3.89864082e+01 -3.92682648e+01 -3.90827789e+01 -3.88039932e+01 -3.90899239e+01 -3.84775124e+01 -3.86161194e+01 -3.91606140e+01 -3.90925140e+01 -3.94032440e+01 -3.93744431e+01 -3.86282234e+01 -3.88092422e+01 -3.94077148e+01 -3.93306046e+01 -3.92079849e+01 -3.79521523e+01 -3.78830414e+01 -3.91948471e+01 -4.04769287e+01 -4.05396500e+01 -3.89583893e+01 -3.93834076e+01 -3.99238892e+01 -3.94768448e+01 -3.93022461e+01 -3.91324730e+01 -3.89631767e+01 -3.88945503e+01 -3.90937881e+01 -3.91952591e+01 -3.93530884e+01 -3.94604301e+01 -3.91329689e+01 -3.95266647e+01 -3.93092613e+01 -3.86819649e+01 -3.94368629e+01 -3.94897423e+01 -3.90718765e+01 -3.91170425e+01 -3.96807823e+01 -3.90999641e+01 -3.84989929e+01 -3.87134972e+01 -3.87776031e+01 -3.91020851e+01 -3.88357391e+01 -3.89703979e+01 -3.90084381e+01 -3.89913750e+01 -3.85286255e+01 -3.84941788e+01 -3.86153183e+01 -3.86705894e+01 -3.83416939e+01 -3.77384033e+01 -3.85740929e+01 -3.88095741e+01 -3.78896446e+01 -3.74423103e+01 -3.73704643e+01 -3.75833130e+01 -3.78086510e+01 -3.82731667e+01 -3.80255737e+01 -3.78036346e+01 -3.76903534e+01 -3.77973022e+01 -3.76833572e+01 -3.75216103e+01 -3.71110611e+01 -3.74651031e+01 -3.75810051e+01 -3.75373039e+01 -3.68469429e+01 -3.67566795e+01 -3.64048843e+01 -3.69300995e+01 -3.68805428e+01 -3.70382996e+01 -3.65389977e+01 -3.68051872e+01 -3.66981697e+01 -3.72098923e+01 -3.64288673e+01 -3.57361450e+01 -3.61906090e+01 -3.65743065e+01 -3.60561104e+01 -3.59175415e+01 -3.60554810e+01 -3.57856636e+01 -3.64586143e+01 -3.63418999e+01 -3.49323120e+01 -3.46294479e+01 -3.53235931e+01 -3.52722321e+01 -3.39753532e+01 -3.43147430e+01 -3.48460884e+01 -3.48446922e+01 -3.60083008e+01 -3.53320656e+01 -3.44860191e+01 -3.43623199e+01 -3.42931747e+01 -3.39789658e+01 -3.33411026e+01 -3.34798164e+01 -3.43058662e+01 -3.38428917e+01 -3.37122307e+01 -3.39325294e+01 -3.34464264e+01 -3.31835594e+01 -3.32584610e+01 -3.31058159e+01 -3.35307884e+01 -3.23463249e+01 -3.20949516e+01 -3.21469536e+01 -3.13759880e+01 -3.11543579e+01 -3.08126965e+01 -3.06081772e+01 -3.10208855e+01 -3.13936501e+01 -3.13621426e+01 -3.14628487e+01 -3.14480038e+01 -3.04817142e+01 -3.00358658e+01 -3.01410160e+01 -3.03809147e+01 -2.99869614e+01 -2.98212700e+01 -2.95883427e+01 -2.92118340e+01 -2.95116444e+01 -2.94983120e+01 -2.97351112e+01 -2.90064716e+01 -2.82059212e+01 -2.82017117e+01 -2.86727390e+01 -2.83198051e+01 -2.81965809e+01 -2.74155998e+01 -2.75689774e+01 -2.83309669e+01 -2.85555687e+01 -2.81433887e+01 -2.67615719e+01 -2.66070957e+01 -2.62191315e+01 -2.62791729e+01 -2.63384800e+01 -2.64149628e+01 -2.62448044e+01 -2.57083149e+01 -2.55040798e+01 -2.51702099e+01 -2.55416584e+01 -2.49314957e+01 -2.45188179e+01 -2.44771996e+01 -2.44981651e+01 -2.43585320e+01 -2.41893578e+01 -2.35276260e+01 -2.35429134e+01 -2.33519268e+01 -2.31795444e+01 -2.28731956e+01 -2.30714092e+01 -2.30611458e+01 -2.25735741e+01 -2.21146450e+01 -2.22464218e+01 -2.20188065e+01 -2.16481380e+01 -2.13864155e+01 -2.11932392e+01 -2.07216797e+01 -2.03369656e+01 -2.05056171e+01 -2.02737656e+01 -1.98423023e+01 -1.98681393e+01 -1.98818130e+01 -1.99215946e+01 -1.94734421e+01 -1.92150593e+01 -1.88549461e+01 -1.87037334e+01 -1.82941780e+01 -1.78815022e+01 -1.76156635e+01 -1.74232693e+01 -1.74951210e+01 -1.76865616e+01 -1.74819832e+01 -1.73970070e+01 -1.67514725e+01 -1.65987129e+01 -1.61112671e+01 -1.59639091e+01 -1.54864750e+01 -1.54541807e+01 -1.53075886e+01 -1.51132727e+01 -1.50682344e+01 -1.53345032e+01 -1.50409603e+01 -1.41156464e+01 -1.36967468e+01 -1.39028482e+01 -1.38938627e+01 -1.34918375e+01 -1.31991940e+01 -1.30003376e+01 -1.24603271e+01 -1.23458366e+01 -1.21737051e+01 -1.17881775e+01 -1.15424299e+01 -1.12197027e+01 -1.10514755e+01 -1.08751297e+01 -1.06090412e+01 -1.03337317e+01 -9.82745266e+00 -8.52771473e+00 -8.07269001e+00 -9.02513790e+00 -8.66951561e+00 -8.92601109e+00 -9.29383087e+00 -8.87337685e+00 -8.38275337e+00 -7.41315031e+00 7.54058533e+01 8.74817352e+01 -2.00406174e+02 -3.66412854e+00 -6.82812166e+00 1.75162003e+02 5.99949217e+00 -1.66930054e+02 2.85425758e+00 2.41377783e+00 1.18675172e+00 -6.76288300e+01 -5.20091295e+00 -6.11584759e+00 -3.99717369e+01 -6.19182110e+00 -4.85941362e+00 -4.00603342e+00 -3.59133577e+00 -3.42755032e+00 -2.98970008e+00 -2.80636573e+00 -2.86253715e+00 -2.57572079e+00 -2.18721938e+00 -1.84068060e+00 -1.77002311e+00 -1.63399875e+00 -1.29643154e+00 -1.02937603e+00 -8.04372609e-01 -5.45983076e-01 -2.86694765e-01 -6.19295537e-02 1.85525939e-01 4.20724481e-01 6.60082459e-01 9.06004369e-01 1.14502263e+00 1.38715029e+00 1.62644589e+00 1.86846495e+00 2.11300445e+00 2.36052966e+00 2.59347844e+00 2.83583546e+00 3.07927370e+00 3.31751275e+00 3.55552292e+00 3.80365109e+00 4.06864262e+00 4.26915359e+00 4.49689960e+00 4.74933338e+00 5.00489855e+00 5.22286224e+00 5.44829607e+00 5.72814417e+00 5.95237875e+00 6.23654079e+00 6.53519058e+00 6.69296026e+00 6.90261555e+00 7.14782047e+00 7.33624458e+00 7.58645725e+00 7.80414915e+00 8.02537155e+00 8.40190601e+00 8.72166443e+00 8.89385128e+00 8.96217728e+00 9.17172241e+00 9.55439949e+00 9.67328453e+00 9.78473091e+00 1.00141764e+01 1.03077650e+01 1.06171446e+01 1.09550438e+01 1.10928135e+01 1.13940020e+01 1.15832348e+01 1.17818747e+01 1.20668459e+01 1.23031855e+01 1.25676146e+01 1.29062681e+01 1.29151793e+01 1.30811415e+01 1.34343433e+01 1.38818026e+01 1.40174570e+01 1.42127190e+01 1.43684492e+01 1.46610403e+01 1.46145754e+01 1.45495396e+01 1.53011217e+01 1.60217857e+01 1.58598728e+01 1.62227764e+01 1.62603951e+01 1.62114239e+01 1.62412186e+01 1.61053524e+01 1.65269299e+01 1.73662472e+01 1.80337677e+01 1.81809311e+01 1.75314903e+01 1.78301468e+01 1.81237736e+01 1.85316944e+01 1.89735641e+01 1.91135635e+01 1.93309307e+01 1.94934120e+01 1.95448780e+01 1.96877346e+01 2.00664139e+01 2.02866497e+01 2.04689484e+01 2.06137466e+01 2.08631611e+01 2.11635189e+01 2.16068268e+01 2.19555950e+01 2.21804886e+01 2.19596310e+01 2.24153805e+01 2.23783531e+01 2.27319813e+01 2.26122761e+01 2.25037823e+01 2.28048992e+01 2.28436069e+01 2.34606800e+01 2.34468517e+01 2.24113503e+01 2.18947678e+01 2.31141644e+01 2.48995190e+01 2.66334038e+01 2.67189445e+01 2.53284054e+01 2.56728935e+01 2.57606125e+01 2.59479065e+01 2.57332039e+01 2.57733669e+01 2.58967609e+01 2.59700432e+01 2.65242443e+01 2.65966530e+01 2.70979309e+01 2.71542301e+01 2.68725758e+01 2.69607697e+01 2.77700729e+01 2.78709221e+01 2.80925426e+01 2.82146530e+01 2.79770222e+01 2.80050488e+01 2.87619553e+01 2.88006802e+01 2.93289356e+01 2.94407024e+01 2.82592754e+01 2.90850677e+01 2.98719749e+01 3.05516586e+01 3.05412788e+01 3.00747471e+01 2.90081329e+01 2.89103127e+01 3.06285000e+01 3.17911358e+01 3.18843746e+01 3.12760525e+01 3.10202618e+01 3.09481277e+01 3.13079643e+01 3.09091072e+01 3.04780331e+01 3.13236904e+01 3.15127945e+01 2.22809639e+01 -1.42686844e+02 -2.52854218e+02 6.61209717e+01 6.43522415e+01 6.12276230e+01 6.00228119e+01 3.62829193e+02 6.75717163e+02 3.51105286e+02 7.32601685e+02 2.07045288e+03 103750064. 1196035840. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1122135808. 2.40978271e+03 2.42428802e+02 3.15759144e+01 2.53385132e+02 3.73270683e+01 4.01706276e+01 3.72722244e+01 3.70741005e+01 3.73228722e+01 3.82257805e+01 3.85174446e+01 3.82617836e+01 3.78244934e+01 3.71586761e+01 3.66985588e+01 3.62376060e+01 3.61769867e+01 3.49126205e+01 3.60031624e+01 3.79943810e+01 3.84308891e+01 3.84590340e+01 3.78792763e+01 3.71810074e+01 3.68240967e+01 3.62409706e+01 3.67643929e+01 3.75512581e+01 3.86789589e+01 3.86504593e+01 3.80601387e+01 3.78314590e+01 3.69928703e+01 3.74165497e+01 3.76304588e+01 3.84554405e+01 3.80259628e+01 3.83814354e+01 3.82125511e+01 3.83587341e+01 3.79802856e+01 3.84782791e+01 3.83836060e+01 3.86759033e+01 3.92896996e+01 3.93777351e+01 3.91601105e+01 3.87858467e+01 3.91072235e+01 3.89109879e+01 3.87869263e+01 3.89121361e+01 3.88741455e+01 3.88669243e+01 3.86938515e+01 3.87844048e+01 3.86576881e+01 3.93049850e+01 3.89146614e+01 3.81100578e+01 3.76991348e+01 3.57130394e+01 3.22491417e+01 4.00142860e+01 1.73280457e+02 7.46662450e+06 0. 0. 0. 0. 0. 4.05737293e+09 4.05737293e+09 4.05737293e+09 0. 0. 0. 0. 0. 0. -2.51298161e+10 -2083047040. 1.30391230e+04 1.37533438e+04 2.09184462e+06 1.81105803e+11 0. 0. 6.21589555e+09 -1001272064. 7.34425312e+05 2.36597852e+03 9.41724609e+02 3.81120796e+01 5.04733467e+01 4.38749268e+02 5.73424301e+01 4.17991371e+01 4.39928703e+01 -3.41894379e+02 4.50626335e+01 4.23186264e+01 4.12639084e+01 4.17301102e+01 4.50303345e+01 4.98007164e+01 4.91467743e+01 4.85504608e+01 4.43278618e+01 4.20355301e+01 3.83354950e+01 4.03813896e+01 5.48916092e+01 5.69281845e+01 4.17936798e+02 4.65810204e+01 -3.31489441e+02 4.15620079e+01 4.60154228e+01 4.51242485e+01 4.22849236e+01 4.03317947e+01 4.96755457e+00 2.62730289e+00 3.96105118e+01 4.44151993e+01 7.08725128e+01 8.33131180e+01 5.79432411e+01 4.85536880e+01 4.86925774e+01 4.46148872e+01 4.27682495e+01 4.06698273e+02 2.55095047e+02 3.32347946e+01 3.35913315e+01 3.39758301e+01 3.37292786e+01 3.28810005e+01 3.17095032e+01 3.25157242e+01 3.26846390e+01 3.17776146e+01 3.07111301e+01 3.03123093e+01 3.09801235e+01 3.10713558e+01 -1.67243698e+02 -3.15037811e+02 2.69920464e+01 -7.81005554e+02 -2.01615906e+03 3.24872883e+09 9.59438541e+09 0. 2.73123584e+09 2.73123584e+09 2.73123584e+09 0. 0. -2.30841114e+09 -2.30841114e+09 -2.30841114e+09 0. 0. 0. 0. 0. -415871712. -3.38808105e+03 -6.68542542e+02 -2.80939148e+02 -1.47501877e+02 3.03273182e+01 3.10213547e+01 2.98968296e+01 2.97384930e+01 -1.47034119e+02 -2.77265076e+02 3.63076782e+01 3.54913101e+01 3.89415932e+01 4.17780113e+01 4.45596581e+01 3.42300262e+02 2.15701553e+02 2.94485722e+01 2.09491882e+01 2.80994568e+01 3.57237968e+01 2.98945866e+01 2.86445446e+01 2.76526566e+01 2.79141312e+01 2.76558552e+01 2.71578884e+01 2.66748753e+01 2.66844864e+01 2.68228245e+01 2.64980927e+01 2.62446995e+01 2.59102612e+01 2.57678814e+01 2.53168144e+01 2.55898762e+01 2.54231262e+01 2.50493145e+01 2.48847446e+01 2.48130665e+01 2.52545700e+01 2.55531731e+01 2.57327652e+01 2.55681515e+01 2.53140507e+01 2.47593670e+01 2.41945419e+01 2.37573586e+01 2.37036934e+01 2.38175182e+01 2.41464653e+01 2.37044506e+01 2.31202831e+01 2.34097805e+01 2.34571724e+01 2.31322689e+01 2.30496521e+01 2.32859459e+01 2.36977692e+01 2.31594296e+01 2.30840912e+01 2.22626781e+01 2.18177834e+01 2.11057968e+01 2.15554142e+01 2.16200104e+01 2.12194080e+01 2.11137009e+01 2.10023613e+01 2.13735886e+01 2.15460510e+01 2.14597473e+01 2.10895443e+01 2.06759453e+01 2.05731430e+01 2.06026230e+01 2.08615704e+01 2.04787846e+01 2.00622482e+01 1.96107407e+01 1.91461487e+01 1.88689499e+01 1.85155296e+01 1.84586411e+01 1.85117207e+01 1.85341454e+01 1.83518791e+01 1.80726299e+01 1.79930973e+01 1.78039646e+01 1.76486454e+01 1.75734749e+01 1.71952038e+01 1.70673409e+01 1.67962074e+01 1.65581684e+01 1.63806438e+01 1.62120705e+01 1.60983601e+01 1.57458839e+01 1.56158991e+01 1.54227304e+01 1.41498985e+01 1.39284344e+01 1.56776094e+01 1.59746284e+01 1.52181625e+01 1.46745453e+01 1.43177538e+01 1.39527111e+01 1.39911318e+01 1.37849512e+01 1.35901756e+01 1.34256392e+01 1.32377882e+01 1.29357386e+01 1.27006264e+01 1.25799217e+01 1.24987059e+01 1.22176342e+01 1.20959978e+01 1.19896107e+01 1.18421679e+01 1.16393337e+01 1.14244518e+01 1.12469921e+01 1.10684605e+01 1.07979975e+01 1.05438433e+01 1.03894472e+01 1.01790714e+01 9.97397327e+00 9.88775730e+00 9.62755203e+00 9.45339012e+00 9.11220837e+00 8.76271152e+00 8.83827496e+00 8.80680370e+00 8.40970421e+00 8.17451191e+00 8.01986790e+00 7.85258007e+00 7.63723183e+00 7.49118710e+00 7.27343607e+00 7.04236031e+00 6.83266735e+00 6.60837078e+00 6.44875765e+00 6.26677608e+00 6.05634260e+00 5.84929991e+00 5.64415979e+00 5.44448709e+00 5.23764896e+00 5.03831339e+00 4.84126472e+00 4.64557981e+00 4.43352699e+00 4.23283339e+00 4.03335333e+00 3.83470011e+00 3.63477635e+00 3.43191218e+00 3.22881675e+00 3.03061581e+00 2.83131385e+00 2.62724233e+00 2.42412066e+00 2.21321821e+00 2.00629044e+00 1.83792126e+00 1.61609828e+00 1.40176725e+00 1.26339459e+00 1.28343570e+00 1.52916217e+00 5.16049862e-01 -2.33678222e-02 6.60752505e-02 -1.31107330e-01 -3.24355423e-01 2.45974369e+01 4.85567474e+01 -5.22903481e+01 -3.30160637e+01 -1.27741921e+00 -2.58312345e+00 -3.35474181e+00 -3.69278145e+00 -5.00767946e+00 -5.34026337e+00 -5.52982235e+00 -5.58485174e+00 -5.81761742e+00 -6.33464813e+00 -6.64769459e+00 -6.91196108e+00 -7.29405499e+00 -7.60336018e+00 -7.89583254e+00 -8.24204540e+00 -8.50664711e+00 -8.88333225e+00 -9.19539165e+00 -9.46660519e+00 -8.23987484e+00 -9.77006626e+00 -7.01521683e+00 -1.08373690e+01 -6.57885647e+00 -8.70694160e+00 -8.46302986e+00 -6.88924122e+00 -6.85821009e+00 -7.16130447e+00 -7.08131170e+00 -7.47211933e+00 -7.80928516e+00 -8.02585602e+00 -8.03858757e+00 -8.22815895e+00 -8.64218044e+00 -8.90392780e+00 -8.78790092e+00 -9.08442307e+00 -9.67704964e+00 -9.60630131e+00 -9.65093231e+00 -9.95938492e+00 -1.00513821e+01 -1.01258583e+01 -1.05319262e+01 -1.04017258e+01 -1.10390177e+01 -1.10516644e+01 -1.13932467e+01 -1.15404406e+01 -1.17585535e+01 -1.18982010e+01 -1.21003294e+01 -1.24600592e+01 -1.26980886e+01 -1.26872263e+01 -1.27608204e+01 -1.23187141e+01 -1.26057482e+01 -1.29389877e+01 -1.32290678e+01 -1.36540680e+01 -1.39119864e+01 -1.40322199e+01 -1.41257772e+01 -1.44931393e+01 -1.49825668e+01 -1.53218956e+01 -1.50094624e+01 -1.53952827e+01 -1.55716820e+01 -1.53691750e+01 -1.56438627e+01 -1.56783600e+01 -1.64802418e+01 -1.61665173e+01 -1.58030701e+01 -1.63499069e+01 -1.63382587e+01 -1.66513119e+01 -1.68386860e+01 -1.67748013e+01 -1.68326130e+01 -1.69062481e+01 -1.76303005e+01 -1.81043072e+01 -1.79805202e+01 -1.86051655e+01 -1.87908840e+01 -1.90868340e+01 -1.88985634e+01 -1.96026859e+01 -1.96517525e+01 -1.98496685e+01 -1.94501228e+01 -1.92474747e+01 -1.98500538e+01 -1.99124489e+01 -1.98697453e+01 -2.01747112e+01 -2.07527561e+01 -2.03152752e+01 -2.05542660e+01 -2.09165592e+01 -2.07246780e+01 -2.07771683e+01 -2.07685242e+01 -2.14159279e+01 -2.20076008e+01 -2.22681007e+01 -2.24675827e+01 -2.25950890e+01 -2.23604469e+01 -2.14391117e+01 -2.11768017e+01 -2.28078098e+01 -2.41304169e+01 -2.37057457e+01 -2.34405499e+01 -2.31409512e+01 -2.31910267e+01 -2.34581299e+01 -2.34677258e+01 -2.36319275e+01 -2.42097797e+01 -2.51580067e+01 -2.52405663e+01 -2.54314327e+01 -2.44773846e+01 -2.47299995e+01 -2.43544540e+01 -2.52541237e+01 -2.54658375e+01 -2.52632980e+01 -2.47591572e+01 -2.32603016e+01 -2.45231285e+01 -2.74243088e+01 -2.66160870e+01 -2.53220329e+01 -2.52123756e+01 -2.55423622e+01 -2.67604027e+01 -2.74572754e+01 -2.70522633e+01 -2.64400501e+01 -2.67725964e+01 -2.68446579e+01 -2.69626293e+01 -2.68338814e+01 -2.69821014e+01 -2.73599300e+01 -2.77698879e+01 -2.77566090e+01 -2.75865669e+01 -2.77135334e+01 -2.81125259e+01 -2.82474499e+01 -2.86519375e+01 -2.86122589e+01 -2.87676468e+01 -2.88751869e+01 -2.85216751e+01 -2.84273262e+01 -2.83710270e+01 -2.88876095e+01 -2.86233768e+01 -2.87953682e+01 -2.89014683e+01 -2.90845051e+01 -2.88216534e+01 -2.90408001e+01 -2.92366028e+01 -3.00300446e+01 -3.02211914e+01 -3.01329708e+01 -3.00407410e+01 -3.01775951e+01 -3.05342026e+01 -3.06857624e+01 -3.03809700e+01 -3.01635685e+01 -2.97980843e+01 -3.02552872e+01 -3.09158535e+01 -3.11799507e+01 -3.05809746e+01 -3.07003269e+01 -3.12778492e+01 -3.19233398e+01 -3.16109848e+01 -3.21665649e+01 -3.23953362e+01 -3.19223614e+01 -3.14449348e+01 -3.11044350e+01 -3.11795349e+01 -3.15669022e+01 -3.19078598e+01 -3.25110779e+01 -3.22319679e+01 -3.20840378e+01 -3.13481865e+01 -3.15137939e+01 -3.22364807e+01 -3.22785072e+01 -3.19829025e+01 -3.19465256e+01 -3.16858482e+01 -3.17600975e+01 -3.28086243e+01 -3.29114227e+01 -3.23803291e+01 -3.25201187e+01 -3.23092499e+01 -3.26467133e+01 -3.26374893e+01 -3.15058899e+01 -3.17167263e+01 -3.28209953e+01 -3.27310333e+01 -3.26837158e+01 -3.13136673e+01 -3.13820190e+01 -3.27608070e+01 -3.40755119e+01 -3.41758537e+01 -3.24829445e+01 -3.28267097e+01 -3.35405617e+01 -3.31027718e+01 -3.29570427e+01 -3.27943382e+01 -3.26215897e+01 -3.27612648e+01 -3.30095406e+01 -3.30679054e+01 -3.32199821e+01 -3.32249794e+01 -3.27362518e+01 -3.35291481e+01 -3.35376930e+01 -3.28135071e+01 -3.39249420e+01 -3.40070038e+01 -3.37805748e+01 -3.39209557e+01 -3.35233459e+01 -3.34263191e+01 -3.27033119e+01 -3.22423935e+01 -3.35005417e+01 -3.35527687e+01 -3.27063713e+01 -3.27904358e+01 -3.34752617e+01 -3.36232643e+01 -3.34199638e+01 -3.36445465e+01 -3.32584457e+01 -3.35197411e+01 -3.28816872e+01 -3.26280212e+01 -3.28334541e+01 -3.27421494e+01 -3.29930496e+01 -3.26955795e+01 -3.28294411e+01 -3.27702217e+01 -3.28979683e+01 -3.27706451e+01 -3.29441948e+01 -3.30086136e+01 -3.30019302e+01 -3.26114693e+01 -3.25903320e+01 -3.32616692e+01 -3.34971848e+01 -3.28766479e+01 -3.23602829e+01 -3.16422939e+01 -3.19538651e+01 -3.21907501e+01 -3.23059387e+01 -3.22583885e+01 -3.26112022e+01 -3.27756958e+01 -3.28529358e+01 -3.25357742e+01 -3.24983292e+01 -3.27657127e+01 -3.23108673e+01 -3.16227779e+01 -3.16928387e+01 -3.24084702e+01 -3.23527298e+01 -3.24246254e+01 -3.22155151e+01 -3.19187336e+01 -3.16854038e+01 -3.20718498e+01 -3.17028618e+01 -3.15189400e+01 -3.13744316e+01 -3.18270302e+01 -3.04223938e+01 -3.07881107e+01 -3.11654606e+01 -3.16321888e+01 -3.24817352e+01 -3.18071194e+01 -3.07886734e+01 -3.05699100e+01 -2.99062386e+01 -2.99799709e+01 -2.93264999e+01 -2.98947353e+01 -3.07805080e+01 -2.98957100e+01 -2.99868813e+01 -3.01771564e+01 -2.96015396e+01 -3.01540279e+01 -3.06966763e+01 -3.05851250e+01 -3.03935680e+01 -2.95663891e+01 -3.03129539e+01 -3.06437607e+01 -2.95863113e+01 -2.88284359e+01 -2.79656849e+01 -2.80454903e+01 -2.90180092e+01 -2.89190578e+01 -2.78543797e+01 -2.78527775e+01 -2.79862995e+01 -2.75145035e+01 -2.71284752e+01 -2.80905724e+01 -2.79619675e+01 -2.77183285e+01 -2.82757454e+01 -2.78617516e+01 -2.77652569e+01 -2.71804867e+01 -2.77976570e+01 -2.78385983e+01 -2.73000832e+01 -2.67180939e+01 -2.66085110e+01 -2.66983566e+01 -2.63675632e+01 -2.64568138e+01 -2.54582787e+01 -2.58912392e+01 -2.63169708e+01 -2.67434273e+01 -2.64889202e+01 -2.55103798e+01 -2.55851173e+01 -2.51048546e+01 -2.54629841e+01 -2.54323158e+01 -2.53520737e+01 -2.52508926e+01 -2.53805485e+01 -2.48059750e+01 -2.38781357e+01 -2.39101582e+01 -2.36892128e+01 -2.38730412e+01 -2.41012421e+01 -2.39329529e+01 -2.33557014e+01 -2.29794254e+01 -2.29397163e+01 -2.28016891e+01 -2.27551689e+01 -2.30374508e+01 -2.32215500e+01 -2.26554203e+01 -2.32642555e+01 -2.24293633e+01 -2.25497875e+01 -2.22743034e+01 -2.21459465e+01 -2.17398548e+01 -2.12014866e+01 -2.09939346e+01 -2.06178093e+01 -2.09066849e+01 -2.11883087e+01 -2.10645275e+01 -2.06408730e+01 -2.04795780e+01 -2.04918747e+01 -2.01744480e+01 -2.01570263e+01 -1.98903980e+01 -1.96734715e+01 -1.95891190e+01 -1.92918701e+01 -1.92222328e+01 -1.89811363e+01 -1.88773403e+01 -1.86303024e+01 -1.85055351e+01 -1.84397106e+01 -1.81594505e+01 -1.76729412e+01 -1.76392117e+01 -1.76590214e+01 -1.74719429e+01 -1.73899879e+01 -1.72649002e+01 -1.68949776e+01 -1.62981739e+01 -1.62305412e+01 -1.65439148e+01 -1.61820545e+01 -1.54608240e+01 -1.54800844e+01 -1.58014088e+01 -1.58671093e+01 -1.53893147e+01 -1.50896006e+01 -1.49658384e+01 -1.46182146e+01 -1.46460924e+01 -1.45854454e+01 -1.39873819e+01 -1.38223648e+01 -1.35476685e+01 -1.35077314e+01 -1.32761822e+01 -1.29846849e+01 -1.27756815e+01 -1.23584404e+01 -1.11333799e+01 -1.07443447e+01 -1.17125549e+01 -1.14351206e+01 -1.16398907e+01 -1.20970306e+01 -1.17980423e+01 -1.14268055e+01 -1.04403839e+01 -1.08266960e+02 -2.19275951e+01 7.39483566e+01 -1.41550245e+01 -1.48436422e+01 -1.13233643e+02 -1.46407766e+01 6.34619408e+01 -1.17994442e+01 -1.16903210e+01 -1.17796679e+01 -5.94846296e+00 -1.11604118e+01 -9.93399811e+00 -8.83549023e+00 -9.23545933e+00 -6.78250504e+00 -8.28940487e+00 -9.11230659e+00 -7.20053339e+00 -6.90530682e+00 -6.66999531e+00 -6.91419888e+00 -5.84062910e+00 -4.35382175e+00 -6.73829174e+00 -7.71199036e+00 -6.11256075e+00 -5.66346550e+00 -5.29545593e+00 -5.09360409e+00 -4.86671782e+00 -4.65065384e+00 -4.46281004e+00 -4.25247717e+00 -4.06303310e+00 -3.86473823e+00 -3.65619397e+00 -3.44918323e+00 -3.24615121e+00 -3.05119300e+00 -2.85181856e+00 -2.63999271e+00 -2.43374062e+00 -2.24226904e+00 -2.04310584e+00 -1.82520902e+00 -1.60706389e+00 -1.41291738e+00 -1.20411456e+00 -9.90564644e-01 -8.14534843e-01 -6.22357190e-01 -3.98814112e-01 -1.82713673e-01 1.60181113e-02 2.07503885e-01 4.49015796e-01 6.32978976e-01 9.00774717e-01 1.12202370e+00 1.21366119e+00 1.43156171e+00 1.65202141e+00 1.89242232e+00 2.12198663e+00 2.26785970e+00 2.42583704e+00 2.66814709e+00 2.93035531e+00 3.06201053e+00 3.06570125e+00 3.34885859e+00 3.73705935e+00 3.84498405e+00 3.85064411e+00 4.16044378e+00 4.38039589e+00 4.66265631e+00 4.97446775e+00 5.09850359e+00 5.13452911e+00 5.38464308e+00 6.02670670e+00 6.43134737e+00 6.11713696e+00 6.16505957e+00 6.39004660e+00 6.55107450e+00 6.66893435e+00 7.23114061e+00 7.46753454e+00 7.58760262e+00 7.90426779e+00 8.33283806e+00 8.15555286e+00 7.97398567e+00 7.51156139e+00 8.78932762e+00 9.73019886e+00 9.37341309e+00 9.71830273e+00 9.62179375e+00 9.73857307e+00 9.83468819e+00 9.46204567e+00 8.89536476e+00 9.85983086e+00 1.18848982e+01 1.23554840e+01 1.09563656e+01 1.13174934e+01 1.13232183e+01 1.15631676e+01 1.17990370e+01 1.20761967e+01 1.23133450e+01 1.26623707e+01 1.26493378e+01 1.26234312e+01 1.23871670e+01 1.25840406e+01 1.27865839e+01 1.31044254e+01 1.33959732e+01 1.38669720e+01 1.38877611e+01 1.39341984e+01 1.42895670e+01 1.48641052e+01 1.54125109e+01 1.54866838e+01 1.53349905e+01 1.50839424e+01 1.53426800e+01 1.59341888e+01 1.58500013e+01 1.59779615e+01 1.57119427e+01 1.48710852e+01 1.36671743e+01 1.46680317e+01 1.67760773e+01 1.92962761e+01 1.92892284e+01 1.68367863e+01 1.70666218e+01 1.77636242e+01 1.79496155e+01 1.78584061e+01 1.84049587e+01 1.85815830e+01 1.91096096e+01 1.88188267e+01 1.94549351e+01 1.94516106e+01 1.94934921e+01 1.90217667e+01 1.91964073e+01 1.97455044e+01 1.98113174e+01 2.00404205e+01 2.02352962e+01 1.96655312e+01 1.93478107e+01 2.04398098e+01 2.06382771e+01 2.15581875e+01 2.16834488e+01 2.03023834e+01 2.06173077e+01 2.09944115e+01 2.00121918e+01 7.99408579e+00 2.41457319e+00 -3.40276566e+01 4.59798927e+01 8.65916672e+01 -1.39061340e+02 -2.57764648e+02 3.30160484e+01 3.04201145e+01 2.81601658e+01 2.92520428e+01 2.95276432e+01 2.56933098e+01 3.14257164e+01 3.11140041e+01 3.21388794e+02 2.39171463e+02 4.16713715e+01 3.75113640e+01 3.93594666e+01 3.77384415e+01 3.79645729e+01 3.32054749e+01 3.08501053e+01 2.19454994e+01 2.02266708e+02 1.76150269e+02 6.18230835e+02 -7753498. -1344101120. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.19708656e+05 -3.52851318e+03 -1.26551542e+01 8.83224426e+02 4.42495804e+01 6.17963028e+01 4.80955200e+01 3.92096436e+02 2.51869263e+02 3.76205750e+01 3.11408405e+01 2.99026794e+01 2.92962074e+01 2.88505287e+01 2.82361889e+01 2.88699074e+01 2.92489414e+01 2.80695190e+01 2.91238365e+01 3.09087906e+01 3.04444733e+01 3.03120975e+01 3.00508289e+01 2.96773548e+01 2.95844116e+01 3.01980152e+01 3.10742588e+01 3.14208698e+01 3.18653755e+01 3.06489658e+01 2.97985497e+01 2.94864159e+01 2.93061047e+01 2.93023758e+01 3.07829895e+01 3.25963974e+01 3.26021843e+01 3.24552231e+01 3.22451324e+01 3.20609131e+01 3.13181324e+01 3.02373581e+01 3.09194107e+01 3.21257401e+01 3.31859207e+01 3.30056686e+01 3.24634590e+01 3.19138832e+01 3.14959812e+01 3.07721500e+01 3.02966232e+01 3.20351448e+01 3.30109863e+01 3.22543716e+01 3.32585106e+01 3.00210972e+01 3.05149651e+01 -1.80087555e+02 -3.36678009e+02 3.97686157e+01 3.89032478e+01 3.22734184e+01 2.12561417e+01 2.79046345e+01 1.72498138e+02 4.24083250e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.76951728e+11 -2.76951728e+11 0. 0. -2.51298161e+10 -2083047040. 1.30391230e+04 1.37533438e+04 2.09184462e+06 1.81105803e+11 0. 0. 0. 0. 0. 7.41446450e+06 -1.74803442e+03 -9.83233398e+02 -3735443. 2.52332129e+03 1.82399994e+02 1.13293457e+02 8.89580154e+01 -2.15989990e+03 2.88641150e+06 -3.46490156e+05 -17462202. -38777380. -105504. 303809248. 145489024. 198758608. 2.57082150e+06 4040611. -1228883. -7.98101875e+05 1.18920435e+03 1.17540337e+02 -2.88894592e+02 9.94732056e+01 -1.95409253e+03 3.71257781e+05 -102020400. 4958718. -68659448. -92109272. -4.23682531e+05 -5.12575438e+05 -1643392. 17803480. 7.72042562e+05 34513832. 1525430. 119721744. -624803648. 11231494. 42657072. 2.28837891e+03 9.62511719e+02 6.60046082e+01 6.79297028e+01 7.01985245e+01 4.17092621e+02 2.56914093e+02 3.33791771e+01 4.00752563e+01 4.05398216e+01 -1.62014313e+02 -3.12129974e+02 4.53120346e+01 5.46326485e+01 5.67633400e+01 -7.58597229e+02 -2.03097131e+03 -4727591. -86239808. -1446469760. 0. 0. 0. 2.73123584e+09 2.73123584e+09 2.73123584e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.32045547e+05 -5.73556641e+02 -1.45014862e+02 3.53830833e+01 3.72726669e+01 3.58133469e+01 3.46676369e+01 3.37746696e+01 3.38406868e+01 4.20794296e+01 4.34746170e+01 5.00941505e+01 4.69516754e+01 4.71070480e+01 4.90389519e+01 4.97846222e+01 3.88615150e+01 4.02166176e+01 3.45003662e+01 2.68948975e+01 3.51450195e+01 4.18977470e+01 3.59636841e+01 3.37479019e+01 3.24535103e+01 3.19187412e+01 3.15877342e+01 3.22158279e+01 3.26891899e+01 3.22108650e+01 3.16882973e+01 3.19065304e+01 3.16983128e+01 3.12500515e+01 3.08092461e+01 3.03026714e+01 3.10292339e+01 3.14105129e+01 3.07182217e+01 3.10507259e+01 3.11923389e+01 3.11349487e+01 3.08347225e+01 3.02014294e+01 2.97095013e+01 3.00865841e+01 3.00192490e+01 2.98412685e+01 2.95140705e+01 2.92852478e+01 2.88864365e+01 2.88892097e+01 2.88193951e+01 2.92792587e+01 2.95965176e+01 2.91513824e+01 2.87978153e+01 2.90620136e+01 2.89156170e+01 2.81118546e+01 2.76884308e+01 2.75456505e+01 2.78886356e+01 2.78756084e+01 2.73570938e+01 2.73114624e+01 2.70463085e+01 2.69378338e+01 2.68683624e+01 2.67307472e+01 2.67095299e+01 2.65248661e+01 2.65507088e+01 2.63778782e+01 2.59330673e+01 2.57190647e+01 2.54399605e+01 2.58033981e+01 2.60096188e+01 2.59558411e+01 2.55229836e+01 2.49933758e+01 2.50351486e+01 2.48921719e+01 2.46027489e+01 2.43173714e+01 2.37191257e+01 2.38717690e+01 2.37844105e+01 2.34245491e+01 2.31124535e+01 2.30436363e+01 2.33718700e+01 2.27136364e+01 2.25323429e+01 2.22690258e+01 2.22019806e+01 2.20639820e+01 2.18024349e+01 2.18157444e+01 2.13372822e+01 2.11077728e+01 2.07828102e+01 1.92591686e+01 1.92540588e+01 2.15796585e+01 2.17408829e+01 2.05476704e+01 1.98517876e+01 1.96141701e+01 1.95825119e+01 1.94558182e+01 1.91449814e+01 1.87860279e+01 1.88192387e+01 1.87307491e+01 1.86468163e+01 1.82498493e+01 1.80406151e+01 1.78492985e+01 1.75791073e+01 1.73608093e+01 1.71170712e+01 1.69810905e+01 1.68116131e+01 1.65164127e+01 1.63231106e+01 1.62784214e+01 1.60976467e+01 1.58974047e+01 1.56652565e+01 1.54315310e+01 1.51787014e+01 1.49588919e+01 1.48051586e+01 1.45917034e+01 1.43572512e+01 1.38963184e+01 1.39517784e+01 1.39992266e+01 1.34888573e+01 1.32753353e+01 1.31091404e+01 1.29318743e+01 1.26868734e+01 1.24714756e+01 1.22504406e+01 1.20182104e+01 1.17760458e+01 1.15006723e+01 1.13113852e+01 1.11283131e+01 1.09226618e+01 1.06962223e+01 1.04749355e+01 1.02722292e+01 1.00532045e+01 9.82060623e+00 9.61040306e+00 9.38423157e+00 9.14639187e+00 8.92401791e+00 8.69651318e+00 8.47505283e+00 8.25923347e+00 8.04370213e+00 7.82100916e+00 7.60375690e+00 7.37960386e+00 7.14507389e+00 6.91333342e+00 6.68404055e+00 6.46127558e+00 6.25746298e+00 6.01203346e+00 5.77965498e+00 5.59702063e+00 5.54906321e+00 5.64343739e+00 4.61453247e+00 4.05791855e+00 4.26761389e+00 3.99931622e+00 4.07062244e+00 3.87900567e+00 5.80442715e+00 8.66727412e-01 -6.38210237e-01 1.94892299e+00 1.25805187e+00 -3.07592506e+01 -5.17581825e+01 2.94841423e+01 2.90379677e+01 2.85833912e+01 1.97736618e+02 4.91035217e+02 -3.68978638e+02 -1.38564178e+02 3.50909348e+01 2.35664215e+01 2.66817570e+01 2.51193333e+01 2.52063541e+01 2.70088902e+01 2.64631462e+01 2.59357567e+01 2.54563732e+01 1.05403145e+02 1.41101682e+00 -1.00184143e+02 2.40475693e+01 1.11664597e+02 5.97490807e+01 -5.48770761e+00 -3.76004863e+00 -3.62398410e+00 -3.85919905e+00 -3.90894103e+00 -4.15230036e+00 -4.34218407e+00 -4.69874668e+00 -4.80625534e+00 -5.13815165e+00 -5.41799831e+00 -5.73676538e+00 -5.64779043e+00 -5.83333492e+00 -6.23756886e+00 -6.40090132e+00 -6.52658796e+00 -6.63727379e+00 -6.56428432e+00 -7.02242470e+00 -7.70674562e+00 -7.71298265e+00 -8.10591984e+00 -8.46688747e+00 -8.57650185e+00 -8.79639053e+00 -8.63134384e+00 -8.97464180e+00 -9.13457298e+00 -9.44649315e+00 -9.54403877e+00 -1.02580891e+01 -1.06310129e+01 -1.04389696e+01 -1.04381800e+01 -1.05470800e+01 -1.07669592e+01 -1.10999651e+01 -1.14420452e+01 -1.17744246e+01 -1.18727865e+01 -1.19030104e+01 -1.21728048e+01 -1.24126492e+01 -1.25561371e+01 -1.29355745e+01 -1.36998348e+01 -1.36392813e+01 -1.35800829e+01 -1.38132639e+01 -1.46905012e+01 -1.49301901e+01 -1.48370037e+01 -1.49613819e+01 -1.50331268e+01 -1.50752316e+01 -1.49556999e+01 -1.49372559e+01 -1.53235703e+01 -1.54462261e+01 -1.61300678e+01 -1.67152004e+01 -1.70337811e+01 -1.69563293e+01 -1.70800533e+01 -1.70353184e+01 -1.72186813e+01 -1.73821831e+01 -1.71346264e+01 -1.82065716e+01 -1.83405037e+01 -1.84746113e+01 -1.79519596e+01 -1.89395084e+01 -1.85141754e+01 -1.91069107e+01 -1.91403637e+01 -1.96605473e+01 -1.98578587e+01 -2.01791401e+01 -2.05481567e+01 -2.07982502e+01 -2.09167175e+01 -2.09257240e+01 -2.03189278e+01 -1.97115688e+01 -1.98942337e+01 -2.14420471e+01 -2.17257690e+01 -2.15958366e+01 -2.07828808e+01 -2.19332027e+01 -2.31753139e+01 -2.26510849e+01 -2.25704098e+01 -2.28290539e+01 -2.30580921e+01 -2.34061584e+01 -2.36806602e+01 -2.38674278e+01 -2.41500206e+01 -2.39197750e+01 -2.38665257e+01 -2.38979607e+01 -2.43644657e+01 -2.53165817e+01 -2.53978195e+01 -2.52950993e+01 -2.50903282e+01 -2.58056736e+01 -2.57460346e+01 -2.46088581e+01 -2.42776203e+01 -2.66516132e+01 -2.66464977e+01 -2.49917908e+01 -2.47411823e+01 -2.55223217e+01 -2.64307213e+01 -2.77437782e+01 -2.78014698e+01 -2.72908592e+01 -2.82058315e+01 -2.79949551e+01 -2.80816021e+01 -2.83092670e+01 -2.84316063e+01 -2.81973057e+01 -2.79176445e+01 -2.80445004e+01 -2.78075447e+01 -2.83257923e+01 -2.91332302e+01 -2.90601387e+01 -2.93365402e+01 -2.91716251e+01 -2.96823921e+01 -2.96961651e+01 -2.95462170e+01 -3.00536175e+01 -2.99264889e+01 -3.01926479e+01 -2.95217266e+01 -2.95573158e+01 -2.97121906e+01 -3.01248741e+01 -3.06593990e+01 -3.10596790e+01 -3.05302181e+01 -3.05781002e+01 -3.08853550e+01 -3.10986500e+01 -3.15201912e+01 -3.14576092e+01 -3.20998726e+01 -3.20581894e+01 -3.21848030e+01 -3.27779808e+01 -3.30979500e+01 -3.26125793e+01 -3.29357948e+01 -3.30128174e+01 -3.27585182e+01 -3.26463509e+01 -3.30440636e+01 -3.36052551e+01 -3.29444885e+01 -3.33397598e+01 -3.34618073e+01 -3.36289864e+01 -3.37687645e+01 -3.31764908e+01 -3.30800400e+01 -3.39153709e+01 -3.47208862e+01 -3.49219856e+01 -3.46291733e+01 -3.44992561e+01 -3.41098480e+01 -3.43636589e+01 -3.52978477e+01 -3.53177299e+01 -3.47063065e+01 -3.41079521e+01 -3.38562698e+01 -3.52738647e+01 -3.60647240e+01 -3.49547806e+01 -3.44683113e+01 -3.50759659e+01 -3.50362358e+01 -3.55589943e+01 -3.57257957e+01 -3.46292191e+01 -3.47224579e+01 -3.56666756e+01 -3.56902084e+01 -3.57093773e+01 -3.43078537e+01 -3.42756195e+01 -3.57135735e+01 -3.70890312e+01 -3.73175392e+01 -3.57026749e+01 -3.60034981e+01 -3.66581459e+01 -3.63615150e+01 -3.62245636e+01 -3.60327454e+01 -3.60676422e+01 -3.62084160e+01 -3.61800156e+01 -3.64805794e+01 -3.67630692e+01 -3.65364838e+01 -3.62305183e+01 -3.67032471e+01 -3.67064972e+01 -3.66343079e+01 -3.75374908e+01 -3.74489326e+01 -3.72969360e+01 -3.73925629e+01 -3.71811981e+01 -3.71875076e+01 -3.64715538e+01 -3.63972664e+01 -3.75685158e+01 -3.76850014e+01 -3.69593124e+01 -3.72401085e+01 -3.75957870e+01 -3.70472221e+01 -3.68235855e+01 -3.72907486e+01 -3.71786346e+01 -3.82520065e+01 -3.73610992e+01 -3.65796776e+01 -3.74933167e+01 -3.71214676e+01 -3.73816948e+01 -3.73083916e+01 -3.74458313e+01 -3.77532082e+01 -3.84409142e+01 -3.78562546e+01 -3.71536293e+01 -3.73627205e+01 -3.77897072e+01 -3.75312119e+01 -3.71520920e+01 -3.66822281e+01 -3.69726448e+01 -3.70191765e+01 -3.74081268e+01 -3.70914154e+01 -3.73674736e+01 -3.72262459e+01 -3.72005577e+01 -3.69658737e+01 -3.70457344e+01 -3.67316933e+01 -3.65522308e+01 -3.65972061e+01 -3.70934029e+01 -3.71667709e+01 -3.68413429e+01 -3.60243034e+01 -3.61062202e+01 -3.69072838e+01 -3.69886131e+01 -3.58662567e+01 -3.60517960e+01 -3.65448914e+01 -3.68080254e+01 -3.68563385e+01 -3.68345337e+01 -3.66220741e+01 -3.72860909e+01 -3.73067055e+01 -3.53270111e+01 -3.44377098e+01 -3.49982719e+01 -3.56688957e+01 -3.63898773e+01 -3.54407272e+01 -3.51019096e+01 -3.56393433e+01 -3.58520317e+01 -3.57795181e+01 -3.49337082e+01 -3.49982033e+01 -3.53336906e+01 -3.46678467e+01 -3.49686508e+01 -3.53365097e+01 -3.47389374e+01 -3.45961838e+01 -3.47525978e+01 -3.50136719e+01 -3.50831566e+01 -3.47866287e+01 -3.54130211e+01 -3.50501404e+01 -3.42494469e+01 -3.40461884e+01 -3.42878838e+01 -3.43621902e+01 -3.47624245e+01 -3.48501282e+01 -3.35690765e+01 -3.33536224e+01 -3.32714691e+01 -3.31064148e+01 -3.26715698e+01 -3.36383362e+01 -3.36231232e+01 -3.37301559e+01 -3.35151634e+01 -3.28563004e+01 -3.27697182e+01 -3.25913773e+01 -3.27749443e+01 -3.26549721e+01 -3.26218910e+01 -3.20132713e+01 -3.21835709e+01 -3.12681732e+01 -3.19018688e+01 -3.15524960e+01 -3.10880699e+01 -3.09896908e+01 -3.24427643e+01 -3.24470329e+01 -3.18503742e+01 -3.15869675e+01 -3.18072701e+01 -3.14616737e+01 -3.12687817e+01 -3.03070278e+01 -2.94747391e+01 -2.94325314e+01 -3.04519272e+01 -3.01264801e+01 -2.97944489e+01 -2.95101357e+01 -2.94279099e+01 -2.92683964e+01 -2.93729134e+01 -2.88693810e+01 -2.86262550e+01 -2.86823578e+01 -2.89998760e+01 -2.88235054e+01 -2.89683838e+01 -2.88387432e+01 -2.83166904e+01 -2.74080200e+01 -2.76182404e+01 -2.76935139e+01 -2.80911369e+01 -2.77778492e+01 -2.75417576e+01 -2.72556858e+01 -2.74018879e+01 -2.73170872e+01 -2.68883381e+01 -2.65443573e+01 -2.61227722e+01 -2.58104839e+01 -2.56966610e+01 -2.58163681e+01 -2.58483543e+01 -2.54746780e+01 -2.55036812e+01 -2.56068382e+01 -2.56071968e+01 -2.57820568e+01 -2.51461391e+01 -2.51892757e+01 -2.50364552e+01 -2.46552849e+01 -2.41941910e+01 -2.35637245e+01 -2.37011890e+01 -2.34963608e+01 -2.30694218e+01 -2.31052055e+01 -2.31306896e+01 -2.31042862e+01 -2.30541458e+01 -2.30985222e+01 -2.26934490e+01 -2.19895954e+01 -2.21152306e+01 -2.21354084e+01 -2.15227947e+01 -2.10425434e+01 -2.13091278e+01 -2.13835983e+01 -2.11958675e+01 -2.09314194e+01 -2.07408848e+01 -2.04021111e+01 -1.99712524e+01 -1.98457165e+01 -1.97852974e+01 -1.96096935e+01 -1.93214035e+01 -1.90812531e+01 -1.88583908e+01 -1.88728180e+01 -1.88119011e+01 -1.85512447e+01 -1.80845089e+01 -1.73478680e+01 -1.67325554e+01 -1.69715443e+01 -1.63266354e+01 -1.61412468e+01 -1.68369026e+01 -1.67910023e+01 -1.64889584e+01 -1.58381748e+01 -7.33119431e+01 -1.16305222e+02 -5.14392624e+01 -5.07022514e+01 -5.11633492e+01 -5.12298431e+01 -4.79827614e+01 -5.47599869e+01 -5.78994522e+01 -5.09225998e+01 -5.26009140e+01 3.99532013e+01 -2.27070408e+01 -1.63166199e+01 1.50205936e+01 -1.08729963e+01 -1.02715845e+01 -1.66355953e+01 -1.55683079e+01 -1.25009604e+01 -1.20698290e+01 -1.16988525e+01 -1.17312450e+01 -1.04941597e+01 -8.91863251e+00 -1.09570894e+01 -1.18753262e+01 -1.06956129e+01 -1.03791533e+01 -1.00408335e+01 -9.79640865e+00 -9.56699467e+00 -9.35411358e+00 -9.13822937e+00 -8.91412830e+00 -8.69663143e+00 -8.47966099e+00 -8.26656532e+00 -8.05414104e+00 -7.83483315e+00 -7.61973429e+00 -7.38775444e+00 -7.15407085e+00 -6.92792749e+00 -6.71100616e+00 -6.48573303e+00 -6.24271107e+00 -6.00744581e+00 -5.79947472e+00 -5.58074999e+00 -5.35399008e+00 -5.12969685e+00 -4.88194036e+00 -4.63501263e+00 -4.46163177e+00 -4.25528526e+00 -4.00688601e+00 -3.67061973e+00 -3.44622517e+00 -3.20001960e+00 -3.03008723e+00 -2.85479522e+00 -2.60322237e+00 -2.38982129e+00 -2.18613172e+00 -1.90712082e+00 -1.73583484e+00 -1.46887028e+00 -1.17812252e+00 -9.61863756e-01 -7.92765081e-01 -7.44718611e-01 -4.80583817e-01 -4.68748733e-02 9.49777961e-02 3.06940377e-01 6.39007986e-01 8.80614102e-01 1.04738104e+00 1.31866264e+00 1.56235969e+00 1.47695506e+00 1.73850954e+00 2.39047599e+00 2.66796398e+00 2.46850944e+00 2.92086124e+00 3.34760165e+00 3.32116151e+00 3.33929682e+00 3.86367774e+00 4.09031725e+00 4.05464315e+00 4.32674980e+00 4.84630299e+00 4.89876747e+00 4.83224678e+00 4.33951712e+00 6.12962532e+00 6.96388960e+00 5.95717382e+00 6.11054707e+00 6.32909536e+00 6.56846333e+00 6.79321289e+00 6.16649389e+00 5.74010372e+00 6.93472576e+00 9.56978989e+00 9.88965416e+00 8.59957981e+00 8.69067097e+00 8.57379913e+00 8.33399868e+00 8.74833202e+00 8.97581005e+00 9.20775986e+00 9.43876934e+00 9.99255371e+00 1.04856892e+01 1.05930853e+01 1.03216219e+01 1.02638512e+01 1.04272480e+01 1.08321056e+01 1.14038563e+01 1.14670115e+01 1.13676624e+01 1.17649441e+01 1.24237785e+01 1.26406012e+01 1.29445629e+01 1.28031549e+01 1.27413797e+01 1.31927738e+01 1.36993866e+01 1.38601542e+01 1.42927942e+01 1.47538586e+01 1.42100296e+01 1.20893488e+01 1.32116499e+01 1.59913330e+01 1.79634323e+01 1.72639465e+01 1.54169312e+01 1.55844698e+01 1.62587662e+01 1.64316750e+01 1.67527714e+01 1.67802010e+01 1.70066528e+01 1.71869717e+01 1.72990780e+01 1.73353958e+01 1.71821957e+01 1.79961777e+01 1.78794193e+01 1.81949749e+01 1.78346386e+01 1.88317986e+01 1.86362991e+01 1.91868038e+01 1.91355457e+01 1.92247849e+01 1.95081882e+01 1.98453941e+01 2.02071762e+01 2.07226963e+01 2.05641003e+01 2.01983051e+01 1.93730774e+01 1.75075073e+01 6.16982603e+00 3.66693497e+00 -1.70620937e+01 4.09923363e+01 7.40647278e+01 2.88652210e+01 3.04377766e+01 3.69416046e+01 3.69730949e+01 3.66405563e+01 3.66302567e+01 3.66583786e+01 3.57500420e+01 3.80546799e+01 3.78503418e+01 1.83354187e+01 2.20786041e+02 3.30350220e+02 1.88808460e+01 2.75250721e+01 2.14805222e+01 2.32841282e+01 -2.75256165e+02 -1.50391190e+02 2.19699135e+01 1.48278360e+01 3.29131355e+01 1.87875076e+02 6.05170532e+02 2.32085986e+03 364493440. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -762906176. -762906176. 225374416. 377576864. -2.20659707e+04 8.19141438e+05 -483714208. 2.31122925e+03 9.87652405e+02 9.31192932e+01 5.37922363e+01 4.71575050e+01 4.28343239e+01 3.98416016e+02 2.47761032e+02 3.14150906e+01 3.39445190e+01 3.08910103e+01 3.10627460e+01 3.00115871e+01 -1.73091248e+02 -3.24660370e+02 4.10270386e+01 3.99651985e+01 3.89966164e+01 4.40816231e+01 4.95153885e+01 5.29344177e+01 5.18521805e+01 4.75158730e+01 4.12240105e+01 3.88956146e+01 3.81639977e+01 3.66278839e+01 4.57616043e+01 5.67638474e+01 5.75694656e+01 5.38464546e+01 4.20960510e+02 5.07860107e+01 -3.32544708e+02 4.07503548e+01 4.42245293e+01 5.14895325e+01 5.72359695e+01 5.47665634e+01 5.12191963e+01 4.76315269e+01 4.51946068e+01 4.48714066e+01 4.13855667e+01 5.09098511e+01 5.54687462e+01 5.18171082e+01 5.91492653e+01 3.74640846e+01 4.03318825e+01 -8.29536499e+02 -2.19604419e+03 -68946808. -351742880. -10887809. -5356078. -2901485. 386734112. 3.12142822e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.76951728e+11 -2.76951728e+11 0. 0. 0. 0. -3.92612531e+09 2.09184462e+06 2.09184462e+06 1.81105803e+11 0. -4.58208922e+09 -6.36350050e+06 -20388830. 39456816. -140730688. -1.49834813e+10 -1.49834813e+10 0. -979525248. -979525248. 217045888. 3.52582170e+09 3.52582170e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -822512640. -822512640. -39616720. 1582263936. 1582263936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -586053248. -586053248. -586053248. 0. 0. -686466240. -1.52111304e+03 -1.76098621e+03 2.21068954e+01 5.18587158e+02 6.00754700e+01 4.46213379e+01 3.90692673e+01 3.15156517e+01 -1.59705063e+02 -2.98111694e+02 -7.38494995e+02 -1.98391785e+03 -3784028. 6.48944250e+05 4.38432350e+06 -19210926. 278211392. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 252721312. 8245947. 1.56668988e+06 -8.59624268e+02 -2.56836121e+02 3.22586517e+01 3.34223862e+01 3.38485870e+01 3.30098228e+01 3.22893982e+01 3.20839424e+01 3.26929817e+01 2.22248993e+02 3.57696259e+02 7.00219574e+01 5.90209579e+01 6.00909042e+01 6.32301559e+01 6.50354538e+01 -2.47491608e+02 -1.29865326e+02 3.18016853e+01 2.55278816e+01 3.28414574e+01 3.91752510e+01 3.49045448e+01 3.28999977e+01 3.15777626e+01 3.11963100e+01 3.09691525e+01 3.15572567e+01 3.16708336e+01 3.09786339e+01 3.08986397e+01 3.09551983e+01 3.06860294e+01 3.08494492e+01 3.03240318e+01 2.94727421e+01 3.05306435e+01 3.08352757e+01 2.96036301e+01 2.99507408e+01 3.06039238e+01 3.09915638e+01 3.06632843e+01 3.00474014e+01 3.00221958e+01 2.98895454e+01 3.04014568e+01 2.98481197e+01 2.95747681e+01 2.95529709e+01 2.90946827e+01 2.90187969e+01 2.83369942e+01 2.86719208e+01 2.93588200e+01 2.93127975e+01 2.92417450e+01 2.94210644e+01 2.87681446e+01 2.79033146e+01 2.80045815e+01 2.81711292e+01 2.84330273e+01 2.80105686e+01 2.76056004e+01 2.73727856e+01 2.75128155e+01 2.78765793e+01 2.77934341e+01 2.79080029e+01 2.77703705e+01 2.74288845e+01 2.72834415e+01 2.70109921e+01 2.68721237e+01 2.68299179e+01 2.67440491e+01 2.65966988e+01 2.66402988e+01 2.69063396e+01 2.62272930e+01 2.62143879e+01 2.57734966e+01 2.56994915e+01 2.56356659e+01 2.56484852e+01 2.54527302e+01 2.55602970e+01 2.55086403e+01 2.51408539e+01 2.47315674e+01 2.49904690e+01 2.50902405e+01 2.44113693e+01 2.42955132e+01 2.43170643e+01 2.44280224e+01 2.40714531e+01 2.37674580e+01 2.37290173e+01 2.38922825e+01 2.36260128e+01 2.32452240e+01 2.11928177e+01 2.11056614e+01 2.30696983e+01 2.39833107e+01 2.32548714e+01 2.22364082e+01 2.19267902e+01 2.19604149e+01 2.20419521e+01 2.18843117e+01 2.15957012e+01 2.12643738e+01 2.11455231e+01 2.10413227e+01 2.08246899e+01 2.06455708e+01 2.04821568e+01 2.03449764e+01 2.01928730e+01 2.00382156e+01 1.98419685e+01 1.97080994e+01 1.94577160e+01 1.93095512e+01 1.92164803e+01 1.91571636e+01 1.90375957e+01 1.88163185e+01 1.86328793e+01 1.84103355e+01 1.82588844e+01 1.81114788e+01 1.79246960e+01 1.77611752e+01 1.72693882e+01 1.74029846e+01 1.75304661e+01 1.70664577e+01 1.68716412e+01 1.67354679e+01 1.65540657e+01 1.63556347e+01 1.61647663e+01 1.60157146e+01 1.58574591e+01 1.56529608e+01 1.54371538e+01 1.52672482e+01 1.50895462e+01 1.49337854e+01 1.47402525e+01 1.45488958e+01 1.43865261e+01 1.42039976e+01 1.40162411e+01 1.38341131e+01 1.36360550e+01 1.34394608e+01 1.32490053e+01 1.30498285e+01 1.28503637e+01 1.26654587e+01 1.24831467e+01 1.22985001e+01 1.21104317e+01 1.19267769e+01 1.17361479e+01 1.15529661e+01 1.13571882e+01 1.11581497e+01 1.09470263e+01 1.07316685e+01 1.05290699e+01 1.03475199e+01 1.02435637e+01 1.01199636e+01 9.12688065e+00 8.64494514e+00 9.03835964e+00 8.74956894e+00 9.36923409e+00 -1.19619913e+01 -1.98027306e+01 6.58023834e+01 3.83514252e+01 7.92616320e+00 6.61171198e+00 7.77843237e+00 8.93130207e+00 9.07471180e+00 5.47176504e+00 4.61609650e+00 5.69157028e+00 5.57794189e+00 4.87573290e+00 6.20114088e+00 6.21702433e+00 4.28687572e+00 4.77276516e+00 4.50122833e+00 4.79594755e+00 5.85011940e+01 1.03260323e+02 2.59357567e+01 2.54563732e+01 -9.04312592e+01 -5.47324333e+01 4.02073812e+00 1.41979444e+00 2.07924151e+00 2.36211777e+00 2.39479756e+00 2.50831413e+00 2.25205636e+00 2.09668922e+00 2.01173854e+00 2.01788449e+00 1.68749809e+00 1.41724908e+00 1.23429644e+00 1.09364676e+00 8.44812214e-01 6.06130898e-01 6.36587858e-01 4.95904773e-01 2.94711143e-01 1.56644955e-02 1.87973864e-02 -3.91188830e-01 -5.08532047e-01 -1.16337347e+00 -1.74276173e+00 -1.38503408e+00 -1.65801191e+00 -1.96158886e+00 -1.93686306e+00 -2.20451784e+00 -2.17831159e+00 -2.43538189e+00 -2.79071355e+00 -3.21030641e+00 -3.18071318e+00 -3.85782886e+00 -4.08054590e+00 -3.98108315e+00 -4.09595251e+00 -4.46663475e+00 -4.48869944e+00 -4.84662199e+00 -5.10387516e+00 -5.45295763e+00 -5.53442335e+00 -5.40742970e+00 -5.61522293e+00 -5.80284452e+00 -5.57589817e+00 -5.56279325e+00 -6.00671911e+00 -6.43236351e+00 -6.40513372e+00 -6.91578197e+00 -8.08443356e+00 -8.56010532e+00 -8.38149643e+00 -7.98125982e+00 -8.43151474e+00 -9.15204525e+00 -9.10837460e+00 -9.18262386e+00 -9.27501869e+00 -9.73908997e+00 -9.33541107e+00 -9.91251469e+00 -9.90029240e+00 -9.99967384e+00 -1.05216064e+01 -1.04908104e+01 -1.08123121e+01 -1.04350567e+01 -1.02258968e+01 -1.08674536e+01 -1.14881268e+01 -1.18457365e+01 -1.20319881e+01 -1.22256737e+01 -1.22271624e+01 -1.22002726e+01 -1.23913908e+01 -1.29262486e+01 -1.34122591e+01 -1.30304050e+01 -1.29702110e+01 -1.33534794e+01 -1.38068542e+01 -1.40694895e+01 -1.40031767e+01 -1.34868202e+01 -1.35279617e+01 -1.43653345e+01 -1.51617298e+01 -1.49906054e+01 -1.39428072e+01 -1.49411955e+01 -1.62794380e+01 -1.63736420e+01 -1.56203003e+01 -1.59465227e+01 -1.60895119e+01 -1.66251945e+01 -1.74471798e+01 -1.73058128e+01 -1.70934696e+01 -1.67945595e+01 -1.69486313e+01 -1.71671619e+01 -1.79503460e+01 -1.78947754e+01 -1.85421333e+01 -1.77142792e+01 -1.76291943e+01 -1.82608643e+01 -1.90263214e+01 -1.90874252e+01 -1.79963360e+01 -2.02075253e+01 -2.02564259e+01 -1.81801834e+01 -1.81797943e+01 -1.89650517e+01 -1.99729309e+01 -2.11419449e+01 -2.11666203e+01 -2.05833931e+01 -2.02354355e+01 -2.06166019e+01 -1.99989586e+01 -2.01465683e+01 -2.08352699e+01 -2.12315807e+01 -2.16733379e+01 -2.19683685e+01 -2.15948906e+01 -2.20995178e+01 -2.25498276e+01 -2.26605034e+01 -2.21817818e+01 -2.18755589e+01 -2.28217258e+01 -2.30299568e+01 -2.33100758e+01 -2.33260174e+01 -2.34241962e+01 -2.33879871e+01 -2.36293163e+01 -2.40093727e+01 -2.42495441e+01 -2.36404457e+01 -2.39247093e+01 -2.35679283e+01 -2.36040478e+01 -2.32831612e+01 -2.36523399e+01 -2.49330692e+01 -2.49758987e+01 -2.52994938e+01 -2.65665054e+01 -2.66088161e+01 -2.56871262e+01 -2.58733692e+01 -2.60862026e+01 -2.58067265e+01 -2.55949936e+01 -2.55905094e+01 -2.61099701e+01 -2.56531467e+01 -2.61620502e+01 -2.68371811e+01 -2.67115192e+01 -2.72293167e+01 -2.72516212e+01 -2.60620136e+01 -2.66444683e+01 -2.73483257e+01 -2.71410236e+01 -2.84470291e+01 -2.82269650e+01 -2.79183731e+01 -2.81847420e+01 -2.86695576e+01 -2.82379704e+01 -2.81579685e+01 -2.90846481e+01 -2.81409245e+01 -2.81231232e+01 -2.78901863e+01 -2.78261471e+01 -2.95851669e+01 -3.04109211e+01 -2.89245377e+01 -2.80215054e+01 -2.92257290e+01 -2.98137417e+01 -2.87644081e+01 -2.89716930e+01 -2.91131878e+01 -2.94271240e+01 -2.96925507e+01 -2.97011185e+01 -3.01832676e+01 -2.90248508e+01 -2.86963062e+01 -2.98095245e+01 -3.13629951e+01 -3.17411308e+01 -3.01270123e+01 -3.05069199e+01 -3.10807819e+01 -3.08305817e+01 -3.08647671e+01 -3.11862564e+01 -3.12035809e+01 -3.10410442e+01 -3.09644775e+01 -3.11705856e+01 -3.13625717e+01 -3.11229973e+01 -3.05412712e+01 -3.09374447e+01 -3.13516483e+01 -3.10600853e+01 -3.21515198e+01 -3.23941231e+01 -3.23036423e+01 -3.30148659e+01 -3.28085365e+01 -3.20104942e+01 -3.09119740e+01 -3.10193768e+01 -3.27087402e+01 -3.26442604e+01 -3.18472443e+01 -3.21679611e+01 -3.27401276e+01 -3.23881302e+01 -3.19959717e+01 -3.22148933e+01 -3.22836380e+01 -3.34355621e+01 -3.27095184e+01 -3.20357704e+01 -3.38128166e+01 -3.35026894e+01 -3.28651161e+01 -3.29882584e+01 -3.25994110e+01 -3.29088478e+01 -3.35684052e+01 -3.35249329e+01 -3.26358147e+01 -3.27863197e+01 -3.30418663e+01 -3.33096237e+01 -3.30040436e+01 -3.23931618e+01 -3.24165115e+01 -3.30434265e+01 -3.33826256e+01 -3.34945717e+01 -3.33314285e+01 -3.31844597e+01 -3.28148956e+01 -3.26247864e+01 -3.30602951e+01 -3.28276634e+01 -3.28288498e+01 -3.28658257e+01 -3.30207939e+01 -3.22445374e+01 -3.24432297e+01 -3.30024605e+01 -3.26921768e+01 -3.27442436e+01 -3.34520073e+01 -3.21676445e+01 -3.19783936e+01 -3.25966301e+01 -3.32941818e+01 -3.37564163e+01 -3.36915779e+01 -3.31857491e+01 -3.31705475e+01 -3.30459633e+01 -3.26764450e+01 -3.19428787e+01 -3.21836128e+01 -3.28542328e+01 -3.30899010e+01 -3.25461655e+01 -3.27101631e+01 -3.29906006e+01 -3.33312149e+01 -3.30573425e+01 -3.29034348e+01 -3.30235710e+01 -3.30930939e+01 -3.27493858e+01 -3.30613289e+01 -3.35023346e+01 -3.28616829e+01 -3.24817543e+01 -3.30287628e+01 -3.24798164e+01 -3.15518475e+01 -3.14379787e+01 -3.21925774e+01 -3.19966755e+01 -3.18335228e+01 -3.23755836e+01 -3.27994118e+01 -3.26401863e+01 -3.22777367e+01 -3.31712990e+01 -3.31967926e+01 -3.27872047e+01 -3.26236420e+01 -3.22926064e+01 -3.23923302e+01 -3.15761280e+01 -3.17101002e+01 -3.18186970e+01 -3.22330475e+01 -3.18634777e+01 -3.16725693e+01 -3.15759945e+01 -3.15842896e+01 -3.21605911e+01 -3.14706764e+01 -3.07204075e+01 -3.09187469e+01 -3.10167103e+01 -3.14053020e+01 -3.10232601e+01 -3.02147007e+01 -3.06148777e+01 -3.17928066e+01 -3.14271889e+01 -3.07978783e+01 -3.07387486e+01 -3.06816502e+01 -3.09814548e+01 -3.10412807e+01 -3.03469849e+01 -2.93915005e+01 -2.92010746e+01 -3.01454773e+01 -3.03593674e+01 -2.95397434e+01 -2.97327614e+01 -2.96909428e+01 -2.94251366e+01 -2.99949436e+01 -2.92496300e+01 -2.91271667e+01 -2.89021091e+01 -2.90556126e+01 -2.96242847e+01 -2.90421696e+01 -2.87459183e+01 -2.80613480e+01 -2.79351234e+01 -2.80448532e+01 -2.86529732e+01 -2.85394802e+01 -2.86472950e+01 -2.79536057e+01 -2.76736908e+01 -2.80842361e+01 -2.82684269e+01 -2.84618759e+01 -2.80717430e+01 -2.78525372e+01 -2.74157562e+01 -2.68285656e+01 -2.69371948e+01 -2.71648712e+01 -2.70775166e+01 -2.70240288e+01 -2.66451950e+01 -2.65960331e+01 -2.61420059e+01 -2.61945477e+01 -2.56267586e+01 -2.56954632e+01 -2.57390060e+01 -2.58393555e+01 -2.56024590e+01 -2.55779705e+01 -2.53416843e+01 -2.50953465e+01 -2.50328636e+01 -2.50240726e+01 -2.46348362e+01 -2.44731503e+01 -2.45966301e+01 -2.43058357e+01 -2.39057808e+01 -2.41218395e+01 -2.42191772e+01 -2.34297581e+01 -2.33946991e+01 -2.38134842e+01 -2.37155590e+01 -2.32399788e+01 -2.30131035e+01 -2.27181740e+01 -2.26333447e+01 -2.23571835e+01 -2.23607731e+01 -2.22425785e+01 -2.20985050e+01 -2.20396538e+01 -2.18084660e+01 -2.14653301e+01 -2.12632580e+01 -2.11445217e+01 -2.11297894e+01 -2.10236931e+01 -2.06428909e+01 -2.05396900e+01 -2.05484009e+01 -2.03065529e+01 -1.97077446e+01 -1.87283955e+01 -2.10880470e+01 -2.19272747e+01 -1.95870609e+01 -1.95140095e+01 -1.94694881e+01 -1.91915359e+01 -1.88447819e+01 -1.86568050e+01 -1.84179955e+01 -1.75516205e+01 -1.75195599e+01 -1.91386280e+01 1.72512512e+01 -2.01818714e+01 -6.05924606e+01 -1.77770939e+01 -1.76663132e+01 -1.72219524e+01 -1.31182518e+01 -1.26969309e+01 -1.84151020e+01 -1.83516483e+01 -1.62032757e+01 -1.60102482e+01 -1.56847887e+01 -1.55903053e+01 -1.40954437e+01 -1.21768198e+01 -1.41330576e+01 -1.51476088e+01 -1.46149025e+01 -1.44769754e+01 -1.42731485e+01 -1.40799341e+01 -1.38660107e+01 -1.36623917e+01 -1.34702873e+01 -1.32749052e+01 -1.30837803e+01 -1.28963022e+01 -1.27136755e+01 -1.25283833e+01 -1.23426027e+01 -1.21476793e+01 -1.19514723e+01 -1.17432919e+01 -1.15558062e+01 -1.13702526e+01 -1.11789455e+01 -1.09796877e+01 -1.07790651e+01 -1.06026611e+01 -1.04170637e+01 -1.02258101e+01 -1.00164576e+01 -9.78086662e+00 -9.59416866e+00 -9.41670227e+00 -9.25555038e+00 -9.03022480e+00 -8.75549507e+00 -8.54953384e+00 -8.37423801e+00 -8.24193573e+00 -8.04144573e+00 -7.81329489e+00 -7.60536242e+00 -7.42173958e+00 -7.24203968e+00 -7.02238369e+00 -6.85104418e+00 -6.62754345e+00 -6.41387653e+00 -6.17704105e+00 -6.03031063e+00 -5.85621786e+00 -5.54681396e+00 -5.41631699e+00 -5.22061300e+00 -5.05840445e+00 -4.79570293e+00 -4.65181065e+00 -4.54273415e+00 -4.49620962e+00 -4.50505495e+00 -3.92888474e+00 -3.16511416e+00 -3.32007360e+00 -3.39839339e+00 -3.15062428e+00 -2.78984070e+00 -2.64669728e+00 -2.51515675e+00 -2.22119188e+00 -2.01036119e+00 -1.97377491e+00 -1.73668671e+00 -1.45104742e+00 -1.32313871e+00 -1.54816651e+00 -1.60935640e+00 -1.43817468e-02 4.49663222e-01 -3.03374559e-01 -3.15758109e-01 -1.90926239e-01 2.95194574e-02 5.44656098e-01 1.89912647e-01 -1.92286193e-01 7.72661686e-01 3.24068904e+00 3.34504747e+00 1.99250972e+00 1.80854058e+00 1.90917933e+00 2.08552384e+00 2.32268119e+00 2.59798384e+00 2.81309104e+00 3.02187991e+00 3.49366784e+00 3.85108018e+00 4.15436077e+00 4.09638262e+00 4.25240755e+00 4.08039665e+00 4.54674768e+00 5.11819172e+00 5.30857992e+00 5.16565084e+00 5.27572107e+00 5.69694042e+00 5.90338945e+00 5.97937155e+00 5.56473112e+00 5.31728458e+00 5.89861536e+00 6.58418894e+00 7.09787273e+00 7.64652348e+00 8.15266037e+00 8.35785866e+00 5.06344557e+00 5.71078491e+00 1.01606350e+01 1.20327187e+01 1.13286486e+01 9.32234573e+00 9.90090466e+00 9.35281849e+00 9.51401806e+00 9.38788605e+00 9.90355301e+00 1.03947077e+01 1.04465790e+01 1.04998360e+01 1.02115946e+01 1.06282053e+01 1.09372587e+01 1.08540354e+01 1.12263041e+01 1.15551472e+01 1.22272482e+01 1.21187162e+01 1.23330784e+01 1.26274128e+01 1.28277607e+01 1.30184240e+01 1.29941187e+01 1.31261253e+01 1.32384214e+01 1.35675344e+01 1.37368240e+01 1.33480320e+01 1.14628782e+01 1.07298577e+00 -4.59268615e-02 -1.23640814e+01 3.16165257e+01 5.95526695e+01 1.86055481e+02 3.04958801e+02 -4.65141392e+00 -6.15395546e+00 -7.64877081e+00 -7.18237162e+00 -7.61257505e+00 -6.95539761e+00 -7.54280710e+00 -7.19734812e+00 -2.92866974e+02 -1.56414169e+02 1.73846474e+01 1.76375790e+01 1.90528908e+01 1.84538918e+01 1.87599411e+01 1.94965801e+01 1.87848225e+01 1.83428516e+01 1.41859198e+01 2.02886597e+02 -1.99276745e+00 -2.58434391e+01 6.49205078e+02 1.02854163e+03 153892848. 163758944. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1358823040. -766016448. 3.06947250e+05 4.07933525e+06 -2.79850975e+06 436087520. 1.25607080e+03 4.51523102e+02 4.43386803e+01 3.46090469e+01 2.96381130e+01 2.61402969e+01 2.20870552e+01 2.75090351e+01 2.82288170e+01 -3.62091370e+02 -9.83979065e+02 -7390177. -1.26848750e+06 -1.88613719e+05 13870659. 8910673. 61778432. -14403211. -56394816. -52629684. -17992098. -3.39228719e+05 6592334. 9435951. 1.63075638e+06 2.15717383e+03 8.49316483e+01 -2.02057227e+03 -47923808. -2.02287438e+06 606209. 4386974. 2.92372025e+06 11826609. -14361365. -32871414. -21307170. -6.26907850e+06 -1.85647797e+05 1.60997844e+05 -5.78615062e+05 22243590. -3.09427656e+05 -2.17640969e+05 199234544. -2029356032. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.76951728e+11 -2.76951728e+11 0. 0. -1903325824. -1903325824. -1903325824. 0. 0. 0. 0. -4.58208922e+09 -6.36350050e+06 -20388830. 39456816. -140730688. -1.49834813e+10 -1.49834813e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -822512640. -822512640. -822512640. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -586053248. -586053248. -586053248. 0. 0. -686466240. -2137302656. -2137302656. 115914720. 220842112. 1.03378250e+06 -1.98120422e+03 -7.86152100e+02 4.67740021e+01 -6.94703552e+02 -1.82578906e+03 -22125102. 1430365056. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 471989536. -21078134. -1.62828394e+03 -5.23388855e+02 1.49806107e+02 -2.24473465e+02 -1.14260414e+02 5.02241707e+01 5.08970680e+01 5.09960785e+01 5.15624008e+01 5.14860649e+01 5.03168831e+01 4.99478989e+01 5.01270790e+01 5.12944756e+01 5.10623322e+01 4.89584351e+01 4.91778603e+01 4.95820274e+01 4.96367264e+01 4.99430313e+01 4.92748146e+01 4.86414108e+01 5.01938934e+01 5.01779022e+01 4.97912712e+01 5.01045837e+01 4.96017265e+01 4.90055847e+01 4.92502670e+01 4.85576897e+01 4.86328926e+01 4.88105545e+01 4.80912704e+01 4.79193802e+01 4.78008575e+01 4.73175774e+01 4.76882362e+01 4.72798271e+01 4.69313698e+01 4.78994141e+01 4.82622528e+01 4.75759354e+01 4.74663048e+01 4.72002907e+01 4.69286995e+01 4.65175476e+01 4.65257225e+01 4.70739403e+01 4.61832962e+01 4.55490952e+01 4.58633575e+01 4.56719437e+01 4.48651047e+01 4.48567047e+01 4.47545166e+01 4.50049477e+01 4.47928047e+01 4.47991943e+01 4.37712364e+01 4.33151398e+01 4.37575760e+01 4.35258980e+01 4.32570496e+01 4.33244743e+01 4.32590942e+01 4.30353355e+01 4.28450432e+01 4.28100014e+01 4.24289589e+01 4.19654770e+01 4.16411171e+01 4.15075912e+01 4.18347092e+01 4.20252342e+01 4.20677376e+01 4.19179916e+01 4.12904282e+01 4.11368599e+01 4.07337990e+01 4.08744087e+01 4.05658875e+01 4.02901955e+01 3.98569641e+01 3.92529068e+01 3.92157707e+01 3.91728020e+01 3.90213890e+01 3.91529083e+01 3.88403893e+01 3.82733421e+01 3.80689888e+01 3.80726776e+01 3.78077011e+01 3.74753418e+01 3.73717003e+01 3.71786537e+01 3.68385544e+01 3.67124443e+01 3.63718719e+01 3.62541618e+01 3.54829674e+01 3.54479675e+01 3.52362900e+01 3.54094658e+01 3.51622467e+01 3.46365471e+01 3.30571289e+01 3.22992096e+01 3.31469955e+01 3.48500328e+01 3.46905937e+01 3.31227722e+01 3.25792046e+01 3.24296494e+01 3.23802795e+01 3.19471416e+01 3.16799507e+01 3.14092655e+01 3.12042255e+01 3.08616848e+01 3.05602589e+01 3.03828621e+01 3.02584057e+01 2.98625145e+01 2.95327606e+01 2.92692471e+01 2.90410519e+01 2.87682400e+01 2.84748478e+01 2.81887455e+01 2.78274574e+01 2.76709557e+01 2.74040146e+01 2.70338249e+01 2.68180084e+01 2.65298405e+01 2.62796726e+01 2.59366703e+01 2.56868210e+01 2.54183559e+01 2.48268890e+01 2.48203030e+01 2.48319454e+01 2.43365211e+01 2.40330658e+01 2.37367020e+01 2.34289455e+01 2.31089592e+01 2.28450851e+01 2.26077652e+01 2.23688393e+01 2.20735321e+01 2.17374744e+01 2.14680023e+01 2.11571083e+01 2.08656311e+01 2.05427341e+01 2.02282963e+01 1.99386063e+01 1.96395016e+01 1.93489246e+01 1.90680408e+01 1.87665539e+01 1.84579659e+01 1.81661873e+01 1.78666077e+01 1.75683498e+01 1.72590179e+01 1.69334297e+01 1.66198521e+01 1.63048687e+01 1.60097809e+01 1.56985989e+01 1.53989878e+01 1.50963745e+01 1.47845144e+01 1.44471340e+01 1.41514158e+01 1.38620586e+01 1.35396929e+01 1.32161789e+01 1.29194155e+01 1.25937452e+01 1.22753839e+01 1.20039816e+01 1.16605806e+01 1.14052191e+01 1.11783543e+01 1.08366108e+01 9.07790661e+00 7.62686300e+00 9.01361370e+00 9.51594448e+00 9.44767952e+00 9.89691448e+00 9.50992966e+00 6.21060276e+00 5.56668806e+00 -3.06544685e+01 -5.02528496e+01 1.04743622e+02 6.22942467e+01 5.60445175e+01 9.16892319e+01 4.26635513e+01 4.32054520e+01 -7.11166687e+01 -5.28938293e+01 1.49561083e+00 -2.41346574e+00 -2.89741302e+00 1.99281812e+00 2.52785325e+00 1.98501801e+00 -4.32131559e-01 6.18569195e-01 1.24989319e+00 6.78354340e+01 1.27531723e+02 4.43182487e+01 4.37518349e+01 4.35880699e+01 -1.13335526e+02 -6.88784180e+01 4.72057199e+00 -2.47279286e+00 -3.64058423e+00 -3.60206985e+00 -2.74644542e+00 -2.63256359e+00 -2.86759424e+00 -3.35052276e+00 -3.56198120e+00 -3.64682722e+00 -3.90975857e+00 -4.24480343e+00 -4.84786367e+00 -5.39157963e+00 -5.57394838e+00 -5.70320272e+00 -5.85618782e+00 -6.09912491e+00 -6.55007982e+00 -6.95760918e+00 -7.16451979e+00 -7.71798897e+00 -8.25400639e+00 -8.36823559e+00 -8.62678146e+00 -8.57389069e+00 -8.92065525e+00 -9.43055630e+00 -9.89713383e+00 -1.03067207e+01 -1.06647615e+01 -1.12831125e+01 -1.15198784e+01 -1.16634989e+01 -1.17901039e+01 -1.20668936e+01 -1.24483089e+01 -1.22692709e+01 -1.24411306e+01 -1.28089857e+01 -1.36373863e+01 -1.37330675e+01 -1.44530115e+01 -1.52666950e+01 -1.58569002e+01 -1.57153482e+01 -1.55938396e+01 -1.57090874e+01 -1.63498211e+01 -1.70595512e+01 -1.68946323e+01 -1.70558357e+01 -1.72423077e+01 -1.72680283e+01 -1.78272305e+01 -1.83378754e+01 -1.87859745e+01 -1.90891075e+01 -1.96111660e+01 -1.94984989e+01 -1.96993446e+01 -1.95614777e+01 -1.99895000e+01 -2.10774841e+01 -2.11818199e+01 -2.19241009e+01 -2.16308346e+01 -2.19003391e+01 -2.16006889e+01 -2.20089130e+01 -2.28253937e+01 -2.37399673e+01 -2.32043304e+01 -2.30377979e+01 -2.26682472e+01 -2.36123638e+01 -2.40949173e+01 -2.52201576e+01 -2.52270527e+01 -2.55240860e+01 -2.56446304e+01 -2.61572819e+01 -2.66557674e+01 -2.59571571e+01 -2.62169476e+01 -2.77741833e+01 -2.77859802e+01 -2.84131279e+01 -2.84226475e+01 -2.83288460e+01 -2.82583961e+01 -2.84539165e+01 -2.82242203e+01 -2.88293343e+01 -2.93760166e+01 -2.95117989e+01 -2.97938118e+01 -2.99820080e+01 -3.05937099e+01 -3.15612335e+01 -3.11876259e+01 -3.12808113e+01 -3.07304058e+01 -3.11427631e+01 -3.16553497e+01 -3.16138859e+01 -3.39724045e+01 -3.49741287e+01 -3.32143211e+01 -3.30892258e+01 -3.29368095e+01 -3.43936386e+01 -3.53117828e+01 -3.55594444e+01 -3.45925255e+01 -3.38294487e+01 -3.43247108e+01 -3.44700203e+01 -3.41559982e+01 -3.55160446e+01 -3.64554634e+01 -3.68094063e+01 -3.64529305e+01 -3.61916924e+01 -3.68304138e+01 -3.72518845e+01 -3.75401535e+01 -3.72345619e+01 -3.75681610e+01 -3.86625366e+01 -3.86967621e+01 -3.88895454e+01 -3.84460220e+01 -3.90026588e+01 -3.89654007e+01 -3.96566353e+01 -3.99886627e+01 -4.00759544e+01 -3.99589081e+01 -3.96992874e+01 -3.92894096e+01 -3.95092926e+01 -4.00366592e+01 -4.10684280e+01 -4.18311005e+01 -4.13331184e+01 -4.12974205e+01 -4.26676254e+01 -4.34421997e+01 -4.28221016e+01 -4.26820221e+01 -4.27966270e+01 -4.27601891e+01 -4.30317268e+01 -4.32701492e+01 -4.34523087e+01 -4.29146690e+01 -4.30946960e+01 -4.36495056e+01 -4.40497246e+01 -4.51453362e+01 -4.54929276e+01 -4.38705330e+01 -4.35214958e+01 -4.38278999e+01 -4.42909126e+01 -4.62660255e+01 -4.64823189e+01 -4.59514198e+01 -4.58794022e+01 -4.66357918e+01 -4.63460922e+01 -4.63099594e+01 -4.69393654e+01 -4.59172745e+01 -4.62972069e+01 -4.61411095e+01 -4.61172371e+01 -4.82827759e+01 -4.84146194e+01 -4.66531563e+01 -4.63362007e+01 -4.78637009e+01 -4.84089241e+01 -4.73807716e+01 -4.77622757e+01 -4.83651810e+01 -4.86383438e+01 -4.84018440e+01 -4.83976135e+01 -4.89385223e+01 -4.82162361e+01 -4.77044945e+01 -4.86593475e+01 -5.05614052e+01 -5.05250168e+01 -4.90293541e+01 -4.97469406e+01 -4.99624290e+01 -4.96834679e+01 -5.03761864e+01 -5.02225876e+01 -5.00376701e+01 -5.06082115e+01 -5.00697937e+01 -4.99672127e+01 -5.07075310e+01 -5.04770660e+01 -5.00095634e+01 -5.02275505e+01 -5.13504944e+01 -5.07270508e+01 -5.07273636e+01 -5.16120453e+01 -5.17719803e+01 -5.23517799e+01 -5.15540810e+01 -5.09190979e+01 -5.07894516e+01 -5.08884544e+01 -5.15968628e+01 -5.13850670e+01 -5.14000359e+01 -5.13237610e+01 -5.15709648e+01 -5.14422340e+01 -5.16227188e+01 -5.17788811e+01 -5.20194740e+01 -5.31406288e+01 -5.22504349e+01 -5.16261368e+01 -5.23973465e+01 -5.24576874e+01 -5.23215752e+01 -5.26224442e+01 -5.23980408e+01 -5.23045616e+01 -5.30882492e+01 -5.29266930e+01 -5.19206238e+01 -5.24702797e+01 -5.26093788e+01 -5.28962555e+01 -5.25564575e+01 -5.24533958e+01 -5.21878395e+01 -5.21583672e+01 -5.22532539e+01 -5.27427559e+01 -5.26994820e+01 -5.26416168e+01 -5.25552864e+01 -5.26125298e+01 -5.22496147e+01 -5.24540176e+01 -5.22892036e+01 -5.28320885e+01 -5.30718536e+01 -5.25934105e+01 -5.16088028e+01 -5.25002708e+01 -5.28341713e+01 -5.34796066e+01 -5.36913338e+01 -5.22407761e+01 -5.13721695e+01 -5.17547874e+01 -5.26429863e+01 -5.32258453e+01 -5.36573143e+01 -5.30514526e+01 -5.22488785e+01 -5.18094101e+01 -5.16106758e+01 -5.16410065e+01 -5.19786987e+01 -5.29519043e+01 -5.25188293e+01 -5.19151192e+01 -5.13066826e+01 -5.15904999e+01 -5.20594597e+01 -5.16594925e+01 -5.15246696e+01 -5.15000343e+01 -5.17430534e+01 -5.19280853e+01 -5.18099861e+01 -5.18104172e+01 -5.17735710e+01 -5.16813011e+01 -5.15439491e+01 -5.11795959e+01 -5.05171928e+01 -4.99697113e+01 -5.02587852e+01 -5.07933083e+01 -5.12308846e+01 -5.08852119e+01 -5.12739754e+01 -5.12608109e+01 -5.08427925e+01 -5.05107193e+01 -5.00089302e+01 -5.07031937e+01 -5.04891357e+01 -5.00374565e+01 -4.94655151e+01 -4.89596558e+01 -4.91105537e+01 -4.93855171e+01 -4.93173752e+01 -4.93014450e+01 -4.96950111e+01 -4.90519371e+01 -4.89733315e+01 -4.91834526e+01 -4.87417679e+01 -4.87910881e+01 -4.86548347e+01 -4.91307144e+01 -4.84598808e+01 -4.81121902e+01 -4.67913933e+01 -4.69549294e+01 -4.79958382e+01 -4.79600067e+01 -4.71734619e+01 -4.69517593e+01 -4.57076149e+01 -4.61393890e+01 -4.60918427e+01 -4.69513054e+01 -4.68593292e+01 -4.70216179e+01 -4.65126534e+01 -4.57129860e+01 -4.55555267e+01 -4.59618835e+01 -4.53759003e+01 -4.49630814e+01 -4.53850212e+01 -4.58473587e+01 -4.52302475e+01 -4.45217934e+01 -4.38610687e+01 -4.39291954e+01 -4.36651840e+01 -4.34696350e+01 -4.32314339e+01 -4.31459045e+01 -4.28759422e+01 -4.32181740e+01 -4.32254143e+01 -4.35015678e+01 -4.28481712e+01 -4.27787361e+01 -4.20797348e+01 -4.16813965e+01 -4.17201767e+01 -4.18718300e+01 -4.22824249e+01 -4.22235069e+01 -4.13534622e+01 -4.12940712e+01 -4.11249046e+01 -4.10547333e+01 -4.05886765e+01 -4.02134209e+01 -3.98569450e+01 -3.92817497e+01 -3.91565933e+01 -3.88399696e+01 -3.85331154e+01 -3.88188019e+01 -3.88183975e+01 -3.84008751e+01 -3.79515572e+01 -3.76563034e+01 -3.74966354e+01 -3.72801056e+01 -3.71146202e+01 -3.67862396e+01 -3.65960464e+01 -3.65899239e+01 -3.61790733e+01 -3.56405258e+01 -3.54950333e+01 -3.56081924e+01 -3.45280113e+01 -3.46111145e+01 -3.51577835e+01 -3.49039955e+01 -3.44843407e+01 -3.40097618e+01 -3.38093529e+01 -3.37537575e+01 -3.35183487e+01 -3.28990936e+01 -3.14041443e+01 -3.28321991e+01 -2.98635254e+01 3.62951584e+01 7.17452774e+01 -6.79080124e+01 -6.74730682e+01 -6.79118729e+01 -1.58471222e+02 -1.02920914e+02 -3.10542812e+01 -3.02145920e+01 -2.96445980e+01 -2.89316521e+01 -2.77568436e+01 -2.99360924e+01 -3.06821575e+01 -2.84776459e+01 1.77596169e+01 1.02281971e+01 -6.46754379e+01 -7.05706215e+00 -1.21197388e+02 -7.88160706e+01 -2.61883049e+01 -2.48401031e+01 -2.62206192e+01 -2.82521286e+01 -2.48024311e+01 -2.64536037e+01 -2.44001865e+01 -2.41765480e+01 -2.37038193e+01 -1.92939453e+01 -2.00131092e+01 -2.32105618e+01 -2.29282207e+01 -2.24104004e+01 -2.22663288e+01 -2.21364136e+01 -2.19008408e+01 -2.15939331e+01 -2.12990303e+01 -2.09934292e+01 -2.06611519e+01 -2.03433170e+01 -2.00495777e+01 -1.97789574e+01 -1.95063152e+01 -1.91900711e+01 -1.88816586e+01 -1.85835743e+01 -1.82810345e+01 -1.79776096e+01 -1.76718521e+01 -1.73717041e+01 -1.70583134e+01 -1.67504654e+01 -1.64191418e+01 -1.60945225e+01 -1.57590656e+01 -1.54476042e+01 -1.51425581e+01 -1.48283081e+01 -1.45154409e+01 -1.42018881e+01 -1.38961954e+01 -1.35855913e+01 -1.32645006e+01 -1.29418602e+01 -1.26279955e+01 -1.22875023e+01 -1.19242134e+01 -1.15928841e+01 -1.12698956e+01 -1.09383249e+01 -1.06097660e+01 -1.04320011e+01 -1.01537628e+01 -9.84029579e+00 -9.48235893e+00 -9.15172386e+00 -8.82266998e+00 -8.58028221e+00 -8.21483421e+00 -7.84464073e+00 -7.55731440e+00 -7.26855803e+00 -7.02642870e+00 -6.66959238e+00 -6.30445290e+00 -5.93230200e+00 -5.66268921e+00 -5.41619158e+00 -5.11293364e+00 -4.73211813e+00 -4.40107822e+00 -4.12079859e+00 -4.00844765e+00 -3.81291461e+00 -2.96950483e+00 -2.28016114e+00 -2.35865498e+00 -2.25632572e+00 -1.82705975e+00 -1.45140004e+00 -1.24829376e+00 -8.60822558e-01 -4.87059861e-01 -1.10896878e-01 8.87696072e-02 4.39057499e-01 7.43137479e-01 1.19552171e+00 9.30380762e-01 1.30805504e+00 2.78683090e+00 3.07206631e+00 2.79262376e+00 3.41502619e+00 3.43901443e+00 3.48717690e+00 3.74384809e+00 3.19658709e+00 3.61469555e+00 5.12256622e+00 7.13806868e+00 7.16041660e+00 5.84981298e+00 5.85881996e+00 6.12853479e+00 6.65077353e+00 7.19315958e+00 7.78834963e+00 7.90307665e+00 8.05040169e+00 8.32213879e+00 8.57515240e+00 9.02720070e+00 9.34443378e+00 9.87741566e+00 1.02523355e+01 1.05439405e+01 1.11641502e+01 1.14649677e+01 1.14944572e+01 1.16873751e+01 1.22595615e+01 1.27706671e+01 1.27618361e+01 1.25981283e+01 1.24647341e+01 1.33045940e+01 1.38788271e+01 1.44645414e+01 1.46390696e+01 1.53368683e+01 1.56150570e+01 1.27180586e+01 1.31161976e+01 1.80865402e+01 1.97502823e+01 1.81242828e+01 1.71003590e+01 1.73864002e+01 1.74517403e+01 1.76034451e+01 1.77783108e+01 1.86031551e+01 1.90538864e+01 1.94544582e+01 1.92243252e+01 1.94590702e+01 1.98237801e+01 2.00147076e+01 2.07744102e+01 2.09665203e+01 2.17406445e+01 2.16361885e+01 2.17099762e+01 2.20175343e+01 2.26499996e+01 2.30759754e+01 2.33486271e+01 2.33092327e+01 2.34399700e+01 2.30007534e+01 2.38338089e+01 2.42435188e+01 2.54012394e+01 2.55067673e+01 2.59447384e+01 2.56494846e+01 2.58060055e+01 2.62153130e+01 2.67206993e+01 2.64431801e+01 2.71359043e+01 2.83383656e+01 2.86598072e+01 2.80064011e+01 2.82374191e+01 2.80307007e+01 2.83424625e+01 2.83076038e+01 2.87744865e+01 2.87837505e+01 2.96123238e+01 3.02141571e+01 3.00856705e+01 3.04062328e+01 3.16728287e+01 3.21199150e+01 3.14475479e+01 3.10999813e+01 3.18344593e+01 3.17973042e+01 3.11847992e+01 2.95419006e+01 1.02045107e+01 2.04469498e+02 2.90558960e+02 6.09035217e+02 1.41794373e+03 -36486808. -117234712. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -163331632. -163331632. -163331632. 0. 0. -49659096. 2.30663254e+02 6.39597855e+01 4.97586250e+01 -1.59572311e+02 -3.10760529e+02 3.90915649e+02 5.61844360e+02 7.35739594e+01 -28197784. 1282204160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1267846144. -1267846144. -1267846144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1903325824. -1903325824. -1903325824. 0. 0. 0. 0. -4.58208922e+09 -6.36350050e+06 -20388830. 39456816. -5.36689459e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -299497312. 31874760. -1.61245250e+05 19978098. 39169020. -45109816. 2.89121450e+06 -112001728. 2.36843175e+06 2.82265406e+05 -68860520. 114123912. 632696000. 632696000. 0. 0. 0. 0. 0. 0. 0. -586053248. -586053248. -586053248. 0. 0. -686466240. -2137302656. -2137302656. 115914720. 220842112. 1.03378250e+06 1.02845444e+06 9822537. 2597507. -138061632. 364039968. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.27841016e+05 3.36284607e+02 -2.33774017e+02 -1.03855629e+02 6.69196701e+01 6.75773544e+01 6.54789124e+01 6.36650620e+01 6.26172791e+01 6.14053078e+01 6.18614311e+01 6.23337059e+01 6.08327675e+01 6.07638359e+01 6.27028008e+01 -1.00209633e+02 -2.13654099e+02 4.01550018e+02 2.55866455e+02 5.74514389e+01 6.00161896e+01 6.14496803e+01 6.00191765e+01 5.99604492e+01 6.13018150e+01 6.07032700e+01 6.04284515e+01 6.07742958e+01 5.98657379e+01 5.92303429e+01 5.92513924e+01 5.89114494e+01 5.94710579e+01 5.94498291e+01 5.88107910e+01 5.88677979e+01 5.63829269e+01 -8.90100021e+01 -1.86923630e+02 1.31841125e+02 1.30558014e+02 1.36158768e+02 3.66421356e+02 2.35327255e+02 5.81267090e+01 5.72312660e+01 5.77473450e+01 5.77906075e+01 5.76265907e+01 5.78989983e+01 5.69697723e+01 5.63790092e+01 5.64153748e+01 5.66247444e+01 5.60117149e+01 5.54885178e+01 5.51609573e+01 5.55493851e+01 5.55022430e+01 5.51999664e+01 5.39737511e+01 5.37427940e+01 5.36201973e+01 5.41908569e+01 5.38242722e+01 5.28780861e+01 5.26887360e+01 5.23216324e+01 5.26153717e+01 5.24228897e+01 5.22496605e+01 5.20569725e+01 5.15469513e+01 5.10164871e+01 5.07171249e+01 5.03443260e+01 5.06966743e+01 5.03183174e+01 5.02134323e+01 4.97830429e+01 4.99591217e+01 5.00865364e+01 4.95266914e+01 4.92655830e+01 4.86763496e+01 4.87417336e+01 4.81647377e+01 4.78381081e+01 4.75471916e+01 4.73291092e+01 4.70341263e+01 4.66547394e+01 4.64180374e+01 4.62368927e+01 4.59393883e+01 4.57807693e+01 4.54720688e+01 4.49639473e+01 4.47741051e+01 4.45704002e+01 4.42323875e+01 4.38495979e+01 4.34236565e+01 4.30074005e+01 4.27751083e+01 4.28516541e+01 4.27915726e+01 4.22405624e+01 4.13722992e+01 4.03211327e+01 4.06525612e+01 4.25664520e+01 4.23144989e+01 4.05787086e+01 3.98412209e+01 3.96902542e+01 3.94843559e+01 3.90550232e+01 3.87397804e+01 3.85238075e+01 3.83460388e+01 3.80908051e+01 3.76601410e+01 3.74329262e+01 3.70882912e+01 3.65651894e+01 3.61993408e+01 3.59294586e+01 3.56877098e+01 3.53212166e+01 3.50202255e+01 3.45521774e+01 3.41657104e+01 3.38924255e+01 3.36260300e+01 3.32655640e+01 3.29229546e+01 3.26485901e+01 3.24140854e+01 3.21443329e+01 3.18211594e+01 3.14196415e+01 3.07971306e+01 3.06106586e+01 3.04994316e+01 3.00253258e+01 2.96559982e+01 2.93505402e+01 2.89570942e+01 2.85313034e+01 2.81838665e+01 2.78420334e+01 2.74797764e+01 2.71286106e+01 2.67771797e+01 2.64459286e+01 2.61028709e+01 2.57577362e+01 2.53828621e+01 2.50305195e+01 2.46660385e+01 2.42999058e+01 2.39428482e+01 2.35929432e+01 2.32271118e+01 2.28589039e+01 2.25045242e+01 2.21467247e+01 2.17790737e+01 2.14034271e+01 2.10246277e+01 2.06662941e+01 2.03185558e+01 1.99590626e+01 1.95879211e+01 1.91980629e+01 1.88036861e+01 1.84131756e+01 1.80320091e+01 1.76919041e+01 1.73421612e+01 1.69387035e+01 1.65630035e+01 1.61991577e+01 1.58359346e+01 1.54486275e+01 1.50764093e+01 1.46747885e+01 1.43043442e+01 1.39041519e+01 1.35514641e+01 1.32014980e+01 1.27611494e+01 1.23471651e+01 1.19160366e+01 1.16428614e+01 1.16260977e+01 1.05768185e+01 7.56413555e+00 7.30858517e+00 9.84429741e+00 1.01475935e+01 1.07484760e+01 1.05836325e+01 3.24663162e+00 1.46470749e+00 1.57136881e+00 2.68063521e+00 6.68943834e+00 -5.03738976e+01 -7.06098785e+01 3.88903992e+02 9.21911255e+02 6.80777283e+02 2.71199768e+02 3.23936195e+01 -9.63714600e+01 -6.16479836e+01 1.68147326e+00 -2.30460072e+00 -2.69920683e+00 -7.95765686e+00 -8.57161331e+00 -8.78836441e+00 -4.07050705e+00 1.34501839e+00 1.23220310e+01 8.27821350e+01 1.42360428e+02 2.21657181e+01 2.76367512e+01 2.91739216e+01 2.95308056e+01 2.73154926e+01 2.73409653e+01 2.75185299e+01 -1.46797928e+02 -9.84845352e+01 -5.50205946e+00 -6.10886288e+00 -7.25513935e+00 -7.10279512e+00 -7.10903072e+00 -5.76747656e+00 -7.21070957e+00 -9.49838638e+00 -7.30990553e+00 -6.48435354e+00 -9.01786900e+00 -9.19797039e+00 -5.51722860e+00 -4.06956863e+00 -6.72451258e-01 1.05607328e+01 -7.15158606e+00 -2.09151249e+01 -1.10836542e+00 -2.04498081e+01 -2.49853878e+01 -1.74158916e+01 -1.90245209e+01 -1.48711643e+01 -1.58796043e+01 -1.28757391e+01 -1.60028286e+01 -1.67704029e+01 -1.60755291e+01 -1.77414608e+01 -1.71993580e+01 -1.57512484e+01 -1.80614548e+01 -1.67831612e+01 -1.42162933e+01 -1.74997940e+01 -2.00484695e+01 -2.01220818e+01 -2.04692898e+01 -2.04294033e+01 -2.07265587e+01 -2.11715736e+01 -2.17079601e+01 -2.20949554e+01 -2.18934097e+01 -2.21046410e+01 -2.26493034e+01 -2.32629719e+01 -2.36666546e+01 -2.39438133e+01 -2.43710480e+01 -2.47854652e+01 -2.53809128e+01 -2.57685337e+01 -2.55691814e+01 -2.57463493e+01 -2.59989796e+01 -2.60735512e+01 -2.64828072e+01 -2.73655815e+01 -2.76864719e+01 -2.77567749e+01 -2.78588619e+01 -2.79845943e+01 -2.83672428e+01 -2.93256721e+01 -3.02395554e+01 -3.05883713e+01 -3.02782688e+01 -3.04853973e+01 -3.11310005e+01 -3.10143070e+01 -3.15133724e+01 -3.30754929e+01 -3.25994720e+01 -3.26970749e+01 -3.31689682e+01 -3.35024643e+01 -3.37799034e+01 -3.43193169e+01 -3.42740860e+01 -3.52424889e+01 -3.55619583e+01 -3.49717293e+01 -3.54773827e+01 -3.53780823e+01 -3.61754494e+01 -3.68266983e+01 -3.71642494e+01 -3.77283478e+01 -3.74314575e+01 -3.74126167e+01 -3.75612793e+01 -3.74232368e+01 -3.90214653e+01 -3.99107094e+01 -3.96165352e+01 -3.88808632e+01 -3.96613579e+01 -4.13152504e+01 -4.18926048e+01 -4.25110626e+01 -4.16194687e+01 -4.16293221e+01 -4.23215141e+01 -4.27521210e+01 -4.21665306e+01 -4.22574463e+01 -4.32431488e+01 -4.43347359e+01 -4.40047112e+01 -4.36573410e+01 -4.37928047e+01 -4.42119331e+01 -4.48620186e+01 -4.49154205e+01 -4.49984016e+01 -4.53877640e+01 -4.58773308e+01 -4.62130127e+01 -4.68630714e+01 -4.67086792e+01 -4.67661972e+01 -4.71228256e+01 -4.76218758e+01 -4.76272736e+01 -4.78317833e+01 -4.83152428e+01 -4.89445992e+01 -4.85911636e+01 -4.86563148e+01 -4.95982475e+01 -5.02961540e+01 -4.98206787e+01 -4.91750984e+01 -5.04032478e+01 -5.15422287e+01 -5.16284714e+01 -5.20454674e+01 -5.18540001e+01 -5.16843758e+01 -5.20670128e+01 -5.19483528e+01 -5.18634796e+01 -5.15296478e+01 -5.18711472e+01 -5.20761566e+01 -5.20936928e+01 -5.38659592e+01 -5.42518082e+01 -5.28211823e+01 -5.23494606e+01 -5.32111168e+01 -5.40283012e+01 -5.53619270e+01 -5.49620628e+01 -5.48121490e+01 -5.57203102e+01 -5.60401497e+01 -5.53644714e+01 -5.60087318e+01 -5.64509315e+01 -5.53415833e+01 -5.56018333e+01 -5.58692474e+01 -5.63250618e+01 -5.77712746e+01 -5.77537155e+01 -5.68916397e+01 -5.64814262e+01 -5.75908470e+01 -5.82245331e+01 -5.74030380e+01 -5.74390564e+01 -5.80585709e+01 -5.86030273e+01 -5.85887108e+01 -5.85728378e+01 -5.90377274e+01 -5.89638138e+01 -5.81016273e+01 -5.86007843e+01 -6.07983513e+01 -6.06634712e+01 -5.94349060e+01 -5.99486275e+01 -5.99809952e+01 -5.99885178e+01 -6.07055702e+01 -6.08957558e+01 -6.05798035e+01 -6.09291039e+01 -6.07231903e+01 -6.04643745e+01 -6.11135979e+01 -6.12134094e+01 -6.05927925e+01 -6.07940254e+01 -6.25766411e+01 -6.17154312e+01 -6.06931152e+01 -6.17277145e+01 -6.24083786e+01 -6.32639580e+01 -6.21663704e+01 -6.18124657e+01 -6.15444603e+01 -6.17772102e+01 -6.23043900e+01 -6.24379387e+01 -6.24502411e+01 -6.27403946e+01 -6.28573189e+01 -6.26426697e+01 -6.25868988e+01 -6.29182892e+01 -6.27422791e+01 -6.31309013e+01 -6.28411903e+01 -6.29638062e+01 -6.33727684e+01 -6.31410446e+01 -6.29568863e+01 -6.32936516e+01 -6.35094452e+01 -6.32842827e+01 -6.38258858e+01 -6.39955406e+01 -6.35760269e+01 -6.37377510e+01 -6.40739365e+01 -6.36594505e+01 -6.33447495e+01 -6.40653076e+01 -6.39689217e+01 -6.40815506e+01 -6.40777664e+01 -6.45834198e+01 -6.44033585e+01 -6.44954910e+01 -6.43869095e+01 -6.45441132e+01 -6.37793655e+01 -6.37370491e+01 -6.36230087e+01 -6.39448318e+01 -6.45485001e+01 -6.46673279e+01 -6.41746140e+01 -6.44089355e+01 -6.42280731e+01 -6.31164436e+01 -6.39685326e+01 -6.39648933e+01 -6.49977722e+01 -6.49229126e+01 -6.47121887e+01 -6.41590729e+01 -6.35355759e+01 -6.35767365e+01 -6.36931610e+01 -6.43273239e+01 -6.46925430e+01 -6.38983383e+01 -6.35261154e+01 -6.37882309e+01 -6.36371002e+01 -6.32394142e+01 -6.31451950e+01 -6.34007912e+01 -6.37449417e+01 -6.29365807e+01 -6.24742470e+01 -6.17687569e+01 -6.19001236e+01 -6.26031265e+01 -6.28210602e+01 -6.25773315e+01 -6.25459900e+01 -6.20653343e+01 -6.25039215e+01 -6.24450111e+01 -6.25329399e+01 -6.18940468e+01 -6.13593712e+01 -6.18414307e+01 -6.16124229e+01 -6.08583069e+01 -6.07811775e+01 -6.06151390e+01 -6.14970245e+01 -6.07589340e+01 -6.01024628e+01 -6.00301704e+01 -6.01596565e+01 -6.05998306e+01 -6.04357834e+01 -6.06171684e+01 -6.07531204e+01 -6.15024338e+01 -6.04967270e+01 -5.97589989e+01 -5.91924438e+01 -5.91106033e+01 -5.89878082e+01 -5.88179321e+01 -5.90223198e+01 -5.90919609e+01 -5.87621727e+01 -5.88606529e+01 -5.86508141e+01 -5.75488205e+01 -5.71181793e+01 -5.77851524e+01 -5.82752419e+01 -5.73405762e+01 -5.68874664e+01 -5.71350174e+01 -5.62112198e+01 -5.64000168e+01 -5.62988434e+01 -5.68250580e+01 -5.72338562e+01 -5.68767471e+01 -5.58903275e+01 -5.50319595e+01 -5.53420296e+01 -5.59497223e+01 -5.53759499e+01 -5.48429413e+01 -5.39865608e+01 -5.43494987e+01 -5.47295418e+01 -5.46502991e+01 -5.43632202e+01 -5.43226891e+01 -5.42582588e+01 -5.40084229e+01 -5.36172562e+01 -5.27488174e+01 -5.21731415e+01 -5.22487869e+01 -5.31316910e+01 -5.27269707e+01 -5.25933838e+01 -5.28279305e+01 -5.22191505e+01 -5.13914871e+01 -5.11379166e+01 -5.07831116e+01 -5.09393883e+01 -5.09624977e+01 -5.05758324e+01 -5.04725647e+01 -5.03174782e+01 -4.98745995e+01 -4.94474983e+01 -4.96952019e+01 -4.91074257e+01 -4.90704689e+01 -4.88584480e+01 -4.87850113e+01 -4.81945229e+01 -4.81769104e+01 -4.79001999e+01 -4.76870308e+01 -4.71841087e+01 -4.67188301e+01 -4.65176086e+01 -4.59003525e+01 -4.62540970e+01 -4.60994873e+01 -4.55063477e+01 -4.52843056e+01 -4.44918480e+01 -4.38413658e+01 -4.25818100e+01 3.39182587e+01 7.97473221e+01 -1.11004509e+02 -1.13693871e+02 -1.12982391e+02 -1.12751221e+02 -1.12721069e+02 -1.13435516e+02 -1.13989861e+02 -1.12576378e+02 -2.01722458e+02 -1.26804092e+02 -3.98596077e+01 -3.56744385e+01 -4.50994987e+01 -5.08649330e+01 -4.83648491e+01 -4.76309013e+01 -4.71269073e+01 -4.07757225e+01 -4.09583664e+01 1.43139000e+01 4.40722122e+01 -9.96212387e+01 -1.54546082e+02 -5.09371529e+01 3.47742805e+01 -1.55683868e+02 -9.97666321e+01 -3.92060127e+01 -6.18482256e+00 -3.56744423e+01 -5.80370560e+01 -3.44473267e+01 -3.49515343e+01 -3.28646507e+01 -3.02621822e+01 -3.11351566e+01 -8.10367050e+01 -3.56292648e+01 -2.38678265e+00 -2.98332977e+01 -2.98497047e+01 -2.96447544e+01 -2.94784412e+01 -2.91283550e+01 -2.87005920e+01 -2.83433571e+01 -2.80247746e+01 -2.76614685e+01 -2.73170013e+01 -2.69651604e+01 -2.65998230e+01 -2.62450066e+01 -2.58788128e+01 -2.55257740e+01 -2.51565018e+01 -2.47836971e+01 -2.44402485e+01 -2.41158543e+01 -2.37677269e+01 -2.34125290e+01 -2.30538273e+01 -2.26940842e+01 -2.23275394e+01 -2.19606934e+01 -2.15899811e+01 -2.12233257e+01 -2.08527927e+01 -2.04804440e+01 -2.01044388e+01 -1.97317810e+01 -1.93732758e+01 -1.90057220e+01 -1.86119747e+01 -1.82324123e+01 -1.78588734e+01 -1.74980602e+01 -1.70953789e+01 -1.67167397e+01 -1.63354759e+01 -1.59968634e+01 -1.55887060e+01 -1.51511612e+01 -1.47825756e+01 -1.44402227e+01 -1.39260731e+01 -1.34957323e+01 -1.32673635e+01 -1.28643026e+01 -1.24314461e+01 -1.20621634e+01 -1.16772251e+01 -1.13035975e+01 -1.09394693e+01 -1.05359201e+01 -1.00525150e+01 -9.76205730e+00 -9.35028267e+00 -9.05317497e+00 -8.65512943e+00 -8.19885826e+00 -7.78657818e+00 -7.32860756e+00 -7.03859901e+00 -6.66163445e+00 -6.25642300e+00 -5.86386871e+00 -5.43159342e+00 -5.30361557e+00 -4.95612669e+00 -4.05621529e+00 -3.63563371e+00 -3.51861358e+00 -3.10099792e+00 -2.71835923e+00 -2.24520493e+00 -1.97184670e+00 -1.48101449e+00 -1.10502744e+00 -6.64712250e-01 -4.12063986e-01 -7.63335824e-02 4.28549588e-01 8.38050902e-01 5.80684900e-01 1.13529122e+00 3.00758386e+00 3.19410062e+00 2.81128931e+00 3.04647708e+00 3.22136259e+00 3.52667594e+00 4.43164921e+00 3.93582344e+00 4.19365406e+00 5.79561138e+00 7.38663626e+00 7.58707428e+00 6.92476749e+00 7.29659271e+00 7.76385355e+00 8.07025814e+00 8.26333141e+00 8.84876537e+00 8.98829842e+00 9.50463295e+00 9.90142727e+00 1.01737118e+01 1.06622553e+01 1.08983793e+01 1.14175329e+01 1.17470026e+01 1.20093756e+01 1.25522690e+01 1.28485537e+01 1.33254185e+01 1.39688501e+01 1.41767969e+01 1.47443790e+01 1.52331581e+01 1.57138433e+01 1.56797581e+01 1.59135008e+01 1.64836407e+01 1.69356251e+01 1.67970562e+01 1.70059166e+01 1.72698917e+01 1.53980999e+01 1.56083202e+01 2.04793777e+01 2.13760357e+01 1.97569294e+01 1.95865269e+01 2.01227970e+01 2.09941044e+01 2.11946926e+01 2.14513168e+01 2.14983406e+01 2.15104427e+01 2.19106178e+01 2.22677841e+01 2.29930363e+01 2.34016819e+01 2.36633224e+01 2.45855255e+01 2.50716705e+01 2.53362427e+01 2.51757126e+01 2.23024101e+01 1.50134783e+01 7.43319225e+00 -1.34768814e+02 -2.33927155e+02 2.32919273e+01 2.47900562e+01 3.09769897e+02 1.99117004e+02 2.85682697e+01 2.98189850e+01 3.05349903e+01 3.07345314e+01 3.06195793e+01 3.11623573e+01 3.13814430e+01 3.18829117e+01 3.21173286e+01 3.21418762e+01 3.22593117e+01 3.29549866e+01 3.30917549e+01 3.35078239e+01 3.19408016e+01 3.15104752e+01 3.21773911e+01 4.37435112e+01 -1.21041168e+02 4.36463535e-01 2.42074921e+02 4.41927261e+01 5.00022621e+01 5.05408173e+01 4.14315453e+01 3.95258484e+01 3.88967705e+01 3.91099014e+01 3.88237419e+01 3.86720657e+01 3.83799400e+01 3.76286240e+01 3.45112343e+01 1.35259295e+01 1.91631287e+02 1.73270844e+02 -4.71193115e+03 -117234712. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -163331632. -163331632. -163331632. 0. 0. -5.20946250e+06 6.74418152e+02 2.08108231e+02 1.15211510e+02 -8.03460815e+02 -2.33771313e+03 2.26620142e+03 1.22933022e+02 -2.06860278e+03 -28197784. 1282204160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.34037371e+10 -2.34037371e+10 -2.34037371e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1903325824. -1903325824. -1903325824. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1070082752. -1070082752. -1070082752. 0. 0. 0. 0. 0. 0. 0. 0. 0. -299497312. 31874760. -1.61245250e+05 19978098. 39169020. -45109816. 2.89121450e+06 -112001728. 2.08310181e+03 8.04925308e+01 -3.70314868e+03 1.62510327e+03 4.15603076e+03 4.15603076e+03 -12904282. 66773756. 66773756. 110947320. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.27841016e+05 3.36284607e+02 1.29584442e+02 1.33554672e+02 1.34831223e+02 4.01550507e+02 2.46744598e+02 4.43232994e+01 4.41924133e+01 4.31354065e+01 4.25746651e+01 4.33647804e+01 -1.29925583e+02 -2.51684540e+02 1.16408195e+02 -5.68840332e+02 -1.57403088e+03 2.00115247e+03 8.52594971e+02 9.21852875e+01 1.08737541e+02 1.12938919e+02 1.10261894e+02 1.13974190e+02 1.17308853e+02 1.14381210e+02 3.68227295e+02 2.29421997e+02 4.25814209e+01 4.27679214e+01 4.30063133e+01 4.30203590e+01 4.31489639e+01 4.34443283e+01 -1.08133705e+02 -2.10258514e+02 9.99014130e+01 -5.02437714e+02 -1.37329126e+03 -13072694. 2.64824653e+09 35040460. 1.87418530e+03 8.18036438e+02 1.22805847e+02 1.15503906e+02 1.17945816e+02 1.18731522e+02 1.19451843e+02 1.20520348e+02 1.19129631e+02 3.28065643e+02 2.04259506e+02 4.34804688e+01 4.35296440e+01 4.28216820e+01 4.27906494e+01 4.24341164e+01 4.27714729e+01 4.24394569e+01 4.18433456e+01 4.18851738e+01 4.14798203e+01 4.16790390e+01 4.15037346e+01 4.09857178e+01 4.09695549e+01 4.12589188e+01 4.10798416e+01 4.08941040e+01 4.08165855e+01 4.11263542e+01 4.09379768e+01 4.09469910e+01 4.06785507e+01 4.04737206e+01 4.00489502e+01 3.95939140e+01 3.98502007e+01 3.95969391e+01 3.97676201e+01 3.94693375e+01 3.94132996e+01 3.90439224e+01 3.91955376e+01 3.91296501e+01 3.94534187e+01 3.91572037e+01 3.86808052e+01 3.80645180e+01 3.81555901e+01 3.87996445e+01 3.81719780e+01 3.79728737e+01 3.76460953e+01 3.77755432e+01 3.76563187e+01 3.73998985e+01 3.76444130e+01 3.73731880e+01 3.71484299e+01 3.68974380e+01 3.70639915e+01 3.68911629e+01 3.67418365e+01 3.65397110e+01 3.65220909e+01 3.64170761e+01 3.62486038e+01 3.46605492e+01 3.47630196e+01 3.76154747e+01 3.74321594e+01 3.54624519e+01 3.51170387e+01 3.50968628e+01 3.50394516e+01 3.48892326e+01 3.46535225e+01 3.44585915e+01 3.42695503e+01 3.42385178e+01 3.39793968e+01 3.38232880e+01 3.35589867e+01 3.34088707e+01 3.32943230e+01 3.32856598e+01 3.31218796e+01 3.28218536e+01 3.27523499e+01 3.25094872e+01 3.23317528e+01 3.22630615e+01 3.20066147e+01 3.17720795e+01 3.15724068e+01 3.13569927e+01 3.12153664e+01 3.10601826e+01 3.08572636e+01 3.05877285e+01 3.02060375e+01 3.01341324e+01 3.01039715e+01 2.98016720e+01 2.96370296e+01 2.95523224e+01 2.93409576e+01 2.90529442e+01 2.88900394e+01 2.87298107e+01 2.85097675e+01 2.82655487e+01 2.80565147e+01 2.78609028e+01 2.76953793e+01 2.74844646e+01 2.72813969e+01 2.70854721e+01 2.68860912e+01 2.66800232e+01 2.64705563e+01 2.62674675e+01 2.60438118e+01 2.58186111e+01 2.55880108e+01 2.53531303e+01 2.51470985e+01 2.49667015e+01 2.47943993e+01 2.45985870e+01 2.43788528e+01 2.41395874e+01 2.39059849e+01 2.36685753e+01 2.34344215e+01 2.31912327e+01 2.29676857e+01 2.27497768e+01 2.24915333e+01 2.22078190e+01 2.20026741e+01 2.17655010e+01 2.15679874e+01 2.13603573e+01 2.10967674e+01 2.08557587e+01 2.06265049e+01 2.04059372e+01 2.01496487e+01 1.99704037e+01 1.97345581e+01 1.94220829e+01 1.92084351e+01 1.89674702e+01 1.86953983e+01 1.84133053e+01 1.81824360e+01 1.79375439e+01 1.77194424e+01 1.78835793e+01 1.80569439e+01 1.69793758e+01 -2.35497665e+01 -4.32949715e+01 9.50088882e+01 9.63930893e+01 1.26440865e+02 7.37902908e+01 1.64207497e+01 9.72358990e+00 8.40687561e+00 1.13143473e+01 1.30941525e+01 1.40573130e+01 1.45839491e+01 1.38235655e+01 8.52409821e+01 7.07913208e+01 -4.57128204e+02 -39760512. 61125704. -21796014. 9.37154724e+02 3.89129395e+02 1.24983574e+02 3.85430176e+02 9.24474548e+02 7.71617812e+05 45134852. 122460480. -41054408. -30025056. 216877728. -6.71916382e+02 -2.07749985e+02 1.29402695e+02 6.88956680e+01 -8.02003479e+01 4.12728348e+01 1.78772461e+02 5.86301689e+01 6.88595428e+01 6.19976959e+01 4.90083504e+01 -8.55399704e+01 -6.32308121e+01 1.43449524e+02 1.45010242e+01 5.14488907e+01 8.66462631e+01 -1.04250763e+02 4.36684647e+01 5.29312439e+01 -3.98040657e+01 4.67450857e+00 2.04298744e+01 -1.69177036e+01 9.79186058e+00 2.32576580e+01 8.24680042e+00 8.93875885e+00 2.58212757e+01 1.80091248e+01 7.19506836e+00 1.02416468e+01 1.47719070e+02 -4.83717499e+01 -4.47866783e+01 2.07281998e+02 2.08290558e+02 6.46823807e+01 4.48717575e+01 3.00629768e+01 3.07914219e+01 2.97913208e+01 3.15639858e+01 3.02779140e+01 2.99788933e+01 2.89281273e+01 2.79652348e+01 2.80828934e+01 2.67975502e+01 2.70329895e+01 2.60863152e+01 2.54681759e+01 2.29449749e+01 2.22226753e+01 2.20898724e+01 1.91681023e+01 -2.60200195e+02 -1.60983765e+02 -6.66977310e+00 -7.39380693e+00 -7.25171518e+00 -7.56340885e+00 -7.95687675e+00 -8.81507587e+00 -9.06832409e+00 -9.81295490e+00 -9.16997337e+00 -9.23481083e+00 -8.73045635e+00 -8.83513260e+00 -9.03327274e+00 -9.52760220e+00 -1.00560188e+01 -1.04020643e+01 -9.88050079e+00 -1.05659571e+01 -1.13394575e+01 -1.12925663e+01 -1.10005426e+01 -1.19316568e+01 -1.22469378e+01 -1.24573278e+01 -1.25464687e+01 -1.24475794e+01 -1.30794477e+01 -1.31583071e+01 -1.36161299e+01 -1.40505190e+01 -1.39911423e+01 -1.40754948e+01 -1.42492542e+01 -1.45131521e+01 -1.51689587e+01 -1.55805426e+01 -1.60611973e+01 -1.60668564e+01 -1.58978109e+01 -1.61675606e+01 -1.63223419e+01 -1.71682758e+01 -1.54879122e+01 -1.60555592e+01 -1.64081726e+01 -1.82831059e+01 -1.84278221e+01 -1.77572556e+01 -1.70378933e+01 -1.84785690e+01 -1.96381607e+01 -1.86857071e+01 -1.84949474e+01 -1.97095528e+01 -2.11374531e+01 -2.02944508e+01 -2.02179184e+01 -2.01361198e+01 -2.03564358e+01 -2.08591347e+01 -2.12189007e+01 -2.15597668e+01 -2.17558327e+01 -2.21395435e+01 -2.25629025e+01 -2.33522072e+01 -2.26092224e+01 -2.30549011e+01 -2.36496181e+01 -2.36953678e+01 -2.37536526e+01 -2.35951519e+01 -2.36117210e+01 -2.39640293e+01 -2.38222637e+01 -2.50302181e+01 -2.50882187e+01 -2.50262051e+01 -2.52170811e+01 -2.54904499e+01 -2.60870972e+01 -2.64205856e+01 -2.63980846e+01 -2.67795353e+01 -2.71289940e+01 -2.66866817e+01 -2.69603977e+01 -2.74835720e+01 -2.76443386e+01 -2.78214359e+01 -2.80755424e+01 -2.72463875e+01 -2.72461815e+01 -2.86267948e+01 -2.85867977e+01 -2.86311264e+01 -2.87042828e+01 -2.87815075e+01 -2.92887650e+01 -2.96879215e+01 -2.98644238e+01 -3.06302357e+01 -3.06392059e+01 -2.98700333e+01 -3.08548336e+01 -3.16312370e+01 -3.13913593e+01 -3.12068844e+01 -3.12668343e+01 -3.04532356e+01 -3.06087208e+01 -3.20438499e+01 -3.24630775e+01 -3.22488747e+01 -3.24157448e+01 -3.26264877e+01 -3.27102127e+01 -3.29715309e+01 -3.30712166e+01 -3.34875755e+01 -3.37378807e+01 -3.36566162e+01 -3.38826408e+01 -3.40911903e+01 -3.42702408e+01 -3.33254662e+01 -3.38003578e+01 -3.59966850e+01 -3.57519646e+01 -3.48935013e+01 -3.52583618e+01 -3.51193237e+01 -3.52534790e+01 -3.59040680e+01 -3.56588974e+01 -3.48985863e+01 -3.56880417e+01 -3.59612503e+01 -3.57706261e+01 -3.65209503e+01 -3.66391716e+01 -3.68387413e+01 -3.71055069e+01 -3.81882668e+01 -3.75003395e+01 -3.64388123e+01 -3.74657745e+01 -3.84257469e+01 -3.84861221e+01 -3.74183273e+01 -3.75602493e+01 -3.77841797e+01 -3.78281326e+01 -3.80430832e+01 -3.87143478e+01 -3.91527138e+01 -3.90241432e+01 -3.91119690e+01 -3.98699837e+01 -3.97470627e+01 -3.95522041e+01 -3.90424309e+01 -3.91470222e+01 -3.94054222e+01 -3.97115593e+01 -4.04445190e+01 -4.04023743e+01 -3.98741646e+01 -3.99445152e+01 -3.99729347e+01 -3.99972572e+01 -4.00827637e+01 -4.01547546e+01 -4.06777039e+01 -4.05038643e+01 -4.07580147e+01 -4.02787094e+01 -4.06364326e+01 -4.15851707e+01 -4.20326653e+01 -4.15668221e+01 -4.13532944e+01 -4.11359024e+01 -4.18062859e+01 -4.19705734e+01 -4.22801628e+01 -4.20375671e+01 -4.17368622e+01 -4.15328560e+01 -4.16655464e+01 -4.19034081e+01 -4.26084366e+01 -4.24593048e+01 -4.20743217e+01 -4.21957436e+01 -4.21062355e+01 -4.19594536e+01 -4.17931366e+01 -4.17717476e+01 -4.18539009e+01 -4.22391548e+01 -4.20200348e+01 -4.20848541e+01 -4.24146080e+01 -4.30453148e+01 -4.29041100e+01 -4.29895287e+01 -4.37320709e+01 -4.34665565e+01 -4.27428932e+01 -4.22501945e+01 -4.26024055e+01 -4.31474724e+01 -4.33193512e+01 -4.36909790e+01 -4.36948090e+01 -4.38665123e+01 -4.37746887e+01 -4.31899796e+01 -4.28612366e+01 -4.31590843e+01 -4.34289703e+01 -4.35073395e+01 -4.35553970e+01 -4.31989746e+01 -4.23470306e+01 -4.28823471e+01 -4.37444916e+01 -4.31655388e+01 -4.29514351e+01 -4.35731316e+01 -4.33943367e+01 -4.33861771e+01 -4.40199242e+01 -4.34951668e+01 -4.32479248e+01 -4.32660904e+01 -4.37197227e+01 -4.30404663e+01 -4.30469093e+01 -4.31715927e+01 -4.33703537e+01 -4.31111832e+01 -4.33437996e+01 -4.40976753e+01 -4.43488922e+01 -4.34630470e+01 -4.23413963e+01 -4.23642693e+01 -4.29449577e+01 -4.35338860e+01 -4.32837906e+01 -4.28587494e+01 -4.23663216e+01 -4.29127846e+01 -4.27003708e+01 -4.22641869e+01 -4.18719940e+01 -4.29933395e+01 -4.40285149e+01 -4.27197227e+01 -4.28461456e+01 -4.27223740e+01 -4.32241364e+01 -4.31466942e+01 -4.33706551e+01 -4.30095253e+01 -4.30691528e+01 -4.27520676e+01 -4.25725250e+01 -4.19038353e+01 -4.29200211e+01 8.82515335e+01 1.75837051e+02 -3.15025543e+02 -6.91218033e+01 1.72448502e+02 -1.15231239e+02 -1.16589737e+02 -1.17100296e+02 -1.17441704e+02 -2.82704712e+02 -2.66318085e+02 1.96879292e+01 1.47086105e+02 -1.13396645e+02 -1.15346977e+02 -1.19456795e+02 -2.73233215e+02 -2.32938644e+02 -1.49925064e+02 1.12131090e+01 1.45789474e+02 -2.72433716e+02 -9.77517166e+01 7.73114548e+01 -1.15979256e+02 -1.17412315e+02 -1.18310135e+02 -1.20093102e+02 -1.17648483e+02 -1.17155670e+02 -1.18536301e+02 -1.17899742e+02 -1.17787323e+02 -1.19245186e+02 -1.19123543e+02 -1.18755524e+02 -1.18469208e+02 -1.17844612e+02 -1.19147934e+02 -2.43954910e+02 -6.23733749e+01 1.09438728e+02 -1.15841263e+02 -1.19386307e+02 -1.20459915e+02 -1.18181183e+02 -1.17442764e+02 -1.14469124e+02 -1.13174950e+02 -1.06516647e+02 2.19225815e+02 6.53241699e+02 101152008. -21495192. -79362632. 408795072. 131336840. -9.63329468e+02 -1.84940430e+02 4.81950134e+02 -9.90293884e+02 -4.08760010e+02 -1.00290932e+02 -7.51335144e+01 -3.66938141e+02 -8.47589539e+02 134777536. -13814460. 68720424. 3.53208435e+02 -9.13526154e+01 -1.42137604e+02 -6.35426331e+01 -3.91876259e+01 -3.72930946e+01 -3.81075630e+01 -3.39149971e+01 -3.32036057e+01 -3.43599548e+01 -9.54562607e+01 -5.61767530e+00 -3.29174042e+01 -1.07582664e+02 2.14530430e+01 3.30342722e+00 -3.14793530e+01 -3.09322948e+01 -3.09333801e+01 -3.07664108e+01 -3.06270638e+01 -3.04055328e+01 -3.02125530e+01 -3.00990620e+01 -2.98552208e+01 -2.96464367e+01 -2.94744778e+01 -2.92701645e+01 -2.90552235e+01 -2.88375854e+01 -2.86044235e+01 -2.83963394e+01 -2.81844769e+01 -2.79744873e+01 -2.77793045e+01 -2.75683193e+01 -2.73754139e+01 -2.71716366e+01 -2.69524727e+01 -2.67239246e+01 -2.65155067e+01 -2.62812443e+01 -2.60400124e+01 -2.58433399e+01 -2.56891899e+01 -2.55383949e+01 -2.53431034e+01 -2.51160908e+01 -2.48937283e+01 -2.46665382e+01 -2.44674149e+01 -2.42617512e+01 -2.40270138e+01 -2.37892761e+01 -2.35553513e+01 -2.33133240e+01 -2.31317272e+01 -2.29020081e+01 -2.26517696e+01 -2.23998222e+01 -2.21649952e+01 -2.19464951e+01 -2.17544460e+01 -2.15008945e+01 -2.12511978e+01 -2.11117897e+01 -2.09321270e+01 -2.06403522e+01 -2.03856678e+01 -2.02376347e+01 -1.98570671e+01 -1.94923458e+01 -1.93393326e+01 -1.91425400e+01 -1.89222202e+01 -1.87086678e+01 -1.84527626e+01 -1.81006393e+01 -1.79117661e+01 -1.76807995e+01 -1.74725208e+01 -1.71736965e+01 -1.69088593e+01 -1.66070557e+01 -1.62859001e+01 -1.61650734e+01 -1.59440165e+01 -1.57737980e+01 -1.54133310e+01 -1.51760235e+01 -1.52622252e+01 -1.50404940e+01 -1.41856422e+01 -1.38665619e+01 -1.38303823e+01 -1.37491446e+01 -1.34976645e+01 -1.33338223e+01 -1.30674162e+01 -1.25566387e+01 -1.21603680e+01 -1.20636797e+01 -1.17313070e+01 -1.16286516e+01 -1.13911457e+01 -1.11242857e+01 -1.11176643e+01 -1.07767878e+01 -9.49841881e+00 -9.38517666e+00 -9.83591938e+00 -9.75617504e+00 -9.89219284e+00 -9.65779114e+00 -9.08631134e+00 -9.40695381e+00 -9.19823265e+00 -7.34899521e+00 -6.48834372e+00 -6.63016129e+00 -6.99451923e+00 -6.47682381e+00 -6.12263823e+00 -6.17613173e+00 -6.12299776e+00 -5.88533735e+00 -5.67742634e+00 -5.32673979e+00 -4.94388342e+00 -4.63197279e+00 -4.30978870e+00 -3.98165965e+00 -3.67559576e+00 -3.58079410e+00 -3.55973363e+00 -3.65972805e+00 -3.64555073e+00 -3.20757341e+00 -2.49683809e+00 -2.29877234e+00 -2.62616324e+00 -2.86286569e+00 -2.51056671e+00 -5.13989830e+00 -8.78588557e-01 2.67336345e+00 8.14688765e-03 5.17549038e-01 -6.76595509e-01 -1.28878987e+00 -2.09900212e+00 -1.60698116e+00 6.63507760e-01 2.78790331e+00 3.53507757e+00 3.14767218e+00 2.29192162e+00 2.41767573e+00 2.77026391e+00 2.99300981e+00 2.57957101e+00 2.95156932e+00 2.89044809e+00 3.53525209e+00 3.07271624e+00 -1.11950359e+01 -1.76793671e+01 -4.13074112e+00 -1.51813934e+02 -2.59483551e+02 -2.36545296e+01 -4.20534592e+01 -9.55713501e+01 -1.66758102e+02 -9.07993774e+02 -2.21079175e+03 -58799652. 47113444. 1.53215100e+03 6.37002319e+02 -1.43346376e+01 -1.35887642e+01 -1.30630379e+01 -1.32825584e+01 -1.14019556e+01 -6.80490303e+00 -9.27553749e+00 -1.03040466e+01 -7.73737049e+00 -8.62203884e+00 -6.39266491e+00 -7.29959822e+00 -8.60451412e+00 -7.93119097e+00 3.09938782e+02 1.25025110e+01 -3.02447235e+02 4.81757317e+01 -6.28593018e+02 -2.44084930e+02 9.15346863e+02 4.02999229e+01 8.09021072e+01 8.37792282e+01 2.65353737e+01 3.37831177e+02 2.14819626e+02 1.59951229e+01 1.59582634e+01 -1.71123856e+02 -3.01236908e+02 1.52002132e+00 -4.79470682e+00 -2.30022106e+01 -1.20199356e+02 -1.05186975e+03 -4.71193115e+03 -117234712. 0. 0. 0. 0. 0. 0. 0. 0. 0. -208640960. -208640960. -208640960. 0. 0. 0. 0. -163331632. -163331632. -163331632. 0. 0. -22548212. -9.95693812e+05 -1.00007012e+06 -3.83615025e+06 258651632. -315742368. 291674752. 291674752. 291674752. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.34037371e+10 -2.34037371e+10 -2.34037371e+10 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. -1269522176. -1269522176. -1269522176. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1070082752. -1070082752. -1070082752. 0. 0. 0. 0. 0. 0. 0. 0. 0. -299497312. 31874760. -1.61245250e+05 19978098. 39169020. -45109816. 2.89121450e+06 -112001728. 2.08310181e+03 8.04925308e+01 -3.70314868e+03 1.62510327e+03 4.15603076e+03 4.15603076e+03 -12904282. 66773756. 66773756. 110947320. 0. 0. 0. 0. -230937376. -230937376. -230937376. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.41915771e+10 1.41915771e+10 1.41915771e+10 0. 0. 0. 0. 0. 0. 0. -202396224. -202396224. -202396224. 0. 348427424. 43626224. 4.61062250e+06 26787830. 28836338. 2.19325903e+03 9.05063904e+02 9.44977264e+01 9.22619095e+01 8.72815018e+01 8.29410172e+01 8.80868301e+01 -6.13309570e+02 -1.63273889e+03 2433462. 16844692. 1603474432. 1.43568578e+05 -1.51464246e+03 -7.78744751e+02 8129201. 17316812. 16476392. 9.15052185e+02 7.53367233e+01 -7.40845703e+02 1.94223035e+03 8.28484375e+02 9.56491852e+01 9.61798553e+01 9.78198242e+01 9.72384796e+01 9.80506592e+01 1.01842812e+02 1.58116531e+02 -4.22634338e+02 -1.30415161e+03 4.70678076e+03 -68582208. 65399000. 0. 0. 3.03570234e+04 -1.24332739e+03 -6.39604980e+02 -59547860. -69662304. -26793158. 92265672. 38447048. 12121488. 1.73395386e+03 7.39679199e+02 1.10278740e+02 3.05378571e+02 1.85230896e+02 3.32957191e+01 3.33486443e+01 3.34636192e+01 3.34415207e+01 3.32737312e+01 3.31526833e+01 3.26109009e+01 3.23711052e+01 3.26284714e+01 3.30539322e+01 3.32269287e+01 3.34277611e+01 3.36183319e+01 3.33244705e+01 3.27615585e+01 3.31574783e+01 3.32177048e+01 3.33491974e+01 3.30149498e+01 3.35097160e+01 3.33318100e+01 -7.36630096e+01 -1.40168411e+02 2.55240555e+02 1.54870895e+02 3.20663147e+01 3.26532784e+01 3.28276711e+01 3.29852371e+01 -6.49329987e+01 -1.23294815e+02 2.41025040e+02 1.47129959e+02 3.25001793e+01 3.27413101e+01 3.30449028e+01 3.28026199e+01 3.26183090e+01 3.26347504e+01 3.27123070e+01 3.27477646e+01 3.27396584e+01 3.28608246e+01 3.27497063e+01 3.26302071e+01 3.24998322e+01 3.28218269e+01 3.29587555e+01 3.27807999e+01 3.24626846e+01 3.22902679e+01 3.23896599e+01 3.23683929e+01 3.07691174e+01 3.08951550e+01 3.42292709e+01 3.40913506e+01 3.21942940e+01 3.22024956e+01 3.21414871e+01 3.21807060e+01 3.21379662e+01 3.21021500e+01 3.19918461e+01 3.20378494e+01 3.20541039e+01 3.20058746e+01 3.19161301e+01 3.18528900e+01 3.17834091e+01 3.16497993e+01 3.16783257e+01 3.16358566e+01 3.14887657e+01 3.14562626e+01 3.14210796e+01 3.13579044e+01 3.13212662e+01 3.10878658e+01 3.10190067e+01 3.09160156e+01 3.08925610e+01 3.07997513e+01 3.07191315e+01 3.06619186e+01 3.06142693e+01 3.04621620e+01 3.04333248e+01 3.04381466e+01 3.03086472e+01 3.02117348e+01 3.01848011e+01 3.01436768e+01 2.99791279e+01 2.99354076e+01 2.98823433e+01 2.97815838e+01 2.96535149e+01 2.95594883e+01 2.94524937e+01 2.93878193e+01 2.92756996e+01 2.91437721e+01 2.90156326e+01 2.89397392e+01 2.88737850e+01 2.87884769e+01 2.86893005e+01 2.85924015e+01 2.84819412e+01 2.83682671e+01 2.82592278e+01 2.81778297e+01 2.80877686e+01 2.79736748e+01 2.78572330e+01 2.77214470e+01 2.75945702e+01 2.74890213e+01 2.73936348e+01 2.72976589e+01 2.71854477e+01 2.70760956e+01 2.69623280e+01 2.68345070e+01 2.66986046e+01 2.66305656e+01 2.65094337e+01 2.63956604e+01 2.62757607e+01 2.60838108e+01 2.59786816e+01 2.58870068e+01 2.58145714e+01 2.56800385e+01 2.55545254e+01 2.54127388e+01 2.52422409e+01 2.51372528e+01 2.50440903e+01 2.48593616e+01 2.46892357e+01 2.45347557e+01 2.44963112e+01 2.42568436e+01 2.41354809e+01 2.40071697e+01 2.38236656e+01 2.36718063e+01 2.34828148e+01 2.34042797e+01 2.36246700e+01 2.35168705e+01 2.20877228e+01 2.04988937e+01 -2.58073139e+01 -4.94476929e+01 1.09333199e+02 1.10842140e+02 1.07077858e+02 1.45832138e+02 8.92633820e+01 1.70363235e+01 1.36438385e+02 3.54193382e+01 4.09299812e+01 4.19745605e+02 -21796014. -58903556. 49549188. 5.84994727e+04 1974223616. -373007904. 0. 0. 0. 0. 0. 0. -5.60107148e+04 2.61273364e+03 1.27382861e+03 1.38452425e+06 3.78554297e+03 7.02809375e+03 1.84604082e+04 9267628. 1.20125412e+06 5.46767438e+05 5.53489850e+06 3.74871216e+03 1.87359668e+03 5.30009570e+03 6.13708557e+02 2.00942322e+03 2.66021289e+03 -3.35302429e+02 3.98184448e+02 4.17823334e+02 -2.19842957e+02 -2.11843323e+02 2.36577206e+01 1.98696182e+02 1.53859619e+02 2.91562958e+02 2.11027069e+02 2.14124115e+02 4.45861420e+02 3.61964600e+02 2.33864517e+02 2.72032196e+02 1.36999927e+03 -2.97654816e+02 2.63312164e+02 1.42253296e+03 2.04539023e+04 -20505436. 3.81468875e+05 2.05531475e+06 5558920. 4.01657850e+06 -22403872. -76137152. -37140264. -23039426. -109787376. 17467412. 38555604. 20179576. -15140391. -14528468. -16909800. -40866256. -40941412. 28563646. -1.40033813e+03 -5.50630249e+02 5.39441605e+01 -2.52189697e+02 -1.47341537e+02 7.07291079e+00 5.93671179e+00 5.83344555e+00 5.88271761e+00 5.70281601e+00 5.80497408e+00 5.90052319e+00 6.24673128e+00 6.49087572e+00 6.38420725e+00 6.20768261e+00 5.72973347e+00 5.46364832e+00 5.85937881e+00 5.85983419e+00 4.98897505e+00 4.86394501e+00 4.82741690e+00 4.50123978e+00 4.00526810e+00 3.94747281e+00 4.13940477e+00 3.82708335e+00 3.38656521e+00 2.98152447e+00 2.38994551e+00 2.52460217e+00 2.43194890e+00 2.31324053e+00 2.60580230e+00 2.42357254e+00 1.77415979e+00 1.06650341e+00 9.51299667e-01 1.05156684e+00 1.03373408e+00 7.83663929e-01 -3.47623646e-01 -8.41933072e-01 6.24256134e-01 1.24717164e+00 4.04880829e-02 -1.80068743e+00 -1.79347873e+00 -8.18761647e-01 -4.45097566e-01 -6.87621653e-01 -1.69314206e+00 -1.70291448e+00 -1.68164992e+00 -2.56081963e+00 -2.40860558e+00 -2.47832632e+00 -2.75755382e+00 -3.04542756e+00 -3.11941338e+00 -3.42522120e+00 -3.67031026e+00 -3.53416228e+00 -4.02731562e+00 -3.72214651e+00 -4.35525751e+00 -5.17914820e+00 -4.28158903e+00 -5.03640461e+00 -5.90299129e+00 -4.73339224e+00 -5.14854717e+00 -5.15252781e+00 -5.53808546e+00 -5.66189718e+00 -6.77876472e+00 -7.45339727e+00 -6.24052382e+00 -6.30757475e+00 -7.81160259e+00 -7.95082808e+00 -7.63557816e+00 -7.90049601e+00 -7.84292603e+00 -7.61081457e+00 -8.40194416e+00 -8.46430492e+00 -8.73137856e+00 -9.23449612e+00 -9.49870777e+00 -9.76848888e+00 -9.81168079e+00 -9.43455791e+00 -9.71714687e+00 -1.04350224e+01 -1.04462862e+01 -1.03747234e+01 -1.13172026e+01 -1.03809309e+01 -1.08022041e+01 -1.22037039e+01 -1.22603283e+01 -1.24482803e+01 -1.19013548e+01 -1.12909822e+01 -1.28139868e+01 -1.34480715e+01 -1.32001991e+01 -1.28559427e+01 -1.29008884e+01 -1.18731556e+01 -1.20645781e+01 -1.35335693e+01 -1.38716335e+01 -1.41644354e+01 -1.43474607e+01 -1.45139732e+01 -1.46123295e+01 -1.48931694e+01 -1.49197502e+01 -1.54974947e+01 -1.56331520e+01 -1.56091375e+01 -1.57024336e+01 -1.59617920e+01 -1.57246914e+01 -1.50611639e+01 -1.56486206e+01 -1.77466507e+01 -1.78636074e+01 -1.71529922e+01 -1.70997429e+01 -1.69963131e+01 -1.73714943e+01 -1.74767513e+01 -1.78950825e+01 -1.74937801e+01 -1.73154335e+01 -1.79395828e+01 -1.82200794e+01 -1.85189056e+01 -1.86787910e+01 -1.90988064e+01 -1.93525238e+01 -1.95842953e+01 -1.94272041e+01 -1.92569656e+01 -1.94704094e+01 -1.99184494e+01 -2.00355034e+01 -2.01733150e+01 -2.02541714e+01 -2.04875221e+01 -2.04851894e+01 -2.09101295e+01 -2.13013821e+01 -2.16621761e+01 -2.10598850e+01 -2.13708420e+01 -2.20838890e+01 -2.22592430e+01 -2.20815105e+01 -2.19764118e+01 -2.20704021e+01 -2.24659500e+01 -2.25192680e+01 -2.29892673e+01 -2.30557880e+01 -2.28082714e+01 -2.30112534e+01 -2.34701023e+01 -2.35552044e+01 -2.30627060e+01 -2.30619869e+01 -2.35133095e+01 -2.39674358e+01 -2.41274509e+01 -2.35661278e+01 -2.38009682e+01 -2.44490852e+01 -2.45760517e+01 -2.45029984e+01 -2.44557590e+01 -2.44930649e+01 -2.48542194e+01 -2.49124718e+01 -2.54711151e+01 -2.54735336e+01 -2.56645870e+01 -2.58740120e+01 -2.61624336e+01 -2.60598240e+01 -2.59582157e+01 -2.60521088e+01 -2.60694771e+01 -2.66113758e+01 -2.66828995e+01 -2.71964741e+01 -2.68672047e+01 -2.70156059e+01 -2.64195900e+01 -2.64253006e+01 -2.68694782e+01 -2.73051853e+01 -2.76585312e+01 -2.75133572e+01 -2.77674942e+01 -2.77162552e+01 -2.76887398e+01 -2.76631317e+01 -2.82485294e+01 -2.87230282e+01 -2.81913223e+01 -2.83181057e+01 -2.85133095e+01 -2.93477077e+01 -2.91711464e+01 -2.88897190e+01 -2.89244881e+01 -2.88382244e+01 -2.89069805e+01 -2.91826515e+01 -2.92232475e+01 -2.96163292e+01 -2.95968876e+01 -2.96997604e+01 -2.90035191e+01 -2.97852249e+01 -3.03853168e+01 -2.96658878e+01 -3.01683598e+01 -3.07352066e+01 -3.02925625e+01 -3.08396492e+01 -3.13080063e+01 -3.11408100e+01 -2.99800720e+01 -2.99685841e+01 -3.02053394e+01 -3.05298862e+01 -3.11769466e+01 -3.11383934e+01 -3.08982239e+01 -3.05765057e+01 -3.07422771e+01 -3.05333958e+01 -3.11342983e+01 -3.09760551e+01 -3.08775883e+01 -3.12788315e+01 -3.16970158e+01 -3.16660595e+01 -3.19037285e+01 -3.20678406e+01 -3.16957340e+01 -3.18149834e+01 -3.15313969e+01 -3.14916229e+01 -3.07902584e+01 -3.12391624e+01 -3.20356598e+01 -3.17692547e+01 -3.18037815e+01 -3.08747692e+01 -3.05860233e+01 -3.18673363e+01 1.10214020e+02 2.05082977e+02 -1.07785431e+02 -1.09836906e+02 -1.08524216e+02 -1.02589577e+02 -1.10386513e+02 4.33086212e+02 1.19924243e+03 -1.75342371e+03 -2.15771545e+02 1.18278235e+03 26104378. -17352914. 24793584. 48642496. -1.11016748e+04 -2.31280591e+03 -2.68373596e+02 1.41377380e+03 -11396260. -5.33868450e+06 -67458808. -1.34121465e+04 -5.07749854e+03 -1.11573376e+03 -1.55759781e+02 9.60086365e+02 -8.51973438e+03 -2.71904712e+03 1.09546448e+03 -18544556. 22900240. 33351990. -63242752. 96568344. 34836244. 470429792. 71541480. 20053986. 124439856. 20961814. -20871610. -25539894. -5.72230713e+02 -6.82263641e+01 9.79439697e+01 -1.96411636e+02 6.74885010e+02 -11944194. -3.31638750e+06 -4778284. -82562784. -8.19561250e+06 118972680. -24202808. -4.63812531e+02 -9.17881042e+02 -4.62446367e+04 0. 0. 0. 0. 0. -95126408. -95126408. -95126408. -109223440. 27409826. -13656202. -217256720. -55575880. -27044612. -4.13756622e+02 -1.79700333e+02 -3.52632446e+01 -3.50024529e+01 -1.27144661e+01 -9.81311340e+01 -1.79793182e+02 -1.16476410e+02 3.43151512e+01 -5.63902969e+01 -1.52570679e+02 3.17955837e+01 9.87025547e+00 -3.18672485e+01 -3.12168999e+01 -3.12904949e+01 -3.13161392e+01 -3.11815414e+01 -3.10778294e+01 -3.10316372e+01 -3.08527889e+01 -3.09041290e+01 -3.09423752e+01 -3.07732601e+01 -3.06753864e+01 -3.06315536e+01 -3.06556683e+01 -3.05630207e+01 -3.03491249e+01 -3.02975845e+01 -3.02041588e+01 -3.01025600e+01 -3.00774574e+01 -3.00218983e+01 -2.99183064e+01 -2.97991219e+01 -2.97597885e+01 -2.96797256e+01 -2.95721054e+01 -2.94181080e+01 -2.92951450e+01 -2.92141590e+01 -2.91381454e+01 -2.90228271e+01 -2.88986855e+01 -2.87579365e+01 -2.86301994e+01 -2.85263748e+01 -2.84471760e+01 -2.83385124e+01 -2.82538471e+01 -2.81342392e+01 -2.80168839e+01 -2.78946285e+01 -2.77884960e+01 -2.76987247e+01 -2.75647621e+01 -2.74574203e+01 -2.73644047e+01 -2.72731991e+01 -2.71433010e+01 -2.69806938e+01 -2.68925934e+01 -2.67707710e+01 -2.66902637e+01 -2.65987949e+01 -2.65354347e+01 -2.64216099e+01 -2.63412209e+01 -2.62124825e+01 -2.60644264e+01 -2.57825642e+01 -2.59068661e+01 -2.55249214e+01 -2.52242470e+01 -2.52037735e+01 -2.51099110e+01 -2.49494457e+01 -2.47610626e+01 -2.46150188e+01 -2.45415421e+01 -2.44204044e+01 -2.43457355e+01 -2.41604366e+01 -2.39427853e+01 -2.37955418e+01 -2.35808544e+01 -2.34363327e+01 -2.34211922e+01 -2.33457069e+01 -2.32374611e+01 -2.30191689e+01 -2.28594227e+01 -2.30465202e+01 -2.27860641e+01 -2.20525055e+01 -2.20484467e+01 -2.22360229e+01 -2.21869164e+01 -2.17748947e+01 -2.17286243e+01 -2.16410980e+01 -2.13343868e+01 -2.11395893e+01 -2.09504642e+01 -2.07207165e+01 -2.07506256e+01 -2.04875050e+01 -2.02254276e+01 -2.03870964e+01 -2.01942654e+01 -1.95735989e+01 -1.93110390e+01 -1.96358547e+01 -1.92805443e+01 -1.95505333e+01 -1.93705235e+01 -1.91309490e+01 -1.96701469e+01 -1.93841915e+01 -1.73734703e+01 -1.68497963e+01 -1.77407131e+01 -1.79452820e+01 -1.79394226e+01 -1.76802979e+01 -1.75176544e+01 -1.70339909e+01 -1.69498158e+01 -1.69172802e+01 -1.68524837e+01 -1.68638973e+01 -1.65893517e+01 -1.63218670e+01 -1.59739704e+01 -1.58317966e+01 -1.56814690e+01 -1.57073393e+01 -1.56184988e+01 -1.59944305e+01 -1.55930376e+01 -1.49102440e+01 -1.49011631e+01 -1.56093788e+01 -1.62468319e+01 -1.65184383e+01 -3.50619087e+01 -2.44693394e+01 4.71698093e+00 -5.14112091e+00 -1.28337641e+01 -1.36066275e+01 -1.57178917e+01 -1.40763559e+01 -8.90120125e+00 -2.96656284e+01 -2.34508724e+01 3.60309768e+00 -4.51377535e+00 -1.09314184e+01 -1.18055983e+01 -1.20470591e+01 -1.21717358e+01 -1.20486975e+01 -1.19773998e+01 -1.31071968e+01 -2.80181675e+01 -3.01728554e+01 -2.03627975e+02 -3.83774780e+02 2.53888657e+02 -6.64953384e+01 -6.80368347e+02 12111216. -9.31840312e+05 -7.02913875e+05 -4237676. 106256704. 24846358. 0. 0. 115571912. -239138544. 15968233. -21014046. 7.87166850e+06 -31939452. 22158216. -18587394. -6.34972050e+06 -15971887. 7.81233093e+02 6.51240969e+00 -7.97393616e+02 12196080. 98601536. -29528852. 1.43628296e+03 -9.69075699e+01 -1.73849414e+03 2.43010762e+04 30515686. 22869670. -95547704. 2.37869094e+05 1.18380875e+05 1.39682344e+05 -1.41149362e+06 2.14071997e+03 8.53976196e+02 -4.84118538e+01 -5.00951157e+01 -9.84890015e+02 -2.48816870e+03 63405796. 835709184. -8714612. -1.86029844e+05 -4.99730944e+09 -161156000. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -208640960. -208640960. -208640960. 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. 0. 0. 0. 0. 0. 0. 0. -2.34037371e+10 -2.34037371e+10 -2.34037371e+10 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. -1269522176. -1269522176. -507511040. -270754208. -270754208. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -535041376. -535041376. -535041376. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.54082688e+09 -3.54082688e+09 -3.54082688e+09 1155655296. 4348127. 4348127. -6452141. 33386878. 33386878. 55473660. 0. 0. 0. 0. -230937376. -230937376. -230937376. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.41915771e+10 1.41915771e+10 1.41915771e+10 0. 0. 0. 0. 0. 0. 0. -202396224. -202396224. -202396224. 0. 0. 0. 0. 0. 0. -113311184. -13548414. -3629071. 3.68873225e+06 -32110310. -4.17955525e+06 3.06138875e+06 -55973468. -47914780. 0. 0. 0. 169540176. 169540176. 169540176. 0. 0. 0. 262940768. 262940768. 262940768. -54913952. -16588549. 3.92021225e+06 5903341. -15103611. 19440576. 13298400. 80088672. 6.50912266e+04 -6940551. -194486864. 65399000. 65399000. 65399000. 0. 0. 15546382. 15546382. 15546382. 0. 0. 0. 0. 0. 0. 17749282. 9291197. 31575172. 8.95645264e+02 4.16040985e+02 7.56821442e+01 7.64133301e+01 7.71172562e+01 7.72094116e+01 7.57064133e+01 7.52436218e+01 7.42959518e+01 7.42338104e+01 7.49354324e+01 7.54365768e+01 7.58458710e+01 7.64210281e+01 7.78263702e+01 7.68145065e+01 7.63001633e+01 7.72158737e+01 7.78004456e+01 7.72738800e+01 7.64883041e+01 7.73984375e+01 7.86323700e+01 -1.44204498e+02 -3.53929291e+02 7.61481750e+02 3.53624146e+02 7.79860153e+01 7.92309036e+01 8.00468979e+01 8.07134171e+01 -1.20900429e+02 -2.99346741e+02 7.36691467e+02 3.43515564e+02 7.86364136e+01 7.95553665e+01 8.19531097e+01 8.17771225e+01 8.18103409e+01 8.21670837e+01 8.25681305e+01 8.28747330e+01 8.28635788e+01 8.30465393e+01 8.26488190e+01 8.18278503e+01 8.14268188e+01 8.25559998e+01 8.33271790e+01 8.35683365e+01 8.28519516e+01 8.23711700e+01 8.30401459e+01 8.32263718e+01 7.74514465e+01 7.76324921e+01 8.92700500e+01 8.93547897e+01 8.37930527e+01 8.45293274e+01 8.46669998e+01 8.44469299e+01 8.44119873e+01 8.48436737e+01 8.54226608e+01 8.58500824e+01 8.56997986e+01 8.57923126e+01 8.58209915e+01 8.58601379e+01 8.58134995e+01 8.52693939e+01 8.57118912e+01 8.55851898e+01 8.54380569e+01 8.57288513e+01 8.55071793e+01 8.57556992e+01 8.60827255e+01 8.60088196e+01 8.62812119e+01 8.63574295e+01 8.65181503e+01 8.64688187e+01 8.66544647e+01 8.68189926e+01 8.67583313e+01 8.63156357e+01 8.66385422e+01 8.68808594e+01 8.65876923e+01 8.65769424e+01 8.70353851e+01 8.70947189e+01 8.66210480e+01 8.65551376e+01 8.66413727e+01 8.65818176e+01 8.65388641e+01 8.64967117e+01 8.64198990e+01 8.63795471e+01 8.62564240e+01 8.60285721e+01 8.58908539e+01 8.59885788e+01 8.61246109e+01 8.61799469e+01 8.61691055e+01 8.61791687e+01 8.60760422e+01 8.60322876e+01 8.60219269e+01 8.59170761e+01 8.57072754e+01 8.54590454e+01 8.53978424e+01 8.54010391e+01 8.53729553e+01 8.54342422e+01 8.54267044e+01 8.53898697e+01 8.53088379e+01 8.51919098e+01 8.50795212e+01 8.50349579e+01 8.49683685e+01 8.51721954e+01 8.50753174e+01 8.49821472e+01 8.48945923e+01 8.44231110e+01 8.43870621e+01 8.45031052e+01 8.45109634e+01 8.43721466e+01 8.41440125e+01 8.38966675e+01 8.33926468e+01 8.34767838e+01 8.36702652e+01 8.32465057e+01 8.30622559e+01 8.27971039e+01 8.29361725e+01 8.23348083e+01 8.22524948e+01 8.23035583e+01 8.17804489e+01 8.17330093e+01 8.15564651e+01 8.12470779e+01 8.10365372e+01 8.07544937e+01 8.04366226e+01 8.02964172e+01 8.03076019e+01 8.04481735e+01 8.15022659e+01 8.40864563e+01 8.16694031e+01 7.56311111e+01 7.03343353e+01 -9.94101105e+01 -9.59075317e+02 31660784. -20962724. -20962724. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.38449453e+04 5.38449453e+04 5.38449453e+04 0. -49478088. -49478088. -49478088. 0. 0. 0. 0. 64191312. 14476741. 14476741. -2.59655150e+06 67390832. 38747496. 2.95345025e+06 -8.89755676e+02 1.28635227e+05 -4.49322510e+03 -4.17743164e+02 1.36378189e+02 3.31220428e+02 5.71981836e+03 4.37923281e+04 8.50664922e+04 5.94661719e+04 1.36468475e+06 2.12732703e+05 320696. 1.67332391e+05 55085824. 3.93682475e+06 -8.60568375e+05 -8.60568375e+05 -11012354. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -79423080. 19185700. -76148424. -6.04728516e+02 -2.61247406e+02 4.74813881e+01 4.35726662e+01 4.42916565e+01 4.57894821e+01 4.68599129e+01 4.83658791e+01 4.93061142e+01 5.01442032e+01 5.07065163e+01 5.13502502e+01 5.17577362e+01 5.12144165e+01 5.05932961e+01 5.06156960e+01 5.06641579e+01 4.97565613e+01 4.95477180e+01 4.93920403e+01 4.88440323e+01 4.71342964e+01 4.55629196e+01 4.62269096e+01 4.59292564e+01 4.51598434e+01 4.45610313e+01 4.33979721e+01 4.35150642e+01 4.26999626e+01 4.17629089e+01 4.26630020e+01 4.21095581e+01 4.13495598e+01 3.97184296e+01 3.95700111e+01 3.99832191e+01 3.97877159e+01 3.83209419e+01 3.56766968e+01 3.39754066e+01 3.77195129e+01 3.98597565e+01 3.57978897e+01 3.07381630e+01 2.92325840e+01 3.32683487e+01 3.54184341e+01 3.50037880e+01 3.21725235e+01 3.36551590e+01 3.38929520e+01 3.11475124e+01 3.09917545e+01 2.97152500e+01 2.88071957e+01 2.85132980e+01 2.86632671e+01 2.78600788e+01 2.73104515e+01 2.74157448e+01 2.77157478e+01 2.89948750e+01 2.69862080e+01 2.36915207e+01 2.73280697e+01 2.38494396e+01 2.04271889e+01 2.55595970e+01 2.41901913e+01 2.27724228e+01 2.24274998e+01 2.58710251e+01 2.20113735e+01 1.77161312e+01 2.05436268e+01 2.17938175e+01 1.78043652e+01 1.77451248e+01 1.89796543e+01 1.69076729e+01 1.77752743e+01 1.74717979e+01 1.57321606e+01 1.48121529e+01 1.42043886e+01 1.32171440e+01 1.21418858e+01 1.28607559e+01 1.20319071e+01 1.39136810e+01 1.27886791e+01 1.04477015e+01 1.18440599e+01 1.12386713e+01 8.27181530e+00 9.14618397e+00 8.08545876e+00 5.37884665e+00 5.34482813e+00 4.00914097e+00 6.39477730e+00 7.76504755e+00 2.08828425e+00 1.60731745e+00 3.91677332e+00 3.79175758e+00 2.92813897e+00 4.12137938e+00 4.13481140e+00 1.83802247e+00 9.64966536e-01 8.10170025e-02 -5.68268061e-01 -1.40598071e+00 -1.68588209e+00 -1.85935426e+00 -2.36044121e+00 -5.35304642e+00 -5.51693249e+00 -4.38822842e+00 -4.68572521e+00 -5.24251699e+00 -4.33361101e+00 -2.51743460e+00 -4.68831253e+00 -1.09507427e+01 -1.13518734e+01 -9.02908516e+00 -9.23139572e+00 -9.07237434e+00 -9.84536362e+00 -1.00564251e+01 -1.07454443e+01 -8.39331055e+00 -8.41981316e+00 -1.15652218e+01 -1.25504780e+01 -1.33838854e+01 -1.37206373e+01 -1.51683445e+01 -1.51819620e+01 -1.48936129e+01 -1.61788521e+01 -1.67768574e+01 -1.71385841e+01 -1.72911777e+01 -1.81689110e+01 -1.90245476e+01 -1.90673065e+01 -1.98201981e+01 -2.02677326e+01 -2.12167606e+01 -2.20506229e+01 -2.49330082e+01 -2.23486061e+01 -2.26864281e+01 -2.63046799e+01 -2.44566460e+01 -2.37023563e+01 -2.42857895e+01 -2.48168488e+01 -2.59176159e+01 -2.63890400e+01 -2.69691582e+01 -2.72544956e+01 -2.72779942e+01 -2.79875221e+01 -2.92104034e+01 -2.99340324e+01 -2.98651619e+01 -3.05058689e+01 -3.09596481e+01 -3.20578079e+01 -3.22899666e+01 -3.27032547e+01 -3.27356873e+01 -3.33872833e+01 -3.32018700e+01 -3.38020401e+01 -3.41785774e+01 -3.52886658e+01 -3.49690781e+01 -3.58667107e+01 -3.65575104e+01 -3.71267242e+01 -3.85960922e+01 -3.88779945e+01 -3.98169098e+01 -3.85892754e+01 -3.87353172e+01 -3.86776848e+01 -3.98275070e+01 -4.11768532e+01 -4.18965912e+01 -4.13344078e+01 -4.19484978e+01 -4.31835022e+01 -4.43926582e+01 -4.41880684e+01 -4.48589478e+01 -4.48847542e+01 -4.49953423e+01 -4.46494522e+01 -4.59692841e+01 -4.67782745e+01 -4.67668533e+01 -4.70694466e+01 -4.86080399e+01 -4.95584412e+01 -4.87539673e+01 -4.87907600e+01 -5.07588043e+01 -5.08918343e+01 -4.93852692e+01 -4.78587494e+01 -4.90777092e+01 -5.10931244e+01 -5.16641273e+01 -5.20239334e+01 -5.28036499e+01 -5.32927704e+01 -5.29752388e+01 -5.40251770e+01 -5.28772926e+01 -5.47039032e+01 -5.81728821e+01 -5.29166107e+01 -5.50957642e+01 -5.72710304e+01 -5.58877220e+01 -5.64898338e+01 -6.00615349e+01 -6.03821411e+01 -5.77471504e+01 -5.82967339e+01 -5.76079941e+01 -5.78773537e+01 -5.98744278e+01 -6.19722900e+01 -6.07887077e+01 -6.10473518e+01 -6.14520035e+01 -6.13945236e+01 -6.21770554e+01 -6.27147598e+01 -6.14620285e+01 -6.28191261e+01 -6.45033569e+01 -6.42994156e+01 -6.53822174e+01 -6.58955231e+01 -6.53281250e+01 -6.59327927e+01 -6.36051292e+01 -6.18195915e+01 -5.99252129e+01 -6.18121719e+01 -6.55878754e+01 -6.46312408e+01 -6.45739059e+01 -6.36927948e+01 -6.33033791e+01 -6.59034576e+01 2.35757629e+02 5.61596802e+02 205213904. 16502059. -24756200. -1.63722962e+06 -7.20369625e+05 -44919664. 238031488. 43313544. 43313544. 43313544. 0. 0. 0. 0. -68896688. 3.41193150e+06 3.41193150e+06 2.28073825e+06 0. 0. 0. -9408352. 74201088. -1.01076260e+04 5389721. -41867260. 1116613120. 1116613120. 1116613120. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -302337312. -302337312. 73725752. 16669606. 16669606. 0. 0. 0. 0. 0. 0. 0. 224321600. 224321600. 224321600. 0. 0. 0. 0. 0. -47563204. -47563204. -47563204. 0. 0. 0. 0. 0. 0. 73357832. -13598752. 69406176. 25791814. 2.89223816e+02 3.89948344e+00 -1.26793457e+02 -8.57795715e+01 -8.45102997e+01 -8.48811264e+01 -8.50885239e+01 -8.54672241e+01 -8.61200180e+01 -8.67112732e+01 -8.72358780e+01 -8.73921127e+01 -8.73217239e+01 -8.71944046e+01 -8.71222229e+01 -8.71927338e+01 -8.70772018e+01 -8.73341217e+01 -8.75100708e+01 -8.73449707e+01 -8.76723709e+01 -8.79219131e+01 -8.81760178e+01 -8.80877228e+01 -8.76502380e+01 -8.74828720e+01 -8.76737442e+01 -8.77062988e+01 -8.80781174e+01 -8.81822739e+01 -8.82021561e+01 -8.82161713e+01 -8.84831238e+01 -8.84786224e+01 -8.83893967e+01 -8.80742569e+01 -8.80322342e+01 -8.80002975e+01 -8.80431519e+01 -8.79105911e+01 -8.78798447e+01 -8.77098770e+01 -8.73232803e+01 -8.68599854e+01 -8.65964279e+01 -8.64087372e+01 -8.65121689e+01 -8.64280701e+01 -8.63640900e+01 -8.61121521e+01 -8.59605865e+01 -8.60135727e+01 -8.60199127e+01 -8.61507263e+01 -8.61780624e+01 -8.60208435e+01 -8.57721786e+01 -8.54217529e+01 -8.56962128e+01 -8.56670685e+01 -8.56676407e+01 -8.56545486e+01 -8.57882690e+01 -8.58531952e+01 -8.59549408e+01 -8.57435379e+01 -8.56315308e+01 -8.47364960e+01 -8.48936081e+01 -8.39610138e+01 -8.37787781e+01 -8.39101334e+01 -8.39488754e+01 -8.36021576e+01 -8.31096649e+01 -8.29873810e+01 -8.28730316e+01 -8.28618927e+01 -8.26153870e+01 -8.22418060e+01 -8.19206161e+01 -8.17744675e+01 -8.14094772e+01 -8.14783630e+01 -8.17929611e+01 -8.16659470e+01 -8.15029678e+01 -8.13452148e+01 -8.10789261e+01 -8.18238602e+01 -8.10079041e+01 -7.95391922e+01 -7.98878021e+01 -8.06751022e+01 -8.06075363e+01 -7.87535858e+01 -7.87888870e+01 -7.95746460e+01 -7.86823273e+01 -7.87334595e+01 -7.82625961e+01 -7.80648727e+01 -7.79983673e+01 -7.74313278e+01 -7.73469086e+01 -7.78628311e+01 -7.79184189e+01 -7.72654877e+01 -7.66857910e+01 -7.67638321e+01 -7.71130219e+01 -7.72636490e+01 -7.60456696e+01 -7.47503357e+01 -7.66689606e+01 -7.62429123e+01 -7.06976318e+01 -6.99017334e+01 -7.34435120e+01 -7.35890961e+01 -7.41669540e+01 -7.34664307e+01 -7.27980804e+01 -7.18928070e+01 -7.12004013e+01 -7.17752533e+01 -7.15434723e+01 -7.17319489e+01 -7.13297348e+01 -7.16027222e+01 -7.13443375e+01 -7.10258484e+01 -7.10662689e+01 -7.08635559e+01 -7.01656265e+01 -7.07270966e+01 -6.98530807e+01 -6.89240036e+01 -6.90577087e+01 -7.17541046e+01 -7.51760254e+01 -7.52733459e+01 -1.42288147e+02 -1.01259247e+02 -1.05235703e-01 -3.96889343e+01 -6.16134796e+01 -6.79234161e+01 -7.73625793e+01 -6.75483932e+01 -5.05322838e+01 -1.22613861e+02 -1.01861191e+02 -1.12381611e+01 -3.85096931e+01 -5.99056015e+01 -6.52738419e+01 -6.62207565e+01 -6.67765350e+01 -6.56611633e+01 -6.62500610e+01 -6.98787842e+01 -1.23222672e+02 -1.42798538e+02 -7.39684753e+02 -1.74621094e+03 3.91324097e+02 1.04633521e+03 2.95962871e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -134289232. -134289232. -134289232. 0. 0. 0. 24663148. 24663148. 24663148. 0. 0. 0. 0. 0. 0. 0. 0. 101137928. -14222967. -9147435. -1.61231475e+06 -3.20422625e+06 -62494116. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -104320480. -104320480. -104320480. 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. 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. 0. 0. 0. 0. 0. 0. 0. -634761088. -634761088. 259436416. -270754208. -270754208. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_6.xml ================================================ 16 1024
f
3.64280150e+06 1.27991173e+02 8.44696579e+01 8.47647324e+01 8.50740433e+01 8.53444061e+01 8.56367416e+01 8.61333084e+01 8.65810471e+01 8.70222473e+01 8.70815735e+01 8.73020554e+01 8.75481949e+01 8.76806488e+01 8.78692551e+01 8.80321655e+01 8.84458313e+01 8.86664047e+01 8.89416962e+01 8.93561707e+01 8.97175217e+01 8.99293442e+01 9.01003036e+01 9.03093567e+01 9.05606689e+01 9.08422852e+01 9.12613449e+01 9.15640717e+01 9.17246246e+01 9.18645401e+01 9.21271591e+01 9.24270096e+01 9.24322968e+01 9.29039078e+01 9.33397217e+01 9.38845749e+01 9.43726501e+01 9.46433640e+01 9.48895264e+01 9.52222519e+01 9.53925858e+01 9.53695984e+01 9.54900360e+01 9.58032608e+01 9.61595612e+01 9.61688614e+01 9.67740479e+01 9.67512360e+01 9.66316452e+01 9.69784393e+01 9.73929977e+01 9.74912415e+01 9.76443558e+01 9.77815552e+01 9.76877136e+01 9.80987167e+01 9.86889343e+01 9.89437790e+01 9.91350250e+01 9.97230301e+01 1.00009529e+02 9.98187256e+01 9.92857361e+01 9.94010925e+01 9.90777893e+01 9.95848694e+01 9.96450272e+01 9.92380676e+01 9.93816528e+01 9.99204178e+01 9.99618912e+01 1.00302147e+02 1.00427536e+02 1.01075638e+02 1.01166916e+02 1.01993874e+02 1.02511444e+02 1.01988586e+02 1.01617607e+02 1.01290474e+02 1.02076599e+02 1.02085487e+02 1.01974144e+02 1.01028053e+02 1.00864120e+02 1.08783104e+02 8.51793976e+01 1.04329033e+02 -2.40378571e+02 -8.76062012e+02 6.90583057e+03 -7.67390438e+05 -561579264. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -25443220. 1.54065350e+06 1.01571344e+05 -3.46078094e+02 -1.29819153e+02 1.08687538e+02 1.05481277e+02 9.78236465e+01 5.14425392e+01 4.89636688e+01 8.26068573e+01 9.73199615e+01 1.12451263e+02 1.04816833e+02 1.02786278e+02 1.02903175e+02 1.02516556e+02 1.02292740e+02 1.01846497e+02 1.00768333e+02 1.01009560e+02 9.97623215e+01 9.98872910e+01 9.95718002e+01 1.00093140e+02 1.12939575e+02 1.30382599e+02 1.40611008e+02 1.19884026e+02 9.67085266e+01 1.02476410e+02 1.04921791e+02 9.58908997e+01 7.78678284e+01 7.17543335e+01 7.18816452e+01 8.35729828e+01 9.54866867e+01 1.00996399e+02 1.09061630e+02 1.18085419e+02 1.12366898e+02 1.10442764e+02 1.16341614e+02 1.15269814e+02 1.14449402e+02 9.56050873e+01 8.37894821e+01 8.65342865e+01 9.24448547e+01 9.61770782e+01 9.73400192e+01 9.66548843e+01 9.53593216e+01 9.47915344e+01 9.21320267e+01 8.99360657e+01 8.71039352e+01 8.60089188e+01 8.30250092e+01 8.20607224e+01 8.78899536e+01 9.27140503e+01 9.22689743e+01 9.35724258e+01 9.71577377e+01 9.78062592e+01 9.78459091e+01 9.55465622e+01 9.45184097e+01 9.31638565e+01 9.15809860e+01 9.11193314e+01 9.11525803e+01 9.01858063e+01 8.98365326e+01 8.78774338e+01 8.76250534e+01 8.77059250e+01 8.87563629e+01 8.89375916e+01 8.89366302e+01 8.91318359e+01 8.86542664e+01 8.79247589e+01 8.75771408e+01 8.76256561e+01 8.71711731e+01 8.65442047e+01 8.65652618e+01 8.62749252e+01 8.63054428e+01 8.62298431e+01 8.47474823e+01 8.36681519e+01 8.25493393e+01 8.36885071e+01 8.38488312e+01 8.42586060e+01 8.42325974e+01 8.23318863e+01 8.15673141e+01 8.01493607e+01 8.06783600e+01 8.11321259e+01 8.16812820e+01 8.10693359e+01 8.04833298e+01 7.99505539e+01 7.80772400e+01 7.77926636e+01 7.72336426e+01 7.67566223e+01 7.66759872e+01 7.67569199e+01 7.70154495e+01 7.68747482e+01 7.62163544e+01 7.63050537e+01 7.58014526e+01 7.48196716e+01 7.40755310e+01 7.31814423e+01 7.34199829e+01 7.40312576e+01 7.34053879e+01 7.29850616e+01 7.18348694e+01 7.09751968e+01 7.01319580e+01 6.98448563e+01 6.93401108e+01 6.92110748e+01 6.88212967e+01 6.87426605e+01 6.81024170e+01 6.75423660e+01 6.67018280e+01 6.67091751e+01 6.61504898e+01 6.53152084e+01 6.46595459e+01 6.44926147e+01 6.46791382e+01 6.37130241e+01 6.28846359e+01 6.27784462e+01 6.17681885e+01 6.13358765e+01 6.14421959e+01 6.05128517e+01 6.00242729e+01 5.98279610e+01 5.84821205e+01 5.83185272e+01 5.82993774e+01 5.76431503e+01 5.78169785e+01 5.67301826e+01 5.55489998e+01 5.59043846e+01 5.52195015e+01 5.47198143e+01 5.46209564e+01 5.38544197e+01 5.27336655e+01 5.18185539e+01 5.19216499e+01 5.10722885e+01 5.00907974e+01 4.99424019e+01 4.96222572e+01 4.90098763e+01 4.88319855e+01 4.81165504e+01 4.71696777e+01 4.60139847e+01 4.58799171e+01 4.61322479e+01 4.53272705e+01 4.49206429e+01 4.46769524e+01 4.35167961e+01 4.16816254e+01 4.14783936e+01 4.09453316e+01 4.14903641e+01 4.16217957e+01 4.05066528e+01 3.94687119e+01 3.98530273e+01 3.93226357e+01 3.75562439e+01 3.71406555e+01 3.63973160e+01 3.54331818e+01 3.50071983e+01 3.52219582e+01 3.47764015e+01 3.36234779e+01 3.29646111e+01 3.33154678e+01 3.18555508e+01 3.04276810e+01 2.93055725e+01 2.92194328e+01 2.97737808e+01 2.97380276e+01 2.92988148e+01 2.86879234e+01 2.87293549e+01 2.87688808e+01 2.81202469e+01 2.57612095e+01 2.43971291e+01 2.30488682e+01 2.37071648e+01 2.37238636e+01 2.25236568e+01 2.02867870e+01 2.07866631e+01 2.07314491e+01 2.03708115e+01 1.78964653e+01 1.86007004e+01 1.92021961e+01 2.08191032e+01 1.98677807e+01 1.74148293e+01 1.64392204e+01 1.55470629e+01 1.53667707e+01 1.43722992e+01 1.45834436e+01 1.39418125e+01 1.29648600e+01 1.19206200e+01 1.07152309e+01 9.09480667e+00 9.63907337e+00 1.02064390e+01 1.00804319e+01 8.47177124e+00 6.88603687e+00 7.89105368e+00 8.78597736e+00 7.03485298e+00 5.88527012e+00 4.03007698e+00 4.19723988e+00 4.58845758e+00 4.92302799e+00 2.97697544e+00 1.87031770e+00 1.23867464e+00 6.01673424e-01 3.02442878e-01 9.52385664e-02 -3.38144839e-01 -2.58628774e+00 -4.08318043e+00 -4.74851036e+00 -5.64291143e+00 -6.00724745e+00 -6.92090511e+00 -7.02932549e+00 -7.40517139e+00 -6.90544987e+00 -6.90801954e+00 -8.38777065e+00 -9.62357140e+00 -9.88830185e+00 -1.03344965e+01 -1.09153061e+01 -1.21100101e+01 -1.30671263e+01 -1.32067728e+01 -1.46362553e+01 -1.50413303e+01 -1.55911856e+01 -1.64216824e+01 -1.67791252e+01 -1.71181145e+01 -1.79284267e+01 -1.82160454e+01 -1.84551830e+01 -1.78756237e+01 -1.89291668e+01 -1.95365086e+01 -2.15390434e+01 -2.27071972e+01 -2.34658737e+01 -2.35246353e+01 -2.44897938e+01 -2.43033276e+01 -2.41844215e+01 -2.46756191e+01 -2.62343903e+01 -2.67779198e+01 -2.71765919e+01 -2.87512531e+01 -2.94542847e+01 -3.07593307e+01 -2.98576698e+01 -3.05288773e+01 -3.04071503e+01 -3.09638081e+01 -3.16243153e+01 -3.23936768e+01 -3.37734566e+01 -3.37466202e+01 -3.47982712e+01 -3.58664856e+01 -3.67700844e+01 -3.62862358e+01 -3.71984940e+01 -3.73468742e+01 -3.81749268e+01 -3.78454666e+01 -3.86370201e+01 -4.00845413e+01 -4.07322578e+01 -4.14557648e+01 -4.13388596e+01 -4.18774452e+01 -4.17799835e+01 -4.30449638e+01 -4.39761429e+01 -4.45472641e+01 -4.45654755e+01 -4.54307556e+01 -4.62424431e+01 -4.75060425e+01 -4.84630699e+01 -4.87867050e+01 -4.87111740e+01 -4.87197800e+01 -4.87729530e+01 -4.94365196e+01 -5.02740898e+01 -5.10359039e+01 -5.14979286e+01 -5.18527832e+01 -5.24982262e+01 -5.31258926e+01 -5.31872787e+01 -5.38214645e+01 -5.41240082e+01 -5.46436729e+01 -5.57159042e+01 -5.64925232e+01 -5.71250992e+01 -5.70290184e+01 -5.70810890e+01 -5.76641006e+01 -5.83306541e+01 -5.93294716e+01 -5.97614479e+01 -6.06627045e+01 -6.08967590e+01 -6.11339149e+01 -6.13450661e+01 -6.17892723e+01 -6.24075317e+01 -6.31880798e+01 -6.39513016e+01 -6.41837692e+01 -6.46089554e+01 -6.51233139e+01 -6.56264877e+01 -6.61248779e+01 -6.65960007e+01 -6.69244995e+01 -6.72474136e+01 -6.74397354e+01 -6.81197205e+01 -6.87241135e+01 -6.90625687e+01 -6.95698471e+01 -7.01529083e+01 -7.05054245e+01 -7.08796310e+01 -7.13501434e+01 -7.19747620e+01 -7.23360443e+01 -7.26769333e+01 -7.31624527e+01 -7.37461395e+01 -7.40981293e+01 -7.44848785e+01 -7.48850479e+01 -7.53426971e+01 -7.57911682e+01 -7.62581406e+01 -7.66663208e+01 -7.70402985e+01 -7.73225555e+01 -7.77496872e+01 -7.82024689e+01 -7.86371460e+01 -7.90210114e+01 -7.94275513e+01 -7.97645874e+01 -8.01514359e+01 -8.05453720e+01 -8.09949036e+01 -8.14009857e+01 -8.17899933e+01 -8.21729660e+01 -8.25733566e+01 -8.29023819e+01 -8.31888962e+01 -8.35287933e+01 -8.38640518e+01 -8.41878967e+01 -8.44907303e+01 -8.48477936e+01 -8.51037292e+01 -8.54376144e+01 -8.57615814e+01 -8.60362244e+01 -8.64021454e+01 -8.67133331e+01 -8.71207199e+01 -8.73613739e+01 -8.75999908e+01 -8.79742813e+01 -8.83168564e+01 -8.86044388e+01 -8.89751968e+01 -8.92355270e+01 -8.93418198e+01 -8.94373474e+01 -8.98640137e+01 -9.02491684e+01 -9.04287033e+01 -9.09689865e+01 -9.13878479e+01 -9.14906387e+01 -9.13097000e+01 -9.15067902e+01 -9.18793030e+01 -9.23962860e+01 -9.30968170e+01 -9.33243713e+01 -9.34416656e+01 -9.37507629e+01 -9.39870605e+01 -9.39904404e+01 -9.42521973e+01 -9.41492004e+01 -9.43244629e+01 -9.49361267e+01 -9.55394592e+01 -9.57753143e+01 -9.57961807e+01 -9.61017532e+01 -9.64368362e+01 -9.62844849e+01 -9.60153580e+01 -9.60228577e+01 -9.63570023e+01 -9.70242157e+01 -9.72518158e+01 -9.75438843e+01 -9.75904999e+01 -9.82062149e+01 -9.82764511e+01 -9.82743988e+01 -9.83803406e+01 -9.85247421e+01 -9.76903687e+01 -9.82927551e+01 -9.85599976e+01 -9.83893356e+01 -9.79035645e+01 -9.86091843e+01 -9.90167923e+01 -9.94983673e+01 -9.83269653e+01 -9.86418381e+01 -9.98746643e+01 -1.00580620e+02 -1.00732513e+02 -1.00328705e+02 -1.00485718e+02 -1.00314278e+02 -1.00394440e+02 -1.00969337e+02 -1.01096123e+02 -1.00555740e+02 -1.00324463e+02 -1.00368240e+02 -1.00611534e+02 -1.01279175e+02 -1.02306129e+02 -1.02521790e+02 -1.01659508e+02 -1.01296059e+02 -1.01434631e+02 -1.01428665e+02 -1.02413696e+02 -1.03537903e+02 -1.03821228e+02 -1.02479530e+02 -1.02634140e+02 -1.03578789e+02 -1.04308395e+02 -1.04411789e+02 -1.03635849e+02 -1.02933594e+02 -1.01944946e+02 -1.01951042e+02 -1.02537155e+02 -1.02960472e+02 -1.02465103e+02 -1.01410492e+02 -1.01404518e+02 -1.01307220e+02 -1.01107018e+02 -1.00639305e+02 -1.00978439e+02 -1.01287178e+02 -1.02817345e+02 -1.03255791e+02 -1.03218903e+02 -1.01682304e+02 -1.01973854e+02 -1.02720413e+02 -1.02604767e+02 -1.01158043e+02 -9.99484024e+01 -1.00436539e+02 -9.96869202e+01 -1.00931763e+02 -1.01287430e+02 -1.01460693e+02 -1.00724335e+02 -1.01139244e+02 -1.00872086e+02 -1.00065369e+02 -9.94776077e+01 -1.00997810e+02 -1.01650665e+02 -1.00678581e+02 -9.82123795e+01 -9.80902328e+01 -9.85478058e+01 -9.96485748e+01 -9.98266907e+01 -1.00663574e+02 -1.00786469e+02 -1.00618370e+02 -9.86463623e+01 -9.86105194e+01 -9.82026596e+01 -9.65943222e+01 -9.79279175e+01 -9.63915482e+01 -9.75305557e+01 -9.67804947e+01 -9.76018143e+01 -9.69614182e+01 -9.61758194e+01 -9.63918839e+01 -9.56801224e+01 -9.49399490e+01 -9.49641266e+01 -9.49543533e+01 -9.32787476e+01 -9.44957199e+01 -9.46944046e+01 -9.54996490e+01 -9.48214264e+01 -9.56659012e+01 -9.55112076e+01 -9.40580902e+01 -9.30684204e+01 -9.19666290e+01 -9.28525238e+01 -9.20724945e+01 -9.24277267e+01 -9.21100082e+01 -9.09845505e+01 -9.01230087e+01 -9.11994858e+01 -9.10622330e+01 -8.98160172e+01 -8.78166580e+01 -8.73383255e+01 -8.71476593e+01 -8.81836929e+01 -8.87262802e+01 -8.86751099e+01 -8.83546677e+01 -8.77790833e+01 -8.72934265e+01 -8.68102417e+01 -8.69927444e+01 -8.68693619e+01 -8.68254318e+01 -8.69759369e+01 -8.57543488e+01 -8.57740707e+01 -8.57791138e+01 -8.41388245e+01 -8.32259140e+01 -8.13537140e+01 -8.18901978e+01 -8.27312241e+01 -8.36128082e+01 -8.35915222e+01 -8.15918961e+01 -8.14987106e+01 -7.98603210e+01 -8.04992523e+01 -8.01300888e+01 -8.05418320e+01 -8.01764069e+01 -7.94211807e+01 -7.95029907e+01 -7.76845551e+01 -7.72504425e+01 -7.74455414e+01 -7.70417099e+01 -7.63312454e+01 -7.55108566e+01 -7.62305298e+01 -7.66621628e+01 -7.55162125e+01 -7.54947128e+01 -7.50044861e+01 -7.46570129e+01 -7.39932251e+01 -7.27765656e+01 -7.19721298e+01 -7.29346695e+01 -7.32025681e+01 -7.23676987e+01 -7.09758759e+01 -7.07331467e+01 -7.04517975e+01 -7.00594940e+01 -6.92943649e+01 -6.85580444e+01 -6.83973999e+01 -6.84747772e+01 -6.75945663e+01 -6.73701172e+01 -6.61577377e+01 -6.64771271e+01 -6.57976990e+01 -6.50755005e+01 -6.45533905e+01 -6.44524002e+01 -6.43419037e+01 -6.31112556e+01 -6.25173950e+01 -6.25246582e+01 -6.19646835e+01 -6.14518509e+01 -6.08600273e+01 -5.97896957e+01 -5.99278679e+01 -5.95817337e+01 -5.83817062e+01 -5.84707375e+01 -5.81535912e+01 -5.73663902e+01 -5.76114006e+01 -5.68875275e+01 -5.56836548e+01 -5.53783646e+01 -5.49801331e+01 -5.41113510e+01 -5.38825798e+01 -5.34126091e+01 -5.21282578e+01 -5.19803963e+01 -5.19734612e+01 -5.09046631e+01 -5.01401978e+01 -5.01265144e+01 -5.01427956e+01 -4.93910561e+01 -4.87764893e+01 -4.78822556e+01 -4.68535767e+01 -4.58042145e+01 -4.56489029e+01 -4.57930260e+01 -4.54360046e+01 -4.52802200e+01 -4.43505516e+01 -4.30882988e+01 -4.15341988e+01 -4.17992363e+01 -4.15178108e+01 -4.16907539e+01 -4.15415688e+01 -4.00219078e+01 -3.93821983e+01 -3.94973183e+01 -3.85471268e+01 -3.74240799e+01 -3.60492210e+01 -3.57498856e+01 -3.63106422e+01 -3.49098930e+01 -3.44765244e+01 -3.37995300e+01 -3.27254333e+01 -3.18698006e+01 -3.16450310e+01 -3.11904049e+01 -3.01907215e+01 -2.93800392e+01 -2.94773102e+01 -2.95875893e+01 -2.91629753e+01 -2.88076305e+01 -2.78476887e+01 -2.82900734e+01 -2.82745056e+01 -2.72249603e+01 -2.52296085e+01 -2.43217754e+01 -2.24321785e+01 -2.29625359e+01 -2.25737667e+01 -2.21022606e+01 -2.05457573e+01 -2.11404686e+01 -2.00198803e+01 -1.99729424e+01 -1.77323055e+01 -1.82342987e+01 -1.92683506e+01 -2.09329643e+01 -1.96870422e+01 -1.69443455e+01 -1.73077736e+01 -1.62086792e+01 -1.50076180e+01 -1.50377264e+01 -1.39001446e+01 -1.23705664e+01 -1.26663914e+01 -1.14421844e+01 -1.04239464e+01 -1.04831543e+01 -1.09104509e+01 -1.12093897e+01 -1.04799843e+01 -9.11992455e+00 -8.31233406e+00 -7.45384359e+00 -7.63131857e+00 -6.27352428e+00 -5.53714800e+00 -3.56341529e+00 -3.74826431e+00 -3.48422146e+00 -4.00232124e+00 -2.80839109e+00 -1.30869687e+00 -6.98546886e-01 2.56751627e-01 9.57647383e-01 4.45736676e-01 8.90078604e-01 2.98652053e+00 3.89793563e+00 4.99851465e+00 5.71999550e+00 6.36621046e+00 7.14974213e+00 7.91072941e+00 8.69351959e+00 8.06792450e+00 7.98865891e+00 8.03369713e+00 9.17541313e+00 9.62670708e+00 1.06761856e+01 1.09661388e+01 1.24052191e+01 1.40553780e+01 1.38565550e+01 1.55361052e+01 1.53676882e+01 1.61885338e+01 1.66399136e+01 1.72048111e+01 1.75251732e+01 1.85527611e+01 1.92535381e+01 1.63722324e+01 -4.19666290e+00 -4.36721573e+01 -3.14853592e+01 1.34153118e+01 2.50882874e+01 2.57503281e+01 2.41516590e+01 2.32471447e+01 2.44004135e+01 2.78056870e+01 4.38929138e+01 2.87627296e+01 -2.14067047e+02 -4.45435516e+02 -6.67891250e+06 134192872. 0. 0. 0. 0. 41271896. 41271896. 41271896. 0. 0. 0. -10370003. -1.81799725e+06 7.94732812e+04 -1.27769043e+03 -5.63828857e+02 -1.16991432e+02 -8.66778870e+01 -1.32107025e+02 -1.29604233e+02 -4.26925774e+01 2.52731152e+01 3.97091751e+01 4.24025612e+01 4.27663345e+01 4.40927658e+01 4.50034790e+01 4.56086922e+01 4.57309914e+01 4.64374390e+01 4.47022095e+01 2.96729908e+01 1.33577509e+01 2.65191593e+01 4.35019264e+01 4.87458992e+01 5.05704613e+01 5.34047661e+01 6.69044800e+01 9.30553818e+01 9.07052994e+01 6.24456673e+01 3.89019852e+01 4.98687553e+01 6.88014069e+01 6.16951485e+01 5.44916763e+01 5.31815834e+01 5.38902245e+01 5.60386391e+01 5.74456520e+01 5.77346954e+01 5.82169113e+01 5.83026924e+01 5.89063911e+01 5.98735580e+01 6.01070328e+01 6.09591904e+01 6.13405113e+01 6.17805634e+01 6.19567947e+01 6.24233055e+01 6.32399101e+01 6.37558174e+01 6.44118576e+01 6.48775864e+01 6.54358673e+01 6.59001236e+01 6.63818741e+01 6.67748718e+01 6.72087250e+01 6.74547653e+01 6.80204544e+01 6.82848129e+01 6.87223816e+01 6.93661118e+01 6.99531403e+01 7.06484680e+01 7.11770782e+01 7.13796463e+01 7.17632446e+01 7.22504578e+01 7.29375687e+01 7.34748077e+01 7.40197372e+01 7.44657516e+01 7.49655762e+01 7.53797073e+01 7.57810440e+01 7.62100143e+01 7.67690353e+01 7.73268814e+01 7.78060226e+01 7.82743683e+01 7.88995209e+01 7.96022797e+01 7.99628067e+01 8.02287064e+01 8.06560211e+01 8.10963058e+01 8.14984436e+01 8.19150772e+01 8.23924255e+01 8.27598801e+01 8.30542755e+01 8.20723114e+01 3.21845605e+03 4.20871811e+01 2.74759159e+01 2.77400494e+01 2.79917068e+01 2.82386456e+01 2.85035896e+01 2.87459469e+01 2.89779606e+01 2.92555237e+01 2.95264263e+01 2.98439693e+01 3.00491734e+01 3.02643108e+01 3.05293961e+01 3.07670593e+01 3.10293617e+01 3.12664032e+01 3.14906845e+01 3.17079220e+01 3.19835072e+01 3.22532425e+01 3.24871063e+01 3.27293129e+01 3.29850845e+01 3.32050285e+01 3.34783325e+01 3.37307205e+01 3.39743347e+01 3.42044525e+01 3.45176506e+01 3.47129860e+01 3.48858757e+01 3.50589371e+01 3.53625565e+01 3.56615334e+01 3.60116043e+01 3.62042351e+01 3.64559402e+01 3.66428413e+01 3.68239479e+01 3.70227013e+01 3.72848511e+01 3.76399384e+01 3.78189926e+01 3.80531616e+01 3.83146057e+01 3.84992142e+01 3.86480141e+01 3.89629135e+01 3.91728134e+01 3.93575630e+01 3.95427971e+01 3.97862740e+01 3.99160042e+01 4.02056732e+01 4.05888481e+01 4.07231750e+01 4.10002594e+01 4.10646629e+01 4.12386208e+01 4.13982277e+01 4.16047745e+01 4.19682770e+01 4.19679604e+01 4.21588745e+01 4.26516418e+01 4.28268967e+01 4.29668732e+01 4.31017952e+01 4.30320206e+01 4.33490944e+01 4.36466904e+01 4.36525192e+01 4.36206284e+01 4.39419594e+01 4.45413895e+01 4.44792290e+01 4.49254837e+01 4.46542511e+01 4.50962448e+01 4.48505898e+01 4.51750603e+01 4.82075386e+01 4.65820923e+01 -4.77655640e+01 -1.19169968e+02 1.37150955e+02 -3.30839661e+02 -8.64732056e+02 7.00750732e+03 -1.58558975e+06 -1123158528. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 159610656. -2.11236572e+03 -3.57046051e+02 1.06564392e+02 -1.62736969e+02 -7.84421310e+01 5.46455231e+01 5.34223785e+01 4.68444519e+01 3.81398125e+01 4.09137497e+01 4.12539902e+01 4.72182770e+01 5.42756271e+01 5.12305984e+01 5.09740677e+01 5.01804199e+01 4.99670601e+01 5.05918770e+01 5.05822601e+01 5.10350723e+01 5.13052902e+01 5.17989502e+01 5.15939064e+01 5.10122414e+01 5.09557152e+01 5.55279617e+01 5.96755829e+01 6.01321716e+01 5.51305084e+01 5.08999825e+01 5.14679031e+01 5.09124222e+01 4.77730637e+01 4.33232346e+01 4.22502251e+01 4.29001732e+01 4.76623917e+01 5.23014717e+01 5.39356079e+01 5.59855042e+01 5.81625481e+01 5.65820541e+01 5.62727203e+01 5.70500565e+01 5.67520180e+01 5.56525345e+01 5.01216812e+01 4.68401985e+01 4.86330032e+01 5.06495209e+01 5.18269615e+01 5.19068718e+01 5.21652603e+01 5.23523178e+01 5.21018105e+01 5.12811356e+01 5.10230980e+01 5.04884224e+01 4.98890190e+01 4.83375053e+01 4.89852982e+01 5.13189964e+01 5.32273407e+01 5.30011673e+01 5.38556786e+01 5.46248856e+01 5.46090546e+01 5.42269745e+01 5.36377716e+01 5.29302177e+01 5.23407555e+01 5.17716599e+01 5.23696251e+01 5.19417801e+01 5.24701576e+01 5.15919456e+01 5.14252548e+01 5.06092606e+01 5.10849495e+01 5.18246117e+01 5.24423256e+01 5.24744072e+01 5.21695518e+01 5.15523529e+01 5.07031784e+01 5.10186577e+01 5.16663895e+01 5.17195930e+01 5.18154221e+01 5.20191498e+01 5.17834091e+01 5.12096214e+01 5.07641106e+01 5.10459061e+01 5.11798363e+01 5.14509315e+01 5.14409676e+01 5.18821449e+01 5.14311447e+01 5.12307816e+01 5.07844925e+01 5.09979744e+01 5.08043633e+01 5.06718521e+01 5.07102470e+01 5.05615730e+01 5.07463036e+01 5.07575760e+01 5.06855469e+01 4.99272652e+01 4.99409637e+01 4.99764977e+01 5.02358818e+01 5.00443115e+01 4.98456039e+01 4.98899078e+01 5.01621437e+01 4.99698219e+01 4.98460808e+01 4.97032471e+01 4.97377777e+01 4.94291687e+01 4.93145180e+01 4.92182808e+01 4.94125557e+01 4.91715317e+01 4.90239372e+01 4.86725540e+01 4.85723915e+01 4.81374435e+01 4.79793663e+01 4.77482948e+01 4.78282890e+01 4.77005005e+01 4.77585602e+01 4.75111809e+01 4.73705101e+01 4.70832710e+01 4.71140633e+01 4.69639664e+01 4.67759933e+01 4.65871506e+01 4.65276756e+01 4.65007133e+01 4.62327232e+01 4.60769005e+01 4.59774399e+01 4.56442528e+01 4.55678482e+01 4.55841637e+01 4.52817192e+01 4.51731796e+01 4.50955353e+01 4.46575089e+01 4.46357994e+01 4.46544189e+01 4.43540306e+01 4.43407059e+01 4.41641884e+01 4.38108673e+01 4.37297058e+01 4.34381638e+01 4.33290253e+01 4.33403854e+01 4.31914101e+01 4.30589447e+01 4.27144241e+01 4.25583572e+01 4.20628281e+01 4.18351097e+01 4.15879097e+01 4.14814987e+01 4.13051071e+01 4.11792908e+01 4.09426918e+01 4.07110062e+01 4.01587219e+01 4.00042229e+01 4.00481262e+01 3.99833565e+01 3.97934875e+01 4.00034447e+01 3.95142632e+01 3.89478035e+01 3.82698174e+01 3.82063484e+01 3.82664261e+01 3.85879364e+01 3.81082611e+01 3.78880730e+01 3.76797333e+01 3.73587494e+01 3.70004807e+01 3.67990112e+01 3.67332802e+01 3.61792564e+01 3.61216812e+01 3.60511284e+01 3.58345680e+01 3.53619804e+01 3.49752922e+01 3.49049606e+01 3.47615471e+01 3.45089073e+01 3.41656342e+01 3.36752625e+01 3.36864395e+01 3.39388542e+01 3.36516304e+01 3.34794731e+01 3.25281792e+01 3.24205055e+01 3.24412308e+01 3.18932266e+01 3.19414043e+01 3.11333942e+01 3.13957787e+01 3.19530678e+01 3.20278015e+01 3.10271320e+01 3.05751266e+01 3.00899887e+01 3.03047028e+01 2.97038879e+01 2.89826279e+01 2.82731075e+01 2.87500248e+01 2.93376141e+01 2.83446388e+01 2.89953079e+01 2.80977478e+01 2.83509064e+01 2.77531624e+01 2.82284222e+01 2.83103981e+01 2.69979057e+01 2.65259266e+01 2.57459164e+01 2.54305229e+01 2.46776543e+01 2.42285271e+01 2.42666435e+01 2.41187840e+01 2.39957390e+01 2.43228951e+01 2.45645370e+01 2.42040195e+01 2.39085007e+01 2.32403278e+01 2.29909821e+01 2.27163029e+01 2.23717747e+01 2.16006927e+01 2.12662983e+01 2.04315910e+01 2.00473347e+01 2.00883865e+01 2.02789860e+01 2.04474335e+01 1.91432037e+01 1.90291576e+01 1.87775764e+01 1.92534866e+01 1.89550343e+01 1.75343246e+01 1.73630199e+01 1.68926601e+01 1.71513901e+01 1.72834225e+01 1.65237312e+01 1.67503281e+01 1.57699957e+01 1.52854080e+01 1.51842432e+01 1.48315048e+01 1.48787851e+01 1.48476267e+01 1.49313049e+01 1.45362167e+01 1.33812504e+01 1.30020666e+01 1.27814531e+01 1.22395496e+01 1.17392120e+01 1.10127878e+01 1.10853119e+01 1.08718405e+01 1.03712244e+01 1.01504354e+01 1.01485176e+01 9.82820034e+00 9.40837097e+00 9.08320808e+00 8.90529156e+00 8.55580330e+00 8.24988079e+00 8.10324669e+00 7.49738312e+00 7.15177298e+00 6.85140610e+00 6.73851538e+00 6.03380156e+00 5.32751322e+00 5.48489189e+00 5.38696432e+00 5.34153795e+00 4.92444611e+00 4.36161423e+00 4.13025331e+00 3.97524834e+00 3.60185838e+00 2.88941813e+00 2.67384005e+00 2.39861012e+00 2.22501445e+00 1.27728784e+00 1.58309877e+00 1.49984467e+00 1.66613948e+00 1.10095704e+00 5.72471082e-01 -5.54857627e-02 -5.56951344e-01 -7.87792265e-01 -9.44272280e-01 -1.24794245e+00 -1.88167465e+00 -2.36211371e+00 -2.32449436e+00 -2.55792713e+00 -2.63442492e+00 -3.44074655e+00 -3.99894524e+00 -4.64990854e+00 -4.66982889e+00 -4.60464621e+00 -4.65444136e+00 -4.86881781e+00 -5.34935331e+00 -5.94180012e+00 -6.53846216e+00 -6.79322815e+00 -6.91491365e+00 -7.28311682e+00 -7.52908802e+00 -7.69434023e+00 -8.04936886e+00 -8.54314995e+00 -9.01117420e+00 -9.27015305e+00 -9.52491379e+00 -9.55434227e+00 -9.86705875e+00 -1.00026922e+01 -1.05620394e+01 -1.09739485e+01 -1.13676710e+01 -1.15953913e+01 -1.19597464e+01 -1.21988268e+01 -1.24550371e+01 -1.27513266e+01 -1.30196543e+01 -1.33250637e+01 -1.37149525e+01 -1.41310759e+01 -1.43592806e+01 -1.46087475e+01 -1.48096485e+01 -1.51593781e+01 -1.55357256e+01 -1.58413677e+01 -1.60789585e+01 -1.63471718e+01 -1.65722370e+01 -1.69225273e+01 -1.72273540e+01 -1.75502911e+01 -1.78601990e+01 -1.82088165e+01 -1.84401913e+01 -1.87155704e+01 -1.90195103e+01 -1.93874378e+01 -1.96650028e+01 -1.99603214e+01 -2.02732334e+01 -2.06073723e+01 -2.08617039e+01 -2.11618347e+01 -2.14331398e+01 -2.17436752e+01 -2.20317593e+01 -2.23331070e+01 -2.26157951e+01 -2.28971710e+01 -2.31498833e+01 -2.34518452e+01 -2.37542133e+01 -2.40438766e+01 -2.43320637e+01 -2.46127453e+01 -2.48901806e+01 -2.51705284e+01 -2.54530754e+01 -2.57450409e+01 -2.60339985e+01 -2.63191071e+01 -2.65966187e+01 -2.68780537e+01 -2.71543465e+01 -2.74153938e+01 -2.76805401e+01 -2.79499836e+01 -2.82207165e+01 -2.84913445e+01 -2.87631435e+01 -2.90097790e+01 -2.92679005e+01 -2.95389938e+01 -2.98036709e+01 -3.00718193e+01 -3.03264141e+01 -3.06073589e+01 -3.08433819e+01 -3.10801010e+01 -3.13224468e+01 -3.15760326e+01 -3.18388100e+01 -3.21146088e+01 -3.23541870e+01 -3.25643158e+01 -3.27519226e+01 -3.30186157e+01 -3.33102570e+01 -3.35133247e+01 -3.38185654e+01 -3.41842232e+01 -3.43420296e+01 -3.44481544e+01 -3.46191483e+01 -3.49115601e+01 -3.51814880e+01 -3.55343323e+01 -3.57701607e+01 -3.60411835e+01 -3.62532616e+01 -3.64495316e+01 -3.66463318e+01 -3.69171371e+01 -3.70573273e+01 -3.72546806e+01 -3.76399879e+01 -3.78977852e+01 -3.80819016e+01 -3.82219849e+01 -3.84995117e+01 -3.87632332e+01 -3.88609161e+01 -3.89554176e+01 -3.92316551e+01 -3.94310722e+01 -3.97543030e+01 -4.00872154e+01 -4.01558189e+01 -4.04424782e+01 -4.04408836e+01 -4.05512619e+01 -4.07005386e+01 -4.10398331e+01 -4.14403915e+01 -4.13785782e+01 -4.17019768e+01 -4.21605721e+01 -4.24296722e+01 -4.24218559e+01 -4.26025314e+01 -4.26120071e+01 -4.29755936e+01 -4.29433670e+01 -4.28967476e+01 -4.31163559e+01 -4.34101448e+01 -4.38776131e+01 -4.38477058e+01 -4.43587723e+01 -4.43450356e+01 -4.46263275e+01 -4.47293129e+01 -4.50551071e+01 -4.51646500e+01 -4.48937111e+01 -4.51721573e+01 -4.52176285e+01 -4.55605392e+01 -4.56411743e+01 -4.59143982e+01 -4.58463783e+01 -4.59666557e+01 -4.60472145e+01 -4.63298988e+01 -4.68002357e+01 -4.75446053e+01 -4.76493149e+01 -4.73903313e+01 -4.73702393e+01 -4.78158302e+01 -4.79745216e+01 -4.81834488e+01 -4.81827240e+01 -4.77036324e+01 -4.76806068e+01 -4.79365578e+01 -4.83648987e+01 -4.89091682e+01 -4.85048180e+01 -4.87161827e+01 -4.89314919e+01 -4.93309326e+01 -4.93240929e+01 -4.85277138e+01 -4.88242760e+01 -4.90896378e+01 -5.00342293e+01 -5.06650467e+01 -5.03370628e+01 -5.05515289e+01 -4.98054962e+01 -4.98641968e+01 -5.02800941e+01 -4.99620552e+01 -5.03063583e+01 -5.06300316e+01 -5.11995811e+01 -5.15265465e+01 -5.12059364e+01 -5.12427139e+01 -5.10106468e+01 -5.08443604e+01 -5.06783485e+01 -4.99243507e+01 -5.01969872e+01 -5.02597542e+01 -5.08249893e+01 -5.09608269e+01 -5.12547874e+01 -5.13114548e+01 -5.14424706e+01 -5.16827202e+01 -5.18799667e+01 -5.19032745e+01 -5.19316444e+01 -5.21781998e+01 -5.15377274e+01 -5.16066170e+01 -5.13757019e+01 -5.16062737e+01 -5.17799835e+01 -5.13015556e+01 -5.16252136e+01 -5.20764885e+01 -5.21503983e+01 -5.19721909e+01 -5.15134506e+01 -5.22251511e+01 -5.23720894e+01 -5.20473061e+01 -5.17104721e+01 -5.21505547e+01 -5.20449409e+01 -5.22670860e+01 -5.17092476e+01 -5.26687508e+01 -5.28725204e+01 -5.36505051e+01 -5.32084732e+01 -5.30806541e+01 -5.25614128e+01 -5.21190033e+01 -5.22429466e+01 -5.22845612e+01 -5.23443565e+01 -5.20442467e+01 -5.17621422e+01 -5.22461319e+01 -5.22513924e+01 -5.27655678e+01 -5.18330574e+01 -5.13766747e+01 -5.08583641e+01 -5.11045761e+01 -5.18153725e+01 -5.24871216e+01 -5.24629173e+01 -5.22201157e+01 -5.15063362e+01 -5.07747688e+01 -5.08932228e+01 -5.14874153e+01 -5.16632690e+01 -5.17441521e+01 -5.18958130e+01 -5.17029495e+01 -5.10322380e+01 -5.05359268e+01 -5.06258583e+01 -5.07457237e+01 -5.11000061e+01 -5.10035744e+01 -5.15377731e+01 -5.11970024e+01 -5.11229630e+01 -5.06556358e+01 -5.08717422e+01 -5.04426956e+01 -5.04998512e+01 -5.04869957e+01 -5.02524185e+01 -5.02868385e+01 -5.04840317e+01 -5.03698769e+01 -4.95978088e+01 -4.97142410e+01 -4.99944382e+01 -5.01462669e+01 -4.98118782e+01 -4.94843826e+01 -4.96124496e+01 -4.99734001e+01 -4.96541290e+01 -4.96266518e+01 -4.96281586e+01 -4.95445633e+01 -4.91801338e+01 -4.91137619e+01 -4.87775803e+01 -4.91745224e+01 -4.91049767e+01 -4.88016701e+01 -4.84158783e+01 -4.83036957e+01 -4.80891571e+01 -4.80849075e+01 -4.78002014e+01 -4.76281166e+01 -4.75544128e+01 -4.76816521e+01 -4.73847885e+01 -4.72886810e+01 -4.68853531e+01 -4.69344406e+01 -4.68439560e+01 -4.68440857e+01 -4.65988922e+01 -4.64875221e+01 -4.64432983e+01 -4.61105309e+01 -4.59347191e+01 -4.58371124e+01 -4.55777245e+01 -4.54802475e+01 -4.53974915e+01 -4.50248909e+01 -4.50652847e+01 -4.50086327e+01 -4.44869080e+01 -4.45121193e+01 -4.45213547e+01 -4.42555046e+01 -4.42258186e+01 -4.40929565e+01 -4.37937164e+01 -4.36379089e+01 -4.33676033e+01 -4.31045952e+01 -4.32039146e+01 -4.31053505e+01 -4.28072968e+01 -4.25722961e+01 -4.24541817e+01 -4.21397552e+01 -4.19667053e+01 -4.15931320e+01 -4.13969688e+01 -4.12894516e+01 -4.11686287e+01 -4.07747383e+01 -4.04284286e+01 -4.00176811e+01 -3.99234695e+01 -3.99073448e+01 -3.97661400e+01 -3.99052773e+01 -3.97687149e+01 -3.91460609e+01 -3.86946182e+01 -3.83241310e+01 -3.85237617e+01 -3.83540764e+01 -3.84771080e+01 -3.80418243e+01 -3.79827118e+01 -3.76338348e+01 -3.73064041e+01 -3.70689125e+01 -3.66343498e+01 -3.66660881e+01 -3.65036240e+01 -3.63908844e+01 -3.59630280e+01 -3.55566978e+01 -3.50577660e+01 -3.48699532e+01 -3.45976219e+01 -3.43130951e+01 -3.41445656e+01 -3.40148239e+01 -3.39136391e+01 -3.37721519e+01 -3.39537506e+01 -3.33732300e+01 -3.32156258e+01 -3.25606079e+01 -3.23308258e+01 -3.22278442e+01 -3.17774849e+01 -3.18617687e+01 -3.10789967e+01 -3.10528145e+01 -3.14323559e+01 -3.18686218e+01 -3.09235344e+01 -3.05830917e+01 -2.97198143e+01 -3.01147976e+01 -2.95999222e+01 -2.90242729e+01 -2.84713669e+01 -2.88138847e+01 -2.92328262e+01 -2.81566200e+01 -2.89185123e+01 -2.80455246e+01 -2.81506557e+01 -2.76608829e+01 -2.81418629e+01 -2.78272724e+01 -2.67611599e+01 -2.63316040e+01 -2.54942455e+01 -2.55422478e+01 -2.48849907e+01 -2.46972542e+01 -2.46746273e+01 -2.42670593e+01 -2.40763798e+01 -2.39796638e+01 -2.41814079e+01 -2.42121830e+01 -2.36037731e+01 -2.28316479e+01 -2.23400879e+01 -2.22339954e+01 -2.19579048e+01 -2.15192509e+01 -2.09451790e+01 -2.01530800e+01 -1.98166695e+01 -1.99231358e+01 -2.00406399e+01 -2.01531754e+01 -1.93611221e+01 -1.92061462e+01 -1.87412167e+01 -1.89095364e+01 -1.87027817e+01 -1.73822880e+01 -1.71253090e+01 -1.66129379e+01 -1.71893215e+01 -1.72649918e+01 -1.68200417e+01 -1.69484367e+01 -1.55448017e+01 -1.48663626e+01 -1.50014486e+01 -1.45894051e+01 -1.48110485e+01 -1.47864227e+01 -1.49593706e+01 -1.44997759e+01 -1.33552761e+01 -1.30552635e+01 -1.28067026e+01 -1.23415165e+01 -1.16535797e+01 -1.08199644e+01 -1.19959984e+01 -1.88417492e+01 -2.43259506e+01 -1.75613403e+01 -1.80156250e+01 -1.66298866e+01 -9.01520824e+00 -8.85804367e+00 -8.70572567e+00 -8.18649292e+00 -6.75570107e+00 -8.67412627e-01 -6.81558132e+00 -1.37798065e+02 -2.04119431e+02 -4.10134308e+02 -1.10476147e+03 -266767888. 105182784. 0. 0. 41271896. 41271896. 41271896. 0. 0. 0. -10370003. -1.81799725e+06 7.94732812e+04 -1.18621973e+03 -6.16771362e+02 -3.40557678e+02 -2.38883942e+02 -6.02879829e+01 -2.31003304e+01 -2.77447472e+01 -2.08345299e+01 -9.09373188e+00 -9.82702672e-01 7.64430642e-01 1.81850541e+00 2.68915296e+00 2.59946203e+00 2.89279461e+00 2.93234301e+00 2.53934288e+00 -2.95249867e+00 -8.18999577e+00 -2.45264244e+00 4.49514961e+00 6.31502151e+00 6.61777973e+00 5.97518444e+00 8.13003540e+00 1.38828459e+01 1.34075317e+01 7.13618517e+00 2.99461269e+00 5.66473818e+00 9.86581039e+00 1.50210009e+01 2.07709866e+01 1.16834688e+01 4.08952188e+00 7.32618237e+00 8.91412926e+00 9.80611992e+00 1.02412319e+01 1.07372274e+01 1.11215448e+01 1.15207577e+01 1.16866531e+01 1.20402098e+01 1.23722782e+01 1.26598606e+01 1.28942833e+01 1.31961079e+01 1.36085367e+01 1.39642210e+01 1.43182535e+01 1.45695782e+01 1.48698521e+01 1.50908899e+01 1.54785175e+01 1.58464499e+01 1.61031876e+01 1.63016357e+01 1.66656055e+01 1.69623623e+01 1.72744808e+01 1.75432396e+01 1.78939590e+01 1.82341404e+01 1.85660553e+01 1.87768250e+01 1.90792885e+01 1.93959026e+01 1.97675381e+01 2.00907097e+01 2.04697170e+01 2.07774734e+01 2.11265736e+01 2.13677998e+01 2.16666908e+01 2.19784698e+01 2.23040276e+01 2.25930176e+01 2.28858013e+01 2.32169399e+01 2.35164547e+01 2.35287132e+01 2.38142376e+01 2.41536446e+01 2.45837288e+01 2.49459133e+01 2.52562714e+01 2.54973392e+01 2.54763813e+01 2.52751598e+01 2.54126911e+01 2.44634972e+01 7.01441345e+02 3.21153908e+01 2.12633438e+01 2.14191265e+01 2.16253033e+01 2.19456196e+01 2.22462902e+01 2.23853188e+01 2.24149742e+01 2.26495266e+01 2.31159534e+01 2.33363075e+01 2.37144833e+01 2.38561802e+01 2.39991055e+01 2.40533981e+01 2.41404705e+01 2.42013187e+01 2.42510548e+01 2.42733822e+01 2.43581219e+01 2.44328365e+01 2.44796906e+01 2.46142693e+01 2.46631126e+01 2.46557751e+01 2.47140083e+01 2.47939854e+01 2.48897648e+01 2.48909302e+01 2.50027676e+01 2.50670605e+01 2.50949383e+01 2.50784473e+01 2.51254234e+01 2.51345253e+01 2.52581387e+01 2.53400955e+01 2.54015179e+01 2.53566322e+01 2.53867760e+01 2.54302692e+01 2.54293919e+01 2.55595627e+01 2.55803757e+01 2.55852909e+01 2.56013794e+01 2.56616592e+01 2.57494888e+01 2.57867680e+01 2.58446178e+01 2.58676720e+01 2.60645771e+01 2.61038895e+01 2.61124763e+01 2.59282703e+01 2.59549084e+01 2.59814720e+01 2.60656910e+01 2.59272728e+01 2.59193897e+01 2.59911575e+01 2.63428764e+01 2.64682446e+01 2.64872150e+01 2.63057861e+01 2.63325806e+01 2.63289452e+01 2.63519993e+01 2.62313194e+01 2.61425571e+01 2.61840534e+01 2.63857937e+01 2.60274220e+01 2.57152786e+01 2.58432007e+01 2.59905071e+01 2.60504608e+01 2.62321339e+01 2.59696007e+01 2.65588684e+01 2.91113834e+01 2.56466732e+01 -6.90757294e+01 -1.25415230e+02 -2.68781769e+02 2.31371292e+02 7.41960831e+01 -8.13489197e+02 396830720. -1123158528. -1123158528. 1841341. 401538080. 401538080. 0. 0. 0. 0. 0. 0. -460605760. 42401352. 2.25080176e+04 -9.81433228e+02 -4.67140869e+02 -1.05246834e+02 2.32337437e+01 2.45464783e+01 2.77052746e+01 2.62109337e+01 2.35984974e+01 2.31309605e+01 1.40641470e+01 1.99675350e+01 2.84205227e+01 2.80426292e+01 2.68616657e+01 2.64910870e+01 2.66711769e+01 2.59771633e+01 2.56184464e+01 2.56719856e+01 2.56395435e+01 2.62386436e+01 2.66544647e+01 2.70863457e+01 2.66305695e+01 2.62897358e+01 2.56536541e+01 2.56466141e+01 2.67419567e+01 2.80758686e+01 2.57188320e+01 2.32192192e+01 2.34570808e+01 2.42468643e+01 2.46228390e+01 2.47994347e+01 2.48387070e+01 2.46154137e+01 2.55474014e+01 2.55269928e+01 2.52981319e+01 2.56056232e+01 2.67438030e+01 2.54493885e+01 2.45512390e+01 2.39857502e+01 2.49357758e+01 2.48677483e+01 2.50308781e+01 2.51774921e+01 2.51917152e+01 2.46767387e+01 2.37902203e+01 2.30296326e+01 2.34234657e+01 2.36904736e+01 2.41427231e+01 2.42230053e+01 2.47245502e+01 2.47327557e+01 2.39710541e+01 2.36303596e+01 2.33348846e+01 2.37658405e+01 2.39951973e+01 2.40844460e+01 2.42433987e+01 2.35806332e+01 2.37199230e+01 2.30638962e+01 2.25103283e+01 2.11698704e+01 2.12111034e+01 2.15120754e+01 2.21939278e+01 2.18488560e+01 2.25107136e+01 2.23602009e+01 2.24963722e+01 2.18587742e+01 2.15855541e+01 2.17493725e+01 2.15876369e+01 2.14009609e+01 2.09891510e+01 2.09209709e+01 2.04052067e+01 2.02566948e+01 2.08347969e+01 2.10942192e+01 2.13609447e+01 2.07856636e+01 2.04413986e+01 1.96503830e+01 1.94065628e+01 2.03046722e+01 2.07303123e+01 2.09481869e+01 2.01196804e+01 1.95036259e+01 1.89566536e+01 1.87722492e+01 1.95936871e+01 1.95670528e+01 2.03533840e+01 1.97278347e+01 1.91623459e+01 1.83023815e+01 1.84436970e+01 1.90284214e+01 1.91469059e+01 1.86654778e+01 1.84006844e+01 1.84051418e+01 1.88010883e+01 1.85638351e+01 1.83530827e+01 1.77386150e+01 1.77358322e+01 1.75596981e+01 1.73817101e+01 1.71904774e+01 1.75622692e+01 1.73212624e+01 1.74131317e+01 1.72622833e+01 1.69047890e+01 1.64680252e+01 1.64063568e+01 1.64464130e+01 1.64914551e+01 1.62007809e+01 1.58557367e+01 1.58435659e+01 1.57758827e+01 1.58008757e+01 1.57517662e+01 1.54123783e+01 1.52177753e+01 1.49077463e+01 1.48877687e+01 1.47868767e+01 1.46851635e+01 1.45772486e+01 1.44155893e+01 1.42732496e+01 1.41273184e+01 1.40144062e+01 1.39481115e+01 1.37453232e+01 1.36112890e+01 1.35673208e+01 1.33241653e+01 1.31726933e+01 1.31749353e+01 1.28123560e+01 1.27103319e+01 1.27428131e+01 1.24467363e+01 1.24360647e+01 1.22004042e+01 1.19885015e+01 1.20411797e+01 1.18519421e+01 1.15875416e+01 1.15849991e+01 1.15387907e+01 1.13576269e+01 1.13006735e+01 1.10926991e+01 1.08768539e+01 1.07279835e+01 1.04084501e+01 1.02058735e+01 1.00888748e+01 9.95769119e+00 9.86583233e+00 9.77279663e+00 9.35133266e+00 9.19005013e+00 9.39425373e+00 9.43212700e+00 8.99865150e+00 9.19160652e+00 8.89862728e+00 8.90372276e+00 8.24064255e+00 7.99607658e+00 7.80401850e+00 8.03312874e+00 7.88608980e+00 7.92277670e+00 7.42232990e+00 7.37181044e+00 7.14467096e+00 7.08563709e+00 7.06237984e+00 6.63583374e+00 6.79720068e+00 6.34794188e+00 6.41677618e+00 6.14289999e+00 5.65542603e+00 5.79908276e+00 5.94731617e+00 6.08413076e+00 5.80942440e+00 5.30059719e+00 4.69792318e+00 4.62315845e+00 4.89641762e+00 4.61320066e+00 3.49049473e+00 3.36438870e+00 3.65049314e+00 4.05888319e+00 4.17348909e+00 4.14565134e+00 3.49275064e+00 3.36206746e+00 3.56578183e+00 3.56471920e+00 2.72765851e+00 2.75860643e+00 2.63059330e+00 2.50427556e+00 1.00780904e+00 -4.00593728e-02 -1.95282832e-01 2.34530836e-01 3.83367956e-01 1.20149887e+00 1.12804019e+00 1.20582986e+00 -8.13823845e-03 1.54639512e-01 5.92398524e-01 2.47939184e-01 4.98596042e-01 9.49244276e-02 2.44144008e-01 -9.53875601e-01 -1.40533543e+00 -1.29324675e+00 -5.12845397e-01 -1.11402833e+00 -1.47907650e+00 -1.99774647e+00 -1.36617494e+00 -1.38193536e+00 -1.16722190e+00 -1.80401921e+00 -1.98173416e+00 -2.78163958e+00 -3.01129532e+00 -2.74321818e+00 -3.29794002e+00 -3.37960196e+00 -3.59823155e+00 -3.05667877e+00 -2.54901409e+00 -3.13947010e+00 -2.87480021e+00 -3.11163068e+00 -2.54617476e+00 -3.11442542e+00 -3.93696713e+00 -4.11051893e+00 -4.64008808e+00 -4.73906422e+00 -5.12591839e+00 -4.95730782e+00 -4.55022478e+00 -5.28184748e+00 -5.84943581e+00 -6.10989285e+00 -6.05291796e+00 -5.45770836e+00 -5.03860092e+00 -4.61258602e+00 -5.49184847e+00 -6.35013056e+00 -6.57447767e+00 -6.49678230e+00 -6.79746675e+00 -6.93743181e+00 -7.71751785e+00 -8.00001907e+00 -8.53705502e+00 -8.54180241e+00 -8.74628067e+00 -8.75772095e+00 -8.81570530e+00 -9.35192204e+00 -9.09453297e+00 -8.88563633e+00 -8.97017097e+00 -9.12885857e+00 -8.82445526e+00 -9.31174660e+00 -9.65589905e+00 -1.03691158e+01 -9.60928535e+00 -1.01763344e+01 -9.89561749e+00 -1.00879364e+01 -9.91742325e+00 -1.04998360e+01 -1.11349430e+01 -1.19339495e+01 -1.14488859e+01 -1.12608299e+01 -1.10273304e+01 -1.12282219e+01 -1.11665859e+01 -1.13660183e+01 -1.20701036e+01 -1.26983404e+01 -1.26592703e+01 -1.24703455e+01 -1.24982243e+01 -1.25353136e+01 -1.23741903e+01 -1.27801437e+01 -1.27299595e+01 -1.31075058e+01 -1.35234041e+01 -1.39536324e+01 -1.42761345e+01 -1.41698904e+01 -1.41476173e+01 -1.43921595e+01 -1.42532415e+01 -1.44774075e+01 -1.44525537e+01 -1.47388325e+01 -1.48840961e+01 -1.49155521e+01 -1.50711479e+01 -1.52909060e+01 -1.55019598e+01 -1.56141195e+01 -1.59685907e+01 -1.60636463e+01 -1.59177637e+01 -1.60195789e+01 -1.60078621e+01 -1.62855301e+01 -1.64925880e+01 -1.68819370e+01 -1.70663853e+01 -1.69083271e+01 -1.67558231e+01 -1.66694946e+01 -1.70470486e+01 -1.73715324e+01 -1.76688042e+01 -1.77519035e+01 -1.76883430e+01 -1.77724876e+01 -1.76833000e+01 -1.78563938e+01 -1.80436287e+01 -1.83442917e+01 -1.84138603e+01 -1.84255238e+01 -1.85145397e+01 -1.86819477e+01 -1.87326584e+01 -1.88140430e+01 -1.87387600e+01 -1.89405060e+01 -1.90433731e+01 -1.92214394e+01 -1.93744049e+01 -1.95067635e+01 -1.96086655e+01 -1.96943817e+01 -1.97530804e+01 -1.98876858e+01 -1.99643345e+01 -2.01110611e+01 -2.02051926e+01 -2.03171062e+01 -2.04208469e+01 -2.05189667e+01 -2.05915108e+01 -2.06853676e+01 -2.08196354e+01 -2.09226799e+01 -2.10024014e+01 -2.11018963e+01 -2.11995144e+01 -2.13206215e+01 -2.13946171e+01 -2.14851799e+01 -2.15739918e+01 -2.16524525e+01 -2.17211342e+01 -2.18324051e+01 -2.19376774e+01 -2.20102921e+01 -2.20990238e+01 -2.21870995e+01 -2.22738705e+01 -2.23618412e+01 -2.24463062e+01 -2.25358620e+01 -2.26266346e+01 -2.27183781e+01 -2.28003559e+01 -2.28813324e+01 -2.29662800e+01 -2.30425777e+01 -2.31118584e+01 -2.31953506e+01 -2.32684135e+01 -2.33390179e+01 -2.34189930e+01 -2.34784756e+01 -2.35415649e+01 -2.36248989e+01 -2.37037239e+01 -2.37758160e+01 -2.38441620e+01 -2.39165020e+01 -2.39667377e+01 -2.40226460e+01 -2.40533409e+01 -2.41177940e+01 -2.41883907e+01 -2.42494755e+01 -2.43571510e+01 -2.44172001e+01 -2.43758621e+01 -2.44387417e+01 -2.45371571e+01 -2.46025372e+01 -2.46765461e+01 -2.48666630e+01 -2.48856831e+01 -2.48387985e+01 -2.48312817e+01 -2.48673210e+01 -2.48594761e+01 -2.49628086e+01 -2.50516663e+01 -2.51397953e+01 -2.51779938e+01 -2.52196426e+01 -2.52483902e+01 -2.52974148e+01 -2.53446369e+01 -2.53723907e+01 -2.54663811e+01 -2.54539318e+01 -2.55374546e+01 -2.56595173e+01 -2.56338406e+01 -2.58048401e+01 -2.57807140e+01 -2.57927437e+01 -2.57916012e+01 -2.57934246e+01 -2.57228565e+01 -2.57073860e+01 -2.56674614e+01 -2.57176685e+01 -2.55099564e+01 -2.55090771e+01 -2.55859928e+01 -2.60854969e+01 -2.63258133e+01 -2.63519478e+01 -2.61322002e+01 -2.62211266e+01 -2.62293110e+01 -2.63048344e+01 -2.61665001e+01 -2.60963860e+01 -2.60205269e+01 -2.58070011e+01 -2.54579220e+01 -2.52484226e+01 -2.53324432e+01 -2.54423122e+01 -2.55526524e+01 -2.59978237e+01 -2.60427494e+01 -2.61657124e+01 -2.60004063e+01 -2.61830444e+01 -2.63353691e+01 -2.60732422e+01 -2.61670151e+01 -2.62500839e+01 -2.63015175e+01 -2.58312778e+01 -2.56440697e+01 -2.57498817e+01 -2.61618042e+01 -2.61976070e+01 -2.60028248e+01 -2.56096401e+01 -2.60568161e+01 -2.62247295e+01 -2.63937130e+01 -2.63629494e+01 -2.60671539e+01 -2.57749195e+01 -2.56806030e+01 -2.61024208e+01 -2.60204258e+01 -2.62766151e+01 -2.61124020e+01 -2.63963184e+01 -2.67966499e+01 -2.63319092e+01 -2.65288334e+01 -2.62241116e+01 -2.65439873e+01 -2.61411057e+01 -2.56211872e+01 -2.56466484e+01 -2.56392078e+01 -2.57659187e+01 -2.58788128e+01 -2.57102757e+01 -2.59920483e+01 -2.55278282e+01 -2.54194469e+01 -2.52608509e+01 -2.51639290e+01 -2.59449253e+01 -2.62873058e+01 -2.69097252e+01 -2.63184528e+01 -2.62375240e+01 -2.58392296e+01 -2.56021252e+01 -2.51112728e+01 -2.55117855e+01 -2.49653606e+01 -2.44969730e+01 -2.40312881e+01 -2.44002647e+01 -2.45689735e+01 -2.46428623e+01 -2.48414249e+01 -2.44330292e+01 -2.49752998e+01 -2.49982224e+01 -2.47597961e+01 -2.48675861e+01 -2.52936783e+01 -2.46940765e+01 -2.45956135e+01 -2.37439156e+01 -2.44389286e+01 -2.43993092e+01 -2.45918427e+01 -2.44273548e+01 -2.48241253e+01 -2.42231483e+01 -2.35643654e+01 -2.29329681e+01 -2.39635448e+01 -2.40340557e+01 -2.41142941e+01 -2.41065807e+01 -2.45366192e+01 -2.44955273e+01 -2.37759418e+01 -2.32066631e+01 -2.29166660e+01 -2.30578060e+01 -2.32217083e+01 -2.33175354e+01 -2.40060482e+01 -2.35948105e+01 -2.35633411e+01 -2.30348892e+01 -2.23984394e+01 -2.15979481e+01 -2.16868801e+01 -2.20461979e+01 -2.21812897e+01 -2.17356033e+01 -2.20085468e+01 -2.19264355e+01 -2.18619766e+01 -2.17607212e+01 -2.15666027e+01 -2.17016506e+01 -2.16414566e+01 -2.14051819e+01 -2.12746735e+01 -2.12978020e+01 -2.05895290e+01 -2.02895584e+01 -2.08267822e+01 -2.09089699e+01 -2.09331112e+01 -2.06043072e+01 -2.01962299e+01 -1.95359955e+01 -1.93453083e+01 -2.01459179e+01 -2.06014061e+01 -2.08869724e+01 -2.01229935e+01 -1.93283691e+01 -1.88441086e+01 -1.87659187e+01 -1.93696690e+01 -1.94901066e+01 -2.00100994e+01 -1.95034046e+01 -1.88567352e+01 -1.78111973e+01 -1.81681290e+01 -1.86361122e+01 -1.89716663e+01 -1.82859058e+01 -1.80480595e+01 -1.82111111e+01 -1.87506466e+01 -1.80541267e+01 -1.79705219e+01 -1.78648357e+01 -1.77364597e+01 -1.74840164e+01 -1.73865528e+01 -1.75793781e+01 -1.73457699e+01 -1.70621681e+01 -1.72314167e+01 -1.70899391e+01 -1.69048100e+01 -1.63991585e+01 -1.63793716e+01 -1.64804440e+01 -1.66247215e+01 -1.64619617e+01 -1.61416550e+01 -1.59707537e+01 -1.55604610e+01 -1.56029711e+01 -1.57446222e+01 -1.52989607e+01 -1.51483822e+01 -1.48023376e+01 -1.48307619e+01 -1.47752972e+01 -1.46235819e+01 -1.46271820e+01 -1.45160599e+01 -1.44455280e+01 -1.40951958e+01 -1.39417639e+01 -1.37794247e+01 -1.34965363e+01 -1.34255972e+01 -1.33970881e+01 -1.29802027e+01 -1.29815207e+01 -1.29981060e+01 -1.25993853e+01 -1.25699110e+01 -1.24631681e+01 -1.21863079e+01 -1.22939930e+01 -1.23118849e+01 -1.19165859e+01 -1.18233814e+01 -1.19279337e+01 -1.14970093e+01 -1.14842653e+01 -1.15022631e+01 -1.11113434e+01 -1.10757265e+01 -1.09344225e+01 -1.08039684e+01 -1.07171669e+01 -1.02989826e+01 -1.01957884e+01 -1.00067883e+01 -9.83235931e+00 -9.91965961e+00 -9.68891525e+00 -9.09502506e+00 -9.03375912e+00 -8.90816784e+00 -8.90039253e+00 -8.90859795e+00 -8.99458885e+00 -8.70618153e+00 -8.43236065e+00 -8.16021347e+00 -8.26510525e+00 -7.98692846e+00 -8.01843834e+00 -7.85539007e+00 -7.88409996e+00 -7.31005096e+00 -7.15332985e+00 -7.03342152e+00 -6.67007065e+00 -6.65038347e+00 -6.67258978e+00 -6.70457029e+00 -6.00173044e+00 -5.92023611e+00 -5.68692636e+00 -5.31086540e+00 -5.33280516e+00 -5.61946106e+00 -5.89954138e+00 -5.35987759e+00 -4.99149275e+00 -4.37526560e+00 -4.32848358e+00 -4.30487394e+00 -4.33423138e+00 -3.38641953e+00 -3.19600034e+00 -3.37901855e+00 -4.00707197e+00 -4.19838190e+00 -4.30953121e+00 -3.38339305e+00 -3.06633186e+00 -3.33249378e+00 -3.43117571e+00 -2.76719189e+00 -2.30523205e+00 -2.18898511e+00 -2.22050953e+00 -1.03824031e+00 -1.37495250e-01 -1.98726788e-01 -3.73382479e-01 6.52749315e-02 -9.08018887e-01 -1.03101003e+00 -9.83244181e-01 -8.48002210e-02 -2.68637657e-01 -5.43655753e-01 -1.68149248e-01 -2.41701782e-01 3.02710205e-01 9.03429389e-02 1.02671254e+00 1.28547478e+00 1.18341935e+00 1.10295725e+00 1.48904407e+00 1.51125455e+00 2.01832199e+00 1.51891744e+00 1.74595368e+00 1.40569651e+00 2.11164761e+00 2.35065198e+00 3.02745771e+00 3.06176686e+00 3.09385562e+00 3.54168487e+00 3.12520528e+00 3.29417467e+00 2.91127133e+00 2.64202213e+00 3.01998806e+00 2.81914735e+00 3.65826917e+00 3.37352443e+00 3.88488603e+00 4.43647909e+00 4.76252031e+00 5.15157747e+00 4.92718267e+00 5.00040483e+00 4.97511530e+00 4.74863386e+00 5.70567751e+00 6.28807974e+00 6.43492079e+00 6.54604912e+00 5.75844717e+00 5.19997406e+00 4.63726330e+00 5.49357271e+00 6.22368002e+00 6.99757719e+00 7.18630791e+00 7.71106577e+00 7.64719343e+00 7.77090406e+00 7.76820850e+00 8.48419571e+00 2.80336952e+00 1.95373809e+00 1.46658659e+00 3.04191422e+00 4.56867361e+00 4.14630270e+00 9.86151123e+00 9.96104336e+00 1.00244932e+01 9.71148491e+00 1.06752234e+01 1.42958937e+01 1.37867584e+01 -1.12151024e+02 -1.92547943e+02 -4.00247711e+02 -1.18183887e+03 12580737. -126164672. 0. 0. 0. 4.97597850e+09 4.97597850e+09 4.97597850e+09 0. 0. 0. 51098584. 4.43151150e+06 -1.98542590e+03 -6.61543091e+02 -1.65770493e+02 -2.54349426e+02 -1.60209915e+02 -5.91024017e+00 -8.37418175e+00 -2.33665490e+00 6.67927122e+00 1.17617369e+01 8.62431335e+00 9.35392284e+00 1.27822857e+01 1.31935682e+01 1.32722845e+01 1.17310848e+01 5.19060135e+00 6.28563929e+00 1.43931208e+01 1.65855312e+01 1.66679058e+01 1.56169376e+01 1.68279324e+01 1.93383980e+01 1.81066093e+01 1.49981842e+01 1.33194618e+01 1.86890030e+01 1.82308884e+01 1.92602215e+01 2.55710468e+01 1.90630875e+01 1.52642918e+01 1.89413853e+01 1.64846115e+01 1.50866499e+01 1.65732079e+01 1.73857021e+01 1.77857876e+01 1.77984200e+01 1.78351974e+01 1.77030296e+01 1.80476475e+01 1.82617455e+01 1.85105305e+01 1.85553417e+01 1.86262360e+01 1.86857510e+01 1.87759819e+01 1.88816338e+01 1.89872017e+01 1.89707508e+01 1.91913300e+01 1.93446407e+01 1.94603825e+01 1.96384296e+01 1.98249187e+01 2.00198307e+01 2.00848579e+01 2.00428162e+01 2.01286087e+01 2.02392063e+01 2.03852539e+01 2.04688416e+01 2.06051998e+01 2.07354965e+01 2.08121471e+01 2.09222126e+01 2.09775887e+01 2.07580376e+01 2.07836933e+01 2.08030453e+01 2.07890015e+01 2.07955379e+01 2.06888428e+01 2.06648254e+01 2.09003830e+01 2.04862061e+01 2.00719433e+01 1.99116993e+01 2.00408916e+01 2.02261219e+01 2.03172817e+01 2.04072609e+01 2.04674282e+01 2.05293331e+01 2.05284538e+01 2.05505772e+01 2.07149448e+01 2.04821529e+01 3.11084961e+02 2.77322044e+01 1.79973660e+01 1.82851734e+01 1.85327454e+01 1.88119411e+01 1.91937428e+01 1.95446148e+01 1.96383457e+01 1.98443642e+01 2.01669540e+01 2.04175625e+01 2.07842407e+01 2.10428524e+01 2.13498230e+01 2.16335583e+01 2.18860722e+01 2.21565647e+01 2.26027985e+01 2.33162060e+01 2.41103859e+01 2.46183834e+01 2.47766705e+01 2.49508247e+01 2.50485077e+01 2.51659279e+01 2.53183060e+01 2.55340462e+01 2.57700958e+01 2.60350342e+01 2.61909885e+01 2.64844704e+01 2.67152557e+01 2.70011711e+01 2.72242851e+01 2.74479485e+01 2.76417656e+01 2.79031601e+01 2.81756897e+01 2.84727459e+01 2.87107258e+01 2.87472038e+01 2.89618587e+01 2.91126232e+01 2.94889507e+01 2.96002502e+01 2.97936459e+01 2.99713383e+01 3.01171894e+01 3.02908611e+01 3.05684013e+01 3.07934666e+01 3.12187023e+01 3.13482914e+01 3.14656639e+01 3.16251450e+01 3.17505894e+01 3.20578423e+01 3.23799706e+01 3.25235291e+01 3.28239517e+01 3.31147079e+01 3.33572960e+01 3.34792252e+01 3.35261116e+01 3.36476326e+01 3.38369026e+01 3.39282799e+01 3.39513855e+01 3.43068962e+01 3.44040947e+01 3.47183151e+01 3.50022011e+01 3.51726189e+01 3.54986954e+01 3.58739433e+01 3.57284927e+01 3.57581520e+01 3.51172485e+01 3.45410461e+01 2.99179020e+01 -5.89632530e+01 -1.26620552e+02 -3.04828064e+02 -8.16039246e+02 -132549216. 3.83057350e+06 -157534928. -157534928. 0. -131372528. -131372528. -20722990. 401538080. 401538080. 0. 0. 0. 0. -1167919104. -20580638. -1.05170459e+03 -3.37784943e+02 1.01461098e+02 -1.53163391e+02 -7.87236099e+01 4.14086227e+01 3.91117668e+01 3.57043915e+01 3.97849846e+01 4.11133766e+01 3.93298988e+01 3.87013855e+01 3.91704597e+01 4.29257851e+01 4.25476532e+01 4.21430168e+01 4.16586952e+01 4.23173218e+01 4.23425789e+01 4.27124214e+01 4.25071754e+01 4.26438942e+01 4.29570732e+01 4.30191803e+01 4.31108971e+01 4.29310875e+01 4.34385796e+01 4.35771523e+01 4.37256470e+01 4.40140381e+01 4.39189606e+01 4.37432556e+01 4.39977989e+01 4.43020554e+01 4.44809532e+01 4.46477242e+01 4.48209991e+01 4.48325958e+01 4.45796127e+01 4.49916077e+01 4.54177475e+01 4.56594124e+01 4.59542351e+01 4.60814972e+01 4.54121819e+01 4.56985550e+01 4.57195587e+01 4.55979843e+01 4.55296021e+01 4.56099358e+01 4.59170647e+01 4.64563446e+01 4.59382935e+01 4.54108582e+01 4.54352646e+01 4.51692581e+01 4.49951477e+01 4.46676674e+01 4.55727158e+01 4.57754517e+01 4.57315254e+01 4.61249619e+01 4.67992287e+01 4.74091988e+01 4.65782776e+01 4.64028015e+01 4.58421631e+01 4.57399025e+01 4.57923622e+01 4.63626938e+01 4.66135521e+01 4.65136490e+01 4.61979523e+01 4.62345848e+01 4.65255966e+01 4.66947441e+01 4.60790062e+01 4.64595032e+01 4.62677536e+01 4.68099403e+01 4.63876076e+01 4.68708191e+01 4.62068100e+01 4.63789444e+01 4.59696159e+01 4.64523468e+01 4.63751717e+01 4.70356750e+01 4.70344543e+01 4.67422180e+01 4.66243019e+01 4.64777908e+01 4.69280014e+01 4.64293365e+01 4.64692535e+01 4.65171700e+01 4.66322060e+01 4.65919533e+01 4.67139359e+01 4.62345772e+01 4.62747993e+01 4.60641365e+01 4.63735504e+01 4.64305038e+01 4.65355759e+01 4.61734734e+01 4.59332390e+01 4.63433609e+01 4.65592155e+01 4.67919388e+01 4.64089890e+01 4.59595833e+01 4.59351692e+01 4.61370010e+01 4.58710556e+01 4.55021515e+01 4.49407043e+01 4.55287819e+01 4.57715797e+01 4.56237297e+01 4.53774567e+01 4.51644554e+01 4.55040779e+01 4.52369270e+01 4.50023575e+01 4.49514351e+01 4.50514183e+01 4.51644974e+01 4.46083946e+01 4.46195412e+01 4.45794868e+01 4.48747444e+01 4.50075073e+01 4.49092026e+01 4.47421722e+01 4.50136986e+01 4.48178520e+01 4.47574997e+01 4.44315681e+01 4.41688232e+01 4.41837845e+01 4.40632858e+01 4.40936928e+01 4.39019127e+01 4.37414665e+01 4.37303696e+01 4.35941124e+01 4.33553696e+01 4.31543159e+01 4.31825790e+01 4.30330887e+01 4.29691696e+01 4.28560295e+01 4.27472687e+01 4.26340103e+01 4.25479469e+01 4.25596542e+01 4.22896614e+01 4.22664146e+01 4.22157707e+01 4.18984070e+01 4.17087250e+01 4.15237274e+01 4.14809990e+01 4.14789810e+01 4.13418922e+01 4.12072945e+01 4.09965439e+01 4.07994499e+01 4.06509323e+01 4.07952309e+01 4.04964790e+01 4.03311348e+01 4.01854286e+01 4.00688820e+01 3.98295708e+01 3.97747078e+01 3.95749283e+01 3.95834808e+01 3.94625626e+01 3.94733086e+01 3.89338608e+01 3.90527992e+01 3.88015823e+01 3.85368538e+01 3.80966644e+01 3.84489288e+01 3.83967857e+01 3.84650421e+01 3.78360100e+01 3.77701836e+01 3.75295296e+01 3.77924080e+01 3.77615700e+01 3.76238632e+01 3.72570877e+01 3.64393158e+01 3.65534401e+01 3.60072365e+01 3.59889755e+01 3.59610329e+01 3.59507027e+01 3.54583549e+01 3.48158875e+01 3.44512978e+01 3.46112213e+01 3.47916298e+01 3.49812393e+01 3.43201981e+01 3.40358429e+01 3.38232307e+01 3.35284920e+01 3.37276230e+01 3.38938637e+01 3.30812263e+01 3.33124886e+01 3.32368622e+01 3.24873543e+01 3.22277832e+01 3.24102516e+01 3.17398548e+01 3.11210709e+01 3.08127098e+01 3.04328384e+01 3.05462513e+01 3.04783516e+01 3.04932766e+01 3.01985779e+01 3.02051144e+01 3.02400875e+01 3.03914661e+01 2.96655483e+01 2.95210419e+01 2.80351601e+01 2.84168282e+01 2.84872475e+01 2.86746349e+01 2.82386169e+01 2.74395981e+01 2.78421612e+01 2.75621796e+01 2.72771111e+01 2.71044064e+01 2.68496113e+01 2.72538948e+01 2.64339333e+01 2.63632889e+01 2.54380341e+01 2.54545383e+01 2.45194511e+01 2.46320400e+01 2.43065662e+01 2.40774212e+01 2.40246391e+01 2.40428562e+01 2.35337639e+01 2.32413197e+01 2.35960693e+01 2.39169884e+01 2.40268536e+01 2.34605331e+01 2.32326908e+01 2.21607513e+01 2.22818985e+01 2.18952789e+01 2.13590546e+01 2.06875725e+01 1.97170429e+01 2.04229145e+01 2.00652409e+01 2.01117477e+01 1.94961319e+01 1.88430882e+01 1.92796936e+01 1.88406391e+01 1.90323277e+01 1.80565205e+01 1.77695541e+01 1.83527565e+01 1.80985107e+01 1.78365574e+01 1.71109524e+01 1.69880943e+01 1.65399227e+01 1.63906765e+01 1.60584526e+01 1.58634377e+01 1.61138744e+01 1.57682915e+01 1.52713165e+01 1.46348219e+01 1.47245531e+01 1.44425240e+01 1.38738823e+01 1.35989008e+01 1.35609417e+01 1.32495499e+01 1.33373404e+01 1.37111597e+01 1.34836779e+01 1.30008049e+01 1.24426699e+01 1.19659328e+01 1.12894926e+01 1.08800421e+01 1.09187517e+01 1.12173119e+01 1.11752033e+01 1.01988621e+01 9.24178982e+00 9.18560219e+00 8.79228115e+00 8.73092270e+00 8.25531197e+00 8.77051926e+00 8.54253387e+00 7.80305815e+00 7.28466177e+00 7.01033115e+00 7.10483503e+00 6.53313828e+00 6.19879627e+00 5.54872656e+00 5.22592783e+00 5.07990980e+00 5.27187252e+00 5.09020805e+00 4.65698671e+00 4.21069622e+00 4.01037407e+00 3.94514489e+00 3.61509299e+00 2.90886211e+00 2.65006876e+00 2.30778313e+00 2.33185673e+00 1.90477169e+00 1.73438859e+00 1.16891205e+00 1.03560102e+00 6.34859502e-01 4.87623483e-01 8.02651700e-03 5.92552647e-02 -2.90920526e-01 -6.55882478e-01 -8.21223736e-01 -1.05116200e+00 -1.07655942e+00 -1.56983674e+00 -1.99604428e+00 -2.25683951e+00 -2.51876497e+00 -2.83876801e+00 -3.01565146e+00 -3.33443141e+00 -3.49638510e+00 -3.81405854e+00 -4.07921362e+00 -4.37069511e+00 -4.68674517e+00 -5.06856632e+00 -5.48923826e+00 -5.67838573e+00 -5.84998608e+00 -6.06578970e+00 -6.39162350e+00 -6.75905752e+00 -6.97422361e+00 -7.24360895e+00 -7.60293245e+00 -8.04531384e+00 -8.28516579e+00 -8.44612217e+00 -8.67057514e+00 -9.03717422e+00 -9.40306759e+00 -9.63918304e+00 -9.85541630e+00 -1.01469002e+01 -1.04654665e+01 -1.07114153e+01 -1.09529152e+01 -1.12223577e+01 -1.15754728e+01 -1.18083639e+01 -1.21028938e+01 -1.23343296e+01 -1.25987177e+01 -1.28315897e+01 -1.31102037e+01 -1.33457203e+01 -1.36321554e+01 -1.39476433e+01 -1.42427902e+01 -1.45246878e+01 -1.47774105e+01 -1.50212746e+01 -1.52757406e+01 -1.55529108e+01 -1.58317480e+01 -1.61070709e+01 -1.63828735e+01 -1.66424522e+01 -1.69080486e+01 -1.71710472e+01 -1.74330425e+01 -1.76983662e+01 -1.79599934e+01 -1.82228184e+01 -1.84870701e+01 -1.87470970e+01 -1.90105381e+01 -1.92674751e+01 -1.95325947e+01 -1.97967091e+01 -2.00490971e+01 -2.03160744e+01 -2.05707207e+01 -2.08195305e+01 -2.10799942e+01 -2.13157063e+01 -2.15594406e+01 -2.18247757e+01 -2.20808430e+01 -2.23381672e+01 -2.25999813e+01 -2.28404408e+01 -2.30867157e+01 -2.33562317e+01 -2.35705700e+01 -2.37879791e+01 -2.40662918e+01 -2.42919388e+01 -2.45595360e+01 -2.48062401e+01 -2.49868412e+01 -2.51754341e+01 -2.54395733e+01 -2.56942444e+01 -2.59946709e+01 -2.61942749e+01 -2.64535160e+01 -2.66037045e+01 -2.69135456e+01 -2.71282787e+01 -2.73218231e+01 -2.75378056e+01 -2.77881107e+01 -2.80731258e+01 -2.83484688e+01 -2.85750923e+01 -2.87004070e+01 -2.89169827e+01 -2.90362682e+01 -2.93965931e+01 -2.95524406e+01 -2.97477989e+01 -2.99870167e+01 -3.01459637e+01 -3.03179970e+01 -3.06592083e+01 -3.08458519e+01 -3.11017437e+01 -3.12646885e+01 -3.13606319e+01 -3.15905266e+01 -3.16914845e+01 -3.20200691e+01 -3.22738686e+01 -3.24121056e+01 -3.26266289e+01 -3.30375290e+01 -3.33772926e+01 -3.34700699e+01 -3.34776344e+01 -3.34794960e+01 -3.36914711e+01 -3.39111595e+01 -3.40222130e+01 -3.44269524e+01 -3.45189400e+01 -3.47387085e+01 -3.46692467e+01 -3.49812965e+01 -3.54004822e+01 -3.56508446e+01 -3.55749207e+01 -3.56798172e+01 -3.55623970e+01 -3.59535179e+01 -3.63864899e+01 -3.68030128e+01 -3.69272537e+01 -3.68735504e+01 -3.69684258e+01 -3.70368767e+01 -3.74709587e+01 -3.76543007e+01 -3.77445984e+01 -3.81152229e+01 -3.81923561e+01 -3.82922440e+01 -3.83454323e+01 -3.85408249e+01 -3.83194313e+01 -3.84663734e+01 -3.89267426e+01 -3.90256844e+01 -3.94177399e+01 -3.92838516e+01 -3.93051758e+01 -3.97071037e+01 -4.01198349e+01 -4.05222511e+01 -4.07336349e+01 -4.08815956e+01 -4.13317680e+01 -4.06273041e+01 -4.08377800e+01 -4.06288033e+01 -4.05465050e+01 -4.05505104e+01 -4.03961182e+01 -4.14502296e+01 -4.12365608e+01 -4.13647041e+01 -4.13768730e+01 -4.11057320e+01 -4.18199348e+01 -4.18972588e+01 -4.25970078e+01 -4.22993813e+01 -4.22750130e+01 -4.27473030e+01 -4.31376686e+01 -4.30842934e+01 -4.30155869e+01 -4.32432823e+01 -4.32462845e+01 -4.33044891e+01 -4.34947777e+01 -4.35532761e+01 -4.40727425e+01 -4.39987030e+01 -4.36438217e+01 -4.36065483e+01 -4.40028992e+01 -4.42168427e+01 -4.39580154e+01 -4.38078651e+01 -4.39677238e+01 -4.44735718e+01 -4.51417542e+01 -4.57519302e+01 -4.60439453e+01 -4.57676544e+01 -4.57009964e+01 -4.57171898e+01 -4.52333832e+01 -4.45171661e+01 -4.53850594e+01 -4.57106628e+01 -4.61105156e+01 -4.54773941e+01 -4.50128593e+01 -4.53319016e+01 -4.54687958e+01 -4.57381554e+01 -4.54025536e+01 -4.59672279e+01 -4.61467171e+01 -4.56627007e+01 -4.59405785e+01 -4.61188545e+01 -4.66061401e+01 -4.58323708e+01 -4.57081566e+01 -4.52928467e+01 -4.52423630e+01 -4.56630707e+01 -4.64890862e+01 -4.66127930e+01 -4.64703064e+01 -4.62069740e+01 -4.59692116e+01 -4.62863693e+01 -4.64450760e+01 -4.58545570e+01 -4.57986031e+01 -4.55438919e+01 -4.60850677e+01 -4.59368935e+01 -4.64759712e+01 -4.58867760e+01 -4.60093155e+01 -4.59457207e+01 -4.63987312e+01 -4.62098465e+01 -4.68536491e+01 -4.67676735e+01 -4.65919991e+01 -4.67522812e+01 -4.64963799e+01 -4.67012024e+01 -4.63838730e+01 -4.62627487e+01 -4.65442238e+01 -4.66023827e+01 -4.66362305e+01 -4.65871162e+01 -4.64272003e+01 -4.65526199e+01 -4.61268196e+01 -4.59373932e+01 -4.58781128e+01 -4.59898186e+01 -4.60008659e+01 -4.55923691e+01 -4.57363586e+01 -4.59417877e+01 -4.62303123e+01 -4.60598755e+01 -4.57279892e+01 -4.57322044e+01 -4.56456375e+01 -4.56645737e+01 -4.54350395e+01 -4.52855377e+01 -4.53418388e+01 -4.55729980e+01 -4.55394249e+01 -4.51754723e+01 -4.50003471e+01 -4.52744179e+01 -4.53907509e+01 -4.49317207e+01 -4.49872513e+01 -4.52031136e+01 -4.52550812e+01 -4.47049789e+01 -4.44760857e+01 -4.45752029e+01 -4.50366821e+01 -4.51148987e+01 -4.51336174e+01 -4.49595184e+01 -4.48739471e+01 -4.45329018e+01 -4.45329933e+01 -4.43767357e+01 -4.40695610e+01 -4.39832306e+01 -4.38390083e+01 -4.38801613e+01 -4.39289322e+01 -4.36317749e+01 -4.34786682e+01 -4.33646049e+01 -4.34026299e+01 -4.31451721e+01 -4.31777534e+01 -4.28301773e+01 -4.25291214e+01 -4.25970268e+01 -4.25113068e+01 -4.21887169e+01 -4.23412209e+01 -4.22891388e+01 -4.17682610e+01 -4.17126923e+01 -4.16918831e+01 -4.15322342e+01 -4.16455650e+01 -4.19169235e+01 -4.15800476e+01 -4.12952995e+01 -4.12182808e+01 -4.08005905e+01 -4.07375412e+01 -4.08263016e+01 -4.03722763e+01 -4.05507584e+01 -4.03424835e+01 -4.03470383e+01 -4.04434891e+01 -4.02005234e+01 -4.00594330e+01 -3.99967995e+01 -3.96095734e+01 -3.97727737e+01 -3.96410789e+01 -3.92219887e+01 -3.91325645e+01 -3.89767685e+01 -3.86498032e+01 -3.89680481e+01 -3.84879684e+01 -3.85812683e+01 -3.81287346e+01 -3.85345459e+01 -3.84402695e+01 -3.82785149e+01 -3.79126205e+01 -3.81539612e+01 -3.77530785e+01 -3.74954033e+01 -3.71774673e+01 -3.65362892e+01 -3.63962059e+01 -3.57826233e+01 -3.60626640e+01 -3.58117256e+01 -3.55879898e+01 -3.50373344e+01 -3.46536751e+01 -3.43139801e+01 -3.43944283e+01 -3.43160400e+01 -3.46676292e+01 -3.40076370e+01 -3.34393806e+01 -3.33602982e+01 -3.33347397e+01 -3.35966263e+01 -3.38308678e+01 -3.28688049e+01 -3.30077095e+01 -3.30473633e+01 -3.27237434e+01 -3.24020042e+01 -3.23154335e+01 -3.15838337e+01 -3.09892120e+01 -3.07931099e+01 -3.05832253e+01 -3.06835995e+01 -3.02856560e+01 -3.03873920e+01 -3.00780602e+01 -3.00019436e+01 -2.99404984e+01 -3.02784634e+01 -2.95568428e+01 -2.91184921e+01 -2.78745499e+01 -2.86386471e+01 -2.85249195e+01 -2.85953255e+01 -2.82428665e+01 -2.75807552e+01 -2.78396225e+01 -2.73195419e+01 -2.71703968e+01 -2.70350876e+01 -2.67749977e+01 -2.71624947e+01 -2.65072002e+01 -2.60126610e+01 -2.51665230e+01 -2.51204967e+01 -2.44454536e+01 -2.45210361e+01 -2.45151558e+01 -2.42633743e+01 -2.43198795e+01 -2.39323368e+01 -2.33838825e+01 -2.30864029e+01 -2.32271767e+01 -2.37992363e+01 -2.39203014e+01 -2.36543465e+01 -2.36057014e+01 -2.23390598e+01 -2.23459606e+01 -2.18626156e+01 -2.07458401e+01 -2.02195930e+01 -1.94999161e+01 -2.03332233e+01 -1.98056660e+01 -1.95635071e+01 -1.91449051e+01 -1.85321884e+01 -1.92581158e+01 -1.88530636e+01 -1.88573360e+01 -1.79844761e+01 -1.79128780e+01 -1.84534016e+01 -1.83049297e+01 -1.77870712e+01 -1.71629906e+01 -1.70949707e+01 -1.67794456e+01 -1.64645958e+01 -1.58050480e+01 -1.53402557e+01 -1.52731771e+01 -1.53771534e+01 -1.53344784e+01 -1.47950773e+01 -1.44792795e+01 -1.40160608e+01 -2.09306011e+01 -2.07606277e+01 -1.89577312e+01 -1.82531452e+01 -1.50559111e+01 -1.53159142e+01 -1.21355896e+01 -1.31194534e+01 -1.28037262e+01 -1.09575958e+01 -1.04078970e+01 -5.09951019e+00 -5.09917736e+00 -1.46977921e+02 -2.63215790e+02 -6.16302246e+02 -1.42701758e+03 -147235568. 203670320. 0. 4.97597850e+09 4.97597850e+09 4.97597850e+09 0. 0. 122415200. 122415200. 122415200. 2.63395686e+09 -4587961. -8.12564258e+03 -8.40789307e+02 -4.81444336e+02 -2.44250290e+02 -1.67187119e+02 -2.78908310e+01 -2.11145306e+01 -1.33568230e+01 -1.36346140e+01 -6.50661325e+00 1.04184322e+01 1.22491579e+01 -8.93771744e+00 -1.46328754e+01 -1.02983961e+01 -5.56642914e+00 -9.65466142e-01 -1.11100510e-01 -2.36035854e-01 -8.21050763e-01 -6.78058743e-01 2.27790236e+00 1.08713865e+01 1.04906244e+01 2.01864624e+00 7.18928623e+00 3.85360062e-01 1.39311826e+00 1.14173899e+01 5.33066893e+00 1.36696410e+00 2.56383681e+00 -1.45599976e-01 1.23490632e+00 4.52641487e+00 3.79638886e+00 3.83405113e+00 4.34922171e+00 4.85029745e+00 5.32557917e+00 5.67324972e+00 5.89414597e+00 6.07782936e+00 6.38408995e+00 6.77412176e+00 7.00348616e+00 7.24972486e+00 7.62191153e+00 8.06162071e+00 8.33492374e+00 8.55481434e+00 8.81301308e+00 9.07377052e+00 9.44651413e+00 8.92975807e+00 9.22263336e+00 9.14893723e+00 8.88407135e+00 9.55887318e+00 1.00582838e+01 1.03071947e+01 1.05751953e+01 1.08220844e+01 1.10757771e+01 1.13456326e+01 1.16436520e+01 1.18759985e+01 1.19814215e+01 1.22875824e+01 1.26491480e+01 1.28836241e+01 1.32269058e+01 1.34021463e+01 1.36873569e+01 1.40949306e+01 1.40347662e+01 1.40780926e+01 1.45706625e+01 1.51043453e+01 1.55134478e+01 1.56500950e+01 1.58639603e+01 1.60317497e+01 1.62442055e+01 1.65198669e+01 1.69804420e+01 1.74360485e+01 1.68478279e+01 1.55511316e+03 2.46903553e+01 1.79500885e+01 2.54685516e+01 7.04370193e+01 6.97455978e+01 7.04070129e+01 7.15304871e+01 7.03043823e+01 7.00294037e+01 6.93468399e+01 6.90119019e+01 6.93804779e+01 6.79865799e+01 4.64459190e+01 2.08457928e+01 2.19758148e+01 2.12822475e+01 2.12348442e+01 2.15595245e+01 2.22152653e+01 2.27723236e+01 2.31361561e+01 2.34156876e+01 2.36962833e+01 2.40366821e+01 2.44077663e+01 2.48451385e+01 2.52322865e+01 2.57458897e+01 2.60482864e+01 2.63029346e+01 2.65090981e+01 2.68375568e+01 2.72314911e+01 2.76251831e+01 2.80190239e+01 2.84130630e+01 2.87494183e+01 2.90959320e+01 2.94160881e+01 2.97725677e+01 3.00693626e+01 3.04871502e+01 3.09783077e+01 3.12987328e+01 3.14823589e+01 3.17651024e+01 3.20085487e+01 3.24023666e+01 3.25274734e+01 3.29717598e+01 3.34041443e+01 3.37746429e+01 3.41117287e+01 3.45688133e+01 3.48086166e+01 3.52759552e+01 3.56760902e+01 3.62136345e+01 3.63753014e+01 3.66440315e+01 3.66323280e+01 3.69863777e+01 3.73493156e+01 3.77627602e+01 3.79986725e+01 3.81273232e+01 3.85327454e+01 3.87934418e+01 3.90679703e+01 3.93530159e+01 3.99843369e+01 4.02778587e+01 4.06199760e+01 4.08908501e+01 4.08670883e+01 3.96965065e+01 3.51432381e+01 3.55437965e+01 -6.40726929e+01 -3.34749390e+02 -8.77164001e+02 7928168. 80773872. 0. -157534928. -157534928. -157534928. 0. -131372528. -131372528. -20722990. 401538080. -15627365. 67967792. 67967792. 0. -331316192. -2.04296375e+03 -4.33591736e+02 -1.66586243e+02 -7.11846542e+01 4.44316635e+01 5.08487358e+01 5.05145378e+01 4.59138336e+01 4.43850784e+01 4.77660255e+01 5.37051468e+01 5.07742386e+01 4.80394592e+01 5.16065102e+01 5.19956207e+01 5.15352898e+01 5.16707954e+01 5.15431557e+01 5.21692085e+01 5.23183174e+01 5.27305031e+01 5.28487968e+01 5.32569275e+01 5.35321007e+01 5.35866737e+01 5.34226723e+01 5.31633949e+01 5.31258278e+01 5.39338646e+01 5.44240799e+01 5.49972916e+01 5.56175232e+01 5.55165863e+01 5.56987610e+01 5.54923515e+01 5.55915680e+01 5.59903526e+01 5.60136185e+01 5.64559708e+01 5.72855110e+01 5.81883888e+01 5.86712494e+01 5.78464508e+01 5.75785561e+01 5.68980484e+01 5.71701775e+01 5.67064362e+01 5.76647224e+01 5.79025574e+01 5.87238846e+01 5.89733086e+01 5.90124474e+01 5.93077965e+01 5.88721237e+01 5.89836655e+01 5.91699486e+01 5.92529984e+01 5.96977158e+01 5.89193993e+01 5.91308937e+01 5.91516571e+01 5.95960159e+01 5.97503700e+01 6.03127136e+01 6.08612823e+01 6.15503693e+01 6.19217339e+01 6.19901123e+01 6.15417099e+01 6.11566811e+01 6.15188751e+01 6.18288078e+01 6.14225693e+01 6.15647049e+01 6.21801758e+01 6.29280472e+01 6.26307716e+01 6.26165390e+01 6.21257629e+01 6.23344498e+01 6.23463478e+01 6.24607239e+01 6.29313622e+01 6.34052048e+01 6.32836342e+01 6.29743423e+01 6.28571320e+01 6.28377953e+01 6.30349426e+01 6.35979195e+01 6.42976303e+01 6.42844009e+01 6.32942276e+01 6.32381096e+01 6.32629890e+01 6.36321220e+01 6.39619217e+01 6.42035141e+01 6.42503586e+01 6.34685440e+01 6.37331696e+01 6.34537506e+01 6.40362320e+01 6.45559464e+01 6.49819412e+01 6.49560852e+01 6.42824707e+01 6.41198273e+01 6.39507256e+01 6.42155304e+01 6.45417557e+01 6.45772629e+01 6.42537155e+01 6.36380997e+01 6.37828064e+01 6.41936722e+01 6.43021545e+01 6.41949921e+01 6.39142075e+01 6.41300583e+01 6.44258575e+01 6.47588120e+01 6.43684082e+01 6.41675491e+01 6.42774048e+01 6.44692993e+01 6.42783585e+01 6.42080154e+01 6.41532135e+01 6.41825943e+01 6.40995941e+01 6.41936035e+01 6.39177055e+01 6.41741562e+01 6.42698746e+01 6.41080399e+01 6.38710442e+01 6.40859222e+01 6.41796875e+01 6.40721817e+01 6.36740990e+01 6.36189804e+01 6.36118622e+01 6.36242523e+01 6.37497101e+01 6.38170280e+01 6.34373779e+01 6.34773483e+01 6.33868675e+01 6.31165695e+01 6.31500702e+01 6.32718468e+01 6.29701195e+01 6.29568405e+01 6.29127579e+01 6.27978477e+01 6.27803421e+01 6.26484756e+01 6.27263412e+01 6.26157722e+01 6.25284500e+01 6.23098030e+01 6.19176712e+01 6.18010483e+01 6.16668282e+01 6.17483673e+01 6.20180054e+01 6.20166359e+01 6.16508636e+01 6.13093796e+01 6.14129868e+01 6.13026314e+01 6.10523872e+01 6.08383179e+01 6.08871117e+01 6.06580238e+01 6.04258995e+01 6.03472939e+01 6.00655746e+01 6.01893539e+01 6.01975288e+01 6.01376991e+01 6.02667007e+01 5.97196999e+01 5.96875420e+01 5.94439735e+01 5.91879196e+01 5.88094482e+01 5.89642448e+01 5.86866341e+01 5.86828613e+01 5.82873306e+01 5.84502983e+01 5.81137238e+01 5.83763504e+01 5.79349403e+01 5.77814560e+01 5.74813652e+01 5.69800682e+01 5.74644585e+01 5.72978516e+01 5.68465118e+01 5.70437050e+01 5.69827766e+01 5.63623352e+01 5.52335014e+01 5.50441933e+01 5.45957260e+01 5.49591026e+01 5.47628555e+01 5.44159698e+01 5.43814812e+01 5.46557922e+01 5.44070015e+01 5.43157005e+01 5.41874733e+01 5.43581200e+01 5.41255112e+01 5.36612473e+01 5.20371742e+01 5.19365730e+01 5.21019516e+01 5.23825111e+01 5.19220581e+01 5.14450645e+01 5.09603500e+01 5.07332726e+01 5.08195534e+01 5.09543076e+01 5.10749359e+01 5.08170280e+01 5.08118248e+01 5.05438232e+01 5.01072159e+01 5.01244240e+01 4.91440468e+01 4.85641327e+01 4.86466255e+01 4.87123413e+01 4.87370567e+01 4.79250526e+01 4.76310768e+01 4.69005966e+01 4.65810013e+01 4.62859116e+01 4.59947701e+01 4.56271896e+01 4.55770645e+01 4.51766281e+01 4.51348152e+01 4.44486008e+01 4.38030243e+01 4.32821617e+01 4.31877136e+01 4.29543877e+01 4.28596535e+01 4.27873802e+01 4.26742020e+01 4.23907127e+01 4.20106506e+01 4.22847939e+01 4.20437584e+01 4.13963966e+01 4.07975006e+01 3.99046516e+01 3.97097931e+01 3.95360909e+01 3.97362366e+01 3.88806763e+01 3.83114128e+01 3.85416031e+01 3.78185730e+01 3.81602783e+01 3.72749062e+01 3.73870468e+01 3.70329132e+01 3.68465385e+01 3.64830627e+01 3.58088913e+01 3.55810280e+01 3.55375557e+01 3.52149048e+01 3.42290764e+01 3.37758179e+01 3.39330368e+01 3.40694733e+01 3.36514320e+01 3.31517639e+01 3.28967972e+01 3.24676514e+01 3.22267380e+01 3.16111870e+01 3.14127541e+01 3.08238354e+01 3.05214539e+01 3.05869865e+01 3.10320187e+01 3.10379601e+01 2.99214649e+01 2.94207916e+01 2.87698631e+01 2.86233368e+01 2.74861889e+01 2.73001862e+01 2.69429054e+01 2.72316017e+01 2.65032635e+01 2.62611580e+01 2.61305351e+01 2.54647484e+01 2.47546768e+01 2.47148514e+01 2.42079430e+01 2.45288925e+01 2.36051540e+01 2.34291859e+01 2.29265480e+01 2.27716370e+01 2.22190304e+01 2.18221455e+01 2.13349934e+01 2.13334122e+01 2.10899315e+01 2.06641941e+01 2.00057392e+01 1.93094616e+01 1.90411472e+01 1.89128838e+01 1.83399715e+01 1.77698479e+01 1.77602882e+01 1.74990978e+01 1.70956001e+01 1.65871754e+01 1.59753141e+01 1.57047186e+01 1.53531876e+01 1.51885414e+01 1.49826727e+01 1.47433329e+01 1.40799141e+01 1.35895548e+01 1.31557045e+01 1.27081070e+01 1.23223314e+01 1.20903997e+01 1.18986921e+01 1.14603920e+01 1.07731762e+01 1.03438892e+01 1.00147276e+01 9.81912327e+00 9.51660442e+00 9.15674591e+00 8.68066788e+00 8.00610161e+00 7.69025612e+00 7.12199831e+00 6.92457819e+00 6.60199451e+00 6.30097103e+00 5.87626457e+00 5.37223053e+00 4.99663734e+00 4.56919718e+00 4.11263227e+00 3.73230672e+00 3.30746317e+00 2.91203761e+00 2.48256588e+00 2.12361646e+00 1.80218017e+00 1.39608991e+00 1.01128876e+00 5.61470509e-01 2.34874308e-01 -1.65350169e-01 -6.16008341e-01 -1.04670727e+00 -1.34305155e+00 -1.68858695e+00 -2.06675625e+00 -2.49748850e+00 -2.88492584e+00 -3.29097056e+00 -3.67763352e+00 -4.10048580e+00 -4.43198109e+00 -4.86104822e+00 -5.27226114e+00 -5.67890310e+00 -6.03513098e+00 -6.41809273e+00 -6.77478266e+00 -7.17496395e+00 -7.58003521e+00 -7.99057293e+00 -8.38882828e+00 -8.76535511e+00 -9.12914085e+00 -9.51774502e+00 -9.90171337e+00 -1.03223658e+01 -1.07145348e+01 -1.10977612e+01 -1.14799089e+01 -1.18707342e+01 -1.22598143e+01 -1.26420908e+01 -1.30211105e+01 -1.34114494e+01 -1.37936382e+01 -1.41774187e+01 -1.45560198e+01 -1.49425678e+01 -1.53233471e+01 -1.57115154e+01 -1.60968246e+01 -1.64762688e+01 -1.68644104e+01 -1.72443352e+01 -1.76290741e+01 -1.80129108e+01 -1.83702812e+01 -1.87408562e+01 -1.91253433e+01 -1.95193996e+01 -1.98903542e+01 -2.02667332e+01 -2.06096096e+01 -2.09865036e+01 -2.13990593e+01 -2.17683086e+01 -2.21372986e+01 -2.25184803e+01 -2.28460159e+01 -2.31996002e+01 -2.35623035e+01 -2.39271717e+01 -2.42410641e+01 -2.46228237e+01 -2.49680920e+01 -2.53340378e+01 -2.56363983e+01 -2.60138588e+01 -2.62953262e+01 -2.66985493e+01 -2.70460186e+01 -2.74280891e+01 -2.78521996e+01 -2.82528954e+01 -2.85522671e+01 -2.88391914e+01 -2.90802059e+01 -2.95068035e+01 -2.98412151e+01 -3.02233906e+01 -3.07228470e+01 -3.10028305e+01 -3.12744465e+01 -3.16490250e+01 -3.18904495e+01 -3.22771072e+01 -3.24759293e+01 -3.28875237e+01 -3.32253380e+01 -3.36479988e+01 -3.40308800e+01 -3.45147324e+01 -3.47939262e+01 -3.52268562e+01 -3.56064911e+01 -3.61133118e+01 -3.62175484e+01 -3.65595245e+01 -3.66315002e+01 -3.68568459e+01 -3.71145706e+01 -3.75014076e+01 -3.78767128e+01 -3.81342125e+01 -3.85241318e+01 -3.87609634e+01 -3.90368500e+01 -3.93627930e+01 -3.98276672e+01 -4.02077522e+01 -4.06138268e+01 -4.08191299e+01 -4.11321945e+01 -4.16046371e+01 -4.17529106e+01 -4.18901939e+01 -4.23214607e+01 -4.25507927e+01 -4.28359909e+01 -4.29861870e+01 -4.32150269e+01 -4.33728828e+01 -4.37363396e+01 -4.43776855e+01 -4.46004333e+01 -4.51015434e+01 -4.53741226e+01 -4.53321075e+01 -4.55716209e+01 -4.57096748e+01 -4.56992912e+01 -4.59381752e+01 -4.63710175e+01 -4.66702690e+01 -4.69461403e+01 -4.74379349e+01 -4.76786385e+01 -4.81675453e+01 -4.84335136e+01 -4.90391846e+01 -4.91853714e+01 -4.91208153e+01 -4.92623558e+01 -4.90825882e+01 -4.93741035e+01 -4.94035759e+01 -5.01643715e+01 -5.01541138e+01 -5.04572716e+01 -5.11763077e+01 -5.10183067e+01 -5.15311394e+01 -5.15571442e+01 -5.20442467e+01 -5.23086815e+01 -5.27510643e+01 -5.30377350e+01 -5.31634903e+01 -5.33063622e+01 -5.34831009e+01 -5.34008255e+01 -5.29775467e+01 -5.32810707e+01 -5.41871338e+01 -5.45004883e+01 -5.47188492e+01 -5.50004387e+01 -5.52890091e+01 -5.52365112e+01 -5.52595100e+01 -5.52397003e+01 -5.59274902e+01 -5.56530952e+01 -5.59056015e+01 -5.67063637e+01 -5.77670059e+01 -5.83573570e+01 -5.75553093e+01 -5.75928841e+01 -5.73546028e+01 -5.76328278e+01 -5.69917030e+01 -5.72460289e+01 -5.76898384e+01 -5.82909050e+01 -5.78229179e+01 -5.82099571e+01 -5.83481979e+01 -5.81924400e+01 -5.85801582e+01 -5.90991974e+01 -5.91619797e+01 -5.99258232e+01 -5.96304131e+01 -5.99958649e+01 -5.97943802e+01 -6.01886330e+01 -5.99422340e+01 -6.02474632e+01 -6.04096489e+01 -6.06956367e+01 -6.11832771e+01 -6.12097359e+01 -6.08924789e+01 -6.04556885e+01 -6.10120926e+01 -6.16070099e+01 -6.11974831e+01 -6.12915421e+01 -6.20446892e+01 -6.23726845e+01 -6.20581322e+01 -6.18847237e+01 -6.15127411e+01 -6.18998528e+01 -6.19533195e+01 -6.21419106e+01 -6.27637596e+01 -6.31846619e+01 -6.29423065e+01 -6.28531609e+01 -6.30326500e+01 -6.29436646e+01 -6.29185829e+01 -6.31388931e+01 -6.35659103e+01 -6.39531784e+01 -6.33624992e+01 -6.29036179e+01 -6.30918579e+01 -6.37661972e+01 -6.41102829e+01 -6.40222549e+01 -6.40741806e+01 -6.36176186e+01 -6.39426193e+01 -6.34687309e+01 -6.37341156e+01 -6.36332207e+01 -6.41319427e+01 -6.42179565e+01 -6.38577499e+01 -6.37643700e+01 -6.35272446e+01 -6.36013412e+01 -6.37543755e+01 -6.40387039e+01 -6.40375595e+01 -6.35174332e+01 -6.36545372e+01 -6.37185287e+01 -6.37994156e+01 -6.40121841e+01 -6.41398849e+01 -6.40302277e+01 -6.40037231e+01 -6.40489578e+01 -6.37408600e+01 -6.40719299e+01 -6.41726532e+01 -6.44493179e+01 -6.43564606e+01 -6.41874619e+01 -6.40464172e+01 -6.40606232e+01 -6.39568710e+01 -6.40000687e+01 -6.39508591e+01 -6.39744492e+01 -6.37734070e+01 -6.40334473e+01 -6.40100555e+01 -6.40365906e+01 -6.38871994e+01 -6.38312569e+01 -6.35462494e+01 -6.32913017e+01 -6.33499908e+01 -6.35892296e+01 -6.37094231e+01 -6.35536728e+01 -6.31013298e+01 -6.30851860e+01 -6.29565582e+01 -6.29428673e+01 -6.28506470e+01 -6.28485680e+01 -6.26576385e+01 -6.25676765e+01 -6.25683899e+01 -6.22422409e+01 -6.19728775e+01 -6.24556046e+01 -6.22667122e+01 -6.18524551e+01 -6.18398705e+01 -6.15535507e+01 -6.16519508e+01 -6.19541893e+01 -6.19847183e+01 -6.15729713e+01 -6.13036003e+01 -6.14375191e+01 -6.11035652e+01 -6.07929916e+01 -6.09785423e+01 -6.06390457e+01 -6.06875076e+01 -6.05339851e+01 -6.05423355e+01 -6.06583252e+01 -6.05996475e+01 -6.06630936e+01 -6.00673180e+01 -5.97134132e+01 -5.98429909e+01 -5.98365822e+01 -5.95630722e+01 -5.93400116e+01 -5.95793152e+01 -5.92891235e+01 -5.94369659e+01 -5.92178802e+01 -5.90177002e+01 -5.84423103e+01 -5.84845352e+01 -5.86408081e+01 -5.85737152e+01 -5.84441109e+01 -5.84857559e+01 -5.79270592e+01 -5.75629921e+01 -5.68757362e+01 -5.68612480e+01 -5.69495239e+01 -5.71425667e+01 -5.71391869e+01 -5.68472481e+01 -5.64307289e+01 -5.60055542e+01 -5.53088455e+01 -5.48190651e+01 -5.42245941e+01 -5.43245392e+01 -5.43101387e+01 -5.42430840e+01 -5.40433006e+01 -5.44123268e+01 -5.41130257e+01 -5.40363121e+01 -5.40935860e+01 -5.38664360e+01 -5.34623947e+01 -5.34060364e+01 -5.20723381e+01 -5.19744148e+01 -5.19453468e+01 -5.21585045e+01 -5.18199234e+01 -5.14487572e+01 -5.13038826e+01 -5.08989525e+01 -5.07723045e+01 -5.08420105e+01 -5.08960571e+01 -5.07020950e+01 -5.03468781e+01 -5.00759087e+01 -4.99816093e+01 -4.97502174e+01 -4.88961143e+01 -4.86641312e+01 -4.86592484e+01 -4.84971123e+01 -4.82422104e+01 -4.75122528e+01 -4.73280220e+01 -4.65428925e+01 -4.64575996e+01 -4.61488533e+01 -4.56175728e+01 -4.51791725e+01 -4.55403633e+01 -4.49081078e+01 -4.46080322e+01 -4.40701866e+01 -4.35493507e+01 -4.33201218e+01 -4.30916443e+01 -4.27793579e+01 -4.27219124e+01 -4.26277351e+01 -4.22483406e+01 -4.20521126e+01 -4.16492805e+01 -4.20647507e+01 -4.17046051e+01 -4.12135315e+01 -4.07783470e+01 -4.00076790e+01 -4.01301117e+01 -3.96110764e+01 -3.95378532e+01 -3.86396408e+01 -3.83192902e+01 -3.84864731e+01 -3.76256371e+01 -3.76536102e+01 -3.67243919e+01 -3.69960785e+01 -3.69237251e+01 -3.69746437e+01 -3.65460739e+01 -3.61579742e+01 -3.58481483e+01 -3.57795448e+01 -3.50995636e+01 -3.40931244e+01 -3.35398140e+01 -3.39389572e+01 -3.38811188e+01 -3.39290466e+01 -3.37170486e+01 -3.30123825e+01 -3.19162102e+01 -3.16954746e+01 -3.17283058e+01 -3.14625072e+01 -3.05869007e+01 -3.02747631e+01 -3.04849930e+01 -3.08401909e+01 -3.67662697e+01 -3.56350822e+01 -3.20719948e+01 -3.08797035e+01 -2.72790833e+01 -2.79296761e+01 -2.75106392e+01 -2.67936134e+01 -2.74911518e+01 -2.49309902e+01 -2.19921608e+01 -2.11260777e+01 -2.76985130e+01 -1.65669922e+02 -2.48627502e+02 -5.81767029e+02 -1.05193652e+03 -12222066. 3.02385425e+06 4.97597850e+09 4.97597850e+09 150547056. 150547056. 5.68310050e+06 122415200. 122415200. 0. 0. 0. 311827328. -32326390. -9.39594971e+02 -5.90506470e+02 -1.22653885e+02 -2.64849060e+02 -1.51814621e+02 -3.13606300e+01 -2.57775040e+01 -5.59173059e+00 -4.22132349e+00 -2.29379482e+01 -2.83364143e+01 -2.01021290e+01 -1.55722694e+01 -1.45166283e+01 -1.33136950e+01 -1.31898422e+01 -1.03815718e+01 -7.13519573e+00 -7.89271164e+00 -1.77799106e+00 -3.00205445e+00 -1.25825911e+01 -7.53811312e+00 -1.28778305e+01 -1.65731850e+01 -8.25728321e+00 -4.59737778e+00 -2.69500542e+00 -5.72428656e+00 -9.75848770e+00 -8.87535572e+00 -5.84686947e+00 -6.68883419e+00 -6.51310015e+00 -5.85411501e+00 -5.34393215e+00 -4.75838614e+00 -4.19228935e+00 -3.69139624e+00 -3.25370932e+00 -2.90406632e+00 -2.47726202e+00 -2.09026194e+00 -1.71002173e+00 -1.21223187e+00 -8.45237792e-01 -4.01680857e-01 1.74508183e-04 3.84425581e-01 7.40838528e-01 1.13072121e+00 7.33344793e-01 1.26509976e+00 1.65342176e+00 1.71395612e+00 2.76859379e+00 3.40718055e+00 3.71298623e+00 4.06330347e+00 4.36074495e+00 4.73053503e+00 5.15386486e+00 5.62765932e+00 5.93233681e+00 6.15256357e+00 6.66635990e+00 7.36670494e+00 7.87100887e+00 8.60092926e+00 9.69860649e+00 8.79309654e+00 3.08600979e+01 1.30036507e+01 1.90244560e+01 4.97356834e+01 2.22510600e+00 3.14088082e+00 1.17297525e+01 1.20020323e+01 1.21039429e+01 1.23984737e+01 1.28882256e+01 1.32967033e+01 1.36213102e+01 1.25109816e+01 3673053. 7.73604126e+01 6.34864845e+01 1.15741493e+02 6.55968552e+01 2.72791195e+01 -3.02648234e+00 -141602224. -39718708. 1.06986275e+02 5.01466179e+01 1.40962276e+01 1.44503307e+01 1.34427519e+01 1.29000683e+01 1.36858969e+01 1.50596676e+01 1.42844524e+01 1.38525133e+01 1.38708153e+01 1.43020830e+01 1.47515621e+01 1.50696917e+01 1.52142649e+01 1.53958597e+01 1.55179529e+01 1.57210255e+01 1.58918419e+01 1.60584412e+01 1.63715515e+01 1.66465626e+01 1.68183632e+01 1.69873028e+01 1.71697445e+01 1.74321880e+01 1.76275101e+01 1.77941494e+01 1.79597378e+01 1.80811939e+01 1.81299992e+01 1.83866997e+01 1.88044243e+01 1.89617081e+01 1.90722408e+01 1.93222542e+01 1.96789150e+01 1.98607960e+01 2.00213394e+01 2.01642456e+01 2.03595047e+01 2.05093136e+01 2.07447681e+01 2.07834091e+01 2.10231781e+01 2.12432957e+01 2.13735638e+01 2.16074486e+01 2.18269062e+01 2.20561466e+01 2.23311768e+01 2.24751072e+01 2.24859085e+01 2.24965897e+01 2.26643276e+01 2.29343204e+01 2.31530628e+01 2.33681374e+01 2.36250324e+01 2.39046040e+01 2.39327927e+01 2.40070763e+01 2.41462212e+01 2.44842319e+01 2.46014099e+01 2.44401398e+01 2.36413803e+01 2.11184959e+01 -7.53366394e+01 -1.62968216e+02 2.32155457e+01 -4.66908325e+02 -2.50502368e+03 136875168. 0. 0. -494129408. -494129408. -494129408. 0. 0. -131372528. -131372528. -131372528. 0. 67967792. 67967792. -7165310. 782688000. -1.13916626e+03 -4.42375092e+02 -9.26796646e+01 2.76170750e+01 3.25322723e+01 2.66013622e+01 2.61177368e+01 2.91854877e+01 2.87012768e+01 2.80526524e+01 2.91181889e+01 3.07885189e+01 3.13110352e+01 3.14403152e+01 3.14008980e+01 3.09306202e+01 3.07838764e+01 3.06409607e+01 3.14115086e+01 3.16214485e+01 3.11371021e+01 3.13039627e+01 3.14316139e+01 3.20733452e+01 3.16096210e+01 3.13233490e+01 3.09756546e+01 3.08964481e+01 3.05910835e+01 3.13480835e+01 3.16545372e+01 3.23604622e+01 3.20792770e+01 3.22335396e+01 3.24436302e+01 3.26889610e+01 3.31586800e+01 3.35685768e+01 3.34636078e+01 3.36863823e+01 3.34361382e+01 3.34609184e+01 3.30236053e+01 3.34405289e+01 3.30671844e+01 3.30663986e+01 3.29421196e+01 3.34995041e+01 3.40880051e+01 3.41226616e+01 3.44632645e+01 3.46060677e+01 3.46638451e+01 3.42277832e+01 3.38230629e+01 3.41554565e+01 3.51354370e+01 3.49987030e+01 3.47933197e+01 3.43803635e+01 3.47320099e+01 3.47567902e+01 3.50601463e+01 3.55364380e+01 3.60266151e+01 3.61376839e+01 3.60770111e+01 3.59360237e+01 3.60433311e+01 3.64035187e+01 3.63624840e+01 3.59447861e+01 3.56038361e+01 3.55971031e+01 3.60273438e+01 3.62723885e+01 3.64006805e+01 3.62577744e+01 3.64997063e+01 3.61004143e+01 3.61952438e+01 3.59927483e+01 3.61513443e+01 3.60540848e+01 3.62766533e+01 3.63789902e+01 3.64276047e+01 3.63787766e+01 3.62960777e+01 3.59004326e+01 3.56546745e+01 3.56575623e+01 3.58491707e+01 3.60309219e+01 3.68026009e+01 3.69392586e+01 3.70208778e+01 3.67721786e+01 3.68981934e+01 3.71964569e+01 3.69278870e+01 3.68423271e+01 3.63695831e+01 3.65763206e+01 3.67670250e+01 3.75427895e+01 3.73156395e+01 3.69893417e+01 3.69765930e+01 3.68632126e+01 3.66354332e+01 3.65509682e+01 3.66609879e+01 3.67273483e+01 3.65148697e+01 3.65360031e+01 3.68993073e+01 3.70593338e+01 3.72495079e+01 3.71630249e+01 3.71581268e+01 3.69963989e+01 3.72019424e+01 3.68924026e+01 3.66159630e+01 3.64519310e+01 3.67473106e+01 3.69607468e+01 3.70176010e+01 3.66517258e+01 3.62097282e+01 3.67754402e+01 3.69508934e+01 3.64214935e+01 3.63441124e+01 3.66272049e+01 3.63951797e+01 3.61376839e+01 3.59658546e+01 3.60108948e+01 3.63173180e+01 3.61633644e+01 3.61716614e+01 3.60866585e+01 3.59430847e+01 3.59647255e+01 3.62252769e+01 3.59006004e+01 3.57535782e+01 3.58280220e+01 3.55582542e+01 3.56387177e+01 3.58299370e+01 3.55993690e+01 3.55798759e+01 3.55587273e+01 3.55162354e+01 3.54434853e+01 3.52826843e+01 3.54680405e+01 3.53827019e+01 3.52097778e+01 3.50919495e+01 3.45799179e+01 3.43296890e+01 3.43839607e+01 3.45819092e+01 3.49471664e+01 3.49079323e+01 3.44397163e+01 3.41035614e+01 3.44843674e+01 3.45345459e+01 3.41886940e+01 3.41281776e+01 3.40208588e+01 3.36230621e+01 3.34979820e+01 3.35945969e+01 3.33675041e+01 3.38268242e+01 3.36095047e+01 3.35620537e+01 3.39138298e+01 3.40015907e+01 3.36378670e+01 3.31500359e+01 3.24675064e+01 3.27678680e+01 3.28056908e+01 3.25612907e+01 3.24313545e+01 3.27158089e+01 3.28350601e+01 3.25818443e+01 3.26074104e+01 3.23497734e+01 3.19641933e+01 3.18159885e+01 3.18358231e+01 3.22583656e+01 3.19060440e+01 3.15094490e+01 3.18345203e+01 3.20377045e+01 3.17052002e+01 3.07898121e+01 3.05307426e+01 3.06132736e+01 3.08211365e+01 3.05341320e+01 3.01810551e+01 3.00425186e+01 3.02336540e+01 3.01297131e+01 2.99919415e+01 2.96356163e+01 2.99801903e+01 3.00389194e+01 2.96106415e+01 2.87913666e+01 2.87937012e+01 2.88713779e+01 2.89670048e+01 2.89628963e+01 2.88725624e+01 2.85093708e+01 2.79969902e+01 2.80668163e+01 2.80450401e+01 2.85314960e+01 2.82885303e+01 2.77143822e+01 2.68705502e+01 2.69152470e+01 2.71954117e+01 2.69632854e+01 2.65569286e+01 2.63035431e+01 2.58345108e+01 2.58455181e+01 2.57148705e+01 2.56482468e+01 2.59838066e+01 2.57325573e+01 2.55468464e+01 2.47329788e+01 2.39603138e+01 2.42831383e+01 2.46245422e+01 2.49344902e+01 2.47303448e+01 2.44917526e+01 2.42469273e+01 2.41443920e+01 2.42875652e+01 2.39608097e+01 2.35421562e+01 2.32379780e+01 2.32329674e+01 2.28918419e+01 2.25149403e+01 2.19746914e+01 2.17718391e+01 2.15793724e+01 2.15460052e+01 2.14975166e+01 2.11500549e+01 2.14914703e+01 2.14485703e+01 2.18582478e+01 2.10624409e+01 2.06080360e+01 2.02177219e+01 2.07130032e+01 2.08075752e+01 1.99812832e+01 1.99590607e+01 1.97094212e+01 1.98979626e+01 1.87950478e+01 1.81238842e+01 1.78099670e+01 1.75547733e+01 1.71029434e+01 1.71300068e+01 1.73522530e+01 1.76214123e+01 1.71663704e+01 1.74777641e+01 1.72437096e+01 1.72719879e+01 1.70458050e+01 1.72290974e+01 1.65761299e+01 1.64071789e+01 1.56912193e+01 1.54399700e+01 1.49061737e+01 1.50138044e+01 1.45820713e+01 1.40278702e+01 1.38630896e+01 1.37565613e+01 1.39974174e+01 1.37925434e+01 1.41294079e+01 1.35777617e+01 1.32658501e+01 1.27931433e+01 1.24275446e+01 1.25499363e+01 1.30934553e+01 1.24036798e+01 1.23523474e+01 1.19046898e+01 1.20390072e+01 1.15980225e+01 1.11725264e+01 1.13317089e+01 1.12392015e+01 1.09358988e+01 1.05924520e+01 1.02464781e+01 1.01940002e+01 9.75187111e+00 9.51037502e+00 9.30679703e+00 9.03595924e+00 8.77396679e+00 8.79404831e+00 8.67101383e+00 8.51070404e+00 8.14146900e+00 7.97583675e+00 7.49458933e+00 7.26228094e+00 6.83230448e+00 6.95297337e+00 6.79287386e+00 6.57864952e+00 6.28777885e+00 6.03713226e+00 5.80501080e+00 5.45869541e+00 5.04959345e+00 4.63317347e+00 4.34696913e+00 4.25222492e+00 4.15339851e+00 4.21764517e+00 3.92601299e+00 3.75057626e+00 3.53388524e+00 3.38513780e+00 3.20700765e+00 2.77001095e+00 2.55190802e+00 2.13828135e+00 2.07299042e+00 1.96310318e+00 1.85213065e+00 1.57895339e+00 1.25474036e+00 1.01930034e+00 7.68988073e-01 5.60157359e-01 2.34901875e-01 5.82632497e-02 -1.58641011e-01 -3.21513593e-01 -6.45429730e-01 -7.66750574e-01 -9.40986633e-01 -1.11695766e+00 -1.37612212e+00 -1.55727291e+00 -1.90877664e+00 -2.18265533e+00 -2.39304018e+00 -2.51855350e+00 -2.79770327e+00 -3.03388810e+00 -3.17060852e+00 -3.44859886e+00 -3.74486136e+00 -3.98725700e+00 -4.15711737e+00 -4.34351826e+00 -4.58665943e+00 -4.86737680e+00 -5.13669014e+00 -5.35043240e+00 -5.55138111e+00 -5.78226089e+00 -6.00203800e+00 -6.18159008e+00 -6.42130566e+00 -6.64468050e+00 -6.86157084e+00 -7.07374096e+00 -7.30572796e+00 -7.51365137e+00 -7.75464630e+00 -7.97965908e+00 -8.23210049e+00 -8.46095181e+00 -8.67667580e+00 -8.87213612e+00 -9.08075047e+00 -9.29898643e+00 -9.51380634e+00 -9.72699928e+00 -9.93739986e+00 -1.01543322e+01 -1.03726826e+01 -1.05901613e+01 -1.08088150e+01 -1.10261154e+01 -1.12417746e+01 -1.14569464e+01 -1.16708145e+01 -1.18926611e+01 -1.21061888e+01 -1.23057814e+01 -1.25191746e+01 -1.27416763e+01 -1.29619989e+01 -1.31664085e+01 -1.33719082e+01 -1.36022835e+01 -1.37687397e+01 -1.39400454e+01 -1.42424831e+01 -1.44672403e+01 -1.46633825e+01 -1.48392334e+01 -1.49776382e+01 -1.52218370e+01 -1.54450493e+01 -1.56961880e+01 -1.58966684e+01 -1.60405235e+01 -1.61765919e+01 -1.64261990e+01 -1.65580750e+01 -1.67837486e+01 -1.70285549e+01 -1.72287674e+01 -1.74514999e+01 -1.76400394e+01 -1.78852882e+01 -1.81259956e+01 -1.81872253e+01 -1.82162571e+01 -1.85373325e+01 -1.87562275e+01 -1.89536781e+01 -1.92028198e+01 -1.94592800e+01 -1.96919441e+01 -1.98933258e+01 -1.99575768e+01 -2.00936413e+01 -2.02729454e+01 -2.05096169e+01 -2.06365242e+01 -2.07545986e+01 -2.09855442e+01 -2.12808552e+01 -2.15941238e+01 -2.17892036e+01 -2.20314846e+01 -2.22248707e+01 -2.23900318e+01 -2.23997593e+01 -2.24872494e+01 -2.26119766e+01 -2.26020412e+01 -2.29147892e+01 -2.33606262e+01 -2.36713505e+01 -2.41013718e+01 -2.39813023e+01 -2.36329117e+01 -2.38747177e+01 -2.45051270e+01 -2.47219372e+01 -2.46163883e+01 -2.45835629e+01 -2.46697178e+01 -2.52130680e+01 -2.54074364e+01 -2.55050983e+01 -2.55996456e+01 -2.57346153e+01 -2.57279625e+01 -2.59345570e+01 -2.61026402e+01 -2.64382229e+01 -2.65106773e+01 -2.65952721e+01 -2.65071621e+01 -2.64423294e+01 -2.69496784e+01 -2.72959137e+01 -2.78517189e+01 -2.79017067e+01 -2.78435631e+01 -2.77394466e+01 -2.79342365e+01 -2.82432518e+01 -2.85855503e+01 -2.88610687e+01 -2.88032417e+01 -2.88794899e+01 -2.92145786e+01 -2.94497662e+01 -2.91933002e+01 -2.91816311e+01 -2.91975842e+01 -2.92344303e+01 -2.92326298e+01 -2.95374336e+01 -3.01576691e+01 -3.05156746e+01 -3.08288422e+01 -3.05358105e+01 -3.06070442e+01 -3.06089058e+01 -3.14916973e+01 -3.14293461e+01 -3.11842537e+01 -3.13832588e+01 -3.15548878e+01 -3.22389145e+01 -3.14451027e+01 -3.09892845e+01 -3.06301155e+01 -3.06126957e+01 -3.07623634e+01 -3.15925617e+01 -3.17615471e+01 -3.21238861e+01 -3.20004005e+01 -3.26719551e+01 -3.26854858e+01 -3.28187141e+01 -3.29131470e+01 -3.36059875e+01 -3.32015305e+01 -3.31595535e+01 -3.31086159e+01 -3.30304642e+01 -3.29152946e+01 -3.32718086e+01 -3.34145012e+01 -3.31040573e+01 -3.32397690e+01 -3.32582207e+01 -3.36998825e+01 -3.39489288e+01 -3.43402023e+01 -3.40218964e+01 -3.38100052e+01 -3.36138268e+01 -3.34074783e+01 -3.41868553e+01 -3.51763191e+01 -3.48344269e+01 -3.48385239e+01 -3.48642502e+01 -3.53779526e+01 -3.54235077e+01 -3.51647758e+01 -3.53067703e+01 -3.56640816e+01 -3.57321281e+01 -3.57687798e+01 -3.56856804e+01 -3.58393707e+01 -3.57165794e+01 -3.56006622e+01 -3.55283775e+01 -3.55657310e+01 -3.54851074e+01 -3.59148903e+01 -3.62845917e+01 -3.64586983e+01 -3.63284416e+01 -3.64294548e+01 -3.58273849e+01 -3.59616814e+01 -3.55154572e+01 -3.58192863e+01 -3.59858589e+01 -3.62785454e+01 -3.64280319e+01 -3.67311592e+01 -3.67208672e+01 -3.64158211e+01 -3.58554878e+01 -3.53255272e+01 -3.49917450e+01 -3.54850540e+01 -3.61587296e+01 -3.66928215e+01 -3.67935104e+01 -3.66319313e+01 -3.64914169e+01 -3.65607491e+01 -3.67972298e+01 -3.66527519e+01 -3.68512230e+01 -3.64352913e+01 -3.64771347e+01 -3.65422859e+01 -3.70025826e+01 -3.68347092e+01 -3.66748428e+01 -3.67219276e+01 -3.65551186e+01 -3.61855888e+01 -3.57731552e+01 -3.61401176e+01 -3.64432373e+01 -3.67362442e+01 -3.65146370e+01 -3.66360626e+01 -3.67612762e+01 -3.69422989e+01 -3.70302353e+01 -3.70037270e+01 -3.66042633e+01 -3.65977402e+01 -3.66510391e+01 -3.68887215e+01 -3.66349258e+01 -3.67736702e+01 -3.72138252e+01 -3.69578247e+01 -3.64603844e+01 -3.61937828e+01 -3.67446938e+01 -3.67905426e+01 -3.66306801e+01 -3.61674347e+01 -3.59859009e+01 -3.61508064e+01 -3.62296562e+01 -3.59516907e+01 -3.59053192e+01 -3.61106606e+01 -3.60423508e+01 -3.60716743e+01 -3.58891029e+01 -3.60866890e+01 -3.61387177e+01 -3.61085243e+01 -3.58620033e+01 -3.55198975e+01 -3.53804855e+01 -3.54323196e+01 -3.55704918e+01 -3.55377808e+01 -3.53900452e+01 -3.53545074e+01 -3.54139023e+01 -3.50943260e+01 -3.48760757e+01 -3.54047890e+01 -3.51279221e+01 -3.47105637e+01 -3.47934914e+01 -3.46768684e+01 -3.48822174e+01 -3.50099297e+01 -3.49293022e+01 -3.46386566e+01 -3.43228149e+01 -3.43083153e+01 -3.42449417e+01 -3.41360779e+01 -3.40764313e+01 -3.40707779e+01 -3.39938927e+01 -3.38990135e+01 -3.37134171e+01 -3.37071915e+01 -3.42274399e+01 -3.41535072e+01 -3.34587402e+01 -3.34036446e+01 -3.31444740e+01 -3.34745789e+01 -3.34740219e+01 -3.35691833e+01 -3.36259460e+01 -3.31205482e+01 -3.27809601e+01 -3.32699356e+01 -3.30515785e+01 -3.27368279e+01 -3.23481102e+01 -3.29006233e+01 -3.27938271e+01 -3.26296158e+01 -3.25135040e+01 -3.20988197e+01 -3.16165810e+01 -3.15266285e+01 -3.16635609e+01 -3.16838837e+01 -3.15188160e+01 -3.15184326e+01 -3.15414219e+01 -3.16177635e+01 -3.13404961e+01 -3.07046947e+01 -3.04230137e+01 -3.01151772e+01 -3.05700817e+01 -3.01757870e+01 -2.98322163e+01 -2.97562981e+01 -3.00795536e+01 -2.98271790e+01 -2.95139408e+01 -2.93457642e+01 -2.93055878e+01 -2.93572655e+01 -2.92348804e+01 -2.86978436e+01 -2.86772308e+01 -2.87080498e+01 -2.85968838e+01 -2.85153141e+01 -2.83863506e+01 -2.84110775e+01 -2.80082436e+01 -2.79880409e+01 -2.80093250e+01 -2.81260204e+01 -2.78563824e+01 -2.73733463e+01 -2.66343708e+01 -2.68789482e+01 -2.71210384e+01 -2.69071217e+01 -2.64466629e+01 -2.61357956e+01 -2.58131199e+01 -2.57293663e+01 -2.54860058e+01 -2.52705803e+01 -2.53065834e+01 -2.54175053e+01 -2.52228489e+01 -2.42628078e+01 -2.33555527e+01 -2.39920998e+01 -2.47925701e+01 -2.48854027e+01 -2.44276123e+01 -2.41103745e+01 -2.38076763e+01 -2.37370605e+01 -2.35629444e+01 -2.36093884e+01 -2.34103260e+01 -2.29930153e+01 -2.27562752e+01 -2.25468712e+01 -2.24589901e+01 -2.20214977e+01 -2.16028099e+01 -2.13508358e+01 -2.14015980e+01 -2.17158966e+01 -2.13494797e+01 -2.12320442e+01 -2.09527607e+01 -2.12888184e+01 -2.06463928e+01 -2.03938751e+01 -2.00791779e+01 -2.03950996e+01 -2.01551800e+01 -1.98504601e+01 -1.99432945e+01 -1.96396275e+01 -1.99655819e+01 -1.89178410e+01 -1.83990383e+01 -1.77883644e+01 -1.72311745e+01 -1.69586468e+01 -1.72126808e+01 -1.72893982e+01 -1.74058704e+01 -1.72377262e+01 -1.72348003e+01 -1.67157078e+01 -1.68859901e+01 -1.70892391e+01 -1.72084408e+01 -1.62673893e+01 -1.60471783e+01 -1.55697784e+01 -1.53263283e+01 -1.46893082e+01 -1.47006073e+01 -1.74466534e+01 -1.65785618e+01 -1.29739799e+01 -1.41459246e+01 -1.39609556e+01 -1.32907686e+01 -1.43172894e+01 -1.22223663e+01 -9.97094631e+00 -1.16512766e+01 -1.33346243e+01 -1.08499556e+01 -1.05454645e+01 -1.48216064e+02 -1.99181274e+02 -4.34404327e+02 -2.46269824e+03 560128384. 0. 150547056. 150547056. 5.68310050e+06 122415200. 122415200. 0. 0. 0. 0. 0. -126059192. -71584032. -6.31877979e+03 -1.38713684e+03 -5.50055725e+02 -3.13691883e+01 -2.10277451e+02 -9.75711594e+01 -3.15437055e+00 -1.64319534e+01 -2.05077324e+01 -1.20934200e+01 -6.76314735e+00 -5.90669346e+00 -4.81183243e+00 -5.18570900e+00 -2.99170327e+00 -2.86813021e-01 -1.51133144e+00 2.89848948e+00 1.04795790e+00 -7.91038656e+00 -6.33122826e+00 -7.14499331e+00 -7.25687361e+00 -2.47822666e+00 -1.72514188e+00 -2.14195156e+00 -3.71937394e+00 -3.51248121e+00 -9.27938282e-01 1.05480216e-01 -1.81067204e+00 -1.94012761e+00 -1.66315567e+00 -1.42982614e+00 -1.00115943e+00 -5.77359378e-01 -8.35400298e-02 1.75607219e-01 2.79924423e-01 3.54273319e-01 6.00571990e-01 8.26947153e-01 1.14774716e+00 1.34786677e+00 1.63709319e+00 1.92308724e+00 2.13377357e+00 2.25946975e+00 2.45807076e+00 1.97645056e+00 2.48657823e+00 2.93243957e+00 2.89250016e+00 3.90776730e+00 4.36762667e+00 4.55928898e+00 4.69613218e+00 4.84753704e+00 5.04768467e+00 5.38872862e+00 5.69900513e+00 5.85860348e+00 6.01588011e+00 6.27811098e+00 6.64935160e+00 6.97938013e+00 7.50857782e+00 8.47982883e+00 6.66293192e+00 4.09284897e+01 5.32978363e+01 1.01649307e+02 2.98434052e+02 4.57936287e+00 1.63960648e+01 4.58266258e+01 4.06594276e+00 1.68453941e+01 3.08416862e+01 4.54298706e+01 4.60997505e+01 4.61721268e+01 4.49262428e+01 31273378. 105598960. 105598960. 270841728. -126840040. -126840040. -126840040. 0. 0. 476654848. 3.90038361e+02 9.38689804e+01 2.08252506e+01 -1.74435673e+01 -8.94463062e+00 9.18114948e+00 1.07395515e+01 1.05826635e+01 1.05590429e+01 1.05947676e+01 1.07334909e+01 1.10756426e+01 1.13531570e+01 1.15877962e+01 1.18959179e+01 1.20078878e+01 1.21701803e+01 1.23569460e+01 1.26597395e+01 1.29951324e+01 1.32731094e+01 1.35304432e+01 1.38836842e+01 1.42092714e+01 1.43741798e+01 1.45374908e+01 1.46405106e+01 1.48830376e+01 1.50855322e+01 1.53801451e+01 1.57772627e+01 1.60045738e+01 1.61931324e+01 1.63148441e+01 1.61939831e+01 1.64171467e+01 1.71394501e+01 1.74767151e+01 1.83327808e+01 1.85286121e+01 1.81831379e+01 1.83980980e+01 1.86076851e+01 1.89688587e+01 1.90677681e+01 1.91705799e+01 1.94702320e+01 1.96238842e+01 1.98112774e+01 1.98693657e+01 2.02874718e+01 2.05162563e+01 2.08125381e+01 2.10026817e+01 2.11677856e+01 2.14042072e+01 2.15012512e+01 2.20804176e+01 2.23155365e+01 2.23790016e+01 2.24441223e+01 2.27170410e+01 2.29479122e+01 2.23065624e+01 2.24241123e+01 -7.08526840e+01 -1.50839661e+02 -3.87111023e+02 -1.20433459e+03 -6.49290977e+04 -144773488. 162565248. 0. -251944816. -251944816. 1742333568. -494129408. -494129408. 0. 0. 0. 0. 0. 0. -1.74448953e+05 1.52849902e+03 2.56537231e+02 -4.12032654e+02 -1.73033569e+02 -8.68375168e+01 2.93207932e+01 2.79401798e+01 3.03904152e+01 2.96285191e+01 2.94076633e+01 2.94493332e+01 2.97423820e+01 2.89824581e+01 2.99467487e+01 3.10683136e+01 3.09691734e+01 3.12612591e+01 3.12343807e+01 3.12508183e+01 3.10719624e+01 3.11004066e+01 3.12544575e+01 3.13257713e+01 3.16449738e+01 3.21233444e+01 3.23085861e+01 3.21930008e+01 3.24680634e+01 3.25519028e+01 3.27671394e+01 3.30648804e+01 3.32756195e+01 3.34374847e+01 3.35715027e+01 3.36423340e+01 3.37502441e+01 3.38686752e+01 3.41372032e+01 3.40439529e+01 3.39135437e+01 3.40364227e+01 3.48789177e+01 3.47308998e+01 3.53617516e+01 3.53609657e+01 3.52110710e+01 3.53686905e+01 3.55666580e+01 3.64717445e+01 3.66674614e+01 3.68842354e+01 3.65301437e+01 3.64664803e+01 3.63462219e+01 3.60047379e+01 3.56475372e+01 3.62936211e+01 3.65230141e+01 3.72674026e+01 3.73956833e+01 3.81194572e+01 3.71561699e+01 3.71257896e+01 3.75590286e+01 3.77927513e+01 3.75283203e+01 3.73483467e+01 3.80970306e+01 3.85685883e+01 3.88376694e+01 3.85371552e+01 3.83998795e+01 3.87676811e+01 3.86883545e+01 3.86259842e+01 3.91133423e+01 3.94707909e+01 3.91597023e+01 3.90442848e+01 3.93444633e+01 3.99631958e+01 3.97991409e+01 3.97579536e+01 3.95059700e+01 3.98536263e+01 3.97866669e+01 3.94173775e+01 3.89417572e+01 3.96229782e+01 4.02318344e+01 4.03454552e+01 4.03156128e+01 3.96823692e+01 3.99237328e+01 3.99656639e+01 3.97390518e+01 4.03437042e+01 4.09267654e+01 4.12245445e+01 4.04585533e+01 4.00206642e+01 4.08604889e+01 4.15643196e+01 4.16405144e+01 4.04433136e+01 4.07489014e+01 4.06717491e+01 4.10961037e+01 4.12778969e+01 4.11422005e+01 4.12262039e+01 4.12876778e+01 4.13728981e+01 4.12613144e+01 4.14703903e+01 4.16407242e+01 4.15255203e+01 4.16449623e+01 4.21244431e+01 4.21553726e+01 4.18959503e+01 4.16371117e+01 4.15398598e+01 4.17436600e+01 4.18618431e+01 4.21013107e+01 4.18687897e+01 4.15160370e+01 4.16611137e+01 4.17027664e+01 4.18064461e+01 4.19673462e+01 4.18182182e+01 4.12929955e+01 4.23142166e+01 4.22947540e+01 4.16000404e+01 4.16737137e+01 4.21552353e+01 4.22363167e+01 4.18194160e+01 4.15284233e+01 4.15901871e+01 4.19313431e+01 4.19103012e+01 4.18875351e+01 4.21302795e+01 4.19086647e+01 4.18336601e+01 4.19494743e+01 4.16148911e+01 4.14511986e+01 4.16628304e+01 4.15379105e+01 4.16228867e+01 4.18966141e+01 4.17828751e+01 4.16703339e+01 4.17314186e+01 4.16584778e+01 4.15304108e+01 4.14642525e+01 4.16802635e+01 4.16168709e+01 4.12732086e+01 4.12657700e+01 4.08023415e+01 4.07434654e+01 4.09993858e+01 4.08509979e+01 4.12138786e+01 4.12190285e+01 4.05335083e+01 4.04831848e+01 4.08277435e+01 4.09015160e+01 4.07540665e+01 4.08069267e+01 4.04571381e+01 4.00977364e+01 4.02090950e+01 3.99976425e+01 4.01700401e+01 4.06297455e+01 4.04838905e+01 4.04188194e+01 4.08915138e+01 4.04859886e+01 4.00961533e+01 3.98435669e+01 3.96097488e+01 3.95611649e+01 3.96739616e+01 3.98841248e+01 3.98714142e+01 3.97911720e+01 3.95264664e+01 3.92354507e+01 3.93085403e+01 3.93906174e+01 3.96455612e+01 3.92911568e+01 3.92332993e+01 3.95444870e+01 3.91181641e+01 3.82799683e+01 3.83225288e+01 3.87198257e+01 3.84963150e+01 3.86828880e+01 3.83941383e+01 3.84579353e+01 3.82487106e+01 3.78880348e+01 3.75990143e+01 3.70535545e+01 3.69516678e+01 3.72592735e+01 3.72442780e+01 3.69785767e+01 3.64298477e+01 3.66379433e+01 3.62440529e+01 3.64435387e+01 3.63296013e+01 3.59767265e+01 3.59702377e+01 3.59780083e+01 3.62559242e+01 3.60369492e+01 3.57506714e+01 3.55083313e+01 3.51671715e+01 3.56084518e+01 3.48567848e+01 3.48769760e+01 3.45816307e+01 3.46453934e+01 3.46274757e+01 3.40227852e+01 3.38494186e+01 3.37874069e+01 3.44889183e+01 3.44035187e+01 3.36741982e+01 3.35890999e+01 3.36434822e+01 3.34695282e+01 3.30591698e+01 3.27557716e+01 3.27082100e+01 3.22789993e+01 3.16122169e+01 3.16296024e+01 3.19894352e+01 3.27341003e+01 3.27660103e+01 3.21923409e+01 3.17402534e+01 3.15558167e+01 3.10722313e+01 3.13764439e+01 3.11084709e+01 3.06605854e+01 3.02268715e+01 2.96693535e+01 2.98331566e+01 2.97501316e+01 2.96512089e+01 2.90744629e+01 2.87620983e+01 2.87988033e+01 2.93355694e+01 2.88619156e+01 2.83428993e+01 2.77345524e+01 2.75105839e+01 2.72178249e+01 2.70762234e+01 2.71930561e+01 2.73595943e+01 2.73167229e+01 2.70915241e+01 2.67272739e+01 2.63101368e+01 2.61963482e+01 2.58909626e+01 2.55433369e+01 2.54599380e+01 2.55039940e+01 2.51589375e+01 2.53300037e+01 2.50865574e+01 2.48845043e+01 2.43289948e+01 2.41599751e+01 2.37835007e+01 2.40427761e+01 2.34214706e+01 2.33460636e+01 2.28047390e+01 2.28646393e+01 2.27359314e+01 2.18735561e+01 2.21414433e+01 2.22735195e+01 2.23310032e+01 2.19723434e+01 2.17240696e+01 2.12785702e+01 2.05640240e+01 1.99935970e+01 2.01805401e+01 1.97758045e+01 2.00775242e+01 1.99697170e+01 2.01652164e+01 1.94104252e+01 1.91172981e+01 1.90490208e+01 1.91355267e+01 1.81773815e+01 1.79269753e+01 1.81798782e+01 1.75834408e+01 1.73016109e+01 1.68106747e+01 1.65889587e+01 1.63756428e+01 1.60594997e+01 1.59164257e+01 1.59448719e+01 1.59667568e+01 1.57344656e+01 1.53572626e+01 1.51335793e+01 1.51198769e+01 1.47543411e+01 1.45260515e+01 1.40930748e+01 1.39041224e+01 1.36418352e+01 1.33351240e+01 1.27354460e+01 1.26706867e+01 1.26023893e+01 1.23905954e+01 1.21726618e+01 1.16701612e+01 1.13797712e+01 1.11179867e+01 1.08101072e+01 1.07147284e+01 1.05283766e+01 1.03419456e+01 1.01190872e+01 9.74295998e+00 9.50929260e+00 9.08335018e+00 8.92434025e+00 8.63104534e+00 8.52900314e+00 8.39941692e+00 8.23596287e+00 7.80182362e+00 7.49119234e+00 7.35002089e+00 7.07536888e+00 6.87725639e+00 6.72366714e+00 6.45068932e+00 6.17653608e+00 5.84725857e+00 5.60078239e+00 5.35210371e+00 5.03394318e+00 4.77193546e+00 4.40237045e+00 4.19528484e+00 4.04125881e+00 3.79041028e+00 3.52582288e+00 3.25313354e+00 2.98116255e+00 2.67382050e+00 2.39923906e+00 2.22853303e+00 1.94808793e+00 1.74316692e+00 1.47357082e+00 1.20927405e+00 9.28696632e-01 6.89597070e-01 4.51839179e-01 1.71917900e-01 -9.98251960e-02 -3.26480597e-01 -6.32462919e-01 -9.01085377e-01 -1.11082089e+00 -1.37337220e+00 -1.63382339e+00 -1.89290297e+00 -2.16077137e+00 -2.41586447e+00 -2.66563463e+00 -2.93111515e+00 -3.19442034e+00 -3.49686170e+00 -3.76393294e+00 -3.99568725e+00 -4.21213531e+00 -4.45718193e+00 -4.73590517e+00 -4.98634243e+00 -5.23760080e+00 -5.49255085e+00 -5.74878645e+00 -6.00354099e+00 -6.25724983e+00 -6.51375389e+00 -6.77025270e+00 -7.02495718e+00 -7.28200102e+00 -7.53770304e+00 -7.79479742e+00 -8.05821800e+00 -8.27953339e+00 -8.48940659e+00 -8.81408787e+00 -9.07899475e+00 -9.28458023e+00 -9.53984165e+00 -9.84166241e+00 -1.00414467e+01 -1.02228842e+01 -1.05115738e+01 -1.07808046e+01 -1.10862284e+01 -1.12987862e+01 -1.15341187e+01 -1.18269453e+01 -1.20757914e+01 -1.23168583e+01 -1.25090046e+01 -1.27601023e+01 -1.30074987e+01 -1.33120308e+01 -1.34976044e+01 -1.39391050e+01 -1.42536182e+01 -1.42856312e+01 -1.44224186e+01 -1.45881672e+01 -1.49541941e+01 -1.53482141e+01 -1.56792269e+01 -1.58222980e+01 -1.59515438e+01 -1.62170639e+01 -1.64607716e+01 -1.66782322e+01 -1.68146839e+01 -1.71105251e+01 -1.74498577e+01 -1.77469902e+01 -1.78978786e+01 -1.80749359e+01 -1.82922688e+01 -1.84959221e+01 -1.87884178e+01 -1.89229279e+01 -1.90846558e+01 -1.93884773e+01 -1.96569576e+01 -1.98647804e+01 -1.98397655e+01 -2.01324520e+01 -2.03534584e+01 -2.08577976e+01 -2.10507221e+01 -2.11484947e+01 -2.14455357e+01 -2.17747250e+01 -2.22244091e+01 -2.26124115e+01 -2.27368946e+01 -2.24895802e+01 -2.27912216e+01 -2.35198383e+01 -2.34040184e+01 -2.33944244e+01 -2.35000782e+01 -2.37603741e+01 -2.41191635e+01 -2.44081211e+01 -2.44896355e+01 -2.46006489e+01 -2.52998066e+01 -2.54168930e+01 -2.54252224e+01 -2.54118958e+01 -2.57189102e+01 -2.60995178e+01 -2.59850864e+01 -2.60656204e+01 -2.63709908e+01 -2.65352440e+01 -2.67475834e+01 -2.72221909e+01 -2.74602299e+01 -2.78877125e+01 -2.81007671e+01 -2.81590462e+01 -2.79491367e+01 -2.82590866e+01 -2.84280205e+01 -2.90531902e+01 -2.90130539e+01 -2.89193153e+01 -2.93335953e+01 -2.97210007e+01 -3.00881138e+01 -3.00715408e+01 -2.98631744e+01 -2.95483208e+01 -2.99473095e+01 -3.04495506e+01 -3.13140945e+01 -3.09475670e+01 -3.07935905e+01 -3.10283699e+01 -3.12970104e+01 -3.16143894e+01 -3.14164104e+01 -3.15890121e+01 -3.19709625e+01 -3.22392426e+01 -3.26472054e+01 -3.25591812e+01 -3.26091881e+01 -3.25236511e+01 -3.26447258e+01 -3.31051979e+01 -3.38153114e+01 -3.39361076e+01 -3.35310631e+01 -3.37547150e+01 -3.39730530e+01 -3.42772331e+01 -3.40436096e+01 -3.39825325e+01 -3.39720345e+01 -3.45493965e+01 -3.44984741e+01 -3.50166283e+01 -3.48314247e+01 -3.48557663e+01 -3.53462410e+01 -3.55320702e+01 -3.61069260e+01 -3.62659340e+01 -3.64927177e+01 -3.65045128e+01 -3.66570129e+01 -3.64596596e+01 -3.60447617e+01 -3.57286644e+01 -3.63245811e+01 -3.62661552e+01 -3.68967018e+01 -3.69305191e+01 -3.76417847e+01 -3.73208122e+01 -3.77347603e+01 -3.81190109e+01 -3.82854233e+01 -3.79218292e+01 -3.73889999e+01 -3.75725746e+01 -3.79357681e+01 -3.81759186e+01 -3.82864647e+01 -3.87446709e+01 -3.89188385e+01 -3.85307426e+01 -3.85280418e+01 -3.86753807e+01 -3.91808510e+01 -3.93544426e+01 -3.91357651e+01 -3.92807770e+01 -3.97290916e+01 -3.98014870e+01 -3.96971970e+01 -3.94007874e+01 -3.96451073e+01 -3.94200974e+01 -3.92892151e+01 -3.89006424e+01 -3.94708061e+01 -4.02223358e+01 -4.03707581e+01 -4.04454384e+01 -3.98649635e+01 -3.95678253e+01 -3.98435936e+01 -4.00598412e+01 -4.02840195e+01 -4.05378799e+01 -4.11047668e+01 -4.10032539e+01 -4.03529167e+01 -4.04142723e+01 -4.00889511e+01 -4.01108284e+01 -4.03028450e+01 -4.11263390e+01 -4.08706207e+01 -4.11327286e+01 -4.06856613e+01 -4.06353874e+01 -4.11483803e+01 -4.12082825e+01 -4.12796364e+01 -4.06886139e+01 -3.82693214e+01 -3.88928032e+01 -4.11384048e+01 -4.23698311e+01 -4.29949036e+01 -4.19398193e+01 -4.11228104e+01 -4.12660141e+01 -3.97351494e+01 1.64729614e+02 -4.26349716e+01 -2.70377045e+02 -4.34670792e+01 -4.60173836e+01 1.62735672e+02 -4.03361702e+01 -2.71173279e+02 -4.00100212e+01 -4.07522621e+01 -4.22294579e+01 -4.25230179e+01 -4.24905510e+01 -4.27728615e+01 -4.30329933e+01 -4.36771851e+01 -4.40111847e+01 -4.26237526e+01 -4.16479988e+01 -4.18750153e+01 -4.14578285e+01 -4.16033592e+01 -4.21535645e+01 -4.18044434e+01 -4.18264771e+01 -4.20542984e+01 -4.22461052e+01 -4.18879089e+01 -4.12526779e+01 -4.13011208e+01 -4.18710327e+01 -4.16600342e+01 -4.10862236e+01 -4.17320557e+01 -4.16038322e+01 -4.17031479e+01 -4.16612015e+01 -4.08020782e+01 -4.11989784e+01 -4.17467651e+01 -4.15230789e+01 -4.11930885e+01 -4.11155624e+01 -4.13948250e+01 -4.14673500e+01 -4.11702728e+01 -4.09223442e+01 -4.08141327e+01 -4.08591881e+01 -4.09086800e+01 -4.09265823e+01 -4.05433044e+01 -4.04500465e+01 -4.03558197e+01 -4.05460739e+01 -4.04095039e+01 -4.01842957e+01 -4.06656342e+01 -4.05680084e+01 -4.03048363e+01 -4.06573372e+01 -4.06153717e+01 -4.04813766e+01 -4.03069649e+01 -3.99287186e+01 -3.99125519e+01 -3.99170036e+01 -3.94363327e+01 -3.97991867e+01 -4.03262825e+01 -4.03831596e+01 -4.02032776e+01 -4.00750809e+01 -3.97019386e+01 -3.88595200e+01 -3.88437042e+01 -3.87596130e+01 -3.92058754e+01 -3.89244270e+01 -3.88196373e+01 -3.84815331e+01 -3.78181648e+01 -3.78242950e+01 -3.74890251e+01 -3.80150375e+01 -3.81058998e+01 -3.83713531e+01 -3.85159340e+01 -3.82605362e+01 -3.82554893e+01 -3.75968018e+01 -3.77078972e+01 -3.72496872e+01 -3.69524879e+01 -3.67483215e+01 -3.65460472e+01 -3.62146606e+01 -3.56064224e+01 -3.63518562e+01 -3.64286308e+01 -3.66434441e+01 -3.66536064e+01 -3.62167625e+01 -3.53246346e+01 -3.48300591e+01 -3.53355827e+01 -3.57336922e+01 -3.55907097e+01 -3.57701225e+01 -3.52681427e+01 -3.52777977e+01 -3.46258125e+01 -3.48082848e+01 -3.44461594e+01 -3.47059708e+01 -3.46744957e+01 -3.36824417e+01 -3.33884621e+01 -3.34704552e+01 -3.42398453e+01 -3.42612762e+01 -3.38458977e+01 -3.34723587e+01 -3.32415352e+01 -3.31499062e+01 -3.28863258e+01 -3.23740730e+01 -3.21497078e+01 -3.20453529e+01 -3.19939327e+01 -3.19614372e+01 -3.18722782e+01 -3.21111221e+01 -3.24156151e+01 -3.23130951e+01 -3.15217705e+01 -3.13386421e+01 -3.08669910e+01 -3.11811047e+01 -3.09056168e+01 -2.94670830e+01 -2.94648914e+01 -3.03241367e+01 -3.09266319e+01 -3.04109974e+01 -2.94022942e+01 -2.90703068e+01 -2.89291668e+01 -2.88076668e+01 -2.91904964e+01 -2.83752117e+01 -2.80545216e+01 -2.78225613e+01 -2.76090412e+01 -2.71197796e+01 -2.66614170e+01 -2.69777203e+01 -2.71882401e+01 -2.68805008e+01 -2.67142696e+01 -2.67576771e+01 -2.65248699e+01 -2.65129910e+01 -2.50038395e+01 -2.49250813e+01 -2.57382469e+01 -2.54205036e+01 -2.60784531e+01 -2.60647984e+01 -2.46268005e+01 -2.44176579e+01 -2.42157745e+01 -2.40193996e+01 -2.35058041e+01 -2.36280766e+01 -2.22830029e+01 -2.25899811e+01 -2.30984936e+01 -2.32914219e+01 -2.30492306e+01 -2.20148106e+01 -2.22468414e+01 -2.21197491e+01 -2.14994068e+01 -2.07677174e+01 -2.12581043e+01 -2.16811275e+01 -2.08358746e+01 -2.00306072e+01 -2.00745125e+01 -1.91508808e+01 -1.88551273e+01 -1.66711197e+01 -2.06449375e+01 -1.25375347e+01 -1.41808212e+02 -5.22686401e+02 -1.30341089e+03 -395095872. -2.08441438e+06 150547056. 150547056. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -105002672. -45696220. -7.60661230e+03 -1.23495618e+03 -4.69576111e+02 -1.28836945e+02 -1.49427404e+01 -1.61329823e+01 -1.50531435e+01 -1.37369776e+01 -1.30395155e+01 -1.21398163e+01 -1.24426651e+01 -1.06495123e+01 -8.07132149e+00 -1.07589455e+01 -1.16896181e+01 -1.08552942e+01 -1.16729717e+01 -1.07539654e+01 -1.00850334e+01 -9.37411785e+00 -9.06386185e+00 -9.23526192e+00 -9.70753288e+00 -9.26931667e+00 -8.88287735e+00 -8.43232250e+00 -8.07389450e+00 -7.49499226e+00 -6.97466135e+00 -7.19069862e+00 -7.43671417e+00 -7.20764589e+00 -6.84945297e+00 -6.35901213e+00 -6.02539444e+00 -5.83509350e+00 -5.58409595e+00 -5.39170551e+00 -4.96200037e+00 -4.72446346e+00 -4.34898901e+00 -4.00272274e+00 -3.76396227e+00 -3.68277454e+00 -3.57554960e+00 -3.28883934e+00 -3.07340884e+00 -2.75151896e+00 -2.40658259e+00 -2.19517350e+00 -1.95131767e+00 -1.69787514e+00 -1.42522860e+00 -1.23841596e+00 -1.01716089e+00 -7.37912357e-01 -4.09632802e-01 -1.58668920e-01 8.98334682e-02 2.56226212e-01 6.29652560e-01 1.06878304e+00 1.38026214e+00 1.87002873e+00 2.68144250e+00 1.14795685e+00 -1.04134369e+01 1.03192497e+02 69258424. 69258424. -254580928. -102906360. 3.47857219e+05 3.79364657e+00 6.21549873e+01 1.63007690e+02 1.55875050e+06 571887. 58337280. -34182836. 0. 0. 959236352. -633417088. -1.63658600e+02 97526872. -126840040. 0. 0. 476654848. 3.90038361e+02 9.38689804e+01 2.08252506e+01 4.11961212e+01 2.55270042e+01 4.67332602e+00 5.54556370e+00 5.87579393e+00 6.03918791e+00 5.91783810e+00 5.86380672e+00 6.19683647e+00 6.57866812e+00 6.80210876e+00 7.03426695e+00 7.27197599e+00 7.55796099e+00 7.92074919e+00 8.15750122e+00 8.36485100e+00 8.41308880e+00 8.60043430e+00 8.84862614e+00 9.21725845e+00 9.85096550e+00 1.00852175e+01 9.79568386e+00 9.92978954e+00 1.02155094e+01 1.03864079e+01 1.08544235e+01 1.10971937e+01 1.12619257e+01 1.14494152e+01 1.01455402e+01 1.02010460e+01 1.20803614e+01 1.26939011e+01 1.42529936e+01 1.50640154e+01 1.39137678e+01 1.36038361e+01 1.38958607e+01 1.42172527e+01 1.42784529e+01 1.44508762e+01 1.45490112e+01 1.47820635e+01 1.50087290e+01 1.54490452e+01 1.56792870e+01 1.58685503e+01 1.58371506e+01 1.63198051e+01 1.64711742e+01 1.64965572e+01 1.67311840e+01 1.70963631e+01 1.71363602e+01 1.69670944e+01 1.67713776e+01 1.66564865e+01 1.67489395e+01 -7.37938614e+01 -1.41247299e+02 -3.41167969e+02 -1.01370770e+03 -40371856. 2631699. 900671936. 900671936. 0. 0. -251944816. -251944816. 1742333568. -494129408. -494129408. 0. 0. 0. 0. 206530640. -266227296. -1.20688904e+03 -4.55784943e+02 -1.82065674e+02 -9.34383469e+01 2.32483349e+01 2.33227501e+01 2.44514275e+01 2.46283760e+01 2.41469193e+01 2.40380402e+01 2.47630444e+01 2.54811306e+01 2.59328976e+01 2.60182362e+01 2.57678967e+01 2.59085312e+01 2.59394150e+01 2.57524586e+01 2.58476715e+01 2.61002350e+01 2.61082745e+01 2.66421318e+01 2.69549255e+01 2.73733311e+01 2.72732849e+01 2.70387917e+01 2.73231716e+01 2.77712021e+01 2.81405964e+01 2.82337875e+01 2.81422672e+01 2.86078491e+01 2.87848072e+01 2.86665726e+01 2.87619839e+01 2.84841938e+01 2.85926132e+01 2.89547482e+01 2.96597786e+01 3.03520718e+01 3.06271172e+01 3.08555546e+01 3.05344543e+01 3.04493160e+01 3.05964241e+01 3.13306580e+01 3.15567455e+01 3.13015823e+01 3.15056343e+01 3.10657425e+01 3.13062992e+01 3.18594379e+01 3.16829529e+01 3.19854279e+01 3.20527954e+01 3.20186081e+01 3.23252945e+01 3.27985992e+01 3.32217178e+01 3.29624062e+01 3.21562157e+01 3.21236877e+01 3.23606033e+01 3.29493866e+01 3.33501244e+01 3.34972610e+01 3.31323318e+01 3.33028488e+01 3.38083572e+01 3.42636948e+01 3.41496353e+01 3.44531136e+01 3.45829849e+01 3.52166061e+01 3.59379463e+01 3.58244209e+01 3.53839226e+01 3.54958611e+01 3.48630028e+01 3.43008575e+01 3.36133308e+01 3.39627151e+01 3.49678764e+01 3.59133797e+01 3.60430603e+01 3.60051918e+01 3.59691582e+01 3.59954185e+01 3.60997276e+01 3.61790771e+01 3.56395988e+01 3.58759232e+01 3.60654411e+01 3.66489105e+01 3.70442696e+01 3.73981781e+01 3.71488152e+01 3.67224045e+01 3.67046051e+01 3.70805054e+01 3.53355637e+01 3.53743591e+01 3.79162598e+01 3.92664413e+01 3.85756302e+01 3.74117165e+01 3.71250381e+01 3.69913101e+01 3.76846962e+01 3.79956322e+01 3.81639671e+01 3.77693214e+01 3.78962975e+01 3.75289879e+01 3.77374458e+01 3.78439598e+01 3.79131699e+01 3.76545753e+01 3.83411484e+01 3.91892700e+01 3.85014954e+01 3.82395325e+01 3.79756813e+01 3.81889420e+01 3.83852119e+01 3.87667503e+01 3.88188515e+01 3.88261833e+01 3.83881721e+01 3.88316078e+01 3.89985580e+01 3.84922829e+01 3.87035828e+01 3.85991669e+01 3.81194000e+01 3.91947823e+01 3.95245781e+01 3.88924980e+01 3.89220009e+01 3.92223854e+01 3.91258965e+01 3.89995003e+01 3.90808945e+01 3.90545807e+01 3.91987762e+01 3.92363663e+01 3.90032959e+01 3.93024979e+01 3.94737434e+01 3.91759186e+01 3.93157463e+01 3.92666740e+01 3.91657600e+01 3.92758865e+01 3.92780685e+01 3.94020271e+01 3.95881004e+01 3.93073654e+01 3.93381310e+01 3.93804131e+01 3.94900665e+01 3.95708771e+01 3.94859467e+01 3.95771332e+01 3.93275642e+01 3.87910233e+01 3.90201263e+01 3.89068489e+01 3.90583687e+01 3.92657928e+01 3.87294693e+01 3.90668221e+01 3.90157890e+01 3.80684319e+01 3.82444954e+01 3.83750000e+01 3.87441902e+01 3.90268173e+01 3.76704865e+01 3.50531158e+01 3.89212151e+01 4.06896057e+01 3.44296265e+01 3.58573532e+01 4.33323593e+01 4.40490723e+01 3.90597267e+01 -1.67575836e+02 -3.14550842e+02 7.01551208e+01 6.91927872e+01 6.93638000e+01 6.88755722e+01 6.81767349e+01 6.85584259e+01 6.94297409e+01 7.05397873e+01 6.95985718e+01 6.77554703e+01 6.75360107e+01 6.88085556e+01 7.01567993e+01 6.80144958e+01 6.87165146e+01 6.97433167e+01 4.20080261e+02 5.86112823e+01 -3.07257904e+02 6.63323059e+01 4.16598175e+02 2.68338287e+02 4.40958710e+01 3.83542442e+01 3.70580521e+01 3.69210167e+01 3.64992371e+01 3.65689964e+01 3.70153580e+01 3.66493263e+01 3.69007416e+01 3.68611450e+01 3.68807449e+01 3.63923988e+01 3.58040581e+01 3.60180779e+01 3.66845016e+01 3.59458923e+01 3.56424980e+01 3.57331467e+01 3.58060875e+01 3.57856102e+01 3.55849190e+01 3.51686935e+01 3.49867096e+01 3.45939140e+01 3.48413734e+01 3.48338547e+01 3.51156960e+01 3.51481819e+01 3.48061523e+01 3.50037651e+01 3.48790016e+01 3.42998886e+01 3.39881706e+01 3.39688492e+01 3.37749329e+01 3.37479935e+01 3.33101425e+01 3.37398415e+01 3.37248764e+01 3.38245201e+01 3.40598793e+01 3.40504189e+01 3.30767479e+01 3.28876076e+01 3.22012138e+01 3.30711594e+01 3.25607033e+01 3.15047932e+01 3.13677082e+01 3.11861362e+01 3.22002831e+01 3.17912273e+01 3.07755260e+01 3.08970699e+01 3.06895123e+01 3.14838505e+01 3.14843006e+01 3.11421242e+01 3.09213104e+01 3.06421032e+01 3.05016575e+01 3.04538460e+01 2.98188381e+01 2.95640240e+01 2.95646496e+01 2.92377663e+01 2.95106850e+01 2.92421837e+01 2.94520779e+01 2.90932293e+01 2.83150253e+01 2.81623116e+01 2.87172394e+01 2.85203094e+01 2.79778385e+01 2.78327808e+01 2.81296730e+01 2.78912735e+01 2.72912731e+01 2.72878475e+01 2.65078259e+01 2.63972111e+01 2.61757431e+01 2.63138790e+01 2.66241608e+01 2.67252121e+01 2.65098495e+01 2.59170666e+01 2.54169178e+01 2.45510082e+01 2.48322315e+01 2.57955894e+01 2.55492840e+01 2.47847729e+01 2.43133602e+01 2.42434711e+01 2.42027454e+01 2.37651825e+01 2.37790642e+01 2.34363441e+01 2.29906158e+01 2.29603157e+01 2.31720085e+01 2.27999763e+01 2.22839298e+01 2.17274551e+01 2.16758556e+01 2.14668560e+01 2.13491344e+01 2.11911640e+01 2.08135319e+01 1.96445885e+01 1.98616371e+01 2.08577003e+01 2.02770252e+01 1.96149406e+01 1.94042225e+01 1.91543541e+01 1.94596405e+01 1.93141327e+01 1.91918201e+01 1.85113773e+01 1.84858475e+01 1.81567822e+01 1.77683372e+01 1.73608055e+01 1.71741238e+01 1.73135223e+01 1.76621819e+01 1.74011955e+01 1.71043720e+01 1.67564602e+01 1.65868111e+01 1.62382202e+01 1.60746918e+01 1.55604134e+01 1.54504976e+01 1.53079910e+01 1.52335691e+01 1.50857172e+01 1.49851675e+01 1.47667122e+01 1.43517866e+01 1.38598194e+01 1.37116880e+01 1.34598818e+01 1.32896500e+01 1.30571547e+01 1.27533646e+01 1.26279516e+01 1.24002647e+01 1.20544939e+01 1.18336105e+01 1.16404238e+01 1.14081268e+01 1.12177048e+01 1.09527817e+01 1.06976347e+01 1.04521570e+01 1.02431469e+01 1.01184273e+01 9.69539833e+00 9.35783005e+00 9.19524574e+00 9.10572243e+00 8.78595829e+00 8.52939701e+00 8.36116791e+00 8.20823669e+00 7.88608265e+00 7.73324680e+00 7.44325352e+00 7.17085218e+00 6.93115759e+00 6.76553297e+00 6.54722214e+00 6.25049019e+00 5.98675823e+00 5.72351551e+00 5.51530313e+00 5.35410929e+00 5.06826925e+00 4.82581139e+00 4.62403774e+00 4.35247564e+00 4.07109118e+00 3.86660242e+00 3.54555774e+00 3.31984830e+00 3.13712716e+00 2.88687062e+00 2.67659593e+00 2.43210053e+00 2.12325048e+00 1.89646947e+00 1.69842494e+00 1.45099545e+00 1.20088065e+00 8.84531856e-01 6.41454935e-01 4.58760113e-01 2.69044638e-01 2.70265043e-02 -2.57709354e-01 -4.89503682e-01 -7.24698126e-01 -9.70420003e-01 -1.21262634e+00 -1.45386541e+00 -1.69371033e+00 -1.93480563e+00 -2.18095541e+00 -2.42652583e+00 -2.67279410e+00 -2.91960120e+00 -3.14677525e+00 -3.40967178e+00 -3.64024711e+00 -3.83998585e+00 -4.13406372e+00 -4.38115788e+00 -4.58807945e+00 -4.83479786e+00 -5.13248968e+00 -5.31732988e+00 -5.49332094e+00 -5.75908852e+00 -6.00926542e+00 -6.29420328e+00 -6.50257683e+00 -6.76534891e+00 -7.01599407e+00 -7.25800037e+00 -7.42876530e+00 -7.66593361e+00 -7.93271208e+00 -8.18933296e+00 -8.37656403e+00 -8.50634003e+00 -8.91521358e+00 -9.21116638e+00 -9.26543331e+00 -9.41313362e+00 -9.64005756e+00 -9.93289757e+00 -1.02307863e+01 -1.05903997e+01 -1.07783470e+01 -1.09706411e+01 -1.11901379e+01 -1.14692364e+01 -1.16901007e+01 -1.18966360e+01 -1.20292511e+01 -1.23839750e+01 -1.26723175e+01 -1.29142265e+01 -1.29512205e+01 -1.31752987e+01 -1.33126049e+01 -1.37424698e+01 -1.39821587e+01 -1.42943497e+01 -1.43749466e+01 -1.47283058e+01 -1.49480877e+01 -1.53986330e+01 -1.53631649e+01 -1.53546972e+01 -1.57998209e+01 -1.62195415e+01 -1.62696629e+01 -1.64735317e+01 -1.67946720e+01 -1.69414043e+01 -1.75027981e+01 -1.77198181e+01 -1.73429680e+01 -1.74644642e+01 -1.80488796e+01 -1.82897434e+01 -1.79268265e+01 -1.83642120e+01 -1.89036789e+01 -1.91741848e+01 -2.00457020e+01 -1.99684696e+01 -1.97923374e+01 -2.00014973e+01 -2.02398300e+01 -2.03432274e+01 -2.02661114e+01 -2.06238995e+01 -2.13873692e+01 -2.13991890e+01 -2.16079159e+01 -2.20302391e+01 -2.20242004e+01 -2.21506462e+01 -2.24877586e+01 -2.26769409e+01 -2.32417164e+01 -2.27593040e+01 -2.28810501e+01 -2.32076836e+01 -2.29678516e+01 -2.31075363e+01 -2.31610088e+01 -2.33120041e+01 -2.38974342e+01 -2.44639492e+01 -2.47375336e+01 -2.51199818e+01 -2.54187450e+01 -2.49922028e+01 -2.49572849e+01 -2.53508244e+01 -2.58532867e+01 -2.58464088e+01 -2.60250397e+01 -2.61462097e+01 -2.61471691e+01 -2.67198811e+01 -2.70314121e+01 -2.75638065e+01 -2.72503815e+01 -2.68615952e+01 -2.71796532e+01 -2.79372368e+01 -2.79418869e+01 -2.81597824e+01 -2.77584305e+01 -2.82447491e+01 -2.93275070e+01 -2.98859749e+01 -2.98166084e+01 -2.87651043e+01 -2.89500198e+01 -2.88938828e+01 -2.93028297e+01 -2.97187099e+01 -3.01585274e+01 -3.03363571e+01 -3.01093540e+01 -3.02445164e+01 -3.02330246e+01 -3.10251846e+01 -3.06998425e+01 -3.05922928e+01 -3.09203072e+01 -3.13224716e+01 -3.15370216e+01 -3.17164440e+01 -3.12814198e+01 -3.16889629e+01 -3.18376694e+01 -3.20110207e+01 -3.20087738e+01 -3.26740723e+01 -3.30685616e+01 -3.28195724e+01 -3.25998077e+01 -3.31999130e+01 -3.32978859e+01 -3.31908531e+01 -3.32387962e+01 -3.33820419e+01 -3.31116371e+01 -3.29580193e+01 -3.36524048e+01 -3.37363129e+01 -3.35089951e+01 -3.40018654e+01 -3.44820671e+01 -3.50113373e+01 -3.47395210e+01 -3.47781487e+01 -3.46391182e+01 -3.48550949e+01 -3.46188698e+01 -3.43669739e+01 -3.43732605e+01 -3.45115891e+01 -3.51481056e+01 -3.60285606e+01 -3.61658859e+01 -3.65375328e+01 -3.58046913e+01 -3.60434113e+01 -3.56037483e+01 -3.58503151e+01 -3.54059715e+01 -3.58953171e+01 -3.61497803e+01 -3.63084755e+01 -3.68075905e+01 -3.80314789e+01 -3.79804497e+01 -3.64335709e+01 -3.60561028e+01 -3.71882477e+01 -3.78071175e+01 -3.74459534e+01 -3.73612404e+01 -3.75227966e+01 -3.67779541e+01 -3.71670532e+01 -3.74088783e+01 -3.70381851e+01 -3.70608292e+01 -3.68540764e+01 -3.71050186e+01 -3.73355484e+01 -3.72891922e+01 -3.72108383e+01 -3.63900604e+01 -3.29283409e+01 -3.22605362e+01 -3.65007706e+01 -3.61958466e+01 -3.80539513e+01 -4.04123573e+01 -3.97058868e+01 -3.87293091e+01 -3.57999496e+01 3.03991272e+02 3.52041626e+02 -1.00674530e+03 -8.51693115e+01 -1.00922485e+02 7.42011230e+02 -6.93387909e+01 -9.92864014e+02 -6.18669167e+01 -6.75986481e+01 -7.78958054e+01 -4.43946228e+02 -6.64782562e+01 -5.77962112e+01 -2.89244354e+02 -5.32514877e+01 -4.51196632e+01 -4.04240875e+01 -3.90589447e+01 -3.97297745e+01 -3.80890427e+01 -3.86112213e+01 -4.15730743e+01 -4.10393372e+01 -3.93547592e+01 -3.81182175e+01 -4.03252869e+01 -4.18307495e+01 -4.02100525e+01 -3.96861420e+01 -3.99605408e+01 -3.96051826e+01 -3.91266518e+01 -3.96127739e+01 -3.94041481e+01 -3.96222420e+01 -3.98125153e+01 -3.91316185e+01 -3.93127174e+01 -3.93849945e+01 -3.91217728e+01 -3.90657272e+01 -3.92173691e+01 -3.94039192e+01 -3.91344452e+01 -3.91426048e+01 -3.91710968e+01 -3.91175461e+01 -3.90553665e+01 -3.91594620e+01 -3.94850426e+01 -3.89451180e+01 -3.87897453e+01 -3.88991776e+01 -3.90433235e+01 -3.88059502e+01 -3.86622391e+01 -3.89976730e+01 -3.88429604e+01 -3.91929512e+01 -3.96148567e+01 -3.90061493e+01 -3.87717094e+01 -3.87743149e+01 -3.84252701e+01 -3.84637070e+01 -3.82982864e+01 -3.81587067e+01 -3.88728752e+01 -3.92603455e+01 -3.88838425e+01 -3.79920502e+01 -3.78164139e+01 -3.84418373e+01 -3.78615417e+01 -3.72658844e+01 -3.71889877e+01 -3.73837204e+01 -3.76306686e+01 -3.79843369e+01 -3.75498009e+01 -3.77517891e+01 -3.75150070e+01 -3.73356209e+01 -3.74494705e+01 -3.74035378e+01 -3.74443512e+01 -3.77242966e+01 -3.69425774e+01 -3.66735878e+01 -3.69742813e+01 -3.75510521e+01 -3.71931190e+01 -3.70187492e+01 -3.67369118e+01 -3.68404045e+01 -3.60132675e+01 -3.51373291e+01 -3.64293137e+01 -3.76036644e+01 -3.65509262e+01 -3.67986984e+01 -3.62472572e+01 -3.55013733e+01 -3.49575806e+01 -3.40249405e+01 -3.43774071e+01 -3.56449318e+01 -3.65445175e+01 -3.62979469e+01 -3.43712769e+01 -3.44472504e+01 -3.45043602e+01 -3.47858353e+01 -3.51246643e+01 -3.48606110e+01 -3.47506828e+01 -3.45341568e+01 -3.41151199e+01 -3.38725166e+01 -3.40647469e+01 -3.39579887e+01 -3.37842751e+01 -3.35448685e+01 -3.34922066e+01 -3.35252266e+01 -3.37900925e+01 -3.38892746e+01 -3.37791443e+01 -3.29571991e+01 -3.32236176e+01 -3.27120514e+01 -3.28103752e+01 -3.21797981e+01 -3.15804882e+01 -3.15970268e+01 -3.12304535e+01 -3.17011395e+01 -3.12615967e+01 -2.93795891e+01 -2.82499180e+01 -2.95149574e+01 -3.15269260e+01 -3.34477081e+01 -3.31504326e+01 -3.09371166e+01 -3.09760666e+01 -3.06858349e+01 -3.05268192e+01 -2.98716202e+01 -2.95383625e+01 -2.93087254e+01 -2.90207195e+01 -2.93002815e+01 -2.90099792e+01 -2.92137432e+01 -2.89063969e+01 -2.82247524e+01 -2.79642010e+01 -2.84917831e+01 -2.82424545e+01 -2.81226273e+01 -2.78971138e+01 -2.72911968e+01 -2.69686489e+01 -2.73871212e+01 -2.70812263e+01 -2.72688751e+01 -2.70404644e+01 -2.55667896e+01 -2.60287704e+01 -2.64401016e+01 -2.67387810e+01 -2.63919334e+01 -2.56345291e+01 -2.43451519e+01 -2.39397221e+01 -2.51246910e+01 -2.58116741e+01 -2.55656738e+01 -2.47339725e+01 -2.42034149e+01 -2.38315487e+01 -2.38110046e+01 -2.31775360e+01 -2.25196762e+01 -2.28778133e+01 -2.27066116e+01 -1.52765827e+01 1.10468422e+02 1.94383774e+02 -3.14118137e+01 -2.96102219e+01 -2.69078236e+01 -2.56059494e+01 -2.45595901e+02 -4.60329193e+02 -2.38173767e+02 -5.00457550e+02 -1.39911597e+03 -82093344. -940311552. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -394538816. -1.22758972e+03 -1.18090912e+02 -1.34021254e+01 -1.22470840e+02 -1.67233028e+01 -1.78213863e+01 -1.61944008e+01 -1.58454065e+01 -1.57052889e+01 -1.58546286e+01 -1.57196169e+01 -1.53373423e+01 -1.48783989e+01 -1.43281450e+01 -1.38722248e+01 -1.34229374e+01 -1.31384258e+01 -1.23735008e+01 -1.25421686e+01 -1.30421352e+01 -1.29516449e+01 -1.27023802e+01 -1.22358112e+01 -1.17330561e+01 -1.13547745e+01 -1.09009104e+01 -1.08237257e+01 -1.08287201e+01 -1.09400244e+01 -1.06766119e+01 -1.02437925e+01 -9.92210960e+00 -9.42638397e+00 -9.29987812e+00 -9.10969639e+00 -9.08664608e+00 -8.72226906e+00 -8.56923103e+00 -8.27837181e+00 -8.07040882e+00 -7.73493862e+00 -7.60960436e+00 -7.33928585e+00 -7.15833998e+00 -7.04133463e+00 -6.81411934e+00 -6.52211094e+00 -6.20306158e+00 -6.01809788e+00 -5.73632908e+00 -5.46936321e+00 -5.24610662e+00 -4.99728394e+00 -4.75359774e+00 -4.48497868e+00 -4.25527000e+00 -3.99588609e+00 -3.83958030e+00 -3.54555845e+00 -3.20641041e+00 -2.91667151e+00 -2.46120381e+00 -1.87060440e+00 -2.36099553e+00 -1.34165182e+01 -6.41923875e+05 0. 0. 0. 0. 0. 298558336. 298558336. 298558336. 0. 0. 0. 0. 0. 0. 959236352. -633417088. 1.46480194e+02 1.87256088e+02 -60026796. 1067954432. 0. 0. 1529941248. 2.47631411e+09 2.26314922e+05 1.95126923e+02 7.94991608e+01 -3.69399071e-01 1.04110897e+00 4.23949509e+01 2.76101589e+00 1.44141805e+00 1.88813972e+00 -4.79336472e+01 2.06559253e+00 1.95221639e+00 2.04710317e+00 2.35244823e+00 3.12360168e+00 4.19602871e+00 4.38578081e+00 4.58566141e+00 4.10911655e+00 3.96647859e+00 3.51690722e+00 4.18967867e+00 7.50599432e+00 8.27525520e+00 9.03525925e+01 7.25111723e+00 -8.23483658e+01 5.96261120e+00 7.34112358e+00 7.39870548e+00 6.93317747e+00 6.68093157e+00 -2.75456047e+00 -3.27707314e+00 7.57633543e+00 9.28272915e+00 1.74977398e+01 2.17136993e+01 1.41083374e+01 1.14422483e+01 1.18013010e+01 1.07503405e+01 1.04135962e+01 1.38983734e+02 8.76781082e+01 8.56047916e+00 8.92687702e+00 9.31001282e+00 9.45020580e+00 9.34978962e+00 9.10442352e+00 9.65241241e+00 9.94464588e+00 9.78730583e+00 9.53877735e+00 9.55876350e+00 1.00552759e+01 1.03128614e+01 -8.04088135e+01 -1.50652954e+02 8.31542683e+00 -3.77478333e+02 -9.78183289e+02 268139424. 860920768. 0. 900671936. 900671936. 900671936. 0. 0. -251944816. -251944816. -251944816. 0. 0. 0. 0. 0. -94990984. -2.25556494e+03 -4.70753845e+02 -1.93723007e+02 -1.03351906e+02 1.63434486e+01 1.70426254e+01 1.64952011e+01 1.66252365e+01 -1.07757179e+02 -2.02283295e+02 2.12029285e+01 2.09314327e+01 2.38193893e+01 2.63039417e+01 2.87840691e+01 2.59294373e+02 1.64020508e+02 1.89875164e+01 1.24188747e+01 1.83950939e+01 2.49313793e+01 2.04987659e+01 1.97547512e+01 1.91950569e+01 1.96929836e+01 1.97434006e+01 1.95792503e+01 1.94194221e+01 1.96976719e+01 2.00982456e+01 2.00747299e+01 2.01151867e+01 2.00761013e+01 2.02178688e+01 2.00573063e+01 2.06051712e+01 2.07221680e+01 2.06294231e+01 2.07459049e+01 2.09593716e+01 2.17135544e+01 2.23260632e+01 2.28219090e+01 2.29485836e+01 2.29770489e+01 2.26680565e+01 2.23369427e+01 2.21404552e+01 2.23803654e+01 2.28207951e+01 2.35244045e+01 2.33107014e+01 2.29123383e+01 2.35801220e+01 2.39655056e+01 2.38893623e+01 2.41169071e+01 2.47570248e+01 2.56385937e+01 2.52736931e+01 2.55182190e+01 2.47502174e+01 2.44802647e+01 2.38267117e+01 2.48012486e+01 2.52448311e+01 2.50207214e+01 2.52192974e+01 2.54134960e+01 2.63385372e+01 2.69817276e+01 2.72315407e+01 2.70366821e+01 2.67638588e+01 2.69841290e+01 2.74237137e+01 2.82500515e+01 2.80183640e+01 2.77157497e+01 2.73448105e+01 2.69321156e+01 2.68466511e+01 2.66190853e+01 2.69276829e+01 2.74514523e+01 2.79283981e+01 2.80233440e+01 2.79249821e+01 2.82141628e+01 2.82855892e+01 2.84254627e+01 2.87384319e+01 2.84211922e+01 2.86329498e+01 2.85359039e+01 2.85047379e+01 2.85977516e+01 2.87110558e+01 2.89560604e+01 2.86443119e+01 2.88525524e+01 2.89020023e+01 2.62696972e+01 2.62174206e+01 3.12818642e+01 3.26370201e+01 3.12092876e+01 3.02978191e+01 2.99182434e+01 2.94986610e+01 3.02306480e+01 3.02533112e+01 3.03029575e+01 3.04498329e+01 3.05278130e+01 3.02389927e+01 3.01552410e+01 3.04523373e+01 3.08955154e+01 3.06597919e+01 3.09815331e+01 3.13608456e+01 3.15828857e+01 3.16012745e+01 3.15850830e+01 3.17197876e+01 3.18530159e+01 3.15913544e+01 3.13875656e+01 3.16222115e+01 3.16092167e+01 3.16130486e+01 3.22191658e+01 3.19551468e+01 3.21373024e+01 3.14300194e+01 3.06105099e+01 3.22437859e+01 3.33036232e+01 3.20828819e+01 3.18874683e+01 3.22238388e+01 3.24892349e+01 3.23899879e+01 3.28418732e+01 3.27440758e+01 3.25087967e+01 3.24750900e+01 3.22851028e+01 3.27289810e+01 3.29466095e+01 3.28306389e+01 3.27979469e+01 3.27973824e+01 3.29028130e+01 3.28536644e+01 3.29419174e+01 3.30391884e+01 3.32089081e+01 3.29060669e+01 3.28984299e+01 3.29814911e+01 3.30789795e+01 3.34011612e+01 3.35548935e+01 3.33928223e+01 3.30696449e+01 3.27855530e+01 3.29056511e+01 3.28411179e+01 3.31762848e+01 3.32553673e+01 3.25503731e+01 3.29410172e+01 3.31142044e+01 3.21361580e+01 2.93599968e+01 2.44816608e+01 3.45642509e+01 3.80821190e+01 3.42649422e+01 3.37945976e+01 3.33859444e+01 -1.80071976e+02 -3.63056122e+02 4.31369629e+02 2.68723724e+02 3.31934776e+01 4.08411217e+01 4.41908340e+01 4.45927162e+01 5.06147652e+01 5.06876564e+01 4.99678192e+01 4.85570641e+01 4.81654854e+01 4.92178650e+01 4.92283669e+01 4.90140610e+01 4.93632164e+01 4.93631134e+01 4.92749710e+01 4.94132500e+01 4.92073174e+01 4.94669800e+01 4.94685974e+01 4.93149910e+01 4.35419769e+01 4.81931763e+01 3.75039368e+01 4.96555939e+01 3.39969482e+01 4.02790413e+01 3.87838173e+01 3.31166992e+01 3.23752098e+01 3.26546021e+01 3.17726898e+01 3.22944756e+01 3.26424904e+01 3.26416855e+01 3.20784874e+01 3.20094070e+01 3.25351677e+01 3.26416435e+01 3.17687988e+01 3.19673290e+01 3.28808327e+01 3.21642380e+01 3.17369041e+01 3.19381638e+01 3.16444321e+01 3.13119793e+01 3.17305508e+01 3.09585304e+01 3.18645248e+01 3.14151173e+01 3.16571465e+01 3.14888840e+01 3.14686794e+01 3.12912712e+01 3.12420330e+01 3.14923248e+01 3.15022717e+01 3.10368538e+01 3.07386513e+01 2.95117722e+01 2.96273766e+01 2.98187981e+01 2.99250183e+01 3.02585258e+01 3.02987251e+01 3.01063728e+01 2.98722363e+01 3.00844536e+01 3.04820595e+01 3.06244335e+01 2.97460003e+01 2.99676971e+01 2.98644428e+01 2.91934223e+01 2.92347870e+01 2.89248657e+01 2.97300282e+01 2.89283524e+01 2.80746765e+01 2.84949627e+01 2.81389389e+01 2.82273827e+01 2.81419735e+01 2.77260017e+01 2.74727135e+01 2.72419109e+01 2.78393612e+01 2.81098099e+01 2.76357594e+01 2.80813980e+01 2.79835567e+01 2.80145988e+01 2.74732609e+01 2.79744091e+01 2.77141972e+01 2.76256847e+01 2.68715382e+01 2.63439407e+01 2.67061062e+01 2.64738159e+01 2.61339016e+01 2.61623497e+01 2.64697933e+01 2.57253036e+01 2.56809235e+01 2.57599144e+01 2.52850704e+01 2.50586720e+01 2.47737160e+01 2.51192017e+01 2.53991394e+01 2.53636665e+01 2.52699852e+01 2.51089344e+01 2.46206760e+01 2.35266418e+01 2.30296917e+01 2.41872501e+01 2.50531368e+01 2.44254284e+01 2.39304066e+01 2.34203358e+01 2.32029991e+01 2.31621990e+01 2.29142265e+01 2.27895679e+01 2.29801350e+01 2.34453278e+01 2.32439060e+01 2.31242390e+01 2.21633682e+01 2.20947094e+01 2.15783234e+01 2.19697418e+01 2.18697395e+01 2.14842834e+01 2.09051094e+01 1.96611767e+01 2.02769547e+01 2.19337940e+01 2.11658630e+01 2.00977383e+01 1.97893887e+01 1.97610588e+01 2.02665997e+01 2.04432735e+01 1.99576550e+01 1.93597832e+01 1.93178940e+01 1.91261806e+01 1.89612427e+01 1.86608124e+01 1.85138969e+01 1.84884758e+01 1.84768581e+01 1.82415390e+01 1.79273872e+01 1.77669640e+01 1.77400990e+01 1.75798931e+01 1.75485725e+01 1.73020897e+01 1.71495361e+01 1.69733143e+01 1.65902958e+01 1.63272629e+01 1.60835800e+01 1.60882778e+01 1.57577114e+01 1.56120033e+01 1.54377832e+01 1.52933111e+01 1.49730988e+01 1.48422394e+01 1.47011700e+01 1.47819939e+01 1.46340647e+01 1.43855333e+01 1.41371222e+01 1.39700508e+01 1.38761501e+01 1.37106581e+01 1.33968601e+01 1.31144886e+01 1.27903662e+01 1.27228699e+01 1.27136831e+01 1.25803623e+01 1.21957016e+01 1.20162306e+01 1.19594355e+01 1.19158306e+01 1.16190233e+01 1.15466118e+01 1.13884048e+01 1.10618982e+01 1.07391872e+01 1.04537916e+01 1.02631531e+01 1.01397657e+01 1.00032978e+01 9.91623878e+00 9.65179348e+00 9.41530514e+00 9.07314491e+00 8.89758492e+00 8.81576729e+00 8.61798382e+00 8.36804295e+00 8.15936184e+00 7.92102814e+00 7.73442507e+00 7.67057037e+00 7.47288036e+00 7.19732332e+00 7.00490046e+00 6.77762699e+00 6.60807419e+00 6.40315199e+00 6.10215902e+00 5.92302418e+00 5.80827141e+00 5.59891510e+00 5.39249229e+00 5.10812807e+00 4.91152525e+00 4.77144670e+00 4.62273026e+00 4.42106962e+00 4.17197037e+00 3.97874379e+00 3.78594828e+00 3.57921576e+00 3.37617493e+00 3.17502499e+00 2.97553730e+00 2.77071977e+00 2.56211710e+00 2.35669851e+00 2.14973783e+00 1.94637775e+00 1.76774693e+00 1.52822280e+00 1.32308805e+00 1.16591561e+00 8.82473946e-01 6.72030449e-01 4.86198992e-01 2.63489366e-01 9.19863731e-02 -1.03492707e-01 -2.24713221e-01 -3.70098561e-01 -7.25254834e-01 -9.43220913e-01 -1.03800571e+00 -1.25199604e+00 -1.55773723e+00 -1.78331757e+00 -1.95448327e+00 -2.19418216e+00 -2.34027696e+00 -2.60002303e+00 -2.69489789e+00 -2.85333323e+00 -3.09830308e+00 -3.28592801e+00 -3.54397321e+00 -3.68521595e+00 -3.91947126e+00 -4.11129045e+00 -4.34761381e+00 -4.52411079e+00 -4.77534199e+00 -5.00097322e+00 -5.20953465e+00 -5.31452560e+00 -5.51827908e+00 -5.91839170e+00 -6.20160866e+00 -6.23359013e+00 -6.28956795e+00 -6.27812338e+00 -6.58463240e+00 -6.87315464e+00 -7.12482834e+00 -7.32252550e+00 -7.65810585e+00 -7.93306684e+00 -8.18003368e+00 -8.28343296e+00 -8.48766899e+00 -8.80683613e+00 -8.85557270e+00 -8.80795097e+00 -9.05609417e+00 -9.56764030e+00 -9.76604557e+00 -1.00194197e+01 -1.01491079e+01 -1.02422428e+01 -1.03583164e+01 -1.07548113e+01 -1.08090677e+01 -1.09466248e+01 -1.10977764e+01 -1.15396929e+01 -1.10847816e+01 -1.14911718e+01 -1.19075317e+01 -1.23741989e+01 -1.30407639e+01 -1.29194746e+01 -1.26046629e+01 -1.27151508e+01 -1.25796785e+01 -1.28479004e+01 -1.27163906e+01 -1.32749119e+01 -1.40286064e+01 -1.37421837e+01 -1.40293274e+01 -1.43817997e+01 -1.42670546e+01 -1.48476725e+01 -1.54319324e+01 -1.56067257e+01 -1.57295866e+01 -1.54327660e+01 -1.61751690e+01 -1.66514587e+01 -1.61802597e+01 -1.59036627e+01 -1.55427084e+01 -1.58442802e+01 -1.67874889e+01 -1.69670811e+01 -1.64268246e+01 -1.66717930e+01 -1.70205021e+01 -1.69123192e+01 -1.68648758e+01 -1.78771725e+01 -1.80335846e+01 -1.80945625e+01 -1.88125401e+01 -1.87381191e+01 -1.89264317e+01 -1.86981869e+01 -1.94989529e+01 -1.98122902e+01 -1.96154041e+01 -1.93692131e+01 -1.95393200e+01 -1.98944550e+01 -1.98628082e+01 -2.02216034e+01 -1.95566559e+01 -2.02554703e+01 -2.09572086e+01 -2.16541309e+01 -2.16809177e+01 -2.09764614e+01 -2.13403015e+01 -2.11331005e+01 -2.17979622e+01 -2.20648346e+01 -2.22796803e+01 -2.24739456e+01 -2.29263840e+01 -2.25982742e+01 -2.18592892e+01 -2.21942272e+01 -2.22469864e+01 -2.27679920e+01 -2.33510208e+01 -2.34640446e+01 -2.30816231e+01 -2.29345818e+01 -2.32011013e+01 -2.33476639e+01 -2.36091709e+01 -2.43061352e+01 -2.48853283e+01 -2.44775391e+01 -2.56350269e+01 -2.48509407e+01 -2.53689651e+01 -2.53393402e+01 -2.55110111e+01 -2.52827244e+01 -2.48580322e+01 -2.49045277e+01 -2.46985893e+01 -2.54874706e+01 -2.62876530e+01 -2.64716396e+01 -2.61891346e+01 -2.63113194e+01 -2.67123756e+01 -2.65744324e+01 -2.69351082e+01 -2.68860607e+01 -2.69180984e+01 -2.71720371e+01 -2.70536861e+01 -2.73340530e+01 -2.73169518e+01 -2.75488548e+01 -2.75213051e+01 -2.77195663e+01 -2.80342693e+01 -2.79311295e+01 -2.74108276e+01 -2.77876568e+01 -2.82887402e+01 -2.83706188e+01 -2.86753025e+01 -2.88939190e+01 -2.85803833e+01 -2.77550182e+01 -2.80957451e+01 -2.93125782e+01 -2.89819603e+01 -2.77906704e+01 -2.83626690e+01 -2.96789341e+01 -3.03811264e+01 -2.97127323e+01 -2.94951611e+01 -2.97383327e+01 -2.93982944e+01 -3.00653877e+01 -3.05130329e+01 -2.94337654e+01 -2.95785294e+01 -2.93998165e+01 -2.99156837e+01 -2.98486080e+01 -2.95929432e+01 -2.95895481e+01 -2.89439964e+01 -2.56680202e+01 -2.51546211e+01 -2.93559208e+01 -2.91306324e+01 -3.05817623e+01 -3.30715027e+01 -3.27045937e+01 -3.21105652e+01 -2.90451126e+01 -4.29388641e+02 -7.25832291e+01 3.57666870e+02 -4.95800629e+01 -5.41086044e+01 -5.18304443e+02 -4.60051422e+01 3.63426666e+02 -4.51999092e+01 -4.63802834e+01 -4.87195053e+01 -1.65526543e+01 -4.94922523e+01 -4.37757797e+01 -3.76752586e+01 -4.16432457e+01 -2.44145622e+01 -3.69283524e+01 -4.54597511e+01 -3.20766258e+01 -3.12555771e+01 -3.08836937e+01 -3.53922234e+01 -2.55054169e+01 -8.79603863e+00 -3.91059265e+01 -5.61542625e+01 -3.91825104e+01 -3.59972382e+01 -3.35720253e+01 -3.36011086e+01 -3.31138535e+01 -3.27507706e+01 -3.32249794e+01 -3.29241943e+01 -3.32673988e+01 -3.35736809e+01 -3.30707474e+01 -3.31470261e+01 -3.31109619e+01 -3.27915077e+01 -3.28429108e+01 -3.32519379e+01 -3.33363533e+01 -3.30040283e+01 -3.29334602e+01 -3.32265205e+01 -3.34875374e+01 -3.32751846e+01 -3.33549995e+01 -3.34973526e+01 -3.31590347e+01 -3.30103798e+01 -3.31814766e+01 -3.32598419e+01 -3.32005539e+01 -3.30835838e+01 -3.34153481e+01 -3.32253418e+01 -3.37423820e+01 -3.38951874e+01 -3.31147003e+01 -3.32268639e+01 -3.33141861e+01 -3.35294495e+01 -3.36549530e+01 -3.32848015e+01 -3.29846573e+01 -3.31735497e+01 -3.34595947e+01 -3.30928421e+01 -3.21013527e+01 -3.25004158e+01 -3.33533783e+01 -3.29090080e+01 -3.20106583e+01 -3.24351082e+01 -3.24712753e+01 -3.27663307e+01 -3.31756973e+01 -3.28388405e+01 -3.22108688e+01 -3.23607826e+01 -3.38905373e+01 -3.45144691e+01 -3.26987686e+01 -3.21629143e+01 -3.22187462e+01 -3.20663605e+01 -3.17854748e+01 -3.28534889e+01 -3.29133339e+01 -3.26313057e+01 -3.29181137e+01 -3.35016212e+01 -3.23941269e+01 -3.13058090e+01 -2.95097351e+01 -3.22920685e+01 -3.41291237e+01 -3.26636963e+01 -3.29724770e+01 -3.21995087e+01 -3.19360447e+01 -3.16252460e+01 -3.02331657e+01 -2.84766846e+01 -3.01771622e+01 -3.41613007e+01 -3.46598778e+01 -3.11858349e+01 -3.14714565e+01 -3.10172863e+01 -3.10463104e+01 -3.10654736e+01 -3.11614819e+01 -3.11743221e+01 -3.13957367e+01 -3.09335766e+01 -3.04574471e+01 -2.96125374e+01 -2.95604420e+01 -2.95186329e+01 -2.96790981e+01 -2.97902794e+01 -3.01997147e+01 -2.98398170e+01 -2.95295906e+01 -2.97259617e+01 -3.02642784e+01 -3.07407646e+01 -3.04635143e+01 -2.98429298e+01 -2.90912457e+01 -2.91211624e+01 -2.96393871e+01 -2.91538620e+01 -2.89825268e+01 -2.82542191e+01 -2.67246075e+01 -2.47158356e+01 -2.57666798e+01 -2.82945061e+01 -3.13348255e+01 -3.09739342e+01 -2.74378071e+01 -2.74082661e+01 -2.79680347e+01 -2.78775158e+01 -2.74432907e+01 -2.77929478e+01 -2.76846905e+01 -2.79929218e+01 -2.73298397e+01 -2.77541618e+01 -2.74329357e+01 -2.71695633e+01 -2.63348331e+01 -2.62317963e+01 -2.65343971e+01 -2.63091354e+01 -2.62588387e+01 -2.61718464e+01 -2.52620430e+01 -2.46315899e+01 -2.54396038e+01 -2.53574448e+01 -2.60110531e+01 -2.58714447e+01 -2.42819443e+01 -2.43226223e+01 -2.44205246e+01 -2.32674408e+01 -1.21118422e+01 -7.12546682e+00 2.51209297e+01 -4.56901627e+01 -8.04238510e+01 1.15337921e+02 2.14697464e+02 -3.34469681e+01 -3.09103985e+01 -2.87076588e+01 -2.92661667e+01 -2.91545277e+01 -2.57906876e+01 -2.99748478e+01 -2.93877583e+01 -2.48968826e+02 -1.84028946e+02 -3.51120071e+01 -3.16681919e+01 -3.26285286e+01 -3.10797863e+01 -3.08576679e+01 -2.71333218e+01 -2.51755829e+01 -1.88704014e+01 -1.41399857e+02 -1.27183655e+02 -4.51889465e+02 5103758. 1761492736. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.63312250e+05 1.79006458e+03 3.42631197e+00 -4.39401459e+02 -2.59819641e+01 -3.41271210e+01 -2.72256260e+01 -1.86482590e+02 -1.19168861e+02 -2.06879101e+01 -1.74969826e+01 -1.67144775e+01 -1.62240906e+01 -1.58152351e+01 -1.53444910e+01 -1.53897285e+01 -1.53187189e+01 -1.46227312e+01 -1.48092890e+01 -1.52676382e+01 -1.48804970e+01 -1.46254749e+01 -1.43258610e+01 -1.39876490e+01 -1.37458277e+01 -1.37324181e+01 -1.37926073e+01 -1.36726389e+01 -1.35944309e+01 -1.30011539e+01 -1.25415430e+01 -1.22485638e+01 -1.19994736e+01 -1.18039198e+01 -1.20123358e+01 -1.22887926e+01 -1.20533886e+01 -1.17905626e+01 -1.15161171e+01 -1.12607813e+01 -1.08757029e+01 -1.04284115e+01 -1.03869610e+01 -1.04475145e+01 -1.04561052e+01 -1.01990366e+01 -9.87315083e+00 -9.55897808e+00 -9.28066921e+00 -8.95270252e+00 -8.67894363e+00 -8.77421188e+00 -8.73119164e+00 -8.39728832e+00 -8.33554077e+00 -7.66889811e+00 -7.54999399e+00 1.98040752e+01 3.78113594e+01 -8.83159351e+00 -8.45214176e+00 -7.46554136e+00 -6.09336758e+00 -6.50901413e+00 -2.12087097e+01 -3.64481469e+05 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 925190592. 925190592. 0. 0. 959236352. -633417088. 1.46480194e+02 1.87256088e+02 -60026796. 1067954432. 0. 0. 0. 0. 0. 6.39481562e+05 -1.71663483e+02 -1.03577393e+02 -11128080. 2.14339020e+02 -1.88998890e+01 -1.41094532e+01 -2.55037861e+01 -3.26224060e+02 -9022259. -1.87770238e+06 -24245522. -59340668. -2.00184088e+06 -304432768. -149923120. -208280656. -6060239. -35977732. -3.43879125e+06 -2749376. 2.38334732e+02 1.46230860e+01 -7.68729248e+01 -1.04665489e+01 -5.06271820e+02 -7.62163050e+06 209971808. -26514462. -689611712. -388341984. -2.23484656e+05 -2.64305312e+05 -5457362. -53045072. -6.64739375e+04 2566595. -1.73135062e+05 -78739992. 385426400. -12829301. -108533608. 7.52542053e+02 3.13843689e+02 -5.16733110e-01 8.00445735e-01 2.23842621e+00 1.47374634e+02 9.07102814e+01 4.69243145e+00 7.63315010e+00 8.12548923e+00 -7.84711227e+01 -1.47530533e+02 -5.78252649e+00 -1.56272376e+00 -2.47727156e-01 -3.79142548e+02 -9.97466614e+02 -7393042. -239200816. 1430286848. 0. 0. 0. 900671936. 900671936. 900671936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.47125438e+05 -3.90548492e+02 -1.06125473e+02 1.36364164e+01 1.51580105e+01 1.44347792e+01 1.38913164e+01 1.35430489e+01 1.38823528e+01 1.99349461e+01 2.12932358e+01 2.65179119e+01 2.46623745e+01 2.51567116e+01 2.69562950e+01 2.78921223e+01 1.99264412e+01 2.12833805e+01 1.70743675e+01 1.13552961e+01 1.83027172e+01 2.41786251e+01 1.95965881e+01 1.80627403e+01 1.72715816e+01 1.71059513e+01 1.71004124e+01 1.79416409e+01 1.86636410e+01 1.85373516e+01 1.83568134e+01 1.88586426e+01 1.89716492e+01 1.88561649e+01 1.87378826e+01 1.85445557e+01 1.95709476e+01 2.02728004e+01 1.99121189e+01 2.05817547e+01 2.10644569e+01 2.13451881e+01 2.13564453e+01 2.10042305e+01 2.07835960e+01 2.15122280e+01 2.17571716e+01 2.18820343e+01 2.18390503e+01 2.19099979e+01 2.17777424e+01 2.21012688e+01 2.23419647e+01 2.32338524e+01 2.39933586e+01 2.38033943e+01 2.37160225e+01 2.44115334e+01 2.45929985e+01 2.39077930e+01 2.37068176e+01 2.38750858e+01 2.47159595e+01 2.50782814e+01 2.47469711e+01 2.50722504e+01 2.50817528e+01 2.53091526e+01 2.55928860e+01 2.57816086e+01 2.61441536e+01 2.62518692e+01 2.66804771e+01 2.68071442e+01 2.65111065e+01 2.65814838e+01 2.65449123e+01 2.75482635e+01 2.83284607e+01 2.86714287e+01 2.83847599e+01 2.78967342e+01 2.84269733e+01 2.86396599e+01 2.85784016e+01 2.85203133e+01 2.78438358e+01 2.86016808e+01 2.89125519e+01 2.87034302e+01 2.85799332e+01 2.89554977e+01 3.01765785e+01 2.93384991e+01 2.94764252e+01 2.94322433e+01 2.98228168e+01 3.00582409e+01 3.00094872e+01 3.05948811e+01 3.00409946e+01 3.00615978e+01 2.98479691e+01 2.66451569e+01 2.71873894e+01 3.37168274e+01 3.47887688e+01 3.22500458e+01 3.10370045e+01 3.10160217e+01 3.15942688e+01 3.19040413e+01 3.16780300e+01 3.12839642e+01 3.20939445e+01 3.25541496e+01 3.30479584e+01 3.25342674e+01 3.26328926e+01 3.27937393e+01 3.26890678e+01 3.27185287e+01 3.26473389e+01 3.29623375e+01 3.31712379e+01 3.28891869e+01 3.29979439e+01 3.37493439e+01 3.39659729e+01 3.41086159e+01 3.41127930e+01 3.40904541e+01 3.39621658e+01 3.39941864e+01 3.43651161e+01 3.44493752e+01 3.44215050e+01 3.30863152e+01 3.46995277e+01 3.63794937e+01 3.45858841e+01 3.46546669e+01 3.50607033e+01 3.54197769e+01 3.52957458e+01 3.53841629e+01 3.54507446e+01 3.54392662e+01 3.52819786e+01 3.47722588e+01 3.50689583e+01 3.55192375e+01 3.57032585e+01 3.56624260e+01 3.56571007e+01 3.59948425e+01 3.60784874e+01 3.60228691e+01 3.63041344e+01 3.62741318e+01 3.58414688e+01 3.60053825e+01 3.60929451e+01 3.62140274e+01 3.65948944e+01 3.66554832e+01 3.67123871e+01 3.61844864e+01 3.59190979e+01 3.63365631e+01 3.62966919e+01 3.65601959e+01 3.65339088e+01 3.61335754e+01 3.64533501e+01 3.64655685e+01 3.55486298e+01 3.27239380e+01 2.81328735e+01 3.78780251e+01 4.12026482e+01 3.67029343e+01 3.64245796e+01 3.42706032e+01 3.49634743e+01 1.87107620e+01 5.48177261e+01 6.25949783e+01 4.13874283e+01 4.44489632e+01 2.72258362e+02 4.36578247e+02 6.85969009e+01 6.88546066e+01 6.89934998e+01 -7.75778442e+02 -2.05465454e+03 2.37255933e+03 9.63846741e+02 4.75575790e+01 1.00438942e+02 7.73241425e+01 7.91872177e+01 7.50349121e+01 6.46203842e+01 6.49879837e+01 6.51135483e+01 6.53932495e+01 -3.19198212e+02 5.70571060e+01 4.22980255e+02 6.39907150e+01 -3.15087616e+02 -1.59792679e+02 4.40687561e+01 3.82990341e+01 3.72495956e+01 3.72659912e+01 3.67077637e+01 3.67253227e+01 3.65871506e+01 3.69327431e+01 3.65688591e+01 3.68190804e+01 3.69375954e+01 3.71466026e+01 3.62869186e+01 3.61562233e+01 3.65597343e+01 3.63912430e+01 3.61105003e+01 3.58259315e+01 3.51281090e+01 3.56541138e+01 3.66359291e+01 3.61110764e+01 3.64240952e+01 3.66818924e+01 3.63914413e+01 3.63473930e+01 3.55147705e+01 3.57268257e+01 3.55571480e+01 3.56888504e+01 3.53968391e+01 3.62639580e+01 3.64665451e+01 3.56302757e+01 3.51720009e+01 3.49145164e+01 3.48588676e+01 3.49931984e+01 3.51392021e+01 3.52667542e+01 3.50001717e+01 3.46324310e+01 3.46472359e+01 3.46208572e+01 3.44273643e+01 3.46154594e+01 3.53660164e+01 3.48720932e+01 3.43744621e+01 3.43208961e+01 3.51963692e+01 3.51451302e+01 3.46241608e+01 3.44134445e+01 3.41326561e+01 3.38127823e+01 3.32807541e+01 3.28898544e+01 3.30287514e+01 3.28181305e+01 3.33270836e+01 3.37023773e+01 3.37360001e+01 3.32821693e+01 3.30816345e+01 3.26849480e+01 3.25608864e+01 3.24086952e+01 3.17960892e+01 3.26868362e+01 3.25080605e+01 3.23176270e+01 3.14171791e+01 3.21657829e+01 3.13883324e+01 3.16953964e+01 3.14064770e+01 3.16177521e+01 3.14865932e+01 3.14864407e+01 3.15331497e+01 3.14632835e+01 3.12561512e+01 3.09525185e+01 3.00746727e+01 2.92248497e+01 2.91166801e+01 3.02503548e+01 3.01994991e+01 2.97719135e+01 2.87562904e+01 2.94813156e+01 3.02720203e+01 2.95439262e+01 2.91884155e+01 2.91161556e+01 2.90177078e+01 2.90131378e+01 2.89477425e+01 2.88112316e+01 2.87467442e+01 2.82865257e+01 2.79681644e+01 2.77124424e+01 2.77775078e+01 2.81859035e+01 2.79613819e+01 2.76081715e+01 2.71969967e+01 2.74301434e+01 2.71300945e+01 2.60956364e+01 2.56198101e+01 2.69146461e+01 2.66517410e+01 2.53350220e+01 2.49209023e+01 2.51510906e+01 2.54497433e+01 2.59852276e+01 2.57505875e+01 2.51837769e+01 2.54447765e+01 2.50623150e+01 2.48600769e+01 2.47359066e+01 2.45528679e+01 2.41722145e+01 2.37701130e+01 2.35890083e+01 2.32192669e+01 2.32391415e+01 2.33878746e+01 2.30991764e+01 2.29918194e+01 2.26761379e+01 2.26716576e+01 2.24212151e+01 2.21018791e+01 2.20858078e+01 2.17860794e+01 2.16596146e+01 2.11328182e+01 2.09116020e+01 2.07402058e+01 2.06698532e+01 2.06440086e+01 2.05574379e+01 2.01214600e+01 1.99119282e+01 1.97952843e+01 1.96411381e+01 1.95564137e+01 1.93035526e+01 1.92886353e+01 1.90345802e+01 1.88375721e+01 1.87821064e+01 1.86392365e+01 1.82466679e+01 1.81147308e+01 1.79053078e+01 1.76002712e+01 1.73299370e+01 1.72093220e+01 1.71310081e+01 1.67323437e+01 1.66111794e+01 1.64196987e+01 1.62406750e+01 1.60458145e+01 1.56962395e+01 1.54622145e+01 1.54271708e+01 1.53532295e+01 1.51511803e+01 1.48524170e+01 1.45989790e+01 1.42897921e+01 1.40988960e+01 1.40306187e+01 1.38130713e+01 1.34990549e+01 1.31955853e+01 1.29483509e+01 1.29205713e+01 1.27863474e+01 1.24098263e+01 1.21332121e+01 1.19803162e+01 1.17532692e+01 1.15861130e+01 1.13834429e+01 1.10529366e+01 1.08288326e+01 1.06648788e+01 1.04439459e+01 1.02190866e+01 9.91422081e+00 9.69292927e+00 9.53905106e+00 9.37126160e+00 9.15166950e+00 8.87988091e+00 8.66237068e+00 8.44822788e+00 8.22325802e+00 7.99883699e+00 7.77497530e+00 7.54817009e+00 7.31701851e+00 7.09189367e+00 6.85569191e+00 6.62452173e+00 6.40890265e+00 6.19977379e+00 5.94701242e+00 5.72569323e+00 5.51321507e+00 5.22822428e+00 4.99933910e+00 4.78241682e+00 4.55026817e+00 4.34967375e+00 4.12676239e+00 3.97846723e+00 3.76557922e+00 3.40191650e+00 3.16326332e+00 3.04000139e+00 2.77718759e+00 2.50149465e+00 2.35768032e+00 2.17103148e+00 1.87189484e+00 1.66499650e+00 1.23604453e+00 1.16359258e+00 1.08212447e+00 6.85714245e-01 5.33709884e-01 2.52680808e-01 3.65386084e-02 -2.25514874e-01 -5.31650066e-01 -9.36568618e-01 -1.03259802e+00 -1.08870959e+00 -1.36049640e+00 -1.70370674e+00 -1.87307823e+00 -2.00682735e+00 -2.10777116e+00 -2.42077947e+00 -2.66700125e+00 -3.02086234e+00 -3.16187716e+00 -3.48468924e+00 -3.67922020e+00 -3.91088963e+00 -4.07491541e+00 -4.34011650e+00 -4.46643162e+00 -4.63734627e+00 -4.89150667e+00 -5.31612015e+00 -5.57658052e+00 -5.69417429e+00 -5.62170839e+00 -5.90683222e+00 -6.48416853e+00 -6.76928282e+00 -6.53684187e+00 -6.83959818e+00 -7.27793980e+00 -7.63757992e+00 -7.90400505e+00 -8.13862419e+00 -8.28957081e+00 -8.83143139e+00 -9.08252907e+00 -8.36983013e+00 -8.18821621e+00 -8.71670914e+00 -9.29071522e+00 -9.89320850e+00 -9.63252163e+00 -9.68421555e+00 -1.02198591e+01 -1.05850735e+01 -1.08008671e+01 -1.05890150e+01 -1.08797312e+01 -1.13343735e+01 -1.11959743e+01 -1.16338425e+01 -1.21230078e+01 -1.20290661e+01 -1.22098007e+01 -1.25722256e+01 -1.29862995e+01 -1.32800732e+01 -1.33511314e+01 -1.40301695e+01 -1.40578938e+01 -1.37640963e+01 -1.39047127e+01 -1.43559151e+01 -1.47016935e+01 -1.52516603e+01 -1.55805225e+01 -1.48937168e+01 -1.50132008e+01 -1.52289085e+01 -1.53981180e+01 -1.53521948e+01 -1.64013882e+01 -1.66789036e+01 -1.70547791e+01 -1.71823654e+01 -1.69286079e+01 -1.71485748e+01 -1.72893906e+01 -1.77413158e+01 -1.79309902e+01 -1.82004986e+01 -1.79578686e+01 -1.84065762e+01 -1.78672142e+01 -1.87441483e+01 -1.87183170e+01 -1.85822010e+01 -1.87901821e+01 -2.05067348e+01 -2.08005314e+01 -2.04998932e+01 -2.05304794e+01 -2.10761414e+01 -2.10484810e+01 -2.11773415e+01 -2.04916039e+01 -1.99176579e+01 -2.01847897e+01 -2.16166420e+01 -2.15854988e+01 -2.15408821e+01 -2.15564671e+01 -2.18121243e+01 -2.19774017e+01 -2.24574661e+01 -2.22028103e+01 -2.22561512e+01 -2.26726036e+01 -2.34186802e+01 -2.35571346e+01 -2.41092339e+01 -2.43135509e+01 -2.40019951e+01 -2.31568222e+01 -2.37812443e+01 -2.42493038e+01 -2.51644783e+01 -2.51169205e+01 -2.51579685e+01 -2.51326103e+01 -2.57414284e+01 -2.60096474e+01 -2.57780952e+01 -2.56485310e+01 -2.54063568e+01 -2.53215599e+01 -2.55586853e+01 -2.61691360e+01 -2.66402760e+01 -2.64453659e+01 -2.69136391e+01 -2.75126591e+01 -2.79453144e+01 -2.86916656e+01 -2.80282917e+01 -2.85590820e+01 -2.87422943e+01 -2.85075073e+01 -2.81219482e+01 -2.74065361e+01 -2.81306553e+01 -2.82030258e+01 -2.78351078e+01 -2.83982105e+01 -2.89635468e+01 -2.94216671e+01 -2.98496819e+01 -3.04797001e+01 -3.01560268e+01 -2.91564713e+01 -2.99871540e+01 -3.05966702e+01 -2.97268867e+01 -2.91618347e+01 -3.03694363e+01 -3.11542416e+01 -3.12755680e+01 -3.12136993e+01 -3.13395004e+01 -3.10789928e+01 -3.05840034e+01 -3.09017124e+01 -3.14129105e+01 -3.15775280e+01 -3.14197655e+01 -3.13967361e+01 -3.14244804e+01 -3.21880493e+01 -3.27311287e+01 -3.26736412e+01 -3.19783382e+01 -3.05148544e+01 -2.95001183e+01 -3.13672180e+01 -3.02091045e+01 -3.04544563e+01 -3.39645119e+01 -3.44061317e+01 -3.39363251e+01 -3.21676369e+01 -2.60406952e+02 -4.22027649e+02 -3.88915100e+01 -3.54815521e+01 -3.66327782e+01 -3.58860779e+01 -1.50822315e+01 -5.09450493e+01 -6.94753113e+01 -3.75272789e+01 -4.79963074e+01 3.36537598e+02 -5.19942894e+01 -4.57096176e+01 1.73028976e+02 -2.00628395e+01 -1.30040312e+01 -6.14640236e+01 -5.92097778e+01 -3.76937675e+01 -3.70691605e+01 -3.64750023e+01 -3.94264374e+01 -2.88769321e+01 -1.38078098e+01 -4.08118324e+01 -5.60748024e+01 -4.16094704e+01 -3.93307648e+01 -3.68160362e+01 -3.61798210e+01 -3.58860779e+01 -3.59980354e+01 -3.61029053e+01 -3.60366516e+01 -3.61984253e+01 -3.63779869e+01 -3.66825256e+01 -3.65517044e+01 -3.58358727e+01 -3.54905052e+01 -3.58339996e+01 -3.65867538e+01 -3.66064987e+01 -3.63358345e+01 -3.63582039e+01 -3.67753181e+01 -3.70104218e+01 -3.67358513e+01 -3.66904526e+01 -3.68239899e+01 -3.68457146e+01 -3.71350517e+01 -3.73320160e+01 -3.68636818e+01 -3.67415237e+01 -3.70207558e+01 -3.79378700e+01 -3.78290367e+01 -3.79761734e+01 -3.75874329e+01 -3.72904472e+01 -3.74618797e+01 -3.73483467e+01 -3.71969528e+01 -3.74863396e+01 -3.70959244e+01 -3.72691879e+01 -3.76083717e+01 -3.76037865e+01 -3.73706207e+01 -3.64589539e+01 -3.66032906e+01 -3.75155411e+01 -3.70950241e+01 -3.69920082e+01 -3.73816185e+01 -3.74134865e+01 -3.71344948e+01 -3.73035927e+01 -3.73361931e+01 -3.62337685e+01 -3.63418922e+01 -3.78586235e+01 -3.79485512e+01 -3.65031128e+01 -3.72550926e+01 -3.79071808e+01 -3.70625153e+01 -3.63900871e+01 -3.72552872e+01 -3.72452354e+01 -3.64566879e+01 -3.65983238e+01 -3.74302406e+01 -3.69604301e+01 -3.61725044e+01 -3.41644707e+01 -3.82072601e+01 -3.96725960e+01 -3.65603561e+01 -3.63544655e+01 -3.63034897e+01 -3.63201447e+01 -3.63005219e+01 -3.42594223e+01 -3.27129135e+01 -3.48193398e+01 -4.01097565e+01 -4.02604561e+01 -3.69949226e+01 -3.66591721e+01 -3.59001045e+01 -3.49135971e+01 -3.52581024e+01 -3.52277985e+01 -3.52063408e+01 -3.51752625e+01 -3.57538834e+01 -3.61949844e+01 -3.59299126e+01 -3.49655037e+01 -3.44076462e+01 -3.42373085e+01 -3.44980278e+01 -3.50380898e+01 -3.47083244e+01 -3.41336098e+01 -3.43723412e+01 -3.50245094e+01 -3.49501152e+01 -3.50099487e+01 -3.43893089e+01 -3.38969765e+01 -3.41887894e+01 -3.45453758e+01 -3.43885994e+01 -3.46232758e+01 -3.48916702e+01 -3.36758842e+01 -3.03430405e+01 -3.15227375e+01 -3.49358864e+01 -3.71945267e+01 -3.58805618e+01 -3.31290131e+01 -3.29785461e+01 -3.34714470e+01 -3.33354416e+01 -3.33835411e+01 -3.30681038e+01 -3.29922333e+01 -3.28593750e+01 -3.26459084e+01 -3.23440552e+01 -3.18299236e+01 -3.24206429e+01 -3.19543056e+01 -3.19731579e+01 -3.12522678e+01 -3.20118484e+01 -3.14791126e+01 -3.17397327e+01 -3.13647137e+01 -3.11386051e+01 -3.11129322e+01 -3.11391182e+01 -3.11862545e+01 -3.13739414e+01 -3.09001446e+01 -3.02359219e+01 -2.91540203e+01 -2.71161022e+01 -1.63080006e+01 -1.37055588e+01 5.73133039e+00 -4.58261948e+01 -7.44590149e+01 -3.54500809e+01 -3.64386787e+01 -4.14989433e+01 -4.10885963e+01 -4.03808136e+01 -3.99423599e+01 -3.95304832e+01 -3.83456726e+01 -3.97206497e+01 -3.90832939e+01 -2.33816071e+01 -1.78960251e+02 -2.65930267e+02 -6.14863548e+01 -6.74243164e+01 -6.26135826e+01 -6.37824593e+01 1.69945007e+02 8.99418335e+01 -2.42288666e+01 -1.89916286e+01 -3.07808399e+01 -1.34733582e+02 -4.14251862e+02 -1.58748853e+03 -204983264. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -241726160. -241726160. -75617416. -113941664. -3.84233945e+04 -7.21223125e+05 966734528. -1.13379578e+03 -4.85968933e+02 -6.82629852e+01 -4.93319054e+01 -4.58989639e+01 -4.35877151e+01 -1.81913284e+02 -1.13101929e+02 -2.15345345e+01 -2.22510796e+01 -2.06807728e+01 -2.04684639e+01 -1.98521843e+01 5.42768974e+01 1.04918625e+02 -3.94105301e+01 -3.88174782e+01 -3.81596222e+01 -3.94005089e+01 -4.06966782e+01 -4.12843552e+01 -4.05433693e+01 -3.87614136e+01 -3.65107765e+01 -3.55619125e+01 -3.51415939e+01 -3.45849380e+01 -3.68179436e+01 -3.94100761e+01 -3.90247650e+01 -3.75541267e+01 -1.18154457e+02 -2.40379295e+01 6.64123840e+01 -3.32817001e+01 -3.38381577e+01 -3.51200943e+01 -3.58481560e+01 -3.49131889e+01 -3.37526398e+01 -3.26948128e+01 -3.19659119e+01 -3.17098904e+01 -3.10044060e+01 -3.23702583e+01 -3.28209152e+01 -3.17861805e+01 -3.24410439e+01 -2.91316166e+01 -2.93714561e+01 7.76713333e+01 2.21939133e+02 -157344304. -568543936. -8861726. -1.80331962e+06 -1.12493912e+06 336935776. 58122560. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 925190592. 925190592. 0. 0. 0. 0. -1466635776. -60026796. -60026796. 1067954432. 0. 53502272. 90715280. 295344000. -572696704. -16985452. -1228782848. -1228782848. 0. -1203652096. -1203652096. -62323532. 714537216. 714537216. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70341464. -70341464. -10072857. 411714016. 411714016. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70665224. -70665224. -70665224. 0. 0. -205965712. -5.80657288e+02 -6.65602478e+02 -6.99031830e+00 1.75483322e+02 9.14113998e+00 3.70619512e+00 1.78666580e+00 -9.89564121e-01 -8.16190948e+01 -1.46559097e+02 -3.68661407e+02 -9.54258911e+02 -10850295. -2.55366250e+06 -8.07003150e+06 75077776. 325799392. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -227256832. -26704650. -2.22729675e+06 -5.83973877e+02 -1.83644958e+02 6.44443846e+00 7.40738010e+00 7.88725328e+00 7.58552170e+00 7.39152145e+00 7.54716825e+00 8.17973042e+00 1.36310287e+02 2.23043869e+02 -1.84495544e+01 -2.62709484e+01 -2.48006248e+01 -2.16477318e+01 -1.99345818e+01 -2.22683945e+02 -1.21895210e+02 9.92907524e+00 5.41948795e+00 1.15707970e+01 1.69205685e+01 1.32060547e+01 1.16474934e+01 1.07307968e+01 1.06272812e+01 1.06839218e+01 1.14621773e+01 1.18430958e+01 1.14930429e+01 1.16975632e+01 1.19995937e+01 1.20188541e+01 1.24323683e+01 1.22139502e+01 1.16460571e+01 1.29488163e+01 1.35365705e+01 1.25793476e+01 1.32030716e+01 1.41434116e+01 1.48436155e+01 1.47754059e+01 1.43881254e+01 1.46072512e+01 1.47262506e+01 1.55554848e+01 1.52109737e+01 1.51792660e+01 1.54434872e+01 1.51991835e+01 1.53976250e+01 1.48898277e+01 1.56030502e+01 1.67676010e+01 1.69873714e+01 1.71657391e+01 1.76543140e+01 1.71016998e+01 1.62597485e+01 1.66986504e+01 1.72455902e+01 1.79350510e+01 1.76944275e+01 1.74733009e+01 1.74744320e+01 1.79974709e+01 1.88442955e+01 1.90771732e+01 1.95905190e+01 1.97284832e+01 1.95274677e+01 1.96246319e+01 1.95185375e+01 1.96370869e+01 1.99293156e+01 2.01561317e+01 2.02777348e+01 2.06709423e+01 2.14519577e+01 2.06138020e+01 2.09662380e+01 2.05658913e+01 2.08105640e+01 2.10904808e+01 2.14972229e+01 2.15196114e+01 2.21134758e+01 2.24362164e+01 2.21330070e+01 2.17504654e+01 2.26984310e+01 2.33572483e+01 2.23719349e+01 2.25653725e+01 2.30492649e+01 2.37381172e+01 2.34062176e+01 2.31785603e+01 2.35612392e+01 2.44694366e+01 2.43893356e+01 2.40340347e+01 1.94828796e+01 1.97470970e+01 2.51755733e+01 2.81088009e+01 2.67313309e+01 2.46408501e+01 2.43351326e+01 2.49727535e+01 2.57793980e+01 2.59053612e+01 2.56660118e+01 2.52754650e+01 2.55220909e+01 2.58140965e+01 2.57386036e+01 2.57969837e+01 2.59187717e+01 2.61373463e+01 2.62955265e+01 2.64378490e+01 2.64288235e+01 2.66531200e+01 2.64210377e+01 2.65963039e+01 2.69945755e+01 2.75464249e+01 2.78459988e+01 2.77016907e+01 2.77118549e+01 2.75597343e+01 2.77630463e+01 2.80135841e+01 2.80567322e+01 2.82141495e+01 2.65047226e+01 2.83624039e+01 3.03107014e+01 2.86069221e+01 2.85838547e+01 2.89699001e+01 2.90204105e+01 2.89050236e+01 2.88456879e+01 2.91340446e+01 2.94123707e+01 2.93211441e+01 2.91561127e+01 2.94620628e+01 2.96730843e+01 3.00738716e+01 2.99941368e+01 2.98885555e+01 3.02352753e+01 3.03028450e+01 3.03145447e+01 3.05867329e+01 3.05066833e+01 3.05081520e+01 3.07671337e+01 3.08017616e+01 3.05904179e+01 3.07892990e+01 3.10017414e+01 3.12004261e+01 3.09040890e+01 3.08007145e+01 3.10302238e+01 3.10160637e+01 3.11760082e+01 3.12434196e+01 3.13924141e+01 3.15753288e+01 3.16025410e+01 3.12513313e+01 2.84148865e+01 2.40337849e+01 3.33827591e+01 3.63540039e+01 3.34711800e+01 3.53050728e+01 2.92732391e+01 2.48914581e+02 3.69391907e+02 -3.08688782e+02 -1.62190567e+02 3.07158031e+01 3.80644455e+01 3.17130547e+01 2.57572784e+01 2.63134766e+01 4.56737671e+01 4.71246986e+01 3.80213127e+01 3.73066139e+01 3.92990036e+01 3.14566154e+01 3.05558796e+01 3.85332527e+01 3.54264259e+01 3.57890358e+01 3.38567848e+01 -1.75125259e+02 -3.23871704e+02 6.51135483e+01 6.53932495e+01 4.21133850e+02 2.59519043e+02 3.47048149e+01 4.24645538e+01 3.82312164e+01 3.59786072e+01 3.48918457e+01 3.37226868e+01 3.38073158e+01 3.35983658e+01 3.32074928e+01 3.25780182e+01 3.29050255e+01 3.30746613e+01 3.29765930e+01 3.28045883e+01 3.29371948e+01 3.30602150e+01 3.25207596e+01 3.23912926e+01 3.24156914e+01 3.26055031e+01 3.21170235e+01 3.26246796e+01 3.23965645e+01 3.33967781e+01 3.41555138e+01 3.28543587e+01 3.29799042e+01 3.31695824e+01 3.27336731e+01 3.28751717e+01 3.24437408e+01 3.25505905e+01 3.28566246e+01 3.32623215e+01 3.27891502e+01 3.36717720e+01 3.36973457e+01 3.31343307e+01 3.29393349e+01 3.31902847e+01 3.28364830e+01 3.30772858e+01 3.31400757e+01 3.33508873e+01 3.31054955e+01 3.25289497e+01 3.24986229e+01 3.24564018e+01 3.17500916e+01 3.14062939e+01 3.17351913e+01 3.20402145e+01 3.16492462e+01 3.20663757e+01 3.34226990e+01 3.37679062e+01 3.31864891e+01 3.23013115e+01 3.25925026e+01 3.32348137e+01 3.28419266e+01 3.26150131e+01 3.24159317e+01 3.26938629e+01 3.18670063e+01 3.22783928e+01 3.19529133e+01 3.17724228e+01 3.21089020e+01 3.17766895e+01 3.18461514e+01 3.11065121e+01 3.05771828e+01 3.10300579e+01 3.14385071e+01 3.15466232e+01 3.14676704e+01 3.13968182e+01 3.11128674e+01 3.08157482e+01 3.07555332e+01 3.10539780e+01 3.12646141e+01 3.06101780e+01 3.02856407e+01 3.04112606e+01 3.05825539e+01 3.05701599e+01 3.02471924e+01 2.95073166e+01 2.92915955e+01 2.98032074e+01 3.02740536e+01 2.98691673e+01 2.87050114e+01 2.93182945e+01 3.02332134e+01 3.00672398e+01 2.92098675e+01 2.92308025e+01 2.90995064e+01 2.92884064e+01 2.97005043e+01 2.93525085e+01 2.89424725e+01 2.84654617e+01 2.83397503e+01 2.82645588e+01 2.86064968e+01 2.83314018e+01 2.85654583e+01 2.77489605e+01 2.74607315e+01 2.76675072e+01 2.79576874e+01 2.77455482e+01 2.67944832e+01 2.80180454e+01 2.78418694e+01 2.62856255e+01 2.60550556e+01 2.63067455e+01 2.66981106e+01 2.71857090e+01 2.69788971e+01 2.64170399e+01 2.59974403e+01 2.59999657e+01 2.54412937e+01 2.53180428e+01 2.54892178e+01 2.54943066e+01 2.55163441e+01 2.54526234e+01 2.50444145e+01 2.50885105e+01 2.51044903e+01 2.49533787e+01 2.45124912e+01 2.41587944e+01 2.43929043e+01 2.42808762e+01 2.41993256e+01 2.39938164e+01 2.38252430e+01 2.35987282e+01 2.34918365e+01 2.34396343e+01 2.33270454e+01 2.28756752e+01 2.27851868e+01 2.24452324e+01 2.22544003e+01 2.19440880e+01 2.18874874e+01 2.21465950e+01 2.19586792e+01 2.18769741e+01 2.21141624e+01 2.19102306e+01 2.13900051e+01 2.12463837e+01 2.11133614e+01 2.08303833e+01 2.05685234e+01 2.03726883e+01 2.03255444e+01 2.00264301e+01 2.00053768e+01 2.00281620e+01 1.98135509e+01 1.97325497e+01 1.95226536e+01 1.90502987e+01 1.90282364e+01 1.90192795e+01 1.87775211e+01 1.88360596e+01 1.85965977e+01 1.83462105e+01 1.82301025e+01 1.81045609e+01 1.78224506e+01 1.75994415e+01 1.75680389e+01 1.72264996e+01 1.70512161e+01 1.68376369e+01 1.66220951e+01 1.66284904e+01 1.65228367e+01 1.61288548e+01 1.58730745e+01 1.58244362e+01 1.57010450e+01 1.54040766e+01 1.52539244e+01 1.50820580e+01 1.49006701e+01 1.47178135e+01 1.45269995e+01 1.43655767e+01 1.40880957e+01 1.38694525e+01 1.37275743e+01 1.36045370e+01 1.34284430e+01 1.31904097e+01 1.30096598e+01 1.28260403e+01 1.26332579e+01 1.24403410e+01 1.22236967e+01 1.20058470e+01 1.17971087e+01 1.16063080e+01 1.14111338e+01 1.12117538e+01 1.10284958e+01 1.08778086e+01 1.06904125e+01 1.04918156e+01 1.03265219e+01 1.00580006e+01 9.85554600e+00 9.69318676e+00 9.43827438e+00 9.26106167e+00 9.13046265e+00 9.05056286e+00 8.84375381e+00 8.46467495e+00 8.29689026e+00 8.22022629e+00 7.97564363e+00 7.70236158e+00 7.55596304e+00 7.42089939e+00 7.18524790e+00 6.99408102e+00 6.62247133e+00 6.56826162e+00 6.51649046e+00 5.96788311e+00 5.83754730e+00 5.77359009e+00 5.53991318e+00 5.42143488e+00 5.14561558e+00 4.79648161e+00 4.60510445e+00 4.63179398e+00 4.39751816e+00 4.13560247e+00 3.85946321e+00 3.74422884e+00 3.71869731e+00 3.51887560e+00 3.13632154e+00 2.83411956e+00 2.59307075e+00 2.44072413e+00 2.28460622e+00 2.20930362e+00 2.07482934e+00 1.72777319e+00 1.60901177e+00 1.40782332e+00 1.19433486e+00 9.35638368e-01 1.03232110e+00 7.60445833e-01 3.31168324e-01 2.40065694e-01 1.95481889e-02 -4.70559329e-01 -1.26131386e-01 -2.53637344e-01 -7.14982212e-01 -1.23279440e+00 -1.63833272e+00 -1.81326532e+00 -1.78324687e+00 -1.98859489e+00 -2.15152216e+00 -2.18633842e+00 -2.02945209e+00 -2.34734058e+00 -2.87712216e+00 -3.19428730e+00 -3.10595822e+00 -3.39546490e+00 -3.75344396e+00 -4.14364719e+00 -4.20302582e+00 -4.32761860e+00 -4.60655975e+00 -4.86286020e+00 -4.88606501e+00 -5.29782772e+00 -5.78426313e+00 -5.62323713e+00 -5.61949539e+00 -6.19919300e+00 -6.07032585e+00 -5.69443703e+00 -5.84424353e+00 -6.56632137e+00 -6.66092682e+00 -6.77759886e+00 -7.38841820e+00 -7.91490650e+00 -8.03687191e+00 -8.00993252e+00 -8.89504051e+00 -9.15639400e+00 -9.09666538e+00 -9.21983242e+00 -9.21413422e+00 -9.53664970e+00 -9.14121056e+00 -9.49191189e+00 -9.82127666e+00 -1.04045467e+01 -1.03393393e+01 -1.04246302e+01 -1.05921354e+01 -1.08415470e+01 -1.15870533e+01 -1.12295027e+01 -1.08194742e+01 -1.12508144e+01 -1.15920162e+01 -1.22065029e+01 -1.21130543e+01 -1.16149464e+01 -1.22443151e+01 -1.36526155e+01 -1.35572357e+01 -1.32122040e+01 -1.34163923e+01 -1.36367874e+01 -1.42293224e+01 -1.45680723e+01 -1.41009674e+01 -1.33385067e+01 -1.34010344e+01 -1.47010345e+01 -1.52130318e+01 -1.45780439e+01 -1.50880537e+01 -1.53340816e+01 -1.53085079e+01 -1.62741241e+01 -1.56761847e+01 -1.58257475e+01 -1.58599443e+01 -1.63623943e+01 -1.73820248e+01 -1.69600716e+01 -1.68683510e+01 -1.62965889e+01 -1.64375229e+01 -1.69189911e+01 -1.80606670e+01 -1.82060356e+01 -1.86678829e+01 -1.80118103e+01 -1.79480419e+01 -1.88779945e+01 -1.94827995e+01 -2.01135921e+01 -1.98783321e+01 -1.99271088e+01 -1.96391125e+01 -1.91051750e+01 -1.96328373e+01 -2.03583622e+01 -2.05795269e+01 -2.08550549e+01 -2.05813007e+01 -2.08583908e+01 -2.04452515e+01 -2.09138889e+01 -2.02775402e+01 -2.07441807e+01 -2.11709328e+01 -2.17287407e+01 -2.16918964e+01 -2.20647659e+01 -2.20277901e+01 -2.19834309e+01 -2.22925358e+01 -2.27055721e+01 -2.23276176e+01 -2.24106598e+01 -2.31231689e+01 -2.29486237e+01 -2.25528793e+01 -2.35063572e+01 -2.42068233e+01 -2.28313866e+01 -2.32035198e+01 -2.46528549e+01 -2.48956203e+01 -2.42021122e+01 -2.41332684e+01 -2.39002457e+01 -2.42065105e+01 -2.40410786e+01 -2.45913429e+01 -2.48227501e+01 -2.49377136e+01 -2.53278561e+01 -2.52186260e+01 -2.47715950e+01 -2.47689896e+01 -2.49784203e+01 -2.55577354e+01 -2.57495537e+01 -2.49544811e+01 -2.50289955e+01 -2.55181923e+01 -2.51653156e+01 -2.32813663e+01 -1.93785305e+01 -2.92657566e+01 -3.38061752e+01 -2.61494598e+01 -2.65878944e+01 -2.72519493e+01 -2.69181347e+01 -2.63071480e+01 -2.63430290e+01 -2.61178055e+01 -2.27651119e+01 -2.24151592e+01 -3.19226074e+01 1.86300629e+02 -2.79688892e+01 -2.65803436e+02 -2.96199684e+01 -3.04325771e+01 -2.96081886e+01 -4.74122810e+00 -6.44202662e+00 -5.10723572e+01 -5.15653305e+01 -3.17399635e+01 -3.19542885e+01 -3.10070019e+01 -3.16538219e+01 -2.15859299e+01 -9.42442989e+00 -3.60405083e+01 -4.88939667e+01 -3.35126762e+01 -3.21960297e+01 -3.07077522e+01 -3.07371597e+01 -3.04905014e+01 -3.03754711e+01 -3.04522800e+01 -3.04501438e+01 -3.05971546e+01 -3.07053909e+01 -3.09531498e+01 -3.06952896e+01 -3.05737038e+01 -3.05052319e+01 -3.06354008e+01 -3.13329697e+01 -3.12963257e+01 -3.12059650e+01 -3.11430931e+01 -3.14365387e+01 -3.16874466e+01 -3.15826321e+01 -3.15161018e+01 -3.14915905e+01 -3.16401825e+01 -3.21471786e+01 -3.21125679e+01 -3.20394592e+01 -3.17090015e+01 -3.20262718e+01 -3.27675743e+01 -3.29152870e+01 -3.28111534e+01 -3.23062630e+01 -3.23980103e+01 -3.26169662e+01 -3.27432213e+01 -3.26637039e+01 -3.26357040e+01 -3.28072548e+01 -3.27328911e+01 -3.28843765e+01 -3.30289268e+01 -3.32520828e+01 -3.30287399e+01 -3.29097900e+01 -3.34085159e+01 -3.30853348e+01 -3.30806961e+01 -3.29435463e+01 -3.32369194e+01 -3.30238419e+01 -3.26749229e+01 -3.21403770e+01 -3.13423901e+01 -3.26793137e+01 -3.46743126e+01 -3.34890442e+01 -3.25883522e+01 -3.27304306e+01 -3.32406845e+01 -3.30810356e+01 -3.28763733e+01 -3.32174339e+01 -3.32647095e+01 -3.27862930e+01 -3.28956070e+01 -3.31624336e+01 -3.30049629e+01 -3.18601933e+01 -3.11263599e+01 -3.47592239e+01 -3.53643532e+01 -3.29713135e+01 -3.24324303e+01 -3.22625504e+01 -3.23360519e+01 -3.30963478e+01 -3.18637848e+01 -3.04554920e+01 -3.20928802e+01 -3.69807663e+01 -3.67680664e+01 -3.34750824e+01 -3.26883240e+01 -3.24978294e+01 -3.24597435e+01 -3.25214996e+01 -3.26613045e+01 -3.26796150e+01 -3.26790848e+01 -3.31641655e+01 -3.34327126e+01 -3.35923119e+01 -3.31015930e+01 -3.29909019e+01 -3.22867508e+01 -3.26898003e+01 -3.32751160e+01 -3.32137833e+01 -3.25994186e+01 -3.24026489e+01 -3.27321930e+01 -3.27398376e+01 -3.25326118e+01 -3.15617409e+01 -3.08197041e+01 -3.13380375e+01 -3.19948425e+01 -3.24095459e+01 -3.28642921e+01 -3.32473946e+01 -3.31925049e+01 -2.82477131e+01 -2.88216972e+01 -3.45076561e+01 -3.66979599e+01 -3.54419403e+01 -3.25326576e+01 -3.29637947e+01 -3.19517746e+01 -3.18494511e+01 -3.13920498e+01 -3.17221584e+01 -3.20117874e+01 -3.17712040e+01 -3.15338669e+01 -3.09019470e+01 -3.10919304e+01 -3.11504841e+01 -3.07669411e+01 -3.08914318e+01 -3.09741077e+01 -3.14242134e+01 -3.10314579e+01 -3.09817123e+01 -3.10140114e+01 -3.09461517e+01 -3.08661404e+01 -3.05636177e+01 -3.04163094e+01 -3.02422256e+01 -3.02670593e+01 -3.01015720e+01 -2.94028702e+01 -2.72155285e+01 -1.65433464e+01 -1.42985773e+01 -5.59816420e-01 -4.00240440e+01 -6.48920670e+01 -1.82821182e+02 -2.95000244e+02 -7.26476822e+01 -7.10308380e+01 -6.94620819e+01 -6.94562531e+01 -6.87305603e+01 -6.89102936e+01 -6.81868134e+01 -6.82239456e+01 1.89842590e+02 9.68763580e+01 -2.79054432e+01 -2.78557777e+01 -2.86745453e+01 -2.80115814e+01 -2.80448589e+01 -2.83360329e+01 -2.76448898e+01 -2.70897121e+01 -2.38020515e+01 -1.53358688e+02 -1.51736660e+01 -6.17336130e+00 -4.43279724e+02 -7.69356262e+02 -73065304. -282787552. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.88663375e+06 537763584. -2.80449688e+05 -25487672. -26622898. 1524076928. -5.63489746e+02 -2.05911682e+02 -3.25462074e+01 -2.75856724e+01 -2.50930882e+01 -2.33785038e+01 -2.15723896e+01 -2.34474316e+01 -2.35216293e+01 1.13129181e+02 3.17784546e+02 -14852270. -15363801. -48945672. 319367808. 122173928. 245470608. -30091450. -75174488. -65227220. -18303046. -1.17719025e+06 -25161532. -59384724. -22739106. -6.31336426e+02 -8.87923431e+01 3.90599091e+02 -54442540. -5.28924250e+06 -141424928. -39146092. -32037836. 169315216. -55147896. -65490856. -37612512. -7689055. -9.78784312e+05 -2210088. -4.86473350e+06 -71174624. -2.80197875e+05 -2.37283328e+05 -301843296. -110606600. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 925190592. 925190592. 0. 0. 129619688. 129619688. 129619688. 0. 0. 0. 0. 53502272. 90715280. 295344000. -572696704. -16985452. -1228782848. -1228782848. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70341464. -70341464. -70341464. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -70665224. -70665224. -70665224. 0. 0. -205965712. -233591728. -233591728. 94530224. -26735972. -3.36577344e+05 -9.60596863e+02 -4.03147888e+02 -4.47293777e+01 -3.66818237e+02 -9.10290466e+02 -747123008. -13897377. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -251897856. 208069440. -1.22746875e+03 -4.39827820e+02 6.02682161e+00 -1.79762283e+02 -9.80351791e+01 1.28017149e+01 1.36373482e+01 1.40349922e+01 1.47414837e+01 1.50803175e+01 1.46775379e+01 1.47961960e+01 1.52848473e+01 1.64146347e+01 1.65535088e+01 1.54012432e+01 1.60156307e+01 1.67834053e+01 1.72293358e+01 1.78644867e+01 1.77194252e+01 1.75862980e+01 1.91197529e+01 1.93993111e+01 1.93544064e+01 1.99271584e+01 1.98585072e+01 1.97340584e+01 2.03552246e+01 2.01890106e+01 2.06678219e+01 2.12159061e+01 2.09503975e+01 2.11764641e+01 2.14380894e+01 2.13538322e+01 2.20796089e+01 2.20894623e+01 2.21938934e+01 2.35727005e+01 2.44116745e+01 2.42074394e+01 2.45910053e+01 2.48008461e+01 2.49353638e+01 2.49272823e+01 2.53410873e+01 2.64038963e+01 2.58835049e+01 2.56458626e+01 2.64376888e+01 2.66833496e+01 2.62038326e+01 2.66412735e+01 2.70376167e+01 2.78711891e+01 2.81515484e+01 2.85985718e+01 2.77879562e+01 2.76682720e+01 2.87074490e+01 2.88840790e+01 2.90285645e+01 2.96251183e+01 3.00447178e+01 3.02309647e+01 3.04848537e+01 3.09549999e+01 3.09635658e+01 3.08597775e+01 3.09485321e+01 3.13029842e+01 3.23298149e+01 3.31826820e+01 3.38225403e+01 3.41694183e+01 3.37399826e+01 3.40503235e+01 3.39751778e+01 3.47803078e+01 3.48539505e+01 3.49271622e+01 3.47453308e+01 3.42632790e+01 3.48073845e+01 3.53549461e+01 3.57150764e+01 3.66022530e+01 3.66719322e+01 3.62842407e+01 3.65463486e+01 3.72149734e+01 3.73454018e+01 3.74118080e+01 3.78664169e+01 3.81207352e+01 3.80430527e+01 3.85313950e+01 3.85863190e+01 3.91055412e+01 3.81585121e+01 3.88335266e+01 3.91203499e+01 4.02918396e+01 4.05115852e+01 4.00632133e+01 3.71969948e+01 3.61741295e+01 3.91915512e+01 4.43298302e+01 4.48295631e+01 4.15453300e+01 4.09534607e+01 4.14189911e+01 4.22020798e+01 4.18945045e+01 4.20624008e+01 4.22020073e+01 4.25683212e+01 4.24792786e+01 4.25349197e+01 4.29905663e+01 4.36491356e+01 4.33771667e+01 4.33315582e+01 4.35752258e+01 4.39275742e+01 4.41550674e+01 4.42795372e+01 4.44504051e+01 4.42538338e+01 4.49161453e+01 4.50952034e+01 4.48236465e+01 4.52329826e+01 4.53356285e+01 4.56236382e+01 4.54268265e+01 4.57134628e+01 4.58913116e+01 4.43124886e+01 4.59777298e+01 4.79014015e+01 4.66935997e+01 4.68227615e+01 4.70067863e+01 4.70718536e+01 4.69589233e+01 4.72778931e+01 4.77728729e+01 4.82501221e+01 4.82578850e+01 4.79804497e+01 4.84194527e+01 4.84468117e+01 4.86606445e+01 4.85675430e+01 4.85665359e+01 4.88848839e+01 4.89916344e+01 4.91192665e+01 4.95301552e+01 4.94806099e+01 4.93872833e+01 4.97230339e+01 4.96670303e+01 4.96401596e+01 5.00186996e+01 5.01764717e+01 5.03634453e+01 5.00436554e+01 4.96878281e+01 4.99727249e+01 5.02661591e+01 5.03227234e+01 5.04948158e+01 5.10018044e+01 5.08935699e+01 5.07045822e+01 5.10884018e+01 5.12320595e+01 5.10050201e+01 5.12127266e+01 5.12905197e+01 5.03983231e+01 5.01858635e+01 4.80019379e+01 4.47463913e+01 4.03900566e+01 5.18774452e+01 6.25550919e+01 5.45752029e+01 5.02812119e+01 4.89733391e+01 4.44162636e+01 4.54038277e+01 6.36509666e+01 6.59474945e+01 2.94856049e+02 4.60452118e+02 -3.37351685e+02 -1.85371155e+02 -1.59504013e+02 -2.79558777e+02 6.31352577e+01 6.42499695e+01 4.29731934e+02 3.07336639e+02 6.36864243e+01 7.72405701e+01 7.73182983e+01 5.70730057e+01 5.36819000e+01 5.46205750e+01 6.20111465e+01 5.74061623e+01 5.43792419e+01 -1.48117661e+02 -3.03414703e+02 5.69423294e+01 5.73162117e+01 5.66143188e+01 4.23549896e+02 2.64326508e+02 4.09102631e+01 6.14740486e+01 6.20140266e+01 5.96186028e+01 5.54830284e+01 5.38831291e+01 5.33681374e+01 5.36014366e+01 5.32051582e+01 5.25475655e+01 5.22750320e+01 5.21596031e+01 5.26650162e+01 5.31086311e+01 5.27214813e+01 5.22783890e+01 5.18423424e+01 5.16768684e+01 5.18780899e+01 5.20183563e+01 5.17232933e+01 5.21530228e+01 5.25248604e+01 5.20978127e+01 5.19616394e+01 5.12547226e+01 5.12835007e+01 5.15672150e+01 5.17638245e+01 5.18506279e+01 5.18623047e+01 5.23114243e+01 5.21151886e+01 5.17559013e+01 5.13612671e+01 5.12195396e+01 5.12494392e+01 5.03955116e+01 5.01076889e+01 5.01208382e+01 5.08378296e+01 5.04411850e+01 5.09681664e+01 5.16185722e+01 5.19236832e+01 5.11860771e+01 5.04710464e+01 5.00932732e+01 5.04344101e+01 5.08575096e+01 5.01279068e+01 4.98141136e+01 4.95482368e+01 4.90687218e+01 4.92871780e+01 4.94348145e+01 4.94953232e+01 4.93716621e+01 4.95052071e+01 4.88894691e+01 4.86475067e+01 4.80094719e+01 4.80409050e+01 4.88091736e+01 4.84777565e+01 4.88387756e+01 4.80634232e+01 4.79029922e+01 4.71312256e+01 4.71193619e+01 4.75516357e+01 4.80760574e+01 4.71258049e+01 4.65331421e+01 4.57542763e+01 4.62620659e+01 4.63097076e+01 4.69639702e+01 4.65251274e+01 4.63732948e+01 4.60567856e+01 4.61412048e+01 4.61893044e+01 4.51739922e+01 4.49957771e+01 4.59323845e+01 4.55413437e+01 4.56612587e+01 4.52645836e+01 4.47867661e+01 4.43400307e+01 4.41142044e+01 4.35653610e+01 4.36656342e+01 4.37130318e+01 4.34391327e+01 4.32735672e+01 4.30384293e+01 4.31234322e+01 4.34591942e+01 4.28308640e+01 4.25225105e+01 4.17643127e+01 4.16693497e+01 4.16199341e+01 4.11799583e+01 4.23656540e+01 4.26279984e+01 4.11445808e+01 4.06629066e+01 4.01992378e+01 4.07253418e+01 4.09266396e+01 4.07174873e+01 3.97995110e+01 3.90245285e+01 3.89641571e+01 3.86861725e+01 3.81514130e+01 3.85529518e+01 3.87221947e+01 3.85634880e+01 3.80182228e+01 3.75346870e+01 3.75116730e+01 3.74016151e+01 3.72223320e+01 3.67283745e+01 3.65324974e+01 3.67071838e+01 3.64004173e+01 3.61510048e+01 3.55974197e+01 3.54942894e+01 3.51428146e+01 3.51030731e+01 3.49041290e+01 3.45983925e+01 3.42135353e+01 3.37748184e+01 3.33071327e+01 3.30737305e+01 3.29493103e+01 3.29827766e+01 3.29183846e+01 3.24116287e+01 3.20788727e+01 3.22383690e+01 3.21760178e+01 3.16493340e+01 3.12776260e+01 3.09928875e+01 3.06650639e+01 3.04291496e+01 3.01802120e+01 2.99141827e+01 2.94428368e+01 2.91753235e+01 2.90180473e+01 2.88182659e+01 2.87947350e+01 2.85601826e+01 2.78481827e+01 2.74740887e+01 2.72187443e+01 2.70013847e+01 2.70823078e+01 2.68433895e+01 2.64520512e+01 2.61541290e+01 2.59879990e+01 2.56200390e+01 2.53058357e+01 2.50983410e+01 2.46202278e+01 2.43690357e+01 2.40039082e+01 2.36649628e+01 2.36580715e+01 2.33846703e+01 2.28482037e+01 2.24751644e+01 2.23193150e+01 2.20592670e+01 2.16443958e+01 2.13765907e+01 2.11304340e+01 2.08500214e+01 2.05318451e+01 2.02273998e+01 1.99595909e+01 1.95809841e+01 1.92374306e+01 1.89491482e+01 1.87270737e+01 1.84085732e+01 1.80679398e+01 1.77730083e+01 1.74725742e+01 1.71613102e+01 1.68534355e+01 1.65499496e+01 1.62590504e+01 1.59475565e+01 1.56463566e+01 1.53431644e+01 1.50282631e+01 1.47299929e+01 1.44380627e+01 1.41250381e+01 1.37133570e+01 1.34324932e+01 1.31261415e+01 1.27945652e+01 1.24550867e+01 1.20611706e+01 1.18155470e+01 1.15960646e+01 1.13352604e+01 1.10339718e+01 1.06525116e+01 1.03721695e+01 1.00550795e+01 9.75817871e+00 9.41318321e+00 9.12247944e+00 8.77647781e+00 8.42978001e+00 8.07689190e+00 7.59576035e+00 7.45006990e+00 7.26254940e+00 6.77810574e+00 6.45370102e+00 6.16975927e+00 5.79393959e+00 5.52878475e+00 5.23975563e+00 4.76902819e+00 4.49506903e+00 4.42844009e+00 3.94934511e+00 3.59489512e+00 3.20007801e+00 2.96951270e+00 2.67345738e+00 2.42528200e+00 2.12319899e+00 1.78680849e+00 1.32439971e+00 1.01506662e+00 7.12820888e-01 4.21283811e-01 7.87377581e-02 -1.27089128e-01 -5.24716079e-01 -7.94420302e-01 -1.30527914e+00 -1.73432994e+00 -1.87349451e+00 -1.83055389e+00 -2.48876786e+00 -2.96632457e+00 -3.52842307e+00 -3.92271852e+00 -3.65056133e+00 -3.64649820e+00 -4.17189121e+00 -4.88830328e+00 -5.47989321e+00 -6.01164865e+00 -6.08144426e+00 -6.04207230e+00 -6.16230583e+00 -6.38778782e+00 -6.74696493e+00 -7.26909304e+00 -8.12197113e+00 -8.25049973e+00 -8.28355598e+00 -8.30765343e+00 -8.80451393e+00 -9.40487099e+00 -9.52733040e+00 -9.80534935e+00 -1.01398554e+01 -1.06332731e+01 -1.10924530e+01 -1.13879681e+01 -1.17413092e+01 -1.20768709e+01 -1.23740034e+01 -1.26480103e+01 -1.27753019e+01 -1.27128401e+01 -1.27184381e+01 -1.32715197e+01 -1.39958763e+01 -1.46653214e+01 -1.48070517e+01 -1.54563036e+01 -1.58344812e+01 -1.59212608e+01 -1.60695534e+01 -1.60905037e+01 -1.69935818e+01 -1.72197342e+01 -1.72579269e+01 -1.72077217e+01 -1.72018356e+01 -1.77067394e+01 -1.83002472e+01 -1.86236000e+01 -1.90041046e+01 -1.97331295e+01 -1.95996838e+01 -1.99327526e+01 -2.05369129e+01 -2.05816612e+01 -2.10635548e+01 -2.13745823e+01 -2.22247696e+01 -2.20281830e+01 -2.21230202e+01 -2.13076744e+01 -2.19062233e+01 -2.33271961e+01 -2.37071304e+01 -2.33297138e+01 -2.35450287e+01 -2.27062588e+01 -2.35536652e+01 -2.39139996e+01 -2.52392159e+01 -2.55930386e+01 -2.62190609e+01 -2.61282387e+01 -2.56945839e+01 -2.59761944e+01 -2.68859997e+01 -2.66837730e+01 -2.66712570e+01 -2.76432838e+01 -2.86650505e+01 -2.84061165e+01 -2.80228691e+01 -2.77005520e+01 -2.82872505e+01 -2.84451160e+01 -2.86885757e+01 -2.88763103e+01 -2.92697754e+01 -2.94238701e+01 -3.03856773e+01 -3.09259071e+01 -3.18396339e+01 -3.14702568e+01 -3.19451504e+01 -3.14866333e+01 -3.14478626e+01 -3.20134277e+01 -3.27817917e+01 -3.39579620e+01 -3.44401131e+01 -3.36604805e+01 -3.41621132e+01 -3.45324135e+01 -3.50577011e+01 -3.49164238e+01 -3.48780022e+01 -3.48561020e+01 -3.44520073e+01 -3.48361015e+01 -3.48997917e+01 -3.49810104e+01 -3.61431007e+01 -3.67907944e+01 -3.66539192e+01 -3.64496689e+01 -3.65372391e+01 -3.69146461e+01 -3.71694679e+01 -3.75347214e+01 -3.75552063e+01 -3.78586082e+01 -3.85056953e+01 -3.82685013e+01 -3.77707596e+01 -3.81683083e+01 -3.91687317e+01 -3.73733749e+01 -3.82455673e+01 -4.02381477e+01 -4.02768593e+01 -3.99015274e+01 -3.93466492e+01 -3.95411873e+01 -4.01395378e+01 -4.02411766e+01 -3.90896835e+01 -3.48285408e+01 -3.90873795e+01 -2.90207157e+01 1.80665604e+02 3.24767090e+02 -1.51548357e+01 -1.39367237e+01 -1.55423994e+01 -4.13589142e+02 -2.69274628e+02 -4.46276131e+01 -4.32793694e+01 -4.24275169e+01 -4.11008339e+01 -3.80728760e+01 -4.76928253e+01 -5.20064316e+01 -4.44186440e+01 1.66160065e+02 1.70960037e+02 -4.27558060e+01 2.21867783e+02 -4.21016296e+02 -2.76040710e+02 -4.56412849e+01 -4.16719246e+01 -5.10033836e+01 -6.33962059e+01 -4.66676941e+01 -5.86511078e+01 -4.78196983e+01 -4.83970299e+01 -4.76504860e+01 -2.67396431e+01 -3.67867432e+01 -6.35844765e+01 -5.67815666e+01 -5.06892548e+01 -5.02405777e+01 -5.02807388e+01 -4.96686554e+01 -4.89008369e+01 -4.87255936e+01 -4.87416229e+01 -4.85098076e+01 -4.84656219e+01 -4.86088524e+01 -4.90566444e+01 -4.95253983e+01 -4.93357887e+01 -4.93123741e+01 -4.95516396e+01 -4.96227379e+01 -4.96656418e+01 -4.97185364e+01 -4.98731346e+01 -4.96927567e+01 -4.97609520e+01 -4.98806419e+01 -4.99653969e+01 -5.04114838e+01 -5.04514465e+01 -5.04182129e+01 -5.04883804e+01 -5.06220932e+01 -5.07947960e+01 -5.08460159e+01 -5.08504257e+01 -5.09602127e+01 -5.10856552e+01 -5.12751236e+01 -5.16190186e+01 -5.19680557e+01 -5.17849350e+01 -5.16520386e+01 -5.19182930e+01 -5.22705154e+01 -5.15442009e+01 -5.14026566e+01 -5.14747467e+01 -5.17303505e+01 -5.18998528e+01 -5.20259705e+01 -5.17368317e+01 -5.21725121e+01 -5.26132736e+01 -5.24517250e+01 -5.22997475e+01 -5.19247398e+01 -5.21320801e+01 -5.24008980e+01 -5.26421051e+01 -5.24480667e+01 -5.21294441e+01 -5.21209183e+01 -5.24026184e+01 -5.24821777e+01 -5.23364258e+01 -5.15684814e+01 -5.10154686e+01 -5.29158249e+01 -5.42187576e+01 -5.28946762e+01 -5.21467896e+01 -5.24737625e+01 -5.26471977e+01 -5.22896538e+01 -5.25035057e+01 -5.26595726e+01 -5.28038902e+01 -5.24405937e+01 -5.25066223e+01 -5.24338531e+01 -5.27854080e+01 -5.11554680e+01 -5.13187370e+01 -5.43656883e+01 -5.42542152e+01 -5.27151184e+01 -5.34316635e+01 -5.26715622e+01 -5.19722862e+01 -5.17641716e+01 -4.97512321e+01 -4.99691734e+01 -5.26145096e+01 -5.62985344e+01 -5.56071014e+01 -5.21049690e+01 -5.14166107e+01 -5.12723732e+01 -5.16663475e+01 -5.20687065e+01 -5.25638428e+01 -5.21013718e+01 -5.17600441e+01 -5.16491623e+01 -5.15034332e+01 -5.16971207e+01 -5.16667366e+01 -5.19939728e+01 -5.20412292e+01 -5.19274597e+01 -5.23791618e+01 -5.22766571e+01 -5.16867256e+01 -5.13752060e+01 -5.16914253e+01 -5.19601822e+01 -5.14021645e+01 -5.05953178e+01 -4.97918167e+01 -5.04715767e+01 -5.07449036e+01 -5.10637512e+01 -5.07720642e+01 -5.12339249e+01 -5.10839195e+01 -4.64589348e+01 -4.64649582e+01 -5.26773415e+01 -5.44291115e+01 -5.18016281e+01 -5.00003395e+01 -4.98753281e+01 -4.94588432e+01 -4.91426620e+01 -4.88643341e+01 -4.93861732e+01 -4.94548874e+01 -4.94488258e+01 -4.87000046e+01 -4.85102425e+01 -4.84743423e+01 -4.82344513e+01 -4.86292877e+01 -4.83836975e+01 -4.87818756e+01 -4.82226143e+01 -4.78650246e+01 -4.77571602e+01 -4.79872704e+01 -4.79998283e+01 -4.78473701e+01 -4.73688240e+01 -4.70491905e+01 -4.61681366e+01 -4.65286484e+01 -4.64759407e+01 -4.71316071e+01 -4.67930107e+01 -4.67696342e+01 -4.60718155e+01 -4.58023758e+01 -4.57645111e+01 -4.58144073e+01 -4.51682854e+01 -4.53376694e+01 -4.59223557e+01 -4.57462273e+01 -4.47874107e+01 -4.45668678e+01 -4.40081787e+01 -4.38650627e+01 -4.34665070e+01 -4.34599380e+01 -4.31291809e+01 -4.34059258e+01 -4.35014305e+01 -4.30418663e+01 -4.29102058e+01 -4.34211006e+01 -4.33204231e+01 -4.24644928e+01 -4.18657532e+01 -4.19914856e+01 -4.15514755e+01 -4.06863594e+01 -3.90714111e+01 -2.46459541e+01 -1.53424271e+02 -2.14895828e+02 -4.77194763e+02 -1.04395325e+03 7469192. -44941720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5267423. 5267423. 5267423. 0. 0. 20586100. -1.26065559e+02 -4.70261688e+01 -4.11275749e+01 3.66540680e+01 8.38761215e+01 -1.80844543e+02 -2.50737656e+02 -8.16253586e+01 -35165424. -59987064. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 399658688. 399658688. 399658688. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 129619688. 129619688. 129619688. 0. 0. 0. 0. 53502272. 90715280. 295344000. -572696704. -974818688. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.07369719e+05 24424656. -2.39277094e+05 -78548992. -111749376. 151267904. -21269158. 4.41671731e+09 -21567020. -7.12624250e+06 -547796352. 113355000. -364349472. -364349472. 0. 0. 0. 0. 0. 0. 0. -70665224. -70665224. -70665224. 0. 0. -205965712. -233591728. -233591728. 94530224. -26735972. -3.36577344e+05 -1691978. -35712672. -3441318. 113085688. 29294388. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.35006703e+05 3.66021004e+01 -1.89564972e+02 -9.48055115e+01 1.69678440e+01 1.78595276e+01 1.68671799e+01 1.60000229e+01 1.56726952e+01 1.52373447e+01 1.58169012e+01 1.63843555e+01 1.55943813e+01 1.58106709e+01 1.75686703e+01 -1.04325249e+02 -2.01232346e+02 2.45654434e+02 1.56083984e+02 1.67079315e+01 1.88116817e+01 2.02708340e+01 1.95986252e+01 2.00841675e+01 2.16834335e+01 2.17501774e+01 2.20658379e+01 2.29428024e+01 2.28126259e+01 2.28271027e+01 2.33599339e+01 2.35305119e+01 2.44465332e+01 2.48725700e+01 2.47233715e+01 2.51993160e+01 2.31953049e+01 -1.20055283e+02 -2.30652084e+02 1.88644104e+01 1.87190304e+01 2.52747746e+01 3.09514069e+02 1.98863754e+02 2.88477993e+01 2.85152454e+01 2.94884338e+01 3.00544395e+01 3.04251156e+01 3.13319378e+01 3.08990135e+01 3.08518887e+01 3.15144272e+01 3.23953171e+01 3.23606682e+01 3.24012985e+01 3.26579132e+01 3.37500076e+01 3.43305855e+01 3.45652122e+01 3.36506500e+01 3.39587746e+01 3.44167671e+01 3.57578773e+01 3.59012260e+01 3.52458611e+01 3.55715103e+01 3.56594353e+01 3.66797676e+01 3.70714798e+01 3.75063286e+01 3.79352036e+01 3.78883018e+01 3.77752228e+01 3.79824486e+01 3.80689011e+01 3.92552567e+01 3.93457794e+01 3.98841095e+01 3.99174652e+01 4.09163971e+01 4.18431625e+01 4.16536369e+01 4.19773331e+01 4.17346191e+01 4.26175232e+01 4.23694763e+01 4.25794678e+01 4.28475342e+01 4.32419395e+01 4.34906464e+01 4.35648956e+01 4.39013367e+01 4.43360786e+01 4.45542412e+01 4.50780602e+01 4.52905159e+01 4.50747147e+01 4.55092773e+01 4.59352722e+01 4.60955391e+01 4.61573143e+01 4.61303482e+01 4.61175957e+01 4.65074883e+01 4.75372887e+01 4.82554169e+01 4.78168869e+01 4.68919716e+01 4.53373070e+01 4.72614861e+01 5.31036453e+01 5.35221710e+01 4.99359169e+01 4.89892616e+01 4.96457596e+01 5.01188889e+01 4.99420128e+01 5.00933952e+01 5.05605888e+01 5.12106972e+01 5.16768341e+01 5.16398735e+01 5.22195244e+01 5.23902664e+01 5.18865356e+01 5.19426041e+01 5.23878593e+01 5.29702759e+01 5.30886345e+01 5.34167633e+01 5.30677414e+01 5.30482063e+01 5.34659424e+01 5.39379768e+01 5.39425964e+01 5.40441971e+01 5.44160233e+01 5.50463943e+01 5.55311203e+01 5.57849617e+01 5.56430855e+01 5.44534111e+01 5.55340042e+01 5.71819458e+01 5.64028511e+01 5.64933052e+01 5.69595337e+01 5.69409714e+01 5.66812897e+01 5.70621071e+01 5.74241524e+01 5.76035118e+01 5.77666206e+01 5.78052216e+01 5.80566864e+01 5.83347931e+01 5.86357574e+01 5.86040344e+01 5.87481232e+01 5.88176804e+01 5.88235779e+01 5.90387650e+01 5.94534264e+01 5.95833931e+01 5.95820694e+01 5.98462944e+01 5.96847725e+01 5.99550591e+01 6.05413628e+01 6.02985001e+01 6.02413979e+01 6.03540268e+01 6.01317024e+01 6.02213783e+01 6.06152496e+01 6.09255066e+01 6.12409439e+01 6.15776558e+01 6.12550163e+01 6.11500473e+01 6.17411346e+01 6.17971344e+01 6.17544975e+01 6.17154274e+01 6.19450760e+01 6.19277725e+01 6.21507988e+01 6.20339622e+01 6.22415810e+01 6.19459190e+01 6.15437698e+01 6.16248512e+01 6.13437271e+01 6.10380516e+01 5.89112129e+01 5.32343407e+01 5.42014542e+01 7.12691116e+01 7.38866806e+01 6.16336174e+01 5.82364426e+01 5.31676865e+01 5.23127899e+01 8.64674759e+01 9.30579529e+01 9.06960907e+01 8.50200043e+01 6.82292175e+01 3.40574585e+02 4.95314148e+02 -8.50772156e+02 -2.25424316e+03 -1.78546814e+03 -6.37186096e+02 1.27459625e+02 4.64642975e+02 3.00562164e+02 6.60698776e+01 7.82429886e+01 7.81727600e+01 9.28376923e+01 9.30202484e+01 9.20346909e+01 7.64806671e+01 5.94416084e+01 3.11041527e+01 -1.43811020e+02 -2.57886932e+02 1.79335968e+02 1.53172577e+02 1.42726044e+02 1.37175491e+02 1.39299927e+02 1.36487457e+02 1.33559189e+02 4.54366455e+02 3.03638641e+02 7.23547974e+01 7.16006622e+01 7.23250122e+01 7.00094223e+01 6.84396973e+01 6.45867844e+01 6.65168991e+01 7.00016556e+01 6.44767456e+01 6.22220955e+01 6.65476913e+01 6.61047745e+01 5.89919777e+01 5.69164581e+01 5.26460991e+01 3.65236206e+01 6.98682327e+01 9.36867676e+01 5.75982132e+01 8.75048981e+01 9.28471527e+01 7.47087936e+01 7.59455872e+01 6.64679108e+01 6.74143066e+01 6.15265465e+01 6.58172073e+01 6.59694672e+01 6.39687080e+01 6.53688202e+01 6.37383919e+01 6.09349861e+01 6.36574593e+01 6.13614998e+01 5.75361977e+01 6.18291473e+01 6.46878052e+01 6.36947021e+01 6.32725601e+01 6.23434410e+01 6.19716339e+01 6.17943192e+01 6.17846909e+01 6.16098595e+01 6.07119789e+01 6.02990799e+01 6.02921906e+01 6.04080696e+01 6.02595139e+01 5.99442482e+01 5.97791481e+01 5.96363792e+01 5.96824989e+01 5.95030251e+01 5.87090530e+01 5.83548317e+01 5.80511208e+01 5.75263596e+01 5.74061241e+01 5.78252563e+01 5.76490021e+01 5.71726494e+01 5.66992531e+01 5.62845268e+01 5.61414337e+01 5.65668488e+01 5.69369736e+01 5.67712288e+01 5.59853935e+01 5.56692963e+01 5.57428246e+01 5.51417885e+01 5.51112900e+01 5.59679909e+01 5.50732727e+01 5.46551933e+01 5.45686607e+01 5.43682976e+01 5.41213799e+01 5.40822449e+01 5.35803833e+01 5.38968277e+01 5.36984940e+01 5.28098831e+01 5.27247314e+01 5.21987000e+01 5.23283806e+01 5.23430634e+01 5.21284943e+01 5.20731125e+01 5.14110107e+01 5.09391861e+01 5.05807648e+01 4.99897346e+01 5.06084137e+01 5.07112846e+01 5.00949440e+01 4.91530533e+01 4.92043381e+01 4.97864456e+01 4.96897736e+01 4.96136398e+01 4.86472740e+01 4.82335205e+01 4.82113533e+01 4.80351105e+01 4.72810974e+01 4.69232140e+01 4.70350876e+01 4.71965637e+01 4.65893402e+01 4.59959984e+01 4.56574783e+01 4.54601479e+01 4.53689766e+01 4.49819298e+01 4.46269035e+01 4.44059563e+01 4.42287979e+01 4.39461098e+01 4.38179207e+01 4.33303299e+01 4.29530602e+01 4.27027626e+01 4.25084648e+01 4.21073112e+01 4.18102913e+01 4.16247330e+01 4.14835739e+01 4.09446297e+01 4.05354195e+01 4.04657478e+01 4.03192101e+01 3.97644234e+01 3.91547241e+01 3.92011528e+01 3.92168579e+01 3.88738556e+01 3.85946426e+01 3.81253128e+01 3.76693153e+01 3.73970184e+01 3.69739609e+01 3.65646667e+01 3.60457611e+01 3.57189293e+01 3.53764076e+01 3.50235367e+01 3.51592789e+01 3.49039955e+01 3.41644173e+01 3.36250763e+01 3.34189606e+01 3.32382011e+01 3.31957550e+01 3.27152481e+01 3.22843361e+01 3.20433197e+01 3.17783947e+01 3.13066845e+01 3.10745201e+01 3.07512493e+01 3.01672363e+01 2.98123283e+01 2.94888210e+01 2.92261505e+01 2.91253090e+01 2.87798843e+01 2.83290043e+01 2.78716869e+01 2.76333561e+01 2.73281803e+01 2.68697681e+01 2.64664555e+01 2.61121635e+01 2.57946548e+01 2.54104996e+01 2.50387993e+01 2.46958103e+01 2.43184853e+01 2.39087009e+01 2.35529022e+01 2.32841244e+01 2.28988094e+01 2.24848156e+01 2.21290474e+01 2.17623978e+01 2.14103699e+01 2.10494804e+01 2.06974125e+01 2.03531876e+01 2.00010548e+01 1.96442795e+01 1.92871723e+01 1.88996964e+01 1.85253105e+01 1.81420078e+01 1.77105618e+01 1.71743469e+01 1.68303661e+01 1.65408669e+01 1.61193428e+01 1.57058125e+01 1.52956486e+01 1.50657673e+01 1.47767200e+01 1.44097052e+01 1.39830017e+01 1.35199318e+01 1.31182518e+01 1.27389278e+01 1.23146133e+01 1.19293890e+01 1.15949144e+01 1.12253284e+01 1.07812872e+01 1.04053907e+01 9.95407200e+00 9.61499023e+00 9.20227146e+00 8.72795963e+00 8.38465405e+00 8.03417110e+00 7.59192419e+00 7.16722584e+00 6.84395885e+00 6.33040524e+00 5.91188383e+00 5.62781715e+00 5.20698214e+00 4.73867750e+00 4.50411081e+00 4.23590088e+00 3.67538786e+00 3.31178975e+00 2.89758301e+00 2.51802802e+00 1.98562956e+00 1.65199423e+00 1.24230349e+00 8.80967915e-01 4.45056826e-01 3.12455267e-01 -5.12908213e-02 -4.02569801e-01 -9.13485169e-01 -1.53340125e+00 -1.99277318e+00 -2.21506739e+00 -2.68999505e+00 -3.01052761e+00 -2.96130180e+00 -3.72245479e+00 -4.12822580e+00 -4.97067881e+00 -5.36156702e+00 -5.67223740e+00 -5.83475685e+00 -5.95906687e+00 -6.39222670e+00 -6.85356903e+00 -7.55115747e+00 -8.14091396e+00 -8.18366718e+00 -8.42940140e+00 -8.98598671e+00 -9.32232189e+00 -9.53843880e+00 -9.92378902e+00 -1.05282154e+01 -1.11776505e+01 -1.11781502e+01 -1.13183632e+01 -1.13041258e+01 -1.17714157e+01 -1.25947866e+01 -1.31569328e+01 -1.34431276e+01 -1.38511267e+01 -1.39834051e+01 -1.46830940e+01 -1.50914497e+01 -1.55926266e+01 -1.56260128e+01 -1.57041807e+01 -1.64671898e+01 -1.67632904e+01 -1.66945305e+01 -1.70963516e+01 -1.74296932e+01 -1.85143204e+01 -1.84272976e+01 -1.83904266e+01 -1.87908573e+01 -1.93471127e+01 -2.01409054e+01 -2.04821091e+01 -2.10973377e+01 -2.16956882e+01 -2.28048954e+01 -2.25060139e+01 -2.24119625e+01 -2.24329853e+01 -2.28462181e+01 -2.32150269e+01 -2.35323563e+01 -2.41957073e+01 -2.47532578e+01 -2.49679623e+01 -2.55578880e+01 -2.58676662e+01 -2.53187237e+01 -2.54211693e+01 -2.65785236e+01 -2.76117611e+01 -2.72184410e+01 -2.72893524e+01 -2.80310421e+01 -2.75892353e+01 -2.82773876e+01 -2.87097931e+01 -2.98215313e+01 -3.08191891e+01 -3.09878578e+01 -3.03952484e+01 -2.99543304e+01 -3.08041496e+01 -3.20694199e+01 -3.19432888e+01 -3.18515949e+01 -3.13728638e+01 -3.23402824e+01 -3.33370972e+01 -3.37964821e+01 -3.40130539e+01 -3.45530586e+01 -3.50473366e+01 -3.52934608e+01 -3.53324699e+01 -3.47357712e+01 -3.44240417e+01 -3.50524864e+01 -3.67872314e+01 -3.69212303e+01 -3.74086914e+01 -3.84611168e+01 -3.82653923e+01 -3.77144928e+01 -3.79950294e+01 -3.81388931e+01 -3.89969788e+01 -3.96525040e+01 -3.96594238e+01 -4.01765327e+01 -4.06262093e+01 -4.05532608e+01 -4.05238419e+01 -4.16155663e+01 -4.13621216e+01 -4.20173302e+01 -4.23851471e+01 -4.30196838e+01 -4.27669258e+01 -4.35296669e+01 -4.37754822e+01 -4.41262398e+01 -4.39396553e+01 -4.38618126e+01 -4.42449493e+01 -4.36801834e+01 -4.51745071e+01 -4.56376152e+01 -4.53340645e+01 -4.55980873e+01 -4.45819321e+01 -4.36335526e+01 -4.06544533e+01 1.47509903e+02 2.87353790e+02 -6.47209396e+01 -7.21512222e+01 -7.14772644e+01 -7.16659088e+01 -7.22596741e+01 -7.47185974e+01 -7.70800705e+01 -7.39545517e+01 -4.34020447e+02 -2.71756165e+02 -4.85715256e+01 -3.82218437e+01 -6.67831650e+01 -8.55292511e+01 -7.97691269e+01 -7.95282135e+01 -7.98851929e+01 -6.14438820e+01 -6.39606285e+01 1.42217178e+02 2.90517548e+02 -7.96689377e+01 -4.29456940e+02 -6.72157898e+01 2.73221283e+02 -4.59122345e+02 -2.92549530e+02 -7.27546844e+01 5.37778854e+01 -7.72216415e+01 -1.78522232e+02 -6.31431084e+01 -6.78844299e+01 -5.96285629e+01 -5.02863197e+01 -5.68220482e+01 -2.93875519e+02 -5.39210815e+01 1.47938370e+02 -5.64980164e+01 -5.84008217e+01 -5.82552757e+01 -5.86589928e+01 -5.80189056e+01 -5.72461472e+01 -5.72644196e+01 -5.76053619e+01 -5.76606331e+01 -5.78829880e+01 -5.80539818e+01 -5.81441116e+01 -5.83689690e+01 -5.84253006e+01 -5.86475220e+01 -5.87124443e+01 -5.88161774e+01 -5.91182785e+01 -5.95578156e+01 -5.95258255e+01 -5.94827003e+01 -5.96794548e+01 -5.97737617e+01 -5.99705162e+01 -6.00631790e+01 -6.00868568e+01 -6.01343880e+01 -6.02867432e+01 -6.06089859e+01 -6.08626671e+01 -6.10288048e+01 -6.08785744e+01 -6.09676590e+01 -6.14539452e+01 -6.13464966e+01 -6.12987518e+01 -6.13621101e+01 -6.18804054e+01 -6.19991646e+01 -6.20279007e+01 -6.17544594e+01 -6.21231079e+01 -6.28347244e+01 -6.26652718e+01 -6.24684105e+01 -6.33339157e+01 -6.35057030e+01 -6.20645409e+01 -6.24008064e+01 -6.28680077e+01 -6.28180656e+01 -6.29063950e+01 -6.28811378e+01 -6.27348404e+01 -6.28929710e+01 -6.35025787e+01 -6.30871773e+01 -6.32639351e+01 -6.28694649e+01 -6.29300728e+01 -6.33020554e+01 -6.35020027e+01 -6.39146538e+01 -6.35382957e+01 -6.34857750e+01 -6.35597000e+01 -6.35861816e+01 -6.37732964e+01 -6.28072624e+01 -6.27066498e+01 -6.46165619e+01 -6.47384949e+01 -6.37774315e+01 -6.39329033e+01 -6.39250298e+01 -6.41924057e+01 -6.37784462e+01 -6.40424957e+01 -6.39717827e+01 -6.41745529e+01 -6.37676888e+01 -6.36077957e+01 -6.38590317e+01 -6.38964691e+01 -6.21535568e+01 -6.26252289e+01 -6.65370331e+01 -6.59712982e+01 -6.39920578e+01 -6.36207428e+01 -6.31071167e+01 -6.29143181e+01 -6.41290131e+01 -6.20028191e+01 -6.16707306e+01 -6.42697220e+01 -6.68951187e+01 -6.64202194e+01 -6.41939621e+01 -6.40563049e+01 -6.41160202e+01 -6.38301849e+01 -6.33836098e+01 -6.37102089e+01 -6.31638565e+01 -6.33296890e+01 -6.32834244e+01 -6.29964638e+01 -6.31288643e+01 -6.27902374e+01 -6.29598312e+01 -6.27619743e+01 -6.24469452e+01 -6.26295929e+01 -6.24636192e+01 -6.25759010e+01 -6.29435921e+01 -6.25229149e+01 -6.27293205e+01 -6.28039551e+01 -6.28900337e+01 -6.21567841e+01 -6.18466415e+01 -6.20315208e+01 -6.20359268e+01 -6.11774597e+01 -6.08355141e+01 -6.05930061e+01 -5.73431282e+01 -5.70323524e+01 -6.29370346e+01 -6.35378609e+01 -6.07829475e+01 -6.00826950e+01 -6.01758347e+01 -6.07048836e+01 -6.03771248e+01 -6.01362648e+01 -5.96376152e+01 -5.91188278e+01 -5.90717201e+01 -5.89813232e+01 -5.92981567e+01 -5.92406006e+01 -5.90152168e+01 -5.95329094e+01 -5.95384941e+01 -5.93032722e+01 -5.86227226e+01 -5.53903503e+01 -4.84046707e+01 -4.25165253e+01 9.38274002e+01 1.73910980e+02 -1.32984161e+02 -1.33484558e+02 -3.58237274e+02 -2.30340637e+02 -5.69164276e+01 -5.76216240e+01 -5.77844353e+01 -5.74290810e+01 -5.67721405e+01 -5.66625366e+01 -5.63064537e+01 -5.62106285e+01 -5.59478455e+01 -5.55017662e+01 -5.51721649e+01 -5.53143959e+01 -5.49963951e+01 -5.48816338e+01 -5.33330040e+01 -5.27288628e+01 -5.31566696e+01 -6.09338913e+01 5.92836456e+01 -3.42409706e+01 -2.19724854e+02 -6.34663925e+01 -6.54918900e+01 -6.40149841e+01 -5.58914833e+01 -5.37524681e+01 -5.27057114e+01 -5.22870331e+01 -5.15720863e+01 -5.09703064e+01 -5.03288918e+01 -4.93935165e+01 -4.68501472e+01 -3.15527000e+01 -1.49405533e+02 -1.55136459e+02 2.46388525e+03 -44941720. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5267423. 5267423. 5267423. 0. 0. 2.16375850e+06 -4.10028046e+02 -1.79196915e+02 -1.55042816e+02 1.63289398e+02 6.03803833e+02 -1.08552429e+03 -2.06701477e+02 5.45942078e+02 -35165424. -59987064. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.84576538e+09 2.84576538e+09 2.84576538e+09 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 129619688. 129619688. 129619688. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 827010048. 827010048. 827010048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.07369719e+05 24424656. -2.39277094e+05 -78548992. -111749376. 151267904. -21269158. 4.41671731e+09 2.20673447e+02 -1.63034760e+02 -1.14014429e+03 1.54054276e+02 7.88498108e+02 7.88498108e+02 -12231849. -268952864. -268952864. -138468800. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.35006703e+05 3.66021004e+01 -3.04770012e+01 -2.53635464e+01 -2.46902714e+01 1.95140182e+02 1.17678528e+02 -1.96944129e+00 -1.76279771e+00 -2.18375182e+00 -2.37525725e+00 -1.60839248e+00 -1.28389984e+02 -2.32368942e+02 -3.76721458e+01 -5.67499390e+02 -1.44151184e+03 1.17456921e+03 4.75732422e+02 -4.68002510e+01 -3.65120811e+01 -3.33094521e+01 -3.52084007e+01 -3.13951778e+01 -2.80118141e+01 -2.92296066e+01 2.41652863e+02 1.49049179e+02 3.00835061e+00 3.31758070e+00 3.64882588e+00 3.86870933e+00 4.19772053e+00 4.76934004e+00 -1.41063522e+02 -2.55352554e+02 -3.51697083e+01 -6.47273376e+02 -1.64463586e+03 15776011. -2.84588621e+09 -31432704. 1.52168213e+03 6.41616699e+02 -1.02324924e+01 -1.75388107e+01 -1.47421103e+01 -1.32954550e+01 -1.14308062e+01 -9.66950226e+00 -1.02628603e+01 2.95636780e+02 1.82271576e+02 1.14183578e+01 1.19244423e+01 1.15807734e+01 1.20084686e+01 1.20111456e+01 1.28242750e+01 1.28445148e+01 1.24966259e+01 1.29332638e+01 1.27698746e+01 1.33604803e+01 1.34650230e+01 1.31047735e+01 1.34324427e+01 1.41997223e+01 1.43633165e+01 1.45436449e+01 1.48656902e+01 1.57330332e+01 1.58648205e+01 1.62875595e+01 1.63027363e+01 1.63985176e+01 1.61370335e+01 1.58003960e+01 1.66069202e+01 1.66094532e+01 1.73096333e+01 1.72612019e+01 1.76257324e+01 1.74726028e+01 1.81644306e+01 1.85033379e+01 1.96048260e+01 1.96045856e+01 1.93015003e+01 1.85397930e+01 1.91449757e+01 2.07817955e+01 2.01340694e+01 2.02445679e+01 2.00869904e+01 2.07791443e+01 2.10313892e+01 2.10174503e+01 2.20963097e+01 2.20105171e+01 2.19307079e+01 2.17664547e+01 2.25778866e+01 2.27404900e+01 2.29983826e+01 2.31104164e+01 2.36100292e+01 2.39101543e+01 2.40566483e+01 2.05290432e+01 2.12187881e+01 2.92684383e+01 2.95217819e+01 2.48920174e+01 2.46127949e+01 2.52417603e+01 2.57373009e+01 2.58765564e+01 2.58486118e+01 2.60215588e+01 2.62055798e+01 2.69012794e+01 2.68360100e+01 2.70682621e+01 2.69137039e+01 2.71245117e+01 2.74804268e+01 2.82325897e+01 2.83951454e+01 2.80529861e+01 2.85995102e+01 2.85138512e+01 2.87660046e+01 2.94275951e+01 2.93447933e+01 2.92984962e+01 2.95244274e+01 2.96380711e+01 3.01116333e+01 3.05285625e+01 3.07481918e+01 3.05785160e+01 2.98241062e+01 3.07712936e+01 3.20058937e+01 3.13411598e+01 3.14950619e+01 3.23391991e+01 3.24456291e+01 3.19053421e+01 3.22119713e+01 3.26167183e+01 3.26369438e+01 3.24664421e+01 3.25787125e+01 3.28678360e+01 3.34544220e+01 3.35308838e+01 3.36641388e+01 3.39009209e+01 3.40761757e+01 3.42470131e+01 3.44323540e+01 3.47785301e+01 3.49342728e+01 3.49044952e+01 3.50434189e+01 3.49198074e+01 3.50551987e+01 3.56939964e+01 3.57604713e+01 3.57089729e+01 3.58722000e+01 3.58623199e+01 3.58377190e+01 3.61766052e+01 3.66200523e+01 3.68772354e+01 3.70168610e+01 3.67586441e+01 3.70954895e+01 3.76186752e+01 3.73746758e+01 3.76209335e+01 3.75678978e+01 3.75007744e+01 3.80786591e+01 3.81908798e+01 3.81391830e+01 3.81722565e+01 3.84007111e+01 3.81591606e+01 3.83213577e+01 3.89874229e+01 3.88648453e+01 3.87939606e+01 3.90297852e+01 3.91119194e+01 3.89806938e+01 3.88961792e+01 3.85279350e+01 3.48792534e+01 2.92943363e+01 2.93511944e+01 2.55785019e+02 4.16347351e+02 4.83152618e+01 2.56820965e+01 -3.21671783e+02 -1.67298996e+02 3.52145500e+01 6.12372017e+01 6.56279449e+01 5.44602242e+01 4.86482315e+01 4.67726517e+01 4.70194168e+01 5.10020218e+01 -1.60613098e+02 -3.56667557e+01 2.34033936e+03 -13435681. 20299972. -6.55823250e+06 -1.90993933e+03 -7.54764160e+02 -9.15332565e+01 -7.12440308e+02 -1.72064172e+03 1.53453675e+06 42231520. 85671848. -22628356. -15605513. 106922120. 2.16762402e+03 8.26772522e+02 -2.78632183e+01 1.50015717e+02 4.21651733e+02 1.35280045e+02 -1.62602844e+02 1.28708160e+02 1.05345566e+02 1.17168999e+02 1.40415054e+02 3.67193451e+02 2.91173248e+02 -1.12493645e+02 1.18759399e+02 6.82102585e+01 -9.87838840e+00 3.39752441e+02 4.62372246e+01 2.47007790e+01 1.73353073e+02 8.54232330e+01 5.05654755e+01 1.13663399e+02 6.87599106e+01 4.63747177e+01 7.31030655e+01 7.03125916e+01 4.33835068e+01 5.68878822e+01 7.26452026e+01 6.61198273e+01 -1.24046967e+02 1.39444214e+02 1.38588501e+02 -2.15609344e+02 -1.47490280e+02 8.44692612e+01 1.14854538e+02 1.34638412e+02 1.28581024e+02 1.26705910e+02 1.21274712e+02 1.20943794e+02 1.19563759e+02 1.19379700e+02 1.19313354e+02 1.17987045e+02 1.18207848e+02 1.16587662e+02 1.16492599e+02 1.16076378e+02 1.17812599e+02 1.17241890e+02 1.16223862e+02 1.18169617e+02 3.55155212e+02 2.22458633e+02 4.54038277e+01 4.56688766e+01 4.50027084e+01 4.48282433e+01 4.46914062e+01 4.49939804e+01 4.46827660e+01 4.48928413e+01 4.37831688e+01 4.34305878e+01 4.25684471e+01 4.23286247e+01 4.21805038e+01 4.23191490e+01 4.24761429e+01 4.24792023e+01 4.16785088e+01 4.19586678e+01 4.23174438e+01 4.20189018e+01 4.15152779e+01 4.20168953e+01 4.19996567e+01 4.18760452e+01 4.16559906e+01 4.12837639e+01 4.14964447e+01 4.12754326e+01 4.13514786e+01 4.13976517e+01 4.10746841e+01 4.08555450e+01 4.07048035e+01 4.06211395e+01 4.08136444e+01 4.08336983e+01 4.08884506e+01 4.06187553e+01 4.02322235e+01 4.01448364e+01 3.99808235e+01 4.02465782e+01 3.89207687e+01 3.90220909e+01 3.90234184e+01 3.98917580e+01 3.97060966e+01 3.90117798e+01 3.83469849e+01 3.89348488e+01 3.93415527e+01 3.85579872e+01 3.81939964e+01 3.86051750e+01 3.91315956e+01 3.84572525e+01 3.81723976e+01 3.78788071e+01 3.77379570e+01 3.77492065e+01 3.76842537e+01 3.76069908e+01 3.74568672e+01 3.74015694e+01 3.73741913e+01 3.74891281e+01 3.69459839e+01 3.68776627e+01 3.68832817e+01 3.66327057e+01 3.64167824e+01 3.61111259e+01 3.58706169e+01 3.57755318e+01 3.54848442e+01 3.56935692e+01 3.54756775e+01 3.52347717e+01 3.50805397e+01 3.49450264e+01 3.49017525e+01 3.47971992e+01 3.45790100e+01 3.45090065e+01 3.44085503e+01 3.40432816e+01 3.38858795e+01 3.37771530e+01 3.35681763e+01 3.33648453e+01 3.31989861e+01 3.27580490e+01 3.25355682e+01 3.26664734e+01 3.24384804e+01 3.22363930e+01 3.20170975e+01 3.17788906e+01 3.16377449e+01 3.14873581e+01 3.12909107e+01 3.11969051e+01 3.09882221e+01 3.06302090e+01 3.05898495e+01 3.04721222e+01 3.01824417e+01 2.99344540e+01 2.97259617e+01 2.94036865e+01 2.92258511e+01 2.92332630e+01 2.90733318e+01 2.88295803e+01 2.86217384e+01 2.84218864e+01 2.82113228e+01 2.80245533e+01 2.78128586e+01 2.76130562e+01 2.73869610e+01 2.71324444e+01 2.69219360e+01 2.67112312e+01 2.65025635e+01 2.62314129e+01 2.60541897e+01 2.59366398e+01 2.57182312e+01 2.54581985e+01 2.52544193e+01 2.50236111e+01 2.48177853e+01 2.46118259e+01 2.43847332e+01 2.41953945e+01 2.40014515e+01 2.38219604e+01 2.36189709e+01 2.33614788e+01 2.31465778e+01 2.29223385e+01 2.26895199e+01 2.24577141e+01 2.22893066e+01 2.21452255e+01 2.18050003e+01 2.15481739e+01 2.13650246e+01 2.12608414e+01 2.09944324e+01 2.07087288e+01 2.04588013e+01 2.01953411e+01 1.98778095e+01 1.95676956e+01 1.93617878e+01 1.91063213e+01 1.87559185e+01 1.85091438e+01 1.83072815e+01 1.81730671e+01 1.79406528e+01 1.76705818e+01 1.73957310e+01 1.70276375e+01 1.68106232e+01 1.66951599e+01 1.64535732e+01 1.62196827e+01 1.59874439e+01 1.57403097e+01 1.55061188e+01 1.51526756e+01 1.49720678e+01 1.46808815e+01 1.45878935e+01 1.42723436e+01 1.37796812e+01 1.34192762e+01 1.33152218e+01 1.31431656e+01 1.29764318e+01 1.25396957e+01 1.22528467e+01 1.19126253e+01 1.17595882e+01 1.16326704e+01 1.14736423e+01 1.11900721e+01 1.08656559e+01 1.04052734e+01 1.02271423e+01 1.01459103e+01 9.83884144e+00 9.64224815e+00 9.45717239e+00 9.27943325e+00 9.04560375e+00 8.77692986e+00 8.37486458e+00 8.23866749e+00 7.97764874e+00 7.60381937e+00 7.09356594e+00 6.91527700e+00 6.61834335e+00 5.98714924e+00 5.86685562e+00 5.97935247e+00 5.98736191e+00 5.56846666e+00 5.03917360e+00 4.69377804e+00 4.23183537e+00 3.97037339e+00 3.62719893e+00 3.42855978e+00 3.51543283e+00 3.45431781e+00 3.02608252e+00 2.60199142e+00 2.28945661e+00 1.99524772e+00 1.95838523e+00 2.28729343e+00 1.70293939e+00 8.97551596e-01 1.00827861e+00 9.14840877e-01 2.67847329e-01 1.21908568e-01 -1.37645483e-01 -9.10049200e-01 -8.66366684e-01 -1.01160836e+00 -1.29175770e+00 -1.89066684e+00 -1.63620353e+00 -1.90829599e+00 -2.28764009e+00 -2.73939681e+00 -2.82409286e+00 -3.28787947e+00 -4.17947006e+00 -4.67683125e+00 -4.23388338e+00 -3.55493665e+00 -3.83782959e+00 -4.60984182e+00 -5.39561415e+00 -5.42587852e+00 -5.28314066e+00 -5.09118032e+00 -5.85848856e+00 -5.90046549e+00 -5.70002890e+00 -5.47193861e+00 -6.72802401e+00 -7.93929195e+00 -6.89471483e+00 -7.22802687e+00 -7.29895782e+00 -8.01389408e+00 -8.18049335e+00 -8.68786526e+00 -8.58603096e+00 -8.93348217e+00 -8.90836430e+00 -9.06990051e+00 -8.55187893e+00 -1.00386429e+01 1.49688644e+02 2.74124878e+02 -2.96579224e+02 -1.56671534e+01 2.80452240e+02 5.10051823e+00 3.00311327e+00 1.83760178e+00 8.58780146e-01 -2.37967865e+02 -2.60187958e+02 1.07068466e+02 2.89828369e+02 6.01551104e+00 3.45290256e+00 -2.04742002e+00 -2.46264755e+02 -2.17397598e+02 -1.45672150e+02 8.71711960e+01 2.98306244e+02 -2.70016632e+02 -1.59129658e+01 2.56887817e+02 -5.23271132e+00 -8.05215740e+00 -9.96669292e+00 -1.29585075e+01 -8.70129776e+00 -7.99863243e+00 -1.08417244e+01 -1.07843256e+01 -1.13552742e+01 -1.45908728e+01 -1.50392284e+01 -1.51237411e+01 -1.53373919e+01 -1.48233662e+01 -1.81429482e+01 -3.70464172e+02 -3.18722992e+01 3.17465057e+02 -1.36397381e+01 -2.11426201e+01 -2.36225491e+01 -2.05314522e+01 -1.90508289e+01 -1.24170818e+01 -6.91020584e+00 1.70482407e+01 8.65575623e+02 2.24622656e+03 -58943888. 10050929. 39429684. -211116608. -68663712. -1.92913257e+03 -6.78539886e+01 1.86394482e+03 -2.02631775e+03 -7.91483459e+02 -2.80696545e+01 1.93760433e+01 -7.50926392e+02 -1.91465698e+03 -39524472. 3952981. -20429162. 2.03764795e+03 -3.20528374e+01 -3.44768036e+02 -1.16572212e+02 -4.75953026e+01 -4.25211639e+01 -4.69937096e+01 -3.20847282e+01 -3.10040245e+01 -3.69794998e+01 -2.58793335e+02 6.07570038e+01 -4.34479141e+01 -3.66975861e+02 3.33851837e+02 1.72822525e+02 -3.52928619e+01 -3.18163242e+01 -3.23016815e+01 -3.19747181e+01 -3.18251781e+01 -3.14954243e+01 -3.13772812e+01 -3.19374485e+01 -3.17883759e+01 -3.18868103e+01 -3.22317924e+01 -3.23871040e+01 -3.25086441e+01 -3.26440430e+01 -3.25715981e+01 -3.27476997e+01 -3.29589424e+01 -3.31786232e+01 -3.34965439e+01 -3.35522804e+01 -3.37751579e+01 -3.40227852e+01 -3.40873604e+01 -3.40756531e+01 -3.45367813e+01 -3.46998482e+01 -3.44915771e+01 -3.41437035e+01 -3.41464462e+01 -3.49167252e+01 -3.53232765e+01 -3.53793144e+01 -3.55317917e+01 -3.56660385e+01 -3.56778183e+01 -3.59970322e+01 -3.67113228e+01 -3.65240440e+01 -3.64188766e+01 -3.69594498e+01 -3.66134033e+01 -3.68408546e+01 -3.73183479e+01 -3.73979530e+01 -3.75356941e+01 -3.75937767e+01 -3.73809090e+01 -3.80185852e+01 -3.87122040e+01 -3.83682098e+01 -3.83222504e+01 -3.91071701e+01 -3.93932915e+01 -3.84950676e+01 -3.92932205e+01 -3.98915482e+01 -3.92851906e+01 -3.91453323e+01 -3.91455460e+01 -3.90301056e+01 -3.90686417e+01 -3.97666702e+01 -3.96294785e+01 -3.97613907e+01 -3.96549988e+01 -4.00003891e+01 -4.01151314e+01 -4.04475365e+01 -4.08314247e+01 -4.03766022e+01 -4.03333817e+01 -4.01010361e+01 -4.06282196e+01 -4.06791420e+01 -3.95766449e+01 -3.96195488e+01 -4.19435081e+01 -4.21911736e+01 -4.15478058e+01 -4.11373787e+01 -4.12353401e+01 -4.10173302e+01 -4.10456696e+01 -4.19067192e+01 -4.23362923e+01 -4.19449387e+01 -4.22145996e+01 -4.18461533e+01 -4.18079262e+01 -4.18783684e+01 -4.11420326e+01 -4.13665733e+01 -4.41614609e+01 -4.40013885e+01 -4.23971214e+01 -4.20677299e+01 -4.12519951e+01 -4.13486137e+01 -4.22112350e+01 -4.08289948e+01 -4.07009430e+01 -4.40457420e+01 -4.54180374e+01 -4.45700607e+01 -4.34353027e+01 -4.40085831e+01 -4.42344322e+01 -4.35753212e+01 -4.31764412e+01 -4.31462631e+01 -4.30512390e+01 -4.31691551e+01 -4.33613243e+01 -4.34468918e+01 -4.35821571e+01 -4.36848297e+01 -4.37818413e+01 -4.35100288e+01 -4.31437225e+01 -4.25706749e+01 -4.22226181e+01 -4.25902138e+01 -4.33960648e+01 -4.33150520e+01 -4.24920540e+01 -4.19317360e+01 -4.23961945e+01 -3.88680916e+01 -4.48638954e+01 -4.95567207e+01 -4.42740440e+01 -4.44357910e+01 -4.22611580e+01 -4.12497139e+01 -3.98418312e+01 -4.02838173e+01 -4.32936707e+01 -4.59570236e+01 -4.64391098e+01 -4.50278511e+01 -4.33221779e+01 -4.30895271e+01 -4.32761688e+01 -4.32811050e+01 -4.25105247e+01 -4.26884537e+01 -4.23443756e+01 -4.28060532e+01 -4.20327644e+01 -2.73987961e+01 -2.29701767e+01 -4.15511627e+01 1.09902451e+02 2.03544266e+02 -1.13126122e+02 -9.61658783e+01 -5.05916481e+01 -1.80056036e+00 6.62097046e+02 1.67002246e+03 -59429016. 49697208. -1.84115576e+03 -7.95197571e+02 -1.17316238e+02 -1.17862854e+02 -1.17958382e+02 -1.17180962e+02 -1.18170135e+02 -1.20910614e+02 -1.17530098e+02 -1.15509872e+02 -1.17396172e+02 -1.16494583e+02 -1.18702049e+02 -1.18152885e+02 -1.17134567e+02 -1.17379143e+02 -3.06287720e+02 -6.19310379e+01 1.78648636e+02 -1.58090927e+02 3.23510925e+02 1.98158340e+01 -9.17100647e+02 -1.93424133e+02 -2.02785995e+02 -1.90827164e+02 -1.39173508e+02 -3.01005859e+02 -1.94012573e+02 -4.77550583e+01 -4.73817635e+01 6.77174072e+01 1.33611618e+02 -1.11809357e+02 -1.08095360e+02 -9.72745209e+01 -4.51486816e+01 4.73297150e+02 2.46388525e+03 -44941720. 0. 0. 0. 0. 0. 0. 0. 0. 0. -115607928. -115607928. -115607928. 0. 0. 0. 0. 5267423. 5267423. 5267423. 0. 0. -71735328. -23928980. -3406612. -4228635. 202364224. 2.47866525e+06 56524316. 56524316. 56524316. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.84576538e+09 2.84576538e+09 2.84576538e+09 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. -666764. -666764. -666764. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 827010048. 827010048. 827010048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.07369719e+05 24424656. -2.39277094e+05 -78548992. -111749376. 151267904. -21269158. 4.41671731e+09 2.20673447e+02 -1.63034760e+02 -1.14014429e+03 1.54054276e+02 7.88498108e+02 7.88498108e+02 -12231849. -268952864. -268952864. -138468800. 0. 0. 0. 0. -83195784. -83195784. -83195784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.37004093e+10 1.37004093e+10 1.37004093e+10 0. 0. 0. 0. 0. 0. 0. -34077768. -34077768. -34077768. 0. -10514144. -17545476. -2.79007550e+06 -25635526. -26739002. 1.02032019e+03 3.89515411e+02 -7.39746475e+01 -7.46735916e+01 -7.68372879e+01 -7.86006851e+01 -7.33606873e+01 -6.01756165e+02 -1.47772717e+03 -2.98586175e+06 -12729093. 63542612. 1.06678703e+05 -1.22569470e+03 -6.69753235e+02 -13349513. -22836150. -22664062. 6.36880798e+02 -5.30100393e+00 -6.89350464e+02 1.23553357e+03 4.98287048e+02 -6.07977333e+01 -6.18691101e+01 -6.13935738e+01 -6.19596443e+01 -6.11101875e+01 -5.73801689e+01 7.22831488e+00 -5.63033142e+02 -1.52012732e+03 4.13009229e+03 -62663220. -451043616. 0. 0. 3.07015898e+04 -1.37256934e+03 -7.50779602e+02 64374604. 68517808. 23372388. -78004272. -33526550. -10244756. 1.51712573e+03 6.14404663e+02 -3.73119850e+01 2.73566620e+02 1.62074280e+02 -4.36900949e+00 -4.16818714e+00 -3.83959866e+00 -3.64483118e+00 -3.57781005e+00 -3.46573400e+00 -3.89025474e+00 -4.01576424e+00 -3.48731065e+00 -2.75059533e+00 -2.29222679e+00 -1.82051599e+00 -1.22886217e+00 -1.36151385e+00 -1.86752987e+00 -1.13027930e+00 -8.29907000e-01 -4.44318026e-01 -8.16547930e-01 1.07745521e-01 6.90607950e-02 -1.80646729e+02 -3.18708771e+02 3.11135406e+02 1.84146881e+02 -8.12908709e-01 2.05187023e-01 6.29622340e-01 1.16956973e+00 -1.84530869e+02 -3.23088928e+02 3.25428223e+02 1.93957504e+02 1.41084182e+00 2.03749394e+00 2.87493777e+00 2.65070677e+00 2.53088379e+00 2.76169991e+00 3.15096068e+00 3.46202278e+00 3.69677591e+00 4.19655609e+00 4.21740103e+00 4.20055676e+00 4.16259289e+00 5.14205170e+00 5.74149990e+00 5.62766171e+00 5.16983271e+00 5.02941132e+00 5.54803038e+00 5.79766464e+00 1.94089270e+00 2.41495562e+00 1.13475475e+01 1.13584070e+01 6.50917292e+00 6.84263468e+00 6.99534035e+00 7.49726057e+00 7.75610304e+00 8.03595924e+00 8.08189964e+00 8.56540871e+00 8.93415928e+00 9.03764915e+00 9.04151535e+00 9.18316555e+00 9.38799858e+00 9.33167839e+00 9.81177807e+00 1.00038347e+01 9.82417965e+00 1.01491423e+01 1.04690132e+01 1.07221928e+01 1.11109152e+01 1.06753454e+01 1.09797421e+01 1.11382513e+01 1.16665726e+01 1.17835665e+01 1.19099350e+01 1.21243372e+01 1.24047108e+01 1.21566458e+01 1.25580349e+01 1.31549826e+01 1.29074402e+01 1.29466648e+01 1.35695238e+01 1.40063562e+01 1.35610085e+01 1.39710093e+01 1.44816542e+01 1.44886618e+01 1.43679571e+01 1.45654507e+01 1.47391129e+01 1.53491430e+01 1.56005602e+01 1.55603819e+01 1.53557205e+01 1.55118732e+01 1.59207239e+01 1.62972813e+01 1.64400940e+01 1.67928181e+01 1.70346336e+01 1.69119854e+01 1.67646046e+01 1.70118351e+01 1.73759899e+01 1.74062920e+01 1.74789906e+01 1.77304115e+01 1.81208363e+01 1.79227295e+01 1.80009842e+01 1.86805763e+01 1.91405182e+01 1.91626282e+01 1.90247669e+01 1.93746967e+01 1.96967545e+01 1.93454094e+01 1.94852543e+01 1.97247486e+01 1.98146954e+01 2.06236210e+01 2.05947113e+01 2.04962578e+01 2.03961563e+01 2.06988335e+01 2.08439274e+01 2.09957008e+01 2.13856506e+01 2.13807716e+01 2.13475819e+01 2.18435802e+01 2.21846657e+01 2.23473206e+01 2.18483791e+01 2.23587532e+01 2.22353973e+01 2.21392288e+01 2.22923603e+01 2.22012882e+01 2.21603355e+01 2.12524757e+01 1.77100277e+01 1.41376371e+01 1.59434910e+01 1.91710396e+01 2.31338272e+02 3.86390656e+02 3.00783215e+01 8.46143913e+00 2.13992906e+00 -3.10778900e+02 -1.73871506e+02 3.99962616e+01 -3.13270691e+02 9.20403957e+00 6.69730835e+01 -1.01447235e+03 -6.55823250e+06 -16958520. 12791272. -6.79396250e+04 -3.28821043e+09 1286979328. 0. 0. 0. 0. 0. 0. 1.30834039e+05 -5.28457129e+03 -2.30604565e+03 1.70111875e+06 2.75257871e+04 1.04385625e+04 -2.47194531e+03 8725150. 3.56173219e+05 2.93528719e+05 7204792. 1.61686758e+04 5.88054736e+03 -1.28408289e+03 2.45184912e+03 -3.08579163e+02 -1.76908850e+03 2.16780566e+03 2.00047932e+01 -1.26806847e+02 8.36442627e+02 4.51114258e+02 3.71893387e+01 -2.45420776e+02 2.81399811e+02 8.17815857e+01 4.18280640e+02 3.75017548e+02 5.15382080e+01 2.22252182e+02 4.39072662e+02 3.61731567e+02 -9.86434265e+02 8.13414062e+02 -2.03623238e+01 -1.54215491e+03 -5.62981934e+03 1.83804043e+04 2.32922109e+05 3.01157925e+06 6.93725450e+06 5031631. -21863326. -75404464. -35423736. -21104908. -99831448. 16442697. 37194280. 19366362. -14024411. -13602573. -16643721. -41303472. -39452952. 29793738. 1.98684851e+03 8.31286621e+02 1.14808388e+02 3.45793579e+02 2.07207825e+02 3.48982887e+01 3.55619812e+01 3.51373177e+01 3.47464027e+01 3.46165466e+01 3.42367363e+01 3.38229294e+01 3.32017899e+01 3.27072601e+01 3.26108589e+01 3.26111031e+01 3.29245987e+01 3.30238342e+01 3.25265198e+01 3.23683586e+01 3.30111809e+01 3.30242653e+01 3.29601784e+01 3.30795364e+01 3.33145409e+01 3.31825409e+01 3.28482170e+01 3.29362411e+01 3.31134605e+01 3.32687302e+01 3.35253067e+01 3.32758064e+01 3.31582069e+01 3.30868340e+01 3.26925659e+01 3.26886635e+01 3.30056381e+01 3.33528061e+01 3.33067284e+01 3.31276779e+01 3.30323143e+01 3.30452156e+01 3.36477890e+01 3.38019333e+01 3.27546425e+01 3.22150345e+01 3.27735634e+01 3.37192650e+01 3.35469589e+01 3.28614426e+01 3.24954300e+01 3.24950066e+01 3.29202652e+01 3.27990837e+01 3.26379242e+01 3.29787865e+01 3.27772751e+01 3.27165489e+01 3.27434769e+01 3.27526550e+01 3.26599083e+01 3.26877975e+01 3.26883354e+01 3.24812851e+01 3.25901527e+01 3.23723755e+01 3.25926781e+01 3.28705444e+01 3.23829117e+01 3.25859756e+01 3.28222618e+01 3.21716309e+01 3.22516899e+01 3.21212997e+01 3.21586952e+01 3.20770760e+01 3.23789673e+01 3.24901199e+01 3.19303017e+01 3.18885021e+01 3.22885666e+01 3.21968193e+01 3.19608784e+01 3.19892368e+01 3.19012051e+01 3.17664948e+01 3.19437752e+01 3.18696594e+01 3.18317184e+01 3.18665390e+01 3.18299427e+01 3.17933750e+01 3.16901093e+01 3.14265099e+01 3.13468533e+01 3.13746719e+01 3.12826271e+01 3.11624660e+01 3.12337494e+01 3.08748360e+01 3.08091259e+01 3.09998512e+01 3.08935738e+01 3.08582821e+01 3.06552639e+01 3.04294434e+01 3.05807400e+01 3.05943642e+01 3.04657860e+01 3.03179169e+01 3.02031746e+01 2.98851776e+01 2.97572250e+01 2.98169670e+01 2.97592773e+01 2.96896305e+01 2.96006451e+01 2.95044575e+01 2.93983536e+01 2.93160076e+01 2.92052040e+01 2.91436157e+01 2.90313797e+01 2.89197617e+01 2.88168755e+01 2.87271862e+01 2.86430321e+01 2.85167961e+01 2.84506550e+01 2.83934059e+01 2.82680187e+01 2.81240044e+01 2.79951077e+01 2.78775673e+01 2.77616138e+01 2.76564445e+01 2.75616322e+01 2.74637260e+01 2.73615742e+01 2.72288208e+01 2.71083965e+01 2.69909611e+01 2.68775101e+01 2.67548695e+01 2.66479435e+01 2.65700474e+01 2.64946766e+01 2.63961868e+01 2.62321110e+01 2.60790787e+01 2.59561005e+01 2.58290710e+01 2.56961212e+01 2.55558567e+01 2.54478683e+01 2.52821255e+01 2.51264267e+01 2.49635029e+01 2.49380455e+01 2.47720203e+01 2.45453930e+01 2.44207649e+01 2.43536110e+01 2.42884178e+01 2.41699829e+01 2.39915695e+01 2.38745556e+01 2.36926556e+01 2.35970993e+01 2.35649300e+01 2.34134808e+01 2.31995792e+01 2.30688190e+01 2.30775700e+01 2.29678574e+01 2.27350864e+01 2.24970016e+01 2.23352871e+01 2.23366356e+01 2.21225281e+01 2.17850780e+01 2.16296177e+01 2.15334988e+01 2.14350033e+01 2.13086910e+01 2.10844994e+01 2.09422359e+01 2.06486530e+01 2.05200005e+01 2.03391056e+01 2.01309624e+01 1.99083633e+01 1.98296967e+01 1.97602158e+01 1.96160679e+01 1.94939613e+01 1.91630001e+01 1.90211201e+01 1.87034035e+01 1.87337017e+01 1.85660858e+01 1.87188740e+01 1.86114578e+01 1.83049049e+01 1.79858952e+01 1.77053070e+01 1.76441364e+01 1.73990593e+01 1.72920818e+01 1.71793423e+01 1.70749302e+01 1.66689358e+01 1.63163662e+01 1.64762592e+01 1.62965946e+01 1.60776463e+01 1.55472221e+01 1.55535727e+01 1.56341677e+01 1.54833050e+01 1.53636637e+01 1.51353579e+01 1.48018293e+01 1.46472759e+01 1.42925959e+01 1.41875629e+01 1.40059261e+01 1.43169947e+01 1.36946297e+01 1.32092447e+01 1.35877943e+01 1.31549778e+01 1.26390257e+01 1.28179665e+01 1.23142767e+01 1.18753052e+01 1.18664980e+01 1.25909433e+01 1.24766903e+01 1.22057457e+01 1.18744240e+01 1.12884235e+01 1.11844912e+01 1.12286949e+01 1.13397789e+01 1.10969992e+01 1.12072754e+01 1.06663275e+01 1.07328777e+01 1.06949358e+01 1.02414465e+01 9.75706577e+00 9.67500973e+00 9.33740902e+00 9.06136513e+00 9.26072311e+00 9.03904057e+00 9.23546791e+00 9.19223785e+00 9.82645512e+00 9.41252327e+00 8.72203064e+00 9.02194309e+00 9.01608467e+00 9.96049213e+00 1.03770304e+01 9.14159393e+00 1.70292465e+02 2.98781891e+02 5.13360748e+01 4.89606705e+01 4.92693138e+01 5.59909134e+01 4.62471619e+01 7.31869324e+02 1.83942908e+03 -1.59024780e+03 9.08367844e+01 1.89662231e+03 -23122738. 14405515. -19734686. -39558160. -4.42443262e+03 -2.07320166e+03 3.45190491e+02 2.83890894e+03 11987811. 4707957. 45217728. -5.32257031e+03 -2.98631250e+03 -1.14201562e+03 1.41625580e+02 1.92183105e+03 -4.95306104e+03 1.62798865e+03 9.62789648e+03 12315628. -14723673. -20675858. 38457684. -66907044. -22299516. -264832592. -43710028. -11902365. -71351032. -11939257. 11385853. 13902528. -9.31626404e+02 -2.30793953e+01 2.99069489e+02 1.85537071e+01 1.89177515e+03 8424259. 1.66917975e+06 2.01748162e+06 43006188. 4308214. -81371176. 21135692. -8.97173340e+02 -1.92294238e+03 -1.06283844e+05 0. 0. 0. 0. 0. 220810304. 220810304. 220810304. 317480928. -4638865. 3.20085875e+06 70386928. 17422840. 7.57477750e+06 -1.05256421e+03 -4.42664368e+02 -1.85820770e+01 -1.86734486e+01 5.12692566e+01 -2.18604126e+02 -4.49075043e+02 1.20383179e+00 3.47186340e+02 -1.19249516e+01 -3.63795776e+02 3.50250183e+02 1.91523865e+02 -1.67251377e+01 -1.24731684e+01 -1.27444906e+01 -1.29805803e+01 -1.23838844e+01 -1.21997814e+01 -1.22719202e+01 -1.16261444e+01 -1.22186699e+01 -1.26886349e+01 -1.21734867e+01 -1.20028715e+01 -1.23855038e+01 -1.34501762e+01 -1.38497610e+01 -1.32701044e+01 -1.37558680e+01 -1.37325096e+01 -1.36293850e+01 -1.40832376e+01 -1.45866108e+01 -1.46156082e+01 -1.45042181e+01 -1.48828993e+01 -1.52970047e+01 -1.56074953e+01 -1.55711880e+01 -1.53302364e+01 -1.56194801e+01 -1.61372414e+01 -1.65494862e+01 -1.68260517e+01 -1.64641304e+01 -1.57198610e+01 -1.59080000e+01 -1.68511906e+01 -1.70049305e+01 -1.70596142e+01 -1.75866261e+01 -1.77368183e+01 -1.74700642e+01 -1.78865871e+01 -1.82944145e+01 -1.85935898e+01 -1.87102737e+01 -1.85510960e+01 -1.87409000e+01 -1.91986332e+01 -1.93620358e+01 -1.92731800e+01 -1.94894104e+01 -1.95485592e+01 -1.93549576e+01 -1.95457916e+01 -2.00668201e+01 -2.03004990e+01 -2.04230213e+01 -2.12733135e+01 -2.25137787e+01 -2.10324306e+01 -2.22015324e+01 -2.31894073e+01 -2.17659149e+01 -2.15777359e+01 -2.18583927e+01 -2.22720203e+01 -2.24480152e+01 -2.22314224e+01 -2.23592339e+01 -2.22509136e+01 -2.25569973e+01 -2.30479527e+01 -2.30856380e+01 -2.35132103e+01 -2.35927238e+01 -2.32169094e+01 -2.31549244e+01 -2.32439423e+01 -2.37075539e+01 -2.39464664e+01 -2.27485123e+01 -2.31986160e+01 -2.54480419e+01 -2.50676918e+01 -2.41770897e+01 -2.40074139e+01 -2.49592190e+01 -2.47596722e+01 -2.46526814e+01 -2.53487415e+01 -2.55764160e+01 -2.56877956e+01 -2.59884033e+01 -2.55702209e+01 -2.60589619e+01 -2.64881210e+01 -2.55507469e+01 -2.56725368e+01 -2.70032578e+01 -2.75436134e+01 -2.65794563e+01 -2.71850929e+01 -2.61942692e+01 -2.63064156e+01 -2.64776115e+01 -2.49442806e+01 -2.53002758e+01 -2.95190086e+01 -3.04479904e+01 -2.83085918e+01 -2.77054405e+01 -2.74687176e+01 -2.77623177e+01 -2.78581448e+01 -2.85503712e+01 -2.84509983e+01 -2.82832375e+01 -2.82404881e+01 -2.80594063e+01 -2.84169788e+01 -2.87052536e+01 -2.91311226e+01 -2.91779060e+01 -2.92584629e+01 -2.90581093e+01 -2.90230064e+01 -2.81433220e+01 -2.85620842e+01 -2.94269257e+01 -2.93130341e+01 -2.81141624e+01 -2.71567497e+01 -2.68632412e+01 -2.23171782e+00 -2.04261475e+01 -6.30690308e+01 -4.42984238e+01 -3.09313469e+01 -2.97878494e+01 -2.69383450e+01 -2.88008881e+01 -3.47566757e+01 -9.21301651e+00 -1.93742256e+01 -5.63158379e+01 -4.21409111e+01 -3.23049889e+01 -3.08815727e+01 -3.04234657e+01 -3.01544838e+01 -3.01989059e+01 -3.02045135e+01 -2.90292511e+01 -1.41191015e+01 -1.47476130e+01 1.65665527e+02 3.30993835e+02 -3.64636688e+02 6.17842734e-01 6.44303833e+02 10024523. -2.44863016e+05 2.15142844e+05 2146934. -58086164. 39575756. 0. 0. -103955936. -222783152. 15557502. -21983256. 8456586. -34927728. 25890376. -26664872. -8.03527750e+06 -17299162. -7.59685974e+02 -7.00985947e+01 5.84635864e+02 13938259. 107401880. -33064630. -1.45431079e+03 -1.47726166e+02 1.05703467e+03 -9.65457812e+04 -44564748. -9351756. 289626656. -1.60200650e+06 -2.62890781e+05 -2.98479562e+05 -8.15493750e+06 -2.01004626e+03 -8.57117981e+02 -1.64862686e+02 -1.64160065e+02 3.78464447e+02 1.10174390e+03 81256752. 822987520. -5735278. 2.28421641e+04 1496791424. 11049033. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -115607928. -115607928. -115607928. 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. 0. 0. 0. 0. 0. 0. 0. 2.84576538e+09 2.84576538e+09 2.84576538e+09 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. -666764. -666764. 68852944. 90862584. 90862584. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 413505024. 413505024. 413505024. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2016075008. 2016075008. 2016075008. 170807072. -15098876. -15098876. -6.11592450e+06 -134476432. -134476432. -69234400. 0. 0. 0. 0. -83195784. -83195784. -83195784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.37004093e+10 1.37004093e+10 1.37004093e+10 0. 0. 0. 0. 0. 0. 0. -34077768. -34077768. -34077768. 0. 0. 0. 0. 0. 0. 25364174. 19846232. 5.33365150e+06 -5.25354150e+06 49221932. 7.20719050e+06 -4158076. 61596048. -29585664. 0. 0. 0. 62839560. 62839560. 62839560. 0. 0. 0. 87957592. 87957592. 87957592. -20787226. 20504132. -6147997. -9263180. 18891632. -24703874. -16713144. -84602568. 9.84972168e+03 -3.40544025e+06 227931424. -451043616. -451043616. -451043616. 0. 0. 181617968. 181617968. 181617968. 0. 0. 0. 0. 0. 0. -20934184. -7.73959450e+06 -25146050. 6.77502563e+02 2.98876160e+02 -4.52314301e+01 -4.47393951e+01 -4.38425713e+01 -4.34705353e+01 -4.47435722e+01 -4.46938095e+01 -4.52886925e+01 -4.51417389e+01 -4.40136185e+01 -4.32230759e+01 -4.24148788e+01 -4.14837379e+01 -3.86230431e+01 -3.94411964e+01 -3.95496597e+01 -3.83093987e+01 -3.71861725e+01 -3.78151474e+01 -3.93428917e+01 -3.81506195e+01 -3.60175781e+01 -4.50463562e+02 -9.96929810e+02 7.85921814e+02 3.45885590e+02 -3.52693596e+01 -3.42136421e+01 -3.33777046e+01 -3.17410545e+01 -4.56110565e+02 -1.00507825e+03 8.38606079e+02 3.71123810e+02 -3.51464615e+01 -3.34228439e+01 -2.82925644e+01 -2.90447769e+01 -2.90025101e+01 -2.84491177e+01 -2.74862328e+01 -2.67919292e+01 -2.67570820e+01 -2.63971138e+01 -2.70684147e+01 -2.83014240e+01 -2.84194508e+01 -2.52096977e+01 -2.32090492e+01 -2.27204533e+01 -2.44076786e+01 -2.53187675e+01 -2.33888283e+01 -2.24804058e+01 -3.66627731e+01 -3.57226562e+01 -5.40075684e+00 -5.26642704e+00 -2.07722111e+01 -1.88544159e+01 -1.87549515e+01 -1.94021969e+01 -1.90088711e+01 -1.74170208e+01 -1.57822256e+01 -1.48002720e+01 -1.53786783e+01 -1.50828762e+01 -1.46826277e+01 -1.40649605e+01 -1.34083233e+01 -1.45671663e+01 -1.26181383e+01 -1.23057108e+01 -1.23201313e+01 -1.02285995e+01 -1.06065807e+01 -9.24287128e+00 -7.70241499e+00 -8.17469120e+00 -7.09490490e+00 -6.98455381e+00 -6.56153202e+00 -6.80312204e+00 -5.70031977e+00 -4.84283972e+00 -4.98700762e+00 -6.44738865e+00 -4.36411572e+00 -2.70572019e+00 -4.47439241e+00 -3.31814933e+00 2.06632778e-01 2.33341619e-01 -2.68670535e+00 -1.64410377e+00 1.03245234e+00 1.20983315e+00 1.61623645e+00 1.96772385e+00 2.36492419e+00 3.71264076e+00 4.99072409e+00 4.77750778e+00 4.01442146e+00 4.33356476e+00 5.36795282e+00 6.60069466e+00 7.04765224e+00 8.28660774e+00 8.90895462e+00 8.51959038e+00 8.44585705e+00 7.52693892e+00 8.12261486e+00 1.05049343e+01 1.09341030e+01 1.16205215e+01 1.31068010e+01 1.13105946e+01 1.13206997e+01 1.36183519e+01 1.49838753e+01 1.53046923e+01 1.50323219e+01 1.66311893e+01 1.78699226e+01 1.59219904e+01 1.67331657e+01 1.71149940e+01 1.67769051e+01 2.01466923e+01 2.02207184e+01 1.93343983e+01 1.92185917e+01 2.02948093e+01 2.06347198e+01 2.09687538e+01 2.38217239e+01 2.31223068e+01 2.26186619e+01 2.45001411e+01 2.54548607e+01 2.57146950e+01 2.41831951e+01 2.69540863e+01 2.66850796e+01 2.59486809e+01 2.75990391e+01 2.72566586e+01 2.74948235e+01 2.83387833e+01 2.88120918e+01 2.91547565e+01 2.96433964e+01 2.93565941e+01 2.85721607e+01 2.62264481e+01 1.72838593e+01 -3.91573381e+00 -9.69700432e+00 -3.42059231e+00 5.32974052e+00 6.43768127e+02 3.83839453e+03 -22825018. 365558432. 365558432. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.24441250e+05 -1.24441250e+05 -1.24441250e+05 0. -20913630. -20913630. -20913630. 0. 0. 0. 0. 3.38632575e+06 35442572. 35442572. 81324912. -49938220. -33809280. -7.36222950e+06 7.96469531e+03 -8.58625234e+04 1.38130078e+04 9.01472107e+02 -7.59350357e+01 -3.82745056e+02 2.58013696e+03 -2.68209629e+04 2.03430438e+05 8.81154141e+04 -1.61054922e+05 3.44566602e+04 6.76877250e+05 2.40620750e+05 23148164. -7.99474250e+06 1.12205662e+06 1.12205662e+06 82945920. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 305395488. 20144728. -91475640. 9.84107788e+02 4.51022339e+02 7.72898331e+01 8.06920700e+01 7.94553452e+01 7.81508713e+01 7.71956863e+01 7.57801819e+01 7.44654922e+01 7.33560791e+01 7.24279556e+01 7.16682968e+01 7.12190628e+01 7.18756714e+01 7.24676819e+01 7.26264954e+01 7.26175308e+01 7.35821762e+01 7.37376404e+01 7.38003006e+01 7.40004578e+01 7.50841675e+01 7.61217957e+01 7.52997055e+01 7.53873825e+01 7.57383194e+01 7.60130768e+01 7.64498138e+01 7.61767502e+01 7.64353638e+01 7.69443130e+01 7.59084778e+01 7.62171936e+01 7.66135406e+01 7.75957336e+01 7.76383972e+01 7.73964157e+01 7.76068115e+01 7.83955536e+01 8.00693359e+01 8.09790878e+01 7.86152878e+01 7.70618744e+01 7.88839111e+01 8.16287003e+01 8.22374649e+01 8.01428757e+01 7.85088120e+01 7.85146408e+01 7.98857880e+01 7.90286636e+01 7.87256699e+01 7.99991837e+01 8.00378876e+01 8.07058716e+01 8.12075958e+01 8.12590561e+01 8.10977631e+01 8.13370667e+01 8.15273819e+01 8.13650589e+01 8.11377487e+01 8.06883316e+01 8.15868454e+01 8.31434250e+01 8.14298401e+01 8.29954758e+01 8.43577347e+01 8.20701065e+01 8.27095108e+01 8.32751465e+01 8.35849533e+01 8.19510345e+01 8.30778275e+01 8.42725525e+01 8.33020630e+01 8.30167160e+01 8.42553024e+01 8.40176392e+01 8.35663071e+01 8.44506378e+01 8.42630692e+01 8.43547211e+01 8.48962402e+01 8.51841507e+01 8.53154984e+01 8.57509232e+01 8.61948090e+01 8.61097488e+01 8.63318710e+01 8.54545288e+01 8.54873276e+01 8.57532578e+01 8.53250275e+01 8.53300095e+01 8.55722275e+01 8.52559738e+01 8.51768951e+01 8.58047714e+01 8.56512680e+01 8.60863800e+01 8.54930878e+01 8.51176758e+01 8.61318130e+01 8.63916016e+01 8.61710358e+01 8.60830917e+01 8.61442261e+01 8.57495880e+01 8.55466232e+01 8.56373749e+01 8.56665649e+01 8.56968994e+01 8.57154007e+01 8.57439346e+01 8.57017136e+01 8.56176987e+01 8.55769196e+01 8.58829269e+01 8.59394226e+01 8.59062576e+01 8.58518906e+01 8.58194885e+01 8.59089050e+01 8.58293610e+01 8.59440002e+01 8.59451370e+01 8.57865601e+01 8.55528336e+01 8.54348907e+01 8.53582687e+01 8.53105240e+01 8.52571487e+01 8.51891403e+01 8.48800583e+01 8.45388412e+01 8.41089630e+01 8.39751205e+01 8.38557510e+01 8.37651062e+01 8.36466675e+01 8.35634918e+01 8.35275497e+01 8.33777542e+01 8.33050385e+01 8.32215729e+01 8.31292038e+01 8.29869232e+01 8.27869263e+01 8.26921844e+01 8.25166931e+01 8.24109497e+01 8.21921310e+01 8.20368042e+01 8.17742615e+01 8.20908051e+01 8.21397552e+01 8.15881348e+01 8.21018524e+01 8.22426605e+01 8.20839081e+01 8.19314957e+01 8.16399612e+01 8.14393082e+01 8.12318420e+01 8.11287231e+01 8.10768509e+01 8.08767776e+01 8.05547638e+01 8.03474808e+01 8.02820892e+01 8.00149307e+01 7.97586060e+01 7.93434601e+01 7.92020950e+01 7.90250320e+01 7.89685898e+01 7.86977921e+01 7.86674500e+01 7.83977966e+01 7.82298965e+01 7.77975540e+01 7.78469772e+01 7.74889526e+01 7.72266998e+01 7.69732056e+01 7.63848038e+01 7.61863708e+01 7.57623138e+01 7.61514359e+01 7.60636215e+01 7.59990692e+01 7.54576950e+01 7.48426437e+01 7.45857925e+01 7.48805695e+01 7.46450043e+01 7.41085205e+01 7.35468063e+01 7.35945740e+01 7.32259293e+01 7.30604630e+01 7.28874283e+01 7.29093094e+01 7.22166367e+01 7.16779251e+01 7.15564117e+01 7.13194122e+01 7.05304947e+01 7.00624390e+01 7.04274139e+01 7.04053802e+01 6.92906418e+01 6.91717987e+01 6.98862610e+01 7.07221909e+01 7.00235367e+01 6.87884369e+01 6.82781830e+01 6.78986359e+01 6.74067001e+01 6.71651535e+01 6.74338760e+01 6.68032455e+01 6.71272736e+01 6.57977371e+01 6.35738716e+01 6.71701965e+01 6.56379166e+01 6.38104439e+01 6.46774216e+01 6.42119980e+01 6.21470184e+01 6.22956009e+01 6.46545410e+01 6.42887955e+01 6.50009308e+01 6.48949280e+01 6.34769859e+01 6.18347855e+01 6.27407150e+01 6.24565964e+01 6.20823402e+01 6.22563095e+01 6.17635002e+01 6.14423599e+01 6.22807045e+01 6.11125031e+01 5.96816559e+01 6.01696777e+01 5.92711258e+01 5.86834602e+01 5.89850998e+01 5.83850517e+01 6.04896660e+01 6.19734764e+01 6.32134972e+01 6.14180183e+01 5.79571953e+01 5.93673058e+01 5.95784302e+01 6.07528915e+01 6.20643578e+01 6.01444359e+01 4.33482300e+02 9.58003296e+02 -200468768. -14770068. 20946910. 1.88610912e+06 6.42720312e+05 21349338. -186212848. 34441660. 34441660. 34441660. 0. 0. 0. 0. -88268144. 3.82991575e+06 3.82991575e+06 -34977040. 0. 0. 0. -81082712. 57678516. -1.21039131e+04 6.99405650e+06 -61604996. -185440256. -185440256. -185440256. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -189898464. -189898464. 177319392. -27032950. -27032950. 0. 0. 0. 0. 0. 0. 0. 41697316. 41697316. 41697316. 0. 0. 0. 0. 0. 110405152. 110405152. 110405152. 0. 0. 0. 0. 0. 0. 12185555. 2.67072650e+06 -12652946. -4.81303950e+06 1.33047485e+03 2.17989853e+02 -2.44896881e+02 -3.83721054e-01 6.99219322e+00 6.58529472e+00 7.16097498e+00 7.30943203e+00 6.77343893e+00 6.27141380e+00 5.74603701e+00 6.09814310e+00 6.23046684e+00 6.87922525e+00 6.60079241e+00 6.23929739e+00 7.44093418e+00 6.11193371e+00 5.51808119e+00 6.03341818e+00 5.34315777e+00 4.30431175e+00 1.69251800e+00 5.11000276e-01 2.16956067e+00 1.83383191e+00 7.21837521e-01 1.10598385e+00 4.84383106e-03 -1.59623194e+00 -1.76913595e+00 -1.75239694e+00 -2.65884423e+00 -3.47415709e+00 -4.70372200e+00 -4.49912119e+00 -3.71224523e+00 -4.19740391e+00 -5.59871674e+00 -7.52818918e+00 -8.73953056e+00 -7.15947866e+00 -2.96544552e+00 -3.22263169e+00 -7.67686319e+00 -8.66341877e+00 -9.10407639e+00 -1.10147114e+01 -1.10167656e+01 -9.37466812e+00 -1.09523287e+01 -1.34833469e+01 -1.47862740e+01 -1.42053509e+01 -1.27156210e+01 -1.26452007e+01 -1.55320883e+01 -1.75401745e+01 -1.60699482e+01 -1.64059601e+01 -1.64761047e+01 -1.56943598e+01 -1.67014046e+01 -1.78624363e+01 -1.87071648e+01 -1.99019623e+01 -2.05356903e+01 -2.39354630e+01 -2.34217911e+01 -2.73443165e+01 -2.91316948e+01 -2.43154984e+01 -2.31403122e+01 -2.42290134e+01 -2.54112568e+01 -2.54620361e+01 -2.51450939e+01 -2.53969059e+01 -2.64925594e+01 -2.78490067e+01 -2.88163815e+01 -2.86045990e+01 -3.02406330e+01 -2.97584324e+01 -2.87551441e+01 -2.93533287e+01 -3.01636028e+01 -3.05525036e+01 -3.14414196e+01 -2.80482655e+01 -3.04969025e+01 -3.54109116e+01 -3.40967484e+01 -3.13110428e+01 -3.10453815e+01 -3.68313522e+01 -3.65307121e+01 -3.42029572e+01 -3.70260963e+01 -3.72093048e+01 -3.80129929e+01 -3.83047447e+01 -3.80912209e+01 -3.98549843e+01 -4.01075287e+01 -3.85297241e+01 -3.84420013e+01 -3.99120255e+01 -4.11471977e+01 -4.08365326e+01 -3.97048683e+01 -3.87798386e+01 -4.11366844e+01 -4.32725372e+01 -3.86485481e+01 -3.93601418e+01 -5.23103523e+01 -5.41715546e+01 -4.66754723e+01 -4.61442947e+01 -4.47100449e+01 -4.59765701e+01 -4.71205711e+01 -4.86674423e+01 -4.97480774e+01 -4.87918129e+01 -4.94769821e+01 -4.94895210e+01 -5.04269485e+01 -4.99985542e+01 -5.05427170e+01 -5.10409164e+01 -5.08925705e+01 -5.11639214e+01 -5.22233467e+01 -5.10786285e+01 -5.22150993e+01 -5.32823219e+01 -5.31657219e+01 -4.87687988e+01 -4.32525139e+01 -4.27976990e+01 4.25811920e+01 -3.41036224e+01 -1.82972137e+02 -1.05833824e+02 -6.26632423e+01 -5.49444618e+01 -4.19562302e+01 -5.34904175e+01 -7.03846970e+01 1.31728153e+01 -2.51165924e+01 -1.55712357e+02 -1.02492195e+02 -6.79526901e+01 -6.06757622e+01 -5.90889282e+01 -5.83275490e+01 -5.95711746e+01 -5.90476189e+01 -5.66241913e+01 -1.22815695e+01 -1.28688707e+01 5.70885620e+02 1.45224109e+03 -6.45025635e+02 -1.38390137e+03 -3.27780898e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -84203840. -84203840. -84203840. 0. 0. 0. 60923704. 60923704. 60923704. 0. 0. 0. 0. 0. 0. 0. 0. -11231910. -26436280. -14682468. -2.62304425e+06 -6.18916750e+06 12952885. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -57803964. -57803964. -57803964. 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. 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. 0. 0. 0. 0. 0. 0. 0. -333382. -333382. -35197244. 90862584. 90862584. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_7.xml ================================================ 16 1024
f
498627904. 2.41588745e+02 5.92198944e+01 5.90848389e+01 5.92807770e+01 5.79948349e+01 5.66465187e+01 5.57279167e+01 5.69209290e+01 5.86400909e+01 5.69737587e+01 5.67713623e+01 5.68107910e+01 5.58918343e+01 5.47810936e+01 5.28905334e+01 5.29704056e+01 5.13272705e+01 5.00665436e+01 5.02461128e+01 5.05456009e+01 4.98336906e+01 4.86147728e+01 4.77962799e+01 4.70892715e+01 4.66116829e+01 4.65550385e+01 4.59910469e+01 4.50324402e+01 4.38789330e+01 4.34917679e+01 4.29626694e+01 4.10706978e+01 4.11935692e+01 4.08542824e+01 4.10242691e+01 4.10540924e+01 4.04658241e+01 3.97344360e+01 3.94233017e+01 3.86280136e+01 3.73208923e+01 3.64139862e+01 3.62406654e+01 3.61791916e+01 3.48244247e+01 3.55552330e+01 3.41890030e+01 3.27713737e+01 3.27497253e+01 3.28378143e+01 3.18889961e+01 3.10577564e+01 3.03442230e+01 2.89279881e+01 2.89092751e+01 2.94389191e+01 2.90093842e+01 2.85799961e+01 2.90512867e+01 2.88822021e+01 2.75046387e+01 2.53393803e+01 2.46700859e+01 2.30315628e+01 2.33881073e+01 2.26605816e+01 2.08106251e+01 2.01210575e+01 2.03338165e+01 1.93901081e+01 1.91250210e+01 1.85585194e+01 1.89785423e+01 1.82925816e+01 1.89370518e+01 1.91105118e+01 1.72210941e+01 1.56445189e+01 1.40186005e+01 1.45547686e+01 1.36918259e+01 1.26562662e+01 9.62047005e+00 8.10994816e+00 2.32663288e+01 -2.14831123e+01 2.20784283e+01 -5.83151794e+02 -1.77710010e+03 9.95683789e+03 -1.15692688e+06 631358784. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -69586696. -10739157. -1.17796562e+05 -7.68343384e+02 -3.35646881e+02 1.05685730e+01 1.20289874e+00 -1.27404699e+01 -7.87353363e+01 -8.83537521e+01 -4.30294838e+01 -1.51111536e+01 6.98989058e+00 -5.72426701e+00 -9.15172291e+00 -9.53257656e+00 -1.03865042e+01 -1.10469398e+01 -1.20230865e+01 -1.35833921e+01 -1.37467670e+01 -1.53632174e+01 -1.56322708e+01 -1.63339214e+01 -1.64457474e+01 -7.79566622e+00 3.92904639e+00 7.53420305e+00 -1.56288233e+01 -4.09917641e+01 -3.92011871e+01 -3.82998466e+01 -4.28730621e+01 -5.02815857e+01 -4.55268478e+01 -3.65036621e+01 -2.22583237e+01 -1.14573002e+01 -9.66586399e+00 -7.05900526e+00 -4.90430689e+00 -1.48837376e+01 -2.22320156e+01 -2.32019157e+01 -2.93720169e+01 -3.33702736e+01 -4.65599518e+01 -5.08807640e+01 -4.36541710e+01 -3.64193268e+01 -3.28168335e+01 -3.20724030e+01 -3.29848137e+01 -3.42987976e+01 -3.51029549e+01 -3.71973763e+01 -3.87152634e+01 -4.02729568e+01 -4.01087723e+01 -4.02943993e+01 -3.90528336e+01 -3.44693108e+01 -3.16118374e+01 -3.25376205e+01 -3.27709732e+01 -3.23382339e+01 -3.41835747e+01 -3.64070473e+01 -3.93919945e+01 -4.10978546e+01 -4.24998245e+01 -4.38711929e+01 -4.45320282e+01 -4.49071503e+01 -4.57483292e+01 -4.63179474e+01 -4.77022934e+01 -4.82908211e+01 -4.86814842e+01 -4.86112289e+01 -4.89110489e+01 -4.93358307e+01 -4.96674652e+01 -5.03263664e+01 -5.10101166e+01 -5.15696106e+01 -5.19523849e+01 -5.25532875e+01 -5.32070236e+01 -5.36179237e+01 -5.41556244e+01 -5.45316086e+01 -5.49491501e+01 -5.59661674e+01 -5.67665901e+01 -5.75718994e+01 -5.74961319e+01 -5.78391953e+01 -5.80610619e+01 -5.84404640e+01 -5.94385300e+01 -6.00525093e+01 -6.09001999e+01 -6.10541840e+01 -6.12297401e+01 -6.13703575e+01 -6.18854790e+01 -6.24330978e+01 -6.29745331e+01 -6.39303932e+01 -6.44436417e+01 -6.50142212e+01 -6.55230560e+01 -6.59379120e+01 -6.62714157e+01 -6.65604858e+01 -6.69388046e+01 -6.74593582e+01 -6.78064041e+01 -6.83063431e+01 -6.89401550e+01 -6.95362396e+01 -7.01163559e+01 -7.04306870e+01 -7.06509781e+01 -7.10842743e+01 -7.15050507e+01 -7.20752563e+01 -7.25723724e+01 -7.30880966e+01 -7.34863434e+01 -7.39473267e+01 -7.43516541e+01 -7.47541122e+01 -7.51081390e+01 -7.55006714e+01 -7.59008713e+01 -7.63278885e+01 -7.66787643e+01 -7.70969009e+01 -7.75170670e+01 -7.79119797e+01 -7.82906799e+01 -7.86606293e+01 -7.91153641e+01 -7.95352554e+01 -7.99282074e+01 -8.02989502e+01 -8.06549530e+01 -8.09912720e+01 -8.13694839e+01 -8.17401581e+01 -8.21323395e+01 -8.25048599e+01 -8.29234619e+01 -8.33474884e+01 -8.37639160e+01 -8.41247025e+01 -8.44824600e+01 -8.47717667e+01 -8.51969604e+01 -8.54724274e+01 -8.57972870e+01 -8.61229324e+01 -8.64365005e+01 -8.67119370e+01 -8.69839859e+01 -8.73242950e+01 -8.75503464e+01 -8.78105621e+01 -8.81623459e+01 -8.85264893e+01 -8.88281097e+01 -8.92223892e+01 -8.94846954e+01 -8.97265549e+01 -8.99277573e+01 -9.02937775e+01 -9.07026520e+01 -9.09331970e+01 -9.12528000e+01 -9.15833511e+01 -9.17408295e+01 -9.16772614e+01 -9.19909744e+01 -9.22506027e+01 -9.27857132e+01 -9.31513290e+01 -9.31921310e+01 -9.32644806e+01 -9.37228317e+01 -9.39578629e+01 -9.38539886e+01 -9.41647949e+01 -9.43797455e+01 -9.45077057e+01 -9.47379379e+01 -9.51605301e+01 -9.53309860e+01 -9.53005676e+01 -9.54072800e+01 -9.59012146e+01 -9.57886200e+01 -9.57093964e+01 -9.57211761e+01 -9.61059494e+01 -9.67191772e+01 -9.71251907e+01 -9.73588486e+01 -9.75651932e+01 -9.80237198e+01 -9.85454330e+01 -9.87211151e+01 -9.82304153e+01 -9.80739136e+01 -9.78915329e+01 -9.85357895e+01 -9.89310913e+01 -9.88176270e+01 -9.82462463e+01 -9.88597870e+01 -9.92027740e+01 -9.93990326e+01 -9.85659256e+01 -9.93168793e+01 -1.00034401e+02 -1.01321030e+02 -1.01308006e+02 -1.00502991e+02 -1.00416176e+02 -1.00355705e+02 -1.00648598e+02 -1.00529488e+02 -1.01097244e+02 -1.01190216e+02 -1.01049507e+02 -1.00845840e+02 -1.00549843e+02 -1.00019943e+02 -1.00785866e+02 -1.01592506e+02 -1.01931953e+02 -1.01377815e+02 -1.00814400e+02 -1.01962280e+02 -1.03017899e+02 -1.02317528e+02 -1.01975174e+02 -1.01172356e+02 -1.01735397e+02 -1.02464516e+02 -1.03160492e+02 -1.02236244e+02 -1.01899681e+02 -1.01890945e+02 -1.01865479e+02 -1.02126251e+02 -1.02435280e+02 -1.02560059e+02 -1.01241783e+02 -1.00478523e+02 -1.00402054e+02 -1.00174034e+02 -1.00419250e+02 -1.00182777e+02 -1.00558311e+02 -1.00657288e+02 -1.01528481e+02 -1.02017151e+02 -1.01263802e+02 -1.00693657e+02 -1.00946632e+02 -1.00989822e+02 -1.00950783e+02 -1.00310974e+02 -9.98863144e+01 -1.00222626e+02 -9.93400726e+01 -9.94740524e+01 -9.94321976e+01 -9.91210251e+01 -9.92660675e+01 -9.94449234e+01 -9.91387329e+01 -9.93764801e+01 -9.97194366e+01 -1.00949356e+02 -1.00408539e+02 -1.00344345e+02 -9.87028122e+01 -9.79820633e+01 -9.77215958e+01 -9.82746353e+01 -9.77463074e+01 -9.86185074e+01 -9.93725128e+01 -9.94219818e+01 -9.80685120e+01 -9.80243454e+01 -9.80933762e+01 -9.66507568e+01 -9.62327271e+01 -9.50482864e+01 -9.67913818e+01 -9.63915100e+01 -9.70984802e+01 -9.68798599e+01 -9.66016006e+01 -9.61091995e+01 -9.47688141e+01 -9.54664841e+01 -9.46264801e+01 -9.36605530e+01 -9.29383545e+01 -9.43493271e+01 -9.36168137e+01 -9.40668106e+01 -9.33261032e+01 -9.44258347e+01 -9.37375183e+01 -9.19947739e+01 -9.16794739e+01 -9.11280060e+01 -9.21079865e+01 -9.18942871e+01 -9.29199600e+01 -9.14134598e+01 -9.04920883e+01 -9.02646332e+01 -9.10918198e+01 -9.03389435e+01 -8.96112823e+01 -8.79503250e+01 -8.68146286e+01 -8.69657440e+01 -8.79418106e+01 -8.87617035e+01 -8.96705704e+01 -8.92526932e+01 -8.84205704e+01 -8.74810486e+01 -8.72819138e+01 -8.73137207e+01 -8.66816483e+01 -8.60128784e+01 -8.67790298e+01 -8.61366119e+01 -8.62822952e+01 -8.59459381e+01 -8.41488037e+01 -8.30822372e+01 -8.24557419e+01 -8.37818832e+01 -8.48051758e+01 -8.41861267e+01 -8.33573532e+01 -8.16177902e+01 -8.13782196e+01 -7.97882004e+01 -8.00945435e+01 -8.05150070e+01 -8.09119186e+01 -8.06315155e+01 -7.98756638e+01 -7.85004425e+01 -7.71095657e+01 -7.76831436e+01 -7.75185089e+01 -7.70379639e+01 -7.67404709e+01 -7.62578812e+01 -7.58822937e+01 -7.57480392e+01 -7.59216614e+01 -7.66878891e+01 -7.53633499e+01 -7.41349030e+01 -7.40958481e+01 -7.31122055e+01 -7.19763794e+01 -7.23035507e+01 -7.25305710e+01 -7.21655350e+01 -7.06980591e+01 -7.04621506e+01 -7.04492798e+01 -6.93803177e+01 -6.81313553e+01 -6.86104965e+01 -6.85237045e+01 -6.82143402e+01 -6.74253845e+01 -6.68997269e+01 -6.57978516e+01 -6.53477936e+01 -6.55077820e+01 -6.63985825e+01 -6.51879501e+01 -6.36971626e+01 -6.37176781e+01 -6.33175278e+01 -6.28944206e+01 -6.26600113e+01 -6.21566200e+01 -6.16301765e+01 -6.18123398e+01 -6.13421974e+01 -6.03128090e+01 -5.97312050e+01 -5.90989456e+01 -5.87430153e+01 -5.71107521e+01 -5.65242348e+01 -5.70749550e+01 -5.62955513e+01 -5.61458168e+01 -5.57310181e+01 -5.41556702e+01 -5.39826469e+01 -5.34504623e+01 -5.28242760e+01 -5.26301651e+01 -5.23062630e+01 -5.27128563e+01 -5.13725395e+01 -4.96933250e+01 -4.93511391e+01 -4.91323853e+01 -4.86192513e+01 -4.86039696e+01 -4.82217522e+01 -4.65828209e+01 -4.49333572e+01 -4.51283531e+01 -4.50597038e+01 -4.39906960e+01 -4.44632149e+01 -4.47714119e+01 -4.32896767e+01 -4.07081413e+01 -3.97381020e+01 -3.94524040e+01 -3.96481514e+01 -4.08792267e+01 -4.04584656e+01 -3.95899124e+01 -3.93150787e+01 -3.87591133e+01 -3.75113029e+01 -3.71969452e+01 -3.52932014e+01 -3.43744087e+01 -3.48605728e+01 -3.53623657e+01 -3.45986137e+01 -3.34277534e+01 -3.31020966e+01 -3.31970367e+01 -3.18682232e+01 -3.02541180e+01 -2.92098465e+01 -2.91562481e+01 -2.99039421e+01 -2.95779476e+01 -2.91466637e+01 -2.81178112e+01 -2.84931087e+01 -2.75555000e+01 -2.64853230e+01 -2.59231853e+01 -2.54874802e+01 -2.28705330e+01 -2.34305973e+01 -2.31276245e+01 -2.17019062e+01 -1.97572365e+01 -2.04546432e+01 -2.05694103e+01 -2.06634579e+01 -1.71403904e+01 -1.66725864e+01 -1.81516552e+01 -1.86043110e+01 -1.80430965e+01 -1.64268627e+01 -1.59400654e+01 -1.47297611e+01 -1.39747639e+01 -1.41776152e+01 -1.35989008e+01 -1.18417606e+01 -1.07680216e+01 -1.01154470e+01 -9.77777958e+00 -1.00878859e+01 -1.10376682e+01 -1.07160769e+01 -8.49601364e+00 -7.03721952e+00 -6.41630554e+00 -5.57824373e+00 -6.30696344e+00 -7.20934963e+00 -6.99571514e+00 -4.50894165e+00 -4.24197483e+00 -5.05969334e+00 -5.48225689e+00 -5.02761650e+00 -3.39760852e+00 -1.91462803e+00 -3.94344851e-02 5.81553280e-01 5.03438592e-01 6.84091389e-01 1.89318347e+00 3.77886510e+00 4.29475880e+00 5.01238966e+00 5.81407595e+00 6.94742250e+00 7.22515106e+00 7.53749657e+00 6.44746065e+00 6.59184551e+00 7.31338024e+00 9.71605015e+00 9.99262047e+00 9.69691467e+00 1.03399782e+01 1.23093958e+01 1.40518131e+01 1.40338192e+01 1.54318676e+01 1.47746658e+01 1.49333944e+01 1.52177725e+01 1.64617805e+01 1.66134834e+01 1.74207745e+01 1.87009773e+01 1.98107548e+01 1.90035114e+01 1.88629360e+01 2.02307034e+01 2.28519630e+01 2.35631847e+01 2.35923252e+01 2.30760899e+01 2.32802868e+01 2.30262089e+01 2.33670902e+01 2.39302425e+01 2.59726238e+01 2.64190750e+01 2.71575661e+01 2.87830811e+01 2.81907654e+01 2.97873287e+01 2.93214417e+01 3.03245220e+01 3.01928997e+01 3.11547813e+01 3.21966629e+01 3.24830933e+01 3.34247437e+01 3.43692818e+01 3.48028145e+01 3.52370186e+01 3.67309494e+01 3.63974075e+01 3.67052078e+01 3.66601562e+01 3.75316277e+01 3.74869614e+01 3.79752502e+01 3.91995659e+01 4.01433220e+01 4.11938362e+01 4.11128311e+01 4.19931412e+01 4.22036705e+01 4.27910881e+01 4.37683640e+01 4.46228371e+01 4.44989166e+01 4.49508705e+01 4.59547119e+01 4.72971535e+01 4.79822884e+01 4.84899063e+01 4.84093246e+01 4.85063477e+01 4.89003563e+01 4.94384308e+01 5.00689316e+01 5.06626015e+01 5.12829437e+01 5.16054153e+01 5.20715790e+01 5.24619751e+01 5.27879372e+01 5.36477013e+01 5.40077438e+01 5.44147987e+01 5.54318237e+01 5.61412048e+01 5.72160797e+01 5.73970680e+01 5.75521698e+01 5.76324577e+01 5.80904045e+01 5.91538048e+01 5.96193085e+01 6.04894981e+01 6.05968666e+01 6.10300903e+01 6.12765350e+01 6.18193169e+01 6.25063095e+01 6.28599510e+01 6.37701912e+01 6.42409363e+01 6.45812073e+01 6.49591064e+01 6.54596329e+01 6.60402908e+01 6.63030624e+01 6.66175232e+01 6.72407150e+01 6.76325912e+01 6.81159363e+01 6.85684586e+01 6.90938339e+01 6.97313614e+01 7.03018265e+01 7.05281830e+01 7.08550873e+01 7.13876038e+01 7.20452194e+01 7.24542694e+01 7.28825989e+01 7.32677536e+01 7.37425079e+01 7.42256165e+01 7.46271515e+01 7.49995804e+01 7.54137955e+01 7.58015976e+01 7.62932739e+01 7.65974884e+01 7.70464249e+01 7.74617844e+01 7.79377060e+01 7.83051453e+01 7.86777267e+01 7.90928040e+01 7.94903564e+01 7.98613663e+01 8.02447510e+01 8.06295624e+01 8.10156937e+01 8.13885498e+01 8.17741699e+01 8.21811371e+01 8.25676422e+01 8.29582672e+01 8.33224182e+01 8.36932602e+01 8.40465851e+01 8.43864059e+01 8.46794281e+01 8.50481796e+01 8.53424149e+01 8.56353607e+01 8.59447479e+01 8.62957230e+01 8.65480957e+01 8.69075851e+01 8.72330246e+01 8.74505386e+01 8.77408600e+01 8.81094589e+01 8.84552383e+01 8.87118454e+01 8.89763947e+01 8.91878967e+01 8.93582077e+01 8.95637741e+01 8.99521255e+01 9.03641052e+01 9.06448975e+01 9.09780273e+01 9.11506119e+01 9.13202057e+01 9.13660889e+01 9.18292542e+01 9.21946640e+01 9.26558914e+01 9.29787064e+01 9.29467697e+01 9.31589508e+01 9.35921936e+01 9.37501907e+01 9.38492508e+01 9.39203491e+01 9.42241898e+01 9.47490997e+01 9.47328949e+01 9.50449524e+01 9.52900696e+01 9.53684845e+01 9.55396347e+01 9.58879242e+01 9.60545044e+01 9.59753418e+01 9.59863968e+01 9.63974991e+01 9.68821182e+01 9.71725616e+01 9.74963379e+01 9.75507202e+01 9.81239624e+01 9.85442810e+01 9.85148544e+01 9.81111450e+01 9.81102066e+01 9.76909790e+01 9.82430420e+01 9.84556808e+01 9.86429138e+01 9.83684464e+01 9.89950790e+01 9.88910751e+01 9.92921371e+01 9.86676254e+01 9.93336563e+01 1.00250061e+02 1.01426750e+02 1.01182350e+02 1.00155579e+02 1.00727135e+02 1.00502029e+02 1.00222557e+02 1.00683121e+02 1.00576035e+02 1.00246185e+02 1.00892509e+02 1.00589607e+02 1.00399895e+02 1.00885719e+02 1.01579224e+02 1.02178032e+02 1.02152954e+02 1.01842148e+02 1.01909981e+02 1.01932213e+02 1.02535149e+02 1.02089401e+02 1.02012680e+02 1.01067108e+02 1.01601120e+02 1.01903122e+02 1.02773125e+02 1.02426743e+02 1.01814240e+02 1.01835594e+02 1.01599052e+02 1.01569550e+02 1.02457207e+02 1.02639969e+02 1.01485954e+02 1.01294930e+02 1.00926964e+02 1.00911926e+02 1.00874130e+02 1.00737968e+02 1.00597687e+02 1.00410759e+02 1.01440216e+02 1.01997353e+02 1.02528397e+02 1.02070900e+02 1.02219742e+02 1.01774269e+02 1.02017616e+02 1.01233360e+02 1.00194550e+02 1.00907761e+02 9.97197647e+01 1.00329552e+02 9.99777374e+01 1.00013748e+02 9.99451675e+01 1.00104790e+02 9.95004044e+01 9.92271729e+01 1.03997246e+02 1.35961655e+02 1.83531555e+02 1.70248062e+02 1.11313782e+02 9.64988937e+01 9.65112228e+01 9.93195267e+01 1.01149918e+02 9.99554443e+01 9.50819397e+01 6.76489639e+01 8.74086838e+01 4.49950256e+02 9.55707214e+02 -6369800. 589390080. 0. 0. 0. 0. -98937536. -98937536. -98937536. 0. 0. 0. 107782896. 49361064. 2.63467188e+05 2.74379004e+03 1.21994507e+03 4.26417236e+02 4.10134766e+02 5.41735718e+02 4.84596436e+02 2.74385529e+02 1.29117065e+02 9.82903824e+01 9.31355743e+01 9.30727539e+01 9.13230667e+01 9.04809723e+01 9.02293549e+01 9.10111084e+01 9.09159317e+01 9.87394333e+01 1.42398636e+02 1.81408234e+02 1.52432312e+02 1.05558037e+02 9.19540100e+01 8.86027374e+01 8.35778503e+01 5.77794876e+01 3.29113483e-01 5.49322224e+00 7.10350037e+01 1.23827789e+02 9.72068024e+01 4.79392662e+01 6.82738647e+01 8.72273026e+01 9.16144638e+01 9.13142776e+01 8.69616928e+01 8.41729279e+01 8.43913422e+01 8.41602554e+01 8.49880905e+01 8.42278900e+01 8.22568512e+01 8.25729218e+01 8.11396027e+01 8.12638092e+01 8.11903610e+01 8.17370834e+01 8.12930756e+01 7.98467712e+01 7.94076996e+01 7.84824448e+01 7.81138229e+01 7.74914932e+01 7.71750946e+01 7.66633911e+01 7.63508911e+01 7.60795212e+01 7.67369995e+01 7.60109482e+01 7.64887085e+01 7.60572739e+01 7.49205704e+01 7.38997269e+01 7.24391632e+01 7.17786255e+01 7.30290756e+01 7.30131531e+01 7.23421631e+01 7.06391068e+01 6.96534576e+01 6.85179596e+01 6.81450195e+01 6.74316025e+01 6.75182037e+01 6.76231537e+01 6.75932617e+01 6.62983398e+01 6.55710373e+01 6.55832443e+01 6.50913239e+01 6.29046631e+01 6.12625465e+01 6.40048599e+01 6.63588104e+01 6.43022919e+01 6.32428055e+01 6.36494179e+01 6.23135223e+01 5.95341568e+01 6.10749016e+01 6.27780800e+01 1.81806641e+02 4.90310031e+05 1.80366623e+02 4.48109245e+01 4.52089500e+01 4.48731003e+01 4.43686256e+01 4.45678024e+01 4.45311165e+01 4.44010887e+01 4.39158287e+01 4.38412170e+01 4.45807457e+01 4.42671089e+01 4.36345711e+01 4.34542656e+01 4.29400711e+01 4.27935181e+01 4.24603004e+01 4.20613899e+01 4.15894470e+01 4.15915565e+01 4.15082741e+01 4.11499176e+01 4.09026489e+01 4.07251053e+01 4.03619537e+01 4.02251549e+01 4.00029488e+01 3.97704353e+01 3.95164948e+01 3.96822701e+01 3.92574577e+01 3.87136765e+01 3.82007866e+01 3.82396927e+01 3.82980003e+01 3.85760841e+01 3.81951714e+01 3.80172501e+01 3.75810318e+01 3.71423798e+01 3.67900467e+01 3.67044220e+01 3.69309998e+01 3.65701141e+01 3.63553467e+01 3.62461243e+01 3.58435783e+01 3.53715897e+01 3.54599533e+01 3.51809120e+01 3.48242264e+01 3.44373512e+01 3.42741432e+01 3.37831688e+01 3.37835770e+01 3.40174370e+01 3.35500336e+01 3.34713173e+01 3.28518600e+01 3.25320168e+01 3.22059174e+01 3.19919758e+01 3.21775932e+01 3.14569263e+01 3.11979332e+01 3.16387196e+01 3.13462505e+01 3.09819736e+01 3.06082172e+01 2.97688808e+01 2.97848778e+01 2.97487068e+01 2.91000652e+01 2.83966026e+01 2.84049492e+01 2.89723701e+01 2.82159634e+01 2.84509735e+01 2.72997589e+01 2.74557667e+01 2.62728214e+01 2.61018543e+01 3.18093529e+01 2.88315029e+01 -1.51121002e+02 -3.09821106e+02 2.10239277e+01 -8.20229309e+02 -1.89280566e+03 1.00091553e+04 -2.39030475e+06 1262717568. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -525940352. -3.28226978e+03 -6.93044922e+02 -2.20646667e+01 -2.86388031e+02 -1.53529480e+02 2.40896530e+01 2.13991508e+01 1.16580448e+01 1.66541100e-01 3.14567065e+00 5.59275818e+00 1.37162437e+01 2.20848694e+01 1.76028442e+01 1.67997036e+01 1.55049887e+01 1.48692322e+01 1.51471806e+01 1.47465124e+01 1.48425550e+01 1.47393799e+01 1.48717737e+01 1.42865238e+01 1.33328581e+01 1.28822794e+01 1.64688072e+01 1.92549076e+01 1.80524158e+01 1.21933317e+01 7.44974804e+00 7.65491009e+00 6.97783041e+00 4.49667549e+00 1.52024794e+00 1.89105761e+00 3.68513060e+00 8.25801754e+00 1.20312643e+01 1.26040735e+01 1.32539768e+01 1.37377195e+01 1.12308674e+01 9.75676537e+00 9.31605625e+00 8.04175854e+00 6.44709110e+00 2.12792730e+00 6.32063970e-02 1.90386295e+00 3.56438494e+00 4.28364420e+00 4.06466103e+00 3.90725994e+00 3.69856262e+00 3.19517732e+00 2.34559631e+00 1.92201793e+00 1.39970756e+00 9.38578129e-01 2.46896911e-02 5.28603196e-01 1.90058768e+00 2.79132533e+00 2.25153494e+00 2.30641794e+00 2.18694544e+00 1.52807701e+00 6.60932839e-01 -2.05309838e-01 -1.04047775e+00 -1.71803045e+00 -2.35928273e+00 -2.35625648e+00 -2.89181924e+00 -2.92465639e+00 -3.67526531e+00 -4.06465006e+00 -4.76855135e+00 -4.83689976e+00 -4.78018188e+00 -4.78917742e+00 -5.07528830e+00 -5.51661015e+00 -6.09425688e+00 -6.76420498e+00 -6.92495108e+00 -6.95165539e+00 -7.22491121e+00 -7.48049307e+00 -7.69346285e+00 -8.08646870e+00 -8.60237026e+00 -9.06846619e+00 -9.25016022e+00 -9.48512363e+00 -9.67112541e+00 -9.97195625e+00 -1.01259718e+01 -1.05776510e+01 -1.09383917e+01 -1.13637676e+01 -1.15818253e+01 -1.19257078e+01 -1.22525024e+01 -1.25246496e+01 -1.28495245e+01 -1.30790300e+01 -1.33596754e+01 -1.36701040e+01 -1.41689644e+01 -1.44531059e+01 -1.47302399e+01 -1.49525061e+01 -1.52889128e+01 -1.56187792e+01 -1.58905354e+01 -1.61111164e+01 -1.64349613e+01 -1.67385826e+01 -1.70522175e+01 -1.73310165e+01 -1.76822968e+01 -1.79854660e+01 -1.82887383e+01 -1.85361214e+01 -1.88587666e+01 -1.91644764e+01 -1.95013618e+01 -1.97933140e+01 -2.01352921e+01 -2.04316597e+01 -2.07455826e+01 -2.10168476e+01 -2.13084736e+01 -2.15774956e+01 -2.18775024e+01 -2.21689568e+01 -2.24732914e+01 -2.27473602e+01 -2.30396824e+01 -2.33265686e+01 -2.36103630e+01 -2.38874664e+01 -2.41730289e+01 -2.44710236e+01 -2.47575798e+01 -2.50395374e+01 -2.53224964e+01 -2.55991173e+01 -2.58723373e+01 -2.61530628e+01 -2.64308834e+01 -2.67093773e+01 -2.69819717e+01 -2.72611256e+01 -2.75396976e+01 -2.78145752e+01 -2.80950508e+01 -2.83732738e+01 -2.86314754e+01 -2.89062271e+01 -2.91631832e+01 -2.94343224e+01 -2.97167435e+01 -2.99920406e+01 -3.02624378e+01 -3.04930611e+01 -3.07415466e+01 -3.09590473e+01 -3.12206459e+01 -3.14688740e+01 -3.17346115e+01 -3.19831352e+01 -3.22557945e+01 -3.25038528e+01 -3.27551994e+01 -3.29389954e+01 -3.31878853e+01 -3.34643440e+01 -3.37372475e+01 -3.39929199e+01 -3.43352661e+01 -3.45218658e+01 -3.46744041e+01 -3.47926712e+01 -3.50560570e+01 -3.53554535e+01 -3.57070007e+01 -3.58696594e+01 -3.60891495e+01 -3.63227119e+01 -3.65287552e+01 -3.67253036e+01 -3.69700432e+01 -3.72561874e+01 -3.73992348e+01 -3.76715660e+01 -3.79320908e+01 -3.81506195e+01 -3.82911148e+01 -3.84544182e+01 -3.87243423e+01 -3.89645309e+01 -3.91703072e+01 -3.93403664e+01 -3.94595718e+01 -3.97533951e+01 -4.01400719e+01 -4.03301430e+01 -4.05700645e+01 -4.05076027e+01 -4.07727509e+01 -4.10759125e+01 -4.11627464e+01 -4.14756241e+01 -4.14357071e+01 -4.18327332e+01 -4.23741875e+01 -4.27193336e+01 -4.25870667e+01 -4.26878319e+01 -4.27655869e+01 -4.31689186e+01 -4.31794853e+01 -4.31310806e+01 -4.30921707e+01 -4.36461411e+01 -4.42678337e+01 -4.40756035e+01 -4.47293129e+01 -4.45705566e+01 -4.50213432e+01 -4.50086250e+01 -4.55933762e+01 -4.59693985e+01 -4.55515900e+01 -4.56016045e+01 -4.54644966e+01 -4.55993309e+01 -4.54569359e+01 -4.55021362e+01 -4.58531036e+01 -4.60952454e+01 -4.63517303e+01 -4.68957367e+01 -4.73997993e+01 -4.75055008e+01 -4.76529655e+01 -4.75433426e+01 -4.77100258e+01 -4.78583717e+01 -4.79603653e+01 -4.77616539e+01 -4.78626175e+01 -4.75876350e+01 -4.76368370e+01 -4.80146065e+01 -4.85087128e+01 -4.89930687e+01 -4.83287621e+01 -4.85895767e+01 -4.87449570e+01 -4.94917793e+01 -4.96174583e+01 -4.88020134e+01 -4.90189133e+01 -4.89825401e+01 -4.95774307e+01 -5.00734062e+01 -4.97827606e+01 -5.03581352e+01 -4.98450050e+01 -4.97760239e+01 -5.00693626e+01 -5.01177063e+01 -5.05494919e+01 -5.09090691e+01 -5.13898354e+01 -5.13986511e+01 -5.06451492e+01 -5.06638260e+01 -5.08415871e+01 -5.06793060e+01 -5.05462837e+01 -5.01625557e+01 -5.06355057e+01 -5.08059082e+01 -5.06641006e+01 -5.08308754e+01 -5.12500191e+01 -5.13010750e+01 -5.12372780e+01 -5.12902031e+01 -5.15163307e+01 -5.15334740e+01 -5.15982971e+01 -5.18557053e+01 -5.15361099e+01 -5.15409775e+01 -5.16136360e+01 -5.19197655e+01 -5.14400635e+01 -5.09501724e+01 -5.16153374e+01 -5.19434319e+01 -5.23471298e+01 -5.22417450e+01 -5.19198570e+01 -5.20671043e+01 -5.23260078e+01 -5.22677078e+01 -5.17051239e+01 -5.18833389e+01 -5.19745979e+01 -5.22137604e+01 -5.12431984e+01 -5.22372665e+01 -5.26096954e+01 -5.33910179e+01 -5.29861259e+01 -5.26477394e+01 -5.21280632e+01 -5.18096695e+01 -5.19588966e+01 -5.22336349e+01 -5.22678909e+01 -5.16741028e+01 -5.13551064e+01 -5.20016251e+01 -5.21612167e+01 -5.26379356e+01 -5.16796494e+01 -5.11888542e+01 -5.04822578e+01 -5.10435715e+01 -5.17957611e+01 -5.23347893e+01 -5.25727386e+01 -5.22304077e+01 -5.16186333e+01 -5.09390182e+01 -5.10441780e+01 -5.14639244e+01 -5.13014259e+01 -5.13983803e+01 -5.17241936e+01 -5.15620193e+01 -5.10529404e+01 -5.05594444e+01 -5.06200867e+01 -5.06943092e+01 -5.14267502e+01 -5.13907051e+01 -5.18757515e+01 -5.11086159e+01 -5.07470436e+01 -5.04066544e+01 -5.05729027e+01 -5.03150978e+01 -5.04640846e+01 -5.05581131e+01 -5.04981422e+01 -5.05491562e+01 -5.04851418e+01 -5.01027489e+01 -4.95918579e+01 -4.97872887e+01 -4.99362869e+01 -5.02931252e+01 -5.00446358e+01 -4.96511230e+01 -4.95539513e+01 -4.97186699e+01 -4.97601433e+01 -5.00229378e+01 -4.96589622e+01 -4.94760933e+01 -4.92131271e+01 -4.90236092e+01 -4.86384583e+01 -4.89049644e+01 -4.89301186e+01 -4.88006821e+01 -4.82359886e+01 -4.82353172e+01 -4.81305199e+01 -4.78554764e+01 -4.74334068e+01 -4.76217041e+01 -4.74411812e+01 -4.75512161e+01 -4.73100624e+01 -4.72177849e+01 -4.69003258e+01 -4.67284393e+01 -4.66799355e+01 -4.70018005e+01 -4.66537590e+01 -4.62407379e+01 -4.62221298e+01 -4.60463676e+01 -4.60069847e+01 -4.59336777e+01 -4.57419815e+01 -4.56766205e+01 -4.56339188e+01 -4.54341125e+01 -4.52152596e+01 -4.50539894e+01 -4.47187462e+01 -4.45965958e+01 -4.42270432e+01 -4.40340614e+01 -4.41516571e+01 -4.39476852e+01 -4.38419762e+01 -4.36895523e+01 -4.32534904e+01 -4.30944290e+01 -4.30516853e+01 -4.29152374e+01 -4.28084946e+01 -4.25898170e+01 -4.26164780e+01 -4.21493378e+01 -4.16969795e+01 -4.13689575e+01 -4.12363472e+01 -4.11832657e+01 -4.11805420e+01 -4.09135704e+01 -4.04313927e+01 -3.98115959e+01 -3.97409706e+01 -3.97987900e+01 -3.93929329e+01 -3.94503746e+01 -3.98904343e+01 -3.91812935e+01 -3.83032074e+01 -3.77451820e+01 -3.78431473e+01 -3.77964516e+01 -3.81177330e+01 -3.79194679e+01 -3.78754578e+01 -3.75712738e+01 -3.72193680e+01 -3.69020195e+01 -3.68694572e+01 -3.63188591e+01 -3.60339127e+01 -3.64028511e+01 -3.63128128e+01 -3.59132729e+01 -3.53747177e+01 -3.52982521e+01 -3.52141571e+01 -3.46540108e+01 -3.40992737e+01 -3.40853195e+01 -3.38432007e+01 -3.39484673e+01 -3.40557098e+01 -3.34191132e+01 -3.33898582e+01 -3.26175194e+01 -3.21569443e+01 -3.17942333e+01 -3.18908386e+01 -3.21431122e+01 -3.12770615e+01 -3.13234673e+01 -3.16619263e+01 -3.15334816e+01 -3.08564396e+01 -3.06109829e+01 -3.00046730e+01 -3.00909996e+01 -2.93390064e+01 -2.85738373e+01 -2.84115791e+01 -2.83851585e+01 -2.87106323e+01 -2.80378017e+01 -2.84162884e+01 -2.77878819e+01 -2.77198086e+01 -2.73272552e+01 -2.73449669e+01 -2.69700203e+01 -2.59460812e+01 -2.58745823e+01 -2.54063568e+01 -2.54316826e+01 -2.50115299e+01 -2.49268837e+01 -2.42788734e+01 -2.39581223e+01 -2.35576439e+01 -2.34812908e+01 -2.36880131e+01 -2.43001194e+01 -2.39477005e+01 -2.30675964e+01 -2.25613766e+01 -2.27098179e+01 -2.24265423e+01 -2.22226601e+01 -2.17452660e+01 -2.06412392e+01 -2.01408825e+01 -2.00189571e+01 -2.00997658e+01 -2.03327827e+01 -1.93414898e+01 -1.91609898e+01 -1.89751835e+01 -1.90017948e+01 -1.85258751e+01 -1.71155186e+01 -1.70193272e+01 -1.68802738e+01 -1.75256500e+01 -1.78046036e+01 -1.69877167e+01 -1.68026314e+01 -1.55719776e+01 -1.52342358e+01 -1.52774076e+01 -1.45297041e+01 -1.44930849e+01 -1.44174719e+01 -1.45974169e+01 -1.45281458e+01 -1.38187885e+01 -1.34656248e+01 -1.28479815e+01 -1.23030815e+01 -1.17702551e+01 -1.06846676e+01 -1.05567970e+01 -1.02261944e+01 -1.03669682e+01 -1.01283875e+01 -1.00362253e+01 -9.71504974e+00 -9.45014668e+00 -9.28812885e+00 -9.09733391e+00 -8.76484680e+00 -8.42929649e+00 -8.28222847e+00 -7.43535948e+00 -7.15223551e+00 -6.62459040e+00 -6.45628643e+00 -6.24961662e+00 -5.55082655e+00 -5.44917536e+00 -5.42174578e+00 -5.11003065e+00 -4.63028765e+00 -3.96716857e+00 -4.15681934e+00 -3.93394637e+00 -3.39166975e+00 -2.82437587e+00 -2.77810454e+00 -2.38289285e+00 -2.20803189e+00 -1.55127883e+00 -1.83239913e+00 -1.63551676e+00 -1.76743722e+00 -1.15931463e+00 -7.40579665e-01 -1.08327396e-01 4.69746232e-01 7.16850042e-01 1.00948107e+00 1.28423965e+00 1.75245941e+00 2.20108485e+00 2.23811221e+00 2.54617953e+00 2.59350753e+00 3.38562322e+00 3.91843939e+00 4.48466873e+00 4.67154741e+00 4.63364458e+00 4.61894464e+00 4.91968536e+00 5.31871748e+00 5.92262220e+00 6.53383350e+00 6.77943277e+00 6.81337595e+00 7.03193521e+00 7.29004908e+00 7.53694963e+00 7.91195774e+00 8.46671391e+00 8.93802166e+00 9.18937206e+00 9.43033314e+00 9.59525776e+00 9.91689205e+00 1.00218639e+01 1.04323425e+01 1.07675304e+01 1.12207632e+01 1.14511738e+01 1.18755550e+01 1.21501408e+01 1.24368849e+01 1.27972412e+01 1.30745687e+01 1.33207903e+01 1.36408577e+01 1.41476421e+01 1.44049149e+01 1.46161823e+01 1.48545828e+01 1.52194471e+01 1.55845337e+01 1.58370810e+01 1.60382004e+01 1.63902435e+01 1.66795635e+01 1.69568253e+01 1.72522106e+01 1.76068630e+01 1.79072838e+01 1.82494774e+01 1.84587803e+01 1.87577038e+01 1.90960884e+01 1.94464531e+01 1.97382393e+01 2.00519447e+01 2.03255424e+01 2.06461239e+01 2.09414749e+01 2.12345695e+01 2.14932823e+01 2.17980366e+01 2.20794392e+01 2.24008503e+01 2.26771355e+01 2.29692593e+01 2.32402344e+01 2.35310249e+01 2.38103752e+01 2.40908451e+01 2.43811150e+01 2.46588497e+01 2.49413128e+01 2.52334766e+01 2.55263100e+01 2.58096790e+01 2.60909214e+01 2.63687534e+01 2.66541538e+01 2.69340191e+01 2.72220383e+01 2.75058651e+01 2.77803364e+01 2.80627937e+01 2.83431110e+01 2.86104527e+01 2.88737736e+01 2.91332893e+01 2.93892479e+01 2.96761761e+01 2.99468765e+01 3.01977787e+01 3.04509754e+01 3.07123184e+01 3.09514027e+01 3.12085247e+01 3.14404144e+01 3.16984177e+01 3.19675922e+01 3.22360458e+01 3.24560432e+01 3.26784172e+01 3.28924942e+01 3.31568832e+01 3.34473000e+01 3.37077217e+01 3.40317612e+01 3.43027039e+01 3.44867020e+01 3.46872787e+01 3.48943405e+01 3.52141075e+01 3.54568558e+01 3.57564087e+01 3.59227562e+01 3.61811981e+01 3.63756065e+01 3.65718040e+01 3.67877960e+01 3.69460144e+01 3.72453613e+01 3.74795303e+01 3.77369766e+01 3.78960228e+01 3.80713844e+01 3.82120781e+01 3.84429779e+01 3.86453934e+01 3.88357773e+01 3.90620613e+01 3.93016472e+01 3.95595970e+01 3.98084831e+01 4.01737671e+01 4.02593842e+01 4.04924240e+01 4.05314255e+01 4.07333679e+01 4.09774017e+01 4.10945168e+01 4.14229584e+01 4.13967781e+01 4.16855469e+01 4.21569977e+01 4.26664467e+01 4.25514870e+01 4.26980667e+01 4.26140785e+01 4.31125946e+01 4.31791267e+01 4.32022705e+01 4.32368546e+01 4.37148285e+01 4.42477646e+01 4.40108452e+01 4.47258987e+01 4.45758781e+01 4.49515190e+01 4.49997139e+01 4.55872421e+01 4.57312737e+01 4.54495201e+01 4.55215149e+01 4.53561440e+01 4.57080116e+01 4.56407585e+01 4.58426819e+01 4.61459732e+01 4.62278099e+01 4.64635658e+01 4.67655678e+01 4.72496605e+01 4.76156387e+01 4.75485992e+01 4.73596840e+01 4.73621292e+01 4.76305313e+01 4.77863731e+01 4.78256493e+01 4.77631416e+01 4.75442963e+01 4.76449356e+01 4.80719833e+01 4.85010262e+01 4.89313965e+01 4.86577110e+01 4.88862076e+01 4.88872719e+01 4.94141846e+01 4.96230049e+01 4.88900566e+01 4.90398102e+01 4.89802780e+01 4.98457069e+01 5.02765961e+01 5.02549858e+01 5.07550201e+01 4.98754387e+01 4.96397285e+01 5.01527443e+01 5.01508331e+01 5.07373962e+01 5.10957527e+01 5.16451988e+01 5.15867958e+01 5.08365364e+01 5.09271660e+01 5.10672989e+01 5.09784966e+01 5.06509323e+01 5.01558647e+01 5.19949226e+01 6.12479362e+01 6.93582382e+01 6.38168411e+01 6.34509621e+01 6.09976006e+01 5.13305016e+01 5.16332474e+01 5.19545593e+01 5.17580719e+01 5.02376404e+01 4.19923363e+01 4.97051392e+01 2.27152893e+02 3.40565338e+02 7.39964783e+02 1.85993140e+03 -1236108928. -136547312. 0. 0. -98937536. -98937536. -98937536. 0. 0. 0. 107782896. 49361064. 2.63467188e+05 2.86556934e+03 1.42557263e+03 7.29259094e+02 5.02961182e+02 1.83942474e+02 1.17092186e+02 1.22467903e+02 1.02102211e+02 7.50737228e+01 5.76923676e+01 5.41813049e+01 5.24525185e+01 5.12733727e+01 5.19848671e+01 5.20324974e+01 5.26130753e+01 5.45253525e+01 6.80381775e+01 7.99459305e+01 6.87925034e+01 5.35921745e+01 5.08193741e+01 5.11699142e+01 5.31282654e+01 4.81993866e+01 3.34195671e+01 3.25698280e+01 4.62402382e+01 5.67753906e+01 5.13234901e+01 4.14278374e+01 3.14299698e+01 2.28703728e+01 5.19153519e+01 7.27911835e+01 6.05594978e+01 5.51415596e+01 5.27675476e+01 5.21409912e+01 5.14730301e+01 5.11547508e+01 5.07803841e+01 5.11312027e+01 5.09247093e+01 5.08134880e+01 5.08658485e+01 5.10465317e+01 5.09758949e+01 5.05220528e+01 5.02670364e+01 5.00120277e+01 5.00919456e+01 5.00552101e+01 5.02920494e+01 4.99116135e+01 4.95273590e+01 4.96843376e+01 5.00699463e+01 4.97331657e+01 4.97362442e+01 4.96479759e+01 4.97727928e+01 4.94136124e+01 4.90859375e+01 4.87971153e+01 4.92309151e+01 4.90877876e+01 4.88939629e+01 4.83249588e+01 4.80955849e+01 4.74638023e+01 4.73795891e+01 4.70125809e+01 4.73947792e+01 4.73509216e+01 4.71954765e+01 4.69554787e+01 4.70047264e+01 4.68991394e+01 4.64853935e+01 4.61607895e+01 4.79767609e+01 4.69671211e+01 4.52934952e+01 4.55392838e+01 4.53598213e+01 4.61188393e+01 4.63892059e+01 4.83512383e+01 5.07480774e+01 4.56660805e+01 1.29606369e+02 1.33100984e+05 5.39616814e+01 1.33902073e+01 1.27749176e+01 1.05951252e+01 9.90281010e+00 1.26235151e+01 1.38836794e+01 9.86278629e+00 9.61269665e+00 1.05530863e+01 1.04573736e+01 1.18136663e+01 1.16632500e+01 1.17562323e+01 1.12630396e+01 1.11900539e+01 1.10580177e+01 1.08201571e+01 1.03689127e+01 1.03618851e+01 1.02228289e+01 9.91390705e+00 1.02493534e+01 1.00156546e+01 9.38017178e+00 9.24159050e+00 9.27056122e+00 9.36320972e+00 8.90153408e+00 9.01155567e+00 8.93831825e+00 8.66336060e+00 8.20396519e+00 8.05763626e+00 7.74214172e+00 7.95010805e+00 7.93403864e+00 7.82194567e+00 7.29047060e+00 7.07787657e+00 6.91819525e+00 6.59043741e+00 6.75485897e+00 6.54678440e+00 6.27815151e+00 6.05446434e+00 5.97398758e+00 5.97526026e+00 5.82765532e+00 5.70309162e+00 5.48164463e+00 5.77245283e+00 5.60281134e+00 5.36104441e+00 4.59623575e+00 4.43641663e+00 4.27546406e+00 4.26280165e+00 3.66314387e+00 3.39923263e+00 3.35252929e+00 4.00854397e+00 4.10376692e+00 3.92229819e+00 3.27891278e+00 3.13866830e+00 2.93472815e+00 2.79825616e+00 2.32750463e+00 1.93600380e+00 1.83094537e+00 2.06926370e+00 1.12322593e+00 3.03412437e-01 4.04300570e-01 5.37846625e-01 4.67989028e-01 6.05625391e-01 -1.64629802e-01 7.70140469e-01 6.26422644e+00 -1.91560432e-01 -1.84940781e+02 -3.15485687e+02 -7.37170593e+02 3.07741974e+02 3.62243690e+01 -1.49504382e+03 -1157379584. 1262717568. 1262717568. 2.71939975e+06 92080408. 92080408. 0. 0. 0. 0. 0. 0. -550745792. 140042224. -5.73526055e+04 -1.66581177e+03 -7.06874634e+02 -1.87422485e+02 -8.99699783e+00 -8.27484417e+00 -4.76126051e+00 -7.24731731e+00 -1.07099590e+01 -1.17835617e+01 -2.12070503e+01 -1.27267752e+01 -1.83697331e+00 -2.64459133e+00 -4.33061123e+00 -4.92620945e+00 -4.86761236e+00 -5.78967285e+00 -6.31514454e+00 -6.37784958e+00 -6.52029800e+00 -6.00798798e+00 -5.70616865e+00 -5.39506483e+00 -5.98507738e+00 -6.45047760e+00 -7.19792795e+00 -7.32002115e+00 -6.50751162e+00 -5.65706825e+00 -8.18093681e+00 -1.05368834e+01 -1.00856056e+01 -9.27746201e+00 -8.96066380e+00 -8.88834190e+00 -8.92342091e+00 -9.18766689e+00 -8.47186375e+00 -8.60376740e+00 -8.91698742e+00 -8.82754993e+00 -8.11217976e+00 -9.30436611e+00 -1.01191788e+01 -1.05847282e+01 -9.91865349e+00 -1.00485220e+01 -1.00199261e+01 -1.00114937e+01 -1.00982389e+01 -1.05744791e+01 -1.13139019e+01 -1.19551325e+01 -1.17863321e+01 -1.17140598e+01 -1.15208912e+01 -1.15731230e+01 -1.13362179e+01 -1.14055576e+01 -1.19560881e+01 -1.22177610e+01 -1.24465113e+01 -1.22413826e+01 -1.21855316e+01 -1.22449760e+01 -1.22636700e+01 -1.27715816e+01 -1.27998295e+01 -1.32751904e+01 -1.36730146e+01 -1.44950399e+01 -1.45504208e+01 -1.44678402e+01 -1.41861115e+01 -1.44462404e+01 -1.41841831e+01 -1.43522434e+01 -1.43763685e+01 -1.47831297e+01 -1.49999695e+01 -1.50043192e+01 -1.51677713e+01 -1.53341427e+01 -1.56072779e+01 -1.57225399e+01 -1.60401573e+01 -1.61860867e+01 -1.60194988e+01 -1.59967413e+01 -1.59766855e+01 -1.63001213e+01 -1.65253658e+01 -1.69167919e+01 -1.70886879e+01 -1.68218040e+01 -1.67499237e+01 -1.67587738e+01 -1.71484547e+01 -1.74426899e+01 -1.77100067e+01 -1.78527527e+01 -1.76631908e+01 -1.77582664e+01 -1.75914154e+01 -1.78815460e+01 -1.81401386e+01 -1.84839306e+01 -1.85245686e+01 -1.84418602e+01 -1.84924965e+01 -1.86998215e+01 -1.88469257e+01 -1.89274921e+01 -1.89167061e+01 -1.90606709e+01 -1.91961823e+01 -1.94247093e+01 -1.95094700e+01 -1.96330814e+01 -1.97519112e+01 -1.98765259e+01 -1.98834743e+01 -2.00172539e+01 -2.00820808e+01 -2.01966648e+01 -2.03426685e+01 -2.04996910e+01 -2.05912437e+01 -2.06618690e+01 -2.07325840e+01 -2.08544636e+01 -2.09803066e+01 -2.10642929e+01 -2.11497784e+01 -2.12280045e+01 -2.13149738e+01 -2.14335499e+01 -2.15374851e+01 -2.16526871e+01 -2.17411957e+01 -2.18326702e+01 -2.19219418e+01 -2.20072174e+01 -2.20982628e+01 -2.21925068e+01 -2.22851868e+01 -2.23733482e+01 -2.24538860e+01 -2.25381947e+01 -2.26203632e+01 -2.27019100e+01 -2.27856426e+01 -2.28677559e+01 -2.29444618e+01 -2.30186443e+01 -2.30903454e+01 -2.31696148e+01 -2.32409210e+01 -2.33255672e+01 -2.33978233e+01 -2.34686737e+01 -2.35442867e+01 -2.36109562e+01 -2.36723480e+01 -2.37524052e+01 -2.38307629e+01 -2.38977509e+01 -2.39734764e+01 -2.40381660e+01 -2.40948124e+01 -2.41601601e+01 -2.42013206e+01 -2.42598305e+01 -2.43251534e+01 -2.43854675e+01 -2.44546299e+01 -2.45238037e+01 -2.45456562e+01 -2.46025105e+01 -2.47230415e+01 -2.48099270e+01 -2.48098278e+01 -2.49256840e+01 -2.49542160e+01 -2.50411930e+01 -2.49868927e+01 -2.50153236e+01 -2.50549660e+01 -2.51950226e+01 -2.52477493e+01 -2.53418026e+01 -2.53014107e+01 -2.53712311e+01 -2.53995075e+01 -2.54597492e+01 -2.55333157e+01 -2.54946098e+01 -2.56188221e+01 -2.55726013e+01 -2.56797829e+01 -2.56975842e+01 -2.56494560e+01 -2.57870522e+01 -2.59222050e+01 -2.60516052e+01 -2.60498180e+01 -2.59578972e+01 -2.58217754e+01 -2.58721638e+01 -2.60512924e+01 -2.60399590e+01 -2.57084007e+01 -2.57467670e+01 -2.59388657e+01 -2.61858959e+01 -2.63230247e+01 -2.64060745e+01 -2.62181759e+01 -2.62560272e+01 -2.64382381e+01 -2.65322475e+01 -2.62467804e+01 -2.63507175e+01 -2.63764935e+01 -2.64004726e+01 -2.57637329e+01 -2.53333454e+01 -2.53362312e+01 -2.56304207e+01 -2.57881794e+01 -2.62971363e+01 -2.63533535e+01 -2.64927921e+01 -2.59224834e+01 -2.60922203e+01 -2.64201622e+01 -2.63152409e+01 -2.65539532e+01 -2.64173393e+01 -2.66042747e+01 -2.59777985e+01 -2.57875271e+01 -2.59522781e+01 -2.65298233e+01 -2.62423840e+01 -2.60939102e+01 -2.58553276e+01 -2.63702068e+01 -2.64635010e+01 -2.67102280e+01 -2.63834858e+01 -2.63523941e+01 -2.58846302e+01 -2.58075542e+01 -2.60980320e+01 -2.57938061e+01 -2.58424702e+01 -2.57843628e+01 -2.63086033e+01 -2.68152752e+01 -2.64827538e+01 -2.67968540e+01 -2.67152271e+01 -2.72765388e+01 -2.69283085e+01 -2.63590794e+01 -2.63265476e+01 -2.59968624e+01 -2.60329723e+01 -2.58096313e+01 -2.60599079e+01 -2.65241108e+01 -2.59759274e+01 -2.55831833e+01 -2.54518356e+01 -2.56175385e+01 -2.62905273e+01 -2.68215542e+01 -2.73621387e+01 -2.66237564e+01 -2.58982239e+01 -2.57981224e+01 -2.60155182e+01 -2.58328724e+01 -2.58117332e+01 -2.50968475e+01 -2.49051323e+01 -2.44302216e+01 -2.45355835e+01 -2.44189110e+01 -2.45243416e+01 -2.45747700e+01 -2.40672340e+01 -2.44777603e+01 -2.48424053e+01 -2.48624821e+01 -2.47891426e+01 -2.52877159e+01 -2.48231659e+01 -2.45212040e+01 -2.37441216e+01 -2.48467903e+01 -2.42423801e+01 -2.47391930e+01 -2.46170197e+01 -2.49947872e+01 -2.43468113e+01 -2.36111202e+01 -2.26187572e+01 -2.34441948e+01 -2.38419228e+01 -2.43170547e+01 -2.41501865e+01 -2.43953896e+01 -2.42584896e+01 -2.33405094e+01 -2.25082417e+01 -2.27030373e+01 -2.31483326e+01 -2.32590237e+01 -2.33592587e+01 -2.37920418e+01 -2.32590008e+01 -2.35075569e+01 -2.30128937e+01 -2.24476223e+01 -2.18359604e+01 -2.14026051e+01 -2.17509193e+01 -2.19496021e+01 -2.16474476e+01 -2.20748386e+01 -2.18056965e+01 -2.20282421e+01 -2.16314850e+01 -2.15104408e+01 -2.16175385e+01 -2.14739857e+01 -2.11872406e+01 -2.09194260e+01 -2.08640480e+01 -2.02720356e+01 -2.02685165e+01 -2.08274403e+01 -2.07907848e+01 -2.10152988e+01 -2.05363483e+01 -2.02247791e+01 -1.94534359e+01 -1.91752071e+01 -1.97994041e+01 -2.04346542e+01 -2.09222431e+01 -2.01216087e+01 -1.94519520e+01 -1.88255806e+01 -1.88269558e+01 -1.92401180e+01 -1.92400188e+01 -1.97746468e+01 -1.95104141e+01 -1.91688557e+01 -1.84358006e+01 -1.84823551e+01 -1.87284584e+01 -1.86919823e+01 -1.83450642e+01 -1.84417210e+01 -1.84387684e+01 -1.90852470e+01 -1.85925541e+01 -1.85217991e+01 -1.81121712e+01 -1.78021278e+01 -1.75620937e+01 -1.74640713e+01 -1.74348049e+01 -1.75511875e+01 -1.72987118e+01 -1.73367462e+01 -1.69706306e+01 -1.68278255e+01 -1.65971107e+01 -1.64026318e+01 -1.62798061e+01 -1.63701954e+01 -1.63428822e+01 -1.59491024e+01 -1.57343702e+01 -1.56738052e+01 -1.55430899e+01 -1.54175596e+01 -1.50545425e+01 -1.50902166e+01 -1.49578352e+01 -1.47498264e+01 -1.47060127e+01 -1.49521027e+01 -1.46046448e+01 -1.42216625e+01 -1.42447662e+01 -1.40974607e+01 -1.39834862e+01 -1.39835186e+01 -1.38510189e+01 -1.36671915e+01 -1.35033960e+01 -1.34014158e+01 -1.33169079e+01 -1.31288471e+01 -1.28536968e+01 -1.28402033e+01 -1.26239204e+01 -1.22927113e+01 -1.24943266e+01 -1.22813473e+01 -1.20474710e+01 -1.20506468e+01 -1.16686583e+01 -1.14128227e+01 -1.14719095e+01 -1.14773245e+01 -1.14613400e+01 -1.13507328e+01 -1.11926289e+01 -1.08602753e+01 -1.06176519e+01 -1.01951275e+01 -1.00677662e+01 -1.00165215e+01 -9.89612865e+00 -1.00541525e+01 -9.87253094e+00 -9.05617332e+00 -8.95323563e+00 -9.03146839e+00 -8.92118645e+00 -8.87392044e+00 -9.44189453e+00 -9.08065891e+00 -8.43302059e+00 -8.04153538e+00 -7.89392376e+00 -7.55847168e+00 -7.69976950e+00 -7.72839451e+00 -7.72205210e+00 -7.52776814e+00 -7.35234880e+00 -7.11569786e+00 -6.94772387e+00 -6.81051445e+00 -6.63695526e+00 -6.71701241e+00 -6.38193464e+00 -6.39041138e+00 -6.51413774e+00 -6.19102335e+00 -6.45368910e+00 -6.08766222e+00 -5.84212923e+00 -5.57905245e+00 -5.34430981e+00 -4.90830946e+00 -4.63110018e+00 -4.31151390e+00 -4.22713614e+00 -3.47396922e+00 -3.25540328e+00 -3.25839305e+00 -4.27704334e+00 -4.62015533e+00 -4.39536572e+00 -3.61504269e+00 -3.58118033e+00 -3.39652610e+00 -3.38188481e+00 -2.89807200e+00 -2.54852772e+00 -2.18502903e+00 -1.56664681e+00 -6.94627166e-01 -1.50296152e-01 -1.81656614e-01 -2.39504337e-01 -2.96899199e-01 -9.92696524e-01 -9.22977269e-01 -9.88087237e-01 -5.12817800e-01 -6.95958138e-01 -8.19210052e-01 -2.12011456e-01 -2.22373337e-01 -2.02256233e-01 -1.17717929e-01 8.44854176e-01 1.30661154e+00 1.26765358e+00 7.33951092e-01 8.25791419e-01 1.27101719e+00 2.01154900e+00 1.46505606e+00 1.35938776e+00 1.26766551e+00 1.47504365e+00 2.07085419e+00 2.65120292e+00 2.92689013e+00 2.49462461e+00 2.75223398e+00 2.55656958e+00 2.91996813e+00 2.68613720e+00 2.31508160e+00 3.06980371e+00 2.97495031e+00 3.51188111e+00 3.26627135e+00 3.91478777e+00 4.67662096e+00 4.77108145e+00 4.90799475e+00 4.89481115e+00 4.89649391e+00 5.21585035e+00 5.01283169e+00 5.64126730e+00 5.86944962e+00 6.16194105e+00 6.38908958e+00 5.67779303e+00 5.43977690e+00 4.89825058e+00 5.61817169e+00 5.81404686e+00 6.34972715e+00 6.71303129e+00 7.31437492e+00 7.04030180e+00 7.66874695e+00 8.21564007e+00 8.75712585e+00 8.54203892e+00 8.50124550e+00 8.54743671e+00 8.46293354e+00 8.93129253e+00 8.57940102e+00 8.68832970e+00 9.00142097e+00 9.02846718e+00 8.79906654e+00 9.38977146e+00 9.57266140e+00 1.03420677e+01 9.91228008e+00 1.00527430e+01 1.00310450e+01 1.02799892e+01 1.01035604e+01 1.06483612e+01 1.12120628e+01 1.17487936e+01 1.11006126e+01 1.11377573e+01 1.11676550e+01 1.12818022e+01 1.11054182e+01 1.12444706e+01 1.18063316e+01 1.22574511e+01 1.25287428e+01 1.25221767e+01 1.25156088e+01 1.25594654e+01 1.22626123e+01 1.26020718e+01 1.27162886e+01 1.31036272e+01 1.35508881e+01 1.40781097e+01 1.41173458e+01 1.40146303e+01 1.40321569e+01 1.43582373e+01 1.43249121e+01 1.44712229e+01 1.46088467e+01 1.47477369e+01 1.49352541e+01 1.49590645e+01 1.50718565e+01 1.52619829e+01 1.53959703e+01 1.54663668e+01 1.58601933e+01 1.60610504e+01 1.59065123e+01 1.59531851e+01 1.60361538e+01 1.62673626e+01 1.65164089e+01 1.68645344e+01 1.70113926e+01 1.67826061e+01 1.66884537e+01 1.66595173e+01 1.70125179e+01 1.73656807e+01 1.76224785e+01 1.77380905e+01 1.76236897e+01 1.76661549e+01 1.75911217e+01 1.78458424e+01 1.81356144e+01 1.85274582e+01 1.85017033e+01 1.84497204e+01 1.84453220e+01 1.87202473e+01 1.88724957e+01 1.89217110e+01 1.88753834e+01 1.91290951e+01 1.92223587e+01 1.93300304e+01 1.94374256e+01 1.95820446e+01 1.96786861e+01 1.97113094e+01 1.98380222e+01 1.99809475e+01 2.00412617e+01 2.01416321e+01 2.02526226e+01 2.04177933e+01 2.04989967e+01 2.05574303e+01 2.06091175e+01 2.07147560e+01 2.08383350e+01 2.09473629e+01 2.10791969e+01 2.11608658e+01 2.12259712e+01 2.13592529e+01 2.14516335e+01 2.15672398e+01 2.16426849e+01 2.17381744e+01 2.18372021e+01 2.19209728e+01 2.20050507e+01 2.20879593e+01 2.21854267e+01 2.22733078e+01 2.23659668e+01 2.24633503e+01 2.25560970e+01 2.26410923e+01 2.27369709e+01 2.28242474e+01 2.29145069e+01 2.29914207e+01 2.30791740e+01 2.31697445e+01 2.32632771e+01 2.33606625e+01 2.34453297e+01 2.35105133e+01 2.35843258e+01 2.36724129e+01 2.37190304e+01 2.37970333e+01 2.38777122e+01 2.39308414e+01 2.40064602e+01 2.40846672e+01 2.41508713e+01 2.42249794e+01 2.42600346e+01 2.43337345e+01 2.44004135e+01 2.44635372e+01 2.45662785e+01 2.46190529e+01 2.46155205e+01 2.46897793e+01 2.47610531e+01 2.48531475e+01 2.49440327e+01 2.50425835e+01 2.50592670e+01 2.50886192e+01 2.51061935e+01 2.51991100e+01 2.51924782e+01 2.52563972e+01 2.52689552e+01 2.53329029e+01 2.52601261e+01 2.53086262e+01 2.53665218e+01 2.53551559e+01 2.54292603e+01 2.55204868e+01 2.56089935e+01 2.54871883e+01 2.55334244e+01 2.55486794e+01 2.55149822e+01 2.56103745e+01 2.57986317e+01 2.59904537e+01 2.59126625e+01 2.58779430e+01 2.57395859e+01 2.58059444e+01 2.58666821e+01 2.59594269e+01 2.56737232e+01 2.56761131e+01 2.58218594e+01 2.61569042e+01 2.63331299e+01 2.64826450e+01 2.61922226e+01 2.61478882e+01 2.63532352e+01 2.64842472e+01 2.62757969e+01 2.61541080e+01 2.61857433e+01 2.62808590e+01 2.57954617e+01 2.54428387e+01 2.55633698e+01 2.57402096e+01 2.56141090e+01 2.62251415e+01 2.63937340e+01 2.64614258e+01 2.60507717e+01 2.62314339e+01 2.64657116e+01 2.63443832e+01 2.64844341e+01 2.62705212e+01 2.64939556e+01 2.60366898e+01 2.59753494e+01 2.61345406e+01 2.62822304e+01 2.61431885e+01 2.62318611e+01 2.60022583e+01 2.64264088e+01 2.63790150e+01 2.67137280e+01 2.63352528e+01 2.62620544e+01 2.58849144e+01 2.59558163e+01 2.60361576e+01 2.58106785e+01 2.62163200e+01 2.61836433e+01 2.65648403e+01 2.68722305e+01 2.66858711e+01 2.69447556e+01 2.63872547e+01 2.67275448e+01 2.64342556e+01 2.60836697e+01 2.59167538e+01 2.56923313e+01 2.60016079e+01 2.60533695e+01 2.61899319e+01 2.65056210e+01 2.57622242e+01 2.53463593e+01 2.53218365e+01 2.53175049e+01 2.61615410e+01 2.68026428e+01 2.74650421e+01 2.67518616e+01 2.61429768e+01 2.54817657e+01 2.53992500e+01 2.49794788e+01 2.51791725e+01 2.51744766e+01 2.52965755e+01 2.46114922e+01 3.18383369e+01 3.41654625e+01 3.61652908e+01 3.48056717e+01 3.20986748e+01 3.17741356e+01 2.42640934e+01 2.43357906e+01 2.44072132e+01 2.48824406e+01 2.36215916e+01 1.83942432e+01 1.84729843e+01 1.90545746e+02 3.18846436e+02 7.12812073e+02 1.94963647e+03 -60530716. -258594160. 0. 0. 0. 2.47411738e+09 2.47411738e+09 2.47411738e+09 0. 0. 0. -131358120. -12028001. 4.35065283e+03 1.46256641e+03 5.33941772e+02 5.45680054e+02 3.58925232e+02 7.41854935e+01 7.70873184e+01 6.01129608e+01 3.92529106e+01 2.75622482e+01 3.16602802e+01 2.89503975e+01 2.14676437e+01 2.08135910e+01 2.09586182e+01 2.46894455e+01 3.95274925e+01 3.91885529e+01 2.37200165e+01 1.94804440e+01 1.93964939e+01 2.17340622e+01 1.85164051e+01 1.14168196e+01 1.27655106e+01 1.91769123e+01 2.41482182e+01 1.31150942e+01 1.46092892e+01 1.13477345e+01 -6.49850988e+00 1.16751995e+01 2.45378208e+01 1.82607880e+01 2.63004131e+01 2.95520515e+01 2.36303787e+01 2.06457844e+01 1.93320618e+01 1.94443588e+01 1.95641727e+01 2.02677307e+01 1.94517841e+01 1.90574379e+01 1.85247631e+01 1.86563396e+01 1.86693707e+01 1.87250996e+01 1.87060242e+01 1.86350384e+01 1.85844688e+01 1.89833965e+01 1.84495697e+01 1.81753025e+01 1.80776081e+01 1.76829166e+01 1.72349682e+01 1.67702160e+01 1.69123764e+01 1.75378418e+01 1.74897041e+01 1.72850456e+01 1.69161472e+01 1.68934097e+01 1.65474586e+01 1.62619743e+01 1.62422581e+01 1.60739384e+01 1.60490284e+01 1.73422718e+01 1.67568378e+01 1.60315170e+01 1.63292809e+01 1.60296097e+01 1.65494976e+01 1.62224522e+01 1.41600351e+01 1.75447330e+01 2.01132965e+01 1.82075844e+01 1.54975166e+01 1.36579990e+01 1.38160286e+01 1.37731895e+01 1.43954535e+01 1.48568964e+01 1.70976810e+01 1.93091736e+01 1.45700836e+01 3.74118271e+01 4.58789883e+04 1.63513412e+02 4.06479645e+01 4.01178818e+01 3.81305580e+01 3.80067368e+01 4.09712296e+01 4.25379372e+01 3.87195053e+01 3.84378624e+01 3.98074150e+01 3.97876472e+01 4.07799263e+01 4.03564987e+01 4.05100174e+01 4.02020988e+01 3.89685593e+01 3.67984161e+01 3.53347816e+01 3.62973175e+01 3.91325150e+01 4.09818649e+01 4.09114838e+01 4.09712639e+01 4.03520088e+01 3.96631699e+01 3.91562920e+01 3.89172325e+01 3.87539520e+01 3.87408600e+01 3.81612663e+01 3.83086357e+01 3.80871887e+01 3.81496544e+01 3.79402237e+01 3.77406311e+01 3.74018517e+01 3.73298569e+01 3.73096008e+01 3.73952751e+01 3.72619553e+01 3.63750725e+01 3.61712379e+01 3.57471581e+01 3.61320229e+01 3.56023445e+01 3.53588028e+01 3.50937881e+01 3.46964188e+01 3.43968582e+01 3.44037743e+01 3.42556496e+01 3.47148895e+01 3.42634811e+01 3.37877388e+01 3.34444237e+01 3.30177498e+01 3.31172142e+01 3.32543106e+01 3.29112892e+01 3.29718895e+01 3.29869614e+01 3.28771973e+01 3.24633255e+01 3.18886452e+01 3.15137005e+01 3.13030128e+01 3.08652973e+01 3.02772560e+01 3.04401779e+01 3.00462246e+01 3.01170006e+01 3.01277313e+01 2.98820190e+01 2.99559231e+01 3.01096916e+01 2.92096806e+01 2.86343002e+01 2.66834545e+01 2.46113968e+01 1.36623688e+01 -1.64745880e+02 -3.16849152e+02 -7.83515991e+02 -1.94551550e+03 301316256. 5868675. -70056360. -70056360. 0. -126921904. -126921904. -36096712. 92080408. 92080408. 0. 0. 0. 0. 2.22274099e+09 387926848. -1.78250574e+03 -6.21254761e+02 1.96401482e+01 -2.64170929e+02 -1.45902832e+02 2.13300667e+01 1.73550892e+01 1.28941689e+01 1.81362286e+01 1.99394512e+01 1.73462791e+01 1.68244267e+01 1.74962864e+01 2.19833488e+01 2.09935493e+01 2.00368137e+01 1.90513096e+01 1.93853149e+01 1.90043125e+01 1.90109386e+01 1.83964520e+01 1.81582260e+01 1.81005650e+01 1.77704792e+01 1.74759502e+01 1.69072247e+01 1.70408058e+01 1.67998638e+01 1.65859451e+01 1.64743767e+01 1.59835548e+01 1.54384756e+01 1.53345308e+01 1.52710075e+01 1.50422726e+01 1.48092937e+01 1.46014833e+01 1.42816124e+01 1.37262640e+01 1.37521381e+01 1.37605505e+01 1.36144400e+01 1.35090446e+01 1.32634888e+01 1.23748388e+01 1.22630033e+01 1.19477110e+01 1.15295324e+01 1.11532793e+01 1.08945637e+01 1.08046284e+01 1.08810101e+01 1.01842155e+01 9.48733234e+00 9.18875408e+00 8.67006302e+00 8.21802139e+00 7.65649843e+00 7.93594456e+00 7.72789717e+00 7.37048817e+00 7.31139851e+00 7.45036983e+00 7.54725552e+00 6.73870993e+00 6.34339571e+00 5.71419287e+00 5.37012005e+00 5.11310959e+00 5.15875006e+00 5.00947285e+00 4.65837049e+00 4.18460894e+00 3.90793943e+00 3.77226186e+00 3.57039118e+00 2.95700145e+00 2.87200713e+00 2.48984480e+00 2.47502947e+00 1.97051084e+00 1.91253412e+00 1.29765761e+00 1.08723390e+00 6.04283690e-01 5.39379776e-01 2.20225945e-01 2.28546724e-01 -5.44220395e-02 -4.62822825e-01 -7.94099092e-01 -1.14225984e+00 -1.24298918e+00 -1.72504961e+00 -1.98243690e+00 -2.23714304e+00 -2.46393776e+00 -2.75873256e+00 -2.99811387e+00 -3.45550394e+00 -3.71675873e+00 -4.05983210e+00 -4.22395515e+00 -4.47417927e+00 -4.71407461e+00 -5.10082388e+00 -5.45051241e+00 -5.59534121e+00 -5.79787493e+00 -5.99724579e+00 -6.37731171e+00 -6.78326845e+00 -7.06523180e+00 -7.29096413e+00 -7.63306236e+00 -8.00316906e+00 -8.41032600e+00 -8.53532600e+00 -8.74484825e+00 -9.03803349e+00 -9.35561562e+00 -9.66245651e+00 -9.86492157e+00 -1.01893263e+01 -1.05100527e+01 -1.07848215e+01 -1.10306797e+01 -1.12712517e+01 -1.16281204e+01 -1.18861465e+01 -1.21547441e+01 -1.23682327e+01 -1.26118345e+01 -1.28859167e+01 -1.31699619e+01 -1.33988581e+01 -1.36848116e+01 -1.39587746e+01 -1.42618237e+01 -1.45533800e+01 -1.48174667e+01 -1.50919428e+01 -1.53576527e+01 -1.56417036e+01 -1.59200449e+01 -1.61838779e+01 -1.64477997e+01 -1.67200737e+01 -1.69909115e+01 -1.72569656e+01 -1.75276031e+01 -1.77902279e+01 -1.80560207e+01 -1.83169155e+01 -1.85813828e+01 -1.88397369e+01 -1.91001091e+01 -1.93542385e+01 -1.96108932e+01 -1.98707371e+01 -2.01224365e+01 -2.03824120e+01 -2.06405544e+01 -2.09057808e+01 -2.11684151e+01 -2.14157639e+01 -2.16621094e+01 -2.18983212e+01 -2.21386890e+01 -2.23855381e+01 -2.26656685e+01 -2.29014950e+01 -2.31476116e+01 -2.33923244e+01 -2.36494560e+01 -2.38919315e+01 -2.41646233e+01 -2.43988457e+01 -2.46701012e+01 -2.49119549e+01 -2.51910419e+01 -2.53707199e+01 -2.56618671e+01 -2.58810844e+01 -2.60999031e+01 -2.62721272e+01 -2.66110783e+01 -2.68725796e+01 -2.71713352e+01 -2.73082829e+01 -2.75593700e+01 -2.77703781e+01 -2.80921345e+01 -2.83495712e+01 -2.85777569e+01 -2.87584114e+01 -2.88206387e+01 -2.91107979e+01 -2.92244759e+01 -2.94759560e+01 -2.97311573e+01 -2.99838905e+01 -3.01025429e+01 -3.01827393e+01 -3.03540802e+01 -3.06914616e+01 -3.10267277e+01 -3.13654079e+01 -3.14133644e+01 -3.15907707e+01 -3.17845707e+01 -3.19524059e+01 -3.22998466e+01 -3.26419449e+01 -3.26170006e+01 -3.29783096e+01 -3.32324257e+01 -3.32208710e+01 -3.34098816e+01 -3.37758904e+01 -3.37854309e+01 -3.38096771e+01 -3.39550323e+01 -3.40697823e+01 -3.44012642e+01 -3.46610565e+01 -3.49493675e+01 -3.50941124e+01 -3.53774834e+01 -3.56721230e+01 -3.60347824e+01 -3.59549866e+01 -3.61742744e+01 -3.56879272e+01 -3.61802979e+01 -3.65097198e+01 -3.69069481e+01 -3.69608574e+01 -3.68150749e+01 -3.73467064e+01 -3.74930153e+01 -3.76246300e+01 -3.78190613e+01 -3.79677925e+01 -3.85177383e+01 -3.83161163e+01 -3.85730896e+01 -3.82905006e+01 -3.86112213e+01 -3.83118286e+01 -3.86934052e+01 -3.87803764e+01 -3.89345703e+01 -3.92143707e+01 -3.95440712e+01 -3.95004692e+01 -3.95961571e+01 -4.01682510e+01 -4.07346115e+01 -4.11535263e+01 -4.10644684e+01 -4.12282906e+01 -4.07405281e+01 -4.11713333e+01 -4.12039795e+01 -4.11114807e+01 -4.08949203e+01 -4.04192924e+01 -4.13283997e+01 -4.13658218e+01 -4.17454224e+01 -4.15581207e+01 -4.13264427e+01 -4.20529480e+01 -4.20064049e+01 -4.25245018e+01 -4.19770546e+01 -4.20571823e+01 -4.29625359e+01 -4.30806274e+01 -4.31836052e+01 -4.28376350e+01 -4.30925903e+01 -4.30273590e+01 -4.32499428e+01 -4.32824478e+01 -4.34526634e+01 -4.40974541e+01 -4.41112900e+01 -4.39593239e+01 -4.36470337e+01 -4.41332436e+01 -4.42145042e+01 -4.39709854e+01 -4.40607338e+01 -4.44206085e+01 -4.44614296e+01 -4.49690857e+01 -4.58379326e+01 -4.59786758e+01 -4.58054695e+01 -4.55352173e+01 -4.53692284e+01 -4.49359779e+01 -4.48382225e+01 -4.53140450e+01 -4.61409569e+01 -4.65238647e+01 -4.56401672e+01 -4.47715302e+01 -4.51326141e+01 -4.50337753e+01 -4.53995819e+01 -4.51714935e+01 -4.63967590e+01 -4.65269165e+01 -4.58725243e+01 -4.55445824e+01 -4.55961151e+01 -4.62257652e+01 -4.58061752e+01 -4.57570076e+01 -4.51945343e+01 -4.51567001e+01 -4.54134674e+01 -4.62481613e+01 -4.64585190e+01 -4.62254524e+01 -4.59786148e+01 -4.61459999e+01 -4.65736961e+01 -4.65067596e+01 -4.57389755e+01 -4.58106461e+01 -4.57100868e+01 -4.63194923e+01 -4.60294037e+01 -4.62586021e+01 -4.56880836e+01 -4.60003090e+01 -4.57478294e+01 -4.60316353e+01 -4.56082954e+01 -4.63662834e+01 -4.62337379e+01 -4.60525284e+01 -4.63427582e+01 -4.64662132e+01 -4.70990639e+01 -4.65650063e+01 -4.61980782e+01 -4.62425804e+01 -4.63114319e+01 -4.62146225e+01 -4.64998245e+01 -4.63869057e+01 -4.67106552e+01 -4.66008568e+01 -4.66242142e+01 -4.65805321e+01 -4.64594650e+01 -4.61247139e+01 -4.56436996e+01 -4.59165230e+01 -4.62682381e+01 -4.64986725e+01 -4.63332100e+01 -4.59879723e+01 -4.61817474e+01 -4.61730804e+01 -4.58409920e+01 -4.51549873e+01 -4.52796364e+01 -4.57086296e+01 -4.58741798e+01 -4.54284286e+01 -4.49907761e+01 -4.51337166e+01 -4.53861465e+01 -4.52940674e+01 -4.50636597e+01 -4.51443024e+01 -4.52278214e+01 -4.51751289e+01 -4.46475220e+01 -4.48101196e+01 -4.45665016e+01 -4.47012024e+01 -4.46665230e+01 -4.48698807e+01 -4.47629204e+01 -4.49946098e+01 -4.48012962e+01 -4.43605881e+01 -4.40319977e+01 -4.38124962e+01 -4.39086609e+01 -4.41008949e+01 -4.41575432e+01 -4.38951378e+01 -4.37138634e+01 -4.35415573e+01 -4.33067932e+01 -4.32611961e+01 -4.31099281e+01 -4.30433235e+01 -4.29873314e+01 -4.29378433e+01 -4.28889999e+01 -4.26417313e+01 -4.24595375e+01 -4.25790253e+01 -4.24640884e+01 -4.20030098e+01 -4.20435600e+01 -4.19991150e+01 -4.16735687e+01 -4.17289429e+01 -4.15868340e+01 -4.14133034e+01 -4.15108871e+01 -4.10890694e+01 -4.07908096e+01 -4.08093414e+01 -4.07871666e+01 -4.07405396e+01 -4.07385139e+01 -4.04299736e+01 -4.02748985e+01 -4.03711433e+01 -4.00232773e+01 -3.96613312e+01 -3.97639923e+01 -3.94693604e+01 -3.95212326e+01 -3.94449081e+01 -3.89993248e+01 -3.85981789e+01 -3.86457100e+01 -3.85802078e+01 -3.87963753e+01 -3.84295807e+01 -3.84260139e+01 -3.78443832e+01 -3.81000862e+01 -3.78417168e+01 -3.75350342e+01 -3.73318748e+01 -3.72831154e+01 -3.73554344e+01 -3.73492165e+01 -3.71484337e+01 -3.65675163e+01 -3.63537636e+01 -3.58086929e+01 -3.61304550e+01 -3.57028275e+01 -3.54038277e+01 -3.52848892e+01 -3.49405441e+01 -3.46429787e+01 -3.48566170e+01 -3.45707207e+01 -3.45129318e+01 -3.41919975e+01 -3.36892395e+01 -3.35598526e+01 -3.30739059e+01 -3.32067413e+01 -3.31509247e+01 -3.27702026e+01 -3.26095467e+01 -3.29480667e+01 -3.31143761e+01 -3.26405754e+01 -3.19596024e+01 -3.12635727e+01 -3.11048183e+01 -3.09892082e+01 -3.06204700e+01 -3.08958492e+01 -3.04718666e+01 -3.03473759e+01 -2.96198215e+01 -2.96988258e+01 -2.99814072e+01 -2.98989868e+01 -2.91688671e+01 -2.88231869e+01 -2.80667362e+01 -2.82732906e+01 -2.85458717e+01 -2.87766628e+01 -2.84707966e+01 -2.78449421e+01 -2.74949474e+01 -2.71195068e+01 -2.73625278e+01 -2.71649132e+01 -2.67943993e+01 -2.68988380e+01 -2.65253086e+01 -2.61988850e+01 -2.58039017e+01 -2.56410503e+01 -2.48321533e+01 -2.45878162e+01 -2.48052826e+01 -2.44721794e+01 -2.45730057e+01 -2.39134960e+01 -2.34967766e+01 -2.36222839e+01 -2.37462234e+01 -2.38386688e+01 -2.36646976e+01 -2.34070492e+01 -2.35563889e+01 -2.21961823e+01 -2.20426121e+01 -2.13425064e+01 -2.08281708e+01 -2.04327679e+01 -1.98645306e+01 -2.07571411e+01 -2.01090660e+01 -1.98693333e+01 -1.94926052e+01 -1.87857952e+01 -1.92037354e+01 -1.88892555e+01 -1.92697945e+01 -1.85572491e+01 -1.81475677e+01 -1.82885857e+01 -1.83305340e+01 -1.79136162e+01 -1.74735928e+01 -1.73335819e+01 -1.69548054e+01 -1.66265030e+01 -1.64307785e+01 -1.61187134e+01 -1.62461624e+01 -1.58089075e+01 -1.51198959e+01 -1.47402630e+01 -1.47531586e+01 -1.45941610e+01 -1.40149641e+01 -1.35433493e+01 -1.33451490e+01 -1.34222870e+01 -1.36251783e+01 -1.37701578e+01 -1.36579800e+01 -1.30804853e+01 -1.26740885e+01 -1.23402586e+01 -1.16331940e+01 -1.07455730e+01 -1.10671597e+01 -1.09573641e+01 -1.09119711e+01 -1.01148767e+01 -9.46589851e+00 -9.39039707e+00 -9.18072128e+00 -9.04724216e+00 -8.50467777e+00 -8.57875729e+00 -8.38920212e+00 -7.75383139e+00 -7.61909008e+00 -7.42136192e+00 -7.40534735e+00 -6.60516644e+00 -6.21889162e+00 -5.67274523e+00 -5.34926796e+00 -5.30967331e+00 -5.49734020e+00 -5.27006292e+00 -4.88960695e+00 -4.44292307e+00 -4.00918102e+00 -3.88035297e+00 -3.65704489e+00 -3.03854775e+00 -2.70738220e+00 -2.27857065e+00 -2.25788569e+00 -1.88870883e+00 -1.86376727e+00 -1.29781103e+00 -1.07243967e+00 -7.62718379e-01 -6.76392794e-01 -2.96256065e-01 -2.84901142e-01 4.66391370e-02 4.06028658e-01 6.24840260e-01 1.01341903e+00 1.20950127e+00 1.61190474e+00 1.93246877e+00 2.10153604e+00 2.35905099e+00 2.62401819e+00 2.91376901e+00 3.23860645e+00 3.47072244e+00 3.90133786e+00 4.24883556e+00 4.54433823e+00 4.77812529e+00 5.04698896e+00 5.43843365e+00 5.66661644e+00 5.88631725e+00 6.08304024e+00 6.41188574e+00 6.76974869e+00 7.03977823e+00 7.32627439e+00 7.59148121e+00 7.92181730e+00 8.22412205e+00 8.46951866e+00 8.67472076e+00 8.95493698e+00 9.31051540e+00 9.61179924e+00 9.81685925e+00 1.00590048e+01 1.04147024e+01 1.06637793e+01 1.08806276e+01 1.11366196e+01 1.14948282e+01 1.17899160e+01 1.20289145e+01 1.22167540e+01 1.24737339e+01 1.27382774e+01 1.30284271e+01 1.33040190e+01 1.36095982e+01 1.38773546e+01 1.41625071e+01 1.44642382e+01 1.47413120e+01 1.50189934e+01 1.52767878e+01 1.55340214e+01 1.58222332e+01 1.61062050e+01 1.63857861e+01 1.66556549e+01 1.69321423e+01 1.71917057e+01 1.74634457e+01 1.77279606e+01 1.79889297e+01 1.82531357e+01 1.85213966e+01 1.87829113e+01 1.90473709e+01 1.93071728e+01 1.95813160e+01 1.98523293e+01 2.01218090e+01 2.03871479e+01 2.06529179e+01 2.08870773e+01 2.11339188e+01 2.13950176e+01 2.16454716e+01 2.19105339e+01 2.21928558e+01 2.24231606e+01 2.27054062e+01 2.29527626e+01 2.32172718e+01 2.34924793e+01 2.37264690e+01 2.39643459e+01 2.42148361e+01 2.44204407e+01 2.47076893e+01 2.49537296e+01 2.51538296e+01 2.53941784e+01 2.56157608e+01 2.58129025e+01 2.61193600e+01 2.62803860e+01 2.65338135e+01 2.66960144e+01 2.70402660e+01 2.72951622e+01 2.75304928e+01 2.77113323e+01 2.80250187e+01 2.81915932e+01 2.83974495e+01 2.86004925e+01 2.87138138e+01 2.89548149e+01 2.90482368e+01 2.93906517e+01 2.95837193e+01 2.97902241e+01 2.98964214e+01 3.00520573e+01 3.02241173e+01 3.05275612e+01 3.07780514e+01 3.11667423e+01 3.12198677e+01 3.13061981e+01 3.15537987e+01 3.18228512e+01 3.21908340e+01 3.25587273e+01 3.24790764e+01 3.28159180e+01 3.31250916e+01 3.32813568e+01 3.34385567e+01 3.36857414e+01 3.36546135e+01 3.36706657e+01 3.38587456e+01 3.40531616e+01 3.43915596e+01 3.44883308e+01 3.48134613e+01 3.49441032e+01 3.51983452e+01 3.54647408e+01 3.59303780e+01 3.58646889e+01 3.59342003e+01 3.55810204e+01 3.62785339e+01 3.65147629e+01 3.68537598e+01 3.69557724e+01 3.68906403e+01 3.73391075e+01 3.73532486e+01 3.75745010e+01 3.78116379e+01 3.79666710e+01 3.85267029e+01 3.84482956e+01 3.84614334e+01 3.82372704e+01 3.85108299e+01 3.83782310e+01 3.87294998e+01 3.90360260e+01 3.91860352e+01 3.95326157e+01 3.95740623e+01 3.94922600e+01 3.95988083e+01 4.00163269e+01 4.07526093e+01 4.11619034e+01 4.12876587e+01 4.15868149e+01 4.09560089e+01 4.12951622e+01 4.12454147e+01 4.06789131e+01 4.05764618e+01 4.03215485e+01 4.13466187e+01 4.12482262e+01 4.13717422e+01 4.13577957e+01 4.11760330e+01 4.21733131e+01 4.21608734e+01 4.25112839e+01 4.20609283e+01 4.23445816e+01 4.32014160e+01 4.34233932e+01 4.32839737e+01 4.30409698e+01 4.33334579e+01 4.33821564e+01 4.34332504e+01 4.31341972e+01 4.30345955e+01 4.33543892e+01 4.38616180e+01 4.42037926e+01 4.40000038e+01 4.40299416e+01 4.38707542e+01 5.28805885e+01 5.40295258e+01 5.33306427e+01 5.29437599e+01 4.91139832e+01 4.94705772e+01 4.56768494e+01 4.71993256e+01 4.70790672e+01 4.49705772e+01 4.45266724e+01 3.77007751e+01 3.82530594e+01 2.36340591e+02 4.16383270e+02 1.01263953e+03 2.31445728e+03 1403066240. -947091392. 0. 2.47411738e+09 2.47411738e+09 2.47411738e+09 0. 0. -440080640. -440080640. -440080640. -685678592. 9506764. 2.37407754e+04 1.85423694e+03 1.09285828e+03 5.17954834e+02 3.59482819e+02 9.55672379e+01 8.27731400e+01 6.61838150e+01 6.56103439e+01 5.19119377e+01 2.24408913e+01 2.23257046e+01 6.52679214e+01 7.41602859e+01 6.39741249e+01 5.49142151e+01 4.65832024e+01 4.49763336e+01 4.55927048e+01 4.76069221e+01 4.82640419e+01 4.30610008e+01 2.65177727e+01 3.10871143e+01 5.36858215e+01 4.10763397e+01 5.56421356e+01 4.97553062e+01 1.84932652e+01 3.33801117e+01 4.55314865e+01 4.60398407e+01 5.50148773e+01 5.27223740e+01 4.48190536e+01 4.87302971e+01 4.92733345e+01 4.81215324e+01 4.70989075e+01 4.63348923e+01 4.60498085e+01 4.62261772e+01 4.65454521e+01 4.64532204e+01 4.60246582e+01 4.61746635e+01 4.62786293e+01 4.59491577e+01 4.52875748e+01 4.52890854e+01 4.54525642e+01 4.54671555e+01 4.54625015e+01 4.49982109e+01 4.78764915e+01 4.71687317e+01 4.73650169e+01 4.92482910e+01 4.60037766e+01 4.45207443e+01 4.46808395e+01 4.47083397e+01 4.48253441e+01 4.48139038e+01 4.47233925e+01 4.43773575e+01 4.45923576e+01 4.57235718e+01 4.53427544e+01 4.44711075e+01 4.46910362e+01 4.39438782e+01 4.47224312e+01 4.44694786e+01 4.26159935e+01 4.59920311e+01 4.84673843e+01 4.60844307e+01 4.25293274e+01 4.04160347e+01 4.10435486e+01 4.10270233e+01 4.20133324e+01 4.29559059e+01 4.57430992e+01 4.78050423e+01 4.20400391e+01 1.19753632e+02 2.26145547e+05 2.42359940e+02 -1.43161804e+02 -2.91860138e+02 1.11807800e+02 1.11299927e+02 1.26570663e+02 1.35928070e+02 1.12581100e+02 1.13396988e+02 1.18254684e+02 1.13340607e+02 1.19948586e+02 4.54073700e+02 2.93957642e+02 6.00308189e+01 6.75492401e+01 6.03040962e+01 5.74977188e+01 5.76249924e+01 6.01052284e+01 6.16224174e+01 6.15676270e+01 6.08245049e+01 5.99983330e+01 5.95047607e+01 5.92250557e+01 5.92582817e+01 5.91072655e+01 5.98105583e+01 5.95411110e+01 5.90451813e+01 5.82309036e+01 5.79497643e+01 5.79271393e+01 5.78979187e+01 5.78604088e+01 5.78460693e+01 5.75920792e+01 5.73946877e+01 5.71185226e+01 5.69808197e+01 5.66363411e+01 5.67192879e+01 5.70613976e+01 5.67927818e+01 5.60565834e+01 5.56766624e+01 5.51634903e+01 5.51434326e+01 5.42819366e+01 5.44283409e+01 5.45397415e+01 5.44469070e+01 5.42501297e+01 5.43898735e+01 5.39260330e+01 5.40851212e+01 5.40490761e+01 5.43690796e+01 5.37041740e+01 5.33292084e+01 5.22528725e+01 5.21010551e+01 5.19710732e+01 5.19612885e+01 5.15361938e+01 5.08906021e+01 5.08796997e+01 5.05565453e+01 5.02566986e+01 4.99818382e+01 5.04228668e+01 5.01438370e+01 4.99516296e+01 4.95901184e+01 4.85653000e+01 4.49778252e+01 3.39505730e+01 3.23213615e+01 -1.68064835e+02 -7.11646729e+02 -2.13537085e+03 116564224. 292684096. 0. -70056360. -70056360. -70056360. 0. -126921904. -126921904. -36096712. 92080408. -22965170. -176459200. -176459200. 0. -291323936. -3.15922852e+03 -7.36492798e+02 -2.80058014e+02 -1.30441574e+02 3.47167358e+01 4.29266472e+01 4.14477654e+01 3.50104752e+01 3.28257828e+01 3.69484520e+01 4.37646065e+01 3.97072601e+01 3.59046898e+01 3.99939308e+01 3.98188705e+01 3.86113739e+01 3.81350250e+01 3.73800735e+01 3.75117950e+01 3.71032791e+01 3.69859123e+01 3.65454063e+01 3.64220352e+01 3.61523132e+01 3.56435356e+01 3.49084854e+01 3.40758667e+01 3.34770088e+01 3.37390480e+01 3.36754799e+01 3.37008934e+01 3.37679749e+01 3.31290016e+01 3.27566032e+01 3.20197601e+01 3.15865841e+01 3.14393444e+01 3.09615593e+01 3.08649216e+01 3.10955124e+01 3.13662434e+01 3.12536259e+01 3.00310593e+01 2.92981968e+01 2.82312241e+01 2.79604206e+01 2.70910149e+01 2.73703346e+01 2.70675125e+01 2.72262688e+01 2.69241581e+01 2.64619789e+01 2.61889153e+01 2.53895912e+01 2.49953480e+01 2.46652374e+01 2.42507572e+01 2.40915909e+01 2.30691109e+01 2.27454605e+01 2.23042088e+01 2.21444454e+01 2.17941723e+01 2.17001839e+01 2.15995960e+01 2.15759640e+01 2.13511734e+01 2.09375343e+01 2.02180176e+01 1.95485668e+01 1.93311615e+01 1.90757580e+01 1.83997307e+01 1.80277367e+01 1.79097843e+01 1.78585815e+01 1.72427769e+01 1.67964478e+01 1.60996513e+01 1.57704868e+01 1.53372068e+01 1.49638538e+01 1.47672663e+01 1.45683508e+01 1.40792656e+01 1.35086679e+01 1.30331182e+01 1.25990553e+01 1.22610188e+01 1.20878010e+01 1.19678211e+01 1.15354958e+01 1.06869860e+01 1.02474222e+01 9.84705162e+00 9.59215164e+00 9.31268215e+00 8.99650860e+00 8.59932995e+00 7.89347219e+00 7.57835770e+00 7.07119370e+00 6.86983585e+00 6.64024544e+00 6.37640238e+00 5.96425009e+00 5.34232092e+00 4.89106941e+00 4.43534040e+00 4.11586714e+00 3.80891466e+00 3.42026281e+00 2.92940354e+00 2.35498357e+00 1.99219120e+00 1.69863832e+00 1.33227384e+00 9.13810074e-01 4.52353925e-01 1.05939977e-01 -2.23590672e-01 -5.40583909e-01 -1.02118444e+00 -1.45998025e+00 -1.83774757e+00 -2.18881249e+00 -2.61252308e+00 -3.00433278e+00 -3.39979863e+00 -3.78602386e+00 -4.18849516e+00 -4.56265020e+00 -4.99169254e+00 -5.34488297e+00 -5.71606684e+00 -6.11724615e+00 -6.53467226e+00 -6.90416193e+00 -7.29100132e+00 -7.69780636e+00 -8.12615681e+00 -8.51730728e+00 -8.90070152e+00 -9.28462887e+00 -9.66149902e+00 -1.00431185e+01 -1.04591150e+01 -1.08454075e+01 -1.12420206e+01 -1.16408806e+01 -1.20220928e+01 -1.23946400e+01 -1.27864618e+01 -1.31722612e+01 -1.35639906e+01 -1.39504604e+01 -1.43360243e+01 -1.47216644e+01 -1.51074038e+01 -1.54890785e+01 -1.58690062e+01 -1.62474747e+01 -1.66287022e+01 -1.70213985e+01 -1.74142170e+01 -1.78107128e+01 -1.82114925e+01 -1.85929127e+01 -1.89520683e+01 -1.93215637e+01 -1.97198315e+01 -2.00960255e+01 -2.04568329e+01 -2.08269882e+01 -2.12312870e+01 -2.16058941e+01 -2.19824543e+01 -2.23720436e+01 -2.27371216e+01 -2.31540031e+01 -2.35475883e+01 -2.39155788e+01 -2.42987423e+01 -2.45792713e+01 -2.49487324e+01 -2.52988300e+01 -2.56510010e+01 -2.59782619e+01 -2.63982677e+01 -2.67333755e+01 -2.71262302e+01 -2.74416695e+01 -2.78714142e+01 -2.81829758e+01 -2.86250477e+01 -2.89114475e+01 -2.92655659e+01 -2.95898170e+01 -2.98514557e+01 -3.03674126e+01 -3.07125587e+01 -3.09817066e+01 -3.14357052e+01 -3.18075752e+01 -3.20137939e+01 -3.20684776e+01 -3.24110718e+01 -3.26733742e+01 -3.31853638e+01 -3.35205460e+01 -3.37999878e+01 -3.41981087e+01 -3.47059212e+01 -3.50229836e+01 -3.53975258e+01 -3.57571411e+01 -3.62305984e+01 -3.65433273e+01 -3.67737885e+01 -3.65400925e+01 -3.69177666e+01 -3.74012680e+01 -3.79386330e+01 -3.81516037e+01 -3.83545647e+01 -3.85503464e+01 -3.88657188e+01 -3.93258820e+01 -3.98172989e+01 -4.03056908e+01 -4.06100845e+01 -4.10330925e+01 -4.13245735e+01 -4.15390701e+01 -4.19823685e+01 -4.19137383e+01 -4.20379219e+01 -4.25144844e+01 -4.29852448e+01 -4.34385681e+01 -4.34308624e+01 -4.37109528e+01 -4.37385521e+01 -4.39915619e+01 -4.42556953e+01 -4.45253716e+01 -4.47483025e+01 -4.51648674e+01 -4.53687248e+01 -4.58013420e+01 -4.58211899e+01 -4.58486671e+01 -4.59529915e+01 -4.63412819e+01 -4.66439285e+01 -4.70380325e+01 -4.74611053e+01 -4.78586502e+01 -4.81359138e+01 -4.83315315e+01 -4.90087738e+01 -4.93082008e+01 -4.93033524e+01 -4.93217087e+01 -4.91142654e+01 -4.94456978e+01 -4.98036308e+01 -5.04597816e+01 -5.02613907e+01 -5.02807770e+01 -5.09608307e+01 -5.08485146e+01 -5.16402168e+01 -5.13820648e+01 -5.19877968e+01 -5.21879425e+01 -5.25336533e+01 -5.27182846e+01 -5.26084595e+01 -5.29217834e+01 -5.34086342e+01 -5.36390800e+01 -5.32160149e+01 -5.33049240e+01 -5.39993668e+01 -5.46812744e+01 -5.48082771e+01 -5.48435287e+01 -5.51325531e+01 -5.52308769e+01 -5.55317726e+01 -5.54247169e+01 -5.57686958e+01 -5.56781769e+01 -5.59100838e+01 -5.65570946e+01 -5.76556931e+01 -5.82661018e+01 -5.75610161e+01 -5.75648918e+01 -5.73831482e+01 -5.78123817e+01 -5.70128822e+01 -5.73750114e+01 -5.75328293e+01 -5.85280952e+01 -5.82272377e+01 -5.85503387e+01 -5.90189972e+01 -5.87675362e+01 -5.84337387e+01 -5.90226364e+01 -5.89644928e+01 -6.00923386e+01 -5.94524803e+01 -5.98829002e+01 -5.98393631e+01 -6.02989273e+01 -6.01563301e+01 -6.02355957e+01 -6.01805611e+01 -6.08938179e+01 -6.12353134e+01 -6.12808495e+01 -6.09351463e+01 -6.05107193e+01 -6.07977524e+01 -6.13281555e+01 -6.10982971e+01 -6.08598099e+01 -6.16192055e+01 -6.19384575e+01 -6.20024529e+01 -6.18649902e+01 -6.15250854e+01 -6.18375587e+01 -6.20065956e+01 -6.25418053e+01 -6.29962845e+01 -6.33847275e+01 -6.28980980e+01 -6.27641754e+01 -6.27439308e+01 -6.26937294e+01 -6.27799721e+01 -6.32155914e+01 -6.37522469e+01 -6.37221069e+01 -6.30997467e+01 -6.30788994e+01 -6.32996483e+01 -6.38476524e+01 -6.41364136e+01 -6.42700272e+01 -6.41060715e+01 -6.34035378e+01 -6.36641541e+01 -6.32196922e+01 -6.38148956e+01 -6.40615845e+01 -6.43856964e+01 -6.43341370e+01 -6.40421753e+01 -6.41232300e+01 -6.40427399e+01 -6.38575249e+01 -6.39251328e+01 -6.38304710e+01 -6.38239098e+01 -6.36932144e+01 -6.38137894e+01 -6.40875397e+01 -6.40401611e+01 -6.40872192e+01 -6.38662033e+01 -6.41658554e+01 -6.41473846e+01 -6.38879166e+01 -6.37020950e+01 -6.41299362e+01 -6.43658142e+01 -6.44322205e+01 -6.42264252e+01 -6.42206497e+01 -6.41186905e+01 -6.41200104e+01 -6.39141808e+01 -6.42541046e+01 -6.39933243e+01 -6.38275299e+01 -6.36940804e+01 -6.39266052e+01 -6.39597015e+01 -6.42000885e+01 -6.40794983e+01 -6.38990135e+01 -6.36470947e+01 -6.34830627e+01 -6.35113525e+01 -6.37146988e+01 -6.37005157e+01 -6.37629128e+01 -6.33411293e+01 -6.32320862e+01 -6.32519531e+01 -6.31892128e+01 -6.29590149e+01 -6.27906303e+01 -6.28283081e+01 -6.29123116e+01 -6.27392921e+01 -6.25998230e+01 -6.24917870e+01 -6.25034866e+01 -6.24207535e+01 -6.20460320e+01 -6.20696640e+01 -6.19852943e+01 -6.17989006e+01 -6.18597946e+01 -6.17520905e+01 -6.17616959e+01 -6.17745476e+01 -6.13654060e+01 -6.11320190e+01 -6.11471062e+01 -6.12501221e+01 -6.10940514e+01 -6.10030823e+01 -6.05816422e+01 -6.05147476e+01 -6.07616692e+01 -6.06297340e+01 -6.05162125e+01 -6.04988480e+01 -6.00908279e+01 -5.98827858e+01 -5.97511635e+01 -5.96564903e+01 -5.92578964e+01 -5.93036308e+01 -5.91048431e+01 -5.90101471e+01 -5.85485458e+01 -5.84993095e+01 -5.79644356e+01 -5.80430527e+01 -5.78272591e+01 -5.77673340e+01 -5.78850517e+01 -5.79141769e+01 -5.75301247e+01 -5.71021576e+01 -5.64965401e+01 -5.66242104e+01 -5.64002953e+01 -5.63642197e+01 -5.67467918e+01 -5.63283119e+01 -5.58862495e+01 -5.57918358e+01 -5.52555046e+01 -5.51811447e+01 -5.45072594e+01 -5.45146332e+01 -5.42912140e+01 -5.43429642e+01 -5.42711143e+01 -5.45043297e+01 -5.41434402e+01 -5.42117157e+01 -5.41265640e+01 -5.43740540e+01 -5.35790176e+01 -5.34010696e+01 -5.25505562e+01 -5.20885429e+01 -5.17257576e+01 -5.16768341e+01 -5.15981483e+01 -5.12406654e+01 -5.11872711e+01 -5.07870522e+01 -5.04750595e+01 -5.02710686e+01 -5.03667221e+01 -5.02827225e+01 -5.02430687e+01 -4.97980576e+01 -4.95809593e+01 -4.96738586e+01 -4.91244659e+01 -4.85628624e+01 -4.85651627e+01 -4.81954041e+01 -4.79159737e+01 -4.73933716e+01 -4.70164566e+01 -4.65316658e+01 -4.64100189e+01 -4.67474060e+01 -4.63637695e+01 -4.64368820e+01 -4.61378021e+01 -4.53466225e+01 -4.50129738e+01 -4.45226288e+01 -4.38036919e+01 -4.34710617e+01 -4.34189529e+01 -4.31657181e+01 -4.28889580e+01 -4.29284630e+01 -4.26019821e+01 -4.26187820e+01 -4.23269272e+01 -4.24953842e+01 -4.20346832e+01 -4.12984009e+01 -4.08451004e+01 -3.99837456e+01 -3.97282257e+01 -3.91454849e+01 -3.94812775e+01 -3.88697281e+01 -3.86531105e+01 -3.89333572e+01 -3.81558304e+01 -3.81741180e+01 -3.76219902e+01 -3.75968285e+01 -3.73159027e+01 -3.72313232e+01 -3.69716873e+01 -3.65288048e+01 -3.61134262e+01 -3.57368927e+01 -3.50911064e+01 -3.40933876e+01 -3.38523674e+01 -3.42223625e+01 -3.39740448e+01 -3.36361618e+01 -3.33586044e+01 -3.31021996e+01 -3.25191154e+01 -3.20178146e+01 -3.14876308e+01 -3.16174545e+01 -3.08564453e+01 -3.05711021e+01 -3.07651939e+01 -3.11718025e+01 -3.11600361e+01 -2.99520550e+01 -2.94823208e+01 -2.87884922e+01 -2.85294170e+01 -2.75229511e+01 -2.72408142e+01 -2.71058788e+01 -2.70932674e+01 -2.62493095e+01 -2.60671978e+01 -2.56931419e+01 -2.51063404e+01 -2.49168205e+01 -2.48187714e+01 -2.43884850e+01 -2.44581890e+01 -2.37775745e+01 -2.35622997e+01 -2.29615040e+01 -2.27741909e+01 -2.21605263e+01 -2.19073277e+01 -2.15545864e+01 -2.12739716e+01 -2.11195221e+01 -2.06760998e+01 -2.00311432e+01 -1.93246288e+01 -1.92128220e+01 -1.91096382e+01 -1.84233665e+01 -1.80271225e+01 -1.80103455e+01 -1.77526398e+01 -1.71473942e+01 -1.66212692e+01 -1.59940901e+01 -1.57718248e+01 -1.53773117e+01 -1.50461731e+01 -1.49252310e+01 -1.46943855e+01 -1.41459141e+01 -1.36763563e+01 -1.33330736e+01 -1.28688259e+01 -1.24353676e+01 -1.21099072e+01 -1.18686504e+01 -1.16005154e+01 -1.09232149e+01 -1.03145161e+01 -9.97855091e+00 -9.83555984e+00 -9.55294418e+00 -9.10537243e+00 -8.71240234e+00 -8.12727833e+00 -7.83339071e+00 -7.25245762e+00 -6.94009495e+00 -6.50016975e+00 -6.26476622e+00 -5.88746214e+00 -5.36300564e+00 -4.92810011e+00 -4.45347023e+00 -4.06928825e+00 -3.71048284e+00 -3.38602948e+00 -2.98681641e+00 -2.44521403e+00 -2.08573985e+00 -1.70853376e+00 -1.33274329e+00 -9.95314121e-01 -6.27647698e-01 -2.05344945e-01 1.97088465e-01 5.77293992e-01 1.03653073e+00 1.35315621e+00 1.73124886e+00 2.07395792e+00 2.48276424e+00 2.88888240e+00 3.29106188e+00 3.67740107e+00 4.08308125e+00 4.46135044e+00 4.85338974e+00 5.23639870e+00 5.65496540e+00 6.00426435e+00 6.39635324e+00 6.77914858e+00 7.18161583e+00 7.57500267e+00 7.98873901e+00 8.40224552e+00 8.78202820e+00 9.14165974e+00 9.51285744e+00 9.89909935e+00 1.03108921e+01 1.06932716e+01 1.10939980e+01 1.14879179e+01 1.18854704e+01 1.22728176e+01 1.26623783e+01 1.30469131e+01 1.34261427e+01 1.38208027e+01 1.42072220e+01 1.45889063e+01 1.49675150e+01 1.53428507e+01 1.57274189e+01 1.61012497e+01 1.64766293e+01 1.68627243e+01 1.72437172e+01 1.76110783e+01 1.79849949e+01 1.83785362e+01 1.87446079e+01 1.91098671e+01 1.95155487e+01 1.98743038e+01 2.02686291e+01 2.06392403e+01 2.10342407e+01 2.14401245e+01 2.18226700e+01 2.22169189e+01 2.25276604e+01 2.28733711e+01 2.32783661e+01 2.36544075e+01 2.39847202e+01 2.43274727e+01 2.47474613e+01 2.50811043e+01 2.54937820e+01 2.58486347e+01 2.62056599e+01 2.64760284e+01 2.68710232e+01 2.72875214e+01 2.76756725e+01 2.80451336e+01 2.84659557e+01 2.87338161e+01 2.90464344e+01 2.92683697e+01 2.96610966e+01 3.00786819e+01 3.05291653e+01 3.09303341e+01 3.12585640e+01 3.15406380e+01 3.18184624e+01 3.20038414e+01 3.22544403e+01 3.24612999e+01 3.28846512e+01 3.32751923e+01 3.36492958e+01 3.39833946e+01 3.45162697e+01 3.48133011e+01 3.52019806e+01 3.56407356e+01 3.59897423e+01 3.62539444e+01 3.66579895e+01 3.65346565e+01 3.68996201e+01 3.72852097e+01 3.77827034e+01 3.80540276e+01 3.83158798e+01 3.86767006e+01 3.89245796e+01 3.92872047e+01 3.97494011e+01 4.02072182e+01 4.05534325e+01 4.08073921e+01 4.11015167e+01 4.14823723e+01 4.17913399e+01 4.17739029e+01 4.20896835e+01 4.25352020e+01 4.28964958e+01 4.31986465e+01 4.32328262e+01 4.35730705e+01 4.35677567e+01 4.39575081e+01 4.42158203e+01 4.43446999e+01 4.45341148e+01 4.52112083e+01 4.52647476e+01 4.55195656e+01 4.56260033e+01 4.57430229e+01 4.60436172e+01 4.63406906e+01 4.65858345e+01 4.70104675e+01 4.74163551e+01 4.76193466e+01 4.79510002e+01 4.81311455e+01 4.89082069e+01 4.91153450e+01 4.92228012e+01 4.93707008e+01 4.92587814e+01 4.98387146e+01 4.99213486e+01 5.03540802e+01 5.01242943e+01 5.03524094e+01 5.09913864e+01 5.07643242e+01 5.12812080e+01 5.09789696e+01 5.17199402e+01 5.21722298e+01 5.27325401e+01 5.28620338e+01 5.30223732e+01 5.32523689e+01 5.37073097e+01 5.35868034e+01 5.31514359e+01 5.31456070e+01 5.40755386e+01 5.45685081e+01 5.51719818e+01 5.55194588e+01 5.53493347e+01 5.47529335e+01 5.50719070e+01 5.56614609e+01 5.59416771e+01 5.55469017e+01 5.57740593e+01 5.65849533e+01 5.75892792e+01 6.56077271e+01 6.55220718e+01 6.25065231e+01 6.16985970e+01 5.79457626e+01 5.94251633e+01 5.96439171e+01 5.94081459e+01 6.08868599e+01 5.80680199e+01 5.46839142e+01 5.37560196e+01 6.33834686e+01 2.59651001e+02 3.93572327e+02 9.44494385e+02 1.73604980e+03 14223753. -4.20534150e+06 2.47411738e+09 2.47411738e+09 -268468640. -268468640. -8252523. -440080640. -440080640. 0. 0. 0. -1970944384. 24324094. 1.99104712e+03 1.24891614e+03 3.63948700e+02 5.59324768e+02 3.29382324e+02 9.43870239e+01 8.48422928e+01 4.61865959e+01 4.33943329e+01 8.08640442e+01 9.22980499e+01 7.60308228e+01 6.70820465e+01 6.57597122e+01 6.41641464e+01 6.48717041e+01 6.00470276e+01 5.45679092e+01 5.78692322e+01 4.48808670e+01 4.81609535e+01 7.19712524e+01 5.92088470e+01 7.31511307e+01 8.38375397e+01 6.44540558e+01 5.51612701e+01 4.93825912e+01 5.67530174e+01 6.85110855e+01 6.77236328e+01 6.12367554e+01 6.55433273e+01 6.65520477e+01 6.58931656e+01 6.55485535e+01 6.48790741e+01 6.42526245e+01 6.38717079e+01 6.37059441e+01 6.38814812e+01 6.37579918e+01 6.37925949e+01 6.38568954e+01 6.35093002e+01 6.37087212e+01 6.36176147e+01 6.37045364e+01 6.37903442e+01 6.39782524e+01 6.39031296e+01 6.75011826e+01 6.67299347e+01 6.66475677e+01 6.84437943e+01 6.50276031e+01 6.37710457e+01 6.43252182e+01 6.45336685e+01 6.50092087e+01 6.49808731e+01 6.46285400e+01 6.39501762e+01 6.45880356e+01 6.63522263e+01 6.58986893e+01 6.41828690e+01 6.39620361e+01 6.25608940e+01 5.93438225e+01 7.21923752e+01 -1.25440010e+02 7.20785217e+01 1.22648987e+02 -2.80819427e+02 4.90485229e+02 3.09566589e+02 5.69628372e+01 6.12083588e+01 6.84980469e+01 6.51431808e+01 6.14894333e+01 6.24188004e+01 6.51792374e+01 1.89627029e+02 589828992. 1.67690140e+02 -8.38651794e+02 -2.18275293e+03 1.20691919e+03 1.04639908e+02 -9.99322449e+02 3.37814650e+06 -8.96873938e+05 1.24318970e+03 5.37965576e+02 5.20448380e+01 5.21254120e+01 3.45458145e+01 2.40274315e+01 3.01377316e+01 4.22838173e+01 3.46792526e+01 3.09185581e+01 3.08769302e+01 3.33899307e+01 3.51756783e+01 3.55219002e+01 3.46222496e+01 3.41508408e+01 3.34011993e+01 3.32509689e+01 3.29119453e+01 3.25840759e+01 3.30636673e+01 3.32783356e+01 3.29495354e+01 3.26693230e+01 3.25277748e+01 3.27731323e+01 3.26671562e+01 3.24105301e+01 3.21580925e+01 3.17054329e+01 3.09284248e+01 3.10031452e+01 3.17342720e+01 3.14963722e+01 3.10913773e+01 3.11967182e+01 3.16516705e+01 3.14861584e+01 3.12464447e+01 3.09649563e+01 3.08553486e+01 3.06139355e+01 3.06386223e+01 3.00739994e+01 3.01721649e+01 3.02054691e+01 2.99727840e+01 2.99843807e+01 2.99479828e+01 2.99400387e+01 3.00434933e+01 2.97987537e+01 2.92195911e+01 2.86550732e+01 2.84962482e+01 2.85854244e+01 2.85475616e+01 2.84939651e+01 2.85432854e+01 2.86443253e+01 2.81861553e+01 2.78291512e+01 2.76121159e+01 2.78089256e+01 2.75275211e+01 2.66429043e+01 2.43670578e+01 1.83173027e+01 -1.79993530e+02 -3.68625000e+02 -8.74532852e+01 -1.07150012e+03 -5.09439014e+03 105150272. 0. 0. -844416064. -844416064. -844416064. 0. 0. -126921904. -126921904. -126921904. 0. -176459200. -176459200. -10222370. -493076352. -1.78591321e+03 -6.70439453e+02 -1.53547165e+02 2.05908661e+01 2.70527725e+01 1.86707439e+01 1.79011955e+01 2.18645306e+01 2.08456326e+01 1.96689606e+01 2.07478600e+01 2.25827694e+01 2.29018745e+01 2.26727600e+01 2.22076607e+01 2.12483578e+01 2.07145844e+01 2.01999893e+01 2.07606697e+01 2.06626511e+01 1.97797394e+01 1.96410294e+01 1.94597759e+01 1.98376675e+01 1.90133381e+01 1.83938389e+01 1.77177429e+01 1.73287811e+01 1.67112293e+01 1.71819401e+01 1.71863079e+01 1.75729370e+01 1.69865303e+01 1.68306255e+01 1.67388611e+01 1.66784763e+01 1.68290691e+01 1.69196873e+01 1.65388870e+01 1.64490776e+01 1.59304171e+01 1.56628675e+01 1.49980879e+01 1.50734015e+01 1.44744673e+01 1.41906395e+01 1.38098831e+01 1.39889164e+01 1.41904478e+01 1.39415045e+01 1.39251356e+01 1.37516136e+01 1.35173016e+01 1.29159040e+01 1.23482809e+01 1.23262281e+01 1.27666588e+01 1.23959618e+01 1.19836521e+01 1.14324303e+01 1.14220848e+01 1.11874247e+01 1.11459589e+01 1.12127762e+01 1.12741194e+01 1.10782146e+01 1.07609625e+01 1.04027843e+01 1.02012167e+01 1.01626167e+01 9.88194370e+00 9.38342762e+00 8.93664455e+00 8.68232632e+00 8.67863274e+00 8.56218529e+00 8.38024426e+00 8.04382515e+00 7.91908026e+00 7.45462656e+00 7.25830030e+00 6.91196299e+00 6.75205898e+00 6.46563339e+00 6.33378172e+00 6.14196968e+00 5.91991806e+00 5.65175009e+00 5.36906147e+00 4.94657326e+00 4.59812975e+00 4.36297655e+00 4.21275854e+00 4.05842495e+00 4.14900589e+00 3.97165489e+00 3.77069998e+00 3.43156433e+00 3.24047923e+00 3.11384964e+00 2.77772999e+00 2.51182747e+00 2.10840034e+00 1.94821441e+00 1.78344989e+00 1.81673932e+00 1.51121831e+00 1.17757070e+00 9.46679354e-01 6.85332477e-01 3.87942374e-01 1.30460426e-01 -6.43163621e-02 -2.72324473e-01 -5.49709022e-01 -7.65612423e-01 -8.87021005e-01 -1.06934690e+00 -1.24308896e+00 -1.48737144e+00 -1.71300936e+00 -1.97371173e+00 -2.15168762e+00 -2.44273496e+00 -2.72667027e+00 -2.98028445e+00 -3.14007592e+00 -3.31768370e+00 -3.52753162e+00 -3.81738114e+00 -4.11387014e+00 -4.23793888e+00 -4.42885494e+00 -4.73286629e+00 -4.96496725e+00 -5.14279222e+00 -5.39120150e+00 -5.64329052e+00 -5.88231134e+00 -6.09462643e+00 -6.27297211e+00 -6.50343084e+00 -6.71646595e+00 -6.94078827e+00 -7.17021418e+00 -7.38274765e+00 -7.57316828e+00 -7.81074858e+00 -8.03495502e+00 -8.25481033e+00 -8.48718739e+00 -8.70194244e+00 -8.91009998e+00 -9.13047791e+00 -9.34439278e+00 -9.55723667e+00 -9.77146912e+00 -9.98637867e+00 -1.02042227e+01 -1.04213562e+01 -1.06381531e+01 -1.08536711e+01 -1.10712395e+01 -1.12811747e+01 -1.14917202e+01 -1.17164660e+01 -1.19402752e+01 -1.21765680e+01 -1.23937912e+01 -1.25912399e+01 -1.27945967e+01 -1.30450792e+01 -1.32648439e+01 -1.34485121e+01 -1.36610909e+01 -1.38678436e+01 -1.40428038e+01 -1.42463160e+01 -1.44776335e+01 -1.46657028e+01 -1.49374781e+01 -1.51154470e+01 -1.53176308e+01 -1.55808916e+01 -1.58074684e+01 -1.59613647e+01 -1.61002941e+01 -1.61986198e+01 -1.64745922e+01 -1.66997337e+01 -1.68772297e+01 -1.70727062e+01 -1.73516331e+01 -1.75957985e+01 -1.77614346e+01 -1.79950352e+01 -1.81607151e+01 -1.82898598e+01 -1.84771175e+01 -1.87030525e+01 -1.90424786e+01 -1.91701908e+01 -1.92889271e+01 -1.96055412e+01 -1.99022274e+01 -2.00340862e+01 -1.99871712e+01 -2.01279964e+01 -2.03760109e+01 -2.06667557e+01 -2.07973366e+01 -2.09083118e+01 -2.10881901e+01 -2.13886509e+01 -2.15809231e+01 -2.17575970e+01 -2.18490677e+01 -2.22098312e+01 -2.24713993e+01 -2.25441895e+01 -2.24528027e+01 -2.26814346e+01 -2.29423885e+01 -2.32111206e+01 -2.34414711e+01 -2.36357880e+01 -2.37122250e+01 -2.37170086e+01 -2.39827309e+01 -2.42133255e+01 -2.46856480e+01 -2.48150692e+01 -2.47813225e+01 -2.46073475e+01 -2.48713360e+01 -2.52569923e+01 -2.53848972e+01 -2.54166317e+01 -2.55250416e+01 -2.55152092e+01 -2.57669163e+01 -2.59399815e+01 -2.61492863e+01 -2.65901413e+01 -2.67000332e+01 -2.68456135e+01 -2.66154671e+01 -2.63926849e+01 -2.68386002e+01 -2.73053894e+01 -2.77641087e+01 -2.78950996e+01 -2.79993916e+01 -2.80983696e+01 -2.82934628e+01 -2.86553860e+01 -2.86970119e+01 -2.86726131e+01 -2.87286549e+01 -2.89988136e+01 -2.90239029e+01 -2.90152760e+01 -2.88796902e+01 -2.89912453e+01 -2.91116791e+01 -2.93575001e+01 -2.95950451e+01 -2.95956306e+01 -3.01455536e+01 -3.03961105e+01 -3.10212631e+01 -3.06517029e+01 -3.05566063e+01 -3.05102463e+01 -3.12245846e+01 -3.15978470e+01 -3.11647301e+01 -3.14378681e+01 -3.15090599e+01 -3.19797344e+01 -3.12575436e+01 -3.09213352e+01 -3.09159431e+01 -3.09654484e+01 -3.08191929e+01 -3.11352463e+01 -3.16491146e+01 -3.22227058e+01 -3.20646782e+01 -3.26968193e+01 -3.27655563e+01 -3.31135902e+01 -3.31920471e+01 -3.37164841e+01 -3.33242302e+01 -3.34613342e+01 -3.29814072e+01 -3.30228691e+01 -3.27338142e+01 -3.31874428e+01 -3.30076523e+01 -3.26680450e+01 -3.27969589e+01 -3.29986572e+01 -3.36364861e+01 -3.37141190e+01 -3.44873962e+01 -3.41298599e+01 -3.40832291e+01 -3.38157959e+01 -3.36789818e+01 -3.42018127e+01 -3.53146439e+01 -3.47272720e+01 -3.50282021e+01 -3.47696991e+01 -3.53493881e+01 -3.51030388e+01 -3.48813248e+01 -3.55308418e+01 -3.57952499e+01 -3.57143402e+01 -3.55804176e+01 -3.54331474e+01 -3.57649727e+01 -3.54752998e+01 -3.55067978e+01 -3.56020851e+01 -3.55655823e+01 -3.55436745e+01 -3.60192146e+01 -3.62440605e+01 -3.64183083e+01 -3.62095070e+01 -3.63760757e+01 -3.59316940e+01 -3.59475937e+01 -3.55731888e+01 -3.62901001e+01 -3.64612770e+01 -3.65264664e+01 -3.64290466e+01 -3.64172440e+01 -3.64415207e+01 -3.62133331e+01 -3.58343849e+01 -3.54260216e+01 -3.53019333e+01 -3.56147308e+01 -3.59240303e+01 -3.66418610e+01 -3.65149117e+01 -3.66691284e+01 -3.67178497e+01 -3.69363098e+01 -3.70885429e+01 -3.65486946e+01 -3.65922279e+01 -3.60876884e+01 -3.65561409e+01 -3.69065323e+01 -3.72688866e+01 -3.71479111e+01 -3.68603134e+01 -3.68427849e+01 -3.67721367e+01 -3.68344460e+01 -3.64892387e+01 -3.66436615e+01 -3.66553612e+01 -3.68817291e+01 -3.65242386e+01 -3.69263306e+01 -3.71156960e+01 -3.73080788e+01 -3.71606750e+01 -3.73462296e+01 -3.68123398e+01 -3.65859451e+01 -3.66313591e+01 -3.70492554e+01 -3.67665901e+01 -3.66735458e+01 -3.71223259e+01 -3.68461647e+01 -3.64708786e+01 -3.63454437e+01 -3.66323853e+01 -3.68452873e+01 -3.67245941e+01 -3.63120384e+01 -3.59723892e+01 -3.60121956e+01 -3.61829987e+01 -3.60673904e+01 -3.60311852e+01 -3.63218346e+01 -3.61108360e+01 -3.60579033e+01 -3.60881805e+01 -3.61694260e+01 -3.60028648e+01 -3.61296501e+01 -3.57864494e+01 -3.56585617e+01 -3.52840195e+01 -3.52717972e+01 -3.56124077e+01 -3.59452477e+01 -3.59181557e+01 -3.55449715e+01 -3.55444183e+01 -3.56257858e+01 -3.54707794e+01 -3.53186836e+01 -3.51403809e+01 -3.48389931e+01 -3.48807411e+01 -3.48838997e+01 -3.48085022e+01 -3.47782936e+01 -3.47377548e+01 -3.48725128e+01 -3.47667236e+01 -3.44192886e+01 -3.43182678e+01 -3.44056778e+01 -3.44608421e+01 -3.43480453e+01 -3.42261314e+01 -3.45315170e+01 -3.40197678e+01 -3.36049995e+01 -3.42025070e+01 -3.42684555e+01 -3.41579056e+01 -3.38752823e+01 -3.33229370e+01 -3.34758301e+01 -3.34936333e+01 -3.36821213e+01 -3.35654373e+01 -3.31387253e+01 -3.27088737e+01 -3.28926849e+01 -3.23741951e+01 -3.24127312e+01 -3.25376091e+01 -3.24977760e+01 -3.24584160e+01 -3.22591171e+01 -3.23180161e+01 -3.24258385e+01 -3.18093071e+01 -3.10758057e+01 -3.14610691e+01 -3.14370651e+01 -3.13423271e+01 -3.14347515e+01 -3.15488987e+01 -3.15778275e+01 -3.14913425e+01 -3.09433212e+01 -3.06387119e+01 -3.04824467e+01 -3.05083904e+01 -3.01913471e+01 -2.98588753e+01 -2.98569908e+01 -3.00561466e+01 -3.02958031e+01 -3.02103443e+01 -3.02302513e+01 -3.01189957e+01 -2.99304771e+01 -2.93512917e+01 -2.89973507e+01 -2.87434673e+01 -2.81573830e+01 -2.83449554e+01 -2.88258419e+01 -2.90012054e+01 -2.94696236e+01 -2.87036018e+01 -2.74184303e+01 -2.74093952e+01 -2.82378960e+01 -2.82194595e+01 -2.75133190e+01 -2.69550362e+01 -2.66133251e+01 -2.71874161e+01 -2.70644341e+01 -2.67842636e+01 -2.64968166e+01 -2.62896690e+01 -2.58289776e+01 -2.57558098e+01 -2.56145020e+01 -2.57601337e+01 -2.54505558e+01 -2.51647320e+01 -2.46028557e+01 -2.40894604e+01 -2.45092430e+01 -2.46500530e+01 -2.51157093e+01 -2.47818775e+01 -2.42880192e+01 -2.37342739e+01 -2.36398239e+01 -2.37148170e+01 -2.38319378e+01 -2.38472233e+01 -2.33808594e+01 -2.30993519e+01 -2.31835880e+01 -2.31308842e+01 -2.24293747e+01 -2.20725403e+01 -2.17569275e+01 -2.14562016e+01 -2.10844059e+01 -2.11033058e+01 -2.15242310e+01 -2.16226597e+01 -2.16583023e+01 -2.09591675e+01 -2.07022705e+01 -2.03718624e+01 -2.10677986e+01 -2.06642094e+01 -2.00586777e+01 -1.99511490e+01 -1.98124657e+01 -2.02276745e+01 -1.90393257e+01 -1.82265816e+01 -1.75292320e+01 -1.72001629e+01 -1.70521870e+01 -1.75964012e+01 -1.74784031e+01 -1.75499439e+01 -1.71397324e+01 -1.74897480e+01 -1.72031441e+01 -1.70313072e+01 -1.68265972e+01 -1.71673393e+01 -1.65012093e+01 -1.61665573e+01 -1.58260727e+01 -1.54683199e+01 -1.50848370e+01 -1.51130161e+01 -1.49580889e+01 -1.44248104e+01 -1.42628174e+01 -1.40023518e+01 -1.40834007e+01 -1.40082684e+01 -1.40411348e+01 -1.35228329e+01 -1.30918407e+01 -1.26789150e+01 -1.22629709e+01 -1.25753479e+01 -1.30255814e+01 -1.25090933e+01 -1.22429161e+01 -1.19913740e+01 -1.20762510e+01 -1.18360891e+01 -1.13965101e+01 -1.12264404e+01 -1.11961660e+01 -1.09749088e+01 -1.07376060e+01 -1.04257183e+01 -1.02639275e+01 -9.92979240e+00 -9.60348701e+00 -9.30292511e+00 -9.06856823e+00 -8.76691437e+00 -8.75735283e+00 -8.71143246e+00 -8.55644608e+00 -8.23638439e+00 -8.04332733e+00 -7.47781420e+00 -7.30726385e+00 -6.83764458e+00 -6.75366879e+00 -6.59557343e+00 -6.49688530e+00 -6.32451630e+00 -6.22458839e+00 -5.97450590e+00 -5.59417105e+00 -5.10330534e+00 -4.63455105e+00 -4.25861359e+00 -4.24256277e+00 -4.29745960e+00 -4.28355169e+00 -4.08509111e+00 -3.78054523e+00 -3.48748136e+00 -3.28027630e+00 -3.13423252e+00 -2.84351087e+00 -2.67873359e+00 -2.29350901e+00 -2.07829261e+00 -1.87225354e+00 -1.79949558e+00 -1.51303232e+00 -1.23069835e+00 -1.01698101e+00 -7.31792092e-01 -3.86918724e-01 -3.63935530e-02 8.02646279e-02 2.18189344e-01 3.65030915e-01 6.52460396e-01 8.44761848e-01 1.03726768e+00 1.21979094e+00 1.42651844e+00 1.65989983e+00 1.97751379e+00 2.20044088e+00 2.40768623e+00 2.57640886e+00 2.85129476e+00 3.04375124e+00 3.18056703e+00 3.45164680e+00 3.76604009e+00 4.02856350e+00 4.15082264e+00 4.36220694e+00 4.60648394e+00 4.89547491e+00 5.13237190e+00 5.32355738e+00 5.52924538e+00 5.78419018e+00 6.00758982e+00 6.19981241e+00 6.42192554e+00 6.63193655e+00 6.86321592e+00 7.05786896e+00 7.26875496e+00 7.48431349e+00 7.71935081e+00 7.95509005e+00 8.17959976e+00 8.39122295e+00 8.60132122e+00 8.82240963e+00 9.04381275e+00 9.26239777e+00 9.47176170e+00 9.68918133e+00 9.90219784e+00 1.01155062e+01 1.03295870e+01 1.05355453e+01 1.07444429e+01 1.09505224e+01 1.11653738e+01 1.13839302e+01 1.15975447e+01 1.18067465e+01 1.20107965e+01 1.22306633e+01 1.24373083e+01 1.26413403e+01 1.28462868e+01 1.30588636e+01 1.32663708e+01 1.34708939e+01 1.36762638e+01 1.38982887e+01 1.41807613e+01 1.43947277e+01 1.45289154e+01 1.47463779e+01 1.49311447e+01 1.51963902e+01 1.54108715e+01 1.56452951e+01 1.58750219e+01 1.60141754e+01 1.61743851e+01 1.64861889e+01 1.66662369e+01 1.68235168e+01 1.69645348e+01 1.73013477e+01 1.75030155e+01 1.76973782e+01 1.79053078e+01 1.80436287e+01 1.81580715e+01 1.83591633e+01 1.86171169e+01 1.88452587e+01 1.90298996e+01 1.92588787e+01 1.94972305e+01 1.97495937e+01 1.98971882e+01 1.99294891e+01 2.00675678e+01 2.01929607e+01 2.05633659e+01 2.06584187e+01 2.07658195e+01 2.09625454e+01 2.13022614e+01 2.14458408e+01 2.15670586e+01 2.17403355e+01 2.19598255e+01 2.22154121e+01 2.23992729e+01 2.24165344e+01 2.26324558e+01 2.28718224e+01 2.30568237e+01 2.32659225e+01 2.34548321e+01 2.37071056e+01 2.37589970e+01 2.39855690e+01 2.42376480e+01 2.45387955e+01 2.46535664e+01 2.46579189e+01 2.45303669e+01 2.48863182e+01 2.52483349e+01 2.53823147e+01 2.53890076e+01 2.54713154e+01 2.55415497e+01 2.57415676e+01 2.58498096e+01 2.59747696e+01 2.62401981e+01 2.65540886e+01 2.66875591e+01 2.63647003e+01 2.60599308e+01 2.66939201e+01 2.74413414e+01 2.77542915e+01 2.77195129e+01 2.77729759e+01 2.78348751e+01 2.80480709e+01 2.81913624e+01 2.84884338e+01 2.86172981e+01 2.85955582e+01 2.86939602e+01 2.88144054e+01 2.90190868e+01 2.89673843e+01 2.89252148e+01 2.90075378e+01 2.93193302e+01 2.98454819e+01 2.98384266e+01 3.00246563e+01 3.00754662e+01 3.06271210e+01 3.03780117e+01 3.04460926e+01 3.04625511e+01 3.10233650e+01 3.11067562e+01 3.11308289e+01 3.15056458e+01 3.15285034e+01 3.21287422e+01 3.14619942e+01 3.12724247e+01 3.09866199e+01 3.07448845e+01 3.07731667e+01 3.13190994e+01 3.16964531e+01 3.21175385e+01 3.22538033e+01 3.25611610e+01 3.23282509e+01 3.28150864e+01 3.33478508e+01 3.38012695e+01 3.30960770e+01 3.31770096e+01 3.29669266e+01 3.30184288e+01 3.26076241e+01 3.29457359e+01 3.67092857e+01 3.62064285e+01 3.23457909e+01 3.41882172e+01 3.43933945e+01 3.39861183e+01 3.56688194e+01 3.32168236e+01 3.03766708e+01 3.27390480e+01 3.53393822e+01 3.23687439e+01 3.25107880e+01 2.29917664e+02 3.12665283e+02 6.89369995e+02 3.68677319e+03 -324448992. 0. -268468640. -268468640. -8252523. -440080640. -440080640. 0. 0. 0. 0. 0. -299095488. -5035621. 1.15053344e+05 2.91747681e+03 1.21402759e+03 1.93025360e+02 4.57712067e+02 2.19550201e+02 2.75025101e+01 5.34834747e+01 6.35991936e+01 4.87213631e+01 3.87745361e+01 3.75465050e+01 3.57863960e+01 3.71507835e+01 3.28218002e+01 2.72034073e+01 3.01512127e+01 1.90660496e+01 2.25475636e+01 4.40558586e+01 4.10604973e+01 4.46996460e+01 4.63166313e+01 3.55697136e+01 3.39429817e+01 3.54135208e+01 4.01623688e+01 4.05237312e+01 3.37125435e+01 3.09948368e+01 3.68801422e+01 3.80891266e+01 3.81900215e+01 3.83442726e+01 3.77456627e+01 3.71016426e+01 3.62094154e+01 3.61096764e+01 3.65603180e+01 3.71156540e+01 3.70374107e+01 3.70053062e+01 3.66010132e+01 3.66909981e+01 3.64537010e+01 3.62734528e+01 3.64045639e+01 3.68906212e+01 3.69798775e+01 4.06183624e+01 3.95160980e+01 3.91208839e+01 4.09953270e+01 3.74405632e+01 3.62408562e+01 3.63370438e+01 3.67855682e+01 3.72013893e+01 3.73775787e+01 3.66169319e+01 3.60397949e+01 3.64563293e+01 3.68560181e+01 3.64215660e+01 3.50920029e+01 3.42290840e+01 3.17095814e+01 2.52627869e+01 4.56391411e+01 -2.91109741e+02 -3.62302948e+02 1.22114822e+02 -2.14127368e+03 2.24159814e+03 9.37617554e+02 2.32167091e+01 4.19520813e+02 6.82539825e+01 -3.14507812e+02 4.79597855e+01 5.39303780e+01 7.04701080e+01 1.80153992e+02 -1.06193347e+10 -161225136. -161225136. -9.24121805e+09 8.71484006e+09 8.71484006e+09 8.71484006e+09 0. 0. 2.56066335e+10 5.08697754e+03 1.01593292e+03 8.35211258e+01 -3.21685669e+02 -1.78295334e+02 3.77952919e+01 5.12217789e+01 4.61635170e+01 4.33054771e+01 4.11266403e+01 4.00021324e+01 4.05237923e+01 4.05722008e+01 4.04094963e+01 4.08134613e+01 3.99854240e+01 3.95037079e+01 3.91687813e+01 3.94830627e+01 3.98971481e+01 3.99095612e+01 3.97761726e+01 4.01585770e+01 4.04366608e+01 3.99933929e+01 3.95785942e+01 3.89115868e+01 3.88475914e+01 3.85951157e+01 3.87124405e+01 3.92386055e+01 3.90903931e+01 3.88029289e+01 3.82709656e+01 3.67692032e+01 3.65225754e+01 3.80059586e+01 3.82195663e+01 4.02782784e+01 4.01177444e+01 3.82689285e+01 3.80980530e+01 3.79167519e+01 3.81823959e+01 3.76753845e+01 3.71990547e+01 3.72879372e+01 3.69661751e+01 3.67380905e+01 3.61697235e+01 3.65660934e+01 3.64517784e+01 3.65128822e+01 3.62926178e+01 3.60273056e+01 3.59310112e+01 3.55167007e+01 3.62254257e+01 3.61247635e+01 3.56381874e+01 3.51482887e+01 3.51292877e+01 3.49830513e+01 3.29759102e+01 3.25470276e+01 -1.61941742e+02 -3.31951263e+02 -8.73748596e+02 -2.58746826e+03 -2.85450406e+05 788625088. 524555392. 0. -2.30841114e+09 -2.30841114e+09 3.10406579e+09 -844416064. -844416064. 0. 0. 0. 0. 0. 0. -2.64499344e+05 2.28154810e+03 3.68495483e+02 -6.37369873e+02 -2.66755646e+02 -1.36382675e+02 3.16316109e+01 2.92518120e+01 3.22753983e+01 3.07377052e+01 2.99849586e+01 2.96132641e+01 2.95971737e+01 2.82433662e+01 2.90977917e+01 3.01007156e+01 2.95185089e+01 2.94459419e+01 2.89911156e+01 2.86011925e+01 2.79883823e+01 2.76325951e+01 2.74252834e+01 2.71230202e+01 2.71044807e+01 2.72612152e+01 2.70888596e+01 2.65857983e+01 2.65097275e+01 2.62250462e+01 2.60820560e+01 2.60249252e+01 2.58764553e+01 2.56768742e+01 2.54500656e+01 2.51587982e+01 2.49043751e+01 2.46614552e+01 2.45663471e+01 2.41338387e+01 2.36727295e+01 2.34516773e+01 2.38804798e+01 2.34043407e+01 2.36210995e+01 2.32748127e+01 2.28028984e+01 2.25960159e+01 2.24262199e+01 2.28458672e+01 2.26731396e+01 2.25139942e+01 2.18958626e+01 2.15149632e+01 2.10939503e+01 2.05098228e+01 1.99235229e+01 2.01015720e+01 1.99583511e+01 2.01889477e+01 1.99609261e+01 2.01592445e+01 1.91627026e+01 1.88376751e+01 1.88328171e+01 1.86856213e+01 1.82052994e+01 1.77883873e+01 1.79810085e+01 1.79830475e+01 1.78484650e+01 1.73542042e+01 1.69664135e+01 1.68911572e+01 1.65452862e+01 1.62108307e+01 1.62041779e+01 1.61176510e+01 1.56514730e+01 1.52985058e+01 1.51763706e+01 1.52222862e+01 1.48377628e+01 1.45229807e+01 1.41015673e+01 1.39941034e+01 1.36765795e+01 1.32126455e+01 1.27049026e+01 1.27574472e+01 1.27640867e+01 1.25297318e+01 1.22305775e+01 1.16644192e+01 1.14984703e+01 1.12427330e+01 1.08705702e+01 1.08522549e+01 1.08178129e+01 1.06628456e+01 1.00647392e+01 9.60680866e+00 9.64600849e+00 9.65806103e+00 9.42798138e+00 8.73499489e+00 8.57154560e+00 8.27091503e+00 8.14382648e+00 7.93671227e+00 7.62373638e+00 7.38432598e+00 7.13694143e+00 6.89763021e+00 6.59839582e+00 6.39507151e+00 6.17821836e+00 5.87618494e+00 5.64315891e+00 5.51037169e+00 5.25878668e+00 4.93143559e+00 4.60306025e+00 4.31870222e+00 4.10847044e+00 3.87667584e+00 3.66826463e+00 3.35690379e+00 3.02301311e+00 2.79777527e+00 2.54666829e+00 2.30705690e+00 2.07611561e+00 1.78141713e+00 1.42557979e+00 1.33928120e+00 1.08209014e+00 7.21253872e-01 4.74103838e-01 2.84729600e-01 3.59392986e-02 -2.72445679e-01 -5.58761656e-01 -8.02812576e-01 -1.01719522e+00 -1.28062165e+00 -1.54277933e+00 -1.77649713e+00 -2.04767513e+00 -2.30273175e+00 -2.54832721e+00 -2.82588124e+00 -3.09156322e+00 -3.33212209e+00 -3.59279180e+00 -3.84235430e+00 -4.08746338e+00 -4.34555769e+00 -4.59979725e+00 -4.84929276e+00 -5.10251236e+00 -5.35703516e+00 -5.60926914e+00 -5.86287546e+00 -6.11497736e+00 -6.36608124e+00 -6.61956882e+00 -6.86173630e+00 -7.10751724e+00 -7.36928511e+00 -7.61415100e+00 -7.88975954e+00 -8.15003872e+00 -8.36229992e+00 -8.61124134e+00 -8.89211559e+00 -9.15354347e+00 -9.39682865e+00 -9.65473843e+00 -9.87572861e+00 -1.00914125e+01 -1.03601980e+01 -1.05883522e+01 -1.08630295e+01 -1.11765747e+01 -1.14160786e+01 -1.16696548e+01 -1.20092392e+01 -1.22073851e+01 -1.24029741e+01 -1.26203909e+01 -1.28364124e+01 -1.30898304e+01 -1.33752279e+01 -1.36844130e+01 -1.39445362e+01 -1.41870108e+01 -1.43864098e+01 -1.45801210e+01 -1.48601360e+01 -1.51422415e+01 -1.54683981e+01 -1.56424608e+01 -1.58883934e+01 -1.62324905e+01 -1.63802166e+01 -1.64193325e+01 -1.66944675e+01 -1.70831699e+01 -1.72835255e+01 -1.76097164e+01 -1.77844810e+01 -1.80727139e+01 -1.82772579e+01 -1.84304295e+01 -1.86074944e+01 -1.86905918e+01 -1.89254055e+01 -1.93049850e+01 -1.95738811e+01 -1.97480717e+01 -1.98133640e+01 -2.01651897e+01 -2.02883816e+01 -2.06415901e+01 -2.08701611e+01 -2.10005856e+01 -2.12764854e+01 -2.15621243e+01 -2.19618149e+01 -2.21481628e+01 -2.23004169e+01 -2.24728241e+01 -2.25927601e+01 -2.30822659e+01 -2.30061092e+01 -2.33021545e+01 -2.34421082e+01 -2.37598305e+01 -2.40351810e+01 -2.40077553e+01 -2.42030602e+01 -2.44593029e+01 -2.51317806e+01 -2.53833752e+01 -2.52747154e+01 -2.55220737e+01 -2.58494148e+01 -2.60467091e+01 -2.61025562e+01 -2.62180634e+01 -2.64865189e+01 -2.65232773e+01 -2.64074726e+01 -2.67199001e+01 -2.72551517e+01 -2.80460491e+01 -2.83819809e+01 -2.83154526e+01 -2.83293762e+01 -2.85192032e+01 -2.84936695e+01 -2.90154285e+01 -2.91380692e+01 -2.91347084e+01 -2.91368332e+01 -2.90413857e+01 -2.94823246e+01 -2.97416763e+01 -2.99904099e+01 -2.98686733e+01 -2.99465160e+01 -3.02998428e+01 -3.10595074e+01 -3.10048599e+01 -3.09083614e+01 -3.07317142e+01 -3.08734169e+01 -3.09566593e+01 -3.11662560e+01 -3.16058159e+01 -3.20951843e+01 -3.24067802e+01 -3.25513763e+01 -3.25646057e+01 -3.25220947e+01 -3.27649689e+01 -3.28260803e+01 -3.28448448e+01 -3.31190338e+01 -3.35219345e+01 -3.35367165e+01 -3.40759239e+01 -3.41960373e+01 -3.43570976e+01 -3.41434746e+01 -3.43339424e+01 -3.42984085e+01 -3.49645576e+01 -3.46599388e+01 -3.49708366e+01 -3.47537842e+01 -3.52109985e+01 -3.54451714e+01 -3.48055954e+01 -3.55217209e+01 -3.60853996e+01 -3.65674095e+01 -3.65356293e+01 -3.66375427e+01 -3.64828186e+01 -3.59747543e+01 -3.56396904e+01 -3.63042412e+01 -3.61844330e+01 -3.70282249e+01 -3.73227615e+01 -3.80408974e+01 -3.74196968e+01 -3.74422112e+01 -3.77942963e+01 -3.83723335e+01 -3.74245453e+01 -3.74977837e+01 -3.83518753e+01 -3.78809853e+01 -3.79164963e+01 -3.76274719e+01 -3.77572784e+01 -3.79030571e+01 -3.78718452e+01 -3.81303558e+01 -3.86853447e+01 -3.92385330e+01 -3.93540878e+01 -3.92081070e+01 -3.93333015e+01 -3.98457069e+01 -3.97145271e+01 -3.98321686e+01 -3.95548592e+01 -3.97400055e+01 -3.97855148e+01 -3.97422485e+01 -3.90957870e+01 -3.95410728e+01 -3.99908943e+01 -4.01408501e+01 -4.02774696e+01 -3.97813339e+01 -3.97497406e+01 -3.97795982e+01 -3.96988487e+01 -4.01162682e+01 -4.03293152e+01 -4.05497589e+01 -4.06849670e+01 -4.04305038e+01 -4.05382042e+01 -4.01403923e+01 -4.04388962e+01 -4.03745918e+01 -4.08343773e+01 -4.12323456e+01 -4.15401382e+01 -4.10529556e+01 -4.09181366e+01 -4.12994156e+01 -4.12817307e+01 -4.15047607e+01 -4.18753777e+01 -4.18483925e+01 -4.18190575e+01 -4.16113892e+01 -4.16939125e+01 -4.17727966e+01 -4.15771141e+01 -4.15858955e+01 -4.11579018e+01 -4.13687668e+01 -4.18078842e+01 -4.18557587e+01 -4.18496246e+01 -4.18113899e+01 -4.17624817e+01 -4.15272751e+01 -4.14321480e+01 -4.18761826e+01 -4.17644043e+01 -4.20736046e+01 -4.20243416e+01 -4.19984589e+01 -4.18600616e+01 -4.19800568e+01 -4.21110001e+01 -4.19577713e+01 -4.18412170e+01 -4.20638084e+01 -4.16840515e+01 -4.15862389e+01 -4.20162926e+01 -4.19651146e+01 -4.19462471e+01 -4.19598007e+01 -4.18628540e+01 -4.18724670e+01 -4.19300575e+01 -4.17586021e+01 -4.16278496e+01 -4.09680634e+01 -4.09072609e+01 -4.16350708e+01 -4.24359207e+01 -4.25589828e+01 -4.15586700e+01 -4.17049751e+01 -4.20378914e+01 -4.17496872e+01 -4.15679092e+01 -4.13854523e+01 -4.11731644e+01 -4.12200623e+01 -4.12811546e+01 -4.12715950e+01 -4.13428764e+01 -4.13358116e+01 -4.13555336e+01 -4.16100731e+01 -4.10064697e+01 -4.03239136e+01 -4.12946396e+01 -4.14792061e+01 -4.09704819e+01 -4.09476051e+01 -4.14162521e+01 -4.08313675e+01 -4.01574059e+01 -4.04069099e+01 -4.04869423e+01 -4.08250046e+01 -4.04426384e+01 -4.02480621e+01 -4.04547005e+01 -4.04142342e+01 -4.03249931e+01 -3.99417801e+01 -3.98639030e+01 -3.97736435e+01 -3.99818878e+01 -3.95724640e+01 -4.04731827e+01 -4.07105980e+01 -3.96149063e+01 -3.90468216e+01 -3.86385117e+01 -3.91058350e+01 -3.96678581e+01 -3.99369736e+01 -3.94399529e+01 -3.89082680e+01 -3.89148521e+01 -3.88395233e+01 -3.86602402e+01 -3.82012672e+01 -3.83089523e+01 -3.85596275e+01 -3.86563759e+01 -3.82683029e+01 -3.79748306e+01 -3.78114891e+01 -3.76137657e+01 -3.76882591e+01 -3.72933922e+01 -3.69827118e+01 -3.70755348e+01 -3.70673294e+01 -3.68931770e+01 -3.61027451e+01 -3.61560287e+01 -3.60215454e+01 -3.65967979e+01 -3.63833542e+01 -3.59528427e+01 -3.60052567e+01 -3.61393547e+01 -3.65346489e+01 -3.67817116e+01 -3.64291840e+01 -3.52757492e+01 -3.53270378e+01 -3.62714310e+01 -3.54221115e+01 -3.48110657e+01 -3.44429550e+01 -3.43908501e+01 -3.45353928e+01 -3.45556755e+01 -3.41775589e+01 -3.38580208e+01 -3.46150703e+01 -3.42924690e+01 -3.37786140e+01 -3.32182770e+01 -3.32268639e+01 -3.33579254e+01 -3.26609726e+01 -3.23061981e+01 -3.23262100e+01 -3.21107826e+01 -3.19730663e+01 -3.22505417e+01 -3.21475754e+01 -3.23332825e+01 -3.21865273e+01 -3.18110790e+01 -3.10451202e+01 -3.10502396e+01 -3.08485546e+01 -3.12951107e+01 -3.07880173e+01 -3.02184086e+01 -3.03524418e+01 -3.04501114e+01 -3.05128517e+01 -3.00671597e+01 -2.93747139e+01 -2.85562019e+01 -2.86532440e+01 -2.88793716e+01 -2.95442390e+01 -2.86896305e+01 -2.81038761e+01 -2.79866562e+01 -2.79098625e+01 -2.78867588e+01 -2.72710781e+01 -2.70846958e+01 -2.71300716e+01 -2.70473194e+01 -2.71139069e+01 -2.66426468e+01 -2.63257160e+01 -2.58586826e+01 -2.56133499e+01 -2.57141743e+01 -2.60840893e+01 -2.58537712e+01 -2.51056786e+01 -2.49740162e+01 -2.48332882e+01 -2.47742176e+01 -2.42030544e+01 -2.38019905e+01 -2.34486160e+01 -2.36348534e+01 -2.32487278e+01 -2.33685055e+01 -2.28662167e+01 -2.25505047e+01 -2.26421032e+01 -2.24681587e+01 -2.26165867e+01 -2.24103394e+01 -2.22576332e+01 -2.19340534e+01 -2.17256927e+01 -2.12463055e+01 -2.06039619e+01 -2.00445232e+01 -2.01795273e+01 -1.98198776e+01 -1.99707680e+01 -1.96809273e+01 -1.98802605e+01 -1.93421574e+01 -1.93213024e+01 -1.92705784e+01 -1.90696468e+01 -1.85136585e+01 -1.78562450e+01 -1.76748638e+01 -1.76113148e+01 -1.74634666e+01 -1.72369614e+01 -1.72252712e+01 -1.70394421e+01 -1.65104942e+01 -1.62131195e+01 -1.60039120e+01 -1.60051899e+01 -1.58131008e+01 -1.54019918e+01 -1.51907368e+01 -1.51459265e+01 -1.48928108e+01 -1.45485773e+01 -1.41034632e+01 -1.39446287e+01 -1.35465727e+01 -1.32021313e+01 -1.27330313e+01 -1.27323780e+01 -1.28096514e+01 -1.25920811e+01 -1.23407249e+01 -1.17886343e+01 -1.13746862e+01 -1.12215223e+01 -1.10469656e+01 -1.08695965e+01 -1.06922722e+01 -1.06465197e+01 -1.03364191e+01 -9.81655025e+00 -9.57391739e+00 -9.18029976e+00 -8.91468430e+00 -8.71689510e+00 -8.74006748e+00 -8.38061905e+00 -8.19588280e+00 -7.77108288e+00 -7.48660278e+00 -7.38694763e+00 -7.13515043e+00 -6.88712645e+00 -6.42657757e+00 -5.39202166e+00 -5.26195860e+00 -5.59520388e+00 -5.67888546e+00 -5.60798931e+00 -5.07699203e+00 -4.61127520e+00 -4.36956310e+00 -3.69795060e+00 4.76682930e+01 -1.72798681e+00 -5.17908249e+01 -3.50065494e+00 -3.83874059e+00 4.17092590e+01 -2.01380208e-01 -4.35453110e+01 -1.59346497e+00 -1.43735468e+00 -1.41559243e+00 -1.21567941e+00 -9.59989786e-01 -7.60522902e-01 -5.55925429e-01 -4.20102715e-01 -2.40776554e-01 1.74327701e-01 5.36314309e-01 7.58855462e-01 1.06205761e+00 1.30603111e+00 1.51263773e+00 1.80030727e+00 2.05361152e+00 2.29169607e+00 2.52652931e+00 2.80428457e+00 3.09851623e+00 3.35487413e+00 3.57353258e+00 3.83540869e+00 4.10785389e+00 4.34048462e+00 4.59676886e+00 4.84124041e+00 5.09136343e+00 5.34851694e+00 5.60430431e+00 5.85990858e+00 6.10804653e+00 6.35004234e+00 6.60100031e+00 6.86151314e+00 7.11897564e+00 7.36343002e+00 7.60670280e+00 7.85336018e+00 8.11194897e+00 8.36883450e+00 8.62434769e+00 8.84498692e+00 9.09253979e+00 9.34254742e+00 9.62007809e+00 9.86225796e+00 1.00917568e+01 1.04020185e+01 1.06495056e+01 1.08690166e+01 1.11648426e+01 1.14104280e+01 1.16487942e+01 1.18844175e+01 1.20821953e+01 1.23358173e+01 1.25939407e+01 1.27704477e+01 1.30968723e+01 1.34593134e+01 1.37316494e+01 1.39596758e+01 1.41964912e+01 1.43773441e+01 1.44503345e+01 1.47135010e+01 1.49643965e+01 1.53424826e+01 1.55380926e+01 1.57713270e+01 1.59466515e+01 1.60309830e+01 1.62966385e+01 1.64614296e+01 1.68734684e+01 1.71644936e+01 1.75115261e+01 1.78254337e+01 1.80134792e+01 1.82812996e+01 1.83324871e+01 1.86373482e+01 1.87488327e+01 1.89152241e+01 1.91132259e+01 1.93112450e+01 1.94659195e+01 1.95086708e+01 2.00680847e+01 2.03672924e+01 2.07223148e+01 2.09967690e+01 2.10913887e+01 2.10009861e+01 2.10726643e+01 2.15746040e+01 2.20309772e+01 2.22468243e+01 2.26011620e+01 2.26395721e+01 2.29151478e+01 2.28822536e+01 2.32522316e+01 2.33583546e+01 2.37737408e+01 2.40454922e+01 2.38205051e+01 2.39498425e+01 2.42769547e+01 2.49802608e+01 2.52847843e+01 2.53483810e+01 2.54313240e+01 2.55933170e+01 2.58362064e+01 2.59774303e+01 2.59669914e+01 2.61257172e+01 2.63582649e+01 2.66266232e+01 2.69077473e+01 2.71534328e+01 2.76145191e+01 2.81256657e+01 2.83723240e+01 2.81511726e+01 2.83358536e+01 2.83188057e+01 2.88502903e+01 2.89716206e+01 2.82773342e+01 2.86131268e+01 2.95899754e+01 3.03422489e+01 3.02580872e+01 2.97914181e+01 2.98606129e+01 3.00758190e+01 3.03033695e+01 3.09393330e+01 3.06046066e+01 3.06693134e+01 3.08078728e+01 3.09621601e+01 3.08763790e+01 3.08109741e+01 3.14219685e+01 3.19522839e+01 3.20199013e+01 3.22164001e+01 3.26051331e+01 3.27404480e+01 3.30836105e+01 3.20227623e+01 3.23265991e+01 3.35173264e+01 3.35611954e+01 3.45546150e+01 3.48791809e+01 3.37297821e+01 3.38770294e+01 3.40305557e+01 3.41898994e+01 3.40026512e+01 3.45104675e+01 3.34253235e+01 3.41836853e+01 3.51857796e+01 3.57637215e+01 3.58393784e+01 3.49725189e+01 3.56432381e+01 3.58854332e+01 3.55144272e+01 3.49822159e+01 3.59967155e+01 3.69653511e+01 3.63235435e+01 3.56957970e+01 3.61641121e+01 3.53205986e+01 3.53002472e+01 3.26040840e+01 3.86271896e+01 2.73136654e+01 2.15051712e+02 7.75827454e+02 1.96699170e+03 994388864. 3109245. -268468640. -268468640. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1172492288. -18423924. 2.28281750e+05 2.61072266e+03 9.50846008e+02 2.71584381e+02 4.27107468e+01 4.57873421e+01 4.42533302e+01 4.22492867e+01 4.14218979e+01 4.00929298e+01 4.13223572e+01 3.78144493e+01 3.22832565e+01 3.87663078e+01 4.14403763e+01 4.02080841e+01 4.28722038e+01 4.14325829e+01 4.05244675e+01 3.94404640e+01 3.93541412e+01 4.05346031e+01 4.25612030e+01 4.21451416e+01 4.18447304e+01 4.13432426e+01 4.10833511e+01 4.01673546e+01 3.94061546e+01 4.08888168e+01 4.25031128e+01 4.26348267e+01 4.23333511e+01 4.15986481e+01 4.13747826e+01 4.16557846e+01 4.17255821e+01 4.20079880e+01 4.14199791e+01 4.14959183e+01 4.10154114e+01 4.05963593e+01 4.06438446e+01 4.13808823e+01 4.20446167e+01 4.19423714e+01 4.21668701e+01 4.18871346e+01 4.14470520e+01 4.16382675e+01 4.16489716e+01 4.16351166e+01 4.15441895e+01 4.19934006e+01 4.22353249e+01 4.21609039e+01 4.17425423e+01 4.18285484e+01 4.19173698e+01 4.26154938e+01 4.17531509e+01 4.01548958e+01 3.95585899e+01 3.70798912e+01 3.07337532e+01 5.01037369e+01 2.14513184e+02 -9.96777954e+02 2.45936102e+09 2.45936102e+09 5.25647053e+09 42531004. -5.29378500e+05 2.24754468e+03 2.29510071e+02 -2.06356445e+03 -9.45902250e+05 -1.38574234e+05 48479208. -33083930. 0. 0. -2.51298161e+10 -2083047040. -6.46987598e+03 3.61175142e+09 8.71484006e+09 0. 0. 2.56066335e+10 5.08697754e+03 1.01593292e+03 8.35211258e+01 4.44362793e+02 2.64674072e+02 3.60257378e+01 4.25299072e+01 4.33082542e+01 4.25854607e+01 3.94424095e+01 3.70027084e+01 3.76980133e+01 3.87242508e+01 3.85605545e+01 3.84602623e+01 3.83635292e+01 3.86158524e+01 3.93313599e+01 3.93062325e+01 3.91133957e+01 3.80513039e+01 3.77605324e+01 3.77497253e+01 3.83387108e+01 4.01936798e+01 4.01527672e+01 3.77428169e+01 3.72600327e+01 3.74070663e+01 3.71051636e+01 3.79954071e+01 3.79700737e+01 3.76366653e+01 3.73852577e+01 3.16094379e+01 3.08726139e+01 3.64546623e+01 3.76702194e+01 4.20641098e+01 4.39080849e+01 3.94915695e+01 3.77728691e+01 3.79034042e+01 3.81040611e+01 3.75261116e+01 3.72789459e+01 3.68317032e+01 3.67681961e+01 3.66822548e+01 3.71646500e+01 3.70906525e+01 3.69129066e+01 3.61790848e+01 3.67297668e+01 3.64577370e+01 3.58964386e+01 3.58311729e+01 3.60700722e+01 3.55525055e+01 3.45786438e+01 3.35495529e+01 3.27136726e+01 3.23258133e+01 -1.59484573e+02 -3.01571320e+02 -7.41231567e+02 -2.13960303e+03 -129402768. 5.04896050e+06 2.73123584e+09 2.73123584e+09 0. 0. -2.30841114e+09 -2.30841114e+09 3.10406579e+09 -844416064. -844416064. 0. 0. 0. 0. -873056960. -137949360. -1.80614197e+03 -6.75039551e+02 -2.71924286e+02 -1.39398727e+02 3.15984669e+01 3.12796173e+01 3.24613152e+01 3.22817764e+01 3.11925297e+01 3.06295948e+01 3.12040615e+01 3.17623920e+01 3.19639416e+01 3.16804924e+01 3.09648743e+01 3.07488976e+01 3.03957558e+01 2.97774429e+01 2.95144958e+01 2.94428215e+01 2.90772095e+01 2.93325081e+01 2.93220596e+01 2.94296703e+01 2.89448318e+01 2.83179760e+01 2.82748089e+01 2.84068298e+01 2.84469891e+01 2.81873302e+01 2.77346592e+01 2.78651543e+01 2.76918240e+01 2.72207298e+01 2.69702930e+01 2.63535004e+01 2.61227360e+01 2.61392193e+01 2.64784431e+01 2.67976341e+01 2.67178898e+01 2.65947914e+01 2.59714184e+01 2.55690918e+01 2.53766842e+01 2.56965084e+01 2.55641346e+01 2.50197392e+01 2.48697643e+01 2.41845455e+01 2.40710373e+01 2.42089634e+01 2.37549782e+01 2.36856270e+01 2.34300270e+01 2.30989799e+01 2.30308075e+01 2.30837307e+01 2.30932827e+01 2.25967312e+01 2.17115860e+01 2.13937473e+01 2.12683296e+01 2.13861332e+01 2.13683987e+01 2.11756973e+01 2.06413097e+01 2.04698048e+01 2.05171089e+01 2.05277462e+01 2.01723194e+01 2.00796108e+01 1.98753872e+01 1.99771729e+01 2.01280251e+01 1.97743454e+01 1.92352962e+01 1.90179768e+01 1.83799667e+01 1.77905197e+01 1.71418476e+01 1.70688095e+01 1.73421383e+01 1.75713768e+01 1.73641281e+01 1.70710468e+01 1.67808514e+01 1.65220814e+01 1.63034229e+01 1.60716133e+01 1.55481396e+01 1.53937597e+01 1.52158184e+01 1.52144537e+01 1.51237211e+01 1.50111675e+01 1.46359472e+01 1.41901665e+01 1.39212837e+01 1.38144407e+01 1.28447905e+01 1.26006870e+01 1.33287516e+01 1.35892220e+01 1.30741472e+01 1.23906898e+01 1.20307169e+01 1.17287560e+01 1.17153435e+01 1.15661268e+01 1.13669825e+01 1.09830074e+01 1.07701139e+01 1.04031935e+01 1.02159233e+01 9.99610710e+00 9.76494694e+00 9.43974209e+00 9.38268757e+00 9.36162853e+00 8.92831230e+00 8.61274433e+00 8.29969406e+00 8.10690498e+00 7.90791178e+00 7.75021172e+00 7.51423597e+00 7.26848984e+00 6.92862892e+00 6.77630806e+00 6.56291676e+00 6.21878195e+00 6.01425934e+00 5.74937963e+00 5.41867495e+00 5.35879087e+00 5.16786814e+00 4.82759762e+00 4.58844233e+00 4.38844013e+00 4.13161898e+00 3.87321568e+00 3.64207792e+00 3.39699626e+00 3.17170978e+00 2.93336582e+00 2.66707444e+00 2.45413280e+00 2.22688293e+00 1.96199882e+00 1.73118293e+00 1.48608506e+00 1.23777270e+00 1.00348437e+00 7.61951029e-01 5.27806342e-01 2.94049531e-01 4.35833223e-02 -1.97060972e-01 -4.38497245e-01 -6.77681684e-01 -9.18082595e-01 -1.15805268e+00 -1.39905131e+00 -1.63812053e+00 -1.87205255e+00 -2.11816025e+00 -2.35798621e+00 -2.60206199e+00 -2.85237455e+00 -3.06825638e+00 -3.32784247e+00 -3.56854916e+00 -3.75107980e+00 -4.00684309e+00 -4.26435089e+00 -4.53870869e+00 -4.81146812e+00 -4.93051052e+00 -4.92239475e+00 -5.58073902e+00 -6.03902674e+00 -5.53335714e+00 -5.96653128e+00 -7.20627594e+00 -7.54173708e+00 -7.04964209e+00 2.34745331e+01 4.55182152e+01 -2.54108219e+01 -2.57084694e+01 -2.61881447e+01 -2.65758438e+01 -2.69222126e+01 -2.74760742e+01 -2.81068230e+01 -2.88004990e+01 -2.90509701e+01 -2.90897331e+01 -2.94857273e+01 -3.02431030e+01 -3.10386696e+01 -3.09569397e+01 -3.15709534e+01 -3.22697678e+01 -1.18824463e+02 -2.05608826e+01 8.20822144e+01 -3.32019386e+01 -1.29319565e+02 -8.41520309e+01 -1.49446754e+01 -1.33710232e+01 -1.32018652e+01 -1.34088840e+01 -1.35215178e+01 -1.37996559e+01 -1.42118073e+01 -1.43389206e+01 -1.46879110e+01 -1.49336967e+01 -1.52011080e+01 -1.52748814e+01 -1.53072414e+01 -1.56513500e+01 -1.61841793e+01 -1.61424294e+01 -1.62782860e+01 -1.65798779e+01 -1.68759289e+01 -1.71334476e+01 -1.73099880e+01 -1.73864594e+01 -1.75655632e+01 -1.76442833e+01 -1.80255299e+01 -1.82887554e+01 -1.86957664e+01 -1.89840298e+01 -1.90825310e+01 -1.94585228e+01 -1.96697922e+01 -1.96387596e+01 -1.97461853e+01 -2.00114250e+01 -2.01803322e+01 -2.04428177e+01 -2.04707870e+01 -2.09987125e+01 -2.12723446e+01 -2.16157818e+01 -2.20465927e+01 -2.23330402e+01 -2.20206337e+01 -2.21902008e+01 -2.20418949e+01 -2.28926849e+01 -2.28528500e+01 -2.24390030e+01 -2.26361313e+01 -2.28004608e+01 -2.37920132e+01 -2.38008537e+01 -2.33720627e+01 -2.37529163e+01 -2.38978062e+01 -2.47848110e+01 -2.50936909e+01 -2.51450672e+01 -2.52884560e+01 -2.53860989e+01 -2.55888844e+01 -2.58636723e+01 -2.56632710e+01 -2.57656536e+01 -2.60788269e+01 -2.61201458e+01 -2.66697941e+01 -2.67629070e+01 -2.72694950e+01 -2.72803822e+01 -2.69098492e+01 -2.70956154e+01 -2.79297256e+01 -2.80811920e+01 -2.79076366e+01 -2.81054306e+01 -2.87308369e+01 -2.88431358e+01 -2.85978584e+01 -2.89362907e+01 -2.84944859e+01 -2.87222633e+01 -2.88395195e+01 -2.93305683e+01 -3.00131416e+01 -3.04821491e+01 -3.06137352e+01 -3.03268299e+01 -3.01348763e+01 -2.95256329e+01 -3.02143726e+01 -3.16970119e+01 -3.17872200e+01 -3.12586079e+01 -3.10739250e+01 -3.13700695e+01 -3.17052631e+01 -3.15487232e+01 -3.19552708e+01 -3.19111538e+01 -3.17303619e+01 -3.20879135e+01 -3.27731667e+01 -3.26863174e+01 -3.23977776e+01 -3.20418663e+01 -3.23780632e+01 -3.24959869e+01 -3.27438507e+01 -3.29341507e+01 -3.27995453e+01 -3.14869671e+01 -3.22346153e+01 -3.41916046e+01 -3.37334900e+01 -3.31372757e+01 -3.32583847e+01 -3.33105431e+01 -3.42751160e+01 -3.44997063e+01 -3.47703209e+01 -3.40871849e+01 -3.45261230e+01 -3.44346619e+01 -3.42296753e+01 -3.39804268e+01 -3.41280441e+01 -3.48870049e+01 -3.60611343e+01 -3.60917320e+01 -3.60519485e+01 -3.59065590e+01 -3.61131020e+01 -3.59541588e+01 -3.61705513e+01 -3.56502800e+01 -3.59791298e+01 -3.62479401e+01 -3.66719170e+01 -3.69417267e+01 -3.73264771e+01 -3.74439125e+01 -3.70977364e+01 -3.65504799e+01 -3.68268929e+01 -3.68515053e+01 -3.70810547e+01 -3.71565514e+01 -3.70418892e+01 -3.73968086e+01 -3.74822121e+01 -3.72351723e+01 -3.73326302e+01 -3.75084267e+01 -3.75694466e+01 -3.77588844e+01 -3.77228165e+01 -3.77186966e+01 -3.77411156e+01 -3.78819618e+01 -3.82999802e+01 -3.77093925e+01 -3.73949928e+01 -3.77065468e+01 -3.82928543e+01 -3.80262375e+01 -3.79877548e+01 -3.82917709e+01 -3.86714897e+01 -3.83529968e+01 -3.87568703e+01 -3.85731316e+01 -3.84591179e+01 -3.84892502e+01 -3.88744316e+01 -3.90112381e+01 -3.87481956e+01 -3.86444244e+01 -3.85530548e+01 -3.87685242e+01 -3.92611351e+01 -3.89960594e+01 -3.89864082e+01 -3.92682648e+01 -3.90827789e+01 -3.88039932e+01 -3.90899239e+01 -3.84775124e+01 -3.86161194e+01 -3.91606140e+01 -3.90925140e+01 -3.94032440e+01 -3.93744431e+01 -3.86282234e+01 -3.88092422e+01 -3.94077148e+01 -3.93306046e+01 -3.92079849e+01 -3.79521523e+01 -3.78830414e+01 -3.91948471e+01 -4.04769287e+01 -4.05396500e+01 -3.89583893e+01 -3.93834076e+01 -3.99238892e+01 -3.94768448e+01 -3.93022461e+01 -3.91324730e+01 -3.89631767e+01 -3.88945503e+01 -3.90937881e+01 -3.91952591e+01 -3.93530884e+01 -3.94604301e+01 -3.91329689e+01 -3.95266647e+01 -3.93092613e+01 -3.86819649e+01 -3.94368629e+01 -3.94897423e+01 -3.90718765e+01 -3.91170425e+01 -3.96807823e+01 -3.90999641e+01 -3.84989929e+01 -3.87134972e+01 -3.87776031e+01 -3.91020851e+01 -3.88357391e+01 -3.89703979e+01 -3.90084381e+01 -3.89913750e+01 -3.85286255e+01 -3.84941788e+01 -3.86153183e+01 -3.86705894e+01 -3.83416939e+01 -3.77384033e+01 -3.85740929e+01 -3.88095741e+01 -3.78896446e+01 -3.74423103e+01 -3.73704643e+01 -3.75833130e+01 -3.78086510e+01 -3.82731667e+01 -3.80255737e+01 -3.78036346e+01 -3.76903534e+01 -3.77973022e+01 -3.76833572e+01 -3.75216103e+01 -3.71110611e+01 -3.74651031e+01 -3.75810051e+01 -3.75373039e+01 -3.68469429e+01 -3.67566795e+01 -3.64048843e+01 -3.69300995e+01 -3.68805428e+01 -3.70382996e+01 -3.65389977e+01 -3.68051872e+01 -3.66981697e+01 -3.72098923e+01 -3.64288673e+01 -3.57361450e+01 -3.61906090e+01 -3.65743065e+01 -3.60561104e+01 -3.59175415e+01 -3.60554810e+01 -3.57856636e+01 -3.64586143e+01 -3.63418999e+01 -3.49323120e+01 -3.46294479e+01 -3.53235931e+01 -3.52722321e+01 -3.39753532e+01 -3.43147430e+01 -3.48460884e+01 -3.48446922e+01 -3.60083008e+01 -3.53320656e+01 -3.44860191e+01 -3.43623199e+01 -3.42931747e+01 -3.39789658e+01 -3.33411026e+01 -3.34798164e+01 -3.43058662e+01 -3.38428917e+01 -3.37122307e+01 -3.39325294e+01 -3.34464264e+01 -3.31835594e+01 -3.32584610e+01 -3.31058159e+01 -3.35307884e+01 -3.23463249e+01 -3.20949516e+01 -3.21469536e+01 -3.13759880e+01 -3.11543579e+01 -3.08126965e+01 -3.06081772e+01 -3.10208855e+01 -3.13936501e+01 -3.13621426e+01 -3.14628487e+01 -3.14480038e+01 -3.04817142e+01 -3.00358658e+01 -3.01410160e+01 -3.03809147e+01 -2.99869614e+01 -2.98212700e+01 -2.95883427e+01 -2.92118340e+01 -2.95116444e+01 -2.94983120e+01 -2.97351112e+01 -2.90064716e+01 -2.82059212e+01 -2.82017117e+01 -2.86727390e+01 -2.83198051e+01 -2.81965809e+01 -2.74155998e+01 -2.75689774e+01 -2.83309669e+01 -2.85555687e+01 -2.81433887e+01 -2.67615719e+01 -2.66070957e+01 -2.62191315e+01 -2.62791729e+01 -2.63384800e+01 -2.64149628e+01 -2.62448044e+01 -2.57083149e+01 -2.55040798e+01 -2.51702099e+01 -2.55416584e+01 -2.49314957e+01 -2.45188179e+01 -2.44771996e+01 -2.44981651e+01 -2.43585320e+01 -2.41893578e+01 -2.35276260e+01 -2.35429134e+01 -2.33519268e+01 -2.31795444e+01 -2.28731956e+01 -2.30714092e+01 -2.30611458e+01 -2.25735741e+01 -2.21146450e+01 -2.22464218e+01 -2.20188065e+01 -2.16481380e+01 -2.13864155e+01 -2.11932392e+01 -2.07216797e+01 -2.03369656e+01 -2.05056171e+01 -2.02737656e+01 -1.98423023e+01 -1.98681393e+01 -1.98818130e+01 -1.99215946e+01 -1.94734421e+01 -1.92150593e+01 -1.88549461e+01 -1.87037334e+01 -1.82941780e+01 -1.78815022e+01 -1.76156635e+01 -1.74232693e+01 -1.74951210e+01 -1.76865616e+01 -1.74819832e+01 -1.73970070e+01 -1.67514725e+01 -1.65987129e+01 -1.61112671e+01 -1.59639091e+01 -1.54864750e+01 -1.54541807e+01 -1.53075886e+01 -1.51132727e+01 -1.50682344e+01 -1.53345032e+01 -1.50409603e+01 -1.41156464e+01 -1.36967468e+01 -1.39028482e+01 -1.38938627e+01 -1.34918375e+01 -1.31991940e+01 -1.30003376e+01 -1.24603271e+01 -1.23458366e+01 -1.21737051e+01 -1.17881775e+01 -1.15424299e+01 -1.12197027e+01 -1.10514755e+01 -1.08751297e+01 -1.06090412e+01 -1.03337317e+01 -9.82745266e+00 -8.52771473e+00 -8.07269001e+00 -9.02513790e+00 -8.66951561e+00 -8.92601109e+00 -9.29383087e+00 -8.87337685e+00 -8.38275337e+00 -7.41315031e+00 7.54058533e+01 8.74817352e+01 -2.00406174e+02 -3.66412854e+00 -6.82812166e+00 1.75162003e+02 5.99949217e+00 -1.66930054e+02 2.85425758e+00 2.41377783e+00 1.18675172e+00 -6.76288300e+01 -5.20091295e+00 -6.11584759e+00 -3.99717369e+01 -6.19182110e+00 -4.85941362e+00 -4.00603342e+00 -3.59133577e+00 -3.42755032e+00 -2.98970008e+00 -2.80636573e+00 -2.86253715e+00 -2.57572079e+00 -2.18721938e+00 -1.84068060e+00 -1.77002311e+00 -1.63399875e+00 -1.29643154e+00 -1.02937603e+00 -8.04372609e-01 -5.45983076e-01 -2.86694765e-01 -6.19295537e-02 1.85525939e-01 4.20724481e-01 6.60082459e-01 9.06004369e-01 1.14502263e+00 1.38715029e+00 1.62644589e+00 1.86846495e+00 2.11300445e+00 2.36052966e+00 2.59347844e+00 2.83583546e+00 3.07927370e+00 3.31751275e+00 3.55552292e+00 3.80365109e+00 4.06864262e+00 4.26915359e+00 4.49689960e+00 4.74933338e+00 5.00489855e+00 5.22286224e+00 5.44829607e+00 5.72814417e+00 5.95237875e+00 6.23654079e+00 6.53519058e+00 6.69296026e+00 6.90261555e+00 7.14782047e+00 7.33624458e+00 7.58645725e+00 7.80414915e+00 8.02537155e+00 8.40190601e+00 8.72166443e+00 8.89385128e+00 8.96217728e+00 9.17172241e+00 9.55439949e+00 9.67328453e+00 9.78473091e+00 1.00141764e+01 1.03077650e+01 1.06171446e+01 1.09550438e+01 1.10928135e+01 1.13940020e+01 1.15832348e+01 1.17818747e+01 1.20668459e+01 1.23031855e+01 1.25676146e+01 1.29062681e+01 1.29151793e+01 1.30811415e+01 1.34343433e+01 1.38818026e+01 1.40174570e+01 1.42127190e+01 1.43684492e+01 1.46610403e+01 1.46145754e+01 1.45495396e+01 1.53011217e+01 1.60217857e+01 1.58598728e+01 1.62227764e+01 1.62603951e+01 1.62114239e+01 1.62412186e+01 1.61053524e+01 1.65269299e+01 1.73662472e+01 1.80337677e+01 1.81809311e+01 1.75314903e+01 1.78301468e+01 1.81237736e+01 1.85316944e+01 1.89735641e+01 1.91135635e+01 1.93309307e+01 1.94934120e+01 1.95448780e+01 1.96877346e+01 2.00664139e+01 2.02866497e+01 2.04689484e+01 2.06137466e+01 2.08631611e+01 2.11635189e+01 2.16068268e+01 2.19555950e+01 2.21804886e+01 2.19596310e+01 2.24153805e+01 2.23783531e+01 2.27319813e+01 2.26122761e+01 2.25037823e+01 2.28048992e+01 2.28436069e+01 2.34606800e+01 2.34468517e+01 2.24113503e+01 2.18947678e+01 2.31141644e+01 2.48995190e+01 2.66334038e+01 2.67189445e+01 2.53284054e+01 2.56728935e+01 2.57606125e+01 2.59479065e+01 2.57332039e+01 2.57733669e+01 2.58967609e+01 2.59700432e+01 2.65242443e+01 2.65966530e+01 2.70979309e+01 2.71542301e+01 2.68725758e+01 2.69607697e+01 2.77700729e+01 2.78709221e+01 2.80925426e+01 2.82146530e+01 2.79770222e+01 2.80050488e+01 2.87619553e+01 2.88006802e+01 2.93289356e+01 2.94407024e+01 2.82592754e+01 2.90850677e+01 2.98719749e+01 3.05516586e+01 3.05412788e+01 3.00747471e+01 2.90081329e+01 2.89103127e+01 3.06285000e+01 3.17911358e+01 3.18843746e+01 3.12760525e+01 3.10202618e+01 3.09481277e+01 3.13079643e+01 3.09091072e+01 3.04780331e+01 3.13236904e+01 3.15127945e+01 2.22809639e+01 -1.42686844e+02 -2.52854218e+02 6.61209717e+01 6.43522415e+01 6.12276230e+01 6.00228119e+01 3.62829193e+02 6.75717163e+02 3.51105286e+02 7.32601685e+02 2.07045288e+03 103750064. 1196035840. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1122135808. 2.40978271e+03 2.42428802e+02 3.15759144e+01 2.53385132e+02 3.73270683e+01 4.01706276e+01 3.72722244e+01 3.70741005e+01 3.73228722e+01 3.82257805e+01 3.85174446e+01 3.82617836e+01 3.78244934e+01 3.71586761e+01 3.66985588e+01 3.62376060e+01 3.61769867e+01 3.49126205e+01 3.60031624e+01 3.79943810e+01 3.84308891e+01 3.84590340e+01 3.78792763e+01 3.71810074e+01 3.68240967e+01 3.62409706e+01 3.67643929e+01 3.75512581e+01 3.86789589e+01 3.86504593e+01 3.80601387e+01 3.78314590e+01 3.69928703e+01 3.74165497e+01 3.76304588e+01 3.84554405e+01 3.80259628e+01 3.83814354e+01 3.82125511e+01 3.83587341e+01 3.79802856e+01 3.84782791e+01 3.83836060e+01 3.86759033e+01 3.92896996e+01 3.93777351e+01 3.91601105e+01 3.87858467e+01 3.91072235e+01 3.89109879e+01 3.87869263e+01 3.89121361e+01 3.88741455e+01 3.88669243e+01 3.86938515e+01 3.87844048e+01 3.86576881e+01 3.93049850e+01 3.89146614e+01 3.81100578e+01 3.76991348e+01 3.57130394e+01 3.22491417e+01 4.00142860e+01 1.73280457e+02 7.46662450e+06 0. 0. 0. 0. 0. 4.05737293e+09 4.05737293e+09 4.05737293e+09 0. 0. 0. 0. 0. 0. -2.51298161e+10 -2083047040. 1.30391230e+04 1.37533438e+04 2.09184462e+06 1.81105803e+11 0. 0. 6.21589555e+09 -1001272064. 7.34425312e+05 2.36597852e+03 9.41724609e+02 3.81120796e+01 5.04733467e+01 4.38749268e+02 5.73424301e+01 4.17991371e+01 4.39928703e+01 -3.41894379e+02 4.50626335e+01 4.23186264e+01 4.12639084e+01 4.17301102e+01 4.50303345e+01 4.98007164e+01 4.91467743e+01 4.85504608e+01 4.43278618e+01 4.20355301e+01 3.83354950e+01 4.03813896e+01 5.48916092e+01 5.69281845e+01 4.17936798e+02 4.65810204e+01 -3.31489441e+02 4.15620079e+01 4.60154228e+01 4.51242485e+01 4.22849236e+01 4.03317947e+01 4.96755457e+00 2.62730289e+00 3.96105118e+01 4.44151993e+01 7.08725128e+01 8.33131180e+01 5.79432411e+01 4.85536880e+01 4.86925774e+01 4.46148872e+01 4.27682495e+01 4.06698273e+02 2.55095047e+02 3.32347946e+01 3.35913315e+01 3.39758301e+01 3.37292786e+01 3.28810005e+01 3.17095032e+01 3.25157242e+01 3.26846390e+01 3.17776146e+01 3.07111301e+01 3.03123093e+01 3.09801235e+01 3.10713558e+01 -1.67243698e+02 -3.15037811e+02 2.69920464e+01 -7.81005554e+02 -2.01615906e+03 3.24872883e+09 9.59438541e+09 0. 2.73123584e+09 2.73123584e+09 2.73123584e+09 0. 0. -2.30841114e+09 -2.30841114e+09 -2.30841114e+09 0. 0. 0. 0. 0. -415871712. -3.38808105e+03 -6.68542542e+02 -2.80939148e+02 -1.47501877e+02 3.03273182e+01 3.10213547e+01 2.98968296e+01 2.97384930e+01 -1.47034119e+02 -2.77265076e+02 3.63076782e+01 3.54913101e+01 3.89415932e+01 4.17780113e+01 4.45596581e+01 3.42300262e+02 2.15701553e+02 2.94485722e+01 2.09491882e+01 2.80994568e+01 3.57237968e+01 2.98945866e+01 2.86445446e+01 2.76526566e+01 2.79141312e+01 2.76558552e+01 2.71578884e+01 2.66748753e+01 2.66844864e+01 2.68228245e+01 2.64980927e+01 2.62446995e+01 2.59102612e+01 2.57678814e+01 2.53168144e+01 2.55898762e+01 2.54231262e+01 2.50493145e+01 2.48847446e+01 2.48130665e+01 2.52545700e+01 2.55531731e+01 2.57327652e+01 2.55681515e+01 2.53140507e+01 2.47593670e+01 2.41945419e+01 2.37573586e+01 2.37036934e+01 2.38175182e+01 2.41464653e+01 2.37044506e+01 2.31202831e+01 2.34097805e+01 2.34571724e+01 2.31322689e+01 2.30496521e+01 2.32859459e+01 2.36977692e+01 2.31594296e+01 2.30840912e+01 2.22626781e+01 2.18177834e+01 2.11057968e+01 2.15554142e+01 2.16200104e+01 2.12194080e+01 2.11137009e+01 2.10023613e+01 2.13735886e+01 2.15460510e+01 2.14597473e+01 2.10895443e+01 2.06759453e+01 2.05731430e+01 2.06026230e+01 2.08615704e+01 2.04787846e+01 2.00622482e+01 1.96107407e+01 1.91461487e+01 1.88689499e+01 1.85155296e+01 1.84586411e+01 1.85117207e+01 1.85341454e+01 1.83518791e+01 1.80726299e+01 1.79930973e+01 1.78039646e+01 1.76486454e+01 1.75734749e+01 1.71952038e+01 1.70673409e+01 1.67962074e+01 1.65581684e+01 1.63806438e+01 1.62120705e+01 1.60983601e+01 1.57458839e+01 1.56158991e+01 1.54227304e+01 1.41498985e+01 1.39284344e+01 1.56776094e+01 1.59746284e+01 1.52181625e+01 1.46745453e+01 1.43177538e+01 1.39527111e+01 1.39911318e+01 1.37849512e+01 1.35901756e+01 1.34256392e+01 1.32377882e+01 1.29357386e+01 1.27006264e+01 1.25799217e+01 1.24987059e+01 1.22176342e+01 1.20959978e+01 1.19896107e+01 1.18421679e+01 1.16393337e+01 1.14244518e+01 1.12469921e+01 1.10684605e+01 1.07979975e+01 1.05438433e+01 1.03894472e+01 1.01790714e+01 9.97397327e+00 9.88775730e+00 9.62755203e+00 9.45339012e+00 9.11220837e+00 8.76271152e+00 8.83827496e+00 8.80680370e+00 8.40970421e+00 8.17451191e+00 8.01986790e+00 7.85258007e+00 7.63723183e+00 7.49118710e+00 7.27343607e+00 7.04236031e+00 6.83266735e+00 6.60837078e+00 6.44875765e+00 6.26677608e+00 6.05634260e+00 5.84929991e+00 5.64415979e+00 5.44448709e+00 5.23764896e+00 5.03831339e+00 4.84126472e+00 4.64557981e+00 4.43352699e+00 4.23283339e+00 4.03335333e+00 3.83470011e+00 3.63477635e+00 3.43191218e+00 3.22881675e+00 3.03061581e+00 2.83131385e+00 2.62724233e+00 2.42412066e+00 2.21321821e+00 2.00629044e+00 1.83792126e+00 1.61609828e+00 1.40176725e+00 1.26339459e+00 1.28343570e+00 1.52916217e+00 5.16049862e-01 -2.33678222e-02 6.60752505e-02 -1.31107330e-01 -3.24355423e-01 2.45974369e+01 4.85567474e+01 -5.22903481e+01 -3.30160637e+01 -1.27741921e+00 -2.58312345e+00 -3.35474181e+00 -3.69278145e+00 -5.00767946e+00 -5.34026337e+00 -5.52982235e+00 -5.58485174e+00 -5.81761742e+00 -6.33464813e+00 -6.64769459e+00 -6.91196108e+00 -7.29405499e+00 -7.60336018e+00 -7.89583254e+00 -8.24204540e+00 -8.50664711e+00 -8.88333225e+00 -9.19539165e+00 -9.46660519e+00 -8.23987484e+00 -9.77006626e+00 -7.01521683e+00 -1.08373690e+01 -6.57885647e+00 -8.70694160e+00 -8.46302986e+00 -6.88924122e+00 -6.85821009e+00 -7.16130447e+00 -7.08131170e+00 -7.47211933e+00 -7.80928516e+00 -8.02585602e+00 -8.03858757e+00 -8.22815895e+00 -8.64218044e+00 -8.90392780e+00 -8.78790092e+00 -9.08442307e+00 -9.67704964e+00 -9.60630131e+00 -9.65093231e+00 -9.95938492e+00 -1.00513821e+01 -1.01258583e+01 -1.05319262e+01 -1.04017258e+01 -1.10390177e+01 -1.10516644e+01 -1.13932467e+01 -1.15404406e+01 -1.17585535e+01 -1.18982010e+01 -1.21003294e+01 -1.24600592e+01 -1.26980886e+01 -1.26872263e+01 -1.27608204e+01 -1.23187141e+01 -1.26057482e+01 -1.29389877e+01 -1.32290678e+01 -1.36540680e+01 -1.39119864e+01 -1.40322199e+01 -1.41257772e+01 -1.44931393e+01 -1.49825668e+01 -1.53218956e+01 -1.50094624e+01 -1.53952827e+01 -1.55716820e+01 -1.53691750e+01 -1.56438627e+01 -1.56783600e+01 -1.64802418e+01 -1.61665173e+01 -1.58030701e+01 -1.63499069e+01 -1.63382587e+01 -1.66513119e+01 -1.68386860e+01 -1.67748013e+01 -1.68326130e+01 -1.69062481e+01 -1.76303005e+01 -1.81043072e+01 -1.79805202e+01 -1.86051655e+01 -1.87908840e+01 -1.90868340e+01 -1.88985634e+01 -1.96026859e+01 -1.96517525e+01 -1.98496685e+01 -1.94501228e+01 -1.92474747e+01 -1.98500538e+01 -1.99124489e+01 -1.98697453e+01 -2.01747112e+01 -2.07527561e+01 -2.03152752e+01 -2.05542660e+01 -2.09165592e+01 -2.07246780e+01 -2.07771683e+01 -2.07685242e+01 -2.14159279e+01 -2.20076008e+01 -2.22681007e+01 -2.24675827e+01 -2.25950890e+01 -2.23604469e+01 -2.14391117e+01 -2.11768017e+01 -2.28078098e+01 -2.41304169e+01 -2.37057457e+01 -2.34405499e+01 -2.31409512e+01 -2.31910267e+01 -2.34581299e+01 -2.34677258e+01 -2.36319275e+01 -2.42097797e+01 -2.51580067e+01 -2.52405663e+01 -2.54314327e+01 -2.44773846e+01 -2.47299995e+01 -2.43544540e+01 -2.52541237e+01 -2.54658375e+01 -2.52632980e+01 -2.47591572e+01 -2.32603016e+01 -2.45231285e+01 -2.74243088e+01 -2.66160870e+01 -2.53220329e+01 -2.52123756e+01 -2.55423622e+01 -2.67604027e+01 -2.74572754e+01 -2.70522633e+01 -2.64400501e+01 -2.67725964e+01 -2.68446579e+01 -2.69626293e+01 -2.68338814e+01 -2.69821014e+01 -2.73599300e+01 -2.77698879e+01 -2.77566090e+01 -2.75865669e+01 -2.77135334e+01 -2.81125259e+01 -2.82474499e+01 -2.86519375e+01 -2.86122589e+01 -2.87676468e+01 -2.88751869e+01 -2.85216751e+01 -2.84273262e+01 -2.83710270e+01 -2.88876095e+01 -2.86233768e+01 -2.87953682e+01 -2.89014683e+01 -2.90845051e+01 -2.88216534e+01 -2.90408001e+01 -2.92366028e+01 -3.00300446e+01 -3.02211914e+01 -3.01329708e+01 -3.00407410e+01 -3.01775951e+01 -3.05342026e+01 -3.06857624e+01 -3.03809700e+01 -3.01635685e+01 -2.97980843e+01 -3.02552872e+01 -3.09158535e+01 -3.11799507e+01 -3.05809746e+01 -3.07003269e+01 -3.12778492e+01 -3.19233398e+01 -3.16109848e+01 -3.21665649e+01 -3.23953362e+01 -3.19223614e+01 -3.14449348e+01 -3.11044350e+01 -3.11795349e+01 -3.15669022e+01 -3.19078598e+01 -3.25110779e+01 -3.22319679e+01 -3.20840378e+01 -3.13481865e+01 -3.15137939e+01 -3.22364807e+01 -3.22785072e+01 -3.19829025e+01 -3.19465256e+01 -3.16858482e+01 -3.17600975e+01 -3.28086243e+01 -3.29114227e+01 -3.23803291e+01 -3.25201187e+01 -3.23092499e+01 -3.26467133e+01 -3.26374893e+01 -3.15058899e+01 -3.17167263e+01 -3.28209953e+01 -3.27310333e+01 -3.26837158e+01 -3.13136673e+01 -3.13820190e+01 -3.27608070e+01 -3.40755119e+01 -3.41758537e+01 -3.24829445e+01 -3.28267097e+01 -3.35405617e+01 -3.31027718e+01 -3.29570427e+01 -3.27943382e+01 -3.26215897e+01 -3.27612648e+01 -3.30095406e+01 -3.30679054e+01 -3.32199821e+01 -3.32249794e+01 -3.27362518e+01 -3.35291481e+01 -3.35376930e+01 -3.28135071e+01 -3.39249420e+01 -3.40070038e+01 -3.37805748e+01 -3.39209557e+01 -3.35233459e+01 -3.34263191e+01 -3.27033119e+01 -3.22423935e+01 -3.35005417e+01 -3.35527687e+01 -3.27063713e+01 -3.27904358e+01 -3.34752617e+01 -3.36232643e+01 -3.34199638e+01 -3.36445465e+01 -3.32584457e+01 -3.35197411e+01 -3.28816872e+01 -3.26280212e+01 -3.28334541e+01 -3.27421494e+01 -3.29930496e+01 -3.26955795e+01 -3.28294411e+01 -3.27702217e+01 -3.28979683e+01 -3.27706451e+01 -3.29441948e+01 -3.30086136e+01 -3.30019302e+01 -3.26114693e+01 -3.25903320e+01 -3.32616692e+01 -3.34971848e+01 -3.28766479e+01 -3.23602829e+01 -3.16422939e+01 -3.19538651e+01 -3.21907501e+01 -3.23059387e+01 -3.22583885e+01 -3.26112022e+01 -3.27756958e+01 -3.28529358e+01 -3.25357742e+01 -3.24983292e+01 -3.27657127e+01 -3.23108673e+01 -3.16227779e+01 -3.16928387e+01 -3.24084702e+01 -3.23527298e+01 -3.24246254e+01 -3.22155151e+01 -3.19187336e+01 -3.16854038e+01 -3.20718498e+01 -3.17028618e+01 -3.15189400e+01 -3.13744316e+01 -3.18270302e+01 -3.04223938e+01 -3.07881107e+01 -3.11654606e+01 -3.16321888e+01 -3.24817352e+01 -3.18071194e+01 -3.07886734e+01 -3.05699100e+01 -2.99062386e+01 -2.99799709e+01 -2.93264999e+01 -2.98947353e+01 -3.07805080e+01 -2.98957100e+01 -2.99868813e+01 -3.01771564e+01 -2.96015396e+01 -3.01540279e+01 -3.06966763e+01 -3.05851250e+01 -3.03935680e+01 -2.95663891e+01 -3.03129539e+01 -3.06437607e+01 -2.95863113e+01 -2.88284359e+01 -2.79656849e+01 -2.80454903e+01 -2.90180092e+01 -2.89190578e+01 -2.78543797e+01 -2.78527775e+01 -2.79862995e+01 -2.75145035e+01 -2.71284752e+01 -2.80905724e+01 -2.79619675e+01 -2.77183285e+01 -2.82757454e+01 -2.78617516e+01 -2.77652569e+01 -2.71804867e+01 -2.77976570e+01 -2.78385983e+01 -2.73000832e+01 -2.67180939e+01 -2.66085110e+01 -2.66983566e+01 -2.63675632e+01 -2.64568138e+01 -2.54582787e+01 -2.58912392e+01 -2.63169708e+01 -2.67434273e+01 -2.64889202e+01 -2.55103798e+01 -2.55851173e+01 -2.51048546e+01 -2.54629841e+01 -2.54323158e+01 -2.53520737e+01 -2.52508926e+01 -2.53805485e+01 -2.48059750e+01 -2.38781357e+01 -2.39101582e+01 -2.36892128e+01 -2.38730412e+01 -2.41012421e+01 -2.39329529e+01 -2.33557014e+01 -2.29794254e+01 -2.29397163e+01 -2.28016891e+01 -2.27551689e+01 -2.30374508e+01 -2.32215500e+01 -2.26554203e+01 -2.32642555e+01 -2.24293633e+01 -2.25497875e+01 -2.22743034e+01 -2.21459465e+01 -2.17398548e+01 -2.12014866e+01 -2.09939346e+01 -2.06178093e+01 -2.09066849e+01 -2.11883087e+01 -2.10645275e+01 -2.06408730e+01 -2.04795780e+01 -2.04918747e+01 -2.01744480e+01 -2.01570263e+01 -1.98903980e+01 -1.96734715e+01 -1.95891190e+01 -1.92918701e+01 -1.92222328e+01 -1.89811363e+01 -1.88773403e+01 -1.86303024e+01 -1.85055351e+01 -1.84397106e+01 -1.81594505e+01 -1.76729412e+01 -1.76392117e+01 -1.76590214e+01 -1.74719429e+01 -1.73899879e+01 -1.72649002e+01 -1.68949776e+01 -1.62981739e+01 -1.62305412e+01 -1.65439148e+01 -1.61820545e+01 -1.54608240e+01 -1.54800844e+01 -1.58014088e+01 -1.58671093e+01 -1.53893147e+01 -1.50896006e+01 -1.49658384e+01 -1.46182146e+01 -1.46460924e+01 -1.45854454e+01 -1.39873819e+01 -1.38223648e+01 -1.35476685e+01 -1.35077314e+01 -1.32761822e+01 -1.29846849e+01 -1.27756815e+01 -1.23584404e+01 -1.11333799e+01 -1.07443447e+01 -1.17125549e+01 -1.14351206e+01 -1.16398907e+01 -1.20970306e+01 -1.17980423e+01 -1.14268055e+01 -1.04403839e+01 -1.08266960e+02 -2.19275951e+01 7.39483566e+01 -1.41550245e+01 -1.48436422e+01 -1.13233643e+02 -1.46407766e+01 6.34619408e+01 -1.17994442e+01 -1.16903210e+01 -1.17796679e+01 -5.94846296e+00 -1.11604118e+01 -9.93399811e+00 -8.83549023e+00 -9.23545933e+00 -6.78250504e+00 -8.28940487e+00 -9.11230659e+00 -7.20053339e+00 -6.90530682e+00 -6.66999531e+00 -6.91419888e+00 -5.84062910e+00 -4.35382175e+00 -6.73829174e+00 -7.71199036e+00 -6.11256075e+00 -5.66346550e+00 -5.29545593e+00 -5.09360409e+00 -4.86671782e+00 -4.65065384e+00 -4.46281004e+00 -4.25247717e+00 -4.06303310e+00 -3.86473823e+00 -3.65619397e+00 -3.44918323e+00 -3.24615121e+00 -3.05119300e+00 -2.85181856e+00 -2.63999271e+00 -2.43374062e+00 -2.24226904e+00 -2.04310584e+00 -1.82520902e+00 -1.60706389e+00 -1.41291738e+00 -1.20411456e+00 -9.90564644e-01 -8.14534843e-01 -6.22357190e-01 -3.98814112e-01 -1.82713673e-01 1.60181113e-02 2.07503885e-01 4.49015796e-01 6.32978976e-01 9.00774717e-01 1.12202370e+00 1.21366119e+00 1.43156171e+00 1.65202141e+00 1.89242232e+00 2.12198663e+00 2.26785970e+00 2.42583704e+00 2.66814709e+00 2.93035531e+00 3.06201053e+00 3.06570125e+00 3.34885859e+00 3.73705935e+00 3.84498405e+00 3.85064411e+00 4.16044378e+00 4.38039589e+00 4.66265631e+00 4.97446775e+00 5.09850359e+00 5.13452911e+00 5.38464308e+00 6.02670670e+00 6.43134737e+00 6.11713696e+00 6.16505957e+00 6.39004660e+00 6.55107450e+00 6.66893435e+00 7.23114061e+00 7.46753454e+00 7.58760262e+00 7.90426779e+00 8.33283806e+00 8.15555286e+00 7.97398567e+00 7.51156139e+00 8.78932762e+00 9.73019886e+00 9.37341309e+00 9.71830273e+00 9.62179375e+00 9.73857307e+00 9.83468819e+00 9.46204567e+00 8.89536476e+00 9.85983086e+00 1.18848982e+01 1.23554840e+01 1.09563656e+01 1.13174934e+01 1.13232183e+01 1.15631676e+01 1.17990370e+01 1.20761967e+01 1.23133450e+01 1.26623707e+01 1.26493378e+01 1.26234312e+01 1.23871670e+01 1.25840406e+01 1.27865839e+01 1.31044254e+01 1.33959732e+01 1.38669720e+01 1.38877611e+01 1.39341984e+01 1.42895670e+01 1.48641052e+01 1.54125109e+01 1.54866838e+01 1.53349905e+01 1.50839424e+01 1.53426800e+01 1.59341888e+01 1.58500013e+01 1.59779615e+01 1.57119427e+01 1.48710852e+01 1.36671743e+01 1.46680317e+01 1.67760773e+01 1.92962761e+01 1.92892284e+01 1.68367863e+01 1.70666218e+01 1.77636242e+01 1.79496155e+01 1.78584061e+01 1.84049587e+01 1.85815830e+01 1.91096096e+01 1.88188267e+01 1.94549351e+01 1.94516106e+01 1.94934921e+01 1.90217667e+01 1.91964073e+01 1.97455044e+01 1.98113174e+01 2.00404205e+01 2.02352962e+01 1.96655312e+01 1.93478107e+01 2.04398098e+01 2.06382771e+01 2.15581875e+01 2.16834488e+01 2.03023834e+01 2.06173077e+01 2.09944115e+01 2.00121918e+01 7.99408579e+00 2.41457319e+00 -3.40276566e+01 4.59798927e+01 8.65916672e+01 -1.39061340e+02 -2.57764648e+02 3.30160484e+01 3.04201145e+01 2.81601658e+01 2.92520428e+01 2.95276432e+01 2.56933098e+01 3.14257164e+01 3.11140041e+01 3.21388794e+02 2.39171463e+02 4.16713715e+01 3.75113640e+01 3.93594666e+01 3.77384415e+01 3.79645729e+01 3.32054749e+01 3.08501053e+01 2.19454994e+01 2.02266708e+02 1.76150269e+02 6.18230835e+02 -7753498. -1344101120. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.19708656e+05 -3.52851318e+03 -1.26551542e+01 8.83224426e+02 4.42495804e+01 6.17963028e+01 4.80955200e+01 3.92096436e+02 2.51869263e+02 3.76205750e+01 3.11408405e+01 2.99026794e+01 2.92962074e+01 2.88505287e+01 2.82361889e+01 2.88699074e+01 2.92489414e+01 2.80695190e+01 2.91238365e+01 3.09087906e+01 3.04444733e+01 3.03120975e+01 3.00508289e+01 2.96773548e+01 2.95844116e+01 3.01980152e+01 3.10742588e+01 3.14208698e+01 3.18653755e+01 3.06489658e+01 2.97985497e+01 2.94864159e+01 2.93061047e+01 2.93023758e+01 3.07829895e+01 3.25963974e+01 3.26021843e+01 3.24552231e+01 3.22451324e+01 3.20609131e+01 3.13181324e+01 3.02373581e+01 3.09194107e+01 3.21257401e+01 3.31859207e+01 3.30056686e+01 3.24634590e+01 3.19138832e+01 3.14959812e+01 3.07721500e+01 3.02966232e+01 3.20351448e+01 3.30109863e+01 3.22543716e+01 3.32585106e+01 3.00210972e+01 3.05149651e+01 -1.80087555e+02 -3.36678009e+02 3.97686157e+01 3.89032478e+01 3.22734184e+01 2.12561417e+01 2.79046345e+01 1.72498138e+02 4.24083250e+06 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.76951728e+11 -2.76951728e+11 0. 0. -2.51298161e+10 -2083047040. 1.30391230e+04 1.37533438e+04 2.09184462e+06 1.81105803e+11 0. 0. 0. 0. 0. 7.41446450e+06 -1.74803442e+03 -9.83233398e+02 -3735443. 2.52332129e+03 1.82399994e+02 1.13293457e+02 8.89580154e+01 -2.15989990e+03 2.88641150e+06 -3.46490156e+05 -17462202. -38777380. -105504. 303809248. 145489024. 198758608. 2.57082150e+06 4040611. -1228883. -7.98101875e+05 1.18920435e+03 1.17540337e+02 -2.88894592e+02 9.94732056e+01 -1.95409253e+03 3.71257781e+05 -102020400. 4958718. -68659448. -92109272. -4.23682531e+05 -5.12575438e+05 -1643392. 17803480. 7.72042562e+05 34513832. 1525430. 119721744. -624803648. 11231494. 42657072. 2.28837891e+03 9.62511719e+02 6.60046082e+01 6.79297028e+01 7.01985245e+01 4.17092621e+02 2.56914093e+02 3.33791771e+01 4.00752563e+01 4.05398216e+01 -1.62014313e+02 -3.12129974e+02 4.53120346e+01 5.46326485e+01 5.67633400e+01 -7.58597229e+02 -2.03097131e+03 -4727591. -86239808. -1446469760. 0. 0. 0. 2.73123584e+09 2.73123584e+09 2.73123584e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.32045547e+05 -5.73556641e+02 -1.45014862e+02 3.53830833e+01 3.72726669e+01 3.58133469e+01 3.46676369e+01 3.37746696e+01 3.38406868e+01 4.20794296e+01 4.34746170e+01 5.00941505e+01 4.69516754e+01 4.71070480e+01 4.90389519e+01 4.97846222e+01 3.88615150e+01 4.02166176e+01 3.45003662e+01 2.68948975e+01 3.51450195e+01 4.18977470e+01 3.59636841e+01 3.37479019e+01 3.24535103e+01 3.19187412e+01 3.15877342e+01 3.22158279e+01 3.26891899e+01 3.22108650e+01 3.16882973e+01 3.19065304e+01 3.16983128e+01 3.12500515e+01 3.08092461e+01 3.03026714e+01 3.10292339e+01 3.14105129e+01 3.07182217e+01 3.10507259e+01 3.11923389e+01 3.11349487e+01 3.08347225e+01 3.02014294e+01 2.97095013e+01 3.00865841e+01 3.00192490e+01 2.98412685e+01 2.95140705e+01 2.92852478e+01 2.88864365e+01 2.88892097e+01 2.88193951e+01 2.92792587e+01 2.95965176e+01 2.91513824e+01 2.87978153e+01 2.90620136e+01 2.89156170e+01 2.81118546e+01 2.76884308e+01 2.75456505e+01 2.78886356e+01 2.78756084e+01 2.73570938e+01 2.73114624e+01 2.70463085e+01 2.69378338e+01 2.68683624e+01 2.67307472e+01 2.67095299e+01 2.65248661e+01 2.65507088e+01 2.63778782e+01 2.59330673e+01 2.57190647e+01 2.54399605e+01 2.58033981e+01 2.60096188e+01 2.59558411e+01 2.55229836e+01 2.49933758e+01 2.50351486e+01 2.48921719e+01 2.46027489e+01 2.43173714e+01 2.37191257e+01 2.38717690e+01 2.37844105e+01 2.34245491e+01 2.31124535e+01 2.30436363e+01 2.33718700e+01 2.27136364e+01 2.25323429e+01 2.22690258e+01 2.22019806e+01 2.20639820e+01 2.18024349e+01 2.18157444e+01 2.13372822e+01 2.11077728e+01 2.07828102e+01 1.92591686e+01 1.92540588e+01 2.15796585e+01 2.17408829e+01 2.05476704e+01 1.98517876e+01 1.96141701e+01 1.95825119e+01 1.94558182e+01 1.91449814e+01 1.87860279e+01 1.88192387e+01 1.87307491e+01 1.86468163e+01 1.82498493e+01 1.80406151e+01 1.78492985e+01 1.75791073e+01 1.73608093e+01 1.71170712e+01 1.69810905e+01 1.68116131e+01 1.65164127e+01 1.63231106e+01 1.62784214e+01 1.60976467e+01 1.58974047e+01 1.56652565e+01 1.54315310e+01 1.51787014e+01 1.49588919e+01 1.48051586e+01 1.45917034e+01 1.43572512e+01 1.38963184e+01 1.39517784e+01 1.39992266e+01 1.34888573e+01 1.32753353e+01 1.31091404e+01 1.29318743e+01 1.26868734e+01 1.24714756e+01 1.22504406e+01 1.20182104e+01 1.17760458e+01 1.15006723e+01 1.13113852e+01 1.11283131e+01 1.09226618e+01 1.06962223e+01 1.04749355e+01 1.02722292e+01 1.00532045e+01 9.82060623e+00 9.61040306e+00 9.38423157e+00 9.14639187e+00 8.92401791e+00 8.69651318e+00 8.47505283e+00 8.25923347e+00 8.04370213e+00 7.82100916e+00 7.60375690e+00 7.37960386e+00 7.14507389e+00 6.91333342e+00 6.68404055e+00 6.46127558e+00 6.25746298e+00 6.01203346e+00 5.77965498e+00 5.59702063e+00 5.54906321e+00 5.64343739e+00 4.61453247e+00 4.05791855e+00 4.26761389e+00 3.99931622e+00 4.07062244e+00 3.87900567e+00 5.80442715e+00 8.66727412e-01 -6.38210237e-01 1.94892299e+00 1.25805187e+00 -3.07592506e+01 -5.17581825e+01 2.94841423e+01 2.90379677e+01 2.85833912e+01 1.97736618e+02 4.91035217e+02 -3.68978638e+02 -1.38564178e+02 3.50909348e+01 2.35664215e+01 2.66817570e+01 2.51193333e+01 2.52063541e+01 2.70088902e+01 2.64631462e+01 2.59357567e+01 2.54563732e+01 1.05403145e+02 1.41101682e+00 -1.00184143e+02 2.40475693e+01 1.11664597e+02 5.97490807e+01 -5.48770761e+00 -3.76004863e+00 -3.62398410e+00 -3.85919905e+00 -3.90894103e+00 -4.15230036e+00 -4.34218407e+00 -4.69874668e+00 -4.80625534e+00 -5.13815165e+00 -5.41799831e+00 -5.73676538e+00 -5.64779043e+00 -5.83333492e+00 -6.23756886e+00 -6.40090132e+00 -6.52658796e+00 -6.63727379e+00 -6.56428432e+00 -7.02242470e+00 -7.70674562e+00 -7.71298265e+00 -8.10591984e+00 -8.46688747e+00 -8.57650185e+00 -8.79639053e+00 -8.63134384e+00 -8.97464180e+00 -9.13457298e+00 -9.44649315e+00 -9.54403877e+00 -1.02580891e+01 -1.06310129e+01 -1.04389696e+01 -1.04381800e+01 -1.05470800e+01 -1.07669592e+01 -1.10999651e+01 -1.14420452e+01 -1.17744246e+01 -1.18727865e+01 -1.19030104e+01 -1.21728048e+01 -1.24126492e+01 -1.25561371e+01 -1.29355745e+01 -1.36998348e+01 -1.36392813e+01 -1.35800829e+01 -1.38132639e+01 -1.46905012e+01 -1.49301901e+01 -1.48370037e+01 -1.49613819e+01 -1.50331268e+01 -1.50752316e+01 -1.49556999e+01 -1.49372559e+01 -1.53235703e+01 -1.54462261e+01 -1.61300678e+01 -1.67152004e+01 -1.70337811e+01 -1.69563293e+01 -1.70800533e+01 -1.70353184e+01 -1.72186813e+01 -1.73821831e+01 -1.71346264e+01 -1.82065716e+01 -1.83405037e+01 -1.84746113e+01 -1.79519596e+01 -1.89395084e+01 -1.85141754e+01 -1.91069107e+01 -1.91403637e+01 -1.96605473e+01 -1.98578587e+01 -2.01791401e+01 -2.05481567e+01 -2.07982502e+01 -2.09167175e+01 -2.09257240e+01 -2.03189278e+01 -1.97115688e+01 -1.98942337e+01 -2.14420471e+01 -2.17257690e+01 -2.15958366e+01 -2.07828808e+01 -2.19332027e+01 -2.31753139e+01 -2.26510849e+01 -2.25704098e+01 -2.28290539e+01 -2.30580921e+01 -2.34061584e+01 -2.36806602e+01 -2.38674278e+01 -2.41500206e+01 -2.39197750e+01 -2.38665257e+01 -2.38979607e+01 -2.43644657e+01 -2.53165817e+01 -2.53978195e+01 -2.52950993e+01 -2.50903282e+01 -2.58056736e+01 -2.57460346e+01 -2.46088581e+01 -2.42776203e+01 -2.66516132e+01 -2.66464977e+01 -2.49917908e+01 -2.47411823e+01 -2.55223217e+01 -2.64307213e+01 -2.77437782e+01 -2.78014698e+01 -2.72908592e+01 -2.82058315e+01 -2.79949551e+01 -2.80816021e+01 -2.83092670e+01 -2.84316063e+01 -2.81973057e+01 -2.79176445e+01 -2.80445004e+01 -2.78075447e+01 -2.83257923e+01 -2.91332302e+01 -2.90601387e+01 -2.93365402e+01 -2.91716251e+01 -2.96823921e+01 -2.96961651e+01 -2.95462170e+01 -3.00536175e+01 -2.99264889e+01 -3.01926479e+01 -2.95217266e+01 -2.95573158e+01 -2.97121906e+01 -3.01248741e+01 -3.06593990e+01 -3.10596790e+01 -3.05302181e+01 -3.05781002e+01 -3.08853550e+01 -3.10986500e+01 -3.15201912e+01 -3.14576092e+01 -3.20998726e+01 -3.20581894e+01 -3.21848030e+01 -3.27779808e+01 -3.30979500e+01 -3.26125793e+01 -3.29357948e+01 -3.30128174e+01 -3.27585182e+01 -3.26463509e+01 -3.30440636e+01 -3.36052551e+01 -3.29444885e+01 -3.33397598e+01 -3.34618073e+01 -3.36289864e+01 -3.37687645e+01 -3.31764908e+01 -3.30800400e+01 -3.39153709e+01 -3.47208862e+01 -3.49219856e+01 -3.46291733e+01 -3.44992561e+01 -3.41098480e+01 -3.43636589e+01 -3.52978477e+01 -3.53177299e+01 -3.47063065e+01 -3.41079521e+01 -3.38562698e+01 -3.52738647e+01 -3.60647240e+01 -3.49547806e+01 -3.44683113e+01 -3.50759659e+01 -3.50362358e+01 -3.55589943e+01 -3.57257957e+01 -3.46292191e+01 -3.47224579e+01 -3.56666756e+01 -3.56902084e+01 -3.57093773e+01 -3.43078537e+01 -3.42756195e+01 -3.57135735e+01 -3.70890312e+01 -3.73175392e+01 -3.57026749e+01 -3.60034981e+01 -3.66581459e+01 -3.63615150e+01 -3.62245636e+01 -3.60327454e+01 -3.60676422e+01 -3.62084160e+01 -3.61800156e+01 -3.64805794e+01 -3.67630692e+01 -3.65364838e+01 -3.62305183e+01 -3.67032471e+01 -3.67064972e+01 -3.66343079e+01 -3.75374908e+01 -3.74489326e+01 -3.72969360e+01 -3.73925629e+01 -3.71811981e+01 -3.71875076e+01 -3.64715538e+01 -3.63972664e+01 -3.75685158e+01 -3.76850014e+01 -3.69593124e+01 -3.72401085e+01 -3.75957870e+01 -3.70472221e+01 -3.68235855e+01 -3.72907486e+01 -3.71786346e+01 -3.82520065e+01 -3.73610992e+01 -3.65796776e+01 -3.74933167e+01 -3.71214676e+01 -3.73816948e+01 -3.73083916e+01 -3.74458313e+01 -3.77532082e+01 -3.84409142e+01 -3.78562546e+01 -3.71536293e+01 -3.73627205e+01 -3.77897072e+01 -3.75312119e+01 -3.71520920e+01 -3.66822281e+01 -3.69726448e+01 -3.70191765e+01 -3.74081268e+01 -3.70914154e+01 -3.73674736e+01 -3.72262459e+01 -3.72005577e+01 -3.69658737e+01 -3.70457344e+01 -3.67316933e+01 -3.65522308e+01 -3.65972061e+01 -3.70934029e+01 -3.71667709e+01 -3.68413429e+01 -3.60243034e+01 -3.61062202e+01 -3.69072838e+01 -3.69886131e+01 -3.58662567e+01 -3.60517960e+01 -3.65448914e+01 -3.68080254e+01 -3.68563385e+01 -3.68345337e+01 -3.66220741e+01 -3.72860909e+01 -3.73067055e+01 -3.53270111e+01 -3.44377098e+01 -3.49982719e+01 -3.56688957e+01 -3.63898773e+01 -3.54407272e+01 -3.51019096e+01 -3.56393433e+01 -3.58520317e+01 -3.57795181e+01 -3.49337082e+01 -3.49982033e+01 -3.53336906e+01 -3.46678467e+01 -3.49686508e+01 -3.53365097e+01 -3.47389374e+01 -3.45961838e+01 -3.47525978e+01 -3.50136719e+01 -3.50831566e+01 -3.47866287e+01 -3.54130211e+01 -3.50501404e+01 -3.42494469e+01 -3.40461884e+01 -3.42878838e+01 -3.43621902e+01 -3.47624245e+01 -3.48501282e+01 -3.35690765e+01 -3.33536224e+01 -3.32714691e+01 -3.31064148e+01 -3.26715698e+01 -3.36383362e+01 -3.36231232e+01 -3.37301559e+01 -3.35151634e+01 -3.28563004e+01 -3.27697182e+01 -3.25913773e+01 -3.27749443e+01 -3.26549721e+01 -3.26218910e+01 -3.20132713e+01 -3.21835709e+01 -3.12681732e+01 -3.19018688e+01 -3.15524960e+01 -3.10880699e+01 -3.09896908e+01 -3.24427643e+01 -3.24470329e+01 -3.18503742e+01 -3.15869675e+01 -3.18072701e+01 -3.14616737e+01 -3.12687817e+01 -3.03070278e+01 -2.94747391e+01 -2.94325314e+01 -3.04519272e+01 -3.01264801e+01 -2.97944489e+01 -2.95101357e+01 -2.94279099e+01 -2.92683964e+01 -2.93729134e+01 -2.88693810e+01 -2.86262550e+01 -2.86823578e+01 -2.89998760e+01 -2.88235054e+01 -2.89683838e+01 -2.88387432e+01 -2.83166904e+01 -2.74080200e+01 -2.76182404e+01 -2.76935139e+01 -2.80911369e+01 -2.77778492e+01 -2.75417576e+01 -2.72556858e+01 -2.74018879e+01 -2.73170872e+01 -2.68883381e+01 -2.65443573e+01 -2.61227722e+01 -2.58104839e+01 -2.56966610e+01 -2.58163681e+01 -2.58483543e+01 -2.54746780e+01 -2.55036812e+01 -2.56068382e+01 -2.56071968e+01 -2.57820568e+01 -2.51461391e+01 -2.51892757e+01 -2.50364552e+01 -2.46552849e+01 -2.41941910e+01 -2.35637245e+01 -2.37011890e+01 -2.34963608e+01 -2.30694218e+01 -2.31052055e+01 -2.31306896e+01 -2.31042862e+01 -2.30541458e+01 -2.30985222e+01 -2.26934490e+01 -2.19895954e+01 -2.21152306e+01 -2.21354084e+01 -2.15227947e+01 -2.10425434e+01 -2.13091278e+01 -2.13835983e+01 -2.11958675e+01 -2.09314194e+01 -2.07408848e+01 -2.04021111e+01 -1.99712524e+01 -1.98457165e+01 -1.97852974e+01 -1.96096935e+01 -1.93214035e+01 -1.90812531e+01 -1.88583908e+01 -1.88728180e+01 -1.88119011e+01 -1.85512447e+01 -1.80845089e+01 -1.73478680e+01 -1.67325554e+01 -1.69715443e+01 -1.63266354e+01 -1.61412468e+01 -1.68369026e+01 -1.67910023e+01 -1.64889584e+01 -1.58381748e+01 -7.33119431e+01 -1.16305222e+02 -5.14392624e+01 -5.07022514e+01 -5.11633492e+01 -5.12298431e+01 -4.79827614e+01 -5.47599869e+01 -5.78994522e+01 -5.09225998e+01 -5.26009140e+01 3.99532013e+01 -2.27070408e+01 -1.63166199e+01 1.50205936e+01 -1.08729963e+01 -1.02715845e+01 -1.66355953e+01 -1.55683079e+01 -1.25009604e+01 -1.20698290e+01 -1.16988525e+01 -1.17312450e+01 -1.04941597e+01 -8.91863251e+00 -1.09570894e+01 -1.18753262e+01 -1.06956129e+01 -1.03791533e+01 -1.00408335e+01 -9.79640865e+00 -9.56699467e+00 -9.35411358e+00 -9.13822937e+00 -8.91412830e+00 -8.69663143e+00 -8.47966099e+00 -8.26656532e+00 -8.05414104e+00 -7.83483315e+00 -7.61973429e+00 -7.38775444e+00 -7.15407085e+00 -6.92792749e+00 -6.71100616e+00 -6.48573303e+00 -6.24271107e+00 -6.00744581e+00 -5.79947472e+00 -5.58074999e+00 -5.35399008e+00 -5.12969685e+00 -4.88194036e+00 -4.63501263e+00 -4.46163177e+00 -4.25528526e+00 -4.00688601e+00 -3.67061973e+00 -3.44622517e+00 -3.20001960e+00 -3.03008723e+00 -2.85479522e+00 -2.60322237e+00 -2.38982129e+00 -2.18613172e+00 -1.90712082e+00 -1.73583484e+00 -1.46887028e+00 -1.17812252e+00 -9.61863756e-01 -7.92765081e-01 -7.44718611e-01 -4.80583817e-01 -4.68748733e-02 9.49777961e-02 3.06940377e-01 6.39007986e-01 8.80614102e-01 1.04738104e+00 1.31866264e+00 1.56235969e+00 1.47695506e+00 1.73850954e+00 2.39047599e+00 2.66796398e+00 2.46850944e+00 2.92086124e+00 3.34760165e+00 3.32116151e+00 3.33929682e+00 3.86367774e+00 4.09031725e+00 4.05464315e+00 4.32674980e+00 4.84630299e+00 4.89876747e+00 4.83224678e+00 4.33951712e+00 6.12962532e+00 6.96388960e+00 5.95717382e+00 6.11054707e+00 6.32909536e+00 6.56846333e+00 6.79321289e+00 6.16649389e+00 5.74010372e+00 6.93472576e+00 9.56978989e+00 9.88965416e+00 8.59957981e+00 8.69067097e+00 8.57379913e+00 8.33399868e+00 8.74833202e+00 8.97581005e+00 9.20775986e+00 9.43876934e+00 9.99255371e+00 1.04856892e+01 1.05930853e+01 1.03216219e+01 1.02638512e+01 1.04272480e+01 1.08321056e+01 1.14038563e+01 1.14670115e+01 1.13676624e+01 1.17649441e+01 1.24237785e+01 1.26406012e+01 1.29445629e+01 1.28031549e+01 1.27413797e+01 1.31927738e+01 1.36993866e+01 1.38601542e+01 1.42927942e+01 1.47538586e+01 1.42100296e+01 1.20893488e+01 1.32116499e+01 1.59913330e+01 1.79634323e+01 1.72639465e+01 1.54169312e+01 1.55844698e+01 1.62587662e+01 1.64316750e+01 1.67527714e+01 1.67802010e+01 1.70066528e+01 1.71869717e+01 1.72990780e+01 1.73353958e+01 1.71821957e+01 1.79961777e+01 1.78794193e+01 1.81949749e+01 1.78346386e+01 1.88317986e+01 1.86362991e+01 1.91868038e+01 1.91355457e+01 1.92247849e+01 1.95081882e+01 1.98453941e+01 2.02071762e+01 2.07226963e+01 2.05641003e+01 2.01983051e+01 1.93730774e+01 1.75075073e+01 6.16982603e+00 3.66693497e+00 -1.70620937e+01 4.09923363e+01 7.40647278e+01 2.88652210e+01 3.04377766e+01 3.69416046e+01 3.69730949e+01 3.66405563e+01 3.66302567e+01 3.66583786e+01 3.57500420e+01 3.80546799e+01 3.78503418e+01 1.83354187e+01 2.20786041e+02 3.30350220e+02 1.88808460e+01 2.75250721e+01 2.14805222e+01 2.32841282e+01 -2.75256165e+02 -1.50391190e+02 2.19699135e+01 1.48278360e+01 3.29131355e+01 1.87875076e+02 6.05170532e+02 2.32085986e+03 364493440. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -762906176. -762906176. 225374416. 377576864. -2.20659707e+04 8.19141438e+05 -483714208. 2.31122925e+03 9.87652405e+02 9.31192932e+01 5.37922363e+01 4.71575050e+01 4.28343239e+01 3.98416016e+02 2.47761032e+02 3.14150906e+01 3.39445190e+01 3.08910103e+01 3.10627460e+01 3.00115871e+01 -1.73091248e+02 -3.24660370e+02 4.10270386e+01 3.99651985e+01 3.89966164e+01 4.40816231e+01 4.95153885e+01 5.29344177e+01 5.18521805e+01 4.75158730e+01 4.12240105e+01 3.88956146e+01 3.81639977e+01 3.66278839e+01 4.57616043e+01 5.67638474e+01 5.75694656e+01 5.38464546e+01 4.20960510e+02 5.07860107e+01 -3.32544708e+02 4.07503548e+01 4.42245293e+01 5.14895325e+01 5.72359695e+01 5.47665634e+01 5.12191963e+01 4.76315269e+01 4.51946068e+01 4.48714066e+01 4.13855667e+01 5.09098511e+01 5.54687462e+01 5.18171082e+01 5.91492653e+01 3.74640846e+01 4.03318825e+01 -8.29536499e+02 -2.19604419e+03 -68946808. -351742880. -10887809. -5356078. -2901485. 386734112. 3.12142822e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.76951728e+11 -2.76951728e+11 0. 0. 0. 0. -3.92612531e+09 2.09184462e+06 2.09184462e+06 1.81105803e+11 0. -4.58208922e+09 -6.36350050e+06 -20388830. 39456816. -140730688. -1.49834813e+10 -1.49834813e+10 0. -979525248. -979525248. 217045888. 3.52582170e+09 3.52582170e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -822512640. -822512640. -39616720. 1582263936. 1582263936. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -586053248. -586053248. -586053248. 0. 0. -686466240. -1.52111304e+03 -1.76098621e+03 2.21068954e+01 5.18587158e+02 6.00754700e+01 4.46213379e+01 3.90692673e+01 3.15156517e+01 -1.59705063e+02 -2.98111694e+02 -7.38494995e+02 -1.98391785e+03 -3784028. 6.48944250e+05 4.38432350e+06 -19210926. 278211392. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 252721312. 8245947. 1.56668988e+06 -8.59624268e+02 -2.56836121e+02 3.22586517e+01 3.34223862e+01 3.38485870e+01 3.30098228e+01 3.22893982e+01 3.20839424e+01 3.26929817e+01 2.22248993e+02 3.57696259e+02 7.00219574e+01 5.90209579e+01 6.00909042e+01 6.32301559e+01 6.50354538e+01 -2.47491608e+02 -1.29865326e+02 3.18016853e+01 2.55278816e+01 3.28414574e+01 3.91752510e+01 3.49045448e+01 3.28999977e+01 3.15777626e+01 3.11963100e+01 3.09691525e+01 3.15572567e+01 3.16708336e+01 3.09786339e+01 3.08986397e+01 3.09551983e+01 3.06860294e+01 3.08494492e+01 3.03240318e+01 2.94727421e+01 3.05306435e+01 3.08352757e+01 2.96036301e+01 2.99507408e+01 3.06039238e+01 3.09915638e+01 3.06632843e+01 3.00474014e+01 3.00221958e+01 2.98895454e+01 3.04014568e+01 2.98481197e+01 2.95747681e+01 2.95529709e+01 2.90946827e+01 2.90187969e+01 2.83369942e+01 2.86719208e+01 2.93588200e+01 2.93127975e+01 2.92417450e+01 2.94210644e+01 2.87681446e+01 2.79033146e+01 2.80045815e+01 2.81711292e+01 2.84330273e+01 2.80105686e+01 2.76056004e+01 2.73727856e+01 2.75128155e+01 2.78765793e+01 2.77934341e+01 2.79080029e+01 2.77703705e+01 2.74288845e+01 2.72834415e+01 2.70109921e+01 2.68721237e+01 2.68299179e+01 2.67440491e+01 2.65966988e+01 2.66402988e+01 2.69063396e+01 2.62272930e+01 2.62143879e+01 2.57734966e+01 2.56994915e+01 2.56356659e+01 2.56484852e+01 2.54527302e+01 2.55602970e+01 2.55086403e+01 2.51408539e+01 2.47315674e+01 2.49904690e+01 2.50902405e+01 2.44113693e+01 2.42955132e+01 2.43170643e+01 2.44280224e+01 2.40714531e+01 2.37674580e+01 2.37290173e+01 2.38922825e+01 2.36260128e+01 2.32452240e+01 2.11928177e+01 2.11056614e+01 2.30696983e+01 2.39833107e+01 2.32548714e+01 2.22364082e+01 2.19267902e+01 2.19604149e+01 2.20419521e+01 2.18843117e+01 2.15957012e+01 2.12643738e+01 2.11455231e+01 2.10413227e+01 2.08246899e+01 2.06455708e+01 2.04821568e+01 2.03449764e+01 2.01928730e+01 2.00382156e+01 1.98419685e+01 1.97080994e+01 1.94577160e+01 1.93095512e+01 1.92164803e+01 1.91571636e+01 1.90375957e+01 1.88163185e+01 1.86328793e+01 1.84103355e+01 1.82588844e+01 1.81114788e+01 1.79246960e+01 1.77611752e+01 1.72693882e+01 1.74029846e+01 1.75304661e+01 1.70664577e+01 1.68716412e+01 1.67354679e+01 1.65540657e+01 1.63556347e+01 1.61647663e+01 1.60157146e+01 1.58574591e+01 1.56529608e+01 1.54371538e+01 1.52672482e+01 1.50895462e+01 1.49337854e+01 1.47402525e+01 1.45488958e+01 1.43865261e+01 1.42039976e+01 1.40162411e+01 1.38341131e+01 1.36360550e+01 1.34394608e+01 1.32490053e+01 1.30498285e+01 1.28503637e+01 1.26654587e+01 1.24831467e+01 1.22985001e+01 1.21104317e+01 1.19267769e+01 1.17361479e+01 1.15529661e+01 1.13571882e+01 1.11581497e+01 1.09470263e+01 1.07316685e+01 1.05290699e+01 1.03475199e+01 1.02435637e+01 1.01199636e+01 9.12688065e+00 8.64494514e+00 9.03835964e+00 8.74956894e+00 9.36923409e+00 -1.19619913e+01 -1.98027306e+01 6.58023834e+01 3.83514252e+01 7.92616320e+00 6.61171198e+00 7.77843237e+00 8.93130207e+00 9.07471180e+00 5.47176504e+00 4.61609650e+00 5.69157028e+00 5.57794189e+00 4.87573290e+00 6.20114088e+00 6.21702433e+00 4.28687572e+00 4.77276516e+00 4.50122833e+00 4.79594755e+00 5.85011940e+01 1.03260323e+02 2.59357567e+01 2.54563732e+01 -9.04312592e+01 -5.47324333e+01 4.02073812e+00 1.41979444e+00 2.07924151e+00 2.36211777e+00 2.39479756e+00 2.50831413e+00 2.25205636e+00 2.09668922e+00 2.01173854e+00 2.01788449e+00 1.68749809e+00 1.41724908e+00 1.23429644e+00 1.09364676e+00 8.44812214e-01 6.06130898e-01 6.36587858e-01 4.95904773e-01 2.94711143e-01 1.56644955e-02 1.87973864e-02 -3.91188830e-01 -5.08532047e-01 -1.16337347e+00 -1.74276173e+00 -1.38503408e+00 -1.65801191e+00 -1.96158886e+00 -1.93686306e+00 -2.20451784e+00 -2.17831159e+00 -2.43538189e+00 -2.79071355e+00 -3.21030641e+00 -3.18071318e+00 -3.85782886e+00 -4.08054590e+00 -3.98108315e+00 -4.09595251e+00 -4.46663475e+00 -4.48869944e+00 -4.84662199e+00 -5.10387516e+00 -5.45295763e+00 -5.53442335e+00 -5.40742970e+00 -5.61522293e+00 -5.80284452e+00 -5.57589817e+00 -5.56279325e+00 -6.00671911e+00 -6.43236351e+00 -6.40513372e+00 -6.91578197e+00 -8.08443356e+00 -8.56010532e+00 -8.38149643e+00 -7.98125982e+00 -8.43151474e+00 -9.15204525e+00 -9.10837460e+00 -9.18262386e+00 -9.27501869e+00 -9.73908997e+00 -9.33541107e+00 -9.91251469e+00 -9.90029240e+00 -9.99967384e+00 -1.05216064e+01 -1.04908104e+01 -1.08123121e+01 -1.04350567e+01 -1.02258968e+01 -1.08674536e+01 -1.14881268e+01 -1.18457365e+01 -1.20319881e+01 -1.22256737e+01 -1.22271624e+01 -1.22002726e+01 -1.23913908e+01 -1.29262486e+01 -1.34122591e+01 -1.30304050e+01 -1.29702110e+01 -1.33534794e+01 -1.38068542e+01 -1.40694895e+01 -1.40031767e+01 -1.34868202e+01 -1.35279617e+01 -1.43653345e+01 -1.51617298e+01 -1.49906054e+01 -1.39428072e+01 -1.49411955e+01 -1.62794380e+01 -1.63736420e+01 -1.56203003e+01 -1.59465227e+01 -1.60895119e+01 -1.66251945e+01 -1.74471798e+01 -1.73058128e+01 -1.70934696e+01 -1.67945595e+01 -1.69486313e+01 -1.71671619e+01 -1.79503460e+01 -1.78947754e+01 -1.85421333e+01 -1.77142792e+01 -1.76291943e+01 -1.82608643e+01 -1.90263214e+01 -1.90874252e+01 -1.79963360e+01 -2.02075253e+01 -2.02564259e+01 -1.81801834e+01 -1.81797943e+01 -1.89650517e+01 -1.99729309e+01 -2.11419449e+01 -2.11666203e+01 -2.05833931e+01 -2.02354355e+01 -2.06166019e+01 -1.99989586e+01 -2.01465683e+01 -2.08352699e+01 -2.12315807e+01 -2.16733379e+01 -2.19683685e+01 -2.15948906e+01 -2.20995178e+01 -2.25498276e+01 -2.26605034e+01 -2.21817818e+01 -2.18755589e+01 -2.28217258e+01 -2.30299568e+01 -2.33100758e+01 -2.33260174e+01 -2.34241962e+01 -2.33879871e+01 -2.36293163e+01 -2.40093727e+01 -2.42495441e+01 -2.36404457e+01 -2.39247093e+01 -2.35679283e+01 -2.36040478e+01 -2.32831612e+01 -2.36523399e+01 -2.49330692e+01 -2.49758987e+01 -2.52994938e+01 -2.65665054e+01 -2.66088161e+01 -2.56871262e+01 -2.58733692e+01 -2.60862026e+01 -2.58067265e+01 -2.55949936e+01 -2.55905094e+01 -2.61099701e+01 -2.56531467e+01 -2.61620502e+01 -2.68371811e+01 -2.67115192e+01 -2.72293167e+01 -2.72516212e+01 -2.60620136e+01 -2.66444683e+01 -2.73483257e+01 -2.71410236e+01 -2.84470291e+01 -2.82269650e+01 -2.79183731e+01 -2.81847420e+01 -2.86695576e+01 -2.82379704e+01 -2.81579685e+01 -2.90846481e+01 -2.81409245e+01 -2.81231232e+01 -2.78901863e+01 -2.78261471e+01 -2.95851669e+01 -3.04109211e+01 -2.89245377e+01 -2.80215054e+01 -2.92257290e+01 -2.98137417e+01 -2.87644081e+01 -2.89716930e+01 -2.91131878e+01 -2.94271240e+01 -2.96925507e+01 -2.97011185e+01 -3.01832676e+01 -2.90248508e+01 -2.86963062e+01 -2.98095245e+01 -3.13629951e+01 -3.17411308e+01 -3.01270123e+01 -3.05069199e+01 -3.10807819e+01 -3.08305817e+01 -3.08647671e+01 -3.11862564e+01 -3.12035809e+01 -3.10410442e+01 -3.09644775e+01 -3.11705856e+01 -3.13625717e+01 -3.11229973e+01 -3.05412712e+01 -3.09374447e+01 -3.13516483e+01 -3.10600853e+01 -3.21515198e+01 -3.23941231e+01 -3.23036423e+01 -3.30148659e+01 -3.28085365e+01 -3.20104942e+01 -3.09119740e+01 -3.10193768e+01 -3.27087402e+01 -3.26442604e+01 -3.18472443e+01 -3.21679611e+01 -3.27401276e+01 -3.23881302e+01 -3.19959717e+01 -3.22148933e+01 -3.22836380e+01 -3.34355621e+01 -3.27095184e+01 -3.20357704e+01 -3.38128166e+01 -3.35026894e+01 -3.28651161e+01 -3.29882584e+01 -3.25994110e+01 -3.29088478e+01 -3.35684052e+01 -3.35249329e+01 -3.26358147e+01 -3.27863197e+01 -3.30418663e+01 -3.33096237e+01 -3.30040436e+01 -3.23931618e+01 -3.24165115e+01 -3.30434265e+01 -3.33826256e+01 -3.34945717e+01 -3.33314285e+01 -3.31844597e+01 -3.28148956e+01 -3.26247864e+01 -3.30602951e+01 -3.28276634e+01 -3.28288498e+01 -3.28658257e+01 -3.30207939e+01 -3.22445374e+01 -3.24432297e+01 -3.30024605e+01 -3.26921768e+01 -3.27442436e+01 -3.34520073e+01 -3.21676445e+01 -3.19783936e+01 -3.25966301e+01 -3.32941818e+01 -3.37564163e+01 -3.36915779e+01 -3.31857491e+01 -3.31705475e+01 -3.30459633e+01 -3.26764450e+01 -3.19428787e+01 -3.21836128e+01 -3.28542328e+01 -3.30899010e+01 -3.25461655e+01 -3.27101631e+01 -3.29906006e+01 -3.33312149e+01 -3.30573425e+01 -3.29034348e+01 -3.30235710e+01 -3.30930939e+01 -3.27493858e+01 -3.30613289e+01 -3.35023346e+01 -3.28616829e+01 -3.24817543e+01 -3.30287628e+01 -3.24798164e+01 -3.15518475e+01 -3.14379787e+01 -3.21925774e+01 -3.19966755e+01 -3.18335228e+01 -3.23755836e+01 -3.27994118e+01 -3.26401863e+01 -3.22777367e+01 -3.31712990e+01 -3.31967926e+01 -3.27872047e+01 -3.26236420e+01 -3.22926064e+01 -3.23923302e+01 -3.15761280e+01 -3.17101002e+01 -3.18186970e+01 -3.22330475e+01 -3.18634777e+01 -3.16725693e+01 -3.15759945e+01 -3.15842896e+01 -3.21605911e+01 -3.14706764e+01 -3.07204075e+01 -3.09187469e+01 -3.10167103e+01 -3.14053020e+01 -3.10232601e+01 -3.02147007e+01 -3.06148777e+01 -3.17928066e+01 -3.14271889e+01 -3.07978783e+01 -3.07387486e+01 -3.06816502e+01 -3.09814548e+01 -3.10412807e+01 -3.03469849e+01 -2.93915005e+01 -2.92010746e+01 -3.01454773e+01 -3.03593674e+01 -2.95397434e+01 -2.97327614e+01 -2.96909428e+01 -2.94251366e+01 -2.99949436e+01 -2.92496300e+01 -2.91271667e+01 -2.89021091e+01 -2.90556126e+01 -2.96242847e+01 -2.90421696e+01 -2.87459183e+01 -2.80613480e+01 -2.79351234e+01 -2.80448532e+01 -2.86529732e+01 -2.85394802e+01 -2.86472950e+01 -2.79536057e+01 -2.76736908e+01 -2.80842361e+01 -2.82684269e+01 -2.84618759e+01 -2.80717430e+01 -2.78525372e+01 -2.74157562e+01 -2.68285656e+01 -2.69371948e+01 -2.71648712e+01 -2.70775166e+01 -2.70240288e+01 -2.66451950e+01 -2.65960331e+01 -2.61420059e+01 -2.61945477e+01 -2.56267586e+01 -2.56954632e+01 -2.57390060e+01 -2.58393555e+01 -2.56024590e+01 -2.55779705e+01 -2.53416843e+01 -2.50953465e+01 -2.50328636e+01 -2.50240726e+01 -2.46348362e+01 -2.44731503e+01 -2.45966301e+01 -2.43058357e+01 -2.39057808e+01 -2.41218395e+01 -2.42191772e+01 -2.34297581e+01 -2.33946991e+01 -2.38134842e+01 -2.37155590e+01 -2.32399788e+01 -2.30131035e+01 -2.27181740e+01 -2.26333447e+01 -2.23571835e+01 -2.23607731e+01 -2.22425785e+01 -2.20985050e+01 -2.20396538e+01 -2.18084660e+01 -2.14653301e+01 -2.12632580e+01 -2.11445217e+01 -2.11297894e+01 -2.10236931e+01 -2.06428909e+01 -2.05396900e+01 -2.05484009e+01 -2.03065529e+01 -1.97077446e+01 -1.87283955e+01 -2.10880470e+01 -2.19272747e+01 -1.95870609e+01 -1.95140095e+01 -1.94694881e+01 -1.91915359e+01 -1.88447819e+01 -1.86568050e+01 -1.84179955e+01 -1.75516205e+01 -1.75195599e+01 -1.91386280e+01 1.72512512e+01 -2.01818714e+01 -6.05924606e+01 -1.77770939e+01 -1.76663132e+01 -1.72219524e+01 -1.31182518e+01 -1.26969309e+01 -1.84151020e+01 -1.83516483e+01 -1.62032757e+01 -1.60102482e+01 -1.56847887e+01 -1.55903053e+01 -1.40954437e+01 -1.21768198e+01 -1.41330576e+01 -1.51476088e+01 -1.46149025e+01 -1.44769754e+01 -1.42731485e+01 -1.40799341e+01 -1.38660107e+01 -1.36623917e+01 -1.34702873e+01 -1.32749052e+01 -1.30837803e+01 -1.28963022e+01 -1.27136755e+01 -1.25283833e+01 -1.23426027e+01 -1.21476793e+01 -1.19514723e+01 -1.17432919e+01 -1.15558062e+01 -1.13702526e+01 -1.11789455e+01 -1.09796877e+01 -1.07790651e+01 -1.06026611e+01 -1.04170637e+01 -1.02258101e+01 -1.00164576e+01 -9.78086662e+00 -9.59416866e+00 -9.41670227e+00 -9.25555038e+00 -9.03022480e+00 -8.75549507e+00 -8.54953384e+00 -8.37423801e+00 -8.24193573e+00 -8.04144573e+00 -7.81329489e+00 -7.60536242e+00 -7.42173958e+00 -7.24203968e+00 -7.02238369e+00 -6.85104418e+00 -6.62754345e+00 -6.41387653e+00 -6.17704105e+00 -6.03031063e+00 -5.85621786e+00 -5.54681396e+00 -5.41631699e+00 -5.22061300e+00 -5.05840445e+00 -4.79570293e+00 -4.65181065e+00 -4.54273415e+00 -4.49620962e+00 -4.50505495e+00 -3.92888474e+00 -3.16511416e+00 -3.32007360e+00 -3.39839339e+00 -3.15062428e+00 -2.78984070e+00 -2.64669728e+00 -2.51515675e+00 -2.22119188e+00 -2.01036119e+00 -1.97377491e+00 -1.73668671e+00 -1.45104742e+00 -1.32313871e+00 -1.54816651e+00 -1.60935640e+00 -1.43817468e-02 4.49663222e-01 -3.03374559e-01 -3.15758109e-01 -1.90926239e-01 2.95194574e-02 5.44656098e-01 1.89912647e-01 -1.92286193e-01 7.72661686e-01 3.24068904e+00 3.34504747e+00 1.99250972e+00 1.80854058e+00 1.90917933e+00 2.08552384e+00 2.32268119e+00 2.59798384e+00 2.81309104e+00 3.02187991e+00 3.49366784e+00 3.85108018e+00 4.15436077e+00 4.09638262e+00 4.25240755e+00 4.08039665e+00 4.54674768e+00 5.11819172e+00 5.30857992e+00 5.16565084e+00 5.27572107e+00 5.69694042e+00 5.90338945e+00 5.97937155e+00 5.56473112e+00 5.31728458e+00 5.89861536e+00 6.58418894e+00 7.09787273e+00 7.64652348e+00 8.15266037e+00 8.35785866e+00 5.06344557e+00 5.71078491e+00 1.01606350e+01 1.20327187e+01 1.13286486e+01 9.32234573e+00 9.90090466e+00 9.35281849e+00 9.51401806e+00 9.38788605e+00 9.90355301e+00 1.03947077e+01 1.04465790e+01 1.04998360e+01 1.02115946e+01 1.06282053e+01 1.09372587e+01 1.08540354e+01 1.12263041e+01 1.15551472e+01 1.22272482e+01 1.21187162e+01 1.23330784e+01 1.26274128e+01 1.28277607e+01 1.30184240e+01 1.29941187e+01 1.31261253e+01 1.32384214e+01 1.35675344e+01 1.37368240e+01 1.33480320e+01 1.14628782e+01 1.07298577e+00 -4.59268615e-02 -1.23640814e+01 3.16165257e+01 5.95526695e+01 1.86055481e+02 3.04958801e+02 -4.65141392e+00 -6.15395546e+00 -7.64877081e+00 -7.18237162e+00 -7.61257505e+00 -6.95539761e+00 -7.54280710e+00 -7.19734812e+00 -2.92866974e+02 -1.56414169e+02 1.73846474e+01 1.76375790e+01 1.90528908e+01 1.84538918e+01 1.87599411e+01 1.94965801e+01 1.87848225e+01 1.83428516e+01 1.41859198e+01 2.02886597e+02 -1.99276745e+00 -2.58434391e+01 6.49205078e+02 1.02854163e+03 153892848. 163758944. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1358823040. -766016448. 3.06947250e+05 4.07933525e+06 -2.79850975e+06 436087520. 1.25607080e+03 4.51523102e+02 4.43386803e+01 3.46090469e+01 2.96381130e+01 2.61402969e+01 2.20870552e+01 2.75090351e+01 2.82288170e+01 -3.62091370e+02 -9.83979065e+02 -7390177. -1.26848750e+06 -1.88613719e+05 13870659. 8910673. 61778432. -14403211. -56394816. -52629684. -17992098. -3.39228719e+05 6592334. 9435951. 1.63075638e+06 2.15717383e+03 8.49316483e+01 -2.02057227e+03 -47923808. -2.02287438e+06 606209. 4386974. 2.92372025e+06 11826609. -14361365. -32871414. -21307170. -6.26907850e+06 -1.85647797e+05 1.60997844e+05 -5.78615062e+05 22243590. -3.09427656e+05 -2.17640969e+05 199234544. -2029356032. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.76951728e+11 -2.76951728e+11 0. 0. -1903325824. -1903325824. -1903325824. 0. 0. 0. 0. -4.58208922e+09 -6.36350050e+06 -20388830. 39456816. -140730688. -1.49834813e+10 -1.49834813e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -822512640. -822512640. -822512640. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -586053248. -586053248. -586053248. 0. 0. -686466240. -2137302656. -2137302656. 115914720. 220842112. 1.03378250e+06 -1.98120422e+03 -7.86152100e+02 4.67740021e+01 -6.94703552e+02 -1.82578906e+03 -22125102. 1430365056. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 471989536. -21078134. -1.62828394e+03 -5.23388855e+02 1.49806107e+02 -2.24473465e+02 -1.14260414e+02 5.02241707e+01 5.08970680e+01 5.09960785e+01 5.15624008e+01 5.14860649e+01 5.03168831e+01 4.99478989e+01 5.01270790e+01 5.12944756e+01 5.10623322e+01 4.89584351e+01 4.91778603e+01 4.95820274e+01 4.96367264e+01 4.99430313e+01 4.92748146e+01 4.86414108e+01 5.01938934e+01 5.01779022e+01 4.97912712e+01 5.01045837e+01 4.96017265e+01 4.90055847e+01 4.92502670e+01 4.85576897e+01 4.86328926e+01 4.88105545e+01 4.80912704e+01 4.79193802e+01 4.78008575e+01 4.73175774e+01 4.76882362e+01 4.72798271e+01 4.69313698e+01 4.78994141e+01 4.82622528e+01 4.75759354e+01 4.74663048e+01 4.72002907e+01 4.69286995e+01 4.65175476e+01 4.65257225e+01 4.70739403e+01 4.61832962e+01 4.55490952e+01 4.58633575e+01 4.56719437e+01 4.48651047e+01 4.48567047e+01 4.47545166e+01 4.50049477e+01 4.47928047e+01 4.47991943e+01 4.37712364e+01 4.33151398e+01 4.37575760e+01 4.35258980e+01 4.32570496e+01 4.33244743e+01 4.32590942e+01 4.30353355e+01 4.28450432e+01 4.28100014e+01 4.24289589e+01 4.19654770e+01 4.16411171e+01 4.15075912e+01 4.18347092e+01 4.20252342e+01 4.20677376e+01 4.19179916e+01 4.12904282e+01 4.11368599e+01 4.07337990e+01 4.08744087e+01 4.05658875e+01 4.02901955e+01 3.98569641e+01 3.92529068e+01 3.92157707e+01 3.91728020e+01 3.90213890e+01 3.91529083e+01 3.88403893e+01 3.82733421e+01 3.80689888e+01 3.80726776e+01 3.78077011e+01 3.74753418e+01 3.73717003e+01 3.71786537e+01 3.68385544e+01 3.67124443e+01 3.63718719e+01 3.62541618e+01 3.54829674e+01 3.54479675e+01 3.52362900e+01 3.54094658e+01 3.51622467e+01 3.46365471e+01 3.30571289e+01 3.22992096e+01 3.31469955e+01 3.48500328e+01 3.46905937e+01 3.31227722e+01 3.25792046e+01 3.24296494e+01 3.23802795e+01 3.19471416e+01 3.16799507e+01 3.14092655e+01 3.12042255e+01 3.08616848e+01 3.05602589e+01 3.03828621e+01 3.02584057e+01 2.98625145e+01 2.95327606e+01 2.92692471e+01 2.90410519e+01 2.87682400e+01 2.84748478e+01 2.81887455e+01 2.78274574e+01 2.76709557e+01 2.74040146e+01 2.70338249e+01 2.68180084e+01 2.65298405e+01 2.62796726e+01 2.59366703e+01 2.56868210e+01 2.54183559e+01 2.48268890e+01 2.48203030e+01 2.48319454e+01 2.43365211e+01 2.40330658e+01 2.37367020e+01 2.34289455e+01 2.31089592e+01 2.28450851e+01 2.26077652e+01 2.23688393e+01 2.20735321e+01 2.17374744e+01 2.14680023e+01 2.11571083e+01 2.08656311e+01 2.05427341e+01 2.02282963e+01 1.99386063e+01 1.96395016e+01 1.93489246e+01 1.90680408e+01 1.87665539e+01 1.84579659e+01 1.81661873e+01 1.78666077e+01 1.75683498e+01 1.72590179e+01 1.69334297e+01 1.66198521e+01 1.63048687e+01 1.60097809e+01 1.56985989e+01 1.53989878e+01 1.50963745e+01 1.47845144e+01 1.44471340e+01 1.41514158e+01 1.38620586e+01 1.35396929e+01 1.32161789e+01 1.29194155e+01 1.25937452e+01 1.22753839e+01 1.20039816e+01 1.16605806e+01 1.14052191e+01 1.11783543e+01 1.08366108e+01 9.07790661e+00 7.62686300e+00 9.01361370e+00 9.51594448e+00 9.44767952e+00 9.89691448e+00 9.50992966e+00 6.21060276e+00 5.56668806e+00 -3.06544685e+01 -5.02528496e+01 1.04743622e+02 6.22942467e+01 5.60445175e+01 9.16892319e+01 4.26635513e+01 4.32054520e+01 -7.11166687e+01 -5.28938293e+01 1.49561083e+00 -2.41346574e+00 -2.89741302e+00 1.99281812e+00 2.52785325e+00 1.98501801e+00 -4.32131559e-01 6.18569195e-01 1.24989319e+00 6.78354340e+01 1.27531723e+02 4.43182487e+01 4.37518349e+01 4.35880699e+01 -1.13335526e+02 -6.88784180e+01 4.72057199e+00 -2.47279286e+00 -3.64058423e+00 -3.60206985e+00 -2.74644542e+00 -2.63256359e+00 -2.86759424e+00 -3.35052276e+00 -3.56198120e+00 -3.64682722e+00 -3.90975857e+00 -4.24480343e+00 -4.84786367e+00 -5.39157963e+00 -5.57394838e+00 -5.70320272e+00 -5.85618782e+00 -6.09912491e+00 -6.55007982e+00 -6.95760918e+00 -7.16451979e+00 -7.71798897e+00 -8.25400639e+00 -8.36823559e+00 -8.62678146e+00 -8.57389069e+00 -8.92065525e+00 -9.43055630e+00 -9.89713383e+00 -1.03067207e+01 -1.06647615e+01 -1.12831125e+01 -1.15198784e+01 -1.16634989e+01 -1.17901039e+01 -1.20668936e+01 -1.24483089e+01 -1.22692709e+01 -1.24411306e+01 -1.28089857e+01 -1.36373863e+01 -1.37330675e+01 -1.44530115e+01 -1.52666950e+01 -1.58569002e+01 -1.57153482e+01 -1.55938396e+01 -1.57090874e+01 -1.63498211e+01 -1.70595512e+01 -1.68946323e+01 -1.70558357e+01 -1.72423077e+01 -1.72680283e+01 -1.78272305e+01 -1.83378754e+01 -1.87859745e+01 -1.90891075e+01 -1.96111660e+01 -1.94984989e+01 -1.96993446e+01 -1.95614777e+01 -1.99895000e+01 -2.10774841e+01 -2.11818199e+01 -2.19241009e+01 -2.16308346e+01 -2.19003391e+01 -2.16006889e+01 -2.20089130e+01 -2.28253937e+01 -2.37399673e+01 -2.32043304e+01 -2.30377979e+01 -2.26682472e+01 -2.36123638e+01 -2.40949173e+01 -2.52201576e+01 -2.52270527e+01 -2.55240860e+01 -2.56446304e+01 -2.61572819e+01 -2.66557674e+01 -2.59571571e+01 -2.62169476e+01 -2.77741833e+01 -2.77859802e+01 -2.84131279e+01 -2.84226475e+01 -2.83288460e+01 -2.82583961e+01 -2.84539165e+01 -2.82242203e+01 -2.88293343e+01 -2.93760166e+01 -2.95117989e+01 -2.97938118e+01 -2.99820080e+01 -3.05937099e+01 -3.15612335e+01 -3.11876259e+01 -3.12808113e+01 -3.07304058e+01 -3.11427631e+01 -3.16553497e+01 -3.16138859e+01 -3.39724045e+01 -3.49741287e+01 -3.32143211e+01 -3.30892258e+01 -3.29368095e+01 -3.43936386e+01 -3.53117828e+01 -3.55594444e+01 -3.45925255e+01 -3.38294487e+01 -3.43247108e+01 -3.44700203e+01 -3.41559982e+01 -3.55160446e+01 -3.64554634e+01 -3.68094063e+01 -3.64529305e+01 -3.61916924e+01 -3.68304138e+01 -3.72518845e+01 -3.75401535e+01 -3.72345619e+01 -3.75681610e+01 -3.86625366e+01 -3.86967621e+01 -3.88895454e+01 -3.84460220e+01 -3.90026588e+01 -3.89654007e+01 -3.96566353e+01 -3.99886627e+01 -4.00759544e+01 -3.99589081e+01 -3.96992874e+01 -3.92894096e+01 -3.95092926e+01 -4.00366592e+01 -4.10684280e+01 -4.18311005e+01 -4.13331184e+01 -4.12974205e+01 -4.26676254e+01 -4.34421997e+01 -4.28221016e+01 -4.26820221e+01 -4.27966270e+01 -4.27601891e+01 -4.30317268e+01 -4.32701492e+01 -4.34523087e+01 -4.29146690e+01 -4.30946960e+01 -4.36495056e+01 -4.40497246e+01 -4.51453362e+01 -4.54929276e+01 -4.38705330e+01 -4.35214958e+01 -4.38278999e+01 -4.42909126e+01 -4.62660255e+01 -4.64823189e+01 -4.59514198e+01 -4.58794022e+01 -4.66357918e+01 -4.63460922e+01 -4.63099594e+01 -4.69393654e+01 -4.59172745e+01 -4.62972069e+01 -4.61411095e+01 -4.61172371e+01 -4.82827759e+01 -4.84146194e+01 -4.66531563e+01 -4.63362007e+01 -4.78637009e+01 -4.84089241e+01 -4.73807716e+01 -4.77622757e+01 -4.83651810e+01 -4.86383438e+01 -4.84018440e+01 -4.83976135e+01 -4.89385223e+01 -4.82162361e+01 -4.77044945e+01 -4.86593475e+01 -5.05614052e+01 -5.05250168e+01 -4.90293541e+01 -4.97469406e+01 -4.99624290e+01 -4.96834679e+01 -5.03761864e+01 -5.02225876e+01 -5.00376701e+01 -5.06082115e+01 -5.00697937e+01 -4.99672127e+01 -5.07075310e+01 -5.04770660e+01 -5.00095634e+01 -5.02275505e+01 -5.13504944e+01 -5.07270508e+01 -5.07273636e+01 -5.16120453e+01 -5.17719803e+01 -5.23517799e+01 -5.15540810e+01 -5.09190979e+01 -5.07894516e+01 -5.08884544e+01 -5.15968628e+01 -5.13850670e+01 -5.14000359e+01 -5.13237610e+01 -5.15709648e+01 -5.14422340e+01 -5.16227188e+01 -5.17788811e+01 -5.20194740e+01 -5.31406288e+01 -5.22504349e+01 -5.16261368e+01 -5.23973465e+01 -5.24576874e+01 -5.23215752e+01 -5.26224442e+01 -5.23980408e+01 -5.23045616e+01 -5.30882492e+01 -5.29266930e+01 -5.19206238e+01 -5.24702797e+01 -5.26093788e+01 -5.28962555e+01 -5.25564575e+01 -5.24533958e+01 -5.21878395e+01 -5.21583672e+01 -5.22532539e+01 -5.27427559e+01 -5.26994820e+01 -5.26416168e+01 -5.25552864e+01 -5.26125298e+01 -5.22496147e+01 -5.24540176e+01 -5.22892036e+01 -5.28320885e+01 -5.30718536e+01 -5.25934105e+01 -5.16088028e+01 -5.25002708e+01 -5.28341713e+01 -5.34796066e+01 -5.36913338e+01 -5.22407761e+01 -5.13721695e+01 -5.17547874e+01 -5.26429863e+01 -5.32258453e+01 -5.36573143e+01 -5.30514526e+01 -5.22488785e+01 -5.18094101e+01 -5.16106758e+01 -5.16410065e+01 -5.19786987e+01 -5.29519043e+01 -5.25188293e+01 -5.19151192e+01 -5.13066826e+01 -5.15904999e+01 -5.20594597e+01 -5.16594925e+01 -5.15246696e+01 -5.15000343e+01 -5.17430534e+01 -5.19280853e+01 -5.18099861e+01 -5.18104172e+01 -5.17735710e+01 -5.16813011e+01 -5.15439491e+01 -5.11795959e+01 -5.05171928e+01 -4.99697113e+01 -5.02587852e+01 -5.07933083e+01 -5.12308846e+01 -5.08852119e+01 -5.12739754e+01 -5.12608109e+01 -5.08427925e+01 -5.05107193e+01 -5.00089302e+01 -5.07031937e+01 -5.04891357e+01 -5.00374565e+01 -4.94655151e+01 -4.89596558e+01 -4.91105537e+01 -4.93855171e+01 -4.93173752e+01 -4.93014450e+01 -4.96950111e+01 -4.90519371e+01 -4.89733315e+01 -4.91834526e+01 -4.87417679e+01 -4.87910881e+01 -4.86548347e+01 -4.91307144e+01 -4.84598808e+01 -4.81121902e+01 -4.67913933e+01 -4.69549294e+01 -4.79958382e+01 -4.79600067e+01 -4.71734619e+01 -4.69517593e+01 -4.57076149e+01 -4.61393890e+01 -4.60918427e+01 -4.69513054e+01 -4.68593292e+01 -4.70216179e+01 -4.65126534e+01 -4.57129860e+01 -4.55555267e+01 -4.59618835e+01 -4.53759003e+01 -4.49630814e+01 -4.53850212e+01 -4.58473587e+01 -4.52302475e+01 -4.45217934e+01 -4.38610687e+01 -4.39291954e+01 -4.36651840e+01 -4.34696350e+01 -4.32314339e+01 -4.31459045e+01 -4.28759422e+01 -4.32181740e+01 -4.32254143e+01 -4.35015678e+01 -4.28481712e+01 -4.27787361e+01 -4.20797348e+01 -4.16813965e+01 -4.17201767e+01 -4.18718300e+01 -4.22824249e+01 -4.22235069e+01 -4.13534622e+01 -4.12940712e+01 -4.11249046e+01 -4.10547333e+01 -4.05886765e+01 -4.02134209e+01 -3.98569450e+01 -3.92817497e+01 -3.91565933e+01 -3.88399696e+01 -3.85331154e+01 -3.88188019e+01 -3.88183975e+01 -3.84008751e+01 -3.79515572e+01 -3.76563034e+01 -3.74966354e+01 -3.72801056e+01 -3.71146202e+01 -3.67862396e+01 -3.65960464e+01 -3.65899239e+01 -3.61790733e+01 -3.56405258e+01 -3.54950333e+01 -3.56081924e+01 -3.45280113e+01 -3.46111145e+01 -3.51577835e+01 -3.49039955e+01 -3.44843407e+01 -3.40097618e+01 -3.38093529e+01 -3.37537575e+01 -3.35183487e+01 -3.28990936e+01 -3.14041443e+01 -3.28321991e+01 -2.98635254e+01 3.62951584e+01 7.17452774e+01 -6.79080124e+01 -6.74730682e+01 -6.79118729e+01 -1.58471222e+02 -1.02920914e+02 -3.10542812e+01 -3.02145920e+01 -2.96445980e+01 -2.89316521e+01 -2.77568436e+01 -2.99360924e+01 -3.06821575e+01 -2.84776459e+01 1.77596169e+01 1.02281971e+01 -6.46754379e+01 -7.05706215e+00 -1.21197388e+02 -7.88160706e+01 -2.61883049e+01 -2.48401031e+01 -2.62206192e+01 -2.82521286e+01 -2.48024311e+01 -2.64536037e+01 -2.44001865e+01 -2.41765480e+01 -2.37038193e+01 -1.92939453e+01 -2.00131092e+01 -2.32105618e+01 -2.29282207e+01 -2.24104004e+01 -2.22663288e+01 -2.21364136e+01 -2.19008408e+01 -2.15939331e+01 -2.12990303e+01 -2.09934292e+01 -2.06611519e+01 -2.03433170e+01 -2.00495777e+01 -1.97789574e+01 -1.95063152e+01 -1.91900711e+01 -1.88816586e+01 -1.85835743e+01 -1.82810345e+01 -1.79776096e+01 -1.76718521e+01 -1.73717041e+01 -1.70583134e+01 -1.67504654e+01 -1.64191418e+01 -1.60945225e+01 -1.57590656e+01 -1.54476042e+01 -1.51425581e+01 -1.48283081e+01 -1.45154409e+01 -1.42018881e+01 -1.38961954e+01 -1.35855913e+01 -1.32645006e+01 -1.29418602e+01 -1.26279955e+01 -1.22875023e+01 -1.19242134e+01 -1.15928841e+01 -1.12698956e+01 -1.09383249e+01 -1.06097660e+01 -1.04320011e+01 -1.01537628e+01 -9.84029579e+00 -9.48235893e+00 -9.15172386e+00 -8.82266998e+00 -8.58028221e+00 -8.21483421e+00 -7.84464073e+00 -7.55731440e+00 -7.26855803e+00 -7.02642870e+00 -6.66959238e+00 -6.30445290e+00 -5.93230200e+00 -5.66268921e+00 -5.41619158e+00 -5.11293364e+00 -4.73211813e+00 -4.40107822e+00 -4.12079859e+00 -4.00844765e+00 -3.81291461e+00 -2.96950483e+00 -2.28016114e+00 -2.35865498e+00 -2.25632572e+00 -1.82705975e+00 -1.45140004e+00 -1.24829376e+00 -8.60822558e-01 -4.87059861e-01 -1.10896878e-01 8.87696072e-02 4.39057499e-01 7.43137479e-01 1.19552171e+00 9.30380762e-01 1.30805504e+00 2.78683090e+00 3.07206631e+00 2.79262376e+00 3.41502619e+00 3.43901443e+00 3.48717690e+00 3.74384809e+00 3.19658709e+00 3.61469555e+00 5.12256622e+00 7.13806868e+00 7.16041660e+00 5.84981298e+00 5.85881996e+00 6.12853479e+00 6.65077353e+00 7.19315958e+00 7.78834963e+00 7.90307665e+00 8.05040169e+00 8.32213879e+00 8.57515240e+00 9.02720070e+00 9.34443378e+00 9.87741566e+00 1.02523355e+01 1.05439405e+01 1.11641502e+01 1.14649677e+01 1.14944572e+01 1.16873751e+01 1.22595615e+01 1.27706671e+01 1.27618361e+01 1.25981283e+01 1.24647341e+01 1.33045940e+01 1.38788271e+01 1.44645414e+01 1.46390696e+01 1.53368683e+01 1.56150570e+01 1.27180586e+01 1.31161976e+01 1.80865402e+01 1.97502823e+01 1.81242828e+01 1.71003590e+01 1.73864002e+01 1.74517403e+01 1.76034451e+01 1.77783108e+01 1.86031551e+01 1.90538864e+01 1.94544582e+01 1.92243252e+01 1.94590702e+01 1.98237801e+01 2.00147076e+01 2.07744102e+01 2.09665203e+01 2.17406445e+01 2.16361885e+01 2.17099762e+01 2.20175343e+01 2.26499996e+01 2.30759754e+01 2.33486271e+01 2.33092327e+01 2.34399700e+01 2.30007534e+01 2.38338089e+01 2.42435188e+01 2.54012394e+01 2.55067673e+01 2.59447384e+01 2.56494846e+01 2.58060055e+01 2.62153130e+01 2.67206993e+01 2.64431801e+01 2.71359043e+01 2.83383656e+01 2.86598072e+01 2.80064011e+01 2.82374191e+01 2.80307007e+01 2.83424625e+01 2.83076038e+01 2.87744865e+01 2.87837505e+01 2.96123238e+01 3.02141571e+01 3.00856705e+01 3.04062328e+01 3.16728287e+01 3.21199150e+01 3.14475479e+01 3.10999813e+01 3.18344593e+01 3.17973042e+01 3.11847992e+01 2.95419006e+01 1.02045107e+01 2.04469498e+02 2.90558960e+02 6.09035217e+02 1.41794373e+03 -36486808. -117234712. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -163331632. -163331632. -163331632. 0. 0. -49659096. 2.30663254e+02 6.39597855e+01 4.97586250e+01 -1.59572311e+02 -3.10760529e+02 3.90915649e+02 5.61844360e+02 7.35739594e+01 -28197784. 1282204160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1267846144. -1267846144. -1267846144. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1903325824. -1903325824. -1903325824. 0. 0. 0. 0. -4.58208922e+09 -6.36350050e+06 -20388830. 39456816. -5.36689459e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -299497312. 31874760. -1.61245250e+05 19978098. 39169020. -45109816. 2.89121450e+06 -112001728. 2.36843175e+06 2.82265406e+05 -68860520. 114123912. 632696000. 632696000. 0. 0. 0. 0. 0. 0. 0. -586053248. -586053248. -586053248. 0. 0. -686466240. -2137302656. -2137302656. 115914720. 220842112. 1.03378250e+06 1.02845444e+06 9822537. 2597507. -138061632. 364039968. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.27841016e+05 3.36284607e+02 -2.33774017e+02 -1.03855629e+02 6.69196701e+01 6.75773544e+01 6.54789124e+01 6.36650620e+01 6.26172791e+01 6.14053078e+01 6.18614311e+01 6.23337059e+01 6.08327675e+01 6.07638359e+01 6.27028008e+01 -1.00209633e+02 -2.13654099e+02 4.01550018e+02 2.55866455e+02 5.74514389e+01 6.00161896e+01 6.14496803e+01 6.00191765e+01 5.99604492e+01 6.13018150e+01 6.07032700e+01 6.04284515e+01 6.07742958e+01 5.98657379e+01 5.92303429e+01 5.92513924e+01 5.89114494e+01 5.94710579e+01 5.94498291e+01 5.88107910e+01 5.88677979e+01 5.63829269e+01 -8.90100021e+01 -1.86923630e+02 1.31841125e+02 1.30558014e+02 1.36158768e+02 3.66421356e+02 2.35327255e+02 5.81267090e+01 5.72312660e+01 5.77473450e+01 5.77906075e+01 5.76265907e+01 5.78989983e+01 5.69697723e+01 5.63790092e+01 5.64153748e+01 5.66247444e+01 5.60117149e+01 5.54885178e+01 5.51609573e+01 5.55493851e+01 5.55022430e+01 5.51999664e+01 5.39737511e+01 5.37427940e+01 5.36201973e+01 5.41908569e+01 5.38242722e+01 5.28780861e+01 5.26887360e+01 5.23216324e+01 5.26153717e+01 5.24228897e+01 5.22496605e+01 5.20569725e+01 5.15469513e+01 5.10164871e+01 5.07171249e+01 5.03443260e+01 5.06966743e+01 5.03183174e+01 5.02134323e+01 4.97830429e+01 4.99591217e+01 5.00865364e+01 4.95266914e+01 4.92655830e+01 4.86763496e+01 4.87417336e+01 4.81647377e+01 4.78381081e+01 4.75471916e+01 4.73291092e+01 4.70341263e+01 4.66547394e+01 4.64180374e+01 4.62368927e+01 4.59393883e+01 4.57807693e+01 4.54720688e+01 4.49639473e+01 4.47741051e+01 4.45704002e+01 4.42323875e+01 4.38495979e+01 4.34236565e+01 4.30074005e+01 4.27751083e+01 4.28516541e+01 4.27915726e+01 4.22405624e+01 4.13722992e+01 4.03211327e+01 4.06525612e+01 4.25664520e+01 4.23144989e+01 4.05787086e+01 3.98412209e+01 3.96902542e+01 3.94843559e+01 3.90550232e+01 3.87397804e+01 3.85238075e+01 3.83460388e+01 3.80908051e+01 3.76601410e+01 3.74329262e+01 3.70882912e+01 3.65651894e+01 3.61993408e+01 3.59294586e+01 3.56877098e+01 3.53212166e+01 3.50202255e+01 3.45521774e+01 3.41657104e+01 3.38924255e+01 3.36260300e+01 3.32655640e+01 3.29229546e+01 3.26485901e+01 3.24140854e+01 3.21443329e+01 3.18211594e+01 3.14196415e+01 3.07971306e+01 3.06106586e+01 3.04994316e+01 3.00253258e+01 2.96559982e+01 2.93505402e+01 2.89570942e+01 2.85313034e+01 2.81838665e+01 2.78420334e+01 2.74797764e+01 2.71286106e+01 2.67771797e+01 2.64459286e+01 2.61028709e+01 2.57577362e+01 2.53828621e+01 2.50305195e+01 2.46660385e+01 2.42999058e+01 2.39428482e+01 2.35929432e+01 2.32271118e+01 2.28589039e+01 2.25045242e+01 2.21467247e+01 2.17790737e+01 2.14034271e+01 2.10246277e+01 2.06662941e+01 2.03185558e+01 1.99590626e+01 1.95879211e+01 1.91980629e+01 1.88036861e+01 1.84131756e+01 1.80320091e+01 1.76919041e+01 1.73421612e+01 1.69387035e+01 1.65630035e+01 1.61991577e+01 1.58359346e+01 1.54486275e+01 1.50764093e+01 1.46747885e+01 1.43043442e+01 1.39041519e+01 1.35514641e+01 1.32014980e+01 1.27611494e+01 1.23471651e+01 1.19160366e+01 1.16428614e+01 1.16260977e+01 1.05768185e+01 7.56413555e+00 7.30858517e+00 9.84429741e+00 1.01475935e+01 1.07484760e+01 1.05836325e+01 3.24663162e+00 1.46470749e+00 1.57136881e+00 2.68063521e+00 6.68943834e+00 -5.03738976e+01 -7.06098785e+01 3.88903992e+02 9.21911255e+02 6.80777283e+02 2.71199768e+02 3.23936195e+01 -9.63714600e+01 -6.16479836e+01 1.68147326e+00 -2.30460072e+00 -2.69920683e+00 -7.95765686e+00 -8.57161331e+00 -8.78836441e+00 -4.07050705e+00 1.34501839e+00 1.23220310e+01 8.27821350e+01 1.42360428e+02 2.21657181e+01 2.76367512e+01 2.91739216e+01 2.95308056e+01 2.73154926e+01 2.73409653e+01 2.75185299e+01 -1.46797928e+02 -9.84845352e+01 -5.50205946e+00 -6.10886288e+00 -7.25513935e+00 -7.10279512e+00 -7.10903072e+00 -5.76747656e+00 -7.21070957e+00 -9.49838638e+00 -7.30990553e+00 -6.48435354e+00 -9.01786900e+00 -9.19797039e+00 -5.51722860e+00 -4.06956863e+00 -6.72451258e-01 1.05607328e+01 -7.15158606e+00 -2.09151249e+01 -1.10836542e+00 -2.04498081e+01 -2.49853878e+01 -1.74158916e+01 -1.90245209e+01 -1.48711643e+01 -1.58796043e+01 -1.28757391e+01 -1.60028286e+01 -1.67704029e+01 -1.60755291e+01 -1.77414608e+01 -1.71993580e+01 -1.57512484e+01 -1.80614548e+01 -1.67831612e+01 -1.42162933e+01 -1.74997940e+01 -2.00484695e+01 -2.01220818e+01 -2.04692898e+01 -2.04294033e+01 -2.07265587e+01 -2.11715736e+01 -2.17079601e+01 -2.20949554e+01 -2.18934097e+01 -2.21046410e+01 -2.26493034e+01 -2.32629719e+01 -2.36666546e+01 -2.39438133e+01 -2.43710480e+01 -2.47854652e+01 -2.53809128e+01 -2.57685337e+01 -2.55691814e+01 -2.57463493e+01 -2.59989796e+01 -2.60735512e+01 -2.64828072e+01 -2.73655815e+01 -2.76864719e+01 -2.77567749e+01 -2.78588619e+01 -2.79845943e+01 -2.83672428e+01 -2.93256721e+01 -3.02395554e+01 -3.05883713e+01 -3.02782688e+01 -3.04853973e+01 -3.11310005e+01 -3.10143070e+01 -3.15133724e+01 -3.30754929e+01 -3.25994720e+01 -3.26970749e+01 -3.31689682e+01 -3.35024643e+01 -3.37799034e+01 -3.43193169e+01 -3.42740860e+01 -3.52424889e+01 -3.55619583e+01 -3.49717293e+01 -3.54773827e+01 -3.53780823e+01 -3.61754494e+01 -3.68266983e+01 -3.71642494e+01 -3.77283478e+01 -3.74314575e+01 -3.74126167e+01 -3.75612793e+01 -3.74232368e+01 -3.90214653e+01 -3.99107094e+01 -3.96165352e+01 -3.88808632e+01 -3.96613579e+01 -4.13152504e+01 -4.18926048e+01 -4.25110626e+01 -4.16194687e+01 -4.16293221e+01 -4.23215141e+01 -4.27521210e+01 -4.21665306e+01 -4.22574463e+01 -4.32431488e+01 -4.43347359e+01 -4.40047112e+01 -4.36573410e+01 -4.37928047e+01 -4.42119331e+01 -4.48620186e+01 -4.49154205e+01 -4.49984016e+01 -4.53877640e+01 -4.58773308e+01 -4.62130127e+01 -4.68630714e+01 -4.67086792e+01 -4.67661972e+01 -4.71228256e+01 -4.76218758e+01 -4.76272736e+01 -4.78317833e+01 -4.83152428e+01 -4.89445992e+01 -4.85911636e+01 -4.86563148e+01 -4.95982475e+01 -5.02961540e+01 -4.98206787e+01 -4.91750984e+01 -5.04032478e+01 -5.15422287e+01 -5.16284714e+01 -5.20454674e+01 -5.18540001e+01 -5.16843758e+01 -5.20670128e+01 -5.19483528e+01 -5.18634796e+01 -5.15296478e+01 -5.18711472e+01 -5.20761566e+01 -5.20936928e+01 -5.38659592e+01 -5.42518082e+01 -5.28211823e+01 -5.23494606e+01 -5.32111168e+01 -5.40283012e+01 -5.53619270e+01 -5.49620628e+01 -5.48121490e+01 -5.57203102e+01 -5.60401497e+01 -5.53644714e+01 -5.60087318e+01 -5.64509315e+01 -5.53415833e+01 -5.56018333e+01 -5.58692474e+01 -5.63250618e+01 -5.77712746e+01 -5.77537155e+01 -5.68916397e+01 -5.64814262e+01 -5.75908470e+01 -5.82245331e+01 -5.74030380e+01 -5.74390564e+01 -5.80585709e+01 -5.86030273e+01 -5.85887108e+01 -5.85728378e+01 -5.90377274e+01 -5.89638138e+01 -5.81016273e+01 -5.86007843e+01 -6.07983513e+01 -6.06634712e+01 -5.94349060e+01 -5.99486275e+01 -5.99809952e+01 -5.99885178e+01 -6.07055702e+01 -6.08957558e+01 -6.05798035e+01 -6.09291039e+01 -6.07231903e+01 -6.04643745e+01 -6.11135979e+01 -6.12134094e+01 -6.05927925e+01 -6.07940254e+01 -6.25766411e+01 -6.17154312e+01 -6.06931152e+01 -6.17277145e+01 -6.24083786e+01 -6.32639580e+01 -6.21663704e+01 -6.18124657e+01 -6.15444603e+01 -6.17772102e+01 -6.23043900e+01 -6.24379387e+01 -6.24502411e+01 -6.27403946e+01 -6.28573189e+01 -6.26426697e+01 -6.25868988e+01 -6.29182892e+01 -6.27422791e+01 -6.31309013e+01 -6.28411903e+01 -6.29638062e+01 -6.33727684e+01 -6.31410446e+01 -6.29568863e+01 -6.32936516e+01 -6.35094452e+01 -6.32842827e+01 -6.38258858e+01 -6.39955406e+01 -6.35760269e+01 -6.37377510e+01 -6.40739365e+01 -6.36594505e+01 -6.33447495e+01 -6.40653076e+01 -6.39689217e+01 -6.40815506e+01 -6.40777664e+01 -6.45834198e+01 -6.44033585e+01 -6.44954910e+01 -6.43869095e+01 -6.45441132e+01 -6.37793655e+01 -6.37370491e+01 -6.36230087e+01 -6.39448318e+01 -6.45485001e+01 -6.46673279e+01 -6.41746140e+01 -6.44089355e+01 -6.42280731e+01 -6.31164436e+01 -6.39685326e+01 -6.39648933e+01 -6.49977722e+01 -6.49229126e+01 -6.47121887e+01 -6.41590729e+01 -6.35355759e+01 -6.35767365e+01 -6.36931610e+01 -6.43273239e+01 -6.46925430e+01 -6.38983383e+01 -6.35261154e+01 -6.37882309e+01 -6.36371002e+01 -6.32394142e+01 -6.31451950e+01 -6.34007912e+01 -6.37449417e+01 -6.29365807e+01 -6.24742470e+01 -6.17687569e+01 -6.19001236e+01 -6.26031265e+01 -6.28210602e+01 -6.25773315e+01 -6.25459900e+01 -6.20653343e+01 -6.25039215e+01 -6.24450111e+01 -6.25329399e+01 -6.18940468e+01 -6.13593712e+01 -6.18414307e+01 -6.16124229e+01 -6.08583069e+01 -6.07811775e+01 -6.06151390e+01 -6.14970245e+01 -6.07589340e+01 -6.01024628e+01 -6.00301704e+01 -6.01596565e+01 -6.05998306e+01 -6.04357834e+01 -6.06171684e+01 -6.07531204e+01 -6.15024338e+01 -6.04967270e+01 -5.97589989e+01 -5.91924438e+01 -5.91106033e+01 -5.89878082e+01 -5.88179321e+01 -5.90223198e+01 -5.90919609e+01 -5.87621727e+01 -5.88606529e+01 -5.86508141e+01 -5.75488205e+01 -5.71181793e+01 -5.77851524e+01 -5.82752419e+01 -5.73405762e+01 -5.68874664e+01 -5.71350174e+01 -5.62112198e+01 -5.64000168e+01 -5.62988434e+01 -5.68250580e+01 -5.72338562e+01 -5.68767471e+01 -5.58903275e+01 -5.50319595e+01 -5.53420296e+01 -5.59497223e+01 -5.53759499e+01 -5.48429413e+01 -5.39865608e+01 -5.43494987e+01 -5.47295418e+01 -5.46502991e+01 -5.43632202e+01 -5.43226891e+01 -5.42582588e+01 -5.40084229e+01 -5.36172562e+01 -5.27488174e+01 -5.21731415e+01 -5.22487869e+01 -5.31316910e+01 -5.27269707e+01 -5.25933838e+01 -5.28279305e+01 -5.22191505e+01 -5.13914871e+01 -5.11379166e+01 -5.07831116e+01 -5.09393883e+01 -5.09624977e+01 -5.05758324e+01 -5.04725647e+01 -5.03174782e+01 -4.98745995e+01 -4.94474983e+01 -4.96952019e+01 -4.91074257e+01 -4.90704689e+01 -4.88584480e+01 -4.87850113e+01 -4.81945229e+01 -4.81769104e+01 -4.79001999e+01 -4.76870308e+01 -4.71841087e+01 -4.67188301e+01 -4.65176086e+01 -4.59003525e+01 -4.62540970e+01 -4.60994873e+01 -4.55063477e+01 -4.52843056e+01 -4.44918480e+01 -4.38413658e+01 -4.25818100e+01 3.39182587e+01 7.97473221e+01 -1.11004509e+02 -1.13693871e+02 -1.12982391e+02 -1.12751221e+02 -1.12721069e+02 -1.13435516e+02 -1.13989861e+02 -1.12576378e+02 -2.01722458e+02 -1.26804092e+02 -3.98596077e+01 -3.56744385e+01 -4.50994987e+01 -5.08649330e+01 -4.83648491e+01 -4.76309013e+01 -4.71269073e+01 -4.07757225e+01 -4.09583664e+01 1.43139000e+01 4.40722122e+01 -9.96212387e+01 -1.54546082e+02 -5.09371529e+01 3.47742805e+01 -1.55683868e+02 -9.97666321e+01 -3.92060127e+01 -6.18482256e+00 -3.56744423e+01 -5.80370560e+01 -3.44473267e+01 -3.49515343e+01 -3.28646507e+01 -3.02621822e+01 -3.11351566e+01 -8.10367050e+01 -3.56292648e+01 -2.38678265e+00 -2.98332977e+01 -2.98497047e+01 -2.96447544e+01 -2.94784412e+01 -2.91283550e+01 -2.87005920e+01 -2.83433571e+01 -2.80247746e+01 -2.76614685e+01 -2.73170013e+01 -2.69651604e+01 -2.65998230e+01 -2.62450066e+01 -2.58788128e+01 -2.55257740e+01 -2.51565018e+01 -2.47836971e+01 -2.44402485e+01 -2.41158543e+01 -2.37677269e+01 -2.34125290e+01 -2.30538273e+01 -2.26940842e+01 -2.23275394e+01 -2.19606934e+01 -2.15899811e+01 -2.12233257e+01 -2.08527927e+01 -2.04804440e+01 -2.01044388e+01 -1.97317810e+01 -1.93732758e+01 -1.90057220e+01 -1.86119747e+01 -1.82324123e+01 -1.78588734e+01 -1.74980602e+01 -1.70953789e+01 -1.67167397e+01 -1.63354759e+01 -1.59968634e+01 -1.55887060e+01 -1.51511612e+01 -1.47825756e+01 -1.44402227e+01 -1.39260731e+01 -1.34957323e+01 -1.32673635e+01 -1.28643026e+01 -1.24314461e+01 -1.20621634e+01 -1.16772251e+01 -1.13035975e+01 -1.09394693e+01 -1.05359201e+01 -1.00525150e+01 -9.76205730e+00 -9.35028267e+00 -9.05317497e+00 -8.65512943e+00 -8.19885826e+00 -7.78657818e+00 -7.32860756e+00 -7.03859901e+00 -6.66163445e+00 -6.25642300e+00 -5.86386871e+00 -5.43159342e+00 -5.30361557e+00 -4.95612669e+00 -4.05621529e+00 -3.63563371e+00 -3.51861358e+00 -3.10099792e+00 -2.71835923e+00 -2.24520493e+00 -1.97184670e+00 -1.48101449e+00 -1.10502744e+00 -6.64712250e-01 -4.12063986e-01 -7.63335824e-02 4.28549588e-01 8.38050902e-01 5.80684900e-01 1.13529122e+00 3.00758386e+00 3.19410062e+00 2.81128931e+00 3.04647708e+00 3.22136259e+00 3.52667594e+00 4.43164921e+00 3.93582344e+00 4.19365406e+00 5.79561138e+00 7.38663626e+00 7.58707428e+00 6.92476749e+00 7.29659271e+00 7.76385355e+00 8.07025814e+00 8.26333141e+00 8.84876537e+00 8.98829842e+00 9.50463295e+00 9.90142727e+00 1.01737118e+01 1.06622553e+01 1.08983793e+01 1.14175329e+01 1.17470026e+01 1.20093756e+01 1.25522690e+01 1.28485537e+01 1.33254185e+01 1.39688501e+01 1.41767969e+01 1.47443790e+01 1.52331581e+01 1.57138433e+01 1.56797581e+01 1.59135008e+01 1.64836407e+01 1.69356251e+01 1.67970562e+01 1.70059166e+01 1.72698917e+01 1.53980999e+01 1.56083202e+01 2.04793777e+01 2.13760357e+01 1.97569294e+01 1.95865269e+01 2.01227970e+01 2.09941044e+01 2.11946926e+01 2.14513168e+01 2.14983406e+01 2.15104427e+01 2.19106178e+01 2.22677841e+01 2.29930363e+01 2.34016819e+01 2.36633224e+01 2.45855255e+01 2.50716705e+01 2.53362427e+01 2.51757126e+01 2.23024101e+01 1.50134783e+01 7.43319225e+00 -1.34768814e+02 -2.33927155e+02 2.32919273e+01 2.47900562e+01 3.09769897e+02 1.99117004e+02 2.85682697e+01 2.98189850e+01 3.05349903e+01 3.07345314e+01 3.06195793e+01 3.11623573e+01 3.13814430e+01 3.18829117e+01 3.21173286e+01 3.21418762e+01 3.22593117e+01 3.29549866e+01 3.30917549e+01 3.35078239e+01 3.19408016e+01 3.15104752e+01 3.21773911e+01 4.37435112e+01 -1.21041168e+02 4.36463535e-01 2.42074921e+02 4.41927261e+01 5.00022621e+01 5.05408173e+01 4.14315453e+01 3.95258484e+01 3.88967705e+01 3.91099014e+01 3.88237419e+01 3.86720657e+01 3.83799400e+01 3.76286240e+01 3.45112343e+01 1.35259295e+01 1.91631287e+02 1.73270844e+02 -4.71193115e+03 -117234712. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -163331632. -163331632. -163331632. 0. 0. -5.20946250e+06 6.74418152e+02 2.08108231e+02 1.15211510e+02 -8.03460815e+02 -2.33771313e+03 2.26620142e+03 1.22933022e+02 -2.06860278e+03 -28197784. 1282204160. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.34037371e+10 -2.34037371e+10 -2.34037371e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1903325824. -1903325824. -1903325824. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1070082752. -1070082752. -1070082752. 0. 0. 0. 0. 0. 0. 0. 0. 0. -299497312. 31874760. -1.61245250e+05 19978098. 39169020. -45109816. 2.89121450e+06 -112001728. 2.08310181e+03 8.04925308e+01 -3.70314868e+03 1.62510327e+03 4.15603076e+03 4.15603076e+03 -12904282. 66773756. 66773756. 110947320. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.27841016e+05 3.36284607e+02 1.29584442e+02 1.33554672e+02 1.34831223e+02 4.01550507e+02 2.46744598e+02 4.43232994e+01 4.41924133e+01 4.31354065e+01 4.25746651e+01 4.33647804e+01 -1.29925583e+02 -2.51684540e+02 1.16408195e+02 -5.68840332e+02 -1.57403088e+03 2.00115247e+03 8.52594971e+02 9.21852875e+01 1.08737541e+02 1.12938919e+02 1.10261894e+02 1.13974190e+02 1.17308853e+02 1.14381210e+02 3.68227295e+02 2.29421997e+02 4.25814209e+01 4.27679214e+01 4.30063133e+01 4.30203590e+01 4.31489639e+01 4.34443283e+01 -1.08133705e+02 -2.10258514e+02 9.99014130e+01 -5.02437714e+02 -1.37329126e+03 -13072694. 2.64824653e+09 35040460. 1.87418530e+03 8.18036438e+02 1.22805847e+02 1.15503906e+02 1.17945816e+02 1.18731522e+02 1.19451843e+02 1.20520348e+02 1.19129631e+02 3.28065643e+02 2.04259506e+02 4.34804688e+01 4.35296440e+01 4.28216820e+01 4.27906494e+01 4.24341164e+01 4.27714729e+01 4.24394569e+01 4.18433456e+01 4.18851738e+01 4.14798203e+01 4.16790390e+01 4.15037346e+01 4.09857178e+01 4.09695549e+01 4.12589188e+01 4.10798416e+01 4.08941040e+01 4.08165855e+01 4.11263542e+01 4.09379768e+01 4.09469910e+01 4.06785507e+01 4.04737206e+01 4.00489502e+01 3.95939140e+01 3.98502007e+01 3.95969391e+01 3.97676201e+01 3.94693375e+01 3.94132996e+01 3.90439224e+01 3.91955376e+01 3.91296501e+01 3.94534187e+01 3.91572037e+01 3.86808052e+01 3.80645180e+01 3.81555901e+01 3.87996445e+01 3.81719780e+01 3.79728737e+01 3.76460953e+01 3.77755432e+01 3.76563187e+01 3.73998985e+01 3.76444130e+01 3.73731880e+01 3.71484299e+01 3.68974380e+01 3.70639915e+01 3.68911629e+01 3.67418365e+01 3.65397110e+01 3.65220909e+01 3.64170761e+01 3.62486038e+01 3.46605492e+01 3.47630196e+01 3.76154747e+01 3.74321594e+01 3.54624519e+01 3.51170387e+01 3.50968628e+01 3.50394516e+01 3.48892326e+01 3.46535225e+01 3.44585915e+01 3.42695503e+01 3.42385178e+01 3.39793968e+01 3.38232880e+01 3.35589867e+01 3.34088707e+01 3.32943230e+01 3.32856598e+01 3.31218796e+01 3.28218536e+01 3.27523499e+01 3.25094872e+01 3.23317528e+01 3.22630615e+01 3.20066147e+01 3.17720795e+01 3.15724068e+01 3.13569927e+01 3.12153664e+01 3.10601826e+01 3.08572636e+01 3.05877285e+01 3.02060375e+01 3.01341324e+01 3.01039715e+01 2.98016720e+01 2.96370296e+01 2.95523224e+01 2.93409576e+01 2.90529442e+01 2.88900394e+01 2.87298107e+01 2.85097675e+01 2.82655487e+01 2.80565147e+01 2.78609028e+01 2.76953793e+01 2.74844646e+01 2.72813969e+01 2.70854721e+01 2.68860912e+01 2.66800232e+01 2.64705563e+01 2.62674675e+01 2.60438118e+01 2.58186111e+01 2.55880108e+01 2.53531303e+01 2.51470985e+01 2.49667015e+01 2.47943993e+01 2.45985870e+01 2.43788528e+01 2.41395874e+01 2.39059849e+01 2.36685753e+01 2.34344215e+01 2.31912327e+01 2.29676857e+01 2.27497768e+01 2.24915333e+01 2.22078190e+01 2.20026741e+01 2.17655010e+01 2.15679874e+01 2.13603573e+01 2.10967674e+01 2.08557587e+01 2.06265049e+01 2.04059372e+01 2.01496487e+01 1.99704037e+01 1.97345581e+01 1.94220829e+01 1.92084351e+01 1.89674702e+01 1.86953983e+01 1.84133053e+01 1.81824360e+01 1.79375439e+01 1.77194424e+01 1.78835793e+01 1.80569439e+01 1.69793758e+01 -2.35497665e+01 -4.32949715e+01 9.50088882e+01 9.63930893e+01 1.26440865e+02 7.37902908e+01 1.64207497e+01 9.72358990e+00 8.40687561e+00 1.13143473e+01 1.30941525e+01 1.40573130e+01 1.45839491e+01 1.38235655e+01 8.52409821e+01 7.07913208e+01 -4.57128204e+02 -39760512. 61125704. -21796014. 9.37154724e+02 3.89129395e+02 1.24983574e+02 3.85430176e+02 9.24474548e+02 7.71617812e+05 45134852. 122460480. -41054408. -30025056. 216877728. -6.71916382e+02 -2.07749985e+02 1.29402695e+02 6.88956680e+01 -8.02003479e+01 4.12728348e+01 1.78772461e+02 5.86301689e+01 6.88595428e+01 6.19976959e+01 4.90083504e+01 -8.55399704e+01 -6.32308121e+01 1.43449524e+02 1.45010242e+01 5.14488907e+01 8.66462631e+01 -1.04250763e+02 4.36684647e+01 5.29312439e+01 -3.98040657e+01 4.67450857e+00 2.04298744e+01 -1.69177036e+01 9.79186058e+00 2.32576580e+01 8.24680042e+00 8.93875885e+00 2.58212757e+01 1.80091248e+01 7.19506836e+00 1.02416468e+01 1.47719070e+02 -4.83717499e+01 -4.47866783e+01 2.07281998e+02 2.08290558e+02 6.46823807e+01 4.48717575e+01 3.00629768e+01 3.07914219e+01 2.97913208e+01 3.15639858e+01 3.02779140e+01 2.99788933e+01 2.89281273e+01 2.79652348e+01 2.80828934e+01 2.67975502e+01 2.70329895e+01 2.60863152e+01 2.54681759e+01 2.29449749e+01 2.22226753e+01 2.20898724e+01 1.91681023e+01 -2.60200195e+02 -1.60983765e+02 -6.66977310e+00 -7.39380693e+00 -7.25171518e+00 -7.56340885e+00 -7.95687675e+00 -8.81507587e+00 -9.06832409e+00 -9.81295490e+00 -9.16997337e+00 -9.23481083e+00 -8.73045635e+00 -8.83513260e+00 -9.03327274e+00 -9.52760220e+00 -1.00560188e+01 -1.04020643e+01 -9.88050079e+00 -1.05659571e+01 -1.13394575e+01 -1.12925663e+01 -1.10005426e+01 -1.19316568e+01 -1.22469378e+01 -1.24573278e+01 -1.25464687e+01 -1.24475794e+01 -1.30794477e+01 -1.31583071e+01 -1.36161299e+01 -1.40505190e+01 -1.39911423e+01 -1.40754948e+01 -1.42492542e+01 -1.45131521e+01 -1.51689587e+01 -1.55805426e+01 -1.60611973e+01 -1.60668564e+01 -1.58978109e+01 -1.61675606e+01 -1.63223419e+01 -1.71682758e+01 -1.54879122e+01 -1.60555592e+01 -1.64081726e+01 -1.82831059e+01 -1.84278221e+01 -1.77572556e+01 -1.70378933e+01 -1.84785690e+01 -1.96381607e+01 -1.86857071e+01 -1.84949474e+01 -1.97095528e+01 -2.11374531e+01 -2.02944508e+01 -2.02179184e+01 -2.01361198e+01 -2.03564358e+01 -2.08591347e+01 -2.12189007e+01 -2.15597668e+01 -2.17558327e+01 -2.21395435e+01 -2.25629025e+01 -2.33522072e+01 -2.26092224e+01 -2.30549011e+01 -2.36496181e+01 -2.36953678e+01 -2.37536526e+01 -2.35951519e+01 -2.36117210e+01 -2.39640293e+01 -2.38222637e+01 -2.50302181e+01 -2.50882187e+01 -2.50262051e+01 -2.52170811e+01 -2.54904499e+01 -2.60870972e+01 -2.64205856e+01 -2.63980846e+01 -2.67795353e+01 -2.71289940e+01 -2.66866817e+01 -2.69603977e+01 -2.74835720e+01 -2.76443386e+01 -2.78214359e+01 -2.80755424e+01 -2.72463875e+01 -2.72461815e+01 -2.86267948e+01 -2.85867977e+01 -2.86311264e+01 -2.87042828e+01 -2.87815075e+01 -2.92887650e+01 -2.96879215e+01 -2.98644238e+01 -3.06302357e+01 -3.06392059e+01 -2.98700333e+01 -3.08548336e+01 -3.16312370e+01 -3.13913593e+01 -3.12068844e+01 -3.12668343e+01 -3.04532356e+01 -3.06087208e+01 -3.20438499e+01 -3.24630775e+01 -3.22488747e+01 -3.24157448e+01 -3.26264877e+01 -3.27102127e+01 -3.29715309e+01 -3.30712166e+01 -3.34875755e+01 -3.37378807e+01 -3.36566162e+01 -3.38826408e+01 -3.40911903e+01 -3.42702408e+01 -3.33254662e+01 -3.38003578e+01 -3.59966850e+01 -3.57519646e+01 -3.48935013e+01 -3.52583618e+01 -3.51193237e+01 -3.52534790e+01 -3.59040680e+01 -3.56588974e+01 -3.48985863e+01 -3.56880417e+01 -3.59612503e+01 -3.57706261e+01 -3.65209503e+01 -3.66391716e+01 -3.68387413e+01 -3.71055069e+01 -3.81882668e+01 -3.75003395e+01 -3.64388123e+01 -3.74657745e+01 -3.84257469e+01 -3.84861221e+01 -3.74183273e+01 -3.75602493e+01 -3.77841797e+01 -3.78281326e+01 -3.80430832e+01 -3.87143478e+01 -3.91527138e+01 -3.90241432e+01 -3.91119690e+01 -3.98699837e+01 -3.97470627e+01 -3.95522041e+01 -3.90424309e+01 -3.91470222e+01 -3.94054222e+01 -3.97115593e+01 -4.04445190e+01 -4.04023743e+01 -3.98741646e+01 -3.99445152e+01 -3.99729347e+01 -3.99972572e+01 -4.00827637e+01 -4.01547546e+01 -4.06777039e+01 -4.05038643e+01 -4.07580147e+01 -4.02787094e+01 -4.06364326e+01 -4.15851707e+01 -4.20326653e+01 -4.15668221e+01 -4.13532944e+01 -4.11359024e+01 -4.18062859e+01 -4.19705734e+01 -4.22801628e+01 -4.20375671e+01 -4.17368622e+01 -4.15328560e+01 -4.16655464e+01 -4.19034081e+01 -4.26084366e+01 -4.24593048e+01 -4.20743217e+01 -4.21957436e+01 -4.21062355e+01 -4.19594536e+01 -4.17931366e+01 -4.17717476e+01 -4.18539009e+01 -4.22391548e+01 -4.20200348e+01 -4.20848541e+01 -4.24146080e+01 -4.30453148e+01 -4.29041100e+01 -4.29895287e+01 -4.37320709e+01 -4.34665565e+01 -4.27428932e+01 -4.22501945e+01 -4.26024055e+01 -4.31474724e+01 -4.33193512e+01 -4.36909790e+01 -4.36948090e+01 -4.38665123e+01 -4.37746887e+01 -4.31899796e+01 -4.28612366e+01 -4.31590843e+01 -4.34289703e+01 -4.35073395e+01 -4.35553970e+01 -4.31989746e+01 -4.23470306e+01 -4.28823471e+01 -4.37444916e+01 -4.31655388e+01 -4.29514351e+01 -4.35731316e+01 -4.33943367e+01 -4.33861771e+01 -4.40199242e+01 -4.34951668e+01 -4.32479248e+01 -4.32660904e+01 -4.37197227e+01 -4.30404663e+01 -4.30469093e+01 -4.31715927e+01 -4.33703537e+01 -4.31111832e+01 -4.33437996e+01 -4.40976753e+01 -4.43488922e+01 -4.34630470e+01 -4.23413963e+01 -4.23642693e+01 -4.29449577e+01 -4.35338860e+01 -4.32837906e+01 -4.28587494e+01 -4.23663216e+01 -4.29127846e+01 -4.27003708e+01 -4.22641869e+01 -4.18719940e+01 -4.29933395e+01 -4.40285149e+01 -4.27197227e+01 -4.28461456e+01 -4.27223740e+01 -4.32241364e+01 -4.31466942e+01 -4.33706551e+01 -4.30095253e+01 -4.30691528e+01 -4.27520676e+01 -4.25725250e+01 -4.19038353e+01 -4.29200211e+01 8.82515335e+01 1.75837051e+02 -3.15025543e+02 -6.91218033e+01 1.72448502e+02 -1.15231239e+02 -1.16589737e+02 -1.17100296e+02 -1.17441704e+02 -2.82704712e+02 -2.66318085e+02 1.96879292e+01 1.47086105e+02 -1.13396645e+02 -1.15346977e+02 -1.19456795e+02 -2.73233215e+02 -2.32938644e+02 -1.49925064e+02 1.12131090e+01 1.45789474e+02 -2.72433716e+02 -9.77517166e+01 7.73114548e+01 -1.15979256e+02 -1.17412315e+02 -1.18310135e+02 -1.20093102e+02 -1.17648483e+02 -1.17155670e+02 -1.18536301e+02 -1.17899742e+02 -1.17787323e+02 -1.19245186e+02 -1.19123543e+02 -1.18755524e+02 -1.18469208e+02 -1.17844612e+02 -1.19147934e+02 -2.43954910e+02 -6.23733749e+01 1.09438728e+02 -1.15841263e+02 -1.19386307e+02 -1.20459915e+02 -1.18181183e+02 -1.17442764e+02 -1.14469124e+02 -1.13174950e+02 -1.06516647e+02 2.19225815e+02 6.53241699e+02 101152008. -21495192. -79362632. 408795072. 131336840. -9.63329468e+02 -1.84940430e+02 4.81950134e+02 -9.90293884e+02 -4.08760010e+02 -1.00290932e+02 -7.51335144e+01 -3.66938141e+02 -8.47589539e+02 134777536. -13814460. 68720424. 3.53208435e+02 -9.13526154e+01 -1.42137604e+02 -6.35426331e+01 -3.91876259e+01 -3.72930946e+01 -3.81075630e+01 -3.39149971e+01 -3.32036057e+01 -3.43599548e+01 -9.54562607e+01 -5.61767530e+00 -3.29174042e+01 -1.07582664e+02 2.14530430e+01 3.30342722e+00 -3.14793530e+01 -3.09322948e+01 -3.09333801e+01 -3.07664108e+01 -3.06270638e+01 -3.04055328e+01 -3.02125530e+01 -3.00990620e+01 -2.98552208e+01 -2.96464367e+01 -2.94744778e+01 -2.92701645e+01 -2.90552235e+01 -2.88375854e+01 -2.86044235e+01 -2.83963394e+01 -2.81844769e+01 -2.79744873e+01 -2.77793045e+01 -2.75683193e+01 -2.73754139e+01 -2.71716366e+01 -2.69524727e+01 -2.67239246e+01 -2.65155067e+01 -2.62812443e+01 -2.60400124e+01 -2.58433399e+01 -2.56891899e+01 -2.55383949e+01 -2.53431034e+01 -2.51160908e+01 -2.48937283e+01 -2.46665382e+01 -2.44674149e+01 -2.42617512e+01 -2.40270138e+01 -2.37892761e+01 -2.35553513e+01 -2.33133240e+01 -2.31317272e+01 -2.29020081e+01 -2.26517696e+01 -2.23998222e+01 -2.21649952e+01 -2.19464951e+01 -2.17544460e+01 -2.15008945e+01 -2.12511978e+01 -2.11117897e+01 -2.09321270e+01 -2.06403522e+01 -2.03856678e+01 -2.02376347e+01 -1.98570671e+01 -1.94923458e+01 -1.93393326e+01 -1.91425400e+01 -1.89222202e+01 -1.87086678e+01 -1.84527626e+01 -1.81006393e+01 -1.79117661e+01 -1.76807995e+01 -1.74725208e+01 -1.71736965e+01 -1.69088593e+01 -1.66070557e+01 -1.62859001e+01 -1.61650734e+01 -1.59440165e+01 -1.57737980e+01 -1.54133310e+01 -1.51760235e+01 -1.52622252e+01 -1.50404940e+01 -1.41856422e+01 -1.38665619e+01 -1.38303823e+01 -1.37491446e+01 -1.34976645e+01 -1.33338223e+01 -1.30674162e+01 -1.25566387e+01 -1.21603680e+01 -1.20636797e+01 -1.17313070e+01 -1.16286516e+01 -1.13911457e+01 -1.11242857e+01 -1.11176643e+01 -1.07767878e+01 -9.49841881e+00 -9.38517666e+00 -9.83591938e+00 -9.75617504e+00 -9.89219284e+00 -9.65779114e+00 -9.08631134e+00 -9.40695381e+00 -9.19823265e+00 -7.34899521e+00 -6.48834372e+00 -6.63016129e+00 -6.99451923e+00 -6.47682381e+00 -6.12263823e+00 -6.17613173e+00 -6.12299776e+00 -5.88533735e+00 -5.67742634e+00 -5.32673979e+00 -4.94388342e+00 -4.63197279e+00 -4.30978870e+00 -3.98165965e+00 -3.67559576e+00 -3.58079410e+00 -3.55973363e+00 -3.65972805e+00 -3.64555073e+00 -3.20757341e+00 -2.49683809e+00 -2.29877234e+00 -2.62616324e+00 -2.86286569e+00 -2.51056671e+00 -5.13989830e+00 -8.78588557e-01 2.67336345e+00 8.14688765e-03 5.17549038e-01 -6.76595509e-01 -1.28878987e+00 -2.09900212e+00 -1.60698116e+00 6.63507760e-01 2.78790331e+00 3.53507757e+00 3.14767218e+00 2.29192162e+00 2.41767573e+00 2.77026391e+00 2.99300981e+00 2.57957101e+00 2.95156932e+00 2.89044809e+00 3.53525209e+00 3.07271624e+00 -1.11950359e+01 -1.76793671e+01 -4.13074112e+00 -1.51813934e+02 -2.59483551e+02 -2.36545296e+01 -4.20534592e+01 -9.55713501e+01 -1.66758102e+02 -9.07993774e+02 -2.21079175e+03 -58799652. 47113444. 1.53215100e+03 6.37002319e+02 -1.43346376e+01 -1.35887642e+01 -1.30630379e+01 -1.32825584e+01 -1.14019556e+01 -6.80490303e+00 -9.27553749e+00 -1.03040466e+01 -7.73737049e+00 -8.62203884e+00 -6.39266491e+00 -7.29959822e+00 -8.60451412e+00 -7.93119097e+00 3.09938782e+02 1.25025110e+01 -3.02447235e+02 4.81757317e+01 -6.28593018e+02 -2.44084930e+02 9.15346863e+02 4.02999229e+01 8.09021072e+01 8.37792282e+01 2.65353737e+01 3.37831177e+02 2.14819626e+02 1.59951229e+01 1.59582634e+01 -1.71123856e+02 -3.01236908e+02 1.52002132e+00 -4.79470682e+00 -2.30022106e+01 -1.20199356e+02 -1.05186975e+03 -4.71193115e+03 -117234712. 0. 0. 0. 0. 0. 0. 0. 0. 0. -208640960. -208640960. -208640960. 0. 0. 0. 0. -163331632. -163331632. -163331632. 0. 0. -22548212. -9.95693812e+05 -1.00007012e+06 -3.83615025e+06 258651632. -315742368. 291674752. 291674752. 291674752. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.34037371e+10 -2.34037371e+10 -2.34037371e+10 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. -1269522176. -1269522176. -1269522176. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1070082752. -1070082752. -1070082752. 0. 0. 0. 0. 0. 0. 0. 0. 0. -299497312. 31874760. -1.61245250e+05 19978098. 39169020. -45109816. 2.89121450e+06 -112001728. 2.08310181e+03 8.04925308e+01 -3.70314868e+03 1.62510327e+03 4.15603076e+03 4.15603076e+03 -12904282. 66773756. 66773756. 110947320. 0. 0. 0. 0. -230937376. -230937376. -230937376. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.41915771e+10 1.41915771e+10 1.41915771e+10 0. 0. 0. 0. 0. 0. 0. -202396224. -202396224. -202396224. 0. 348427424. 43626224. 4.61062250e+06 26787830. 28836338. 2.19325903e+03 9.05063904e+02 9.44977264e+01 9.22619095e+01 8.72815018e+01 8.29410172e+01 8.80868301e+01 -6.13309570e+02 -1.63273889e+03 2433462. 16844692. 1603474432. 1.43568578e+05 -1.51464246e+03 -7.78744751e+02 8129201. 17316812. 16476392. 9.15052185e+02 7.53367233e+01 -7.40845703e+02 1.94223035e+03 8.28484375e+02 9.56491852e+01 9.61798553e+01 9.78198242e+01 9.72384796e+01 9.80506592e+01 1.01842812e+02 1.58116531e+02 -4.22634338e+02 -1.30415161e+03 4.70678076e+03 -68582208. 65399000. 0. 0. 3.03570234e+04 -1.24332739e+03 -6.39604980e+02 -59547860. -69662304. -26793158. 92265672. 38447048. 12121488. 1.73395386e+03 7.39679199e+02 1.10278740e+02 3.05378571e+02 1.85230896e+02 3.32957191e+01 3.33486443e+01 3.34636192e+01 3.34415207e+01 3.32737312e+01 3.31526833e+01 3.26109009e+01 3.23711052e+01 3.26284714e+01 3.30539322e+01 3.32269287e+01 3.34277611e+01 3.36183319e+01 3.33244705e+01 3.27615585e+01 3.31574783e+01 3.32177048e+01 3.33491974e+01 3.30149498e+01 3.35097160e+01 3.33318100e+01 -7.36630096e+01 -1.40168411e+02 2.55240555e+02 1.54870895e+02 3.20663147e+01 3.26532784e+01 3.28276711e+01 3.29852371e+01 -6.49329987e+01 -1.23294815e+02 2.41025040e+02 1.47129959e+02 3.25001793e+01 3.27413101e+01 3.30449028e+01 3.28026199e+01 3.26183090e+01 3.26347504e+01 3.27123070e+01 3.27477646e+01 3.27396584e+01 3.28608246e+01 3.27497063e+01 3.26302071e+01 3.24998322e+01 3.28218269e+01 3.29587555e+01 3.27807999e+01 3.24626846e+01 3.22902679e+01 3.23896599e+01 3.23683929e+01 3.07691174e+01 3.08951550e+01 3.42292709e+01 3.40913506e+01 3.21942940e+01 3.22024956e+01 3.21414871e+01 3.21807060e+01 3.21379662e+01 3.21021500e+01 3.19918461e+01 3.20378494e+01 3.20541039e+01 3.20058746e+01 3.19161301e+01 3.18528900e+01 3.17834091e+01 3.16497993e+01 3.16783257e+01 3.16358566e+01 3.14887657e+01 3.14562626e+01 3.14210796e+01 3.13579044e+01 3.13212662e+01 3.10878658e+01 3.10190067e+01 3.09160156e+01 3.08925610e+01 3.07997513e+01 3.07191315e+01 3.06619186e+01 3.06142693e+01 3.04621620e+01 3.04333248e+01 3.04381466e+01 3.03086472e+01 3.02117348e+01 3.01848011e+01 3.01436768e+01 2.99791279e+01 2.99354076e+01 2.98823433e+01 2.97815838e+01 2.96535149e+01 2.95594883e+01 2.94524937e+01 2.93878193e+01 2.92756996e+01 2.91437721e+01 2.90156326e+01 2.89397392e+01 2.88737850e+01 2.87884769e+01 2.86893005e+01 2.85924015e+01 2.84819412e+01 2.83682671e+01 2.82592278e+01 2.81778297e+01 2.80877686e+01 2.79736748e+01 2.78572330e+01 2.77214470e+01 2.75945702e+01 2.74890213e+01 2.73936348e+01 2.72976589e+01 2.71854477e+01 2.70760956e+01 2.69623280e+01 2.68345070e+01 2.66986046e+01 2.66305656e+01 2.65094337e+01 2.63956604e+01 2.62757607e+01 2.60838108e+01 2.59786816e+01 2.58870068e+01 2.58145714e+01 2.56800385e+01 2.55545254e+01 2.54127388e+01 2.52422409e+01 2.51372528e+01 2.50440903e+01 2.48593616e+01 2.46892357e+01 2.45347557e+01 2.44963112e+01 2.42568436e+01 2.41354809e+01 2.40071697e+01 2.38236656e+01 2.36718063e+01 2.34828148e+01 2.34042797e+01 2.36246700e+01 2.35168705e+01 2.20877228e+01 2.04988937e+01 -2.58073139e+01 -4.94476929e+01 1.09333199e+02 1.10842140e+02 1.07077858e+02 1.45832138e+02 8.92633820e+01 1.70363235e+01 1.36438385e+02 3.54193382e+01 4.09299812e+01 4.19745605e+02 -21796014. -58903556. 49549188. 5.84994727e+04 1974223616. -373007904. 0. 0. 0. 0. 0. 0. -5.60107148e+04 2.61273364e+03 1.27382861e+03 1.38452425e+06 3.78554297e+03 7.02809375e+03 1.84604082e+04 9267628. 1.20125412e+06 5.46767438e+05 5.53489850e+06 3.74871216e+03 1.87359668e+03 5.30009570e+03 6.13708557e+02 2.00942322e+03 2.66021289e+03 -3.35302429e+02 3.98184448e+02 4.17823334e+02 -2.19842957e+02 -2.11843323e+02 2.36577206e+01 1.98696182e+02 1.53859619e+02 2.91562958e+02 2.11027069e+02 2.14124115e+02 4.45861420e+02 3.61964600e+02 2.33864517e+02 2.72032196e+02 1.36999927e+03 -2.97654816e+02 2.63312164e+02 1.42253296e+03 2.04539023e+04 -20505436. 3.81468875e+05 2.05531475e+06 5558920. 4.01657850e+06 -22403872. -76137152. -37140264. -23039426. -109787376. 17467412. 38555604. 20179576. -15140391. -14528468. -16909800. -40866256. -40941412. 28563646. -1.40033813e+03 -5.50630249e+02 5.39441605e+01 -2.52189697e+02 -1.47341537e+02 7.07291079e+00 5.93671179e+00 5.83344555e+00 5.88271761e+00 5.70281601e+00 5.80497408e+00 5.90052319e+00 6.24673128e+00 6.49087572e+00 6.38420725e+00 6.20768261e+00 5.72973347e+00 5.46364832e+00 5.85937881e+00 5.85983419e+00 4.98897505e+00 4.86394501e+00 4.82741690e+00 4.50123978e+00 4.00526810e+00 3.94747281e+00 4.13940477e+00 3.82708335e+00 3.38656521e+00 2.98152447e+00 2.38994551e+00 2.52460217e+00 2.43194890e+00 2.31324053e+00 2.60580230e+00 2.42357254e+00 1.77415979e+00 1.06650341e+00 9.51299667e-01 1.05156684e+00 1.03373408e+00 7.83663929e-01 -3.47623646e-01 -8.41933072e-01 6.24256134e-01 1.24717164e+00 4.04880829e-02 -1.80068743e+00 -1.79347873e+00 -8.18761647e-01 -4.45097566e-01 -6.87621653e-01 -1.69314206e+00 -1.70291448e+00 -1.68164992e+00 -2.56081963e+00 -2.40860558e+00 -2.47832632e+00 -2.75755382e+00 -3.04542756e+00 -3.11941338e+00 -3.42522120e+00 -3.67031026e+00 -3.53416228e+00 -4.02731562e+00 -3.72214651e+00 -4.35525751e+00 -5.17914820e+00 -4.28158903e+00 -5.03640461e+00 -5.90299129e+00 -4.73339224e+00 -5.14854717e+00 -5.15252781e+00 -5.53808546e+00 -5.66189718e+00 -6.77876472e+00 -7.45339727e+00 -6.24052382e+00 -6.30757475e+00 -7.81160259e+00 -7.95082808e+00 -7.63557816e+00 -7.90049601e+00 -7.84292603e+00 -7.61081457e+00 -8.40194416e+00 -8.46430492e+00 -8.73137856e+00 -9.23449612e+00 -9.49870777e+00 -9.76848888e+00 -9.81168079e+00 -9.43455791e+00 -9.71714687e+00 -1.04350224e+01 -1.04462862e+01 -1.03747234e+01 -1.13172026e+01 -1.03809309e+01 -1.08022041e+01 -1.22037039e+01 -1.22603283e+01 -1.24482803e+01 -1.19013548e+01 -1.12909822e+01 -1.28139868e+01 -1.34480715e+01 -1.32001991e+01 -1.28559427e+01 -1.29008884e+01 -1.18731556e+01 -1.20645781e+01 -1.35335693e+01 -1.38716335e+01 -1.41644354e+01 -1.43474607e+01 -1.45139732e+01 -1.46123295e+01 -1.48931694e+01 -1.49197502e+01 -1.54974947e+01 -1.56331520e+01 -1.56091375e+01 -1.57024336e+01 -1.59617920e+01 -1.57246914e+01 -1.50611639e+01 -1.56486206e+01 -1.77466507e+01 -1.78636074e+01 -1.71529922e+01 -1.70997429e+01 -1.69963131e+01 -1.73714943e+01 -1.74767513e+01 -1.78950825e+01 -1.74937801e+01 -1.73154335e+01 -1.79395828e+01 -1.82200794e+01 -1.85189056e+01 -1.86787910e+01 -1.90988064e+01 -1.93525238e+01 -1.95842953e+01 -1.94272041e+01 -1.92569656e+01 -1.94704094e+01 -1.99184494e+01 -2.00355034e+01 -2.01733150e+01 -2.02541714e+01 -2.04875221e+01 -2.04851894e+01 -2.09101295e+01 -2.13013821e+01 -2.16621761e+01 -2.10598850e+01 -2.13708420e+01 -2.20838890e+01 -2.22592430e+01 -2.20815105e+01 -2.19764118e+01 -2.20704021e+01 -2.24659500e+01 -2.25192680e+01 -2.29892673e+01 -2.30557880e+01 -2.28082714e+01 -2.30112534e+01 -2.34701023e+01 -2.35552044e+01 -2.30627060e+01 -2.30619869e+01 -2.35133095e+01 -2.39674358e+01 -2.41274509e+01 -2.35661278e+01 -2.38009682e+01 -2.44490852e+01 -2.45760517e+01 -2.45029984e+01 -2.44557590e+01 -2.44930649e+01 -2.48542194e+01 -2.49124718e+01 -2.54711151e+01 -2.54735336e+01 -2.56645870e+01 -2.58740120e+01 -2.61624336e+01 -2.60598240e+01 -2.59582157e+01 -2.60521088e+01 -2.60694771e+01 -2.66113758e+01 -2.66828995e+01 -2.71964741e+01 -2.68672047e+01 -2.70156059e+01 -2.64195900e+01 -2.64253006e+01 -2.68694782e+01 -2.73051853e+01 -2.76585312e+01 -2.75133572e+01 -2.77674942e+01 -2.77162552e+01 -2.76887398e+01 -2.76631317e+01 -2.82485294e+01 -2.87230282e+01 -2.81913223e+01 -2.83181057e+01 -2.85133095e+01 -2.93477077e+01 -2.91711464e+01 -2.88897190e+01 -2.89244881e+01 -2.88382244e+01 -2.89069805e+01 -2.91826515e+01 -2.92232475e+01 -2.96163292e+01 -2.95968876e+01 -2.96997604e+01 -2.90035191e+01 -2.97852249e+01 -3.03853168e+01 -2.96658878e+01 -3.01683598e+01 -3.07352066e+01 -3.02925625e+01 -3.08396492e+01 -3.13080063e+01 -3.11408100e+01 -2.99800720e+01 -2.99685841e+01 -3.02053394e+01 -3.05298862e+01 -3.11769466e+01 -3.11383934e+01 -3.08982239e+01 -3.05765057e+01 -3.07422771e+01 -3.05333958e+01 -3.11342983e+01 -3.09760551e+01 -3.08775883e+01 -3.12788315e+01 -3.16970158e+01 -3.16660595e+01 -3.19037285e+01 -3.20678406e+01 -3.16957340e+01 -3.18149834e+01 -3.15313969e+01 -3.14916229e+01 -3.07902584e+01 -3.12391624e+01 -3.20356598e+01 -3.17692547e+01 -3.18037815e+01 -3.08747692e+01 -3.05860233e+01 -3.18673363e+01 1.10214020e+02 2.05082977e+02 -1.07785431e+02 -1.09836906e+02 -1.08524216e+02 -1.02589577e+02 -1.10386513e+02 4.33086212e+02 1.19924243e+03 -1.75342371e+03 -2.15771545e+02 1.18278235e+03 26104378. -17352914. 24793584. 48642496. -1.11016748e+04 -2.31280591e+03 -2.68373596e+02 1.41377380e+03 -11396260. -5.33868450e+06 -67458808. -1.34121465e+04 -5.07749854e+03 -1.11573376e+03 -1.55759781e+02 9.60086365e+02 -8.51973438e+03 -2.71904712e+03 1.09546448e+03 -18544556. 22900240. 33351990. -63242752. 96568344. 34836244. 470429792. 71541480. 20053986. 124439856. 20961814. -20871610. -25539894. -5.72230713e+02 -6.82263641e+01 9.79439697e+01 -1.96411636e+02 6.74885010e+02 -11944194. -3.31638750e+06 -4778284. -82562784. -8.19561250e+06 118972680. -24202808. -4.63812531e+02 -9.17881042e+02 -4.62446367e+04 0. 0. 0. 0. 0. -95126408. -95126408. -95126408. -109223440. 27409826. -13656202. -217256720. -55575880. -27044612. -4.13756622e+02 -1.79700333e+02 -3.52632446e+01 -3.50024529e+01 -1.27144661e+01 -9.81311340e+01 -1.79793182e+02 -1.16476410e+02 3.43151512e+01 -5.63902969e+01 -1.52570679e+02 3.17955837e+01 9.87025547e+00 -3.18672485e+01 -3.12168999e+01 -3.12904949e+01 -3.13161392e+01 -3.11815414e+01 -3.10778294e+01 -3.10316372e+01 -3.08527889e+01 -3.09041290e+01 -3.09423752e+01 -3.07732601e+01 -3.06753864e+01 -3.06315536e+01 -3.06556683e+01 -3.05630207e+01 -3.03491249e+01 -3.02975845e+01 -3.02041588e+01 -3.01025600e+01 -3.00774574e+01 -3.00218983e+01 -2.99183064e+01 -2.97991219e+01 -2.97597885e+01 -2.96797256e+01 -2.95721054e+01 -2.94181080e+01 -2.92951450e+01 -2.92141590e+01 -2.91381454e+01 -2.90228271e+01 -2.88986855e+01 -2.87579365e+01 -2.86301994e+01 -2.85263748e+01 -2.84471760e+01 -2.83385124e+01 -2.82538471e+01 -2.81342392e+01 -2.80168839e+01 -2.78946285e+01 -2.77884960e+01 -2.76987247e+01 -2.75647621e+01 -2.74574203e+01 -2.73644047e+01 -2.72731991e+01 -2.71433010e+01 -2.69806938e+01 -2.68925934e+01 -2.67707710e+01 -2.66902637e+01 -2.65987949e+01 -2.65354347e+01 -2.64216099e+01 -2.63412209e+01 -2.62124825e+01 -2.60644264e+01 -2.57825642e+01 -2.59068661e+01 -2.55249214e+01 -2.52242470e+01 -2.52037735e+01 -2.51099110e+01 -2.49494457e+01 -2.47610626e+01 -2.46150188e+01 -2.45415421e+01 -2.44204044e+01 -2.43457355e+01 -2.41604366e+01 -2.39427853e+01 -2.37955418e+01 -2.35808544e+01 -2.34363327e+01 -2.34211922e+01 -2.33457069e+01 -2.32374611e+01 -2.30191689e+01 -2.28594227e+01 -2.30465202e+01 -2.27860641e+01 -2.20525055e+01 -2.20484467e+01 -2.22360229e+01 -2.21869164e+01 -2.17748947e+01 -2.17286243e+01 -2.16410980e+01 -2.13343868e+01 -2.11395893e+01 -2.09504642e+01 -2.07207165e+01 -2.07506256e+01 -2.04875050e+01 -2.02254276e+01 -2.03870964e+01 -2.01942654e+01 -1.95735989e+01 -1.93110390e+01 -1.96358547e+01 -1.92805443e+01 -1.95505333e+01 -1.93705235e+01 -1.91309490e+01 -1.96701469e+01 -1.93841915e+01 -1.73734703e+01 -1.68497963e+01 -1.77407131e+01 -1.79452820e+01 -1.79394226e+01 -1.76802979e+01 -1.75176544e+01 -1.70339909e+01 -1.69498158e+01 -1.69172802e+01 -1.68524837e+01 -1.68638973e+01 -1.65893517e+01 -1.63218670e+01 -1.59739704e+01 -1.58317966e+01 -1.56814690e+01 -1.57073393e+01 -1.56184988e+01 -1.59944305e+01 -1.55930376e+01 -1.49102440e+01 -1.49011631e+01 -1.56093788e+01 -1.62468319e+01 -1.65184383e+01 -3.50619087e+01 -2.44693394e+01 4.71698093e+00 -5.14112091e+00 -1.28337641e+01 -1.36066275e+01 -1.57178917e+01 -1.40763559e+01 -8.90120125e+00 -2.96656284e+01 -2.34508724e+01 3.60309768e+00 -4.51377535e+00 -1.09314184e+01 -1.18055983e+01 -1.20470591e+01 -1.21717358e+01 -1.20486975e+01 -1.19773998e+01 -1.31071968e+01 -2.80181675e+01 -3.01728554e+01 -2.03627975e+02 -3.83774780e+02 2.53888657e+02 -6.64953384e+01 -6.80368347e+02 12111216. -9.31840312e+05 -7.02913875e+05 -4237676. 106256704. 24846358. 0. 0. 115571912. -239138544. 15968233. -21014046. 7.87166850e+06 -31939452. 22158216. -18587394. -6.34972050e+06 -15971887. 7.81233093e+02 6.51240969e+00 -7.97393616e+02 12196080. 98601536. -29528852. 1.43628296e+03 -9.69075699e+01 -1.73849414e+03 2.43010762e+04 30515686. 22869670. -95547704. 2.37869094e+05 1.18380875e+05 1.39682344e+05 -1.41149362e+06 2.14071997e+03 8.53976196e+02 -4.84118538e+01 -5.00951157e+01 -9.84890015e+02 -2.48816870e+03 63405796. 835709184. -8714612. -1.86029844e+05 -4.99730944e+09 -161156000. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -208640960. -208640960. -208640960. 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. 0. 0. 0. 0. 0. 0. 0. -2.34037371e+10 -2.34037371e+10 -2.34037371e+10 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. -1269522176. -1269522176. -507511040. -270754208. -270754208. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -535041376. -535041376. -535041376. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.54082688e+09 -3.54082688e+09 -3.54082688e+09 1155655296. 4348127. 4348127. -6452141. 33386878. 33386878. 55473660. 0. 0. 0. 0. -230937376. -230937376. -230937376. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.41915771e+10 1.41915771e+10 1.41915771e+10 0. 0. 0. 0. 0. 0. 0. -202396224. -202396224. -202396224. 0. 0. 0. 0. 0. 0. -113311184. -13548414. -3629071. 3.68873225e+06 -32110310. -4.17955525e+06 3.06138875e+06 -55973468. -47914780. 0. 0. 0. 169540176. 169540176. 169540176. 0. 0. 0. 262940768. 262940768. 262940768. -54913952. -16588549. 3.92021225e+06 5903341. -15103611. 19440576. 13298400. 80088672. 6.50912266e+04 -6940551. -194486864. 65399000. 65399000. 65399000. 0. 0. 15546382. 15546382. 15546382. 0. 0. 0. 0. 0. 0. 17749282. 9291197. 31575172. 8.95645264e+02 4.16040985e+02 7.56821442e+01 7.64133301e+01 7.71172562e+01 7.72094116e+01 7.57064133e+01 7.52436218e+01 7.42959518e+01 7.42338104e+01 7.49354324e+01 7.54365768e+01 7.58458710e+01 7.64210281e+01 7.78263702e+01 7.68145065e+01 7.63001633e+01 7.72158737e+01 7.78004456e+01 7.72738800e+01 7.64883041e+01 7.73984375e+01 7.86323700e+01 -1.44204498e+02 -3.53929291e+02 7.61481750e+02 3.53624146e+02 7.79860153e+01 7.92309036e+01 8.00468979e+01 8.07134171e+01 -1.20900429e+02 -2.99346741e+02 7.36691467e+02 3.43515564e+02 7.86364136e+01 7.95553665e+01 8.19531097e+01 8.17771225e+01 8.18103409e+01 8.21670837e+01 8.25681305e+01 8.28747330e+01 8.28635788e+01 8.30465393e+01 8.26488190e+01 8.18278503e+01 8.14268188e+01 8.25559998e+01 8.33271790e+01 8.35683365e+01 8.28519516e+01 8.23711700e+01 8.30401459e+01 8.32263718e+01 7.74514465e+01 7.76324921e+01 8.92700500e+01 8.93547897e+01 8.37930527e+01 8.45293274e+01 8.46669998e+01 8.44469299e+01 8.44119873e+01 8.48436737e+01 8.54226608e+01 8.58500824e+01 8.56997986e+01 8.57923126e+01 8.58209915e+01 8.58601379e+01 8.58134995e+01 8.52693939e+01 8.57118912e+01 8.55851898e+01 8.54380569e+01 8.57288513e+01 8.55071793e+01 8.57556992e+01 8.60827255e+01 8.60088196e+01 8.62812119e+01 8.63574295e+01 8.65181503e+01 8.64688187e+01 8.66544647e+01 8.68189926e+01 8.67583313e+01 8.63156357e+01 8.66385422e+01 8.68808594e+01 8.65876923e+01 8.65769424e+01 8.70353851e+01 8.70947189e+01 8.66210480e+01 8.65551376e+01 8.66413727e+01 8.65818176e+01 8.65388641e+01 8.64967117e+01 8.64198990e+01 8.63795471e+01 8.62564240e+01 8.60285721e+01 8.58908539e+01 8.59885788e+01 8.61246109e+01 8.61799469e+01 8.61691055e+01 8.61791687e+01 8.60760422e+01 8.60322876e+01 8.60219269e+01 8.59170761e+01 8.57072754e+01 8.54590454e+01 8.53978424e+01 8.54010391e+01 8.53729553e+01 8.54342422e+01 8.54267044e+01 8.53898697e+01 8.53088379e+01 8.51919098e+01 8.50795212e+01 8.50349579e+01 8.49683685e+01 8.51721954e+01 8.50753174e+01 8.49821472e+01 8.48945923e+01 8.44231110e+01 8.43870621e+01 8.45031052e+01 8.45109634e+01 8.43721466e+01 8.41440125e+01 8.38966675e+01 8.33926468e+01 8.34767838e+01 8.36702652e+01 8.32465057e+01 8.30622559e+01 8.27971039e+01 8.29361725e+01 8.23348083e+01 8.22524948e+01 8.23035583e+01 8.17804489e+01 8.17330093e+01 8.15564651e+01 8.12470779e+01 8.10365372e+01 8.07544937e+01 8.04366226e+01 8.02964172e+01 8.03076019e+01 8.04481735e+01 8.15022659e+01 8.40864563e+01 8.16694031e+01 7.56311111e+01 7.03343353e+01 -9.94101105e+01 -9.59075317e+02 31660784. -20962724. -20962724. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.38449453e+04 5.38449453e+04 5.38449453e+04 0. -49478088. -49478088. -49478088. 0. 0. 0. 0. 64191312. 14476741. 14476741. -2.59655150e+06 67390832. 38747496. 2.95345025e+06 -8.89755676e+02 1.28635227e+05 -4.49322510e+03 -4.17743164e+02 1.36378189e+02 3.31220428e+02 5.71981836e+03 4.37923281e+04 8.50664922e+04 5.94661719e+04 1.36468475e+06 2.12732703e+05 320696. 1.67332391e+05 55085824. 3.93682475e+06 -8.60568375e+05 -8.60568375e+05 -11012354. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -79423080. 19185700. -76148424. -6.04728516e+02 -2.61247406e+02 4.74813881e+01 4.35726662e+01 4.42916565e+01 4.57894821e+01 4.68599129e+01 4.83658791e+01 4.93061142e+01 5.01442032e+01 5.07065163e+01 5.13502502e+01 5.17577362e+01 5.12144165e+01 5.05932961e+01 5.06156960e+01 5.06641579e+01 4.97565613e+01 4.95477180e+01 4.93920403e+01 4.88440323e+01 4.71342964e+01 4.55629196e+01 4.62269096e+01 4.59292564e+01 4.51598434e+01 4.45610313e+01 4.33979721e+01 4.35150642e+01 4.26999626e+01 4.17629089e+01 4.26630020e+01 4.21095581e+01 4.13495598e+01 3.97184296e+01 3.95700111e+01 3.99832191e+01 3.97877159e+01 3.83209419e+01 3.56766968e+01 3.39754066e+01 3.77195129e+01 3.98597565e+01 3.57978897e+01 3.07381630e+01 2.92325840e+01 3.32683487e+01 3.54184341e+01 3.50037880e+01 3.21725235e+01 3.36551590e+01 3.38929520e+01 3.11475124e+01 3.09917545e+01 2.97152500e+01 2.88071957e+01 2.85132980e+01 2.86632671e+01 2.78600788e+01 2.73104515e+01 2.74157448e+01 2.77157478e+01 2.89948750e+01 2.69862080e+01 2.36915207e+01 2.73280697e+01 2.38494396e+01 2.04271889e+01 2.55595970e+01 2.41901913e+01 2.27724228e+01 2.24274998e+01 2.58710251e+01 2.20113735e+01 1.77161312e+01 2.05436268e+01 2.17938175e+01 1.78043652e+01 1.77451248e+01 1.89796543e+01 1.69076729e+01 1.77752743e+01 1.74717979e+01 1.57321606e+01 1.48121529e+01 1.42043886e+01 1.32171440e+01 1.21418858e+01 1.28607559e+01 1.20319071e+01 1.39136810e+01 1.27886791e+01 1.04477015e+01 1.18440599e+01 1.12386713e+01 8.27181530e+00 9.14618397e+00 8.08545876e+00 5.37884665e+00 5.34482813e+00 4.00914097e+00 6.39477730e+00 7.76504755e+00 2.08828425e+00 1.60731745e+00 3.91677332e+00 3.79175758e+00 2.92813897e+00 4.12137938e+00 4.13481140e+00 1.83802247e+00 9.64966536e-01 8.10170025e-02 -5.68268061e-01 -1.40598071e+00 -1.68588209e+00 -1.85935426e+00 -2.36044121e+00 -5.35304642e+00 -5.51693249e+00 -4.38822842e+00 -4.68572521e+00 -5.24251699e+00 -4.33361101e+00 -2.51743460e+00 -4.68831253e+00 -1.09507427e+01 -1.13518734e+01 -9.02908516e+00 -9.23139572e+00 -9.07237434e+00 -9.84536362e+00 -1.00564251e+01 -1.07454443e+01 -8.39331055e+00 -8.41981316e+00 -1.15652218e+01 -1.25504780e+01 -1.33838854e+01 -1.37206373e+01 -1.51683445e+01 -1.51819620e+01 -1.48936129e+01 -1.61788521e+01 -1.67768574e+01 -1.71385841e+01 -1.72911777e+01 -1.81689110e+01 -1.90245476e+01 -1.90673065e+01 -1.98201981e+01 -2.02677326e+01 -2.12167606e+01 -2.20506229e+01 -2.49330082e+01 -2.23486061e+01 -2.26864281e+01 -2.63046799e+01 -2.44566460e+01 -2.37023563e+01 -2.42857895e+01 -2.48168488e+01 -2.59176159e+01 -2.63890400e+01 -2.69691582e+01 -2.72544956e+01 -2.72779942e+01 -2.79875221e+01 -2.92104034e+01 -2.99340324e+01 -2.98651619e+01 -3.05058689e+01 -3.09596481e+01 -3.20578079e+01 -3.22899666e+01 -3.27032547e+01 -3.27356873e+01 -3.33872833e+01 -3.32018700e+01 -3.38020401e+01 -3.41785774e+01 -3.52886658e+01 -3.49690781e+01 -3.58667107e+01 -3.65575104e+01 -3.71267242e+01 -3.85960922e+01 -3.88779945e+01 -3.98169098e+01 -3.85892754e+01 -3.87353172e+01 -3.86776848e+01 -3.98275070e+01 -4.11768532e+01 -4.18965912e+01 -4.13344078e+01 -4.19484978e+01 -4.31835022e+01 -4.43926582e+01 -4.41880684e+01 -4.48589478e+01 -4.48847542e+01 -4.49953423e+01 -4.46494522e+01 -4.59692841e+01 -4.67782745e+01 -4.67668533e+01 -4.70694466e+01 -4.86080399e+01 -4.95584412e+01 -4.87539673e+01 -4.87907600e+01 -5.07588043e+01 -5.08918343e+01 -4.93852692e+01 -4.78587494e+01 -4.90777092e+01 -5.10931244e+01 -5.16641273e+01 -5.20239334e+01 -5.28036499e+01 -5.32927704e+01 -5.29752388e+01 -5.40251770e+01 -5.28772926e+01 -5.47039032e+01 -5.81728821e+01 -5.29166107e+01 -5.50957642e+01 -5.72710304e+01 -5.58877220e+01 -5.64898338e+01 -6.00615349e+01 -6.03821411e+01 -5.77471504e+01 -5.82967339e+01 -5.76079941e+01 -5.78773537e+01 -5.98744278e+01 -6.19722900e+01 -6.07887077e+01 -6.10473518e+01 -6.14520035e+01 -6.13945236e+01 -6.21770554e+01 -6.27147598e+01 -6.14620285e+01 -6.28191261e+01 -6.45033569e+01 -6.42994156e+01 -6.53822174e+01 -6.58955231e+01 -6.53281250e+01 -6.59327927e+01 -6.36051292e+01 -6.18195915e+01 -5.99252129e+01 -6.18121719e+01 -6.55878754e+01 -6.46312408e+01 -6.45739059e+01 -6.36927948e+01 -6.33033791e+01 -6.59034576e+01 2.35757629e+02 5.61596802e+02 205213904. 16502059. -24756200. -1.63722962e+06 -7.20369625e+05 -44919664. 238031488. 43313544. 43313544. 43313544. 0. 0. 0. 0. -68896688. 3.41193150e+06 3.41193150e+06 2.28073825e+06 0. 0. 0. -9408352. 74201088. -1.01076260e+04 5389721. -41867260. 1116613120. 1116613120. 1116613120. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -302337312. -302337312. 73725752. 16669606. 16669606. 0. 0. 0. 0. 0. 0. 0. 224321600. 224321600. 224321600. 0. 0. 0. 0. 0. -47563204. -47563204. -47563204. 0. 0. 0. 0. 0. 0. 73357832. -13598752. 69406176. 25791814. 2.89223816e+02 3.89948344e+00 -1.26793457e+02 -8.57795715e+01 -8.45102997e+01 -8.48811264e+01 -8.50885239e+01 -8.54672241e+01 -8.61200180e+01 -8.67112732e+01 -8.72358780e+01 -8.73921127e+01 -8.73217239e+01 -8.71944046e+01 -8.71222229e+01 -8.71927338e+01 -8.70772018e+01 -8.73341217e+01 -8.75100708e+01 -8.73449707e+01 -8.76723709e+01 -8.79219131e+01 -8.81760178e+01 -8.80877228e+01 -8.76502380e+01 -8.74828720e+01 -8.76737442e+01 -8.77062988e+01 -8.80781174e+01 -8.81822739e+01 -8.82021561e+01 -8.82161713e+01 -8.84831238e+01 -8.84786224e+01 -8.83893967e+01 -8.80742569e+01 -8.80322342e+01 -8.80002975e+01 -8.80431519e+01 -8.79105911e+01 -8.78798447e+01 -8.77098770e+01 -8.73232803e+01 -8.68599854e+01 -8.65964279e+01 -8.64087372e+01 -8.65121689e+01 -8.64280701e+01 -8.63640900e+01 -8.61121521e+01 -8.59605865e+01 -8.60135727e+01 -8.60199127e+01 -8.61507263e+01 -8.61780624e+01 -8.60208435e+01 -8.57721786e+01 -8.54217529e+01 -8.56962128e+01 -8.56670685e+01 -8.56676407e+01 -8.56545486e+01 -8.57882690e+01 -8.58531952e+01 -8.59549408e+01 -8.57435379e+01 -8.56315308e+01 -8.47364960e+01 -8.48936081e+01 -8.39610138e+01 -8.37787781e+01 -8.39101334e+01 -8.39488754e+01 -8.36021576e+01 -8.31096649e+01 -8.29873810e+01 -8.28730316e+01 -8.28618927e+01 -8.26153870e+01 -8.22418060e+01 -8.19206161e+01 -8.17744675e+01 -8.14094772e+01 -8.14783630e+01 -8.17929611e+01 -8.16659470e+01 -8.15029678e+01 -8.13452148e+01 -8.10789261e+01 -8.18238602e+01 -8.10079041e+01 -7.95391922e+01 -7.98878021e+01 -8.06751022e+01 -8.06075363e+01 -7.87535858e+01 -7.87888870e+01 -7.95746460e+01 -7.86823273e+01 -7.87334595e+01 -7.82625961e+01 -7.80648727e+01 -7.79983673e+01 -7.74313278e+01 -7.73469086e+01 -7.78628311e+01 -7.79184189e+01 -7.72654877e+01 -7.66857910e+01 -7.67638321e+01 -7.71130219e+01 -7.72636490e+01 -7.60456696e+01 -7.47503357e+01 -7.66689606e+01 -7.62429123e+01 -7.06976318e+01 -6.99017334e+01 -7.34435120e+01 -7.35890961e+01 -7.41669540e+01 -7.34664307e+01 -7.27980804e+01 -7.18928070e+01 -7.12004013e+01 -7.17752533e+01 -7.15434723e+01 -7.17319489e+01 -7.13297348e+01 -7.16027222e+01 -7.13443375e+01 -7.10258484e+01 -7.10662689e+01 -7.08635559e+01 -7.01656265e+01 -7.07270966e+01 -6.98530807e+01 -6.89240036e+01 -6.90577087e+01 -7.17541046e+01 -7.51760254e+01 -7.52733459e+01 -1.42288147e+02 -1.01259247e+02 -1.05235703e-01 -3.96889343e+01 -6.16134796e+01 -6.79234161e+01 -7.73625793e+01 -6.75483932e+01 -5.05322838e+01 -1.22613861e+02 -1.01861191e+02 -1.12381611e+01 -3.85096931e+01 -5.99056015e+01 -6.52738419e+01 -6.62207565e+01 -6.67765350e+01 -6.56611633e+01 -6.62500610e+01 -6.98787842e+01 -1.23222672e+02 -1.42798538e+02 -7.39684753e+02 -1.74621094e+03 3.91324097e+02 1.04633521e+03 2.95962871e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -134289232. -134289232. -134289232. 0. 0. 0. 24663148. 24663148. 24663148. 0. 0. 0. 0. 0. 0. 0. 0. 101137928. -14222967. -9147435. -1.61231475e+06 -3.20422625e+06 -62494116. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -104320480. -104320480. -104320480. 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. 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. 0. 0. 0. 0. 0. 0. 0. -634761088. -634761088. 259436416. -270754208. -270754208. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_M_8.xml ================================================ 16 1024
f
6.37843650e+06 5.05789337e+02 3.35940216e+02 3.35663116e+02 3.35397949e+02 3.35138153e+02 3.34996307e+02 3.35646973e+02 3.35750916e+02 3.35685242e+02 3.34807159e+02 3.34272308e+02 3.33752777e+02 3.33086731e+02 3.32714996e+02 3.32554596e+02 3.32700928e+02 3.32753662e+02 3.32919922e+02 3.33022034e+02 3.32846741e+02 3.32562836e+02 3.32399902e+02 3.32209320e+02 3.32142517e+02 3.32080566e+02 3.32302521e+02 3.32387909e+02 3.32196045e+02 3.32075165e+02 3.31928497e+02 3.32020325e+02 3.32032684e+02 3.32340973e+02 3.32872406e+02 3.33395996e+02 3.33799103e+02 3.33897827e+02 3.34052856e+02 3.34160248e+02 3.34094360e+02 3.33805389e+02 3.33708527e+02 3.33637329e+02 3.33596588e+02 3.33617096e+02 3.33668488e+02 3.33620117e+02 3.33310364e+02 3.33192596e+02 3.33198517e+02 3.33250092e+02 3.33403687e+02 3.33373901e+02 3.33388641e+02 3.33511749e+02 3.33558777e+02 3.33608734e+02 3.33431061e+02 3.33468475e+02 3.33263947e+02 3.33018890e+02 3.32726013e+02 3.32674744e+02 3.32499542e+02 3.32365845e+02 3.32248657e+02 3.32203644e+02 3.32372253e+02 3.32521667e+02 3.32747498e+02 3.32946686e+02 3.32886322e+02 3.33036316e+02 3.33070618e+02 3.33403839e+02 3.33420959e+02 3.33442841e+02 3.33507385e+02 3.33872437e+02 3.34175629e+02 3.34333282e+02 3.34415192e+02 3.35441071e+02 3.36332336e+02 3.32482483e+02 3.38210236e+02 3.15665558e+02 3.58254608e+02 6.28888306e+02 2.58227173e+03 -1.75904156e+05 -3.52738483e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 93655144. 33208374. 6.53678688e+05 8.33832275e+02 4.36536163e+02 3.19294891e+02 3.31487305e+02 3.41594696e+02 3.64662933e+02 3.80923065e+02 3.64971100e+02 3.35842468e+02 3.22075562e+02 3.31172272e+02 3.32717560e+02 3.32598450e+02 3.32257202e+02 3.31888916e+02 3.31743500e+02 3.31411224e+02 3.31094727e+02 3.30539490e+02 3.30200806e+02 3.29824036e+02 3.30165344e+02 3.40231781e+02 3.53839203e+02 3.70423126e+02 3.78897614e+02 3.88182343e+02 3.97140472e+02 3.99524139e+02 3.87125793e+02 3.59489410e+02 3.27451202e+02 2.99074371e+02 2.85028564e+02 2.81510529e+02 2.88763763e+02 2.99893066e+02 3.14660889e+02 3.29847778e+02 3.46731110e+02 3.62942322e+02 3.78424042e+02 3.87638184e+02 3.82490967e+02 3.66418732e+02 3.48125885e+02 3.37156097e+02 3.32685760e+02 3.31444946e+02 3.31366852e+02 3.31254822e+02 3.31159363e+02 3.30690796e+02 3.29443817e+02 3.27002991e+02 3.22633545e+02 3.15342072e+02 3.07620667e+02 3.02958313e+02 3.01856476e+02 3.02667389e+02 3.04720856e+02 3.09092804e+02 3.15356567e+02 3.21734375e+02 3.26154541e+02 3.28652252e+02 3.29469666e+02 3.29810242e+02 3.29808105e+02 3.29727051e+02 3.29470154e+02 3.29413788e+02 3.29419342e+02 3.29673584e+02 3.29799957e+02 3.29919647e+02 3.29850220e+02 3.29913147e+02 3.29959991e+02 3.30096283e+02 3.29947998e+02 3.29982178e+02 3.29996704e+02 3.30032959e+02 3.30022491e+02 3.30103302e+02 3.30192352e+02 3.30145966e+02 3.30101593e+02 3.30330475e+02 3.30378540e+02 3.30440704e+02 3.30241699e+02 3.30277710e+02 3.30156464e+02 3.30060822e+02 3.29981171e+02 3.29914093e+02 3.29983917e+02 3.29754272e+02 3.29490356e+02 3.29165527e+02 3.28968933e+02 3.28948273e+02 3.28991241e+02 3.29272461e+02 3.29518372e+02 3.29718781e+02 3.29786072e+02 3.29871399e+02 3.29788330e+02 3.29676880e+02 3.29550873e+02 3.29542175e+02 3.29484497e+02 3.29549194e+02 3.29791321e+02 3.30104645e+02 3.30271027e+02 3.30217407e+02 3.30017242e+02 3.29820648e+02 3.29718384e+02 3.29781769e+02 3.29771729e+02 3.29873779e+02 3.29832031e+02 3.29940369e+02 3.30018219e+02 3.29974457e+02 3.29877014e+02 3.29703796e+02 3.29606171e+02 3.29531128e+02 3.29462372e+02 3.29480164e+02 3.29447662e+02 3.29378784e+02 3.29385437e+02 3.29431458e+02 3.29593933e+02 3.29667572e+02 3.29756104e+02 3.29644714e+02 3.29565277e+02 3.29443146e+02 3.29445648e+02 3.29450439e+02 3.29551025e+02 3.29606323e+02 3.29830597e+02 3.30051300e+02 3.30320404e+02 3.30266937e+02 3.30384033e+02 3.30277954e+02 3.30431458e+02 3.30206818e+02 3.30155670e+02 3.30004517e+02 3.30007568e+02 3.29995850e+02 3.29928040e+02 3.29777710e+02 3.29544830e+02 3.29537567e+02 3.29542847e+02 3.29672852e+02 3.29703339e+02 3.29886017e+02 3.29841370e+02 3.29867401e+02 3.29885101e+02 3.29953461e+02 3.29944458e+02 3.29924469e+02 3.30000580e+02 3.30003845e+02 3.30001678e+02 3.29696136e+02 3.29638000e+02 3.29635864e+02 3.29811920e+02 3.29644135e+02 3.29303772e+02 3.29054047e+02 3.29009521e+02 3.28944458e+02 3.28796051e+02 3.28958282e+02 3.29093567e+02 3.29147766e+02 3.29041870e+02 3.28969971e+02 3.28656128e+02 3.28392151e+02 3.28120850e+02 3.28127686e+02 3.28006287e+02 3.28021637e+02 3.28045410e+02 3.28174225e+02 3.28310608e+02 3.28414001e+02 3.28412262e+02 3.28552429e+02 3.28725037e+02 3.29114563e+02 3.29194427e+02 3.29341675e+02 3.29330811e+02 3.29249573e+02 3.29171082e+02 3.29142700e+02 3.29158569e+02 3.29203857e+02 3.29189911e+02 3.29073792e+02 3.28927551e+02 3.28647247e+02 3.28700470e+02 3.28760101e+02 3.29020233e+02 3.29130219e+02 3.29159698e+02 3.29142792e+02 3.29099274e+02 3.28992126e+02 3.28960083e+02 3.29056152e+02 3.29120911e+02 3.29045197e+02 3.28920959e+02 3.28833038e+02 3.28818878e+02 3.28878174e+02 3.28976044e+02 3.28898499e+02 3.28899200e+02 3.28888031e+02 3.29128967e+02 3.29218872e+02 3.29170563e+02 3.29053497e+02 3.29030884e+02 3.29037781e+02 3.29048584e+02 3.29031097e+02 3.28969269e+02 3.28940613e+02 3.28901489e+02 3.28837463e+02 3.28894073e+02 3.28871796e+02 3.28806610e+02 3.28640503e+02 3.28472382e+02 3.28444916e+02 3.28533844e+02 3.28769928e+02 3.28913971e+02 3.28903168e+02 3.28728821e+02 3.28616089e+02 3.28604797e+02 3.28733215e+02 3.28830231e+02 3.28819061e+02 3.28675751e+02 3.28651581e+02 3.28560120e+02 3.28494110e+02 3.28398926e+02 3.28385040e+02 3.28458527e+02 3.28442413e+02 3.28475067e+02 3.28463409e+02 3.28482910e+02 3.28517670e+02 3.28543976e+02 3.28707794e+02 3.28846222e+02 3.28979614e+02 3.29101257e+02 3.29216675e+02 3.29361633e+02 3.29524170e+02 3.29699036e+02 3.29815674e+02 3.30020203e+02 3.30085327e+02 3.30222931e+02 3.30178192e+02 3.30290680e+02 3.30239227e+02 3.30203094e+02 3.29974274e+02 3.29842682e+02 3.29702026e+02 3.29451111e+02 3.29255432e+02 3.29061523e+02 3.29076813e+02 3.28976135e+02 3.28985779e+02 3.29014221e+02 3.29152496e+02 3.29122498e+02 3.29126526e+02 3.29129578e+02 3.29154022e+02 3.29132111e+02 3.28890045e+02 3.28576904e+02 3.28358124e+02 3.28280518e+02 3.28423553e+02 3.28378540e+02 3.28469910e+02 3.28462616e+02 3.28636871e+02 3.28688232e+02 3.28745880e+02 3.28872223e+02 3.29006744e+02 3.29219666e+02 3.29336792e+02 3.29441925e+02 3.29456635e+02 3.29480377e+02 3.29458252e+02 3.29432922e+02 3.29676239e+02 3.29911346e+02 3.30122314e+02 3.29919159e+02 3.29834686e+02 3.29719482e+02 3.29642334e+02 3.29465302e+02 3.29363464e+02 3.29278625e+02 3.29128601e+02 3.29079041e+02 3.29065277e+02 3.29037537e+02 3.29123505e+02 3.29100220e+02 3.29171417e+02 3.29075317e+02 3.29054321e+02 3.29188599e+02 3.29076233e+02 3.29140320e+02 3.28957031e+02 3.28889496e+02 3.28668793e+02 3.28570099e+02 3.28638702e+02 3.28707153e+02 3.28746216e+02 3.28769562e+02 3.28793213e+02 3.28877136e+02 3.29098480e+02 3.29145386e+02 3.29181244e+02 3.28875183e+02 3.28797546e+02 3.28690186e+02 3.28799805e+02 3.28742065e+02 3.28568359e+02 3.28376099e+02 3.28412903e+02 3.28553894e+02 3.28692963e+02 3.28830109e+02 3.28929230e+02 3.28758209e+02 3.28639709e+02 3.28528687e+02 3.28757324e+02 3.28926239e+02 3.28962524e+02 3.28947876e+02 3.28974945e+02 3.29082336e+02 3.29071838e+02 3.29079681e+02 3.29156036e+02 3.29074615e+02 3.28980560e+02 3.28968292e+02 3.29240143e+02 3.29229156e+02 3.29315735e+02 3.29161652e+02 3.29178619e+02 3.29238525e+02 3.29583099e+02 3.29714447e+02 3.29781555e+02 3.29847595e+02 3.29997803e+02 3.29865021e+02 3.29660431e+02 3.29621613e+02 3.29413788e+02 3.29354187e+02 3.29119293e+02 3.29151733e+02 3.29057129e+02 3.28964844e+02 3.28926880e+02 3.28742279e+02 3.28793579e+02 3.28680511e+02 3.28684814e+02 3.28702606e+02 3.28902069e+02 3.29083221e+02 3.29079926e+02 3.29002808e+02 3.29008911e+02 3.28776459e+02 3.28663879e+02 3.28564148e+02 3.28675140e+02 3.28773621e+02 3.28732880e+02 3.29080627e+02 3.29041534e+02 3.29069550e+02 3.28873199e+02 3.28970337e+02 3.29212067e+02 3.29612030e+02 3.29815704e+02 3.29587982e+02 3.29360870e+02 3.29348633e+02 3.29318787e+02 3.29078766e+02 3.28944855e+02 3.29034515e+02 3.29231110e+02 3.29613708e+02 3.29927460e+02 3.30216461e+02 3.30174561e+02 3.30261932e+02 3.29968811e+02 3.29530670e+02 3.29054443e+02 3.28948090e+02 3.28837250e+02 3.28912933e+02 3.28728668e+02 3.28925110e+02 3.29037933e+02 3.29327850e+02 3.29419128e+02 3.29454193e+02 3.29201569e+02 3.28921356e+02 3.28357239e+02 3.28292175e+02 3.28302551e+02 3.28472321e+02 3.28364990e+02 3.28358521e+02 3.28188873e+02 3.28308929e+02 3.28549927e+02 3.29042725e+02 3.29422546e+02 3.29650909e+02 3.29666931e+02 3.29623993e+02 3.29582397e+02 3.29722443e+02 3.29945343e+02 3.30100861e+02 3.30152191e+02 3.30163147e+02 3.29969330e+02 3.29940002e+02 3.30000916e+02 3.30229004e+02 3.30356506e+02 3.30249573e+02 3.30424561e+02 3.30777649e+02 3.31111359e+02 3.31428894e+02 3.31680176e+02 3.31961792e+02 3.31849030e+02 3.31426483e+02 3.31053314e+02 3.30804138e+02 3.30702423e+02 3.30534515e+02 3.30273834e+02 3.29968353e+02 3.29749664e+02 3.29790527e+02 3.30002472e+02 3.30292755e+02 3.30186127e+02 3.30040802e+02 3.29847839e+02 3.29878723e+02 3.29808685e+02 3.29769531e+02 3.30058777e+02 3.30347321e+02 3.30688782e+02 3.30883087e+02 3.31154114e+02 3.31431183e+02 3.31552826e+02 3.31469635e+02 3.31359863e+02 3.30993164e+02 3.30781677e+02 3.30682617e+02 3.30948334e+02 3.31209290e+02 3.31199036e+02 3.31032410e+02 3.31039459e+02 3.31146057e+02 3.31239197e+02 3.31250732e+02 3.31407379e+02 3.31673187e+02 3.31499664e+02 3.31429504e+02 3.31211090e+02 3.31589081e+02 3.31460846e+02 3.31333405e+02 3.30955994e+02 3.30843262e+02 3.30696625e+02 3.30496246e+02 3.30380127e+02 3.30206024e+02 3.30016693e+02 3.29733246e+02 3.29641327e+02 3.29560852e+02 3.29357971e+02 3.29334229e+02 3.29380737e+02 3.29505371e+02 3.29591248e+02 3.29536560e+02 3.29533417e+02 3.29514893e+02 3.29558167e+02 3.29529938e+02 3.29409454e+02 3.29498322e+02 3.29496460e+02 3.29574646e+02 3.29601654e+02 3.29714111e+02 3.29556549e+02 3.29293854e+02 3.29072723e+02 3.29046539e+02 3.29070007e+02 3.29127441e+02 3.29074036e+02 3.29037354e+02 3.28863373e+02 3.28801788e+02 3.28900238e+02 3.28775574e+02 3.28625031e+02 3.28404510e+02 3.28606445e+02 3.28690796e+02 3.28767944e+02 3.28591003e+02 3.28467834e+02 3.28411896e+02 3.28292694e+02 3.28208008e+02 3.28248108e+02 3.28245331e+02 3.28291962e+02 3.28188202e+02 3.28140991e+02 3.28038971e+02 3.27925537e+02 3.27944763e+02 3.27949799e+02 3.27881927e+02 3.27932770e+02 3.27903625e+02 3.28134430e+02 3.28098846e+02 3.28313171e+02 3.28373047e+02 3.28566406e+02 3.28457886e+02 3.28183258e+02 3.27951385e+02 3.27889313e+02 3.28071594e+02 3.28413513e+02 3.28386353e+02 3.28543823e+02 3.28472961e+02 3.28521790e+02 3.28141327e+02 3.27951538e+02 3.27998993e+02 3.28200989e+02 3.28323730e+02 3.28304596e+02 3.28337677e+02 3.28354828e+02 3.28380371e+02 3.28474213e+02 3.28627716e+02 3.28854034e+02 3.28928467e+02 3.28905273e+02 3.28986572e+02 3.29264648e+02 3.29275360e+02 3.29355621e+02 3.29208771e+02 3.29244995e+02 3.29338013e+02 3.29405609e+02 3.29443024e+02 3.29263306e+02 3.29241882e+02 3.29289734e+02 3.29142181e+02 3.29243591e+02 3.29230377e+02 3.29521454e+02 3.29502686e+02 3.29492828e+02 3.29448730e+02 3.29471466e+02 3.29489319e+02 3.29483948e+02 3.29510437e+02 3.29540222e+02 3.29516785e+02 3.29595306e+02 3.29751892e+02 3.29864319e+02 3.29958008e+02 3.29963806e+02 3.30061859e+02 3.29971954e+02 3.29961700e+02 3.29874176e+02 3.29934998e+02 3.29727844e+02 3.29637665e+02 3.29468201e+02 3.29529297e+02 3.29484314e+02 3.29499695e+02 3.29327332e+02 3.29148315e+02 3.29165710e+02 3.29177582e+02 3.29076660e+02 3.28996033e+02 3.28892395e+02 3.28744232e+02 3.28538757e+02 3.28512848e+02 3.28689178e+02 3.28760132e+02 3.28645386e+02 3.28596191e+02 3.28472168e+02 3.28599670e+02 3.28515106e+02 3.28674744e+02 3.28878418e+02 3.29069611e+02 3.28973999e+02 3.28704071e+02 3.28642242e+02 3.28743744e+02 3.28786438e+02 3.28799957e+02 3.28986115e+02 3.29015900e+02 3.28989624e+02 3.28968781e+02 3.29184692e+02 3.29415070e+02 3.29478088e+02 3.29676025e+02 3.29812775e+02 3.29542633e+02 3.29023895e+02 3.28648834e+02 3.28632782e+02 3.28851898e+02 3.29034821e+02 3.29248840e+02 3.29289764e+02 3.29322083e+02 3.29399933e+02 3.29289734e+02 3.29228973e+02 3.29116333e+02 3.28980682e+02 3.28768341e+02 3.28703125e+02 3.28683655e+02 3.28726074e+02 3.28608368e+02 3.28613281e+02 3.28695190e+02 3.28762421e+02 3.28864380e+02 3.28884460e+02 3.28670471e+02 3.28470734e+02 3.28236206e+02 3.28121613e+02 3.27861328e+02 3.27640778e+02 3.27713562e+02 3.28003845e+02 3.28315948e+02 3.28506165e+02 3.28389893e+02 3.28301971e+02 3.28394379e+02 3.28419617e+02 3.28345215e+02 3.28255920e+02 3.28554199e+02 3.29011963e+02 3.29438019e+02 3.29573273e+02 3.29523468e+02 3.29380188e+02 3.29142609e+02 3.29014008e+02 3.29104248e+02 3.29251648e+02 3.29344421e+02 3.29333069e+02 3.29347198e+02 3.29361267e+02 3.29463409e+02 3.29572144e+02 3.29717651e+02 3.29704346e+02 3.29890137e+02 3.30023224e+02 3.30336426e+02 3.30390167e+02 3.30499054e+02 3.30552979e+02 3.30545563e+02 3.30577118e+02 3.30560242e+02 3.30772247e+02 3.30941193e+02 3.31102356e+02 3.31114166e+02 3.31118958e+02 3.31244659e+02 3.31281616e+02 3.31333740e+02 3.31130585e+02 3.30956757e+02 3.30808868e+02 3.30731415e+02 3.30681213e+02 3.30560577e+02 3.30368805e+02 3.30173645e+02 3.33396057e+02 3.58686523e+02 3.69272919e+02 3.67879547e+02 3.42889404e+02 3.37200348e+02 3.37810303e+02 3.38882690e+02 3.39393829e+02 3.38337189e+02 3.34793243e+02 3.13033295e+02 3.14577393e+02 4.62973083e+02 1.00367725e+03 -39237460. 1994973568. 0. 0. 0. 0. -87154144. -87154144. -87154144. 0. 0. 0. 167718416. 84984736. 7.03484438e+05 1.37203186e+03 6.15301086e+02 4.65897308e+02 5.29812073e+02 6.40555847e+02 5.33162048e+02 4.04861847e+02 3.46606964e+02 3.33966644e+02 3.31741150e+02 3.31404205e+02 3.31199585e+02 3.31333496e+02 3.31534821e+02 3.31953278e+02 3.32809448e+02 3.39431549e+02 3.62828644e+02 3.71975220e+02 3.66904419e+02 3.45351166e+02 3.39565735e+02 3.39039673e+02 3.39527557e+02 3.45038849e+02 3.46345184e+02 3.44815643e+02 3.42387726e+02 3.35871277e+02 3.33930023e+02 3.28732391e+02 3.31035156e+02 3.30292023e+02 3.30206573e+02 3.30934082e+02 3.31483032e+02 3.31521667e+02 3.31452759e+02 3.31495056e+02 3.31397919e+02 3.31205627e+02 3.30929291e+02 3.30732361e+02 3.30799347e+02 3.30954559e+02 3.31096344e+02 3.30905304e+02 3.30707764e+02 3.30783020e+02 3.30830994e+02 3.30934662e+02 3.30909058e+02 3.31007050e+02 3.31051422e+02 3.30988190e+02 3.30766907e+02 3.30751190e+02 3.30805267e+02 3.30910217e+02 3.30842987e+02 3.30708832e+02 3.30862061e+02 3.30928741e+02 3.31135345e+02 3.31300842e+02 3.31478943e+02 3.31490265e+02 3.31500427e+02 3.31698120e+02 3.31784973e+02 3.31847351e+02 3.31956665e+02 3.32114410e+02 3.32336090e+02 3.32514893e+02 3.32731476e+02 3.32945526e+02 3.33409943e+02 3.33851562e+02 3.34075165e+02 3.34405579e+02 3.35264832e+02 3.35971252e+02 3.36107819e+02 3.35888977e+02 3.35976044e+02 3.36175415e+02 3.36168182e+02 3.36270630e+02 3.36426147e+02 3.36226746e+02 3.37651764e+02 4.90726123e+03 1.72483551e+02 1.14257835e+02 1.14182343e+02 1.14095848e+02 1.14026573e+02 1.13943642e+02 1.13799072e+02 1.13627731e+02 1.13727806e+02 1.13719360e+02 1.13690674e+02 1.13468163e+02 1.13402016e+02 1.13404121e+02 1.13419930e+02 1.13409904e+02 1.13373695e+02 1.13324966e+02 1.13293228e+02 1.13285393e+02 1.13291962e+02 1.13298943e+02 1.13288422e+02 1.13297005e+02 1.13279610e+02 1.13344368e+02 1.13383133e+02 1.13398140e+02 1.13375084e+02 1.13382278e+02 1.13349495e+02 1.13339188e+02 1.13325821e+02 1.13394249e+02 1.13417877e+02 1.13440765e+02 1.13417862e+02 1.13454895e+02 1.13481125e+02 1.13497490e+02 1.13508247e+02 1.13504402e+02 1.13537224e+02 1.13491051e+02 1.13513847e+02 1.13526917e+02 1.13571823e+02 1.13569038e+02 1.13557968e+02 1.13580238e+02 1.13609810e+02 1.13692688e+02 1.13722488e+02 1.13743172e+02 1.13734055e+02 1.13755943e+02 1.13778122e+02 1.13813354e+02 1.13809006e+02 1.13809952e+02 1.13770050e+02 1.13748398e+02 1.13708603e+02 1.13685265e+02 1.13681175e+02 1.13694321e+02 1.13669632e+02 1.13636490e+02 1.13609032e+02 1.13619942e+02 1.13632446e+02 1.13654129e+02 1.13677544e+02 1.13684807e+02 1.13729683e+02 1.13755356e+02 1.13782234e+02 1.13826317e+02 1.13876694e+02 1.14043121e+02 1.14305565e+02 1.14673134e+02 1.13069504e+02 1.11970360e+02 1.38976532e+02 2.10373032e+02 4.19775482e+02 5.14697327e+02 8.75463257e+02 2.79236865e+03 -3.63799375e+05 -7.05476966e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.26646502e+09 1.40808728e+03 6.44081482e+02 4.59157043e+02 2.14385727e+02 1.46589478e+02 1.18822998e+02 1.20735840e+02 1.23929695e+02 1.25216904e+02 1.25024010e+02 1.18170181e+02 1.13936760e+02 1.12090988e+02 1.13711761e+02 1.13968361e+02 1.13948326e+02 1.13928589e+02 1.13909958e+02 1.13858109e+02 1.13791389e+02 1.13726395e+02 1.13632645e+02 1.13534523e+02 1.13430168e+02 1.13436501e+02 1.15055229e+02 1.17645477e+02 1.21490341e+02 1.23702065e+02 1.24969635e+02 1.24789803e+02 1.24138573e+02 1.21819801e+02 1.17484299e+02 1.12131516e+02 1.07049660e+02 1.04394585e+02 1.03759621e+02 1.05180077e+02 1.07429871e+02 1.10512939e+02 1.13376755e+02 1.16295761e+02 1.18613968e+02 1.20933571e+02 1.22261833e+02 1.21473885e+02 1.18970734e+02 1.16032784e+02 1.14200195e+02 1.13463463e+02 1.13241814e+02 1.13249634e+02 1.13250183e+02 1.13232513e+02 1.13100151e+02 1.12824364e+02 1.12263306e+02 1.11354103e+02 1.09908936e+02 1.08411980e+02 1.07537743e+02 1.07364059e+02 1.07637604e+02 1.08111687e+02 1.09017654e+02 1.10221138e+02 1.11434189e+02 1.12227211e+02 1.12685593e+02 1.12828773e+02 1.12911270e+02 1.12926880e+02 1.12922997e+02 1.12903252e+02 1.12882256e+02 1.12889549e+02 1.12894043e+02 1.12900688e+02 1.12886070e+02 1.12864395e+02 1.12838829e+02 1.12823090e+02 1.12817757e+02 1.12812897e+02 1.12831284e+02 1.12859566e+02 1.12849808e+02 1.12837692e+02 1.12823647e+02 1.12824310e+02 1.12803940e+02 1.12813690e+02 1.12803688e+02 1.12776535e+02 1.12743790e+02 1.12755142e+02 1.12804832e+02 1.12810600e+02 1.12813362e+02 1.12765297e+02 1.12754143e+02 1.12725189e+02 1.12713997e+02 1.12697021e+02 1.12669472e+02 1.12649910e+02 1.12631912e+02 1.12644447e+02 1.12683395e+02 1.12702286e+02 1.12711243e+02 1.12720558e+02 1.12739136e+02 1.12735222e+02 1.12728615e+02 1.12715431e+02 1.12702110e+02 1.12673264e+02 1.12675529e+02 1.12684502e+02 1.12722374e+02 1.12720955e+02 1.12737831e+02 1.12729362e+02 1.12725929e+02 1.12722794e+02 1.12727722e+02 1.12713860e+02 1.12717804e+02 1.12703636e+02 1.12731392e+02 1.12746780e+02 1.12744530e+02 1.12733963e+02 1.12718956e+02 1.12718719e+02 1.12721855e+02 1.12720306e+02 1.12733322e+02 1.12718460e+02 1.12693466e+02 1.12680222e+02 1.12709549e+02 1.12745964e+02 1.12760971e+02 1.12768730e+02 1.12752731e+02 1.12747215e+02 1.12731834e+02 1.12735214e+02 1.12738052e+02 1.12745911e+02 1.12740875e+02 1.12756126e+02 1.12759918e+02 1.12786194e+02 1.12801689e+02 1.12831841e+02 1.12815086e+02 1.12820740e+02 1.12802780e+02 1.12806244e+02 1.12819954e+02 1.12852081e+02 1.12859413e+02 1.12781883e+02 1.12715981e+02 1.12668266e+02 1.12702599e+02 1.12696815e+02 1.12700432e+02 1.12669731e+02 1.12712036e+02 1.12718094e+02 1.12739944e+02 1.12691132e+02 1.12671196e+02 1.12636673e+02 1.12654907e+02 1.12690727e+02 1.12779449e+02 1.12759644e+02 1.12681198e+02 1.12578033e+02 1.12567574e+02 1.12592018e+02 1.12580986e+02 1.12525719e+02 1.12471016e+02 1.12467651e+02 1.12469055e+02 1.12478035e+02 1.12528168e+02 1.12600319e+02 1.12633034e+02 1.12643761e+02 1.12618614e+02 1.12593582e+02 1.12567139e+02 1.12545486e+02 1.12563744e+02 1.12553604e+02 1.12545868e+02 1.12520935e+02 1.12501610e+02 1.12499512e+02 1.12516823e+02 1.12511238e+02 1.12541260e+02 1.12534897e+02 1.12586830e+02 1.12587799e+02 1.12615982e+02 1.12603577e+02 1.12576149e+02 1.12540802e+02 1.12556358e+02 1.12578964e+02 1.12571625e+02 1.12557716e+02 1.12531433e+02 1.12529449e+02 1.12468796e+02 1.12422577e+02 1.12421326e+02 1.12481583e+02 1.12550880e+02 1.12536270e+02 1.12555649e+02 1.12524467e+02 1.12522545e+02 1.12476555e+02 1.12489098e+02 1.12499405e+02 1.12466034e+02 1.12451187e+02 1.12420799e+02 1.12416740e+02 1.12358284e+02 1.12346016e+02 1.12377937e+02 1.12418716e+02 1.12449944e+02 1.12475693e+02 1.12521599e+02 1.12530098e+02 1.12538368e+02 1.12531639e+02 1.12517685e+02 1.12503441e+02 1.12500069e+02 1.12511383e+02 1.12506256e+02 1.12473839e+02 1.12452431e+02 1.12475159e+02 1.12489708e+02 1.12501526e+02 1.12474281e+02 1.12477379e+02 1.12485924e+02 1.12509460e+02 1.12521660e+02 1.12497673e+02 1.12505569e+02 1.12512764e+02 1.12551559e+02 1.12591362e+02 1.12599243e+02 1.12602005e+02 1.12574425e+02 1.12571938e+02 1.12606247e+02 1.12602089e+02 1.12618095e+02 1.12623589e+02 1.12642426e+02 1.12633583e+02 1.12618042e+02 1.12638550e+02 1.12660355e+02 1.12655792e+02 1.12632446e+02 1.12592560e+02 1.12589806e+02 1.12582787e+02 1.12584366e+02 1.12596031e+02 1.12620056e+02 1.12611015e+02 1.12605568e+02 1.12629501e+02 1.12653008e+02 1.12660667e+02 1.12661995e+02 1.12659325e+02 1.12632874e+02 1.12624481e+02 1.12648537e+02 1.12653687e+02 1.12616241e+02 1.12595284e+02 1.12600960e+02 1.12596001e+02 1.12584312e+02 1.12575218e+02 1.12553726e+02 1.12544334e+02 1.12532173e+02 1.12521591e+02 1.12520813e+02 1.12537529e+02 1.12557106e+02 1.12554878e+02 1.12556923e+02 1.12545631e+02 1.12493988e+02 1.12426727e+02 1.12380493e+02 1.12373161e+02 1.12367264e+02 1.12360451e+02 1.12359886e+02 1.12342346e+02 1.12363487e+02 1.12342163e+02 1.12335503e+02 1.12323387e+02 1.12341675e+02 1.12376289e+02 1.12403870e+02 1.12432121e+02 1.12441200e+02 1.12421967e+02 1.12392105e+02 1.12383224e+02 1.12446243e+02 1.12513702e+02 1.12570381e+02 1.12563332e+02 1.12583748e+02 1.12600922e+02 1.12609795e+02 1.12566589e+02 1.12563210e+02 1.12533836e+02 1.12530090e+02 1.12477173e+02 1.12444878e+02 1.12413490e+02 1.12427238e+02 1.12451355e+02 1.12493492e+02 1.12502647e+02 1.12503929e+02 1.12476952e+02 1.12451645e+02 1.12431702e+02 1.12424133e+02 1.12410957e+02 1.12373894e+02 1.12354393e+02 1.12352501e+02 1.12342903e+02 1.12318420e+02 1.12302032e+02 1.12316544e+02 1.12339157e+02 1.12356506e+02 1.12357964e+02 1.12359215e+02 1.12320061e+02 1.12288124e+02 1.12269974e+02 1.12235970e+02 1.12176781e+02 1.12134979e+02 1.12106789e+02 1.12103828e+02 1.12088203e+02 1.12076523e+02 1.12080544e+02 1.12082832e+02 1.12075729e+02 1.12083870e+02 1.12074020e+02 1.12088249e+02 1.12089264e+02 1.12099663e+02 1.12123817e+02 1.12155830e+02 1.12160889e+02 1.12139023e+02 1.12101921e+02 1.12106087e+02 1.12104958e+02 1.12110886e+02 1.12116386e+02 1.12166138e+02 1.12179909e+02 1.12191811e+02 1.12184135e+02 1.12177155e+02 1.12196808e+02 1.12259613e+02 1.12302864e+02 1.12335526e+02 1.12340599e+02 1.12371826e+02 1.12379692e+02 1.12342529e+02 1.12317993e+02 1.12268280e+02 1.12273109e+02 1.12264038e+02 1.12272232e+02 1.12246887e+02 1.12209358e+02 1.12192474e+02 1.12178024e+02 1.12170753e+02 1.12152657e+02 1.12156013e+02 1.12175003e+02 1.12206543e+02 1.12215134e+02 1.12182884e+02 1.12147148e+02 1.12136063e+02 1.12123833e+02 1.12127251e+02 1.12136993e+02 1.12137924e+02 1.12152946e+02 1.12124023e+02 1.12193665e+02 1.12215050e+02 1.12252266e+02 1.12237747e+02 1.12256172e+02 1.12228935e+02 1.12226494e+02 1.12226265e+02 1.12213409e+02 1.12204346e+02 1.12207199e+02 1.12201157e+02 1.12170929e+02 1.12150055e+02 1.12152702e+02 1.12114914e+02 1.12100410e+02 1.12084633e+02 1.12132362e+02 1.12182289e+02 1.12231972e+02 1.12235519e+02 1.12181000e+02 1.12127106e+02 1.12091370e+02 1.12053436e+02 1.12031342e+02 1.12032684e+02 1.12041016e+02 1.12051537e+02 1.12020134e+02 1.11990349e+02 1.11974884e+02 1.12003098e+02 1.12013062e+02 1.11993843e+02 1.12021965e+02 1.12079269e+02 1.12151970e+02 1.12084824e+02 1.12023010e+02 1.11942764e+02 1.12014084e+02 1.12055573e+02 1.12096710e+02 1.12066185e+02 1.12068909e+02 1.12051193e+02 1.12041336e+02 1.12055840e+02 1.12049156e+02 1.12058601e+02 1.12045242e+02 1.12035721e+02 1.12017624e+02 1.11951027e+02 1.11950783e+02 1.11940071e+02 1.11977753e+02 1.12018478e+02 1.12030067e+02 1.12048119e+02 1.12037003e+02 1.12071053e+02 1.12096977e+02 1.12125687e+02 1.12161194e+02 1.12155258e+02 1.12130905e+02 1.12088280e+02 1.12105064e+02 1.12158173e+02 1.12191353e+02 1.12184837e+02 1.12119423e+02 1.12145050e+02 1.12171738e+02 1.12253235e+02 1.12310905e+02 1.12344231e+02 1.12352478e+02 1.12381195e+02 1.12446312e+02 1.12501961e+02 1.12516594e+02 1.12584618e+02 1.12664391e+02 1.12758774e+02 1.12811836e+02 1.12848328e+02 1.12857040e+02 1.12806152e+02 1.12789299e+02 1.12793373e+02 1.12792046e+02 1.12785652e+02 1.12814568e+02 1.12825623e+02 1.12817749e+02 1.12773323e+02 1.12762451e+02 1.12758553e+02 1.12747864e+02 1.12722626e+02 1.12709412e+02 1.12753159e+02 1.12811623e+02 1.12835747e+02 1.12812439e+02 1.12769264e+02 1.12780426e+02 1.12824364e+02 1.12844704e+02 1.12832283e+02 1.12804390e+02 1.12804016e+02 1.12773209e+02 1.12686119e+02 1.12644051e+02 1.12627327e+02 1.12628937e+02 1.12606331e+02 1.12585846e+02 1.12603767e+02 1.12669319e+02 1.12749390e+02 1.12782974e+02 1.12782028e+02 1.12694496e+02 1.12650558e+02 1.12597328e+02 1.12628731e+02 1.12663864e+02 1.12653488e+02 1.12620857e+02 1.12530930e+02 1.12526886e+02 1.12506104e+02 1.12554070e+02 1.12582581e+02 1.12634178e+02 1.12641357e+02 1.12648796e+02 1.12651497e+02 1.12646179e+02 1.12611656e+02 1.12569260e+02 1.12512352e+02 1.12451263e+02 1.12443146e+02 1.12441429e+02 1.12461273e+02 1.12454834e+02 1.12489365e+02 1.12517097e+02 1.12521484e+02 1.12505096e+02 1.12437202e+02 1.12366005e+02 1.12291420e+02 1.12254814e+02 1.12264420e+02 1.12230293e+02 1.12205727e+02 1.12177208e+02 1.12213089e+02 1.12208847e+02 1.12193398e+02 1.12146492e+02 1.12128082e+02 1.12107742e+02 1.12114983e+02 1.12091377e+02 1.12079102e+02 1.12075119e+02 1.12145271e+02 1.12180115e+02 1.12221550e+02 1.12220123e+02 1.12239311e+02 1.12218689e+02 1.12233849e+02 1.12234543e+02 1.12293144e+02 1.12298531e+02 1.12355545e+02 1.12375450e+02 1.12369423e+02 1.12333603e+02 1.12325340e+02 1.12341728e+02 1.12337830e+02 1.12329147e+02 1.12321373e+02 1.12319199e+02 1.12293388e+02 1.12273941e+02 1.12285332e+02 1.12310867e+02 1.12316292e+02 1.12298935e+02 1.12316383e+02 1.12346809e+02 1.12390816e+02 1.12374397e+02 1.12397148e+02 1.12376541e+02 1.12403732e+02 1.12390114e+02 1.12422363e+02 1.12399582e+02 1.12384514e+02 1.12359779e+02 1.12390129e+02 1.12404945e+02 1.12437416e+02 1.12413811e+02 1.12402023e+02 1.12385979e+02 1.12389542e+02 1.12380081e+02 1.12354546e+02 1.12365211e+02 1.12398689e+02 1.12459854e+02 1.12481331e+02 1.12483902e+02 1.12491730e+02 1.12527565e+02 1.12557869e+02 1.12607597e+02 1.12635254e+02 1.12655617e+02 1.12682274e+02 1.12715118e+02 1.12727760e+02 1.12701691e+02 1.12690643e+02 1.12670212e+02 1.12680321e+02 1.12676247e+02 1.12660614e+02 1.12639175e+02 1.12612961e+02 1.12580162e+02 1.12569267e+02 1.12553986e+02 1.12571136e+02 1.12592316e+02 1.12615501e+02 1.12595802e+02 1.12570724e+02 1.12561562e+02 1.12569450e+02 1.12629051e+02 1.12652740e+02 1.12731758e+02 1.12788177e+02 1.12863632e+02 1.12894684e+02 1.12902794e+02 1.12898888e+02 1.12888489e+02 1.12844269e+02 1.12763023e+02 1.12713562e+02 1.12684296e+02 1.12652855e+02 1.12616684e+02 1.12557930e+02 1.12577713e+02 1.12543320e+02 1.12549271e+02 1.12522125e+02 1.12544586e+02 1.12551331e+02 1.12555473e+02 1.12551826e+02 1.12523872e+02 1.12492050e+02 1.12464684e+02 1.12468941e+02 1.12489967e+02 1.12516731e+02 1.12511490e+02 1.12493645e+02 1.12446960e+02 1.12427048e+02 1.12381874e+02 1.12376915e+02 1.12368111e+02 1.12353630e+02 1.12363220e+02 1.12402008e+02 1.12462822e+02 1.12431938e+02 1.12408287e+02 1.12417969e+02 1.12467857e+02 1.12464119e+02 1.12429123e+02 1.12414124e+02 1.12432854e+02 1.12480179e+02 1.12456230e+02 1.12495316e+02 1.12451302e+02 1.12464607e+02 1.12433167e+02 1.12443642e+02 1.12410011e+02 1.12374580e+02 1.12353493e+02 1.12343880e+02 1.12359444e+02 1.12364990e+02 1.12346901e+02 1.12328041e+02 1.12365028e+02 1.12473373e+02 1.12598442e+02 1.12671936e+02 1.12695168e+02 1.12675415e+02 1.12639496e+02 1.12635796e+02 1.12645126e+02 1.12670616e+02 1.12695938e+02 1.12718918e+02 1.12774254e+02 1.12807945e+02 1.12833961e+02 1.12817497e+02 1.12796799e+02 1.12753090e+02 1.12748634e+02 1.12800827e+02 1.12912552e+02 1.12954063e+02 1.12929276e+02 1.12944588e+02 1.12984993e+02 1.13010696e+02 1.12989525e+02 1.12970711e+02 1.13002098e+02 1.13016426e+02 1.13048225e+02 1.13094643e+02 1.13105186e+02 1.13091072e+02 1.13068550e+02 1.13028313e+02 1.13000473e+02 1.12957817e+02 1.12948334e+02 1.12931297e+02 1.12895424e+02 1.12859100e+02 1.12815254e+02 1.13370262e+02 1.17626190e+02 1.22511169e+02 1.26859749e+02 1.23249344e+02 1.19442696e+02 1.15662727e+02 1.15838203e+02 1.16039581e+02 1.16013428e+02 1.15385063e+02 1.11286705e+02 1.11193359e+02 1.46802078e+02 2.24206909e+02 6.15289673e+02 1.24223291e+03 -4.92193229e+09 9320808. 0. 0. -87154144. -87154144. -87154144. 0. 0. 0. 167718416. 84984736. 7.03484438e+05 1.85276428e+03 8.33390564e+02 3.51082153e+02 2.25912277e+02 1.74456848e+02 1.63920151e+02 1.57411423e+02 1.38391022e+02 1.23448242e+02 1.16010437e+02 1.14070312e+02 1.13295433e+02 1.13011986e+02 1.12939232e+02 1.12963905e+02 1.13066154e+02 1.14106071e+02 1.17889336e+02 1.19173210e+02 1.19138527e+02 1.16710732e+02 1.17521210e+02 1.18151909e+02 1.17939209e+02 1.16486023e+02 1.12231323e+02 1.07833237e+02 1.04994629e+02 1.04950996e+02 1.05385368e+02 1.05002953e+02 1.08425743e+02 1.16780182e+02 1.23893204e+02 1.23677917e+02 1.17380959e+02 1.14693558e+02 1.13697624e+02 1.13381218e+02 1.13272346e+02 1.13213058e+02 1.13157555e+02 1.13115189e+02 1.13112984e+02 1.13151733e+02 1.13213203e+02 1.13205368e+02 1.13171783e+02 1.13153137e+02 1.13150047e+02 1.13152954e+02 1.13108864e+02 1.13137299e+02 1.13119240e+02 1.13159660e+02 1.13133507e+02 1.13173203e+02 1.13173126e+02 1.13195869e+02 1.13246948e+02 1.13285675e+02 1.13324287e+02 1.13318855e+02 1.13307693e+02 1.13304581e+02 1.13318558e+02 1.13299965e+02 1.13312706e+02 1.13324692e+02 1.13363525e+02 1.13408531e+02 1.13484795e+02 1.13585434e+02 1.13629036e+02 1.13693413e+02 1.13761696e+02 1.13854713e+02 1.13918297e+02 1.13939041e+02 1.14012863e+02 1.13999245e+02 1.13442528e+02 1.13175117e+02 1.13026527e+02 1.13721046e+02 1.14049423e+02 1.14322243e+02 1.14209770e+02 1.13202774e+02 1.11413536e+02 1.10428276e+02 1.10391586e+02 5.58199402e+02 1.61461914e+02 1.07544586e+02 1.07946472e+02 1.08786980e+02 1.10093010e+02 1.10762283e+02 1.10786560e+02 1.11408806e+02 1.12275711e+02 1.13926781e+02 1.14680672e+02 1.15693436e+02 1.16057983e+02 1.16321297e+02 1.16401688e+02 1.16464821e+02 1.16429031e+02 1.16397400e+02 1.16358963e+02 1.16386932e+02 1.16442551e+02 1.16474434e+02 1.16507256e+02 1.16501801e+02 1.16532600e+02 1.16526451e+02 1.16498520e+02 1.16489967e+02 1.16486000e+02 1.16529121e+02 1.16496933e+02 1.16482979e+02 1.16447014e+02 1.16420784e+02 1.16394058e+02 1.16373428e+02 1.16386978e+02 1.16405731e+02 1.16401505e+02 1.16401436e+02 1.16407341e+02 1.16414024e+02 1.16432892e+02 1.16405296e+02 1.16390259e+02 1.16377571e+02 1.16377808e+02 1.16393433e+02 1.16381470e+02 1.16436356e+02 1.16477005e+02 1.16551712e+02 1.16592697e+02 1.16608215e+02 1.16583618e+02 1.16579208e+02 1.16580994e+02 1.16602936e+02 1.16613708e+02 1.16667870e+02 1.16706757e+02 1.16745346e+02 1.16736343e+02 1.16750183e+02 1.16736786e+02 1.16728401e+02 1.16704514e+02 1.16671593e+02 1.16667870e+02 1.16666557e+02 1.16674675e+02 1.16682343e+02 1.16701927e+02 1.16712753e+02 1.16705322e+02 1.16702225e+02 1.16754181e+02 1.16862793e+02 1.17083359e+02 1.17107124e+02 1.14956520e+02 1.14662827e+02 1.45726974e+02 2.18814316e+02 5.99872925e+02 2.15154373e+02 2.11680252e+02 2.91794617e+02 3.99140352e+09 -7.05476966e+09 -7.05476966e+09 5.52255188e+05 1855519232. 1855519232. 0. 0. 0. 0. 0. 0. -333169920. -305034016. 3.31372656e+05 1.22348389e+03 2.82790436e+02 1.55617905e+02 1.22844795e+02 1.25424652e+02 1.26757187e+02 1.28148102e+02 1.28533585e+02 1.29646469e+02 1.24112267e+02 1.19262657e+02 1.15944138e+02 1.16717461e+02 1.17365631e+02 1.17520691e+02 1.17584702e+02 1.17673882e+02 1.17726707e+02 1.17752373e+02 1.17731972e+02 1.17752991e+02 1.17788307e+02 1.17814301e+02 1.17801483e+02 1.17794861e+02 1.17779282e+02 1.17787811e+02 1.18315247e+02 1.19491776e+02 1.20127647e+02 1.19790237e+02 1.18536919e+02 1.17826157e+02 1.17518967e+02 1.17453606e+02 1.17327736e+02 1.17213463e+02 1.17151314e+02 1.17183586e+02 1.17242081e+02 1.17475456e+02 1.17895760e+02 1.18032448e+02 1.18009315e+02 1.17680481e+02 1.17572304e+02 1.17466194e+02 1.17431633e+02 1.17410751e+02 1.17368889e+02 1.17346672e+02 1.17351204e+02 1.17380463e+02 1.17444260e+02 1.17511192e+02 1.17574318e+02 1.17584663e+02 1.17544678e+02 1.17403046e+02 1.17203079e+02 1.16972534e+02 1.16746452e+02 1.16612534e+02 1.16562790e+02 1.16634720e+02 1.16698593e+02 1.16782692e+02 1.16836166e+02 1.16853584e+02 1.16826584e+02 1.16788879e+02 1.16777977e+02 1.16767342e+02 1.16743546e+02 1.16700874e+02 1.16657310e+02 1.16652145e+02 1.16649025e+02 1.16647316e+02 1.16623550e+02 1.16596291e+02 1.16588364e+02 1.16550652e+02 1.16544304e+02 1.16541954e+02 1.16572006e+02 1.16573395e+02 1.16559654e+02 1.16557137e+02 1.16561005e+02 1.16567123e+02 1.16575089e+02 1.16569656e+02 1.16561867e+02 1.16514503e+02 1.16508118e+02 1.16499680e+02 1.16525230e+02 1.16498497e+02 1.16491730e+02 1.16501068e+02 1.16496460e+02 1.16502991e+02 1.16467842e+02 1.16504524e+02 1.16517288e+02 1.16557991e+02 1.16567291e+02 1.16565536e+02 1.16556618e+02 1.16520844e+02 1.16492157e+02 1.16480980e+02 1.16492462e+02 1.16490303e+02 1.16492996e+02 1.16513504e+02 1.16525833e+02 1.16542145e+02 1.16542175e+02 1.16563652e+02 1.16554489e+02 1.16573219e+02 1.16564034e+02 1.16581772e+02 1.16589752e+02 1.16605301e+02 1.16609894e+02 1.16586510e+02 1.16563293e+02 1.16554497e+02 1.16545448e+02 1.16551964e+02 1.16533081e+02 1.16533371e+02 1.16532364e+02 1.16543808e+02 1.16563766e+02 1.16595741e+02 1.16629333e+02 1.16644318e+02 1.16652740e+02 1.16638924e+02 1.16642456e+02 1.16671570e+02 1.16697639e+02 1.16712021e+02 1.16700035e+02 1.16687286e+02 1.16680534e+02 1.16680138e+02 1.16682289e+02 1.16686493e+02 1.16666702e+02 1.16645386e+02 1.16610558e+02 1.16597336e+02 1.16590080e+02 1.16612038e+02 1.16613075e+02 1.16611603e+02 1.16571434e+02 1.16553459e+02 1.16541229e+02 1.16538612e+02 1.16539116e+02 1.16538116e+02 1.16533035e+02 1.16545135e+02 1.16529579e+02 1.16525810e+02 1.16506126e+02 1.16514175e+02 1.16511658e+02 1.16491737e+02 1.16494392e+02 1.16496864e+02 1.16515427e+02 1.16522301e+02 1.16555428e+02 1.16545654e+02 1.16513184e+02 1.16499397e+02 1.16498451e+02 1.16512375e+02 1.16494339e+02 1.16482384e+02 1.16477478e+02 1.16513687e+02 1.16529495e+02 1.16539108e+02 1.16520065e+02 1.16517601e+02 1.16528183e+02 1.16488518e+02 1.16462959e+02 1.16429794e+02 1.16406021e+02 1.16394470e+02 1.16411369e+02 1.16481285e+02 1.16564476e+02 1.16607796e+02 1.16620293e+02 1.16605476e+02 1.16606483e+02 1.16570946e+02 1.16509758e+02 1.16474861e+02 1.16455643e+02 1.16480896e+02 1.16500618e+02 1.16525047e+02 1.16522705e+02 1.16522400e+02 1.16531448e+02 1.16547417e+02 1.16522690e+02 1.16548485e+02 1.16570145e+02 1.16578667e+02 1.16560112e+02 1.16565742e+02 1.16545143e+02 1.16515862e+02 1.16458443e+02 1.16442001e+02 1.16456085e+02 1.16469185e+02 1.16476997e+02 1.16490211e+02 1.16509392e+02 1.16536087e+02 1.16499031e+02 1.16472137e+02 1.16452271e+02 1.16435562e+02 1.16448486e+02 1.16455162e+02 1.16468903e+02 1.16427788e+02 1.16394691e+02 1.16430466e+02 1.16436592e+02 1.16409447e+02 1.16367271e+02 1.16381897e+02 1.16419800e+02 1.16441063e+02 1.16448570e+02 1.16466766e+02 1.16435959e+02 1.16408417e+02 1.16372513e+02 1.16380905e+02 1.16388985e+02 1.16443192e+02 1.16476013e+02 1.16540169e+02 1.16590286e+02 1.16652718e+02 1.16647011e+02 1.16627655e+02 1.16597107e+02 1.16578964e+02 1.16557388e+02 1.16565865e+02 1.16601303e+02 1.16652481e+02 1.16668167e+02 1.16645737e+02 1.16609512e+02 1.16591217e+02 1.16644043e+02 1.16646851e+02 1.16661743e+02 1.16651817e+02 1.16681358e+02 1.16676819e+02 1.16647072e+02 1.16653954e+02 1.16673965e+02 1.16735107e+02 1.16750290e+02 1.16759880e+02 1.16718987e+02 1.16700073e+02 1.16673676e+02 1.16670341e+02 1.16658775e+02 1.16669914e+02 1.16667603e+02 1.16642914e+02 1.16624260e+02 1.16607651e+02 1.16584679e+02 1.16551804e+02 1.16533554e+02 1.16547997e+02 1.16540703e+02 1.16545776e+02 1.16535835e+02 1.16534279e+02 1.16506699e+02 1.16489738e+02 1.16501770e+02 1.16520233e+02 1.16543724e+02 1.16549782e+02 1.16563599e+02 1.16525345e+02 1.16488182e+02 1.16428360e+02 1.16421143e+02 1.16440514e+02 1.16475327e+02 1.16483444e+02 1.16451447e+02 1.16428558e+02 1.16428734e+02 1.16432953e+02 1.16423050e+02 1.16389328e+02 1.16371552e+02 1.16355774e+02 1.16371590e+02 1.16373276e+02 1.16371094e+02 1.16354149e+02 1.16330902e+02 1.16319069e+02 1.16285446e+02 1.16272217e+02 1.16256203e+02 1.16256264e+02 1.16246483e+02 1.16216469e+02 1.16211586e+02 1.16204201e+02 1.16215775e+02 1.16222618e+02 1.16265274e+02 1.16317772e+02 1.16355843e+02 1.16352592e+02 1.16320709e+02 1.16301331e+02 1.16292114e+02 1.16317902e+02 1.16311661e+02 1.16295815e+02 1.16281090e+02 1.16284691e+02 1.16300652e+02 1.16331177e+02 1.16341721e+02 1.16363342e+02 1.16319702e+02 1.16323723e+02 1.16290039e+02 1.16310280e+02 1.16301781e+02 1.16310081e+02 1.16318329e+02 1.16309105e+02 1.16281143e+02 1.16231720e+02 1.16193542e+02 1.16175507e+02 1.16174088e+02 1.16148148e+02 1.16149139e+02 1.16138321e+02 1.16136177e+02 1.16120720e+02 1.16118080e+02 1.16107048e+02 1.16102341e+02 1.16116058e+02 1.16116722e+02 1.16103432e+02 1.16035362e+02 1.15989120e+02 1.15942612e+02 1.15928543e+02 1.15946671e+02 1.15983192e+02 1.15979355e+02 1.15950150e+02 1.15903961e+02 1.15920273e+02 1.15932259e+02 1.15945435e+02 1.15928665e+02 1.15914612e+02 1.15866287e+02 1.15837349e+02 1.15867134e+02 1.15900421e+02 1.15909576e+02 1.15871475e+02 1.15874611e+02 1.15886749e+02 1.15916298e+02 1.15931107e+02 1.15927498e+02 1.15956261e+02 1.16001152e+02 1.16053192e+02 1.16059669e+02 1.16069611e+02 1.16092667e+02 1.16087318e+02 1.16073326e+02 1.16052032e+02 1.16049088e+02 1.16049492e+02 1.16042076e+02 1.16041458e+02 1.16035225e+02 1.16024582e+02 1.16007736e+02 1.15962120e+02 1.15942009e+02 1.15968391e+02 1.15976555e+02 1.15975731e+02 1.15959702e+02 1.15956131e+02 1.15938202e+02 1.15918587e+02 1.15940948e+02 1.15957306e+02 1.15950882e+02 1.15942551e+02 1.15962158e+02 1.15974365e+02 1.15973595e+02 1.15992195e+02 1.15998962e+02 1.15973145e+02 1.15912132e+02 1.15831596e+02 1.15739098e+02 1.15690697e+02 1.15689804e+02 1.15722969e+02 1.15729568e+02 1.15735817e+02 1.15760818e+02 1.15806709e+02 1.15803093e+02 1.15760635e+02 1.15697525e+02 1.15694397e+02 1.15677521e+02 1.15673569e+02 1.15608231e+02 1.15622406e+02 1.15646172e+02 1.15670685e+02 1.15660645e+02 1.15633080e+02 1.15603294e+02 1.15593689e+02 1.15551041e+02 1.15540215e+02 1.15500999e+02 1.15510277e+02 1.15483170e+02 1.15540550e+02 1.15596703e+02 1.15718086e+02 1.15782028e+02 1.15845436e+02 1.15828896e+02 1.15786972e+02 1.15721230e+02 1.15717148e+02 1.15727760e+02 1.15667824e+02 1.15576813e+02 1.15451218e+02 1.15403931e+02 1.15404800e+02 1.15398186e+02 1.15407318e+02 1.15367897e+02 1.15354546e+02 1.15344658e+02 1.15305771e+02 1.15258080e+02 1.15183098e+02 1.15151825e+02 1.15149445e+02 1.15173637e+02 1.15214226e+02 1.15228584e+02 1.15203255e+02 1.15159286e+02 1.15148872e+02 1.15117020e+02 1.15078346e+02 1.15070038e+02 1.15080879e+02 1.15123238e+02 1.15167732e+02 1.15232079e+02 1.15305595e+02 1.15339088e+02 1.15416412e+02 1.15451424e+02 1.15508095e+02 1.15530113e+02 1.15549171e+02 1.15585602e+02 1.15626213e+02 1.15687088e+02 1.15737267e+02 1.15785881e+02 1.15834381e+02 1.15833130e+02 1.15830536e+02 1.15843430e+02 1.15882431e+02 1.15914680e+02 1.15933563e+02 1.15911530e+02 1.15882568e+02 1.15861038e+02 1.15882584e+02 1.15915108e+02 1.15908218e+02 1.15888130e+02 1.15787819e+02 1.15737297e+02 1.15708511e+02 1.15779099e+02 1.15827538e+02 1.15864723e+02 1.15860764e+02 1.15854164e+02 1.15852036e+02 1.15872719e+02 1.15951157e+02 1.15983727e+02 1.16016106e+02 1.15959099e+02 1.15993767e+02 1.16040894e+02 1.16130692e+02 1.16167511e+02 1.16216835e+02 1.16268646e+02 1.16269157e+02 1.16274841e+02 1.16264534e+02 1.16310760e+02 1.16341087e+02 1.16428871e+02 1.16522751e+02 1.16572670e+02 1.16584381e+02 1.16544594e+02 1.16521904e+02 1.16448593e+02 1.16396835e+02 1.16334534e+02 1.16365463e+02 1.16394379e+02 1.16428169e+02 1.16402687e+02 1.16369217e+02 1.16350090e+02 1.16305046e+02 1.16301750e+02 1.16331367e+02 1.16401138e+02 1.16393616e+02 1.16385094e+02 1.16334518e+02 1.16312614e+02 1.16287125e+02 1.16300049e+02 1.16321571e+02 1.16322266e+02 1.16334442e+02 1.16418221e+02 1.16481979e+02 1.16551308e+02 1.16547020e+02 1.16564262e+02 1.16564293e+02 1.16545128e+02 1.16515755e+02 1.16458527e+02 1.16429474e+02 1.16406792e+02 1.16350380e+02 1.16307327e+02 1.16280441e+02 1.16305191e+02 1.16354065e+02 1.16359795e+02 1.16394150e+02 1.16362640e+02 1.16320862e+02 1.16261932e+02 1.16189201e+02 1.16146019e+02 1.16097473e+02 1.16140671e+02 1.16181931e+02 1.16190758e+02 1.16170959e+02 1.16175400e+02 1.16224693e+02 1.16269753e+02 1.16282799e+02 1.16271049e+02 1.16257271e+02 1.16271492e+02 1.16295395e+02 1.16330025e+02 1.16367195e+02 1.16386185e+02 1.16381950e+02 1.16330917e+02 1.16326950e+02 1.16306259e+02 1.16340302e+02 1.16309921e+02 1.16258278e+02 1.16245796e+02 1.16276642e+02 1.16314430e+02 1.16271332e+02 1.16248863e+02 1.16244873e+02 1.16228081e+02 1.16186836e+02 1.16138550e+02 1.16135811e+02 1.16128311e+02 1.16154160e+02 1.16154869e+02 1.16183113e+02 1.16174889e+02 1.16204300e+02 1.16188316e+02 1.16203140e+02 1.16191948e+02 1.16239098e+02 1.16277824e+02 1.16289078e+02 1.16272568e+02 1.16260803e+02 1.16260658e+02 1.16264420e+02 1.16294655e+02 1.16336487e+02 1.16389908e+02 1.16407677e+02 1.16460342e+02 1.16496544e+02 1.16541557e+02 1.16538116e+02 1.16576706e+02 1.16636162e+02 1.16738388e+02 1.16806740e+02 1.16820999e+02 1.16830078e+02 1.16820885e+02 1.16826302e+02 1.16789017e+02 1.16780556e+02 1.16766228e+02 1.16782753e+02 1.16769432e+02 1.16818718e+02 1.16810219e+02 1.16818428e+02 1.16825264e+02 1.16854034e+02 1.16902534e+02 1.16929619e+02 1.16976059e+02 1.16996811e+02 1.17017181e+02 1.17035873e+02 1.17087524e+02 1.17153160e+02 1.17191223e+02 1.17194839e+02 1.17130615e+02 1.17127930e+02 1.17079765e+02 1.17029694e+02 1.16890244e+02 1.16772110e+02 1.16615372e+02 1.16491737e+02 1.16402267e+02 1.16425888e+02 1.16452652e+02 1.16451027e+02 1.16432968e+02 1.16442192e+02 1.16420967e+02 1.16396767e+02 1.16334084e+02 1.16339249e+02 1.16330719e+02 1.16355331e+02 1.16414207e+02 1.16476601e+02 1.16541122e+02 1.16558273e+02 1.16512711e+02 1.16510109e+02 1.16441971e+02 1.16427559e+02 1.16359314e+02 1.16333046e+02 1.16303841e+02 1.16310959e+02 1.16354294e+02 1.16407265e+02 1.16424240e+02 1.16431396e+02 1.16439163e+02 1.16424698e+02 1.16412880e+02 1.16406013e+02 1.16394997e+02 1.16353569e+02 1.16310677e+02 1.16318054e+02 1.16379555e+02 1.16423775e+02 1.16490196e+02 1.16611908e+02 1.16682503e+02 1.16691994e+02 1.16614014e+02 1.16574303e+02 1.16529739e+02 1.16509285e+02 1.16529907e+02 1.16558495e+02 1.16582336e+02 1.16606880e+02 1.16634483e+02 1.16669060e+02 1.16695312e+02 1.16737251e+02 1.16774612e+02 1.16789764e+02 1.16801407e+02 1.16820923e+02 1.16848541e+02 1.16849693e+02 1.16819061e+02 1.16810837e+02 1.16810738e+02 1.16836441e+02 1.16848373e+02 1.16856918e+02 1.16828911e+02 1.16789932e+02 1.16768051e+02 1.16759171e+02 1.16727989e+02 1.16719078e+02 1.16721542e+02 1.16758514e+02 1.16737770e+02 1.16727074e+02 1.16718254e+02 1.16755066e+02 1.16778580e+02 1.16796379e+02 1.16806534e+02 1.16824181e+02 1.16851814e+02 1.16872673e+02 1.16846977e+02 1.16810898e+02 1.16762589e+02 1.16723579e+02 1.16701180e+02 1.16666153e+02 1.16653404e+02 1.16630302e+02 1.16644783e+02 1.16705765e+02 1.16731316e+02 1.16734177e+02 1.16632927e+02 1.19804543e+02 1.24085403e+02 1.28774567e+02 1.29740417e+02 1.26255501e+02 1.23026489e+02 1.20060448e+02 1.20298882e+02 1.20392899e+02 1.20282722e+02 1.19626793e+02 1.16945122e+02 1.14759789e+02 1.47810776e+02 2.22230698e+02 6.42686584e+02 1.32221008e+03 -165321216. -1638984192. 0. 0. 0. 3.57584978e+10 3.57584978e+10 3.57584978e+10 0. 0. 0. -101103008. -10055615. 2.38782031e+03 8.18221069e+02 5.73393188e+02 2.70463165e+02 2.02972687e+02 1.57161316e+02 1.53308197e+02 1.37492325e+02 1.25644180e+02 1.19410156e+02 1.14928329e+02 1.11252846e+02 1.08625748e+02 1.08546768e+02 1.08818146e+02 1.09910332e+02 1.13136101e+02 1.16867775e+02 1.19778435e+02 1.20306038e+02 1.20142776e+02 1.19833237e+02 1.18297211e+02 1.14933525e+02 1.11491776e+02 1.09298180e+02 1.10796944e+02 1.14153778e+02 1.14597206e+02 1.12701080e+02 1.09209595e+02 1.11153732e+02 1.15601212e+02 1.21662483e+02 1.23501778e+02 1.21889984e+02 1.18716965e+02 1.17327980e+02 1.16755501e+02 1.16607498e+02 1.16569580e+02 1.16582939e+02 1.16606956e+02 1.16656128e+02 1.16700562e+02 1.16710335e+02 1.16670204e+02 1.16629822e+02 1.16632523e+02 1.16649551e+02 1.16687454e+02 1.16673355e+02 1.16691437e+02 1.16707092e+02 1.16744850e+02 1.16773270e+02 1.16806557e+02 1.16885735e+02 1.16954697e+02 1.16952591e+02 1.16918922e+02 1.16862259e+02 1.16843750e+02 1.16824402e+02 1.16807457e+02 1.16823479e+02 1.16782967e+02 1.16794319e+02 1.16641640e+02 1.16001945e+02 1.15326530e+02 1.14577171e+02 1.14257355e+02 1.13711853e+02 1.13029137e+02 1.12323822e+02 1.12146385e+02 1.11110962e+02 1.09576859e+02 1.07643845e+02 1.06944016e+02 1.06910316e+02 1.06979538e+02 1.07003334e+02 1.07009819e+02 1.06980621e+02 1.06888008e+02 1.06821396e+02 1.06784882e+02 1.06893440e+02 5.85018677e+02 1.68044113e+02 1.11513557e+02 1.11766457e+02 1.11975250e+02 1.12159363e+02 1.12354683e+02 1.12552834e+02 1.12580574e+02 1.12384377e+02 1.12263268e+02 1.12235733e+02 1.12457359e+02 1.12650650e+02 1.12857063e+02 1.13163597e+02 1.13828476e+02 1.15244606e+02 1.17380272e+02 1.19530060e+02 1.20746292e+02 1.20820366e+02 1.20222755e+02 1.19611130e+02 1.19122231e+02 1.18848671e+02 1.18646637e+02 1.18589104e+02 1.18584496e+02 1.18593895e+02 1.18566933e+02 1.18571365e+02 1.18615883e+02 1.18655701e+02 1.18645538e+02 1.18638474e+02 1.18646042e+02 1.18710220e+02 1.18760933e+02 1.18795845e+02 1.18785583e+02 1.18721596e+02 1.18711304e+02 1.18680473e+02 1.18698952e+02 1.18633217e+02 1.18594879e+02 1.18503738e+02 1.18470444e+02 1.18449036e+02 1.18476929e+02 1.18482895e+02 1.18488533e+02 1.18513634e+02 1.18540848e+02 1.18573692e+02 1.18591415e+02 1.18580406e+02 1.18554817e+02 1.18528069e+02 1.18525002e+02 1.18551605e+02 1.18573601e+02 1.18610329e+02 1.18616013e+02 1.18602264e+02 1.18590584e+02 1.18583847e+02 1.18590118e+02 1.18601555e+02 1.18559013e+02 1.18544151e+02 1.18503517e+02 1.18504982e+02 1.18516991e+02 1.18558884e+02 1.18618050e+02 1.18782784e+02 1.19180473e+02 1.20363640e+02 1.25168045e+02 1.60380905e+02 2.40940002e+02 6.26127563e+02 1.29469226e+03 -1346798080. 2.07841850e+06 -645391168. -645391168. 0. -375361056. -375361056. 12805715. 1855519232. 1855519232. 0. 0. 0. 0. -1.86515702e+10 -2003420672. 1.39748901e+03 6.69465576e+02 5.07918243e+02 2.32983810e+02 1.61045807e+02 1.27702583e+02 1.29787048e+02 1.28289948e+02 1.26637260e+02 1.24349594e+02 1.24307243e+02 1.21586868e+02 1.19639595e+02 1.18014191e+02 1.18591217e+02 1.18939880e+02 1.19084846e+02 1.19198204e+02 1.19278427e+02 1.19343033e+02 1.19352615e+02 1.19370461e+02 1.19424744e+02 1.19492958e+02 1.19550072e+02 1.19593323e+02 1.19657631e+02 1.19700516e+02 1.19673309e+02 1.19799866e+02 1.19955856e+02 1.20020538e+02 1.19952530e+02 1.19898148e+02 1.20069496e+02 1.20204445e+02 1.20248650e+02 1.20146606e+02 1.20076172e+02 1.20023109e+02 1.20082512e+02 1.20109978e+02 1.20138802e+02 1.20154846e+02 1.20144989e+02 1.20168175e+02 1.20140404e+02 1.20084435e+02 1.20047386e+02 1.20008217e+02 1.19979004e+02 1.19958183e+02 1.19881180e+02 1.19828133e+02 1.19813179e+02 1.19873375e+02 1.19945572e+02 1.20056931e+02 1.20185410e+02 1.20328979e+02 1.20397102e+02 1.20427536e+02 1.20358116e+02 1.20252838e+02 1.20111992e+02 1.20009636e+02 1.19924026e+02 1.19841805e+02 1.19797737e+02 1.19750931e+02 1.19715836e+02 1.19675323e+02 1.19661423e+02 1.19665489e+02 1.19657257e+02 1.19632584e+02 1.19582695e+02 1.19539474e+02 1.19489708e+02 1.19480560e+02 1.19481834e+02 1.19507668e+02 1.19516525e+02 1.19547752e+02 1.19574455e+02 1.19598557e+02 1.19590584e+02 1.19598343e+02 1.19564766e+02 1.19538551e+02 1.19518990e+02 1.19543152e+02 1.19562309e+02 1.19551956e+02 1.19514008e+02 1.19477982e+02 1.19425148e+02 1.19430145e+02 1.19463524e+02 1.19499535e+02 1.19494064e+02 1.19460373e+02 1.19431465e+02 1.19395157e+02 1.19389709e+02 1.19363861e+02 1.19374313e+02 1.19364479e+02 1.19327911e+02 1.19284561e+02 1.19256226e+02 1.19300369e+02 1.19333290e+02 1.19387550e+02 1.19401947e+02 1.19443115e+02 1.19455009e+02 1.19467690e+02 1.19465141e+02 1.19417061e+02 1.19396141e+02 1.19371948e+02 1.19423088e+02 1.19447220e+02 1.19509216e+02 1.19517433e+02 1.19523468e+02 1.19500885e+02 1.19489548e+02 1.19477211e+02 1.19477745e+02 1.19453743e+02 1.19448967e+02 1.19421562e+02 1.19405724e+02 1.19395981e+02 1.19377441e+02 1.19392830e+02 1.19414536e+02 1.19427979e+02 1.19446121e+02 1.19450600e+02 1.19483025e+02 1.19520058e+02 1.19550865e+02 1.19559250e+02 1.19524857e+02 1.19511536e+02 1.19515121e+02 1.19554131e+02 1.19583733e+02 1.19584496e+02 1.19599792e+02 1.19590363e+02 1.19606529e+02 1.19590263e+02 1.19587967e+02 1.19558174e+02 1.19537758e+02 1.19534988e+02 1.19532181e+02 1.19564812e+02 1.19593758e+02 1.19633705e+02 1.19645477e+02 1.19609993e+02 1.19573219e+02 1.19510765e+02 1.19475311e+02 1.19464340e+02 1.19504768e+02 1.19519936e+02 1.19528229e+02 1.19514374e+02 1.19562714e+02 1.19613129e+02 1.19716614e+02 1.19699226e+02 1.19736618e+02 1.19704269e+02 1.19778343e+02 1.19774727e+02 1.19823669e+02 1.19805191e+02 1.19808510e+02 1.19731567e+02 1.19778641e+02 1.19810913e+02 1.19916145e+02 1.19908745e+02 1.19891235e+02 1.19865189e+02 1.19827751e+02 1.19791756e+02 1.19729294e+02 1.19720444e+02 1.19708328e+02 1.19656677e+02 1.19587791e+02 1.19513535e+02 1.19468864e+02 1.19378349e+02 1.19324341e+02 1.19330688e+02 1.19407982e+02 1.19504532e+02 1.19536095e+02 1.19545090e+02 1.19499161e+02 1.19496239e+02 1.19457634e+02 1.19439659e+02 1.19441246e+02 1.19448036e+02 1.19444832e+02 1.19407043e+02 1.19417183e+02 1.19432030e+02 1.19506302e+02 1.19558617e+02 1.19599335e+02 1.19636383e+02 1.19632339e+02 1.19644638e+02 1.19649437e+02 1.19695518e+02 1.19683876e+02 1.19674332e+02 1.19640221e+02 1.19573112e+02 1.19541489e+02 1.19474014e+02 1.19473656e+02 1.19402985e+02 1.19438538e+02 1.19438065e+02 1.19448288e+02 1.19414986e+02 1.19417503e+02 1.19471405e+02 1.19501610e+02 1.19481590e+02 1.19445694e+02 1.19433624e+02 1.19430679e+02 1.19379204e+02 1.19341591e+02 1.19297928e+02 1.19323555e+02 1.19310043e+02 1.19325233e+02 1.19298767e+02 1.19298065e+02 1.19325104e+02 1.19348282e+02 1.19334000e+02 1.19273956e+02 1.19268677e+02 1.19312134e+02 1.19344978e+02 1.19339027e+02 1.19345009e+02 1.19340843e+02 1.19373077e+02 1.19384483e+02 1.19386620e+02 1.19350189e+02 1.19290268e+02 1.19284660e+02 1.19282639e+02 1.19290955e+02 1.19282272e+02 1.19262062e+02 1.19275116e+02 1.19268860e+02 1.19260719e+02 1.19218498e+02 1.19202080e+02 1.19235550e+02 1.19222244e+02 1.19180351e+02 1.19153625e+02 1.19212868e+02 1.19275459e+02 1.19299278e+02 1.19299583e+02 1.19299110e+02 1.19331490e+02 1.19319817e+02 1.19303368e+02 1.19279861e+02 1.19296547e+02 1.19313911e+02 1.19325531e+02 1.19371651e+02 1.19406494e+02 1.19418739e+02 1.19413795e+02 1.19442635e+02 1.19414108e+02 1.19385445e+02 1.19373367e+02 1.19401108e+02 1.19409225e+02 1.19434349e+02 1.19432007e+02 1.19417755e+02 1.19387016e+02 1.19349258e+02 1.19362358e+02 1.19360153e+02 1.19396965e+02 1.19407730e+02 1.19426552e+02 1.19459679e+02 1.19438026e+02 1.19369614e+02 1.19323448e+02 1.19317230e+02 1.19303452e+02 1.19286331e+02 1.19274155e+02 1.19289978e+02 1.19301743e+02 1.19310448e+02 1.19308327e+02 1.19312637e+02 1.19303307e+02 1.19350174e+02 1.19331871e+02 1.19343727e+02 1.19320053e+02 1.19336815e+02 1.19367165e+02 1.19371201e+02 1.19351189e+02 1.19305550e+02 1.19275574e+02 1.19284622e+02 1.19272896e+02 1.19261917e+02 1.19232979e+02 1.19254219e+02 1.19284760e+02 1.19322746e+02 1.19340645e+02 1.19375984e+02 1.19367569e+02 1.19379547e+02 1.19338554e+02 1.19340233e+02 1.19335533e+02 1.19391731e+02 1.19421967e+02 1.19446106e+02 1.19442459e+02 1.19437302e+02 1.19442284e+02 1.19416931e+02 1.19413605e+02 1.19414230e+02 1.19410873e+02 1.19394417e+02 1.19406807e+02 1.19435425e+02 1.19491562e+02 1.19512817e+02 1.19499702e+02 1.19479881e+02 1.19450050e+02 1.19456818e+02 1.19453796e+02 1.19488373e+02 1.19481354e+02 1.19455284e+02 1.19432663e+02 1.19448235e+02 1.19463387e+02 1.19490517e+02 1.19538521e+02 1.19594261e+02 1.19578278e+02 1.19531731e+02 1.19498520e+02 1.19490723e+02 1.19473030e+02 1.19431396e+02 1.19366020e+02 1.19339478e+02 1.19323456e+02 1.19321510e+02 1.19322777e+02 1.19305344e+02 1.19307274e+02 1.19285240e+02 1.19270454e+02 1.19275299e+02 1.19269279e+02 1.19246689e+02 1.19207268e+02 1.19232567e+02 1.19247162e+02 1.19252625e+02 1.19227272e+02 1.19212105e+02 1.19211067e+02 1.19208488e+02 1.19230827e+02 1.19230583e+02 1.19218369e+02 1.19231506e+02 1.19232498e+02 1.19249825e+02 1.19249771e+02 1.19278137e+02 1.19302292e+02 1.19306496e+02 1.19335922e+02 1.19330826e+02 1.19306778e+02 1.19273880e+02 1.19266235e+02 1.19282349e+02 1.19303574e+02 1.19284065e+02 1.19283768e+02 1.19287086e+02 1.19335083e+02 1.19336723e+02 1.19316368e+02 1.19257469e+02 1.19248825e+02 1.19268181e+02 1.19278816e+02 1.19262680e+02 1.19222321e+02 1.19115875e+02 1.19042854e+02 1.18996819e+02 1.19006134e+02 1.18981949e+02 1.18983795e+02 1.18944183e+02 1.18924995e+02 1.18869766e+02 1.18867714e+02 1.18814308e+02 1.18773430e+02 1.18733894e+02 1.18729553e+02 1.18765945e+02 1.18792068e+02 1.18800385e+02 1.18814697e+02 1.18784035e+02 1.18809074e+02 1.18838676e+02 1.18909210e+02 1.18931358e+02 1.18879448e+02 1.18840096e+02 1.18862411e+02 1.18894173e+02 1.18904175e+02 1.18875290e+02 1.18837822e+02 1.18848221e+02 1.18846695e+02 1.18889969e+02 1.18885208e+02 1.18916862e+02 1.18914154e+02 1.18914330e+02 1.18859886e+02 1.18856682e+02 1.18878822e+02 1.18943031e+02 1.18943985e+02 1.18882187e+02 1.18847145e+02 1.18850571e+02 1.18855217e+02 1.18807312e+02 1.18724861e+02 1.18664284e+02 1.18633606e+02 1.18627533e+02 1.18604973e+02 1.18547729e+02 1.18456261e+02 1.18434540e+02 1.18417717e+02 1.18394150e+02 1.18350143e+02 1.18315140e+02 1.18279160e+02 1.18190536e+02 1.18160706e+02 1.18145187e+02 1.18187035e+02 1.18206467e+02 1.18200958e+02 1.18181564e+02 1.18153366e+02 1.18110817e+02 1.18074120e+02 1.18081497e+02 1.18128311e+02 1.18188698e+02 1.18243767e+02 1.18268715e+02 1.18263481e+02 1.18256233e+02 1.18284561e+02 1.18349777e+02 1.18406151e+02 1.18456650e+02 1.18474548e+02 1.18485596e+02 1.18486954e+02 1.18536018e+02 1.18526443e+02 1.18492966e+02 1.18394821e+02 1.18323677e+02 1.18262283e+02 1.18225983e+02 1.18204926e+02 1.18227974e+02 1.18271706e+02 1.18332977e+02 1.18380531e+02 1.18378441e+02 1.18387718e+02 1.18320679e+02 1.18268898e+02 1.18177551e+02 1.18148109e+02 1.18150749e+02 1.18211578e+02 1.18301247e+02 1.18380653e+02 1.18403847e+02 1.18441811e+02 1.18459389e+02 1.18442833e+02 1.18394295e+02 1.18374458e+02 1.18376503e+02 1.18376808e+02 1.18362701e+02 1.18345711e+02 1.18426437e+02 1.18521881e+02 1.18615616e+02 1.18639160e+02 1.18663628e+02 1.18716034e+02 1.18748894e+02 1.18694656e+02 1.18697411e+02 1.18781754e+02 1.18906708e+02 1.18968239e+02 1.18965210e+02 1.18908981e+02 1.18842957e+02 1.18785233e+02 1.18815132e+02 1.18793304e+02 1.18783073e+02 1.18746025e+02 1.18735161e+02 1.18766670e+02 1.18781815e+02 1.18870728e+02 1.18882202e+02 1.18909042e+02 1.18854073e+02 1.18827156e+02 1.18787125e+02 1.18778267e+02 1.18757545e+02 1.18742287e+02 1.18732895e+02 1.18758774e+02 1.18795753e+02 1.18864372e+02 1.18922501e+02 1.18980934e+02 1.19022270e+02 1.19056938e+02 1.19084427e+02 1.19092407e+02 1.19042419e+02 1.19037697e+02 1.19016388e+02 1.19089058e+02 1.19145645e+02 1.19229630e+02 1.19265106e+02 1.19252251e+02 1.19267700e+02 1.19255775e+02 1.19243126e+02 1.19193832e+02 1.19151329e+02 1.19143562e+02 1.19138931e+02 1.19125519e+02 1.19082481e+02 1.19017769e+02 1.19010101e+02 1.19036751e+02 1.19077583e+02 1.19080688e+02 1.19060768e+02 1.19053734e+02 1.19000168e+02 1.19008598e+02 1.19064110e+02 1.19111320e+02 1.19145325e+02 1.19101387e+02 1.19108360e+02 1.19063744e+02 1.19063400e+02 1.19078598e+02 1.19072235e+02 1.19027451e+02 1.18982895e+02 1.19009071e+02 1.19058861e+02 1.19048981e+02 1.19036545e+02 1.19042046e+02 1.19046021e+02 1.19022095e+02 1.18968254e+02 1.18967468e+02 1.18963333e+02 1.18931770e+02 1.18886436e+02 1.18853920e+02 1.18875565e+02 1.18884430e+02 1.18895325e+02 1.18891273e+02 1.18888130e+02 1.18908760e+02 1.18936157e+02 1.18982010e+02 1.19024521e+02 1.19035614e+02 1.19030441e+02 1.19015381e+02 1.19046577e+02 1.19122025e+02 1.19198441e+02 1.19264458e+02 1.19287201e+02 1.19289207e+02 1.19279976e+02 1.19252487e+02 1.19263687e+02 1.19276619e+02 1.19302109e+02 1.19315674e+02 1.19333817e+02 1.19355934e+02 1.19445435e+02 1.19512405e+02 1.19592712e+02 1.19599632e+02 1.19561798e+02 1.19484024e+02 1.19487923e+02 1.19514969e+02 1.19613037e+02 1.19669319e+02 1.19756088e+02 1.19795708e+02 1.19830353e+02 1.19860146e+02 1.19877113e+02 1.19889809e+02 1.19879524e+02 1.19826164e+02 1.19789528e+02 1.19743309e+02 1.19743797e+02 1.19739922e+02 1.19721344e+02 1.19658478e+02 1.19540306e+02 1.19465034e+02 1.19367210e+02 1.19257103e+02 1.19070969e+02 1.18966675e+02 1.18936676e+02 1.18967964e+02 1.18975334e+02 1.18935730e+02 1.18880592e+02 1.18820908e+02 1.18803177e+02 1.18859665e+02 1.18889046e+02 1.18936356e+02 1.18860504e+02 1.18846527e+02 1.18806015e+02 1.18808304e+02 1.18787888e+02 1.18787796e+02 1.18826363e+02 1.18869186e+02 1.18888046e+02 1.18883362e+02 1.18866623e+02 1.18899590e+02 1.18916603e+02 1.18938942e+02 1.18930763e+02 1.18944275e+02 1.18952904e+02 1.18984650e+02 1.19058609e+02 1.19065842e+02 1.19087196e+02 1.19082520e+02 1.19030037e+02 1.18960663e+02 1.18921822e+02 1.18965134e+02 1.19038933e+02 1.19004372e+02 1.18973587e+02 1.18916916e+02 1.18944290e+02 1.18980934e+02 1.19021210e+02 1.19016151e+02 1.19011307e+02 1.18990562e+02 1.19054771e+02 1.19071442e+02 1.19106552e+02 1.19085213e+02 1.19110634e+02 1.19141243e+02 1.19192307e+02 1.19228622e+02 1.19301140e+02 1.19331123e+02 1.19437698e+02 1.19506248e+02 1.19569092e+02 1.19573982e+02 1.19557533e+02 1.19540764e+02 1.19517555e+02 1.19522751e+02 1.19558327e+02 1.19528694e+02 1.19489761e+02 1.19416718e+02 1.19421532e+02 1.19409248e+02 1.19386269e+02 1.19328171e+02 1.19279137e+02 1.19281097e+02 1.19296539e+02 1.19315681e+02 1.19300591e+02 1.19247673e+02 1.19207893e+02 1.19223907e+02 1.19266968e+02 1.19283974e+02 1.19237251e+02 1.19256966e+02 1.19314789e+02 1.19412376e+02 1.19419815e+02 1.19412460e+02 1.19383759e+02 1.19380211e+02 1.19363472e+02 1.19359085e+02 1.19322472e+02 1.19316437e+02 1.19297867e+02 1.19277008e+02 1.19268364e+02 1.19274956e+02 1.19310730e+02 1.19377975e+02 1.19453995e+02 1.19473412e+02 1.19448898e+02 1.19404305e+02 1.19241455e+02 1.22961853e+02 1.26775246e+02 1.30984055e+02 1.30979752e+02 1.29139557e+02 1.27566620e+02 1.26084175e+02 1.25691101e+02 1.25061829e+02 1.24209312e+02 1.23525261e+02 1.21798592e+02 1.22389732e+02 1.64295807e+02 2.57866638e+02 7.71040283e+02 1.60361194e+03 5.84523571e+09 -3.23326464e+09 0. 3.57584978e+10 3.57584978e+10 3.57584978e+10 0. 0. -1120734336. -1120734336. -1120734336. 8.43902925e+09 4.62116550e+06 2.45194355e+04 1.09914331e+03 6.98019775e+02 2.61498322e+02 1.88294754e+02 1.37461716e+02 1.33784439e+02 1.24951126e+02 1.20010452e+02 1.17397888e+02 1.23985603e+02 1.32634415e+02 1.34775177e+02 1.25997223e+02 1.20452354e+02 1.20630562e+02 1.22574173e+02 1.21471863e+02 1.20751854e+02 1.21026611e+02 1.21906448e+02 1.24069054e+02 1.30665070e+02 1.38382141e+02 1.42513702e+02 1.40515930e+02 1.33885193e+02 1.23891869e+02 1.09528473e+02 1.05846855e+02 1.07773521e+02 1.14323761e+02 1.15942818e+02 1.17496704e+02 1.19093582e+02 1.21043175e+02 1.20689178e+02 1.19850891e+02 1.19241127e+02 1.19010834e+02 1.18936867e+02 1.18940804e+02 1.18960564e+02 1.18993523e+02 1.18975433e+02 1.18973587e+02 1.18984657e+02 1.19075523e+02 1.19089073e+02 1.19140236e+02 1.19095299e+02 1.19062332e+02 1.19011185e+02 1.19028580e+02 1.18069778e+02 1.17275253e+02 1.15473991e+02 1.14446007e+02 1.13151497e+02 1.12916580e+02 1.12998383e+02 1.13046448e+02 1.13058830e+02 1.12980247e+02 1.12926201e+02 1.12817650e+02 1.12804283e+02 1.12764313e+02 1.12707314e+02 1.12674675e+02 1.12649635e+02 1.12656677e+02 1.12632706e+02 1.12630775e+02 1.12509071e+02 1.12331924e+02 1.12161026e+02 1.12582489e+02 1.12846809e+02 1.13056786e+02 1.12514847e+02 1.12263611e+02 1.11979065e+02 1.11929497e+02 1.12595291e+02 1.14189209e+02 1.14820793e+02 1.16339424e+02 3.34453003e+03 1.90613342e+02 1.57107483e+02 2.32959366e+02 4.91729950e+02 4.80951569e+02 4.76325867e+02 4.75854248e+02 4.68568909e+02 4.60772247e+02 4.47832672e+02 4.42118286e+02 4.35693359e+02 2.41846741e+02 1.68408569e+02 1.26411385e+02 1.26490952e+02 1.23587524e+02 1.22466751e+02 1.21845123e+02 1.21622917e+02 1.21447021e+02 1.21317444e+02 1.21277870e+02 1.21386360e+02 1.21602432e+02 1.21821907e+02 1.22158325e+02 1.22341591e+02 1.22326576e+02 1.22000381e+02 1.21659836e+02 1.21458908e+02 1.21424248e+02 1.21485802e+02 1.21548698e+02 1.21618355e+02 1.21640579e+02 1.21644073e+02 1.21634941e+02 1.21582619e+02 1.21551689e+02 1.21473137e+02 1.21462204e+02 1.21450638e+02 1.21407799e+02 1.21359619e+02 1.21320091e+02 1.21304886e+02 1.21314079e+02 1.21273445e+02 1.21267029e+02 1.21224037e+02 1.21212799e+02 1.21210938e+02 1.21231094e+02 1.21201668e+02 1.21211555e+02 1.21228256e+02 1.21253960e+02 1.21246803e+02 1.21238693e+02 1.21245636e+02 1.21277596e+02 1.21305534e+02 1.21330002e+02 1.21333290e+02 1.21272705e+02 1.21229904e+02 1.21131302e+02 1.21065697e+02 1.21003059e+02 1.21019531e+02 1.21018669e+02 1.21070564e+02 1.21198456e+02 1.21598969e+02 1.23114746e+02 1.27989998e+02 1.33958557e+02 1.74862381e+02 3.13931396e+02 1.69304102e+03 -312798272. -450893216. 0. -645391168. -645391168. -645391168. 0. -375361056. -375361056. 12805715. 1855519232. -5.08326250e+06 1854898688. 1854898688. 0. -1256041728. 1.44703772e+03 7.11116211e+02 2.47021591e+02 1.61609818e+02 1.28086533e+02 1.27363327e+02 1.29197891e+02 1.27695465e+02 1.25479721e+02 1.23603333e+02 1.24328957e+02 1.22914581e+02 1.21954414e+02 1.20304939e+02 1.20552902e+02 1.20868515e+02 1.21117348e+02 1.21226318e+02 1.21276505e+02 1.21261658e+02 1.21282562e+02 1.21266396e+02 1.21273720e+02 1.21273499e+02 1.21289650e+02 1.21306717e+02 1.21368294e+02 1.21467987e+02 1.21597923e+02 1.21686920e+02 1.21715622e+02 1.21708260e+02 1.21705460e+02 1.21769432e+02 1.21836411e+02 1.21852455e+02 1.21815575e+02 1.21695457e+02 1.21580246e+02 1.21547684e+02 1.21584175e+02 1.21662544e+02 1.21661163e+02 1.21670784e+02 1.21673950e+02 1.21701881e+02 1.21728577e+02 1.21794975e+02 1.21839043e+02 1.21851372e+02 1.21905014e+02 1.21956543e+02 1.22047432e+02 1.22015175e+02 1.22040146e+02 1.22007538e+02 1.22032700e+02 1.22053444e+02 1.22097282e+02 1.22130264e+02 1.22079514e+02 1.22063972e+02 1.22020966e+02 1.22066231e+02 1.22081375e+02 1.22148247e+02 1.22174255e+02 1.22186409e+02 1.22148239e+02 1.22091705e+02 1.22027588e+02 1.21982422e+02 1.21968224e+02 1.22062988e+02 1.22230423e+02 1.22389748e+02 1.22454819e+02 1.22448570e+02 1.22452682e+02 1.22500824e+02 1.22564384e+02 1.22578545e+02 1.22594398e+02 1.22596077e+02 1.22586151e+02 1.22551033e+02 1.22525856e+02 1.22551147e+02 1.22600311e+02 1.22626167e+02 1.22656143e+02 1.22669182e+02 1.22714813e+02 1.22723938e+02 1.22706001e+02 1.22645729e+02 1.22621887e+02 1.22594749e+02 1.22602211e+02 1.22613174e+02 1.22652039e+02 1.22647232e+02 1.22661850e+02 1.22681503e+02 1.22675026e+02 1.22623344e+02 1.22572899e+02 1.22536575e+02 1.22540993e+02 1.22537277e+02 1.22566154e+02 1.22543625e+02 1.22525276e+02 1.22553810e+02 1.22615990e+02 1.22675735e+02 1.22663116e+02 1.22618629e+02 1.22593758e+02 1.22631508e+02 1.22671181e+02 1.22659027e+02 1.22650826e+02 1.22670769e+02 1.22733055e+02 1.22710945e+02 1.22663475e+02 1.22566704e+02 1.22532524e+02 1.22547188e+02 1.22541718e+02 1.22546997e+02 1.22522316e+02 1.22559204e+02 1.22536797e+02 1.22461395e+02 1.22449265e+02 1.22520134e+02 1.22599922e+02 1.22651169e+02 1.22640038e+02 1.22645233e+02 1.22623489e+02 1.22617165e+02 1.22622520e+02 1.22619507e+02 1.22638443e+02 1.22667953e+02 1.22716187e+02 1.22713631e+02 1.22701729e+02 1.22642586e+02 1.22618011e+02 1.22630943e+02 1.22680870e+02 1.22685143e+02 1.22692665e+02 1.22699570e+02 1.22711205e+02 1.22693611e+02 1.22670349e+02 1.22654770e+02 1.22718231e+02 1.22816467e+02 1.22927330e+02 1.22994240e+02 1.23011322e+02 1.22980331e+02 1.22956482e+02 1.23025063e+02 1.23066620e+02 1.23060379e+02 1.23035629e+02 1.23071419e+02 1.23175255e+02 1.23267731e+02 1.23389374e+02 1.23474358e+02 1.23569115e+02 1.23668953e+02 1.23691620e+02 1.23592552e+02 1.23376038e+02 1.23184425e+02 1.23061531e+02 1.23069992e+02 1.23121529e+02 1.23168640e+02 1.23163490e+02 1.23142593e+02 1.23145157e+02 1.23175407e+02 1.23178818e+02 1.23106056e+02 1.23012054e+02 1.22958328e+02 1.22924370e+02 1.22931656e+02 1.22868927e+02 1.22820862e+02 1.22739342e+02 1.22683304e+02 1.22669266e+02 1.22571274e+02 1.22457253e+02 1.22384521e+02 1.22386299e+02 1.22401550e+02 1.22374985e+02 1.22351074e+02 1.22294243e+02 1.22338440e+02 1.22390846e+02 1.22362030e+02 1.22347076e+02 1.22304337e+02 1.22265030e+02 1.22150169e+02 1.22105865e+02 1.22070137e+02 1.22126678e+02 1.22149078e+02 1.22185562e+02 1.22114784e+02 1.22051842e+02 1.21986832e+02 1.21982582e+02 1.21992149e+02 1.22046028e+02 1.22092102e+02 1.22080307e+02 1.22040970e+02 1.21958229e+02 1.21942207e+02 1.21930542e+02 1.21922127e+02 1.21874825e+02 1.21857445e+02 1.21840927e+02 1.21822853e+02 1.21809517e+02 1.21829597e+02 1.21836372e+02 1.21814247e+02 1.21770691e+02 1.21763710e+02 1.21752136e+02 1.21749123e+02 1.21762299e+02 1.21816124e+02 1.21839348e+02 1.21786194e+02 1.21741112e+02 1.21730293e+02 1.21752663e+02 1.21748604e+02 1.21821625e+02 1.21894135e+02 1.21958755e+02 1.21936646e+02 1.21956696e+02 1.21926247e+02 1.21898018e+02 1.21824387e+02 1.21797455e+02 1.21817635e+02 1.21896530e+02 1.21963120e+02 1.21968330e+02 1.21943039e+02 1.21938660e+02 1.21913757e+02 1.21939072e+02 1.21918915e+02 1.21949265e+02 1.21962242e+02 1.21968315e+02 1.21955605e+02 1.21888069e+02 1.21921120e+02 1.21944580e+02 1.21991203e+02 1.21954422e+02 1.21973854e+02 1.22034210e+02 1.22071320e+02 1.22078789e+02 1.22050529e+02 1.22060837e+02 1.22022148e+02 1.22025200e+02 1.21984047e+02 1.21972351e+02 1.21915161e+02 1.21912964e+02 1.21902870e+02 1.21932579e+02 1.21954468e+02 1.21919067e+02 1.21894066e+02 1.21868027e+02 1.21891785e+02 1.21841049e+02 1.21795280e+02 1.21780083e+02 1.21829529e+02 1.21877686e+02 1.21929230e+02 1.21957184e+02 1.21953087e+02 1.21899109e+02 1.21890877e+02 1.21859909e+02 1.21914337e+02 1.21934143e+02 1.21985435e+02 1.22042046e+02 1.22062843e+02 1.22042091e+02 1.21980354e+02 1.21948029e+02 1.21955154e+02 1.21959679e+02 1.21946167e+02 1.21907188e+02 1.21861900e+02 1.21838699e+02 1.21821594e+02 1.21807991e+02 1.21781921e+02 1.21780907e+02 1.21775574e+02 1.21777100e+02 1.21765656e+02 1.21754204e+02 1.21779373e+02 1.21840225e+02 1.21890427e+02 1.21909042e+02 1.21897049e+02 1.21871399e+02 1.21869781e+02 1.21875458e+02 1.21892090e+02 1.21922173e+02 1.21963707e+02 1.21997910e+02 1.22007599e+02 1.22020744e+02 1.22061394e+02 1.22110283e+02 1.22134628e+02 1.22144447e+02 1.22111786e+02 1.22092354e+02 1.22080956e+02 1.22108246e+02 1.22112366e+02 1.22144333e+02 1.22157494e+02 1.22192741e+02 1.22190117e+02 1.22211121e+02 1.22195137e+02 1.22188667e+02 1.22174629e+02 1.22179680e+02 1.22163773e+02 1.22129890e+02 1.22103058e+02 1.22078094e+02 1.22072838e+02 1.22053520e+02 1.22063766e+02 1.22070038e+02 1.22118561e+02 1.22140152e+02 1.22129837e+02 1.22115318e+02 1.22096878e+02 1.22118393e+02 1.22111015e+02 1.22098412e+02 1.22066292e+02 1.22048920e+02 1.22027466e+02 1.22019463e+02 1.22011307e+02 1.22004921e+02 1.21993637e+02 1.21995544e+02 1.22010689e+02 1.22011063e+02 1.22007271e+02 1.21985428e+02 1.21957169e+02 1.21927849e+02 1.21894081e+02 1.21848175e+02 1.21820381e+02 1.21831795e+02 1.21851776e+02 1.21886597e+02 1.21889160e+02 1.21887665e+02 1.21843781e+02 1.21812019e+02 1.21802666e+02 1.21806335e+02 1.21789940e+02 1.21813408e+02 1.21785881e+02 1.21778847e+02 1.21742447e+02 1.21767197e+02 1.21772293e+02 1.21811722e+02 1.21838959e+02 1.21850418e+02 1.21872536e+02 1.21876930e+02 1.21883980e+02 1.21875954e+02 1.21848038e+02 1.21859947e+02 1.21853386e+02 1.21867676e+02 1.21859596e+02 1.21858902e+02 1.21841431e+02 1.21837822e+02 1.21840332e+02 1.21815117e+02 1.21773071e+02 1.21732285e+02 1.21679504e+02 1.21640366e+02 1.21595901e+02 1.21524139e+02 1.21430016e+02 1.21312714e+02 1.21228241e+02 1.21168961e+02 1.21149574e+02 1.21136047e+02 1.21113129e+02 1.21100296e+02 1.21109268e+02 1.21138817e+02 1.21180496e+02 1.21179558e+02 1.21135452e+02 1.21101082e+02 1.21082489e+02 1.21094757e+02 1.21078400e+02 1.21051964e+02 1.21035789e+02 1.21014992e+02 1.21007988e+02 1.21032898e+02 1.21061287e+02 1.21151039e+02 1.21237389e+02 1.21319710e+02 1.21402420e+02 1.21429276e+02 1.21461037e+02 1.21437660e+02 1.21430756e+02 1.21423439e+02 1.21421341e+02 1.21420280e+02 1.21356644e+02 1.21327469e+02 1.21286736e+02 1.21285355e+02 1.21244446e+02 1.21196686e+02 1.21151085e+02 1.21124779e+02 1.21108337e+02 1.21090446e+02 1.21080750e+02 1.21078110e+02 1.21058197e+02 1.21015465e+02 1.20992523e+02 1.20943504e+02 1.20869614e+02 1.20811905e+02 1.20782753e+02 1.20759514e+02 1.20724838e+02 1.20660797e+02 1.20661247e+02 1.20667107e+02 1.20682137e+02 1.20647629e+02 1.20607353e+02 1.20605453e+02 1.20624557e+02 1.20673668e+02 1.20690002e+02 1.20662743e+02 1.20645943e+02 1.20633507e+02 1.20644508e+02 1.20675415e+02 1.20766251e+02 1.20845909e+02 1.20879234e+02 1.20887589e+02 1.20907784e+02 1.20966454e+02 1.20987976e+02 1.21039742e+02 1.21068848e+02 1.21095108e+02 1.21119469e+02 1.21117401e+02 1.21186081e+02 1.21218910e+02 1.21279640e+02 1.21230415e+02 1.21164551e+02 1.21116043e+02 1.21060951e+02 1.21038857e+02 1.21005501e+02 1.21023857e+02 1.21027283e+02 1.21047867e+02 1.21060455e+02 1.21112442e+02 1.21124908e+02 1.21136070e+02 1.21135658e+02 1.21169136e+02 1.21247673e+02 1.21322289e+02 1.21444420e+02 1.21523361e+02 1.21605484e+02 1.21603233e+02 1.21607903e+02 1.21589272e+02 1.21524193e+02 1.21432152e+02 1.21376450e+02 1.21377808e+02 1.21416031e+02 1.21477592e+02 1.21497932e+02 1.21513130e+02 1.21475975e+02 1.21434601e+02 1.21393105e+02 1.21342987e+02 1.21358955e+02 1.21385872e+02 1.21384026e+02 1.21355598e+02 1.21347038e+02 1.21336037e+02 1.21303970e+02 1.21325943e+02 1.21361694e+02 1.21395973e+02 1.21411659e+02 1.21441307e+02 1.21462784e+02 1.21464569e+02 1.21404449e+02 1.21334274e+02 1.21313004e+02 1.21331245e+02 1.21393227e+02 1.21436028e+02 1.21476295e+02 1.21474838e+02 1.21458786e+02 1.21468025e+02 1.21538162e+02 1.21586769e+02 1.21670631e+02 1.21681564e+02 1.21665588e+02 1.21613861e+02 1.21585838e+02 1.21565666e+02 1.21524307e+02 1.21457558e+02 1.21435921e+02 1.21446548e+02 1.21493202e+02 1.21496841e+02 1.21500389e+02 1.21530800e+02 1.21534988e+02 1.21545708e+02 1.21572983e+02 1.21632164e+02 1.21735901e+02 1.21776672e+02 1.21791466e+02 1.21800507e+02 1.21814743e+02 1.21842278e+02 1.21820030e+02 1.21809761e+02 1.21828285e+02 1.21872131e+02 1.21894241e+02 1.21902809e+02 1.21891342e+02 1.21877701e+02 1.21858200e+02 1.21863464e+02 1.21881432e+02 1.21880531e+02 1.21935875e+02 1.21969246e+02 1.22025848e+02 1.22010857e+02 1.21996346e+02 1.22010979e+02 1.22001068e+02 1.22008980e+02 1.21974495e+02 1.22010689e+02 1.22023026e+02 1.22049919e+02 1.22025467e+02 1.22016190e+02 1.21988518e+02 1.22045570e+02 1.22103836e+02 1.22090385e+02 1.21959412e+02 1.21847641e+02 1.21846306e+02 1.21837051e+02 1.21814682e+02 1.21786827e+02 1.21781982e+02 1.21804214e+02 1.21797684e+02 1.21813454e+02 1.21801514e+02 1.21773392e+02 1.21768631e+02 1.21741432e+02 1.21760979e+02 1.21771507e+02 1.21736069e+02 1.21702164e+02 1.21600479e+02 1.21556114e+02 1.21528427e+02 1.21604538e+02 1.21681038e+02 1.21760681e+02 1.21791870e+02 1.21786743e+02 1.21776360e+02 1.21739799e+02 1.21786232e+02 1.21790459e+02 1.21795738e+02 1.21748795e+02 1.21716927e+02 1.21723175e+02 1.21694016e+02 1.21607368e+02 1.21548080e+02 1.21516205e+02 1.21535004e+02 1.21571175e+02 1.21591171e+02 1.21614189e+02 1.21646164e+02 1.21703323e+02 1.21720566e+02 1.21767792e+02 1.21767456e+02 1.21844276e+02 1.21901726e+02 1.21921631e+02 1.21916260e+02 1.21897362e+02 1.21946304e+02 1.21946426e+02 1.21864265e+02 1.21728806e+02 1.21650078e+02 1.21582146e+02 1.21524864e+02 1.21492424e+02 1.21521790e+02 1.21555969e+02 1.21491547e+02 1.21462204e+02 1.21401451e+02 1.21480408e+02 1.21523582e+02 1.21664459e+02 1.21697617e+02 1.21738907e+02 1.21702110e+02 1.21709946e+02 1.21686920e+02 1.21688416e+02 1.21690872e+02 1.21751465e+02 1.21744080e+02 1.21749123e+02 1.21690681e+02 1.21693527e+02 1.21642471e+02 1.21588188e+02 1.21545738e+02 1.21501953e+02 1.21484482e+02 1.21481888e+02 1.21434669e+02 1.21493179e+02 1.21536957e+02 1.21688782e+02 1.21718002e+02 1.21796097e+02 1.21729309e+02 1.21681625e+02 1.21572823e+02 1.21528419e+02 1.21511307e+02 1.21541031e+02 1.21582603e+02 1.21646866e+02 1.21642990e+02 1.21694855e+02 1.21739166e+02 1.21805489e+02 1.21762177e+02 1.21726807e+02 1.21685425e+02 1.21615089e+02 1.21509438e+02 1.21528214e+02 1.21612511e+02 1.21687813e+02 1.21686668e+02 1.21665985e+02 1.21683784e+02 1.21683090e+02 1.21667389e+02 1.21633293e+02 1.21636063e+02 1.21697548e+02 1.21760208e+02 1.21725357e+02 1.21678467e+02 1.21658417e+02 1.21673309e+02 1.21663696e+02 1.21627876e+02 1.21615540e+02 1.21651787e+02 1.21707794e+02 1.21729599e+02 1.21747063e+02 1.21737709e+02 1.21748993e+02 1.21709793e+02 1.21681862e+02 1.21665955e+02 1.21655800e+02 1.21692726e+02 1.21733856e+02 1.21761017e+02 1.21776840e+02 1.21767433e+02 1.21812965e+02 1.21777489e+02 1.21753212e+02 1.21703163e+02 1.21726616e+02 1.21770683e+02 1.21791420e+02 1.21783226e+02 1.21752144e+02 1.21712128e+02 1.21673492e+02 1.21640015e+02 1.21655487e+02 1.21699997e+02 1.21763245e+02 1.21836632e+02 1.21890259e+02 1.21942078e+02 1.21924652e+02 1.21865250e+02 1.21847862e+02 1.21830750e+02 1.21853004e+02 1.21843750e+02 1.21866692e+02 1.21862976e+02 1.21931427e+02 1.25300262e+02 1.28535751e+02 1.31787964e+02 1.31743500e+02 1.31743408e+02 1.32141815e+02 1.32757355e+02 1.33001144e+02 1.32793533e+02 1.31933456e+02 1.30961609e+02 1.28799194e+02 1.29865372e+02 1.75268295e+02 2.72273956e+02 7.83510193e+02 1.53114233e+03 -21499044. 8.95333125e+05 3.57584978e+10 3.57584978e+10 -252834768. -252834768. 3.19644925e+06 -1120734336. -1120734336. 0. 0. 0. -4.29172941e+09 -92296392. 1.11170178e+03 6.70399048e+02 4.86398010e+02 2.79869843e+02 1.85849533e+02 1.38848709e+02 1.39022415e+02 1.35136032e+02 1.31805389e+02 1.31145447e+02 1.30161118e+02 1.28510330e+02 1.26728455e+02 1.26657341e+02 1.26841438e+02 1.27010254e+02 1.28344238e+02 1.31171188e+02 1.33261444e+02 1.33508896e+02 1.31946060e+02 1.31643921e+02 1.26677139e+02 1.26238113e+02 1.26836227e+02 1.29583801e+02 1.27016167e+02 1.21814049e+02 1.16291565e+02 1.14962692e+02 1.16353683e+02 1.19302109e+02 1.21031906e+02 1.21855003e+02 1.22135498e+02 1.22098297e+02 1.21872009e+02 1.21651154e+02 1.21539948e+02 1.21468948e+02 1.21492630e+02 1.21463776e+02 1.21478485e+02 1.21493980e+02 1.21587204e+02 1.21765762e+02 1.21977341e+02 1.22206627e+02 1.22300804e+02 1.22349869e+02 1.22202194e+02 1.22129402e+02 1.21879829e+02 1.21773582e+02 1.21891197e+02 1.21994537e+02 1.22130051e+02 1.22227829e+02 1.22175690e+02 1.22045242e+02 1.21828140e+02 1.21652115e+02 1.21527008e+02 1.21568138e+02 1.22116577e+02 1.22631004e+02 1.23482887e+02 1.24206154e+02 1.25742142e+02 1.28835281e+02 1.28498291e+02 1.58207855e+02 1.51196320e+02 2.16522415e+02 2.32163467e+02 2.50672455e+02 1.64787628e+02 1.22693962e+02 1.23548958e+02 1.23609680e+02 1.21877541e+02 1.21908310e+02 1.22342880e+02 1.22216660e+02 1.23574608e+02 4794650. 7.53095703e+02 6.89850159e+02 1.36850537e+03 3.47935760e+02 2.40072327e+02 3.13123627e+02 -1185847168. -331911936. 3.68268494e+02 1.86039124e+02 1.27959656e+02 1.28204651e+02 1.28066620e+02 1.28899216e+02 1.29558655e+02 1.29337646e+02 1.26692673e+02 1.23775970e+02 1.21489456e+02 1.20452904e+02 1.20510422e+02 1.21129730e+02 1.21717354e+02 1.22087578e+02 1.22271950e+02 1.22359673e+02 1.22408920e+02 1.22439507e+02 1.22545509e+02 1.22726013e+02 1.22883316e+02 1.22916603e+02 1.22812187e+02 1.22691612e+02 1.22631393e+02 1.22624687e+02 1.22619431e+02 1.22667847e+02 1.22830894e+02 1.23045135e+02 1.23167450e+02 1.23120911e+02 1.23074699e+02 1.23064743e+02 1.23119438e+02 1.23141212e+02 1.23178070e+02 1.23170395e+02 1.23181900e+02 1.23143944e+02 1.23130486e+02 1.23076149e+02 1.22873665e+02 1.22668495e+02 1.22478035e+02 1.22464699e+02 1.22471451e+02 1.22463539e+02 1.22486946e+02 1.22505310e+02 1.22519455e+02 1.22538322e+02 1.22543533e+02 1.22552628e+02 1.22557388e+02 1.22579681e+02 1.22564522e+02 1.22521255e+02 1.22449837e+02 1.22420815e+02 1.22420517e+02 1.22470772e+02 1.22555138e+02 1.22801781e+02 1.23605927e+02 1.26254562e+02 1.63214630e+02 2.55267303e+02 5.84619141e+02 8.29952271e+02 1.76911853e+03 557518208. 0. 0. -44978044. -44978044. -44978044. 0. 0. -375361056. -375361056. -375361056. 0. 1854898688. 1854898688. -4369092. 1.96343521e+10 1.30143298e+03 2.89710449e+02 1.60207794e+02 1.26165840e+02 1.26099525e+02 1.24999016e+02 1.23356201e+02 1.21801926e+02 1.21973488e+02 1.21794746e+02 1.21426392e+02 1.20970848e+02 1.20875572e+02 1.21171677e+02 1.21691673e+02 1.22034012e+02 1.22168098e+02 1.22240364e+02 1.22253464e+02 1.22260918e+02 1.22242897e+02 1.22237236e+02 1.22218636e+02 1.22220619e+02 1.22200523e+02 1.22174309e+02 1.22163818e+02 1.22176460e+02 1.22200142e+02 1.22223114e+02 1.22246094e+02 1.22359398e+02 1.22418938e+02 1.22474258e+02 1.22423386e+02 1.22378738e+02 1.22301613e+02 1.22201118e+02 1.22094780e+02 1.22063591e+02 1.22112320e+02 1.22130417e+02 1.22154968e+02 1.22176918e+02 1.22222641e+02 1.22301849e+02 1.22352821e+02 1.22384705e+02 1.22361725e+02 1.22364510e+02 1.22449928e+02 1.22529564e+02 1.22570953e+02 1.22572975e+02 1.22581833e+02 1.22631157e+02 1.22697685e+02 1.22715363e+02 1.22689255e+02 1.22640617e+02 1.22523521e+02 1.22393684e+02 1.22210350e+02 1.22070366e+02 1.22021370e+02 1.22077911e+02 1.22257408e+02 1.22384750e+02 1.22513702e+02 1.22560570e+02 1.22574203e+02 1.22553421e+02 1.22531891e+02 1.22561447e+02 1.22561188e+02 1.22582367e+02 1.22583572e+02 1.22653755e+02 1.22714355e+02 1.22767868e+02 1.22781502e+02 1.22771194e+02 1.22758240e+02 1.22719589e+02 1.22719849e+02 1.22717331e+02 1.22758888e+02 1.22809975e+02 1.22865158e+02 1.22927742e+02 1.22984734e+02 1.23045944e+02 1.23078964e+02 1.23080750e+02 1.23067070e+02 1.23044403e+02 1.23038612e+02 1.23104034e+02 1.23180435e+02 1.23248772e+02 1.23266273e+02 1.23285538e+02 1.23309647e+02 1.23358063e+02 1.23380852e+02 1.23385986e+02 1.23366081e+02 1.23339096e+02 1.23326180e+02 1.23300247e+02 1.23309624e+02 1.23390121e+02 1.23429726e+02 1.23463257e+02 1.23387688e+02 1.23366371e+02 1.23296013e+02 1.23284378e+02 1.23233490e+02 1.23192627e+02 1.23171432e+02 1.23149193e+02 1.23168922e+02 1.23158173e+02 1.23184982e+02 1.23157829e+02 1.23144051e+02 1.23113998e+02 1.23099892e+02 1.23116112e+02 1.23107628e+02 1.23125999e+02 1.23106667e+02 1.23101311e+02 1.23120697e+02 1.23130768e+02 1.23107338e+02 1.23108414e+02 1.23102356e+02 1.23113319e+02 1.23070427e+02 1.23025307e+02 1.22987518e+02 1.22967262e+02 1.22955971e+02 1.22918327e+02 1.22832916e+02 1.22790207e+02 1.22765213e+02 1.22848846e+02 1.22865463e+02 1.22892609e+02 1.22879616e+02 1.22827354e+02 1.22791504e+02 1.22735046e+02 1.22700493e+02 1.22666466e+02 1.22675919e+02 1.22677261e+02 1.22682648e+02 1.22703026e+02 1.22740288e+02 1.22823822e+02 1.22855980e+02 1.22927071e+02 1.22907677e+02 1.22910194e+02 1.22934593e+02 1.23053185e+02 1.23176857e+02 1.23233780e+02 1.23210358e+02 1.23177841e+02 1.23189980e+02 1.23183556e+02 1.23179604e+02 1.23174377e+02 1.23185600e+02 1.23156174e+02 1.23072136e+02 1.22941597e+02 1.22849525e+02 1.22750679e+02 1.22663704e+02 1.22577309e+02 1.22590111e+02 1.22586296e+02 1.22615051e+02 1.22587952e+02 1.22644386e+02 1.22653473e+02 1.22632072e+02 1.22578773e+02 1.22562454e+02 1.22627754e+02 1.22663635e+02 1.22669601e+02 1.22679367e+02 1.22654984e+02 1.22711823e+02 1.22666649e+02 1.22695656e+02 1.22696968e+02 1.22825829e+02 1.22840210e+02 1.22829765e+02 1.22755302e+02 1.22688148e+02 1.22654213e+02 1.22612282e+02 1.22634583e+02 1.22623207e+02 1.22678314e+02 1.22664696e+02 1.22623466e+02 1.22538589e+02 1.22534576e+02 1.22589905e+02 1.22631927e+02 1.22623520e+02 1.22560562e+02 1.22504311e+02 1.22435234e+02 1.22386101e+02 1.22339767e+02 1.22309059e+02 1.22266014e+02 1.22224236e+02 1.22241318e+02 1.22266701e+02 1.22274300e+02 1.22285103e+02 1.22285538e+02 1.22312798e+02 1.22324364e+02 1.22350983e+02 1.22345680e+02 1.22330620e+02 1.22330185e+02 1.22355560e+02 1.22353279e+02 1.22348366e+02 1.22339111e+02 1.22375626e+02 1.22395851e+02 1.22428299e+02 1.22389885e+02 1.22406410e+02 1.22432037e+02 1.22491829e+02 1.22490120e+02 1.22465836e+02 1.22442543e+02 1.22446999e+02 1.22445213e+02 1.22409782e+02 1.22383850e+02 1.22401955e+02 1.22459297e+02 1.22466766e+02 1.22435837e+02 1.22391319e+02 1.22360703e+02 1.22345558e+02 1.22361549e+02 1.22379219e+02 1.22370689e+02 1.22387009e+02 1.22430481e+02 1.22490051e+02 1.22490440e+02 1.22489052e+02 1.22485641e+02 1.22501976e+02 1.22474167e+02 1.22456657e+02 1.22467140e+02 1.22485153e+02 1.22501450e+02 1.22473030e+02 1.22454651e+02 1.22465736e+02 1.22508057e+02 1.22525322e+02 1.22498322e+02 1.22454933e+02 1.22441147e+02 1.22422615e+02 1.22430656e+02 1.22416786e+02 1.22425438e+02 1.22424339e+02 1.22430801e+02 1.22395584e+02 1.22366158e+02 1.22336342e+02 1.22338295e+02 1.22332428e+02 1.22333199e+02 1.22325569e+02 1.22279243e+02 1.22286255e+02 1.22305481e+02 1.22322929e+02 1.22254501e+02 1.22200073e+02 1.22167747e+02 1.22200073e+02 1.22219650e+02 1.22217621e+02 1.22221558e+02 1.22193413e+02 1.22162323e+02 1.22125999e+02 1.22115494e+02 1.22112648e+02 1.22169563e+02 1.22303642e+02 1.22409309e+02 1.22430809e+02 1.22317123e+02 1.22280815e+02 1.22225685e+02 1.22234184e+02 1.22305542e+02 1.22367493e+02 1.22432434e+02 1.22417633e+02 1.22412964e+02 1.22428207e+02 1.22400658e+02 1.22448135e+02 1.22487617e+02 1.22547646e+02 1.22519875e+02 1.22467926e+02 1.22405678e+02 1.22416557e+02 1.22435661e+02 1.22460869e+02 1.22466721e+02 1.22499512e+02 1.22529259e+02 1.22541435e+02 1.22533173e+02 1.22528267e+02 1.22529060e+02 1.22522903e+02 1.22500618e+02 1.22516182e+02 1.22556007e+02 1.22597672e+02 1.22618660e+02 1.22617195e+02 1.22621155e+02 1.22621117e+02 1.22647446e+02 1.22668091e+02 1.22709099e+02 1.22728661e+02 1.22762238e+02 1.22770050e+02 1.22768394e+02 1.22782509e+02 1.22784096e+02 1.22784698e+02 1.22729156e+02 1.22690903e+02 1.22638023e+02 1.22651367e+02 1.22667496e+02 1.22717941e+02 1.22688293e+02 1.22661003e+02 1.22613289e+02 1.22612183e+02 1.22631248e+02 1.22627975e+02 1.22605743e+02 1.22526764e+02 1.22491318e+02 1.22447731e+02 1.22472160e+02 1.22508568e+02 1.22589859e+02 1.22604752e+02 1.22598213e+02 1.22606453e+02 1.22641022e+02 1.22630371e+02 1.22652863e+02 1.22680511e+02 1.22748184e+02 1.22737419e+02 1.22724495e+02 1.22673141e+02 1.22656952e+02 1.22658051e+02 1.22678909e+02 1.22695946e+02 1.22700722e+02 1.22703094e+02 1.22687706e+02 1.22687073e+02 1.22843842e+02 1.22993851e+02 1.23167953e+02 1.23077904e+02 1.22960678e+02 1.22857513e+02 1.22835709e+02 1.22809319e+02 1.22712318e+02 1.22711929e+02 1.22734612e+02 1.22777718e+02 1.22796791e+02 1.22800392e+02 1.22815086e+02 1.22807632e+02 1.22796753e+02 1.22786453e+02 1.22809441e+02 1.22840919e+02 1.22874794e+02 1.22864891e+02 1.22852646e+02 1.22811935e+02 1.22803658e+02 1.22620667e+02 1.22615364e+02 1.22611221e+02 1.22796356e+02 1.22762650e+02 1.22649223e+02 1.22574265e+02 1.22539871e+02 1.22589928e+02 1.22612846e+02 1.22627182e+02 1.22606003e+02 1.22556557e+02 1.22478378e+02 1.22444626e+02 1.22556931e+02 1.22547096e+02 1.22536911e+02 1.22389801e+02 1.22477913e+02 1.22578369e+02 1.22672745e+02 1.22589371e+02 1.22437431e+02 1.22324303e+02 1.22353127e+02 1.22377228e+02 1.22373299e+02 1.22376266e+02 1.22360374e+02 1.22323372e+02 1.22296173e+02 1.22303871e+02 1.22331978e+02 1.22344879e+02 1.22348938e+02 1.22375343e+02 1.22399078e+02 1.22455978e+02 1.22434013e+02 1.22404350e+02 1.22324013e+02 1.22336205e+02 1.22334885e+02 1.22352196e+02 1.22349434e+02 1.22303658e+02 1.22249580e+02 1.22236542e+02 1.22251244e+02 1.22315361e+02 1.22280792e+02 1.22119637e+02 1.21911201e+02 1.21880119e+02 1.21978149e+02 1.21997437e+02 1.21810944e+02 1.21731483e+02 1.21725792e+02 1.21882355e+02 1.21980919e+02 1.22099243e+02 1.22076561e+02 1.22086716e+02 1.22092377e+02 1.22085625e+02 1.22092430e+02 1.22089165e+02 1.22121201e+02 1.22132019e+02 1.22150352e+02 1.22112442e+02 1.22086975e+02 1.22104813e+02 1.22168175e+02 1.22220001e+02 1.22240356e+02 1.22240524e+02 1.22231781e+02 1.22214439e+02 1.22179955e+02 1.22159546e+02 1.22126823e+02 1.22126999e+02 1.22199463e+02 1.22254364e+02 1.22268959e+02 1.22158020e+02 1.22023048e+02 1.21888939e+02 1.21864662e+02 1.21993530e+02 1.22135712e+02 1.22203491e+02 1.22171707e+02 1.22159195e+02 1.22139091e+02 1.22144501e+02 1.22113167e+02 1.22087898e+02 1.22023994e+02 1.21968307e+02 1.21978981e+02 1.21993187e+02 1.22038712e+02 1.22050919e+02 1.22129997e+02 1.22218330e+02 1.22300484e+02 1.22343056e+02 1.22367867e+02 1.22260124e+02 1.22148331e+02 1.22039040e+02 1.22042068e+02 1.22021858e+02 1.22003189e+02 1.21950119e+02 1.21940315e+02 1.21913269e+02 1.21936363e+02 1.21974213e+02 1.21994781e+02 1.21993271e+02 1.21948387e+02 1.21891479e+02 1.21850945e+02 1.21854218e+02 1.21879692e+02 1.21892006e+02 1.21875732e+02 1.21862259e+02 1.21815720e+02 1.21782349e+02 1.21737526e+02 1.21717949e+02 1.21701012e+02 1.21712944e+02 1.21717857e+02 1.21745010e+02 1.21790085e+02 1.21846687e+02 1.21901093e+02 1.21918900e+02 1.21942566e+02 1.21965050e+02 1.21997589e+02 1.21989990e+02 1.21984428e+02 1.21974152e+02 1.21994797e+02 1.22012810e+02 1.22064453e+02 1.22121635e+02 1.22182579e+02 1.22239159e+02 1.22269577e+02 1.22262070e+02 1.22240387e+02 1.22212860e+02 1.22196487e+02 1.22155388e+02 1.22120911e+02 1.22085030e+02 1.22074478e+02 1.22077759e+02 1.22107140e+02 1.22130112e+02 1.22165070e+02 1.22155510e+02 1.22151299e+02 1.22140343e+02 1.22139771e+02 1.22154083e+02 1.22160355e+02 1.22193367e+02 1.22235863e+02 1.22281715e+02 1.22326469e+02 1.22345665e+02 1.22385788e+02 1.22429413e+02 1.22501160e+02 1.22556305e+02 1.22571434e+02 1.22561378e+02 1.22542572e+02 1.22523140e+02 1.22528053e+02 1.22530624e+02 1.22591133e+02 1.22637642e+02 1.22658241e+02 1.22664368e+02 1.22667656e+02 1.22712273e+02 1.22726624e+02 1.22728722e+02 1.22721687e+02 1.22750069e+02 1.22782303e+02 1.22800819e+02 1.22803413e+02 1.22789597e+02 1.22751518e+02 1.22723976e+02 1.22712547e+02 1.22704117e+02 1.22708351e+02 1.22715485e+02 1.22747841e+02 1.22713570e+02 1.22681839e+02 1.22659096e+02 1.22644859e+02 1.22644577e+02 1.22576363e+02 1.22550919e+02 1.22540497e+02 1.22566849e+02 1.22584045e+02 1.22565056e+02 1.22536171e+02 1.22478996e+02 1.22433205e+02 1.22371353e+02 1.22339912e+02 1.22289536e+02 1.22288597e+02 1.22244156e+02 1.22237984e+02 1.22210396e+02 1.22209763e+02 1.22245239e+02 1.22242363e+02 1.22254776e+02 1.22182655e+02 1.22125549e+02 1.22062546e+02 1.22049454e+02 1.22015076e+02 1.21942207e+02 1.21830376e+02 1.21735886e+02 1.21650017e+02 1.21620888e+02 1.21625320e+02 1.21693665e+02 1.21739128e+02 1.21787491e+02 1.21710327e+02 1.21650589e+02 1.21559875e+02 1.21514977e+02 1.21481682e+02 1.21442192e+02 1.21520027e+02 1.21584816e+02 1.21645859e+02 1.21684677e+02 1.21721687e+02 1.21800064e+02 1.21838730e+02 1.21847717e+02 1.21805443e+02 1.21812508e+02 1.21814720e+02 1.21871361e+02 1.21892944e+02 1.21930443e+02 1.21946915e+02 1.21935341e+02 1.21938148e+02 1.21957123e+02 1.21973869e+02 1.22070763e+02 1.22202675e+02 1.22354599e+02 1.22452972e+02 1.22468216e+02 1.22472321e+02 1.22456810e+02 1.22504860e+02 1.22550430e+02 1.22612923e+02 1.22646530e+02 1.22645714e+02 1.22594437e+02 1.22566010e+02 1.22517006e+02 1.22496460e+02 1.22450203e+02 1.22402588e+02 1.22346809e+02 1.22331833e+02 1.22349800e+02 1.22395226e+02 1.22445328e+02 1.22470787e+02 1.22502335e+02 1.22468460e+02 1.22445808e+02 1.22369629e+02 1.22315674e+02 1.22293953e+02 1.22380859e+02 1.22456238e+02 1.22486809e+02 1.22411461e+02 1.22389900e+02 1.22413315e+02 1.22458366e+02 1.22449989e+02 1.22395401e+02 1.22347191e+02 1.22288490e+02 1.22252663e+02 1.22236443e+02 1.22249214e+02 1.22266319e+02 1.22265823e+02 1.22283661e+02 1.22266724e+02 1.22268982e+02 1.22236160e+02 1.22230682e+02 1.22181450e+02 1.22162003e+02 1.22127022e+02 1.22118309e+02 1.22100647e+02 1.22059219e+02 1.22020325e+02 1.22002930e+02 1.22005417e+02 1.22003822e+02 1.21980202e+02 1.21994942e+02 1.21997475e+02 1.22040016e+02 1.22032150e+02 1.22059944e+02 1.22062775e+02 1.22095085e+02 1.22142967e+02 1.22208771e+02 1.22255890e+02 1.22350800e+02 1.22404152e+02 1.22429733e+02 1.22393173e+02 1.22336128e+02 1.22295807e+02 1.22246277e+02 1.22236160e+02 1.22242401e+02 1.22231178e+02 1.22222725e+02 1.22225189e+02 1.22237434e+02 1.22269485e+02 1.22263885e+02 1.22275246e+02 1.22283691e+02 1.22316986e+02 1.22357254e+02 1.22400818e+02 1.22430115e+02 1.22433540e+02 1.22422928e+02 1.22394691e+02 1.22333679e+02 1.22247345e+02 1.22206566e+02 1.22181068e+02 1.22166161e+02 1.22143494e+02 1.22135704e+02 1.22138374e+02 1.22106033e+02 1.22082710e+02 1.23638321e+02 1.25085472e+02 1.26444695e+02 1.27015541e+02 1.27665039e+02 1.28356995e+02 1.28532471e+02 1.27687889e+02 1.25828758e+02 1.24324837e+02 1.24218712e+02 1.24450180e+02 1.25916763e+02 1.67689880e+02 2.39781021e+02 6.09872925e+02 1.23325574e+03 5.96224563e+09 0. -252834768. -252834768. 3.19644925e+06 -1120734336. -1120734336. 0. 0. 0. 0. 0. -2013340544. -506582880. 3.99449719e+05 1.63227551e+03 8.70591736e+02 6.08767151e+02 2.83599792e+02 1.60782700e+02 1.13286392e+02 1.10037201e+02 1.17604370e+02 1.26667450e+02 1.29693588e+02 1.29992630e+02 1.30312393e+02 1.30517731e+02 1.30271103e+02 1.29840652e+02 1.28151077e+02 1.21102791e+02 1.14978401e+02 1.12778061e+02 1.13825394e+02 1.18739914e+02 1.21707909e+02 1.25835678e+02 1.24631454e+02 1.23631332e+02 1.22928391e+02 1.24134811e+02 1.23325951e+02 1.21860764e+02 1.20250412e+02 1.20733223e+02 1.21650505e+02 1.22270386e+02 1.22411865e+02 1.22403328e+02 1.22404297e+02 1.22484062e+02 1.22590736e+02 1.22644623e+02 1.22627724e+02 1.22538071e+02 1.22421959e+02 1.22388519e+02 1.22438026e+02 1.22625366e+02 1.22827194e+02 1.22964447e+02 1.22914108e+02 1.23880272e+02 1.24458885e+02 1.26257538e+02 1.27431145e+02 1.28836456e+02 1.29062531e+02 1.28923737e+02 1.28844055e+02 1.28833969e+02 1.28918839e+02 1.28976105e+02 1.29072037e+02 1.29054337e+02 1.28945389e+02 1.28786530e+02 1.28688904e+02 1.28843765e+02 1.29265274e+02 1.30362015e+02 1.29773560e+02 1.70237335e+02 2.49059769e+02 1.00347949e+03 1.34717456e+03 1.28017310e+03 6.51128479e+02 4.67498535e+02 2.37752502e+02 2.09770020e+02 2.24445786e+02 4.65611908e+02 4.70544556e+02 4.70448120e+02 4.68862579e+02 1098707200. 1295646976. 1295646976. 4.56711526e+09 -8.78688051e+09 -8.78688051e+09 -8.78688051e+09 0. 0. -2.33433088e+10 1.65573145e+03 7.44801270e+02 5.11667114e+02 2.31678284e+02 1.50994232e+02 1.19053864e+02 1.19154694e+02 1.21296837e+02 1.21903847e+02 1.22491791e+02 1.22892555e+02 1.23325356e+02 1.23603516e+02 1.23606209e+02 1.23420341e+02 1.22976700e+02 1.22611145e+02 1.22287109e+02 1.22141602e+02 1.22223137e+02 1.22575554e+02 1.23049446e+02 1.23386993e+02 1.23497368e+02 1.23367004e+02 1.23175423e+02 1.22986099e+02 1.22942551e+02 1.22967644e+02 1.23047028e+02 1.23102394e+02 1.23099182e+02 1.23106522e+02 1.23127785e+02 1.23663971e+02 1.24330193e+02 1.24995033e+02 1.25163727e+02 1.24612442e+02 1.24024864e+02 1.23328461e+02 1.23313423e+02 1.23298073e+02 1.23359184e+02 1.23388054e+02 1.23387726e+02 1.23359039e+02 1.23336060e+02 1.23353203e+02 1.23383812e+02 1.23332100e+02 1.23338905e+02 1.23301697e+02 1.23356720e+02 1.23336121e+02 1.23360626e+02 1.23326691e+02 1.23265205e+02 1.23236809e+02 1.23248093e+02 1.23364662e+02 1.23384216e+02 1.23642693e+02 1.24219238e+02 1.25012444e+02 1.59217194e+02 2.41871567e+02 7.31367615e+02 1.51675793e+03 8.57928875e+05 -5.57898650e+09 -1157822336. 0. 8.16336650e+10 8.16336650e+10 -1274621056. -44978044. -44978044. 0. 0. 0. 0. 0. 0. -2.59937964e+03 4.30506073e+02 2.67234619e+02 6.78415222e+02 2.30701859e+02 1.56388855e+02 1.22712204e+02 1.22826721e+02 1.22041046e+02 1.22726418e+02 1.22991478e+02 1.22982208e+02 1.22692322e+02 1.21880615e+02 1.21601410e+02 1.21768776e+02 1.22462563e+02 1.22847542e+02 1.23026756e+02 1.23107071e+02 1.23110947e+02 1.23067398e+02 1.23049370e+02 1.23051674e+02 1.23055061e+02 1.23035110e+02 1.22986732e+02 1.22969246e+02 1.22975967e+02 1.23001122e+02 1.22993576e+02 1.22941513e+02 1.22863678e+02 1.22803543e+02 1.22743759e+02 1.22738823e+02 1.22746056e+02 1.22753845e+02 1.22728241e+02 1.22640190e+02 1.22571938e+02 1.22497017e+02 1.22493202e+02 1.22524620e+02 1.22593941e+02 1.22668922e+02 1.22752220e+02 1.22887001e+02 1.22968719e+02 1.22988556e+02 1.22913246e+02 1.22878876e+02 1.22871628e+02 1.22892738e+02 1.22922348e+02 1.22903191e+02 1.22897598e+02 1.22871254e+02 1.22903107e+02 1.22939178e+02 1.23003151e+02 1.23023956e+02 1.22951057e+02 1.22804298e+02 1.22676056e+02 1.22598206e+02 1.22494507e+02 1.22411873e+02 1.22332558e+02 1.22325859e+02 1.22339996e+02 1.22397720e+02 1.22478065e+02 1.22569992e+02 1.22638916e+02 1.22733810e+02 1.22741592e+02 1.22697334e+02 1.22569588e+02 1.22451981e+02 1.22364853e+02 1.22310371e+02 1.22341179e+02 1.22360779e+02 1.22372246e+02 1.22359032e+02 1.22308029e+02 1.22238876e+02 1.22143341e+02 1.22126213e+02 1.22152122e+02 1.22216774e+02 1.22247467e+02 1.22210594e+02 1.22162437e+02 1.22126930e+02 1.22131912e+02 1.22141586e+02 1.22165009e+02 1.22156395e+02 1.22385048e+02 1.22599747e+02 1.22875801e+02 1.22582771e+02 1.22291664e+02 1.21945686e+02 1.22031921e+02 1.22096703e+02 1.22202629e+02 1.22210289e+02 1.22225609e+02 1.22237213e+02 1.22247978e+02 1.22232414e+02 1.22208466e+02 1.22206451e+02 1.22225433e+02 1.22283897e+02 1.22300224e+02 1.22252998e+02 1.22124504e+02 1.22031921e+02 1.22021355e+02 1.21993500e+02 1.21940315e+02 1.21894318e+02 1.21915871e+02 1.21880074e+02 1.21828476e+02 1.21746986e+02 1.21758469e+02 1.21791367e+02 1.21856995e+02 1.22007256e+02 1.22107498e+02 1.22161118e+02 1.22051132e+02 1.21935753e+02 1.21970451e+02 1.22030685e+02 1.22082962e+02 1.22003441e+02 1.21871094e+02 1.21796600e+02 1.21760765e+02 1.21856491e+02 1.21934349e+02 1.21942062e+02 1.21840477e+02 1.21713821e+02 1.21700424e+02 1.21672539e+02 1.21690636e+02 1.21647339e+02 1.21634651e+02 1.21620651e+02 1.21656029e+02 1.21646629e+02 1.21582550e+02 1.21502464e+02 1.21455093e+02 1.21431938e+02 1.21387993e+02 1.21363152e+02 1.21321442e+02 1.21366379e+02 1.21357986e+02 1.21351562e+02 1.21230484e+02 1.21149788e+02 1.21092781e+02 1.21144615e+02 1.21244812e+02 1.21285255e+02 1.21256302e+02 1.21262260e+02 1.21275124e+02 1.21303368e+02 1.21240623e+02 1.21232475e+02 1.21208931e+02 1.21204277e+02 1.21148560e+02 1.21078613e+02 1.20995049e+02 1.21030518e+02 1.21169922e+02 1.21393616e+02 1.21490189e+02 1.21553230e+02 1.21602943e+02 1.21598534e+02 1.21670601e+02 1.21772057e+02 1.21906670e+02 1.21919456e+02 1.21865265e+02 1.21780609e+02 1.21759232e+02 1.21844376e+02 1.21877136e+02 1.21920753e+02 1.21860657e+02 1.21816940e+02 1.21797447e+02 1.21750587e+02 1.21844345e+02 1.21882202e+02 1.22082375e+02 1.22119080e+02 1.22151642e+02 1.22037811e+02 1.21991707e+02 1.22035629e+02 1.22079712e+02 1.22174118e+02 1.22185539e+02 1.22239822e+02 1.22299095e+02 1.22386269e+02 1.22422974e+02 1.22452286e+02 1.22516098e+02 1.22612854e+02 1.22646568e+02 1.22630959e+02 1.22646172e+02 1.22732544e+02 1.22873482e+02 1.22923264e+02 1.22973373e+02 1.22977539e+02 1.23016373e+02 1.22980461e+02 1.22996445e+02 1.23003380e+02 1.23095558e+02 1.23151039e+02 1.23186073e+02 1.23165436e+02 1.23128700e+02 1.23161560e+02 1.23211594e+02 1.23296257e+02 1.23348640e+02 1.23367126e+02 1.23397354e+02 1.23404991e+02 1.23423447e+02 1.23415939e+02 1.23406723e+02 1.23402435e+02 1.23413826e+02 1.23424164e+02 1.23491348e+02 1.23570457e+02 1.23625694e+02 1.23652023e+02 1.23647636e+02 1.23711609e+02 1.23748978e+02 1.23680740e+02 1.23583687e+02 1.23492546e+02 1.23499199e+02 1.23514038e+02 1.23521492e+02 1.23560303e+02 1.23593391e+02 1.23612442e+02 1.23626099e+02 1.23631905e+02 1.23629868e+02 1.23603195e+02 1.23579491e+02 1.23584763e+02 1.23610672e+02 1.23629196e+02 1.23667099e+02 1.23672668e+02 1.23693069e+02 1.23713455e+02 1.23790733e+02 1.23829483e+02 1.23819626e+02 1.23781334e+02 1.23770660e+02 1.23793587e+02 1.23823753e+02 1.23826874e+02 1.23815392e+02 1.23804146e+02 1.23789848e+02 1.23794861e+02 1.23810120e+02 1.23835945e+02 1.23839775e+02 1.23823448e+02 1.23880890e+02 1.23912010e+02 1.24051727e+02 1.24194054e+02 1.24204201e+02 1.24112724e+02 1.23972351e+02 1.24013359e+02 1.24040939e+02 1.24081841e+02 1.24094528e+02 1.24084305e+02 1.24028465e+02 1.23988594e+02 1.23959328e+02 1.23992310e+02 1.24029083e+02 1.24140358e+02 1.24220932e+02 1.24246292e+02 1.24181969e+02 1.24105568e+02 1.24088387e+02 1.23982124e+02 1.24117455e+02 1.24051674e+02 1.24087013e+02 1.23910461e+02 1.23950729e+02 1.24108131e+02 1.24213570e+02 1.24321533e+02 1.24382523e+02 1.24451851e+02 1.24532715e+02 1.24581146e+02 1.24609451e+02 1.24613693e+02 1.24608284e+02 1.24602020e+02 1.24610466e+02 1.24588043e+02 1.24547516e+02 1.24477989e+02 1.24439499e+02 1.24433891e+02 1.24436867e+02 1.24460762e+02 1.24478683e+02 1.24477303e+02 1.24454231e+02 1.24398430e+02 1.24376968e+02 1.24348785e+02 1.24318459e+02 1.24286667e+02 1.24281082e+02 1.24300835e+02 1.24341476e+02 1.24372589e+02 1.24447014e+02 1.24505234e+02 1.24539558e+02 1.24542587e+02 1.24524658e+02 1.24519058e+02 1.24491577e+02 1.24444626e+02 1.24412285e+02 1.24384659e+02 1.24403671e+02 1.24406944e+02 1.24378014e+02 1.24309349e+02 1.24268913e+02 1.24327110e+02 1.24395882e+02 1.24478951e+02 1.24499596e+02 1.24525642e+02 1.24515938e+02 1.24511063e+02 1.24485466e+02 1.24479355e+02 1.24496803e+02 1.24539665e+02 1.24571968e+02 1.24557167e+02 1.24531212e+02 1.24524437e+02 1.24536789e+02 1.24578300e+02 1.24598854e+02 1.24616089e+02 1.24611870e+02 1.24616859e+02 1.24607353e+02 1.24582573e+02 1.24536995e+02 1.24506180e+02 1.24532753e+02 1.24574158e+02 1.24641396e+02 1.24645798e+02 1.24678276e+02 1.24745987e+02 1.24797729e+02 1.24796814e+02 1.24762985e+02 1.24709564e+02 1.24701454e+02 1.24855919e+02 1.25072166e+02 1.25272079e+02 1.25146721e+02 1.24982376e+02 1.24894150e+02 1.24874077e+02 1.24885818e+02 1.24818329e+02 1.24830017e+02 1.24826202e+02 1.24836746e+02 1.24849838e+02 1.24845718e+02 1.24837852e+02 1.24819672e+02 1.24826073e+02 1.24837616e+02 1.24727669e+02 1.24718414e+02 1.24707680e+02 1.24737679e+02 1.24617210e+02 1.24463364e+02 1.24492615e+02 1.24518753e+02 1.24533943e+02 1.24515831e+02 1.24588501e+02 1.24668633e+02 1.24789520e+02 1.24903076e+02 1.25012184e+02 1.25107071e+02 1.25056564e+02 1.25001083e+02 1.24959480e+02 1.25089615e+02 1.25202095e+02 1.25335693e+02 1.25375961e+02 1.25439262e+02 1.25441696e+02 1.25372032e+02 1.25306503e+02 1.25232132e+02 1.25224037e+02 1.25246109e+02 1.25270653e+02 1.25265366e+02 1.25235626e+02 1.25215492e+02 1.25196838e+02 1.25229034e+02 1.25246178e+02 1.25262260e+02 1.25247292e+02 1.25234131e+02 1.25229622e+02 1.25215790e+02 1.25213676e+02 1.25185303e+02 1.25143959e+02 1.25126549e+02 1.25164597e+02 1.25217133e+02 1.25255981e+02 1.25276451e+02 1.25318451e+02 1.25393913e+02 1.25460068e+02 1.25546600e+02 1.25615082e+02 1.25610634e+02 1.25602959e+02 1.25519676e+02 1.25510841e+02 1.25490105e+02 1.25477661e+02 1.25379974e+02 1.25310677e+02 1.25303154e+02 1.25353676e+02 1.25390778e+02 1.25442833e+02 1.25451591e+02 1.25435326e+02 1.25268364e+02 1.25123871e+02 1.25006409e+02 1.25006783e+02 1.24963867e+02 1.24921432e+02 1.25040482e+02 1.25167519e+02 1.25305511e+02 1.25275436e+02 1.25235710e+02 1.25207314e+02 1.25193596e+02 1.25200272e+02 1.25193069e+02 1.25193542e+02 1.25192825e+02 1.25165245e+02 1.25099136e+02 1.25032776e+02 1.25009308e+02 1.24983223e+02 1.24969299e+02 1.24991753e+02 1.24998604e+02 1.25022705e+02 1.24981659e+02 1.24960892e+02 1.24912766e+02 1.24888290e+02 1.24839622e+02 1.24834198e+02 1.24775848e+02 1.24748581e+02 1.24696861e+02 1.24689774e+02 1.24709686e+02 1.24717209e+02 1.24732124e+02 1.24729752e+02 1.24744316e+02 1.24771126e+02 1.24772896e+02 1.24768066e+02 1.24732307e+02 1.24672142e+02 1.24734276e+02 1.24778664e+02 1.24880592e+02 1.24713234e+02 1.24523834e+02 1.24313927e+02 1.24222679e+02 1.24170990e+02 1.24123184e+02 1.24110519e+02 1.24089745e+02 1.24111992e+02 1.24084732e+02 1.24054718e+02 1.24050354e+02 1.24053764e+02 1.24085716e+02 1.24024673e+02 1.24010155e+02 1.24011948e+02 1.24071945e+02 1.24135231e+02 1.24144333e+02 1.24140030e+02 1.24104828e+02 1.24075684e+02 1.24091209e+02 1.24087517e+02 1.24107101e+02 1.24088097e+02 1.24085976e+02 1.24031036e+02 1.23969887e+02 1.23940636e+02 1.23983719e+02 1.24001556e+02 1.24020508e+02 1.24015305e+02 1.24032784e+02 1.23991478e+02 1.23975548e+02 1.23889473e+02 1.23816925e+02 1.23670204e+02 1.23603088e+02 1.23598129e+02 1.23612747e+02 1.23546417e+02 1.23455055e+02 1.23361771e+02 1.23361153e+02 1.23329285e+02 1.23314011e+02 1.23269264e+02 1.23295250e+02 1.23256149e+02 1.23215569e+02 1.23134277e+02 1.23092133e+02 1.23058685e+02 1.23048515e+02 1.23111496e+02 1.23172073e+02 1.23311813e+02 1.23393555e+02 1.23377304e+02 1.23249641e+02 1.23196953e+02 1.23311096e+02 1.23323273e+02 1.23168617e+02 1.22959076e+02 1.22877922e+02 1.22870819e+02 1.22973518e+02 1.22999695e+02 1.23092987e+02 1.23062004e+02 1.23153816e+02 1.23200165e+02 1.23212509e+02 1.23219673e+02 1.23264709e+02 1.23302795e+02 1.23492966e+02 1.24327332e+02 1.25373016e+02 1.26268944e+02 1.26173958e+02 1.25664253e+02 1.25298340e+02 1.25095703e+02 1.25368591e+02 1.25973145e+02 1.59754257e+02 1.55581650e+02 1.68396637e+02 1.26260468e+02 1.25120918e+02 1.56689072e+02 1.51547119e+02 1.65144012e+02 1.24788002e+02 1.25525536e+02 1.25995163e+02 1.25808228e+02 1.25623840e+02 1.25332848e+02 1.25010452e+02 1.24408051e+02 1.23689056e+02 1.23096970e+02 1.22749878e+02 1.22643204e+02 1.22641754e+02 1.22744659e+02 1.22851242e+02 1.22803421e+02 1.22801605e+02 1.22836761e+02 1.22723763e+02 1.22644142e+02 1.22612129e+02 1.22698730e+02 1.22572990e+02 1.22486343e+02 1.22396530e+02 1.22403008e+02 1.22341087e+02 1.22195831e+02 1.22057587e+02 1.21952126e+02 1.22028793e+02 1.22008690e+02 1.21913460e+02 1.21755516e+02 1.21722801e+02 1.21694466e+02 1.21693817e+02 1.21727379e+02 1.21719818e+02 1.21671776e+02 1.21691727e+02 1.21675880e+02 1.21656990e+02 1.21562477e+02 1.21577187e+02 1.21644554e+02 1.21725174e+02 1.21711685e+02 1.21673035e+02 1.21669281e+02 1.21713928e+02 1.21640427e+02 1.21466431e+02 1.21320587e+02 1.21331718e+02 1.21428879e+02 1.21446785e+02 1.21449722e+02 1.21451759e+02 1.21539200e+02 1.21594574e+02 1.21647545e+02 1.21637276e+02 1.21667236e+02 1.21707489e+02 1.21693001e+02 1.21707771e+02 1.21851997e+02 1.22062469e+02 1.22215828e+02 1.22242073e+02 1.22179131e+02 1.22186783e+02 1.22201218e+02 1.22274361e+02 1.22251961e+02 1.22261505e+02 1.22267990e+02 1.22289452e+02 1.22273079e+02 1.22222298e+02 1.22205559e+02 1.22157295e+02 1.22148315e+02 1.22114853e+02 1.22150131e+02 1.22190948e+02 1.22230713e+02 1.22355537e+02 1.22387085e+02 1.22487450e+02 1.22428185e+02 1.22380180e+02 1.22302643e+02 1.22300735e+02 1.22461945e+02 1.22635132e+02 1.22794289e+02 1.22852409e+02 1.22854919e+02 1.22732140e+02 1.22535309e+02 1.22348511e+02 1.22279312e+02 1.22289818e+02 1.22323563e+02 1.22364594e+02 1.22388420e+02 1.22395424e+02 1.22386787e+02 1.22359482e+02 1.22357346e+02 1.22324776e+02 1.22307785e+02 1.22274750e+02 1.22252022e+02 1.22258751e+02 1.22257591e+02 1.22229744e+02 1.22190186e+02 1.22177353e+02 1.22223610e+02 1.22263870e+02 1.22266602e+02 1.22279556e+02 1.22293640e+02 1.22306129e+02 1.22266060e+02 1.22223724e+02 1.22166389e+02 1.22124252e+02 1.22101242e+02 1.22437042e+02 1.22836037e+02 1.23248543e+02 1.22965607e+02 1.22652481e+02 1.22385963e+02 1.22450653e+02 1.22500862e+02 1.22488518e+02 1.22444855e+02 1.22402916e+02 1.22389847e+02 1.22412376e+02 1.22459755e+02 1.22450867e+02 1.22451416e+02 1.22434006e+02 1.22490356e+02 1.22522667e+02 1.22571449e+02 1.22588020e+02 1.22630226e+02 1.22659241e+02 1.23082504e+02 1.23511757e+02 1.23985657e+02 1.23950020e+02 1.23504593e+02 1.23023926e+02 1.22512657e+02 1.22461449e+02 1.22406357e+02 1.22391273e+02 1.22352760e+02 1.22334900e+02 1.22686142e+02 1.23144829e+02 1.23575607e+02 1.23137718e+02 1.22656509e+02 1.22183266e+02 1.22124481e+02 1.21988815e+02 1.21690445e+02 1.21223892e+02 1.21070961e+02 1.21267235e+02 1.21725815e+02 1.21938248e+02 1.21916321e+02 1.21617546e+02 1.21071053e+02 1.19428535e+02 1.20381439e+02 1.15689133e+02 1.53702942e+02 2.81913055e+02 1.41565259e+03 2.24517181e+10 -6.14256625e+05 -252834768. -252834768. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.37897523e+09 -554025152. 1.15269888e+06 1.56276868e+03 3.19225830e+02 1.66816559e+02 1.24271103e+02 1.25475632e+02 1.26193108e+02 1.27495895e+02 1.27824890e+02 1.27698326e+02 1.27397209e+02 1.25615746e+02 1.22257484e+02 1.20200935e+02 1.18919037e+02 1.19762070e+02 1.20077209e+02 1.21128273e+02 1.21696091e+02 1.21852425e+02 1.21943169e+02 1.22149887e+02 1.22495216e+02 1.22784645e+02 1.22956375e+02 1.22988129e+02 1.22942039e+02 1.22882828e+02 1.22895882e+02 1.22976669e+02 1.23038521e+02 1.23072418e+02 1.23035393e+02 1.23057747e+02 1.23087135e+02 1.23150215e+02 1.23233131e+02 1.23301781e+02 1.23435715e+02 1.23324570e+02 1.23121651e+02 1.22782387e+02 1.22559410e+02 1.22421959e+02 1.22315392e+02 1.22378975e+02 1.22465645e+02 1.22576279e+02 1.22549553e+02 1.22368805e+02 1.22088692e+02 1.21909767e+02 1.21859818e+02 1.21968201e+02 1.22046707e+02 1.22250565e+02 1.22418930e+02 1.22535088e+02 1.22606598e+02 1.22651947e+02 1.22785400e+02 1.22620834e+02 1.22373085e+02 1.21612427e+02 1.19653755e+02 1.21582054e+02 1.84580124e+02 3.60267426e+02 3.04202163e+09 3.04202163e+09 481611200. -1241831424. 3.94175050e+06 1.35306982e+03 9.76468994e+02 1.32526318e+03 18900200. 7001414. 725857280. -425822912. 0. 0. -5.08327076e+10 2.11135836e+10 1.05505005e+03 -275279200. -8.78688051e+09 0. 0. -2.33433088e+10 1.65573145e+03 7.44801270e+02 5.11667114e+02 2.54026596e+02 1.66734924e+02 1.25377907e+02 1.25650520e+02 1.26319946e+02 1.26055138e+02 1.25368652e+02 1.25251236e+02 1.25573814e+02 1.25760292e+02 1.25960007e+02 1.26329185e+02 1.26992851e+02 1.27290482e+02 1.27231300e+02 1.26817810e+02 1.26335487e+02 1.25949234e+02 1.25683647e+02 1.25863266e+02 1.26139336e+02 1.26063286e+02 1.25510017e+02 1.25214699e+02 1.25231674e+02 1.25463371e+02 1.25193939e+02 1.25024185e+02 1.24900696e+02 1.25034332e+02 1.25318604e+02 1.26955772e+02 1.28845078e+02 1.30800766e+02 1.31027420e+02 1.30195435e+02 1.28604996e+02 1.26846115e+02 1.25841774e+02 1.25447838e+02 1.25322281e+02 1.25361794e+02 1.25473328e+02 1.25388000e+02 1.25289368e+02 1.25270584e+02 1.25181168e+02 1.24980476e+02 1.24706642e+02 1.24569397e+02 1.24411964e+02 1.24302071e+02 1.24111549e+02 1.24067978e+02 1.23981041e+02 1.24091469e+02 1.24308701e+02 1.24876556e+02 1.25642715e+02 1.26492912e+02 1.60952560e+02 2.39319946e+02 6.85699524e+02 1.34995081e+03 462301824. 9.59636750e+05 1.74624031e+10 1.74624031e+10 0. 0. 8.16336650e+10 8.16336650e+10 -1274621056. -44978044. -44978044. 0. 0. 0. 0. -2.48655114e+10 5.75557990e+09 1.36093616e+03 6.88777649e+02 2.35891068e+02 1.57853653e+02 1.24295975e+02 1.24576813e+02 1.24977821e+02 1.25434105e+02 1.25661400e+02 1.25843071e+02 1.25843681e+02 1.25543365e+02 1.24992752e+02 1.24528366e+02 1.24194572e+02 1.24175262e+02 1.24172348e+02 1.24204269e+02 1.24167923e+02 1.24157249e+02 1.24165138e+02 1.24215088e+02 1.24236656e+02 1.24255554e+02 1.24266327e+02 1.24272644e+02 1.24301811e+02 1.24315102e+02 1.24332825e+02 1.24347015e+02 1.24369041e+02 1.24412773e+02 1.24469414e+02 1.24506699e+02 1.24557816e+02 1.24578331e+02 1.24625160e+02 1.24635567e+02 1.24678772e+02 1.24634377e+02 1.24610031e+02 1.24554291e+02 1.24533798e+02 1.24502571e+02 1.24471474e+02 1.24451859e+02 1.24487778e+02 1.24496536e+02 1.24562141e+02 1.24559769e+02 1.24559471e+02 1.24546806e+02 1.24558868e+02 1.24563065e+02 1.24541275e+02 1.24481140e+02 1.24452477e+02 1.24461418e+02 1.24456886e+02 1.24450554e+02 1.24447090e+02 1.24514038e+02 1.24586472e+02 1.24611794e+02 1.24583809e+02 1.24512169e+02 1.24457977e+02 1.24425308e+02 1.24329399e+02 1.24192604e+02 1.23967781e+02 1.23876709e+02 1.23824074e+02 1.23857300e+02 1.23736595e+02 1.23638542e+02 1.23477463e+02 1.23436546e+02 1.23347466e+02 1.23314529e+02 1.23301292e+02 1.23219635e+02 1.23159706e+02 1.23070679e+02 1.23022903e+02 1.23007904e+02 1.23018074e+02 1.23094330e+02 1.23107079e+02 1.23129303e+02 1.23055023e+02 1.23024734e+02 1.22996735e+02 1.22988953e+02 1.22954750e+02 1.22913582e+02 1.22887642e+02 1.22880257e+02 1.22899605e+02 1.22955437e+02 1.23331802e+02 1.23687859e+02 1.23781235e+02 1.23390648e+02 1.22980240e+02 1.22830170e+02 1.22776726e+02 1.22717819e+02 1.22654549e+02 1.22626877e+02 1.22627548e+02 1.22682007e+02 1.22732376e+02 1.22755783e+02 1.22798172e+02 1.22813568e+02 1.22882278e+02 1.22956451e+02 1.22973251e+02 1.22974678e+02 1.22895920e+02 1.22873398e+02 1.22848198e+02 1.22851074e+02 1.22843086e+02 1.22858093e+02 1.22871147e+02 1.22895004e+02 1.22877541e+02 1.22856270e+02 1.22861931e+02 1.22842514e+02 1.22896111e+02 1.22915962e+02 1.23075333e+02 1.23074898e+02 1.23084320e+02 1.22922020e+02 1.22925980e+02 1.22938599e+02 1.22957153e+02 1.22947678e+02 1.22939323e+02 1.22938400e+02 1.22975952e+02 1.22958397e+02 1.23003326e+02 1.22995010e+02 1.23013252e+02 1.22974998e+02 1.23038864e+02 1.23068558e+02 1.23098465e+02 1.23041832e+02 1.23032646e+02 1.22941978e+02 1.22882828e+02 1.22877678e+02 1.22958664e+02 1.23071381e+02 1.23098274e+02 1.23071396e+02 1.22972336e+02 1.22937729e+02 1.22959343e+02 1.23072060e+02 1.23169807e+02 1.23220795e+02 1.23129646e+02 1.23051155e+02 1.23039543e+02 1.23121597e+02 1.23229698e+02 1.23396736e+02 1.23649788e+02 1.24097206e+02 1.24361382e+02 1.24699242e+02 1.25190636e+02 1.26585976e+02 1.27065041e+02 1.27356613e+02 1.27768524e+02 1.29177139e+02 1.29324081e+02 1.27686630e+02 1.26453720e+02 1.59431915e+02 2.35710419e+02 4.85425812e+02 4.85649231e+02 4.85517365e+02 4.86071198e+02 4.86823608e+02 4.87403900e+02 4.87213776e+02 4.87283142e+02 4.87142181e+02 4.86963898e+02 4.86750793e+02 4.86876587e+02 4.87139282e+02 4.86542114e+02 4.85797638e+02 4.84622925e+02 2.42679459e+02 2.12154984e+02 2.28349503e+02 4.84722809e+02 2.55137329e+02 1.69815247e+02 1.26502899e+02 1.24091858e+02 1.23633492e+02 1.23630730e+02 1.23678154e+02 1.23775063e+02 1.23813316e+02 1.23853806e+02 1.23944794e+02 1.24090240e+02 1.24100365e+02 1.24125427e+02 1.24232681e+02 1.24287605e+02 1.24369797e+02 1.24311012e+02 1.24427231e+02 1.24516357e+02 1.24641563e+02 1.24717308e+02 1.24782585e+02 1.24812599e+02 1.24811043e+02 1.24818581e+02 1.24821754e+02 1.24831802e+02 1.24774414e+02 1.24750984e+02 1.24729195e+02 1.24748169e+02 1.24757973e+02 1.24774551e+02 1.24824295e+02 1.24850052e+02 1.24862267e+02 1.24873466e+02 1.24903259e+02 1.24931740e+02 1.24942734e+02 1.24917221e+02 1.24957191e+02 1.24965111e+02 1.25002373e+02 1.24962929e+02 1.25043999e+02 1.25048935e+02 1.25124542e+02 1.25067627e+02 1.25170944e+02 1.25218117e+02 1.25204567e+02 1.25106331e+02 1.24999535e+02 1.25022766e+02 1.25062851e+02 1.25139648e+02 1.25207390e+02 1.25260048e+02 1.25358536e+02 1.25464745e+02 1.25537292e+02 1.25525444e+02 1.25503868e+02 1.25508385e+02 1.25534874e+02 1.25528496e+02 1.25546844e+02 1.25575211e+02 1.25612564e+02 1.25604530e+02 1.25561539e+02 1.25590912e+02 1.25604607e+02 1.25579231e+02 1.25558647e+02 1.25590919e+02 1.25670258e+02 1.25663727e+02 1.25687119e+02 1.25647583e+02 1.25664055e+02 1.25664505e+02 1.25749573e+02 1.25786964e+02 1.25837570e+02 1.25870575e+02 1.25893860e+02 1.25847618e+02 1.25843842e+02 1.25912720e+02 1.26058510e+02 1.26012527e+02 1.25833641e+02 1.25644569e+02 1.25642410e+02 1.25657478e+02 1.25674576e+02 1.25667740e+02 1.25683723e+02 1.25677742e+02 1.25673271e+02 1.25677109e+02 1.25694084e+02 1.25763855e+02 1.25829201e+02 1.25884972e+02 1.25899109e+02 1.25917793e+02 1.25878006e+02 1.25767677e+02 1.25604744e+02 1.25592354e+02 1.25712593e+02 1.25725777e+02 1.25712234e+02 1.25627556e+02 1.25856392e+02 1.25964561e+02 1.25992691e+02 1.25811188e+02 1.25702637e+02 1.25696373e+02 1.25809639e+02 1.25836113e+02 1.25854362e+02 1.25827690e+02 1.25802811e+02 1.25766335e+02 1.25760201e+02 1.25740959e+02 1.25796555e+02 1.25823593e+02 1.25862000e+02 1.25836998e+02 1.25778442e+02 1.25709808e+02 1.25676155e+02 1.25704674e+02 1.25695702e+02 1.25661674e+02 1.25635521e+02 1.25597595e+02 1.25585350e+02 1.25566818e+02 1.25563194e+02 1.25603348e+02 1.25649117e+02 1.25729164e+02 1.25723892e+02 1.25692070e+02 1.25665092e+02 1.25628342e+02 1.25612480e+02 1.25580841e+02 1.25519089e+02 1.25500069e+02 1.25479805e+02 1.25494522e+02 1.25499115e+02 1.25512054e+02 1.25457901e+02 1.25413918e+02 1.25416901e+02 1.25520714e+02 1.25521187e+02 1.25454391e+02 1.25417465e+02 1.25332207e+02 1.25274086e+02 1.25187714e+02 1.25186386e+02 1.25183151e+02 1.25174248e+02 1.25267151e+02 1.25291275e+02 1.25303467e+02 1.25241470e+02 1.25217155e+02 1.25308670e+02 1.25440514e+02 1.25439980e+02 1.25313042e+02 1.25165108e+02 1.25222374e+02 1.25197716e+02 1.25175377e+02 1.25123383e+02 1.25247154e+02 1.25399391e+02 1.25595932e+02 1.25630058e+02 1.25551323e+02 1.25404091e+02 1.25422646e+02 1.25572403e+02 1.25756126e+02 1.25761253e+02 1.25766144e+02 1.25726860e+02 1.25727951e+02 1.25742561e+02 1.25761826e+02 1.25768524e+02 1.25780861e+02 1.25845795e+02 1.25905594e+02 1.25932083e+02 1.25947060e+02 1.25956474e+02 1.25942230e+02 1.25989868e+02 1.26033920e+02 1.26091438e+02 1.26040916e+02 1.26032455e+02 1.26053703e+02 1.26128952e+02 1.26082260e+02 1.25977417e+02 1.25911339e+02 1.25953957e+02 1.26002182e+02 1.26027344e+02 1.26191765e+02 1.26141655e+02 1.26124680e+02 1.25951065e+02 1.25988785e+02 1.26073006e+02 1.26074478e+02 1.26057060e+02 1.25993553e+02 1.26002510e+02 1.26016922e+02 1.26032829e+02 1.26077293e+02 1.26154419e+02 1.26218132e+02 1.26111908e+02 1.26107971e+02 1.26092773e+02 1.26184410e+02 1.26112640e+02 1.26037613e+02 1.25987312e+02 1.26083702e+02 1.26174622e+02 1.26216408e+02 1.26148445e+02 1.26116951e+02 1.26162170e+02 1.26230591e+02 1.26287392e+02 1.26339943e+02 1.26365730e+02 1.26400826e+02 1.26402992e+02 1.26380821e+02 1.26405846e+02 1.26430840e+02 1.26511765e+02 1.26549408e+02 1.26586845e+02 1.26632370e+02 1.26677940e+02 1.26708160e+02 1.26584770e+02 1.26614563e+02 1.26714279e+02 1.27065887e+02 1.27195892e+02 1.27158348e+02 1.27044708e+02 1.26979790e+02 1.26999557e+02 1.27214508e+02 1.27396774e+02 1.27317169e+02 1.27174278e+02 1.26887283e+02 1.26884941e+02 1.26885330e+02 1.27083633e+02 1.27078995e+02 1.26925247e+02 1.26665085e+02 1.26505226e+02 1.26335793e+02 1.26317284e+02 1.26288132e+02 1.26253311e+02 1.26363098e+02 1.26361519e+02 1.26429703e+02 1.26342453e+02 1.26411736e+02 1.26491676e+02 1.26569687e+02 1.26623154e+02 1.26632492e+02 1.26466934e+02 1.26272430e+02 1.26239204e+02 1.26189056e+02 1.26189636e+02 1.25986359e+02 1.26126038e+02 1.26266693e+02 1.26442268e+02 1.26292526e+02 1.26157181e+02 1.26014473e+02 1.26195778e+02 1.26353134e+02 1.26552696e+02 1.26594887e+02 1.26554016e+02 1.26508514e+02 1.26459778e+02 1.26531647e+02 1.26520912e+02 1.26521400e+02 1.26589149e+02 1.26640999e+02 1.26694122e+02 1.26721855e+02 1.26706146e+02 1.26710014e+02 1.26677994e+02 1.26600418e+02 1.26520355e+02 1.26534363e+02 1.26599922e+02 1.26545990e+02 1.26166618e+02 1.25878990e+02 1.25729065e+02 1.25769508e+02 1.25763191e+02 1.25794434e+02 1.25835899e+02 1.25854248e+02 1.25829155e+02 1.25787354e+02 1.25757339e+02 1.25721046e+02 1.25730446e+02 1.25860085e+02 1.26008400e+02 1.26201248e+02 1.26238358e+02 1.26297256e+02 1.26317375e+02 1.26354652e+02 1.26436279e+02 1.26500999e+02 1.26520821e+02 1.26486732e+02 1.26417030e+02 1.26285149e+02 1.26223999e+02 1.26195770e+02 1.26250778e+02 1.26199081e+02 1.26146225e+02 1.26155785e+02 1.26078995e+02 1.26063652e+02 1.25924721e+02 1.25912651e+02 1.25891350e+02 1.25985718e+02 1.26054779e+02 1.26078934e+02 1.26020493e+02 1.25954529e+02 1.25841599e+02 1.25693314e+02 1.25569191e+02 1.25459396e+02 1.25389839e+02 1.25325340e+02 1.25291252e+02 1.25296036e+02 1.25326675e+02 1.25252411e+02 1.25179398e+02 1.25095703e+02 1.25098083e+02 1.25161926e+02 1.25163574e+02 1.25211647e+02 1.25133499e+02 1.25105530e+02 1.25108528e+02 1.25132027e+02 1.25151634e+02 1.25097847e+02 1.25158592e+02 1.25206612e+02 1.25159660e+02 1.24970459e+02 1.24823006e+02 1.24769112e+02 1.24734177e+02 1.24767464e+02 1.24849762e+02 1.24949356e+02 1.24918907e+02 1.24868027e+02 1.24835480e+02 1.24851410e+02 1.24856873e+02 1.24823959e+02 1.24804314e+02 1.24949738e+02 1.25647072e+02 1.26852921e+02 1.27929298e+02 1.29309570e+02 1.29934998e+02 1.30343048e+02 1.29309097e+02 1.28550995e+02 1.28320541e+02 1.69701370e+02 2.53292953e+02 7.52878174e+02 5.18594910e+02 5.09419708e+02 6.78410828e+02 6.19240112e+02 7.21704895e+02 5.06846436e+02 5.12578369e+02 5.16738220e+02 2.89603699e+02 2.56638977e+02 1.78791458e+02 1.80168213e+02 1.33099030e+02 1.28841248e+02 1.27541664e+02 1.27478699e+02 1.27531471e+02 1.27936172e+02 1.28007904e+02 1.27837509e+02 1.26967628e+02 1.26514175e+02 1.26745804e+02 1.26837074e+02 1.26415230e+02 1.25488205e+02 1.24920158e+02 1.24673813e+02 1.24565956e+02 1.24482742e+02 1.24426216e+02 1.24361984e+02 1.24333344e+02 1.24299370e+02 1.24169899e+02 1.24050056e+02 1.24057602e+02 1.24148666e+02 1.24301910e+02 1.24333046e+02 1.24384796e+02 1.24434540e+02 1.24510361e+02 1.24513359e+02 1.24448822e+02 1.24342003e+02 1.24310547e+02 1.24245628e+02 1.24241280e+02 1.24194344e+02 1.24203064e+02 1.24135521e+02 1.24024551e+02 1.23932259e+02 1.23882851e+02 1.23852959e+02 1.23675331e+02 1.23488503e+02 1.23304657e+02 1.23299294e+02 1.23354370e+02 1.23406937e+02 1.23504425e+02 1.23622894e+02 1.23741127e+02 1.23784492e+02 1.23729645e+02 1.23630470e+02 1.23745171e+02 1.23891258e+02 1.24044128e+02 1.24075958e+02 1.24124733e+02 1.24206642e+02 1.24204079e+02 1.24255150e+02 1.24256645e+02 1.24325729e+02 1.24204590e+02 1.24321564e+02 1.24267662e+02 1.24369003e+02 1.24274658e+02 1.24268799e+02 1.24141327e+02 1.24128052e+02 1.24154198e+02 1.24302872e+02 1.24276848e+02 1.24240623e+02 1.24124977e+02 1.23971329e+02 1.23772690e+02 1.23674774e+02 1.24045990e+02 1.24072495e+02 1.24030472e+02 1.23615059e+02 1.23659584e+02 1.23720222e+02 1.23717484e+02 1.23652077e+02 1.23998901e+02 1.24455711e+02 1.24978432e+02 1.24594559e+02 1.24111809e+02 1.23603714e+02 1.23618034e+02 1.23669571e+02 1.23738785e+02 1.23795433e+02 1.23833878e+02 1.23819473e+02 1.23817017e+02 1.23753326e+02 1.23747925e+02 1.23696083e+02 1.23803734e+02 1.23865845e+02 1.23955765e+02 1.23940285e+02 1.23908363e+02 1.23923721e+02 1.23887169e+02 1.23909904e+02 1.23892082e+02 1.23876060e+02 1.23830048e+02 1.23773636e+02 1.23837357e+02 1.23877373e+02 1.23953339e+02 1.23945419e+02 1.23977707e+02 1.23945740e+02 1.24356361e+02 1.24796547e+02 1.25328079e+02 1.25373131e+02 1.24954552e+02 1.24451324e+02 1.24007469e+02 1.24030746e+02 1.24101868e+02 1.24075630e+02 1.24063042e+02 1.24048332e+02 1.24062622e+02 1.24054901e+02 1.24057343e+02 1.24006714e+02 1.24003014e+02 1.24023163e+02 1.24088608e+02 1.24141876e+02 1.24145050e+02 1.24095284e+02 1.24102051e+02 1.24128006e+02 1.24144676e+02 1.24137070e+02 1.24146904e+02 1.24153847e+02 1.24191093e+02 1.24231400e+02 1.24224846e+02 1.24214920e+02 1.24198105e+02 1.24211967e+02 1.24241524e+02 1.24270027e+02 1.24260498e+02 1.24243080e+02 1.24276756e+02 1.24312981e+02 1.24342972e+02 1.24293777e+02 1.24255356e+02 1.24238251e+02 1.24270500e+02 1.24316528e+02 1.24712242e+02 1.24878990e+02 1.25443459e+02 1.29195572e+02 1.66606110e+02 2.50631073e+02 4.88508118e+02 4.87185394e+02 4.84087006e+02 4.80989594e+02 2.46875610e+02 2.61528442e+02 2.51162231e+02 7.34510864e+02 1.53067346e+03 470462592. 5.22858598e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.33518208e+09 3.91112274e+02 2.13883591e+02 1.49326035e+02 1.70513672e+02 1.27809799e+02 1.27776497e+02 1.26096642e+02 1.25302917e+02 1.24628029e+02 1.24224747e+02 1.24013870e+02 1.23938499e+02 1.23949585e+02 1.24002426e+02 1.24082054e+02 1.24120110e+02 1.24161667e+02 1.24472221e+02 1.24382164e+02 1.24276718e+02 1.23901810e+02 1.24011909e+02 1.24110397e+02 1.24168137e+02 1.24320000e+02 1.24571304e+02 1.24614616e+02 1.24560760e+02 1.24385132e+02 1.24453957e+02 1.24515961e+02 1.24561989e+02 1.24563614e+02 1.24532158e+02 1.24630943e+02 1.24627625e+02 1.24635094e+02 1.24596596e+02 1.24585670e+02 1.24423553e+02 1.24114845e+02 1.23755585e+02 1.23723915e+02 1.23723755e+02 1.23872482e+02 1.23844795e+02 1.23927261e+02 1.23961617e+02 1.24018066e+02 1.24027344e+02 1.24046028e+02 1.24023346e+02 1.23995293e+02 1.23945526e+02 1.23894478e+02 1.23827492e+02 1.23749626e+02 1.23802826e+02 1.23871178e+02 1.23962555e+02 1.23921356e+02 1.23711723e+02 1.23251213e+02 1.25034203e+02 1.89913391e+02 6.72628281e+04 0. 0. 0. 0. 0. 1.00610017e+10 1.00610017e+10 1.00610017e+10 0. 0. 0. 0. 0. 0. -5.08327076e+10 2.11135836e+10 4.48520801e+03 4.65070459e+03 932547264. 8.87708795e+10 0. 0. 1.03209476e+11 2.36736938e+11 16279297. 1.43041699e+03 7.21735596e+02 5.10011261e+02 5.16631348e+02 2.64679108e+02 2.33531403e+02 1.61669495e+02 2.24018280e+02 2.43170364e+02 5.10455780e+02 5.11955505e+02 5.14706238e+02 5.20961060e+02 5.23958374e+02 5.23823120e+02 5.20887207e+02 5.17480225e+02 5.15313232e+02 5.13126587e+02 5.14030212e+02 5.14847168e+02 5.13476501e+02 5.09049530e+02 2.43319855e+02 2.13693634e+02 2.32675095e+02 5.09485596e+02 5.10007568e+02 5.10226166e+02 5.11434296e+02 5.13364746e+02 5.22691223e+02 5.33264893e+02 5.44197754e+02 5.44859619e+02 5.42975891e+02 5.34649414e+02 5.25723450e+02 5.17356018e+02 5.14048584e+02 5.11080109e+02 5.09635925e+02 2.56528564e+02 1.71866409e+02 1.29556915e+02 1.28859894e+02 1.28117508e+02 1.27512070e+02 1.27093102e+02 1.27040001e+02 1.26868355e+02 1.26875206e+02 1.26826958e+02 1.27520187e+02 1.28556122e+02 1.29313980e+02 1.29561829e+02 1.64590866e+02 2.45458389e+02 5.16033325e+02 7.13578857e+02 1.39189246e+03 -1.11013249e+11 -3.22145976e+11 0. 1.74624031e+10 1.74624031e+10 1.74624031e+10 0. 0. 8.16336650e+10 8.16336650e+10 8.16336650e+10 0. 0. 0. 0. 0. -2.31351680e+09 1.49020557e+03 7.09756287e+02 2.42256897e+02 1.61518036e+02 1.26997971e+02 1.27517723e+02 1.28484390e+02 1.28781326e+02 1.64140930e+02 2.44084015e+02 5.12808899e+02 5.13394836e+02 5.12759216e+02 5.10170776e+02 5.06398773e+02 2.56672241e+02 1.71233902e+02 1.29496872e+02 1.31570984e+02 1.32179184e+02 1.31520187e+02 1.27799347e+02 1.26784096e+02 1.26442451e+02 1.26400536e+02 1.26427711e+02 1.26427536e+02 1.26455132e+02 1.26490860e+02 1.26504997e+02 1.26518318e+02 1.26537582e+02 1.26572762e+02 1.26640358e+02 1.26769104e+02 1.26829590e+02 1.26912842e+02 1.26955734e+02 1.27044044e+02 1.27031670e+02 1.26947617e+02 1.26882751e+02 1.26787544e+02 1.26734062e+02 1.26668884e+02 1.26581017e+02 1.26518929e+02 1.26482712e+02 1.26507172e+02 1.26528145e+02 1.26549675e+02 1.26682838e+02 1.26832520e+02 1.26963791e+02 1.26810646e+02 1.26566139e+02 1.26356659e+02 1.26265610e+02 1.26253616e+02 1.26270653e+02 1.26368835e+02 1.26382019e+02 1.26427254e+02 1.26511444e+02 1.26632217e+02 1.26716728e+02 1.26664307e+02 1.26704765e+02 1.26642639e+02 1.26628723e+02 1.26475525e+02 1.26376862e+02 1.26271202e+02 1.26256783e+02 1.26315315e+02 1.26405098e+02 1.26495651e+02 1.26384171e+02 1.26281479e+02 1.26185089e+02 1.26220726e+02 1.26228859e+02 1.26214577e+02 1.26214745e+02 1.26144363e+02 1.26067787e+02 1.25953117e+02 1.25926064e+02 1.25944321e+02 1.26081436e+02 1.26149147e+02 1.26189018e+02 1.26109566e+02 1.26019882e+02 1.25916306e+02 1.25818970e+02 1.25844070e+02 1.25872261e+02 1.25869392e+02 1.25816391e+02 1.25815269e+02 1.25934990e+02 1.26225922e+02 1.26538109e+02 1.26404770e+02 1.26330437e+02 1.26160667e+02 1.26446350e+02 1.26384918e+02 1.26299202e+02 1.26217781e+02 1.26180305e+02 1.26227440e+02 1.26261383e+02 1.26280205e+02 1.26274452e+02 1.26285400e+02 1.26287849e+02 1.26312279e+02 1.26265144e+02 1.26221619e+02 1.26254982e+02 1.26375572e+02 1.26481339e+02 1.26482506e+02 1.26484848e+02 1.26500374e+02 1.26509338e+02 1.26495949e+02 1.26508804e+02 1.26480698e+02 1.26480186e+02 1.26454155e+02 1.26427910e+02 1.26383392e+02 1.26196053e+02 1.26203178e+02 1.26196136e+02 1.26305550e+02 1.26250725e+02 1.26216293e+02 1.26242249e+02 1.26276863e+02 1.26345314e+02 1.26422829e+02 1.26431900e+02 1.26459427e+02 1.26407372e+02 1.26376427e+02 1.26438110e+02 1.26558601e+02 1.26625343e+02 1.26584930e+02 1.26497276e+02 1.26404327e+02 1.26365189e+02 1.26354080e+02 1.26406990e+02 1.26455673e+02 1.26505798e+02 1.26586143e+02 1.26659981e+02 1.26754959e+02 1.26765434e+02 1.26760284e+02 1.26744789e+02 1.26806206e+02 1.26780174e+02 1.26823868e+02 1.26777809e+02 1.26870789e+02 1.26892136e+02 1.26947182e+02 1.26997383e+02 1.27014183e+02 1.27112625e+02 1.28179993e+02 1.30945602e+02 1.31582214e+02 1.31702103e+02 1.28464111e+02 1.27361519e+02 1.25698990e+02 1.60724808e+02 2.45189789e+02 2.54390854e+02 1.73118118e+02 1.29682770e+02 1.30996765e+02 1.28225113e+02 1.27517082e+02 1.27188232e+02 1.26832985e+02 1.26549828e+02 1.26386612e+02 1.26356895e+02 1.26273415e+02 1.26182739e+02 1.26171089e+02 1.26281464e+02 1.26386253e+02 1.26312958e+02 1.26250938e+02 1.26177261e+02 1.26235497e+02 1.26370529e+02 1.26479942e+02 1.26649155e+02 1.26677139e+02 1.26699005e+02 1.26778198e+02 1.26617455e+02 1.26613342e+02 1.26710472e+02 1.26737625e+02 1.26797142e+02 1.26851120e+02 1.26794212e+02 1.26837296e+02 1.26898918e+02 1.26934578e+02 1.26967087e+02 1.26995346e+02 1.27002960e+02 1.26939941e+02 1.26789139e+02 1.26811462e+02 1.26794266e+02 1.26774857e+02 1.26751656e+02 1.26741730e+02 1.26904121e+02 1.26908714e+02 1.27071426e+02 1.27137901e+02 1.27290642e+02 1.27365532e+02 1.27284538e+02 1.27243385e+02 1.27178329e+02 1.27168076e+02 1.27178398e+02 1.27155472e+02 1.27165497e+02 1.27025131e+02 1.26920235e+02 1.26849625e+02 1.26912880e+02 1.26981842e+02 1.26981773e+02 1.26991508e+02 1.27005264e+02 1.27014641e+02 1.27055122e+02 1.27086159e+02 1.27123528e+02 1.27016769e+02 1.27009689e+02 1.27031487e+02 1.27162567e+02 1.27167534e+02 1.27184433e+02 1.27174957e+02 1.27190338e+02 1.27137383e+02 1.27085251e+02 1.27078903e+02 1.27079742e+02 1.27111046e+02 1.27114807e+02 1.27114052e+02 1.27081673e+02 1.27057869e+02 1.27067528e+02 1.27089455e+02 1.27116348e+02 1.27135422e+02 1.27137421e+02 1.27119057e+02 1.27105789e+02 1.27096832e+02 1.27150467e+02 1.27187195e+02 1.27241325e+02 1.27179520e+02 1.27165314e+02 1.27105156e+02 1.27101814e+02 1.27086777e+02 1.27080254e+02 1.27018105e+02 1.26989670e+02 1.26983665e+02 1.26963600e+02 1.26990997e+02 1.27019943e+02 1.27064301e+02 1.27062263e+02 1.27104088e+02 1.27156815e+02 1.27181282e+02 1.27127502e+02 1.26983711e+02 1.26877861e+02 1.26981285e+02 1.26976471e+02 1.26957146e+02 1.26749947e+02 1.26758163e+02 1.26771851e+02 1.26797173e+02 1.26772957e+02 1.26741386e+02 1.26669640e+02 1.26677040e+02 1.26643555e+02 1.26673538e+02 1.26628372e+02 1.26596107e+02 1.26580528e+02 1.26605820e+02 1.26647400e+02 1.26679131e+02 1.26796654e+02 1.26829109e+02 1.27144318e+02 1.27209854e+02 1.27200294e+02 1.27058899e+02 1.27135422e+02 1.27293617e+02 1.27345810e+02 1.27211853e+02 1.27056847e+02 1.26909637e+02 1.26904022e+02 1.26895149e+02 1.26888306e+02 1.26888977e+02 1.26876213e+02 1.26855309e+02 1.26856148e+02 1.26880432e+02 1.26914917e+02 1.26947556e+02 1.26951736e+02 1.26918320e+02 1.26890770e+02 1.26859543e+02 1.26874321e+02 1.26880203e+02 1.26908524e+02 1.26908630e+02 1.26916008e+02 1.26940918e+02 1.26975357e+02 1.26990784e+02 1.26994499e+02 1.26974030e+02 1.26972618e+02 1.26948769e+02 1.26945541e+02 1.26981415e+02 1.27053169e+02 1.27107437e+02 1.27120453e+02 1.27081459e+02 1.27013214e+02 1.26971527e+02 1.26962837e+02 1.26957680e+02 1.26948448e+02 1.26979034e+02 1.27072166e+02 1.27136909e+02 1.27100250e+02 1.27034477e+02 1.26883682e+02 1.26740364e+02 1.26614929e+02 1.26578133e+02 1.26558136e+02 1.26527802e+02 1.26469986e+02 1.26434143e+02 1.26382393e+02 1.26393089e+02 1.26389557e+02 1.26376740e+02 1.26337379e+02 1.26302269e+02 1.26273170e+02 1.26253906e+02 1.26252914e+02 1.26253166e+02 1.26263016e+02 1.26310127e+02 1.26447884e+02 1.26719009e+02 1.26775253e+02 1.26689072e+02 1.26437599e+02 1.26371841e+02 1.26334679e+02 1.26318245e+02 1.26306305e+02 1.26427155e+02 1.26591232e+02 1.26788368e+02 1.26808022e+02 1.26818123e+02 1.26805809e+02 1.26829185e+02 1.26892670e+02 1.26957924e+02 1.26987892e+02 1.26979248e+02 1.27019783e+02 1.27050247e+02 1.27058945e+02 1.27066368e+02 1.27132286e+02 1.27196510e+02 1.27219704e+02 1.27219299e+02 1.27215111e+02 1.27253632e+02 1.27280052e+02 1.27347855e+02 1.27515320e+02 1.27562897e+02 1.27520248e+02 1.27493431e+02 1.27562256e+02 1.27496315e+02 1.27313675e+02 1.27111801e+02 1.27081642e+02 1.27296059e+02 1.27463745e+02 1.27448036e+02 1.27225662e+02 1.27077728e+02 1.27135551e+02 1.27081909e+02 1.27216995e+02 1.27349808e+02 1.27546738e+02 1.27414124e+02 1.27152428e+02 1.27013329e+02 1.26914803e+02 1.26938354e+02 1.26849449e+02 1.26844360e+02 1.26919792e+02 1.27016518e+02 1.27110817e+02 1.27146423e+02 1.27152092e+02 1.27141159e+02 1.27139320e+02 1.27140732e+02 1.27168022e+02 1.27181351e+02 1.27220695e+02 1.27240952e+02 1.27262489e+02 1.27276718e+02 1.27262985e+02 1.27237450e+02 1.27185501e+02 1.27139763e+02 1.27149147e+02 1.27154182e+02 1.27146805e+02 1.27151840e+02 1.27183983e+02 1.27218468e+02 1.27211029e+02 1.27172134e+02 1.27143013e+02 1.27164268e+02 1.27126129e+02 1.27183502e+02 1.27146088e+02 1.27312286e+02 1.27339836e+02 1.27435242e+02 1.27376900e+02 1.27378723e+02 1.27400436e+02 1.27454742e+02 1.27439713e+02 1.27390305e+02 1.27369797e+02 1.27386375e+02 1.27297859e+02 1.27321465e+02 1.27357986e+02 1.27462395e+02 1.27487007e+02 1.27414238e+02 1.27344490e+02 1.27090309e+02 1.26904266e+02 1.26777626e+02 1.26854523e+02 1.26933197e+02 1.26922127e+02 1.26948898e+02 1.27030617e+02 1.27126434e+02 1.27097069e+02 1.27087227e+02 1.27140022e+02 1.27136765e+02 1.27147858e+02 1.27152466e+02 1.27232788e+02 1.27241898e+02 1.27212875e+02 1.27216713e+02 1.27168205e+02 1.27170517e+02 1.27205864e+02 1.27262268e+02 1.27262047e+02 1.27244591e+02 1.27260796e+02 1.27319908e+02 1.27350456e+02 1.27369095e+02 1.27311821e+02 1.27286606e+02 1.27291252e+02 1.27214027e+02 1.27102402e+02 1.27031639e+02 1.27065239e+02 1.27134247e+02 1.27128815e+02 1.27098381e+02 1.27100433e+02 1.27074600e+02 1.26907738e+02 1.26788002e+02 1.26813087e+02 1.26977837e+02 1.27047775e+02 1.27068573e+02 1.27083679e+02 1.27083145e+02 1.27018242e+02 1.26997002e+02 1.26990227e+02 1.26851204e+02 1.26790352e+02 1.26742554e+02 1.26849518e+02 1.26804108e+02 1.26824249e+02 1.26876656e+02 1.26953407e+02 1.26984543e+02 1.27032600e+02 1.27079697e+02 1.27069458e+02 1.27122437e+02 1.27014046e+02 1.27065201e+02 1.27071960e+02 1.27230736e+02 1.27236237e+02 1.27085030e+02 1.27007317e+02 1.26982193e+02 1.27060066e+02 1.27035568e+02 1.26999832e+02 1.26958740e+02 1.27002396e+02 1.27029900e+02 1.27093620e+02 1.27113174e+02 1.27171494e+02 1.27244026e+02 1.27331520e+02 1.27353149e+02 1.27284737e+02 1.27207314e+02 1.27247375e+02 1.27311501e+02 1.27421989e+02 1.27365547e+02 1.27295471e+02 1.27168098e+02 1.27125221e+02 1.27083015e+02 1.27115196e+02 1.27213409e+02 1.27282135e+02 1.27278137e+02 1.27236473e+02 1.27190964e+02 1.27133263e+02 1.27097450e+02 1.27124855e+02 1.27076332e+02 1.27069145e+02 1.27090950e+02 1.27142319e+02 1.26945976e+02 1.26851250e+02 1.26862900e+02 1.27035225e+02 1.27082497e+02 1.27096268e+02 1.27064552e+02 1.27047867e+02 1.26994423e+02 1.26898201e+02 1.26784073e+02 1.26692253e+02 1.26693428e+02 1.26821320e+02 1.26858788e+02 1.26911705e+02 1.26578583e+02 1.25467888e+02 1.24289230e+02 1.23428711e+02 1.23470818e+02 1.23929985e+02 1.24291016e+02 1.24465401e+02 1.24185753e+02 1.23497635e+02 1.74260635e+02 1.52883926e+02 1.65483078e+02 1.23475662e+02 1.24653778e+02 1.82944809e+02 1.57563309e+02 1.69005539e+02 1.24728523e+02 1.24073257e+02 1.23679466e+02 1.22942032e+02 1.23440765e+02 1.23680397e+02 1.24446152e+02 1.26311844e+02 1.31683258e+02 1.32513535e+02 1.32234940e+02 1.27869331e+02 1.28117828e+02 1.28315948e+02 1.27969307e+02 1.31186234e+02 1.38419739e+02 1.40282272e+02 1.37379898e+02 1.29290497e+02 1.27820740e+02 1.26870224e+02 1.26852821e+02 1.26849480e+02 1.26869202e+02 1.26870277e+02 1.26925865e+02 1.27120811e+02 1.27171471e+02 1.27122849e+02 1.26960434e+02 1.26971542e+02 1.27151573e+02 1.27312546e+02 1.27318527e+02 1.27315903e+02 1.27323235e+02 1.27362473e+02 1.27309746e+02 1.27286659e+02 1.27182732e+02 1.27183479e+02 1.27210609e+02 1.27290985e+02 1.27241699e+02 1.27098808e+02 1.26906044e+02 1.26897224e+02 1.26863060e+02 1.26877693e+02 1.26774254e+02 1.26789169e+02 1.26946365e+02 1.27042923e+02 1.27139442e+02 1.27081940e+02 1.27094955e+02 1.27050423e+02 1.27013649e+02 1.26849823e+02 1.26780876e+02 1.26683243e+02 1.26721191e+02 1.26727211e+02 1.26866371e+02 1.26974892e+02 1.27039513e+02 1.26901413e+02 1.26793198e+02 1.26659897e+02 1.26639717e+02 1.26705246e+02 1.26726479e+02 1.26932343e+02 1.27043587e+02 1.27011940e+02 1.26779312e+02 1.26623177e+02 1.26710495e+02 1.26763489e+02 1.26804359e+02 1.26865845e+02 1.26866501e+02 1.26816254e+02 1.26821587e+02 1.26809517e+02 1.26761887e+02 1.26564430e+02 1.26471306e+02 1.26616959e+02 1.26553909e+02 1.26531128e+02 1.26283913e+02 1.26402122e+02 1.26489410e+02 1.26358978e+02 1.26176628e+02 1.25982727e+02 1.26436584e+02 1.26960640e+02 1.27186577e+02 1.26828781e+02 1.26405289e+02 1.26368477e+02 1.26366692e+02 1.26388390e+02 1.26407074e+02 1.26394951e+02 1.26364319e+02 1.26352272e+02 1.26351738e+02 1.26318413e+02 1.26285454e+02 1.26255547e+02 1.26262764e+02 1.26411919e+02 1.26575867e+02 1.26703468e+02 1.26730576e+02 1.26774872e+02 1.26857498e+02 1.26864998e+02 1.26712326e+02 1.26566628e+02 1.26421188e+02 1.26565125e+02 1.26729156e+02 1.26912498e+02 1.26921425e+02 1.26921402e+02 1.26912918e+02 1.26881363e+02 1.27010277e+02 1.27176193e+02 1.27408272e+02 1.27279587e+02 1.27103928e+02 1.26778900e+02 1.26735352e+02 1.26710678e+02 1.26727798e+02 1.26724426e+02 1.26734848e+02 1.26727692e+02 1.26714462e+02 1.26699165e+02 1.26723099e+02 1.26737740e+02 1.26790489e+02 1.26811569e+02 1.26865189e+02 1.26842621e+02 1.26831482e+02 1.26815323e+02 1.26835403e+02 1.26326271e+02 1.25865379e+02 1.25418701e+02 1.25465363e+02 1.25984596e+02 1.26571289e+02 1.27219879e+02 1.27643898e+02 1.28148773e+02 1.29443558e+02 1.35822083e+02 1.45827042e+02 1.74011719e+02 1.62512329e+02 1.51652939e+02 1.62572021e+02 2.42174393e+02 5.02849792e+02 5.02392181e+02 5.02084259e+02 5.02409363e+02 5.03284332e+02 5.07005707e+02 5.08645355e+02 5.12984009e+02 2.57657074e+02 1.73955963e+02 1.30349518e+02 1.30332062e+02 1.30154999e+02 1.29948013e+02 1.29309235e+02 1.28925995e+02 1.27840057e+02 1.27640625e+02 1.69433014e+02 2.81808838e+02 9.82878723e+02 -2.03668350e+06 -1.37240955e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.05719910e+03 1.28700171e+03 5.87957520e+02 7.36170898e+02 5.18253662e+02 5.20242065e+02 5.09520630e+02 2.64424042e+02 1.75680099e+02 1.31378204e+02 1.28522812e+02 1.27896408e+02 1.27565971e+02 1.27563942e+02 1.27689743e+02 1.27770912e+02 1.27617195e+02 1.27274994e+02 1.26985168e+02 1.26965698e+02 1.27188347e+02 1.27686661e+02 1.28150696e+02 1.28578659e+02 1.28789246e+02 1.28582840e+02 1.28028046e+02 1.27406853e+02 1.27158318e+02 1.27137245e+02 1.27435249e+02 1.27810463e+02 1.28307846e+02 1.28934998e+02 1.29077362e+02 1.28857010e+02 1.27955063e+02 1.27453003e+02 1.27164452e+02 1.27208092e+02 1.27466393e+02 1.27950378e+02 1.28385803e+02 1.28431961e+02 1.28087250e+02 1.27696754e+02 1.27420105e+02 1.27457428e+02 1.27772125e+02 1.28159058e+02 1.28763000e+02 1.28862991e+02 1.29103500e+02 1.28683624e+02 1.28379166e+02 1.28817703e+02 1.29175934e+02 1.65027298e+02 2.43027649e+02 4.99182220e+02 4.99133911e+02 4.99895599e+02 5.02641754e+02 5.07595917e+02 7.67628174e+02 3.01979980e+04 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 9.21718374e+09 9.21718374e+09 0. 0. -5.08327076e+10 2.11135836e+10 4.48520801e+03 4.65070459e+03 932547264. 8.87708795e+10 0. 0. 0. 0. 0. 6.06098516e+04 3.25550659e+02 3.10796326e+02 418750496. 1.58762378e+03 1.12936523e+03 6.78496460e+02 1.03189575e+03 1.38153259e+03 359164672. 69815080. 828222528. 2051161472. 76438816. 1.36619848e+10 6.70174054e+09 9.28671949e+09 247992896. 1390688000. 121055824. 98054560. 3.50411926e+02 2.42600327e+02 2.37523712e+02 9.13790161e+02 1.21502197e+03 287219584. -8.76333158e+09 1032002304. 2.49250775e+10 1.35061780e+10 4.01301925e+06 4.58622250e+06 195776592. 2.29445299e+09 11696645. 310372928. 24509534. 4.32768768e+09 -2.16554455e+10 604460736. 4.46469069e+09 1.49520032e+03 7.55227844e+02 5.26271362e+02 5.20890442e+02 5.16150879e+02 2.54341995e+02 1.70570953e+02 1.29261536e+02 1.29242889e+02 1.28563248e+02 1.62207336e+02 2.43988068e+02 5.28870667e+02 5.33937805e+02 5.34215759e+02 7.27212646e+02 1.42224475e+03 180660624. 6.96897741e+09 -7.49291602e+10 0. 0. 0. 1.74624031e+10 1.74624031e+10 1.74624031e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.64476685e+02 2.89827789e+02 1.61276489e+02 1.27343567e+02 1.27213142e+02 1.27502052e+02 1.28052856e+02 1.28167282e+02 1.27839088e+02 1.27594566e+02 1.27094917e+02 1.26628731e+02 1.26350777e+02 1.26747261e+02 1.27563004e+02 1.28180222e+02 1.28592957e+02 1.28881668e+02 1.28853241e+02 1.28169922e+02 1.27754883e+02 1.27218307e+02 1.26734398e+02 1.26347740e+02 1.26127182e+02 1.26051308e+02 1.26116196e+02 1.26138084e+02 1.26117638e+02 1.26074287e+02 1.26113106e+02 1.26117706e+02 1.26072670e+02 1.26020264e+02 1.26033394e+02 1.26124352e+02 1.26048271e+02 1.25981720e+02 1.25727333e+02 1.25606018e+02 1.25450851e+02 1.25268349e+02 1.25203300e+02 1.25128151e+02 1.25166496e+02 1.25229782e+02 1.25312897e+02 1.25374184e+02 1.25397232e+02 1.25399254e+02 1.25422386e+02 1.25641220e+02 1.25872330e+02 1.26052002e+02 1.25910950e+02 1.25839645e+02 1.25808205e+02 1.25819740e+02 1.25771599e+02 1.25770714e+02 1.25804085e+02 1.25859123e+02 1.25821503e+02 1.25848083e+02 1.25808998e+02 1.25811012e+02 1.25842850e+02 1.25892189e+02 1.25977203e+02 1.25991478e+02 1.26042030e+02 1.26128426e+02 1.26262047e+02 1.26347153e+02 1.26357544e+02 1.26375450e+02 1.26379791e+02 1.26576225e+02 1.26567947e+02 1.26623215e+02 1.26526505e+02 1.26617561e+02 1.26646683e+02 1.26625015e+02 1.26646614e+02 1.26647652e+02 1.26782936e+02 1.26832672e+02 1.26869919e+02 1.26782555e+02 1.26762741e+02 1.26637344e+02 1.26443367e+02 1.26254097e+02 1.26248138e+02 1.26266434e+02 1.26248695e+02 1.26270226e+02 1.26314934e+02 1.26380119e+02 1.26353065e+02 1.26366943e+02 1.26379158e+02 1.26500511e+02 1.26668266e+02 1.27128784e+02 1.27075249e+02 1.26993553e+02 1.26746651e+02 1.26817772e+02 1.26790283e+02 1.26807594e+02 1.26794319e+02 1.26852943e+02 1.26874214e+02 1.26874611e+02 1.26851540e+02 1.26803726e+02 1.26727654e+02 1.26657326e+02 1.26543549e+02 1.26607063e+02 1.26694542e+02 1.26826973e+02 1.26925911e+02 1.27001411e+02 1.27119560e+02 1.27177223e+02 1.27155464e+02 1.27107086e+02 1.27048355e+02 1.27046539e+02 1.27070618e+02 1.27082275e+02 1.27095688e+02 1.27076073e+02 1.27041359e+02 1.27084114e+02 1.27145714e+02 1.27219620e+02 1.27165474e+02 1.27188042e+02 1.27203636e+02 1.27202309e+02 1.27169739e+02 1.27165649e+02 1.27110474e+02 1.27011284e+02 1.26983307e+02 1.26968910e+02 1.27039757e+02 1.27051140e+02 1.27083672e+02 1.27091553e+02 1.27118988e+02 1.27105499e+02 1.27098984e+02 1.26999718e+02 1.27000305e+02 1.26981178e+02 1.26970047e+02 1.26903610e+02 1.26809959e+02 1.26797653e+02 1.26860329e+02 1.26975800e+02 1.26979691e+02 1.26998795e+02 1.26896294e+02 1.26863319e+02 1.26706322e+02 1.26739899e+02 1.26737381e+02 1.26739182e+02 1.26645340e+02 1.26517014e+02 1.26216621e+02 1.25828033e+02 1.25231865e+02 1.25146484e+02 1.24940079e+02 1.24730919e+02 1.23717575e+02 1.24567741e+02 1.26409393e+02 1.30136902e+02 1.29536987e+02 1.27487228e+02 1.24432861e+02 1.24413002e+02 1.65466217e+02 2.47146210e+02 4.95166138e+02 4.94362915e+02 4.93286621e+02 6.74383606e+02 1.31212756e+03 1.46849402e+03 7.75161743e+02 5.45839111e+02 5.49788757e+02 5.29515259e+02 5.19943909e+02 5.13675964e+02 5.09130096e+02 5.07783752e+02 5.05971436e+02 5.05261627e+02 2.42525726e+02 2.24296295e+02 2.54579803e+02 5.00578064e+02 2.29260880e+02 1.55352539e+02 1.23737991e+02 1.25946320e+02 1.26436150e+02 1.26529373e+02 1.26508812e+02 1.26487633e+02 1.26451591e+02 1.26488220e+02 1.26449432e+02 1.26419044e+02 1.26458870e+02 1.26474197e+02 1.26381927e+02 1.26386986e+02 1.26350090e+02 1.26440948e+02 1.26397293e+02 1.26529373e+02 1.26695175e+02 1.26879295e+02 1.26871086e+02 1.26888397e+02 1.26834061e+02 1.26978218e+02 1.26940170e+02 1.27051033e+02 1.27024193e+02 1.27140388e+02 1.27123215e+02 1.27171745e+02 1.27134514e+02 1.27082733e+02 1.26969521e+02 1.26815834e+02 1.26819565e+02 1.26797798e+02 1.26803429e+02 1.26772835e+02 1.26758286e+02 1.26772141e+02 1.26777481e+02 1.26829651e+02 1.26828117e+02 1.26869125e+02 1.26828941e+02 1.26895073e+02 1.26889717e+02 1.26920708e+02 1.26868835e+02 1.26860321e+02 1.26848251e+02 1.26837288e+02 1.26809883e+02 1.26844704e+02 1.26875145e+02 1.26873581e+02 1.26843307e+02 1.26792633e+02 1.26749382e+02 1.26657761e+02 1.26633476e+02 1.26631729e+02 1.26604614e+02 1.26565247e+02 1.26571198e+02 1.26604530e+02 1.26629143e+02 1.26612892e+02 1.26692543e+02 1.26765732e+02 1.26842636e+02 1.26769432e+02 1.26727135e+02 1.26756844e+02 1.26760674e+02 1.26790115e+02 1.26758331e+02 1.26662384e+02 1.26492508e+02 1.26390366e+02 1.26362244e+02 1.26377296e+02 1.26312973e+02 1.26301338e+02 1.26285530e+02 1.26419296e+02 1.26556320e+02 1.26758987e+02 1.26648247e+02 1.26464737e+02 1.26352180e+02 1.26540581e+02 1.26761703e+02 1.26810196e+02 1.26777756e+02 1.26795647e+02 1.26808182e+02 1.26813744e+02 1.26820045e+02 1.26817848e+02 1.26811867e+02 1.26777046e+02 1.26754860e+02 1.26705261e+02 1.26651314e+02 1.26571091e+02 1.26506310e+02 1.26443268e+02 1.26499474e+02 1.26646713e+02 1.26810013e+02 1.26820709e+02 1.26933136e+02 1.26982086e+02 1.27065506e+02 1.26969757e+02 1.27015549e+02 1.27060822e+02 1.27114311e+02 1.27127052e+02 1.27025604e+02 1.26887695e+02 1.26814186e+02 1.26806831e+02 1.26936745e+02 1.27060707e+02 1.27178780e+02 1.27171677e+02 1.27096695e+02 1.27096931e+02 1.27073303e+02 1.27125381e+02 1.27029236e+02 1.26942520e+02 1.27031090e+02 1.27174164e+02 1.27206375e+02 1.27042099e+02 1.26928177e+02 1.26961388e+02 1.26969193e+02 1.26990204e+02 1.26962524e+02 1.26970619e+02 1.26990074e+02 1.26993355e+02 1.27016510e+02 1.26997620e+02 1.27084793e+02 1.27219337e+02 1.27324379e+02 1.27388565e+02 1.27414024e+02 1.27458977e+02 1.27449287e+02 1.27351646e+02 1.27274902e+02 1.27131920e+02 1.27049286e+02 1.26925507e+02 1.27006157e+02 1.27047775e+02 1.27061478e+02 1.26958267e+02 1.26968414e+02 1.27016121e+02 1.27055565e+02 1.27158539e+02 1.27271111e+02 1.27411194e+02 1.27436470e+02 1.27673347e+02 1.27901711e+02 1.28145477e+02 1.27928009e+02 1.27707626e+02 1.27479393e+02 1.27467842e+02 1.27312134e+02 1.27174278e+02 1.27191200e+02 1.27314072e+02 1.27448952e+02 1.27664597e+02 1.27885109e+02 1.27928688e+02 1.27755775e+02 1.27623611e+02 1.27709061e+02 1.27775833e+02 1.27789421e+02 1.27842644e+02 1.27935806e+02 1.27789185e+02 1.27633675e+02 1.27455719e+02 1.27474388e+02 1.27436058e+02 1.27453712e+02 1.27471428e+02 1.27562798e+02 1.27565857e+02 1.27544594e+02 1.27454018e+02 1.27423897e+02 1.27428398e+02 1.27439148e+02 1.27419563e+02 1.27399490e+02 1.27337967e+02 1.27251205e+02 1.27205757e+02 1.27129257e+02 1.27156601e+02 1.27134079e+02 1.27124321e+02 1.27043304e+02 1.27096169e+02 1.27187881e+02 1.27247330e+02 1.27085236e+02 1.26985817e+02 1.27003113e+02 1.27049332e+02 1.27084976e+02 1.27075600e+02 1.27104088e+02 1.27142342e+02 1.27184685e+02 1.27269623e+02 1.27303223e+02 1.27343208e+02 1.27344109e+02 1.27403809e+02 1.27487457e+02 1.27493835e+02 1.27282089e+02 1.27191101e+02 1.27099480e+02 1.27282524e+02 1.27268738e+02 1.27285912e+02 1.27254570e+02 1.27242386e+02 1.27183578e+02 1.27018135e+02 1.26971428e+02 1.26979225e+02 1.27182373e+02 1.27198006e+02 1.27128433e+02 1.27055519e+02 1.27030136e+02 1.27051941e+02 1.27041069e+02 1.26987701e+02 1.26927643e+02 1.26905647e+02 1.26848694e+02 1.26789505e+02 1.26700783e+02 1.26684967e+02 1.26693008e+02 1.26714149e+02 1.26667809e+02 1.26608437e+02 1.26676659e+02 1.26660271e+02 1.26557198e+02 1.26373657e+02 1.26138542e+02 1.25988075e+02 1.26019981e+02 1.26284737e+02 1.26559242e+02 1.26567200e+02 1.26564308e+02 1.26565788e+02 1.26533386e+02 1.26783150e+02 1.26948692e+02 1.26957420e+02 1.26760933e+02 1.26679001e+02 1.26813614e+02 1.27034737e+02 1.27193459e+02 1.27387970e+02 1.27437439e+02 1.27479813e+02 1.27449501e+02 1.27310867e+02 1.27267677e+02 1.27201324e+02 1.27220871e+02 1.27200813e+02 1.27097313e+02 1.26949860e+02 1.26813126e+02 1.26772736e+02 1.26941635e+02 1.27146111e+02 1.27189896e+02 1.27284813e+02 1.27306587e+02 1.27503426e+02 1.27377708e+02 1.27254868e+02 1.27054756e+02 1.27228203e+02 1.27413963e+02 1.27626305e+02 1.27548897e+02 1.27514435e+02 1.27299263e+02 1.27141563e+02 1.27074547e+02 1.27061928e+02 1.27033760e+02 1.26881424e+02 1.26844505e+02 1.26804138e+02 1.26799538e+02 1.26764740e+02 1.26761436e+02 1.26725121e+02 1.26704849e+02 1.26745483e+02 1.26725670e+02 1.26773087e+02 1.26769867e+02 1.26797615e+02 1.26815742e+02 1.26863518e+02 1.27107117e+02 1.27336815e+02 1.27562714e+02 1.27594154e+02 1.27560486e+02 1.27509689e+02 1.27398499e+02 1.27371056e+02 1.27378578e+02 1.27476700e+02 1.27486763e+02 1.27522552e+02 1.27455406e+02 1.27309166e+02 1.27172798e+02 1.27046646e+02 1.26978287e+02 1.26913719e+02 1.26895508e+02 1.26930435e+02 1.26922173e+02 1.26894684e+02 1.26840691e+02 1.26834122e+02 1.26878891e+02 1.27089958e+02 1.27117790e+02 1.27193062e+02 1.27135742e+02 1.27226616e+02 1.27267006e+02 1.27227943e+02 1.27259918e+02 1.27198074e+02 1.27280182e+02 1.27264473e+02 1.27271149e+02 1.27179733e+02 1.27104500e+02 1.27097137e+02 1.27126648e+02 1.27160400e+02 1.27217194e+02 1.27289482e+02 1.27368111e+02 1.27412323e+02 1.27472069e+02 1.27535484e+02 1.27576408e+02 1.27548767e+02 1.27483414e+02 1.27538315e+02 1.27600098e+02 1.27666023e+02 1.27654755e+02 1.27577072e+02 1.27564400e+02 1.27491928e+02 1.27459778e+02 1.27352409e+02 1.27288277e+02 1.27262764e+02 1.27238121e+02 1.27308525e+02 1.27281723e+02 1.27285744e+02 1.27149002e+02 1.27169487e+02 1.27162117e+02 1.27180923e+02 1.27189140e+02 1.27073265e+02 1.26962479e+02 1.26836784e+02 1.26849823e+02 1.26867378e+02 1.26887009e+02 1.26920708e+02 1.26940926e+02 1.27002373e+02 1.26939636e+02 1.26672173e+02 1.25699989e+02 1.24369209e+02 1.23364105e+02 1.22055176e+02 1.21597816e+02 1.21499718e+02 1.22526001e+02 1.23229156e+02 1.23416420e+02 1.64498795e+02 2.48026321e+02 5.11267578e+02 5.15526001e+02 5.22237366e+02 5.29096191e+02 5.44800415e+02 5.45455444e+02 5.46449158e+02 5.36062134e+02 5.38148010e+02 2.14853851e+02 1.96053741e+02 1.38488129e+02 1.53654953e+02 1.29329102e+02 1.38110626e+02 1.41317688e+02 1.33101288e+02 1.28459564e+02 1.26345497e+02 1.24993080e+02 1.24305222e+02 1.24318230e+02 1.23857185e+02 1.23912201e+02 1.24275826e+02 1.24934563e+02 1.25787865e+02 1.26230873e+02 1.26409485e+02 1.26513016e+02 1.26594948e+02 1.26651299e+02 1.26657967e+02 1.26685806e+02 1.26738968e+02 1.26846481e+02 1.27027367e+02 1.27039322e+02 1.27106270e+02 1.27043793e+02 1.27140556e+02 1.27110443e+02 1.27054749e+02 1.27035515e+02 1.27021873e+02 1.27038261e+02 1.27019150e+02 1.27044670e+02 1.27141060e+02 1.27172867e+02 1.27171112e+02 1.27103592e+02 1.27175354e+02 1.27254372e+02 1.27341644e+02 1.27251488e+02 1.27071259e+02 1.27024780e+02 1.27107567e+02 1.27237534e+02 1.27246376e+02 1.27179825e+02 1.27157280e+02 1.27079155e+02 1.26910179e+02 1.26744896e+02 1.26725540e+02 1.26868378e+02 1.27055130e+02 1.26967522e+02 1.26845795e+02 1.26719025e+02 1.26626724e+02 1.26513031e+02 1.26362915e+02 1.26322861e+02 1.26256035e+02 1.26292450e+02 1.26261475e+02 1.26616447e+02 1.26598595e+02 1.26653885e+02 1.26366425e+02 1.26441597e+02 1.26547791e+02 1.26702904e+02 1.26673950e+02 1.26669037e+02 1.26570000e+02 1.26644394e+02 1.26656517e+02 1.26796669e+02 1.26976646e+02 1.27171608e+02 1.27389275e+02 1.27034332e+02 1.26909668e+02 1.26713760e+02 1.26820183e+02 1.26851616e+02 1.26847046e+02 1.26961777e+02 1.27089668e+02 1.26895782e+02 1.26683441e+02 1.26543228e+02 1.26764870e+02 1.26827454e+02 1.26819595e+02 1.26805321e+02 1.26775024e+02 1.26751068e+02 1.26754814e+02 1.26770241e+02 1.26791679e+02 1.26780556e+02 1.26819427e+02 1.26798782e+02 1.26834785e+02 1.26689636e+02 1.26593491e+02 1.26450127e+02 1.26415131e+02 1.26420265e+02 1.26382767e+02 1.26497475e+02 1.26590576e+02 1.26683258e+02 1.26620338e+02 1.26557655e+02 1.26584381e+02 1.26674438e+02 1.26815010e+02 1.26899437e+02 1.26928574e+02 1.26958626e+02 1.26995728e+02 1.26515732e+02 1.26586494e+02 1.26713348e+02 1.26980217e+02 1.26855850e+02 1.26680481e+02 1.26790489e+02 1.26709015e+02 1.26652519e+02 1.26706802e+02 1.26775223e+02 1.26835983e+02 1.26848167e+02 1.26851776e+02 1.26844231e+02 1.26818993e+02 1.26792648e+02 1.26802345e+02 1.26799202e+02 1.26802444e+02 1.26775375e+02 1.26805534e+02 1.26798241e+02 1.26810219e+02 1.26790215e+02 1.26753922e+02 1.26744324e+02 1.26759796e+02 1.26791443e+02 1.26795189e+02 1.26764580e+02 1.26750664e+02 1.26747696e+02 1.26731445e+02 1.26114738e+02 1.25363777e+02 1.20056374e+02 1.20758469e+02 1.22639694e+02 1.26813797e+02 1.26804436e+02 1.26847908e+02 1.26856308e+02 1.26831520e+02 1.26836304e+02 1.26736580e+02 1.26277580e+02 1.26121773e+02 1.25551926e+02 1.21317284e+02 1.58472443e+02 2.31002777e+02 4.76506409e+02 4.77220978e+02 4.76691803e+02 4.79353851e+02 2.33169586e+02 1.58421432e+02 1.24023201e+02 1.21743935e+02 1.22103500e+02 1.57821320e+02 2.88934692e+02 1.10735779e+03 -235696064. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.99325409e+10 1.99325409e+10 -1246027904. -2.52844134e+09 1.72881725e+06 11536147. -2.55979254e+10 1.65906812e+03 8.04596252e+02 5.46006653e+02 5.24453918e+02 5.21236694e+02 5.19438538e+02 2.58575409e+02 1.73133881e+02 1.29881027e+02 1.29064026e+02 1.27257477e+02 1.26601425e+02 1.27012306e+02 1.62748993e+02 2.44752411e+02 5.23833313e+02 5.26915222e+02 5.27520874e+02 5.24609680e+02 5.21150208e+02 5.17586975e+02 5.16846863e+02 5.15502747e+02 5.16022095e+02 5.18052490e+02 5.21109375e+02 5.26188782e+02 5.26595764e+02 5.25518982e+02 5.20188049e+02 5.16979187e+02 2.46636368e+02 2.15942322e+02 2.34707367e+02 5.23382751e+02 5.25878723e+02 5.26265198e+02 5.22962646e+02 5.21280151e+02 5.19039856e+02 5.18668640e+02 5.20301697e+02 5.23504395e+02 5.29228210e+02 5.30877319e+02 5.32527283e+02 5.29588379e+02 5.27265015e+02 5.31637024e+02 5.34640564e+02 7.42096680e+02 1.43822632e+03 6.17360794e+09 2.27448648e+10 376413344. 88645232. 53593932. -1.44067932e+10 -1.26839460e+10 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 9.21718374e+09 9.21718374e+09 0. 0. 0. 0. 2.08502292e+10 932547264. 932547264. 8.87708795e+10 0. -2.47085133e+09 -661475520. -2.15342694e+09 4.17563418e+09 46717272. -749295040. -749295040. 0. 1.80222300e+10 1.80222300e+10 1424990720. -4.42926131e+09 -4.42926131e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1066242496. -1066242496. 13508698. -681825408. -681825408. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -799920960. -799920960. -799920960. 0. 0. -251471648. 3.24223724e+02 3.21571411e+02 1.55593369e+02 1.91461670e+02 1.30473160e+02 1.28767487e+02 1.28744232e+02 1.28408325e+02 1.63406830e+02 2.41420609e+02 6.91115479e+02 1.35979944e+03 135729488. 41954260. 148106000. -1233059456. -2.91246899e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.40652134e+09 200282496. 20098144. 3.20194672e+02 1.62697067e+02 1.21970398e+02 1.22054230e+02 1.22292511e+02 1.22047783e+02 1.21533936e+02 1.20975662e+02 1.21127632e+02 1.60100021e+02 2.39369415e+02 4.76039490e+02 4.76635986e+02 4.73940887e+02 4.70612610e+02 4.70324982e+02 2.25617538e+02 1.53479156e+02 1.20937836e+02 1.18977982e+02 1.18739868e+02 1.19482948e+02 1.22776695e+02 1.23793350e+02 1.24127434e+02 1.24321266e+02 1.24278313e+02 1.24199356e+02 1.24006821e+02 1.23847717e+02 1.23656181e+02 1.23716194e+02 1.23612442e+02 1.23638847e+02 1.23469582e+02 1.23507706e+02 1.23491501e+02 1.23393631e+02 1.23245575e+02 1.23227959e+02 1.23276169e+02 1.23130112e+02 1.23124329e+02 1.23130768e+02 1.23346756e+02 1.23440193e+02 1.23615891e+02 1.23685829e+02 1.23731102e+02 1.23737297e+02 1.23739128e+02 1.23784111e+02 1.23690514e+02 1.23600227e+02 1.23444809e+02 1.23607307e+02 1.23845177e+02 1.24175934e+02 1.24304176e+02 1.24408119e+02 1.24407669e+02 1.24345726e+02 1.24251152e+02 1.24152199e+02 1.24038658e+02 1.24012466e+02 1.24056717e+02 1.24145546e+02 1.24073387e+02 1.24075752e+02 1.24095627e+02 1.24229088e+02 1.24360649e+02 1.24497795e+02 1.24564728e+02 1.24558243e+02 1.24539276e+02 1.24544762e+02 1.24782692e+02 1.25032883e+02 1.25235199e+02 1.25272240e+02 1.25273323e+02 1.25311951e+02 1.25286179e+02 1.25358154e+02 1.25420944e+02 1.25520523e+02 1.25505692e+02 1.25491524e+02 1.25439171e+02 1.25463737e+02 1.25410400e+02 1.25387444e+02 1.25390656e+02 1.25452896e+02 1.25535934e+02 1.25564041e+02 1.25600777e+02 1.25634476e+02 1.25494606e+02 1.25267807e+02 1.25001274e+02 1.24891014e+02 1.24898758e+02 1.25455383e+02 1.25418556e+02 1.25335739e+02 1.24839737e+02 1.24852112e+02 1.24923233e+02 1.24963165e+02 1.24980110e+02 1.24917091e+02 1.24872658e+02 1.24873985e+02 1.24895042e+02 1.24937515e+02 1.24929573e+02 1.24895767e+02 1.24848007e+02 1.24847130e+02 1.24878113e+02 1.24893967e+02 1.24924889e+02 1.24943657e+02 1.24961021e+02 1.25009094e+02 1.25071777e+02 1.25154427e+02 1.25211403e+02 1.25300598e+02 1.25320000e+02 1.25314552e+02 1.25267014e+02 1.25231590e+02 1.25220726e+02 1.25242317e+02 1.25295250e+02 1.25369392e+02 1.25310242e+02 1.25317284e+02 1.25318420e+02 1.25360222e+02 1.25440315e+02 1.25513023e+02 1.25572304e+02 1.25570763e+02 1.25520844e+02 1.25418427e+02 1.25322197e+02 1.25257195e+02 1.25268021e+02 1.25300575e+02 1.25349709e+02 1.25401543e+02 1.25435356e+02 1.25445938e+02 1.25399330e+02 1.25348076e+02 1.25274406e+02 1.25194443e+02 1.25092529e+02 1.25021271e+02 1.25045029e+02 1.25113304e+02 1.25164139e+02 1.25154854e+02 1.25184402e+02 1.25230072e+02 1.25282936e+02 1.25276375e+02 1.25204544e+02 1.25057045e+02 1.24893448e+02 1.24779900e+02 1.24629700e+02 1.23479630e+02 1.20727463e+02 1.20408836e+02 1.20365402e+02 1.23280060e+02 1.24256554e+02 1.25782631e+02 1.64253174e+02 2.33877060e+02 2.28460739e+02 1.53488342e+02 1.22743622e+02 1.22424904e+02 1.26267067e+02 1.30265366e+02 1.34427429e+02 1.33406876e+02 1.29675613e+02 1.25536903e+02 1.25299507e+02 1.25339752e+02 1.25006439e+02 1.24971214e+02 1.24970825e+02 1.24847649e+02 1.24900337e+02 1.25281982e+02 1.60399902e+02 2.39902206e+02 5.05971436e+02 5.05261627e+02 2.60568848e+02 1.78380798e+02 1.34670883e+02 1.33138260e+02 1.29379578e+02 1.27474037e+02 1.26504059e+02 1.25991096e+02 1.25717796e+02 1.25500710e+02 1.25339775e+02 1.25245972e+02 1.25062378e+02 1.24956482e+02 1.24768051e+02 1.24723557e+02 1.24725891e+02 1.24802322e+02 1.24991631e+02 1.25066231e+02 1.25131943e+02 1.25119537e+02 1.25101257e+02 1.25190880e+02 1.25098686e+02 1.25024933e+02 1.24769257e+02 1.24541748e+02 1.24461845e+02 1.24427094e+02 1.24634605e+02 1.24726242e+02 1.24901909e+02 1.24936813e+02 1.25010628e+02 1.25021767e+02 1.24960197e+02 1.24995224e+02 1.25068100e+02 1.25137512e+02 1.25089317e+02 1.24991188e+02 1.24934326e+02 1.24934181e+02 1.24935257e+02 1.24926918e+02 1.24880325e+02 1.24853531e+02 1.24814552e+02 1.24874863e+02 1.24856026e+02 1.24924561e+02 1.24856651e+02 1.24838562e+02 1.24737503e+02 1.24725822e+02 1.24723907e+02 1.24753685e+02 1.24784813e+02 1.24795013e+02 1.24788467e+02 1.24762581e+02 1.24722298e+02 1.24702866e+02 1.24694359e+02 1.24686241e+02 1.24679871e+02 1.24635971e+02 1.24588295e+02 1.24566307e+02 1.24605560e+02 1.24632828e+02 1.24539398e+02 1.24481461e+02 1.24455902e+02 1.24500069e+02 1.24477982e+02 1.24445641e+02 1.24446632e+02 1.24454384e+02 1.24410217e+02 1.24470245e+02 1.24575851e+02 1.24720238e+02 1.24630257e+02 1.24615639e+02 1.24615028e+02 1.24729492e+02 1.24714996e+02 1.24729965e+02 1.24741302e+02 1.24737152e+02 1.24718201e+02 1.24737373e+02 1.24807037e+02 1.24829620e+02 1.24872368e+02 1.24830269e+02 1.24985588e+02 1.25025803e+02 1.25161743e+02 1.25139282e+02 1.25109940e+02 1.25126747e+02 1.25178436e+02 1.25258492e+02 1.25224892e+02 1.25132965e+02 1.25061691e+02 1.25037209e+02 1.25055298e+02 1.25070671e+02 1.25121376e+02 1.25141876e+02 1.25132416e+02 1.25131264e+02 1.25147514e+02 1.25021454e+02 1.25086906e+02 1.25133698e+02 1.25352814e+02 1.25214188e+02 1.25154060e+02 1.25042091e+02 1.25047440e+02 1.25093452e+02 1.25118301e+02 1.25116600e+02 1.25118881e+02 1.25140968e+02 1.25172447e+02 1.25235138e+02 1.25312828e+02 1.25364479e+02 1.25377579e+02 1.25360077e+02 1.25341507e+02 1.25363297e+02 1.25407272e+02 1.25472321e+02 1.25491280e+02 1.25488670e+02 1.25475456e+02 1.25477417e+02 1.25484253e+02 1.25464157e+02 1.25437790e+02 1.25405602e+02 1.25382408e+02 1.25357292e+02 1.25334282e+02 1.25327530e+02 1.25330765e+02 1.25329407e+02 1.25286446e+02 1.25376816e+02 1.25436859e+02 1.25412445e+02 1.25399025e+02 1.25462067e+02 1.25553810e+02 1.25415993e+02 1.25228065e+02 1.25183693e+02 1.25182167e+02 1.25183029e+02 1.25160385e+02 1.25159233e+02 1.25154053e+02 1.25395638e+02 1.25734367e+02 1.26124527e+02 1.26252838e+02 1.26069656e+02 1.25861641e+02 1.25912155e+02 1.26244789e+02 1.26538033e+02 1.26534210e+02 1.26288063e+02 1.26298637e+02 1.26325157e+02 1.26563461e+02 1.26307335e+02 1.26206169e+02 1.26013321e+02 1.26069153e+02 1.26126678e+02 1.26317589e+02 1.26466690e+02 1.26307480e+02 1.25856445e+02 1.25640938e+02 1.25483231e+02 1.25892235e+02 1.25934998e+02 1.25992599e+02 1.25974655e+02 1.26165741e+02 1.26229385e+02 1.26045448e+02 1.25920532e+02 1.25892853e+02 1.25867737e+02 1.25670319e+02 1.25522560e+02 1.25509369e+02 1.25552032e+02 1.25591316e+02 1.25526299e+02 1.25523956e+02 1.25507942e+02 1.25494217e+02 1.25454887e+02 1.25192299e+02 1.24910492e+02 1.24686440e+02 1.24654869e+02 1.24649559e+02 1.24618080e+02 1.24578659e+02 1.24696556e+02 1.24914474e+02 1.25085434e+02 1.25127052e+02 1.25110451e+02 1.25184982e+02 1.25378944e+02 1.25376846e+02 1.25319565e+02 1.25093285e+02 1.25011566e+02 1.24952271e+02 1.25123680e+02 1.25291779e+02 1.25371017e+02 1.25286911e+02 1.25309456e+02 1.25239777e+02 1.25180992e+02 1.25106346e+02 1.25223190e+02 1.25447380e+02 1.25526154e+02 1.25624016e+02 1.25605042e+02 1.25641251e+02 1.25621269e+02 1.25499298e+02 1.25397163e+02 1.25285675e+02 1.25293434e+02 1.25248611e+02 1.25263451e+02 1.25255028e+02 1.25252113e+02 1.25167198e+02 1.25146370e+02 1.25125778e+02 1.25130058e+02 1.25096207e+02 1.25068359e+02 1.24993874e+02 1.24955208e+02 1.24909431e+02 1.24919022e+02 1.24898972e+02 1.24896103e+02 1.24885559e+02 1.24869698e+02 1.24853668e+02 1.24835609e+02 1.24854271e+02 1.24869125e+02 1.24755714e+02 1.24641121e+02 1.24626060e+02 1.24663597e+02 1.24737541e+02 1.24669617e+02 1.24756104e+02 1.24695496e+02 1.24776917e+02 1.24817688e+02 1.24865112e+02 1.24827553e+02 1.24694595e+02 1.24631622e+02 1.24639534e+02 1.24711220e+02 1.24871834e+02 1.24994469e+02 1.25116196e+02 1.25201408e+02 1.25266510e+02 1.25366585e+02 1.25398430e+02 1.25429955e+02 1.25483421e+02 1.25512436e+02 1.25469193e+02 1.25433014e+02 1.25463249e+02 1.25397751e+02 1.25299896e+02 1.25200104e+02 1.25214783e+02 1.25167923e+02 1.25111382e+02 1.25105286e+02 1.25078682e+02 1.25040977e+02 1.24978737e+02 1.25010971e+02 1.25019424e+02 1.25023804e+02 1.25056816e+02 1.25067345e+02 1.25046173e+02 1.25013313e+02 1.24963234e+02 1.24955582e+02 1.24926331e+02 1.24904129e+02 1.24894936e+02 1.24894341e+02 1.24946945e+02 1.24972099e+02 1.24975983e+02 1.25022461e+02 1.25085556e+02 1.25122124e+02 1.25068085e+02 1.25063744e+02 1.25070473e+02 1.25084770e+02 1.25048157e+02 1.24999916e+02 1.25095901e+02 1.25124741e+02 1.25156898e+02 1.25067436e+02 1.25109100e+02 1.25066681e+02 1.25014114e+02 1.25041054e+02 1.25110718e+02 1.25186600e+02 1.25180458e+02 1.25252121e+02 1.25341499e+02 1.25334068e+02 1.25321304e+02 1.25282730e+02 1.25313408e+02 1.25349678e+02 1.25370499e+02 1.25356522e+02 1.25275620e+02 1.25216820e+02 1.25261375e+02 1.25218994e+02 1.25321625e+02 1.25227524e+02 1.25220100e+02 1.25105057e+02 1.25139664e+02 1.25278275e+02 1.25380981e+02 1.25416260e+02 1.25368080e+02 1.25359779e+02 1.25407898e+02 1.25459152e+02 1.25484177e+02 1.25320282e+02 1.25127930e+02 1.24913475e+02 1.24902565e+02 1.24928787e+02 1.24953636e+02 1.25004997e+02 1.25060455e+02 1.25142799e+02 1.25174232e+02 1.25204956e+02 1.25251526e+02 1.25459305e+02 1.25674538e+02 1.25802002e+02 1.25768974e+02 1.25728630e+02 1.25711563e+02 1.25633224e+02 1.25602577e+02 1.25618721e+02 1.25660858e+02 1.25719231e+02 1.25699913e+02 1.25678810e+02 1.25574982e+02 1.25565865e+02 1.25576218e+02 1.25685387e+02 1.25802963e+02 1.26021156e+02 1.26119202e+02 1.26192711e+02 1.26224823e+02 1.26191666e+02 1.26186104e+02 1.26054398e+02 1.26062355e+02 1.26054062e+02 1.26197906e+02 1.26274628e+02 1.26355675e+02 1.26421661e+02 1.26405182e+02 1.26541191e+02 1.26570892e+02 1.26916374e+02 1.27447128e+02 1.28145279e+02 1.28788361e+02 1.29315231e+02 1.30397522e+02 1.32884171e+02 1.32642258e+02 1.31749420e+02 1.29122498e+02 1.29278885e+02 1.29230865e+02 1.29177307e+02 1.29005478e+02 1.28999573e+02 1.29026245e+02 1.29068863e+02 1.31280991e+02 1.31438705e+02 1.69056183e+02 1.59809204e+02 1.72979080e+02 1.29719223e+02 1.29276611e+02 1.27990150e+02 1.25007454e+02 1.19790970e+02 1.20103920e+02 1.21175087e+02 1.25028809e+02 1.24754478e+02 1.24421921e+02 1.24689056e+02 1.21297989e+02 1.14622238e+02 1.13912781e+02 1.16666718e+02 1.23803535e+02 1.25171181e+02 1.25864716e+02 1.25813446e+02 1.25686096e+02 1.25586769e+02 1.25538292e+02 1.25475830e+02 1.25428543e+02 1.25430588e+02 1.25476440e+02 1.25527977e+02 1.25551521e+02 1.25495850e+02 1.25440193e+02 1.25411682e+02 1.25423210e+02 1.25425194e+02 1.25381859e+02 1.25414299e+02 1.25440773e+02 1.25505745e+02 1.25499809e+02 1.25464691e+02 1.25382431e+02 1.25354218e+02 1.25363289e+02 1.25420372e+02 1.25378159e+02 1.25367058e+02 1.25383499e+02 1.25414909e+02 1.25444527e+02 1.25367844e+02 1.25405884e+02 1.25370247e+02 1.25405426e+02 1.25370140e+02 1.25442833e+02 1.25453926e+02 1.25517487e+02 1.25482979e+02 1.25556480e+02 1.25586174e+02 1.25629776e+02 1.25596313e+02 1.25533386e+02 1.25464394e+02 1.25444115e+02 1.25454971e+02 1.25496948e+02 1.25494179e+02 1.25464531e+02 1.25544548e+02 1.25454666e+02 1.25302292e+02 1.25254829e+02 1.25352928e+02 1.25429047e+02 1.25350708e+02 1.25300949e+02 1.25362587e+02 1.25381279e+02 1.25537086e+02 1.25567749e+02 1.25552948e+02 1.25541710e+02 1.25631935e+02 1.25763954e+02 1.25801590e+02 1.25641548e+02 1.25595184e+02 1.25409393e+02 1.25417389e+02 1.25361732e+02 1.25402870e+02 1.25503983e+02 1.25628532e+02 1.25892174e+02 1.25599030e+02 1.25379097e+02 1.25074303e+02 1.25206978e+02 1.25285706e+02 1.25439240e+02 1.25567497e+02 1.25684807e+02 1.25689056e+02 1.25723679e+02 1.25755676e+02 1.25768784e+02 1.25759933e+02 1.25785652e+02 1.25804375e+02 1.25830032e+02 1.25819061e+02 1.25704727e+02 1.25574585e+02 1.25530952e+02 1.25504440e+02 1.25473534e+02 1.25410042e+02 1.25471397e+02 1.25625870e+02 1.25726608e+02 1.25757042e+02 1.25586395e+02 1.25441750e+02 1.25293861e+02 1.25262497e+02 1.25249123e+02 1.25245422e+02 1.25215591e+02 1.25062553e+02 1.25031982e+02 1.25004021e+02 1.25083038e+02 1.25113052e+02 1.25230988e+02 1.25263756e+02 1.25248123e+02 1.25251190e+02 1.25244263e+02 1.25231888e+02 1.25209335e+02 1.25188789e+02 1.25154846e+02 1.25111275e+02 1.25087967e+02 1.25047897e+02 1.24997246e+02 1.24943520e+02 1.24947639e+02 1.24970329e+02 1.24988472e+02 1.24992928e+02 1.24994278e+02 1.24986992e+02 1.24970322e+02 1.24912376e+02 1.24833229e+02 1.24709511e+02 1.24516335e+02 1.24091331e+02 1.23593292e+02 1.22347794e+02 1.16171127e+02 1.08621162e+02 9.05515747e+01 9.44358902e+01 1.00785248e+02 1.62908783e+02 2.43853119e+02 4.96591858e+02 4.96383575e+02 4.96196564e+02 4.95738220e+02 4.95215851e+02 4.94966370e+02 4.95158600e+02 4.95528870e+02 2.32889679e+02 1.55655365e+02 1.21807030e+02 1.21777100e+02 1.22001122e+02 1.22035706e+02 1.22407074e+02 1.22500145e+02 1.22725677e+02 1.22519173e+02 1.20332237e+02 1.58068069e+02 1.34478271e+02 1.78023178e+02 2.42304733e+02 8.71935425e+02 -142963872. 1209635328. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.44298189e+09 -2.83614106e+09 2.10932925e+06 347167488. 408023648. -2.50992640e+10 4.32594513e+02 2.02904633e+02 1.37823944e+02 1.29880203e+02 1.26819908e+02 1.25372925e+02 1.24818687e+02 1.25155914e+02 1.25673073e+02 1.70710266e+02 3.32318054e+02 264291520. 240410048. 746573568. -4.93333350e+09 -1905087488. -4.03683814e+09 526790688. 1409549312. 1239475456. 362122656. 19725514. 363274816. 882545600. 345949600. 1.29413635e+03 9.17913818e+02 1.22798120e+03 1022974528. 89997104. 2.21763302e+09 599633088. 493003616. -2.69154278e+09 908842816. 1126175744. 653645760. 138989456. 16025121. 34727108. 78697864. 1078070016. 5162442. 4260638. 4.42013491e+09 5.95786086e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 9.21718374e+09 9.21718374e+09 0. 0. -958390848. -958390848. -958390848. 0. 0. 0. 0. -2.47085133e+09 -661475520. -2.15342694e+09 4.17563418e+09 46717272. -749295040. -749295040. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1066242496. -1066242496. -1066242496. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -799920960. -799920960. -799920960. 0. 0. -251471648. -3.64697856e+09 -3.64697856e+09 -361339584. 768630272. 5.08040850e+06 1.41004346e+03 7.12824890e+02 5.05128845e+02 6.89731873e+02 1.32957251e+03 6.86505216e+09 5.75297434e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.64932890e+09 -1098469376. 1.28323230e+03 6.48427185e+02 4.77945374e+02 2.24736069e+02 1.52200043e+02 1.20839638e+02 1.20593674e+02 1.20789299e+02 1.20987068e+02 1.20872787e+02 1.20702919e+02 1.20680244e+02 1.20728294e+02 1.21158272e+02 1.21587105e+02 1.21545761e+02 1.21104942e+02 1.20635902e+02 1.20512024e+02 1.20430367e+02 1.20508705e+02 1.20638420e+02 1.21176155e+02 1.21765030e+02 1.22447868e+02 1.22932045e+02 1.23219208e+02 1.23340462e+02 1.23323151e+02 1.23164627e+02 1.23133636e+02 1.23251358e+02 1.23410797e+02 1.23573502e+02 1.23835648e+02 1.24095741e+02 1.24358139e+02 1.24484146e+02 1.24418091e+02 1.24432289e+02 1.24226891e+02 1.23941994e+02 1.23658409e+02 1.23433586e+02 1.23547447e+02 1.23627022e+02 1.23832588e+02 1.23778358e+02 1.23787643e+02 1.23732162e+02 1.23848709e+02 1.23853851e+02 1.23923691e+02 1.24024002e+02 1.23831047e+02 1.23589546e+02 1.23340683e+02 1.23546982e+02 1.23619469e+02 1.23741531e+02 1.23810326e+02 1.23884071e+02 1.23889687e+02 1.23871574e+02 1.23891800e+02 1.23994469e+02 1.24015556e+02 1.24058647e+02 1.24004318e+02 1.23898781e+02 1.23785927e+02 1.23722687e+02 1.23739952e+02 1.23710426e+02 1.23681740e+02 1.23670906e+02 1.23752396e+02 1.23855171e+02 1.23895142e+02 1.23968315e+02 1.24030029e+02 1.24280472e+02 1.24460823e+02 1.24612717e+02 1.24621696e+02 1.24618263e+02 1.24616653e+02 1.24615005e+02 1.24633949e+02 1.24552055e+02 1.24577042e+02 1.24613396e+02 1.24700165e+02 1.24558311e+02 1.24655075e+02 1.24817146e+02 1.25050041e+02 1.24948799e+02 1.24767097e+02 1.24669113e+02 1.24573364e+02 1.24585625e+02 1.24575279e+02 1.24644264e+02 1.24621788e+02 1.24556923e+02 1.23924919e+02 1.23713295e+02 1.23737953e+02 1.24206886e+02 1.24122429e+02 1.23851753e+02 1.23830727e+02 1.23900536e+02 1.23933167e+02 1.23889893e+02 1.23884880e+02 1.23926910e+02 1.23926079e+02 1.23967018e+02 1.23972572e+02 1.24003441e+02 1.24024323e+02 1.24026268e+02 1.24031578e+02 1.23938698e+02 1.23902260e+02 1.23796310e+02 1.23736137e+02 1.23653839e+02 1.23658218e+02 1.23672539e+02 1.23717316e+02 1.23723610e+02 1.23790787e+02 1.23808662e+02 1.23836937e+02 1.23874939e+02 1.23914078e+02 1.23975800e+02 1.23953995e+02 1.24072151e+02 1.24165489e+02 1.24174355e+02 1.24074013e+02 1.23966873e+02 1.23903748e+02 1.23919510e+02 1.23946747e+02 1.24034081e+02 1.24150635e+02 1.24249794e+02 1.24251282e+02 1.24235069e+02 1.24200363e+02 1.24189880e+02 1.24130211e+02 1.24071159e+02 1.24046440e+02 1.24055527e+02 1.24119942e+02 1.24170654e+02 1.24223633e+02 1.24226341e+02 1.24268013e+02 1.24327881e+02 1.24385696e+02 1.24340897e+02 1.24198097e+02 1.24147522e+02 1.24062775e+02 1.24094749e+02 1.24105339e+02 1.24214783e+02 1.24256248e+02 1.24263710e+02 1.24211540e+02 1.24252434e+02 1.24292053e+02 1.24363129e+02 1.24320976e+02 1.24264084e+02 1.24252434e+02 1.24224747e+02 1.23867172e+02 1.23438232e+02 1.22106598e+02 1.19931992e+02 1.15816391e+02 1.15749313e+02 1.17957787e+02 1.22106285e+02 1.23391754e+02 1.23692223e+02 1.23967506e+02 1.24547607e+02 1.25547600e+02 1.26308067e+02 1.69684143e+02 2.57770508e+02 2.46443787e+02 1.66852432e+02 1.66229294e+02 2.39451431e+02 4.70424530e+02 4.78946930e+02 2.45521988e+02 1.66115799e+02 1.23966187e+02 1.24210136e+02 1.24291771e+02 1.23976303e+02 1.23827072e+02 1.23987961e+02 1.24324364e+02 1.24427956e+02 1.24690086e+02 1.57743027e+02 2.36319748e+02 5.04183594e+02 5.02631348e+02 5.01422821e+02 2.49204803e+02 1.75131882e+02 1.34396835e+02 1.38690460e+02 1.34285339e+02 1.30656723e+02 1.27888824e+02 1.26646584e+02 1.25891617e+02 1.25503693e+02 1.25222763e+02 1.25028839e+02 1.24722588e+02 1.24374832e+02 1.24071266e+02 1.24012894e+02 1.23869370e+02 1.23876686e+02 1.23738991e+02 1.23825714e+02 1.23723778e+02 1.23720154e+02 1.23628540e+02 1.23670921e+02 1.23689934e+02 1.23743546e+02 1.23834808e+02 1.23930763e+02 1.24003540e+02 1.23969391e+02 1.23927750e+02 1.23881340e+02 1.23905685e+02 1.23936195e+02 1.23985649e+02 1.23990089e+02 1.23944809e+02 1.23922401e+02 1.23923485e+02 1.23897316e+02 1.23905670e+02 1.23911537e+02 1.23990486e+02 1.24026054e+02 1.24098022e+02 1.24168411e+02 1.24196045e+02 1.24187698e+02 1.24120117e+02 1.24053131e+02 1.24008560e+02 1.23972092e+02 1.23977119e+02 1.23891167e+02 1.23863083e+02 1.23765968e+02 1.23776390e+02 1.23768074e+02 1.23747253e+02 1.23715408e+02 1.23681892e+02 1.23644020e+02 1.23614159e+02 1.23539513e+02 1.23562920e+02 1.23605118e+02 1.23660286e+02 1.23688278e+02 1.23663254e+02 1.23659760e+02 1.23596245e+02 1.23601685e+02 1.23750816e+02 1.23917053e+02 1.24028603e+02 1.24024788e+02 1.24041664e+02 1.24099068e+02 1.24125092e+02 1.24199928e+02 1.24089508e+02 1.24069061e+02 1.24026649e+02 1.24226501e+02 1.24327652e+02 1.24380829e+02 1.24382217e+02 1.24442986e+02 1.24453339e+02 1.24458092e+02 1.24456535e+02 1.24439438e+02 1.24456444e+02 1.24504128e+02 1.24598915e+02 1.24675323e+02 1.24746704e+02 1.24773979e+02 1.24804596e+02 1.24836723e+02 1.24949364e+02 1.25094101e+02 1.25188507e+02 1.25200935e+02 1.25143944e+02 1.25085968e+02 1.24932236e+02 1.24681038e+02 1.24767830e+02 1.24746918e+02 1.24762611e+02 1.24547394e+02 1.24501854e+02 1.24510269e+02 1.24572777e+02 1.24612114e+02 1.24636269e+02 1.24749649e+02 1.24778282e+02 1.24706184e+02 1.24596382e+02 1.24643433e+02 1.24739342e+02 1.24750977e+02 1.24662712e+02 1.24614731e+02 1.24593575e+02 1.24740051e+02 1.24875893e+02 1.24833199e+02 1.24722870e+02 1.24737297e+02 1.24848953e+02 1.24853508e+02 1.24714211e+02 1.24618729e+02 1.24603020e+02 1.24607468e+02 1.24592247e+02 1.24542549e+02 1.24503204e+02 1.24452316e+02 1.24569244e+02 1.24615326e+02 1.24647133e+02 1.24519630e+02 1.24443130e+02 1.24412674e+02 1.24432777e+02 1.24563553e+02 1.24599846e+02 1.24591637e+02 1.24543793e+02 1.24541786e+02 1.24555588e+02 1.24573662e+02 1.24582153e+02 1.24590912e+02 1.24574844e+02 1.24573486e+02 1.24669693e+02 1.24765724e+02 1.24885605e+02 1.24877953e+02 1.24828896e+02 1.24975624e+02 1.24903503e+02 1.24851723e+02 1.24656212e+02 1.24888962e+02 1.25090332e+02 1.25289848e+02 1.25299255e+02 1.25278030e+02 1.25286461e+02 1.25274117e+02 1.25263588e+02 1.25249954e+02 1.25030540e+02 1.24825195e+02 1.24843529e+02 1.24989105e+02 1.24923607e+02 1.24720779e+02 1.24569885e+02 1.24515114e+02 1.24482292e+02 1.24505791e+02 1.24573349e+02 1.24611015e+02 1.24667191e+02 1.24681877e+02 1.24715141e+02 1.24496040e+02 1.24403603e+02 1.24221909e+02 1.24296135e+02 1.24235794e+02 1.24263115e+02 1.24230751e+02 1.24262314e+02 1.24232964e+02 1.24211845e+02 1.24231644e+02 1.24322884e+02 1.24351730e+02 1.24305405e+02 1.24290863e+02 1.24421234e+02 1.24409149e+02 1.24353485e+02 1.24384766e+02 1.24106995e+02 1.24008911e+02 1.23996567e+02 1.24334351e+02 1.24193535e+02 1.23946480e+02 1.23840477e+02 1.23995003e+02 1.24240860e+02 1.24370064e+02 1.24475037e+02 1.24483650e+02 1.24428574e+02 1.24418922e+02 1.24403519e+02 1.24379219e+02 1.24313759e+02 1.24231941e+02 1.24228973e+02 1.24445702e+02 1.24486359e+02 1.24507538e+02 1.24365410e+02 1.24366554e+02 1.24370422e+02 1.24388290e+02 1.24382660e+02 1.24398254e+02 1.24597557e+02 1.24621567e+02 1.24604919e+02 1.24435760e+02 1.24419830e+02 1.24407310e+02 1.24360542e+02 1.24305458e+02 1.24251862e+02 1.24288628e+02 1.24347427e+02 1.24393127e+02 1.24372940e+02 1.24368660e+02 1.24378220e+02 1.24365089e+02 1.24309143e+02 1.24279297e+02 1.24247498e+02 1.24320862e+02 1.24219154e+02 1.24274773e+02 1.24202377e+02 1.24306335e+02 1.24202110e+02 1.24411774e+02 1.24616829e+02 1.24615440e+02 1.24373161e+02 1.24179703e+02 1.24225357e+02 1.24278107e+02 1.24320770e+02 1.24266731e+02 1.24271690e+02 1.24305710e+02 1.24399384e+02 1.24354698e+02 1.24279236e+02 1.24206978e+02 1.24183723e+02 1.24165405e+02 1.24148483e+02 1.24157494e+02 1.24191086e+02 1.24215477e+02 1.24181816e+02 1.24190025e+02 1.24196075e+02 1.24238129e+02 1.24197205e+02 1.24237732e+02 1.24256157e+02 1.24301399e+02 1.24318184e+02 1.24341408e+02 1.24310127e+02 1.24277580e+02 1.24274452e+02 1.24288368e+02 1.24302933e+02 1.24272499e+02 1.24289413e+02 1.24263657e+02 1.24234665e+02 1.24184189e+02 1.24116310e+02 1.24119415e+02 1.24125748e+02 1.24149300e+02 1.24116066e+02 1.24081505e+02 1.24096870e+02 1.24197952e+02 1.24277779e+02 1.24296379e+02 1.24322998e+02 1.24289520e+02 1.24308716e+02 1.24224548e+02 1.24078941e+02 1.23927933e+02 1.23831329e+02 1.23862389e+02 1.23859619e+02 1.23863785e+02 1.23784111e+02 1.23659332e+02 1.23746956e+02 1.23824852e+02 1.23953690e+02 1.23923050e+02 1.23904022e+02 1.24041191e+02 1.24167328e+02 1.24317467e+02 1.24330765e+02 1.24386284e+02 1.24359665e+02 1.24383369e+02 1.24383713e+02 1.24477081e+02 1.24448517e+02 1.24438248e+02 1.24454247e+02 1.24542099e+02 1.24542976e+02 1.24541580e+02 1.24469391e+02 1.24402107e+02 1.24378494e+02 1.24355110e+02 1.24340446e+02 1.24322220e+02 1.24290764e+02 1.24376083e+02 1.24349884e+02 1.24370880e+02 1.24299881e+02 1.24143501e+02 1.24070763e+02 1.24030449e+02 1.24188538e+02 1.24262993e+02 1.24346138e+02 1.24375061e+02 1.24339333e+02 1.24283234e+02 1.24066673e+02 1.23895668e+02 1.23782005e+02 1.23832718e+02 1.23920746e+02 1.23988922e+02 1.24023590e+02 1.23996918e+02 1.23964737e+02 1.23969536e+02 1.23987015e+02 1.24008652e+02 1.24024643e+02 1.24043869e+02 1.23989418e+02 1.23977859e+02 1.23951591e+02 1.23963463e+02 1.23986282e+02 1.24181046e+02 1.24420242e+02 1.24567711e+02 1.24627022e+02 1.24678040e+02 1.24852150e+02 1.25141800e+02 1.25508308e+02 1.25954918e+02 1.26388748e+02 1.26896736e+02 1.27239754e+02 1.27541496e+02 1.27913139e+02 1.28829361e+02 1.31379959e+02 1.33056671e+02 1.39128448e+02 1.77387207e+02 2.68671722e+02 5.06964630e+02 5.08575989e+02 5.09929382e+02 2.58028015e+02 1.72040451e+02 1.28187927e+02 1.27227074e+02 1.27152489e+02 1.26925766e+02 1.26588135e+02 1.26542953e+02 1.26541756e+02 1.26341019e+02 1.59952530e+02 2.22842453e+02 4.46549622e+02 4.49440796e+02 2.57636322e+02 1.69903992e+02 1.24342201e+02 1.22348961e+02 1.21855354e+02 1.22512871e+02 1.21580200e+02 1.21732033e+02 1.21765495e+02 1.21738777e+02 1.21344589e+02 1.13519051e+02 1.10464920e+02 1.10510330e+02 1.16889763e+02 1.20567642e+02 1.22109352e+02 1.23365059e+02 1.24341042e+02 1.24872940e+02 1.25081764e+02 1.25090271e+02 1.25038353e+02 1.24979721e+02 1.25007843e+02 1.25080772e+02 1.25156792e+02 1.25153244e+02 1.25145630e+02 1.25155228e+02 1.25172401e+02 1.25190849e+02 1.25191948e+02 1.25230499e+02 1.25186218e+02 1.25174744e+02 1.25006493e+02 1.24880157e+02 1.24742516e+02 1.24714844e+02 1.24713142e+02 1.24676819e+02 1.24674309e+02 1.24690666e+02 1.24719490e+02 1.24693039e+02 1.24646568e+02 1.24600677e+02 1.24666214e+02 1.24648605e+02 1.24495468e+02 1.24192070e+02 1.23977295e+02 1.24023628e+02 1.24185455e+02 1.24458275e+02 1.24524391e+02 1.24553131e+02 1.24452415e+02 1.24478355e+02 1.24479935e+02 1.24626663e+02 1.24766045e+02 1.24913666e+02 1.24873222e+02 1.24831123e+02 1.24800377e+02 1.24780144e+02 1.24812691e+02 1.24759026e+02 1.24758842e+02 1.24701118e+02 1.24755829e+02 1.24766937e+02 1.24797623e+02 1.24781693e+02 1.24794350e+02 1.24586525e+02 1.24543663e+02 1.24536827e+02 1.24654404e+02 1.24619621e+02 1.24532127e+02 1.24520340e+02 1.24558632e+02 1.24578773e+02 1.24579552e+02 1.24538292e+02 1.24530151e+02 1.24501083e+02 1.24468597e+02 1.24477020e+02 1.24412048e+02 1.24458382e+02 1.24560753e+02 1.24567749e+02 1.24513298e+02 1.24518593e+02 1.24506187e+02 1.24450615e+02 1.24355911e+02 1.24407074e+02 1.24446892e+02 1.24564011e+02 1.24568527e+02 1.24598137e+02 1.24563858e+02 1.24548416e+02 1.24515709e+02 1.24589828e+02 1.24585983e+02 1.24599426e+02 1.24549866e+02 1.24682060e+02 1.24776352e+02 1.24859779e+02 1.24856956e+02 1.24949081e+02 1.24965767e+02 1.25011017e+02 1.25001587e+02 1.25038857e+02 1.25044716e+02 1.24904175e+02 1.24768555e+02 1.24698502e+02 1.24846123e+02 1.24956421e+02 1.24982147e+02 1.24784355e+02 1.24643318e+02 1.24522186e+02 1.24553398e+02 1.24548119e+02 1.24576706e+02 1.24562027e+02 1.24286484e+02 1.24131821e+02 1.24164215e+02 1.24392418e+02 1.24541786e+02 1.24701080e+02 1.24738792e+02 1.24712357e+02 1.24625488e+02 1.24568031e+02 1.24552605e+02 1.24593048e+02 1.24583832e+02 1.24568512e+02 1.24593895e+02 1.24642456e+02 1.24669243e+02 1.24687508e+02 1.24695740e+02 1.24741776e+02 1.24789688e+02 1.24854576e+02 1.24923683e+02 1.25003616e+02 1.25095589e+02 1.25157951e+02 1.25145973e+02 1.25048065e+02 1.24899635e+02 1.24758026e+02 1.24623901e+02 1.24539490e+02 1.24469185e+02 1.24454636e+02 1.24407242e+02 1.24428856e+02 1.24479263e+02 1.24568771e+02 1.24568512e+02 1.24445641e+02 1.24281342e+02 1.24061142e+02 1.23944405e+02 1.23889076e+02 1.23892868e+02 1.23894615e+02 1.23983276e+02 1.24076973e+02 1.24349754e+02 1.24551399e+02 1.24746147e+02 1.24825554e+02 1.24900841e+02 1.24776077e+02 1.24543831e+02 1.24468849e+02 1.24522789e+02 1.24494377e+02 1.24201073e+02 1.23638481e+02 1.22547791e+02 1.12800133e+02 1.45879501e+02 1.97506470e+02 5.56191895e+02 9.70185303e+02 72630392. 583192320. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 355357568. 355357568. 355357568. 0. 0. -6.32026500e+05 2.22179230e+02 1.47516403e+02 1.48560135e+02 1.86500198e+02 2.69096649e+02 2.51654221e+02 3.03685516e+02 3.78809082e+02 314360064. -2.76087142e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -882365120. -882365120. -882365120. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -958390848. -958390848. -958390848. 0. 0. 0. 0. -2.47085133e+09 -661475520. -2.15342694e+09 4.17563418e+09 4.15402598e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -253202832. -85823520. 969438. 383584832. 555636288. -744691200. 101341472. -2.05520384e+10 102227232. 33255698. 2.45690163e+09 -397671744. 2.46691098e+09 2.46691098e+09 0. 0. 0. 0. 0. 0. 0. -799920960. -799920960. -799920960. 0. 0. -251471648. -3.64697856e+09 -3.64697856e+09 -361339584. 768630272. 5.08040850e+06 14455523. 272925824. 30817074. -1159357440. 816650048. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.17908569e+03 7.38662292e+02 2.27144684e+02 1.50750854e+02 1.20147522e+02 1.19938332e+02 1.20457268e+02 1.21174454e+02 1.21621391e+02 1.22032646e+02 1.22835274e+02 1.23803513e+02 1.24818466e+02 1.25709778e+02 1.25976433e+02 1.57553436e+02 2.31520782e+02 2.45996323e+02 1.64126129e+02 1.22222702e+02 1.23618721e+02 1.24109497e+02 1.24245827e+02 1.23948074e+02 1.23715385e+02 1.23395508e+02 1.23104500e+02 1.22608681e+02 1.21938904e+02 1.21610107e+02 1.21487968e+02 1.21577385e+02 1.21886307e+02 1.22116127e+02 1.22433838e+02 1.22770660e+02 1.23684578e+02 1.55975510e+02 2.33021729e+02 5.03656433e+02 5.02972931e+02 5.02557617e+02 2.54163498e+02 1.68143738e+02 1.24217789e+02 1.23956665e+02 1.24370483e+02 1.24466652e+02 1.24475174e+02 1.24262749e+02 1.24144371e+02 1.23928986e+02 1.23687866e+02 1.23392738e+02 1.23003494e+02 1.22705147e+02 1.22443199e+02 1.22279358e+02 1.22096985e+02 1.22057144e+02 1.21988174e+02 1.21968185e+02 1.21919205e+02 1.21940331e+02 1.21929817e+02 1.21986549e+02 1.22118187e+02 1.22227058e+02 1.22270432e+02 1.22198845e+02 1.22086990e+02 1.21913345e+02 1.21778831e+02 1.21729500e+02 1.21732529e+02 1.21762695e+02 1.21835091e+02 1.21841179e+02 1.21792709e+02 1.21718102e+02 1.21693054e+02 1.21707458e+02 1.21674080e+02 1.21594254e+02 1.21522102e+02 1.21456062e+02 1.21419617e+02 1.21314339e+02 1.21232376e+02 1.21170280e+02 1.21131645e+02 1.21132057e+02 1.21156921e+02 1.21219154e+02 1.21254929e+02 1.21226891e+02 1.21230843e+02 1.21262718e+02 1.21323090e+02 1.21343628e+02 1.21308594e+02 1.21272049e+02 1.21205948e+02 1.21148323e+02 1.21139030e+02 1.21347389e+02 1.21569313e+02 1.21711075e+02 1.21191681e+02 1.20974564e+02 1.20878075e+02 1.21348579e+02 1.21328659e+02 1.21161522e+02 1.21144196e+02 1.21190865e+02 1.21312729e+02 1.21412796e+02 1.21528404e+02 1.21634583e+02 1.21650833e+02 1.21583580e+02 1.21404915e+02 1.21326897e+02 1.21284805e+02 1.21307190e+02 1.21306870e+02 1.21245827e+02 1.21159317e+02 1.21067528e+02 1.21051720e+02 1.21035492e+02 1.21009819e+02 1.21041573e+02 1.21067558e+02 1.21156532e+02 1.21231850e+02 1.21371643e+02 1.21460396e+02 1.21533897e+02 1.21570999e+02 1.21574478e+02 1.21359909e+02 1.21371109e+02 1.21362167e+02 1.21477470e+02 1.21421356e+02 1.21425743e+02 1.21324799e+02 1.21211945e+02 1.21075302e+02 1.21003365e+02 1.20939621e+02 1.20959595e+02 1.21049339e+02 1.21141701e+02 1.21158844e+02 1.21164742e+02 1.21153946e+02 1.21199043e+02 1.21206848e+02 1.21223267e+02 1.21229820e+02 1.21233795e+02 1.21227600e+02 1.21231705e+02 1.21277596e+02 1.21362030e+02 1.21344650e+02 1.21283363e+02 1.21231369e+02 1.21287193e+02 1.21419273e+02 1.21452553e+02 1.21452263e+02 1.21398849e+02 1.21317879e+02 1.21269958e+02 1.21295464e+02 1.21368286e+02 1.21441643e+02 1.21475845e+02 1.21469765e+02 1.21488029e+02 1.21508568e+02 1.21530579e+02 1.21511696e+02 1.21467171e+02 1.21400902e+02 1.21371140e+02 1.21278114e+02 1.21102837e+02 1.20777008e+02 1.20316292e+02 1.19728218e+02 1.18450630e+02 1.15326279e+02 1.12315865e+02 1.13932701e+02 1.17371727e+02 1.20956253e+02 1.21118927e+02 1.20984955e+02 1.21153862e+02 1.22222778e+02 1.22996330e+02 1.23835510e+02 1.25983513e+02 1.29525391e+02 1.81869446e+02 2.85965942e+02 8.76648132e+02 1.73332910e+03 1.12929736e+03 5.66409973e+02 4.28458832e+02 2.33731766e+02 1.60317841e+02 1.20067474e+02 1.20829926e+02 1.21117630e+02 1.21450111e+02 1.21610657e+02 1.21810661e+02 1.21775177e+02 1.21467697e+02 1.28238281e+02 1.69501129e+02 2.68734131e+02 5.46004944e+02 5.22933228e+02 5.12179565e+02 5.05526062e+02 5.01918732e+02 4.99670898e+02 4.97863342e+02 2.78298065e+02 1.89325409e+02 1.41570328e+02 1.38773956e+02 1.36731613e+02 1.34111008e+02 1.32427307e+02 1.32027008e+02 1.31568970e+02 1.30889648e+02 1.30102829e+02 1.30595505e+02 1.31258469e+02 1.31380356e+02 1.33025650e+02 1.36838867e+02 1.44492966e+02 1.58315781e+02 1.66052383e+02 1.68308578e+02 1.64822586e+02 1.58110321e+02 1.54294159e+02 1.39218445e+02 1.37532623e+02 1.30975891e+02 1.31288391e+02 1.29686035e+02 1.30231277e+02 1.29218842e+02 1.28337921e+02 1.27038315e+02 1.26521141e+02 1.26299347e+02 1.26560455e+02 1.27075966e+02 1.28309402e+02 1.29739426e+02 1.29924057e+02 1.28280197e+02 1.27377747e+02 1.26433105e+02 1.25919106e+02 1.25417137e+02 1.25121880e+02 1.24909874e+02 1.24675560e+02 1.24345482e+02 1.24041466e+02 1.23910469e+02 1.23735100e+02 1.23484917e+02 1.23154625e+02 1.22969208e+02 1.22738419e+02 1.22537689e+02 1.22407150e+02 1.22388908e+02 1.22251266e+02 1.21955109e+02 1.21900742e+02 1.22088249e+02 1.22198967e+02 1.22081161e+02 1.21834755e+02 1.21710442e+02 1.21688179e+02 1.21801880e+02 1.21919968e+02 1.22020409e+02 1.22018143e+02 1.21992348e+02 1.21967644e+02 1.21952255e+02 1.22066673e+02 1.22122208e+02 1.22084190e+02 1.21990685e+02 1.22004059e+02 1.22023659e+02 1.22043503e+02 1.22072273e+02 1.22092316e+02 1.22256142e+02 1.22378960e+02 1.22460609e+02 1.22444237e+02 1.22454262e+02 1.22479828e+02 1.22503036e+02 1.22513268e+02 1.22537048e+02 1.22498436e+02 1.22423203e+02 1.22336784e+02 1.22047112e+02 1.22108971e+02 1.21973648e+02 1.22003777e+02 1.21785278e+02 1.21794868e+02 1.21860954e+02 1.21818718e+02 1.21784134e+02 1.21714035e+02 1.21767540e+02 1.21828995e+02 1.21885605e+02 1.21853218e+02 1.21923187e+02 1.21936203e+02 1.21963058e+02 1.21878227e+02 1.21878036e+02 1.21905846e+02 1.21934509e+02 1.21941498e+02 1.21925896e+02 1.21993576e+02 1.22005959e+02 1.22022720e+02 1.21855133e+02 1.21782326e+02 1.21687469e+02 1.21683037e+02 1.21678139e+02 1.21670723e+02 1.21646019e+02 1.21750114e+02 1.21869461e+02 1.21957428e+02 1.21923897e+02 1.21721550e+02 1.21614868e+02 1.21604263e+02 1.21645988e+02 1.21657417e+02 1.21757652e+02 1.21900810e+02 1.22004555e+02 1.21881340e+02 1.21773270e+02 1.21677551e+02 1.21682945e+02 1.21670464e+02 1.21662170e+02 1.21421532e+02 1.21205582e+02 1.21127785e+02 1.21248878e+02 1.21632439e+02 1.21807442e+02 1.21706070e+02 1.21407608e+02 1.21276108e+02 1.21370041e+02 1.21651596e+02 1.21546249e+02 1.21395378e+02 1.21172897e+02 1.21460426e+02 1.21615715e+02 1.21770920e+02 1.21646042e+02 1.21469856e+02 1.21336121e+02 1.21402184e+02 1.21659546e+02 1.22088104e+02 1.22267120e+02 1.22424980e+02 1.22210403e+02 1.22248695e+02 1.22254761e+02 1.22225555e+02 1.22018135e+02 1.21804718e+02 1.21858307e+02 1.21794891e+02 1.21793144e+02 1.21782898e+02 1.21766968e+02 1.21788445e+02 1.21732635e+02 1.21831467e+02 1.21783546e+02 1.21704231e+02 1.21722824e+02 1.21741219e+02 1.21837074e+02 1.21881920e+02 1.21991135e+02 1.22118065e+02 1.22249916e+02 1.22305412e+02 1.22328529e+02 1.22361595e+02 1.22361702e+02 1.22115669e+02 1.21816704e+02 1.21471878e+02 1.21314728e+02 1.21338409e+02 1.21522087e+02 1.21601768e+02 1.21828194e+02 1.22031578e+02 1.22289879e+02 1.22159149e+02 1.22000458e+02 1.21856941e+02 1.21786850e+02 1.21757660e+02 1.21698761e+02 1.21736389e+02 1.21772514e+02 1.21736694e+02 1.21646515e+02 1.21465050e+02 1.21425545e+02 1.21332802e+02 1.21250137e+02 1.21146759e+02 1.21058342e+02 1.20976593e+02 1.21015053e+02 1.21026505e+02 1.21045464e+02 1.21015190e+02 1.21039108e+02 1.21003342e+02 1.21013359e+02 1.21032494e+02 1.21247986e+02 1.21407516e+02 1.21565582e+02 1.21539757e+02 1.21574905e+02 1.21615089e+02 1.21688644e+02 1.21691895e+02 1.21757690e+02 1.21734940e+02 1.21795326e+02 1.21784706e+02 1.21854462e+02 1.21852341e+02 1.21847008e+02 1.21838150e+02 1.21760933e+02 1.21699211e+02 1.21790016e+02 1.21833832e+02 1.21814850e+02 1.21762405e+02 1.21742256e+02 1.21774384e+02 1.21720695e+02 1.21762871e+02 1.21761436e+02 1.21749298e+02 1.21706192e+02 1.21718887e+02 1.21814438e+02 1.21851570e+02 1.21768936e+02 1.21689819e+02 1.21660355e+02 1.21684166e+02 1.21657898e+02 1.21581772e+02 1.21348053e+02 1.21162529e+02 1.21025589e+02 1.21136101e+02 1.21301140e+02 1.21460556e+02 1.21553947e+02 1.21553764e+02 1.21551300e+02 1.21585777e+02 1.21598198e+02 1.21665817e+02 1.21638962e+02 1.21632500e+02 1.21587807e+02 1.21622993e+02 1.21652878e+02 1.21629356e+02 1.21592728e+02 1.21548294e+02 1.21531349e+02 1.21552406e+02 1.21577988e+02 1.21599495e+02 1.21593712e+02 1.21587479e+02 1.21621063e+02 1.21620491e+02 1.21621979e+02 1.21565804e+02 1.21471245e+02 1.21293716e+02 1.21129822e+02 1.21059616e+02 1.21054260e+02 1.21094734e+02 1.21176743e+02 1.21194542e+02 1.21185509e+02 1.21124023e+02 1.21131866e+02 1.21135788e+02 1.21212227e+02 1.21176720e+02 1.21132500e+02 1.20960495e+02 1.20909164e+02 1.20873810e+02 1.20996429e+02 1.21077194e+02 1.21202393e+02 1.21161438e+02 1.21092911e+02 1.21055695e+02 1.21055038e+02 1.21296761e+02 1.21436966e+02 1.21636063e+02 1.21607155e+02 1.21725304e+02 1.21863571e+02 1.21979210e+02 1.22120293e+02 1.22291061e+02 1.22412788e+02 1.22484680e+02 1.22512764e+02 1.22616432e+02 1.22766983e+02 1.22997986e+02 1.23213676e+02 1.23761452e+02 1.24084908e+02 1.24478065e+02 1.24260933e+02 1.24141418e+02 1.23915169e+02 1.23816452e+02 1.23784546e+02 1.23797386e+02 1.23754372e+02 1.23921135e+02 1.24122269e+02 1.24353004e+02 1.24403221e+02 1.24414383e+02 1.24595268e+02 1.24702499e+02 1.24871635e+02 1.24835480e+02 1.24916161e+02 1.24964561e+02 1.24972275e+02 1.24861603e+02 1.24832336e+02 1.24922501e+02 1.25047684e+02 1.25125954e+02 1.25081200e+02 1.25191597e+02 1.25605469e+02 1.25782951e+02 1.25993881e+02 1.25789764e+02 1.26147530e+02 1.26593620e+02 1.27586525e+02 1.30108810e+02 1.64374405e+02 2.43913132e+02 4.97911072e+02 4.99960327e+02 5.01804840e+02 5.04376190e+02 5.07278534e+02 5.10304474e+02 5.12784973e+02 5.15822571e+02 2.57797638e+02 1.69560410e+02 1.25068733e+02 1.24033066e+02 1.24421967e+02 1.24786942e+02 1.24523384e+02 1.24127106e+02 1.23942993e+02 1.23240936e+02 1.22632668e+02 1.52704361e+02 2.25098145e+02 4.84910919e+02 2.35551346e+02 1.98717026e+02 2.10352310e+02 2.50854767e+02 1.68267090e+02 1.23795349e+02 1.07052170e+02 1.07313721e+02 1.11866570e+02 1.20144478e+02 1.19932899e+02 1.19592865e+02 1.17241547e+02 1.17245010e+02 1.57431168e+02 1.45707428e+02 1.47923630e+02 1.18559982e+02 1.19096054e+02 1.20164085e+02 1.21009659e+02 1.21641403e+02 1.21902870e+02 1.21973038e+02 1.22049957e+02 1.22066216e+02 1.22088005e+02 1.22109261e+02 1.22094719e+02 1.22078087e+02 1.22076103e+02 1.22082657e+02 1.22066566e+02 1.22018044e+02 1.22074501e+02 1.22209564e+02 1.22346519e+02 1.22439171e+02 1.22470955e+02 1.22516907e+02 1.22515831e+02 1.22528450e+02 1.22523567e+02 1.22543381e+02 1.22544189e+02 1.22551483e+02 1.22543282e+02 1.22551262e+02 1.22595520e+02 1.22625710e+02 1.22608925e+02 1.22528267e+02 1.22494705e+02 1.22574135e+02 1.22588654e+02 1.22602242e+02 1.22556412e+02 1.22615189e+02 1.22586830e+02 1.22607498e+02 1.22524902e+02 1.22572159e+02 1.22332596e+02 1.22135918e+02 1.21906807e+02 1.21981819e+02 1.22023804e+02 1.22002190e+02 1.22019096e+02 1.21994522e+02 1.21918343e+02 1.21903313e+02 1.21914444e+02 1.21960175e+02 1.21948166e+02 1.21955559e+02 1.21896523e+02 1.21891388e+02 1.21934563e+02 1.22010605e+02 1.22028198e+02 1.21979088e+02 1.21941978e+02 1.21915642e+02 1.21900375e+02 1.21919052e+02 1.21959251e+02 1.22013191e+02 1.22015007e+02 1.21957069e+02 1.22033806e+02 1.22046402e+02 1.22038116e+02 1.21965782e+02 1.21879227e+02 1.21839348e+02 1.21941414e+02 1.21937073e+02 1.21928596e+02 1.21799713e+02 1.21789764e+02 1.21831856e+02 1.21916252e+02 1.22070496e+02 1.22048424e+02 1.21996407e+02 1.22064812e+02 1.22134712e+02 1.22206917e+02 1.22304573e+02 1.22215126e+02 1.22203087e+02 1.22065941e+02 1.22132439e+02 1.22098724e+02 1.22211449e+02 1.22096344e+02 1.21988899e+02 1.21846230e+02 1.21838936e+02 1.21830505e+02 1.21808037e+02 1.21759865e+02 1.21759781e+02 1.21725449e+02 1.21754242e+02 1.21749672e+02 1.21754738e+02 1.21675438e+02 1.21580078e+02 1.21552979e+02 1.21742691e+02 1.21873634e+02 1.21978798e+02 1.21827026e+02 1.21846313e+02 1.21861244e+02 1.21973396e+02 1.21972481e+02 1.22004242e+02 1.22016159e+02 1.22027946e+02 1.21997124e+02 1.21991882e+02 1.22046738e+02 1.21985161e+02 1.22014771e+02 1.21797134e+02 1.21874512e+02 1.21812553e+02 1.22230797e+02 1.22240623e+02 1.22315704e+02 1.22376808e+02 1.22494720e+02 1.22601936e+02 1.22761375e+02 1.22930862e+02 1.23138779e+02 1.23289108e+02 1.23437080e+02 1.23587936e+02 1.23759636e+02 1.23867653e+02 1.23991478e+02 1.24159248e+02 1.25661026e+02 1.30578476e+02 1.40792816e+02 1.84050369e+02 2.72066650e+02 5.01261078e+02 5.01107880e+02 2.52847656e+02 1.68057953e+02 1.24587708e+02 1.24738388e+02 1.24782234e+02 1.24680855e+02 1.24490417e+02 1.24068764e+02 1.23837311e+02 1.23659836e+02 1.23797081e+02 1.23895355e+02 1.24133919e+02 1.24326180e+02 1.24554611e+02 1.24686920e+02 1.25550636e+02 1.26490540e+02 1.28243683e+02 1.25009789e+02 1.53902008e+02 1.61419525e+02 1.97700150e+02 1.47104614e+02 1.38966003e+02 1.32516205e+02 1.26678520e+02 1.24999954e+02 1.24224686e+02 1.23674423e+02 1.23289536e+02 1.23007111e+02 1.22962234e+02 1.22915184e+02 1.22323891e+02 1.14054649e+02 1.53001816e+02 2.41412994e+02 1.76121936e+03 583192320. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 355357568. 355357568. 355357568. 0. 0. -9.12167422e+04 8.33950012e+02 5.87602966e+02 6.73426819e+02 9.57757996e+02 1.94059717e+03 1.51316150e+03 1.04224231e+03 1.35594202e+03 314360064. -2.76087142e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.21309696e+10 1.21309696e+10 1.21309696e+10 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -958390848. -958390848. -958390848. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.71962342e+09 -3.71962342e+09 -3.71962342e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. -253202832. -85823520. 969438. 383584832. 555636288. -744691200. 101341472. -2.05520384e+10 1.12508826e+03 8.01314880e+02 1.16255554e+03 1.09148767e+03 1.11804749e+03 1.11804749e+03 34345516. 1131874432. 1131874432. 666889920. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.17908569e+03 7.38662292e+02 4.85952332e+02 4.76121155e+02 4.78815460e+02 2.42142426e+02 1.61461639e+02 1.21520149e+02 1.21404427e+02 1.21368057e+02 1.21678085e+02 1.21796791e+02 1.55705933e+02 2.33497849e+02 5.09879822e+02 6.95185486e+02 1.34128894e+03 1.32078918e+03 6.81414551e+02 4.81856506e+02 4.93494385e+02 4.95818298e+02 4.97266388e+02 4.95784180e+02 4.95132660e+02 4.92698669e+02 2.39414993e+02 1.58307938e+02 1.18949326e+02 1.19418266e+02 1.20002510e+02 1.20286949e+02 1.20562233e+02 1.20508194e+02 1.53156235e+02 2.27257828e+02 4.87640350e+02 6.71970337e+02 1.33156104e+03 -117706112. 2.23975772e+10 270813152. 1.40742554e+03 7.12169922e+02 4.94788910e+02 4.96005615e+02 4.97399170e+02 4.97448700e+02 4.95852570e+02 4.95965973e+02 4.94964050e+02 2.41678162e+02 1.59777039e+02 1.19634048e+02 1.19295586e+02 1.18851173e+02 1.18468147e+02 1.18196785e+02 1.18014702e+02 1.17785683e+02 1.17657272e+02 1.17577049e+02 1.17586685e+02 1.17661560e+02 1.17746185e+02 1.17846748e+02 1.17891396e+02 1.17882927e+02 1.17779381e+02 1.17598785e+02 1.17446762e+02 1.17337158e+02 1.17286766e+02 1.17242165e+02 1.17188614e+02 1.17166298e+02 1.17182899e+02 1.17240517e+02 1.17224823e+02 1.17218201e+02 1.17183052e+02 1.17119202e+02 1.17019005e+02 1.16897316e+02 1.16881760e+02 1.16833626e+02 1.16620056e+02 1.16432259e+02 1.16171204e+02 1.16349129e+02 1.16379959e+02 1.16497215e+02 1.16307739e+02 1.16254684e+02 1.16224297e+02 1.16326874e+02 1.16317772e+02 1.16272743e+02 1.16160965e+02 1.16202988e+02 1.16419991e+02 1.16680580e+02 1.16867584e+02 1.16843361e+02 1.16742111e+02 1.16687775e+02 1.16739876e+02 1.16781464e+02 1.16822128e+02 1.17000130e+02 1.17279327e+02 1.17410019e+02 1.17261932e+02 1.17046310e+02 1.16982399e+02 1.16931198e+02 1.16947701e+02 1.17100983e+02 1.17121628e+02 1.17023621e+02 1.16928627e+02 1.16835503e+02 1.16778854e+02 1.16783188e+02 1.16811394e+02 1.16877495e+02 1.16935509e+02 1.16995178e+02 1.17091133e+02 1.17149033e+02 1.17232178e+02 1.17246078e+02 1.17180855e+02 1.17190910e+02 1.17128937e+02 1.17122330e+02 1.17009216e+02 1.16933357e+02 1.16869537e+02 1.16810005e+02 1.16712875e+02 1.16635002e+02 1.16504303e+02 1.16445854e+02 1.16414749e+02 1.16517288e+02 1.16667625e+02 1.16736794e+02 1.16712540e+02 1.16724884e+02 1.16809685e+02 1.16868324e+02 1.16852379e+02 1.16816170e+02 1.16803749e+02 1.16780853e+02 1.16787193e+02 1.16792809e+02 1.16815880e+02 1.16845917e+02 1.16885536e+02 1.16899666e+02 1.16899002e+02 1.16899117e+02 1.16847794e+02 1.16818855e+02 1.16742630e+02 1.16676125e+02 1.16721054e+02 1.16877502e+02 1.17095367e+02 1.17197838e+02 1.17200142e+02 1.17100418e+02 1.17025223e+02 1.16980629e+02 1.16981926e+02 1.16915085e+02 1.16923599e+02 1.16862175e+02 1.16768509e+02 1.16629944e+02 1.16611168e+02 1.16615448e+02 1.16700150e+02 1.16721741e+02 1.16777184e+02 1.16729630e+02 1.16656784e+02 1.16669746e+02 1.16632591e+02 1.16680130e+02 1.16706184e+02 1.16714828e+02 1.16667381e+02 1.16521286e+02 1.16462402e+02 1.16242622e+02 1.16095032e+02 1.15916939e+02 1.15619202e+02 1.14184128e+02 1.10888283e+02 1.06949867e+02 1.40136551e+02 2.10931152e+02 4.46216125e+02 4.31161774e+02 2.14209518e+02 1.46039047e+02 1.16497864e+02 1.17229729e+02 1.17884995e+02 1.18949394e+02 1.21317085e+02 1.24822479e+02 1.29137512e+02 1.32369522e+02 1.68286896e+02 2.78173981e+02 1.34220032e+03 -197472832. 303068288. -107048200. 1.26842944e+03 5.84506958e+02 4.54386444e+02 6.32444275e+02 1.48015320e+03 7343748. 330915680. 837141568. -267653456. -193703248. 1386474368. 1.25184619e+03 7.29700073e+02 5.60571167e+02 6.51151001e+02 5.22157654e+02 4.84216370e+02 4.79037506e+02 5.64486023e+02 5.62379211e+02 5.59275452e+02 5.54856445e+02 4.59295410e+02 3.88915192e+02 3.80507477e+02 3.43992188e+02 3.96029541e+02 3.60463013e+02 3.71720978e+02 3.04927429e+02 2.92251770e+02 2.60892181e+02 2.34698212e+02 2.14206299e+02 2.17682495e+02 2.16694748e+02 2.16555450e+02 2.24472595e+02 2.21609741e+02 2.21170242e+02 2.26285828e+02 2.25756332e+02 2.21783615e+02 2.60528137e+02 1.92514389e+02 2.10968918e+02 2.21942245e+02 4.27011658e+02 5.30414795e+02 5.42485352e+02 5.44286987e+02 5.30530518e+02 5.22808594e+02 5.15076477e+02 5.11011017e+02 5.07573578e+02 5.04972076e+02 5.03128082e+02 5.01479980e+02 4.99294128e+02 4.97030121e+02 4.95172424e+02 4.93541992e+02 4.91827332e+02 4.89315002e+02 4.87528534e+02 4.85276428e+02 2.47057785e+02 1.65393433e+02 1.24412071e+02 1.23855934e+02 1.23208206e+02 1.22634239e+02 1.21902985e+02 1.21092758e+02 1.20250900e+02 1.19561012e+02 1.18957726e+02 1.18588295e+02 1.18298782e+02 1.18158798e+02 1.18038956e+02 1.17981880e+02 1.17902939e+02 1.17867958e+02 1.17683571e+02 1.17597366e+02 1.17552193e+02 1.17645126e+02 1.17716949e+02 1.17783905e+02 1.17822723e+02 1.17784149e+02 1.17745880e+02 1.17681183e+02 1.17687355e+02 1.17667351e+02 1.17687447e+02 1.17678246e+02 1.17653519e+02 1.17613266e+02 1.17587341e+02 1.17572510e+02 1.17581909e+02 1.17596764e+02 1.17578392e+02 1.17548706e+02 1.17501190e+02 1.17489525e+02 1.17453552e+02 1.17386452e+02 1.17304092e+02 1.17305809e+02 1.17468300e+02 1.17425873e+02 1.17349724e+02 1.17117371e+02 1.17111954e+02 1.17180244e+02 1.17232018e+02 1.17202110e+02 1.17148956e+02 1.17177017e+02 1.17272713e+02 1.17324814e+02 1.17320816e+02 1.17282753e+02 1.17246498e+02 1.17275230e+02 1.17287392e+02 1.17300491e+02 1.17296455e+02 1.17337517e+02 1.17422104e+02 1.17440590e+02 1.17532051e+02 1.17429993e+02 1.17401474e+02 1.17263000e+02 1.17252060e+02 1.17228874e+02 1.17171249e+02 1.17198425e+02 1.17187057e+02 1.17155334e+02 1.17129402e+02 1.17186615e+02 1.17234245e+02 1.17242805e+02 1.17182396e+02 1.17249496e+02 1.17332237e+02 1.17492767e+02 1.17583786e+02 1.17565765e+02 1.17509895e+02 1.17351685e+02 1.17225327e+02 1.17105270e+02 1.17069832e+02 1.17100807e+02 1.17106079e+02 1.17151489e+02 1.17181381e+02 1.17232330e+02 1.17179314e+02 1.17033981e+02 1.16904091e+02 1.16843254e+02 1.16787735e+02 1.16659813e+02 1.16720474e+02 1.16753792e+02 1.16764809e+02 1.16619034e+02 1.16487083e+02 1.16501411e+02 1.16515221e+02 1.16611710e+02 1.16694763e+02 1.16844124e+02 1.16873299e+02 1.16889511e+02 1.16851700e+02 1.16833679e+02 1.16830284e+02 1.16858139e+02 1.16848061e+02 1.16761856e+02 1.16633049e+02 1.16489563e+02 1.16455490e+02 1.16431450e+02 1.16431610e+02 1.16411270e+02 1.16495461e+02 1.16581474e+02 1.16625877e+02 1.16524559e+02 1.16558617e+02 1.16508194e+02 1.16557518e+02 1.16611603e+02 1.16565811e+02 1.16659340e+02 1.16831642e+02 1.17053268e+02 1.17091164e+02 1.17033897e+02 1.17073517e+02 1.17088074e+02 1.17089348e+02 1.17329239e+02 1.17365250e+02 1.17343086e+02 1.17159950e+02 1.17368004e+02 1.17573372e+02 1.17626289e+02 1.17472878e+02 1.17280724e+02 1.17158211e+02 1.17072205e+02 1.17015350e+02 1.16871277e+02 1.16861221e+02 1.16759979e+02 1.16712288e+02 1.16509041e+02 1.16454742e+02 1.16448746e+02 1.16476601e+02 1.16471046e+02 1.16494904e+02 1.16497726e+02 1.16493217e+02 1.16477249e+02 1.16459084e+02 1.16435760e+02 1.16413422e+02 1.16391159e+02 1.16414688e+02 1.16419273e+02 1.16417152e+02 1.16418892e+02 1.16435394e+02 1.16472069e+02 1.16493011e+02 1.16497437e+02 1.16455986e+02 1.16426140e+02 1.16400475e+02 1.16416687e+02 1.16409134e+02 1.16386642e+02 1.16384933e+02 1.16393723e+02 1.16397652e+02 1.16372536e+02 1.16345879e+02 1.16495140e+02 1.16503807e+02 1.16526901e+02 1.16420631e+02 1.16427124e+02 1.16378105e+02 1.16320740e+02 1.16279884e+02 1.16279655e+02 1.16283646e+02 1.16295769e+02 1.16311432e+02 1.16367058e+02 1.16460060e+02 1.16450272e+02 1.16396042e+02 1.16303276e+02 1.16290489e+02 1.16267738e+02 1.16257370e+02 1.16279144e+02 1.16290253e+02 1.16271896e+02 1.16221336e+02 1.16189026e+02 1.16211937e+02 1.16239044e+02 1.16272354e+02 1.16276939e+02 1.16280617e+02 1.16247536e+02 1.16212379e+02 1.16184242e+02 1.16177292e+02 1.16365211e+02 1.16412323e+02 1.16467926e+02 1.16435913e+02 1.16537514e+02 1.16686668e+02 1.16675262e+02 1.16677048e+02 1.16444862e+02 1.16208946e+02 1.15989632e+02 1.16001701e+02 1.16040100e+02 1.16113861e+02 1.16132507e+02 1.16097275e+02 1.16023453e+02 1.15986290e+02 1.15995193e+02 1.16004623e+02 1.15998741e+02 1.15988640e+02 1.16065819e+02 1.16128197e+02 1.16173615e+02 1.16235443e+02 1.16380608e+02 1.16572746e+02 1.16699852e+02 1.16790184e+02 1.16996986e+02 1.17309036e+02 1.17853653e+02 1.18279449e+02 1.18653709e+02 1.18870079e+02 1.19211662e+02 1.19608246e+02 1.19996147e+02 1.20251953e+02 1.20418739e+02 1.20558083e+02 1.20688309e+02 1.20703514e+02 1.20592529e+02 1.20918640e+02 1.20879883e+02 1.53601624e+02 2.26688599e+02 2.42557983e+02 2.13795975e+02 2.30365387e+02 4.79555786e+02 4.80424957e+02 4.80988159e+02 4.81504364e+02 3.94159210e+02 2.63467590e+02 2.43065598e+02 2.81787170e+02 4.92232300e+02 4.94714142e+02 4.97536804e+02 4.09879700e+02 3.31450500e+02 1.96870361e+02 1.96468903e+02 2.29957550e+02 3.94454742e+02 3.71083832e+02 3.81309814e+02 4.92715240e+02 4.93332794e+02 4.94213226e+02 4.96135925e+02 4.99041321e+02 5.00866699e+02 5.01734924e+02 5.01240143e+02 5.01477234e+02 5.02008698e+02 5.02592010e+02 5.02951019e+02 5.03353394e+02 5.03975922e+02 5.04143158e+02 2.34808609e+02 2.04722961e+02 2.21896957e+02 5.08240936e+02 5.09835999e+02 5.11656860e+02 5.10033203e+02 5.12125122e+02 5.14698975e+02 5.22623108e+02 5.43988831e+02 7.67431641e+02 1.55455872e+03 -667429056. 136376800. 508589312. -2.63679693e+09 -848941120. 1.15305151e+03 8.12532288e+02 1.07364819e+03 1.33553284e+03 6.44783203e+02 4.46659821e+02 4.06116547e+02 5.57511353e+02 1.02523584e+03 -664370816. 67954016. -339130848. 1.22065027e+03 3.90856262e+02 2.03490753e+02 1.41751862e+02 1.19325905e+02 1.18505180e+02 1.18117874e+02 1.17710861e+02 1.17395035e+02 1.17155457e+02 1.54816452e+02 8.99209747e+01 1.04510483e+02 1.25982269e+02 2.11781586e+02 1.43412094e+02 1.13822746e+02 1.15415932e+02 1.16029457e+02 1.16560692e+02 1.17061256e+02 1.17323853e+02 1.17543488e+02 1.17643036e+02 1.17644615e+02 1.17633522e+02 1.17643219e+02 1.17626694e+02 1.17583031e+02 1.17520500e+02 1.17494377e+02 1.17454689e+02 1.17388412e+02 1.17328636e+02 1.17309212e+02 1.17322456e+02 1.17366051e+02 1.17357567e+02 1.17341156e+02 1.17299057e+02 1.17238731e+02 1.17131912e+02 1.17059769e+02 1.17213455e+02 1.17512642e+02 1.17759514e+02 1.17845802e+02 1.17801872e+02 1.17783142e+02 1.17744064e+02 1.17836899e+02 1.17920395e+02 1.17923958e+02 1.17810287e+02 1.17716080e+02 1.17713089e+02 1.17813240e+02 1.17814430e+02 1.17808731e+02 1.17675575e+02 1.17651443e+02 1.17674858e+02 1.17722359e+02 1.17828423e+02 1.18010361e+02 1.18215042e+02 1.18378822e+02 1.18462112e+02 1.18470886e+02 1.18266479e+02 1.18016830e+02 1.17751953e+02 1.17654526e+02 1.17673767e+02 1.17674179e+02 1.17624672e+02 1.17486931e+02 1.17465782e+02 1.17500427e+02 1.17577003e+02 1.17545464e+02 1.17517555e+02 1.17440109e+02 1.17407478e+02 1.17363159e+02 1.17358101e+02 1.17327911e+02 1.17311913e+02 1.17291046e+02 1.17296684e+02 1.17405182e+02 1.17461708e+02 1.17518646e+02 1.17431969e+02 1.17467216e+02 1.17594284e+02 1.17619759e+02 1.17602776e+02 1.17461311e+02 1.17447624e+02 1.17349487e+02 1.17373756e+02 1.17340569e+02 1.17346992e+02 1.17252808e+02 1.17212181e+02 1.17012215e+02 1.16913727e+02 1.17059700e+02 1.17347488e+02 1.17546379e+02 1.17647728e+02 1.17797386e+02 1.17972519e+02 1.18120811e+02 1.17953491e+02 1.17825768e+02 1.17368454e+02 1.17395218e+02 1.17351181e+02 1.17655449e+02 1.17679359e+02 1.17713593e+02 1.17629295e+02 1.17601860e+02 1.17573189e+02 1.17522072e+02 1.17351143e+02 1.17221733e+02 1.17158234e+02 1.17174530e+02 1.17105270e+02 1.17121368e+02 1.17140015e+02 1.17217018e+02 1.17272728e+02 1.17393166e+02 1.17541771e+02 1.17710281e+02 1.17740837e+02 1.18005615e+02 1.18541046e+02 1.19379082e+02 1.21659874e+02 1.21582932e+02 1.21217804e+02 1.18504898e+02 1.17998070e+02 1.17723495e+02 1.18320580e+02 1.18561165e+02 1.18927124e+02 1.19784462e+02 1.20321182e+02 1.19915451e+02 1.18325264e+02 1.17586479e+02 1.17460709e+02 1.17751770e+02 1.17999542e+02 1.18245911e+02 1.18463158e+02 1.18663216e+02 1.18777939e+02 1.19081505e+02 1.25599426e+02 1.35667511e+02 1.47680954e+02 1.87915771e+02 2.66888489e+02 4.90885437e+02 5.02687012e+02 5.43652039e+02 6.37507629e+02 1.00403467e+03 2.20259839e+03 481427136. -394251040. 1.39782007e+03 7.08636536e+02 4.93837799e+02 4.95500061e+02 4.96248413e+02 4.96275024e+02 4.95716736e+02 4.92576691e+02 4.90216766e+02 4.88007019e+02 4.88977417e+02 4.90623108e+02 4.94138184e+02 4.97184296e+02 4.99629303e+02 5.00648468e+02 2.32742294e+02 2.04122116e+02 2.23857346e+02 4.99697418e+02 6.50155823e+02 6.95306641e+02 1.05098755e+03 7.00446228e+02 6.16674255e+02 5.59960327e+02 5.14120789e+02 2.79043243e+02 1.91713837e+02 1.46721817e+02 1.46441422e+02 1.82642761e+02 2.59995697e+02 4.85128815e+02 4.88644867e+02 4.93464874e+02 5.31250000e+02 7.58844116e+02 1.76121936e+03 583192320. 0. 0. 0. 0. 0. 0. 0. 0. 0. 779857728. 779857728. 779857728. 0. 0. 0. 0. 355357568. 355357568. 355357568. 0. 0. 449800192. 135109456. 21187388. 32094124. -1701009792. 677819968. -894598080. -894598080. -894598080. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 1.21309696e+10 1.21309696e+10 1.21309696e+10 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. 299046848. 299046848. 299046848. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -3.71962342e+09 -3.71962342e+09 -3.71962342e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. -253202832. -85823520. 969438. 383584832. 555636288. -744691200. 101341472. -2.05520384e+10 1.12508826e+03 8.01314880e+02 1.16255554e+03 1.09148767e+03 1.11804749e+03 1.11804749e+03 34345516. 1131874432. 1131874432. 666889920. 0. 0. 0. 0. 25497678. 25497678. 25497678. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.09788396e+10 -2.09788396e+10 -2.09788396e+10 0. 0. 0. 0. 0. 0. 0. -236811568. -236811568. -236811568. 0. 892489984. 178351024. 22678750. 169991104. 179518320. 1.38335840e+03 6.99114624e+02 4.91927002e+02 4.90167938e+02 4.87133453e+02 4.84006561e+02 4.78634125e+02 6.55732788e+02 1.27038354e+03 18238932. 95588864. 4.18445773e+09 9.90918396e+02 3.09417847e+02 2.89260590e+02 73517696. 135602016. 132533024. 3.11225830e+02 2.22377411e+02 2.95993530e+02 1.29083984e+03 6.58447510e+02 4.68176025e+02 4.74137207e+02 4.78266357e+02 4.79429077e+02 4.80005615e+02 4.79852997e+02 4.36414001e+02 5.63262878e+02 1.01139868e+03 9.64839172e+02 -7.28350050e+06 1266527488. 0. 0. 4.79116089e+02 3.03044159e+02 2.84862549e+02 -414313984. -462486208. -168202592. 571246848. 241309936. 75042744. 1.30496155e+03 6.62820374e+02 4.66546478e+02 2.24880173e+02 1.49072296e+02 1.12985191e+02 1.13051170e+02 1.12979607e+02 1.12836998e+02 1.12564705e+02 1.12333061e+02 1.12091843e+02 1.12050034e+02 1.12002769e+02 1.12024734e+02 1.11931915e+02 1.11909508e+02 1.11570724e+02 1.11353844e+02 1.11093330e+02 1.11128960e+02 1.11071053e+02 1.11075012e+02 1.11228661e+02 1.11281487e+02 1.11210770e+02 1.43285477e+02 2.15023209e+02 2.20346771e+02 1.46004807e+02 1.10830246e+02 1.11155754e+02 1.11309273e+02 1.11181450e+02 1.43408798e+02 2.14419647e+02 2.20820755e+02 1.46431503e+02 1.11044403e+02 1.11128029e+02 1.11070717e+02 1.11047737e+02 1.11030922e+02 1.11093048e+02 1.11099617e+02 1.11103882e+02 1.11091331e+02 1.11099419e+02 1.11091049e+02 1.11115585e+02 1.11132126e+02 1.11152534e+02 1.11138145e+02 1.11106758e+02 1.11081711e+02 1.11083778e+02 1.11088058e+02 1.11060936e+02 1.11198936e+02 1.11378128e+02 1.11595879e+02 1.11535904e+02 1.11475075e+02 1.11482056e+02 1.11478760e+02 1.11407143e+02 1.11351418e+02 1.11301697e+02 1.11259445e+02 1.11279427e+02 1.11334595e+02 1.11461044e+02 1.11543610e+02 1.11573662e+02 1.11515114e+02 1.11494850e+02 1.11532211e+02 1.11605843e+02 1.11641258e+02 1.11625549e+02 1.11615067e+02 1.11564018e+02 1.11506454e+02 1.11407005e+02 1.11304901e+02 1.11197853e+02 1.11112114e+02 1.11088898e+02 1.11103104e+02 1.11144196e+02 1.11183182e+02 1.11184944e+02 1.11231270e+02 1.11301590e+02 1.11371330e+02 1.11390877e+02 1.11357071e+02 1.11385345e+02 1.11391312e+02 1.11442085e+02 1.11424759e+02 1.11450562e+02 1.11419357e+02 1.11394714e+02 1.11330231e+02 1.11287415e+02 1.11187897e+02 1.11102150e+02 1.11074570e+02 1.11160583e+02 1.11234756e+02 1.11249641e+02 1.11257263e+02 1.11244202e+02 1.11201408e+02 1.11187859e+02 1.11191078e+02 1.11279228e+02 1.11337563e+02 1.11310272e+02 1.11273727e+02 1.11171524e+02 1.11120026e+02 1.11111305e+02 1.11163956e+02 1.11308037e+02 1.11364845e+02 1.11363655e+02 1.11306694e+02 1.11309456e+02 1.11280220e+02 1.11335075e+02 1.11317551e+02 1.11377182e+02 1.11356316e+02 1.11337830e+02 1.11337875e+02 1.11357658e+02 1.11450439e+02 1.11489868e+02 1.11495491e+02 1.11441910e+02 1.11411880e+02 1.11422661e+02 1.11457764e+02 1.11468788e+02 1.11445641e+02 1.11376945e+02 1.11299973e+02 1.11158257e+02 1.11020172e+02 1.10867554e+02 1.10699585e+02 1.10459023e+02 1.10115677e+02 1.09453094e+02 1.07583916e+02 1.04313080e+02 1.00896896e+02 9.83058167e+01 1.29080063e+02 1.95377441e+02 4.17618896e+02 4.02160828e+02 3.82721710e+02 2.00432999e+02 1.39446396e+02 1.11774765e+02 1.53531387e+02 1.50650360e+02 2.58735291e+02 3.44902954e+02 -107048200. -288124672. 240084976. 1.52386016e+05 3.50111642e+09 454195584. 0. 0. 0. 0. 0. 0. 1.63801611e+03 1.31226697e+03 1.11108191e+03 9463392. 7.10245547e+04 5.13228203e+04 7.47000156e+04 57884948. 5.90615150e+06 2.96033275e+06 38951540. 5.04599141e+04 2.05262383e+04 1.93593945e+04 7.90974316e+03 7.64689648e+03 7.01181445e+03 3.58180420e+03 1.68697583e+03 1.41802136e+03 1.06937000e+03 2.02408173e+02 1.72982880e+02 1.92484451e+02 1.26957263e+03 1.32775073e+03 1.82807825e+03 1.73959485e+03 1.83241382e+03 1.93590051e+03 1.99310437e+03 1.94448230e+03 2.65552637e+03 9.74072632e+02 9.28475525e+02 1.24259106e+03 6.30067148e+04 -78811424. 2.12021150e+06 16416032. 40936020. 29642216. -147382704. -504097824. -241914480. -147501280. -700658752. 113152936. 252479696. 131840976. -97371200. -93879944. -111786424. -273529824. -267987040. 194122928. 1.44790906e+03 7.30519104e+02 5.11864716e+02 2.39034744e+02 1.56866959e+02 1.17812820e+02 1.16868660e+02 1.15804741e+02 1.15254219e+02 1.14808014e+02 1.14430435e+02 1.13928802e+02 1.13504013e+02 1.13145569e+02 1.12999130e+02 1.12950569e+02 1.13040527e+02 1.13066681e+02 1.13046570e+02 1.12990036e+02 1.13110710e+02 1.13255653e+02 1.13390968e+02 1.13360390e+02 1.13269684e+02 1.13141243e+02 1.12989288e+02 1.12919060e+02 1.12832687e+02 1.12778168e+02 1.12610619e+02 1.12569962e+02 1.12400719e+02 1.12321091e+02 1.12136612e+02 1.12120590e+02 1.12099350e+02 1.12073219e+02 1.12098251e+02 1.12160156e+02 1.12232605e+02 1.12154556e+02 1.12161514e+02 1.12057800e+02 1.12055687e+02 1.11939735e+02 1.11758636e+02 1.11625275e+02 1.11481216e+02 1.11495132e+02 1.11396454e+02 1.11330788e+02 1.11278854e+02 1.11266945e+02 1.11173599e+02 1.11147667e+02 1.11151199e+02 1.11228004e+02 1.11241554e+02 1.11185532e+02 1.11152100e+02 1.11144333e+02 1.11149315e+02 1.11060104e+02 1.11042969e+02 1.11190239e+02 1.11365456e+02 1.11471390e+02 1.11547119e+02 1.11516403e+02 1.11473396e+02 1.11276619e+02 1.11360916e+02 1.11291885e+02 1.11289879e+02 1.11237152e+02 1.11211136e+02 1.11125534e+02 1.11119080e+02 1.11290062e+02 1.11234749e+02 1.11149117e+02 1.11093338e+02 1.11299294e+02 1.11463432e+02 1.11643791e+02 1.11800537e+02 1.11862854e+02 1.11835197e+02 1.11830711e+02 1.11832329e+02 1.11835793e+02 1.11828316e+02 1.11632874e+02 1.11473984e+02 1.11320145e+02 1.11385208e+02 1.11413040e+02 1.11268456e+02 1.11123764e+02 1.10920776e+02 1.10935860e+02 1.10908997e+02 1.11053085e+02 1.11103966e+02 1.11083534e+02 1.11024055e+02 1.11079376e+02 1.11170410e+02 1.11237320e+02 1.11185593e+02 1.10963913e+02 1.10761986e+02 1.10630905e+02 1.10654251e+02 1.10665039e+02 1.10657639e+02 1.10634735e+02 1.10601830e+02 1.10594963e+02 1.10574112e+02 1.10557137e+02 1.10498749e+02 1.10488052e+02 1.10482605e+02 1.10489250e+02 1.10639671e+02 1.10697342e+02 1.10755539e+02 1.10639023e+02 1.10561508e+02 1.10480614e+02 1.10402138e+02 1.10363541e+02 1.10319984e+02 1.10328033e+02 1.10385597e+02 1.10409035e+02 1.10411606e+02 1.10371376e+02 1.10351746e+02 1.10354660e+02 1.10357407e+02 1.10377167e+02 1.10437157e+02 1.10609749e+02 1.10698540e+02 1.10681976e+02 1.10524887e+02 1.10496063e+02 1.10479126e+02 1.10456352e+02 1.10389587e+02 1.10363304e+02 1.10359627e+02 1.10336586e+02 1.10348579e+02 1.10326805e+02 1.10318207e+02 1.10263916e+02 1.10233559e+02 1.10282211e+02 1.10331390e+02 1.10430580e+02 1.10457634e+02 1.10474030e+02 1.10482262e+02 1.10561829e+02 1.10669258e+02 1.10764755e+02 1.10770210e+02 1.10766380e+02 1.10764648e+02 1.10766998e+02 1.10751953e+02 1.10700508e+02 1.10650749e+02 1.10616295e+02 1.10466293e+02 1.10313110e+02 1.10148132e+02 1.10120087e+02 1.10094910e+02 1.10085007e+02 1.10063187e+02 1.10060699e+02 1.10011810e+02 1.10019844e+02 1.09966972e+02 1.09961159e+02 1.09887184e+02 1.09871826e+02 1.09870148e+02 1.09897224e+02 1.09913567e+02 1.09905090e+02 1.09889870e+02 1.09902275e+02 1.09935432e+02 1.09981956e+02 1.10028351e+02 1.10077522e+02 1.10106552e+02 1.10118996e+02 1.10091522e+02 1.10086205e+02 1.10046059e+02 1.10020309e+02 1.09969574e+02 1.09937363e+02 1.09935852e+02 1.09961662e+02 1.10004318e+02 1.10030327e+02 1.10057945e+02 1.10080139e+02 1.10228264e+02 1.10342545e+02 1.10504974e+02 1.10482666e+02 1.10331512e+02 1.10108940e+02 1.09949982e+02 1.09929253e+02 1.09962715e+02 1.09998001e+02 1.10032166e+02 1.10027855e+02 1.10038841e+02 1.10160004e+02 1.10279770e+02 1.10393730e+02 1.10400726e+02 1.10428490e+02 1.10460426e+02 1.10544739e+02 1.10572563e+02 1.10628571e+02 1.10646652e+02 1.10758377e+02 1.10903954e+02 1.11038078e+02 1.11050713e+02 1.11027390e+02 1.10999229e+02 1.11071594e+02 1.11297600e+02 1.11554893e+02 1.11769394e+02 1.11815582e+02 1.11897881e+02 1.11952599e+02 1.12058929e+02 1.12106606e+02 1.12158974e+02 1.12183159e+02 1.12280220e+02 1.12520309e+02 1.12722931e+02 1.13073334e+02 1.13548058e+02 1.14225296e+02 1.14756378e+02 1.15264290e+02 1.15703842e+02 1.16453247e+02 1.17122665e+02 1.51932251e+02 2.28999725e+02 4.93433746e+02 4.94004517e+02 4.91706940e+02 4.93032684e+02 4.91236267e+02 6.79921265e+02 1.31798730e+03 1.41063989e+03 1.01132611e+03 1.36074817e+03 -164432080. 106431920. -149570544. -295902944. 2.83706016e+04 2.63722534e+03 1.93160596e+03 2.62293213e+03 77033384. 33535206. 384233440. 3.69318828e+04 1.13889736e+04 1.21191748e+03 9.41847351e+02 1.27152710e+03 2.04040781e+04 1.48019014e+04 2.02247031e+04 105239584. -128729136. -185554656. 349996864. -554586048. -195559792. -2.55366758e+09 -396536608. -110325344. -678750208. -114151216. 112511560. 137614608. 3.00911499e+02 2.15167328e+02 2.12800354e+02 8.28535217e+02 1.11256152e+03 68388040. 17587710. 24553880. 440685664. 43831184. -673497088. 145973232. 2.78960114e+02 3.09743073e+02 7.32576599e+02 0. 0. 0. 0. 0. 776715200. 776715200. 776715200. 991736896. -129782552. 66063780. 1081030016. 275636768. 132791520. 3.20122467e+02 1.62022797e+02 1.12823853e+02 1.12359848e+02 1.07633453e+02 1.34030304e+02 1.98100876e+02 4.16437988e+02 2.14655365e+02 1.96513229e+02 2.20218124e+02 2.02857162e+02 1.37869980e+02 1.08570198e+02 1.10287132e+02 1.10765480e+02 1.11094826e+02 1.11496292e+02 1.11662834e+02 1.11856354e+02 1.12068642e+02 1.12255005e+02 1.12502403e+02 1.12615868e+02 1.12770012e+02 1.12776733e+02 1.12645386e+02 1.12475586e+02 1.12383354e+02 1.12339699e+02 1.12411644e+02 1.12483353e+02 1.12599251e+02 1.12583534e+02 1.12590187e+02 1.12586716e+02 1.12716309e+02 1.12682030e+02 1.12582138e+02 1.12408257e+02 1.12410919e+02 1.12440155e+02 1.12450554e+02 1.12335411e+02 1.12222527e+02 1.12143738e+02 1.12155533e+02 1.12144379e+02 1.12184380e+02 1.12171227e+02 1.12257133e+02 1.12204475e+02 1.12168465e+02 1.12094849e+02 1.12125023e+02 1.12234612e+02 1.12161400e+02 1.12180458e+02 1.12208824e+02 1.12309700e+02 1.12317413e+02 1.12138817e+02 1.12187248e+02 1.12190338e+02 1.12313202e+02 1.12311729e+02 1.12553566e+02 1.12732758e+02 1.12936943e+02 1.12907059e+02 1.13132607e+02 1.13044739e+02 1.13212997e+02 1.12734100e+02 1.12543633e+02 1.12053001e+02 1.11997864e+02 1.11963043e+02 1.11920753e+02 1.11892883e+02 1.11882309e+02 1.11927841e+02 1.11980919e+02 1.11914040e+02 1.11879440e+02 1.11760139e+02 1.11711197e+02 1.11649391e+02 1.11681618e+02 1.11754036e+02 1.11838051e+02 1.11862595e+02 1.11909012e+02 1.11850098e+02 1.11727852e+02 1.11725327e+02 1.11728355e+02 1.11882584e+02 1.11925323e+02 1.11869530e+02 1.11883972e+02 1.11835167e+02 1.11948471e+02 1.11922409e+02 1.11777473e+02 1.11727585e+02 1.11715851e+02 1.11801636e+02 1.11840675e+02 1.11577911e+02 1.11460503e+02 1.11480667e+02 1.11730606e+02 1.11932663e+02 1.11969681e+02 1.11897141e+02 1.11841026e+02 1.11655006e+02 1.11607208e+02 1.11537445e+02 1.11545578e+02 1.11632042e+02 1.11680733e+02 1.11811836e+02 1.11800819e+02 1.11803658e+02 1.11812355e+02 1.11751595e+02 1.11701874e+02 1.11702545e+02 1.11814789e+02 1.11931358e+02 1.12061363e+02 1.12102051e+02 1.12144249e+02 1.12173874e+02 1.12244186e+02 1.12358902e+02 1.12409004e+02 1.12318687e+02 1.12228035e+02 1.12140724e+02 1.12289490e+02 1.12547386e+02 1.13040382e+02 1.13730690e+02 1.22029984e+02 1.27258408e+02 1.26701721e+02 1.17277267e+02 1.12444229e+02 1.12770103e+02 1.13465637e+02 1.12900902e+02 1.10692909e+02 1.17194366e+02 1.21777534e+02 1.25659378e+02 1.17271873e+02 1.13744110e+02 1.13382278e+02 1.13420601e+02 1.13554153e+02 1.13705917e+02 1.13925636e+02 1.14792870e+02 1.22078430e+02 1.30539551e+02 1.81235031e+02 2.86334564e+02 2.34792709e+02 2.07879776e+02 2.82256683e+02 -74263992. 4010658. 1.71714438e+06 7.51800050e+06 -173945312. -224307200. 0. 0. -23770638. 1544657024. -105474920. 144008000. -54714156. 224145360. -161316784. 152749104. 48388812. 111323280. 2.98299835e+02 2.12950195e+02 2.82523834e+02 -87650344. -689320576. 209728272. 1.11017871e+03 7.96843811e+02 1.06524585e+03 2.92906750e+05 80119816. -29770604. -865537408. 5630603. 6.96531750e+05 7.77907062e+05 35575248. 2.00817297e+03 1.01809113e+03 7.21734680e+02 7.24280823e+02 1.00525232e+03 1.96744604e+03 -485080288. -5.40364493e+09 44921412. 3.72435562e+05 6.35791514e+09 360125760. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 779857728. 779857728. 779857728. 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. 0. 0. 0. 0. 0. 0. 0. 1.21309696e+10 1.21309696e+10 1.21309696e+10 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. 299046848. 299046848. -153693760. -266180128. -266180128. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1859811712. -1859811712. -1859811712. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -1.09601198e+10 -1.09601198e+10 -1.09601198e+10 470844128. 62742560. 62742560. 17172758. 565937216. 565937216. 333444960. 0. 0. 0. 0. 25497678. 25497678. 25497678. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -2.09788396e+10 -2.09788396e+10 -2.09788396e+10 0. 0. 0. 0. 0. 0. 0. -236811568. -236811568. -236811568. 0. 0. 0. 0. 0. 0. -329619840. -96259720. -25843578. 25704362. -235448928. -33312544. 20675916. -330376672. -11387633. 0. 0. 0. 173548320. 173548320. 173548320. 0. 0. 0. 330058560. 330058560. 330058560. -76731712. -105170616. 28834376. 43425892. -96563640. 125457544. 85262752. 465604800. 1.45217203e+05 -8614232. -1172395776. 1266527488. 1266527488. 1266527488. 0. 0. -396788000. -396788000. -396788000. 0. 0. 0. 0. 0. 0. 108458168. 48280704. 161034480. 9.33616943e+02 4.77462433e+02 3.29760651e+02 3.30932709e+02 3.31055817e+02 3.30686737e+02 3.29493530e+02 3.28238770e+02 3.27024323e+02 3.26723480e+02 3.26486664e+02 3.26475952e+02 3.26164520e+02 3.26100189e+02 3.24292389e+02 3.23218719e+02 3.22067932e+02 3.22471039e+02 3.22136230e+02 3.22083771e+02 3.23065613e+02 3.23668121e+02 3.23412781e+02 4.64011078e+02 9.05897583e+02 9.06179321e+02 4.63417877e+02 3.21016327e+02 3.23255249e+02 3.24556976e+02 3.23872223e+02 4.65488953e+02 9.07554626e+02 9.24686035e+02 4.72172791e+02 3.24196869e+02 3.24362122e+02 3.23587219e+02 3.24537720e+02 3.24826965e+02 3.25348175e+02 3.25355408e+02 3.25511047e+02 3.25672699e+02 3.25958466e+02 3.25906982e+02 3.25270416e+02 3.24300995e+02 3.23516479e+02 3.23411865e+02 3.23769470e+02 3.23995361e+02 3.23852386e+02 3.23645935e+02 3.23247711e+02 3.22836792e+02 3.22295776e+02 3.22974854e+02 3.23457184e+02 3.23998627e+02 3.24403015e+02 3.25011627e+02 3.25249542e+02 3.24876007e+02 3.24761780e+02 3.25170837e+02 3.25828217e+02 3.26169464e+02 3.26411285e+02 3.26322266e+02 3.26055206e+02 3.25451935e+02 3.24885284e+02 3.24794556e+02 3.24285919e+02 3.23984833e+02 3.23372253e+02 3.23143097e+02 3.23086487e+02 3.23224884e+02 3.23575317e+02 3.23948242e+02 3.24381226e+02 3.24891083e+02 3.25122498e+02 3.25252258e+02 3.25503967e+02 3.25613739e+02 3.25153961e+02 3.25275391e+02 3.25431488e+02 3.25593750e+02 3.25139618e+02 3.25207794e+02 3.25665375e+02 3.25545624e+02 3.25034760e+02 3.24416290e+02 3.24358826e+02 3.24273682e+02 3.24227295e+02 3.24031921e+02 3.23673492e+02 3.23060760e+02 3.22507751e+02 3.22422058e+02 3.22951935e+02 3.23480042e+02 3.23693268e+02 3.23812347e+02 3.23904205e+02 3.23680389e+02 3.23784515e+02 3.23984650e+02 3.23871002e+02 3.23288879e+02 3.22582336e+02 3.22599792e+02 3.22869690e+02 3.23100586e+02 3.23413147e+02 3.23603699e+02 3.24019684e+02 3.24162903e+02 3.24022797e+02 3.23771332e+02 3.24199707e+02 3.24495178e+02 3.24965759e+02 3.25052856e+02 3.25077820e+02 3.24845856e+02 3.24549957e+02 3.24684265e+02 3.24978119e+02 3.25190002e+02 3.25388458e+02 3.24943390e+02 3.24414825e+02 3.24276581e+02 3.24457550e+02 3.25105774e+02 3.24891479e+02 3.25019348e+02 3.24442780e+02 3.24160950e+02 3.24058563e+02 3.23812866e+02 3.23683624e+02 3.23240356e+02 3.23035156e+02 3.22799500e+02 3.22587646e+02 3.22449249e+02 3.21945740e+02 3.21458771e+02 3.20921570e+02 3.20474121e+02 3.18974152e+02 3.14294647e+02 3.02650482e+02 2.88036713e+02 2.72890137e+02 2.63205872e+02 3.46749268e+02 7.88290405e+02 80235624. 325714144. 325714144. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 7.15613098e+02 7.15613098e+02 7.15613098e+02 0. -251613184. -251613184. -251613184. 0. 0. 0. 0. 271669088. 134692400. 134692400. 162722720. 160550624. 81469360. -4551101. 1.41322021e+04 311148. 1.33748486e+04 4.05116089e+02 3.27404633e+02 3.61715607e+02 2.70065781e+04 1.00292289e+05 7.86204625e+05 4.24505031e+05 4616256. 860462. 2.80138975e+06 1.19050950e+06 255043440. -5.41038250e+06 -2.51534656e+05 -2.51534656e+05 179870592. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 603295616. 111458984. -473995232. 9.57336426e+02 4.87306244e+02 3.34608429e+02 3.33364136e+02 3.32216034e+02 3.32919312e+02 3.33395172e+02 3.33720764e+02 3.32790649e+02 3.32134674e+02 3.31240387e+02 3.31013519e+02 3.31016266e+02 3.31721680e+02 3.32064392e+02 3.32802643e+02 3.33117615e+02 3.33896088e+02 3.34069336e+02 3.34106659e+02 3.33599884e+02 3.32927338e+02 3.32503937e+02 3.31857605e+02 3.31658051e+02 3.31175110e+02 3.30872437e+02 3.29782227e+02 3.29462372e+02 3.28651398e+02 3.28377594e+02 3.27393036e+02 3.27365997e+02 3.27184753e+02 3.26992218e+02 3.27056244e+02 3.27401703e+02 3.27887085e+02 3.27583893e+02 3.27738770e+02 3.27448914e+02 3.27660065e+02 3.27124786e+02 3.25285675e+02 3.24563049e+02 3.23940063e+02 3.25028564e+02 3.23998840e+02 3.23460419e+02 3.23007080e+02 3.23107208e+02 3.22743927e+02 3.22316620e+02 3.22402802e+02 3.22651428e+02 3.23029205e+02 3.22961487e+02 3.22922302e+02 3.22658875e+02 3.22654724e+02 3.22506073e+02 3.22423401e+02 3.23116882e+02 3.23283325e+02 3.23832855e+02 3.23636780e+02 3.24062164e+02 3.24045166e+02 3.23683868e+02 3.24167328e+02 3.24379364e+02 3.25225586e+02 3.24389465e+02 3.23394806e+02 3.22216858e+02 3.22683105e+02 3.23485504e+02 3.23127014e+02 3.22460083e+02 3.22549133e+02 3.23496857e+02 3.24073242e+02 3.24270905e+02 3.24506012e+02 3.24754608e+02 3.24803558e+02 3.25553528e+02 3.26290405e+02 3.26935486e+02 3.27165924e+02 3.26026581e+02 3.25306061e+02 3.24375397e+02 3.24295135e+02 3.24001373e+02 3.22591125e+02 3.22386688e+02 3.21450867e+02 3.21896606e+02 3.21553192e+02 3.22418213e+02 3.22190887e+02 3.21956177e+02 3.22151245e+02 3.23067200e+02 3.23917023e+02 3.23749603e+02 3.23707397e+02 3.23145905e+02 3.22611359e+02 3.22017273e+02 3.21928314e+02 3.21867889e+02 3.21884003e+02 3.21881927e+02 3.21849335e+02 3.21708923e+02 3.21610596e+02 3.22017456e+02 3.22430817e+02 3.22851227e+02 3.22807465e+02 3.22788025e+02 3.23561066e+02 3.23832367e+02 3.24129669e+02 3.23475525e+02 3.23090820e+02 3.22647858e+02 3.22429016e+02 3.22376740e+02 3.22412659e+02 3.22445587e+02 3.22435120e+02 3.21412781e+02 3.20337158e+02 3.19243469e+02 3.19084167e+02 3.18987671e+02 3.18935272e+02 3.18987518e+02 3.18923218e+02 3.18951599e+02 3.18948792e+02 3.19073364e+02 3.19099243e+02 3.19035309e+02 3.19034393e+02 3.18840179e+02 3.18735443e+02 3.18627563e+02 3.18663910e+02 3.18523529e+02 3.18585022e+02 3.19298584e+02 3.19377869e+02 3.19948608e+02 3.20219818e+02 3.21260284e+02 3.21535004e+02 3.21549683e+02 3.21565247e+02 3.21477539e+02 3.21303375e+02 3.21197968e+02 3.21263062e+02 3.21319611e+02 3.21371552e+02 3.21426117e+02 3.21513947e+02 3.21450287e+02 3.21272888e+02 3.20978485e+02 3.20723755e+02 3.20672821e+02 3.20675659e+02 3.20739899e+02 3.20655365e+02 3.20577881e+02 3.20469360e+02 3.20499573e+02 3.20406311e+02 3.20442413e+02 3.20412689e+02 3.20512695e+02 3.20522522e+02 3.20475494e+02 3.20379669e+02 3.20326508e+02 3.20369263e+02 3.20476929e+02 3.20384247e+02 3.20250793e+02 3.20179138e+02 3.20529694e+02 3.20994629e+02 3.21288330e+02 3.21479279e+02 3.21596069e+02 3.21720947e+02 3.21730255e+02 3.21450012e+02 3.21266998e+02 3.21009430e+02 3.20990479e+02 3.20707275e+02 3.20510376e+02 3.20445343e+02 3.20639618e+02 3.20960236e+02 3.21054993e+02 3.21288696e+02 3.21329590e+02 3.21425781e+02 3.21278351e+02 3.21423248e+02 3.21574219e+02 3.21524231e+02 3.21157349e+02 3.20834381e+02 3.20972900e+02 3.21381958e+02 3.21838165e+02 3.22139160e+02 3.21125366e+02 3.20841949e+02 3.21233002e+02 3.21912903e+02 3.21900208e+02 3.21058746e+02 3.21043030e+02 3.21114105e+02 3.22701599e+02 3.24100739e+02 3.25692261e+02 3.26006012e+02 3.26820526e+02 3.27312042e+02 3.27816925e+02 3.27960663e+02 3.28127106e+02 3.28094849e+02 3.28165405e+02 3.28751801e+02 3.29386810e+02 3.29960175e+02 3.29549255e+02 3.29716583e+02 3.29995483e+02 3.31096100e+02 3.31468964e+02 3.31350922e+02 3.30990082e+02 3.31093536e+02 3.31192780e+02 3.30870819e+02 3.29589539e+02 3.29835083e+02 3.30690857e+02 3.32171875e+02 3.32819366e+02 3.33808105e+02 3.36457733e+02 3.38710663e+02 4.90038635e+02 9.60519104e+02 -1146913920. -88574816. 129624400. 9911235. 3.86238850e+06 191571104. -1206839168. -44493768. -44493768. -44493768. 0. 0. 0. 0. 4.28504650e+06 -1.70963350e+06 -1.70963350e+06 -96096512. 0. 0. 0. -177690400. -126507040. 6.18612158e+03 -2.03200888e+06 -6.12790125e+05 -4.68008192e+09 -4.68008192e+09 -4.68008192e+09 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 613662912. 613662912. 57775660. -107318328. -107318328. 0. 0. 0. 0. 0. 0. 0. -644726848. -644726848. -644726848. 0. 0. 0. 0. 0. 388357600. 388357600. 388357600. 0. 0. 0. 0. 0. 0. -228319488. 47409152. -240967888. -89658736. 3.55800598e+02 2.14881409e+02 2.15944427e+02 3.13423065e+02 3.16290405e+02 3.17496490e+02 3.19035889e+02 3.20799316e+02 3.22952759e+02 3.24930695e+02 3.26652100e+02 3.27767029e+02 3.27842163e+02 3.28123047e+02 3.27861176e+02 3.28095428e+02 3.28753021e+02 3.29006897e+02 3.29504608e+02 3.29448273e+02 3.30469238e+02 3.30999695e+02 3.30660645e+02 3.29912079e+02 3.29393768e+02 3.28815430e+02 3.29222351e+02 3.29750854e+02 3.30886108e+02 3.30841309e+02 3.31088470e+02 3.31379272e+02 3.32304443e+02 3.32253204e+02 3.31777740e+02 3.30883850e+02 3.31156464e+02 3.31147766e+02 3.31241882e+02 3.30605804e+02 3.30526245e+02 3.30345428e+02 3.29617950e+02 3.28052063e+02 3.26971497e+02 3.26454224e+02 3.27060944e+02 3.26970947e+02 3.26968842e+02 3.26176239e+02 3.25930115e+02 3.26600555e+02 3.27002686e+02 3.27662445e+02 3.27753448e+02 3.27380768e+02 3.27254303e+02 3.26639130e+02 3.27530273e+02 3.27738007e+02 3.27995941e+02 3.27923920e+02 3.29003662e+02 3.29911194e+02 3.30853912e+02 3.30784119e+02 3.30873260e+02 3.29296387e+02 3.29898041e+02 3.28577332e+02 3.29123993e+02 3.27162781e+02 3.26874268e+02 3.26450806e+02 3.25601410e+02 3.25405334e+02 3.25010925e+02 3.25367310e+02 3.25476868e+02 3.25324127e+02 3.25114685e+02 3.24641663e+02 3.24835815e+02 3.24930603e+02 3.25459625e+02 3.25741913e+02 3.26102173e+02 3.26111084e+02 3.26208191e+02 3.25922852e+02 3.25554413e+02 3.25397583e+02 3.25537354e+02 3.25686401e+02 3.25366150e+02 3.25207336e+02 3.25277832e+02 3.25657928e+02 3.25968719e+02 3.26589844e+02 3.26102661e+02 3.25984497e+02 3.25721466e+02 3.26172729e+02 3.26460327e+02 3.26427307e+02 3.26730835e+02 3.26622650e+02 3.26526306e+02 3.26579407e+02 3.26424927e+02 3.25832520e+02 3.25282623e+02 3.24210175e+02 3.24141418e+02 3.23943695e+02 3.25128326e+02 3.25630554e+02 3.26044617e+02 3.25917755e+02 3.25752106e+02 3.25673401e+02 3.25552460e+02 3.25345856e+02 3.25123718e+02 3.25622803e+02 3.26289154e+02 3.27173218e+02 3.27760376e+02 3.28112976e+02 3.28473389e+02 3.28572723e+02 3.28646973e+02 3.28722137e+02 3.28720490e+02 3.28562683e+02 3.28193237e+02 3.27561493e+02 3.27979095e+02 3.27965485e+02 3.27811707e+02 3.27414093e+02 3.62256531e+02 3.93442200e+02 3.92991943e+02 3.51721832e+02 3.26798920e+02 3.29768860e+02 3.30572205e+02 3.26101685e+02 3.12156616e+02 3.43859131e+02 3.67271912e+02 3.94384918e+02 3.53475464e+02 3.37129364e+02 3.36209137e+02 3.35481720e+02 3.35502625e+02 3.35430847e+02 3.36100922e+02 3.40952393e+02 3.86521759e+02 4.44191711e+02 7.01499573e+02 1.36846973e+03 5.65311951e+02 6.11161438e+02 7.23811890e+02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 514824480. 514824480. 514824480. 0. 0. 0. -249928368. -249928368. -249928368. 0. 0. 0. 0. 0. 0. 0. 0. -196883104. 123094560. 71258016. 12678263. 28554452. 96583552. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 389928864. 389928864. 389928864. 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. 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. 0. 0. 0. 0. 0. 0. 0. 149523424. 149523424. 78567496. -266180128. -266180128. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral/ring16_v.xml ================================================ 16 1024
"3f"
0. 0. 0. -9.63813484e-01 3.63323977e-03 2.66421467e-01 -9.63797629e-01 9.54693928e-03 2.66419470e-01 -9.63652015e-01 1.54604949e-02 2.66413361e-01 -9.63578522e-01 2.13731918e-02 2.66420275e-01 -9.63400185e-01 2.72852145e-02 2.66423613e-01 -9.63275313e-01 3.31958644e-02 2.66415924e-01 -9.63029623e-01 3.91050652e-02 2.66454279e-01 -9.62805629e-01 4.50142249e-02 2.66399860e-01 -9.62461770e-01 5.09211160e-02 2.66402721e-01 -9.62163150e-01 5.68260811e-02 2.66386539e-01 -9.61766183e-01 6.27293885e-02 2.66382307e-01 -9.61414337e-01 6.86294064e-02 2.66344875e-01 -9.60958183e-01 7.45270550e-02 2.66346604e-01 -9.60495174e-01 8.04243535e-02 2.66315669e-01 -9.60017145e-01 8.63168240e-02 2.66292632e-01 -9.59403634e-01 9.22058150e-02 2.66273379e-01 -9.58866417e-01 9.80910435e-02 2.66255230e-01 -9.58222032e-01 1.03973404e-01 2.66244084e-01 -9.57568347e-01 1.09852940e-01 2.66243219e-01 -9.56868351e-01 1.15724966e-01 2.66235024e-01 -9.56159055e-01 1.21592037e-01 2.66234040e-01 -9.55397248e-01 1.27458751e-01 2.66237497e-01 -9.54621315e-01 1.33320421e-01 2.66238242e-01 -9.53753054e-01 1.39175832e-01 2.66233593e-01 -9.52870488e-01 1.45023301e-01 2.66229182e-01 -9.51965213e-01 1.50861651e-01 2.66219139e-01 -9.51029241e-01 1.56711400e-01 2.66197443e-01 -9.50055480e-01 1.62540764e-01 2.66204655e-01 -9.49052513e-01 1.68364793e-01 2.66218007e-01 -9.48035181e-01 1.74187377e-01 2.66230077e-01 -9.46930707e-01 1.79997951e-01 2.66227335e-01 -9.45768654e-01 1.85806543e-01 2.66238868e-01 -9.44602370e-01 1.91608936e-01 2.66216129e-01 -9.43425417e-01 1.97399020e-01 2.66207129e-01 -9.42234933e-01 2.03185141e-01 2.66194403e-01 -9.40991044e-01 2.08967194e-01 2.66189694e-01 -9.39658642e-01 2.14738384e-01 2.66170233e-01 -9.38321233e-01 2.20502242e-01 2.66157955e-01 -9.37005877e-01 2.26249516e-01 2.66137153e-01 -9.35592234e-01 2.31996149e-01 2.66147733e-01 -9.34100032e-01 2.37733215e-01 2.66157717e-01 -9.32618499e-01 2.43465111e-01 2.66152620e-01 -9.31132913e-01 2.49171481e-01 2.66167015e-01 -9.29556966e-01 2.54878879e-01 2.66158640e-01 -9.27978516e-01 2.60584056e-01 2.66171277e-01 -9.26409960e-01 2.66277432e-01 2.66158491e-01 -9.24760163e-01 2.71948487e-01 2.66166061e-01 -9.23032701e-01 2.77621478e-01 2.66183168e-01 -9.21301603e-01 2.83280969e-01 2.66186833e-01 -9.19578016e-01 2.88928092e-01 2.66193330e-01 -9.17772532e-01 2.94564724e-01 2.66175359e-01 -9.15923774e-01 3.00184816e-01 2.66160518e-01 -9.14092839e-01 3.05812120e-01 2.66134620e-01 -9.12207127e-01 3.11419874e-01 2.66136825e-01 -9.10257876e-01 3.17006201e-01 2.66131014e-01 -9.08351421e-01 3.22590470e-01 2.66132563e-01 -9.06324446e-01 3.28142673e-01 2.66133696e-01 -9.04310524e-01 3.33708704e-01 2.66128033e-01 -9.02248859e-01 3.39244038e-01 2.66122609e-01 -9.00139928e-01 3.44774723e-01 2.66115159e-01 -8.98018837e-01 3.50295812e-01 2.66111672e-01 -8.95841837e-01 3.55792522e-01 2.66126871e-01 -8.93629074e-01 3.61294657e-01 2.66111284e-01 -8.91417980e-01 3.66764486e-01 2.66115189e-01 -8.89099240e-01 3.72228563e-01 2.66116381e-01 -8.86817694e-01 3.77672255e-01 2.66120762e-01 -8.84526491e-01 3.83103579e-01 2.66128957e-01 -8.82103741e-01 3.88524026e-01 2.66159356e-01 -8.79716516e-01 3.93926024e-01 2.66159147e-01 -8.77297759e-01 3.99317265e-01 2.66164482e-01 -8.74801040e-01 4.04693961e-01 2.66187131e-01 -8.72332215e-01 4.10049051e-01 2.66197532e-01 -8.69766355e-01 4.15395558e-01 2.66191512e-01 -8.67198348e-01 4.20731455e-01 2.66162425e-01 -8.64595652e-01 4.26033348e-01 2.66171008e-01 -8.62002969e-01 4.31329697e-01 2.66161025e-01 -8.59340608e-01 4.36617047e-01 2.66158402e-01 -8.56614292e-01 4.41900700e-01 2.66141981e-01 -8.53929877e-01 4.47126925e-01 2.66138852e-01 -8.51171076e-01 4.52378869e-01 2.66126633e-01 -8.48363936e-01 4.57572371e-01 2.66120791e-01 -8.45533729e-01 4.62765425e-01 2.66147077e-01 -8.42689455e-01 4.67941701e-01 2.66166985e-01 -8.39798689e-01 4.73100215e-01 2.66182363e-01 -8.36839914e-01 4.78256941e-01 2.66226530e-01 -8.33889723e-01 4.83357757e-01 2.66306996e-01 -8.30833554e-01 4.88426089e-01 2.66599566e-01 -8.27514648e-01 4.93318707e-01 2.67859071e-01 -8.22978795e-01 4.97426808e-01 2.74143249e-01 -8.20421338e-01 5.02799869e-01 2.72091687e-01 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. 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. -7.58042037e-01 5.96214890e-01 2.64379382e-01 -7.54555643e-01 6.01011157e-01 2.63490885e-01 -7.51101851e-01 6.05839431e-01 2.62292296e-01 -7.47369051e-01 6.10412180e-01 2.62368977e-01 -7.43604660e-01 6.14992201e-01 2.62376964e-01 -7.39824414e-01 6.19559824e-01 2.62357026e-01 -7.35629678e-01 6.23757064e-01 2.64020979e-01 -7.31052697e-01 6.27578676e-01 2.67588943e-01 -7.27490664e-01 6.32315755e-01 2.66193002e-01 -7.23668218e-01 6.36822701e-01 2.65912294e-01 -7.19721019e-01 6.41270518e-01 2.65871704e-01 -7.15790927e-01 6.45671606e-01 2.65854806e-01 -7.11810648e-01 6.50058031e-01 2.65854388e-01 -7.07807064e-01 6.54415786e-01 2.65864402e-01 -7.03784347e-01 6.58730149e-01 2.65871257e-01 -6.99715853e-01 6.63046181e-01 2.65866429e-01 -6.95626915e-01 6.67318285e-01 2.65890300e-01 -6.91538095e-01 6.71563148e-01 2.65902162e-01 -6.87378764e-01 6.75791562e-01 2.65928656e-01 -6.83225214e-01 6.80003226e-01 2.65942812e-01 -6.79036736e-01 6.84192836e-01 2.65961796e-01 -6.74843550e-01 6.88347578e-01 2.65895277e-01 -6.70897067e-01 6.92783952e-01 2.64396131e-01 -6.66808724e-01 6.97080433e-01 2.63522595e-01 -6.62686467e-01 7.01371670e-01 2.62502521e-01 -6.58364177e-01 7.05430329e-01 2.62496412e-01 -6.54066980e-01 7.09452748e-01 2.62447864e-01 -6.49682522e-01 7.13439822e-01 2.62522250e-01 -6.45189643e-01 7.17353880e-01 2.62904584e-01 -6.40557826e-01 7.20978618e-01 2.64270782e-01 -6.35744989e-01 7.24482596e-01 2.66222835e-01 -6.30991518e-01 7.28002012e-01 2.67886639e-01 -6.26256287e-01 7.31531799e-01 2.69345850e-01 -6.21817172e-01 7.35427082e-01 2.69073933e-01 -6.17368162e-01 7.39324212e-01 2.68596441e-01 -6.12975836e-01 7.43276179e-01 2.67771691e-01 -6.08591974e-01 7.47270048e-01 2.66704559e-01 -6.04191124e-01 7.51278520e-01 2.65505284e-01 -5.99658906e-01 7.55086839e-01 2.64922649e-01 -5.95188618e-01 7.58965552e-01 2.63945669e-01 -5.90599418e-01 7.62746811e-01 2.63369769e-01 -5.86026669e-01 7.66495705e-01 2.62820542e-01 -5.81308842e-01 7.70070732e-01 2.62736022e-01 -5.76368988e-01 7.73368955e-01 2.63913929e-01 -5.71481347e-01 7.76630342e-01 2.64922857e-01 -5.66601336e-01 7.80021608e-01 2.65444636e-01 -5.61790645e-01 7.83457041e-01 2.65668631e-01 -5.56974888e-01 7.86867261e-01 2.65647680e-01 -5.52109897e-01 7.90294945e-01 2.65654713e-01 -5.47257185e-01 7.93628752e-01 2.65666723e-01 -5.42383552e-01 7.96980321e-01 2.65679836e-01 -5.37469268e-01 8.00282955e-01 2.65707552e-01 -5.32525241e-01 8.03542852e-01 2.65813500e-01 -5.27559340e-01 8.06749344e-01 2.65967131e-01 -5.22562563e-01 8.09927762e-01 2.66234070e-01 -5.17546952e-01 8.13010931e-01 2.66662717e-01 -5.12443423e-01 8.16014647e-01 2.67318040e-01 -5.07370532e-01 8.19040358e-01 2.67707109e-01 -5.02363980e-01 8.22190106e-01 2.67566562e-01 -4.97317493e-01 8.25271130e-01 2.67488420e-01 -4.92254436e-01 8.28314543e-01 2.67381847e-01 -4.87203687e-01 8.31409097e-01 2.67047465e-01 -4.82153863e-01 8.34494352e-01 2.66563714e-01 -4.77081269e-01 8.37530673e-01 2.66161621e-01 -4.71982151e-01 8.40544939e-01 2.65861005e-01 -4.66819316e-01 8.43457997e-01 2.65769422e-01 -4.61648077e-01 8.46323729e-01 2.65712261e-01 -4.56444234e-01 8.49139929e-01 2.65706629e-01 -4.51213092e-01 8.51909757e-01 2.65689522e-01 -4.45996165e-01 8.54638338e-01 2.65703052e-01 -4.40730929e-01 8.57388735e-01 2.65715271e-01 -4.35445696e-01 8.60042334e-01 2.65716672e-01 -4.30179536e-01 8.62731099e-01 2.65704006e-01 -4.24868226e-01 8.65365148e-01 2.65703887e-01 -4.19551849e-01 8.67955446e-01 2.65698284e-01 -4.14226294e-01 8.70499611e-01 2.65703619e-01 -4.08880532e-01 8.73000979e-01 2.65702635e-01 -4.03514147e-01 8.75517190e-01 2.65709996e-01 -3.98133874e-01 8.77944648e-01 2.65701741e-01 -3.92728388e-01 8.80391479e-01 2.65698731e-01 -3.87318522e-01 8.82813931e-01 2.65691012e-01 -3.81895572e-01 8.85164320e-01 2.65701324e-01 -3.76476914e-01 8.87509406e-01 2.65684724e-01 -3.71026307e-01 8.89792442e-01 2.65677631e-01 -3.65542084e-01 8.92015338e-01 2.65682131e-01 -3.60080898e-01 8.94273102e-01 2.65673131e-01 -3.54587048e-01 8.96473050e-01 2.65666127e-01 -3.49067628e-01 8.98598254e-01 2.65671700e-01 -3.43538582e-01 9.00720239e-01 2.65679806e-01 -3.38008255e-01 9.02831137e-01 2.65665650e-01 -3.32472861e-01 9.04930592e-01 2.65659750e-01 -3.26911509e-01 9.06889915e-01 2.65669316e-01 -3.21348220e-01 9.08932805e-01 2.65665710e-01 -3.15762132e-01 9.10836041e-01 2.65665412e-01 -3.10172856e-01 9.12769258e-01 2.65664816e-01 -3.04560810e-01 9.14650857e-01 2.65674293e-01 -2.98936337e-01 9.16494787e-01 2.65668035e-01 -2.93307573e-01 9.18345392e-01 2.65683383e-01 -2.87671179e-01 9.20079589e-01 2.65679359e-01 -2.82015651e-01 9.21874523e-01 2.65690744e-01 -2.76348799e-01 9.23549056e-01 2.65697181e-01 -2.70688504e-01 9.25238729e-01 2.65700489e-01 -2.64995575e-01 9.26847458e-01 2.65706927e-01 -2.59311706e-01 9.28478897e-01 2.65714169e-01 -2.53612161e-01 9.30107355e-01 2.65709728e-01 -2.47900322e-01 9.31599200e-01 2.65687704e-01 -2.42173791e-01 9.33136106e-01 2.65679747e-01 -2.36448988e-01 9.34601128e-01 2.65680820e-01 -2.30706081e-01 9.36016500e-01 2.65684187e-01 -2.24959344e-01 9.37429190e-01 2.65671581e-01 -2.19208136e-01 9.38788652e-01 2.65675515e-01 -2.13442236e-01 9.40082908e-01 2.65683740e-01 -2.07672030e-01 9.41417754e-01 2.65676916e-01 -2.01887563e-01 9.42625940e-01 2.65668631e-01 -1.96093291e-01 9.43850517e-01 2.65679121e-01 -1.90302625e-01 9.45029557e-01 2.65672266e-01 -1.84498921e-01 9.46196795e-01 2.65657604e-01 -1.78692847e-01 9.47322369e-01 2.65649974e-01 -1.72879443e-01 9.48440909e-01 2.65639991e-01 -1.67054757e-01 9.49445784e-01 2.65642405e-01 -1.61226645e-01 9.50442791e-01 2.65636563e-01 -1.55391917e-01 9.51396644e-01 2.65636593e-01 -1.49550572e-01 9.52334702e-01 2.65649587e-01 -1.43703341e-01 9.53260183e-01 2.65651256e-01 -1.37853205e-01 9.54147756e-01 2.65648395e-01 -1.31995335e-01 9.54923570e-01 2.65652269e-01 -1.26132041e-01 9.55780029e-01 2.65657574e-01 -1.20264620e-01 9.56499934e-01 2.65657634e-01 -1.14391811e-01 9.57211971e-01 2.65645325e-01 -1.08521342e-01 9.57915366e-01 2.65640587e-01 -1.02638744e-01 9.58567739e-01 2.65646785e-01 -9.67551768e-02 9.59147692e-01 2.65640706e-01 -9.08691138e-02 9.59780812e-01 2.65647143e-01 -8.49776193e-02 9.60271716e-01 2.65644729e-01 -7.90850073e-02 9.60755587e-01 2.65643746e-01 -7.31868520e-02 9.61227596e-01 2.65636384e-01 -6.72876090e-02 9.61684644e-01 2.65637934e-01 -6.13855459e-02 9.62097883e-01 2.65646517e-01 -5.54822646e-02 9.62401688e-01 2.65652955e-01 -4.95744385e-02 9.62793291e-01 2.65643775e-01 -4.36662883e-02 9.63081837e-01 2.65633732e-01 -3.77569422e-02 9.63323653e-01 2.65622646e-01 -3.18452641e-02 9.63555396e-01 2.65626699e-01 -2.59326082e-02 9.63740289e-01 2.65621334e-01 -2.00189948e-02 9.63811040e-01 2.65631974e-01 -1.41047202e-02 9.63973522e-01 2.65631884e-01 -8.18978716e-03 9.64026392e-01 2.65634924e-01 -2.27454607e-03 9.64042246e-01 2.65623778e-01 3.64072993e-03 9.64042485e-01 2.65622288e-01 9.55591723e-03 9.64027345e-01 2.65620738e-01 1.54706845e-02 9.63877380e-01 2.65619278e-01 2.13853493e-02 9.63813066e-01 2.65597850e-01 2.72988454e-02 9.63634074e-01 2.65597016e-01 3.32112238e-02 9.63515997e-01 2.65586674e-01 3.91224474e-02 9.63278770e-01 2.65593916e-01 4.50313240e-02 9.63041544e-01 2.65587658e-01 5.09403311e-02 9.62691784e-01 2.65588760e-01 5.68455495e-02 9.62391317e-01 2.65586346e-01 6.27500415e-02 9.61986661e-01 2.65595734e-01 6.86511919e-02 9.61631358e-01 2.65592456e-01 7.45496899e-02 9.61174190e-01 2.65590012e-01 8.04464146e-02 9.60704386e-01 2.65584469e-01 8.63409042e-02 9.60217655e-01 2.65588671e-01 9.22290236e-02 9.59592998e-01 2.65599132e-01 9.81148481e-02 9.59052384e-01 2.65600950e-01 1.03998192e-01 9.58404303e-01 2.65595376e-01 1.09879434e-01 9.57750857e-01 2.65590578e-01 1.15750335e-01 9.57046270e-01 2.65589565e-01 1.21619813e-01 9.56339240e-01 2.65582591e-01 1.27486348e-01 9.55579519e-01 2.65588373e-01 1.33349404e-01 9.54808831e-01 2.65583873e-01 1.39206991e-01 9.53936040e-01 2.65578181e-01 1.45055667e-01 9.53050196e-01 2.65577048e-01 1.50899440e-01 9.52140808e-01 2.65579045e-01 1.56744897e-01 9.51196730e-01 2.65580356e-01 1.62574872e-01 9.50229406e-01 2.65565276e-01 1.68401048e-01 9.49235082e-01 2.65563071e-01 1.74222559e-01 9.48223352e-01 2.65562356e-01 1.80042192e-01 9.47115958e-01 2.65555352e-01 1.85847834e-01 9.45957363e-01 2.65552104e-01 1.91647097e-01 9.44780588e-01 2.65565813e-01 1.97440833e-01 9.43602145e-01 2.65562296e-01 2.03228176e-01 9.42408442e-01 2.65566826e-01 2.09004641e-01 9.41163003e-01 2.65570670e-01 2.14777380e-01 9.39816058e-01 2.65581399e-01 2.20537782e-01 9.38474596e-01 2.65580982e-01 2.26290226e-01 9.37151730e-01 2.65589058e-01 2.32038066e-01 9.35744941e-01 2.65580833e-01 2.37774700e-01 9.34255302e-01 2.65569001e-01 2.43506655e-01 9.32773113e-01 2.65570492e-01 2.49224856e-01 9.31296945e-01 2.65543699e-01 2.54933417e-01 9.29720879e-01 2.65537828e-01 2.60637194e-01 9.28141177e-01 2.65546978e-01 2.66328722e-01 9.26572859e-01 2.65549451e-01 2.71999359e-01 9.24923182e-01 2.65551776e-01 2.77678102e-01 9.23194170e-01 2.65557647e-01 2.83343613e-01 9.21468735e-01 2.65544295e-01 2.88993061e-01 9.19749677e-01 2.65540510e-01 2.94625372e-01 9.17939186e-01 2.65535295e-01 3.00241977e-01 9.16077673e-01 2.65523046e-01 3.05872291e-01 9.14249599e-01 2.65519410e-01 3.11475277e-01 9.12362993e-01 2.65529126e-01 3.17064673e-01 9.10414457e-01 2.65523612e-01 3.22654724e-01 9.08511281e-01 2.65523523e-01 3.28204244e-01 9.06483889e-01 2.65516549e-01 3.33771884e-01 9.04471457e-01 2.65509248e-01 3.39311004e-01 9.02414382e-01 2.65473247e-01 3.44840646e-01 9.00302768e-01 2.65476853e-01 3.50368798e-01 8.98189545e-01 2.65447736e-01 3.55866790e-01 8.96018326e-01 2.65439808e-01 3.61377776e-01 8.93801808e-01 2.65425146e-01 3.66840780e-01 8.91591728e-01 2.65432954e-01 3.72315139e-01 8.89273524e-01 2.65426397e-01 3.77753347e-01 8.86992633e-01 2.65419930e-01 3.83195668e-01 8.84716272e-01 2.65399188e-01 3.88614923e-01 8.82294178e-01 2.65395373e-01 3.94023031e-01 8.79885316e-01 2.65397966e-01 3.99409920e-01 8.77490759e-01 2.65398473e-01 4.04805630e-01 8.74996543e-01 2.65393168e-01 4.10149843e-01 8.72534156e-01 2.65397340e-01 4.15498883e-01 8.69963586e-01 2.65402555e-01 4.20828164e-01 8.67386520e-01 2.65402704e-01 4.26134408e-01 8.64791870e-01 2.65383065e-01 4.31432068e-01 8.62198889e-01 2.65371829e-01 4.36721623e-01 8.59539747e-01 2.65368581e-01 4.42008525e-01 8.56807292e-01 2.65360385e-01 4.47231233e-01 8.54126513e-01 2.65363425e-01 4.52487260e-01 8.51362348e-01 2.65354812e-01 4.57677603e-01 8.48550379e-01 2.65363067e-01 4.62877840e-01 8.45726311e-01 2.65364319e-01 4.68058646e-01 8.42889428e-01 2.65351295e-01 4.73227024e-01 8.40004504e-01 2.65352696e-01 4.78384286e-01 8.37039232e-01 2.65347987e-01 4.83506560e-01 8.34127069e-01 2.65340924e-01 4.88617778e-01 8.31136525e-01 2.65343100e-01 4.93685633e-01 8.28094542e-01 2.65352070e-01 4.98774171e-01 8.25050235e-01 2.65352458e-01 5.03811598e-01 8.21975946e-01 2.65351951e-01 5.08863270e-01 8.18897545e-01 2.65344292e-01 5.13885677e-01 8.15764785e-01 2.65340805e-01 5.18869936e-01 8.12577963e-01 2.65333503e-01 5.23845673e-01 8.09410810e-01 2.65316039e-01 5.28796852e-01 8.06178093e-01 2.65315711e-01 5.33736229e-01 8.02900195e-01 2.65315294e-01 5.38649201e-01 7.99606264e-01 2.65310854e-01 5.43571889e-01 7.96309531e-01 2.65307903e-01 5.48418581e-01 7.92947471e-01 2.65314698e-01 5.53277135e-01 7.89564192e-01 2.65306741e-01 5.58130145e-01 7.86171734e-01 2.65306950e-01 5.62926769e-01 7.82693386e-01 2.65306681e-01 5.67717016e-01 7.79231012e-01 2.65311420e-01 5.72515547e-01 7.75753736e-01 2.65298814e-01 5.77249467e-01 7.72223294e-01 2.65302747e-01 5.81964970e-01 7.68687189e-01 2.65298933e-01 5.86671352e-01 7.65089571e-01 2.65290737e-01 5.91374397e-01 7.61475265e-01 2.65291333e-01 5.96054494e-01 7.57818222e-01 2.65283197e-01 6.00666523e-01 7.54165232e-01 2.65288740e-01 6.05271101e-01 7.50442505e-01 2.65277356e-01 6.09870732e-01 7.46736646e-01 2.65271872e-01 6.14447474e-01 7.42974699e-01 2.65268654e-01 6.19011879e-01 7.39167094e-01 2.65273213e-01 6.23521328e-01 7.35361874e-01 2.65263557e-01 6.28017426e-01 7.31528163e-01 2.65262038e-01 6.32492363e-01 7.27675736e-01 2.65263647e-01 6.36944532e-01 7.23800302e-01 2.65258133e-01 6.41391456e-01 7.19845355e-01 2.65249252e-01 6.45788252e-01 7.15912580e-01 2.65247166e-01 6.50181174e-01 7.11931944e-01 2.65248835e-01 6.54549718e-01 7.07931519e-01 2.65243292e-01 6.58855319e-01 7.03908563e-01 2.65242815e-01 6.63167119e-01 6.99838102e-01 2.65251160e-01 6.67448997e-01 6.95748866e-01 2.65236825e-01 6.71694160e-01 6.91670120e-01 2.65238434e-01 6.75933003e-01 6.87507272e-01 2.65229821e-01 6.80147588e-01 6.83361113e-01 2.65227824e-01 6.84339881e-01 6.79168224e-01 2.65224338e-01 6.88496292e-01 6.74969852e-01 2.65216798e-01 6.92622006e-01 6.70735359e-01 2.65209645e-01 6.96724653e-01 6.66454732e-01 2.65208274e-01 7.00813353e-01 6.62187696e-01 2.65201658e-01 7.04838276e-01 6.57853663e-01 2.65204132e-01 7.08877563e-01 6.53552353e-01 2.65199840e-01 7.12879241e-01 6.49177551e-01 2.65194803e-01 7.16845930e-01 6.44781888e-01 2.65186697e-01 7.20780849e-01 6.40393853e-01 2.65182495e-01 7.24728107e-01 6.35947287e-01 2.65179843e-01 7.28601396e-01 6.31482899e-01 2.65174836e-01 7.32450902e-01 6.27005577e-01 2.65168816e-01 7.36299813e-01 6.22517586e-01 2.65166104e-01 7.40084827e-01 6.17960811e-01 2.65169978e-01 7.43854821e-01 6.13431156e-01 2.65166700e-01 7.47614086e-01 6.08865976e-01 2.65169084e-01 7.51362085e-01 6.04255378e-01 2.65165031e-01 7.55045891e-01 5.99611759e-01 2.65158832e-01 7.58686244e-01 5.94985843e-01 2.65156388e-01 7.62347698e-01 5.90304613e-01 2.65154034e-01 7.65961587e-01 5.85610271e-01 2.65154332e-01 7.69508123e-01 5.80898166e-01 2.65167624e-01 7.73082793e-01 5.76170325e-01 2.65170068e-01 7.76571751e-01 5.71441591e-01 2.65171736e-01 7.80080676e-01 5.66640496e-01 2.65181214e-01 7.83571005e-01 5.61862886e-01 2.65184045e-01 7.86972821e-01 5.57046771e-01 2.65186667e-01 7.90401161e-01 5.52182138e-01 2.65186548e-01 7.93736041e-01 5.47331214e-01 2.65192360e-01 7.97091365e-01 5.42458355e-01 2.65199065e-01 8.00401866e-01 5.37547171e-01 2.65186876e-01 8.03684950e-01 5.32620728e-01 2.65186042e-01 8.06928813e-01 5.27675807e-01 2.65196353e-01 8.10187638e-01 5.22718072e-01 2.65198678e-01 8.13344777e-01 5.17759442e-01 2.65204996e-01 8.16535890e-01 5.12736678e-01 2.65223533e-01 8.19625556e-01 5.07727981e-01 2.65255451e-01 8.22727859e-01 5.02687991e-01 2.65279710e-01 8.25784445e-01 4.97627795e-01 2.65297413e-01 8.28839242e-01 4.92538899e-01 2.65297920e-01 8.31838906e-01 4.87432927e-01 2.65300095e-01 8.34816873e-01 4.82332200e-01 2.65303433e-01 8.37738574e-01 4.77186680e-01 2.65308976e-01 8.40681553e-01 4.72056746e-01 2.65311778e-01 8.43572915e-01 4.66881990e-01 2.65304267e-01 8.46426845e-01 4.61701900e-01 2.65302271e-01 8.49238753e-01 4.56484765e-01 2.65305638e-01 8.52000177e-01 4.51262563e-01 2.65311420e-01 8.54737997e-01 4.46044862e-01 2.65317082e-01 8.57490063e-01 4.40782368e-01 2.65309036e-01 8.60150397e-01 4.35497582e-01 2.65302241e-01 8.62831414e-01 4.30223763e-01 2.65300095e-01 8.65479469e-01 4.24909651e-01 2.65297264e-01 8.68066788e-01 4.19599384e-01 2.65313834e-01 8.70596170e-01 4.14271116e-01 2.65317947e-01 8.73100579e-01 4.08918887e-01 2.65334636e-01 8.75616193e-01 4.03557867e-01 2.65326142e-01 8.78055513e-01 3.98181170e-01 2.65288740e-01 8.80498409e-01 3.92776519e-01 2.65285701e-01 8.82919192e-01 3.87364119e-01 2.65291542e-01 8.85268331e-01 3.81940931e-01 2.65310079e-01 8.87613356e-01 3.76519024e-01 2.65296221e-01 8.89891386e-01 3.71065170e-01 2.65303373e-01 8.92111480e-01 3.65581214e-01 2.65322655e-01 8.94359529e-01 3.60112906e-01 2.65334070e-01 8.96564245e-01 3.54621857e-01 2.65331507e-01 8.98686051e-01 3.49098504e-01 2.65341491e-01 9.00809109e-01 3.43573183e-01 2.65344679e-01 9.02915120e-01 3.38039130e-01 2.65355915e-01 9.05003548e-01 3.32499772e-01 2.65377432e-01 9.06974137e-01 3.26932669e-01 2.65375733e-01 9.09016848e-01 3.21381599e-01 2.65364766e-01 9.10923064e-01 3.15790653e-01 2.65357286e-01 9.12861526e-01 3.10201317e-01 2.65347213e-01 9.14745927e-01 3.04585755e-01 2.65352398e-01 9.16586757e-01 2.98963070e-01 2.65350968e-01 9.18436468e-01 2.93330163e-01 2.65359819e-01 9.20169115e-01 2.87693053e-01 2.65374482e-01 9.21959460e-01 2.82037318e-01 2.65387356e-01 9.23638582e-01 2.76373863e-01 2.65383124e-01 9.25322413e-01 2.70710617e-01 2.65405655e-01 9.26930666e-01 2.65016496e-01 2.65411317e-01 9.28560674e-01 2.59329647e-01 2.65413314e-01 9.30183589e-01 2.53631651e-01 2.65423715e-01 9.31668222e-01 2.47915387e-01 2.65440792e-01 9.33188438e-01 2.42189854e-01 2.65463561e-01 9.34659243e-01 2.36460805e-01 2.65461117e-01 9.36079025e-01 2.30718240e-01 2.65455484e-01 9.37492907e-01 2.24974081e-01 2.65440047e-01 9.38852310e-01 2.19220757e-01 2.65434086e-01 9.40155685e-01 2.13454589e-01 2.65436828e-01 9.41477835e-01 2.07681969e-01 2.65456200e-01 9.42679405e-01 2.01898441e-01 2.65481710e-01 9.43909228e-01 1.96104094e-01 2.65480191e-01 9.45093393e-01 1.90311462e-01 2.65458822e-01 9.46254134e-01 1.84509546e-01 2.65470684e-01 9.47366774e-01 1.78703353e-01 2.65492946e-01 9.48477328e-01 1.72885790e-01 2.65499532e-01 9.49486196e-01 1.67059422e-01 2.65497714e-01 9.50484872e-01 1.61232203e-01 2.65503317e-01 9.51436639e-01 1.55400038e-01 2.65515119e-01 9.52375829e-01 1.49555460e-01 2.65518308e-01 9.53300476e-01 1.43705085e-01 2.65518486e-01 9.54175174e-01 1.37854859e-01 2.65541881e-01 9.54957187e-01 1.31995440e-01 2.65549093e-01 9.55811977e-01 1.26135513e-01 2.65533566e-01 9.56530154e-01 1.20269924e-01 2.65554726e-01 9.57243204e-01 1.14394426e-01 2.65540302e-01 9.57943201e-01 1.08521387e-01 2.65545666e-01 9.58590448e-01 1.02642819e-01 2.65552074e-01 9.59180415e-01 9.67584103e-02 2.65547723e-01 9.59807515e-01 9.08711255e-02 2.65553981e-01 9.60294962e-01 8.49792734e-02 2.65564799e-01 9.60776329e-01 7.90851936e-02 2.65580982e-01 9.61246490e-01 7.31877685e-02 2.65585005e-01 9.61701453e-01 6.72883540e-02 2.65587449e-01 9.62113261e-01 6.13874346e-02 2.65580058e-01 9.62427616e-01 5.54816760e-02 2.65574127e-01 9.62804258e-01 4.95753661e-02 2.65586257e-01 9.63096797e-01 4.36667800e-02 2.65582711e-01 9.63332117e-01 3.77569422e-02 2.65594780e-01 9.63567495e-01 3.18453088e-02 2.65583515e-01 9.63740826e-01 2.59325337e-02 2.65595168e-01 9.63827431e-01 2.00189110e-02 2.65578210e-01 9.63988602e-01 1.41044101e-02 2.65561521e-01 9.64056909e-01 8.18923768e-03 2.65530288e-01 9.64070678e-01 2.27389461e-03 2.65536547e-01 9.64075446e-01 -3.64173227e-03 2.65518278e-01 9.64059830e-01 -9.55716707e-03 2.65511692e-01 9.63918030e-01 -1.54722519e-02 2.65507162e-01 9.63839889e-01 -2.13864930e-02 2.65517771e-01 9.63656247e-01 -2.72996780e-02 2.65550047e-01 9.63522851e-01 -3.32120657e-02 2.65549064e-01 9.63277817e-01 -3.91224176e-02 2.65585601e-01 9.63040948e-01 -4.50322814e-02 2.65575588e-01 9.62705374e-01 -5.09405620e-02 2.65568107e-01 9.62394059e-01 -5.68471551e-02 2.65585601e-01 9.61998105e-01 -6.27507344e-02 2.65587747e-01 9.61622059e-01 -6.86503127e-02 2.65612334e-01 9.61162269e-01 -7.45486915e-02 2.65622288e-01 9.60689068e-01 -8.04459229e-02 2.65629768e-01 9.60201740e-01 -8.63402039e-02 2.65631020e-01 9.59592044e-01 -9.22291428e-02 2.65622109e-01 9.59049523e-01 -9.81149301e-02 2.65600413e-01 9.58409488e-01 -1.03999078e-01 2.65592426e-01 9.57759023e-01 -1.09880209e-01 2.65596896e-01 9.57053900e-01 -1.15752801e-01 2.65599877e-01 9.56339598e-01 -1.21620104e-01 2.65622526e-01 9.55571294e-01 -1.27484620e-01 2.65634030e-01 9.54794824e-01 -1.33350804e-01 2.65624642e-01 9.53923166e-01 -1.39206022e-01 2.65640140e-01 9.53043938e-01 -1.45056650e-01 2.65638530e-01 9.52131808e-01 -1.50894463e-01 2.65657693e-01 9.51183319e-01 -1.56740591e-01 2.65680194e-01 9.50209200e-01 -1.62570074e-01 2.65673935e-01 9.49201524e-01 -1.68395475e-01 2.65692204e-01 9.48188484e-01 -1.74218580e-01 2.65667796e-01 9.47085142e-01 -1.80037677e-01 2.65671611e-01 9.45929408e-01 -1.85843110e-01 2.65666306e-01 9.44750905e-01 -1.91639602e-01 2.65688151e-01 9.43563461e-01 -1.97432950e-01 2.65711308e-01 9.42361593e-01 -2.03217715e-01 2.65735835e-01 9.41106498e-01 -2.08994985e-01 2.65743136e-01 9.39772308e-01 -2.14763343e-01 2.65753150e-01 9.38422263e-01 -2.20526695e-01 2.65771747e-01 9.37102497e-01 -2.26279601e-01 2.65755028e-01 9.35692310e-01 -2.32028052e-01 2.65752792e-01 9.34215128e-01 -2.37763181e-01 2.65773445e-01 9.32725310e-01 -2.43493587e-01 2.65765756e-01 9.31237459e-01 -2.49211192e-01 2.65753716e-01 9.29664612e-01 -2.54917234e-01 2.65777737e-01 9.28099096e-01 -2.60621309e-01 2.65772700e-01 9.26514924e-01 -2.66311347e-01 2.65751362e-01 9.24871087e-01 -2.71986872e-01 2.65739828e-01 9.23164427e-01 -2.77666897e-01 2.65724927e-01 9.21428621e-01 -2.83324897e-01 2.65720427e-01 9.19701099e-01 -2.88974166e-01 2.65714914e-01 9.17897224e-01 -2.94613302e-01 2.65715539e-01 9.16030824e-01 -3.00228208e-01 2.65738219e-01 9.14206862e-01 -3.05853009e-01 2.65741497e-01 9.12307382e-01 -3.11452627e-01 2.65756011e-01 9.10354435e-01 -3.17042619e-01 2.65774995e-01 9.08449471e-01 -3.22625190e-01 2.65768290e-01 9.06418681e-01 -3.28181326e-01 2.65767068e-01 9.04401779e-01 -3.33749115e-01 2.65764773e-01 9.02352929e-01 -3.39290172e-01 2.65740156e-01 9.00237262e-01 -3.44819665e-01 2.65745133e-01 8.98112535e-01 -3.50338846e-01 2.65764445e-01 8.95932734e-01 -3.55832428e-01 2.65759975e-01 8.93736005e-01 -3.61343145e-01 2.65749067e-01 8.91514063e-01 -3.66812646e-01 2.65752852e-01 8.89201462e-01 -3.72284234e-01 2.65744478e-01 8.86933148e-01 -3.77720445e-01 2.65720129e-01 8.84630561e-01 -3.83161664e-01 2.65712202e-01 8.82229865e-01 -3.88582587e-01 2.65722990e-01 8.79818320e-01 -3.93982351e-01 2.65750349e-01 8.77405584e-01 -3.99368197e-01 2.65757650e-01 8.74922216e-01 -4.04757082e-01 2.65760839e-01 8.72451425e-01 -4.10113305e-01 2.65741259e-01 8.69875014e-01 -4.15455192e-01 2.65774190e-01 8.67300332e-01 -4.20780867e-01 2.65778571e-01 8.64693165e-01 -4.26082462e-01 2.65802890e-01 8.62095535e-01 -4.31378096e-01 2.65811324e-01 8.59416425e-01 -4.36661750e-01 2.65836090e-01 8.56691539e-01 -4.41942185e-01 2.65855163e-01 8.53998542e-01 -4.47173744e-01 2.65839964e-01 8.51241231e-01 -4.52417076e-01 2.65855074e-01 8.48434508e-01 -4.57612127e-01 2.65855670e-01 8.45609009e-01 -4.62813884e-01 2.65858263e-01 8.42760623e-01 -4.67988580e-01 2.65882194e-01 8.39860916e-01 -4.73150402e-01 2.65900582e-01 8.36901724e-01 -4.78298068e-01 2.65948206e-01 8.33968878e-01 -4.83418494e-01 2.65945524e-01 8.31002176e-01 -4.88540858e-01 2.65925825e-01 8.27969551e-01 -4.93608177e-01 2.65911311e-01 8.24935853e-01 -4.98692930e-01 2.65877515e-01 8.21852803e-01 -5.03730714e-01 2.65899271e-01 8.18773091e-01 -5.08787692e-01 2.65885144e-01 8.15633118e-01 -5.13809502e-01 2.65857577e-01 8.12449276e-01 -5.18794656e-01 2.65854180e-01 8.09274435e-01 -5.23764133e-01 2.65850037e-01 8.06053758e-01 -5.28714955e-01 2.65853852e-01 8.02786827e-01 -5.33656895e-01 2.65824229e-01 7.99492538e-01 -5.38572431e-01 2.65821517e-01 7.96190143e-01 -5.43489575e-01 2.65837848e-01 7.92824209e-01 -5.48341095e-01 2.65824586e-01 7.89467812e-01 -5.53196728e-01 2.65816122e-01 7.86065996e-01 -5.58056116e-01 2.65778452e-01 7.82597125e-01 -5.62850654e-01 2.65781552e-01 7.79152036e-01 -5.67648470e-01 2.65754998e-01 7.75646746e-01 -5.72440326e-01 2.65744776e-01 7.72122860e-01 -5.77183843e-01 2.65723258e-01 7.68591583e-01 -5.81901729e-01 2.65698344e-01 7.65020967e-01 -5.86612284e-01 2.65677333e-01 7.61400461e-01 -5.91316760e-01 2.65652806e-01 7.57752538e-01 -5.95988870e-01 2.65663058e-01 7.54086792e-01 -6.00612462e-01 2.65651047e-01 7.50369906e-01 -6.05211377e-01 2.65641093e-01 7.46667385e-01 -6.09798849e-01 2.65650660e-01 7.42902219e-01 -6.14380002e-01 2.65670121e-01 7.39089608e-01 -6.18938386e-01 2.65688539e-01 7.35283315e-01 -6.23447061e-01 2.65645146e-01 7.31440663e-01 -6.27944350e-01 2.65632182e-01 7.27610052e-01 -6.32416904e-01 2.65634477e-01 7.23729193e-01 -6.36878550e-01 2.65591294e-01 7.19783187e-01 -6.41335547e-01 2.65564561e-01 7.15856433e-01 -6.45722091e-01 2.65573293e-01 7.11879313e-01 -6.50124133e-01 2.65569955e-01 7.07881272e-01 -6.54487312e-01 2.65558839e-01 7.03856766e-01 -6.58794165e-01 2.65555710e-01 6.99772656e-01 -6.63109958e-01 2.65594900e-01 6.95668161e-01 -6.67369664e-01 2.65595078e-01 6.91610098e-01 -6.71614528e-01 2.65595853e-01 6.87426507e-01 -6.75849319e-01 2.65593797e-01 6.83282316e-01 -6.80060506e-01 2.65585810e-01 6.79111838e-01 -6.84280217e-01 2.65558004e-01 6.74919307e-01 -6.88429117e-01 2.65543878e-01 6.70683324e-01 -6.92544043e-01 2.65537530e-01 6.66400313e-01 -6.96655273e-01 2.65532106e-01 6.62120879e-01 -7.00749874e-01 2.65525758e-01 6.57790303e-01 -7.04780281e-01 2.65516341e-01 6.53493106e-01 -7.08791792e-01 2.65539974e-01 6.49105906e-01 -7.12791800e-01 2.65539080e-01 6.44711137e-01 -7.16774464e-01 2.65545100e-01 6.40326560e-01 -7.20700920e-01 2.65543133e-01 6.35869563e-01 -7.24641204e-01 2.65553504e-01 6.31413817e-01 -7.28530824e-01 2.65516549e-01 6.26940012e-01 -7.32365191e-01 2.65511125e-01 6.22455776e-01 -7.36223161e-01 2.65501648e-01 6.17902577e-01 -7.40015507e-01 2.65478522e-01 6.13381386e-01 -7.43788660e-01 2.65461236e-01 6.08809888e-01 -7.47547686e-01 2.65455544e-01 6.04208291e-01 -7.51296401e-01 2.65451044e-01 5.99557161e-01 -7.54970908e-01 2.65443891e-01 5.94932377e-01 -7.58620143e-01 2.65447289e-01 5.90250432e-01 -7.62264132e-01 2.65480846e-01 5.85564911e-01 -7.65889466e-01 2.65466124e-01 5.80850542e-01 -7.69443810e-01 2.65453786e-01 5.76122165e-01 -7.73021698e-01 2.65452832e-01 5.71395099e-01 -7.76510954e-01 2.65438497e-01 5.66598237e-01 -7.80023456e-01 2.65422404e-01 5.61824977e-01 -7.83513784e-01 2.65410483e-01 5.57008326e-01 -7.86919653e-01 2.65428483e-01 5.52146435e-01 -7.90342271e-01 2.65429258e-01 5.47290266e-01 -7.93681145e-01 2.65436560e-01 5.42422950e-01 -7.97040582e-01 2.65425712e-01 5.37505746e-01 -8.00347447e-01 2.65434265e-01 5.32583117e-01 -8.03633869e-01 2.65417337e-01 5.27642727e-01 -8.06879342e-01 2.65401542e-01 5.22687674e-01 -8.10134113e-01 2.65414596e-01 5.17721772e-01 -8.13299537e-01 2.65408665e-01 5.12714326e-01 -8.16487312e-01 2.65401781e-01 5.07707715e-01 -8.19589376e-01 2.65402347e-01 5.02670705e-01 -8.22701275e-01 2.65399307e-01 4.97615695e-01 -8.25765729e-01 2.65383720e-01 4.92533535e-01 -8.28821242e-01 2.65380532e-01 4.87426311e-01 -8.31824005e-01 2.65363067e-01 4.82324928e-01 -8.34803462e-01 2.65357733e-01 4.77187186e-01 -8.37731302e-01 2.65340090e-01 4.72051978e-01 -8.40673029e-01 2.65351355e-01 4.66876209e-01 -8.43561292e-01 2.65350819e-01 4.61694658e-01 -8.46410513e-01 2.65363574e-01 4.56478864e-01 -8.49225819e-01 2.65357286e-01 4.51256901e-01 -8.51988196e-01 2.65359342e-01 4.46037561e-01 -8.54724348e-01 2.65374064e-01 4.40775990e-01 -8.57476532e-01 2.65357524e-01 4.35489655e-01 -8.60133052e-01 2.65361249e-01 4.30215359e-01 -8.62810373e-01 2.65371919e-01 4.24898505e-01 -8.65447342e-01 2.65366733e-01 4.19594675e-01 -8.68054152e-01 2.65347987e-01 4.14263397e-01 -8.70580792e-01 2.65363008e-01 4.08910036e-01 -8.73092592e-01 2.65351862e-01 4.03552532e-01 -8.75603795e-01 2.65359998e-01 3.98171872e-01 -8.78033340e-01 2.65360713e-01 3.92764837e-01 -8.80471468e-01 2.65369654e-01 3.87353390e-01 -8.82892191e-01 2.65380651e-01 3.81931394e-01 -8.85245204e-01 2.65385062e-01 3.76510084e-01 -8.87584507e-01 2.65383601e-01 3.71052921e-01 -8.89856935e-01 2.65406340e-01 3.65572065e-01 -8.92088056e-01 2.65390933e-01 3.60106021e-01 -8.94338787e-01 2.65389711e-01 3.54613245e-01 -8.96540642e-01 2.65393972e-01 3.49092573e-01 -8.98663640e-01 2.65403122e-01 3.43565166e-01 -9.00786042e-01 2.65402138e-01 3.38031381e-01 -9.02888596e-01 2.65427262e-01 3.32492560e-01 -9.04985905e-01 2.65430242e-01 3.26924354e-01 -9.06951249e-01 2.65430897e-01 3.21368366e-01 -9.08986509e-01 2.65445173e-01 3.15778643e-01 -9.10886526e-01 2.65459746e-01 3.10186714e-01 -9.12821293e-01 2.65464664e-01 3.04571867e-01 -9.14704919e-01 2.65464306e-01 2.98956156e-01 -9.16548908e-01 2.65444368e-01 2.93320388e-01 -9.18395936e-01 2.65464842e-01 2.87682444e-01 -9.20135736e-01 2.65455723e-01 2.82025725e-01 -9.21922684e-01 2.65480608e-01 2.76362389e-01 -9.23598230e-01 2.65481293e-01 2.70699769e-01 -9.25285518e-01 2.65499800e-01 2.65004665e-01 -9.26895559e-01 2.65493184e-01 2.59320974e-01 -9.28522825e-01 2.65511304e-01 2.53624827e-01 -9.30152714e-01 2.65498906e-01 2.47908935e-01 -9.31637228e-01 2.65518099e-01 2.42178470e-01 -9.33166623e-01 2.65517861e-01 2.36458614e-01 -9.34634268e-01 2.65523612e-01 2.30710566e-01 -9.36043739e-01 2.65548617e-01 2.24964395e-01 -9.37449753e-01 2.65558839e-01 2.19213605e-01 -9.38805401e-01 2.65566707e-01 2.13448152e-01 -9.40106511e-01 2.65573353e-01 2.07670361e-01 -9.41435397e-01 2.65577227e-01 2.01893851e-01 -9.42648828e-01 2.65560746e-01 1.96097270e-01 -9.43872571e-01 2.65585214e-01 1.90303475e-01 -9.45048988e-01 2.65587479e-01 1.84502736e-01 -9.46215093e-01 2.65578479e-01 1.78696424e-01 -9.47329342e-01 2.65594304e-01 1.72881633e-01 -9.48445261e-01 2.65583783e-01 1.67056724e-01 -9.49454784e-01 2.65577704e-01 1.61227912e-01 -9.50451672e-01 2.65584618e-01 1.55395254e-01 -9.51404154e-01 2.65594870e-01 1.49552092e-01 -9.52347696e-01 2.65584260e-01 1.43700898e-01 -9.53271329e-01 2.65590400e-01 1.37853235e-01 -9.54154372e-01 2.65587807e-01 1.31992936e-01 -9.54935133e-01 2.65592396e-01 1.26134127e-01 -9.55792010e-01 2.65575290e-01 1.20267019e-01 -9.56511021e-01 2.65587568e-01 1.14393808e-01 -9.57224786e-01 2.65572816e-01 1.08520761e-01 -9.57925498e-01 2.65577555e-01 1.02641560e-01 -9.58577096e-01 2.65574843e-01 9.67569277e-02 -9.59158778e-01 2.65584677e-01 9.08703059e-02 -9.59789276e-01 2.65588284e-01 8.49784389e-02 -9.60277140e-01 2.65593588e-01 7.90842474e-02 -9.60762441e-01 2.65590787e-01 7.31872842e-02 -9.61229861e-01 2.65601158e-01 6.72878921e-02 -9.61687624e-01 2.65596628e-01 6.13864176e-02 -9.62100148e-01 2.65594184e-01 5.54803424e-02 -9.62411702e-01 2.65589684e-01 4.95749600e-02 -9.62792695e-01 2.65599430e-01 4.36663479e-02 -9.63081777e-01 2.65599698e-01 3.77564430e-02 -9.63321567e-01 2.65597075e-01 3.18448544e-02 -9.63547528e-01 2.65615582e-01 2.59322301e-02 -9.63730037e-01 2.65606672e-01 2.00188570e-02 -9.63811636e-01 2.65594840e-01 1.41044818e-02 -9.63968277e-01 2.65603453e-01 8.18963908e-03 -9.64022994e-01 2.65614182e-01 2.27453490e-03 -9.64035511e-01 2.65619367e-01 -3.64080910e-03 -9.64038849e-01 2.65608668e-01 -9.55585111e-03 -9.64021623e-01 2.65608311e-01 -1.54706901e-02 -9.63876009e-01 2.65610397e-01 -2.13848948e-02 -9.63804424e-01 2.65604705e-01 -2.72982754e-02 -9.63627398e-01 2.65604973e-01 -3.32104377e-02 -9.63497519e-01 2.65607119e-01 -3.91215570e-02 -9.63263273e-01 2.65611500e-01 -4.50312980e-02 -9.63024318e-01 2.65610814e-01 -5.09391315e-02 -9.62683916e-01 2.65603662e-01 -5.68460152e-02 -9.62374866e-01 2.65620738e-01 -6.27485886e-02 -9.61976230e-01 2.65623480e-01 -6.86486587e-02 -9.61607695e-01 2.65639305e-01 -7.45474175e-02 -9.61151659e-01 2.65638143e-01 -8.04443210e-02 -9.60680842e-01 2.65641063e-01 -8.63382891e-02 -9.60191309e-01 2.65653431e-01 -9.22270566e-02 -9.59574819e-01 2.65650600e-01 -9.81127545e-02 -9.59027588e-01 2.65663773e-01 -1.03995517e-01 -9.58384275e-01 2.65655994e-01 -1.09875776e-01 -9.57732916e-01 2.65652627e-01 -1.15748823e-01 -9.57029700e-01 2.65647739e-01 -1.21617727e-01 -9.56321120e-01 2.65650600e-01 -1.27482414e-01 -9.55561638e-01 2.65642554e-01 -1.33349061e-01 -9.54781711e-01 2.65655875e-01 -1.39204517e-01 -9.53909576e-01 2.65663207e-01 -1.45053864e-01 -9.53027368e-01 2.65659600e-01 -1.50894299e-01 -9.52117264e-01 2.65667200e-01 -1.56740263e-01 -9.51176107e-01 2.65657723e-01 -1.62566081e-01 -9.50201988e-01 2.65658736e-01 -1.68394655e-01 -9.49203432e-01 2.65659392e-01 -1.74216598e-01 -9.48189378e-01 2.65655309e-01 -1.80037066e-01 -9.47084665e-01 2.65647203e-01 -1.85839787e-01 -9.45926428e-01 2.65643835e-01 -1.91641152e-01 -9.44754064e-01 2.65645981e-01 -1.97433323e-01 -9.43577468e-01 2.65635788e-01 -2.03221872e-01 -9.42386329e-01 2.65626699e-01 -2.09002674e-01 -9.41135645e-01 2.65639812e-01 -2.14771777e-01 -9.39793706e-01 2.65647709e-01 -2.20535144e-01 -9.38452721e-01 2.65655398e-01 -2.26283193e-01 -9.37130034e-01 2.65651941e-01 -2.32029200e-01 -9.35717106e-01 2.65655607e-01 -2.37772480e-01 -9.34233069e-01 2.65646011e-01 -2.43500799e-01 -9.32751417e-01 2.65637428e-01 -2.49211192e-01 -9.31260645e-01 2.65658706e-01 -2.54918396e-01 -9.29685354e-01 2.65660435e-01 -2.60626465e-01 -9.28112745e-01 2.65654951e-01 -2.66319573e-01 -9.26539779e-01 2.65651226e-01 -2.71991193e-01 -9.24889803e-01 2.65656203e-01 -2.77670234e-01 -9.23166752e-01 2.65656799e-01 -2.83332169e-01 -9.21435177e-01 2.65660584e-01 -2.88980871e-01 -9.19714272e-01 2.65658975e-01 -2.94614196e-01 -9.17897284e-01 2.65681684e-01 -3.00227910e-01 -9.16028380e-01 2.65700668e-01 -3.05851638e-01 -9.14197206e-01 2.65720606e-01 -3.11454028e-01 -9.12311196e-01 2.65725136e-01 -3.17041069e-01 -9.10359263e-01 2.65722841e-01 -3.22632313e-01 -9.08451557e-01 2.65728831e-01 -3.28180611e-01 -9.06427443e-01 2.65721560e-01 -3.33748996e-01 -9.04406965e-01 2.65729994e-01 -3.39281559e-01 -9.02342856e-01 2.65736431e-01 -3.44810247e-01 -9.00228679e-01 2.65745878e-01 -3.50336581e-01 -8.98106873e-01 2.65742689e-01 -3.55827540e-01 -8.95929039e-01 2.65760213e-01 -3.61337930e-01 -8.93716574e-01 2.65750915e-01 -3.66803110e-01 -8.91502917e-01 2.65754640e-01 -3.72273833e-01 -8.89183402e-01 2.65761286e-01 -3.77707362e-01 -8.86900842e-01 2.65773654e-01 -3.83152783e-01 -8.84612441e-01 2.65764564e-01 -3.88570368e-01 -8.82200360e-01 2.65755773e-01 -3.93979132e-01 -8.79788160e-01 2.65759319e-01 -3.99362177e-01 -8.77395511e-01 2.65754342e-01 -4.04754072e-01 -8.74903142e-01 2.65757769e-01 -4.10103619e-01 -8.72439444e-01 2.65750319e-01 -4.15453076e-01 -8.69866788e-01 2.65766472e-01 -4.20779437e-01 -8.67295861e-01 2.65753478e-01 -4.26082015e-01 -8.64693940e-01 2.65757233e-01 -4.31376964e-01 -8.62096488e-01 2.65764773e-01 -4.36665654e-01 -8.59434187e-01 2.65759736e-01 -4.41949338e-01 -8.56702089e-01 2.65768319e-01 -4.47174639e-01 -8.54018986e-01 2.65758723e-01 -4.52426821e-01 -8.51256669e-01 2.65757531e-01 -4.57618266e-01 -8.48447084e-01 2.65765727e-01 -4.62820143e-01 -8.45625460e-01 2.65757799e-01 -4.67998028e-01 -8.42785120e-01 2.65758038e-01 -4.73167032e-01 -8.39894533e-01 2.65769839e-01 -4.78320301e-01 -8.36946070e-01 2.65764743e-01 -4.83445555e-01 -8.34016919e-01 2.65773773e-01 -4.88548636e-01 -8.31030607e-01 2.65772521e-01 -4.93624419e-01 -8.28004479e-01 2.65755594e-01 -4.98706818e-01 -8.24952066e-01 2.65758812e-01 -5.03746212e-01 -8.21886718e-01 2.65758902e-01 -5.08795559e-01 -8.18799555e-01 2.65750080e-01 -5.13828337e-01 -8.15674126e-01 2.65699714e-01 -5.18817067e-01 -8.12496543e-01 2.65669793e-01 -5.23788512e-01 -8.09321940e-01 2.65678227e-01 -5.28736591e-01 -8.06093454e-01 2.65678406e-01 -5.33671081e-01 -8.02811325e-01 2.65693814e-01 -5.38583100e-01 -7.99514234e-01 2.65706033e-01 -5.43506205e-01 -7.96212673e-01 2.65718460e-01 -5.48351467e-01 -7.92851150e-01 2.65727907e-01 -5.53205073e-01 -7.89471447e-01 2.65731335e-01 -5.58062732e-01 -7.86075950e-01 2.65731484e-01 -5.62851727e-01 -7.82599568e-01 2.65730411e-01 -5.67643166e-01 -7.79136121e-01 2.65745014e-01 -5.72441816e-01 -7.75653780e-01 2.65728474e-01 -5.77174962e-01 -7.72124648e-01 2.65740603e-01 -5.81887245e-01 -7.68584669e-01 2.65741229e-01 -5.86596310e-01 -7.64994621e-01 2.65730351e-01 -5.91295838e-01 -7.61380672e-01 2.65729606e-01 -5.95967114e-01 -7.57725358e-01 2.65719086e-01 -6.00596845e-01 -7.54075766e-01 2.65696108e-01 -6.05195880e-01 -7.50353515e-01 2.65690863e-01 -6.09791696e-01 -7.46650219e-01 2.65688002e-01 -6.14366710e-01 -7.42882252e-01 2.65712053e-01 -6.18924499e-01 -7.39074469e-01 2.65714347e-01 -6.23434424e-01 -7.35275328e-01 2.65727788e-01 -6.27921462e-01 -7.31424034e-01 2.65748292e-01 -6.32394016e-01 -7.27574229e-01 2.65766829e-01 -6.36850417e-01 -7.23693967e-01 2.65761793e-01 -6.41292095e-01 -7.19747603e-01 2.65730351e-01 -6.45692348e-01 -7.15819478e-01 2.65715241e-01 -6.50093496e-01 -7.11840987e-01 2.65710890e-01 -6.54454052e-01 -7.07837939e-01 2.65716374e-01 -6.58758581e-01 -7.03817427e-01 2.65715986e-01 -6.63077354e-01 -6.99747026e-01 2.65716583e-01 -6.67347312e-01 -6.95652127e-01 2.65722275e-01 -6.71593964e-01 -6.91573739e-01 2.65727699e-01 -6.75826550e-01 -6.87406778e-01 2.65734464e-01 -6.80036306e-01 -6.83261633e-01 2.65747637e-01 -6.84235990e-01 -6.79074585e-01 2.65746772e-01 -6.88372493e-01 -6.74870789e-01 2.65757531e-01 -6.92499638e-01 -6.70631409e-01 2.65777856e-01 -6.96596503e-01 -6.66351736e-01 2.65802681e-01 -7.00679719e-01 -6.62068129e-01 2.65816271e-01 -7.04703927e-01 -6.57732606e-01 2.65842289e-01 -7.08838105e-01 -6.53527439e-01 2.65319347e-01 -7.13547349e-01 -6.49771094e-01 2.62002528e-01 -7.17593014e-01 -6.45397484e-01 2.61766583e-01 -7.21506298e-01 -6.41004920e-01 2.61802614e-01 -7.25434184e-01 -6.36530876e-01 2.61885762e-01 -7.29322433e-01 -6.32066250e-01 2.61884481e-01 -7.33170629e-01 -6.27586603e-01 2.61844486e-01 -7.37034082e-01 -6.23102665e-01 2.61801332e-01 -7.40826964e-01 -6.18546188e-01 2.61807203e-01 -7.44585454e-01 -6.13985300e-01 2.61917382e-01 -7.48260617e-01 -6.09333098e-01 2.62323141e-01 -7.51312315e-01 -6.04220510e-01 2.65400976e-01 -7.55703330e-01 -6.00120068e-01 2.62237310e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.88178384e-01 -5.57828069e-01 2.60005087e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.01524103e-01 -5.24357736e-01 2.87416190e-01 -8.05416048e-01 -5.19848287e-01 2.84706593e-01 -8.08598697e-01 -5.14901340e-01 2.84676164e-01 -8.12029004e-01 -5.10098398e-01 2.83562064e-01 -8.15591574e-01 -5.05368829e-01 2.81771868e-01 -8.20690870e-01 -5.01502395e-01 2.73573488e-01 -8.25371146e-01 -4.97376084e-01 2.67051995e-01 -8.28657091e-01 -4.92441386e-01 2.65996814e-01 -8.31693411e-01 -4.87347722e-01 2.65877843e-01 -8.34677696e-01 -4.82259810e-01 2.65860915e-01 -8.37596595e-01 -4.77112174e-01 2.65858740e-01 -8.40543032e-01 -4.71981108e-01 2.65866518e-01 -8.43422651e-01 -4.66805935e-01 2.65890807e-01 -8.46272647e-01 -4.61623996e-01 2.65895605e-01 -8.49081814e-01 -4.56403077e-01 2.65915185e-01 -8.51846933e-01 -4.51182812e-01 2.65922517e-01 -8.54577065e-01 -4.45967466e-01 2.65926540e-01 -8.57334018e-01 -4.40704912e-01 2.65918493e-01 -8.60001266e-01 -4.35435712e-01 2.65865982e-01 -8.62922430e-01 -4.30263042e-01 2.64967442e-01 -8.66339684e-01 -4.25319225e-01 2.61928141e-01 -8.68933439e-01 -4.19991761e-01 2.61923999e-01 -8.71466875e-01 -4.14660305e-01 2.61936188e-01 -8.73995125e-01 -4.09307361e-01 2.61927426e-01 -8.76493394e-01 -4.03929293e-01 2.61937082e-01 -8.78933132e-01 -3.98543388e-01 2.61969358e-01 -8.81341279e-01 -3.93126249e-01 2.62043864e-01 -8.83666635e-01 -3.87671202e-01 2.62424946e-01 -8.85378957e-01 -3.81986141e-01 2.64868349e-01 -8.87405872e-01 -3.76436144e-01 2.66050398e-01 -8.89809310e-01 -3.71029943e-01 2.65594006e-01 -8.92139256e-01 -3.65591228e-01 2.65198767e-01 -8.94271016e-01 -3.60076070e-01 2.65633196e-01 -8.96295071e-01 -3.54522616e-01 2.66321361e-01 -8.98393393e-01 -3.48992944e-01 2.66429514e-01 -9.00528610e-01 -3.43472540e-01 2.66380399e-01 -9.02693868e-01 -3.37959349e-01 2.66170740e-01 -9.04790521e-01 -3.32436413e-01 2.66083837e-01 -9.06782866e-01 -3.26874822e-01 2.66065747e-01 -9.08826530e-01 -3.21315020e-01 2.66051322e-01 -9.10734236e-01 -3.15728754e-01 2.66039014e-01 -9.12657797e-01 -3.10139656e-01 2.66042829e-01 -9.14548695e-01 -3.04531157e-01 2.66047329e-01 -9.16386306e-01 -2.98906296e-01 2.66062617e-01 -9.18237388e-01 -2.93274611e-01 2.66075462e-01 -9.19974446e-01 -2.87642628e-01 2.66065866e-01 -9.21776950e-01 -2.81990141e-01 2.66040474e-01 -9.23455417e-01 -2.76325107e-01 2.66026914e-01 -9.25140142e-01 -2.70664603e-01 2.66028166e-01 -9.26751435e-01 -2.64970690e-01 2.66047180e-01 -9.28382516e-01 -2.59286612e-01 2.66047448e-01 -9.30004537e-01 -2.53589988e-01 2.66053677e-01 -9.31494236e-01 -2.47873306e-01 2.66057581e-01 -9.33026612e-01 -2.42147610e-01 2.66055614e-01 -9.34496820e-01 -2.36425534e-01 2.66046256e-01 -9.35915232e-01 -2.30679587e-01 2.66037256e-01 -9.37320054e-01 -2.24941060e-01 2.66050160e-01 -9.38678980e-01 -2.19186187e-01 2.66052723e-01 -9.39969182e-01 -2.13419646e-01 2.66082734e-01 -9.41304028e-01 -2.07649216e-01 2.66072541e-01 -9.42513347e-01 -2.01867878e-01 2.66060770e-01 -9.43734586e-01 -1.96073428e-01 2.66092181e-01 -9.44912195e-01 -1.90285712e-01 2.66089529e-01 -9.46075618e-01 -1.84478521e-01 2.66089082e-01 -9.47199941e-01 -1.78674445e-01 2.66083479e-01 -9.48300719e-01 -1.72856957e-01 2.66088873e-01 -9.49314356e-01 -1.67032897e-01 2.66094148e-01 -9.50312734e-01 -1.61207840e-01 2.66092718e-01 -9.51265991e-01 -1.55375689e-01 2.66096771e-01 -9.52201545e-01 -1.49530381e-01 2.66113818e-01 -9.53125179e-01 -1.43687025e-01 2.66108632e-01 -9.54007268e-01 -1.37835905e-01 2.66128689e-01 -9.54779148e-01 -1.31978184e-01 2.66150385e-01 -9.55625653e-01 -1.26113534e-01 2.66180575e-01 -9.56343949e-01 -1.20253116e-01 2.66196489e-01 -9.57044780e-01 -1.14377245e-01 2.66229182e-01 -9.57742155e-01 -1.08504765e-01 2.66244859e-01 -9.58394229e-01 -1.02627128e-01 2.66243935e-01 -9.58971202e-01 -9.67439637e-02 2.66268402e-01 -9.59595144e-01 -9.08566490e-02 2.66298532e-01 -9.60088015e-01 -8.49661976e-02 2.66286582e-01 -9.60566461e-01 -7.90739655e-02 2.66303897e-01 -9.61024523e-01 -7.31772184e-02 2.66342431e-01 -9.61471617e-01 -6.72786087e-02 2.66371876e-01 -9.61876690e-01 -6.13789409e-02 2.66399384e-01 -9.62187767e-01 -5.54752983e-02 2.66392261e-01 -9.62570131e-01 -4.95697372e-02 2.66400397e-01 -9.62860763e-01 -4.36624177e-02 2.66393244e-01 -9.63098884e-01 -3.77540551e-02 2.66394466e-01 -9.63332236e-01 -3.18445936e-02 2.66391188e-01 -9.63508010e-01 -2.59332117e-02 2.66411930e-01 -9.63573456e-01 -2.00209785e-02 2.66451448e-01 -9.63739336e-01 -1.41079118e-02 2.66433239e-01 -9.63789701e-01 -8.19465332e-03 2.66456425e-01 0. 0. 0. -9.73122656e-01 4.16548317e-03 2.30129078e-01 -9.73110199e-01 1.01364749e-02 2.30109140e-01 -9.72963214e-01 1.61069017e-02 2.30123177e-01 -9.72895861e-01 2.20772550e-02 2.30083555e-01 -9.72723544e-01 2.80464608e-02 2.30070382e-01 -9.72518146e-01 3.40145342e-02 2.30068728e-01 -9.72341895e-01 3.99808213e-02 2.30100766e-01 -9.72009420e-01 4.59450521e-02 2.30134845e-01 -9.71726477e-01 5.19093424e-02 2.30074719e-01 -9.71432328e-01 5.78739010e-02 2.30004862e-01 -9.71036434e-01 6.38323873e-02 2.29990616e-01 -9.70638454e-01 6.97910935e-02 2.29915798e-01 -9.70260501e-01 7.57466480e-02 2.29885519e-01 -9.69800949e-01 8.17005634e-02 2.29820073e-01 -9.69225764e-01 8.76502693e-02 2.29803532e-01 -9.68692899e-01 9.35968831e-02 2.29792252e-01 -9.68146145e-01 9.95401889e-02 2.29779586e-01 -9.67489064e-01 1.05477482e-01 2.29792804e-01 -9.66795087e-01 1.11409441e-01 2.29784340e-01 -9.66088593e-01 1.17341377e-01 2.29765594e-01 -9.65377569e-01 1.23269752e-01 2.29743034e-01 -9.64609563e-01 1.29188374e-01 2.29734316e-01 -9.63776231e-01 1.35102287e-01 2.29733348e-01 -9.62986708e-01 1.41014740e-01 2.29721963e-01 -9.62059259e-01 1.46923393e-01 2.29717955e-01 -9.61126089e-01 1.52827710e-01 2.29710788e-01 -9.60174680e-01 1.58716574e-01 2.29712218e-01 -9.59210396e-01 1.64606288e-01 2.29707927e-01 -9.58206117e-01 1.70489311e-01 2.29685232e-01 -9.57088232e-01 1.76362664e-01 2.29712263e-01 -9.56047654e-01 1.82235301e-01 2.29704186e-01 -9.54881907e-01 1.88095719e-01 2.29721442e-01 -9.53725159e-01 1.93953156e-01 2.29734942e-01 -9.52497244e-01 1.99799314e-01 2.29733214e-01 -9.51222658e-01 2.05638930e-01 2.29751006e-01 -9.49939668e-01 2.11474389e-01 2.29764670e-01 -9.48672593e-01 2.17300102e-01 2.29761377e-01 -9.47319746e-01 2.23117933e-01 2.29744419e-01 -9.45903122e-01 2.28920162e-01 2.29738593e-01 -9.44480240e-01 2.34723181e-01 2.29736656e-01 -9.43050444e-01 2.40519390e-01 2.29735374e-01 -9.41562235e-01 2.46299759e-01 2.29730055e-01 -9.39980865e-01 2.52069861e-01 2.29744449e-01 -9.38466012e-01 2.57833123e-01 2.29725391e-01 -9.36864853e-01 2.63590366e-01 2.29739130e-01 -9.35209394e-01 2.69331366e-01 2.29742005e-01 -9.33550537e-01 2.75061071e-01 2.29721025e-01 -9.31864679e-01 2.80787170e-01 2.29745999e-01 -9.30081785e-01 2.86502272e-01 2.29730695e-01 -9.28322256e-01 2.92204350e-01 2.29729310e-01 -9.26504374e-01 2.97886878e-01 2.29725718e-01 -9.24683511e-01 3.03571641e-01 2.29725331e-01 -9.22802210e-01 3.09237629e-01 2.29702935e-01 -9.20898914e-01 3.14903468e-01 2.29686037e-01 -9.18922424e-01 3.20546806e-01 2.29695156e-01 -9.16928470e-01 3.26179266e-01 2.29703590e-01 -9.14949894e-01 3.31791848e-01 2.29687244e-01 -9.12885785e-01 3.37406576e-01 2.29693860e-01 -9.10773993e-01 3.43004107e-01 2.29665473e-01 -9.08639491e-01 3.48585844e-01 2.29657307e-01 -9.06503618e-01 3.54147732e-01 2.29633123e-01 -9.04342949e-01 3.59712690e-01 2.29642898e-01 -9.02133167e-01 3.65253747e-01 2.29625717e-01 -8.99837375e-01 3.70772570e-01 2.29629204e-01 -8.97557497e-01 3.76297683e-01 2.29612529e-01 -8.95250380e-01 3.81806880e-01 2.29610085e-01 -8.92881453e-01 3.87278080e-01 2.29627118e-01 -8.90486121e-01 3.92742693e-01 2.29654104e-01 -8.88041914e-01 3.98202479e-01 2.29669958e-01 -8.85568559e-01 4.03653890e-01 2.29685158e-01 -8.83098602e-01 4.09066647e-01 2.29723513e-01 -8.80561650e-01 4.14471656e-01 2.29736939e-01 -8.77976120e-01 4.19865161e-01 2.29704261e-01 -8.75370920e-01 4.25261825e-01 2.29709476e-01 -8.72745931e-01 4.30624187e-01 2.29720101e-01 -8.70111406e-01 4.35970038e-01 2.29725063e-01 -8.67434561e-01 4.41305906e-01 2.29705766e-01 -8.64673316e-01 4.46603894e-01 2.29694888e-01 -8.61950457e-01 4.51895505e-01 2.29717299e-01 -8.59159410e-01 4.57186073e-01 2.29735881e-01 -8.56327653e-01 4.62454796e-01 2.29722202e-01 -8.53468835e-01 4.67688441e-01 2.29755342e-01 -8.50592792e-01 4.72911566e-01 2.29796648e-01 -8.47636759e-01 4.78109062e-01 2.29964972e-01 -8.44652116e-01 4.83290344e-01 2.29983911e-01 -8.41840208e-01 4.88558650e-01 2.29233429e-01 -8.38352740e-01 4.93412793e-01 2.31614515e-01 -8.36086869e-01 4.99045849e-01 2.27832243e-01 0. 0. 0. 0. 0. 0. -8.27519536e-01 5.14859736e-01 2.23899305e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.76267767e-01 5.88388443e-01 2.26290405e-01 -7.72407889e-01 5.92947543e-01 2.27586851e-01 -7.68887699e-01 5.97788572e-01 2.26843879e-01 -7.65343785e-01 6.02617025e-01 2.26054341e-01 -7.61641204e-01 6.07299685e-01 2.25964412e-01 -7.57883012e-01 6.11920714e-01 2.26186410e-01 -7.54112422e-01 6.16570890e-01 2.26130962e-01 -7.50238597e-01 6.21126950e-01 2.26535410e-01 -7.45753944e-01 6.25134647e-01 2.30269253e-01 -7.41906643e-01 6.29713178e-01 2.30056420e-01 -7.38150775e-01 6.34340167e-01 2.29543760e-01 -7.34254837e-01 6.38883352e-01 2.29439691e-01 -7.30331779e-01 6.43359542e-01 2.29408935e-01 -7.26353347e-01 6.47847235e-01 2.29391202e-01 -7.22386301e-01 6.52285933e-01 2.29364544e-01 -7.18356490e-01 6.56735003e-01 2.29333267e-01 -7.14317024e-01 6.61134243e-01 2.29327574e-01 -7.10273325e-01 6.65477574e-01 2.29322493e-01 -7.06155002e-01 6.69847071e-01 2.29325473e-01 -7.02051818e-01 6.74151838e-01 2.29306743e-01 -6.97901368e-01 6.78436100e-01 2.29298219e-01 -6.93716407e-01 6.82710528e-01 2.29298949e-01 -6.89512968e-01 6.86964750e-01 2.29297131e-01 -6.85304403e-01 6.91200912e-01 2.29301512e-01 -6.81035936e-01 6.95372820e-01 2.29319349e-01 -6.76751733e-01 6.99549735e-01 2.29340136e-01 -6.72517180e-01 7.03770638e-01 2.28858173e-01 -6.68282986e-01 7.07970321e-01 2.28237018e-01 -6.63836718e-01 7.12003291e-01 2.28711545e-01 -6.59417689e-01 7.15984046e-01 2.29123801e-01 -6.54947400e-01 7.19971716e-01 2.29398355e-01 -6.50515676e-01 7.23972619e-01 2.29415163e-01 -6.46076560e-01 7.27932394e-01 2.29433760e-01 -6.41592145e-01 7.31877565e-01 2.29423553e-01 -6.37081563e-01 7.35800922e-01 2.29431212e-01 -6.32568777e-01 7.39705682e-01 2.29391918e-01 -6.28034830e-01 7.43591368e-01 2.29356512e-01 -6.23449385e-01 7.47420907e-01 2.29305863e-01 -6.18851900e-01 7.51252830e-01 2.29285836e-01 -6.14275157e-01 7.55051076e-01 2.29139358e-01 -6.09641731e-01 7.58839786e-01 2.28888169e-01 -6.04946017e-01 7.62569487e-01 2.29089022e-01 -6.00272954e-01 7.66228795e-01 2.29097515e-01 -5.95543325e-01 7.69925356e-01 2.29160532e-01 -5.90808034e-01 7.73522019e-01 2.29135811e-01 -5.86059451e-01 7.77154684e-01 2.29112551e-01 -5.81291497e-01 7.80725658e-01 2.29108304e-01 -5.76484859e-01 7.84285843e-01 2.29113236e-01 -5.71672201e-01 7.87828863e-01 2.29097188e-01 -5.66814125e-01 7.91332841e-01 2.29096681e-01 -5.61941445e-01 7.94795990e-01 2.29086787e-01 -5.57061017e-01 7.98227251e-01 2.29092166e-01 -5.52159667e-01 8.01622331e-01 2.29092658e-01 -5.47215223e-01 8.04967821e-01 2.29100734e-01 -5.42283297e-01 8.08337390e-01 2.29137734e-01 -5.37314653e-01 8.11609387e-01 2.29171306e-01 -5.32319486e-01 8.14909995e-01 2.29206905e-01 -5.27295411e-01 8.18155587e-01 2.29269251e-01 -5.22249162e-01 8.21372807e-01 2.29287624e-01 -5.17216682e-01 8.24563324e-01 2.29304239e-01 -5.12115777e-01 8.27668905e-01 2.29340032e-01 -5.07043064e-01 8.30830514e-01 2.29277700e-01 -5.01942277e-01 8.33929539e-01 2.29226187e-01 -4.96825874e-01 8.37014079e-01 2.29173586e-01 -4.91694957e-01 8.40046942e-01 2.29141533e-01 -4.86512274e-01 8.43064845e-01 2.29095757e-01 -4.81353700e-01 8.46016109e-01 2.29079023e-01 -4.76142377e-01 8.48995686e-01 2.29065478e-01 -4.70916450e-01 8.51923525e-01 2.29064673e-01 -4.65688109e-01 8.54793012e-01 2.29052603e-01 -4.60451543e-01 8.57633948e-01 2.29055360e-01 -4.55162466e-01 8.60425472e-01 2.29048103e-01 -4.49884474e-01 8.63180995e-01 2.29045302e-01 -4.44569051e-01 8.65964651e-01 2.29047760e-01 -4.39269930e-01 8.68645191e-01 2.29040504e-01 -4.33926523e-01 8.71345520e-01 2.29039669e-01 -4.28575754e-01 8.73976946e-01 2.29041636e-01 -4.23183769e-01 8.76589358e-01 2.29053348e-01 -4.17802066e-01 8.79182994e-01 2.29059592e-01 -4.12413776e-01 8.81710231e-01 2.29060844e-01 -4.06988144e-01 8.84251773e-01 2.29058564e-01 -4.01535004e-01 8.86700094e-01 2.29066506e-01 -3.96094739e-01 8.89168859e-01 2.29064226e-01 -3.90631646e-01 8.91568422e-01 2.29055032e-01 -3.85152012e-01 8.93992901e-01 2.29045674e-01 -3.79662752e-01 8.96307707e-01 2.29046121e-01 -3.74165058e-01 8.98592591e-01 2.29038402e-01 -3.68631601e-01 9.00906980e-01 2.29032770e-01 -3.63110095e-01 9.03118432e-01 2.29033217e-01 -3.57560009e-01 9.05350506e-01 2.29044035e-01 -3.51987749e-01 9.07546997e-01 2.29036689e-01 -3.46413165e-01 9.09685016e-01 2.29046181e-01 -3.40826154e-01 9.11782742e-01 2.29040697e-01 -3.35224628e-01 9.13813353e-01 2.29043603e-01 -3.29628766e-01 9.15881455e-01 2.29043096e-01 -3.23997617e-01 9.17855501e-01 2.29035527e-01 -3.18351597e-01 9.19903278e-01 2.29037583e-01 -3.12709838e-01 9.21817243e-01 2.29043514e-01 -3.07051420e-01 9.23717380e-01 2.29043707e-01 -3.01362962e-01 9.25610363e-01 2.29021817e-01 -2.95683265e-01 9.27361846e-01 2.29038253e-01 -2.89995253e-01 9.29190099e-01 2.29038790e-01 -2.84281909e-01 9.30924356e-01 2.29036242e-01 -2.78559327e-01 9.32701170e-01 2.29028538e-01 -2.72842765e-01 9.34408069e-01 2.29014426e-01 -2.67093897e-01 9.36070919e-01 2.29020074e-01 -2.61352241e-01 9.37678933e-01 2.29013950e-01 -2.55598336e-01 9.39237297e-01 2.29001045e-01 -2.49828190e-01 9.40829575e-01 2.29002103e-01 -2.44042188e-01 9.42283988e-01 2.29015812e-01 -2.38263637e-01 9.43762481e-01 2.29015931e-01 -2.32465073e-01 9.45246458e-01 2.29025975e-01 -2.26663664e-01 9.46612477e-01 2.29021445e-01 -2.20848337e-01 9.47986245e-01 2.29025766e-01 -2.15029642e-01 9.49382782e-01 2.29016170e-01 -2.09198982e-01 9.50643420e-01 2.29009077e-01 -2.03365013e-01 9.51951504e-01 2.29018345e-01 -1.97511703e-01 9.53184128e-01 2.29012504e-01 -1.91666454e-01 9.54374015e-01 2.29013294e-01 -1.85805529e-01 9.55522418e-01 2.29012787e-01 -1.79938138e-01 9.56597626e-01 2.29010120e-01 -1.74066305e-01 9.57715273e-01 2.29015455e-01 -1.68186128e-01 9.58734393e-01 2.29012564e-01 -1.62301540e-01 9.59802568e-01 2.29000822e-01 -1.56404033e-01 9.60793853e-01 2.28997886e-01 -1.50510997e-01 9.61739957e-01 2.29007334e-01 -1.44606248e-01 9.62628782e-01 2.28996292e-01 -1.38695732e-01 9.63440597e-01 2.28994682e-01 -1.32783398e-01 9.64319885e-01 2.29002565e-01 -1.26863167e-01 9.65088665e-01 2.29004651e-01 -1.20936193e-01 9.65853333e-01 2.29007989e-01 -1.15009837e-01 9.66568172e-01 2.29000747e-01 -1.09078363e-01 9.67241526e-01 2.29001760e-01 -1.03139475e-01 9.67939079e-01 2.28991747e-01 -9.71985385e-02 9.68571782e-01 2.28991151e-01 -9.12554264e-02 9.69131649e-01 2.28979692e-01 -8.53058994e-02 9.69661295e-01 2.28976041e-01 -7.93550014e-02 9.70149636e-01 2.28974953e-01 -7.34008476e-02 9.70617890e-01 2.28961468e-01 -6.74432591e-02 9.71051157e-01 2.28966445e-01 -6.14843406e-02 9.71495688e-01 2.28973582e-01 -5.55218272e-02 9.71802890e-01 2.28970632e-01 -4.95578274e-02 9.72168446e-01 2.28972673e-01 -4.35918458e-02 9.72460389e-01 2.28960007e-01 -3.76243852e-02 9.72698748e-01 2.28965908e-01 -3.16553339e-02 9.72923160e-01 2.28969321e-01 -2.56851912e-02 9.73108470e-01 2.28959188e-01 -1.97140537e-02 9.73190367e-01 2.28960186e-01 -1.37420520e-02 9.73347843e-01 2.28961498e-01 -7.76957348e-03 9.73403335e-01 2.28951842e-01 -1.79686816e-03 9.73415077e-01 2.28955626e-01 4.17590607e-03 9.73414600e-01 2.28954270e-01 1.01485932e-02 9.73398328e-01 2.28953630e-01 1.61206275e-02 9.73243177e-01 2.28967234e-01 2.20924001e-02 9.73173261e-01 2.28965670e-01 2.80631520e-02 9.72989261e-01 2.28968456e-01 3.40329036e-02 9.72784758e-01 2.28961065e-01 4.00015302e-02 9.72632587e-01 2.28951529e-01 4.59682755e-02 9.72293735e-01 2.28961885e-01 5.19333333e-02 9.72003162e-01 2.28962049e-01 5.78969233e-02 9.71697152e-01 2.28959367e-01 6.38586283e-02 9.71293747e-01 2.28947312e-01 6.98172525e-02 9.70873296e-01 2.28945032e-01 7.57733807e-02 9.70498383e-01 2.28944093e-01 8.17250609e-02 9.70020235e-01 2.28946090e-01 8.76768380e-02 9.69434798e-01 2.28939623e-01 9.36222076e-02 9.68902230e-01 2.28944093e-01 9.95657817e-02 9.68357980e-01 2.28938788e-01 1.05504699e-01 9.67703700e-01 2.28934243e-01 1.11442082e-01 9.67007935e-01 2.28929430e-01 1.17372796e-01 9.66298044e-01 2.28918597e-01 1.23298608e-01 9.65576410e-01 2.28935093e-01 1.29223600e-01 9.64810193e-01 2.28935584e-01 1.35139123e-01 9.63971138e-01 2.28929952e-01 1.41052231e-01 9.63182271e-01 2.28933886e-01 1.46960616e-01 9.62253451e-01 2.28932142e-01 1.52861506e-01 9.61314440e-01 2.28939816e-01 1.58754438e-01 9.60363388e-01 2.28936106e-01 1.64645582e-01 9.59400833e-01 2.28918120e-01 1.70531288e-01 9.58393037e-01 2.28924260e-01 1.76406950e-01 9.57280219e-01 2.28914872e-01 1.82277575e-01 9.56245720e-01 2.28905499e-01 1.88140124e-01 9.55071986e-01 2.28914022e-01 1.94003597e-01 9.53924596e-01 2.28902519e-01 1.99846014e-01 9.52697456e-01 2.28904739e-01 2.05685139e-01 9.51419413e-01 2.28911489e-01 2.11525679e-01 9.50142860e-01 2.28903890e-01 2.17357978e-01 9.48881805e-01 2.28894755e-01 2.23169789e-01 9.47518766e-01 2.28889719e-01 2.28974119e-01 9.46103096e-01 2.28883982e-01 2.34779745e-01 9.44683611e-01 2.28861988e-01 2.40572006e-01 9.43251610e-01 2.28865549e-01 2.46361598e-01 9.41766500e-01 2.28866920e-01 2.52125829e-01 9.40185070e-01 2.28852630e-01 2.57889748e-01 9.38671112e-01 2.28860766e-01 2.63651997e-01 9.37065899e-01 2.28852034e-01 2.69396931e-01 9.35416877e-01 2.28841394e-01 2.75122106e-01 9.33753729e-01 2.28843093e-01 2.80856997e-01 9.32081223e-01 2.28810742e-01 2.86576569e-01 9.30288315e-01 2.28799656e-01 2.92280614e-01 9.28537786e-01 2.28787303e-01 2.97969192e-01 9.26714480e-01 2.28772685e-01 3.03642362e-01 9.24905539e-01 2.28777647e-01 3.09317708e-01 9.23016429e-01 2.28781730e-01 3.14984083e-01 9.21105862e-01 2.28780374e-01 3.20626616e-01 9.19121146e-01 2.28784934e-01 3.26261371e-01 9.17136252e-01 2.28786200e-01 3.31868380e-01 9.15159345e-01 2.28784621e-01 3.37486744e-01 9.13094997e-01 2.28764191e-01 3.43083292e-01 9.10975277e-01 2.28762865e-01 3.48666668e-01 9.08840001e-01 2.28755683e-01 3.54236394e-01 9.06699717e-01 2.28759199e-01 3.59797120e-01 9.04544294e-01 2.28750318e-01 3.65342319e-01 9.02334750e-01 2.28752971e-01 3.70858133e-01 9.00035441e-01 2.28747562e-01 3.76391202e-01 8.97748530e-01 2.28729934e-01 3.81898075e-01 8.95449996e-01 2.28728518e-01 3.87371361e-01 8.93090308e-01 2.28708595e-01 3.92841935e-01 8.90702605e-01 2.28705913e-01 3.98303837e-01 8.88247669e-01 2.28716344e-01 4.03762043e-01 8.85786772e-01 2.28701681e-01 4.09179330e-01 8.83336484e-01 2.28682458e-01 4.14587259e-01 8.80794287e-01 2.28683233e-01 4.19976354e-01 8.78201485e-01 2.28668436e-01 4.25387412e-01 8.75588238e-01 2.28684276e-01 4.30745244e-01 8.72971952e-01 2.28677779e-01 4.36093241e-01 8.70342195e-01 2.28673577e-01 4.41433281e-01 8.67664635e-01 2.28671923e-01 4.46729243e-01 8.64895105e-01 2.28664830e-01 4.52021927e-01 8.62187564e-01 2.28664309e-01 4.57324296e-01 8.59397233e-01 2.28648439e-01 4.62589025e-01 8.56560647e-01 2.28651449e-01 4.67824578e-01 8.53706598e-01 2.28665441e-01 4.73054111e-01 8.50839674e-01 2.28659719e-01 4.78277892e-01 8.47926319e-01 2.28652492e-01 4.83475775e-01 8.44927073e-01 2.28636786e-01 4.88618702e-01 8.41990471e-01 2.28627145e-01 4.93801385e-01 8.38975132e-01 2.28632584e-01 4.98938262e-01 8.35891426e-01 2.28644744e-01 5.04056811e-01 8.32808673e-01 2.28645653e-01 5.09156227e-01 8.29707801e-01 2.28653148e-01 5.14246106e-01 8.26606452e-01 2.28621349e-01 5.19282341e-01 8.23423147e-01 2.28634387e-01 5.24357975e-01 8.20205629e-01 2.28636071e-01 5.29373288e-01 8.16978633e-01 2.28619248e-01 5.34372330e-01 8.13726425e-01 2.28621647e-01 5.39355040e-01 8.10445964e-01 2.28617862e-01 5.44326186e-01 8.07121038e-01 2.28607848e-01 5.49237132e-01 8.03746164e-01 2.28607431e-01 5.54189801e-01 8.00353408e-01 2.28608698e-01 5.59085667e-01 7.96927094e-01 2.28589192e-01 5.63963592e-01 7.93509603e-01 2.28605449e-01 5.68824768e-01 7.90026665e-01 2.28602797e-01 5.73654890e-01 7.86502779e-01 2.28594020e-01 5.78468144e-01 7.82984376e-01 2.28586808e-01 5.83254993e-01 7.79421091e-01 2.28578895e-01 5.88037074e-01 7.75817096e-01 2.28583708e-01 5.92772186e-01 7.72207618e-01 2.28574306e-01 5.97508788e-01 7.68574715e-01 2.28558496e-01 6.02229476e-01 7.64865220e-01 2.28547215e-01 6.06881440e-01 7.61191368e-01 2.28551179e-01 6.11551702e-01 7.57457197e-01 2.28547111e-01 6.16178036e-01 7.53672123e-01 2.28554890e-01 6.20806158e-01 7.49867678e-01 2.28569552e-01 6.25406146e-01 7.46061504e-01 2.28567600e-01 6.29960358e-01 7.42193997e-01 2.28545815e-01 6.34522080e-01 7.38328338e-01 2.28538275e-01 6.39046907e-01 7.34423161e-01 2.28532299e-01 6.43512905e-01 7.30490446e-01 2.28531376e-01 6.47989333e-01 7.26507723e-01 2.28544205e-01 6.52428865e-01 7.22540259e-01 2.28531018e-01 6.56883180e-01 7.18505383e-01 2.28519917e-01 6.61280036e-01 7.14466810e-01 2.28512481e-01 6.65621400e-01 7.10417867e-01 2.28524014e-01 6.69994235e-01 7.06306815e-01 2.28514433e-01 6.74298584e-01 7.02196598e-01 2.28502691e-01 6.78582489e-01 6.98047817e-01 2.28499502e-01 6.82858407e-01 6.93849385e-01 2.28492618e-01 6.87113166e-01 6.89659119e-01 2.28499845e-01 6.91357136e-01 6.85449183e-01 2.28490382e-01 6.95527375e-01 6.81180537e-01 2.28484273e-01 6.99712992e-01 6.76901400e-01 2.28478238e-01 7.03846753e-01 6.72577918e-01 2.28469342e-01 7.07947314e-01 6.68267310e-01 2.28475258e-01 7.12067068e-01 6.63886845e-01 2.28480175e-01 7.16113925e-01 6.59524500e-01 2.28484288e-01 7.20152915e-01 6.55096829e-01 2.28485942e-01 7.24164665e-01 6.50680125e-01 2.28486627e-01 7.28125513e-01 6.46239996e-01 2.28489473e-01 7.32061207e-01 6.41750097e-01 2.28494659e-01 7.35993385e-01 6.37234151e-01 2.28495434e-01 7.39885509e-01 6.32717669e-01 2.28502885e-01 7.43758440e-01 6.28172755e-01 2.28509963e-01 7.47579157e-01 6.23578489e-01 2.28514165e-01 7.51413167e-01 6.18971348e-01 2.28528902e-01 7.55181372e-01 6.14379406e-01 2.28521645e-01 7.58935571e-01 6.09704673e-01 2.28523195e-01 7.62692988e-01 6.05038106e-01 2.28520766e-01 7.66349673e-01 6.00364864e-01 2.28530064e-01 7.70060897e-01 5.95642269e-01 2.28513479e-01 7.73652852e-01 5.90902805e-01 2.28507310e-01 7.77282000e-01 5.86142540e-01 2.28505239e-01 7.80863702e-01 5.81382871e-01 2.28508890e-01 7.84414291e-01 5.76564372e-01 2.28496373e-01 7.87962914e-01 5.71761310e-01 2.28478909e-01 7.91459799e-01 5.66893935e-01 2.28479549e-01 7.94922888e-01 5.62027931e-01 2.28480771e-01 7.98352420e-01 5.57147563e-01 2.28481919e-01 8.01747680e-01 5.52245200e-01 2.28482187e-01 8.05094600e-01 5.47299623e-01 2.28494763e-01 8.08471560e-01 5.42361438e-01 2.28486180e-01 8.11751306e-01 5.37395000e-01 2.28500113e-01 8.15051854e-01 5.32402515e-01 2.28500694e-01 8.18313718e-01 5.27385771e-01 2.28495359e-01 8.21536124e-01 5.22343040e-01 2.28513375e-01 8.24721932e-01 5.17303765e-01 2.28529215e-01 8.27836812e-01 5.12215972e-01 2.28542671e-01 8.30981374e-01 5.07129252e-01 2.28544101e-01 8.34072173e-01 5.02024889e-01 2.28541538e-01 8.37143362e-01 4.96895254e-01 2.28553653e-01 8.40169907e-01 4.91765201e-01 2.28562802e-01 8.43174875e-01 4.86573279e-01 2.28571862e-01 8.46127868e-01 4.81412411e-01 2.28563264e-01 8.49096000e-01 4.76198852e-01 2.28581816e-01 8.52028728e-01 4.70973074e-01 2.28574470e-01 8.54891300e-01 4.65742111e-01 2.28577644e-01 8.57730925e-01 4.60502476e-01 2.28597134e-01 8.60518813e-01 4.55204308e-01 2.28593603e-01 8.63277078e-01 4.49931890e-01 2.28616521e-01 8.66056144e-01 4.44616973e-01 2.28615597e-01 8.68738472e-01 4.39298928e-01 2.28626624e-01 8.71432006e-01 4.33967620e-01 2.28621870e-01 8.74065161e-01 4.28609639e-01 2.28621185e-01 8.76676738e-01 4.23228174e-01 2.28633627e-01 8.79270315e-01 4.17844146e-01 2.28642195e-01 8.81801188e-01 4.12442595e-01 2.28657991e-01 8.84340465e-01 4.07029450e-01 2.28646681e-01 8.86795342e-01 4.01574820e-01 2.28648484e-01 8.89254153e-01 3.96134555e-01 2.28650093e-01 8.91664207e-01 3.90672207e-01 2.28641644e-01 8.94075572e-01 3.85188758e-01 2.28639036e-01 8.96391749e-01 3.79700482e-01 2.28635594e-01 8.98686111e-01 3.74197483e-01 2.28628397e-01 9.00994301e-01 3.68662238e-01 2.28641883e-01 9.03209329e-01 3.63141000e-01 2.28648484e-01 9.05449212e-01 3.57595980e-01 2.28641987e-01 9.07634079e-01 3.52020532e-01 2.28648454e-01 9.09774959e-01 3.46439511e-01 2.28644952e-01 9.11866188e-01 3.40851516e-01 2.28661314e-01 9.13902521e-01 3.35255742e-01 2.28666708e-01 9.15965736e-01 3.29658240e-01 2.28669673e-01 9.17943597e-01 3.24020803e-01 2.28668734e-01 9.19988871e-01 3.18380654e-01 2.28661269e-01 9.21908021e-01 3.12734306e-01 2.28646591e-01 9.23806429e-01 3.07079375e-01 2.28661910e-01 9.25694585e-01 3.01390082e-01 2.28652686e-01 9.27449703e-01 2.95698822e-01 2.28673041e-01 9.29276466e-01 2.90021241e-01 2.28665203e-01 9.31011140e-01 2.84300983e-01 2.28682935e-01 9.32779133e-01 2.78581649e-01 2.28680253e-01 9.34485793e-01 2.72865385e-01 2.28683352e-01 9.36144531e-01 2.67113090e-01 2.28693798e-01 9.37748969e-01 2.61367291e-01 2.28693768e-01 9.39310133e-01 2.55617768e-01 2.28699088e-01 9.40890849e-01 2.49837950e-01 2.28732854e-01 9.42349315e-01 2.44056672e-01 2.28741094e-01 9.43831146e-01 2.38281101e-01 2.28738219e-01 9.45323527e-01 2.32474744e-01 2.28748322e-01 9.46685851e-01 2.26680681e-01 2.28733003e-01 9.48051691e-01 2.20863789e-01 2.28749901e-01 9.49446976e-01 2.15043873e-01 2.28740752e-01 9.50706840e-01 2.09211513e-01 2.28758320e-01 9.52009201e-01 2.03368396e-01 2.28766292e-01 9.53242004e-01 1.97524056e-01 2.28770554e-01 9.54433501e-01 1.91677406e-01 2.28757143e-01 9.55574274e-01 1.85816407e-01 2.28773072e-01 9.56660986e-01 1.79943770e-01 2.28758216e-01 9.57777321e-01 1.74076661e-01 2.28749409e-01 9.58799064e-01 1.68196440e-01 2.28762954e-01 9.59847152e-01 1.62308484e-01 2.28790164e-01 9.60836411e-01 1.56412810e-01 2.28806242e-01 9.61781561e-01 1.50519207e-01 2.28822201e-01 9.62661982e-01 1.44611359e-01 2.28826076e-01 9.63482678e-01 1.38700634e-01 2.28827193e-01 9.64358151e-01 1.32787988e-01 2.28818610e-01 9.65135574e-01 1.26872048e-01 2.28806168e-01 9.65899348e-01 1.20940119e-01 2.28832617e-01 9.66611207e-01 1.15015425e-01 2.28844330e-01 9.67280865e-01 1.09080963e-01 2.28845909e-01 9.67976987e-01 1.03142366e-01 2.28835791e-01 9.68596041e-01 9.72005650e-02 2.28855997e-01 9.69159007e-01 9.12567303e-02 2.28863075e-01 9.69683349e-01 8.53073373e-02 2.28866488e-01 9.70174849e-01 7.93572962e-02 2.28885606e-01 9.70638871e-01 7.34020472e-02 2.28903800e-01 9.71069515e-01 6.74452335e-02 2.28894472e-01 9.71519709e-01 6.14855960e-02 2.28863671e-01 9.71830010e-01 5.55218495e-02 2.28882760e-01 9.72180128e-01 4.95588593e-02 2.28896931e-01 9.72473085e-01 4.35919575e-02 2.28904426e-01 9.72714305e-01 3.76244411e-02 2.28896007e-01 9.72936928e-01 3.16553451e-02 2.28907794e-01 9.73119974e-01 2.56851520e-02 2.28891000e-01 9.73210275e-01 1.97137389e-02 2.28883341e-01 9.73355711e-01 1.37418229e-02 2.28898808e-01 9.73420203e-01 7.76915904e-03 2.28881299e-01 9.73438442e-01 1.79619656e-03 2.28862330e-01 9.73435640e-01 -4.17667255e-03 2.28869677e-01 9.73416746e-01 -1.01493699e-02 2.28875533e-01 9.73277092e-01 -1.61219817e-02 2.28858024e-01 9.73202169e-01 -2.20936723e-02 2.28851229e-01 9.73016024e-01 -2.80642323e-02 2.28885993e-01 9.72814262e-01 -3.40342075e-02 2.28880376e-01 9.72644627e-01 -4.00028788e-02 2.28881508e-01 9.72320378e-01 -4.59700972e-02 2.28886440e-01 9.72026825e-01 -5.19346818e-02 2.28868484e-01 9.71712887e-01 -5.78992516e-02 2.28879496e-01 9.71308291e-01 -6.38582930e-02 2.28897229e-01 9.70894754e-01 -6.98179007e-02 2.28887901e-01 9.70498025e-01 -7.57730082e-02 2.28920400e-01 9.70022321e-01 -8.17261115e-02 2.28918761e-01 9.69448686e-01 -8.76781568e-02 2.28912950e-01 9.68913674e-01 -9.36246961e-02 2.28900984e-01 9.68363404e-01 -9.95691493e-02 2.28888094e-01 9.67711627e-01 -1.05508864e-01 2.28899404e-01 9.67014432e-01 -1.11441135e-01 2.28907585e-01 9.66302991e-01 -1.17374167e-01 2.28908807e-01 9.65582073e-01 -1.23303555e-01 2.28920519e-01 9.64806378e-01 -1.29223526e-01 2.28934318e-01 9.63981211e-01 -1.35138839e-01 2.28924870e-01 9.63190138e-01 -1.41051635e-01 2.28909194e-01 9.62256968e-01 -1.46960422e-01 2.28925899e-01 9.61314976e-01 -1.52862251e-01 2.28955358e-01 9.60364282e-01 -1.58754423e-01 2.28952885e-01 9.59389925e-01 -1.64641380e-01 2.28978321e-01 9.58373964e-01 -1.70528173e-01 2.28991821e-01 9.57269371e-01 -1.76402718e-01 2.28982687e-01 9.56227779e-01 -1.82276085e-01 2.28964925e-01 9.55056727e-01 -1.88135028e-01 2.28972226e-01 9.53901947e-01 -1.93996295e-01 2.29006320e-01 9.52665031e-01 -1.99837327e-01 2.29024723e-01 9.51392770e-01 -2.05682918e-01 2.29071409e-01 9.50099945e-01 -2.11515218e-01 2.29103103e-01 9.48827028e-01 -2.17344910e-01 2.29094520e-01 9.47479606e-01 -2.23159567e-01 2.29083821e-01 9.46061552e-01 -2.28965133e-01 2.29080811e-01 9.44636822e-01 -2.34765396e-01 2.29074210e-01 9.43205059e-01 -2.40565389e-01 2.29075581e-01 9.41715777e-01 -2.46348560e-01 2.29073241e-01 9.40144837e-01 -2.52114147e-01 2.29054615e-01 9.38608348e-01 -2.57874161e-01 2.29101434e-01 9.37013745e-01 -2.63635933e-01 2.29111150e-01 9.35357928e-01 -2.69377381e-01 2.29114458e-01 9.33697701e-01 -2.75103986e-01 2.29098201e-01 9.32011604e-01 -2.80841261e-01 2.29112253e-01 9.30239379e-01 -2.86552340e-01 2.29083225e-01 9.28472579e-01 -2.92255580e-01 2.29090095e-01 9.26666617e-01 -2.97948807e-01 2.29043558e-01 9.24838245e-01 -3.03625584e-01 2.29041234e-01 9.22951162e-01 -3.09301734e-01 2.29044914e-01 9.21036541e-01 -3.14955086e-01 2.29073390e-01 9.19074297e-01 -3.20603877e-01 2.29050040e-01 9.17074144e-01 -3.26239884e-01 2.29066819e-01 9.15089130e-01 -3.31844300e-01 2.29053482e-01 9.13027167e-01 -3.37468982e-01 2.29066551e-01 9.10911202e-01 -3.43059629e-01 2.29061112e-01 9.08774197e-01 -3.48642379e-01 2.29063123e-01 9.06630039e-01 -3.54205698e-01 2.29073852e-01 9.04464781e-01 -3.59762162e-01 2.29100153e-01 9.02258933e-01 -3.65304887e-01 2.29034409e-01 8.99975657e-01 -3.70831966e-01 2.29014605e-01 8.97700131e-01 -3.76356781e-01 2.29000002e-01 8.95382047e-01 -3.81865919e-01 2.28991583e-01 8.93022239e-01 -3.87342274e-01 2.28976294e-01 8.90625417e-01 -3.92809123e-01 2.29005426e-01 8.88194203e-01 -3.98270875e-01 2.29010552e-01 8.85717571e-01 -4.03725415e-01 2.29015753e-01 8.83253157e-01 -4.09151137e-01 2.29013994e-01 8.80722821e-01 -4.14550602e-01 2.29014456e-01 8.78114760e-01 -4.19944465e-01 2.29089111e-01 8.75501454e-01 -4.25334036e-01 2.29109779e-01 8.72878373e-01 -4.30692047e-01 2.29135484e-01 8.70239615e-01 -4.36036617e-01 2.29163110e-01 8.67546141e-01 -4.41370785e-01 2.29172558e-01 8.64788949e-01 -4.46678132e-01 2.29183301e-01 8.62064183e-01 -4.51961428e-01 2.29183733e-01 8.59277666e-01 -4.57254022e-01 2.29215711e-01 8.56443465e-01 -4.62519407e-01 2.29228169e-01 8.53591442e-01 -4.67756480e-01 2.29227215e-01 8.50713134e-01 -4.72980499e-01 2.29254663e-01 8.47776532e-01 -4.78196144e-01 2.29278997e-01 8.44800591e-01 -4.83386397e-01 2.29288250e-01 8.41829658e-01 -4.88534898e-01 2.29312122e-01 8.38832200e-01 -4.93710309e-01 2.29312375e-01 8.35758328e-01 -4.98850346e-01 2.29284748e-01 8.32690954e-01 -5.03982604e-01 2.29259178e-01 8.29584122e-01 -5.09071946e-01 2.29268089e-01 8.26464593e-01 -5.14150262e-01 2.29295850e-01 8.23287547e-01 -5.19192874e-01 2.29299009e-01 8.20075989e-01 -5.24263322e-01 2.29277208e-01 8.16860557e-01 -5.29281735e-01 2.29320049e-01 8.13567877e-01 -5.34276903e-01 2.29329512e-01 8.10309172e-01 -5.39267838e-01 2.29287967e-01 8.06985617e-01 -5.44230700e-01 2.29271233e-01 8.03605437e-01 -5.49149394e-01 2.29243413e-01 8.00251245e-01 -5.54100692e-01 2.29224712e-01 7.96807945e-01 -5.59006989e-01 2.29204878e-01 7.93385983e-01 -5.63886523e-01 2.29167759e-01 7.89923072e-01 -5.68753123e-01 2.29153112e-01 7.86411047e-01 -5.73577464e-01 2.29105785e-01 7.82905757e-01 -5.78396142e-01 2.29090899e-01 7.79349804e-01 -5.83191395e-01 2.29061827e-01 7.75740027e-01 -5.87970138e-01 2.29055390e-01 7.72121549e-01 -5.92705071e-01 2.29048371e-01 7.68478155e-01 -5.97430289e-01 2.29028672e-01 7.64786065e-01 -6.02171123e-01 2.29000658e-01 7.61094749e-01 -6.06814623e-01 2.29005173e-01 7.57374644e-01 -6.11487389e-01 2.28995800e-01 7.53594697e-01 -6.16121650e-01 2.28996396e-01 7.49790132e-01 -6.20733976e-01 2.29016364e-01 7.45978236e-01 -6.25337183e-01 2.29039043e-01 7.42095888e-01 -6.29884362e-01 2.29037777e-01 7.38259435e-01 -6.34453714e-01 2.29042515e-01 7.34336913e-01 -6.38970852e-01 2.29031786e-01 7.30423212e-01 -6.43441558e-01 2.29015917e-01 7.26419091e-01 -6.47922695e-01 2.29001477e-01 7.22457647e-01 -6.52352214e-01 2.29021907e-01 7.18424559e-01 -6.56799912e-01 2.29007214e-01 7.14390278e-01 -6.61202013e-01 2.28975430e-01 7.10338056e-01 -6.65547609e-01 2.28986785e-01 7.06219077e-01 -6.69910431e-01 2.28980869e-01 7.02122509e-01 -6.74219251e-01 2.28996098e-01 6.97960079e-01 -6.78501487e-01 2.29007751e-01 6.93768501e-01 -6.82769537e-01 2.29035780e-01 6.89561963e-01 -6.87018812e-01 2.29015008e-01 6.85367465e-01 -6.91268623e-01 2.28969336e-01 6.81109369e-01 -6.95460618e-01 2.28948623e-01 6.76819861e-01 -6.99624419e-01 2.28970230e-01 6.72494173e-01 -7.03770876e-01 2.28954911e-01 6.68182373e-01 -7.07851648e-01 2.28940472e-01 6.63812697e-01 -7.11979568e-01 2.28959978e-01 6.59439266e-01 -7.16019869e-01 2.28991732e-01 6.55018806e-01 -7.20055878e-01 2.28997588e-01 6.50598943e-01 -7.24071383e-01 2.28950247e-01 6.46157086e-01 -7.28016317e-01 2.28988841e-01 6.41677320e-01 -7.31971562e-01 2.28983924e-01 6.37162685e-01 -7.35888422e-01 2.28978440e-01 6.32654309e-01 -7.39802003e-01 2.28937134e-01 6.28109872e-01 -7.43692160e-01 2.28904113e-01 6.23519361e-01 -7.47518897e-01 2.28878915e-01 6.18918955e-01 -7.51337290e-01 2.28856623e-01 6.14329398e-01 -7.55128682e-01 2.28832379e-01 6.09659433e-01 -7.58883417e-01 2.28806406e-01 6.04989052e-01 -7.62631059e-01 2.28836223e-01 6.00328743e-01 -7.66306221e-01 2.28797451e-01 5.95598400e-01 -7.70001948e-01 2.28818908e-01 5.90853035e-01 -7.73600399e-01 2.28806451e-01 5.86102545e-01 -7.77235746e-01 2.28781670e-01 5.81343412e-01 -7.80813813e-01 2.28775799e-01 5.76531589e-01 -7.84371972e-01 2.28744432e-01 5.71722090e-01 -7.87914038e-01 2.28751913e-01 5.66860199e-01 -7.91411996e-01 2.28730217e-01 5.61988413e-01 -7.94861615e-01 2.28757247e-01 5.57107151e-01 -7.98295975e-01 2.28768528e-01 5.52213311e-01 -8.01701009e-01 2.28754759e-01 5.47264636e-01 -8.05051684e-01 2.28755459e-01 5.42325735e-01 -8.08407843e-01 2.28777066e-01 5.37362278e-01 -8.11712742e-01 2.28736132e-01 5.32371402e-01 -8.15013409e-01 2.28736535e-01 5.27363658e-01 -8.18267882e-01 2.28740469e-01 5.22312105e-01 -8.21487546e-01 2.28736281e-01 5.17277837e-01 -8.24685633e-01 2.28726923e-01 5.12193739e-01 -8.27810287e-01 2.28732616e-01 5.07105887e-01 -8.30951631e-01 2.28728995e-01 5.02008140e-01 -8.34043503e-01 2.28719473e-01 4.96880352e-01 -8.37122798e-01 2.28683814e-01 4.91755664e-01 -8.40153456e-01 2.28657633e-01 4.86566633e-01 -8.43158245e-01 2.28657275e-01 4.81398195e-01 -8.46114278e-01 2.28644431e-01 4.76193756e-01 -8.49082947e-01 2.28640765e-01 4.70964223e-01 -8.52010131e-01 2.28665546e-01 4.65735674e-01 -8.54876339e-01 2.28656843e-01 4.60498840e-01 -8.57722461e-01 2.28646800e-01 4.55201298e-01 -8.60508144e-01 2.28647366e-01 4.49928284e-01 -8.63269448e-01 2.28662789e-01 4.44613218e-01 -8.66049826e-01 2.28655785e-01 4.39298153e-01 -8.68738472e-01 2.28631243e-01 4.33967412e-01 -8.71428072e-01 2.28642032e-01 4.28608567e-01 -8.74062479e-01 2.28631541e-01 4.23228294e-01 -8.76674950e-01 2.28639379e-01 4.17845577e-01 -8.79269958e-01 2.28648037e-01 4.12449002e-01 -8.81809235e-01 2.28630513e-01 4.07031983e-01 -8.84345889e-01 2.28628427e-01 4.01578039e-01 -8.86802137e-01 2.28624031e-01 3.96137625e-01 -8.89257491e-01 2.28639171e-01 3.90674174e-01 -8.91668260e-01 2.28623822e-01 3.85185301e-01 -8.94082367e-01 2.28636503e-01 3.79700124e-01 -8.96391213e-01 2.28650525e-01 3.74196440e-01 -8.98683667e-01 2.28643894e-01 3.68662000e-01 -9.00992930e-01 2.28650391e-01 3.63141179e-01 -9.03212786e-01 2.28639930e-01 3.57597798e-01 -9.05440092e-01 2.28625357e-01 3.52019519e-01 -9.07634079e-01 2.28650138e-01 3.46441001e-01 -9.09776092e-01 2.28645161e-01 3.40852350e-01 -9.11866724e-01 2.28666931e-01 3.35256308e-01 -9.13903415e-01 2.28660718e-01 3.29659313e-01 -9.15966332e-01 2.28660837e-01 3.24021876e-01 -9.17938054e-01 2.28684649e-01 3.18377227e-01 -9.19975579e-01 2.28708565e-01 3.12729388e-01 -9.21886444e-01 2.28729159e-01 3.07075322e-01 -9.23791826e-01 2.28714198e-01 3.01384360e-01 -9.25675213e-01 2.28726178e-01 2.95698553e-01 -9.27435398e-01 2.28731439e-01 2.90014952e-01 -9.29257631e-01 2.28736848e-01 2.84300357e-01 -9.30997431e-01 2.28729486e-01 2.78574228e-01 -9.32767630e-01 2.28713751e-01 2.72860169e-01 -9.34467554e-01 2.28744045e-01 2.67104596e-01 -9.36126888e-01 2.28753194e-01 2.61364967e-01 -9.37725186e-01 2.28776768e-01 2.55611986e-01 -9.39287782e-01 2.28785262e-01 2.49838516e-01 -9.40880716e-01 2.28765950e-01 2.44049087e-01 -9.42332387e-01 2.28799209e-01 2.38277182e-01 -9.43814993e-01 2.28801057e-01 2.32468456e-01 -9.45307612e-01 2.28799194e-01 2.26677611e-01 -9.46672261e-01 2.28779539e-01 2.20857114e-01 -9.48035479e-01 2.28814930e-01 2.15035290e-01 -9.49422479e-01 2.28839263e-01 2.09207281e-01 -9.50689971e-01 2.28829399e-01 2.03369454e-01 -9.51986611e-01 2.28847235e-01 1.97520778e-01 -9.53220844e-01 2.28852406e-01 1.91672906e-01 -9.54407811e-01 2.28862166e-01 1.85812831e-01 -9.55552220e-01 2.28863925e-01 1.79938897e-01 -9.56640363e-01 2.28850916e-01 1.74076304e-01 -9.57752347e-01 2.28856996e-01 1.68194816e-01 -9.58772480e-01 2.28884041e-01 1.62304938e-01 -9.59822118e-01 2.28892878e-01 1.56409591e-01 -9.60815728e-01 2.28894398e-01 1.50515765e-01 -9.61761653e-01 2.28903651e-01 1.44609287e-01 -9.62639689e-01 2.28912041e-01 1.38699353e-01 -9.63461220e-01 2.28910297e-01 1.32785529e-01 -9.64335382e-01 2.28905261e-01 1.26869082e-01 -9.65113103e-01 2.28895113e-01 1.20938778e-01 -9.65881884e-01 2.28894934e-01 1.15013890e-01 -9.66597855e-01 2.28883997e-01 1.09079003e-01 -9.67261374e-01 2.28916243e-01 1.03142515e-01 -9.67960954e-01 2.28891417e-01 9.72010791e-02 -9.68581140e-01 2.28911728e-01 9.12557766e-02 -9.69146907e-01 2.28901014e-01 8.53057206e-02 -9.69680250e-01 2.28906736e-01 7.93568715e-02 -9.70164776e-01 2.28923962e-01 7.34023005e-02 -9.70635891e-01 2.28896230e-01 6.74449727e-02 -9.71060753e-01 2.28919014e-01 6.14850558e-02 -9.71502185e-01 2.28924960e-01 5.55216782e-02 -9.71813977e-01 2.28935018e-01 4.95589040e-02 -9.72172797e-01 2.28918552e-01 4.35918570e-02 -9.72465575e-01 2.28922829e-01 3.76242474e-02 -9.72701728e-01 2.28933394e-01 3.16554382e-02 -9.72926497e-01 2.28938520e-01 2.56852005e-02 -9.73106623e-01 2.28930429e-01 1.97138377e-02 -9.73195314e-01 2.28931427e-01 1.37419114e-02 -9.73345041e-01 2.28933007e-01 7.76950968e-03 -9.73400891e-01 2.28944868e-01 1.79689261e-03 -9.73412812e-01 2.28954434e-01 -4.17590979e-03 -9.73412991e-01 2.28949562e-01 -1.01482812e-02 -9.73390996e-01 2.28968740e-01 -1.61205120e-02 -9.73247409e-01 2.28967771e-01 -2.20920648e-02 -9.73172009e-01 2.28963241e-01 -2.80629247e-02 -9.72993314e-01 2.28967175e-01 -3.40324789e-02 -9.72788811e-01 2.28965908e-01 -4.00014222e-02 -9.72625315e-01 2.28952467e-01 -4.59686108e-02 -9.72299278e-01 2.28954032e-01 -5.19322306e-02 -9.72002089e-01 2.28959262e-01 -5.78968376e-02 -9.71688569e-01 2.28964925e-01 -6.38573170e-02 -9.71293509e-01 2.28945524e-01 -6.98152259e-02 -9.70871627e-01 2.28971079e-01 -7.57715777e-02 -9.70487118e-01 2.28960738e-01 -8.17240924e-02 -9.70004976e-01 2.28982821e-01 -8.76757428e-02 -9.69429553e-01 2.28978544e-01 -9.36213732e-02 -9.68892276e-01 2.28976011e-01 -9.95663181e-02 -9.68342960e-01 2.28975773e-01 -1.05504915e-01 -9.67689574e-01 2.28976965e-01 -1.11438140e-01 -9.66995478e-01 2.28974521e-01 -1.17371626e-01 -9.66288686e-01 2.28953078e-01 -1.23300351e-01 -9.65574563e-01 2.28945017e-01 -1.29220247e-01 -9.64800477e-01 2.28951782e-01 -1.35140225e-01 -9.63973701e-01 2.28935763e-01 -1.41052082e-01 -9.63161945e-01 2.28939041e-01 -1.46958038e-01 -9.62250233e-01 2.28938550e-01 -1.52860552e-01 -9.61310089e-01 2.28955045e-01 -1.58754379e-01 -9.60360110e-01 2.28952780e-01 -1.64642423e-01 -9.59391236e-01 2.28951246e-01 -1.70530096e-01 -9.58387613e-01 2.28930965e-01 -1.76403508e-01 -9.57276404e-01 2.28924870e-01 -1.82276249e-01 -9.56237137e-01 2.28920028e-01 -1.88137263e-01 -9.55062687e-01 2.28938669e-01 -1.94002301e-01 -9.53914225e-01 2.28934541e-01 -1.99845031e-01 -9.52685773e-01 2.28933215e-01 -2.05685258e-01 -9.51410770e-01 2.28940055e-01 -2.11526990e-01 -9.50134873e-01 2.28930935e-01 -2.17357486e-01 -9.48870242e-01 2.28929430e-01 -2.23169297e-01 -9.47505355e-01 2.28943557e-01 -2.28969261e-01 -9.46089923e-01 2.28933468e-01 -2.34772474e-01 -9.44665492e-01 2.28933871e-01 -2.40570068e-01 -9.43231046e-01 2.28941813e-01 -2.46355906e-01 -9.41744268e-01 2.28944272e-01 -2.52117872e-01 -9.40156102e-01 2.28973597e-01 -2.57881165e-01 -9.38640118e-01 2.28963852e-01 -2.63645023e-01 -9.37042296e-01 2.28949189e-01 -2.69387454e-01 -9.35385704e-01 2.28967220e-01 -2.75115758e-01 -9.33718801e-01 2.28981435e-01 -2.80845165e-01 -9.32036459e-01 2.28990570e-01 -2.86563218e-01 -9.30245936e-01 2.28995472e-01 -2.92261511e-01 -9.28482234e-01 2.29020312e-01 -2.97945470e-01 -9.26658988e-01 2.29026631e-01 -3.03625435e-01 -9.24846351e-01 2.29002640e-01 -3.09300035e-01 -9.22958910e-01 2.29006618e-01 -3.14962894e-01 -9.21048224e-01 2.29012817e-01 -3.20605427e-01 -9.19073462e-01 2.29010850e-01 -3.26241523e-01 -9.17077243e-01 2.29035035e-01 -3.31844717e-01 -9.15093899e-01 2.29040340e-01 -3.37467253e-01 -9.13029194e-01 2.29048088e-01 -3.43057215e-01 -9.10909593e-01 2.29053691e-01 -3.48641396e-01 -9.08773005e-01 2.29053751e-01 -3.54209244e-01 -9.06629503e-01 2.29065478e-01 -3.59763950e-01 -9.04469669e-01 2.29072154e-01 -3.65305275e-01 -9.02255177e-01 2.29067460e-01 -3.70824903e-01 -8.99962485e-01 2.29060844e-01 -3.76351178e-01 -8.97678614e-01 2.29059711e-01 -3.81861001e-01 -8.95370841e-01 2.29050830e-01 -3.87333512e-01 -8.93005192e-01 2.29061127e-01 -3.92803788e-01 -8.90618265e-01 2.29049668e-01 -3.98265481e-01 -8.88176203e-01 2.29045510e-01 -4.03724402e-01 -8.85711908e-01 2.29026020e-01 -4.09138769e-01 -8.83246243e-01 2.29056403e-01 -4.14544970e-01 -8.80712867e-01 2.29041830e-01 -4.19932932e-01 -8.78115296e-01 2.29056939e-01 -4.25342262e-01 -8.75505269e-01 2.29055494e-01 -4.30699468e-01 -8.72891009e-01 2.29048684e-01 -4.36051637e-01 -8.70265722e-01 2.29011670e-01 -4.41387683e-01 -8.67579997e-01 2.29034632e-01 -4.46690470e-01 -8.64817083e-01 2.29026392e-01 -4.51982915e-01 -8.62114668e-01 2.28981823e-01 -4.57284331e-01 -8.59323144e-01 2.28988469e-01 -4.62546527e-01 -8.56487095e-01 2.28993893e-01 -4.67782885e-01 -8.53635907e-01 2.28992164e-01 -4.73004758e-01 -8.50755870e-01 2.29044348e-01 -4.78224605e-01 -8.47837210e-01 2.29054391e-01 -4.83425289e-01 -8.44848931e-01 2.29025066e-01 -4.88569081e-01 -8.41901660e-01 2.29040176e-01 -4.93753225e-01 -8.38888228e-01 2.29047671e-01 -4.98891175e-01 -8.35811019e-01 2.29028389e-01 -5.04000425e-01 -8.32731545e-01 2.29025885e-01 -5.09111941e-01 -8.29633713e-01 2.29015037e-01 -5.14201283e-01 -8.26525450e-01 2.29010135e-01 -5.19228995e-01 -8.23334217e-01 2.29015872e-01 -5.24304688e-01 -8.20130706e-01 2.29001075e-01 -5.29312670e-01 -8.16902339e-01 2.29003444e-01 -5.34319639e-01 -8.13642263e-01 2.29018271e-01 -5.39291739e-01 -8.10362875e-01 2.29023322e-01 -5.44268131e-01 -8.07037294e-01 2.29018956e-01 -5.49180448e-01 -8.03661942e-01 2.29017526e-01 -5.54129243e-01 -8.00270498e-01 2.29028136e-01 -5.59013247e-01 -7.96837628e-01 2.29045704e-01 -5.63900709e-01 -7.93418109e-01 2.29054362e-01 -5.68754733e-01 -7.89938092e-01 2.29055449e-01 -5.73581219e-01 -7.86410630e-01 2.29064360e-01 -5.78399241e-01 -7.82901108e-01 2.29054868e-01 -5.83179057e-01 -7.79337287e-01 2.29061604e-01 -5.87965310e-01 -7.75723040e-01 2.29074001e-01 -5.92699647e-01 -7.72114158e-01 2.29068577e-01 -5.97428858e-01 -7.68474281e-01 2.29073748e-01 -6.02150142e-01 -7.64781892e-01 2.29059279e-01 -6.06805205e-01 -7.61089563e-01 2.29067922e-01 -6.11471176e-01 -7.57359207e-01 2.29068100e-01 -6.16100430e-01 -7.53574908e-01 2.29079574e-01 -6.20718420e-01 -7.49770045e-01 2.29094118e-01 -6.25319898e-01 -7.45962024e-01 2.29111448e-01 -6.29860878e-01 -7.42085516e-01 2.29128465e-01 -6.34423792e-01 -7.38223910e-01 2.29140431e-01 -6.38943017e-01 -7.34312773e-01 2.29160905e-01 -6.43406391e-01 -7.30382681e-01 2.29158297e-01 -6.47893250e-01 -7.26396143e-01 2.29145482e-01 -6.52328551e-01 -7.22432375e-01 2.29135543e-01 -6.56779289e-01 -7.18397021e-01 2.29131728e-01 -6.61179543e-01 -7.14355886e-01 2.29135498e-01 -6.65511549e-01 -7.10307002e-01 2.29135543e-01 -6.69879496e-01 -7.06187725e-01 2.29165435e-01 -6.74184203e-01 -7.02087879e-01 2.29158834e-01 -6.78468704e-01 -6.97934151e-01 2.29153618e-01 -6.82742178e-01 -6.93748176e-01 2.29156986e-01 -6.86997890e-01 -6.89543724e-01 2.29145646e-01 -6.91237271e-01 -6.85334146e-01 2.29154959e-01 -6.95409179e-01 -6.81068420e-01 2.29164571e-01 -6.99585378e-01 -6.76784635e-01 2.29167566e-01 -7.03717411e-01 -6.72458589e-01 2.29184866e-01 -7.07811058e-01 -6.68145835e-01 2.29191944e-01 -7.11916089e-01 -6.63767993e-01 2.29204059e-01 -7.15976477e-01 -6.59408808e-01 2.29210302e-01 -7.20001400e-01 -6.54967248e-01 2.29266495e-01 -7.24554956e-01 -6.51001573e-01 2.26320043e-01 -7.28661120e-01 -6.46692336e-01 2.25514159e-01 -7.32603729e-01 -6.42197430e-01 2.25537002e-01 -7.36521006e-01 -6.37672544e-01 2.25580812e-01 -7.40407407e-01 -6.33137822e-01 2.25657955e-01 -7.44306803e-01 -6.28592312e-01 2.25612521e-01 -7.48148859e-01 -6.24003530e-01 2.25580797e-01 -7.51960456e-01 -6.19400620e-01 2.25561202e-01 -7.55754888e-01 -6.14796579e-01 2.25591943e-01 -7.59466767e-01 -6.10116065e-01 2.25695834e-01 -7.63140678e-01 -6.05393589e-01 2.26085529e-01 -7.66487956e-01 -6.00442946e-01 2.27945149e-01 -7.70183623e-01 -5.95747173e-01 2.27812856e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.19278121e-01 -5.14119744e-01 2.53897995e-01 -8.23978305e-01 -5.09984910e-01 2.46898994e-01 -8.27290475e-01 -5.05032897e-01 2.46027038e-01 -8.30846429e-01 -5.00210524e-01 2.43868858e-01 -8.35207343e-01 -4.95828032e-01 2.37702668e-01 -8.39589417e-01 -4.91441756e-01 2.31283650e-01 -8.42942357e-01 -4.86450434e-01 2.29622081e-01 -8.45951855e-01 -4.81322765e-01 2.29355887e-01 -8.48930657e-01 -4.76109713e-01 2.29324475e-01 -8.51850450e-01 -4.70885217e-01 2.29306802e-01 -8.54721308e-01 -4.65653241e-01 2.29332581e-01 -8.57558846e-01 -4.60414261e-01 2.29352951e-01 -8.60345483e-01 -4.55121487e-01 2.29366615e-01 -8.63096595e-01 -4.49842870e-01 2.29400650e-01 -8.65875304e-01 -4.44526970e-01 2.29418114e-01 -8.68547797e-01 -4.39215034e-01 2.29455844e-01 -8.71233284e-01 -4.33873773e-01 2.29483321e-01 -8.74004543e-01 -4.28583056e-01 2.28865772e-01 -8.77126098e-01 -4.23437774e-01 2.26549655e-01 -8.79876971e-01 -4.18114156e-01 2.25806817e-01 -8.82459998e-01 -4.12715107e-01 2.25723848e-01 -8.84985387e-01 -4.07300383e-01 2.25697339e-01 -8.87442052e-01 -4.01842833e-01 2.25772619e-01 -8.89846861e-01 -3.96387786e-01 2.25944325e-01 -8.91961277e-01 -3.90809834e-01 2.27191359e-01 -8.93918276e-01 -3.85141522e-01 2.29175746e-01 -8.96127284e-01 -3.79596084e-01 2.29765534e-01 -8.98429871e-01 -3.74096990e-01 2.29737788e-01 -9.01079297e-01 -3.68701696e-01 2.28230134e-01 -9.03088212e-01 -3.63088727e-01 2.29171485e-01 -9.05164599e-01 -3.57495189e-01 2.29792267e-01 -9.07368183e-01 -3.51925164e-01 2.29778931e-01 -9.09520030e-01 -3.46356690e-01 2.29725569e-01 -9.11639929e-01 -3.40777516e-01 2.29607746e-01 -9.13695514e-01 -3.35185677e-01 2.29531005e-01 -9.15763676e-01 -3.29589725e-01 2.29509473e-01 -9.17744577e-01 -3.23961675e-01 2.29486376e-01 -9.19787824e-01 -3.18314850e-01 2.29493633e-01 -9.21704054e-01 -3.12672555e-01 2.29496732e-01 -9.23609316e-01 -3.07018667e-01 2.29482695e-01 -9.25493717e-01 -3.01333755e-01 2.29487881e-01 -9.27254200e-01 -2.95650154e-01 2.29469910e-01 -9.29083824e-01 -2.89964736e-01 2.29465649e-01 -9.30821717e-01 -2.84254044e-01 2.29456872e-01 -9.32589054e-01 -2.78533340e-01 2.29463398e-01 -9.34297025e-01 -2.72812992e-01 2.29452088e-01 -9.35958803e-01 -2.67069250e-01 2.29456708e-01 -9.37565446e-01 -2.61323422e-01 2.29449764e-01 -9.39118207e-01 -2.55570620e-01 2.29477257e-01 -9.40709412e-01 -2.49796078e-01 2.29469314e-01 -9.42169249e-01 -2.44022980e-01 2.29460254e-01 -9.43649769e-01 -2.38238841e-01 2.29466155e-01 -9.45148349e-01 -2.32438117e-01 2.29464084e-01 -9.46501493e-01 -2.26642430e-01 2.29463547e-01 -9.47872400e-01 -2.20827907e-01 2.29464889e-01 -9.49263215e-01 -2.15006009e-01 2.29476050e-01 -9.50520873e-01 -2.09177613e-01 2.29483262e-01 -9.51824129e-01 -2.03335434e-01 2.29499519e-01 -9.53054965e-01 -1.97489187e-01 2.29505017e-01 -9.54244077e-01 -1.91643819e-01 2.29506329e-01 -9.55391288e-01 -1.85784444e-01 2.29501024e-01 -9.56469417e-01 -1.79916158e-01 2.29506254e-01 -9.57585633e-01 -1.74048707e-01 2.29504451e-01 -9.58600402e-01 -1.68169633e-01 2.29533806e-01 -9.59653974e-01 -1.62282735e-01 2.29560271e-01 -9.60647047e-01 -1.56386882e-01 2.29554698e-01 -9.61588025e-01 -1.50493830e-01 2.29572281e-01 -9.62472796e-01 -1.44589901e-01 2.29578331e-01 -9.63285327e-01 -1.38682708e-01 2.29597241e-01 -9.64156926e-01 -1.32767871e-01 2.29620948e-01 -9.64923978e-01 -1.26849055e-01 2.29649633e-01 -9.65681255e-01 -1.20920248e-01 2.29694664e-01 -9.66390431e-01 -1.14997126e-01 2.29719162e-01 -9.67053771e-01 -1.09062061e-01 2.29751438e-01 -9.67742264e-01 -1.03124812e-01 2.29772702e-01 -9.68359888e-01 -9.71842706e-02 2.29801819e-01 -9.68910336e-01 -9.12405699e-02 2.29846925e-01 -9.69412327e-01 -8.52934644e-02 2.29889527e-01 -9.69917476e-01 -7.93435946e-02 2.29904249e-01 -9.70375001e-01 -7.33900219e-02 2.29938388e-01 -9.70784187e-01 -6.74337521e-02 2.30035424e-01 -9.71199811e-01 -6.14752844e-02 2.30150551e-01 -9.71529305e-01 -5.55138923e-02 2.30091646e-01 -9.71886516e-01 -4.95528504e-02 2.30076969e-01 -9.72173035e-01 -4.35875766e-02 2.30109975e-01 -9.72413301e-01 -3.76222879e-02 2.30105132e-01 -9.72640395e-01 -3.16551067e-02 2.30097502e-01 -9.72810209e-01 -2.56865099e-02 2.30129033e-01 -9.72884297e-01 -1.97172556e-02 2.30192244e-01 -9.73040462e-01 -1.37471417e-02 2.30157018e-01 -9.73105609e-01 -7.77651649e-03 2.30134055e-01 0. 0. 0. -9.80992436e-01 4.44445200e-03 1.93928540e-01 -9.80964065e-01 1.04630385e-02 1.93978816e-01 -9.80829775e-01 1.64821614e-02 1.93946764e-01 -9.80767667e-01 2.25015227e-02 1.93846390e-01 -9.80581701e-01 2.85182148e-02 1.93906173e-01 -9.80368197e-01 3.45348865e-02 1.93870515e-01 -9.80167329e-01 4.05510962e-02 1.93782255e-01 -9.79916334e-01 4.65654656e-02 1.93720967e-01 -9.79608536e-01 5.25777340e-02 1.93699732e-01 -9.79276180e-01 5.85858636e-02 1.93823069e-01 -9.78887439e-01 6.45950362e-02 1.93702236e-01 -9.78492320e-01 7.06030279e-02 1.93585187e-01 -9.78049755e-01 7.66059682e-02 1.93559602e-01 -9.77553964e-01 8.26055780e-02 1.93568647e-01 -9.77054894e-01 8.86038840e-02 1.93532854e-01 -9.76525784e-01 9.45985615e-02 1.93525478e-01 -9.75891471e-01 1.00590177e-01 1.93498582e-01 -9.75304008e-01 1.06577709e-01 1.93469509e-01 -9.74627018e-01 1.12555906e-01 1.93445399e-01 -9.73906994e-01 1.18535854e-01 1.93465278e-01 -9.73177731e-01 1.24513157e-01 1.93445131e-01 -9.72400546e-01 1.30477861e-01 1.93442762e-01 -9.71530974e-01 1.36441246e-01 1.93460882e-01 -9.70724881e-01 1.42400622e-01 1.93436891e-01 -9.69835460e-01 1.48355410e-01 1.93447471e-01 -9.68883574e-01 1.54306561e-01 1.93443283e-01 -9.67919946e-01 1.60243735e-01 1.93461239e-01 -9.66945112e-01 1.66178688e-01 1.93460375e-01 -9.65863109e-01 1.72109172e-01 1.93447530e-01 -9.64808166e-01 1.78032413e-01 1.93460107e-01 -9.63673294e-01 1.83950588e-01 1.93465397e-01 -9.62574363e-01 1.89857364e-01 1.93454504e-01 -9.61379945e-01 1.95762292e-01 1.93459988e-01 -9.60177779e-01 2.01654598e-01 1.93456724e-01 -9.58882689e-01 2.07544446e-01 1.93456009e-01 -9.57622528e-01 2.13428438e-01 1.93435460e-01 -9.56257999e-01 2.19301254e-01 1.93416312e-01 -9.54931140e-01 2.25166395e-01 1.93409383e-01 -9.53540623e-01 2.31013343e-01 1.93417072e-01 -9.52102304e-01 2.36863822e-01 1.93423152e-01 -9.50616956e-01 2.42701560e-01 1.93428010e-01 -9.49072719e-01 2.48530313e-01 1.93449229e-01 -9.47564065e-01 2.54348993e-01 1.93439662e-01 -9.45955038e-01 2.60157645e-01 1.93448797e-01 -9.44376767e-01 2.65957206e-01 1.93433389e-01 -9.42712665e-01 2.71750838e-01 1.93446457e-01 -9.41031635e-01 2.77523667e-01 1.93460688e-01 -9.39283490e-01 2.83285648e-01 1.93484187e-01 -9.37517524e-01 2.89054930e-01 1.93479523e-01 -9.35759366e-01 2.94801444e-01 1.93475261e-01 -9.33908820e-01 3.00523132e-01 1.93498313e-01 -9.32055950e-01 3.06261092e-01 1.93491042e-01 -9.30158198e-01 3.11961502e-01 1.93500653e-01 -9.28226054e-01 3.17676753e-01 1.93486631e-01 -9.26248074e-01 3.23366195e-01 1.93479180e-01 -9.24267054e-01 3.29034328e-01 1.93478242e-01 -9.22194958e-01 3.34707201e-01 1.93490177e-01 -9.20169652e-01 3.40348810e-01 1.93499491e-01 -9.18075681e-01 3.45996737e-01 1.93508610e-01 -9.15927708e-01 3.51619154e-01 1.93482071e-01 -9.13767159e-01 3.57226819e-01 1.93488598e-01 -9.11549568e-01 3.62841100e-01 1.93476260e-01 -9.09263492e-01 3.68426114e-01 1.93448037e-01 -9.07021463e-01 3.73993248e-01 1.93441153e-01 -9.04694438e-01 3.79560471e-01 1.93454936e-01 -9.02321577e-01 3.85097742e-01 1.93454444e-01 -8.99971187e-01 3.90634716e-01 1.93452358e-01 -8.97527456e-01 3.96146387e-01 1.93466544e-01 -8.95110369e-01 4.01648402e-01 1.93467930e-01 -8.92639995e-01 4.07125324e-01 1.93471596e-01 -8.90087724e-01 4.12588775e-01 1.93518162e-01 -8.87554348e-01 4.18052942e-01 1.93508536e-01 -8.84971678e-01 4.23480093e-01 1.93517491e-01 -8.82381976e-01 4.28907335e-01 1.93534642e-01 -8.79711926e-01 4.34310526e-01 1.93507448e-01 -8.77042949e-01 4.39698398e-01 1.93525225e-01 -8.74283791e-01 4.45078939e-01 1.93519861e-01 -8.71567190e-01 4.50424731e-01 1.93509847e-01 -8.68766606e-01 4.55775499e-01 1.93528712e-01 -8.65977228e-01 4.61081237e-01 1.93559036e-01 -8.63117218e-01 4.66388822e-01 1.93640992e-01 -8.60200047e-01 4.71658677e-01 1.93820089e-01 -8.57273638e-01 4.76904333e-01 1.93957552e-01 -8.54648709e-01 4.82358277e-01 1.92031443e-01 -8.51543665e-01 4.87511814e-01 1.92875609e-01 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. 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. 0. -7.85623312e-01 5.88213384e-01 1.91822514e-01 -7.82139599e-01 5.93138695e-01 1.90886647e-01 -7.78586328e-01 5.97999036e-01 1.90293968e-01 -7.74896860e-01 6.02784693e-01 1.90198869e-01 -7.70860910e-01 6.07237577e-01 1.92319721e-01 -7.67166078e-01 6.12001419e-01 1.92126036e-01 -7.63356686e-01 6.16670668e-01 1.92230567e-01 -7.59615004e-01 6.21375680e-01 1.91981360e-01 -7.55488992e-01 6.25770688e-01 1.93981841e-01 -7.51703501e-01 6.30416691e-01 1.93674281e-01 -7.47803867e-01 6.35064244e-01 1.93481281e-01 -7.43917108e-01 6.39635623e-01 1.93373173e-01 -7.40013838e-01 6.44190967e-01 1.93347037e-01 -7.36016929e-01 6.48740947e-01 1.93323478e-01 -7.32025683e-01 6.53221786e-01 1.93278179e-01 -7.28040636e-01 6.57732069e-01 1.93261698e-01 -7.23979950e-01 6.62166715e-01 1.93272367e-01 -7.19908893e-01 6.66601539e-01 1.93263218e-01 -7.15778947e-01 6.71026707e-01 1.93241805e-01 -7.11666942e-01 6.75375581e-01 1.93235800e-01 -7.07498670e-01 6.79766178e-01 1.93215162e-01 -7.03304231e-01 6.84093893e-01 1.93204984e-01 -6.99112236e-01 6.88405931e-01 1.93203270e-01 -6.94885969e-01 6.92656994e-01 1.93178087e-01 -6.90602362e-01 6.96905792e-01 1.93176612e-01 -6.86319947e-01 7.01135159e-01 1.93168670e-01 -6.82014465e-01 7.05342591e-01 1.93048462e-01 -6.77684367e-01 7.09522307e-01 1.93019733e-01 -6.73321068e-01 7.13659525e-01 1.93165228e-01 -6.68930709e-01 7.17761576e-01 1.93149477e-01 -6.64502680e-01 7.21866369e-01 1.93103328e-01 -6.60082161e-01 7.25928664e-01 1.93042412e-01 -6.55616105e-01 7.29977727e-01 1.93039477e-01 -6.51101947e-01 7.33974636e-01 1.93038359e-01 -6.46594524e-01 7.37986207e-01 1.93046853e-01 -6.42079473e-01 7.41930902e-01 1.93053782e-01 -6.37493253e-01 7.45837569e-01 1.93026796e-01 -6.32903814e-01 7.49770761e-01 1.92960501e-01 -6.28317833e-01 7.53627539e-01 1.92944869e-01 -6.23687029e-01 7.57464111e-01 1.92927182e-01 -6.19020104e-01 7.61286616e-01 1.92888230e-01 -6.14348233e-01 7.65102684e-01 1.92910790e-01 -6.09639764e-01 7.68838584e-01 1.92890808e-01 -6.04892612e-01 7.72550941e-01 1.92869797e-01 -6.00140989e-01 7.76268244e-01 1.92861527e-01 -5.95392466e-01 7.79956579e-01 1.92843124e-01 -5.90597808e-01 7.83571124e-01 1.92841366e-01 -5.85759103e-01 7.87167728e-01 1.92843109e-01 -5.80940008e-01 7.90761590e-01 1.92827359e-01 -5.76058388e-01 7.94334650e-01 1.92836896e-01 -5.71185946e-01 7.97839522e-01 1.92832813e-01 -5.66286206e-01 8.01307917e-01 1.92821622e-01 -5.61335921e-01 8.04789066e-01 1.92825064e-01 -5.56392133e-01 8.08235645e-01 1.92845136e-01 -5.51429272e-01 8.11597645e-01 1.92855448e-01 -5.46441853e-01 8.14955115e-01 1.92870334e-01 -5.41415513e-01 8.18302095e-01 1.92877665e-01 -5.36383033e-01 8.21634829e-01 1.92894399e-01 -5.31351089e-01 8.24895203e-01 1.92872569e-01 -5.26276290e-01 8.28129828e-01 1.92856804e-01 -5.21176815e-01 8.31328034e-01 1.92844078e-01 -5.16058981e-01 8.34574401e-01 1.92832664e-01 -5.10948956e-01 8.37712228e-01 1.92815810e-01 -5.05800009e-01 8.40830505e-01 1.92799196e-01 -5.00614464e-01 8.43930244e-01 1.92791075e-01 -4.95433688e-01 8.46973598e-01 1.92761898e-01 -4.90237474e-01 8.49959016e-01 1.92771971e-01 -4.85004574e-01 8.52977216e-01 1.92768931e-01 -4.79745358e-01 8.55932593e-01 1.92764580e-01 -4.74494994e-01 8.58867168e-01 1.92752972e-01 -4.69205081e-01 8.61743510e-01 1.92762330e-01 -4.63923872e-01 8.64617050e-01 1.92760423e-01 -4.58621264e-01 8.67439687e-01 1.92767411e-01 -4.53269571e-01 8.70282948e-01 1.92773581e-01 -4.47943628e-01 8.72999191e-01 1.92776173e-01 -4.42572504e-01 8.75778437e-01 1.92778274e-01 -4.37200367e-01 8.78448665e-01 1.92764342e-01 -4.31792349e-01 8.81097376e-01 1.92773342e-01 -4.26383168e-01 8.83733094e-01 1.92760915e-01 -4.20931607e-01 8.86351943e-01 1.92758992e-01 -4.15501952e-01 8.88915539e-01 1.92752808e-01 -4.10026819e-01 8.91447246e-01 1.92739218e-01 -4.04554486e-01 8.93957555e-01 1.92737713e-01 -3.99072766e-01 8.96417916e-01 1.92739487e-01 -3.93564820e-01 8.98833215e-01 1.92723200e-01 -3.88032526e-01 9.01225984e-01 1.92735657e-01 -3.82489532e-01 9.03608859e-01 1.92724749e-01 -3.76957059e-01 9.05947030e-01 1.92728549e-01 -3.71379524e-01 9.08221304e-01 1.92710280e-01 -3.65813881e-01 9.10539746e-01 1.92711383e-01 -3.60201716e-01 9.12720025e-01 1.92693055e-01 -3.54598820e-01 9.14891183e-01 1.92698687e-01 -3.48981559e-01 9.17046130e-01 1.92700446e-01 -3.43350470e-01 9.19184029e-01 1.92713678e-01 -3.37698996e-01 9.21329021e-01 1.92670196e-01 -3.32052112e-01 9.23334658e-01 1.92663342e-01 -3.26365143e-01 9.25401807e-01 1.92675114e-01 -3.20678234e-01 9.27337289e-01 1.92686483e-01 -3.14982742e-01 9.29300785e-01 1.92698076e-01 -3.09292555e-01 9.31187034e-01 1.92695141e-01 -3.03558499e-01 9.33086872e-01 1.92695364e-01 -2.97837317e-01 9.34984386e-01 1.92681178e-01 -2.92094409e-01 9.36737299e-01 1.92693099e-01 -2.86342561e-01 9.38575983e-01 1.92695722e-01 -2.80576319e-01 9.40273702e-01 1.92686021e-01 -2.74800628e-01 9.41961467e-01 1.92692056e-01 -2.69014984e-01 9.43630874e-01 1.92686781e-01 -2.63222933e-01 9.45300698e-01 1.92681372e-01 -2.57416636e-01 9.46896553e-01 1.92679778e-01 -2.51602083e-01 9.48424637e-01 1.92672834e-01 -2.45777607e-01 9.49929714e-01 1.92678392e-01 -2.39942744e-01 9.51478004e-01 1.92671508e-01 -2.34100461e-01 9.52946901e-01 1.92685679e-01 -2.28248402e-01 9.54347372e-01 1.92686588e-01 -2.22390443e-01 9.55675960e-01 1.92677006e-01 -2.16521606e-01 9.57044840e-01 1.92676127e-01 -2.10642308e-01 9.58391368e-01 1.92680523e-01 -2.04760462e-01 9.59664285e-01 1.92671522e-01 -1.98862523e-01 9.60877955e-01 1.92661330e-01 -1.92968339e-01 9.62079346e-01 1.92652956e-01 -1.87060267e-01 9.63270605e-01 1.92660272e-01 -1.81143150e-01 9.64406848e-01 1.92640141e-01 -1.75224811e-01 9.65448618e-01 1.92643076e-01 -1.69297829e-01 9.66561854e-01 1.92642972e-01 -1.63365006e-01 9.67573583e-01 1.92644686e-01 -1.57422543e-01 9.68544304e-01 1.92647681e-01 -1.51479781e-01 9.69500542e-01 1.92651719e-01 -1.45526469e-01 9.70406175e-01 1.92651674e-01 -1.39568642e-01 9.71238613e-01 1.92648113e-01 -1.33608162e-01 9.72126245e-01 1.92641273e-01 -1.27641514e-01 9.72873330e-01 1.92649111e-01 -1.21666491e-01 9.73645806e-01 1.92649245e-01 -1.15691870e-01 9.74365413e-01 1.92647696e-01 -1.09711975e-01 9.75069761e-01 1.92651749e-01 -1.03725649e-01 9.75736558e-01 1.92635715e-01 -9.77362245e-02 9.76393938e-01 1.92644522e-01 -9.17450562e-02 9.76933241e-01 1.92640990e-01 -8.57484192e-02 9.77468014e-01 1.92635879e-01 -7.97487944e-02 9.77959394e-01 1.92640543e-01 -7.37462193e-02 9.78438795e-01 1.92636073e-01 -6.77414238e-02 9.78866756e-01 1.92635998e-01 -6.17332049e-02 9.79325354e-01 1.92631990e-01 -5.57235666e-02 9.79634941e-01 1.92631572e-01 -4.97112907e-02 9.79994357e-01 1.92630351e-01 -4.36970145e-02 9.80283439e-01 1.92638651e-01 -3.76816355e-02 9.80526567e-01 1.92633778e-01 -3.16642448e-02 9.80753183e-01 1.92628071e-01 -2.56459620e-02 9.80937600e-01 1.92631990e-01 -1.96268093e-02 9.81018782e-01 1.92632824e-01 -1.36066908e-02 9.81176555e-01 1.92629382e-01 -7.58624496e-03 9.81239557e-01 1.92631721e-01 -1.56551506e-03 9.81244564e-01 1.92631841e-01 4.45534568e-03 9.81245041e-01 1.92624584e-01 1.04759606e-02 9.81229007e-01 1.92624524e-01 1.64962281e-02 9.81074870e-01 1.92629844e-01 2.25160513e-02 9.81005728e-01 1.92615077e-01 2.85351109e-02 9.80825543e-01 1.92601830e-01 3.45526859e-02 9.80601251e-01 1.92606077e-01 4.05692868e-02 9.80378151e-01 1.92606151e-01 4.65839393e-02 9.80121017e-01 1.92604616e-01 5.25967665e-02 9.79816318e-01 1.92609161e-01 5.86079322e-02 9.79516327e-01 1.92615420e-01 6.46171272e-02 9.79098141e-01 1.92612365e-01 7.06243664e-02 9.78674352e-01 1.92603245e-01 7.66281039e-02 9.78220582e-01 1.92619815e-01 8.26275274e-02 9.77725387e-01 1.92621082e-01 8.86269659e-02 9.77198422e-01 1.92599863e-01 9.46212336e-02 9.76700664e-01 1.92575783e-01 1.00612536e-01 9.76054788e-01 1.92575514e-01 1.06598414e-01 9.75448966e-01 1.92589477e-01 1.12583049e-01 9.74782288e-01 1.92595273e-01 1.18561298e-01 9.74068940e-01 1.92576051e-01 1.24534756e-01 9.73336756e-01 1.92578778e-01 1.30508721e-01 9.72565889e-01 1.92563072e-01 1.36470124e-01 9.71687794e-01 1.92591041e-01 1.42429948e-01 9.70885098e-01 1.92583919e-01 1.48387223e-01 9.69995499e-01 1.92578509e-01 1.54333308e-01 9.69044149e-01 1.92562476e-01 1.60278916e-01 9.68082726e-01 1.92563817e-01 1.66216344e-01 9.67116058e-01 1.92527622e-01 1.72147438e-01 9.66016710e-01 1.92549199e-01 1.78070381e-01 9.64967847e-01 1.92565143e-01 1.83987737e-01 9.63826597e-01 1.92576408e-01 1.89896971e-01 9.62747335e-01 1.92540735e-01 1.95805460e-01 9.61557925e-01 1.92519143e-01 2.01697990e-01 9.60359037e-01 1.92514434e-01 2.07587868e-01 9.59049344e-01 1.92525089e-01 2.13470250e-01 9.57791865e-01 1.92527965e-01 2.19345510e-01 9.56423819e-01 1.92495480e-01 2.25207910e-01 9.55105603e-01 1.92504957e-01 2.31063977e-01 9.53710318e-01 1.92494556e-01 2.36912698e-01 9.52274919e-01 1.92492515e-01 2.42747054e-01 9.50793743e-01 1.92494601e-01 2.48586178e-01 9.49238241e-01 1.92486882e-01 2.54395634e-01 9.47734833e-01 1.92506850e-01 2.60205448e-01 9.46116745e-01 1.92524016e-01 2.66014367e-01 9.44550216e-01 1.92511499e-01 2.71796465e-01 9.42886114e-01 1.92514539e-01 2.77576476e-01 9.41210866e-01 1.92507043e-01 2.83349752e-01 9.39474046e-01 1.92488655e-01 2.89110988e-01 9.37696636e-01 1.92489401e-01 2.94859320e-01 9.35947955e-01 1.92481086e-01 3.00595701e-01 9.34094787e-01 1.92477658e-01 3.06330264e-01 9.32235181e-01 1.92465082e-01 3.12032431e-01 9.30338800e-01 1.92452595e-01 3.17745358e-01 9.28406417e-01 1.92447647e-01 3.23432326e-01 9.26435649e-01 1.92443952e-01 3.29107761e-01 9.24456716e-01 1.92443788e-01 3.34780127e-01 9.22379076e-01 1.92437053e-01 3.40423554e-01 9.20373797e-01 1.92423299e-01 3.46071750e-01 9.18272495e-01 1.92430645e-01 3.51699948e-01 9.16120112e-01 1.92413718e-01 3.57310474e-01 9.13961172e-01 1.92411080e-01 3.62930924e-01 9.11752105e-01 1.92393646e-01 3.68507594e-01 9.09448564e-01 1.92384288e-01 3.74078095e-01 9.07216668e-01 1.92374855e-01 3.79638821e-01 9.04882729e-01 1.92362309e-01 3.85201126e-01 9.02509451e-01 1.92333803e-01 3.90727431e-01 9.00156140e-01 1.92331061e-01 3.96237731e-01 8.97717655e-01 1.92337260e-01 4.01747704e-01 8.95304263e-01 1.92326978e-01 4.07224506e-01 8.92839730e-01 1.92332372e-01 4.12695169e-01 8.90287161e-01 1.92313150e-01 4.18161362e-01 8.87753427e-01 1.92301795e-01 4.23587441e-01 8.85190368e-01 1.92285582e-01 4.29019421e-01 8.82595301e-01 1.92300245e-01 4.34423596e-01 8.79915059e-01 1.92306921e-01 4.39815640e-01 8.77263963e-01 1.92302018e-01 4.45195079e-01 8.74486506e-01 1.92295209e-01 4.50542390e-01 8.71773779e-01 1.92279011e-01 4.55897033e-01 8.68967772e-01 1.92281798e-01 4.61208791e-01 8.66174638e-01 1.92264602e-01 4.66527224e-01 8.63354266e-01 1.92271277e-01 4.71824229e-01 8.60445678e-01 1.92250907e-01 4.77093667e-01 8.57543111e-01 1.92263067e-01 4.82341856e-01 8.54592025e-01 1.92251533e-01 4.87564802e-01 8.51644397e-01 1.92228943e-01 4.92788613e-01 8.48605871e-01 1.92239657e-01 4.97979492e-01 8.45583022e-01 1.92226052e-01 5.03152072e-01 8.42533171e-01 1.92231789e-01 5.08334041e-01 8.39423537e-01 1.92216203e-01 5.13451099e-01 8.36301982e-01 1.92240432e-01 5.18572748e-01 8.33111882e-01 1.92237958e-01 5.23695648e-01 8.29916179e-01 1.92232311e-01 5.28766036e-01 8.26672554e-01 1.92238465e-01 5.33832371e-01 8.23436081e-01 1.92223012e-01 5.38881421e-01 8.20111394e-01 1.92237109e-01 5.43901622e-01 8.16820920e-01 1.92233294e-01 5.48898995e-01 8.13466847e-01 1.92231953e-01 5.53884208e-01 8.10051143e-01 1.92226633e-01 5.58841705e-01 8.06675494e-01 1.92217112e-01 5.63776970e-01 8.03239465e-01 1.92213491e-01 5.68708658e-01 7.99731910e-01 1.92226529e-01 5.73579133e-01 7.96236753e-01 1.92231566e-01 5.78453362e-01 7.92715490e-01 1.92214042e-01 5.83333254e-01 7.89172232e-01 1.92206070e-01 5.88152349e-01 7.85577118e-01 1.92209989e-01 5.92949033e-01 7.81933427e-01 1.92210481e-01 5.97743392e-01 7.78275788e-01 1.92196161e-01 6.02526724e-01 7.74582207e-01 1.92190379e-01 6.07240140e-01 7.70897925e-01 1.92192152e-01 6.11987531e-01 7.67150402e-01 1.92197055e-01 6.16672456e-01 7.63344109e-01 1.92184538e-01 6.21338487e-01 7.59576678e-01 1.92185268e-01 6.26010120e-01 7.55745828e-01 1.92189246e-01 6.30601645e-01 7.51906693e-01 1.92185670e-01 6.35228813e-01 7.47992277e-01 1.92183405e-01 6.39786065e-01 7.44082689e-01 1.92191124e-01 6.44338071e-01 7.40167499e-01 1.92199826e-01 6.48883641e-01 7.36174107e-01 1.92200154e-01 6.53363764e-01 7.32179224e-01 1.92192763e-01 6.57883584e-01 7.28168070e-01 1.92172304e-01 6.62314773e-01 7.24125028e-01 1.92183137e-01 6.66752756e-01 7.20052421e-01 1.92190841e-01 6.71165824e-01 7.15912163e-01 1.92192361e-01 6.75524354e-01 7.11816549e-01 1.92185909e-01 6.79913819e-01 7.07647026e-01 1.92197472e-01 6.84240639e-01 7.03441799e-01 1.92188472e-01 6.88553929e-01 6.99262500e-01 1.92180455e-01 6.92820132e-01 6.95026517e-01 1.92179680e-01 6.97053194e-01 6.90740883e-01 1.92179516e-01 7.01280951e-01 6.86446786e-01 1.92174837e-01 7.05478072e-01 6.82134211e-01 1.92171231e-01 7.09649205e-01 6.77804470e-01 1.92165539e-01 7.13814080e-01 6.73464656e-01 1.92149356e-01 7.17921734e-01 6.69063389e-01 1.92147002e-01 7.22017288e-01 6.64632201e-01 1.92140266e-01 7.26075947e-01 6.60204172e-01 1.92129940e-01 7.30114341e-01 6.55740678e-01 1.92130789e-01 7.34116852e-01 6.51222110e-01 1.92131177e-01 7.38144696e-01 6.46705151e-01 1.92127764e-01 7.42077589e-01 6.42208755e-01 1.92112803e-01 7.45987535e-01 6.37604117e-01 1.92120135e-01 7.49903917e-01 6.33012652e-01 1.92135021e-01 7.53758729e-01 6.28425717e-01 1.92127168e-01 7.57592559e-01 6.23788536e-01 1.92129612e-01 7.61408627e-01 6.19113147e-01 1.92140028e-01 7.65230060e-01 6.14448369e-01 1.92110091e-01 7.68968403e-01 6.09739304e-01 1.92104459e-01 7.72672653e-01 6.04984879e-01 1.92124769e-01 7.76392102e-01 6.00225508e-01 1.92117572e-01 7.80080378e-01 5.95481277e-01 1.92101061e-01 7.83688009e-01 5.90686023e-01 1.92122325e-01 7.87286878e-01 5.85846186e-01 1.92122176e-01 7.90877581e-01 5.81023455e-01 1.92106724e-01 7.94452846e-01 5.76142073e-01 1.92120969e-01 7.97960222e-01 5.71246088e-01 1.92112342e-01 8.01424503e-01 5.66368043e-01 1.92113668e-01 8.04911196e-01 5.61415613e-01 1.92105368e-01 8.08350801e-01 5.56469023e-01 1.92120716e-01 8.11723053e-01 5.51512837e-01 1.92112669e-01 8.15083802e-01 5.46524584e-01 1.92097440e-01 8.18429589e-01 5.41494787e-01 1.92120582e-01 8.21762979e-01 5.36462426e-01 1.92130849e-01 8.25030208e-01 5.31426787e-01 1.92128032e-01 8.28252852e-01 5.26351452e-01 1.92133039e-01 8.31443191e-01 5.21244466e-01 1.92166343e-01 8.34691286e-01 5.16129732e-01 1.92158461e-01 8.37824821e-01 5.11014998e-01 1.92155540e-01 8.40938568e-01 5.05862057e-01 1.92172229e-01 8.44038367e-01 5.00676036e-01 1.92159519e-01 8.47070932e-01 4.95491385e-01 1.92174718e-01 8.50062072e-01 4.90294278e-01 1.92176148e-01 8.53078246e-01 4.85062003e-01 1.92170665e-01 8.56035113e-01 4.79807138e-01 1.92173764e-01 8.58975410e-01 4.74551648e-01 1.92152873e-01 8.61851215e-01 4.69266444e-01 1.92171514e-01 8.64726007e-01 4.63979542e-01 1.92161426e-01 8.67542446e-01 4.58669126e-01 1.92162558e-01 8.70389521e-01 4.53324050e-01 1.92177594e-01 8.73109698e-01 4.47977513e-01 1.92177176e-01 8.75881076e-01 4.42615300e-01 1.92189038e-01 8.78551841e-01 4.37247247e-01 1.92202345e-01 8.81202936e-01 4.31832075e-01 1.92200735e-01 8.83836091e-01 4.26415592e-01 1.92204177e-01 8.86457980e-01 4.20980453e-01 1.92189232e-01 8.89027596e-01 4.15537894e-01 1.92206040e-01 8.91550601e-01 4.10071820e-01 1.92202404e-01 8.94057333e-01 4.04598564e-01 1.92223221e-01 8.96515906e-01 3.99101943e-01 1.92227274e-01 8.98926318e-01 3.93597782e-01 1.92231148e-01 9.01321352e-01 3.88070107e-01 1.92237943e-01 9.03700054e-01 3.82524967e-01 1.92244321e-01 9.06033278e-01 3.76994014e-01 1.92256987e-01 9.08309937e-01 3.71417522e-01 1.92269593e-01 9.10625160e-01 3.65846634e-01 1.92252591e-01 9.12801087e-01 3.60233814e-01 1.92269966e-01 9.14976776e-01 3.54630262e-01 1.92257136e-01 9.17133272e-01 3.49016666e-01 1.92260519e-01 9.19274867e-01 3.43384773e-01 1.92256436e-01 9.21408236e-01 3.37724745e-01 1.92260057e-01 9.23416317e-01 3.32079858e-01 1.92262962e-01 9.25481975e-01 3.26390594e-01 1.92262158e-01 9.27419782e-01 3.20709616e-01 1.92262426e-01 9.29367304e-01 3.15011799e-01 1.92258418e-01 9.31267977e-01 3.09314758e-01 1.92269266e-01 9.33169782e-01 3.03585410e-01 1.92262381e-01 9.35064793e-01 2.97862172e-01 1.92258716e-01 9.36820269e-01 2.92119026e-01 1.92272663e-01 9.38643038e-01 2.86362916e-01 1.92286074e-01 9.40352619e-01 2.80590087e-01 1.92269504e-01 9.42032337e-01 2.74823010e-01 1.92283958e-01 9.43710446e-01 2.69030452e-01 1.92275196e-01 9.45376694e-01 2.63241053e-01 1.92282468e-01 9.46966052e-01 2.57435203e-01 1.92300364e-01 9.48496997e-01 2.51620561e-01 1.92297250e-01 9.50006068e-01 2.45790705e-01 1.92300260e-01 9.51543450e-01 2.39958718e-01 1.92324281e-01 9.52994406e-01 2.34109297e-01 1.92326725e-01 9.54423010e-01 2.28265315e-01 1.92301765e-01 9.55753326e-01 2.22405538e-01 1.92309141e-01 9.57118511e-01 2.16535956e-01 1.92312360e-01 9.58463132e-01 2.10657194e-01 1.92318067e-01 9.59732652e-01 2.04767883e-01 1.92333654e-01 9.60947454e-01 1.98876128e-01 1.92325532e-01 9.62151945e-01 1.92979500e-01 1.92300320e-01 9.63346899e-01 1.87073410e-01 1.92289874e-01 9.64478731e-01 1.81156054e-01 1.92283317e-01 9.65523005e-01 1.75239548e-01 1.92287400e-01 9.66631770e-01 1.69311911e-01 1.92291468e-01 9.67645466e-01 1.63378716e-01 1.92298487e-01 9.68616128e-01 1.57431960e-01 1.92301050e-01 9.69573557e-01 1.51491150e-01 1.92300633e-01 9.70474243e-01 1.45533711e-01 1.92312613e-01 9.71309423e-01 1.39576271e-01 1.92321509e-01 9.72192407e-01 1.33614287e-01 1.92323178e-01 9.72943664e-01 1.27650112e-01 1.92319050e-01 9.73715007e-01 1.21672481e-01 1.92331985e-01 9.74435687e-01 1.15700461e-01 1.92319110e-01 9.75138426e-01 1.09716326e-01 1.92335665e-01 9.75798786e-01 1.03729837e-01 1.92341298e-01 9.76451576e-01 9.77402255e-02 1.92359537e-01 9.76990283e-01 9.17474031e-02 1.92373484e-01 9.77530599e-01 8.57504159e-02 1.92360520e-01 9.78022933e-01 7.97524750e-02 1.92365721e-01 9.78498220e-01 7.37493262e-02 1.92380086e-01 9.78923976e-01 6.77442774e-02 1.92380130e-01 9.79384303e-01 6.17344379e-02 1.92356899e-01 9.79695559e-01 5.57245649e-02 1.92382410e-01 9.80043232e-01 4.97120135e-02 1.92392081e-01 9.80335355e-01 4.36974615e-02 1.92401171e-01 9.80575562e-01 3.76817062e-02 1.92411795e-01 9.80804026e-01 3.16639803e-02 1.92398861e-01 9.80984211e-01 2.56455373e-02 1.92406207e-01 9.81075287e-01 1.96260232e-02 1.92389831e-01 9.81226206e-01 1.36057334e-02 1.92396611e-01 9.81291473e-01 7.58499792e-03 1.92403764e-01 9.81298268e-01 1.56383321e-03 1.92391947e-01 9.81297970e-01 -4.45737271e-03 1.92385852e-01 9.81278956e-01 -1.04782740e-02 1.92390531e-01 9.81128633e-01 -1.64988227e-02 1.92397490e-01 9.81053591e-01 -2.25188676e-02 1.92394346e-01 9.80873227e-01 -2.85378899e-02 1.92399725e-01 9.80652452e-01 -3.45561840e-02 1.92400932e-01 9.80429471e-01 -4.05729786e-02 1.92396536e-01 9.80166376e-01 -4.65873629e-02 1.92416742e-01 9.79858994e-01 -5.26010357e-02 1.92421436e-01 9.79556680e-01 -5.86124621e-02 1.92413881e-01 9.79139566e-01 -6.46204650e-02 1.92418948e-01 9.78717387e-01 -7.06286654e-02 1.92421094e-01 9.78267312e-01 -7.66323507e-02 1.92425981e-01 9.77768958e-01 -8.26322436e-02 1.92440078e-01 9.77266967e-01 -8.86311755e-02 1.92432597e-01 9.76734877e-01 -9.46259424e-02 1.92426741e-01 9.76096272e-01 -1.00618504e-01 1.92411318e-01 9.75495219e-01 -1.06605664e-01 1.92434475e-01 9.74819601e-01 -1.12585999e-01 1.92430332e-01 9.74100292e-01 -1.18567593e-01 1.92434162e-01 9.73368704e-01 -1.24543950e-01 1.92429751e-01 9.72590864e-01 -1.30512670e-01 1.92431301e-01 9.71724987e-01 -1.36477187e-01 1.92428544e-01 9.70912755e-01 -1.42436296e-01 1.92440286e-01 9.70023572e-01 -1.48392782e-01 1.92448914e-01 9.69060957e-01 -1.54340923e-01 1.92494944e-01 9.68104482e-01 -1.60282940e-01 1.92479059e-01 9.67126667e-01 -1.66214675e-01 1.92495540e-01 9.66039598e-01 -1.72146156e-01 1.92497954e-01 9.64982331e-01 -1.78069785e-01 1.92519501e-01 9.63855505e-01 -1.83993801e-01 1.92483947e-01 9.62746859e-01 -1.89899370e-01 1.92532748e-01 9.61547434e-01 -1.95801020e-01 1.92556038e-01 9.60343778e-01 -2.01697513e-01 1.92570791e-01 9.59051847e-01 -2.07587183e-01 1.92557126e-01 9.57780778e-01 -2.13467404e-01 1.92596242e-01 9.56413627e-01 -2.19340071e-01 1.92589656e-01 9.55084085e-01 -2.25206628e-01 1.92592770e-01 9.53693092e-01 -2.31058717e-01 1.92595825e-01 9.52255011e-01 -2.36906976e-01 1.92595199e-01 9.50772762e-01 -2.42750451e-01 1.92587227e-01 9.49236929e-01 -2.48577088e-01 1.92579687e-01 9.47724104e-01 -2.54394680e-01 1.92575231e-01 9.46112335e-01 -2.60202885e-01 1.92597255e-01 9.44537878e-01 -2.66012430e-01 1.92553565e-01 9.42878306e-01 -2.71802247e-01 1.92539901e-01 9.41199958e-01 -2.77575999e-01 1.92535847e-01 9.39452469e-01 -2.83345461e-01 1.92544967e-01 9.37683821e-01 -2.89110750e-01 1.92564577e-01 9.35924768e-01 -2.94858187e-01 1.92560390e-01 9.34080064e-01 -3.00587744e-01 1.92536265e-01 9.32224810e-01 -3.06322008e-01 1.92544252e-01 9.30314302e-01 -3.12027246e-01 1.92536041e-01 9.28392529e-01 -3.17740798e-01 1.92540213e-01 9.26417053e-01 -3.23432595e-01 1.92537412e-01 9.24433887e-01 -3.29099208e-01 1.92532420e-01 9.22360539e-01 -3.34773511e-01 1.92540675e-01 9.20342386e-01 -3.40414762e-01 1.92541629e-01 9.18251634e-01 -3.46075445e-01 1.92519486e-01 9.16101694e-01 -3.51695418e-01 1.92505866e-01 9.13938642e-01 -3.57298464e-01 1.92518353e-01 9.11719501e-01 -3.62911910e-01 1.92529365e-01 9.09427762e-01 -3.68499309e-01 1.92520484e-01 9.07190204e-01 -3.74067783e-01 1.92503184e-01 9.04861927e-01 -3.79635274e-01 1.92505762e-01 9.02485609e-01 -3.85180891e-01 1.92513689e-01 9.00136709e-01 -3.90713573e-01 1.92504257e-01 8.97688568e-01 -3.96222889e-01 1.92542702e-01 8.95280123e-01 -4.01730150e-01 1.92493826e-01 8.92812848e-01 -4.07208830e-01 1.92496628e-01 8.90263796e-01 -4.12684083e-01 1.92509130e-01 8.87718022e-01 -4.18137848e-01 1.92540586e-01 8.85138273e-01 -4.23577517e-01 1.92567840e-01 8.82546782e-01 -4.28993702e-01 1.92593247e-01 8.79866004e-01 -4.34396654e-01 1.92582890e-01 8.77207279e-01 -4.39785719e-01 1.92604899e-01 8.74442339e-01 -4.45166171e-01 1.92606658e-01 8.71712685e-01 -4.50520575e-01 1.92632332e-01 8.68923664e-01 -4.55861390e-01 1.92631483e-01 8.66138458e-01 -4.61182505e-01 1.92632452e-01 8.63284171e-01 -4.66486871e-01 1.92636058e-01 8.60395133e-01 -4.71777648e-01 1.92644715e-01 8.57497334e-01 -4.77047890e-01 1.92647323e-01 8.54530454e-01 -4.82296288e-01 1.92661256e-01 8.51568222e-01 -4.87526923e-01 1.92692161e-01 8.48535120e-01 -4.92746979e-01 1.92708224e-01 8.45530689e-01 -4.97928530e-01 1.92683905e-01 8.42452466e-01 -5.03110647e-01 1.92684337e-01 8.39339793e-01 -5.08288443e-01 1.92686096e-01 8.36223662e-01 -5.13410151e-01 1.92672059e-01 8.33060861e-01 -5.18529296e-01 1.92679495e-01 8.29854429e-01 -5.23658335e-01 1.92652106e-01 8.26624513e-01 -5.28715372e-01 1.92658067e-01 8.23377907e-01 -5.33792853e-01 1.92670166e-01 8.20053756e-01 -5.38838148e-01 1.92660823e-01 8.16766858e-01 -5.43870509e-01 1.92644283e-01 8.13424647e-01 -5.48854709e-01 1.92640305e-01 8.09998989e-01 -5.53847909e-01 1.92628652e-01 8.06624413e-01 -5.58791101e-01 1.92604721e-01 8.03169906e-01 -5.63736856e-01 1.92635268e-01 7.99680710e-01 -5.68669558e-01 1.92621946e-01 7.96204746e-01 -5.73545516e-01 1.92593575e-01 7.92658150e-01 -5.78417718e-01 1.92569137e-01 7.89124250e-01 -5.83293080e-01 1.92547843e-01 7.85529077e-01 -5.88117898e-01 1.92564711e-01 7.81882048e-01 -5.92916012e-01 1.92532152e-01 7.78245270e-01 -5.97705662e-01 1.92543685e-01 7.74539649e-01 -6.02491319e-01 1.92526877e-01 7.70836592e-01 -6.07205689e-01 1.92541227e-01 7.67104626e-01 -6.11951351e-01 1.92523956e-01 7.63298452e-01 -6.16627038e-01 1.92542985e-01 7.59534657e-01 -6.21291459e-01 1.92592457e-01 7.55704522e-01 -6.25956953e-01 1.92602679e-01 7.51860440e-01 -6.30550861e-01 1.92638591e-01 7.47931480e-01 -6.35176182e-01 1.92650780e-01 7.44014502e-01 -6.39735818e-01 1.92638040e-01 7.40120113e-01 -6.44285619e-01 1.92654669e-01 7.36110568e-01 -6.48835957e-01 1.92625090e-01 7.32128322e-01 -6.53316438e-01 1.92609340e-01 7.28126824e-01 -6.57822132e-01 1.92597181e-01 7.24083245e-01 -6.62262678e-01 1.92576632e-01 7.20007300e-01 -6.66693091e-01 1.92586914e-01 7.15868890e-01 -6.71122134e-01 1.92569479e-01 7.11759567e-01 -6.75470769e-01 1.92613199e-01 7.07581222e-01 -6.79838419e-01 1.92620128e-01 7.03394175e-01 -6.84170485e-01 1.92635134e-01 6.99193239e-01 -6.88483715e-01 1.92620605e-01 6.94967270e-01 -6.92764342e-01 1.92597076e-01 6.90695822e-01 -6.97002053e-01 1.92560956e-01 6.86407089e-01 -7.01228499e-01 1.92544177e-01 6.82096243e-01 -7.05419481e-01 1.92540064e-01 6.77761793e-01 -7.09595621e-01 1.92532450e-01 6.73412263e-01 -7.13764846e-01 1.92513496e-01 6.69015646e-01 -7.17854321e-01 1.92533761e-01 6.64581835e-01 -7.21943438e-01 1.92577675e-01 6.60146117e-01 -7.25997329e-01 1.92584112e-01 6.55679405e-01 -7.30059206e-01 1.92572087e-01 6.51172280e-01 -7.34053731e-01 1.92556679e-01 6.46651328e-01 -7.38073230e-01 1.92548797e-01 6.42140985e-01 -7.42016852e-01 1.92554638e-01 6.37544692e-01 -7.45901823e-01 1.92569479e-01 6.32968962e-01 -7.49843299e-01 1.92504525e-01 6.28373027e-01 -7.53696084e-01 1.92499012e-01 6.23740673e-01 -7.57533193e-01 1.92495719e-01 6.19076192e-01 -7.61356711e-01 1.92456603e-01 6.14408016e-01 -7.65175283e-01 1.92431509e-01 6.09699786e-01 -7.68904567e-01 1.92410856e-01 6.04951978e-01 -7.72627890e-01 1.92408815e-01 6.00190461e-01 -7.76325285e-01 1.92449838e-01 5.95441461e-01 -7.80025125e-01 1.92431256e-01 5.90652704e-01 -7.83642769e-01 1.92398772e-01 5.85810721e-01 -7.87240684e-01 1.92408919e-01 5.80989838e-01 -7.90829003e-01 1.92413107e-01 5.76105714e-01 -7.94403791e-01 1.92419365e-01 5.71222425e-01 -7.97895491e-01 1.92440391e-01 5.66332161e-01 -8.01375926e-01 1.92437887e-01 5.61384022e-01 -8.04848552e-01 1.92426071e-01 5.56441128e-01 -8.08310866e-01 1.92377314e-01 5.51484466e-01 -8.11680317e-01 1.92391247e-01 5.46494484e-01 -8.15039992e-01 1.92390487e-01 5.41466713e-01 -8.18387806e-01 1.92389384e-01 5.36435485e-01 -8.21720064e-01 1.92400217e-01 5.31406164e-01 -8.24987352e-01 1.92363352e-01 5.26332617e-01 -8.28222990e-01 1.92344263e-01 5.21231949e-01 -8.31430078e-01 1.92307726e-01 5.16116798e-01 -8.34666193e-01 1.92332327e-01 5.11001647e-01 -8.37802172e-01 1.92313135e-01 5.05849123e-01 -8.40916455e-01 1.92331702e-01 5.00665069e-01 -8.44011724e-01 1.92341566e-01 4.95478660e-01 -8.47043931e-01 1.92327082e-01 4.90282804e-01 -8.50045621e-01 1.92314431e-01 4.85052943e-01 -8.53053391e-01 1.92316622e-01 4.79795486e-01 -8.56018960e-01 1.92306787e-01 4.74545211e-01 -8.58960867e-01 1.92301974e-01 4.69256520e-01 -8.61840665e-01 1.92294016e-01 4.63972896e-01 -8.64715338e-01 1.92281455e-01 4.58661705e-01 -8.67536068e-01 1.92261457e-01 4.53320920e-01 -8.70381236e-01 1.92249328e-01 4.47976977e-01 -8.73101354e-01 1.92271024e-01 4.42611367e-01 -8.75876188e-01 1.92263797e-01 4.37236935e-01 -8.78541291e-01 1.92279562e-01 4.31827337e-01 -8.81192803e-01 1.92283332e-01 4.26416069e-01 -8.83830369e-01 1.92274660e-01 4.20975298e-01 -8.86443555e-01 1.92293555e-01 4.15534705e-01 -8.89018238e-01 1.92266762e-01 4.10068870e-01 -8.91544342e-01 1.92261606e-01 4.04597938e-01 -8.94055605e-01 1.92228988e-01 3.99106771e-01 -8.96518826e-01 1.92217588e-01 3.93601418e-01 -8.98930490e-01 1.92217812e-01 3.88073891e-01 -9.01326597e-01 1.92218304e-01 3.82528126e-01 -9.03706014e-01 1.92227259e-01 3.76999050e-01 -9.06058967e-01 1.92207173e-01 3.71420234e-01 -9.08325016e-01 1.92202255e-01 3.65843654e-01 -9.10634100e-01 1.92216620e-01 3.60238433e-01 -9.12812054e-01 1.92218319e-01 3.54631275e-01 -9.14986014e-01 1.92207962e-01 3.49020243e-01 -9.17142391e-01 1.92218810e-01 3.43388051e-01 -9.19282138e-01 1.92220271e-01 3.37725461e-01 -9.21417117e-01 1.92214131e-01 3.32082927e-01 -9.23425078e-01 1.92229375e-01 3.26393366e-01 -9.25486982e-01 1.92237332e-01 3.20708483e-01 -9.27428305e-01 1.92222878e-01 3.15014690e-01 -9.29393113e-01 1.92239016e-01 3.09310496e-01 -9.31283772e-01 1.92257553e-01 3.03577811e-01 -9.33168173e-01 1.92276701e-01 2.97861904e-01 -9.35059607e-01 1.92287117e-01 2.92113721e-01 -9.36819494e-01 1.92292646e-01 2.86361724e-01 -9.38643336e-01 1.92323834e-01 2.80589253e-01 -9.40344572e-01 1.92320436e-01 2.74821788e-01 -9.42033827e-01 1.92312941e-01 2.69029170e-01 -9.43695664e-01 1.92355931e-01 2.63238460e-01 -9.45364058e-01 1.92353219e-01 2.57429421e-01 -9.46951687e-01 1.92362770e-01 2.51617342e-01 -9.48481798e-01 1.92380652e-01 2.45785639e-01 -9.49990094e-01 1.92413479e-01 2.39957005e-01 -9.51525748e-01 1.92410782e-01 2.34108329e-01 -9.53001440e-01 1.92408606e-01 2.28258625e-01 -9.54397857e-01 1.92426518e-01 2.22403273e-01 -9.55733359e-01 1.92446932e-01 2.16534823e-01 -9.57094431e-01 1.92448184e-01 2.10651651e-01 -9.58436608e-01 1.92434788e-01 2.04768211e-01 -9.59713280e-01 1.92441195e-01 1.98871791e-01 -9.60924208e-01 1.92458972e-01 1.92973331e-01 -9.62126374e-01 1.92446962e-01 1.87070951e-01 -9.63322937e-01 1.92429125e-01 1.81151778e-01 -9.64444280e-01 1.92450866e-01 1.75236166e-01 -9.65497494e-01 1.92443743e-01 1.69307545e-01 -9.66599405e-01 1.92453206e-01 1.63373813e-01 -9.67617929e-01 1.92452163e-01 1.57427311e-01 -9.68590438e-01 1.92448616e-01 1.51484877e-01 -9.69542146e-01 1.92479864e-01 1.45533741e-01 -9.70440626e-01 1.92486495e-01 1.39575690e-01 -9.71287370e-01 1.92472160e-01 1.33614853e-01 -9.72167969e-01 1.92472652e-01 1.27646625e-01 -9.72918749e-01 1.92478716e-01 1.21670403e-01 -9.73698735e-01 1.92454264e-01 1.15697436e-01 -9.74416554e-01 1.92468062e-01 1.09716430e-01 -9.75118637e-01 1.92477465e-01 1.03729993e-01 -9.75778878e-01 1.92471907e-01 9.77406353e-02 -9.76433694e-01 1.92465737e-01 9.17485431e-02 -9.76976693e-01 1.92469925e-01 8.57489556e-02 -9.77514386e-01 1.92468017e-01 7.97518566e-02 -9.78003681e-01 1.92498922e-01 7.37487897e-02 -9.78480041e-01 1.92506880e-01 6.77438527e-02 -9.78905857e-01 1.92495793e-01 6.17341809e-02 -9.79365051e-01 1.92478359e-01 5.57239465e-02 -9.79679942e-01 1.92488208e-01 4.97121103e-02 -9.80029345e-01 1.92483827e-01 4.36974354e-02 -9.80324447e-01 1.92479432e-01 3.76820154e-02 -9.80566025e-01 1.92483932e-01 3.16642784e-02 -9.80793953e-01 1.92476690e-01 2.56458987e-02 -9.80969846e-01 1.92496434e-01 1.96266342e-02 -9.81053948e-01 1.92518339e-01 1.36064598e-02 -9.81202602e-01 1.92526415e-01 7.58571830e-03 -9.81270730e-01 1.92527816e-01 1.56500319e-03 -9.81270909e-01 1.92551851e-01 -4.45610937e-03 -9.81272399e-01 1.92538023e-01 -1.04766926e-02 -9.81250823e-01 1.92556098e-01 -1.64968967e-02 -9.81100798e-01 1.92583248e-01 -2.25167964e-02 -9.81022000e-01 1.92581877e-01 -2.85356976e-02 -9.80845869e-01 1.92579910e-01 -3.45535353e-02 -9.80625093e-01 1.92585245e-01 -4.05697338e-02 -9.80400622e-01 1.92599922e-01 -4.65843007e-02 -9.80138481e-01 1.92600265e-01 -5.25974855e-02 -9.79827642e-01 1.92607686e-01 -5.86094558e-02 -9.79523838e-01 1.92593157e-01 -6.46169558e-02 -9.79106665e-01 1.92614436e-01 -7.06239417e-02 -9.78686810e-01 1.92616373e-01 -7.66283274e-02 -9.78240013e-01 1.92610309e-01 -8.26286077e-02 -9.77744281e-01 1.92619234e-01 -8.86281431e-02 -9.77208674e-01 1.92610979e-01 -9.46213603e-02 -9.76703942e-01 1.92621380e-01 -1.00614294e-01 -9.76065040e-01 1.92618087e-01 -1.06600828e-01 -9.75452423e-01 1.92604601e-01 -1.12582117e-01 -9.74792182e-01 1.92605987e-01 -1.18561015e-01 -9.74074364e-01 1.92602918e-01 -1.24536410e-01 -9.73337591e-01 1.92617148e-01 -1.30506814e-01 -9.72560465e-01 1.92614272e-01 -1.36470094e-01 -9.71694887e-01 1.92614570e-01 -1.42429173e-01 -9.70881462e-01 1.92616701e-01 -1.48385644e-01 -9.69996035e-01 1.92615256e-01 -1.54336959e-01 -9.69039202e-01 1.92636415e-01 -1.60275891e-01 -9.68081951e-01 1.92617282e-01 -1.66210249e-01 -9.67095435e-01 1.92670077e-01 -1.72143772e-01 -9.66017067e-01 1.92641720e-01 -1.78064555e-01 -9.64956522e-01 1.92672551e-01 -1.83986247e-01 -9.63819802e-01 1.92694634e-01 -1.89888880e-01 -9.62712944e-01 1.92722827e-01 -1.95797712e-01 -9.61520553e-01 1.92716807e-01 -2.01687574e-01 -9.60319638e-01 1.92714140e-01 -2.07582340e-01 -9.59031165e-01 1.92677945e-01 -2.13463500e-01 -9.57766533e-01 1.92685202e-01 -2.19342500e-01 -9.56401885e-01 1.92661539e-01 -2.25204483e-01 -9.55078304e-01 1.92642763e-01 -2.31055260e-01 -9.53683376e-01 1.92646205e-01 -2.36903206e-01 -9.52248752e-01 1.92643210e-01 -2.42743254e-01 -9.50775146e-01 1.92602083e-01 -2.48582244e-01 -9.49228406e-01 1.92597955e-01 -2.54392147e-01 -9.47721601e-01 1.92596406e-01 -2.60201007e-01 -9.46108103e-01 1.92627013e-01 -2.66011804e-01 -9.44538295e-01 1.92588449e-01 -2.71798521e-01 -9.42876220e-01 1.92585841e-01 -2.77572542e-01 -9.41194177e-01 1.92594260e-01 -2.83339858e-01 -9.39441144e-01 1.92604721e-01 -2.89107978e-01 -9.37679350e-01 1.92608908e-01 -2.94855386e-01 -9.35922682e-01 1.92603618e-01 -3.00585061e-01 -9.34068441e-01 1.92628860e-01 -3.06317568e-01 -9.32209849e-01 1.92632616e-01 -3.12023729e-01 -9.30314720e-01 1.92636535e-01 -3.17735851e-01 -9.28378761e-01 1.92645490e-01 -3.23425174e-01 -9.26399052e-01 1.92650214e-01 -3.29089940e-01 -9.24414039e-01 1.92655191e-01 -3.34763467e-01 -9.22340155e-01 1.92654103e-01 -3.40404510e-01 -9.20323372e-01 1.92655891e-01 -3.46061051e-01 -9.18229580e-01 1.92654580e-01 -3.51685762e-01 -9.16075826e-01 1.92651436e-01 -3.57290536e-01 -9.13917363e-01 1.92653075e-01 -3.62910032e-01 -9.11703587e-01 1.92632839e-01 -3.68485749e-01 -9.09402907e-01 1.92646727e-01 -3.74052644e-01 -9.07164872e-01 1.92646503e-01 -3.79623652e-01 -9.04844284e-01 1.92631930e-01 -3.85172516e-01 -9.02452946e-01 1.92676246e-01 -3.90698433e-01 -9.00105119e-01 1.92679420e-01 -3.96211445e-01 -8.97665024e-01 1.92661464e-01 -4.01717961e-01 -8.95249844e-01 1.92653224e-01 -4.07193959e-01 -8.92782271e-01 1.92655146e-01 -4.12661403e-01 -8.90226007e-01 1.92685187e-01 -4.18127149e-01 -8.87687981e-01 1.92666590e-01 -4.23554808e-01 -8.85118723e-01 1.92670479e-01 -4.28986251e-01 -8.82530808e-01 1.92665219e-01 -4.34387952e-01 -8.79848719e-01 1.92676902e-01 -4.39779907e-01 -8.77192616e-01 1.92677930e-01 -4.45155889e-01 -8.74420345e-01 1.92684725e-01 -4.50501472e-01 -8.71701539e-01 1.92676827e-01 -4.55855042e-01 -8.68901014e-01 1.92679226e-01 -4.61165369e-01 -8.66113722e-01 1.92653775e-01 -4.66481686e-01 -8.63263130e-01 1.92677617e-01 -4.71781611e-01 -8.60379636e-01 1.92658067e-01 -4.77052212e-01 -8.57482255e-01 1.92653731e-01 -4.82298136e-01 -8.54524612e-01 1.92642629e-01 -4.87517357e-01 -8.51570547e-01 1.92649722e-01 -4.92746830e-01 -8.48537326e-01 1.92648917e-01 -4.97928798e-01 -8.45514357e-01 1.92651272e-01 -5.03106475e-01 -8.42459798e-01 1.92650765e-01 -5.08282185e-01 -8.39345932e-01 1.92658275e-01 -5.13409972e-01 -8.36233020e-01 1.92626998e-01 -5.18534601e-01 -8.33053768e-01 1.92613915e-01 -5.23649156e-01 -8.29853952e-01 1.92629442e-01 -5.28715134e-01 -8.26608241e-01 1.92631409e-01 -5.33792853e-01 -8.23368490e-01 1.92662120e-01 -5.38829446e-01 -8.20043147e-01 1.92665070e-01 -5.43855309e-01 -8.16753805e-01 1.92679077e-01 -5.48836350e-01 -8.13399017e-01 1.92682058e-01 -5.53834796e-01 -8.09981406e-01 1.92677125e-01 -5.58774054e-01 -8.06598961e-01 1.92712292e-01 -5.63719273e-01 -8.03159595e-01 1.92714080e-01 -5.68648815e-01 -7.99658060e-01 1.92715913e-01 -5.73519528e-01 -7.96163678e-01 1.92746848e-01 -5.78389406e-01 -7.92629600e-01 1.92757621e-01 -5.83262146e-01 -7.89081454e-01 1.92788452e-01 -5.88084400e-01 -7.85487831e-01 1.92791328e-01 -5.92880070e-01 -7.81846881e-01 1.92765862e-01 -5.97672164e-01 -7.78199255e-01 1.92759186e-01 -6.02457464e-01 -7.74501920e-01 1.92741230e-01 -6.07181013e-01 -7.70817101e-01 1.92714125e-01 -6.11922503e-01 -7.67075062e-01 1.92718700e-01 -6.16597354e-01 -7.63260484e-01 1.92758948e-01 -6.21266365e-01 -7.59495497e-01 1.92781508e-01 -6.25931084e-01 -7.55663693e-01 1.92773819e-01 -6.30527794e-01 -7.51825690e-01 1.92787886e-01 -6.35145366e-01 -7.47897923e-01 1.92836493e-01 -6.39702141e-01 -7.43984103e-01 1.92853510e-01 -6.44254744e-01 -7.40081787e-01 1.92845345e-01 -6.48802280e-01 -7.36080587e-01 1.92837030e-01 -6.53280556e-01 -7.32090771e-01 1.92815512e-01 -6.57795548e-01 -7.28092313e-01 1.92813531e-01 -6.62224591e-01 -7.24039674e-01 1.92827716e-01 -6.66659296e-01 -7.19965875e-01 1.92843392e-01 -6.71078503e-01 -7.15832353e-01 1.92845657e-01 -6.75426900e-01 -7.11722255e-01 1.92846298e-01 -6.79825544e-01 -7.07555532e-01 1.92827791e-01 -6.84148133e-01 -7.03354180e-01 1.92828551e-01 -6.88457966e-01 -6.99167311e-01 1.92822739e-01 -6.92719519e-01 -6.94934547e-01 1.92827135e-01 -6.96955800e-01 -6.90650582e-01 1.92823902e-01 -7.01182663e-01 -6.86354399e-01 1.92821771e-01 -7.05373645e-01 -6.82040989e-01 1.92831755e-01 -7.09544718e-01 -6.77708983e-01 1.92853376e-01 -7.13704526e-01 -6.73363924e-01 1.92865193e-01 -7.17804134e-01 -6.68969512e-01 1.92879453e-01 -7.21901059e-01 -6.64534152e-01 1.92858204e-01 -7.25953758e-01 -6.60107911e-01 1.92880839e-01 -7.29997754e-01 -6.55637801e-01 1.92903802e-01 -7.33972311e-01 -6.51102722e-01 1.93050712e-01 -7.38516092e-01 -6.47014320e-01 1.89697698e-01 -7.42472053e-01 -6.42501295e-01 1.89680085e-01 -7.46362329e-01 -6.37903929e-01 1.89701289e-01 -7.50274837e-01 -6.33304954e-01 1.89767957e-01 -7.54127264e-01 -6.28701866e-01 1.89783528e-01 -7.57976532e-01 -6.24069333e-01 1.89759776e-01 -7.61792183e-01 -6.19401872e-01 1.89746156e-01 -7.65600204e-01 -6.14722073e-01 1.89746052e-01 -7.69327700e-01 -6.10004961e-01 1.89818203e-01 -7.73030341e-01 -6.05239987e-01 1.89931884e-01 -7.76687860e-01 -6.00459933e-01 1.90266237e-01 -7.80108392e-01 -5.95504403e-01 1.91838995e-01 -7.83904970e-01 -5.90815604e-01 1.90866247e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.32963526e-01 -5.08280933e-01 2.18683064e-01 -8.38584363e-01 -5.04559338e-01 2.05417186e-01 -8.41333687e-01 -4.99223381e-01 2.07194924e-01 -8.44669640e-01 -4.94208008e-01 2.05640480e-01 -8.48725498e-01 -4.89563257e-01 1.99875712e-01 -8.52598667e-01 -4.84812677e-01 1.94827512e-01 -8.55774939e-01 -4.79680687e-01 1.93677694e-01 -8.58789384e-01 -4.74456251e-01 1.93231180e-01 -8.61697495e-01 -4.69193518e-01 1.93042621e-01 -8.64575922e-01 -4.63903517e-01 1.93002611e-01 -8.67392540e-01 -4.58601624e-01 1.93010524e-01 -8.70240748e-01 -4.53252375e-01 1.93004206e-01 -8.72957468e-01 -4.47907329e-01 1.93026379e-01 -8.75707805e-01 -4.42552835e-01 1.93051413e-01 -8.78402472e-01 -4.37178463e-01 1.92989826e-01 -8.81181598e-01 -4.31830674e-01 1.92307353e-01 -8.84266436e-01 -4.26605910e-01 1.89898953e-01 -8.86858702e-01 -4.21155721e-01 1.90033749e-01 -8.89376760e-01 -4.15692002e-01 1.90279201e-01 -8.91828775e-01 -4.10194784e-01 1.90731511e-01 -8.94343495e-01 -4.04720306e-01 1.90649778e-01 -8.96900237e-01 -3.99258047e-01 1.90167159e-01 -8.99352551e-01 -3.93760145e-01 1.89980462e-01 -9.01769280e-01 -3.88250262e-01 1.89887494e-01 -9.04151797e-01 -3.82698506e-01 1.89859584e-01 -9.06473696e-01 -3.77160430e-01 1.89882651e-01 -9.08782244e-01 -3.71586680e-01 1.89923421e-01 -9.11031425e-01 -3.65991473e-01 1.90028250e-01 -9.13160503e-01 -3.60364258e-01 1.90409824e-01 -9.14449275e-01 -3.54439139e-01 1.95190325e-01 -9.15783167e-01 -3.48543614e-01 1.99494451e-01 -9.18576002e-01 -3.43141645e-01 1.95938796e-01 -9.21031296e-01 -3.37604821e-01 1.94227964e-01 -9.23183978e-01 -3.31999481e-01 1.93559110e-01 -9.25282180e-01 -3.26328218e-01 1.93326935e-01 -9.27234054e-01 -3.20651859e-01 1.93249524e-01 -9.29180086e-01 -3.14955324e-01 1.93229020e-01 -9.31090236e-01 -3.09263766e-01 1.93225652e-01 -9.32987511e-01 -3.03531468e-01 1.93219349e-01 -9.34881985e-01 -2.97811151e-01 1.93220735e-01 -9.36645389e-01 -2.92074174e-01 1.93204060e-01 -9.38456595e-01 -2.86319494e-01 1.93196416e-01 -9.40172732e-01 -2.80540794e-01 1.93207771e-01 -9.41856086e-01 -2.74771541e-01 1.93219647e-01 -9.43532288e-01 -2.68985331e-01 1.93194643e-01 -9.45199132e-01 -2.63201326e-01 1.93199247e-01 -9.46783006e-01 -2.57396877e-01 1.93232730e-01 -9.48322535e-01 -2.51582205e-01 1.93200275e-01 -9.49835122e-01 -2.45752454e-01 1.93195656e-01 -9.51373875e-01 -2.39921719e-01 1.93184063e-01 -9.52819467e-01 -2.34071985e-01 1.93209171e-01 -9.54249740e-01 -2.28234664e-01 1.93178967e-01 -9.55577135e-01 -2.22371578e-01 1.93230256e-01 -9.56940293e-01 -2.16503143e-01 1.93234727e-01 -9.58281457e-01 -2.10627317e-01 1.93234622e-01 -9.59555268e-01 -2.04737321e-01 1.93248540e-01 -9.60765123e-01 -1.98845327e-01 1.93274066e-01 -9.61957276e-01 -1.92950100e-01 1.93307072e-01 -9.63149130e-01 -1.87041640e-01 1.93313077e-01 -9.64279294e-01 -1.81125969e-01 1.93299830e-01 -9.65330243e-01 -1.75210088e-01 1.93291381e-01 -9.66433346e-01 -1.69282302e-01 1.93311453e-01 -9.67449903e-01 -1.63351074e-01 1.93313301e-01 -9.68421102e-01 -1.57408342e-01 1.93322957e-01 -9.69378173e-01 -1.51467144e-01 1.93317667e-01 -9.70275402e-01 -1.45512938e-01 1.93338707e-01 -9.71112907e-01 -1.39557153e-01 1.93357393e-01 -9.71985936e-01 -1.33594915e-01 1.93396330e-01 -9.72727239e-01 -1.27629906e-01 1.93449765e-01 -9.73489165e-01 -1.21652395e-01 1.93505883e-01 -9.74195778e-01 -1.15680352e-01 1.93565547e-01 -9.74899650e-01 -1.09698340e-01 1.93557471e-01 -9.75547910e-01 -1.03712752e-01 1.93614632e-01 -9.76185799e-01 -9.77240801e-02 1.93685949e-01 -9.76729751e-01 -9.17328820e-02 1.93698883e-01 -9.77266371e-01 -8.57371911e-02 1.93722561e-01 -9.77757931e-01 -7.97400326e-02 1.93734571e-01 -9.78216827e-01 -7.37379491e-02 1.93834662e-01 -9.78646219e-01 -6.77345023e-02 1.93795562e-01 -9.79207814e-01 -6.17307462e-02 1.93256453e-01 -9.79455113e-01 -5.57196811e-02 1.93642750e-01 -9.79778886e-01 -4.97084707e-02 1.93708777e-01 -9.80034471e-01 -4.36955132e-02 1.93916187e-01 -9.80267286e-01 -3.76814157e-02 1.93957135e-01 -9.80494499e-01 -3.16659324e-02 1.93948358e-01 -9.80698586e-01 -2.56489217e-02 1.93816796e-01 -9.80957985e-01 -1.96283851e-02 1.93001404e-01 -9.81257141e-01 -1.36047043e-02 1.92168832e-01 -9.81182039e-01 -7.58837909e-03 1.92962274e-01 0. 0. 0. -9.88026321e-01 4.47025523e-03 1.54304400e-01 -9.87993181e-01 1.05319833e-02 1.54359058e-01 -9.87881064e-01 1.65944286e-02 1.54308349e-01 -9.87720132e-01 2.26516109e-02 1.54682949e-01 -9.87469196e-01 2.87051182e-02 1.55216679e-01 -9.87186730e-01 3.47586311e-02 1.55597657e-01 -9.87011969e-01 4.08188179e-02 1.55354813e-01 -9.86750901e-01 4.68749367e-02 1.55295163e-01 -9.86270249e-01 5.29134274e-02 1.56257525e-01 -9.85975504e-01 5.89664914e-02 1.56135678e-01 -9.85465825e-01 6.50033429e-02 1.56765506e-01 -9.85044003e-01 7.10478052e-02 1.56831250e-01 -9.84561145e-01 7.70878270e-02 1.56964898e-01 -9.84065831e-01 8.31289440e-02 1.56923860e-01 -9.83559191e-01 8.91649947e-02 1.56965449e-01 -9.83015120e-01 9.51973721e-02 1.56960487e-01 -9.82373893e-01 1.01227671e-01 1.56941742e-01 -9.81797934e-01 1.07253969e-01 1.56920433e-01 -9.81093466e-01 1.13274962e-01 1.56923413e-01 -9.80373263e-01 1.19295016e-01 1.56909809e-01 -9.79648113e-01 1.25307515e-01 1.56895787e-01 -9.78848219e-01 1.31317496e-01 1.56923130e-01 -9.77982461e-01 1.37319550e-01 1.56901076e-01 -9.77175653e-01 1.43318594e-01 1.56895682e-01 -9.76273239e-01 1.49313211e-01 1.56904817e-01 -9.75310922e-01 1.55299887e-01 1.56915575e-01 -9.74351287e-01 1.61281019e-01 1.56886294e-01 -9.73370790e-01 1.67255089e-01 1.56864703e-01 -9.72279847e-01 1.73223436e-01 1.56867385e-01 -9.71216559e-01 1.79189757e-01 1.56884924e-01 -9.70077991e-01 1.85144350e-01 1.56886578e-01 -9.68967736e-01 1.91092879e-01 1.56884134e-01 -9.67775106e-01 1.97034076e-01 1.56890348e-01 -9.66553450e-01 2.02969164e-01 1.56898081e-01 -9.65251148e-01 2.08896220e-01 1.56888038e-01 -9.63976800e-01 2.14814529e-01 1.56904370e-01 -9.62604284e-01 2.20723689e-01 1.56892002e-01 -9.61264670e-01 2.26628914e-01 1.56889364e-01 -9.59864974e-01 2.32521847e-01 1.56893671e-01 -9.58422720e-01 2.38407448e-01 1.56879663e-01 -9.56927180e-01 2.44284496e-01 1.56880140e-01 -9.55397487e-01 2.50147343e-01 1.56879872e-01 -9.53855157e-01 2.56004989e-01 1.56895697e-01 -9.52247083e-01 2.61855394e-01 1.56882182e-01 -9.50659394e-01 2.67688692e-01 1.56868190e-01 -9.49004710e-01 2.73523539e-01 1.56878531e-01 -9.47286606e-01 2.79344440e-01 1.56871721e-01 -9.45578694e-01 2.85145521e-01 1.56875402e-01 -9.43753600e-01 2.90944666e-01 1.56872779e-01 -9.41982567e-01 2.96731025e-01 1.56869560e-01 -9.40115631e-01 3.02502543e-01 1.56904906e-01 -9.38250363e-01 3.08256209e-01 1.56903461e-01 -9.36351001e-01 3.14017147e-01 1.56908751e-01 -9.34393883e-01 3.19756031e-01 1.56898499e-01 -9.32412028e-01 3.25482517e-01 1.56890824e-01 -9.30444717e-01 3.31200361e-01 1.56899169e-01 -9.28360701e-01 3.36894989e-01 1.56897321e-01 -9.26292539e-01 3.42593461e-01 1.56893253e-01 -9.24179435e-01 3.48268598e-01 1.56878412e-01 -9.22019184e-01 3.53932828e-01 1.56891420e-01 -9.19837296e-01 3.59584719e-01 1.56890318e-01 -9.17603076e-01 3.65213364e-01 1.56883702e-01 -9.15303111e-01 3.70848328e-01 1.56872198e-01 -9.13042963e-01 3.76456648e-01 1.56871215e-01 -9.10700500e-01 3.82037640e-01 1.56863257e-01 -9.08353746e-01 3.87633711e-01 1.56853378e-01 -9.05945718e-01 3.93192172e-01 1.56853333e-01 -9.03526723e-01 3.98739427e-01 1.56884834e-01 -9.01051879e-01 4.04278696e-01 1.56885281e-01 -8.98562551e-01 4.09803271e-01 1.56917140e-01 -8.95996928e-01 4.15294230e-01 1.56949669e-01 -8.93472195e-01 4.20789570e-01 1.56962931e-01 -8.90888929e-01 4.26261961e-01 1.56949058e-01 -8.88236165e-01 4.31726426e-01 1.56974018e-01 -8.85582626e-01 4.37164545e-01 1.56967163e-01 -8.82864475e-01 4.42590594e-01 1.56952873e-01 -8.80132139e-01 4.48002398e-01 1.56957075e-01 -8.77381682e-01 4.53384191e-01 1.56991571e-01 -8.74526024e-01 4.58761513e-01 1.57040462e-01 -8.71706963e-01 4.64098036e-01 1.57200739e-01 -8.68854046e-01 4.69470710e-01 1.57026812e-01 -8.66241276e-01 4.74952579e-01 1.55036569e-01 -8.63044560e-01 4.80092287e-01 1.57030359e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.51482511e-01 5.01440942e-01 1.53409451e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.32410157e-01 5.32414675e-01 1.53714076e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.01755309e-01 5.77548742e-01 1.53707176e-01 -7.97867060e-01 5.82193017e-01 1.56378433e-01 -7.94463873e-01 5.87224126e-01 1.54887348e-01 -7.90911019e-01 5.92134237e-01 1.54386088e-01 -7.87186027e-01 5.96935034e-01 1.54874146e-01 -7.83354640e-01 6.01619959e-01 1.56167582e-01 -7.79541433e-01 6.06343687e-01 1.56825498e-01 -7.75813699e-01 6.11095071e-01 1.56866655e-01 -7.72215664e-01 6.15997493e-01 1.55596554e-01 -7.68232405e-01 6.20538592e-01 1.57314628e-01 -7.64407635e-01 6.25248373e-01 1.57276750e-01 -7.60575712e-01 6.29942417e-01 1.57117680e-01 -7.56712258e-01 6.34586751e-01 1.57015771e-01 -7.52782226e-01 6.39245689e-01 1.56942531e-01 -7.48878777e-01 6.43862784e-01 1.56903595e-01 -7.44916201e-01 6.48444057e-01 1.56909332e-01 -7.40922511e-01 6.53003275e-01 1.56899706e-01 -7.36873925e-01 6.57519639e-01 1.56891420e-01 -7.32855678e-01 6.62046969e-01 1.56892091e-01 -7.28776872e-01 6.66526794e-01 1.56909689e-01 -7.24677086e-01 6.70990586e-01 1.56883061e-01 -7.20555782e-01 6.75424695e-01 1.56871617e-01 -7.16362059e-01 6.79808319e-01 1.56874925e-01 -7.12174177e-01 6.84208632e-01 1.56870544e-01 -7.07964122e-01 6.88573897e-01 1.56872392e-01 -7.03732431e-01 6.92908406e-01 1.56874999e-01 -6.99483216e-01 6.97192609e-01 1.56855658e-01 -6.95175052e-01 7.01496005e-01 1.56867176e-01 -6.90883458e-01 7.05727935e-01 1.56884760e-01 -6.86530173e-01 7.09939480e-01 1.56903461e-01 -6.82137787e-01 7.14160740e-01 1.56898052e-01 -6.77777767e-01 7.18340635e-01 1.56859785e-01 -6.73336565e-01 7.22479045e-01 1.56856805e-01 -6.68878675e-01 7.26579905e-01 1.56877220e-01 -6.64414287e-01 7.30677545e-01 1.56884804e-01 -6.59934521e-01 7.34753489e-01 1.56912670e-01 -6.55393302e-01 7.38761842e-01 1.56906456e-01 -6.50870562e-01 7.42762864e-01 1.56848103e-01 -6.46301568e-01 7.46754825e-01 1.56805947e-01 -6.41717553e-01 7.50715315e-01 1.56760395e-01 -6.37085021e-01 7.54688144e-01 1.56714916e-01 -6.32465363e-01 7.58553028e-01 1.56711638e-01 -6.27778590e-01 7.62416124e-01 1.56706661e-01 -6.23081625e-01 7.66270220e-01 1.56707197e-01 -6.18378520e-01 7.70101547e-01 1.56672016e-01 -6.13665164e-01 7.73855031e-01 1.56641707e-01 -6.08883321e-01 7.77609527e-01 1.56650811e-01 -6.04115188e-01 7.81328380e-01 1.56635195e-01 -5.99323630e-01 7.85047054e-01 1.56591132e-01 -5.94488919e-01 7.88711846e-01 1.56570166e-01 -5.89651346e-01 7.92330801e-01 1.56554431e-01 -5.84754825e-01 7.95949280e-01 1.56539485e-01 -5.79882920e-01 7.99538612e-01 1.56512544e-01 -5.74951112e-01 8.03040087e-01 1.56515896e-01 -5.70023954e-01 8.06564391e-01 1.56519279e-01 -5.65059364e-01 8.10031414e-01 1.56530991e-01 -5.60063601e-01 8.13524961e-01 1.56576619e-01 -5.55076063e-01 8.16919208e-01 1.56602129e-01 -5.50027609e-01 8.20293248e-01 1.56631947e-01 -5.44988751e-01 8.23661387e-01 1.56665415e-01 -5.39925516e-01 8.27006221e-01 1.56663403e-01 -5.34837008e-01 8.30271959e-01 1.56632751e-01 -5.29758036e-01 8.33557904e-01 1.56598866e-01 -5.24623096e-01 8.36790085e-01 1.56541049e-01 -5.19488215e-01 8.39998305e-01 1.56503022e-01 -5.14336050e-01 8.43203783e-01 1.56464234e-01 -5.09155452e-01 8.46349835e-01 1.56424209e-01 -5.03943741e-01 8.49468589e-01 1.56399369e-01 -4.98719305e-01 8.52518916e-01 1.56377628e-01 -4.93491530e-01 8.55550349e-01 1.56366602e-01 -4.88210976e-01 8.58585775e-01 1.56349450e-01 -4.82959121e-01 8.61568630e-01 1.56318471e-01 -4.77663994e-01 8.64483595e-01 1.56303346e-01 -4.72353280e-01 8.67425680e-01 1.56286672e-01 -4.67004567e-01 8.70294213e-01 1.56287864e-01 -4.61672395e-01 8.73150170e-01 1.56280503e-01 -4.56297070e-01 8.75984609e-01 1.56258330e-01 -4.50913608e-01 8.78763735e-01 1.56246081e-01 -4.45521027e-01 8.81532371e-01 1.56231254e-01 -4.40096796e-01 8.84245813e-01 1.56244367e-01 -4.34669912e-01 8.86905074e-01 1.56236410e-01 -4.29212034e-01 8.89556408e-01 1.56241447e-01 -4.23749715e-01 8.92202079e-01 1.56245202e-01 -4.18272883e-01 8.94781590e-01 1.56233490e-01 -4.12766099e-01 8.97290885e-01 1.56232312e-01 -4.07255381e-01 8.99848819e-01 1.56220764e-01 -4.01723742e-01 9.02333856e-01 1.56231180e-01 -3.96185815e-01 9.04752314e-01 1.56234488e-01 -3.90624911e-01 9.07167852e-01 1.56217873e-01 -3.85050684e-01 9.09575045e-01 1.56214476e-01 -3.79457623e-01 9.11927044e-01 1.56208530e-01 -3.73856783e-01 9.14218426e-01 1.56206086e-01 -3.68241012e-01 9.16510940e-01 1.56207129e-01 -3.62614304e-01 9.18739974e-01 1.56216413e-01 -3.56970131e-01 9.20925796e-01 1.56215116e-01 -3.51308137e-01 9.23098326e-01 1.56206012e-01 -3.45636845e-01 9.25253749e-01 1.56204998e-01 -3.39960724e-01 9.27405119e-01 1.56193003e-01 -3.34259242e-01 9.29415226e-01 1.56198174e-01 -3.28561038e-01 9.31502044e-01 1.56206205e-01 -3.22833240e-01 9.33455765e-01 1.56192750e-01 -3.17108274e-01 9.35403943e-01 1.56171128e-01 -3.11349392e-01 9.37329948e-01 1.56187966e-01 -3.05600345e-01 9.39242840e-01 1.56186551e-01 -2.99825430e-01 9.41151202e-01 1.56178996e-01 -2.94038773e-01 9.42918122e-01 1.56196177e-01 -2.88251668e-01 9.44732010e-01 1.56179056e-01 -2.82455117e-01 9.46476161e-01 1.56192183e-01 -2.76645422e-01 9.48171198e-01 1.56180531e-01 -2.70820290e-01 9.49856699e-01 1.56189531e-01 -2.64981627e-01 9.51527536e-01 1.56184480e-01 -2.59135365e-01 9.53142107e-01 1.56175286e-01 -2.53287494e-01 9.54684496e-01 1.56160623e-01 -2.47428656e-01 9.56202328e-01 1.56155914e-01 -2.41557822e-01 9.57754731e-01 1.56168014e-01 -2.35671520e-01 9.59202588e-01 1.56181246e-01 -2.29777202e-01 9.60646391e-01 1.56179011e-01 -2.23886326e-01 9.61987078e-01 1.56168327e-01 -2.17979655e-01 9.63363647e-01 1.56168178e-01 -2.12059617e-01 9.64654863e-01 1.56174600e-01 -2.06137851e-01 9.65999603e-01 1.56170860e-01 -2.00207710e-01 9.67218816e-01 1.56181023e-01 -1.94266975e-01 9.68425095e-01 1.56176418e-01 -1.88324183e-01 9.69623506e-01 1.56187981e-01 -1.82367861e-01 9.70763564e-01 1.56182691e-01 -1.76408947e-01 9.71812308e-01 1.56198159e-01 -1.70444235e-01 9.72932458e-01 1.56187370e-01 -1.64471984e-01 9.73954916e-01 1.56180263e-01 -1.58491150e-01 9.74931717e-01 1.56189784e-01 -1.52507290e-01 9.75897014e-01 1.56183168e-01 -1.46514848e-01 9.76808667e-01 1.56177655e-01 -1.40518129e-01 9.77649868e-01 1.56169415e-01 -1.34517327e-01 9.78542149e-01 1.56161040e-01 -1.28511459e-01 9.79294658e-01 1.56177521e-01 -1.22500688e-01 9.80072618e-01 1.56170920e-01 -1.16483837e-01 9.80798960e-01 1.56161398e-01 -1.10464305e-01 9.81508613e-01 1.56161591e-01 -1.04437888e-01 9.82176960e-01 1.56152502e-01 -9.84092653e-02 9.82840240e-01 1.56152651e-01 -9.23790187e-02 9.83385086e-01 1.56144500e-01 -8.63426477e-02 9.83921349e-01 1.56156808e-01 -8.03057477e-02 9.84416246e-01 1.56163752e-01 -7.42625222e-02 9.84898269e-01 1.56160101e-01 -6.82177544e-02 9.85327423e-01 1.56162009e-01 -6.21698461e-02 9.85786617e-01 1.56171709e-01 -5.61198257e-02 9.86104250e-01 1.56157032e-01 -5.00682890e-02 9.86459374e-01 1.56172544e-01 -4.40147705e-02 9.86749828e-01 1.56184360e-01 -3.79591882e-02 9.86994863e-01 1.56175286e-01 -3.19025889e-02 9.87221420e-01 1.56182989e-01 -2.58445088e-02 9.87407863e-01 1.56172007e-01 -1.97855327e-02 9.87494171e-01 1.56158701e-01 -1.37258880e-02 9.87649024e-01 1.56168491e-01 -7.66566349e-03 9.87714291e-01 1.56165794e-01 -1.60514796e-03 9.87721443e-01 1.56157538e-01 4.45533311e-03 9.87719655e-01 1.56166330e-01 1.05158314e-02 9.87706304e-01 1.56147882e-01 1.65758822e-02 9.87553179e-01 1.56151220e-01 2.26352755e-02 9.87480938e-01 1.56145722e-01 2.86938325e-02 9.87298191e-01 1.56151012e-01 3.47513519e-02 9.87075686e-01 1.56136900e-01 4.08073589e-02 9.86906409e-01 1.56147987e-01 4.68625799e-02 9.86587942e-01 1.56145930e-01 5.29151261e-02 9.86283243e-01 1.56137615e-01 5.89665622e-02 9.85983729e-01 1.56122118e-01 6.50141835e-02 9.85563576e-01 1.56112477e-01 7.10612833e-02 9.85146940e-01 1.56111613e-01 7.71052837e-02 9.84701693e-01 1.56091183e-01 8.31450745e-02 9.84188497e-01 1.56096175e-01 8.91827643e-02 9.83686447e-01 1.56105816e-01 9.52161252e-02 9.83147502e-01 1.56099066e-01 1.01246975e-01 9.82498527e-01 1.56101316e-01 1.07273556e-01 9.81927693e-01 1.56085446e-01 1.13297977e-01 9.81222212e-01 1.56081274e-01 1.19316712e-01 9.80499446e-01 1.56080619e-01 1.25328362e-01 9.79769468e-01 1.56095341e-01 1.31342009e-01 9.78981495e-01 1.56083867e-01 1.37343556e-01 9.78108108e-01 1.56067148e-01 1.43341348e-01 9.77297425e-01 1.56088635e-01 1.49338618e-01 9.76396739e-01 1.56085044e-01 1.55323774e-01 9.75434422e-01 1.56102002e-01 1.61307395e-01 9.74467516e-01 1.56104371e-01 1.67283103e-01 9.73488271e-01 1.56099468e-01 1.73253149e-01 9.72398579e-01 1.56062365e-01 1.79217398e-01 9.71341014e-01 1.56053215e-01 1.85175195e-01 9.70196128e-01 1.56055808e-01 1.91120371e-01 9.69095051e-01 1.56065375e-01 1.97065547e-01 9.67904747e-01 1.56047463e-01 2.02998742e-01 9.66683924e-01 1.56057388e-01 2.08931088e-01 9.65373218e-01 1.56049490e-01 2.14848712e-01 9.64104533e-01 1.56052485e-01 2.20757976e-01 9.62722063e-01 1.56063944e-01 2.26664081e-01 9.61396217e-01 1.56039402e-01 2.32562542e-01 9.59993243e-01 1.56039193e-01 2.38439769e-01 9.58549142e-01 1.56031683e-01 2.44327575e-01 9.57062066e-01 1.56012475e-01 2.50189662e-01 9.55511332e-01 1.56016856e-01 2.56043762e-01 9.53990281e-01 1.55984968e-01 2.61895388e-01 9.52370107e-01 1.55974329e-01 2.67734677e-01 9.50794995e-01 1.55981928e-01 2.73568571e-01 9.49119985e-01 1.55943409e-01 2.79383123e-01 9.47424889e-01 1.55955896e-01 2.85197049e-01 9.45721209e-01 1.55953556e-01 2.90990740e-01 9.43884373e-01 1.55964270e-01 2.96776235e-01 9.42117214e-01 1.55979931e-01 3.02559823e-01 9.40256357e-01 1.55952811e-01 3.08311850e-01 9.38385606e-01 1.55946568e-01 3.14075679e-01 9.36485529e-01 1.55953944e-01 3.19810033e-01 9.34528589e-01 1.55955344e-01 3.25535387e-01 9.32554305e-01 1.55927971e-01 3.31263512e-01 9.30591881e-01 1.55915603e-01 3.36954951e-01 9.28499222e-01 1.55927494e-01 3.42658728e-01 9.26446319e-01 1.55888662e-01 3.48326087e-01 9.24328208e-01 1.55915722e-01 3.53992045e-01 9.22165930e-01 1.55937478e-01 3.59654933e-01 9.19987857e-01 1.55913413e-01 3.65287274e-01 9.17763054e-01 1.55891418e-01 3.70910645e-01 9.15443540e-01 1.55909866e-01 3.76526266e-01 9.13192391e-01 1.55903682e-01 3.82110417e-01 9.10850227e-01 1.55881882e-01 3.87695968e-01 9.08497512e-01 1.55871078e-01 3.93267184e-01 9.06089902e-01 1.55878991e-01 3.98817867e-01 9.03674603e-01 1.55873522e-01 4.04360622e-01 9.01204884e-01 1.55870929e-01 4.09878045e-01 8.98728907e-01 1.55866280e-01 4.15378362e-01 8.96161139e-01 1.55846879e-01 4.20885354e-01 8.93655419e-01 1.55819550e-01 4.26351160e-01 8.91064107e-01 1.55812204e-01 4.31815803e-01 8.88414443e-01 1.55820936e-01 4.37251806e-01 8.85762095e-01 1.55808404e-01 4.42677021e-01 8.83046269e-01 1.55822381e-01 4.48095292e-01 8.80296588e-01 1.55804753e-01 4.53482538e-01 8.77562702e-01 1.55802250e-01 4.58872110e-01 8.74704599e-01 1.55812010e-01 4.64215279e-01 8.71894419e-01 1.55797184e-01 4.69562173e-01 8.69059682e-01 1.55804783e-01 4.74885613e-01 8.66166472e-01 1.55793935e-01 4.80193377e-01 8.63210618e-01 1.55782297e-01 4.85479623e-01 8.60226810e-01 1.55771360e-01 4.90746379e-01 8.57266426e-01 1.55749649e-01 4.96009946e-01 8.54210138e-01 1.55758604e-01 5.01230717e-01 8.51160228e-01 1.55762479e-01 5.06455839e-01 8.48089755e-01 1.55770451e-01 5.11642277e-01 8.44961643e-01 1.55752823e-01 5.16824245e-01 8.41808558e-01 1.55763566e-01 5.21969020e-01 8.38608205e-01 1.55768812e-01 5.27116179e-01 8.35387170e-01 1.55736431e-01 5.32221735e-01 8.32166255e-01 1.55720055e-01 5.37326872e-01 8.28872621e-01 1.55733809e-01 5.42391837e-01 8.25519264e-01 1.55732408e-01 5.47456503e-01 8.22209239e-01 1.55727342e-01 5.52479088e-01 8.18832934e-01 1.55734941e-01 5.57512283e-01 8.15396667e-01 1.55728161e-01 5.62485874e-01 8.11990559e-01 1.55740857e-01 5.67470670e-01 8.08534026e-01 1.55695856e-01 5.72415233e-01 8.05006444e-01 1.55698791e-01 5.77334583e-01 8.01500142e-01 1.55699730e-01 5.82262278e-01 7.97940016e-01 1.55705318e-01 5.87131977e-01 7.94374168e-01 1.55698255e-01 5.92001855e-01 7.90750384e-01 1.55733228e-01 5.96850812e-01 7.87083507e-01 1.55725434e-01 6.01667881e-01 7.83408225e-01 1.55742347e-01 6.06464326e-01 7.79679656e-01 1.55747488e-01 6.11213028e-01 7.75968850e-01 1.55748650e-01 6.15993559e-01 7.72206068e-01 1.55708387e-01 6.20724618e-01 7.68416345e-01 1.55721784e-01 6.25424981e-01 7.64592886e-01 1.55726135e-01 6.30108833e-01 7.60739863e-01 1.55715421e-01 6.34729743e-01 7.56860912e-01 1.55721888e-01 6.39391303e-01 7.52928317e-01 1.55721590e-01 6.43995106e-01 7.49031067e-01 1.55717790e-01 6.48575485e-01 7.45045662e-01 1.55736312e-01 6.53140187e-01 7.41069674e-01 1.55727357e-01 6.57661021e-01 7.37014532e-01 1.55697048e-01 6.62194788e-01 7.32990921e-01 1.55701235e-01 6.66663706e-01 7.28912592e-01 1.55697823e-01 6.71132088e-01 7.24807739e-01 1.55720323e-01 6.75567865e-01 7.20687032e-01 1.55696511e-01 6.79944992e-01 7.16498137e-01 1.55697629e-01 6.84376419e-01 7.12316871e-01 1.55694351e-01 6.88723624e-01 7.08082676e-01 1.55689433e-01 6.93065524e-01 7.03877389e-01 1.55678600e-01 6.97334230e-01 6.99618995e-01 1.55667379e-01 7.01627493e-01 6.95299149e-01 1.55685693e-01 7.05870152e-01 6.90982997e-01 1.55678600e-01 7.10090458e-01 6.86624348e-01 1.55693576e-01 7.14308202e-01 6.82260990e-01 1.55684933e-01 7.18489528e-01 6.77907288e-01 1.55685395e-01 7.22613215e-01 6.73467934e-01 1.55666292e-01 7.26734936e-01 6.68999374e-01 1.55677781e-01 7.30832696e-01 6.64546788e-01 1.55669108e-01 7.34895825e-01 6.60066545e-01 1.55670121e-01 7.38917172e-01 6.55512631e-01 1.55670494e-01 7.42933571e-01 6.51002467e-01 1.55691266e-01 7.46897936e-01 6.46427512e-01 1.55677348e-01 7.50865757e-01 6.41841173e-01 1.55672356e-01 7.54823864e-01 6.37189984e-01 1.55684650e-01 7.58690655e-01 6.32573009e-01 1.55683368e-01 7.62553453e-01 6.27885520e-01 1.55673847e-01 7.66406298e-01 6.23186886e-01 1.55663803e-01 7.70241737e-01 6.18480802e-01 1.55673221e-01 7.73976684e-01 6.13762796e-01 1.55682236e-01 7.77743936e-01 6.08981848e-01 1.55670345e-01 7.81454444e-01 6.04215622e-01 1.55662909e-01 7.85195053e-01 5.99414468e-01 1.55665874e-01 7.88836956e-01 5.94583213e-01 1.55651838e-01 7.92460382e-01 5.89736879e-01 1.55633807e-01 7.96077132e-01 5.84846079e-01 1.55631229e-01 7.99673498e-01 5.79953909e-01 1.55630276e-01 8.03163767e-01 5.75041831e-01 1.55620098e-01 8.06689501e-01 5.70109606e-01 1.55638263e-01 8.10153663e-01 5.65147340e-01 1.55638009e-01 8.13662410e-01 5.60155153e-01 1.55638799e-01 8.17064703e-01 5.55170476e-01 1.55621469e-01 8.20449889e-01 5.50132930e-01 1.55605674e-01 8.23823452e-01 5.45090914e-01 1.55602276e-01 8.27174425e-01 5.40022373e-01 1.55616730e-01 8.30413938e-01 5.34933507e-01 1.55631498e-01 8.33703279e-01 5.29843867e-01 1.55651316e-01 8.36924851e-01 5.24705827e-01 1.55649364e-01 8.40144277e-01 5.19568801e-01 1.55661345e-01 8.43331218e-01 5.14407992e-01 1.55664429e-01 8.46468031e-01 5.09222567e-01 1.55672684e-01 8.49593878e-01 5.04012287e-01 1.55676067e-01 8.52648735e-01 4.98780668e-01 1.55666426e-01 8.55665743e-01 4.93550599e-01 1.55668795e-01 8.58698785e-01 4.88279402e-01 1.55662373e-01 8.61678958e-01 4.82993364e-01 1.55669913e-01 8.64590943e-01 4.77720022e-01 1.55680746e-01 8.67531240e-01 4.72383678e-01 1.55672908e-01 8.70397031e-01 4.67060447e-01 1.55678287e-01 8.73253524e-01 4.61718261e-01 1.55689776e-01 8.76083791e-01 4.56340194e-01 1.55695364e-01 8.78862381e-01 4.50967431e-01 1.55693352e-01 8.81625772e-01 4.45567220e-01 1.55691743e-01 8.84343445e-01 4.40143198e-01 1.55687377e-01 8.87003958e-01 4.34715778e-01 1.55684277e-01 8.89653444e-01 4.29261655e-01 1.55696839e-01 8.92299950e-01 4.23786730e-01 1.55699968e-01 8.94886851e-01 4.18314993e-01 1.55697569e-01 8.97387743e-01 4.12808061e-01 1.55697674e-01 8.99952829e-01 4.07297581e-01 1.55705735e-01 9.02428627e-01 4.01767224e-01 1.55699402e-01 9.04847085e-01 3.96224827e-01 1.55706257e-01 9.07256186e-01 3.90657663e-01 1.55725539e-01 9.09661233e-01 3.85082453e-01 1.55734420e-01 9.12012100e-01 3.79490882e-01 1.55733377e-01 9.14305627e-01 3.73892277e-01 1.55730665e-01 9.16599452e-01 3.68276060e-01 1.55718654e-01 9.18829560e-01 3.62650096e-01 1.55723184e-01 9.21015620e-01 3.57001573e-01 1.55725434e-01 9.23187017e-01 3.51339966e-01 1.55731902e-01 9.25339997e-01 3.45668226e-01 1.55738771e-01 9.27488744e-01 3.39990556e-01 1.55745432e-01 9.29501057e-01 3.34282488e-01 1.55742586e-01 9.31586623e-01 3.28584969e-01 1.55761063e-01 9.33541536e-01 3.22868407e-01 1.55738205e-01 9.35485244e-01 3.17128718e-01 1.55746788e-01 9.37415242e-01 3.11372429e-01 1.55744329e-01 9.39327121e-01 3.05625051e-01 1.55750036e-01 9.41206753e-01 2.99848258e-01 1.55747250e-01 9.43001449e-01 2.94062585e-01 1.55758008e-01 9.44810450e-01 2.88274050e-01 1.55760989e-01 9.46555972e-01 2.82474786e-01 1.55764535e-01 9.48249340e-01 2.76658446e-01 1.55763164e-01 9.49935734e-01 2.70838737e-01 1.55769423e-01 9.51604784e-01 2.65000939e-01 1.55786663e-01 9.53217387e-01 2.59156018e-01 1.55782461e-01 9.54757571e-01 2.53304392e-01 1.55782804e-01 9.56275344e-01 2.47446477e-01 1.55789301e-01 9.57827508e-01 2.41564065e-01 1.55788645e-01 9.59277332e-01 2.35688448e-01 1.55784830e-01 9.60722387e-01 2.29793400e-01 1.55783862e-01 9.62064207e-01 2.23896444e-01 1.55769989e-01 9.63440180e-01 2.17988685e-01 1.55773684e-01 9.64772999e-01 2.12071627e-01 1.55795500e-01 9.66073334e-01 2.06148401e-01 1.55785918e-01 9.67293680e-01 2.00223655e-01 1.55790657e-01 9.68502998e-01 1.94277093e-01 1.55782640e-01 9.69694912e-01 1.88334972e-01 1.55782729e-01 9.70840633e-01 1.82382345e-01 1.55787706e-01 9.71893311e-01 1.76422194e-01 1.55789629e-01 9.73012090e-01 1.70454308e-01 1.55781224e-01 9.74030793e-01 1.64483994e-01 1.55800954e-01 9.75011826e-01 1.58499464e-01 1.55783951e-01 9.75975692e-01 1.52518079e-01 1.55784503e-01 9.76884067e-01 1.46524802e-01 1.55791953e-01 9.77724254e-01 1.40526950e-01 1.55797735e-01 9.78614032e-01 1.34526193e-01 1.55802697e-01 9.79369104e-01 1.28521875e-01 1.55803323e-01 9.80148852e-01 1.22505143e-01 1.55796841e-01 9.80872929e-01 1.16492823e-01 1.55795127e-01 9.81580913e-01 1.10469870e-01 1.55805051e-01 9.82246697e-01 1.04444869e-01 1.55815512e-01 9.82903123e-01 9.84158516e-02 1.55822605e-01 9.83448267e-01 9.23831016e-02 1.55830488e-01 9.83988285e-01 8.63456652e-02 1.55831710e-01 9.84484017e-01 8.03095251e-02 1.55835778e-01 9.84966278e-01 7.42659941e-02 1.55827984e-01 9.85395193e-01 6.82218000e-02 1.55832216e-01 9.85852659e-01 6.21718243e-02 1.55842200e-01 9.86169934e-01 5.61210848e-02 1.55840501e-01 9.86523151e-01 5.00700362e-02 1.55846536e-01 9.86817598e-01 4.40154485e-02 1.55845061e-01 9.87060070e-01 3.79593633e-02 1.55856535e-01 9.87285137e-01 3.19024138e-02 1.55868605e-01 9.87470269e-01 2.58442611e-02 1.55859753e-01 9.87557232e-01 1.97847206e-02 1.55858234e-01 9.87711310e-01 1.37246018e-02 1.55857697e-01 9.87774730e-01 7.66410585e-03 1.55878916e-01 9.87779319e-01 1.60324539e-03 1.55880168e-01 9.87778366e-01 -4.45771590e-03 1.55876726e-01 9.87759233e-01 -1.05184494e-02 1.55878812e-01 9.87608671e-01 -1.65787246e-02 1.55885339e-01 9.87533271e-01 -2.26386972e-02 1.55879349e-01 9.87352252e-01 -2.86976360e-02 1.55884996e-01 9.87128973e-01 -3.47551592e-02 1.55894548e-01 9.86913681e-01 -4.08111587e-02 1.55877605e-01 9.86643851e-01 -4.68671359e-02 1.55883238e-01 9.86335397e-01 -5.29188588e-02 1.55885443e-01 9.86032486e-01 -5.89714460e-02 1.55880764e-01 9.85611379e-01 -6.50179386e-02 1.55894220e-01 9.85195279e-01 -7.10646585e-02 1.55902058e-01 9.84736681e-01 -7.71088004e-02 1.55898854e-01 9.84237611e-01 -8.31507519e-02 1.55885905e-01 9.83738780e-01 -8.91888365e-02 1.55884519e-01 9.83198643e-01 -9.52240378e-02 1.55873939e-01 9.82549548e-01 -1.01255976e-01 1.55880794e-01 9.81974423e-01 -1.07282989e-01 1.55880362e-01 9.81269181e-01 -1.13302059e-01 1.55880868e-01 9.80542898e-01 -1.19322903e-01 1.55904546e-01 9.79815602e-01 -1.25337303e-01 1.55898899e-01 9.79025722e-01 -1.31346211e-01 1.55890077e-01 9.78150964e-01 -1.37350798e-01 1.55895054e-01 9.77345765e-01 -1.43351138e-01 1.55900553e-01 9.76441562e-01 -1.49345890e-01 1.55898958e-01 9.75476861e-01 -1.55332550e-01 1.55930445e-01 9.74508524e-01 -1.61314487e-01 1.55942783e-01 9.73523080e-01 -1.67287156e-01 1.55969858e-01 9.72429156e-01 -1.73256591e-01 1.55967504e-01 9.71368551e-01 -1.79224014e-01 1.55972555e-01 9.70229864e-01 -1.85184807e-01 1.55954435e-01 9.69123602e-01 -1.91129774e-01 1.55968755e-01 9.67929780e-01 -1.97069719e-01 1.55970320e-01 9.66709554e-01 -2.03008190e-01 1.55975431e-01 9.65401113e-01 -2.08939850e-01 1.55990452e-01 9.64129806e-01 -2.14853287e-01 1.55989602e-01 9.62755799e-01 -2.20762715e-01 1.55985132e-01 9.61415529e-01 -2.26669416e-01 1.55999288e-01 9.60015833e-01 -2.32567027e-01 1.55996621e-01 9.58570421e-01 -2.38454357e-01 1.55986115e-01 9.57075179e-01 -2.44331345e-01 1.55997157e-01 9.55529630e-01 -2.50187039e-01 1.55999109e-01 9.54000831e-01 -2.56053686e-01 1.56011000e-01 9.52389538e-01 -2.61901885e-01 1.56016171e-01 9.50802147e-01 -2.67732888e-01 1.56004936e-01 9.49153244e-01 -2.73572803e-01 1.56009823e-01 9.47424889e-01 -2.79390782e-01 1.56015545e-01 9.45724905e-01 -2.85200715e-01 1.55989781e-01 9.43899691e-01 -2.90999234e-01 1.55961573e-01 9.42133427e-01 -2.96786457e-01 1.55946136e-01 9.40274358e-01 -3.02564114e-01 1.55928418e-01 9.38402891e-01 -3.08315873e-01 1.55940980e-01 9.36505616e-01 -3.14080894e-01 1.55921221e-01 9.34545279e-01 -3.19816768e-01 1.55946165e-01 9.32569385e-01 -3.25544298e-01 1.55927256e-01 9.30604339e-01 -3.31264347e-01 1.55927479e-01 9.28517818e-01 -3.36958915e-01 1.55919597e-01 9.26459491e-01 -3.42657000e-01 1.55908123e-01 9.24340546e-01 -3.48331839e-01 1.55909657e-01 9.22182381e-01 -3.53999257e-01 1.55907601e-01 9.19994950e-01 -3.59656364e-01 1.55931249e-01 9.17765975e-01 -3.65283459e-01 1.55916438e-01 9.15455937e-01 -3.70914459e-01 1.55908898e-01 9.13199425e-01 -3.76529753e-01 1.55916885e-01 9.10853684e-01 -3.82111609e-01 1.55926734e-01 9.08501267e-01 -3.87703151e-01 1.55937120e-01 9.06094968e-01 -3.93263340e-01 1.55930415e-01 9.03681099e-01 -3.98816288e-01 1.55919030e-01 9.01205838e-01 -4.04356509e-01 1.55915111e-01 8.98727179e-01 -4.09879386e-01 1.55914977e-01 8.96160543e-01 -4.15383577e-01 1.55917212e-01 8.93639565e-01 -4.20875579e-01 1.55934542e-01 8.91048133e-01 -4.26345348e-01 1.55941010e-01 8.88398051e-01 -4.31810975e-01 1.55946925e-01 8.85741353e-01 -4.37246323e-01 1.55946136e-01 8.83022130e-01 -4.42671537e-01 1.55962244e-01 8.80277574e-01 -4.48084295e-01 1.56002134e-01 8.77538025e-01 -4.53476131e-01 1.55989066e-01 8.74687850e-01 -4.58855689e-01 1.55983657e-01 8.71876359e-01 -4.64208007e-01 1.56005993e-01 8.69026899e-01 -4.69547093e-01 1.56012431e-01 8.66129220e-01 -4.74882543e-01 1.56027734e-01 8.63192976e-01 -4.80190575e-01 1.56008691e-01 8.60200942e-01 -4.85462576e-01 1.56010732e-01 8.57226193e-01 -4.90733534e-01 1.56020641e-01 8.54179680e-01 -4.95987058e-01 1.56037062e-01 8.51139367e-01 -5.01209736e-01 1.56045035e-01 8.48053455e-01 -5.06416738e-01 1.56040668e-01 8.44922900e-01 -5.11623621e-01 1.56029150e-01 8.41772437e-01 -5.16787767e-01 1.56018555e-01 8.38596404e-01 -5.21950066e-01 1.56022951e-01 8.35356355e-01 -5.27096272e-01 1.56021506e-01 8.32123756e-01 -5.32199085e-01 1.56017125e-01 8.28842342e-01 -5.37293017e-01 1.56016007e-01 8.25490117e-01 -5.42370737e-01 1.56014517e-01 8.22187662e-01 -5.47432125e-01 1.56012163e-01 8.18815470e-01 -5.52464426e-01 1.55976042e-01 8.15370619e-01 -5.57490289e-01 1.55969709e-01 8.11965525e-01 -5.62470794e-01 1.55989140e-01 8.08495641e-01 -5.67438304e-01 1.55976146e-01 8.04980934e-01 -5.72396219e-01 1.55960977e-01 8.01479936e-01 -5.77316284e-01 1.55948371e-01 7.97908902e-01 -5.82241595e-01 1.55945882e-01 7.94350207e-01 -5.87113500e-01 1.55918926e-01 7.90734053e-01 -5.91990888e-01 1.55910298e-01 7.87061214e-01 -5.96834302e-01 1.55914098e-01 7.83399642e-01 -6.01658642e-01 1.55894712e-01 7.79667258e-01 -6.06454253e-01 1.55905992e-01 7.75953054e-01 -6.11204088e-01 1.55900940e-01 7.72188842e-01 -6.15980446e-01 1.55907363e-01 7.68404901e-01 -6.20701969e-01 1.55924916e-01 7.64582038e-01 -6.25402033e-01 1.55945227e-01 7.60725319e-01 -6.30078614e-01 1.55969024e-01 7.56847620e-01 -6.34709418e-01 1.55968636e-01 7.52905548e-01 -6.39364302e-01 1.55983537e-01 7.48998761e-01 -6.43968880e-01 1.56001002e-01 7.45040119e-01 -6.48550570e-01 1.56001478e-01 7.41041481e-01 -6.53110862e-01 1.55987829e-01 7.36988842e-01 -6.57625318e-01 1.55979499e-01 7.32974589e-01 -6.62157059e-01 1.55969620e-01 7.28898406e-01 -6.66643262e-01 1.55956447e-01 7.24798262e-01 -6.71107769e-01 1.55936509e-01 7.20670164e-01 -6.75543308e-01 1.55955359e-01 7.16480076e-01 -6.79926932e-01 1.55956462e-01 7.12292552e-01 -6.84345007e-01 1.55940175e-01 7.08068252e-01 -6.88690543e-01 1.55948803e-01 7.03853786e-01 -6.93037271e-01 1.55917570e-01 6.99598372e-01 -6.97312176e-01 1.55919045e-01 6.95290744e-01 -7.01619089e-01 1.55879021e-01 6.90974236e-01 -7.05852151e-01 1.55889362e-01 6.86618030e-01 -7.10066676e-01 1.55911952e-01 6.82252884e-01 -7.14287937e-01 1.55906752e-01 6.77889287e-01 -7.18477964e-01 1.55885682e-01 6.73445702e-01 -7.22602129e-01 1.55903056e-01 6.68986380e-01 -7.26701260e-01 1.55941620e-01 6.64520025e-01 -7.30796754e-01 1.55956715e-01 6.60039485e-01 -7.34874010e-01 1.55968979e-01 6.55496657e-01 -7.38884568e-01 1.55969575e-01 6.50967896e-01 -7.42893040e-01 1.55973598e-01 6.46398664e-01 -7.46868968e-01 1.55939251e-01 6.41807377e-01 -7.50819087e-01 1.55953065e-01 6.37170553e-01 -7.54790366e-01 1.55932680e-01 6.32544100e-01 -7.58655667e-01 1.55923635e-01 6.27861142e-01 -7.62520671e-01 1.55908406e-01 6.23163044e-01 -7.66371965e-01 1.55901417e-01 6.18458450e-01 -7.70206511e-01 1.55898228e-01 6.13738954e-01 -7.73955643e-01 1.55891046e-01 6.08959615e-01 -7.77713835e-01 1.55872986e-01 6.04187787e-01 -7.81428516e-01 1.55897558e-01 5.99386156e-01 -7.85154104e-01 1.55911073e-01 5.94550669e-01 -7.88798332e-01 1.55890077e-01 5.89699030e-01 -7.92413354e-01 1.55937687e-01 5.84812582e-01 -7.96028376e-01 1.55928701e-01 5.79930067e-01 -7.99625754e-01 1.55901849e-01 5.75008333e-01 -8.03127825e-01 1.55902207e-01 5.70073903e-01 -8.06646585e-01 1.55906022e-01 5.65117836e-01 -8.10120642e-01 1.55896157e-01 5.60128331e-01 -8.13622653e-01 1.55854821e-01 5.55141032e-01 -8.17020476e-01 1.55859619e-01 5.50099552e-01 -8.20401728e-01 1.55844316e-01 5.45057178e-01 -8.23773921e-01 1.55865490e-01 5.39993525e-01 -8.27128232e-01 1.55862108e-01 5.34908950e-01 -8.30385208e-01 1.55836716e-01 5.29821455e-01 -8.33666742e-01 1.55845925e-01 5.24683595e-01 -8.36896896e-01 1.55815348e-01 5.19545913e-01 -8.40104878e-01 1.55821651e-01 5.14390230e-01 -8.43300104e-01 1.55798078e-01 5.09204566e-01 -8.46438825e-01 1.55813754e-01 5.03995299e-01 -8.49562943e-01 1.55800983e-01 4.98765171e-01 -8.52613151e-01 1.55780882e-01 4.93535817e-01 -8.55643690e-01 1.55739859e-01 4.88261580e-01 -8.58668447e-01 1.55747354e-01 4.82992440e-01 -8.61658037e-01 1.55717179e-01 4.77707356e-01 -8.64571810e-01 1.55722275e-01 4.72381443e-01 -8.67513359e-01 1.55732751e-01 4.67047125e-01 -8.70386124e-01 1.55727684e-01 4.61708426e-01 -8.73234570e-01 1.55729413e-01 4.56332713e-01 -8.76059115e-01 1.55742377e-01 4.50949728e-01 -8.78844261e-01 1.55755669e-01 4.45555061e-01 -8.81592035e-01 1.55793130e-01 4.40131485e-01 -8.84315193e-01 1.55780911e-01 4.34702665e-01 -8.86972487e-01 1.55798003e-01 4.29241240e-01 -8.89623702e-01 1.55793667e-01 4.23776329e-01 -8.92268300e-01 1.55805171e-01 4.18303430e-01 -8.94837916e-01 1.55797154e-01 4.12801087e-01 -8.97365749e-01 1.55756325e-01 4.07282412e-01 -8.99925113e-01 1.55757278e-01 4.01751727e-01 -9.02405620e-01 1.55752182e-01 3.96211594e-01 -9.04829800e-01 1.55729443e-01 3.90648305e-01 -9.07240391e-01 1.55739501e-01 3.85082334e-01 -9.09651816e-01 1.55711815e-01 3.79487097e-01 -9.11998451e-01 1.55713573e-01 3.73883009e-01 -9.14297044e-01 1.55734897e-01 3.68271619e-01 -9.16579485e-01 1.55725494e-01 3.62646818e-01 -9.18813944e-01 1.55737907e-01 3.56994539e-01 -9.21001315e-01 1.55736744e-01 3.51327091e-01 -9.23169553e-01 1.55755877e-01 3.45659882e-01 -9.25324917e-01 1.55748978e-01 3.39988649e-01 -9.27477002e-01 1.55722544e-01 3.34282130e-01 -9.29494500e-01 1.55718371e-01 3.28581423e-01 -9.31578994e-01 1.55710995e-01 3.22858036e-01 -9.33532000e-01 1.55713335e-01 3.17125738e-01 -9.35473263e-01 1.55740887e-01 3.11364084e-01 -9.37398791e-01 1.55763283e-01 3.05616856e-01 -9.39310431e-01 1.55771509e-01 2.99842387e-01 -9.41206872e-01 1.55767485e-01 2.94056326e-01 -9.42987859e-01 1.55774534e-01 2.88266838e-01 -9.44787264e-01 1.55789524e-01 2.82472342e-01 -9.46537256e-01 1.55787289e-01 2.76658773e-01 -9.48225141e-01 1.55820936e-01 2.70832568e-01 -9.49911356e-01 1.55818149e-01 2.64992416e-01 -9.51576829e-01 1.55839145e-01 2.59146094e-01 -9.53179598e-01 1.55857995e-01 2.53295928e-01 -9.54731345e-01 1.55841783e-01 2.47436792e-01 -9.56248701e-01 1.55889302e-01 2.41563246e-01 -9.57786798e-01 1.55912697e-01 2.35681519e-01 -9.59236681e-01 1.55914366e-01 2.29787335e-01 -9.60684121e-01 1.55889764e-01 2.23891079e-01 -9.62032497e-01 1.55920222e-01 2.17984706e-01 -9.63405073e-01 1.55903518e-01 2.12065384e-01 -9.64719296e-01 1.55929446e-01 2.06142008e-01 -9.66034651e-01 1.55931890e-01 2.00211853e-01 -9.67254400e-01 1.55951083e-01 1.94273308e-01 -9.68465686e-01 1.55928448e-01 1.88331157e-01 -9.69668567e-01 1.55899867e-01 1.82374761e-01 -9.70792413e-01 1.55952275e-01 1.76415920e-01 -9.71854866e-01 1.55953959e-01 1.70449600e-01 -9.72959876e-01 1.55961215e-01 1.64478734e-01 -9.73989725e-01 1.55947521e-01 1.58493638e-01 -9.74965990e-01 1.55970871e-01 1.52512699e-01 -9.75929141e-01 1.55967951e-01 1.46519005e-01 -9.76835847e-01 1.55947953e-01 1.40520647e-01 -9.77688909e-01 1.55953556e-01 1.34521991e-01 -9.78575349e-01 1.55928224e-01 1.28516734e-01 -9.79333162e-01 1.55926853e-01 1.22500323e-01 -9.80115831e-01 1.55926242e-01 1.16488285e-01 -9.80840087e-01 1.55927628e-01 1.10466830e-01 -9.81544375e-01 1.55957147e-01 1.04440674e-01 -9.82207894e-01 1.55947357e-01 9.84120071e-02 -9.82863545e-01 1.55948505e-01 9.23805013e-02 -9.83409524e-01 1.55963838e-01 8.63443464e-02 -9.83957887e-01 1.55949220e-01 8.03058371e-02 -9.84452844e-01 1.55974448e-01 7.42638409e-02 -9.84937072e-01 1.55950814e-01 6.82174712e-02 -9.85352397e-01 1.56007484e-01 6.21706285e-02 -9.85808194e-01 1.56014085e-01 5.61201349e-02 -9.86132860e-01 1.56000853e-01 5.00689335e-02 -9.86476958e-01 1.55990645e-01 4.40146923e-02 -9.86772358e-01 1.55998304e-01 3.79591770e-02 -9.87020969e-01 1.55998543e-01 3.19021195e-02 -9.87243772e-01 1.56015977e-01 2.58441642e-02 -9.87418890e-01 1.56035393e-01 1.97850186e-02 -9.87510264e-01 1.56037271e-01 1.37253096e-02 -9.87653077e-01 1.56060755e-01 7.66507536e-03 -9.87725079e-01 1.56068653e-01 1.60485366e-03 -9.87720311e-01 1.56112626e-01 -4.45569493e-03 -9.87720966e-01 1.56113178e-01 -1.05158482e-02 -9.87696826e-01 1.56133413e-01 -1.65758617e-02 -9.87556100e-01 1.56125546e-01 -2.26349402e-02 -9.87465024e-01 1.56162500e-01 -2.86930855e-02 -9.87287283e-01 1.56189442e-01 -3.47498618e-02 -9.87062335e-01 1.56220272e-01 -4.08060029e-02 -9.86857831e-01 1.56206995e-01 -4.68612462e-02 -9.86580729e-01 1.56189993e-01 -5.29123694e-02 -9.86259401e-01 1.56223044e-01 -5.89642897e-02 -9.85948265e-01 1.56219587e-01 -6.50129840e-02 -9.85542297e-01 1.56182468e-01 -7.10582808e-02 -9.85132277e-01 1.56204492e-01 -7.71017820e-02 -9.84675467e-01 1.56197399e-01 -8.31423178e-02 -9.84173775e-01 1.56194136e-01 -8.91796350e-02 -9.83665526e-01 1.56230032e-01 -9.52142924e-02 -9.83118415e-01 1.56211972e-01 -1.01243861e-01 -9.82477129e-01 1.56233326e-01 -1.07269742e-01 -9.81892347e-01 1.56219035e-01 -1.13291875e-01 -9.81188774e-01 1.56218529e-01 -1.19310543e-01 -9.80463266e-01 1.56232700e-01 -1.25323087e-01 -9.79738832e-01 1.56213701e-01 -1.31336138e-01 -9.78936434e-01 1.56239361e-01 -1.37337252e-01 -9.78072822e-01 1.56234086e-01 -1.43335596e-01 -9.77255225e-01 1.56245336e-01 -1.49331555e-01 -9.76359427e-01 1.56248957e-01 -1.55316234e-01 -9.75395620e-01 1.56282187e-01 -1.61298931e-01 -9.74428475e-01 1.56281158e-01 -1.67270526e-01 -9.73441958e-01 1.56309888e-01 -1.73238903e-01 -9.72361445e-01 1.56307325e-01 -1.79205805e-01 -9.71295297e-01 1.56289548e-01 -1.85166374e-01 -9.70162034e-01 1.56266317e-01 -1.91111401e-01 -9.69045222e-01 1.56265676e-01 -1.97053373e-01 -9.67848718e-01 1.56291187e-01 -2.02988997e-01 -9.66634333e-01 1.56249523e-01 -2.08921388e-01 -9.65343356e-01 1.56217456e-01 -2.14839563e-01 -9.64075923e-01 1.56165615e-01 -2.20752344e-01 -9.62708116e-01 1.56119123e-01 -2.26658896e-01 -9.61376905e-01 1.56067237e-01 -2.32557833e-01 -9.59980726e-01 1.56050161e-01 -2.38435194e-01 -9.58532512e-01 1.56056210e-01 -2.44318470e-01 -9.57033515e-01 1.56088337e-01 -2.50184476e-01 -9.55505371e-01 1.56074479e-01 -2.56035149e-01 -9.53961611e-01 1.56097978e-01 -2.61884689e-01 -9.52349901e-01 1.56087756e-01 -2.67727882e-01 -9.50765014e-01 1.56093895e-01 -2.73556471e-01 -9.49089766e-01 1.56064555e-01 -2.79373109e-01 -9.47394788e-01 1.56092644e-01 -2.85189182e-01 -9.45691049e-01 1.56076476e-01 -2.90978104e-01 -9.43861246e-01 1.56096563e-01 -2.96764195e-01 -9.42085505e-01 1.56125754e-01 -3.02548349e-01 -9.40223217e-01 1.56135693e-01 -3.08299601e-01 -9.38355207e-01 1.56155273e-01 -3.14061463e-01 -9.36454177e-01 1.56166911e-01 -3.19790691e-01 -9.34495330e-01 1.56179890e-01 -3.25520843e-01 -9.32509959e-01 1.56184301e-01 -3.31243038e-01 -9.30548728e-01 1.56165168e-01 -3.36934209e-01 -9.28458929e-01 1.56207472e-01 -3.42637420e-01 -9.26395893e-01 1.56159639e-01 -3.48308176e-01 -9.24283147e-01 1.56168044e-01 -3.53973955e-01 -9.22125041e-01 1.56173810e-01 -3.59636039e-01 -9.19944048e-01 1.56160742e-01 -3.65260810e-01 -9.17711198e-01 1.56150073e-01 -3.70896071e-01 -9.15399730e-01 1.56171128e-01 -3.76504809e-01 -9.13138866e-01 1.56190634e-01 -3.82086277e-01 -9.10799205e-01 1.56184241e-01 -3.87675583e-01 -9.08451796e-01 1.56181976e-01 -3.93237025e-01 -9.06043172e-01 1.56192079e-01 -3.98788899e-01 -9.03628886e-01 1.56179592e-01 -4.04331714e-01 -9.01156843e-01 1.56163201e-01 -4.09854889e-01 -8.98674309e-01 1.56153306e-01 -4.15348560e-01 -8.96107674e-01 1.56173855e-01 -4.20853496e-01 -8.93594325e-01 1.56151325e-01 -4.26320493e-01 -8.91005933e-01 1.56152561e-01 -4.31789637e-01 -8.88358474e-01 1.56155661e-01 -4.37222779e-01 -8.85701358e-01 1.56176507e-01 -4.42649484e-01 -8.82985353e-01 1.56154484e-01 -4.48064953e-01 -8.80245209e-01 1.56163692e-01 -4.53444064e-01 -8.77494514e-01 1.56218678e-01 -4.58831131e-01 -8.74638915e-01 1.56225771e-01 -4.64177430e-01 -8.71836126e-01 1.56177744e-01 -4.69524860e-01 -8.68988633e-01 1.56185374e-01 -4.74856526e-01 -8.66097093e-01 1.56175345e-01 -4.80159402e-01 -8.63148451e-01 1.56197771e-01 -4.85438317e-01 -8.60157669e-01 1.56192020e-01 -4.90700811e-01 -8.57188523e-01 1.56189129e-01 -4.95960832e-01 -8.54138672e-01 1.56210124e-01 -5.01184285e-01 -8.51092279e-01 1.56217664e-01 -5.06407678e-01 -8.48015308e-01 1.56215206e-01 -5.11596620e-01 -8.44882011e-01 1.56230792e-01 -5.16773641e-01 -8.41733515e-01 1.56218588e-01 -5.21923125e-01 -8.38545620e-01 1.56219810e-01 -5.27066588e-01 -8.35312307e-01 1.56241745e-01 -5.32171547e-01 -8.32081616e-01 1.56244248e-01 -5.37272334e-01 -8.28794181e-01 1.56253234e-01 -5.42339742e-01 -8.25443208e-01 1.56252384e-01 -5.47399104e-01 -8.22136104e-01 1.56271100e-01 -5.52423358e-01 -8.18758905e-01 1.56282797e-01 -5.57452857e-01 -8.15315783e-01 1.56279236e-01 -5.62430680e-01 -8.11915040e-01 1.56281963e-01 -5.67409575e-01 -8.08444560e-01 1.56289920e-01 -5.72352231e-01 -8.04921627e-01 1.56308651e-01 -5.77269435e-01 -8.01420033e-01 1.56308219e-01 -5.82194984e-01 -7.97847450e-01 1.56331763e-01 -5.87063372e-01 -7.94285297e-01 1.56328917e-01 -5.91940939e-01 -7.90669024e-01 1.56325206e-01 -5.96786797e-01 -7.86999285e-01 1.56313673e-01 -6.01608932e-01 -7.83337831e-01 1.56305388e-01 -6.06405020e-01 -7.79607356e-01 1.56307682e-01 -6.11153185e-01 -7.75895655e-01 1.56289190e-01 -6.15933299e-01 -7.72132993e-01 1.56270802e-01 -6.20655239e-01 -7.68359125e-01 1.56304091e-01 -6.25358224e-01 -7.64524221e-01 1.56316102e-01 -6.30035520e-01 -7.60669529e-01 1.56338453e-01 -6.34662151e-01 -7.56790817e-01 1.56325057e-01 -6.39319122e-01 -7.52856731e-01 1.56355917e-01 -6.43924654e-01 -7.48948336e-01 1.56376407e-01 -6.48503840e-01 -7.44971573e-01 1.56412229e-01 -6.53062761e-01 -7.40988553e-01 1.56409547e-01 -6.57582939e-01 -7.36932218e-01 1.56395063e-01 -6.62110984e-01 -7.32913017e-01 1.56396627e-01 -6.66589260e-01 -7.28839278e-01 1.56402767e-01 -6.71053767e-01 -7.24735320e-01 1.56417757e-01 -6.75486803e-01 -7.20612526e-01 1.56417742e-01 -6.79861605e-01 -7.16421425e-01 1.56405941e-01 -6.84281588e-01 -7.12235808e-01 1.56396225e-01 -6.88647330e-01 -7.08007991e-01 1.56377956e-01 -6.92987621e-01 -7.03799069e-01 1.56364277e-01 -6.97251379e-01 -6.99544072e-01 1.56368956e-01 -7.01556206e-01 -6.95228338e-01 1.56344980e-01 -7.05790579e-01 -6.90938771e-01 1.56359345e-01 -7.10007131e-01 -6.86577678e-01 1.56364575e-01 -7.14225829e-01 -6.82186604e-01 1.56396449e-01 -7.18400776e-01 -6.77824974e-01 1.56449556e-01 -7.22527444e-01 -6.73385322e-01 1.56430751e-01 -7.26639092e-01 -6.68924451e-01 1.56417802e-01 -7.30736315e-01 -6.64463997e-01 1.56428024e-01 -7.34806955e-01 -6.59987032e-01 1.56444728e-01 -7.38819122e-01 -6.55436277e-01 1.56471685e-01 -7.42817998e-01 -6.50914788e-01 1.56492263e-01 -7.46800125e-01 -6.46342516e-01 1.56464517e-01 -7.51106977e-01 -6.42025054e-01 1.53744653e-01 -7.55055547e-01 -6.37380123e-01 1.53772235e-01 -7.58927941e-01 -6.32750154e-01 1.53805777e-01 -7.62787819e-01 -6.28058314e-01 1.53860748e-01 -7.66644239e-01 -6.23367429e-01 1.53832257e-01 -7.70467937e-01 -6.18651807e-01 1.53823823e-01 -7.74241924e-01 -6.13933921e-01 1.53813735e-01 -7.77984083e-01 -6.09153271e-01 1.53822199e-01 -7.81710386e-01 -6.04372978e-01 1.53894082e-01 -7.85385370e-01 -5.99556983e-01 1.54031694e-01 -7.89013505e-01 -5.94700038e-01 1.54275179e-01 -7.92465985e-01 -5.89726746e-01 1.55615598e-01 -7.96333611e-01 -5.85028768e-01 1.53603792e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.17513764e-01 -5.55435777e-01 1.52191639e-01 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. 0. 0. -8.51016521e-01 -4.97931510e-01 1.66838363e-01 -8.53687584e-01 -4.92507964e-01 1.69202760e-01 -8.57024729e-01 -4.87432986e-01 1.67080611e-01 -8.60726058e-01 -4.82528478e-01 1.62093133e-01 -8.64228368e-01 -4.77515221e-01 1.58188581e-01 -8.67285728e-01 -4.72262502e-01 1.57430440e-01 -8.70259702e-01 -4.66996342e-01 1.56548247e-01 -8.73483419e-01 -4.61826891e-01 1.54048070e-01 -8.76311898e-01 -4.56469059e-01 1.53863832e-01 -8.79131854e-01 -4.51073736e-01 1.53925315e-01 -8.81833971e-01 -4.45665449e-01 1.54060051e-01 -8.84549618e-01 -4.40229774e-01 1.54230550e-01 -8.87185335e-01 -4.34782118e-01 1.54464141e-01 -8.89863491e-01 -4.29343015e-01 1.54271066e-01 -8.92527163e-01 -4.23890620e-01 1.54064491e-01 -8.95097494e-01 -4.18410331e-01 1.53985217e-01 -8.97652209e-01 -4.12921965e-01 1.53896615e-01 -9.00182843e-01 -4.07393605e-01 1.53883398e-01 -9.02680993e-01 -4.01861310e-01 1.53921291e-01 -9.05089915e-01 -3.96313071e-01 1.54044345e-01 -9.07471478e-01 -3.90738487e-01 1.54277474e-01 -9.09839869e-01 -3.85152191e-01 1.54458195e-01 -9.12192464e-01 -3.79566312e-01 1.54379547e-01 -9.14433241e-01 -3.73936713e-01 1.54833674e-01 -9.16324317e-01 -3.68183583e-01 1.57378227e-01 -9.18953419e-01 -3.62687439e-01 1.54841512e-01 -9.21193600e-01 -3.57051283e-01 1.54665202e-01 -9.23345625e-01 -3.51385295e-01 1.54805511e-01 -9.25195336e-01 -3.45619380e-01 1.56647801e-01 -9.26985562e-01 -3.39838326e-01 1.58690512e-01 -9.28886890e-01 -3.34096611e-01 1.59717247e-01 -9.31212366e-01 -3.28473002e-01 1.58008665e-01 -9.33301866e-01 -3.22789818e-01 1.57209203e-01 -9.35312152e-01 -3.17078501e-01 1.56823829e-01 -9.37259316e-01 -3.11332792e-01 1.56701326e-01 -9.39175665e-01 -3.05587053e-01 1.56669721e-01 -9.41055059e-01 -2.99804449e-01 1.56671852e-01 -9.42855835e-01 -2.94027686e-01 1.56654283e-01 -9.44661498e-01 -2.88237035e-01 1.56660467e-01 -9.46406722e-01 -2.82438785e-01 1.56682193e-01 -9.48098600e-01 -2.76622266e-01 1.56682745e-01 -9.49782729e-01 -2.70804226e-01 1.56689703e-01 -9.51455057e-01 -2.64967471e-01 1.56676993e-01 -9.53062236e-01 -2.59123474e-01 1.56681806e-01 -9.54609990e-01 -2.53273040e-01 1.56663790e-01 -9.56126690e-01 -2.47414708e-01 1.56691298e-01 -9.57673788e-01 -2.41532281e-01 1.56689659e-01 -9.59123433e-01 -2.35656336e-01 1.56697363e-01 -9.60567117e-01 -2.29765251e-01 1.56686246e-01 -9.61911678e-01 -2.23866165e-01 1.56701356e-01 -9.63279843e-01 -2.17959404e-01 1.56722531e-01 -9.64614451e-01 -2.12044612e-01 1.56737506e-01 -9.65908885e-01 -2.06122905e-01 1.56764746e-01 -9.67125952e-01 -2.00193599e-01 1.56786785e-01 -9.68325555e-01 -1.94253698e-01 1.56828627e-01 -9.69517946e-01 -1.88308001e-01 1.56830564e-01 -9.70665455e-01 -1.82356313e-01 1.56797066e-01 -9.71724272e-01 -1.76397175e-01 1.56795830e-01 -9.72830534e-01 -1.70430392e-01 1.56820163e-01 -9.73855972e-01 -1.64461717e-01 1.56827569e-01 -9.74834323e-01 -1.58478975e-01 1.56829447e-01 -9.75797832e-01 -1.52497232e-01 1.56831890e-01 -9.76700962e-01 -1.46505609e-01 1.56860739e-01 -9.77552414e-01 -1.40509769e-01 1.56840697e-01 -9.78429139e-01 -1.34509027e-01 1.56897888e-01 -9.79204774e-01 -1.28506631e-01 1.56788111e-01 -9.80064154e-01 -1.22497708e-01 1.56323835e-01 -9.80783999e-01 -1.16484582e-01 1.56350836e-01 -9.81519103e-01 -1.10464513e-01 1.56178072e-01 -9.82192218e-01 -1.04439154e-01 1.56088263e-01 -9.82867539e-01 -9.84121636e-02 1.55904099e-01 -9.83476996e-01 -9.23838764e-02 1.55595481e-01 -9.84041989e-01 -8.63475725e-02 1.55517355e-01 -9.84484076e-01 -8.03069919e-02 1.55843303e-01 -9.85167086e-01 -7.42701516e-02 1.54645145e-01 -9.85675275e-01 -6.82260394e-02 1.54086694e-01 -9.86130893e-01 -6.21766672e-02 1.54058307e-01 -9.86471415e-01 -5.61245270e-02 1.54065982e-01 -9.86779034e-01 -5.00704870e-02 1.54096350e-01 -9.87090588e-01 -4.40148152e-02 1.54107064e-01 -9.87334013e-01 -3.79572436e-02 1.54109672e-01 -9.87553716e-01 -3.18987407e-02 1.54129878e-01 -9.87727702e-01 -2.58385371e-02 1.54085100e-01 -9.87846196e-01 -1.97773855e-02 1.54059693e-01 -9.87971067e-01 -1.37154553e-02 1.54067069e-01 -9.88059521e-01 -7.65317306e-03 1.54067174e-01 0. 0. 0. -9.92965758e-01 5.22139110e-03 1.18361175e-01 -9.92870748e-01 1.13135269e-02 1.18410364e-01 -9.92804646e-01 1.74047723e-02 1.18497133e-01 -9.92676675e-01 2.34957859e-02 1.18534915e-01 -9.92487371e-01 2.95859836e-02 1.18574023e-01 -9.92305696e-01 3.56752239e-02 1.18581876e-01 -9.92075443e-01 4.17628475e-02 1.18605018e-01 -9.91771340e-01 4.78497632e-02 1.18552908e-01 -9.91493762e-01 5.39351478e-02 1.18502483e-01 -9.91139770e-01 6.00186028e-02 1.18438475e-01 -9.90775228e-01 6.60996288e-02 1.18389308e-01 -9.90328968e-01 7.21781924e-02 1.18360110e-01 -9.89899158e-01 7.82527477e-02 1.18393704e-01 -9.89355803e-01 8.43244344e-02 1.18454471e-01 -9.88829374e-01 9.03923586e-02 1.18511744e-01 -9.88230109e-01 9.64553058e-02 1.18658885e-01 -9.87558901e-01 1.02509536e-01 1.19065911e-01 -9.86842036e-01 1.08550720e-01 1.19879343e-01 -9.86039102e-01 1.14587501e-01 1.20661780e-01 -9.85290766e-01 1.20628774e-01 1.21025145e-01 -9.84549880e-01 1.26671508e-01 1.20918900e-01 -9.83742654e-01 1.32718429e-01 1.20687440e-01 -9.83000040e-01 1.38757318e-01 1.20479830e-01 -9.82088149e-01 1.44790351e-01 1.20335802e-01 -9.81189728e-01 1.50815800e-01 1.20245203e-01 -9.80308473e-01 1.56830832e-01 1.20210841e-01 -9.79338825e-01 1.62847370e-01 1.20189980e-01 -9.78270292e-01 1.68851182e-01 1.20207772e-01 -9.77234244e-01 1.74850658e-01 1.20209537e-01 -9.76121008e-01 1.80846140e-01 1.20186374e-01 -9.75037336e-01 1.86829314e-01 1.20209076e-01 -9.73842919e-01 1.92806721e-01 1.20207652e-01 -9.72631872e-01 1.98781341e-01 1.20228462e-01 -9.71416652e-01 2.04740569e-01 1.20222934e-01 -9.70146060e-01 2.10702911e-01 1.20208278e-01 -9.68817890e-01 2.16652885e-01 1.20197631e-01 -9.67481434e-01 2.22592548e-01 1.20199643e-01 -9.66086566e-01 2.28526160e-01 1.20213002e-01 -9.64647651e-01 2.34449118e-01 1.20221086e-01 -9.63186264e-01 2.40356624e-01 1.20222799e-01 -9.61724460e-01 2.46272027e-01 1.20223023e-01 -9.60205913e-01 2.52161384e-01 1.20219804e-01 -9.58592176e-01 2.58048177e-01 1.20231926e-01 -9.57041740e-01 2.63926029e-01 1.20226450e-01 -9.55409408e-01 2.69795954e-01 1.20206304e-01 -9.53729689e-01 2.75658369e-01 1.20191202e-01 -9.52022254e-01 2.81500429e-01 1.20198801e-01 -9.50277686e-01 2.87327260e-01 1.20177872e-01 -9.48467612e-01 2.93164253e-01 1.20197050e-01 -9.46686983e-01 2.98969030e-01 1.20196223e-01 -9.44782615e-01 3.04770410e-01 1.20209530e-01 -9.42906022e-01 3.10573041e-01 1.20209806e-01 -9.40985084e-01 3.16341907e-01 1.20213419e-01 -9.39019918e-01 3.22109759e-01 1.20225810e-01 -9.37024534e-01 3.27864379e-01 1.20228916e-01 -9.35046315e-01 3.33609343e-01 1.20231397e-01 -9.32932734e-01 3.39349896e-01 1.20254770e-01 -9.30865824e-01 3.45060438e-01 1.20234519e-01 -9.28746104e-01 3.50759894e-01 1.20228611e-01 -9.26567256e-01 3.56453240e-01 1.20220952e-01 -9.24344242e-01 3.62143159e-01 1.20210491e-01 -9.22089040e-01 3.67797524e-01 1.20210864e-01 -9.19805288e-01 3.73458236e-01 1.20203957e-01 -9.17536736e-01 3.79094511e-01 1.20206915e-01 -9.15191233e-01 3.84713858e-01 1.20210432e-01 -9.12777364e-01 3.90328646e-01 1.20200582e-01 -9.10365760e-01 3.95910650e-01 1.20203130e-01 -9.07924235e-01 4.01486188e-01 1.20219961e-01 -9.05478954e-01 4.07053292e-01 1.20228104e-01 -9.02935982e-01 4.12608504e-01 1.20227292e-01 -9.00403261e-01 4.18138236e-01 1.20238259e-01 -8.97808850e-01 4.23652232e-01 1.20248675e-01 -8.95183027e-01 4.29151088e-01 1.20233133e-01 -8.92560482e-01 4.34636652e-01 1.20251440e-01 -8.89852107e-01 4.40113246e-01 1.20252468e-01 -8.87130082e-01 4.45564032e-01 1.20271593e-01 -8.84399414e-01 4.50989485e-01 1.20312579e-01 -8.81596386e-01 4.56401676e-01 1.20419405e-01 -8.78762722e-01 4.61787432e-01 1.20686568e-01 -8.75790954e-01 4.67116386e-01 1.21477105e-01 -8.72531891e-01 4.72241849e-01 1.25146747e-01 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. -8.42724323e-01 5.25413930e-01 1.17285177e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.12287569e-01 5.71006954e-01 1.18911527e-01 -8.08679581e-01 5.75909376e-01 1.19820260e-01 -8.05213273e-01 5.80926895e-01 1.18961215e-01 -8.01644504e-01 5.85859656e-01 1.18873812e-01 -7.97858536e-01 5.90628445e-01 1.20557472e-01 -7.94236183e-01 5.95532477e-01 1.20414518e-01 -7.90594697e-01 6.00408435e-01 1.20389149e-01 -7.86870360e-01 6.05244696e-01 1.20422132e-01 -7.83159912e-01 6.10037506e-01 1.20549589e-01 -7.79383957e-01 6.14829540e-01 1.20721743e-01 -7.75565803e-01 6.19581759e-01 1.20799728e-01 -7.71788597e-01 6.24338388e-01 1.20583229e-01 -7.67946362e-01 6.29080296e-01 1.20389104e-01 -7.64079809e-01 6.33785784e-01 1.20305002e-01 -7.60197997e-01 6.38491809e-01 1.20251209e-01 -7.56223917e-01 6.43118858e-01 1.20258875e-01 -7.52295315e-01 6.47750020e-01 1.20246701e-01 -7.48319387e-01 6.52353644e-01 1.20259963e-01 -7.44294882e-01 6.56933784e-01 1.20251738e-01 -7.40220249e-01 6.61509693e-01 1.20241493e-01 -7.36180484e-01 6.66019142e-01 1.20249540e-01 -7.32079566e-01 6.70525491e-01 1.20253742e-01 -7.27950335e-01 6.75003529e-01 1.20239839e-01 -7.23774910e-01 6.79467738e-01 1.20246515e-01 -7.19596565e-01 6.83897972e-01 1.20264232e-01 -7.15372860e-01 6.88300312e-01 1.20253161e-01 -7.11134136e-01 6.92673147e-01 1.20261565e-01 -7.06875265e-01 6.97029650e-01 1.20275572e-01 -7.02604473e-01 7.01352656e-01 1.20270200e-01 -6.98271692e-01 7.05641508e-01 1.20273069e-01 -6.93926275e-01 7.09912479e-01 1.20214835e-01 -6.89558923e-01 7.14151144e-01 1.20252058e-01 -6.85179889e-01 7.18370080e-01 1.20262086e-01 -6.80742502e-01 7.22571671e-01 1.20275423e-01 -6.76309764e-01 7.26728082e-01 1.20288208e-01 -6.71845496e-01 7.30853677e-01 1.20291024e-01 -6.67339206e-01 7.34968722e-01 1.20311044e-01 -6.62802458e-01 7.39067733e-01 1.20297603e-01 -6.58275127e-01 7.43097782e-01 1.20265387e-01 -6.53691113e-01 7.47130096e-01 1.20219432e-01 -6.49088800e-01 7.51118839e-01 1.20247826e-01 -6.44474268e-01 7.55091488e-01 1.20193288e-01 -6.39842391e-01 7.59073675e-01 1.20182529e-01 -6.35158539e-01 7.62972474e-01 1.20164923e-01 -6.30487144e-01 7.66857445e-01 1.20116979e-01 -6.25779629e-01 7.70728409e-01 1.20122768e-01 -6.21015370e-01 7.74512231e-01 1.20130986e-01 -6.16251826e-01 7.78336704e-01 1.20094024e-01 -6.11482680e-01 7.82118082e-01 1.20079122e-01 -6.06671989e-01 7.85844624e-01 1.20041549e-01 -6.01831317e-01 7.89536357e-01 1.20010570e-01 -5.96981704e-01 7.93233871e-01 1.20006703e-01 -5.92105091e-01 7.96899676e-01 1.19993508e-01 -5.87191164e-01 8.00488710e-01 1.19967006e-01 -5.82290173e-01 8.04087162e-01 1.19941309e-01 -5.77345192e-01 8.07617962e-01 1.19937800e-01 -5.72377920e-01 8.11191142e-01 1.19955115e-01 -5.67381799e-01 8.14641714e-01 1.19989559e-01 -5.62359214e-01 8.18112433e-01 1.20020449e-01 -5.57338476e-01 8.21553469e-01 1.20098345e-01 -5.52270055e-01 8.24944198e-01 1.20140038e-01 -5.47198653e-01 8.28309715e-01 1.20185874e-01 -5.42107880e-01 8.31662357e-01 1.20199300e-01 -5.36995411e-01 8.34964156e-01 1.20161250e-01 -5.31867623e-01 8.38250875e-01 1.20087795e-01 -5.26705325e-01 8.41516674e-01 1.20042145e-01 -5.21560073e-01 8.44735980e-01 1.20008551e-01 -5.16360819e-01 8.47917438e-01 1.19953267e-01 -5.11149943e-01 8.51071537e-01 1.19922400e-01 -5.05928814e-01 8.54205966e-01 1.19892843e-01 -5.00661492e-01 8.57291222e-01 1.19858995e-01 -4.95401531e-01 8.60368848e-01 1.19851202e-01 -4.90108579e-01 8.63359869e-01 1.19831458e-01 -4.84792918e-01 8.66350889e-01 1.19826786e-01 -4.79477584e-01 8.69341552e-01 1.19823709e-01 -4.74125981e-01 8.72254312e-01 1.19833641e-01 -4.68772948e-01 8.75160813e-01 1.19812980e-01 -4.63401645e-01 8.77987087e-01 1.19810335e-01 -4.57997501e-01 8.80823672e-01 1.19800575e-01 -4.52589393e-01 8.83649349e-01 1.19782872e-01 -4.47163016e-01 8.86387348e-01 1.19776331e-01 -4.41712558e-01 8.89117777e-01 1.19775817e-01 -4.36251998e-01 8.91800404e-01 1.19787380e-01 -4.30767864e-01 8.94465685e-01 1.19778596e-01 -4.25268173e-01 8.97071958e-01 1.19788326e-01 -4.19763505e-01 8.99711370e-01 1.19794823e-01 -4.14231658e-01 9.02226031e-01 1.19787380e-01 -4.08679515e-01 9.04800594e-01 1.19784810e-01 -4.03122634e-01 9.07248259e-01 1.19769104e-01 -3.97549123e-01 9.09721196e-01 1.19770221e-01 -3.91958266e-01 9.12147224e-01 1.19750626e-01 -3.86362404e-01 9.14523959e-01 1.19737990e-01 -3.80742222e-01 9.16913867e-01 1.19759940e-01 -3.75106305e-01 9.19192970e-01 1.19748957e-01 -3.69463295e-01 9.21521783e-01 1.19731441e-01 -3.63800317e-01 9.23725963e-01 1.19720735e-01 -3.58131081e-01 9.25959587e-01 1.19705401e-01 -3.52439731e-01 9.28134739e-01 1.19691893e-01 -3.46740216e-01 9.30275917e-01 1.19691186e-01 -3.41026962e-01 9.32437599e-01 1.19677402e-01 -3.35294604e-01 9.34458792e-01 1.19680472e-01 -3.29556316e-01 9.36553240e-01 1.19695053e-01 -3.23801965e-01 9.38515604e-01 1.19688757e-01 -3.18034083e-01 9.40470099e-01 1.19686514e-01 -3.12264204e-01 9.42407787e-01 1.19683459e-01 -3.06473106e-01 9.44332778e-01 1.19662344e-01 -3.00679475e-01 9.46209550e-01 1.19660735e-01 -2.94862658e-01 9.47987914e-01 1.19660787e-01 -2.89044708e-01 9.49828863e-01 1.19669132e-01 -2.83206433e-01 9.51588809e-01 1.19653597e-01 -2.77365059e-01 9.53302443e-01 1.19627990e-01 -2.71509856e-01 9.54996407e-01 1.19623169e-01 -2.65650541e-01 9.56637084e-01 1.19624265e-01 -2.59771675e-01 9.58213389e-01 1.19654678e-01 -2.53892601e-01 9.59831834e-01 1.19640432e-01 -2.47984096e-01 9.61317360e-01 1.19669393e-01 -2.42091641e-01 9.62832749e-01 1.19662739e-01 -2.36168891e-01 9.64285433e-01 1.19680621e-01 -2.30258152e-01 9.65725005e-01 1.19691350e-01 -2.24325269e-01 9.67119932e-01 1.19677752e-01 -2.18387172e-01 9.68510270e-01 1.19677015e-01 -2.12443531e-01 9.69803870e-01 1.19640797e-01 -2.06479520e-01 9.71076369e-01 1.19645238e-01 -2.00523093e-01 9.72377837e-01 1.19642809e-01 -1.94550157e-01 9.73587155e-01 1.19663998e-01 -1.88575834e-01 9.74709272e-01 1.19660601e-01 -1.82590321e-01 9.75859225e-01 1.19671173e-01 -1.76596224e-01 9.76994276e-01 1.19663045e-01 -1.70598209e-01 9.78031397e-01 1.19646527e-01 -1.64595023e-01 9.79058504e-01 1.19652182e-01 -1.58586428e-01 9.80040967e-01 1.19655006e-01 -1.52567893e-01 9.81000483e-01 1.19643115e-01 -1.46544650e-01 9.81920958e-01 1.19660184e-01 -1.40519485e-01 9.82857823e-01 1.19642451e-01 -1.34483814e-01 9.83664393e-01 1.19626902e-01 -1.28448039e-01 9.84497845e-01 1.19647041e-01 -1.22407205e-01 9.85283434e-01 1.19631015e-01 -1.16356365e-01 9.86010730e-01 1.19631946e-01 -1.10303596e-01 9.86693263e-01 1.19631976e-01 -1.04246579e-01 9.87305701e-01 1.19619161e-01 -9.81865898e-02 9.87963676e-01 1.19639605e-01 -9.21242908e-02 9.88513947e-01 1.19629115e-01 -8.60563889e-02 9.89104331e-01 1.19643994e-01 -7.99872354e-02 9.89601374e-01 1.19651034e-01 -7.39137754e-02 9.90083456e-01 1.19661763e-01 -6.78368583e-02 9.90463376e-01 1.19673893e-01 -6.17585927e-02 9.90875423e-01 1.19657986e-01 -5.56776896e-02 9.91281092e-01 1.19663730e-01 -4.95942160e-02 9.91599381e-01 1.19637139e-01 -4.35085781e-02 9.91845965e-01 1.19656973e-01 -3.74221243e-02 9.92089748e-01 1.19658791e-01 -3.13337818e-02 9.92327273e-01 1.19665191e-01 -2.52447724e-02 9.92503285e-01 1.19680546e-01 -1.91543736e-02 9.92589951e-01 1.19659908e-01 -1.30635193e-02 9.92745101e-01 1.19681366e-01 -6.97190175e-03 9.92805839e-01 1.19672485e-01 -8.80187086e-04 9.92809176e-01 1.19675010e-01 5.21165924e-03 9.92810190e-01 1.19661808e-01 1.13032488e-02 9.92752254e-01 1.19655922e-01 1.73945967e-02 9.92634654e-01 1.19649470e-01 2.34852061e-02 9.92557347e-01 1.19631395e-01 2.95748785e-02 9.92346764e-01 1.19631492e-01 3.56637053e-02 9.92151499e-01 1.19627342e-01 4.17502113e-02 9.91906703e-01 1.19654477e-01 4.78354879e-02 9.91617441e-01 1.19661786e-01 5.39192222e-02 9.91352856e-01 1.19668439e-01 6.00010641e-02 9.91028845e-01 1.19673967e-01 6.60814866e-02 9.90624845e-01 1.19644798e-01 7.21588135e-02 9.90164578e-01 1.19624056e-01 7.82329664e-02 9.89722967e-01 1.19623691e-01 8.43040496e-02 9.89197195e-01 1.19617283e-01 9.03721750e-02 9.88692045e-01 1.19615190e-01 9.64357704e-02 9.88133490e-01 1.19606942e-01 1.02497213e-01 9.87490356e-01 1.19587839e-01 1.08554572e-01 9.86835957e-01 1.19601257e-01 1.14609636e-01 9.86191452e-01 1.19615771e-01 1.20658882e-01 9.85472143e-01 1.19633771e-01 1.26700819e-01 9.84722614e-01 1.19645707e-01 1.32740796e-01 9.83859301e-01 1.19667165e-01 1.38777494e-01 9.83096361e-01 1.19640552e-01 1.44806325e-01 9.82161939e-01 1.19672872e-01 1.50828958e-01 9.81258869e-01 1.19653776e-01 1.56845436e-01 9.80363727e-01 1.19671725e-01 1.62860230e-01 9.79392588e-01 1.19668245e-01 1.68866068e-01 9.78336036e-01 1.19644247e-01 1.74865648e-01 9.77297246e-01 1.19643793e-01 1.80860505e-01 9.76170957e-01 1.19665384e-01 1.86846241e-01 9.75098908e-01 1.19642191e-01 1.92823231e-01 9.73904073e-01 1.19660035e-01 1.98799074e-01 9.72696066e-01 1.19645365e-01 2.04759225e-01 9.71477747e-01 1.19658396e-01 2.10719123e-01 9.70201194e-01 1.19652957e-01 2.16671750e-01 9.68881488e-01 1.19637169e-01 2.22613096e-01 9.67539310e-01 1.19624965e-01 2.28547543e-01 9.66156960e-01 1.19583443e-01 2.34464660e-01 9.64710116e-01 1.19562149e-01 2.40379885e-01 9.63257432e-01 1.19551025e-01 2.46287420e-01 9.61793840e-01 1.19570494e-01 2.52189845e-01 9.60274160e-01 1.19569354e-01 2.58071959e-01 9.58671689e-01 1.19515046e-01 2.63948768e-01 9.57111418e-01 1.19551755e-01 2.69826919e-01 9.55484688e-01 1.19515851e-01 2.75675029e-01 9.53806639e-01 1.19485922e-01 2.81527400e-01 9.52103138e-01 1.19441241e-01 2.87360430e-01 9.50356007e-01 1.19450010e-01 2.93186605e-01 9.48545814e-01 1.19474545e-01 2.98997402e-01 9.46762919e-01 1.19490795e-01 3.04805309e-01 9.44857001e-01 1.19517513e-01 3.10607731e-01 9.42986190e-01 1.19469278e-01 3.16375464e-01 9.41066146e-01 1.19463474e-01 3.22142333e-01 9.39099431e-01 1.19453005e-01 3.27898711e-01 9.37108040e-01 1.19446568e-01 3.33645642e-01 9.35134768e-01 1.19423971e-01 3.39392066e-01 9.33002532e-01 1.19429089e-01 3.45096201e-01 9.30952966e-01 1.19418934e-01 3.50802988e-01 9.28835630e-01 1.19407043e-01 3.56494159e-01 9.26653564e-01 1.19411521e-01 3.62182051e-01 9.24431801e-01 1.19359128e-01 3.67838949e-01 9.22190368e-01 1.19371027e-01 3.73495549e-01 9.19891477e-01 1.19405366e-01 3.79138440e-01 9.17621434e-01 1.19398303e-01 3.84757847e-01 9.15278256e-01 1.19390830e-01 3.90367001e-01 9.12860811e-01 1.19399458e-01 3.95952880e-01 9.10450161e-01 1.19392864e-01 4.01531518e-01 9.08013344e-01 1.19363897e-01 4.07099992e-01 9.05563533e-01 1.19407535e-01 4.12656099e-01 9.03021514e-01 1.19391382e-01 4.18180048e-01 9.00491297e-01 1.19381316e-01 4.23698962e-01 8.97899091e-01 1.19364023e-01 4.29198533e-01 8.95275772e-01 1.19337849e-01 4.34696496e-01 8.92656684e-01 1.19326293e-01 4.40168589e-01 8.89944255e-01 1.19299501e-01 4.45617467e-01 8.87206256e-01 1.19312152e-01 4.51049209e-01 8.84502292e-01 1.19275339e-01 4.56465364e-01 8.81698668e-01 1.19270265e-01 4.61877644e-01 8.78911376e-01 1.19264334e-01 4.67251331e-01 8.76025796e-01 1.19258888e-01 4.72624809e-01 8.73133421e-01 1.19251631e-01 4.77981925e-01 8.70214939e-01 1.19224377e-01 4.83313501e-01 8.67297292e-01 1.19231835e-01 4.88619506e-01 8.64315331e-01 1.19254626e-01 4.93906289e-01 8.61260653e-01 1.19235925e-01 4.99189436e-01 8.58247638e-01 1.19237885e-01 5.04429817e-01 8.55179727e-01 1.19210050e-01 5.09670198e-01 8.52038682e-01 1.19205005e-01 5.14885128e-01 8.48889410e-01 1.19191855e-01 5.20093083e-01 8.45732272e-01 1.19204246e-01 5.25267541e-01 8.42559159e-01 1.19184516e-01 5.30442655e-01 8.39290977e-01 1.19172998e-01 5.35568953e-01 8.36032450e-01 1.19182207e-01 5.40691733e-01 8.32713723e-01 1.19182579e-01 5.45788109e-01 8.29401374e-01 1.19182706e-01 5.50873160e-01 8.26024294e-01 1.19180351e-01 5.55925906e-01 8.22630942e-01 1.19170889e-01 5.60978234e-01 8.19219351e-01 1.19171888e-01 5.65986037e-01 8.15747023e-01 1.19187117e-01 5.70971310e-01 8.12274396e-01 1.19170286e-01 5.75944841e-01 8.08739185e-01 1.19156003e-01 5.80904245e-01 8.05190563e-01 1.19150050e-01 5.85855067e-01 8.01622510e-01 1.19157545e-01 5.90743721e-01 7.97994256e-01 1.19157948e-01 5.95641792e-01 7.94356823e-01 1.19147174e-01 6.00504220e-01 7.90712774e-01 1.19155407e-01 6.05347872e-01 7.87003636e-01 1.19161256e-01 6.10148728e-01 7.83272088e-01 1.19145475e-01 6.14959717e-01 7.79521167e-01 1.19159125e-01 6.19719684e-01 7.75700867e-01 1.19167045e-01 6.24454737e-01 7.71917045e-01 1.19149931e-01 6.29182577e-01 7.68077433e-01 1.19128786e-01 6.33882105e-01 7.64199615e-01 1.19121961e-01 6.38587892e-01 7.60290086e-01 1.19123369e-01 6.43211842e-01 7.56328464e-01 1.19123153e-01 6.47845089e-01 7.52401054e-01 1.19129561e-01 6.52449608e-01 7.48411596e-01 1.19137332e-01 6.57024562e-01 7.44399548e-01 1.19133867e-01 6.61605358e-01 7.40319550e-01 1.19126260e-01 6.66117609e-01 7.36262858e-01 1.19105503e-01 6.70617163e-01 7.32174098e-01 1.19098678e-01 6.75104856e-01 7.28047669e-01 1.19097516e-01 6.79556191e-01 7.23847687e-01 1.19109035e-01 6.84019744e-01 7.19696820e-01 1.19117640e-01 6.88411713e-01 7.15479195e-01 1.19089320e-01 6.92781091e-01 7.11227238e-01 1.19065329e-01 6.97138131e-01 7.06988037e-01 1.19094960e-01 7.01475143e-01 7.02703834e-01 1.19127788e-01 7.05737293e-01 6.98367953e-01 1.19118661e-01 7.10012078e-01 6.94011092e-01 1.19108327e-01 7.14256883e-01 6.89644635e-01 1.19119167e-01 7.18473792e-01 6.85277283e-01 1.19104430e-01 7.22682357e-01 6.80830061e-01 1.19095854e-01 7.26836979e-01 6.76414847e-01 1.19085893e-01 7.30968118e-01 6.71941936e-01 1.19067252e-01 7.35082924e-01 6.67445600e-01 1.19068198e-01 7.39171922e-01 6.62894070e-01 1.19073249e-01 7.43209660e-01 6.58368409e-01 1.19076401e-01 7.47245908e-01 6.53773546e-01 1.19079940e-01 7.51225412e-01 6.49172485e-01 1.19092427e-01 7.55208313e-01 6.44560277e-01 1.19089395e-01 7.59180009e-01 6.39924824e-01 1.19104221e-01 7.63078570e-01 6.35236859e-01 1.19101226e-01 7.66957939e-01 6.30541742e-01 1.19108461e-01 7.70832360e-01 6.25859439e-01 1.19082607e-01 7.74645030e-01 6.21089518e-01 1.19058512e-01 7.78434753e-01 6.16326749e-01 1.19079411e-01 7.82218158e-01 6.11561179e-01 1.19099304e-01 7.85943866e-01 6.06746018e-01 1.19090982e-01 7.89640665e-01 6.01901948e-01 1.19102210e-01 7.93357491e-01 5.97051740e-01 1.19082466e-01 7.97004282e-01 5.92174888e-01 1.19070351e-01 8.00594389e-01 5.87265670e-01 1.19075462e-01 8.04189146e-01 5.82357526e-01 1.19063005e-01 8.07712078e-01 5.77409387e-01 1.19084716e-01 8.11301768e-01 5.72441101e-01 1.19081423e-01 8.14742327e-01 5.67449033e-01 1.19082645e-01 8.18230391e-01 5.62425137e-01 1.19094409e-01 8.21674347e-01 5.57410896e-01 1.19101249e-01 8.25074792e-01 5.52344739e-01 1.19085729e-01 8.28460455e-01 5.47276318e-01 1.19077042e-01 8.31778765e-01 5.42186737e-01 1.19065277e-01 8.35087776e-01 5.37065446e-01 1.19077049e-01 8.38375032e-01 5.31943262e-01 1.19082570e-01 8.41626942e-01 5.26771307e-01 1.19081639e-01 8.44845057e-01 5.21605849e-01 1.19101286e-01 8.48014772e-01 5.16419351e-01 1.19092040e-01 8.51164341e-01 5.11206508e-01 1.19108379e-01 8.54298174e-01 5.05963027e-01 1.19114287e-01 8.57379436e-01 5.00712156e-01 1.19119041e-01 8.60457957e-01 4.95449841e-01 1.19105674e-01 8.63443255e-01 4.90146875e-01 1.19124681e-01 8.66435468e-01 4.84844685e-01 1.19113952e-01 8.69424284e-01 4.79518890e-01 1.19127952e-01 8.72340202e-01 4.74169970e-01 1.19110756e-01 8.75247300e-01 4.68815416e-01 1.19107589e-01 8.78067732e-01 4.63443995e-01 1.19116984e-01 8.80894959e-01 4.58027929e-01 1.19136468e-01 8.83722425e-01 4.52620357e-01 1.19151965e-01 8.86462569e-01 4.47199076e-01 1.19146399e-01 8.89195621e-01 4.41748947e-01 1.19138204e-01 8.91877830e-01 4.36287552e-01 1.19135886e-01 8.94533992e-01 4.30801362e-01 1.19133122e-01 8.97147298e-01 4.25300509e-01 1.19139880e-01 8.99791002e-01 4.19785678e-01 1.19124785e-01 9.02302504e-01 4.14268494e-01 1.19124480e-01 9.04869795e-01 4.08711553e-01 1.19145975e-01 9.07321036e-01 4.03154969e-01 1.19169712e-01 9.09792662e-01 3.97579879e-01 1.19173810e-01 9.12214339e-01 3.91985238e-01 1.19200274e-01 9.14583623e-01 3.86389345e-01 1.19208418e-01 9.16975379e-01 3.80764365e-01 1.19227342e-01 9.19257700e-01 3.75122815e-01 1.19219936e-01 9.21582341e-01 3.69485497e-01 1.19214579e-01 9.23786581e-01 3.63820910e-01 1.19209632e-01 9.25994694e-01 3.58149946e-01 1.19217925e-01 9.28166568e-01 3.52455795e-01 1.19218200e-01 9.30324256e-01 3.46757680e-01 1.19246751e-01 9.32482541e-01 3.41039032e-01 1.19248584e-01 9.34508502e-01 3.35308403e-01 1.19238488e-01 9.36601520e-01 3.29564393e-01 1.19252540e-01 9.38563228e-01 3.23808461e-01 1.19240493e-01 9.40517962e-01 3.18048030e-01 1.19242325e-01 9.42456484e-01 3.12278628e-01 1.19236268e-01 9.44377422e-01 3.06479931e-01 1.19237661e-01 9.46251631e-01 3.00693959e-01 1.19242236e-01 9.48032439e-01 2.94882149e-01 1.19239196e-01 9.49872971e-01 2.89059222e-01 1.19249746e-01 9.51629460e-01 2.83212572e-01 1.19264513e-01 9.53338504e-01 2.77373075e-01 1.19277842e-01 9.55022991e-01 2.71514267e-01 1.19292200e-01 9.56667900e-01 2.65652895e-01 1.19294606e-01 9.58252788e-01 2.59779125e-01 1.19278260e-01 9.59865689e-01 2.53888398e-01 1.19293109e-01 9.61355388e-01 2.47995615e-01 1.19286656e-01 9.62861955e-01 2.42100433e-01 1.19312599e-01 9.64321971e-01 2.36179471e-01 1.19318649e-01 9.65763628e-01 2.30254620e-01 1.19310610e-01 9.67158258e-01 2.24333107e-01 1.19290084e-01 9.68546152e-01 2.18394235e-01 1.19285129e-01 9.69834805e-01 2.12439895e-01 1.19311340e-01 9.71106470e-01 2.06487179e-01 1.19326830e-01 9.72408295e-01 2.00529620e-01 1.19309686e-01 9.73619699e-01 1.94556341e-01 1.19323850e-01 9.74746644e-01 1.88580826e-01 1.19327940e-01 9.75896955e-01 1.82594717e-01 1.19311564e-01 9.77032185e-01 1.76600844e-01 1.19295210e-01 9.78069127e-01 1.70603171e-01 1.19284749e-01 9.79097366e-01 1.64599553e-01 1.19296148e-01 9.80080128e-01 1.58590794e-01 1.19299240e-01 9.81040418e-01 1.52571902e-01 1.19274274e-01 9.81961370e-01 1.46548882e-01 1.19276553e-01 9.82897520e-01 1.40521750e-01 1.19270541e-01 9.83700871e-01 1.34487599e-01 1.19274780e-01 9.84535813e-01 1.28452793e-01 1.19276859e-01 9.85319972e-01 1.22404769e-01 1.19279653e-01 9.86047268e-01 1.16359390e-01 1.19280338e-01 9.86730456e-01 1.10307574e-01 1.19277246e-01 9.87341464e-01 1.04250215e-01 1.19285963e-01 9.87999856e-01 9.81901512e-02 1.19292624e-01 9.88552630e-01 9.21273381e-02 1.19297974e-01 9.89140570e-01 8.60571414e-02 1.19316295e-01 9.89639521e-01 7.99883679e-02 1.19298153e-01 9.90123034e-01 7.39142746e-02 1.19289652e-01 9.90503490e-01 6.78381398e-02 1.19295903e-01 9.90914106e-01 6.17577285e-02 1.19300827e-01 9.91318941e-01 5.56770712e-02 1.19306415e-01 9.91633654e-01 4.95935343e-02 1.19317494e-01 9.91881788e-01 4.35082093e-02 1.19323172e-01 9.92127955e-01 3.74213010e-02 1.19311512e-01 9.92364645e-01 3.13326605e-02 1.19318672e-01 9.92543995e-01 2.52432302e-02 1.19328529e-01 9.92629528e-01 1.91527046e-02 1.19311050e-01 9.92787302e-01 1.30615104e-02 1.19316123e-01 9.92846429e-01 6.96981326e-03 1.19317420e-01 9.92849827e-01 8.77885672e-04 1.19328216e-01 9.92852032e-01 -5.21434192e-03 1.19303033e-01 9.92792666e-01 -1.13061490e-02 1.19316332e-01 9.92671132e-01 -1.73972417e-02 1.19340636e-01 9.92591858e-01 -2.34879926e-02 1.19335629e-01 9.92378891e-01 -2.95777880e-02 1.19348817e-01 9.92183864e-01 -3.56667452e-02 1.19352736e-01 9.91947532e-01 -4.17535715e-02 1.19362488e-01 9.91653204e-01 -4.78394441e-02 1.19362198e-01 9.91390228e-01 -5.39237671e-02 1.19354814e-01 9.91069734e-01 -6.00061864e-02 1.19347736e-01 9.90657091e-01 -6.60843924e-02 1.19371086e-01 9.90192473e-01 -7.21621066e-02 1.19367905e-01 9.89751101e-01 -7.82367140e-02 1.19377054e-01 9.89226580e-01 -8.43082368e-02 1.19367242e-01 9.88720894e-01 -9.03772190e-02 1.19378693e-01 9.88169968e-01 -9.64410901e-02 1.19376346e-01 9.87514079e-01 -1.02503091e-01 1.19385257e-01 9.86862004e-01 -1.08560354e-01 1.19373985e-01 9.86225069e-01 -1.14613444e-01 1.19357750e-01 9.85507727e-01 -1.20662585e-01 1.19359970e-01 9.84721482e-01 -1.26704514e-01 1.19368531e-01 9.83895183e-01 -1.32747129e-01 1.19363092e-01 9.83128250e-01 -1.38782188e-01 1.19372383e-01 9.82198238e-01 -1.44812047e-01 1.19356617e-01 9.81290102e-01 -1.50836483e-01 1.19341724e-01 9.80406165e-01 -1.56851500e-01 1.19341776e-01 9.79433715e-01 -1.62868619e-01 1.19344473e-01 9.78364408e-01 -1.68873817e-01 1.19344868e-01 9.77329969e-01 -1.74873546e-01 1.19350880e-01 9.76198912e-01 -1.80869296e-01 1.19346052e-01 9.75131869e-01 -1.86852887e-01 1.19352460e-01 9.73938227e-01 -1.92833915e-01 1.19338721e-01 9.72725868e-01 -1.98807761e-01 1.19374454e-01 9.71509337e-01 -2.04768956e-01 1.19371109e-01 9.70235527e-01 -2.10727349e-01 1.19370252e-01 9.68907118e-01 -2.16677293e-01 1.19367503e-01 9.67572033e-01 -2.22620681e-01 1.19359955e-01 9.66179430e-01 -2.28549927e-01 1.19361617e-01 9.64742482e-01 -2.34481007e-01 1.19356461e-01 9.63274539e-01 -2.40383357e-01 1.19385056e-01 9.61813867e-01 -2.46299997e-01 1.19383052e-01 9.60297406e-01 -2.52195269e-01 1.19366914e-01 9.58684087e-01 -2.58076191e-01 1.19380429e-01 9.57130611e-01 -2.63953775e-01 1.19377658e-01 9.55499768e-01 -2.69830793e-01 1.19350553e-01 9.53814328e-01 -2.75685877e-01 1.19384237e-01 9.52104628e-01 -2.81527966e-01 1.19378105e-01 9.50360179e-01 -2.87360996e-01 1.19364984e-01 9.48553324e-01 -2.93195367e-01 1.19362444e-01 9.46772814e-01 -2.99008429e-01 1.19370922e-01 9.44870174e-01 -3.04801017e-01 1.19364068e-01 9.42992210e-01 -3.10604483e-01 1.19369082e-01 9.41072524e-01 -3.16375375e-01 1.19352147e-01 9.39108610e-01 -3.22147638e-01 1.19343504e-01 9.37114954e-01 -3.27903897e-01 1.19332969e-01 9.35136199e-01 -3.33646268e-01 1.19362608e-01 9.33035195e-01 -3.39390367e-01 1.19353734e-01 9.30951297e-01 -3.45096409e-01 1.19372316e-01 9.28837478e-01 -3.50797504e-01 1.19337685e-01 9.26657319e-01 -3.56491894e-01 1.19345315e-01 9.24428523e-01 -3.62182170e-01 1.19341157e-01 9.22175527e-01 -3.67839962e-01 1.19331911e-01 9.19898689e-01 -3.73506337e-01 1.19301818e-01 9.17626202e-01 -3.79140675e-01 1.19334519e-01 9.15281236e-01 -3.84755582e-01 1.19348273e-01 9.12863314e-01 -3.90368998e-01 1.19362794e-01 9.10456598e-01 -3.95954460e-01 1.19331904e-01 9.08017635e-01 -4.01534140e-01 1.19326621e-01 9.05573189e-01 -4.07099158e-01 1.19313464e-01 9.03026700e-01 -4.12663549e-01 1.19317919e-01 9.00499105e-01 -4.18191344e-01 1.19301975e-01 8.97903621e-01 -4.23702538e-01 1.19313352e-01 8.95273328e-01 -4.29206461e-01 1.19324178e-01 8.92658174e-01 -4.34689581e-01 1.19320624e-01 8.89942825e-01 -4.40168768e-01 1.19317323e-01 8.87231588e-01 -4.45618808e-01 1.19353235e-01 8.84500921e-01 -4.51048732e-01 1.19330950e-01 8.81699562e-01 -4.56461877e-01 1.19316168e-01 8.78910005e-01 -4.61878359e-01 1.19312987e-01 8.76023412e-01 -4.67246860e-01 1.19319037e-01 8.73134136e-01 -4.72623050e-01 1.19292125e-01 8.70214462e-01 -4.77978468e-01 1.19285718e-01 8.67296517e-01 -4.83302146e-01 1.19298965e-01 8.64316225e-01 -4.88618284e-01 1.19299635e-01 8.61260831e-01 -4.93903190e-01 1.19299293e-01 8.58256996e-01 -4.99191016e-01 1.19284846e-01 8.55177343e-01 -5.04433751e-01 1.19282506e-01 8.52036476e-01 -5.09668589e-01 1.19277768e-01 8.48893821e-01 -5.14888585e-01 1.19295515e-01 8.45730007e-01 -5.20088077e-01 1.19280078e-01 8.42554867e-01 -5.25265455e-01 1.19276337e-01 8.39296043e-01 -5.30442953e-01 1.19244523e-01 8.36034000e-01 -5.35570979e-01 1.19246557e-01 8.32722545e-01 -5.40694416e-01 1.19222254e-01 8.29400301e-01 -5.45788884e-01 1.19231574e-01 8.26022446e-01 -5.50873041e-01 1.19234867e-01 8.22629511e-01 -5.55933416e-01 1.19227782e-01 8.19212556e-01 -5.60979426e-01 1.19257852e-01 8.15750659e-01 -5.65985501e-01 1.19243272e-01 8.12274277e-01 -5.70970833e-01 1.19259998e-01 8.08732212e-01 -5.75941384e-01 1.19241953e-01 8.05181623e-01 -5.80902994e-01 1.19215116e-01 8.01619649e-01 -5.85835636e-01 1.19213015e-01 7.97989488e-01 -5.90730548e-01 1.19214453e-01 7.94348359e-01 -5.95644772e-01 1.19236059e-01 7.90707111e-01 -6.00500762e-01 1.19224139e-01 7.86995113e-01 -6.05344236e-01 1.19225860e-01 7.83266783e-01 -6.10141218e-01 1.19235210e-01 7.79521048e-01 -6.14954054e-01 1.19233735e-01 7.75699139e-01 -6.19709074e-01 1.19257025e-01 7.71916270e-01 -6.24448717e-01 1.19253442e-01 7.68061459e-01 -6.29174829e-01 1.19253978e-01 7.64185250e-01 -6.33874178e-01 1.19253226e-01 7.60285616e-01 -6.38579011e-01 1.19255297e-01 7.56318986e-01 -6.43204868e-01 1.19261704e-01 7.52390563e-01 -6.47832870e-01 1.19261868e-01 7.48409569e-01 -6.52438164e-01 1.19255848e-01 7.44386315e-01 -6.57019973e-01 1.19270831e-01 7.40311980e-01 -6.61594212e-01 1.19255714e-01 7.36259699e-01 -6.66105747e-01 1.19256243e-01 7.32173741e-01 -6.70615256e-01 1.19250961e-01 7.28048861e-01 -6.75093114e-01 1.19240113e-01 7.23842502e-01 -6.79558814e-01 1.19238831e-01 7.19693244e-01 -6.84010684e-01 1.19218804e-01 7.15468049e-01 -6.88405871e-01 1.19219318e-01 7.11226404e-01 -6.92772210e-01 1.19223550e-01 7.06981063e-01 -6.97134912e-01 1.19202040e-01 7.02700555e-01 -7.01472580e-01 1.19196542e-01 6.98365271e-01 -7.05737352e-01 1.19207948e-01 6.94011867e-01 -7.10008681e-01 1.19207226e-01 6.89643204e-01 -7.14257538e-01 1.19210787e-01 6.85274303e-01 -7.18471348e-01 1.19202107e-01 6.80827498e-01 -7.22681463e-01 1.19198717e-01 6.76396132e-01 -7.26821363e-01 1.19225897e-01 6.71930671e-01 -7.30947435e-01 1.19242787e-01 6.67427301e-01 -7.35062420e-01 1.19230486e-01 6.62887454e-01 -7.39168465e-01 1.19237207e-01 6.58360243e-01 -7.43199706e-01 1.19222693e-01 6.53768003e-01 -7.47232914e-01 1.19199231e-01 6.49169326e-01 -7.51219332e-01 1.19206339e-01 6.44553185e-01 -7.55190492e-01 1.19217999e-01 6.39916539e-01 -7.59169161e-01 1.19225167e-01 6.35230362e-01 -7.63067126e-01 1.19233638e-01 6.30533338e-01 -7.66947806e-01 1.19218282e-01 6.25850856e-01 -7.70820856e-01 1.19194560e-01 6.21079504e-01 -7.74624169e-01 1.19189478e-01 6.16318703e-01 -7.78430700e-01 1.19185552e-01 6.11554742e-01 -7.82210290e-01 1.19179405e-01 6.06738448e-01 -7.85938859e-01 1.19178697e-01 6.01891696e-01 -7.89616764e-01 1.19220294e-01 5.97038031e-01 -7.93337464e-01 1.19227618e-01 5.92158854e-01 -7.96979547e-01 1.19250506e-01 5.87244809e-01 -8.00564408e-01 1.19254917e-01 5.82338631e-01 -8.04152966e-01 1.19254977e-01 5.77395439e-01 -8.07693839e-01 1.19234443e-01 5.72427213e-01 -8.11278939e-01 1.19220510e-01 5.67436099e-01 -8.14725101e-01 1.19205348e-01 5.62414169e-01 -8.18199694e-01 1.19188644e-01 5.57402492e-01 -8.21656883e-01 1.19157456e-01 5.52335799e-01 -8.25056970e-01 1.19151242e-01 5.47267556e-01 -8.28442216e-01 1.19169928e-01 5.42177498e-01 -8.31770957e-01 1.19163267e-01 5.37057996e-01 -8.35076034e-01 1.19146302e-01 5.31930506e-01 -8.38359654e-01 1.19131744e-01 5.26766539e-01 -8.41616154e-01 1.19146422e-01 5.21612167e-01 -8.44839990e-01 1.19142152e-01 5.16414344e-01 -8.48010480e-01 1.19126707e-01 5.11198699e-01 -8.51160526e-01 1.19122215e-01 5.05964577e-01 -8.54293466e-01 1.19126745e-01 5.00708878e-01 -8.57374132e-01 1.19099103e-01 4.95445549e-01 -8.60448837e-01 1.19089782e-01 4.90146428e-01 -8.63443136e-01 1.19078860e-01 4.84835535e-01 -8.66436064e-01 1.19065888e-01 4.79521602e-01 -8.69423926e-01 1.19071014e-01 4.74167287e-01 -8.72335494e-01 1.19088322e-01 4.68815356e-01 -8.75242531e-01 1.19071424e-01 4.63441133e-01 -8.78070951e-01 1.19092204e-01 4.58029658e-01 -8.80905688e-01 1.19100370e-01 4.52622771e-01 -8.83722186e-01 1.19118728e-01 4.47197169e-01 -8.86464655e-01 1.19135790e-01 4.41744983e-01 -8.89199197e-01 1.19159952e-01 4.36285853e-01 -8.91880274e-01 1.19159296e-01 4.30803031e-01 -8.94544661e-01 1.19149789e-01 4.25302774e-01 -8.97151351e-01 1.19134039e-01 4.19796497e-01 -8.99792612e-01 1.19137079e-01 4.14267182e-01 -9.02311206e-01 1.19115084e-01 4.08711970e-01 -9.04879749e-01 1.19132899e-01 4.03154016e-01 -9.07328784e-01 1.19138055e-01 3.97580624e-01 -9.09803152e-01 1.19142145e-01 3.91985685e-01 -9.12225842e-01 1.19157068e-01 3.86391789e-01 -9.14596677e-01 1.19140767e-01 3.80769342e-01 -9.16985810e-01 1.19139619e-01 3.75127941e-01 -9.19271410e-01 1.19131222e-01 3.69492948e-01 -9.21593904e-01 1.19113125e-01 3.63820851e-01 -9.23796952e-01 1.19109437e-01 3.58155012e-01 -9.26029623e-01 1.19105011e-01 3.52461606e-01 -9.28205311e-01 1.19107477e-01 3.46763849e-01 -9.30339456e-01 1.19106054e-01 3.41044605e-01 -9.32498038e-01 1.19092889e-01 3.35314065e-01 -9.34523761e-01 1.19074523e-01 3.29567969e-01 -9.36617494e-01 1.19065925e-01 3.23812753e-01 -9.38574672e-01 1.19091839e-01 3.18047464e-01 -9.40528691e-01 1.19115859e-01 3.12281549e-01 -9.42465067e-01 1.19127691e-01 3.06481868e-01 -9.44383502e-01 1.19151190e-01 3.00693512e-01 -9.46256518e-01 1.19143561e-01 2.94878542e-01 -9.48039472e-01 1.19154550e-01 2.89058894e-01 -9.49877203e-01 1.19149387e-01 2.83216357e-01 -9.51634645e-01 1.19188145e-01 2.77375847e-01 -9.53339875e-01 1.19230583e-01 2.71514654e-01 -9.55033541e-01 1.19228564e-01 2.65659660e-01 -9.56667244e-01 1.19250387e-01 2.59783477e-01 -9.58260417e-01 1.19239010e-01 2.53895640e-01 -9.59867656e-01 1.19260401e-01 2.47992307e-01 -9.61358190e-01 1.19272895e-01 2.42098168e-01 -9.62874055e-01 1.19285636e-01 2.36175999e-01 -9.64329600e-01 1.19290769e-01 2.30261520e-01 -9.65770483e-01 1.19277172e-01 2.24332869e-01 -9.67158735e-01 1.19284503e-01 2.18392923e-01 -9.68539119e-01 1.19295269e-01 2.12444440e-01 -9.69835460e-01 1.19307868e-01 2.06485882e-01 -9.71112907e-01 1.19322494e-01 2.00530291e-01 -9.72403467e-01 1.19299859e-01 1.94557548e-01 -9.73614514e-01 1.19311430e-01 1.88579172e-01 -9.74751234e-01 1.19312197e-01 1.82595789e-01 -9.75899577e-01 1.19294062e-01 1.76599890e-01 -9.77029145e-01 1.19286150e-01 1.70601234e-01 -9.78069782e-01 1.19282641e-01 1.64599836e-01 -9.79101539e-01 1.19292475e-01 1.58592269e-01 -9.80086684e-01 1.19287051e-01 1.52571335e-01 -9.81044829e-01 1.19284235e-01 1.46546841e-01 -9.81962681e-01 1.19283602e-01 1.40519142e-01 -9.82895315e-01 1.19283728e-01 1.34484634e-01 -9.83704746e-01 1.19297236e-01 1.28450587e-01 -9.84530151e-01 1.19294502e-01 1.22408569e-01 -9.85319376e-01 1.19276896e-01 1.16358429e-01 -9.86044824e-01 1.19301386e-01 1.10305965e-01 -9.86726224e-01 1.19292654e-01 1.04249015e-01 -9.87343848e-01 1.19302049e-01 9.81892645e-02 -9.87999141e-01 1.19314626e-01 9.21259969e-02 -9.88552690e-01 1.19326539e-01 8.60585570e-02 -9.89131749e-01 1.19346075e-01 7.99873769e-02 -9.89625335e-01 1.19367085e-01 7.39136115e-02 -9.90109622e-01 1.19364634e-01 6.78369105e-02 -9.90504324e-01 1.19353876e-01 6.17592447e-02 -9.90908742e-01 1.19366698e-01 5.56766838e-02 -9.91297066e-01 1.19416818e-01 4.95943204e-02 -9.91621256e-01 1.19413398e-01 4.35080491e-02 -9.91867721e-01 1.19428314e-01 3.74217220e-02 -9.92112219e-01 1.19425759e-01 3.13331112e-02 -9.92353499e-01 1.19401246e-01 2.52436791e-02 -9.92520750e-01 1.19443111e-01 1.91532969e-02 -9.92612064e-01 1.19441427e-01 1.30623383e-02 -9.92759943e-01 1.19459458e-01 6.97086984e-03 -9.92820919e-01 1.19488277e-01 8.79087893e-04 -9.92824137e-01 1.19504213e-01 -5.21297846e-03 -9.92825985e-01 1.19480990e-01 -1.13042705e-02 -9.92753327e-01 1.19527876e-01 -1.73950866e-02 -9.92645562e-01 1.19565055e-01 -2.34851260e-02 -9.92550611e-01 1.19607337e-01 -2.95747072e-02 -9.92344320e-01 1.19615912e-01 -3.56630832e-02 -9.92154837e-01 1.19644418e-01 -4.17505540e-02 -9.91913378e-01 1.19628660e-01 -4.78361547e-02 -9.91621733e-01 1.19594619e-01 -5.39195314e-02 -9.91354585e-01 1.19600572e-01 -6.00015558e-02 -9.91018057e-01 1.19629033e-01 -6.60812929e-02 -9.90619302e-01 1.19641617e-01 -7.21567199e-02 -9.90151823e-01 1.19701512e-01 -7.82310888e-02 -9.89718854e-01 1.19700454e-01 -8.43023211e-02 -9.89184678e-01 1.19717285e-01 -9.03690085e-02 -9.88674283e-01 1.19743854e-01 -9.64349657e-02 -9.88103807e-01 1.19731463e-01 -1.02494560e-01 -9.87467527e-01 1.19744070e-01 -1.08551629e-01 -9.86828268e-01 1.19742550e-01 -1.14605956e-01 -9.86163020e-01 1.19724907e-01 -1.20656013e-01 -9.85448599e-01 1.19721532e-01 -1.26697809e-01 -9.84697044e-01 1.19708285e-01 -1.32742167e-01 -9.83852923e-01 1.19691119e-01 -1.38775349e-01 -9.83081460e-01 1.19702257e-01 -1.44804940e-01 -9.82154429e-01 1.19696416e-01 -1.50829226e-01 -9.81255054e-01 1.19689345e-01 -1.56842411e-01 -9.80344832e-01 1.19705468e-01 -1.62861601e-01 -9.79380012e-01 1.19648367e-01 -1.68864429e-01 -9.78333116e-01 1.19637407e-01 -1.74863681e-01 -9.77289855e-01 1.19645245e-01 -1.80862606e-01 -9.76177692e-01 1.19598418e-01 -1.86845347e-01 -9.75101352e-01 1.19578071e-01 -1.92828327e-01 -9.73912716e-01 1.19543158e-01 -1.98801398e-01 -9.72702742e-01 1.19551115e-01 -2.04763636e-01 -9.71486807e-01 1.19549364e-01 -2.10721657e-01 -9.70210016e-01 1.19531311e-01 -2.16674551e-01 -9.68890071e-01 1.19525276e-01 -2.22617313e-01 -9.67552304e-01 1.19468525e-01 -2.28551731e-01 -9.66169000e-01 1.19430758e-01 -2.34469414e-01 -9.64722633e-01 1.19429782e-01 -2.40381122e-01 -9.63266909e-01 1.19423538e-01 -2.46293545e-01 -9.61804092e-01 1.19446389e-01 -2.52192944e-01 -9.60286021e-01 1.19429633e-01 -2.58072495e-01 -9.58677590e-01 1.19421721e-01 -2.63950765e-01 -9.57123458e-01 1.19415917e-01 -2.69829035e-01 -9.55493331e-01 1.19393088e-01 -2.75682062e-01 -9.53813493e-01 1.19381204e-01 -2.81525552e-01 -9.52104867e-01 1.19380578e-01 -2.87357837e-01 -9.50353682e-01 1.19401962e-01 -2.93192059e-01 -9.48549449e-01 1.19408034e-01 -2.98999757e-01 -9.46764827e-01 1.19431101e-01 -3.04806024e-01 -9.44859624e-01 1.19455710e-01 -3.10601026e-01 -9.42986548e-01 1.19444713e-01 -3.16377640e-01 -9.41066027e-01 1.19449623e-01 -3.22138250e-01 -9.39095497e-01 1.19465120e-01 -3.27893466e-01 -9.37097907e-01 1.19500160e-01 -3.33638340e-01 -9.35121715e-01 1.19489424e-01 -3.39387089e-01 -9.32987809e-01 1.19494297e-01 -3.45090657e-01 -9.30936813e-01 1.19490184e-01 -3.50797474e-01 -9.28821087e-01 1.19489990e-01 -3.56488287e-01 -9.26639140e-01 1.19512081e-01 -3.62175554e-01 -9.24410701e-01 1.19506270e-01 -3.67829412e-01 -9.22161281e-01 1.19526617e-01 -3.73493791e-01 -9.19877350e-01 1.19516551e-01 -3.79133135e-01 -9.17603135e-01 1.19528778e-01 -3.84749085e-01 -9.15260553e-01 1.19528629e-01 -3.90359104e-01 -9.12849009e-01 1.19506478e-01 -3.95945251e-01 -9.10438359e-01 1.19500764e-01 -4.01520997e-01 -9.07995820e-01 1.19523354e-01 -4.07091618e-01 -9.05551314e-01 1.19523823e-01 -4.12646383e-01 -9.03007388e-01 1.19540110e-01 -4.18175668e-01 -9.00477469e-01 1.19522087e-01 -4.23691064e-01 -8.97886097e-01 1.19501576e-01 -4.29190248e-01 -8.95258844e-01 1.19505651e-01 -4.34686810e-01 -8.92637551e-01 1.19519278e-01 -4.40154254e-01 -8.89923930e-01 1.19541876e-01 -4.45607066e-01 -8.87180924e-01 1.19534031e-01 -4.51032519e-01 -8.84476721e-01 1.19551703e-01 -4.56451237e-01 -8.81677806e-01 1.19543754e-01 -4.61858124e-01 -8.78886700e-01 1.19549476e-01 -4.67235774e-01 -8.75999808e-01 1.19554505e-01 -4.72606152e-01 -8.73104334e-01 1.19554818e-01 -4.77963865e-01 -8.70186925e-01 1.19544566e-01 -4.83295441e-01 -8.67271900e-01 1.19539201e-01 -4.88602340e-01 -8.64284158e-01 1.19557120e-01 -4.93888229e-01 -8.61235499e-01 1.19552679e-01 -4.99170274e-01 -8.58215928e-01 1.19589105e-01 -5.04408300e-01 -8.55146229e-01 1.19597614e-01 -5.09646356e-01 -8.51999581e-01 1.19619526e-01 -5.14860094e-01 -8.48851740e-01 1.19617194e-01 -5.20062864e-01 -8.45689952e-01 1.19654126e-01 -5.25237441e-01 -8.42516720e-01 1.19662166e-01 -5.30412793e-01 -8.39256883e-01 1.19654693e-01 -5.35533547e-01 -8.35988045e-01 1.19681813e-01 -5.40661693e-01 -8.32676172e-01 1.19687356e-01 -5.45757949e-01 -8.29352915e-01 1.19686447e-01 -5.50841033e-01 -8.25974524e-01 1.19698130e-01 -5.55892825e-01 -8.22578311e-01 1.19709276e-01 -5.60935855e-01 -8.19163203e-01 1.19732164e-01 -5.65951943e-01 -8.15706670e-01 1.19702242e-01 -5.70932865e-01 -8.12221229e-01 1.19709812e-01 -5.75908542e-01 -8.08700085e-01 1.19705252e-01 -5.80859065e-01 -8.05125654e-01 1.19741470e-01 -5.85807264e-01 -8.01567674e-01 1.19738959e-01 -5.90699673e-01 -7.97938228e-01 1.19733803e-01 -5.95600307e-01 -7.94303894e-01 1.19722962e-01 -6.00464284e-01 -7.90663064e-01 1.19702868e-01 -6.05306506e-01 -7.86947072e-01 1.19708471e-01 -6.10105217e-01 -7.83231258e-01 1.19714387e-01 -6.14918292e-01 -7.79490054e-01 1.19663171e-01 -6.19680405e-01 -7.75657952e-01 1.19650602e-01 -6.24409258e-01 -7.71869719e-01 1.19704030e-01 -6.29136145e-01 -7.68024504e-01 1.19698964e-01 -6.33835018e-01 -7.64143467e-01 1.19734436e-01 -6.38538539e-01 -7.60241449e-01 1.19749181e-01 -6.43160582e-01 -7.56270647e-01 1.19773343e-01 -6.47790432e-01 -7.52341986e-01 1.19776398e-01 -6.52390897e-01 -7.48358905e-01 1.19830564e-01 -6.56968892e-01 -7.44335234e-01 1.19838603e-01 -6.61551178e-01 -7.40259230e-01 1.19804598e-01 -6.66056752e-01 -7.36221790e-01 1.19808704e-01 -6.70564055e-01 -7.32121646e-01 1.19816415e-01 -6.75043225e-01 -7.27991164e-01 1.19817041e-01 -6.79500282e-01 -7.23791361e-01 1.19831420e-01 -6.83953762e-01 -7.19637334e-01 1.19803235e-01 -6.88349247e-01 -7.15415239e-01 1.19792558e-01 -6.92715645e-01 -7.11168647e-01 1.19785324e-01 -6.97078943e-01 -7.06927001e-01 1.19779900e-01 -7.01418757e-01 -7.02650249e-01 1.19775377e-01 -7.05679595e-01 -6.98316693e-01 1.19764283e-01 -7.09953189e-01 -6.93958342e-01 1.19772553e-01 -7.14188278e-01 -6.89594567e-01 1.19793296e-01 -7.18409419e-01 -6.85218275e-01 1.19833939e-01 -7.22609758e-01 -6.80766642e-01 1.19870044e-01 -7.26753414e-01 -6.76342010e-01 1.19902737e-01 -7.30888307e-01 -6.71881318e-01 1.19849272e-01 -7.35001683e-01 -6.67374313e-01 1.19873889e-01 -7.39103854e-01 -6.62832141e-01 1.19886681e-01 -7.43129849e-01 -6.58305049e-01 1.19902112e-01 -7.47164607e-01 -6.53717279e-01 1.19902283e-01 -7.51147747e-01 -6.49111748e-01 1.19927004e-01 -7.55118847e-01 -6.44494534e-01 1.19947627e-01 -7.59096265e-01 -6.39862478e-01 1.19965151e-01 -7.63128400e-01 -6.35279298e-01 1.18582860e-01 -7.67000079e-01 -6.30579591e-01 1.18674740e-01 -7.70841777e-01 -6.25865579e-01 1.18737757e-01 -7.74716437e-01 -6.21157944e-01 1.18170500e-01 -7.78523684e-01 -6.16385639e-01 1.18192315e-01 -7.82284498e-01 -6.11605585e-01 1.18227549e-01 -7.86043823e-01 -6.06801093e-01 1.18115932e-01 -7.89651275e-01 -6.01904750e-01 1.18879899e-01 -7.93256283e-01 -5.96997559e-01 1.19715638e-01 -7.96933830e-01 -5.92137456e-01 1.19408943e-01 -8.00597906e-01 -5.87267280e-01 1.18991695e-01 -8.04129958e-01 -5.82309186e-01 1.19519554e-01 -8.07817757e-01 -5.77446640e-01 1.18260115e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.38556409e-01 -5.32033086e-01 1.17320761e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.62610340e-01 -4.89729226e-01 1.26762345e-01 -8.65557432e-01 -4.84406531e-01 1.27124235e-01 -8.68903339e-01 -4.79274482e-01 1.23656586e-01 -8.72015417e-01 -4.74022985e-01 1.21971957e-01 -8.75202775e-01 -4.68802601e-01 1.19320787e-01 -8.78100753e-01 -4.63439822e-01 1.18994884e-01 -8.80840898e-01 -4.58003610e-01 1.19765379e-01 -8.82874012e-01 -4.52252418e-01 1.26495570e-01 -8.85631979e-01 -4.46826577e-01 1.26498789e-01 -8.89012814e-01 -4.41665441e-01 1.20700300e-01 -8.92002106e-01 -4.36328202e-01 1.18099920e-01 -8.94674957e-01 -4.30852294e-01 1.17996916e-01 -8.97297740e-01 -4.25354987e-01 1.17959723e-01 -8.99919152e-01 -4.19842213e-01 1.17913075e-01 -9.02474463e-01 -4.14319456e-01 1.17884926e-01 -9.04989243e-01 -4.08766001e-01 1.17922120e-01 -9.07476366e-01 -4.03202057e-01 1.18011355e-01 -9.09937680e-01 -3.97632301e-01 1.17904872e-01 -9.12215233e-01 -3.91988873e-01 1.19176269e-01 -9.14080024e-01 -3.86196971e-01 1.23730533e-01 -9.16430235e-01 -3.80580336e-01 1.23749457e-01 -9.18972492e-01 -3.75027061e-01 1.21795706e-01 -9.21158254e-01 -3.69348168e-01 1.22618973e-01 -9.23820496e-01 -3.63826334e-01 1.19086936e-01 -9.26014960e-01 -3.58147174e-01 1.19234413e-01 -9.28193688e-01 -3.52458090e-01 1.19151644e-01 -9.30201471e-01 -3.46718669e-01 1.20288476e-01 -9.32378471e-01 -3.41012865e-01 1.20119311e-01 -9.34467852e-01 -3.35293055e-01 1.19667061e-01 -9.36617911e-01 -3.29573065e-01 1.19038902e-01 -9.38396573e-01 -3.23765516e-01 1.20655343e-01 -9.40326273e-01 -3.17991555e-01 1.20894551e-01 -9.42296028e-01 -3.12232137e-01 1.20616317e-01 -9.44254816e-01 -3.06450248e-01 1.20291196e-01 -9.46150243e-01 -3.00670207e-01 1.20129339e-01 -9.47942913e-01 -2.94857711e-01 1.20042555e-01 -9.49783027e-01 -2.89038062e-01 1.20062865e-01 -9.51540828e-01 -2.83189178e-01 1.20056860e-01 -9.53250229e-01 -2.77351260e-01 1.20066904e-01 -9.54933286e-01 -2.71491706e-01 1.20077141e-01 -9.56580877e-01 -2.65640527e-01 1.20075509e-01 -9.58163619e-01 -2.59765327e-01 1.20061047e-01 -9.59777534e-01 -2.53871977e-01 1.20078377e-01 -9.61266518e-01 -2.47976139e-01 1.20081127e-01 -9.62768972e-01 -2.42082849e-01 1.20099008e-01 -9.64232922e-01 -2.36160785e-01 1.20098926e-01 -9.65671897e-01 -2.30243504e-01 1.20105378e-01 -9.67065454e-01 -2.24319071e-01 1.20108120e-01 -9.68454897e-01 -2.18380719e-01 1.20101258e-01 -9.69743490e-01 -2.12430432e-01 1.20112643e-01 -9.71013844e-01 -2.06470743e-01 1.20140806e-01 -9.72423494e-01 -2.00532943e-01 1.19194143e-01 -9.73605156e-01 -1.94556564e-01 1.19453050e-01 -9.74879563e-01 -1.88592151e-01 1.18469954e-01 -9.76043403e-01 -1.82613656e-01 1.18171148e-01 -9.77139592e-01 -1.76618233e-01 1.18202202e-01 -9.78197873e-01 -1.70618072e-01 1.18256181e-01 -9.79251027e-01 -1.64614111e-01 1.18265286e-01 -9.80236471e-01 -1.58602938e-01 1.18279278e-01 -9.81190383e-01 -1.52584448e-01 1.18275940e-01 -9.82097030e-01 -1.46561578e-01 1.18209504e-01 -9.83011544e-01 -1.40532374e-01 1.18268557e-01 -9.83844399e-01 -1.34497464e-01 1.18254252e-01 -9.84617054e-01 -1.28460750e-01 1.18307270e-01 -9.85414803e-01 -1.22415259e-01 1.18346177e-01 -9.86145675e-01 -1.16365850e-01 1.18373871e-01 -9.86807585e-01 -1.10312663e-01 1.18390515e-01 -9.87479627e-01 -1.04255743e-01 1.18420690e-01 -9.88094091e-01 -9.81941745e-02 1.18505672e-01 -9.88676727e-01 -9.21297371e-02 1.18498161e-01 -9.89197314e-01 -8.60612616e-02 1.18531667e-01 -9.89718616e-01 -7.99907446e-02 1.18470415e-01 -9.90202606e-01 -7.39158690e-02 1.18406944e-01 -9.90650475e-01 -6.78391606e-02 1.18418559e-01 -9.91022229e-01 -6.17591850e-02 1.18473716e-01 -9.91370738e-01 -5.56773581e-02 1.18558243e-01 -9.91719604e-01 -4.95931469e-02 1.18574537e-01 -9.91977572e-01 -4.35071215e-02 1.18599437e-01 -9.92216527e-01 -3.74197923e-02 1.18624836e-01 -9.92462337e-01 -3.13303694e-02 1.18506834e-01 -9.92622137e-01 -2.52400041e-02 1.18420534e-01 -9.92767632e-01 -1.91480294e-02 1.18257910e-01 -9.92890596e-01 -1.30559728e-02 1.18228555e-01 -9.92973804e-01 -6.96351426e-03 1.18262134e-01 0. 0. 0. -9.96623397e-01 5.54037699e-03 8.19170922e-02 -9.96509075e-01 1.16497735e-02 8.26680139e-02 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. 0. 0. 0. 0. 0. -9.92800534e-01 8.49013403e-02 8.44317898e-02 -9.92100418e-01 9.09620449e-02 8.64567161e-02 -9.91651654e-01 9.70725492e-02 8.47788602e-02 -9.91082132e-01 1.03163749e-01 8.42999071e-02 -9.90465462e-01 1.09249480e-01 8.39199200e-02 -9.89767551e-01 1.15327358e-01 8.37557614e-02 -9.89061296e-01 1.21400893e-01 8.36761519e-02 -9.88303006e-01 1.27467617e-01 8.36283863e-02 -9.87516224e-01 1.33529767e-01 8.35539252e-02 -9.86706376e-01 1.39588207e-01 8.35490227e-02 -9.85806644e-01 1.45639017e-01 8.36044326e-02 -9.84892726e-01 1.51681274e-01 8.36505368e-02 -9.83915269e-01 1.57722935e-01 8.37630108e-02 -9.82937396e-01 1.63752854e-01 8.38013217e-02 -9.81886029e-01 1.69780955e-01 8.39082301e-02 -9.80845392e-01 1.75803274e-01 8.38835984e-02 -9.79729891e-01 1.81819230e-01 8.37604180e-02 -9.78664696e-01 1.87832445e-01 8.36479962e-02 -9.77512062e-01 1.93830267e-01 8.35985690e-02 -9.76299584e-01 1.99828357e-01 8.36027563e-02 -9.75034237e-01 2.05810934e-01 8.36237967e-02 -9.73719716e-01 2.11791903e-01 8.36528018e-02 -9.72418606e-01 2.17764363e-01 8.36678296e-02 -9.71041024e-01 2.23726138e-01 8.36804137e-02 -9.69677210e-01 2.29684025e-01 8.36704820e-02 -9.68264997e-01 2.35623851e-01 8.36645737e-02 -9.66805041e-01 2.41562054e-01 8.36602822e-02 -9.65300083e-01 2.47486189e-01 8.36168155e-02 -9.63728487e-01 2.53408819e-01 8.36190581e-02 -9.62190151e-01 2.59319067e-01 8.36097822e-02 -9.60555434e-01 2.65218168e-01 8.36015493e-02 -9.58901703e-01 2.71109939e-01 8.35798904e-02 -9.57258701e-01 2.76977062e-01 8.35529119e-02 -9.55551207e-01 2.82851726e-01 8.35616142e-02 -9.53755856e-01 2.88709611e-01 8.35554376e-02 -9.51985300e-01 2.94550896e-01 8.35452974e-02 -9.50134993e-01 3.00387412e-01 8.35583210e-02 -9.48312759e-01 3.06214005e-01 8.35762918e-02 -9.46387291e-01 3.12024206e-01 8.35571364e-02 -9.44443166e-01 3.17831188e-01 8.35508853e-02 -9.42490518e-01 3.23619992e-01 8.35526660e-02 -9.40488696e-01 3.29397649e-01 8.35441053e-02 -9.38425660e-01 3.35164398e-01 8.35466832e-02 -9.36392844e-01 3.40902239e-01 8.35317373e-02 -9.34239089e-01 3.46659213e-01 8.35375339e-02 -9.32099342e-01 3.52381647e-01 8.35390761e-02 -9.29923296e-01 3.58099937e-01 8.35288018e-02 -9.27717447e-01 3.63780409e-01 8.35404396e-02 -9.25462365e-01 3.69473189e-01 8.35426524e-02 -9.23201919e-01 3.75140697e-01 8.35458189e-02 -9.20843065e-01 3.80796820e-01 8.35498050e-02 -9.18498039e-01 3.86450529e-01 8.35489705e-02 -9.16139245e-01 3.92070651e-01 8.35379809e-02 -9.13711011e-01 3.97684097e-01 8.35465491e-02 -9.11264420e-01 4.03285563e-01 8.35296884e-02 -9.08742428e-01 4.08870250e-01 8.35219920e-02 -9.06238258e-01 4.14432615e-01 8.35199133e-02 -9.03648973e-01 4.19991612e-01 8.35361183e-02 -9.01091278e-01 4.25521582e-01 8.35453868e-02 -8.98451269e-01 4.31043565e-01 8.35460797e-02 -8.95776868e-01 4.36561137e-01 8.35563913e-02 -8.93093705e-01 4.42039996e-01 8.35947171e-02 -8.90340745e-01 4.47509497e-01 8.36726055e-02 -8.87563527e-01 4.52962428e-01 8.39309841e-02 -8.84687066e-01 4.58336085e-01 8.51018727e-02 -8.81617785e-01 4.63603914e-01 8.84114727e-02 -8.78706396e-01 4.68973249e-01 8.90942439e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.32326174e-01 5.48091114e-01 8.26390684e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.18529367e-01 5.68274438e-01 8.41055438e-02 -8.15101266e-01 5.73349655e-01 8.29267576e-02 -8.11472058e-01 5.78256786e-01 8.42577443e-02 -8.07936788e-01 5.83253980e-01 8.38298351e-02 -8.04347098e-01 5.88210583e-01 8.36746022e-02 -8.00734341e-01 5.93126118e-01 8.36460814e-02 -7.97084093e-01 5.98027110e-01 8.36556852e-02 -7.93368399e-01 6.02919340e-01 8.37156847e-02 -7.89681196e-01 6.07752860e-01 8.38593170e-02 -7.85893679e-01 6.12566531e-01 8.42721835e-02 -7.82143593e-01 6.17419899e-01 8.39412361e-02 -7.78362393e-01 6.22194409e-01 8.37153345e-02 -7.74527550e-01 6.26964986e-01 8.36337358e-02 -7.70683110e-01 6.31712079e-01 8.35945085e-02 -7.66798437e-01 6.36428177e-01 8.35708827e-02 -7.62862742e-01 6.41135097e-01 8.35578963e-02 -7.58931935e-01 6.45793438e-01 8.35791752e-02 -7.54926145e-01 6.50429308e-01 8.35838765e-02 -7.50927329e-01 6.55049145e-01 8.35622400e-02 -7.46893704e-01 6.59661293e-01 8.35612491e-02 -7.42843211e-01 6.64232850e-01 8.35664570e-02 -7.38753140e-01 6.68781996e-01 8.35615695e-02 -7.34620869e-01 6.73285007e-01 8.35598186e-02 -7.30483294e-01 6.77787185e-01 8.35515559e-02 -7.26336837e-01 6.82276964e-01 8.35392922e-02 -7.22098589e-01 6.86696470e-01 8.35490301e-02 -7.17907190e-01 6.91126943e-01 8.35756436e-02 -7.13646352e-01 6.95514798e-01 8.36154446e-02 -7.09338486e-01 6.99877381e-01 8.36496726e-02 -7.05040097e-01 7.04199374e-01 8.36557895e-02 -7.00688362e-01 7.08532512e-01 8.36768001e-02 -6.96344495e-01 7.12809443e-01 8.36725906e-02 -6.91942990e-01 7.17066526e-01 8.36857110e-02 -6.87525332e-01 7.21312940e-01 8.37136284e-02 -6.83111906e-01 7.25487053e-01 8.37071165e-02 -6.78640425e-01 7.29686618e-01 8.37151334e-02 -6.74140453e-01 7.33844399e-01 8.37120488e-02 -6.69637978e-01 7.37958968e-01 8.36976096e-02 -6.65109277e-01 7.42033184e-01 8.36647004e-02 -6.60523772e-01 7.46135712e-01 8.36265460e-02 -6.55932248e-01 7.50153482e-01 8.36060271e-02 -6.51319265e-01 7.54174650e-01 8.35696980e-02 -6.46668613e-01 7.58162200e-01 8.35358500e-02 -6.42033219e-01 7.62090862e-01 8.34990367e-02 -6.37333512e-01 7.66022861e-01 8.34955573e-02 -6.32634759e-01 7.69929409e-01 8.35148916e-02 -6.27896607e-01 7.73797095e-01 8.35150033e-02 -6.23145759e-01 7.77640402e-01 8.35016370e-02 -6.18328631e-01 7.81435132e-01 8.34812447e-02 -6.13543928e-01 7.85225987e-01 8.34946558e-02 -6.08710468e-01 7.88973927e-01 8.34545642e-02 -6.03848159e-01 7.92707145e-01 8.34760964e-02 -5.98981559e-01 7.96377718e-01 8.34596679e-02 -5.94090283e-01 8.00041556e-01 8.34517628e-02 -5.89165807e-01 8.03676069e-01 8.34113061e-02 -5.84231436e-01 8.07270706e-01 8.34248811e-02 -5.79269052e-01 8.10870707e-01 8.33883509e-02 -5.74280441e-01 8.14381123e-01 8.34152102e-02 -5.69268763e-01 8.17919254e-01 8.34609568e-02 -5.64228177e-01 8.21352363e-01 8.35092440e-02 -5.59189022e-01 8.24818134e-01 8.35293233e-02 -5.54097831e-01 8.28239322e-01 8.35181996e-02 -5.49016654e-01 8.31624746e-01 8.35803226e-02 -5.43893993e-01 8.34954381e-01 8.35497826e-02 -5.38769484e-01 8.38273108e-01 8.35487321e-02 -5.33624709e-01 8.41574013e-01 8.35119858e-02 -5.28433979e-01 8.44846368e-01 8.34710822e-02 -5.23261189e-01 8.48090827e-01 8.34352672e-02 -5.18054128e-01 8.51263523e-01 8.33891481e-02 -5.12823164e-01 8.54430497e-01 8.33293051e-02 -5.07560849e-01 8.57588887e-01 8.32870156e-02 -5.02287447e-01 8.60681653e-01 8.32396299e-02 -4.97009158e-01 8.63724589e-01 8.32288638e-02 -4.91693527e-01 8.66768837e-01 8.32388550e-02 -4.86346185e-01 8.69760156e-01 8.32596421e-02 -4.81000364e-01 8.72718513e-01 8.33048075e-02 -4.75638211e-01 8.75670075e-01 8.32987949e-02 -4.70274746e-01 8.78541112e-01 8.33023414e-02 -4.64870930e-01 8.81437361e-01 8.32815096e-02 -4.59456265e-01 8.84282053e-01 8.32895562e-02 -4.54012454e-01 8.87052238e-01 8.32979009e-02 -4.48567808e-01 8.89859259e-01 8.32912996e-02 -4.43100035e-01 8.92606735e-01 8.32884610e-02 -4.37611222e-01 8.95298243e-01 8.32979530e-02 -4.32098210e-01 8.97971511e-01 8.32946450e-02 -4.26597595e-01 9.00582135e-01 8.32828060e-02 -4.21065390e-01 9.03179049e-01 8.32695216e-02 -4.15509969e-01 9.05763447e-01 8.32685083e-02 -4.09947485e-01 9.08285022e-01 8.32832828e-02 -4.04354483e-01 9.10795748e-01 8.33096653e-02 -3.98759574e-01 9.13280725e-01 8.32829028e-02 -3.93157810e-01 9.15706873e-01 8.32960159e-02 -3.87525111e-01 9.18083012e-01 8.33067521e-02 -3.81897777e-01 9.20435309e-01 8.33211616e-02 -3.76240462e-01 9.22783196e-01 8.32950175e-02 -3.70565444e-01 9.25058484e-01 8.32826048e-02 -3.64885151e-01 9.27313685e-01 8.32680687e-02 -3.59181285e-01 9.29537177e-01 8.32754225e-02 -3.53479356e-01 9.31728303e-01 8.32549408e-02 -3.47749025e-01 9.33871806e-01 8.32638368e-02 -3.42017263e-01 9.35956836e-01 8.32743421e-02 -3.36268127e-01 9.38095450e-01 8.32791254e-02 -3.30503881e-01 9.40091431e-01 8.32612216e-02 -3.24725091e-01 9.42106426e-01 8.32797661e-02 -3.18944216e-01 9.44118083e-01 8.32577646e-02 -3.13139915e-01 9.46045518e-01 8.32358003e-02 -3.07331473e-01 9.47932959e-01 8.32278281e-02 -3.01510751e-01 9.49808419e-01 8.32281262e-02 -2.95673788e-01 9.51666534e-01 8.32169950e-02 -2.89833337e-01 9.53453720e-01 8.32306519e-02 -2.83974051e-01 9.55178976e-01 8.32333043e-02 -2.78109461e-01 9.56928670e-01 8.32177922e-02 -2.72232115e-01 9.58587170e-01 8.32167119e-02 -2.66352236e-01 9.60270226e-01 8.32195356e-02 -2.60454923e-01 9.61896777e-01 8.32524076e-02 -2.54542679e-01 9.63448346e-01 8.32429156e-02 -2.48628244e-01 9.64981794e-01 8.32370594e-02 -2.42698282e-01 9.66520786e-01 8.32275748e-02 -2.36766636e-01 9.67983723e-01 8.32250193e-02 -2.30820745e-01 9.69426513e-01 8.32435563e-02 -2.24871591e-01 9.70803022e-01 8.32615420e-02 -2.18910441e-01 9.72186089e-01 8.32427293e-02 -2.12937266e-01 9.73492563e-01 8.32233280e-02 -2.06960633e-01 9.74791050e-01 8.32616016e-02 -2.00975195e-01 9.76059318e-01 8.32786411e-02 -1.94981068e-01 9.77274716e-01 8.32794085e-02 -1.88983858e-01 9.78439987e-01 8.32553878e-02 -1.82976156e-01 9.79561210e-01 8.32351595e-02 -1.76963761e-01 9.80701506e-01 8.32162350e-02 -1.70942307e-01 9.81747031e-01 8.32230821e-02 -1.64916649e-01 9.82802212e-01 8.32496807e-02 -1.58881366e-01 9.83785450e-01 8.31993893e-02 -1.52844086e-01 9.84750688e-01 8.32239389e-02 -1.46795556e-01 9.85640526e-01 8.32277983e-02 -1.40745431e-01 9.86542046e-01 8.32093358e-02 -1.34691730e-01 9.87360895e-01 8.31730813e-02 -1.28629178e-01 9.88184810e-01 8.31684843e-02 -1.22563086e-01 9.88973439e-01 8.32052380e-02 -1.16493203e-01 9.89701509e-01 8.32417160e-02 -1.10419631e-01 9.90415752e-01 8.32239687e-02 -1.04341052e-01 9.91014838e-01 8.32281858e-02 -9.82577503e-02 9.91655111e-01 8.32208917e-02 -9.21694040e-02 9.92228746e-01 8.32043961e-02 -8.60796943e-02 9.92799461e-01 8.32167044e-02 -7.99863115e-02 9.93333101e-01 8.32370743e-02 -7.38902763e-02 9.93772745e-01 8.32246542e-02 -6.77908063e-02 9.94238853e-01 8.32207724e-02 -6.16898946e-02 9.94587004e-01 8.32576305e-02 -5.55859096e-02 9.94982421e-01 8.32470804e-02 -4.94799279e-02 9.95296657e-01 8.32681656e-02 -4.33716662e-02 9.95546520e-01 8.32741261e-02 -3.72623019e-02 9.95804250e-01 8.32451805e-02 -3.11510768e-02 9.96032178e-01 8.32177773e-02 -2.50390619e-02 9.96203542e-01 8.32462162e-02 -1.89259276e-02 9.96342838e-01 8.32451954e-02 -1.28123006e-02 9.96442318e-01 8.32473561e-02 -6.69798441e-03 9.96511221e-01 8.32471997e-02 -5.83536923e-04 9.96516526e-01 8.32445100e-02 5.53088170e-03 9.96513367e-01 8.32548365e-02 1.16454223e-02 9.96447921e-01 8.32310989e-02 1.77592002e-02 9.96349096e-01 8.32251608e-02 2.38724276e-02 9.96255875e-01 8.32126737e-02 2.99847089e-02 9.96049047e-01 8.32271725e-02 3.60956565e-02 9.95860100e-01 8.32769349e-02 4.22054380e-02 9.95617270e-01 8.33009481e-02 4.83130515e-02 9.95315969e-01 8.33239183e-02 5.44190481e-02 9.95043516e-01 8.33344012e-02 6.05248101e-02 9.94661808e-01 8.32800418e-02 6.66266456e-02 9.94305789e-01 8.32641646e-02 7.27257729e-02 9.93841231e-01 8.32881182e-02 7.88222477e-02 9.93367612e-01 8.33190903e-02 8.49166214e-02 9.92871225e-01 8.32767785e-02 9.10068974e-02 9.92372632e-01 8.32791105e-02 9.70947146e-02 9.91790593e-01 8.33092481e-02 1.03177816e-01 9.91158664e-01 8.33173692e-02 1.09257273e-01 9.90507245e-01 8.33401531e-02 1.15332551e-01 9.89797771e-01 8.33745375e-02 1.21401712e-01 9.89088595e-01 8.34049284e-02 1.27470151e-01 9.88316357e-01 8.34265947e-02 1.33529291e-01 9.87502515e-01 8.34641904e-02 1.39585316e-01 9.86665785e-01 8.34755525e-02 1.45637661e-01 9.85799611e-01 8.34364146e-02 1.51686206e-01 9.84909415e-01 8.33776966e-02 1.57728553e-01 9.83945310e-01 8.33073333e-02 1.63761586e-01 9.82971132e-01 8.32940787e-02 1.69788554e-01 9.81923461e-01 8.32731202e-02 1.75810292e-01 9.80878055e-01 8.32786709e-02 1.81826487e-01 9.79751825e-01 8.32859874e-02 1.87837005e-01 9.78655636e-01 8.32867771e-02 1.93837985e-01 9.77510035e-01 8.32686275e-02 1.99831381e-01 9.76300120e-01 8.32670853e-02 2.05818400e-01 9.75024343e-01 8.32780972e-02 2.11799055e-01 9.73743796e-01 8.32863003e-02 2.17768744e-01 9.72428441e-01 8.32644254e-02 2.23731041e-01 9.71072674e-01 8.32308158e-02 2.29687035e-01 9.69683230e-01 8.31756145e-02 2.35631973e-01 9.68277037e-01 8.32112730e-02 2.41570577e-01 9.66820717e-01 8.31638202e-02 2.47498184e-01 9.65300977e-01 8.31587911e-02 2.53414243e-01 9.63761508e-01 8.31423849e-02 2.59331912e-01 9.62209761e-01 8.30571055e-02 2.65232384e-01 9.60580468e-01 8.30493197e-02 2.71111697e-01 9.58947897e-01 8.30591992e-02 2.76999742e-01 9.57278311e-01 8.29922035e-02 2.82873362e-01 9.55575883e-01 8.29369202e-02 2.88720340e-01 9.53796327e-01 8.29361528e-02 2.94566512e-01 9.52015460e-01 8.29744488e-02 3.00403357e-01 9.50168371e-01 8.29589590e-02 3.06234300e-01 9.48346019e-01 8.29649642e-02 3.12040061e-01 9.46423709e-01 8.29142332e-02 3.17853123e-01 9.44482505e-01 8.29125717e-02 3.23634416e-01 9.42530096e-01 8.29176903e-02 3.29412341e-01 9.40519273e-01 8.29317421e-02 3.35186690e-01 9.38473046e-01 8.29032809e-02 3.40929717e-01 9.36435521e-01 8.28644708e-02 3.46673310e-01 9.34283435e-01 8.28680471e-02 3.52402657e-01 9.32147920e-01 8.28647837e-02 3.58120561e-01 9.29973602e-01 8.28213841e-02 3.63804519e-01 9.27769065e-01 8.27886090e-02 3.69498372e-01 9.25510049e-01 8.28063488e-02 3.75163883e-01 9.23243284e-01 8.28053281e-02 3.80821019e-01 9.20888007e-01 8.28269124e-02 3.86472732e-01 9.18542325e-01 8.28109533e-02 3.92097414e-01 9.16173816e-01 8.27808976e-02 3.97717088e-01 9.13757920e-01 8.27492028e-02 4.03312981e-01 9.11308587e-01 8.27546641e-02 4.08897728e-01 9.08795953e-01 8.27268511e-02 4.14464682e-01 9.06288028e-01 8.27284679e-02 4.20020670e-01 9.03704524e-01 8.27272534e-02 4.25556272e-01 9.01126385e-01 8.27103555e-02 4.31075543e-01 8.98507118e-01 8.27038586e-02 4.36596811e-01 8.95835578e-01 8.26837122e-02 4.42076117e-01 8.93160880e-01 8.26588124e-02 4.47551072e-01 8.90419185e-01 8.26416910e-02 4.53021646e-01 8.87647808e-01 8.26587901e-02 4.58443463e-01 8.84879649e-01 8.26374069e-02 4.63862926e-01 8.82003903e-01 8.26438591e-02 4.69265282e-01 8.79170358e-01 8.26172829e-02 4.74671900e-01 8.76293957e-01 8.26181471e-02 4.80034530e-01 8.73374283e-01 8.26008543e-02 4.85387772e-01 8.70379567e-01 8.25755447e-02 4.90715921e-01 8.67388308e-01 8.25905576e-02 4.96012509e-01 8.64380062e-01 8.25766474e-02 5.01319706e-01 8.61307144e-01 8.25723261e-02 5.06589115e-01 8.58216405e-01 8.25621113e-02 5.11836886e-01 8.55090857e-01 8.25562924e-02 5.17081916e-01 8.51947665e-01 8.25577006e-02 5.22294998e-01 8.48744869e-01 8.25525299e-02 5.27498364e-01 8.45514059e-01 8.25472251e-02 5.32691419e-01 8.42310131e-01 8.25604275e-02 5.37834525e-01 8.39000106e-01 8.25526491e-02 5.42969823e-01 8.35691035e-01 8.25470611e-02 5.48083246e-01 8.32355261e-01 8.25182274e-02 5.53185880e-01 8.28955114e-01 8.25269297e-02 5.58263540e-01 8.25546026e-01 8.25339854e-02 5.63330531e-01 8.22122931e-01 8.25320631e-02 5.68359792e-01 8.18643034e-01 8.25350434e-02 5.73363423e-01 8.15106392e-01 8.25509727e-02 5.78352094e-01 8.11603308e-01 8.25604722e-02 5.83325922e-01 8.08030903e-01 8.25512335e-02 5.88282585e-01 8.04411471e-01 8.25426728e-02 5.93193054e-01 8.00809681e-01 8.25570896e-02 5.98099768e-01 7.97159314e-01 8.25556815e-02 6.02993309e-01 7.93454111e-01 8.25441480e-02 6.07844412e-01 7.89776921e-01 8.25506374e-02 6.12672627e-01 7.86031246e-01 8.25707763e-02 6.17502689e-01 7.82240450e-01 8.25844184e-02 6.22269094e-01 7.78431773e-01 8.25797096e-02 6.27030075e-01 7.74599433e-01 8.25852528e-02 6.31774127e-01 7.70742357e-01 8.25810507e-02 6.36491477e-01 7.66858578e-01 8.25697035e-02 6.41203821e-01 7.62931824e-01 8.25682431e-02 6.45858645e-01 7.58985519e-01 8.25677142e-02 6.50494277e-01 7.54993439e-01 8.25740993e-02 6.55114949e-01 7.50996828e-01 8.25804844e-02 6.59725070e-01 7.46964395e-01 8.25816169e-02 6.64305627e-01 7.42909908e-01 8.25720131e-02 6.68850482e-01 7.38827586e-01 8.25479105e-02 6.73352242e-01 7.34697998e-01 8.25467408e-02 6.77856565e-01 7.30557859e-01 8.25388134e-02 6.82343125e-01 7.26383746e-01 8.25668648e-02 6.86765730e-01 7.22165525e-01 8.25619474e-02 6.91208839e-01 7.17966616e-01 8.25590864e-02 6.95592999e-01 7.13710845e-01 8.25519711e-02 6.99968278e-01 7.09399641e-01 8.25625435e-02 7.04281747e-01 7.05108821e-01 8.25716034e-02 7.08604157e-01 7.00754642e-01 8.25603604e-02 7.12886333e-01 6.96391881e-01 8.25722814e-02 7.17138469e-01 6.92009687e-01 8.25828016e-02 7.21396863e-01 6.87595963e-01 8.25668275e-02 7.25566328e-01 6.83185637e-01 8.25457945e-02 7.29766905e-01 6.78712368e-01 8.25538114e-02 7.33916104e-01 6.74213409e-01 8.25302005e-02 7.38038361e-01 6.69710457e-01 8.25177208e-02 7.42112279e-01 6.65177226e-01 8.25135857e-02 7.46214747e-01 6.60587966e-01 8.25181156e-02 7.50231206e-01 6.55986249e-01 8.25111344e-02 7.54250169e-01 6.51372552e-01 8.25203061e-02 7.58231282e-01 6.46724999e-01 8.25178623e-02 7.62184322e-01 6.42084837e-01 8.25016126e-02 7.66107202e-01 6.37377381e-01 8.25082809e-02 7.70026803e-01 6.32689416e-01 8.25155601e-02 7.73877263e-01 6.27951503e-01 8.24952573e-02 7.77703166e-01 6.23190880e-01 8.24808553e-02 7.81504869e-01 6.18378758e-01 8.24708268e-02 7.85300493e-01 6.13595545e-01 8.24861377e-02 7.89042294e-01 6.08759046e-01 8.24907124e-02 7.92770028e-01 6.03895307e-01 8.25105906e-02 7.96445131e-01 5.99029660e-01 8.25050995e-02 8.00124049e-01 5.94142556e-01 8.24793503e-02 8.03740263e-01 5.89200735e-01 8.24847370e-02 8.07346344e-01 5.84280610e-01 8.24474692e-02 8.10941935e-01 5.79310715e-01 8.24515149e-02 8.14446747e-01 5.74324667e-01 8.24697092e-02 8.17993462e-01 5.69313288e-01 8.24806243e-02 8.21425438e-01 5.64267814e-01 8.25023279e-02 8.24891090e-01 5.59234917e-01 8.24920982e-02 8.28311086e-01 5.54150224e-01 8.25019330e-02 8.31704021e-01 5.49058020e-01 8.24767426e-02 8.35039735e-01 5.43942869e-01 8.24749395e-02 8.38371933e-01 5.38817585e-01 8.24776664e-02 8.41674268e-01 5.33673108e-01 8.25023428e-02 8.44931901e-01 5.28482378e-01 8.25021118e-02 8.48168314e-01 5.23291230e-01 8.25040862e-02 8.51337552e-01 5.18089473e-01 8.25052410e-02 8.54502141e-01 5.12859344e-01 8.25001225e-02 8.57660055e-01 5.07592499e-01 8.24872553e-02 8.60749722e-01 5.02322495e-01 8.24842229e-02 8.63787889e-01 4.97044832e-01 8.24750066e-02 8.66836846e-01 4.91730720e-01 8.24722722e-02 8.69833171e-01 4.86386329e-01 8.24700966e-02 8.72789383e-01 4.81036454e-01 8.24686959e-02 8.75742197e-01 4.75675315e-01 8.24713930e-02 8.78613651e-01 4.70310986e-01 8.24826285e-02 8.81507814e-01 4.64897782e-01 8.24765787e-02 8.84350777e-01 4.59489197e-01 8.24931413e-02 8.87120664e-01 4.54039603e-01 8.25117007e-02 8.89925718e-01 4.48596001e-01 8.25326592e-02 8.92675817e-01 4.43125546e-01 8.25184360e-02 8.95369291e-01 4.37645644e-01 8.25165063e-02 8.98045063e-01 4.32128012e-01 8.25214311e-02 9.00655329e-01 4.26627338e-01 8.25201720e-02 9.03248906e-01 4.21084195e-01 8.25282708e-02 9.05831158e-01 4.15532202e-01 8.25326890e-02 9.08347070e-01 4.09973979e-01 8.25422108e-02 9.10862625e-01 4.04381126e-01 8.25588703e-02 9.13346887e-01 3.98784161e-01 8.25714022e-02 9.15777922e-01 3.93182755e-01 8.25902447e-02 9.18142915e-01 3.87543738e-01 8.26062933e-02 9.20497000e-01 3.81912112e-01 8.26235712e-02 9.22835886e-01 3.76260042e-01 8.26320276e-02 9.25116599e-01 3.70576322e-01 8.26293230e-02 9.27382290e-01 3.64900053e-01 8.26249346e-02 9.29590106e-01 3.59196842e-01 8.26302245e-02 9.31781054e-01 3.53489012e-01 8.26140046e-02 9.33932483e-01 3.47763598e-01 8.26279297e-02 9.36013162e-01 3.42029780e-01 8.26500356e-02 9.38156426e-01 3.36281717e-01 8.26476440e-02 9.40144241e-01 3.30523878e-01 8.26597959e-02 9.42163050e-01 3.24748188e-01 8.26655924e-02 9.44168150e-01 3.18961859e-01 8.26574638e-02 9.46094036e-01 3.13154846e-01 8.26758668e-02 9.47985530e-01 3.07350308e-01 8.26781467e-02 9.49856818e-01 3.01520050e-01 8.26782063e-02 9.51710939e-01 2.95684129e-01 8.26740116e-02 9.53501463e-01 2.89842129e-01 8.26866850e-02 9.55227077e-01 2.83991516e-01 8.26870427e-02 9.56982851e-01 2.78120369e-01 8.26829225e-02 9.58635807e-01 2.72248596e-01 8.26818794e-02 9.60319221e-01 2.66360760e-01 8.26806650e-02 9.61947739e-01 2.60461777e-01 8.26776847e-02 9.63500142e-01 2.54556686e-01 8.26725736e-02 9.65034068e-01 2.48634681e-01 8.26747939e-02 9.66574073e-01 2.42704451e-01 8.26647729e-02 9.68034983e-01 2.36772239e-01 8.26817602e-02 9.69479203e-01 2.30833858e-01 8.26801583e-02 9.70855653e-01 2.24875987e-01 8.26858953e-02 9.72239614e-01 2.18914911e-01 8.26935247e-02 9.73544121e-01 2.12948814e-01 8.26880783e-02 9.74847078e-01 2.06967726e-01 8.26896727e-02 9.76116419e-01 2.00978220e-01 8.26827511e-02 9.77331460e-01 1.94986418e-01 8.26934576e-02 9.78495359e-01 1.88990146e-01 8.26798007e-02 9.79615867e-01 1.82981551e-01 8.26669484e-02 9.80753481e-01 1.76969469e-01 8.26720521e-02 9.81800675e-01 1.70948267e-01 8.26613531e-02 9.82860625e-01 1.64920345e-01 8.26651007e-02 9.83839452e-01 1.58885017e-01 8.26592371e-02 9.84809756e-01 1.52848050e-01 8.26520324e-02 9.85694945e-01 1.46802112e-01 8.26534182e-02 9.86595273e-01 1.40753537e-01 8.26702341e-02 9.87412572e-01 1.34693548e-01 8.26701149e-02 9.88233328e-01 1.28631666e-01 8.26777369e-02 9.89026070e-01 1.22568697e-01 8.26678127e-02 9.89757955e-01 1.16496406e-01 8.26619640e-02 9.90470946e-01 1.10419489e-01 8.26648772e-02 9.91067350e-01 1.04341127e-01 8.26575905e-02 9.91712093e-01 9.82577577e-02 8.26582164e-02 9.92283344e-01 9.21704620e-02 8.26563537e-02 9.92862701e-01 8.60821381e-02 8.26363564e-02 9.93393838e-01 7.99872503e-02 8.26513618e-02 9.93832529e-01 7.38903731e-02 8.26681107e-02 9.94299710e-01 6.77917153e-02 8.26565698e-02 9.94643927e-01 6.16892315e-02 8.26857835e-02 9.95033622e-01 5.55846579e-02 8.26843679e-02 9.95357335e-01 4.94787320e-02 8.26603994e-02 9.95608151e-01 4.33703400e-02 8.26498121e-02 9.95860577e-01 3.72606032e-02 8.26687440e-02 9.96087074e-01 3.11493892e-02 8.26737583e-02 9.96263623e-01 2.50367764e-02 8.26670304e-02 9.96398151e-01 1.89233627e-02 8.26582015e-02 9.96501863e-01 1.28093893e-02 8.26870576e-02 9.96570528e-01 6.69464050e-03 8.26644450e-02 9.96575117e-01 5.79830434e-04 8.26713368e-02 9.96569872e-01 -5.53502329e-03 8.26718509e-02 9.96506989e-01 -1.16495807e-02 8.26837346e-02 9.96399939e-01 -1.77637786e-02 8.26904178e-02 9.96309340e-01 -2.38770917e-02 8.27085897e-02 9.96100545e-01 -2.99895909e-02 8.27178508e-02 9.95910764e-01 -3.61012183e-02 8.27137381e-02 9.95667279e-01 -4.22111899e-02 8.27236250e-02 9.95371163e-01 -4.83204685e-02 8.27210993e-02 9.95105684e-01 -5.44267967e-02 8.27097371e-02 9.94710982e-01 -6.05319627e-02 8.27107653e-02 9.94362950e-01 -6.66337684e-02 8.27201679e-02 9.93896663e-01 -7.27325752e-02 8.27355087e-02 9.93424237e-01 -7.88301900e-02 8.27241242e-02 9.92926002e-01 -8.49258080e-02 8.27154070e-02 9.92428303e-01 -9.10163894e-02 8.27143863e-02 9.91860986e-01 -9.71040130e-02 8.26988667e-02 9.91219044e-01 -1.03187494e-01 8.27027261e-02 9.90557313e-01 -1.09268062e-01 8.26965868e-02 9.89848256e-01 -1.15343034e-01 8.26936439e-02 9.89118874e-01 -1.21417128e-01 8.26958790e-02 9.88373935e-01 -1.27484024e-01 8.26775655e-02 9.87578571e-01 -1.33543015e-01 8.26635510e-02 9.86765325e-01 -1.39604047e-01 8.26541707e-02 9.85874593e-01 -1.45656183e-01 8.26458335e-02 9.84966636e-01 -1.51698127e-01 8.26326758e-02 9.83999968e-01 -1.57742545e-01 8.26163888e-02 9.83025014e-01 -1.63776055e-01 8.26112777e-02 9.81992424e-01 -1.69806451e-01 8.25887844e-02 9.80953455e-01 -1.75828218e-01 8.25820714e-02 9.79819477e-01 -1.81843624e-01 8.25816691e-02 9.78747129e-01 -1.87854558e-01 8.25750232e-02 9.77589250e-01 -1.93854317e-01 8.25677365e-02 9.76373196e-01 -1.99849799e-01 8.25720355e-02 9.75112081e-01 -2.05836907e-01 8.25704485e-02 9.73794341e-01 -2.11816713e-01 8.25957656e-02 9.72496569e-01 -2.17788383e-01 8.26139525e-02 9.71120358e-01 -2.23751590e-01 8.26135352e-02 9.69757080e-01 -2.29709312e-01 8.25992674e-02 9.68347132e-01 -2.35645920e-01 8.25879574e-02 9.66886044e-01 -2.41591021e-01 8.25897753e-02 9.65373874e-01 -2.47510225e-01 8.25923160e-02 9.63809252e-01 -2.53435642e-01 8.25947300e-02 9.62268412e-01 -2.59346008e-01 8.26021209e-02 9.60641265e-01 -2.65242785e-01 8.25848132e-02 9.58979189e-01 -2.71135837e-01 8.25660229e-02 9.57331061e-01 -2.77008623e-01 8.25840458e-02 9.55624044e-01 -2.82882482e-01 8.25853720e-02 9.53834236e-01 -2.88740844e-01 8.25703740e-02 9.52060044e-01 -2.94581652e-01 8.25754106e-02 9.50200081e-01 -3.00418943e-01 8.25884491e-02 9.48387682e-01 -3.06248695e-01 8.26103985e-02 9.46458817e-01 -3.12054694e-01 8.26211125e-02 9.44515049e-01 -3.17861140e-01 8.26416612e-02 9.42562938e-01 -3.23651105e-01 8.26428235e-02 9.40548420e-01 -3.29429448e-01 8.26326162e-02 9.38503146e-01 -3.35197181e-01 8.26111287e-02 9.36465442e-01 -3.40936989e-01 8.26137662e-02 9.34313595e-01 -3.46688360e-01 8.25916827e-02 9.32177484e-01 -3.52414340e-01 8.25897232e-02 9.30001616e-01 -3.58131349e-01 8.25820342e-02 9.27795470e-01 -3.63821775e-01 8.25725123e-02 9.25538123e-01 -3.69511276e-01 8.25700685e-02 9.23274517e-01 -3.75177592e-01 8.25702995e-02 9.20920730e-01 -3.80832940e-01 8.25634673e-02 9.18570936e-01 -3.86488855e-01 8.25500861e-02 9.16215360e-01 -3.92110109e-01 8.25464427e-02 9.13790584e-01 -3.97727519e-01 8.25382844e-02 9.11343992e-01 -4.03328717e-01 8.25243220e-02 9.08831537e-01 -4.08917904e-01 8.25028121e-02 9.06323731e-01 -4.14477974e-01 8.25080723e-02 9.03737485e-01 -4.20040905e-01 8.25150460e-02 9.01176095e-01 -4.25572038e-01 8.25199410e-02 8.98538411e-01 -4.31091100e-01 8.25052932e-02 8.95865560e-01 -4.36610401e-01 8.24957117e-02 8.93185019e-01 -4.42089826e-01 8.25043842e-02 8.90442669e-01 -4.47564691e-01 8.24889392e-02 8.87665868e-01 -4.53030348e-01 8.24829116e-02 8.84897947e-01 -4.58460301e-01 8.24866667e-02 8.82019341e-01 -4.63869512e-01 8.24898854e-02 8.79187226e-01 -4.69287395e-01 8.24749321e-02 8.76313269e-01 -4.74683493e-01 8.24744031e-02 8.73389661e-01 -4.80044872e-01 8.24788511e-02 8.70393872e-01 -4.85394001e-01 8.24771002e-02 8.67401063e-01 -4.90720809e-01 8.24864879e-02 8.64388883e-01 -4.96018291e-01 8.24890509e-02 8.61316860e-01 -5.01328766e-01 8.24827850e-02 8.58229518e-01 -5.06592929e-01 8.24787021e-02 8.55099916e-01 -5.11861324e-01 8.24899003e-02 8.51945937e-01 -5.17097950e-01 8.24910104e-02 8.48751903e-01 -5.22298872e-01 8.24885592e-02 8.45521510e-01 -5.27502060e-01 8.24858621e-02 8.42319071e-01 -5.32696605e-01 8.24749246e-02 8.39008331e-01 -5.37835300e-01 8.24751630e-02 8.35693598e-01 -5.42974293e-01 8.24778751e-02 8.32357466e-01 -5.48085093e-01 8.24898034e-02 8.28955531e-01 -5.53191006e-01 8.24988782e-02 8.25546622e-01 -5.58265746e-01 8.25136974e-02 8.22119832e-01 -5.63333809e-01 8.25155973e-02 8.18638265e-01 -5.68360686e-01 8.25099200e-02 8.15109551e-01 -5.73364556e-01 8.25132206e-02 8.11595917e-01 -5.78351974e-01 8.25204775e-02 8.08032632e-01 -5.83328724e-01 8.25130716e-02 8.04411471e-01 -5.88293433e-01 8.25020298e-02 8.00817847e-01 -5.93197346e-01 8.25095251e-02 7.97166824e-01 -5.98100364e-01 8.25064480e-02 7.93457747e-01 -6.02997541e-01 8.25048089e-02 7.89777517e-01 -6.07856214e-01 8.25157017e-02 7.86028266e-01 -6.12670600e-01 8.25230330e-02 7.82239974e-01 -6.17503047e-01 8.25548247e-02 7.78440118e-01 -6.22268021e-01 8.25640410e-02 7.74598002e-01 -6.27029359e-01 8.25750157e-02 7.70732760e-01 -6.31775975e-01 8.25572610e-02 7.66865134e-01 -6.36492610e-01 8.25636312e-02 7.62928426e-01 -6.41209602e-01 8.25578049e-02 7.58986652e-01 -6.45858049e-01 8.25648755e-02 7.54993379e-01 -6.50494635e-01 8.25635865e-02 7.50990868e-01 -6.55114174e-01 8.25652853e-02 7.46961892e-01 -6.59724355e-01 8.25693682e-02 7.42912531e-01 -6.64308548e-01 8.25509131e-02 7.38820195e-01 -6.68848395e-01 8.25495124e-02 7.34690249e-01 -6.73353612e-01 8.25490430e-02 7.30549872e-01 -6.77854240e-01 8.25493336e-02 7.26386428e-01 -6.82344556e-01 8.25472921e-02 7.22163022e-01 -6.86761022e-01 8.25643018e-02 7.17967570e-01 -6.91203296e-01 8.25689808e-02 7.13710368e-01 -6.95590675e-01 8.25999007e-02 7.09398448e-01 -6.99959457e-01 8.25931057e-02 7.05108106e-01 -7.04276204e-01 8.25912505e-02 7.00751543e-01 -7.08606362e-01 8.26314092e-02 6.96391761e-01 -7.12883651e-01 8.26380551e-02 6.92009807e-01 -7.17140198e-01 8.26625526e-02 6.87595010e-01 -7.21392334e-01 8.26555043e-02 6.83182001e-01 -7.25564718e-01 8.26446787e-02 6.78709805e-01 -7.29772210e-01 8.26434568e-02 6.74210310e-01 -7.33923197e-01 8.26396942e-02 6.69708312e-01 -7.38044500e-01 8.26216191e-02 6.65172100e-01 -7.42108166e-01 8.26701671e-02 6.60584688e-01 -7.46209621e-01 8.26667845e-02 6.55984998e-01 -7.50229716e-01 8.26494917e-02 6.51370049e-01 -7.54244924e-01 8.26711133e-02 6.46723092e-01 -7.58239508e-01 8.26530010e-02 6.42085493e-01 -7.62168288e-01 8.26522782e-02 6.37377799e-01 -7.66096652e-01 8.26240256e-02 6.32693648e-01 -7.70028949e-01 8.25893357e-02 6.27953112e-01 -7.73870289e-01 8.25812593e-02 6.23195231e-01 -7.77715027e-01 8.25805292e-02 6.18380249e-01 -7.81506658e-01 8.25750455e-02 6.13597810e-01 -7.85297215e-01 8.25682282e-02 6.08761966e-01 -7.89045870e-01 8.25642496e-02 6.03898048e-01 -7.92781770e-01 8.25875327e-02 5.99031746e-01 -7.96452105e-01 8.25677589e-02 5.94137430e-01 -8.00107896e-01 8.25977921e-02 5.89199364e-01 -8.03746104e-01 8.25856775e-02 5.84276736e-01 -8.07354569e-01 8.25931877e-02 5.79306364e-01 -8.10935080e-01 8.25877637e-02 5.74324608e-01 -8.14452231e-01 8.25981870e-02 5.69314003e-01 -8.17988455e-01 8.25866982e-02 5.64269781e-01 -8.21425617e-01 8.25717300e-02 5.59232533e-01 -8.24893355e-01 8.25641677e-02 5.54147005e-01 -8.28312337e-01 8.25429708e-02 5.49050808e-01 -8.31701100e-01 8.25220719e-02 5.43935657e-01 -8.35032701e-01 8.25093165e-02 5.38811922e-01 -8.38360190e-01 8.25113580e-02 5.33668280e-01 -8.41669440e-01 8.25197846e-02 5.28477609e-01 -8.44919741e-01 8.25155303e-02 5.23288131e-01 -8.48158419e-01 8.25267434e-02 5.18084764e-01 -8.51329803e-01 8.25089216e-02 5.12852609e-01 -8.54491293e-01 8.25215429e-02 5.07589102e-01 -8.57649863e-01 8.25018212e-02 5.02317488e-01 -8.60738635e-01 8.24911967e-02 4.97037172e-01 -8.63792002e-01 8.25042129e-02 4.91723984e-01 -8.66821945e-01 8.25081021e-02 4.86377299e-01 -8.69820774e-01 8.24999437e-02 4.81031179e-01 -8.72794807e-01 8.24785158e-02 4.75671589e-01 -8.75735819e-01 8.24718401e-02 4.70306873e-01 -8.78607631e-01 8.24765265e-02 4.64895904e-01 -8.81502509e-01 8.24684948e-02 4.59486008e-01 -8.84347022e-01 8.24753940e-02 4.54033315e-01 -8.87120485e-01 8.24553818e-02 4.48595047e-01 -8.89926672e-01 8.24750960e-02 4.43127811e-01 -8.92674148e-01 8.24922025e-02 4.37642425e-01 -8.95367503e-01 8.25006440e-02 4.32124764e-01 -8.98041785e-01 8.25120658e-02 4.26625758e-01 -9.00648355e-01 8.25260580e-02 4.21092480e-01 -9.03248429e-01 8.25058073e-02 4.15532261e-01 -9.05830622e-01 8.24986473e-02 4.09974754e-01 -9.08354878e-01 8.24845955e-02 4.04383332e-01 -9.10869837e-01 8.24738741e-02 3.98786515e-01 -9.13353026e-01 8.24948251e-02 3.93183202e-01 -9.15783405e-01 8.25188085e-02 3.87545496e-01 -9.18148637e-01 8.25193301e-02 3.81920993e-01 -9.20500219e-01 8.25277641e-02 3.76262754e-01 -9.22848761e-01 8.25378969e-02 3.70576620e-01 -9.25120890e-01 8.25376213e-02 3.64904881e-01 -9.27388191e-01 8.25523511e-02 3.59195739e-01 -9.29595411e-01 8.25562701e-02 3.53490621e-01 -9.31784153e-01 8.25547650e-02 3.47761542e-01 -9.33938205e-01 8.25539157e-02 3.42037112e-01 -9.36016619e-01 8.25633630e-02 3.36281747e-01 -9.38163996e-01 8.25512186e-02 3.30523700e-01 -9.40152586e-01 8.25412646e-02 3.24745417e-01 -9.42165911e-01 8.25636163e-02 3.18962306e-01 -9.44176555e-01 8.25678930e-02 3.13148886e-01 -9.46104586e-01 8.25780109e-02 3.07346165e-01 -9.47988153e-01 8.26046690e-02 3.01526546e-01 -9.49861348e-01 8.26016515e-02 2.95688212e-01 -9.51715469e-01 8.26081112e-02 2.89847314e-01 -9.53503966e-01 8.26308131e-02 2.83987045e-01 -9.55227196e-01 8.26719105e-02 2.78113484e-01 -9.56982553e-01 8.26817825e-02 2.72244930e-01 -9.58633661e-01 8.27025697e-02 2.66359925e-01 -9.60315049e-01 8.27140138e-02 2.60462165e-01 -9.61939871e-01 8.27179775e-02 2.54548758e-01 -9.63494182e-01 8.27382058e-02 2.48635828e-01 -9.65032041e-01 8.27570930e-02 2.42705613e-01 -9.66557384e-01 8.27763304e-02 2.36772805e-01 -9.68020618e-01 8.27737525e-02 2.30827197e-01 -9.69460845e-01 8.27849060e-02 2.24878043e-01 -9.70845938e-01 8.28021839e-02 2.18916103e-01 -9.72221613e-01 8.27893540e-02 2.12941423e-01 -9.73529577e-01 8.28022733e-02 2.06964999e-01 -9.74819005e-01 8.28077570e-02 2.00975820e-01 -9.76091504e-01 8.28035548e-02 1.94982812e-01 -9.77302730e-01 8.28527212e-02 1.88986599e-01 -9.78464246e-01 8.28216448e-02 1.82977512e-01 -9.79592323e-01 8.27890262e-02 1.76966697e-01 -9.80727434e-01 8.27633217e-02 1.70945987e-01 -9.81776476e-01 8.27848688e-02 1.64917678e-01 -9.82826889e-01 8.27854574e-02 1.58882350e-01 -9.83806252e-01 8.27692971e-02 1.52845919e-01 -9.84774888e-01 8.27713609e-02 1.46799743e-01 -9.85670805e-01 8.27596635e-02 1.40747890e-01 -9.86569643e-01 8.27497765e-02 1.34693623e-01 -9.87390101e-01 8.27521458e-02 1.28629535e-01 -9.88210618e-01 8.27300251e-02 1.22563772e-01 -9.89004135e-01 8.27362314e-02 1.16492055e-01 -9.89733756e-01 8.27480629e-02 1.10420249e-01 -9.90447581e-01 8.27405974e-02 1.04340099e-01 -9.91045177e-01 8.27477425e-02 9.82572287e-02 -9.91684496e-01 8.27412754e-02 9.21692550e-02 -9.92256284e-01 8.27639848e-02 8.60796943e-02 -9.92825925e-01 8.27608928e-02 7.99859315e-02 -9.93366063e-01 8.27385485e-02 7.38895983e-02 -9.93808329e-01 8.27187374e-02 6.77903518e-02 -9.94271636e-01 8.27347636e-02 6.16889857e-02 -9.94622469e-01 8.27362537e-02 5.55841029e-02 -9.95016456e-01 8.27446729e-02 4.94785085e-02 -9.95328605e-01 8.27834010e-02 4.33700979e-02 -9.95578349e-01 8.27901214e-02 3.72607484e-02 -9.95831549e-01 8.28091353e-02 3.11491974e-02 -9.96056139e-01 8.28324482e-02 2.50370819e-02 -9.96229887e-01 8.28279704e-02 1.89240444e-02 -9.96369362e-01 8.28464553e-02 1.28100878e-02 -9.96468186e-01 8.28441083e-02 6.69602398e-03 -9.96535301e-01 8.29121694e-02 5.81517874e-04 -9.96538222e-01 8.29282627e-02 -5.53341163e-03 -9.96538699e-01 8.28898624e-02 -1.16475010e-02 -9.96465385e-01 8.29342529e-02 -1.77614763e-02 -9.96371627e-01 8.29222053e-02 -2.38750074e-02 -9.96273994e-01 8.29445347e-02 -2.99869198e-02 -9.96068716e-01 8.29734057e-02 -3.60983089e-02 -9.95883644e-01 8.29357132e-02 -4.22086455e-02 -9.95642066e-01 8.29241425e-02 -4.83167209e-02 -9.95342791e-01 8.29417109e-02 -5.44228554e-02 -9.95070755e-01 8.29657912e-02 -6.05279580e-02 -9.94685590e-01 8.29720199e-02 -6.66298941e-02 -9.94326234e-01 8.29520226e-02 -7.27292150e-02 -9.93863523e-01 8.29683095e-02 -7.88254663e-02 -9.93390620e-01 8.29856247e-02 -8.49204585e-02 -9.92888153e-01 8.30043256e-02 -9.10107195e-02 -9.92388725e-01 8.30191746e-02 -9.70978513e-02 -9.91805434e-01 8.30401629e-02 -1.03181846e-01 -9.91176188e-01 8.30458850e-02 -1.09261811e-01 -9.90526319e-01 8.30693319e-02 -1.15336202e-01 -9.89816844e-01 8.30907300e-02 -1.21407002e-01 -9.89108682e-01 8.30594301e-02 -1.27475426e-01 -9.88340318e-01 8.30546841e-02 -1.33534446e-01 -9.87527668e-01 8.31058025e-02 -1.39590502e-01 -9.86694813e-01 8.31134692e-02 -1.45642281e-01 -9.85823929e-01 8.30812529e-02 -1.51690781e-01 -9.84929323e-01 8.30378905e-02 -1.57732874e-01 -9.83961284e-01 8.30390304e-02 -1.63764760e-01 -9.82985079e-01 8.30505416e-02 -1.69793233e-01 -9.81939554e-01 8.30224752e-02 -1.75816193e-01 -9.80885804e-01 8.30153078e-02 -1.81831554e-01 -9.79768455e-01 8.30159187e-02 -1.87842354e-01 -9.78676617e-01 8.30155313e-02 -1.93840429e-01 -9.77519810e-01 8.30072612e-02 -1.99836254e-01 -9.76319790e-01 8.29734504e-02 -2.05820262e-01 -9.75049615e-01 8.29600170e-02 -2.11807206e-01 -9.73760128e-01 8.28923807e-02 -2.17774078e-01 -9.72451150e-01 8.29118565e-02 -2.23735809e-01 -9.71081853e-01 8.28699246e-02 -2.29690373e-01 -9.69705105e-01 8.28610435e-02 -2.35638842e-01 -9.68298554e-01 8.28362778e-02 -2.41579115e-01 -9.66838717e-01 8.28486457e-02 -2.47503504e-01 -9.65324461e-01 8.28636438e-02 -2.53422588e-01 -9.63768482e-01 8.28631967e-02 -2.59337336e-01 -9.62217510e-01 8.28641951e-02 -2.65237510e-01 -9.60568488e-01 8.28534290e-02 -2.71115661e-01 -9.58942235e-01 8.28778669e-02 -2.76999414e-01 -9.57278848e-01 8.28882232e-02 -2.82874346e-01 -9.55575228e-01 8.28602836e-02 -2.88718790e-01 -9.53793049e-01 8.28693584e-02 -2.94565320e-01 -9.52014267e-01 8.28821138e-02 -3.00398380e-01 -9.50177312e-01 8.29016045e-02 -3.06233764e-01 -9.48345125e-01 8.29021707e-02 -3.12038064e-01 -9.46420252e-01 8.28799754e-02 -3.17849994e-01 -9.44476843e-01 8.29000548e-02 -3.23630273e-01 -9.42525864e-01 8.29002485e-02 -3.29408586e-01 -9.40508783e-01 8.28936771e-02 -3.35184932e-01 -9.38468814e-01 8.28768685e-02 -3.40924650e-01 -9.36426222e-01 8.28874558e-02 -3.46671611e-01 -9.34274733e-01 8.29128027e-02 -3.52397412e-01 -9.32141006e-01 8.29155743e-02 -3.58112633e-01 -9.29967403e-01 8.29891190e-02 -3.63801777e-01 -9.27760422e-01 8.29455629e-02 -3.69491667e-01 -9.25498605e-01 8.29660967e-02 -3.75158012e-01 -9.23228383e-01 8.29603970e-02 -3.80815417e-01 -9.20880973e-01 8.29289928e-02 -3.86468589e-01 -9.18537021e-01 8.29000026e-02 -3.92096490e-01 -9.16167736e-01 8.29139128e-02 -3.97711664e-01 -9.13746953e-01 8.29232857e-02 -4.03308123e-01 -9.11295950e-01 8.29284713e-02 -4.08894837e-01 -9.08785582e-01 8.29297975e-02 -4.14454818e-01 -9.06273901e-01 8.29448029e-02 -4.20016408e-01 -9.03694093e-01 8.29168931e-02 -4.25552279e-01 -9.01102602e-01 8.29527602e-02 -4.31063086e-01 -8.98487151e-01 8.29745233e-02 -4.36584443e-01 -8.95816982e-01 8.29517767e-02 -4.42062557e-01 -8.93135786e-01 8.29425976e-02 -4.47535038e-01 -8.90390396e-01 8.29458386e-02 -4.53004807e-01 -8.87621403e-01 8.29175264e-02 -4.58429843e-01 -8.84852648e-01 8.29249173e-02 -4.63843644e-01 -8.81973803e-01 8.29367712e-02 -4.69251394e-01 -8.79141271e-01 8.29499662e-02 -4.74652350e-01 -8.76257479e-01 8.29643905e-02 -4.80013967e-01 -8.73338401e-01 8.29516724e-02 -4.85365182e-01 -8.70348871e-01 8.29677135e-02 -4.90686715e-01 -8.67352664e-01 8.29682797e-02 -4.95991439e-01 -8.64338160e-01 8.29803571e-02 -5.01294494e-01 -8.61268401e-01 8.29962865e-02 -5.06562769e-01 -8.58181536e-01 8.29749554e-02 -5.11813104e-01 -8.55060697e-01 8.29748288e-02 -5.17061770e-01 -8.51906002e-01 8.30249786e-02 -5.22261441e-01 -8.48704755e-01 8.30349922e-02 -5.27465999e-01 -8.45472753e-01 8.30184445e-02 -5.32656074e-01 -8.42265666e-01 8.30164030e-02 -5.37802696e-01 -8.38961422e-01 8.30202848e-02 -5.42939484e-01 -8.35639000e-01 8.30444545e-02 -5.48048317e-01 -8.32307458e-01 8.30480307e-02 -5.53151608e-01 -8.28909039e-01 8.30368027e-02 -5.58230102e-01 -8.25502038e-01 8.30401257e-02 -5.63292742e-01 -8.22074533e-01 8.30647871e-02 -5.68318725e-01 -8.18587899e-01 8.30759779e-02 -5.73321581e-01 -8.15057874e-01 8.30923766e-02 -5.78307271e-01 -8.11543345e-01 8.31123739e-02 -5.83285332e-01 -8.07979941e-01 8.31148550e-02 -5.88232338e-01 -8.04358780e-01 8.31293464e-02 -5.93145788e-01 -8.00762951e-01 8.31198618e-02 -5.98053157e-01 -7.97113955e-01 8.30963477e-02 -6.02953970e-01 -7.93403387e-01 8.30874890e-02 -6.07807279e-01 -7.89725721e-01 8.30913484e-02 -6.12628877e-01 -7.85976887e-01 8.30891654e-02 -6.17460370e-01 -7.82190859e-01 8.30850303e-02 -6.22220755e-01 -7.78384268e-01 8.30949619e-02 -6.26986206e-01 -7.74548709e-01 8.30984861e-02 -6.31728113e-01 -7.70687878e-01 8.31411183e-02 -6.36443138e-01 -7.66807437e-01 8.31543729e-02 -6.41148627e-01 -7.62877703e-01 8.31501707e-02 -6.45808578e-01 -7.58952558e-01 8.31705481e-02 -6.50449753e-01 -7.54944503e-01 8.31587538e-02 -6.55060709e-01 -7.50938177e-01 8.32094252e-02 -6.59671664e-01 -7.46908009e-01 8.32212120e-02 -6.64254606e-01 -7.42859483e-01 8.32151845e-02 -6.68794990e-01 -7.38765001e-01 8.32052603e-02 -6.73298717e-01 -7.34634101e-01 8.32120702e-02 -6.77799225e-01 -7.30494261e-01 8.32032263e-02 -6.82289600e-01 -7.26348639e-01 8.31892639e-02 -6.86707377e-01 -7.22109079e-01 8.31741765e-02 -6.91147625e-01 -7.17921674e-01 8.31678808e-02 -6.95539236e-01 -7.13662028e-01 8.31904337e-02 -6.99906051e-01 -7.09349513e-01 8.31774324e-02 -7.04225302e-01 -7.05062091e-01 8.31745118e-02 -7.08554447e-01 -7.00706184e-01 8.32078978e-02 -7.12830961e-01 -6.96341097e-01 8.32086727e-02 -7.17083871e-01 -6.91959679e-01 8.32144618e-02 -7.21336901e-01 -6.87547028e-01 8.32567662e-02 -7.25508571e-01 -6.83132946e-01 8.32740963e-02 -7.29710996e-01 -6.78661585e-01 8.32653269e-02 -7.33863115e-01 -6.74165010e-01 8.32494795e-02 -7.37983048e-01 -6.69659972e-01 8.32755566e-02 -7.42051184e-01 -6.65126085e-01 8.32878575e-02 -7.46150076e-01 -6.60536468e-01 8.33221078e-02 -7.50165761e-01 -6.55942202e-01 8.33152682e-02 -7.54183710e-01 -6.51326835e-01 8.33458155e-02 -7.58168757e-01 -6.46671295e-01 8.33679661e-02 -7.62102902e-01 -6.42034233e-01 8.33787471e-02 -7.66024351e-01 -6.37334824e-01 8.34056586e-02 -7.69939661e-01 -6.32634997e-01 8.34654123e-02 -7.73784578e-01 -6.27895296e-01 8.35344642e-02 -7.77637780e-01 -6.23133481e-01 8.37157741e-02 -7.81408548e-01 -6.18312180e-01 8.39125216e-02 -7.85195470e-01 -6.13531291e-01 8.37348104e-02 -7.88965106e-01 -6.08705461e-01 8.35783035e-02 -7.92705297e-01 -6.03846371e-01 8.35228637e-02 -7.96381414e-01 -5.98980546e-01 8.35104212e-02 -8.00030708e-01 -5.94088137e-01 8.35702717e-02 -8.03672731e-01 -5.89156330e-01 8.37222561e-02 -8.07239592e-01 -5.84203780e-01 8.40110257e-02 -8.10748339e-01 -5.79192638e-01 8.50701109e-02 -8.14424694e-01 -5.74294865e-01 8.30480233e-02 -8.17545056e-01 -5.69058597e-01 8.82742032e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.35205495e-01 -5.44034541e-01 8.03626925e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. -8.75308096e-01 -4.75489378e-01 8.80091488e-02 -8.78204405e-01 -4.70107615e-01 8.80667791e-02 -8.81246090e-01 -4.64785129e-01 8.58510807e-02 -8.84168983e-01 -4.59406644e-01 8.47591534e-02 -8.87038708e-01 -4.53999996e-01 8.38854611e-02 -8.89805913e-01 -4.48553830e-01 8.38142857e-02 -8.92578304e-01 -4.43091065e-01 8.36655647e-02 -8.95348251e-01 -4.37635720e-01 8.27425346e-02 -8.98040235e-01 -4.32133377e-01 8.25059935e-02 -9.00666356e-01 -4.26632524e-01 8.21629465e-02 -9.03294921e-01 -4.21096742e-01 8.22306126e-02 -9.05844271e-01 -4.15540665e-01 8.23290348e-02 -9.08389568e-01 -4.09980625e-01 8.21110979e-02 -9.10782635e-01 -4.04361993e-01 8.34414959e-02 -9.13119376e-01 -3.98721755e-01 8.50151256e-02 -9.15624559e-01 -3.93137962e-01 8.41045305e-02 -9.17950988e-01 -3.87493551e-01 8.46852809e-02 -9.20378029e-01 -3.81868869e-01 8.41979459e-02 -9.22733486e-01 -3.76226395e-01 8.38795602e-02 -9.25033629e-01 -3.70553344e-01 8.37415457e-02 -9.27278519e-01 -3.64875376e-01 8.37647617e-02 -9.29489434e-01 -3.59171629e-01 8.38537663e-02 -9.31682587e-01 -3.53464991e-01 8.38496611e-02 -9.33854401e-01 -3.47743958e-01 8.36961195e-02 -9.35951710e-01 -3.42015564e-01 8.35431889e-02 -9.38108981e-01 -3.36266994e-01 8.34375173e-02 -9.40096378e-01 -3.30513597e-01 8.34175944e-02 -9.42104757e-01 -3.24738532e-01 8.34529623e-02 -9.44127321e-01 -3.18948746e-01 8.34687948e-02 -9.46040154e-01 -3.13141435e-01 8.35705623e-02 -9.47915554e-01 -3.07334185e-01 8.36339146e-02 -9.49796975e-01 -3.01508427e-01 8.35738927e-02 -9.51666236e-01 -2.95675695e-01 8.34958553e-02 -9.53456581e-01 -2.89833993e-01 8.34372193e-02 -9.55183923e-01 -2.83984929e-01 8.33976865e-02 -9.56927359e-01 -2.78113931e-01 8.34319293e-02 -9.58590508e-01 -2.72244185e-01 8.34048688e-02 -9.60275710e-01 -2.66355634e-01 8.34117755e-02 -9.61912513e-01 -2.60458469e-01 8.34071413e-02 -9.63455141e-01 -2.54553437e-01 8.33939835e-02 -9.64975119e-01 -2.48622388e-01 8.34390447e-02 -9.66524303e-01 -2.42701262e-01 8.35075602e-02 -9.67976689e-01 -2.36760661e-01 8.35859627e-02 -9.69415545e-01 -2.30822980e-01 8.36308450e-02 -9.70777154e-01 -2.24868178e-01 8.37287381e-02 -9.72163916e-01 -2.18908280e-01 8.36967602e-02 -9.73465681e-01 -2.12935582e-01 8.37199390e-02 -9.74780202e-01 -2.06958503e-01 8.36573243e-02 -9.76050258e-01 -2.00975925e-01 8.36120695e-02 -9.77266192e-01 -1.94982529e-01 8.36149380e-02 -9.78427351e-01 -1.88985929e-01 8.36559460e-02 -9.79535639e-01 -1.82975397e-01 8.37052315e-02 -9.80665386e-01 -1.76959738e-01 8.37974846e-02 -9.81712759e-01 -1.70940310e-01 8.38071853e-02 -9.82769430e-01 -1.64911911e-01 8.38138983e-02 -9.83753264e-01 -1.58879295e-01 8.37715566e-02 -9.84734118e-01 -1.52840734e-01 8.36884603e-02 -9.85621750e-01 -1.46798283e-01 8.36470053e-02 -9.86526787e-01 -1.40748590e-01 8.36321935e-02 -9.87338483e-01 -1.34689718e-01 8.36526453e-02 -9.88169074e-01 -1.28630862e-01 8.35943297e-02 -9.88961875e-01 -1.22565538e-01 8.35503340e-02 -9.89688575e-01 -1.16493471e-01 8.35689381e-02 -9.90384638e-01 -1.10420212e-01 8.37777257e-02 -9.90966737e-01 -1.04339786e-01 8.39567557e-02 -9.91552114e-01 -9.82554555e-02 8.44983608e-02 -9.92028773e-01 -9.21670347e-02 8.59515294e-02 -9.92842019e-01 -8.60812142e-02 8.27901363e-02 0. 0. 0. -9.93859172e-01 -7.38907680e-02 8.23653564e-02 0. 0. 0. 0. 0. 0. -9.95198488e-01 -5.55809662e-02 8.05653110e-02 -9.95501757e-01 -4.94741574e-02 8.07992741e-02 -9.95663583e-01 -4.33691107e-02 8.22469071e-02 -9.95994091e-01 -3.72556150e-02 8.12649801e-02 -9.96251643e-01 -3.11413668e-02 8.06977153e-02 -9.96420383e-01 -2.50280797e-02 8.07394609e-02 -9.96505797e-01 -1.89166795e-02 8.13305378e-02 -9.96631145e-01 -1.28000332e-02 8.09988454e-02 -9.96729672e-01 -6.68178452e-03 8.05313140e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98547077e-01 3.03567946e-02 4.45220955e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.97056603e-01 6.09546006e-02 4.65054102e-02 -9.96658206e-01 6.70700818e-02 4.66271974e-02 -9.96227205e-01 7.31840804e-02 4.66385856e-02 -9.95757639e-01 7.92951658e-02 4.66632359e-02 -9.95244741e-01 8.54020864e-02 4.67858613e-02 -9.94674921e-01 9.14965421e-02 4.77412827e-02 -9.94096935e-01 9.76026431e-02 4.73956950e-02 -9.93515134e-01 1.03705488e-01 4.70290631e-02 -9.92828369e-01 1.09800726e-01 4.68790792e-02 -9.92143631e-01 1.15889437e-01 4.68889810e-02 -9.91411150e-01 1.21977091e-01 4.69203629e-02 -9.90630090e-01 1.28055245e-01 4.69301566e-02 -9.89872992e-01 1.34133920e-01 4.69450541e-02 -9.88986433e-01 1.40206337e-01 4.69305851e-02 -9.88156080e-01 1.46271721e-01 4.68970425e-02 -9.87204611e-01 1.52329460e-01 4.68366817e-02 -9.86242473e-01 1.58384383e-01 4.68364209e-02 -9.85254765e-01 1.64433524e-01 4.68219444e-02 -9.84268069e-01 1.70477808e-01 4.68496047e-02 -9.83213961e-01 1.76513657e-01 4.68733683e-02 -9.82075334e-01 1.82540551e-01 4.69112843e-02 -9.80921686e-01 1.88563496e-01 4.70016561e-02 -9.79785681e-01 1.94572508e-01 4.70155850e-02 -9.78572726e-01 2.00583234e-01 4.69868444e-02 -9.77280021e-01 2.06585512e-01 4.69225161e-02 -9.75997865e-01 2.12584242e-01 4.68972139e-02 -9.74704146e-01 2.18566760e-01 4.68998626e-02 -9.73315656e-01 2.24542260e-01 4.68960814e-02 -9.71915662e-01 2.30512381e-01 4.69002724e-02 -9.70532238e-01 2.36466944e-01 4.69754785e-02 -9.69063520e-01 2.42412567e-01 4.70831729e-02 -9.67506826e-01 2.48359561e-01 4.70996425e-02 -9.65977371e-01 2.54288822e-01 4.70657870e-02 -9.64433312e-01 2.60203838e-01 4.70525287e-02 -9.62802529e-01 2.66116351e-01 4.70670126e-02 -9.61117923e-01 2.72028476e-01 4.70376797e-02 -9.59453464e-01 2.77920991e-01 4.70464230e-02 -9.57704008e-01 2.83797771e-01 4.70568575e-02 -9.55977499e-01 2.89668858e-01 4.70465720e-02 -9.54193473e-01 2.95535952e-01 4.70513031e-02 -9.52323675e-01 3.01383942e-01 4.70643677e-02 -9.50453579e-01 3.07214290e-01 4.70473357e-02 -9.48596954e-01 3.13052624e-01 4.70505506e-02 -9.46648240e-01 3.18856806e-01 4.70449142e-02 -9.44688380e-01 3.24661463e-01 4.68813479e-02 -9.42643523e-01 3.30452859e-01 4.68793921e-02 -9.40622270e-01 3.36235583e-01 4.68884893e-02 -9.38515007e-01 3.42005342e-01 4.68930677e-02 -9.36456084e-01 3.47757936e-01 4.68915142e-02 -9.34282482e-01 3.53491873e-01 4.68777418e-02 -9.32088375e-01 3.59221429e-01 4.68757749e-02 -9.29877102e-01 3.64940494e-01 4.68848124e-02 -9.27617133e-01 3.70623410e-01 4.68831658e-02 -9.25280452e-01 3.76305819e-01 4.68817726e-02 -9.22997892e-01 3.81985098e-01 4.68845852e-02 -9.20627654e-01 3.87636185e-01 4.68844809e-02 -9.18206871e-01 3.93284798e-01 4.68814671e-02 -9.15769339e-01 3.98907900e-01 4.68998067e-02 -9.13315415e-01 4.04520601e-01 4.68788520e-02 -9.10856247e-01 4.10116315e-01 4.68666293e-02 -9.08277214e-01 4.15690690e-01 4.68625575e-02 -9.05748665e-01 4.21277076e-01 4.68748771e-02 -9.03128743e-01 4.26811010e-01 4.68886495e-02 -9.00472164e-01 4.32350487e-01 4.69096303e-02 -8.97832155e-01 4.37868446e-01 4.69653159e-02 -8.95099699e-01 4.43350524e-01 4.71267104e-02 -8.92323256e-01 4.48821217e-01 4.77040485e-02 -8.89503717e-01 4.54241455e-01 4.94687147e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.63264859e-01 5.02793550e-01 4.44122478e-02 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. 0. 0. -8.27298641e-01 5.59789240e-01 4.70361933e-02 -8.23849022e-01 5.64855516e-01 4.70269695e-02 -8.20364356e-01 5.69896102e-01 4.72394004e-02 -8.16845119e-01 5.74910641e-01 4.70979102e-02 -8.13307643e-01 5.79917431e-01 4.69545051e-02 -8.09734404e-01 5.84910512e-01 4.68951501e-02 -8.06141555e-01 5.89862883e-01 4.68882173e-02 -8.02497983e-01 5.94795406e-01 4.68875244e-02 -7.98835218e-01 5.99701703e-01 4.69118059e-02 -7.95147359e-01 6.04585350e-01 4.69217747e-02 -7.91385949e-01 6.09456897e-01 4.69181947e-02 -7.87683129e-01 6.14306867e-01 4.69076559e-02 -7.83888102e-01 6.19148493e-01 4.69005704e-02 -7.80065835e-01 6.23938918e-01 4.68464307e-02 -7.76240826e-01 6.28701150e-01 4.68425006e-02 -7.72348106e-01 6.33454800e-01 4.68374193e-02 -7.68447220e-01 6.38202012e-01 4.68268320e-02 -7.64537454e-01 6.42876208e-01 4.68317717e-02 -7.60557830e-01 6.47591114e-01 4.68365885e-02 -7.56581485e-01 6.52231336e-01 4.68397364e-02 -7.52572775e-01 6.56864941e-01 4.68408689e-02 -7.48528719e-01 6.61478043e-01 4.68322486e-02 -7.44445980e-01 6.66033566e-01 4.68306392e-02 -7.40352809e-01 6.70615852e-01 4.68251370e-02 -7.36233175e-01 6.75143480e-01 4.68180180e-02 -7.32081890e-01 6.79647326e-01 4.68207225e-02 -7.27871537e-01 6.84092343e-01 4.68137078e-02 -7.23663449e-01 6.88564897e-01 4.68111970e-02 -7.19427645e-01 6.92988336e-01 4.68332507e-02 -7.15166926e-01 6.97382152e-01 4.68463190e-02 -7.10878968e-01 7.01760352e-01 4.68529947e-02 -7.06526756e-01 7.06122279e-01 4.68562655e-02 -7.02207088e-01 7.10424781e-01 4.68749627e-02 -6.97835743e-01 7.14751065e-01 4.68853004e-02 -6.93440497e-01 7.19014645e-01 4.69035469e-02 -6.89009130e-01 7.23230004e-01 4.69132885e-02 -6.84553564e-01 7.27464914e-01 4.68962193e-02 -6.80061817e-01 7.31629610e-01 4.68922146e-02 -6.75555825e-01 7.35785842e-01 4.68633473e-02 -6.71028852e-01 7.39920199e-01 4.68315966e-02 -6.66504264e-01 7.44050145e-01 4.68118973e-02 -6.61902189e-01 7.48111725e-01 4.68072966e-02 -6.57332897e-01 7.52156734e-01 4.67940830e-02 -6.52699292e-01 7.56170750e-01 4.67802100e-02 -6.48042083e-01 7.60159552e-01 4.67675440e-02 -6.43350244e-01 7.64139235e-01 4.67670523e-02 -6.38678491e-01 7.68062294e-01 4.67453673e-02 -6.33942723e-01 7.71963537e-01 4.67624292e-02 -6.29193842e-01 7.75849640e-01 4.67564128e-02 -6.24420583e-01 7.79684901e-01 4.67319787e-02 -6.19610429e-01 7.83541262e-01 4.67106961e-02 -6.14808321e-01 7.87306249e-01 4.67171893e-02 -6.09945357e-01 7.91048706e-01 4.67120744e-02 -6.05077446e-01 7.94788480e-01 4.66955900e-02 -6.00193322e-01 7.98467577e-01 4.66805510e-02 -5.95303774e-01 8.02127600e-01 4.66746092e-02 -5.90364337e-01 8.05782676e-01 4.66672629e-02 -5.85416853e-01 8.09418499e-01 4.66585681e-02 -5.80430031e-01 8.12985063e-01 4.66678143e-02 -5.75429738e-01 8.16510618e-01 4.66717295e-02 -5.70415795e-01 8.20050240e-01 4.66896705e-02 -5.65373182e-01 8.23539078e-01 4.67173755e-02 -5.60307622e-01 8.26977313e-01 4.67092134e-02 -5.55202901e-01 8.30392718e-01 4.67218384e-02 -5.50096154e-01 8.33801329e-01 4.67121899e-02 -5.44975579e-01 8.37142646e-01 4.66767922e-02 -5.39827108e-01 8.40471268e-01 4.66917604e-02 -5.34673154e-01 8.43790770e-01 4.66642417e-02 -5.29470980e-01 8.47029567e-01 4.66824509e-02 -5.24290502e-01 8.50269496e-01 4.66571450e-02 -5.19057691e-01 8.53481591e-01 4.66433838e-02 -5.13810217e-01 8.56656671e-01 4.66004349e-02 -5.08545876e-01 8.59760106e-01 4.65519316e-02 -5.03250659e-01 8.62856865e-01 4.65337038e-02 -4.97962296e-01 8.65986824e-01 4.65148985e-02 -4.92633045e-01 8.68998885e-01 4.65216003e-02 -4.87272799e-01 8.72017980e-01 4.64979000e-02 -4.81912851e-01 8.75009894e-01 4.65026163e-02 -4.76540416e-01 8.77937198e-01 4.65242416e-02 -4.71163839e-01 8.80856216e-01 4.65511642e-02 -4.65741009e-01 8.83717775e-01 4.65424657e-02 -4.60313797e-01 8.86513710e-01 4.65438925e-02 -4.54848975e-01 8.89348209e-01 4.65284064e-02 -4.49395120e-01 8.92107725e-01 4.64990474e-02 -4.43917423e-01 8.94858360e-01 4.65061255e-02 -4.38410997e-01 8.97556245e-01 4.65015732e-02 -4.32887942e-01 9.00238514e-01 4.64987680e-02 -4.27369326e-01 9.02853668e-01 4.65162992e-02 -4.21810001e-01 9.05508578e-01 4.65461835e-02 -4.16252553e-01 9.08042133e-01 4.65552397e-02 -4.10680413e-01 9.10615861e-01 4.65646498e-02 -4.05080199e-01 9.13077354e-01 4.65839393e-02 -3.99470866e-01 9.15533304e-01 4.65913005e-02 -3.93851250e-01 9.17970479e-01 4.65838760e-02 -3.88200223e-01 9.20388937e-01 4.65796627e-02 -3.82542282e-01 9.22776401e-01 4.65806425e-02 -3.76878619e-01 9.25095916e-01 4.65619043e-02 -3.71186733e-01 9.27388072e-01 4.65480313e-02 -3.65500748e-01 9.29657757e-01 4.65383343e-02 -3.59783739e-01 9.31857347e-01 4.65784594e-02 -3.54054838e-01 9.34049547e-01 4.65765521e-02 -3.48320901e-01 9.36235726e-01 4.65652905e-02 -3.42575759e-01 9.38345313e-01 4.65693511e-02 -3.36800784e-01 9.40404773e-01 4.65841293e-02 -3.31034243e-01 9.42484975e-01 4.65939008e-02 -3.25248152e-01 9.44508612e-01 4.66261953e-02 -3.19440216e-01 9.46477711e-01 4.66109253e-02 -3.13628823e-01 9.48428929e-01 4.65801209e-02 -3.07806730e-01 9.50311124e-01 4.65821549e-02 -3.01968098e-01 9.52183604e-01 4.65607718e-02 -2.96118170e-01 9.54041421e-01 4.65463959e-02 -2.90262043e-01 9.55822468e-01 4.65669371e-02 -2.84392178e-01 9.57575202e-01 4.65649143e-02 -2.78508157e-01 9.59319830e-01 4.65823151e-02 -2.72617012e-01 9.61017907e-01 4.65553738e-02 -2.66720295e-01 9.62655663e-01 4.65654805e-02 -2.60811031e-01 9.64287162e-01 4.65474911e-02 -2.54883230e-01 9.65844333e-01 4.65506874e-02 -2.48945966e-01 9.67430472e-01 4.65482213e-02 -2.43009955e-01 9.68920767e-01 4.65420336e-02 -2.37056091e-01 9.70386922e-01 4.65482548e-02 -2.31102273e-01 9.71845031e-01 4.65337411e-02 -2.25137249e-01 9.73235369e-01 4.65393104e-02 -2.19161704e-01 9.74558115e-01 4.65212092e-02 -2.13175252e-01 9.75923836e-01 4.64962497e-02 -2.07181051e-01 9.77214992e-01 4.65020947e-02 -2.01181397e-01 9.78440166e-01 4.65150028e-02 -1.95173249e-01 9.79659855e-01 4.64926772e-02 -1.89159632e-01 9.80870664e-01 4.65015061e-02 -1.83136940e-01 9.82005358e-01 4.65188958e-02 -1.77110448e-01 9.83078599e-01 4.64774854e-02 -1.71074972e-01 9.84141290e-01 4.65021022e-02 -1.65030599e-01 9.85195220e-01 4.64967228e-02 -1.58985585e-01 9.86220658e-01 4.64843623e-02 -1.52928904e-01 9.87147033e-01 4.64808308e-02 -1.46870270e-01 9.88042593e-01 4.65051979e-02 -1.40803233e-01 9.88930047e-01 4.64805104e-02 -1.34735078e-01 9.89814818e-01 4.64688912e-02 -1.28657416e-01 9.90626395e-01 4.64737192e-02 -1.22575738e-01 9.91364360e-01 4.64733429e-02 -1.16492093e-01 9.92096901e-01 4.64651622e-02 -1.10402212e-01 9.92821157e-01 4.64672484e-02 -1.04307987e-01 9.93475735e-01 4.64254692e-02 -9.82097760e-02 9.94064033e-01 4.64349017e-02 -9.21089351e-02 9.94689703e-01 4.64332700e-02 -8.60035121e-02 9.95244086e-01 4.64299656e-02 -7.98953995e-02 9.95747864e-01 4.64415364e-02 -7.37846568e-02 9.96221006e-01 4.64280955e-02 -6.76709041e-02 9.96647000e-01 4.63824421e-02 -6.15540333e-02 9.96997118e-01 4.64121997e-02 -5.54352030e-02 9.97391284e-01 4.64068092e-02 -4.93143722e-02 9.97707248e-01 4.64136563e-02 -4.31920253e-02 9.97968674e-01 4.64299060e-02 -3.70670632e-02 9.98212397e-01 4.64260057e-02 -3.09413709e-02 9.98439431e-01 4.64269742e-02 -2.48147175e-02 9.98615146e-01 4.64085191e-02 -1.86866596e-02 9.98752892e-01 4.63981666e-02 -1.25580961e-02 9.98856127e-01 4.63922843e-02 -6.42880285e-03 9.98924613e-01 4.63702008e-02 -2.99563777e-04 9.98928845e-01 4.63799238e-02 5.82972029e-03 9.98924375e-01 4.63838615e-02 1.19590126e-02 9.98861134e-01 4.63512242e-02 1.80874951e-02 9.98758197e-01 4.63607050e-02 2.42156032e-02 9.98663068e-01 4.63735983e-02 3.03427838e-02 9.98447299e-01 4.63615023e-02 3.64681222e-02 9.98265326e-01 4.64210212e-02 4.25921939e-02 9.98022020e-01 4.64307666e-02 4.87154722e-02 9.97711360e-01 4.64553908e-02 5.48367463e-02 9.97442544e-01 4.64405455e-02 6.09552823e-02 9.97054935e-01 4.64400500e-02 6.70719743e-02 9.96704936e-01 4.64598052e-02 7.31860101e-02 9.96237040e-01 4.65083271e-02 7.92968795e-02 9.95754242e-01 4.65069041e-02 8.54050219e-02 9.95262623e-01 4.64772880e-02 9.15107504e-02 9.94748771e-01 4.64770012e-02 9.76127461e-02 9.94140744e-01 4.64643463e-02 1.03710808e-01 9.93535578e-01 4.64585125e-02 1.09805211e-01 9.92844820e-01 4.64560278e-02 1.15894072e-01 9.92177665e-01 4.64747064e-02 1.21979997e-01 9.91445065e-01 4.64967638e-02 1.28061071e-01 9.90651071e-01 4.65037338e-02 1.34137079e-01 9.89887953e-01 4.65076752e-02 1.40208572e-01 9.89025950e-01 4.64195497e-02 1.46274447e-01 9.88171160e-01 4.64239828e-02 1.52336180e-01 9.87222910e-01 4.64067347e-02 1.58391133e-01 9.86269534e-01 4.63541485e-02 1.64441228e-01 9.85279500e-01 4.63293977e-02 1.70483232e-01 9.84292269e-01 4.63238917e-02 1.76518962e-01 9.83217537e-01 4.63469997e-02 1.82547823e-01 9.82100964e-01 4.63372618e-02 1.88570723e-01 9.80963290e-01 4.63371873e-02 1.94587708e-01 9.79800463e-01 4.63374332e-02 2.00594410e-01 9.78580475e-01 4.63688746e-02 2.06597328e-01 9.77324486e-01 4.63633277e-02 2.12591186e-01 9.76025343e-01 4.63020802e-02 2.18575150e-01 9.74717021e-01 4.63079959e-02 2.24551633e-01 9.73341703e-01 4.63161953e-02 2.30521619e-01 9.71961737e-01 4.62902561e-02 2.36478627e-01 9.70542192e-01 4.62700017e-02 2.42432266e-01 9.69077766e-01 4.62558530e-02 2.48375118e-01 9.67554450e-01 4.62859422e-02 2.54305184e-01 9.66010630e-01 4.62481566e-02 2.60227948e-01 9.64446962e-01 4.62621301e-02 2.66140729e-01 9.62838292e-01 4.62298132e-02 2.72042722e-01 9.61156845e-01 4.62224297e-02 2.77932256e-01 9.59502876e-01 4.62242737e-02 2.83816397e-01 9.57741141e-01 4.62260768e-02 2.89685130e-01 9.56013441e-01 4.61745858e-02 2.95542449e-01 9.54208434e-01 4.62159328e-02 3.01393449e-01 9.52359796e-01 4.62103970e-02 3.07238668e-01 9.50503767e-01 4.61812355e-02 3.13071460e-01 9.48614180e-01 4.61754799e-02 3.18876982e-01 9.46669459e-01 4.61517312e-02 3.24679196e-01 9.44702744e-01 4.61405031e-02 3.30470145e-01 9.42680955e-01 4.61418256e-02 3.36250246e-01 9.40649271e-01 4.61535491e-02 3.42014492e-01 9.38551009e-01 4.61025871e-02 3.47771972e-01 9.36482012e-01 4.60772142e-02 3.53507221e-01 9.34310317e-01 4.60637845e-02 3.59234691e-01 9.32116687e-01 4.60710153e-02 3.64958107e-01 9.29907441e-01 4.60639112e-02 3.70644808e-01 9.27635372e-01 4.60719541e-02 3.76324683e-01 9.25311685e-01 4.60679233e-02 3.82001668e-01 9.23017740e-01 4.60414700e-02 3.87657374e-01 9.20653224e-01 4.60360944e-02 3.93308997e-01 9.18239236e-01 4.59966026e-02 3.98924261e-01 9.15803909e-01 4.59901430e-02 4.04537976e-01 9.13350463e-01 4.59680557e-02 4.10140127e-01 9.10886943e-01 4.59801145e-02 4.15710509e-01 9.08320487e-01 4.59541827e-02 4.21295196e-01 9.05784190e-01 4.59453166e-02 4.26838487e-01 9.03154731e-01 4.59493734e-02 4.32381451e-01 9.00515437e-01 4.59138155e-02 4.37892377e-01 8.97879779e-01 4.58971262e-02 4.43383098e-01 8.95146787e-01 4.59011644e-02 4.48869944e-01 8.92395139e-01 4.58986536e-02 4.54353660e-01 8.89674067e-01 4.58687842e-02 4.59794670e-01 8.86840880e-01 4.58764844e-02 4.65218127e-01 8.84010732e-01 4.58735526e-02 4.70637619e-01 8.81155670e-01 4.58523706e-02 4.76054490e-01 8.78233135e-01 4.58466634e-02 4.81427938e-01 8.75305474e-01 4.58422564e-02 4.86792475e-01 8.72357130e-01 4.58458886e-02 4.92140561e-01 8.69306564e-01 4.58433554e-02 4.97442573e-01 8.66284370e-01 4.58481610e-02 5.02762735e-01 8.63203108e-01 4.58322838e-02 5.08043528e-01 8.60121906e-01 4.58343364e-02 5.13296545e-01 8.57000172e-01 4.58365306e-02 5.18552363e-01 8.53842139e-01 4.58305553e-02 5.23783267e-01 8.50655973e-01 4.58063595e-02 5.28997660e-01 8.47415090e-01 4.58206385e-02 5.34202695e-01 8.44110250e-01 4.58212905e-02 5.39355040e-01 8.40845823e-01 4.58283462e-02 5.44504821e-01 8.37508023e-01 4.58185785e-02 5.49626708e-01 8.34156513e-01 4.58099283e-02 5.54741085e-01 8.30754042e-01 4.58049551e-02 5.59836984e-01 8.27340543e-01 4.58084121e-02 5.64892650e-01 8.23874295e-01 4.57904115e-02 5.69951653e-01 8.20432067e-01 4.57845144e-02 5.74963927e-01 8.16926897e-01 4.57897633e-02 5.79964221e-01 8.13363433e-01 4.57970127e-02 5.84957957e-01 8.09783757e-01 4.57943380e-02 5.89913547e-01 8.06197643e-01 4.57855910e-02 5.94839633e-01 8.02550435e-01 4.57748510e-02 5.99742353e-01 7.98878372e-01 4.57568280e-02 6.04629338e-01 7.95186639e-01 4.57527936e-02 6.09499514e-01 7.91435063e-01 4.57599051e-02 6.14351511e-01 7.87732065e-01 4.57699262e-02 6.19195819e-01 7.83925712e-01 4.57710177e-02 6.23980224e-01 7.80108452e-01 4.57657911e-02 6.28744245e-01 7.76279688e-01 4.57806438e-02 6.33495152e-01 7.72385955e-01 4.57752757e-02 6.38238311e-01 7.68484354e-01 4.57602851e-02 6.42913163e-01 7.64575303e-01 4.57637273e-02 6.47624850e-01 7.60591865e-01 4.57764305e-02 6.52270675e-01 7.56618738e-01 4.57695462e-02 6.56902134e-01 7.52609611e-01 4.57823426e-02 6.61512136e-01 7.48556972e-01 4.57547791e-02 6.66074097e-01 7.44479775e-01 4.57614847e-02 6.70658767e-01 7.40380466e-01 4.57574725e-02 6.75183177e-01 7.36270130e-01 4.57391888e-02 6.79686129e-01 7.32117832e-01 4.57413495e-02 6.84127212e-01 7.27889240e-01 4.57498394e-02 6.88610315e-01 7.23702610e-01 4.57478762e-02 6.93030715e-01 7.19466925e-01 4.57442813e-02 6.97426021e-01 7.15197027e-01 4.57465686e-02 7.01804221e-01 7.10918307e-01 4.57463264e-02 7.06173301e-01 7.06568539e-01 4.57521901e-02 7.10473001e-01 7.02249944e-01 4.57541570e-02 7.14808047e-01 6.97878063e-01 4.57426198e-02 7.19075501e-01 6.93481565e-01 4.57375422e-02 7.23282456e-01 6.89034820e-01 4.57356051e-02 7.27517664e-01 6.84594750e-01 4.57153060e-02 7.31683254e-01 6.80102825e-01 4.57015410e-02 7.35835850e-01 6.75599575e-01 4.56961505e-02 7.39972949e-01 6.71069980e-01 4.56810743e-02 7.44102955e-01 6.66541696e-01 4.56700437e-02 7.48165488e-01 6.61944687e-01 4.56799977e-02 7.52225518e-01 6.57373071e-01 4.56815809e-02 7.56228507e-01 6.52738631e-01 4.56933491e-02 7.60209560e-01 6.48060083e-01 4.56945561e-02 7.64192879e-01 6.43382967e-01 4.56951223e-02 7.68113852e-01 6.38707936e-01 4.56984602e-02 7.72015691e-01 6.33979023e-01 4.56805266e-02 7.75901735e-01 6.29227400e-01 4.56784964e-02 7.79734492e-01 6.24459386e-01 4.56700101e-02 7.83592999e-01 6.19632959e-01 4.56562750e-02 7.87359357e-01 6.14840209e-01 4.56349291e-02 7.91103721e-01 6.09979570e-01 4.56397533e-02 7.94836700e-01 6.05114460e-01 4.56554741e-02 7.98514247e-01 6.00222528e-01 4.56466787e-02 8.02177846e-01 5.95328987e-01 4.56412919e-02 8.05826843e-01 5.90372205e-01 4.56281826e-02 8.09464514e-01 5.85445106e-01 4.56272624e-02 8.13036501e-01 5.80456793e-01 4.56175916e-02 8.16555321e-01 5.75456262e-01 4.56150956e-02 8.20101678e-01 5.70444703e-01 4.56121303e-02 8.23592603e-01 5.65374494e-01 4.56220396e-02 8.27026367e-01 5.60329437e-01 4.56273593e-02 8.30438435e-01 5.55232167e-01 4.56690080e-02 8.33846152e-01 5.50119042e-01 4.57286872e-02 8.37176442e-01 5.44989884e-01 4.56770398e-02 8.40508819e-01 5.39846480e-01 4.56765220e-02 8.43834400e-01 5.34699321e-01 4.56353724e-02 8.47085476e-01 5.29485345e-01 4.56643403e-02 8.50306332e-01 5.24286449e-01 4.56532910e-02 8.53516102e-01 5.19071758e-01 4.56489660e-02 8.56677055e-01 5.13825536e-01 4.57628407e-02 8.59813154e-01 5.08543193e-01 4.57220376e-02 8.62898529e-01 5.03267646e-01 4.57327180e-02 8.66023183e-01 4.97975886e-01 4.57498357e-02 8.69045854e-01 4.92652118e-01 4.57329489e-02 8.72048914e-01 4.87293541e-01 4.57375161e-02 8.75044525e-01 4.81930614e-01 4.57440875e-02 8.77974153e-01 4.76557881e-01 4.57589366e-02 8.80895078e-01 4.71180320e-01 4.57725897e-02 8.83748472e-01 4.65747297e-01 4.57863435e-02 8.86551619e-01 4.60331649e-01 4.57667932e-02 8.89382184e-01 4.54860389e-01 4.57670651e-02 8.92143786e-01 4.49404508e-01 4.57633547e-02 8.94897580e-01 4.43920553e-01 4.57671843e-02 8.97594988e-01 4.38425660e-01 4.57674637e-02 9.00276959e-01 4.32903916e-01 4.57740687e-02 9.02891099e-01 4.27376658e-01 4.57772687e-02 9.05544460e-01 4.21819240e-01 4.57864888e-02 9.08083856e-01 4.16266501e-01 4.57927808e-02 9.10652220e-01 4.10695523e-01 4.57997583e-02 9.13114309e-01 4.05093521e-01 4.58308458e-02 9.15570855e-01 3.99483234e-01 4.58424129e-02 9.18008029e-01 3.93862993e-01 4.58552651e-02 9.20424044e-01 3.88209343e-01 4.58605178e-02 9.22799945e-01 3.82548034e-01 4.58719060e-02 9.25130367e-01 3.76877844e-01 4.58817035e-02 9.27417099e-01 3.71197462e-01 4.59023491e-02 9.29687977e-01 3.65514368e-01 4.58941907e-02 9.31889296e-01 3.59792382e-01 4.58978489e-02 9.34082866e-01 3.54063272e-01 4.59051132e-02 9.36267078e-01 3.48329276e-01 4.59333211e-02 9.38373327e-01 3.42588037e-01 4.59353924e-02 9.40436900e-01 3.36810321e-01 4.59476672e-02 9.42513287e-01 3.31031889e-01 4.59612198e-02 9.44539487e-01 3.25246304e-01 4.59622703e-02 9.46508706e-01 3.19441587e-01 4.59669828e-02 9.48458254e-01 3.13634783e-01 4.59750518e-02 9.50340211e-01 3.07801843e-01 4.59651835e-02 9.52207208e-01 3.01978290e-01 4.59653996e-02 9.54066753e-01 2.96128571e-01 4.59919609e-02 9.55853820e-01 2.90270120e-01 4.59790453e-02 9.57629144e-01 2.84388572e-01 4.59892675e-02 9.59347367e-01 2.78514147e-01 4.59819771e-02 9.61049914e-01 2.72616267e-01 4.59868833e-02 9.62683082e-01 2.66718566e-01 4.59709801e-02 9.64312136e-01 2.60809332e-01 4.59937342e-02 9.65870023e-01 2.54878789e-01 4.60040197e-02 9.67462301e-01 2.48948038e-01 4.60083038e-02 9.68948901e-01 2.43016079e-01 4.59996052e-02 9.70412910e-01 2.37058699e-01 4.60074171e-02 9.71868873e-01 2.31101900e-01 4.59897108e-02 9.73256111e-01 2.25138322e-01 4.59731445e-02 9.74581838e-01 2.19163597e-01 4.59931940e-02 9.75949526e-01 2.13175058e-01 4.59898226e-02 9.77239251e-01 2.07182243e-01 4.59908657e-02 9.78468239e-01 2.01182559e-01 4.59404886e-02 9.79683995e-01 1.95173100e-01 4.59688157e-02 9.80895877e-01 1.89161256e-01 4.59541641e-02 9.82033968e-01 1.83136404e-01 4.59630154e-02 9.83101726e-01 1.77112922e-01 4.59765196e-02 9.84160483e-01 1.71076745e-01 4.59844396e-02 9.85226333e-01 1.65032327e-01 4.59609181e-02 9.86246169e-01 1.58984691e-01 4.59771380e-02 9.87176001e-01 1.52930200e-01 4.59809490e-02 9.88061428e-01 1.46871254e-01 4.59712483e-02 9.88958061e-01 1.40805274e-01 4.59349230e-02 9.89841342e-01 1.34735301e-01 4.60061729e-02 9.90652204e-01 1.28656551e-01 4.59965803e-02 9.91390467e-01 1.22580282e-01 4.60029803e-02 9.92122293e-01 1.16491355e-01 4.59974147e-02 9.92848873e-01 1.10400565e-01 4.59850878e-02 9.93506670e-01 1.04308553e-01 4.59659696e-02 9.94089246e-01 9.82105434e-02 4.59986292e-02 9.94719923e-01 9.21077207e-02 4.60108593e-02 9.95269716e-01 8.60027894e-02 4.60113026e-02 9.95772958e-01 7.98953548e-02 4.60214689e-02 9.96246636e-01 7.37850666e-02 4.60052602e-02 9.96675551e-01 6.76692501e-02 4.59942743e-02 9.97018456e-01 6.15537316e-02 4.60123010e-02 9.97420251e-01 5.54341935e-02 4.60210741e-02 9.97711957e-01 4.93131652e-02 4.61553223e-02 9.97972190e-01 4.31895331e-02 4.61692177e-02 9.98216808e-01 3.70657668e-02 4.61770408e-02 9.98460233e-01 3.09401806e-02 4.60717008e-02 9.98636186e-01 2.48129815e-02 4.60689478e-02 9.98770654e-01 1.86850168e-02 4.60927263e-02 9.98879850e-01 1.25561040e-02 4.60490622e-02 9.98944581e-01 6.42678514e-03 4.60330285e-02 9.98951375e-01 2.97305320e-04 4.60209697e-02 9.98946369e-01 -5.83207002e-03 4.60378230e-02 9.98883426e-01 -1.19612161e-02 4.60545979e-02 9.98775423e-01 -1.80896763e-02 4.60769497e-02 9.98684585e-01 -2.42180321e-02 4.60874215e-02 9.98466313e-01 -3.03453207e-02 4.60902564e-02 9.98282850e-01 -3.64706963e-02 4.61032093e-02 9.98039305e-01 -4.25956659e-02 4.61083651e-02 9.97743607e-01 -4.87182997e-02 4.60947864e-02 9.97467458e-01 -5.48398942e-02 4.60926890e-02 9.97067511e-01 -6.09584786e-02 4.61082608e-02 9.96728957e-01 -6.70754761e-02 4.61360477e-02 9.96263623e-01 -7.31906369e-02 4.61378470e-02 9.95780468e-01 -7.93024898e-02 4.61304523e-02 9.95289624e-01 -8.54088590e-02 4.61201370e-02 9.94780123e-01 -9.15163085e-02 4.61131223e-02 9.94152963e-01 -9.76170450e-02 4.61207069e-02 9.93571401e-01 -1.03715889e-01 4.59680520e-02 9.92868960e-01 -1.09809749e-01 4.61071990e-02 9.92190242e-01 -1.15901895e-01 4.61035185e-02 9.91458833e-01 -1.21986531e-01 4.60936613e-02 9.90678370e-01 -1.28067195e-01 4.60665673e-02 9.89924073e-01 -1.34144455e-01 4.60138060e-02 9.89035964e-01 -1.40214086e-01 4.60394882e-02 9.88203645e-01 -1.46280169e-01 4.60359119e-02 9.87250090e-01 -1.52341485e-01 4.60306965e-02 9.86287773e-01 -1.58399314e-01 4.60281409e-02 9.85300243e-01 -1.64445907e-01 4.60235700e-02 9.84315574e-01 -1.70488879e-01 4.60164361e-02 9.83263850e-01 -1.76525742e-01 4.60040197e-02 9.82119203e-01 -1.82554051e-01 4.59653847e-02 9.80964363e-01 -1.88579977e-01 4.59821559e-02 9.79835331e-01 -1.94589630e-01 4.61001918e-02 9.78635192e-01 -2.00600117e-01 4.59844172e-02 9.77329552e-01 -2.06606790e-01 4.59896587e-02 9.76045787e-01 -2.12603226e-01 4.59927171e-02 9.74737525e-01 -2.18579635e-01 4.60534133e-02 9.73347664e-01 -2.24553883e-01 4.60701697e-02 9.71950412e-01 -2.30525970e-01 4.60665077e-02 9.70582664e-01 -2.36488536e-01 4.59676906e-02 9.69115376e-01 -2.42430627e-01 4.59732190e-02 9.67562914e-01 -2.48381183e-01 4.59949784e-02 9.66028869e-01 -2.54310369e-01 4.59912010e-02 9.64483500e-01 -2.60229647e-01 4.59893644e-02 9.62856233e-01 -2.66142875e-01 4.59871292e-02 9.61168170e-01 -2.72049636e-01 4.59717959e-02 9.59508121e-01 -2.77949482e-01 4.59702201e-02 9.57757056e-01 -2.83822864e-01 4.59495559e-02 9.56028044e-01 -2.89689958e-01 4.59642746e-02 9.54242826e-01 -2.95557976e-01 4.59645130e-02 9.52375591e-01 -3.01402777e-01 4.59699854e-02 9.50506210e-01 -3.07238847e-01 4.59768027e-02 9.48638737e-01 -3.13075751e-01 4.59727868e-02 9.46688890e-01 -3.18880439e-01 4.59828638e-02 9.44722891e-01 -3.24681312e-01 4.59826738e-02 9.42686915e-01 -3.30470920e-01 4.59837280e-02 9.40662444e-01 -3.36255908e-01 4.59650606e-02 9.38557208e-01 -3.42032760e-01 4.59569357e-02 9.36494231e-01 -3.47777009e-01 4.59512509e-02 9.34320152e-01 -3.53511125e-01 4.59495373e-02 9.32125449e-01 -3.59240860e-01 4.59462851e-02 9.29917037e-01 -3.64961743e-01 4.59359325e-02 9.27648544e-01 -3.70647967e-01 4.59511764e-02 9.25323248e-01 -3.76329601e-01 4.58641164e-02 9.23030376e-01 -3.82004827e-01 4.58789989e-02 9.20662522e-01 -3.87656510e-01 4.59594764e-02 9.18242872e-01 -3.93307358e-01 4.59345840e-02 9.15807724e-01 -3.98930222e-01 4.59256582e-02 9.13353026e-01 -4.04547721e-01 4.59026210e-02 9.10898685e-01 -4.10143405e-01 4.57284562e-02 9.08324718e-01 -4.15716469e-01 4.57303263e-02 9.05784607e-01 -4.21301246e-01 4.58674394e-02 9.03170049e-01 -4.26838905e-01 4.58160192e-02 9.00519669e-01 -4.32381451e-01 4.57397066e-02 8.97873640e-01 -4.37899768e-01 4.57123518e-02 8.95150721e-01 -4.43388581e-01 4.57561277e-02 8.92401397e-01 -4.48875099e-01 4.57678102e-02 8.89675498e-01 -4.54351425e-01 4.58710045e-02 8.86842430e-01 -4.59803909e-01 4.58342955e-02 8.84015024e-01 -4.65216160e-01 4.58339117e-02 8.81154239e-01 -4.70655382e-01 4.58419248e-02 8.78233671e-01 -4.76055115e-01 4.58222590e-02 8.75306785e-01 -4.81428862e-01 4.58173752e-02 8.72358263e-01 -4.86790270e-01 4.58200760e-02 8.69304717e-01 -4.92130965e-01 4.58302833e-02 8.66284788e-01 -4.97440875e-01 4.58275340e-02 8.63209069e-01 -5.02759635e-01 4.58258837e-02 8.60113800e-01 -5.08034289e-01 4.58263531e-02 8.57006192e-01 -5.13299167e-01 4.58258018e-02 8.53840172e-01 -5.18566608e-01 4.58131917e-02 8.50652218e-01 -5.23777366e-01 4.58105952e-02 8.47408414e-01 -5.28994977e-01 4.58281524e-02 8.44111323e-01 -5.34196615e-01 4.58080508e-02 8.40840340e-01 -5.39356351e-01 4.58109304e-02 8.37508798e-01 -5.44502199e-01 4.57956940e-02 8.34167480e-01 -5.49629033e-01 4.58016209e-02 8.30766737e-01 -5.54735303e-01 4.57977206e-02 8.27348173e-01 -5.59837461e-01 4.57839668e-02 8.23874295e-01 -5.64901888e-01 4.57903817e-02 8.20427954e-01 -5.69951475e-01 4.57840376e-02 8.16912413e-01 -5.74963152e-01 4.57830839e-02 8.13360989e-01 -5.79963446e-01 4.57827710e-02 8.09790194e-01 -5.84951937e-01 4.58232090e-02 8.06184649e-01 -5.89923024e-01 4.57817428e-02 8.02541256e-01 -5.94839215e-01 4.57664989e-02 7.98881948e-01 -5.99745929e-01 4.57516983e-02 7.95184672e-01 -6.04635775e-01 4.56698723e-02 7.91443527e-01 -6.09504044e-01 4.56546061e-02 7.87731290e-01 -6.14354074e-01 4.57334295e-02 7.83937395e-01 -6.19194686e-01 4.58024144e-02 7.80095994e-01 -6.23980165e-01 4.58148457e-02 7.76280642e-01 -6.28741622e-01 4.58021611e-02 7.72387803e-01 -6.33497357e-01 4.57872748e-02 7.68486202e-01 -6.38239980e-01 4.57944945e-02 7.64576852e-01 -6.42915785e-01 4.57943715e-02 7.60584056e-01 -6.47627890e-01 4.58027311e-02 7.56634176e-01 -6.52273834e-01 4.57793735e-02 7.52613187e-01 -6.56907618e-01 4.57580872e-02 7.48571754e-01 -6.61519229e-01 4.57570963e-02 7.44473159e-01 -6.66075826e-01 4.57277335e-02 7.40379035e-01 -6.70658708e-01 4.57671583e-02 7.36270845e-01 -6.75189316e-01 4.57499363e-02 7.32119143e-01 -6.79689348e-01 4.57424410e-02 7.27885664e-01 -6.84126258e-01 4.57768105e-02 7.23698974e-01 -6.88603103e-01 4.57985252e-02 7.19453871e-01 -6.93015754e-01 4.58089225e-02 7.15184331e-01 -6.97410285e-01 4.58388217e-02 7.10901916e-01 -7.01791167e-01 4.58188131e-02 7.06555784e-01 -7.06161618e-01 4.57919203e-02 7.02249229e-01 -7.10473120e-01 4.57262956e-02 6.97877109e-01 -7.14805305e-01 4.57227156e-02 6.93476915e-01 -7.19072938e-01 4.57184650e-02 6.89023316e-01 -7.23274946e-01 4.57095057e-02 6.84593439e-01 -7.27515519e-01 4.56948541e-02 6.80099010e-01 -7.31681287e-01 4.57120426e-02 6.75598443e-01 -7.35835016e-01 4.57034372e-02 6.71067595e-01 -7.39971399e-01 4.57039177e-02 6.66538358e-01 -7.44098485e-01 4.57113571e-02 6.61940396e-01 -7.48150229e-01 4.57066596e-02 6.57368183e-01 -7.52223969e-01 4.57142740e-02 6.52737260e-01 -7.56215572e-01 4.57033142e-02 6.48052990e-01 -7.60208130e-01 4.57051098e-02 6.43386006e-01 -7.64203191e-01 4.56902161e-02 6.38711751e-01 -7.68128216e-01 4.56784964e-02 6.33980811e-01 -7.72031724e-01 4.56773378e-02 6.29231513e-01 -7.75918961e-01 4.56620157e-02 6.24455988e-01 -7.79738665e-01 4.56575863e-02 6.19637489e-01 -7.83589840e-01 4.56472039e-02 6.14843011e-01 -7.87374973e-01 4.56298366e-02 6.09981000e-01 -7.91090488e-01 4.56261300e-02 6.05114758e-01 -7.94839919e-01 4.56459075e-02 6.00224376e-01 -7.98520148e-01 4.56500873e-02 5.95331967e-01 -8.02185476e-01 4.56635840e-02 5.90379238e-01 -8.05835247e-01 4.56667766e-02 5.85445940e-01 -8.09464693e-01 4.56557758e-02 5.80459893e-01 -8.13023150e-01 4.56462950e-02 5.75460553e-01 -8.16566765e-01 4.56404686e-02 5.70448339e-01 -8.20087850e-01 4.56321202e-02 5.65395415e-01 -8.23597908e-01 4.56442349e-02 5.60335815e-01 -8.27033758e-01 4.56236303e-02 5.55235207e-01 -8.30448806e-01 4.56256010e-02 5.50130188e-01 -8.33858132e-01 4.56434116e-02 5.45005560e-01 -8.37195098e-01 4.56496254e-02 5.39860487e-01 -8.40536296e-01 4.56379056e-02 5.34702897e-01 -8.43852460e-01 4.56361175e-02 5.29503703e-01 -8.47113252e-01 4.56284061e-02 5.24314582e-01 -8.50341737e-01 4.56306152e-02 5.19086242e-01 -8.53538573e-01 4.56200428e-02 5.13841629e-01 -8.56707633e-01 4.56259586e-02 5.08553028e-01 -8.59824836e-01 4.56318147e-02 5.03278255e-01 -8.62915277e-01 4.56395783e-02 4.97986197e-01 -8.66039217e-01 4.56460044e-02 4.92662072e-01 -8.69066238e-01 4.56459373e-02 4.87301260e-01 -8.72064948e-01 4.56542820e-02 4.81940746e-01 -8.75063837e-01 4.56484668e-02 4.76568192e-01 -8.77992868e-01 4.56460416e-02 4.71191317e-01 -8.80915701e-01 4.56442945e-02 4.65757936e-01 -8.83771420e-01 4.56447564e-02 4.60338891e-01 -8.86571169e-01 4.56514470e-02 4.54870969e-01 -8.89401555e-01 4.56489548e-02 4.49412525e-01 -8.92162740e-01 4.56617512e-02 4.43929970e-01 -8.94917250e-01 4.56748717e-02 4.38435614e-01 -8.97615790e-01 4.56794500e-02 4.32911158e-01 -9.00296032e-01 4.56753634e-02 4.27383244e-01 -9.02910411e-01 4.56749126e-02 4.21825290e-01 -9.05564308e-01 4.56727855e-02 4.16274995e-01 -9.08100247e-01 4.56730165e-02 4.10704225e-01 -9.10673738e-01 4.56712358e-02 4.05103147e-01 -9.13136899e-01 4.56797555e-02 3.99493843e-01 -9.15593505e-01 4.56968918e-02 3.93874019e-01 -9.18030262e-01 4.56984490e-02 3.88222724e-01 -9.20448005e-01 4.56890389e-02 3.82554501e-01 -9.22843635e-01 4.56916913e-02 3.76887530e-01 -9.25143063e-01 4.56966497e-02 3.71202379e-01 -9.27438498e-01 4.56957519e-02 3.65515202e-01 -9.29702461e-01 4.57081608e-02 3.59800994e-01 -9.31903422e-01 4.57114689e-02 3.54069799e-01 -9.34098840e-01 4.57081720e-02 3.48336279e-01 -9.36282039e-01 4.57379520e-02 3.42589766e-01 -9.38395023e-01 4.57415208e-02 3.36815029e-01 -9.40450907e-01 4.57376912e-02 3.31038594e-01 -9.42539930e-01 4.57506478e-02 3.25254172e-01 -9.44557250e-01 4.57587391e-02 3.19441408e-01 -9.46523368e-01 4.57726009e-02 3.13638628e-01 -9.48471546e-01 4.57931235e-02 3.07809561e-01 -9.50357437e-01 4.58009206e-02 3.01979214e-01 -9.52221096e-01 4.58034202e-02 2.96128243e-01 -9.54078496e-01 4.58224155e-02 2.90270269e-01 -9.55859780e-01 4.58551012e-02 2.84392059e-01 -9.57603395e-01 4.58948836e-02 2.78514743e-01 -9.59341943e-01 4.59188037e-02 2.72612065e-01 -9.61038589e-01 4.59349453e-02 2.66721994e-01 -9.62683022e-01 4.59583439e-02 2.60809392e-01 -9.64306414e-01 4.59652767e-02 2.54884720e-01 -9.65872407e-01 4.59812395e-02 2.48946667e-01 -9.67454016e-01 4.59860265e-02 2.43009686e-01 -9.68940556e-01 4.60044257e-02 2.37056434e-01 -9.70401883e-01 4.60389145e-02 2.31107146e-01 -9.71861362e-01 4.60164696e-02 2.25136489e-01 -9.73240137e-01 4.60206233e-02 2.19159216e-01 -9.74573493e-01 4.60470691e-02 2.13176697e-01 -9.75927234e-01 4.60333303e-02 2.07180515e-01 -9.77229297e-01 4.60250527e-02 2.01179311e-01 -9.78457510e-01 4.60234135e-02 1.95172682e-01 -9.79673743e-01 4.60265353e-02 1.89160317e-01 -9.80888367e-01 4.60058972e-02 1.83136716e-01 -9.82019067e-01 4.60190587e-02 1.77112117e-01 -9.83096659e-01 4.60106172e-02 1.71076208e-01 -9.84163642e-01 4.60082181e-02 1.65033013e-01 -9.85217690e-01 4.59890030e-02 1.58984467e-01 -9.86246169e-01 4.59810644e-02 1.52930677e-01 -9.87172186e-01 4.59902436e-02 1.46871999e-01 -9.88069534e-01 4.59679067e-02 1.40806749e-01 -9.88957524e-01 4.59750034e-02 1.34737149e-01 -9.89846468e-01 4.59443331e-02 1.28657132e-01 -9.90657330e-01 4.59540449e-02 1.22578010e-01 -9.91396308e-01 4.59577851e-02 1.16492391e-01 -9.92126584e-01 4.59707566e-02 1.10402107e-01 -9.92852569e-01 4.59675416e-02 1.04308240e-01 -9.93504465e-01 4.59693745e-02 9.82103199e-02 -9.94095325e-01 4.59593162e-02 9.21088606e-02 -9.94724393e-01 4.59522083e-02 8.60032663e-02 -9.95274723e-01 4.59725000e-02 7.98957944e-02 -9.95781124e-01 4.59572151e-02 7.37851411e-02 -9.96254265e-01 4.59582470e-02 6.76695108e-02 -9.96681690e-01 4.59372625e-02 6.15523569e-02 -9.97025967e-01 4.59560789e-02 5.54341339e-02 -9.97420967e-01 4.59727980e-02 4.93125990e-02 -9.97732222e-01 4.59875129e-02 4.31903824e-02 -9.97993588e-01 4.59927917e-02 3.70652676e-02 -9.98239398e-01 4.59793061e-02 3.09396312e-02 -9.98463154e-01 4.60078232e-02 2.48123873e-02 -9.98638630e-01 4.60063964e-02 1.86846536e-02 -9.98774230e-01 4.60098386e-02 1.25556923e-02 -9.98880327e-01 4.60003279e-02 6.42667525e-03 -9.98946965e-01 4.60050702e-02 2.97269697e-04 -9.98951435e-01 4.60158139e-02 -5.83229586e-03 -9.98948932e-01 4.60025743e-02 -1.19613204e-02 -9.98883426e-01 4.60179485e-02 -1.80902407e-02 -9.98778820e-01 4.60168272e-02 -2.42183171e-02 -9.98683870e-01 4.60269228e-02 -3.03456597e-02 -9.98467445e-01 4.60210405e-02 -3.64714079e-02 -9.98286009e-01 4.60147262e-02 -4.25960049e-02 -9.98040676e-01 4.60195281e-02 -4.87191193e-02 -9.97739077e-01 4.60045077e-02 -5.48401289e-02 -9.97464299e-01 4.60363626e-02 -6.09586649e-02 -9.97067869e-01 4.60601635e-02 -6.70748278e-02 -9.96719122e-01 4.60950397e-02 -7.31903985e-02 -9.96258080e-01 4.60678637e-02 -7.93019980e-02 -9.95772600e-01 4.60794009e-02 -8.54080990e-02 -9.95279133e-01 4.60888557e-02 -9.15163755e-02 -9.94770110e-01 4.60691303e-02 -9.76162627e-02 -9.94151235e-01 4.60811034e-02 -1.03714883e-01 -9.93554771e-01 4.60806862e-02 -1.09809674e-01 -9.92856026e-01 4.61371914e-02 -1.15898140e-01 -9.92184818e-01 4.61330451e-02 -1.21985771e-01 -9.91456151e-01 4.61005680e-02 -1.28066301e-01 -9.90665793e-01 4.61352840e-02 -1.34140685e-01 -9.89904046e-01 4.61464152e-02 -1.40211731e-01 -9.89032328e-01 4.61501032e-02 -1.46276027e-01 -9.88181949e-01 4.61682752e-02 -1.52338833e-01 -9.87234473e-01 4.61426005e-02 -1.58395350e-01 -9.86279070e-01 4.61141169e-02 -1.64442465e-01 -9.85288024e-01 4.61161882e-02 -1.70486420e-01 -9.84305203e-01 4.60919850e-02 -1.76523611e-01 -9.83237028e-01 4.61148843e-02 -1.82552323e-01 -9.82115924e-01 4.60940376e-02 -1.88577756e-01 -9.80976403e-01 4.60528396e-02 -1.94590494e-01 -9.79839087e-01 4.60303910e-02 -2.00602189e-01 -9.78623331e-01 4.60400656e-02 -2.06600681e-01 -9.77336645e-01 4.60309573e-02 -2.12603346e-01 -9.76050019e-01 4.60213572e-02 -2.18581811e-01 -9.74746525e-01 4.60269824e-02 -2.24558339e-01 -9.73366320e-01 4.60389219e-02 -2.30529130e-01 -9.71971273e-01 4.60401550e-02 -2.36488611e-01 -9.70574558e-01 4.60767187e-02 -2.42435157e-01 -9.69103873e-01 4.60934155e-02 -2.48380944e-01 -9.67563272e-01 4.60687205e-02 -2.54308105e-01 -9.66030121e-01 4.60708104e-02 -2.60235786e-01 -9.64477062e-01 4.60758470e-02 -2.66146660e-01 -9.62855279e-01 4.60834950e-02 -2.72047520e-01 -9.61171448e-01 4.60716970e-02 -2.77942896e-01 -9.59511638e-01 4.60847616e-02 -2.83821255e-01 -9.57758725e-01 4.60725985e-02 -2.89689243e-01 -9.56029534e-01 4.60856855e-02 -2.95548648e-01 -9.54238713e-01 4.60751653e-02 -3.01396549e-01 -9.52376127e-01 4.60998528e-02 -3.07243347e-01 -9.50511932e-01 4.60994840e-02 -3.13075423e-01 -9.48640347e-01 4.60855886e-02 -3.18880945e-01 -9.46694553e-01 4.60858420e-02 -3.24684918e-01 -9.44730103e-01 4.60715406e-02 -3.30476105e-01 -9.42692697e-01 4.60886844e-02 -3.36254179e-01 -9.40665662e-01 4.61024120e-02 -3.42025280e-01 -9.38561380e-01 4.61172611e-02 -3.47775400e-01 -9.36495602e-01 4.61240709e-02 -3.53508383e-01 -9.34319556e-01 4.61497270e-02 -3.59237432e-01 -9.32124972e-01 4.61539552e-02 -3.64958316e-01 -9.29910600e-01 4.61650342e-02 -3.70645016e-01 -9.27646637e-01 4.61589247e-02 -3.76326412e-01 -9.25323129e-01 4.61441688e-02 -3.82003933e-01 -9.23038065e-01 4.61151078e-02 -3.87662113e-01 -9.20671880e-01 4.61077392e-02 -3.93312275e-01 -9.18253064e-01 4.61145155e-02 -3.98929119e-01 -9.15811777e-01 4.61653098e-02 -4.04538602e-01 -9.13355887e-01 4.61717211e-02 -4.10139889e-01 -9.10896242e-01 4.61564511e-02 -4.15711552e-01 -9.08324063e-01 4.61395495e-02 -4.21302527e-01 -9.05790389e-01 4.61494736e-02 -4.26839769e-01 -9.03162241e-01 4.61521819e-02 -4.32378948e-01 -9.00519013e-01 4.61428873e-02 -4.37893301e-01 -8.97884011e-01 4.61399145e-02 -4.43385422e-01 -8.95152450e-01 4.61486615e-02 -4.48871583e-01 -8.92403126e-01 4.61371653e-02 -4.54356462e-01 -8.89683485e-01 4.61152419e-02 -4.59800094e-01 -8.86846721e-01 4.61131260e-02 -4.65219468e-01 -8.84020329e-01 4.61363681e-02 -4.70647305e-01 -8.81159961e-01 4.61354144e-02 -4.76053357e-01 -8.78236175e-01 4.61440571e-02 -4.81426984e-01 -8.75307977e-01 4.61377017e-02 -4.86792207e-01 -8.72361600e-01 4.61351722e-02 -4.92133558e-01 -8.69320095e-01 4.61292341e-02 -4.97440904e-01 -8.66285861e-01 4.61483933e-02 -5.02760649e-01 -8.63205194e-01 4.61496525e-02 -5.08038282e-01 -8.60114217e-01 4.61608544e-02 -5.13292909e-01 -8.56999457e-01 4.61728200e-02 -5.18541753e-01 -8.53837669e-01 4.61769849e-02 -5.23778081e-01 -8.50647449e-01 4.62016240e-02 -5.28988838e-01 -8.47405136e-01 4.61923853e-02 -5.34192502e-01 -8.44106853e-01 4.61774170e-02 -5.39345086e-01 -8.40838492e-01 4.61849235e-02 -5.44496477e-01 -8.37502837e-01 4.61879037e-02 -5.49621344e-01 -8.34151924e-01 4.61970456e-02 -5.54730892e-01 -8.30752194e-01 4.62049656e-02 -5.59826791e-01 -8.27333570e-01 4.62068766e-02 -5.64876020e-01 -8.23863745e-01 4.62194309e-02 -5.69941223e-01 -8.20423007e-01 4.62205112e-02 -5.74951649e-01 -8.16915929e-01 4.62111384e-02 -5.79950154e-01 -8.13353419e-01 4.62380871e-02 -5.84945679e-01 -8.09774697e-01 4.62544449e-02 -5.89904308e-01 -8.06180716e-01 4.62650098e-02 -5.94825447e-01 -8.02538216e-01 4.62702326e-02 -5.99733651e-01 -7.98871100e-01 4.62677740e-02 -6.04616761e-01 -7.95181274e-01 4.62733135e-02 -6.09486938e-01 -7.91424334e-01 4.63015288e-02 -6.14336729e-01 -7.87719786e-01 4.62993309e-02 -6.19174063e-01 -7.83922255e-01 4.63105626e-02 -6.23966753e-01 -7.80097842e-01 4.62982021e-02 -6.28731787e-01 -7.76273370e-01 4.63127159e-02 -6.33480847e-01 -7.72379339e-01 4.63155881e-02 -6.38227403e-01 -7.68476903e-01 4.63195331e-02 -6.42901361e-01 -7.64567077e-01 4.63280901e-02 -6.47615433e-01 -7.60584950e-01 4.63508144e-02 -6.52254522e-01 -7.56609619e-01 4.63560149e-02 -6.56885505e-01 -7.52595484e-01 4.64087017e-02 -6.61498368e-01 -7.48554111e-01 4.64055017e-02 -6.66057885e-01 -7.44465649e-01 4.63779196e-02 -6.70642436e-01 -7.40367174e-01 4.63836938e-02 -6.75170064e-01 -7.36255109e-01 4.63974290e-02 -6.79667532e-01 -7.32103348e-01 4.64107133e-02 -6.84113801e-01 -7.27881730e-01 4.64165509e-02 -6.88588321e-01 -7.23687530e-01 4.63985540e-02 -6.93011642e-01 -7.19450474e-01 4.64002155e-02 -6.97402537e-01 -7.15189338e-01 4.64087166e-02 -7.01784968e-01 -7.10897148e-01 4.64134365e-02 -7.06144035e-01 -7.06549227e-01 4.64101546e-02 -7.10447669e-01 -7.02228129e-01 4.64086086e-02 -7.14784384e-01 -6.97855115e-01 4.64064628e-02 -7.19044685e-01 -6.93457246e-01 4.64247502e-02 -7.23255396e-01 -6.89006388e-01 4.64477688e-02 -7.27487981e-01 -6.84575081e-01 4.64538038e-02 -7.31657743e-01 -6.80082858e-01 4.64455076e-02 -7.35809505e-01 -6.75577879e-01 4.64177392e-02 -7.39946842e-01 -6.71050131e-01 4.64248955e-02 -7.44073868e-01 -6.66522682e-01 4.64337841e-02 -7.48132229e-01 -6.61922932e-01 4.64524552e-02 -7.52198100e-01 -6.57351553e-01 4.64560501e-02 -7.56186724e-01 -6.52717590e-01 4.64786366e-02 -7.60180235e-01 -6.48042440e-01 4.64786738e-02 -7.64164686e-01 -6.43367112e-01 4.64894958e-02 -7.68087208e-01 -6.38694644e-01 4.64724079e-02 -7.71987796e-01 -6.33958697e-01 4.64924239e-02 -7.75873959e-01 -6.29209757e-01 4.65008952e-02 -7.79700100e-01 -6.24433398e-01 4.65288423e-02 -7.83554733e-01 -6.19620740e-01 4.65733819e-02 -7.87322521e-01 -6.14817023e-01 4.65876646e-02 -7.91052520e-01 -6.09953284e-01 4.65883724e-02 -7.94797182e-01 -6.05090261e-01 4.65810485e-02 -7.98480630e-01 -6.00201011e-01 4.65322472e-02 -8.02140415e-01 -5.95313251e-01 4.65215333e-02 -8.05791736e-01 -5.90362430e-01 4.65557501e-02 -8.09424639e-01 -5.85422099e-01 4.66013476e-02 -8.12972963e-01 -5.80432951e-01 4.67111729e-02 -8.16493452e-01 -5.75418174e-01 4.70052175e-02 -8.20009649e-01 -5.70394874e-01 4.71272208e-02 -8.23522747e-01 -5.65365016e-01 4.66009565e-02 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. 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. 0. -8.86380434e-01 -4.60250437e-01 4.99978662e-02 -8.89276505e-01 -4.54838187e-01 4.76938710e-02 -8.92086804e-01 -4.49398726e-01 4.70700078e-02 -8.94856989e-01 -4.43915486e-01 4.68271412e-02 -8.97555828e-01 -4.38410997e-01 4.67267185e-02 -9.00235832e-01 -4.32887018e-01 4.67118621e-02 -9.02850151e-01 -4.27367657e-01 4.67272103e-02 -9.05502617e-01 -4.21808511e-01 4.68038283e-02 -9.08040822e-01 -4.16245759e-01 4.68876772e-02 -9.10605788e-01 -4.10678089e-01 4.68433052e-02 -9.13074791e-01 -4.05080914e-01 4.67733964e-02 -9.15533721e-01 -3.99472684e-01 4.67001051e-02 -9.17971611e-01 -3.93853962e-01 4.66739126e-02 -9.20393109e-01 -3.88206780e-01 4.66472954e-02 -9.22782302e-01 -3.82539481e-01 4.66239937e-02 -9.25091684e-01 -3.76879841e-01 4.66231667e-02 -9.27397668e-01 -3.71188521e-01 4.66484055e-02 -9.29654121e-01 -3.65506172e-01 4.67089638e-02 -9.31850612e-01 -3.59784305e-01 4.67901006e-02 -9.34038103e-01 -3.54052901e-01 4.69181314e-02 -9.36225235e-01 -3.48318815e-01 4.68949713e-02 -9.38347101e-01 -3.42579961e-01 4.67704050e-02 -9.40401912e-01 -3.36803705e-01 4.67234328e-02 -9.42498267e-01 -3.31032753e-01 4.67089824e-02 -9.44512784e-01 -3.25240582e-01 4.67073955e-02 -9.46480572e-01 -3.19440335e-01 4.66892682e-02 -9.48428571e-01 -3.13631058e-01 4.67149876e-02 -9.50313509e-01 -3.07801425e-01 4.67668846e-02 -9.52161074e-01 -3.01972330e-01 4.67511527e-02 -9.54039395e-01 -2.96122670e-01 4.66964319e-02 -9.55815613e-01 -2.90265799e-01 4.66708355e-02 -9.57595706e-01 -2.84388661e-01 4.66817543e-02 -9.59325433e-01 -2.78512299e-01 4.67317104e-02 -9.61013913e-01 -2.72614866e-01 4.67616171e-02 -9.62638557e-01 -2.66711146e-01 4.67889942e-02 -9.64277506e-01 -2.60799468e-01 4.67675403e-02 -9.65825617e-01 -2.54880816e-01 4.67442609e-02 -9.67432380e-01 -2.48946220e-01 4.67209816e-02 -9.68914628e-01 -2.43014216e-01 4.67076600e-02 -9.70379293e-01 -2.37056792e-01 4.67401147e-02 -9.71833348e-01 -2.31101289e-01 4.67925183e-02 -9.73213017e-01 -2.25131974e-01 4.68893982e-02 -9.74535584e-01 -2.19157487e-01 4.69165742e-02 -9.75906909e-01 -2.13174373e-01 4.69153784e-02 -9.77196574e-01 -2.07179159e-01 4.68766503e-02 -9.78425145e-01 -2.01183334e-01 4.68199290e-02 -9.79646862e-01 -1.95171803e-01 4.67743762e-02 -9.80861127e-01 -1.89162672e-01 4.67751250e-02 -9.82004464e-01 -1.83136895e-01 4.67866659e-02 -9.83066082e-01 -1.77108809e-01 4.67575863e-02 -9.84116733e-01 -1.71072826e-01 4.67659645e-02 -9.85194147e-01 -1.65030211e-01 4.67622466e-02 -9.86210763e-01 -1.58984438e-01 4.67632338e-02 -9.87144589e-01 -1.52927428e-01 4.67705391e-02 -9.88018394e-01 -1.46868303e-01 4.67692688e-02 -9.88915861e-01 -1.40803277e-01 4.68005873e-02 -9.89803493e-01 -1.34732515e-01 4.68351319e-02 -9.90609348e-01 -1.28656611e-01 4.68494296e-02 -9.91352022e-01 -1.22578211e-01 4.67811860e-02 -9.92080212e-01 -1.16491720e-01 4.68216166e-02 -9.92803156e-01 -1.10402122e-01 4.68711480e-02 -9.93448675e-01 -1.04309760e-01 4.70062196e-02 -9.94016945e-01 -9.82114449e-02 4.73562889e-02 -9.94574070e-01 -9.21108052e-02 4.80300672e-02 -9.95214045e-01 -8.60034376e-02 4.63903658e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.98318672e-01 -3.70584279e-02 4.45697419e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.97659087e-01 6.75383806e-02 1.07213836e-02 -9.97225583e-01 7.36585110e-02 1.07426839e-02 -9.96760726e-01 7.97800869e-02 1.01566389e-02 -9.96250868e-01 8.58925655e-02 1.04520172e-02 -9.95704591e-01 9.20035765e-02 1.05678961e-02 -9.95112896e-01 9.81148630e-02 1.03987381e-02 -9.94536221e-01 1.04220249e-01 1.01523967e-02 -9.93873119e-01 1.10320792e-01 1.00914612e-02 -9.93156970e-01 1.16417728e-01 9.97532718e-03 -9.92424011e-01 1.22509331e-01 1.00954631e-02 -9.91674960e-01 1.28593445e-01 1.01798531e-02 -9.90875363e-01 1.34679481e-01 1.01528652e-02 -9.89986360e-01 1.40755743e-01 1.02125183e-02 -9.89153206e-01 1.46829113e-01 1.01596843e-02 -9.88241434e-01 1.52894080e-01 1.00757461e-02 -9.87278461e-01 1.58955231e-01 1.00447675e-02 -9.86290693e-01 1.65010154e-01 1.00343470e-02 -9.85265136e-01 1.71063721e-01 1.00467186e-02 -9.84145463e-01 1.77106917e-01 1.00244302e-02 -9.83071685e-01 1.83131158e-01 1.00599676e-02 -9.81911063e-01 1.89164191e-01 1.00999614e-02 -9.80708778e-01 1.95183873e-01 1.01651251e-02 -9.79488194e-01 2.01193780e-01 1.01917991e-02 -9.78251755e-01 2.07207277e-01 1.01675019e-02 -9.77010846e-01 2.13203207e-01 1.01139816e-02 -9.75638092e-01 2.19195604e-01 1.00929989e-02 -9.74323571e-01 2.25179121e-01 1.00675263e-02 -9.72880840e-01 2.31146961e-01 1.00889867e-02 -9.71428931e-01 2.37115055e-01 1.01143420e-02 -9.69963074e-01 2.43075550e-01 1.01114893e-02 -9.68481898e-01 2.49017119e-01 1.00749005e-02 -9.66952801e-01 2.54953712e-01 1.00711649e-02 -9.65325177e-01 2.60888845e-01 1.00711444e-02 -9.63763595e-01 2.66808897e-01 1.00886459e-02 -9.62068200e-01 2.72702932e-01 1.05367294e-02 -9.60402191e-01 2.78605551e-01 1.06127812e-02 -9.58648324e-01 2.84487903e-01 1.06045594e-02 -9.56881404e-01 2.90374488e-01 1.06540779e-02 -9.55071032e-01 2.96246469e-01 1.00816628e-02 -9.53269184e-01 3.02102655e-01 1.00838412e-02 -9.51392353e-01 3.07938844e-01 1.00804912e-02 -9.49456334e-01 3.13771695e-01 1.00814942e-02 -9.47504044e-01 3.19583952e-01 1.00611905e-02 -9.45538461e-01 3.25401753e-01 1.01048294e-02 -9.43564534e-01 3.31196129e-01 1.01025430e-02 -9.41463530e-01 3.36976320e-01 1.00625996e-02 -9.39426363e-01 3.42755169e-01 1.00557664e-02 -9.37253714e-01 3.48502338e-01 1.00775156e-02 -9.35105145e-01 3.54244530e-01 1.00722406e-02 -9.32919204e-01 3.59977126e-01 1.00875422e-02 -9.30706501e-01 3.65706146e-01 1.00257695e-02 -9.28445578e-01 3.71403873e-01 1.00829517e-02 -9.26169276e-01 3.77091736e-01 1.00683300e-02 -9.23808217e-01 3.82776737e-01 1.00858072e-02 -9.21434581e-01 3.88422161e-01 1.00727910e-02 -9.19084966e-01 3.94074529e-01 1.00830831e-02 -9.16644037e-01 3.99706841e-01 1.00571727e-02 -9.14125085e-01 4.05329436e-01 9.98081826e-03 -9.11617875e-01 4.10921037e-01 1.00394133e-02 -9.09137607e-01 4.16503578e-01 1.00481361e-02 -9.06497598e-01 4.22095031e-01 1.00983325e-02 -9.03943717e-01 4.27636206e-01 1.00795915e-02 -9.01271701e-01 4.33172017e-01 1.03059513e-02 -8.98596525e-01 4.38690662e-01 1.06675774e-02 -8.95868123e-01 4.44182515e-01 1.08347991e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.69984865e-01 4.92949873e-01 1.12544596e-02 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. 0. 0. -8.34761500e-01 5.50510406e-01 1.05611086e-02 -8.31366658e-01 5.55620015e-01 1.07366154e-02 -8.27962458e-01 5.60716808e-01 1.04977489e-02 -8.24526250e-01 5.65790832e-01 1.03264591e-02 -8.21024835e-01 5.70849955e-01 1.01688225e-02 -8.17514658e-01 5.75891554e-01 1.00852745e-02 -8.13949108e-01 5.80896974e-01 1.00517944e-02 -8.10373664e-01 5.85883915e-01 1.00388164e-02 -8.06774437e-01 5.90817511e-01 1.00462707e-02 -8.03127825e-01 5.95781267e-01 1.00869620e-02 -7.99457669e-01 6.00690246e-01 1.01147359e-02 -7.95762718e-01 6.05576813e-01 1.00834221e-02 -7.91999459e-01 6.10456169e-01 1.00342603e-02 -7.88291812e-01 6.15312219e-01 1.00251315e-02 -7.84484446e-01 6.20113432e-01 1.00306487e-02 -7.80660510e-01 6.24923170e-01 1.00176018e-02 -7.76820004e-01 6.29718900e-01 1.00228265e-02 -7.72932410e-01 6.34476781e-01 1.00277774e-02 -7.69025922e-01 6.39174461e-01 1.00386627e-02 -7.65101135e-01 6.43903017e-01 1.00239851e-02 -7.61117637e-01 6.48570657e-01 1.00229234e-02 -7.57114530e-01 6.53216660e-01 1.00167654e-02 -7.53132284e-01 6.57856643e-01 1.00135552e-02 -7.49032438e-01 6.62473500e-01 1.00088445e-02 -7.44961679e-01 6.67068422e-01 9.99745261e-03 -7.40867555e-01 6.71617389e-01 9.98613425e-03 -7.36721814e-01 6.76147699e-01 9.96391103e-03 -7.32565701e-01 6.80652976e-01 9.97424219e-03 -7.28387237e-01 6.85149014e-01 9.96691827e-03 -7.24137127e-01 6.89593256e-01 9.97624081e-03 -7.19933808e-01 6.94049001e-01 9.99116711e-03 -7.15650082e-01 6.98448956e-01 9.99458227e-03 -7.11333930e-01 7.02836812e-01 1.00055356e-02 -7.07016885e-01 7.07157314e-01 1.00168157e-02 -7.02648580e-01 7.11498380e-01 1.00036580e-02 -6.98285222e-01 7.15797722e-01 1.00258058e-02 -6.93862617e-01 7.20063686e-01 1.00543639e-02 -6.89441442e-01 7.24322736e-01 1.00491615e-02 -6.85013115e-01 7.28506863e-01 1.00359228e-02 -6.80519521e-01 7.32700050e-01 1.00091835e-02 -6.76009953e-01 7.36884475e-01 9.99028794e-03 -6.71477914e-01 7.40977049e-01 9.95895825e-03 -6.66894376e-01 7.45104134e-01 9.93861817e-03 -6.62333071e-01 7.49197841e-01 9.93758813e-03 -6.57706141e-01 7.53242552e-01 9.92046949e-03 -6.53073013e-01 7.57284045e-01 9.91639774e-03 -6.48424029e-01 7.61234641e-01 9.92788095e-03 -6.43754959e-01 7.65219569e-01 9.93580557e-03 -6.39028430e-01 7.69167364e-01 9.91421752e-03 -6.34286404e-01 7.73073077e-01 9.90740769e-03 -6.29531860e-01 7.76935816e-01 9.88056138e-03 -6.24755383e-01 7.80765653e-01 9.88562871e-03 -6.19972289e-01 7.84627497e-01 9.87892225e-03 -6.15127981e-01 7.88394690e-01 9.88416281e-03 -6.10308290e-01 7.92146444e-01 9.87400115e-03 -6.05428517e-01 7.95882642e-01 9.86293890e-03 -6.00537777e-01 7.99562693e-01 9.85505432e-03 -5.95589519e-01 8.03231120e-01 9.83555522e-03 -5.90676248e-01 8.06875229e-01 9.82339215e-03 -5.85692704e-01 8.10524046e-01 9.83917341e-03 -5.80707610e-01 8.14094841e-01 9.82968323e-03 -5.75702727e-01 8.17616105e-01 9.83486325e-03 -5.70677280e-01 8.21125627e-01 9.82922036e-03 -5.65640032e-01 8.24652076e-01 9.82334185e-03 -5.60550869e-01 8.28102231e-01 9.82743222e-03 -5.55487096e-01 8.31521451e-01 9.81657673e-03 -5.50372958e-01 8.34924102e-01 9.80747305e-03 -5.45240343e-01 8.38270307e-01 9.78065468e-03 -5.40059447e-01 8.41575623e-01 9.76108387e-03 -5.34900486e-01 8.44918251e-01 9.72423982e-03 -5.29693782e-01 8.48146617e-01 9.70999058e-03 -5.24497747e-01 8.51387739e-01 9.70777776e-03 -5.19264877e-01 8.54574263e-01 9.67718195e-03 -5.14006138e-01 8.57740760e-01 9.64453444e-03 -5.08743465e-01 8.60895634e-01 9.62451845e-03 -5.03425062e-01 8.63999963e-01 9.61490441e-03 -4.98131752e-01 8.67100537e-01 9.54530947e-03 -4.92790639e-01 8.70106220e-01 9.53128934e-03 -4.87429827e-01 8.73113155e-01 9.52662993e-03 -4.82068568e-01 8.76121402e-01 9.51865688e-03 -4.76684183e-01 8.79062295e-01 9.51098651e-03 -4.71302420e-01 8.81976366e-01 9.51311830e-03 -4.65877414e-01 8.84820998e-01 9.52711981e-03 -4.60439950e-01 8.87678087e-01 9.52067226e-03 -4.54969347e-01 8.90456021e-01 9.52316076e-03 -4.49509412e-01 8.93274963e-01 9.51998495e-03 -4.44021970e-01 8.95983636e-01 9.47500579e-03 -4.38507974e-01 8.98683071e-01 9.46741085e-03 -4.32979196e-01 9.01356280e-01 9.44361463e-03 -4.27451968e-01 9.04032350e-01 9.44568496e-03 -4.21884209e-01 9.06638205e-01 9.45485011e-03 -4.16328520e-01 9.09179688e-01 9.47652943e-03 -4.10749674e-01 9.11752224e-01 9.47703701e-03 -4.05142486e-01 9.14267123e-01 9.47423093e-03 -3.99526328e-01 9.16727066e-01 9.44540743e-03 -3.93891275e-01 9.19156611e-01 9.45700333e-03 -3.88239324e-01 9.21543419e-01 9.47943702e-03 -3.82569879e-01 9.23899651e-01 9.48205497e-03 -3.76898587e-01 9.26248789e-01 9.46781877e-03 -3.71210009e-01 9.28522289e-01 9.44240950e-03 -3.65507871e-01 9.30805922e-01 9.65388864e-03 -3.59789699e-01 9.33017015e-01 9.65256710e-03 -3.54057431e-01 9.35211778e-01 9.65048559e-03 -3.48317116e-01 9.37348306e-01 9.37239826e-03 -3.42553496e-01 9.39454734e-01 9.38726962e-03 -3.36785138e-01 9.41563368e-01 9.37968493e-03 -3.30993980e-01 9.43589926e-01 9.44444537e-03 -3.25197339e-01 9.45615530e-01 9.45453905e-03 -3.19391102e-01 9.47585285e-01 9.44763981e-03 -3.13577086e-01 9.49533641e-01 9.42306779e-03 -3.07735473e-01 9.51417506e-01 9.41868592e-03 -3.01896632e-01 9.53340471e-01 9.42992326e-03 -2.96044707e-01 9.55147982e-01 9.41246003e-03 -2.90174931e-01 9.56977785e-01 9.40829609e-03 -2.84296423e-01 9.58718181e-01 9.41647403e-03 -2.78415471e-01 9.60428596e-01 9.40899365e-03 -2.72512168e-01 9.62135792e-01 9.40982904e-03 -2.66600132e-01 9.63787496e-01 9.45743825e-03 -2.60681957e-01 9.65389132e-01 9.45615955e-03 -2.54756033e-01 9.67000902e-01 9.38495155e-03 -2.48818472e-01 9.68504667e-01 9.35794413e-03 -2.42867976e-01 9.70027506e-01 9.35247168e-03 -2.36913934e-01 9.71504211e-01 9.36095975e-03 -2.30950728e-01 9.72947359e-01 9.34096891e-03 -2.24972382e-01 9.74337935e-01 9.33598354e-03 -2.18990937e-01 9.75705564e-01 9.33481567e-03 -2.13002101e-01 9.77023959e-01 9.33659915e-03 -2.06998229e-01 9.78323400e-01 9.30718612e-03 -2.00991347e-01 9.79563951e-01 9.32942703e-03 -1.94977939e-01 9.80781436e-01 9.31477174e-03 -1.88961118e-01 9.81936216e-01 9.30955820e-03 -1.82927758e-01 9.83128548e-01 9.31727607e-03 -1.76895604e-01 9.84199047e-01 9.30876192e-03 -1.70853779e-01 9.85307217e-01 9.42058675e-03 -1.64802164e-01 9.86305594e-01 9.42912325e-03 -1.58750966e-01 9.87287164e-01 9.32378415e-03 -1.52685821e-01 9.88261461e-01 9.31938644e-03 -1.46623760e-01 9.89169240e-01 9.31535661e-03 -1.40549168e-01 9.90043163e-01 9.36430041e-03 -1.34471804e-01 9.90922153e-01 9.31754336e-03 -1.28389597e-01 9.91684854e-01 9.30121075e-03 -1.22301571e-01 9.92474318e-01 9.29488614e-03 -1.16210259e-01 9.93177950e-01 9.26664099e-03 -1.10112831e-01 9.93883133e-01 9.28596593e-03 -1.04012638e-01 9.94589388e-01 9.28238779e-03 -9.79080424e-02 9.95169163e-01 9.33575351e-03 -9.17987823e-02 9.95736837e-01 9.33975633e-03 -8.56879205e-02 9.96315420e-01 9.27104428e-03 -7.95733184e-02 9.96808171e-01 9.26134177e-03 -7.34558403e-02 9.97292221e-01 9.24598239e-03 -6.73353225e-02 9.97716188e-01 9.25904792e-03 -6.12127036e-02 9.98100579e-01 9.26388055e-03 -5.50871678e-02 9.98492777e-01 9.28729586e-03 -4.89592925e-02 9.98764694e-01 9.26283561e-03 -4.28301133e-02 9.99026716e-01 9.26962495e-03 -3.66985388e-02 9.99270320e-01 9.26907640e-03 -3.05666719e-02 9.99497592e-01 9.24009178e-03 -2.44330633e-02 9.99714017e-01 9.23641212e-03 -1.82984378e-02 9.99809265e-01 9.21226293e-03 -1.21631930e-02 9.99912620e-01 9.19517130e-03 -6.02776092e-03 9.99977410e-01 9.19293519e-03 1.08032087e-04 9.99981523e-01 9.19237919e-03 6.24396978e-03 9.99977887e-01 9.16304439e-03 1.23796584e-02 9.99913514e-01 9.15019866e-03 1.85148120e-02 9.99804199e-01 9.13518853e-03 2.46491674e-02 9.99713182e-01 9.16775875e-03 3.07824519e-02 9.99492526e-01 9.13763791e-03 3.69142890e-02 9.99267399e-01 9.18696355e-03 4.30456139e-02 9.99023080e-01 9.14334692e-03 4.91744764e-02 9.98758256e-01 9.15575773e-03 5.53020686e-02 9.98439074e-01 9.19382833e-03 6.14269339e-02 9.98094559e-01 9.16530006e-03 6.75493926e-02 9.97698963e-01 9.18597821e-03 7.36705810e-02 9.97270226e-01 9.19833221e-03 7.97877684e-02 9.96799469e-01 9.17854719e-03 8.59018564e-02 9.96292531e-01 9.19958390e-03 9.20140669e-02 9.95733559e-01 9.19660367e-03 9.81221274e-02 9.95115936e-01 9.19178687e-03 1.04226962e-01 9.94528890e-01 9.17884707e-03 1.10326715e-01 9.93865907e-01 9.25588422e-03 1.16421059e-01 9.93152261e-01 9.24273208e-03 1.22512974e-01 9.92419422e-01 9.25844535e-03 1.28600344e-01 9.91664767e-01 9.29399952e-03 1.34682953e-01 9.90838110e-01 9.26390383e-03 1.40759096e-01 9.89983141e-01 9.24296118e-03 1.46829665e-01 9.89105523e-01 9.33689065e-03 1.52897581e-01 9.88218546e-01 9.30551626e-03 1.58958271e-01 9.87260878e-01 9.27179586e-03 1.65012673e-01 9.86265719e-01 9.28939879e-03 1.71059176e-01 9.85201240e-01 9.26366635e-03 1.77100927e-01 9.84155118e-01 9.29116830e-03 1.83138639e-01 9.83025610e-01 9.27980337e-03 1.89167440e-01 9.81895208e-01 9.34232119e-03 1.95187300e-01 9.80705440e-01 9.36858915e-03 2.01201990e-01 9.79486763e-01 9.37606301e-03 2.07206950e-01 9.78239119e-01 9.34387371e-03 2.13206634e-01 9.76981938e-01 9.33960080e-03 2.19198093e-01 9.75658655e-01 9.30232182e-03 2.25180313e-01 9.74299788e-01 9.28204693e-03 2.31155500e-01 9.72865939e-01 9.30229947e-03 2.37119541e-01 9.71424699e-01 9.27370973e-03 2.43075281e-01 9.69959378e-01 9.24590882e-03 2.49021471e-01 9.68470335e-01 9.23537649e-03 2.54963428e-01 9.66903031e-01 9.16480366e-03 2.60892540e-01 9.65322793e-01 9.11422633e-03 2.66809195e-01 9.63738024e-01 9.08955466e-03 2.72712588e-01 9.62046802e-01 9.17963777e-03 2.78620273e-01 9.60406065e-01 9.08332039e-03 2.84500033e-01 9.58635330e-01 9.14777815e-03 2.90386856e-01 9.56884921e-01 9.09296982e-03 2.96254814e-01 9.55064893e-01 9.08813719e-03 3.02109867e-01 9.53258455e-01 9.07193217e-03 3.07946026e-01 9.51391876e-01 9.07603558e-03 3.13777179e-01 9.49451208e-01 9.07010864e-03 3.19593608e-01 9.47509468e-01 9.06785298e-03 3.25403273e-01 9.45536852e-01 9.11813509e-03 3.31199884e-01 9.43558395e-01 9.10770893e-03 3.36982489e-01 9.41482782e-01 9.10778437e-03 3.42762947e-01 9.39413786e-01 9.11148079e-03 3.48508239e-01 9.37255979e-01 9.11988504e-03 3.54252785e-01 9.35119927e-01 9.10481252e-03 3.59983057e-01 9.32924688e-01 9.10233706e-03 3.65713030e-01 9.30719912e-01 9.09321848e-03 3.71402711e-01 9.28441226e-01 9.13895760e-03 3.77098471e-01 9.26145852e-01 9.11043677e-03 3.82775873e-01 9.23809171e-01 9.11688246e-03 3.88430059e-01 9.21449959e-01 9.16226674e-03 3.94090027e-01 9.19062674e-01 9.16271005e-03 3.99712980e-01 9.16624129e-01 9.16300807e-03 4.05332506e-01 9.14137244e-01 9.14178416e-03 4.10934269e-01 9.11620975e-01 9.15368274e-03 4.16507751e-01 9.09135163e-01 9.15031042e-03 4.22094375e-01 9.06504631e-01 9.15089343e-03 4.27641571e-01 9.03935730e-01 9.10878927e-03 4.33178276e-01 9.01276946e-01 9.12866369e-03 4.38711375e-01 8.98640513e-01 9.12603550e-03 4.44206119e-01 8.95898759e-01 9.13615711e-03 4.49698776e-01 8.93147528e-01 9.11826733e-03 4.55180407e-01 8.90368581e-01 9.12625156e-03 4.60625350e-01 8.87585998e-01 9.09532886e-03 4.66058493e-01 8.84745121e-01 9.09861922e-03 4.71473545e-01 8.81839216e-01 9.11345240e-03 4.76890892e-01 8.78917694e-01 9.11648478e-03 4.82283026e-01 8.75981152e-01 9.11173690e-03 4.87652749e-01 8.73032272e-01 9.11955256e-03 4.92990583e-01 8.70029032e-01 9.11842380e-03 4.98312712e-01 8.66951585e-01 9.11426544e-03 5.03637433e-01 8.63908827e-01 9.11865942e-03 5.08910596e-01 8.60817969e-01 9.10692941e-03 5.14180183e-01 8.57652903e-01 9.09425970e-03 5.19432008e-01 8.54480088e-01 9.09611769e-03 5.24665594e-01 8.51299822e-01 9.09118820e-03 5.29893637e-01 8.48058045e-01 9.10117757e-03 5.35062015e-01 8.44782472e-01 9.11585707e-03 5.40262580e-01 8.41516674e-01 9.14957840e-03 5.45404136e-01 8.38131011e-01 9.15887114e-03 5.50535142e-01 8.34779680e-01 9.10556689e-03 5.55654228e-01 8.31378520e-01 9.14058741e-03 5.60751677e-01 8.27956378e-01 9.15018190e-03 5.65802395e-01 8.24520648e-01 9.18420777e-03 5.70872903e-01 8.21031451e-01 9.18287970e-03 5.75901151e-01 8.17524612e-01 9.11431853e-03 5.80906093e-01 8.13953936e-01 9.11723636e-03 5.85890830e-01 8.10370088e-01 9.11821797e-03 5.90825140e-01 8.06780815e-01 9.11767036e-03 5.95787525e-01 8.03130448e-01 9.13330074e-03 6.00696802e-01 7.99467206e-01 9.13679413e-03 6.05582774e-01 7.95747995e-01 9.14540887e-03 6.10462189e-01 7.92004108e-01 9.15220007e-03 6.15318060e-01 7.88291693e-01 9.16877668e-03 6.20118976e-01 7.84491718e-01 9.20554996e-03 6.24947011e-01 7.80653417e-01 9.19008628e-03 6.29722059e-01 7.76823103e-01 9.17899236e-03 6.34482801e-01 7.72934437e-01 9.16369818e-03 6.39180243e-01 7.69028187e-01 9.16362181e-03 6.43908441e-01 7.65101612e-01 9.17348452e-03 6.48576677e-01 7.61115909e-01 9.18062497e-03 6.53218210e-01 7.57109523e-01 9.18479729e-03 6.57855451e-01 7.53129065e-01 9.22390539e-03 6.62474096e-01 7.49032378e-01 9.19650309e-03 6.67080224e-01 7.44969249e-01 9.19374824e-03 6.71622157e-01 7.40862191e-01 9.20011476e-03 6.76143885e-01 7.36710966e-01 9.22831241e-03 6.80660427e-01 7.32561827e-01 9.19491891e-03 6.85160935e-01 7.28374243e-01 9.21378657e-03 6.89590991e-01 7.24137962e-01 9.21474304e-03 6.94050610e-01 7.19932377e-01 9.20460001e-03 6.98450923e-01 7.15659618e-01 9.22219642e-03 7.02836692e-01 7.11320698e-01 9.24511813e-03 7.07157612e-01 7.07017958e-01 9.21739172e-03 7.11509585e-01 7.02651799e-01 9.21522174e-03 7.15802133e-01 6.98270500e-01 9.24842432e-03 7.20075428e-01 6.93862975e-01 9.20802727e-03 7.24327087e-01 6.89443290e-01 9.22728423e-03 7.28510261e-01 6.85015142e-01 9.23664309e-03 7.32714772e-01 6.80521548e-01 9.20874253e-03 7.36894310e-01 6.76009357e-01 9.19235963e-03 7.40983069e-01 6.71479046e-01 9.19794105e-03 7.45107412e-01 6.66889012e-01 9.20704287e-03 7.49206722e-01 6.62333965e-01 9.21657030e-03 7.53252506e-01 6.57706439e-01 9.31482483e-03 7.57287741e-01 6.53068483e-01 9.35104489e-03 7.61239946e-01 6.48424804e-01 9.21817776e-03 7.65229642e-01 6.43756390e-01 9.22214519e-03 7.69161761e-01 6.39027536e-01 9.22864676e-03 7.73067653e-01 6.34288192e-01 9.23942495e-03 7.76947320e-01 6.29533648e-01 9.22942907e-03 7.80770183e-01 6.24755144e-01 9.22971033e-03 7.84632385e-01 6.19972110e-01 9.21145733e-03 7.88404584e-01 6.15126014e-01 9.21259262e-03 7.92150855e-01 6.10304058e-01 9.19934642e-03 7.95885026e-01 6.05427504e-01 9.22658667e-03 7.99567640e-01 6.00537896e-01 9.21583921e-03 8.03235412e-01 5.95592737e-01 9.20461304e-03 8.06877673e-01 5.90675533e-01 9.23765730e-03 8.10525656e-01 5.85693359e-01 9.24185012e-03 8.14092517e-01 5.80706656e-01 9.24575701e-03 8.17618549e-01 5.75701773e-01 9.23314318e-03 8.21136892e-01 5.70676446e-01 9.23100580e-03 8.24665487e-01 5.65641701e-01 9.23269149e-03 8.28104377e-01 5.60552239e-01 9.23672784e-03 8.31527650e-01 5.55469632e-01 9.15052369e-03 8.34924221e-01 5.50372541e-01 9.34742950e-03 8.38268518e-01 5.45241535e-01 9.16248746e-03 8.41590047e-01 5.40060341e-01 9.14154109e-03 8.44914615e-01 5.34899116e-01 9.22506861e-03 8.48144233e-01 5.29691041e-01 9.22489353e-03 8.51395607e-01 5.24495840e-01 9.31731239e-03 8.54588032e-01 5.19262075e-01 9.32237040e-03 8.57753217e-01 5.14009953e-01 9.31828935e-03 8.60905588e-01 5.08740187e-01 9.35575925e-03 8.63997459e-01 5.03427804e-01 9.35822353e-03 8.67087722e-01 4.98127103e-01 9.35841165e-03 8.70104730e-01 4.92789805e-01 9.37387999e-03 8.73122334e-01 4.87437248e-01 9.36875772e-03 8.76111507e-01 4.82073814e-01 9.36067011e-03 8.79052997e-01 4.76685256e-01 9.36956238e-03 8.81965220e-01 4.71301496e-01 9.37094074e-03 8.84825289e-01 4.65873182e-01 9.37861763e-03 8.87676179e-01 4.60439622e-01 9.37071070e-03 8.90457749e-01 4.54971522e-01 9.36945528e-03 8.93273890e-01 4.49500531e-01 9.37113445e-03 8.95982862e-01 4.44009513e-01 9.36164521e-03 8.98682714e-01 4.38510329e-01 9.37056635e-03 9.01354849e-01 4.32980567e-01 9.37332399e-03 9.04030025e-01 4.27452058e-01 9.37998202e-03 9.06632066e-01 4.21886414e-01 9.39349364e-03 9.09176469e-01 4.16328877e-01 9.38284956e-03 9.11755443e-01 4.10750091e-01 9.38241091e-03 9.14265156e-01 4.05141652e-01 9.38454643e-03 9.16723788e-01 3.99525911e-01 9.40529164e-03 9.19152677e-01 3.93885255e-01 9.40455776e-03 9.21539068e-01 3.88243765e-01 9.40680783e-03 9.23891008e-01 3.82569969e-01 9.42289364e-03 9.26245868e-01 3.76898348e-01 9.43969749e-03 9.28522110e-01 3.71209472e-01 9.44476575e-03 9.30799782e-01 3.65502775e-01 9.45983548e-03 9.33014631e-01 3.59792441e-01 9.47171729e-03 9.35207844e-01 3.54057640e-01 9.49486624e-03 9.37349617e-01 3.48316699e-01 9.52221639e-03 9.39451873e-01 3.42554003e-01 9.51862894e-03 9.41558421e-01 3.36784869e-01 9.53098945e-03 9.43589270e-01 3.30995649e-01 9.53156315e-03 9.45611596e-01 3.25197399e-01 9.52348486e-03 9.47580636e-01 3.19392949e-01 9.51137580e-03 9.49529529e-01 3.13582569e-01 9.51513089e-03 9.51417863e-01 3.07739049e-01 9.50992014e-03 9.53336835e-01 3.01892191e-01 9.50393081e-03 9.55143213e-01 2.96036690e-01 9.53034777e-03 9.56976295e-01 2.90170461e-01 9.52005479e-03 9.58720505e-01 2.84300119e-01 9.48215183e-03 9.60431099e-01 2.78415501e-01 9.47985519e-03 9.62137759e-01 2.72515953e-01 9.48121212e-03 9.63789642e-01 2.66602248e-01 9.53046605e-03 9.65383708e-01 2.60683715e-01 9.53415595e-03 9.67003822e-01 2.54760653e-01 9.54478886e-03 9.68503356e-01 2.48826548e-01 9.54684429e-03 9.70021129e-01 2.42870495e-01 9.54478607e-03 9.71496344e-01 2.36921281e-01 9.55127738e-03 9.72944856e-01 2.30952203e-01 9.54450201e-03 9.74345446e-01 2.24973604e-01 9.53787938e-03 9.75726306e-01 2.18991905e-01 9.55841225e-03 9.77030039e-01 2.13006109e-01 9.56936926e-03 9.78314757e-01 2.07004398e-01 9.57952160e-03 9.79551136e-01 2.00993836e-01 9.57506616e-03 9.80771899e-01 1.94981813e-01 9.56403464e-03 9.81934547e-01 1.88961968e-01 9.54746641e-03 9.83127236e-01 1.82930261e-01 9.54903848e-03 9.84190583e-01 1.76895663e-01 9.55553260e-03 9.85311627e-01 1.70854002e-01 9.56409238e-03 9.86308873e-01 1.64802924e-01 9.56312474e-03 9.87286627e-01 1.58751875e-01 9.55923740e-03 9.88260746e-01 1.52687341e-01 9.55094956e-03 9.89176214e-01 1.46623284e-01 9.55568533e-03 9.90037382e-01 1.40550613e-01 9.55970492e-03 9.90927875e-01 1.34473100e-01 9.55235492e-03 9.91684973e-01 1.28390580e-01 9.54051036e-03 9.92442667e-01 1.22303411e-01 9.52543039e-03 9.93166566e-01 1.16210520e-01 9.56926309e-03 9.93881345e-01 1.10113792e-01 9.56384372e-03 9.94590044e-01 1.04013458e-01 9.57288872e-03 9.95161891e-01 9.79083776e-02 9.57259256e-03 9.95769262e-01 9.18020308e-02 9.58773680e-03 9.96315002e-01 8.56892616e-02 9.60798282e-03 9.96806979e-01 7.95759782e-02 9.61162150e-03 9.97290790e-01 7.34580606e-02 9.59747750e-03 9.97719646e-01 6.73385710e-02 9.59601626e-03 9.98093188e-01 6.12132736e-02 9.60362609e-03 9.98494565e-01 5.50889745e-02 9.60883964e-03 9.98763978e-01 4.89630513e-02 9.74696316e-03 9.99024093e-01 4.28327210e-02 9.75789409e-03 9.99268174e-01 3.67025211e-02 9.75435134e-03 9.99496400e-01 3.05692144e-02 9.63714719e-03 9.99714434e-01 2.44356953e-02 9.62987915e-03 9.99802947e-01 1.83015037e-02 9.68234520e-03 9.99915898e-01 1.21658929e-02 9.63060372e-03 9.99975681e-01 6.03044825e-03 9.63010080e-03 9.99979794e-01 -1.05269668e-04 9.64072719e-03 9.99975741e-01 -6.24108687e-03 9.62830801e-03 9.99911547e-01 -1.23764742e-02 9.64910258e-03 9.99800801e-01 -1.85116027e-02 9.67242103e-03 9.99714077e-01 -2.46458258e-02 9.67588183e-03 9.99492705e-01 -3.07787228e-02 9.67807323e-03 9.99267578e-01 -3.69111113e-02 9.68691520e-03 9.99023318e-01 -4.30428647e-02 9.67143383e-03 9.98759806e-01 -4.91711721e-02 9.68691241e-03 9.98451173e-01 -5.52993678e-02 9.69228800e-03 9.98092353e-01 -6.14249744e-02 9.55814775e-03 9.97716069e-01 -6.75464943e-02 9.68612637e-03 9.97279346e-01 -7.36679137e-02 9.72152408e-03 9.96807218e-01 -7.97851980e-02 9.58181545e-03 9.96304691e-01 -8.59016404e-02 9.57282539e-03 9.95763004e-01 -9.20130461e-02 9.57001187e-03 9.95120227e-01 -9.81190354e-02 9.57684685e-03 9.94549155e-01 -1.04224235e-01 9.57325101e-03 9.93879497e-01 -1.10322580e-01 9.57474019e-03 9.93162811e-01 -1.16421893e-01 9.56889894e-03 9.92428362e-01 -1.22515157e-01 9.62537993e-03 9.91679370e-01 -1.28598452e-01 9.62471683e-03 9.90875483e-01 -1.34683579e-01 9.63937212e-03 9.89991188e-01 -1.40759349e-01 9.68590565e-03 9.89162147e-01 -1.46830902e-01 9.69156623e-03 9.88246322e-01 -1.52896836e-01 9.68765467e-03 9.87283468e-01 -1.58960223e-01 9.60610528e-03 9.86294806e-01 -1.65012702e-01 9.60852019e-03 9.85263467e-01 -1.71062887e-01 9.61287040e-03 9.84151244e-01 -1.77105680e-01 9.68338922e-03 9.83074367e-01 -1.83138520e-01 9.67839547e-03 9.81916010e-01 -1.89167425e-01 9.70817730e-03 9.80713725e-01 -1.95187032e-01 9.70794447e-03 9.79493678e-01 -2.01205656e-01 9.70252976e-03 9.78257537e-01 -2.07209796e-01 9.69961565e-03 9.77015436e-01 -2.13204592e-01 9.69788339e-03 9.75644410e-01 -2.19200537e-01 9.69774369e-03 9.74326849e-01 -2.25183591e-01 9.68648028e-03 9.72885549e-01 -2.31152967e-01 9.68166906e-03 9.71433640e-01 -2.37117797e-01 9.67907440e-03 9.69967782e-01 -2.43079871e-01 9.67372395e-03 9.68484521e-01 -2.49019593e-01 9.67708230e-03 9.66943264e-01 -2.54960001e-01 9.67029203e-03 9.65329051e-01 -2.60895342e-01 9.66686569e-03 9.63756502e-01 -2.66811699e-01 9.65468958e-03 9.62073445e-01 -2.72710711e-01 9.66996420e-03 9.60408807e-01 -2.78615415e-01 9.67223477e-03 9.58653629e-01 -2.84499466e-01 9.66355950e-03 9.56875503e-01 -2.90383607e-01 9.65362694e-03 9.55074310e-01 -2.96248138e-01 9.64727253e-03 9.53259468e-01 -3.02104980e-01 9.67026409e-03 9.51393604e-01 -3.07943940e-01 9.68459342e-03 9.49460268e-01 -3.13774079e-01 9.69308894e-03 9.47508454e-01 -3.19587409e-01 9.69838630e-03 9.45539653e-01 -3.25405300e-01 9.67780035e-03 9.43561912e-01 -3.31198394e-01 9.69604868e-03 9.41481709e-01 -3.36973518e-01 9.70506389e-03 9.39423501e-01 -3.42756808e-01 9.69203096e-03 9.37258601e-01 -3.48504424e-01 9.68564302e-03 9.35123146e-01 -3.54245901e-01 9.70280729e-03 9.32940602e-01 -3.59978855e-01 9.70879104e-03 9.30723429e-01 -3.65707189e-01 9.73049086e-03 9.28444505e-01 -3.71396154e-01 9.74147581e-03 9.26144302e-01 -3.77093524e-01 9.75953694e-03 9.23806548e-01 -3.82768601e-01 9.78228077e-03 9.21452999e-01 -3.88424456e-01 9.72360000e-03 9.19059515e-01 -3.94084156e-01 9.72565729e-03 9.16622877e-01 -3.99710506e-01 9.67817660e-03 9.14143384e-01 -4.05325532e-01 9.67875030e-03 9.11622465e-01 -4.10933286e-01 9.65627749e-03 9.09133136e-01 -4.16506231e-01 9.64297913e-03 9.06501591e-01 -4.22096997e-01 9.60122887e-03 9.03931975e-01 -4.27645624e-01 9.60888527e-03 9.01266277e-01 -4.33173209e-01 9.61274188e-03 8.98638844e-01 -4.38708186e-01 9.64092091e-03 8.95899355e-01 -4.44204450e-01 9.63500142e-03 8.93148005e-01 -4.49697107e-01 9.64620989e-03 8.90366793e-01 -4.55177724e-01 9.63134319e-03 8.87572348e-01 -4.60622579e-01 9.59793199e-03 8.84742081e-01 -4.66054887e-01 9.50021483e-03 8.81836653e-01 -4.71481532e-01 9.49889980e-03 8.78912747e-01 -4.76883143e-01 9.48271528e-03 8.75978589e-01 -4.82278675e-01 9.46951658e-03 8.73028338e-01 -4.87643480e-01 9.46801901e-03 8.70015979e-01 -4.92987424e-01 9.46637429e-03 8.66949737e-01 -4.98300761e-01 9.59389843e-03 8.63901258e-01 -5.03626764e-01 9.58178099e-03 8.60814929e-01 -5.08905053e-01 9.57482588e-03 8.57649267e-01 -5.14177680e-01 9.57996864e-03 8.54476154e-01 -5.19426644e-01 9.55688767e-03 8.51294696e-01 -5.24659514e-01 9.55742970e-03 8.48041773e-01 -5.29883862e-01 9.56554525e-03 8.44791114e-01 -5.35063028e-01 9.54408292e-03 8.41506004e-01 -5.40258586e-01 9.53023788e-03 8.38133693e-01 -5.45398533e-01 9.55498964e-03 8.34790289e-01 -5.50527573e-01 9.55277868e-03 8.31394315e-01 -5.55648863e-01 9.52809397e-03 8.27973664e-01 -5.60745001e-01 9.53777973e-03 8.24533820e-01 -5.65794885e-01 9.53327958e-03 8.21025014e-01 -5.70866287e-01 9.51447431e-03 8.17492068e-01 -5.75888634e-01 9.51477140e-03 8.13947678e-01 -5.80894232e-01 9.51433089e-03 8.10393095e-01 -5.85882425e-01 9.54460166e-03 8.06751668e-01 -5.90818524e-01 9.51648131e-03 8.03106487e-01 -5.95778704e-01 9.51768272e-03 7.99442589e-01 -6.00690484e-01 9.49575193e-03 7.95752287e-01 -6.05578542e-01 9.49542131e-03 7.92003751e-01 -6.10455692e-01 9.48610436e-03 7.88280129e-01 -6.15309656e-01 9.50388145e-03 7.84494936e-01 -6.20112240e-01 9.51485615e-03 7.80640721e-01 -6.24944627e-01 9.52390023e-03 7.76811957e-01 -6.29713953e-01 9.49726440e-03 7.72928834e-01 -6.34467602e-01 9.47583281e-03 7.69022286e-01 -6.39178038e-01 9.49073397e-03 7.65089810e-01 -6.43900931e-01 9.48186591e-03 7.61097670e-01 -6.48574054e-01 9.49693006e-03 7.57103622e-01 -6.53221786e-01 9.49597079e-03 7.53115714e-01 -6.57857299e-01 9.50028468e-03 7.49033451e-01 -6.62466943e-01 9.50801838e-03 7.44976461e-01 -6.67074621e-01 9.49550141e-03 7.40850508e-01 -6.71616435e-01 9.50128026e-03 7.36707747e-01 -6.76142037e-01 9.48739517e-03 7.32552171e-01 -6.80651784e-01 9.48401634e-03 7.28376627e-01 -6.85156703e-01 9.47296899e-03 7.24135816e-01 -6.89589679e-01 9.45225265e-03 7.19925880e-01 -6.94045067e-01 9.56499763e-03 7.15655863e-01 -6.98447824e-01 9.56695434e-03 7.11321831e-01 -7.02831388e-01 9.56329796e-03 7.07012892e-01 -7.07151592e-01 9.42642614e-03 7.02650249e-01 -7.11497307e-01 9.43307672e-03 6.98267579e-01 -7.15793669e-01 9.43425298e-03 6.93866730e-01 -7.20066071e-01 9.41664167e-03 6.89437747e-01 -7.24313617e-01 9.40981414e-03 6.85003817e-01 -7.28504658e-01 9.39575396e-03 6.80516541e-01 -7.32708335e-01 9.39397793e-03 6.76004887e-01 -7.36883879e-01 9.37847048e-03 6.71471775e-01 -7.40984976e-01 9.39560775e-03 6.66893065e-01 -7.45100498e-01 9.38713551e-03 6.62329912e-01 -7.49193966e-01 9.38238949e-03 6.57702088e-01 -7.53246605e-01 9.41271614e-03 6.53068483e-01 -7.57268786e-01 9.40039195e-03 6.48420274e-01 -7.61242688e-01 9.39929765e-03 6.43742681e-01 -7.65231729e-01 9.35368240e-03 6.39024377e-01 -7.69147813e-01 9.33932699e-03 6.34284794e-01 -7.73054063e-01 9.32501070e-03 6.29535139e-01 -7.76953340e-01 9.33439098e-03 6.24751508e-01 -7.80773163e-01 9.34889819e-03 6.19969428e-01 -7.84618139e-01 9.32417903e-03 6.15128875e-01 -7.88403332e-01 9.31760203e-03 6.10291898e-01 -7.92135835e-01 9.31027159e-03 6.05416894e-01 -7.95879483e-01 9.31942835e-03 6.00524545e-01 -7.99569964e-01 9.34003200e-03 5.95590591e-01 -8.03236127e-01 9.33157653e-03 5.90669811e-01 -8.06872845e-01 9.33782198e-03 5.85689247e-01 -8.10518801e-01 9.33736097e-03 5.80710590e-01 -8.14070046e-01 9.32264980e-03 5.75705111e-01 -8.17614913e-01 9.28888191e-03 5.70673704e-01 -8.21148515e-01 9.28351935e-03 5.65633833e-01 -8.24653149e-01 9.27673653e-03 5.60550690e-01 -8.28099251e-01 9.28915758e-03 5.55470347e-01 -8.31523299e-01 9.25598573e-03 5.50361931e-01 -8.34916651e-01 9.25174821e-03 5.45230925e-01 -8.38247240e-01 9.24350508e-03 5.40064037e-01 -8.41585279e-01 9.23729688e-03 5.34897804e-01 -8.44906926e-01 9.20590200e-03 5.29692888e-01 -8.48151028e-01 9.23224073e-03 5.24488389e-01 -8.51413190e-01 9.17625893e-03 5.19260585e-01 -8.54594290e-01 9.12478380e-03 5.14004946e-01 -8.57766449e-01 9.10574570e-03 5.08733094e-01 -8.60916615e-01 9.09845624e-03 5.03425896e-01 -8.63999426e-01 9.10360552e-03 4.98122036e-01 -8.67080033e-01 9.10098664e-03 4.92788851e-01 -8.70108128e-01 9.03638266e-03 4.87436116e-01 -8.73133421e-01 9.02942847e-03 4.82078344e-01 -8.76111090e-01 8.99785850e-03 4.76684213e-01 -8.79051983e-01 8.99991114e-03 4.71300215e-01 -8.81970644e-01 8.97275750e-03 4.65873748e-01 -8.84829938e-01 8.97313468e-03 4.60439444e-01 -8.87680233e-01 8.96650087e-03 4.54973757e-01 -8.90469015e-01 8.98121204e-03 4.49501604e-01 -8.93276930e-01 8.94069299e-03 4.44013953e-01 -8.95986736e-01 8.95147584e-03 4.38508928e-01 -8.98686230e-01 8.95560905e-03 4.32979107e-01 -9.01362002e-01 8.94596800e-03 4.27452952e-01 -9.04035747e-01 8.94927885e-03 4.21883851e-01 -9.06633377e-01 8.94055981e-03 4.16323483e-01 -9.09182668e-01 8.98871105e-03 4.10747647e-01 -9.11757231e-01 8.96320306e-03 4.05141085e-01 -9.14269149e-01 9.04646143e-03 3.99524003e-01 -9.16727185e-01 9.06580780e-03 3.93891007e-01 -9.19156611e-01 8.97766184e-03 3.88232946e-01 -9.21543539e-01 8.97307694e-03 3.82565796e-01 -9.23909962e-01 9.04838275e-03 3.76894057e-01 -9.26248372e-01 9.09732562e-03 3.71208668e-01 -9.28530574e-01 8.99363682e-03 3.65512222e-01 -9.30805802e-01 8.93726014e-03 3.59789580e-01 -9.33022141e-01 8.94046389e-03 3.54055911e-01 -9.35216010e-01 8.93722847e-03 3.48314613e-01 -9.37339723e-01 8.93826224e-03 3.42554450e-01 -9.39456344e-01 9.04189236e-03 3.36782455e-01 -9.41566706e-01 8.95248726e-03 3.30989867e-01 -9.43593025e-01 8.99624638e-03 3.25194508e-01 -9.45621014e-01 9.02057532e-03 3.19390386e-01 -9.47596908e-01 9.04815737e-03 3.13576221e-01 -9.49547231e-01 9.08397604e-03 3.07735115e-01 -9.51422930e-01 9.07404907e-03 3.01891565e-01 -9.53340530e-01 9.08230618e-03 2.96036839e-01 -9.55166876e-01 9.15385317e-03 2.90172517e-01 -9.56960976e-01 9.13507398e-03 2.84293354e-01 -9.58706141e-01 9.33566317e-03 2.78405994e-01 -9.60402489e-01 1.00182323e-02 2.72508472e-01 -9.62098300e-01 1.01224473e-02 2.66600490e-01 -9.63753939e-01 1.01197744e-02 2.60681480e-01 -9.65373516e-01 9.95157752e-03 2.54752189e-01 -9.66957450e-01 9.70192626e-03 2.48814866e-01 -9.68500912e-01 9.86048859e-03 2.42867485e-01 -9.70009446e-01 9.84640606e-03 2.36911550e-01 -9.71480012e-01 9.97601077e-03 2.30947927e-01 -9.72910047e-01 1.04460698e-02 0. 0. 0. 2.18990639e-01 -9.75673199e-01 1.02393134e-02 2.13000864e-01 -9.76995707e-01 1.04882671e-02 2.06999406e-01 -9.78291929e-01 9.79736075e-03 2.00990364e-01 -9.79549646e-01 9.21559148e-03 0. 0. 0. 1.88955799e-01 -9.81939614e-01 9.47754085e-03 1.82927951e-01 -9.83078361e-01 9.67095327e-03 1.76894426e-01 -9.84177887e-01 1.01164561e-02 1.70852110e-01 -9.85244691e-01 1.00779310e-02 1.64803103e-01 -9.86273944e-01 1.00515094e-02 1.58747628e-01 -9.87256587e-01 9.95425135e-03 1.52686521e-01 -9.88222957e-01 9.90272220e-03 1.46618277e-01 -9.89140749e-01 9.76631138e-03 1.40546381e-01 -9.90010262e-01 9.64535959e-03 1.34468868e-01 -9.90897059e-01 9.34148114e-03 1.28385231e-01 -9.91685510e-01 9.08922218e-03 1.22302562e-01 -9.92454350e-01 9.12251417e-03 1.16207942e-01 -9.93169725e-01 9.03688092e-03 1.10110655e-01 -9.93885338e-01 8.99753999e-03 1.04010917e-01 -9.94583666e-01 9.14410129e-03 9.79071781e-02 -9.95176911e-01 9.12383664e-03 9.18002278e-02 -9.95756269e-01 9.11086053e-03 8.56878906e-02 -9.96313870e-01 9.11758095e-03 7.95730650e-02 -9.96806979e-01 9.11689177e-03 7.34554753e-02 -9.97290909e-01 9.09292791e-03 6.73334897e-02 -9.97723579e-01 8.98423418e-03 6.12104796e-02 -9.98102784e-01 9.05047264e-03 5.50858490e-02 -9.98493135e-01 9.10041016e-03 4.89587784e-02 -9.98764873e-01 9.11003910e-03 4.28279452e-02 -9.99028206e-01 8.97975359e-03 3.66980918e-02 -9.99272943e-01 9.08824243e-03 3.05657145e-02 -9.99497533e-01 9.08742286e-03 2.44317316e-02 -9.99717474e-01 9.01435316e-03 1.82977524e-02 -9.99813557e-01 9.07171704e-03 1.21620931e-02 -9.99920309e-01 8.96566641e-03 6.02635788e-03 -9.99979854e-01 8.97128694e-03 -1.08744811e-04 -9.99981225e-01 9.07184090e-03 -6.24453370e-03 -9.99976575e-01 9.07420367e-03 -1.23806363e-02 -9.99917865e-01 8.96611903e-03 -1.85158644e-02 -9.99804735e-01 8.98197480e-03 -2.46498641e-02 -9.99716401e-01 8.99011083e-03 -3.07834651e-02 -9.99496520e-01 8.97550210e-03 -3.69160511e-02 -9.99271393e-01 8.96254554e-03 -4.30471301e-02 -9.99026954e-01 8.96524172e-03 -4.91758250e-02 -9.98762965e-01 8.97912402e-03 -5.53037822e-02 -9.98448968e-01 8.98966566e-03 -6.14284240e-02 -9.98097241e-01 8.97214189e-03 -6.75517768e-02 -9.97705936e-01 9.00522433e-03 -7.36730471e-02 -9.97278810e-01 8.97846371e-03 -7.97903612e-02 -9.96806085e-01 8.96811299e-03 -8.59041959e-02 -9.96299863e-01 8.97886232e-03 -9.20157880e-02 -9.95725691e-01 9.04086232e-03 -9.81223211e-02 -9.95123029e-01 9.08149034e-03 -1.04226425e-01 -9.94513154e-01 9.08760447e-03 -1.10327139e-01 -9.93872344e-01 9.08145960e-03 -1.16423823e-01 -9.93162990e-01 9.10174474e-03 -1.22515537e-01 -9.92430270e-01 9.08868946e-03 -1.28603458e-01 -9.91673946e-01 9.10858158e-03 -1.34687349e-01 -9.90852952e-01 9.05297883e-03 -1.40763864e-01 -9.89995122e-01 8.97581223e-03 -1.46833986e-01 -9.89141047e-01 9.00076516e-03 -1.52901039e-01 -9.88241553e-01 8.99671856e-03 -1.58963904e-01 -9.87280548e-01 8.99387244e-03 -1.65015742e-01 -9.86289322e-01 8.99235252e-03 -1.71063006e-01 -9.85240877e-01 8.98357015e-03 -1.77105576e-01 -9.84144509e-01 8.96858331e-03 -1.83141544e-01 -9.83043492e-01 9.04460065e-03 -1.89173967e-01 -9.81914043e-01 9.01810545e-03 -1.95192724e-01 -9.80718255e-01 8.99719074e-03 -2.01205522e-01 -9.79498625e-01 8.98671150e-03 -2.07214281e-01 -9.78257477e-01 8.99092946e-03 -2.13214174e-01 -9.77013946e-01 8.92338157e-03 -2.19201744e-01 -9.75650370e-01 8.91917758e-03 -2.25183591e-01 -9.74327683e-01 8.93060025e-03 -2.31161341e-01 -9.72882330e-01 9.02027823e-03 -2.37121895e-01 -9.71437395e-01 9.03452747e-03 -2.43081972e-01 -9.69971299e-01 9.03607905e-03 -2.49023855e-01 -9.68484223e-01 9.05006658e-03 -2.54964352e-01 -9.66931164e-01 9.00663342e-03 -2.60897368e-01 -9.65331852e-01 9.06325970e-03 -2.66808212e-01 -9.63763773e-01 9.06578545e-03 -2.72715867e-01 -9.62075591e-01 9.08606686e-03 -2.78619498e-01 -9.60411668e-01 9.07317828e-03 -2.84500390e-01 -9.58658338e-01 9.06653889e-03 -2.90392429e-01 -9.56897259e-01 9.08019207e-03 -2.96255380e-01 -9.55070436e-01 9.07829031e-03 -3.02111506e-01 -9.53265727e-01 9.09027830e-03 -3.07943881e-01 -9.51396883e-01 9.06846765e-03 -3.13777149e-01 -9.49454069e-01 9.05912463e-03 -3.19589883e-01 -9.47511435e-01 9.05296113e-03 -3.25410217e-01 -9.45542216e-01 9.05474927e-03 -3.31200272e-01 -9.43564355e-01 9.05097276e-03 -3.36980939e-01 -9.41481411e-01 9.06533841e-03 -3.42763424e-01 -9.39418316e-01 9.08129476e-03 -3.48508120e-01 -9.37258303e-01 9.10608005e-03 -3.54251832e-01 -9.35115814e-01 9.22167115e-03 -3.59981418e-01 -9.32924509e-01 9.21995938e-03 -3.65711659e-01 -9.30716813e-01 9.21524782e-03 -3.71404231e-01 -9.28448021e-01 9.21545830e-03 -3.77097249e-01 -9.26162541e-01 9.14203096e-03 -3.82777184e-01 -9.23813045e-01 9.12572350e-03 -3.88430864e-01 -9.21444476e-01 9.15254746e-03 -3.94083798e-01 -9.19080913e-01 9.25691612e-03 -3.99718553e-01 -9.16636050e-01 9.28339642e-03 -4.05332446e-01 -9.14133370e-01 9.31227207e-03 -4.10928756e-01 -9.11621451e-01 9.31396428e-03 -4.16505367e-01 -9.09138441e-01 9.30848159e-03 -4.22101170e-01 -9.06501710e-01 9.18290950e-03 -4.27644342e-01 -9.03943837e-01 9.16716643e-03 -4.33182448e-01 -9.01280820e-01 9.16570984e-03 -4.38711256e-01 -8.98643017e-01 9.16616712e-03 -4.44207013e-01 -8.95907700e-01 9.15947277e-03 -4.49699461e-01 -8.93141150e-01 9.17100534e-03 -4.55183536e-01 -8.90371144e-01 9.15917382e-03 -4.60628271e-01 -8.87593210e-01 9.16297827e-03 -4.66057450e-01 -8.84745538e-01 9.18725226e-03 -4.71470326e-01 -8.81838799e-01 9.18512512e-03 -4.76890862e-01 -8.78914416e-01 9.17028822e-03 -4.82282132e-01 -8.75980496e-01 9.17950086e-03 -4.87650931e-01 -8.73031974e-01 9.17245634e-03 -4.92995590e-01 -8.70028496e-01 9.16612707e-03 -4.98307586e-01 -8.66951048e-01 9.18336399e-03 -5.03631413e-01 -8.63911092e-01 9.18188971e-03 -5.08912861e-01 -8.60819638e-01 9.17798746e-03 -5.14179647e-01 -8.57652903e-01 9.18051973e-03 -5.19428074e-01 -8.54478300e-01 9.18979663e-03 -5.24660587e-01 -8.51296961e-01 9.20326728e-03 -5.29891312e-01 -8.48050654e-01 9.21223126e-03 -5.35060704e-01 -8.44784319e-01 9.22045019e-03 -5.40260315e-01 -8.41512740e-01 9.22379456e-03 -5.45401156e-01 -8.38128924e-01 9.23708547e-03 -5.50531626e-01 -8.34778547e-01 9.25613660e-03 -5.55651248e-01 -8.31378520e-01 9.24212206e-03 -5.60749888e-01 -8.27958047e-01 9.24268551e-03 -5.65797448e-01 -8.24521840e-01 9.25064180e-03 -5.70875406e-01 -8.21029127e-01 9.24407039e-03 -5.75897276e-01 -8.17516506e-01 9.25041549e-03 -5.80903530e-01 -8.13951194e-01 9.25183017e-03 -5.85889637e-01 -8.10372233e-01 9.26305540e-03 -5.90819538e-01 -8.06769490e-01 9.62032471e-03 -5.95781505e-01 -8.03122580e-01 9.61830188e-03 -6.00689411e-01 -7.99456894e-01 9.59351379e-03 -6.05579793e-01 -7.95744896e-01 9.30501707e-03 -6.10457778e-01 -7.92002618e-01 9.31113586e-03 -6.15315914e-01 -7.88288295e-01 9.36415792e-03 -6.20115221e-01 -7.84489751e-01 9.36423335e-03 -6.24951005e-01 -7.80649900e-01 9.35979374e-03 -6.29720330e-01 -7.76820719e-01 9.36302356e-03 -6.34478629e-01 -7.72933602e-01 9.37018264e-03 -6.39175832e-01 -7.69027233e-01 9.39348061e-03 -6.43904865e-01 -7.65101671e-01 9.40550864e-03 -6.48571908e-01 -7.61113822e-01 9.41897836e-03 -6.53216422e-01 -7.57103324e-01 9.44041088e-03 -6.57854319e-01 -7.53129601e-01 9.46509931e-03 -6.62470400e-01 -7.49031425e-01 9.47566703e-03 -6.67078555e-01 -7.44971454e-01 9.46989376e-03 -6.71618223e-01 -7.40857005e-01 9.50165838e-03 -6.76143706e-01 -7.36711502e-01 9.49880946e-03 -6.80653811e-01 -7.32556224e-01 9.50220879e-03 -6.85157657e-01 -7.28374898e-01 9.49436147e-03 -6.89585745e-01 -7.24135935e-01 9.49922670e-03 -6.94049120e-01 -7.19931304e-01 9.48989484e-03 -6.98445857e-01 -7.15654254e-01 9.91041958e-03 -7.02831507e-01 -7.11317897e-01 9.88476258e-03 -7.07151890e-01 -7.07016051e-01 9.89519991e-03 -7.11500108e-01 -7.02646792e-01 9.89963207e-03 -7.15798676e-01 -6.98264360e-01 9.49769747e-03 -7.20065594e-01 -6.93863869e-01 9.49930772e-03 -7.24322915e-01 -6.89442158e-01 9.51512717e-03 -7.28507698e-01 -6.85013592e-01 9.51903779e-03 -7.32717454e-01 -6.80519700e-01 9.49914567e-03 -7.36888647e-01 -6.76009715e-01 9.49214399e-03 -7.40977943e-01 -6.71477020e-01 9.49308835e-03 -7.45103776e-01 -6.66887283e-01 9.49589629e-03 -7.49204218e-01 -6.62331581e-01 9.91241261e-03 -7.53246307e-01 -6.57704473e-01 9.93701909e-03 -7.57276952e-01 -6.53070092e-01 9.92394984e-03 -7.61235714e-01 -6.48423314e-01 9.55403969e-03 -7.65228689e-01 -6.43753946e-01 9.56739299e-03 -7.69153476e-01 -6.39027357e-01 9.57481936e-03 -7.73060322e-01 -6.34287775e-01 9.58570279e-03 -7.76945591e-01 -6.29531205e-01 9.59607121e-03 -7.80766249e-01 -6.24754310e-01 9.62302648e-03 -7.84624696e-01 -6.19971573e-01 9.62337200e-03 -7.88400710e-01 -6.15126848e-01 9.63678118e-03 -7.92133510e-01 -6.10305905e-01 9.65202227e-03 -7.95880020e-01 -6.05426431e-01 9.66609642e-03 -7.99562991e-01 -6.00534558e-01 9.62102599e-03 -8.03226590e-01 -5.95589936e-01 9.61648766e-03 -8.06873143e-01 -5.90675175e-01 9.61032510e-03 -8.10519755e-01 -5.85692465e-01 9.62593779e-03 -8.14083517e-01 -5.80705702e-01 9.66259185e-03 -8.17613184e-01 -5.75700104e-01 9.71706863e-03 -8.21143508e-01 -5.70674002e-01 9.79867019e-03 -8.24629784e-01 -5.65624952e-01 9.86380130e-03 -8.28054607e-01 -5.60547233e-01 1.02551151e-02 -8.31485629e-01 -5.55456758e-01 9.96892247e-03 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. 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. -8.90446305e-01 -4.54969466e-01 1.03953145e-02 -8.93215179e-01 -4.49497283e-01 1.08479979e-02 -8.95948529e-01 -4.44005281e-01 1.04867490e-02 -8.98673773e-01 -4.38511759e-01 1.02524599e-02 -9.01342332e-01 -4.32979137e-01 1.01891644e-02 -9.04016495e-01 -4.27448660e-01 1.01389121e-02 -9.06609416e-01 -4.21890914e-01 1.00382622e-02 -9.09169018e-01 -4.16323692e-01 9.93271917e-03 -9.11752880e-01 -4.10748333e-01 9.81376227e-03 -9.14264739e-01 -4.05142158e-01 9.78621189e-03 -9.16723013e-01 -3.99526536e-01 9.76465363e-03 -9.19153392e-01 -3.93894643e-01 9.77789331e-03 -9.21544135e-01 -3.88244033e-01 9.77357291e-03 -9.23876822e-01 -3.82570207e-01 9.75518208e-03 -9.26245570e-01 -3.76904041e-01 9.79755726e-03 -9.28511262e-01 -3.71210396e-01 9.82432161e-03 -9.30800319e-01 -3.65510076e-01 9.86078288e-03 -9.33005691e-01 -3.59792948e-01 9.93590150e-03 -9.35195744e-01 -3.54056835e-01 1.00191440e-02 -9.37337756e-01 -3.48318517e-01 9.95840225e-03 -9.39448118e-01 -3.42551321e-01 9.90213081e-03 -9.41564262e-01 -3.36785942e-01 9.87347309e-03 -9.43587124e-01 -3.30999345e-01 9.84006282e-03 -9.45601165e-01 -3.25198978e-01 9.84986220e-03 -9.47570801e-01 -3.19395632e-01 9.86704603e-03 -9.49522913e-01 -3.13582182e-01 9.95690376e-03 -9.51412618e-01 -3.07738900e-01 1.00574484e-02 -9.53326106e-01 -3.01893860e-01 1.00236749e-02 -9.55135465e-01 -2.96038806e-01 9.90829058e-03 -9.56975162e-01 -2.90173233e-01 9.88976005e-03 -9.58717704e-01 -2.84301788e-01 9.82022379e-03 -9.60428476e-01 -2.78420150e-01 9.87954717e-03 -9.62135613e-01 -2.72518545e-01 9.88925435e-03 -9.63784575e-01 -2.66604811e-01 9.88558307e-03 -9.65377033e-01 -2.60685951e-01 9.92661249e-03 -9.66998100e-01 -2.54760951e-01 9.93579719e-03 -9.68498468e-01 -2.48822600e-01 1.00444956e-02 -9.70016301e-01 -2.42871866e-01 9.92753543e-03 -9.71490920e-01 -2.36920863e-01 9.95333120e-03 -9.72937346e-01 -2.30952978e-01 9.93732456e-03 -9.74341810e-01 -2.24976406e-01 9.95037984e-03 -9.75729525e-01 -2.18994066e-01 9.92946234e-03 -9.77028072e-01 -2.13007867e-01 9.92034376e-03 -9.78309989e-01 -2.07009301e-01 9.93714482e-03 -9.79545951e-01 -2.00994164e-01 9.91650205e-03 -9.80764747e-01 -1.94986373e-01 9.91766341e-03 -9.81930017e-01 -1.88962981e-01 9.91789438e-03 -9.83122230e-01 -1.82928950e-01 9.84645728e-03 -9.84183013e-01 -1.76896587e-01 9.84639954e-03 -9.85310972e-01 -1.70854628e-01 9.91095882e-03 -9.86306846e-01 -1.64804623e-01 9.90883540e-03 -9.87284660e-01 -1.58752933e-01 9.91302822e-03 -9.88258660e-01 -1.52689248e-01 9.85634699e-03 -9.89176750e-01 -1.46624371e-01 9.92999785e-03 -9.90031958e-01 -1.40551865e-01 9.93280858e-03 -9.90926743e-01 -1.34474784e-01 9.92725696e-03 -9.91681933e-01 -1.28391668e-01 9.93904751e-03 -9.92449641e-01 -1.22305319e-01 9.87967849e-03 -9.93161917e-01 -1.16213053e-01 9.97378211e-03 -9.93877947e-01 -1.10117286e-01 9.99988057e-03 -9.94583011e-01 -1.04018413e-01 1.00789135e-02 -9.95167434e-01 -9.79132131e-02 1.02615198e-02 -9.95725572e-01 -9.18040276e-02 1.04920445e-02 -9.96266901e-01 -8.56925324e-02 1.04173906e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.99428213e-01 1.87575500e-02 -2.81327050e-02 -9.99311328e-01 2.48861983e-02 -2.75245383e-02 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. -9.95948970e-01 8.61118883e-02 -2.58893631e-02 -9.95407462e-01 9.22204033e-02 -2.56490931e-02 -9.94822681e-01 9.83257070e-02 -2.55213249e-02 -9.94197488e-01 1.04427844e-01 -2.55079214e-02 -9.93553579e-01 1.10528216e-01 -2.59441566e-02 -9.92821872e-01 1.16623364e-01 -2.62490902e-02 -9.92087722e-01 1.22712344e-01 -2.61708088e-02 -9.91333127e-01 1.28794506e-01 -2.59591993e-02 -9.90510404e-01 1.34876773e-01 -2.59221066e-02 -9.89660680e-01 1.40949741e-01 -2.60149520e-02 -9.88802552e-01 1.47022784e-01 -2.58159917e-02 -9.87879455e-01 1.53086662e-01 -2.57069934e-02 -9.86930370e-01 1.59143090e-01 -2.55329274e-02 -9.85913038e-01 1.65197566e-01 -2.56388951e-02 -9.84896362e-01 1.71242058e-01 -2.57566404e-02 -9.83803570e-01 1.77280992e-01 -2.58538742e-02 -9.82697725e-01 1.83315799e-01 -2.59654857e-02 -9.81574953e-01 1.89343363e-01 -2.59241797e-02 -9.80376780e-01 1.95361748e-01 -2.59401333e-02 -9.79165971e-01 2.01372638e-01 -2.57335156e-02 -9.77931082e-01 2.07379282e-01 -2.57738046e-02 -9.76600170e-01 2.13374540e-01 -2.61548646e-02 -9.75273132e-01 2.19363332e-01 -2.63042990e-02 -9.73917067e-01 2.25342318e-01 -2.60230266e-02 -9.72532034e-01 2.31313229e-01 -2.61298250e-02 -9.71101761e-01 2.37278327e-01 -2.60281656e-02 -9.69627023e-01 2.43231863e-01 -2.60681119e-02 -9.68087137e-01 2.49176636e-01 -2.60945577e-02 -9.66551542e-01 2.55107105e-01 -2.60462277e-02 -9.64984596e-01 2.61036217e-01 -2.59760283e-02 -9.63362098e-01 2.66952395e-01 -2.58739609e-02 -9.61740911e-01 2.72858500e-01 -2.45476700e-02 -9.60043728e-01 2.78759032e-01 -2.43634023e-02 -9.58328605e-01 2.84643799e-01 -2.43536420e-02 -9.56541121e-01 2.90520489e-01 -2.43734997e-02 -9.54728425e-01 2.96380460e-01 -2.51079742e-02 -9.52881813e-01 3.02234650e-01 -2.57066451e-02 -9.51010346e-01 3.08069319e-01 -2.58090794e-02 -9.49094713e-01 3.13898563e-01 -2.59601288e-02 -9.47146297e-01 3.19715738e-01 -2.60760244e-02 -9.45164144e-01 3.25522065e-01 -2.60926243e-02 -9.43149924e-01 3.31316113e-01 -2.60897819e-02 -9.41083729e-01 3.37098569e-01 -2.61333603e-02 -9.39002931e-01 3.42862189e-01 -2.61492021e-02 -9.36896503e-01 3.48624945e-01 -2.61646807e-02 -9.34729874e-01 3.54365200e-01 -2.61608288e-02 -9.32532847e-01 3.60096484e-01 -2.62556914e-02 -9.30325866e-01 3.65803599e-01 -2.63479576e-02 -9.28035498e-01 3.71512562e-01 -2.63960864e-02 -9.25737977e-01 3.77196372e-01 -2.63603032e-02 -9.23417866e-01 3.82867545e-01 -2.64991894e-02 -9.21071827e-01 3.88536632e-01 -2.64888145e-02 -9.18640733e-01 3.94172579e-01 -2.65225600e-02 -9.16211724e-01 3.99818122e-01 -2.65230983e-02 -9.13735211e-01 4.05425519e-01 -2.65780110e-02 -9.11271393e-01 4.11015332e-01 -2.64305659e-02 -9.08708990e-01 4.16598886e-01 -2.63517611e-02 -9.06140447e-01 4.22163367e-01 -2.60649025e-02 -9.03556406e-01 4.27723765e-01 -2.57203784e-02 -9.00904417e-01 4.33260292e-01 -2.55608037e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.84302914e-01 4.66115266e-01 -2.72931475e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.41085076e-01 5.40279746e-01 -2.59558242e-02 -8.37760866e-01 5.45432866e-01 -2.56777667e-02 -8.34396482e-01 5.50567567e-01 -2.58099250e-02 -8.30999553e-01 5.55660427e-01 -2.59774681e-02 -8.27563941e-01 5.60752928e-01 -2.62785498e-02 -8.24084461e-01 5.65823376e-01 -2.63100993e-02 -8.20625961e-01 5.70858002e-01 -2.60991715e-02 -8.17098081e-01 5.75895965e-01 -2.59627514e-02 -8.13557208e-01 5.80898523e-01 -2.60525662e-02 -8.09973776e-01 5.85866570e-01 -2.60420833e-02 -8.06360185e-01 5.90838075e-01 -2.59560291e-02 -8.02711129e-01 5.95761597e-01 -2.59543713e-02 -7.99038887e-01 6.00679100e-01 -2.60392912e-02 -7.95356810e-01 6.05572999e-01 -2.61980146e-02 -7.91598678e-01 6.10435188e-01 -2.64157448e-02 -7.87842691e-01 6.15285456e-01 -2.64516994e-02 -7.84057915e-01 6.20124340e-01 -2.65046414e-02 -7.80247808e-01 6.24908924e-01 -2.65045390e-02 -7.76399255e-01 6.29685223e-01 -2.65149381e-02 -7.72533000e-01 6.34434462e-01 -2.65300833e-02 -7.68627286e-01 6.39180183e-01 -2.65546832e-02 -7.64663458e-01 6.43863559e-01 -2.65370309e-02 -7.60722399e-01 6.48568332e-01 -2.65202150e-02 -7.56705880e-01 6.53216004e-01 -2.65061222e-02 -7.52680421e-01 6.57850862e-01 -2.65106447e-02 -7.48644650e-01 6.62459910e-01 -2.65152138e-02 -7.44584262e-01 6.67017877e-01 -2.64980122e-02 -7.40466833e-01 6.71580851e-01 -2.65108496e-02 -7.36322224e-01 6.76128805e-01 -2.65066996e-02 -7.32168972e-01 6.80634141e-01 -2.65019219e-02 -7.27988780e-01 6.85095668e-01 -2.65103374e-02 -7.23752379e-01 6.89569473e-01 -2.64998600e-02 -7.19501317e-01 6.93976104e-01 -2.64635384e-02 -7.15226114e-01 6.98373854e-01 -2.64450144e-02 -7.10941374e-01 7.02764153e-01 -2.64091454e-02 -7.06624866e-01 7.07118452e-01 -2.64001470e-02 -7.02266455e-01 7.11420894e-01 -2.63687819e-02 -6.97874725e-01 7.15711653e-01 -2.63489559e-02 -6.93480015e-01 7.19980299e-01 -2.63111144e-02 -6.89051986e-01 7.24231839e-01 -2.63253879e-02 -6.84578955e-01 7.28456736e-01 -2.63109319e-02 -6.80095136e-01 7.32644320e-01 -2.63730846e-02 -6.75589263e-01 7.36799538e-01 -2.63996869e-02 -6.71060503e-01 7.40941584e-01 -2.64254268e-02 -6.66517019e-01 7.45018125e-01 -2.64619440e-02 -6.61916137e-01 7.49125421e-01 -2.64792386e-02 -6.57328844e-01 7.53159821e-01 -2.64898930e-02 -6.52693391e-01 7.57184803e-01 -2.65225973e-02 -6.48018241e-01 7.61182904e-01 -2.64895074e-02 -6.43337250e-01 7.65120804e-01 -2.65003126e-02 -6.38649166e-01 7.69051731e-01 -2.65003331e-02 -6.33913994e-01 7.72954702e-01 -2.64850762e-02 -6.29161358e-01 7.76834190e-01 -2.65129786e-02 -6.24379516e-01 7.80703306e-01 -2.65326556e-02 -6.19559944e-01 7.84515560e-01 -2.65207104e-02 -6.14755273e-01 7.88302541e-01 -2.65511703e-02 -6.09898746e-01 7.92061567e-01 -2.65694316e-02 -6.05023146e-01 7.95766711e-01 -2.65865624e-02 -6.00136995e-01 7.99491048e-01 -2.66158897e-02 -5.95222652e-01 8.03159654e-01 -2.66055111e-02 -5.90267539e-01 8.06762815e-01 -2.66248975e-02 -5.85327506e-01 8.10391724e-01 -2.66370066e-02 -5.80339134e-01 8.13950241e-01 -2.65974216e-02 -5.75328469e-01 8.17491651e-01 -2.65565086e-02 -5.70288122e-01 8.21005464e-01 -2.65443828e-02 -5.65237403e-01 8.24510753e-01 -2.65343878e-02 -5.60180902e-01 8.27956259e-01 -2.65483484e-02 -5.55091202e-01 8.31373811e-01 -2.65747514e-02 -5.49974978e-01 8.34778011e-01 -2.65791751e-02 -5.44843733e-01 8.38112533e-01 -2.66095847e-02 -5.39693356e-01 8.41470182e-01 -2.66973376e-02 -5.34514487e-01 8.44770074e-01 -2.67556887e-02 -5.29332578e-01 8.48001182e-01 -2.67989915e-02 -5.24111450e-01 8.51262927e-01 -2.68165097e-02 -5.18872917e-01 8.54444742e-01 -2.68240646e-02 -5.13623536e-01 8.57616603e-01 -2.68618129e-02 -5.08355677e-01 8.60764444e-01 -2.70406827e-02 -5.03065646e-01 8.63861501e-01 -2.70173717e-02 -4.97743398e-01 8.66893232e-01 -2.70823743e-02 -4.92403626e-01 8.69950950e-01 -2.71078814e-02 -4.87062514e-01 8.72962594e-01 -2.71202438e-02 -4.81710494e-01 8.75902414e-01 -2.71116272e-02 -4.76309329e-01 8.78836632e-01 -2.71029789e-02 -4.70904708e-01 8.81758332e-01 -2.71447413e-02 -4.65495676e-01 8.84660959e-01 -2.71412935e-02 -4.60046381e-01 8.87461424e-01 -2.71782093e-02 -4.54601616e-01 8.90291989e-01 -2.72111148e-02 -4.49136674e-01 8.93049538e-01 -2.71960311e-02 -4.43647951e-01 8.95805299e-01 -2.72034947e-02 -4.38147098e-01 8.98509264e-01 -2.71681584e-02 -4.32615608e-01 9.01188850e-01 -2.71848924e-02 -4.27086085e-01 9.03793454e-01 -2.71720719e-02 -4.21524286e-01 9.06405210e-01 -2.71802563e-02 -4.15959120e-01 9.09001410e-01 -2.71576941e-02 -4.10371870e-01 9.11529303e-01 -2.71500722e-02 -4.04763430e-01 9.13994014e-01 -2.71585304e-02 -3.99148434e-01 9.16483819e-01 -2.71575768e-02 -3.93529654e-01 9.18914735e-01 -2.71722041e-02 -3.87878895e-01 9.21297014e-01 -2.71803048e-02 -3.82215530e-01 9.23706532e-01 -2.71671303e-02 -3.76546293e-01 9.26000416e-01 -2.71745380e-02 -3.70847940e-01 9.28302348e-01 -2.71659847e-02 -3.65158200e-01 9.30571020e-01 -2.68388893e-02 -3.59436005e-01 9.32772219e-01 -2.68377550e-02 -3.53700161e-01 9.34962571e-01 -2.70969197e-02 -3.47957343e-01 9.37139392e-01 -2.71831490e-02 -3.42208207e-01 9.39256370e-01 -2.72027757e-02 -3.36428791e-01 9.41305459e-01 -2.72030551e-02 -3.30650002e-01 9.43356633e-01 -2.71973666e-02 -3.24856937e-01 9.45382297e-01 -2.71963570e-02 -3.19043845e-01 9.47378576e-01 -2.72446424e-02 -3.13233793e-01 9.49289680e-01 -2.72397362e-02 -3.07394952e-01 9.51216161e-01 -2.72412412e-02 -3.01559746e-01 9.53035414e-01 -2.72381306e-02 -2.95709670e-01 9.54901040e-01 -2.72288304e-02 -2.89841026e-01 9.56679583e-01 -2.72284504e-02 -2.83962518e-01 9.58463013e-01 -2.71976516e-02 -2.78083563e-01 9.60180640e-01 -2.71791741e-02 -2.72181273e-01 9.61835742e-01 -2.71783713e-02 -2.66274184e-01 9.63525712e-01 -2.71251742e-02 -2.60354549e-01 9.65149760e-01 -2.72093564e-02 -2.54430681e-01 9.66698766e-01 -2.71944255e-02 -2.48499990e-01 9.68247771e-01 -2.72011943e-02 -2.42551044e-01 9.69773173e-01 -2.72296853e-02 -2.36596152e-01 9.71244574e-01 -2.72142608e-02 -2.30630279e-01 9.72644985e-01 -2.72156820e-02 -2.24654213e-01 9.74033773e-01 -2.72423699e-02 -2.18674466e-01 9.75453317e-01 -2.72330213e-02 -2.12690473e-01 9.76717412e-01 -2.72414386e-02 -2.06689566e-01 9.78008389e-01 -2.72575859e-02 -2.00682685e-01 9.79292870e-01 -2.72476524e-02 -1.94670528e-01 9.80510533e-01 -2.72699539e-02 -1.88653603e-01 9.81660724e-01 -2.72547938e-02 -1.82625443e-01 9.82798696e-01 -2.72530671e-02 -1.76595509e-01 9.83928680e-01 -2.72393227e-02 -1.70555130e-01 9.84989643e-01 -2.72336118e-02 -1.64505348e-01 9.85986531e-01 -2.71237139e-02 -1.58452183e-01 9.86964285e-01 -2.72503980e-02 -1.52390480e-01 9.87929821e-01 -2.72514727e-02 -1.46328777e-01 9.88889992e-01 -2.72502173e-02 -1.40258595e-01 9.89716530e-01 -2.72501968e-02 -1.34182259e-01 9.90599155e-01 -2.72566974e-02 -1.28100768e-01 9.91356790e-01 -2.72639394e-02 -1.22015759e-01 9.92138207e-01 -2.72630006e-02 -1.15925640e-01 9.92869794e-01 -2.72687599e-02 -1.09830439e-01 9.93550301e-01 -2.72704251e-02 -1.03730448e-01 9.94256973e-01 -2.72792242e-02 -9.76286083e-02 9.94826198e-01 -2.73154061e-02 -9.15231854e-02 9.95465994e-01 -2.72596274e-02 -8.54136497e-02 9.95971084e-01 -2.72872932e-02 -7.93012604e-02 9.96463835e-01 -2.72945818e-02 -7.31856599e-02 9.96947706e-01 -2.72943657e-02 -6.70672506e-02 9.97415245e-01 -2.72789076e-02 -6.09467328e-02 9.97764349e-01 -2.72955932e-02 -5.48228920e-02 9.98153210e-01 -2.72869188e-02 -4.86973152e-02 9.98430729e-01 -2.73006912e-02 -4.25699912e-02 9.98728931e-01 -2.72859018e-02 -3.64401154e-02 9.98960376e-01 -2.73515321e-02 -3.03104818e-02 9.99147296e-01 -2.73437444e-02 -2.41794176e-02 9.99370933e-01 -2.73073353e-02 -1.80472098e-02 9.99472260e-01 -2.73065493e-02 -1.19140688e-02 9.99560535e-01 -2.72770654e-02 -5.78039559e-03 9.99623239e-01 -2.73236204e-02 3.53392621e-04 9.99627888e-01 -2.73505133e-02 6.48723030e-03 9.99621451e-01 -2.73736492e-02 1.26205701e-02 9.99555230e-01 -2.73753237e-02 1.87533032e-02 9.99453306e-01 -2.73460094e-02 2.48852093e-02 9.99314904e-01 -2.72738952e-02 3.10166366e-02 9.99146581e-01 -2.72802822e-02 3.71461697e-02 9.98925388e-01 -2.72382051e-02 4.32750024e-02 9.98671889e-01 -2.73009092e-02 4.94015180e-02 9.98405337e-01 -2.72603054e-02 5.55269718e-02 9.98078585e-01 -2.72208899e-02 6.16501570e-02 9.97705996e-01 -2.72230972e-02 6.77708760e-02 9.97325480e-01 -2.71584690e-02 7.38878176e-02 9.96914446e-01 -2.69863233e-02 8.00032988e-02 9.96430576e-01 -2.69307811e-02 8.61150622e-02 9.95921612e-01 -2.67414544e-02 9.22245830e-02 9.95371699e-01 -2.67887320e-02 9.83301103e-02 9.94804919e-01 -2.66783554e-02 1.04430787e-01 9.94183183e-01 -2.63022073e-02 1.10526577e-01 9.93542612e-01 -2.55405791e-02 1.16623081e-01 9.92826521e-01 -2.63138376e-02 1.22711957e-01 9.92099404e-01 -2.60417890e-02 1.28794357e-01 9.91353929e-01 -2.50365268e-02 1.34874970e-01 9.90543425e-01 -2.51019150e-02 1.40952662e-01 9.89670932e-01 -2.61108074e-02 1.47023484e-01 9.88776922e-01 -2.65269708e-02 1.53087214e-01 9.87865210e-01 -2.62048841e-02 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. 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. 2.66952574e-01 9.63302672e-01 -2.80041154e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.90516883e-01 9.56532896e-01 -2.52679847e-02 2.96375901e-01 9.54693079e-01 -2.69531626e-02 3.02231461e-01 9.52858269e-01 -2.73138881e-02 3.08066040e-01 9.50962365e-01 -2.73187067e-02 3.13905269e-01 9.49081600e-01 -2.73851827e-02 3.19715410e-01 9.47133780e-01 -2.73744147e-02 3.25522393e-01 9.45130885e-01 -2.73117982e-02 3.31313789e-01 9.43122327e-01 -2.73351036e-02 3.37095112e-01 9.41059649e-01 -2.73479335e-02 3.42866182e-01 9.38992202e-01 -2.73090079e-02 3.48625034e-01 9.36885536e-01 -2.73242295e-02 3.54360729e-01 9.34707880e-01 -2.73090284e-02 3.60093176e-01 9.32509601e-01 -2.73343455e-02 3.65802407e-01 9.30301726e-01 -2.73084156e-02 3.71507913e-01 9.28014636e-01 -2.71967687e-02 3.77189547e-01 9.25702810e-01 -2.72939317e-02 3.82863700e-01 9.23389971e-01 -2.72709876e-02 3.88527393e-01 9.21042502e-01 -2.72734147e-02 3.94168496e-01 9.18614030e-01 -2.72598974e-02 3.99810851e-01 9.16191399e-01 -2.72464566e-02 4.05424833e-01 9.13730085e-01 -2.72334144e-02 4.11011636e-01 9.11236823e-01 -2.72105243e-02 4.16594118e-01 9.08695877e-01 -2.72226427e-02 4.22158092e-01 9.06131268e-01 -2.72255708e-02 4.27711934e-01 9.03483689e-01 -2.72419807e-02 4.33249801e-01 9.00880158e-01 -2.72509903e-02 4.38772798e-01 8.98189366e-01 -2.72770654e-02 4.44278628e-01 8.95462096e-01 -2.72836573e-02 4.49763209e-01 8.92730117e-01 -2.73243673e-02 4.55228299e-01 8.89941931e-01 -2.73288488e-02 4.60676491e-01 8.87122035e-01 -2.73231901e-02 4.66119766e-01 8.84296000e-01 -2.73384042e-02 4.71526593e-01 8.81421089e-01 -2.73363367e-02 4.76935923e-01 8.78519058e-01 -2.73314510e-02 4.82316881e-01 8.75562847e-01 -2.73227114e-02 4.87677723e-01 8.72590303e-01 -2.73209661e-02 4.93018150e-01 8.69571567e-01 -2.73227505e-02 4.98355687e-01 8.66544604e-01 -2.73086764e-02 5.03656924e-01 8.63463461e-01 -2.73023583e-02 5.08955479e-01 8.60374153e-01 -2.73163058e-02 5.14217675e-01 8.57245445e-01 -2.73119807e-02 5.19463837e-01 8.54070902e-01 -2.73316838e-02 5.24701953e-01 8.50854933e-01 -2.73164529e-02 5.29918671e-01 8.47604096e-01 -2.73241419e-02 5.35093427e-01 8.44353735e-01 -2.72924788e-02 5.40266633e-01 8.41032028e-01 -2.73272879e-02 5.45437336e-01 8.37737679e-01 -2.72445865e-02 5.50560832e-01 8.34380925e-01 -2.73179412e-02 5.55670321e-01 8.30982566e-01 -2.72771493e-02 5.60735047e-01 8.27553034e-01 -2.72877794e-02 5.65830529e-01 8.24090242e-01 -2.72464175e-02 5.70853710e-01 8.20608079e-01 -2.72559933e-02 5.75871170e-01 8.17076325e-01 -2.73397248e-02 5.80875158e-01 8.13521981e-01 -2.73224898e-02 5.85852385e-01 8.09972405e-01 -2.73237471e-02 5.90833843e-01 8.06339800e-01 -2.73273494e-02 5.95754266e-01 8.02686572e-01 -2.73088310e-02 6.00688696e-01 7.99021363e-01 -2.73120906e-02 6.05581820e-01 7.95340240e-01 -2.73032729e-02 6.10445619e-01 7.91588604e-01 -2.72740070e-02 6.15285754e-01 7.87830770e-01 -2.72109993e-02 6.20127797e-01 7.84045279e-01 -2.71894671e-02 6.24902844e-01 7.80237138e-01 -2.72060577e-02 6.29679859e-01 7.76373208e-01 -2.72120107e-02 6.34426951e-01 7.72525311e-01 -2.71941200e-02 6.39171600e-01 7.68618047e-01 -2.72058621e-02 6.43860519e-01 7.64648557e-01 -2.72084884e-02 6.48560643e-01 7.60709703e-01 -2.71959957e-02 6.53207242e-01 7.56693363e-01 -2.71899458e-02 6.57841027e-01 7.52667189e-01 -2.71614231e-02 6.62446916e-01 7.48627603e-01 -2.71945111e-02 6.67002857e-01 7.44570613e-01 -2.72004474e-02 6.71584368e-01 7.40445793e-01 -2.72109974e-02 6.76110148e-01 7.36298859e-01 -2.71853823e-02 6.80621982e-01 7.32145905e-01 -2.72237696e-02 6.85074627e-01 7.27969050e-01 -2.72398740e-02 6.89558089e-01 7.23736346e-01 -2.71870587e-02 6.93965435e-01 7.19482422e-01 -2.71930266e-02 6.98360860e-01 7.15210378e-01 -2.71839797e-02 7.02740967e-01 7.10916638e-01 -2.71936562e-02 7.07107306e-01 7.06613481e-01 -2.71548070e-02 7.11407483e-01 7.02249825e-01 -2.72141639e-02 7.15712488e-01 6.97867095e-01 -2.71707978e-02 7.19979048e-01 6.93470240e-01 -2.71709245e-02 7.24223316e-01 6.89041674e-01 -2.71568000e-02 7.28455544e-01 6.84569478e-01 -2.71716397e-02 7.32634008e-01 6.80081904e-01 -2.71744262e-02 7.36788213e-01 6.75572634e-01 -2.71739904e-02 7.40928888e-01 6.71043515e-01 -2.71845087e-02 7.44995534e-01 6.66496754e-01 -2.72373203e-02 7.49105930e-01 6.61897242e-01 -2.71867011e-02 7.53149688e-01 6.57321811e-01 -2.71080062e-02 7.57178068e-01 6.52688265e-01 -2.70970371e-02 7.61166513e-01 6.47989869e-01 -2.72402335e-02 7.65099883e-01 6.43316865e-01 -2.72491053e-02 7.69026577e-01 6.38604939e-01 -2.72433013e-02 7.72929788e-01 6.33886337e-01 -2.72498038e-02 7.76810408e-01 6.29138887e-01 -2.72560026e-02 7.80681789e-01 6.24360263e-01 -2.72593591e-02 7.84492493e-01 6.19534552e-01 -2.72751488e-02 7.88276374e-01 6.14729047e-01 -2.72905622e-02 7.92038798e-01 6.09877527e-01 -2.72891521e-02 7.95738697e-01 6.05000377e-01 -2.72744708e-02 7.99475312e-01 6.00115716e-01 -2.72793006e-02 8.03138018e-01 5.95205426e-01 -2.72831675e-02 8.06753039e-01 5.90257227e-01 -2.72363797e-02 8.10378969e-01 5.85308731e-01 -2.72348076e-02 8.13932717e-01 5.80329239e-01 -2.72490792e-02 8.17484677e-01 5.75325429e-01 -2.72396468e-02 8.21000338e-01 5.70273519e-01 -2.72343699e-02 8.24508011e-01 5.65234423e-01 -2.72823330e-02 8.27939928e-01 5.60180962e-01 -2.73237638e-02 8.31351101e-01 5.55080354e-01 -2.73135807e-02 8.34764242e-01 5.49969673e-01 -2.71612238e-02 8.38101864e-01 5.44841111e-01 -2.71792952e-02 8.41464579e-01 5.39690554e-01 -2.73282118e-02 8.44752073e-01 5.34498215e-01 -2.72565559e-02 8.47993910e-01 5.29321373e-01 -2.72527710e-02 8.51251662e-01 5.24103343e-01 -2.71509886e-02 8.54430974e-01 5.18866003e-01 -2.71473601e-02 8.57603848e-01 5.13613701e-01 -2.71450505e-02 8.60753298e-01 5.08350730e-01 -2.72424519e-02 8.63839924e-01 5.03056109e-01 -2.71606352e-02 8.66899133e-01 4.97747153e-01 -2.71495488e-02 8.69946003e-01 4.92416948e-01 -2.71392185e-02 8.72970045e-01 4.87072527e-01 -2.71293912e-02 8.75910699e-01 4.81704533e-01 -2.71340124e-02 8.78842890e-01 4.76314813e-01 -2.71299351e-02 8.81763220e-01 4.70908135e-01 -2.71171704e-02 8.84664297e-01 4.65496063e-01 -2.71344874e-02 8.87471259e-01 4.60048020e-01 -2.71456297e-02 8.90296876e-01 4.54599977e-01 -2.71379240e-02 8.93067479e-01 4.49136794e-01 -2.71067452e-02 8.95812809e-01 4.43645567e-01 -2.71164589e-02 8.98504436e-01 4.38145757e-01 -2.71056183e-02 9.01184320e-01 4.32624370e-01 -2.71136872e-02 9.03806150e-01 4.27088469e-01 -2.71595828e-02 9.06410992e-01 4.21530306e-01 -2.71365773e-02 9.08994079e-01 4.15955156e-01 -2.71279365e-02 9.11531627e-01 4.10374433e-01 -2.71151327e-02 9.13997948e-01 4.04768527e-01 -2.71060560e-02 9.16495502e-01 3.99152935e-01 -2.71107201e-02 9.18934882e-01 3.93532991e-01 -2.70869378e-02 9.21303213e-01 3.87873411e-01 -2.71100514e-02 9.23713028e-01 3.82216364e-01 -2.70851199e-02 9.26012635e-01 3.76542538e-01 -2.70660054e-02 9.28299487e-01 3.70849550e-01 -2.70736683e-02 9.30575192e-01 3.65160912e-01 -2.70268917e-02 9.32776034e-01 3.59434992e-01 -2.70122048e-02 9.34971452e-01 3.53704125e-01 -2.70012394e-02 9.37148690e-01 3.47962797e-01 -2.69892905e-02 9.39261198e-01 3.42216849e-01 -2.70061940e-02 9.41319585e-01 3.36435884e-01 -2.69826259e-02 9.43368018e-01 3.30650955e-01 -2.69889478e-02 9.45383549e-01 3.24856490e-01 -2.69937646e-02 9.47392046e-01 3.19050729e-01 -2.69925669e-02 9.49291170e-01 3.13240498e-01 -2.70282794e-02 9.51219976e-01 3.07399839e-01 -2.70093884e-02 9.53048527e-01 3.01560521e-01 -2.70108990e-02 9.54901755e-01 2.95716554e-01 -2.69969497e-02 9.56691444e-01 2.89843947e-01 -2.69914623e-02 9.58471596e-01 2.83967435e-01 -2.69769412e-02 9.60183084e-01 2.78087199e-01 -2.70592887e-02 9.61836636e-01 2.72184014e-01 -2.70121992e-02 9.63520527e-01 2.66273916e-01 -2.69870739e-02 9.65147376e-01 2.60358512e-01 -2.69604176e-02 9.66697812e-01 2.54430920e-01 -2.70025656e-02 9.68244433e-01 2.48500735e-01 -2.70034038e-02 9.69773889e-01 2.42547840e-01 -2.69856919e-02 9.71236527e-01 2.36597776e-01 -2.70776637e-02 9.72647130e-01 2.30629116e-01 -2.70780958e-02 9.74027395e-01 2.24653542e-01 -2.70826314e-02 9.75441337e-01 2.18671381e-01 -2.70983260e-02 9.76705551e-01 2.12688178e-01 -2.70769857e-02 9.77993309e-01 2.06690222e-01 -2.70702243e-02 9.79284763e-01 2.00682372e-01 -2.70698182e-02 9.80502963e-01 1.94671586e-01 -2.70815697e-02 9.81645584e-01 1.88651294e-01 -2.70974748e-02 9.82787311e-01 1.82623759e-01 -2.70977058e-02 9.83918846e-01 1.76594406e-01 -2.70927735e-02 9.84979093e-01 1.70555145e-01 -2.69839931e-02 9.85971034e-01 1.64503753e-01 -2.69875396e-02 9.86949921e-01 1.58450663e-01 -2.71006078e-02 9.87910748e-01 1.52392089e-01 -2.70946398e-02 9.88871515e-01 1.46326706e-01 -2.71058474e-02 9.89697516e-01 1.40257046e-01 -2.70958580e-02 9.90580559e-01 1.34178847e-01 -2.70879343e-02 9.91339684e-01 1.28099710e-01 -2.70963814e-02 9.92123485e-01 1.22019202e-01 -2.70771831e-02 9.92855906e-01 1.15925223e-01 -2.69782934e-02 9.93538439e-01 1.09829687e-01 -2.69764792e-02 9.94245231e-01 1.03731863e-01 -2.69503295e-02 9.94818747e-01 9.76294130e-02 -2.69455183e-02 9.95451272e-01 9.15244818e-02 -2.70235427e-02 9.95959640e-01 8.54135752e-02 -2.70336028e-02 9.96455431e-01 7.93031082e-02 -2.68946178e-02 9.96939182e-01 7.31874332e-02 -2.69010719e-02 9.97406065e-01 6.70704618e-02 -2.68991217e-02 9.97748196e-01 6.09462634e-02 -2.68973634e-02 9.98140574e-01 5.48246764e-02 -2.68786680e-02 9.98422623e-01 4.87008318e-02 -2.67525166e-02 9.98713970e-01 4.25725728e-02 -2.67380159e-02 9.98960316e-01 3.64445485e-02 -2.67299637e-02 9.99146044e-01 3.03134285e-02 -2.68392768e-02 9.99357283e-01 2.41818838e-02 -2.68336795e-02 9.99450684e-01 1.80499703e-02 -2.67796032e-02 9.99554574e-01 1.19167697e-02 -2.68118810e-02 9.99618769e-01 5.78331761e-03 -2.68263519e-02 9.99623239e-01 -3.50221439e-04 -2.68214475e-02 9.99618292e-01 -6.48366893e-03 -2.68074088e-02 9.99550939e-01 -1.26169603e-02 -2.67940331e-02 9.99448180e-01 -1.87498573e-02 -2.67752632e-02 9.99311924e-01 -2.48815808e-02 -2.67157182e-02 9.99137878e-01 -3.10124736e-02 -2.67231707e-02 9.98913348e-01 -3.71426940e-02 -2.67011337e-02 9.98668611e-01 -4.32721674e-02 -2.67411862e-02 9.98407543e-01 -4.93984632e-02 -2.67278180e-02 9.98089910e-01 -5.55237234e-02 -2.66882945e-02 9.97701764e-01 -6.16465919e-02 -2.66820304e-02 9.97340143e-01 -6.77667931e-02 -2.67243162e-02 9.96922135e-01 -7.38852248e-02 -2.67244875e-02 9.96441662e-01 -8.00007805e-02 -2.67292466e-02 9.95949864e-01 -8.61144736e-02 -2.67035086e-02 9.95388627e-01 -9.22239125e-02 -2.67014354e-02 9.94768798e-01 -9.83274952e-02 -2.67187413e-02 9.94171977e-01 -1.04429863e-01 -2.67223977e-02 9.93525922e-01 -1.10528372e-01 -2.67416667e-02 9.92797196e-01 -1.16623998e-01 -2.67422739e-02 9.92065489e-01 -1.22713476e-01 -2.67514065e-02 9.91314530e-01 -1.28795743e-01 -2.67508514e-02 9.90506709e-01 -1.34878710e-01 -2.67645959e-02 9.89627361e-01 -1.40954167e-01 -2.68011931e-02 9.88732934e-01 -1.47023872e-01 -2.68000662e-02 9.87835169e-01 -1.53082862e-01 -2.68037170e-02 9.86909986e-01 -1.59144685e-01 -2.68050656e-02 9.85885084e-01 -1.65193900e-01 -2.67927386e-02 9.84830081e-01 -1.71243742e-01 -2.68048905e-02 9.83772516e-01 -1.77283868e-01 -2.67942213e-02 9.82707500e-01 -1.83315232e-01 -2.67851576e-02 9.81556773e-01 -1.89345419e-01 -2.67787091e-02 9.80350733e-01 -1.95360839e-01 -2.67814156e-02 9.79130685e-01 -2.01369807e-01 -2.67839450e-02 9.77905512e-01 -2.07378820e-01 -2.67894622e-02 9.76609766e-01 -2.13370577e-01 -2.67948899e-02 9.75245714e-01 -2.19360977e-01 -2.67709717e-02 9.73925292e-01 -2.25340217e-01 -2.67737750e-02 9.72526371e-01 -2.31308013e-01 -2.67687757e-02 9.71076608e-01 -2.37276331e-01 -2.67775841e-02 9.69600856e-01 -2.43230894e-01 -2.68007740e-02 9.68070090e-01 -2.49173477e-01 -2.68018059e-02 9.66518462e-01 -2.55102664e-01 -2.68104654e-02 9.64965343e-01 -2.61032403e-01 -2.68108919e-02 9.63293016e-01 -2.66946584e-01 -2.67739128e-02 9.61654365e-01 -2.72854209e-01 -2.67699584e-02 9.59999442e-01 -2.78755754e-01 -2.67790090e-02 9.58241582e-01 -2.84632236e-01 -2.67599467e-02 9.56459761e-01 -2.90517896e-01 -2.67625712e-02 9.54707384e-01 -2.96379834e-01 -2.67574303e-02 9.52856600e-01 -3.02233696e-01 -2.67379880e-02 9.50983465e-01 -3.08061838e-01 -2.67588217e-02 9.49097037e-01 -3.13905001e-01 -2.67270431e-02 9.47148144e-01 -3.19711894e-01 -2.66994126e-02 9.45135236e-01 -3.25519234e-01 -2.66931597e-02 9.43134069e-01 -3.31309021e-01 -2.66841911e-02 9.41075504e-01 -3.37098032e-01 -2.66891625e-02 9.39022481e-01 -3.42877954e-01 -2.66728625e-02 9.36900318e-01 -3.48627359e-01 -2.66827121e-02 9.34722006e-01 -3.54362965e-01 -2.66778320e-02 9.32525694e-01 -3.60096216e-01 -2.68007927e-02 9.30325210e-01 -3.65812808e-01 -2.66609266e-02 9.28038597e-01 -3.71512443e-01 -2.65797209e-02 9.25731778e-01 -3.77192467e-01 -2.65899897e-02 9.23403144e-01 -3.82863373e-01 -2.66142637e-02 9.21062350e-01 -3.88533741e-01 -2.65959948e-02 9.18642998e-01 -3.94172490e-01 -2.66169813e-02 9.16205406e-01 -3.99809837e-01 -2.66274139e-02 9.13743615e-01 -4.05424565e-01 -2.66325455e-02 9.11252558e-01 -4.11016226e-01 -2.66513769e-02 9.08714175e-01 -4.16601568e-01 -2.66659446e-02 9.06149328e-01 -4.22160119e-01 -2.67153010e-02 9.03510332e-01 -4.27712262e-01 -2.66832300e-02 9.00894821e-01 -4.33256567e-01 -2.69157812e-02 8.98218930e-01 -4.38776731e-01 -2.68729366e-02 8.95473301e-01 -4.44291145e-01 -2.67231204e-02 8.92756045e-01 -4.49778736e-01 -2.67253611e-02 8.89973283e-01 -4.55233932e-01 -2.67292820e-02 8.87150228e-01 -4.60696906e-01 -2.67794244e-02 8.84311974e-01 -4.66123790e-01 -2.69057881e-02 8.81418109e-01 -4.71529484e-01 -2.68870797e-02 8.78515601e-01 -4.76940095e-01 -2.69267056e-02 8.75563920e-01 -4.82313573e-01 -2.69379504e-02 8.72600317e-01 -4.87678647e-01 -2.69342866e-02 8.69576871e-01 -4.93022382e-01 -2.69461162e-02 8.66550207e-01 -4.98360366e-01 -2.68233847e-02 8.63459647e-01 -5.03660023e-01 -2.69340109e-02 8.60390902e-01 -5.08955359e-01 -2.69071031e-02 8.57239544e-01 -5.14218330e-01 -2.68944409e-02 8.54068279e-01 -5.19466996e-01 -2.68881302e-02 8.50881755e-01 -5.24704099e-01 -2.68598329e-02 8.47628355e-01 -5.29921889e-01 -2.68191695e-02 8.44359159e-01 -5.35096347e-01 -2.68445536e-02 8.41044903e-01 -5.40274739e-01 -2.68549211e-02 8.37724566e-01 -5.45431495e-01 -2.69943289e-02 8.34386826e-01 -5.50557792e-01 -2.70288270e-02 8.30994964e-01 -5.55666447e-01 -2.68776361e-02 8.27561677e-01 -5.60746908e-01 -2.70477589e-02 8.24075043e-01 -5.65823495e-01 -2.70432141e-02 8.20620358e-01 -5.70853531e-01 -2.70560030e-02 8.17089319e-01 -5.75881600e-01 -2.69261450e-02 8.13546002e-01 -5.80882370e-01 -2.69254334e-02 8.09979320e-01 -5.85860312e-01 -2.68636849e-02 8.06345701e-01 -5.90838134e-01 -2.70679332e-02 8.02691698e-01 -5.95760286e-01 -2.70691868e-02 7.99026906e-01 -6.00690126e-01 -2.70605627e-02 7.95359552e-01 -6.05584621e-01 -2.70264074e-02 7.91590691e-01 -6.10449791e-01 -2.70479228e-02 7.87834585e-01 -6.15279853e-01 -2.68904604e-02 7.84049869e-01 -6.20119095e-01 -2.68519577e-02 7.80234277e-01 -6.24898672e-01 -2.69297194e-02 7.76368499e-01 -6.29676342e-01 -2.68682055e-02 7.72513628e-01 -6.34423435e-01 -2.69039776e-02 7.68608391e-01 -6.39167786e-01 -2.68883631e-02 7.64651835e-01 -6.43859446e-01 -2.68831272e-02 7.60707617e-01 -6.48556411e-01 -2.68847961e-02 7.56690562e-01 -6.53203070e-01 -2.68546566e-02 7.52665699e-01 -6.57838166e-01 -2.68767588e-02 7.48628914e-01 -6.62441432e-01 -2.68939119e-02 7.44569063e-01 -6.67007685e-01 -2.68698204e-02 7.40456760e-01 -6.71592176e-01 -2.68687308e-02 7.36312211e-01 -6.76117003e-01 -2.69009192e-02 7.32160330e-01 -6.80627048e-01 -2.68954504e-02 7.27980554e-01 -6.85090184e-01 -2.69217193e-02 7.23743498e-01 -6.89564586e-01 -2.69229989e-02 7.19496667e-01 -6.93971395e-01 -2.68033408e-02 7.15222657e-01 -6.98369324e-01 -2.68096868e-02 7.10922480e-01 -7.02746034e-01 -2.69706734e-02 7.06607878e-01 -7.07101822e-01 -2.71574929e-02 7.02252924e-01 -7.11411417e-01 -2.71661766e-02 6.97863698e-01 -7.15711355e-01 -2.71719564e-02 6.93467259e-01 -7.19977736e-01 -2.71969885e-02 6.89040899e-01 -7.24221468e-01 -2.71831993e-02 6.84566319e-01 -7.28450298e-01 -2.71772314e-02 6.80084050e-01 -7.32631207e-01 -2.71727089e-02 6.75575435e-01 -7.36786902e-01 -2.71800105e-02 6.71046317e-01 -7.40927339e-01 -2.71897987e-02 6.66496992e-01 -7.45005369e-01 -2.72020530e-02 6.61903739e-01 -7.49103248e-01 -2.72028726e-02 6.57300889e-01 -7.53138721e-01 -2.72076614e-02 6.52667105e-01 -7.57164717e-01 -2.72146277e-02 6.48013234e-01 -7.61149704e-01 -2.70810295e-02 6.43321395e-01 -7.65106261e-01 -2.70981770e-02 6.38620198e-01 -7.69048691e-01 -2.70758867e-02 6.33879542e-01 -7.72951782e-01 -2.70815715e-02 6.29137576e-01 -7.76817143e-01 -2.70773154e-02 6.24349296e-01 -7.80668318e-01 -2.70796865e-02 6.19555831e-01 -7.84496665e-01 -2.70686056e-02 6.14726067e-01 -7.88283050e-01 -2.70435382e-02 6.09883308e-01 -7.92038083e-01 -2.70536877e-02 6.05005026e-01 -7.95746744e-01 -2.70539783e-02 6.00120246e-01 -7.99471080e-01 -2.70500723e-02 5.95194876e-01 -8.03133428e-01 -2.70861778e-02 5.90249598e-01 -8.06745827e-01 -2.71527134e-02 5.85303247e-01 -8.10371518e-01 -2.70906482e-02 5.80313802e-01 -8.13936055e-01 -2.71206181e-02 5.75310051e-01 -8.17479789e-01 -2.71397214e-02 5.70280910e-01 -8.20993662e-01 -2.71594860e-02 5.65228701e-01 -8.24500024e-01 -2.71645728e-02 5.60172260e-01 -8.27946961e-01 -2.71460712e-02 5.55080235e-01 -8.31357777e-01 -2.72323266e-02 5.49969077e-01 -8.34773183e-01 -2.71716379e-02 5.44831693e-01 -8.38100612e-01 -2.72356439e-02 5.39682090e-01 -8.41461599e-01 -2.72406936e-02 5.34503043e-01 -8.44758809e-01 -2.71977112e-02 5.29315889e-01 -8.47989678e-01 -2.71674208e-02 5.24103522e-01 -8.51251423e-01 -2.71951146e-02 5.18862963e-01 -8.54429305e-01 -2.71991417e-02 5.13612628e-01 -8.57601225e-01 -2.72283405e-02 5.08349359e-01 -8.60749602e-01 -2.72443146e-02 5.03057301e-01 -8.63827884e-01 -2.72756927e-02 4.97745872e-01 -8.66900742e-01 -2.73333788e-02 4.92415905e-01 -8.69936705e-01 -2.73409281e-02 4.87070471e-01 -8.72969508e-01 -2.73514129e-02 4.81698245e-01 -8.75904441e-01 -2.73853391e-02 4.76309001e-01 -8.78843248e-01 -2.73949150e-02 4.70899880e-01 -8.81754816e-01 -2.73926090e-02 4.65488881e-01 -8.84655297e-01 -2.73939222e-02 4.60041225e-01 -8.87476325e-01 -2.73754206e-02 4.54605043e-01 -8.90299141e-01 -2.74531692e-02 4.49126601e-01 -8.93071651e-01 -2.74464004e-02 4.43633437e-01 -8.95788968e-01 -2.74102110e-02 4.38135177e-01 -8.98487926e-01 -2.74225511e-02 4.32621241e-01 -9.01151478e-01 -2.73677073e-02 4.27079707e-01 -9.03805494e-01 -2.74114404e-02 4.21528339e-01 -9.06398475e-01 -2.73780897e-02 4.15960073e-01 -9.08985376e-01 -2.74449270e-02 4.10372466e-01 -9.11532938e-01 -2.74424236e-02 4.04767483e-01 -9.14007783e-01 -2.73701604e-02 3.99150610e-01 -9.16503310e-01 -2.74068117e-02 3.93530905e-01 -9.18937266e-01 -2.74172965e-02 3.87870669e-01 -9.21298862e-01 -2.74059828e-02 3.82218570e-01 -9.23693478e-01 -2.73313019e-02 3.76543105e-01 -9.26012635e-01 -2.73690522e-02 3.70841056e-01 -9.28282678e-01 -2.74573229e-02 3.65153313e-01 -9.30560410e-01 -2.74902545e-02 3.59425157e-01 -9.32762802e-01 -2.74767149e-02 3.53693783e-01 -9.34953690e-01 -2.74900552e-02 3.47952843e-01 -9.37129855e-01 -2.74924058e-02 3.42199594e-01 -9.39222097e-01 -2.74032839e-02 3.36422324e-01 -9.41292226e-01 -2.73932628e-02 3.30642611e-01 -9.43351090e-01 -2.73955818e-02 3.24847639e-01 -9.45350826e-01 -2.74053626e-02 3.19037378e-01 -9.47360635e-01 -2.74028201e-02 3.13229501e-01 -9.49255049e-01 -2.73769628e-02 3.07394713e-01 -9.51179564e-01 -2.73516010e-02 3.01558167e-01 -9.53030825e-01 -2.73704249e-02 2.95702577e-01 -9.54866767e-01 -2.73749009e-02 2.89834589e-01 -9.56676960e-01 -2.73123439e-02 2.83963472e-01 -9.58456933e-01 -2.71355473e-02 2.78084755e-01 -9.60190296e-01 -2.66056228e-02 2.72194535e-01 -9.61888194e-01 -2.61746254e-02 2.66287059e-01 -9.63536918e-01 -2.62194239e-02 2.60379761e-01 -9.65170383e-01 -2.53872834e-02 2.54449576e-01 -9.66743946e-01 -2.56330837e-02 2.48510376e-01 -9.68283236e-01 -2.58916803e-02 2.42560670e-01 -9.69782531e-01 -2.61974297e-02 2.36605600e-01 -9.71252501e-01 -2.61990447e-02 2.30643943e-01 -9.72690523e-01 -2.60088779e-02 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. 0. 0. 0. 0. 0. 1.58522695e-01 -9.87156510e-01 -1.98149681e-02 0. 0. 0. 1.46366939e-01 -9.88957763e-01 -2.30419785e-02 1.40274018e-01 -9.89783823e-01 -2.54184175e-02 1.34189546e-01 -9.90604341e-01 -2.63587050e-02 1.28107429e-01 -9.91409421e-01 -2.64965091e-02 1.22022130e-01 -9.92173314e-01 -2.64710430e-02 1.15933239e-01 -9.92910266e-01 -2.63610594e-02 1.09837785e-01 -9.93597806e-01 -2.64465325e-02 1.03742093e-01 -9.94260192e-01 -2.60863099e-02 9.76375937e-02 -9.94873106e-01 -2.63198018e-02 9.15288180e-02 -9.95441973e-01 -2.66543198e-02 8.54173154e-02 -9.95979249e-01 -2.68237852e-02 7.93055668e-02 -9.96494174e-01 -2.66900491e-02 7.31918886e-02 -9.96966481e-01 -2.64271032e-02 6.70701265e-02 -9.97382700e-01 -2.68126391e-02 6.09466285e-02 -9.97785211e-01 -2.70784739e-02 5.48227243e-02 -9.98133183e-01 -2.71985773e-02 4.86971848e-02 -9.98432219e-01 -2.72557586e-02 4.25694324e-02 -9.98742819e-01 -2.72634849e-02 3.64408568e-02 -9.98985291e-01 -2.72815786e-02 3.03103812e-02 -9.99145985e-01 -2.73015574e-02 2.41789557e-02 -9.99350905e-01 -2.73082051e-02 1.80468019e-02 -9.99470949e-01 -2.73049418e-02 1.19135473e-02 -9.99531925e-01 -2.73374934e-02 5.78017486e-03 -9.99611378e-01 -2.73429602e-02 -3.53695272e-04 -9.99618053e-01 -2.74037123e-02 -6.48744777e-03 -9.99612153e-01 -2.74454318e-02 -1.26201073e-02 -9.99528885e-01 -2.73245294e-02 -1.87529679e-02 -9.99474108e-01 -2.73165703e-02 -2.48848367e-02 -9.99292016e-01 -2.72836741e-02 -3.10162250e-02 -9.99138534e-01 -2.72960272e-02 -3.71459685e-02 -9.98920321e-01 -2.72761136e-02 -4.32746783e-02 -9.98677671e-01 -2.72422433e-02 -4.94015701e-02 -9.98406529e-01 -2.72455905e-02 -5.55267334e-02 -9.98068035e-01 -2.72527225e-02 -6.16497993e-02 -9.97706592e-01 -2.72580627e-02 -6.77708760e-02 -9.97314930e-01 -2.72494592e-02 -7.38894343e-02 -9.96909082e-01 -2.72503663e-02 -8.00043046e-02 -9.96430814e-01 -2.73018163e-02 -8.61162618e-02 -9.95933950e-01 -2.72504240e-02 -9.22265351e-02 -9.95357275e-01 -2.72899121e-02 -9.83316749e-02 -9.94770885e-01 -2.72956360e-02 -1.04433544e-01 -9.94142473e-01 -2.73227412e-02 -1.10531911e-01 -9.93518114e-01 -2.73165759e-02 -1.16625950e-01 -9.92794216e-01 -2.73242537e-02 -1.22716472e-01 -9.92060840e-01 -2.73525435e-02 -1.28802761e-01 -9.91305888e-01 -2.73436066e-02 -1.34881243e-01 -9.90489900e-01 -2.74756998e-02 -1.40955284e-01 -9.89619911e-01 -2.74774339e-02 -1.47024363e-01 -9.88740385e-01 -2.74667460e-02 -1.53088257e-01 -9.87828672e-01 -2.74806842e-02 -1.59150034e-01 -9.86908317e-01 -2.74646077e-02 -1.65199012e-01 -9.85872388e-01 -2.74664685e-02 -1.71243951e-01 -9.84850585e-01 -2.74453554e-02 -1.77285358e-01 -9.83767688e-01 -2.73562595e-02 -1.83317602e-01 -9.82665360e-01 -2.73818858e-02 -1.89349413e-01 -9.81542885e-01 -2.74580270e-02 -1.95365041e-01 -9.80354190e-01 -2.74976715e-02 -2.01375395e-01 -9.79128361e-01 -2.75197513e-02 -2.07380891e-01 -9.77897286e-01 -2.73634568e-02 -2.13373661e-01 -9.76571918e-01 -2.73733810e-02 -2.19369218e-01 -9.75246549e-01 -2.74068899e-02 -2.25348100e-01 -9.73886132e-01 -2.73182057e-02 -2.31310949e-01 -9.72506583e-01 -2.73026712e-02 -2.37277851e-01 -9.71064925e-01 -2.72843204e-02 -2.43232012e-01 -9.69598889e-01 -2.72705164e-02 -2.49176264e-01 -9.68062043e-01 -2.72339415e-02 -2.55111456e-01 -9.66529548e-01 -2.72953399e-02 -2.61040568e-01 -9.64956820e-01 -2.72208378e-02 -2.66956270e-01 -9.63301122e-01 -2.73317639e-02 -2.72858858e-01 -9.61681902e-01 -2.71875821e-02 -2.78755724e-01 -9.59970891e-01 -2.72583626e-02 -2.84638196e-01 -9.58254993e-01 -2.72550751e-02 -2.90513843e-01 -9.56472099e-01 -2.72586327e-02 -2.96375364e-01 -9.54688668e-01 -2.72750948e-02 -3.02232057e-01 -9.52861488e-01 -2.73470227e-02 -3.08068454e-01 -9.50972557e-01 -2.72446256e-02 -3.13902289e-01 -9.49066281e-01 -2.72384007e-02 -3.19713026e-01 -9.47118938e-01 -2.72349734e-02 -3.25525761e-01 -9.45122600e-01 -2.73074899e-02 -3.31316054e-01 -9.43133593e-01 -2.72624958e-02 -3.37095559e-01 -9.41063821e-01 -2.73200031e-02 -3.42864662e-01 -9.38980579e-01 -2.73956954e-02 -3.48624259e-01 -9.36876059e-01 -2.74081435e-02 -3.54361713e-01 -9.34710145e-01 -2.73480359e-02 -3.60095471e-01 -9.32525575e-01 -2.70137694e-02 -3.65807861e-01 -9.30308700e-01 -2.73669548e-02 -3.71506035e-01 -9.28009093e-01 -2.73981038e-02 -3.77191991e-01 -9.25712705e-01 -2.73793954e-02 -3.82864147e-01 -9.23385918e-01 -2.73831971e-02 -3.88527215e-01 -9.21041906e-01 -2.73867957e-02 -3.94166976e-01 -9.18609738e-01 -2.74011046e-02 -3.99807066e-01 -9.16187584e-01 -2.73843426e-02 -4.05424416e-01 -9.13729489e-01 -2.69973259e-02 -4.11010861e-01 -9.11246121e-01 -2.69595068e-02 -4.16593105e-01 -9.08698261e-01 -2.69719251e-02 -4.22154367e-01 -9.06119585e-01 -2.73764841e-02 -4.27704781e-01 -9.03470933e-01 -2.73905024e-02 -4.33245093e-01 -9.00870264e-01 -2.73912586e-02 -4.38765645e-01 -8.98191690e-01 -2.73761693e-02 -4.44276839e-01 -8.95445287e-01 -2.73511093e-02 -4.49763417e-01 -8.92723322e-01 -2.73426082e-02 -4.55218285e-01 -8.89926016e-01 -2.73581520e-02 -4.60684568e-01 -8.87119055e-01 -2.73497403e-02 -4.66117680e-01 -8.84301543e-01 -2.73560025e-02 -4.71517235e-01 -8.81399214e-01 -2.73385532e-02 -4.76922363e-01 -8.78500998e-01 -2.73715872e-02 -4.82308567e-01 -8.75546813e-01 -2.73576248e-02 -4.87677127e-01 -8.72582138e-01 -2.73896884e-02 -4.93020594e-01 -8.69565725e-01 -2.72905063e-02 -4.98344749e-01 -8.66520047e-01 -2.72902325e-02 -5.03646612e-01 -8.63448203e-01 -2.72925198e-02 -5.08946776e-01 -8.60371888e-01 -2.72733457e-02 -5.14209926e-01 -8.57220948e-01 -2.72966102e-02 -5.19458234e-01 -8.54045510e-01 -2.72596013e-02 -5.24697065e-01 -8.50865245e-01 -2.72693299e-02 -5.29906094e-01 -8.47601652e-01 -2.72583887e-02 -5.35085678e-01 -8.44336987e-01 -2.72624325e-02 -5.40268958e-01 -8.41024756e-01 -2.73070354e-02 -5.45427680e-01 -8.37722063e-01 -2.72971019e-02 -5.50560832e-01 -8.34383667e-01 -2.72976141e-02 -5.55672169e-01 -8.30986261e-01 -2.72196103e-02 -5.60736954e-01 -8.27555358e-01 -2.72339731e-02 -5.65821171e-01 -8.24077964e-01 -2.72097327e-02 -5.70846140e-01 -8.20600688e-01 -2.72075031e-02 -5.75868726e-01 -8.17080081e-01 -2.72125378e-02 -5.80870986e-01 -8.13529611e-01 -2.72145346e-02 -5.85857928e-01 -8.09986413e-01 -2.67732516e-02 -5.90836644e-01 -8.06351125e-01 -2.67505664e-02 -5.95760643e-01 -8.02701533e-01 -2.67427936e-02 -6.00696445e-01 -7.99033225e-01 -2.67635807e-02 -6.05580151e-01 -7.95340776e-01 -2.71500498e-02 -6.10448658e-01 -7.91583061e-01 -2.71532256e-02 -6.15281522e-01 -7.87829399e-01 -2.70854421e-02 -6.20124459e-01 -7.84043968e-01 -2.70951912e-02 -6.24901712e-01 -7.80236602e-01 -2.70924307e-02 -6.29677236e-01 -7.76362479e-01 -2.70951353e-02 -6.34426415e-01 -7.72524238e-01 -2.70903260e-02 -6.39171600e-01 -7.68620610e-01 -2.70802490e-02 -6.43853784e-01 -7.64648199e-01 -2.70653628e-02 -6.48561597e-01 -7.60711610e-01 -2.70604845e-02 -6.53207541e-01 -7.56694615e-01 -2.70514917e-02 -6.57843351e-01 -7.52671838e-01 -2.70257164e-02 -6.62454545e-01 -7.48636365e-01 -2.70174965e-02 -6.67010546e-01 -7.44578779e-01 -2.70082057e-02 -6.71599984e-01 -7.40460336e-01 -2.69818362e-02 -6.76122665e-01 -7.36313343e-01 -2.69763563e-02 -6.80634379e-01 -7.32163608e-01 -2.69869547e-02 -6.85087323e-01 -7.27984488e-01 -2.69913711e-02 -6.89567566e-01 -7.23746538e-01 -2.69703381e-02 -6.93973124e-01 -7.19490230e-01 -2.69734655e-02 -6.98370039e-01 -7.15217829e-01 -2.69737616e-02 -7.02755213e-01 -7.10931718e-01 -2.69602891e-02 -7.07121849e-01 -7.06628680e-01 -2.69682296e-02 -7.11421907e-01 -7.02264011e-01 -2.69635040e-02 -7.15715051e-01 -6.97876632e-01 -2.69431658e-02 -7.19986379e-01 -6.93482041e-01 -2.69167330e-02 -7.24234223e-01 -6.89059734e-01 -2.69004218e-02 -7.28470087e-01 -6.84578598e-01 -2.69181933e-02 -7.32646763e-01 -6.80093467e-01 -2.69243494e-02 -7.36800134e-01 -6.75581336e-01 -2.69299243e-02 -7.40940690e-01 -6.71052158e-01 -2.69165188e-02 -7.45007038e-01 -6.66510820e-01 -2.68969890e-02 -7.49119103e-01 -6.61906898e-01 -2.68790964e-02 -7.53153980e-01 -6.57328606e-01 -2.68964283e-02 -7.57179081e-01 -6.52695239e-01 -2.68545095e-02 -7.61177301e-01 -6.48006797e-01 -2.68420391e-02 -7.65115559e-01 -6.43333197e-01 -2.68346295e-02 -7.69040227e-01 -6.38631344e-01 -2.68877186e-02 -7.72946298e-01 -6.33899093e-01 -2.68546883e-02 -7.76819468e-01 -6.29141986e-01 -2.68352926e-02 -7.80685782e-01 -6.24362707e-01 -2.68059727e-02 -7.84500778e-01 -6.19557321e-01 -2.67217774e-02 -7.88288713e-01 -6.14740431e-01 -2.63840780e-02 -7.92031288e-01 -6.09890580e-01 -2.66111996e-02 -7.95776725e-01 -6.05026066e-01 -2.62174066e-02 -7.99518824e-01 -6.00193739e-01 -2.29439177e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.24497342e-01 -5.65246761e-01 -2.64380220e-02 -8.27950597e-01 -5.60177386e-01 -2.64385398e-02 -8.31388950e-01 -5.55105031e-01 -2.54520494e-02 -8.34796607e-01 -5.50012469e-01 -2.43740752e-02 -8.38127851e-01 -5.44849277e-01 -2.60954034e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.90257776e-01 -4.54583496e-01 -2.81952582e-02 0. 0. 0. -8.95819068e-01 -4.43664581e-01 -2.58834902e-02 -8.98541391e-01 -4.38174129e-01 -2.49420889e-02 -9.01195586e-01 -4.32640553e-01 -2.58613639e-02 -9.03823137e-01 -4.27099615e-01 -2.60588322e-02 -9.06420588e-01 -4.21541423e-01 -2.62684766e-02 -9.08983588e-01 -4.15969998e-01 -2.63729263e-02 -9.11535382e-01 -4.10378188e-01 -2.65399013e-02 -9.14014339e-01 -4.04773325e-01 -2.66711339e-02 -9.16510165e-01 -3.99157941e-01 -2.67522242e-02 -9.18930590e-01 -3.93535048e-01 -2.67711319e-02 -9.21304345e-01 -3.87876540e-01 -2.67789252e-02 -9.23709154e-01 -3.82227361e-01 -2.67693922e-02 -9.26023781e-01 -3.76552701e-01 -2.67411359e-02 -9.28300023e-01 -3.70858997e-01 -2.67342534e-02 -9.30575430e-01 -3.65164012e-01 -2.66451016e-02 -9.32784617e-01 -3.59440744e-01 -2.62740720e-02 -9.34972942e-01 -3.53705853e-01 -2.65608672e-02 -9.37141597e-01 -3.47965121e-01 -2.65848264e-02 -9.39247608e-01 -3.42215329e-01 -2.66349558e-02 -9.41327333e-01 -3.36438805e-01 -2.66570058e-02 -9.43387151e-01 -3.30662042e-01 -2.66726129e-02 -9.45377767e-01 -3.24868560e-01 -2.66337395e-02 -9.47385907e-01 -3.19052309e-01 -2.65493225e-02 -9.49283719e-01 -3.13243985e-01 -2.64329053e-02 -9.51217115e-01 -3.07409853e-01 -2.65432540e-02 -9.53042746e-01 -3.01571220e-01 -2.65475940e-02 -9.54901814e-01 -2.95716017e-01 -2.66245250e-02 -9.56679642e-01 -2.89840847e-01 -2.65774745e-02 -9.58448470e-01 -2.83964902e-01 -2.65509691e-02 -9.60170388e-01 -2.78086156e-01 -2.65431087e-02 -9.61839080e-01 -2.72188932e-01 -2.64705122e-02 -9.63517964e-01 -2.66275585e-01 -2.64774822e-02 -9.65142190e-01 -2.60364830e-01 -2.64218859e-02 -9.66691554e-01 -2.54433006e-01 -2.65026912e-02 -9.68234420e-01 -2.48504892e-01 -2.65324265e-02 -9.69779730e-01 -2.42553160e-01 -2.65211165e-02 -9.71246481e-01 -2.36605972e-01 -2.65128259e-02 -9.72665608e-01 -2.30636194e-01 -2.66054068e-02 -9.74051774e-01 -2.24662736e-01 -2.66066976e-02 -9.75448072e-01 -2.18676537e-01 -2.66632717e-02 -9.76716518e-01 -2.12692931e-01 -2.65079048e-02 -9.78030801e-01 -2.06697643e-01 -2.66234633e-02 -9.79302704e-01 -2.00690821e-01 -2.66370866e-02 -9.80519295e-01 -1.94677711e-01 -2.66743097e-02 -9.81678069e-01 -1.88657805e-01 -2.66474858e-02 -9.82810259e-01 -1.82630792e-01 -2.66337283e-02 -9.83938277e-01 -1.76600054e-01 -2.66448259e-02 -9.85002995e-01 -1.70559421e-01 -2.66436972e-02 -9.85998452e-01 -1.64509237e-01 -2.66395211e-02 -9.86976087e-01 -1.58455878e-01 -2.66617555e-02 -9.87935364e-01 -1.52396202e-01 -2.66638361e-02 -9.88897860e-01 -1.46334305e-01 -2.66755018e-02 -9.89729881e-01 -1.40263781e-01 -2.66658589e-02 -9.90614116e-01 -1.34188533e-01 -2.66602095e-02 -9.91377652e-01 -1.28104419e-01 -2.66633183e-02 -9.92168725e-01 -1.22021571e-01 -2.66469363e-02 -9.92905438e-01 -1.15930967e-01 -2.66060568e-02 -9.93582249e-01 -1.09837793e-01 -2.65469681e-02 -9.94271576e-01 -1.03738338e-01 -2.64515039e-02 -9.94882226e-01 -9.76365954e-02 -2.62245778e-02 -9.95460808e-01 -9.15358290e-02 -2.57383659e-02 -9.96015787e-01 -8.54276642e-02 -2.55872495e-02 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. 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. -9.97442365e-01 3.12655941e-02 -6.42742142e-02 -9.97231722e-01 3.73852141e-02 -6.42742440e-02 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. 0. 0. 0. 0. 0. -9.92031217e-01 1.10649176e-01 -6.02409802e-02 0. 0. 0. -9.90489781e-01 1.22811683e-01 -6.20260872e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.72175300e-01 2.25256085e-01 -6.43032789e-02 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. 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. -9.39543664e-01 3.36852640e-01 -6.15362339e-02 -9.37448323e-01 3.42610031e-01 -6.17031492e-02 -9.35330153e-01 3.48355353e-01 -6.18361160e-02 -9.33134258e-01 3.54076982e-01 -6.21144436e-02 -9.30930257e-01 3.59795094e-01 -6.23034425e-02 -9.28723037e-01 3.65496188e-01 -6.23985119e-02 -9.26434636e-01 3.71183455e-01 -6.24497682e-02 -9.24178958e-01 3.76875132e-01 -6.23525083e-02 -9.21806872e-01 3.82531524e-01 -6.24966286e-02 -9.19463158e-01 3.88175964e-01 -6.24575615e-02 -9.17062521e-01 3.93817335e-01 -6.23654388e-02 -9.14667785e-01 3.99444431e-01 -6.19149469e-02 -9.12210464e-01 4.05055135e-01 -6.16637617e-02 -9.09700871e-01 4.10641700e-01 -6.17864653e-02 -9.07168031e-01 4.16217059e-01 -6.17203005e-02 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. 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. 0. 0. 0. 0. 0. 0. 0. -8.42913926e-01 5.34524918e-01 -6.14754818e-02 -8.39607418e-01 5.39681256e-01 -6.16707355e-02 -8.36279571e-01 5.44822097e-01 -6.17352501e-02 -8.32922161e-01 5.49934626e-01 -6.19142316e-02 -8.29521000e-01 5.55035233e-01 -6.19629696e-02 -8.26108336e-01 5.60118973e-01 -6.17634393e-02 -8.22647989e-01 5.65179169e-01 -6.17112406e-02 -8.19172561e-01 5.70220947e-01 -6.16949275e-02 -8.15646529e-01 5.75227022e-01 -6.19275905e-02 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.86456525e-01 6.14565849e-01 -6.13972321e-02 -7.82640457e-01 6.19359791e-01 -6.21673502e-02 -7.78844833e-01 6.24163628e-01 -6.16781786e-02 -7.75090218e-01 6.28987670e-01 -5.95114753e-02 -7.71130025e-01 6.33675158e-01 -6.17814027e-02 -7.67188072e-01 6.38376117e-01 -6.23202883e-02 -7.63262451e-01 6.43063664e-01 -6.25720844e-02 -7.59286821e-01 6.47732675e-01 -6.26410469e-02 -7.55307555e-01 6.52386069e-01 -6.26233891e-02 -7.51286864e-01 6.57005310e-01 -6.26253411e-02 -7.47233212e-01 6.61595762e-01 -6.26295209e-02 -7.43168414e-01 6.66171014e-01 -6.26356378e-02 -7.39064813e-01 6.70718849e-01 -6.26223460e-02 -7.34927535e-01 6.75235510e-01 -6.26463443e-02 -7.30777085e-01 6.79739058e-01 -6.26513064e-02 -7.26598322e-01 6.84203684e-01 -6.26257434e-02 -7.22375572e-01 6.88660741e-01 -6.26161918e-02 -7.18147159e-01 6.93082273e-01 -6.25997856e-02 -7.13880956e-01 6.97479129e-01 -6.25394285e-02 -7.09580421e-01 7.01849759e-01 -6.24705926e-02 -7.05273032e-01 7.06180573e-01 -6.25291690e-02 -7.00918376e-01 7.10508645e-01 -6.24592081e-02 -6.96552575e-01 7.14789808e-01 -6.24095947e-02 -6.92143857e-01 7.19052076e-01 -6.24155700e-02 -6.87740207e-01 7.23283112e-01 -6.24248274e-02 -6.83270037e-01 7.27468789e-01 -6.24818355e-02 -6.78804278e-01 7.31659770e-01 -6.25242144e-02 -6.74301028e-01 7.35820293e-01 -6.25721291e-02 -6.69763982e-01 7.39916742e-01 -6.26036674e-02 -6.65204346e-01 7.44022846e-01 -6.26482293e-02 -6.60646498e-01 7.48072088e-01 -6.26921654e-02 -6.56032979e-01 7.52147734e-01 -6.26877099e-02 -6.51409209e-01 7.56148219e-01 -6.26953393e-02 -6.46761894e-01 7.60109186e-01 -6.26827627e-02 -6.42062426e-01 7.64095068e-01 -6.26586303e-02 -6.37377679e-01 7.68019557e-01 -6.26887530e-02 -6.32657349e-01 7.71916568e-01 -6.25822619e-02 -6.27906919e-01 7.75784016e-01 -6.25769943e-02 -6.23131156e-01 7.79601693e-01 -6.26135767e-02 -6.18329823e-01 7.83407390e-01 -6.27452731e-02 -6.13524675e-01 7.87183821e-01 -6.27791733e-02 -6.08666599e-01 7.90929139e-01 -6.28063083e-02 -6.03792906e-01 7.94665754e-01 -6.28489777e-02 -5.98916769e-01 7.98353434e-01 -6.28308803e-02 -5.94012022e-01 8.02006662e-01 -6.28225282e-02 -5.89070022e-01 8.05653870e-01 -6.28062189e-02 -5.84127247e-01 8.09229553e-01 -6.28195032e-02 -5.79147339e-01 8.12820196e-01 -6.27828166e-02 -5.74148476e-01 8.16354871e-01 -6.27097413e-02 -5.69127858e-01 8.19846392e-01 -6.27389029e-02 -5.64084113e-01 8.23332906e-01 -6.27214164e-02 -5.59022367e-01 8.26773465e-01 -6.27560914e-02 -5.53949058e-01 8.30188751e-01 -6.27164692e-02 -5.48839629e-01 8.33569527e-01 -6.27915859e-02 -5.43711662e-01 8.36938262e-01 -6.28276616e-02 -5.38557887e-01 8.40254724e-01 -6.29128069e-02 -5.33390224e-01 8.43542933e-01 -6.29624873e-02 -5.28206468e-01 8.46803248e-01 -6.29841611e-02 -5.23001909e-01 8.50001514e-01 -6.29705489e-02 -5.17774045e-01 8.53192329e-01 -6.29608035e-02 -5.12530684e-01 8.56356740e-01 -6.29762635e-02 -5.07268727e-01 8.59498262e-01 -6.29860386e-02 -5.01963615e-01 8.62553060e-01 -6.31125420e-02 -4.96679127e-01 8.65643501e-01 -6.31557480e-02 -4.91338521e-01 8.68646085e-01 -6.31546974e-02 -4.86005157e-01 8.71650040e-01 -6.31623641e-02 -4.80648786e-01 8.74631822e-01 -6.31719753e-02 -4.75269526e-01 8.77559304e-01 -6.31821826e-02 -4.69884753e-01 8.80465031e-01 -6.31777346e-02 -4.64477450e-01 8.83326948e-01 -6.32305592e-02 -4.59040701e-01 8.86163414e-01 -6.32442012e-02 -4.53595370e-01 8.88941586e-01 -6.32674992e-02 -4.48130041e-01 8.91748786e-01 -6.32577762e-02 -4.42649513e-01 8.94450963e-01 -6.32764772e-02 -4.37155247e-01 8.97149742e-01 -6.32037893e-02 -4.31633383e-01 8.99811864e-01 -6.32769167e-02 -4.26113099e-01 9.02480006e-01 -6.32746518e-02 -4.20560122e-01 9.05069351e-01 -6.32788911e-02 -4.15008396e-01 9.07607496e-01 -6.33231401e-02 -4.09435183e-01 9.10137117e-01 -6.33291975e-02 -4.03842986e-01 9.12645578e-01 -6.33421838e-02 -3.98238271e-01 9.15130794e-01 -6.33325502e-02 -3.92604768e-01 9.17520165e-01 -6.33245111e-02 -3.86974871e-01 9.19933975e-01 -6.33422509e-02 -3.81315857e-01 9.22248840e-01 -6.33358359e-02 -3.75649959e-01 9.24625874e-01 -6.33172691e-02 -3.69976759e-01 9.26876783e-01 -6.32737800e-02 -3.64282578e-01 9.29165900e-01 -6.28746673e-02 -3.58592153e-01 9.31393027e-01 -6.28625527e-02 -3.52857500e-01 9.33536291e-01 -6.32482395e-02 -3.47118676e-01 9.35700893e-01 -6.32382259e-02 -3.41363192e-01 9.37824607e-01 -6.32540509e-02 -3.35617721e-01 9.39872563e-01 -6.32581338e-02 -3.29834878e-01 9.41944420e-01 -6.32132813e-02 -3.24051827e-01 9.43922043e-01 -6.32531792e-02 -3.18258464e-01 9.45886135e-01 -6.32691830e-02 -3.12435150e-01 9.47822452e-01 -6.32649064e-02 -3.06625277e-01 9.49761093e-01 -6.32493943e-02 -3.00788254e-01 9.51621175e-01 -6.32583648e-02 -2.94943005e-01 9.53423738e-01 -6.32591620e-02 -2.89090514e-01 9.55218732e-01 -6.32578954e-02 -2.83221155e-01 9.56986308e-01 -6.32609203e-02 -2.77341217e-01 9.58705246e-01 -6.32639006e-02 -2.71453559e-01 9.60396647e-01 -6.32413849e-02 -2.65557051e-01 9.62031603e-01 -6.32568970e-02 -2.59648114e-01 9.63656366e-01 -6.32577837e-02 -2.53730148e-01 9.65215027e-01 -6.32404611e-02 -2.47801349e-01 9.66751575e-01 -6.32541701e-02 -2.41869509e-01 9.68279600e-01 -6.32700026e-02 -2.35920876e-01 9.69743609e-01 -6.32636026e-02 -2.29963839e-01 9.71187294e-01 -6.32700101e-02 -2.24003702e-01 9.72521722e-01 -6.32724315e-02 -2.18032017e-01 9.73890305e-01 -6.32768199e-02 -2.12048620e-01 9.75198090e-01 -6.32808730e-02 -2.06067607e-01 9.76498902e-01 -6.32925928e-02 -2.00068250e-01 9.77766514e-01 -6.33068383e-02 -1.94067478e-01 9.78984892e-01 -6.33034632e-02 -1.88053623e-01 9.80147779e-01 -6.33209795e-02 -1.82037830e-01 9.81259406e-01 -6.33360371e-02 -1.76011190e-01 9.82390046e-01 -6.33500665e-02 -1.69980690e-01 9.83400345e-01 -6.33591637e-02 -1.63946986e-01 9.84436512e-01 -6.32071942e-02 -1.57897472e-01 9.85412776e-01 -6.33599982e-02 -1.51850998e-01 9.86370146e-01 -6.33801147e-02 -1.45796239e-01 9.87282872e-01 -6.33517057e-02 -1.39735922e-01 9.88189340e-01 -6.33468479e-02 -1.33668989e-01 9.88991141e-01 -6.33626059e-02 -1.27598122e-01 9.89795923e-01 -6.33388683e-02 -1.21522933e-01 9.90609646e-01 -6.33553192e-02 -1.15438789e-01 9.91327167e-01 -6.33544549e-02 -1.09355927e-01 9.91977334e-01 -6.33441806e-02 -1.03268787e-01 9.92642224e-01 -6.33386299e-02 -9.71733704e-02 9.93287504e-01 -6.33284748e-02 -9.10799503e-02 9.93855476e-01 -6.33149818e-02 -8.49779025e-02 9.94354069e-01 -6.33017421e-02 -7.88766965e-02 9.94856298e-01 -6.32997900e-02 -7.27705806e-02 9.95325983e-01 -6.33473620e-02 -6.66596666e-02 9.95789528e-01 -6.33492321e-02 -6.05501793e-02 9.96136963e-01 -6.33724257e-02 -5.44361323e-02 9.96532083e-01 -6.33877814e-02 -4.83208299e-02 9.96800900e-01 -6.33774996e-02 -4.22032401e-02 9.97093916e-01 -6.33781627e-02 -3.60847861e-02 9.97339427e-01 -6.33619726e-02 -2.99647357e-02 9.97529507e-01 -6.33599535e-02 -2.38430854e-02 9.97736573e-01 -6.33628890e-02 -1.77208930e-02 9.97830451e-01 -6.33483082e-02 -1.15979668e-02 9.97929335e-01 -6.33421689e-02 -5.47456462e-03 9.98000622e-01 -6.33257627e-02 6.49304246e-04 9.98000920e-01 -6.33630827e-02 6.77303597e-03 9.97994781e-01 -6.33803532e-02 1.28962155e-02 9.97929215e-01 -6.33794516e-02 1.90190990e-02 9.97826159e-01 -6.33634552e-02 2.51415037e-02 9.97688293e-01 -6.33937046e-02 3.12623046e-02 9.97515798e-01 -6.33565933e-02 3.73820439e-02 9.97289717e-01 -6.33508936e-02 4.35015596e-02 9.97035384e-01 -6.33433759e-02 4.96178269e-02 9.96785104e-01 -6.33212849e-02 5.57331890e-02 9.96450782e-01 -6.32875487e-02 6.18465766e-02 9.96079028e-01 -6.32829070e-02 6.79579154e-02 9.95678186e-01 -6.32779226e-02 7.40636587e-02 9.95229483e-01 -6.31850734e-02 8.01682174e-02 9.94823575e-01 -6.23222962e-02 8.62704068e-02 9.94407177e-01 -6.08852208e-02 9.23706666e-02 9.93741870e-01 -6.27886355e-02 9.84665975e-02 9.93189156e-01 -6.22622669e-02 1.04558274e-01 9.92486238e-01 -6.35461658e-02 1.10646315e-01 9.91823256e-01 -6.36301562e-02 1.16729282e-01 9.91123080e-01 -6.36394918e-02 0. 0. 0. 0. 0. 0. 1.34952217e-01 9.88790512e-01 -6.38842657e-02 1.41025871e-01 9.88135099e-01 -6.08121492e-02 1.47080779e-01 9.87144709e-01 -6.25177994e-02 1.53132111e-01 9.86194193e-01 -6.29207939e-02 1.59179673e-01 9.85215604e-01 -6.31029829e-02 1.65221870e-01 9.84227598e-01 -6.31704554e-02 1.71256557e-01 9.83170509e-01 -6.32692203e-02 1.77286103e-01 9.82127488e-01 -6.33903146e-02 1.83312029e-01 9.81024444e-01 -6.34163469e-02 1.89325422e-01 9.79850888e-01 -6.33138344e-02 1.95335671e-01 9.78708446e-01 -6.33347407e-02 2.01337814e-01 9.77489412e-01 -6.34068623e-02 2.07329988e-01 9.76207316e-01 -6.33921251e-02 2.13315442e-01 9.74937797e-01 -6.33699968e-02 2.19293296e-01 9.73617733e-01 -6.33887798e-02 2.25262314e-01 9.72251594e-01 -6.33635595e-02 2.31222793e-01 9.70823169e-01 -6.34704828e-02 2.37178281e-01 9.69381273e-01 -6.34736642e-02 2.43122876e-01 9.67899621e-01 -6.34608865e-02 2.49056652e-01 9.66421127e-01 -6.34904057e-02 2.54978597e-01 9.64847207e-01 -6.34661615e-02 2.60893285e-01 9.63264644e-01 -6.34967163e-02 2.66799510e-01 9.61675167e-01 -6.34618625e-02 2.72697628e-01 9.59979951e-01 -6.34323359e-02 2.78583705e-01 9.58292961e-01 -6.34230673e-02 2.84458816e-01 9.56571579e-01 -6.34496808e-02 2.90320843e-01 9.54842269e-01 -6.34695068e-02 2.96171457e-01 9.53012168e-01 -6.35019913e-02 3.02015662e-01 9.51203704e-01 -6.34770840e-02 3.07851791e-01 9.49347854e-01 -6.34230375e-02 3.13667446e-01 9.47413743e-01 -6.34605214e-02 3.19480896e-01 9.45473492e-01 -6.34395555e-02 3.25273097e-01 9.43508029e-01 -6.34188503e-02 3.31056744e-01 9.41466451e-01 -6.33919910e-02 3.36823076e-01 9.39413428e-01 -6.33512437e-02 3.42579275e-01 9.37334776e-01 -6.33939654e-02 3.48325193e-01 9.35239494e-01 -6.33464828e-02 3.54059786e-01 9.33058918e-01 -6.33301288e-02 3.59778911e-01 9.30876672e-01 -6.34053573e-02 3.65481496e-01 9.28668618e-01 -6.34283051e-02 3.71178001e-01 9.26385224e-01 -6.34148791e-02 3.76859903e-01 9.24106896e-01 -6.33822158e-02 3.82523179e-01 9.21756029e-01 -6.34329990e-02 3.88164908e-01 9.19415474e-01 -6.33987710e-02 3.93797964e-01 9.16998565e-01 -6.33440465e-02 3.99414182e-01 9.14567709e-01 -6.33990914e-02 4.05019432e-01 9.12104785e-01 -6.32758066e-02 4.10610288e-01 9.09606576e-01 -6.33468181e-02 4.16181922e-01 9.07082438e-01 -6.32784665e-02 4.21745986e-01 9.04520214e-01 -6.32013306e-02 4.27283496e-01 9.01877940e-01 -6.32738099e-02 4.32803392e-01 8.99275303e-01 -6.32308200e-02 4.38326836e-01 8.96608174e-01 -6.32985905e-02 4.43808764e-01 8.93860638e-01 -6.32808805e-02 4.49291319e-01 8.91149998e-01 -6.32972866e-02 4.54752177e-01 8.88353705e-01 -6.33054823e-02 4.60193992e-01 8.85548294e-01 -6.33127093e-02 4.65614945e-01 8.82735670e-01 -6.33405149e-02 4.71026897e-01 8.79822195e-01 -6.33114725e-02 4.76408064e-01 8.76916528e-01 -6.34070635e-02 4.81776536e-01 8.73978138e-01 -6.34136647e-02 4.87133682e-01 8.71040225e-01 -6.33493289e-02 4.92467731e-01 8.68012130e-01 -6.33527786e-02 4.97778296e-01 8.64960730e-01 -6.33564815e-02 5.03084421e-01 8.61906171e-01 -6.33523688e-02 5.08368969e-01 8.58813763e-01 -6.33620396e-02 5.13620257e-01 8.55689943e-01 -6.33669347e-02 5.18863678e-01 8.52525711e-01 -6.33666143e-02 5.24090946e-01 8.49305928e-01 -6.33412972e-02 5.29299080e-01 8.46064568e-01 -6.33371323e-02 5.34462154e-01 8.42791915e-01 -6.33209422e-02 5.39637446e-01 8.39507997e-01 -6.33769706e-02 5.44785440e-01 8.36200833e-01 -6.32756799e-02 5.49902737e-01 8.32815647e-01 -6.33170754e-02 5.55004299e-01 8.29421699e-01 -6.32749200e-02 5.60063124e-01 8.25998664e-01 -6.32695183e-02 5.65139055e-01 8.22564960e-01 -6.32259101e-02 5.70154309e-01 8.19064021e-01 -6.32368177e-02 5.75173140e-01 8.15587342e-01 -6.33057430e-02 5.80165029e-01 8.12009037e-01 -6.33270591e-02 5.85137486e-01 8.08437288e-01 -6.33347407e-02 5.90108156e-01 8.04867566e-01 -6.33165762e-02 5.95021427e-01 8.01219881e-01 -6.33073151e-02 5.99930108e-01 7.97557712e-01 -6.32930025e-02 6.04818285e-01 7.93834984e-01 -6.32854328e-02 6.09654129e-01 7.90129185e-01 -6.32842407e-02 6.14495754e-01 7.86373973e-01 -6.32856116e-02 6.19327724e-01 7.82598794e-01 -6.32443205e-02 6.24111235e-01 7.78754115e-01 -6.32495582e-02 6.28868580e-01 7.74926305e-01 -6.32626116e-02 6.33614779e-01 7.71032751e-01 -6.32556677e-02 6.38350368e-01 7.67133772e-01 -6.32697269e-02 6.43023252e-01 7.63226271e-01 -6.32665977e-02 6.47713780e-01 7.59242177e-01 -6.32584989e-02 6.52365088e-01 7.55286336e-01 -6.32539764e-02 6.56992912e-01 7.51266956e-01 -6.32348061e-02 6.61575735e-01 7.47189164e-01 -6.31950498e-02 6.66142344e-01 7.43134558e-01 -6.32122159e-02 6.70683980e-01 7.39025116e-01 -6.32005706e-02 6.75202012e-01 7.34890044e-01 -6.32096976e-02 6.79703832e-01 7.30741262e-01 -6.32313266e-02 6.84178829e-01 7.26568699e-01 -6.32362217e-02 6.88641727e-01 7.22336471e-01 -6.32236227e-02 6.93058491e-01 7.18124568e-01 -6.32366464e-02 6.97448850e-01 7.13860035e-01 -6.32408112e-02 7.01822579e-01 7.09543109e-01 -6.32359684e-02 7.06136703e-01 7.05238640e-01 -6.32493719e-02 7.10473597e-01 7.00869679e-01 -6.32565394e-02 7.14748144e-01 6.96506977e-01 -6.32444173e-02 7.19011903e-01 6.92099810e-01 -6.32325113e-02 7.23244429e-01 6.87695801e-01 -6.32166788e-02 7.27432668e-01 6.83232725e-01 -6.32260069e-02 7.31632233e-01 6.78769350e-01 -6.32416457e-02 7.35789239e-01 6.74268126e-01 -6.32183701e-02 7.39889979e-01 6.69727623e-01 -6.32200688e-02 7.43990719e-01 6.65172219e-01 -6.32216632e-02 7.48048186e-01 6.60609305e-01 -6.32334426e-02 7.52115071e-01 6.56002939e-01 -6.32086173e-02 7.56121397e-01 6.51379824e-01 -6.31621629e-02 7.60076880e-01 6.46731436e-01 -6.31673858e-02 7.64057159e-01 6.42029822e-01 -6.33239672e-02 7.67981052e-01 6.37344301e-01 -6.32919520e-02 7.71877944e-01 6.32624805e-01 -6.33174703e-02 7.75745690e-01 6.27876222e-01 -6.33031055e-02 7.79562712e-01 6.23098612e-01 -6.32773861e-02 7.83367932e-01 6.18297756e-01 -6.33246228e-02 7.87143350e-01 6.13491654e-01 -6.33376837e-02 7.90892899e-01 6.08637631e-01 -6.33342937e-02 7.94637144e-01 6.03770018e-01 -6.33795261e-02 7.98318267e-01 5.98890603e-01 -6.33416176e-02 8.01970065e-01 5.93977332e-01 -6.33578822e-02 8.05620313e-01 5.89034915e-01 -6.33441880e-02 8.09190631e-01 5.84104776e-01 -6.33359775e-02 8.12789857e-01 5.79122186e-01 -6.33466691e-02 8.16323638e-01 5.74125469e-01 -6.33542612e-02 8.19839835e-01 5.69089711e-01 -6.33387119e-02 8.23294938e-01 5.64054251e-01 -6.33235872e-02 8.26729715e-01 5.59004724e-01 -6.33160099e-02 8.30141723e-01 5.53923726e-01 -6.33066669e-02 8.33545148e-01 5.48826635e-01 -6.31580353e-02 8.36925864e-01 5.43703496e-01 -6.31378666e-02 8.40224266e-01 5.38547456e-01 -6.33031800e-02 8.43519211e-01 5.33368945e-01 -6.32750690e-02 8.46784174e-01 5.28201699e-01 -6.31746575e-02 8.49989712e-01 5.22996485e-01 -6.30574077e-02 8.53179395e-01 5.17764509e-01 -6.30465895e-02 8.56339514e-01 5.12523293e-01 -6.30521700e-02 8.59478533e-01 5.07264137e-01 -6.31417632e-02 8.62556875e-01 5.01967311e-01 -6.31357729e-02 8.65645945e-01 4.96679783e-01 -6.31278530e-02 8.68646204e-01 4.91338223e-01 -6.31319135e-02 8.71659935e-01 4.86009449e-01 -6.31328225e-02 8.74626577e-01 4.80653048e-01 -6.31308332e-02 8.77555251e-01 4.75267768e-01 -6.31320104e-02 8.80459964e-01 4.69885468e-01 -6.31416366e-02 8.83333147e-01 4.64477390e-01 -6.31349012e-02 8.86169612e-01 4.59044456e-01 -6.31347820e-02 8.88957024e-01 4.53603923e-01 -6.31211549e-02 8.91753256e-01 4.48133171e-01 -6.31090701e-02 8.94456804e-01 4.42654729e-01 -6.31163269e-02 8.97153556e-01 4.37162727e-01 -6.31198809e-02 8.99819851e-01 4.31639761e-01 -6.31366670e-02 9.02483106e-01 4.26112682e-01 -6.31261021e-02 9.05070543e-01 4.20561045e-01 -6.31211624e-02 9.07612145e-01 4.15008456e-01 -6.31144792e-02 9.10147965e-01 4.09429282e-01 -6.31178021e-02 9.12639439e-01 4.03848499e-01 -6.30987436e-02 9.15137649e-01 3.98244232e-01 -6.30893931e-02 9.17520285e-01 3.92602801e-01 -6.30874336e-02 9.19933677e-01 3.86981368e-01 -6.30615577e-02 9.22259033e-01 3.81320864e-01 -6.30368739e-02 9.24640000e-01 3.75655413e-01 -6.30415976e-02 9.26884532e-01 3.69985193e-01 -6.30199835e-02 9.29158568e-01 3.64276499e-01 -6.30193278e-02 9.31357086e-01 3.58584315e-01 -6.30054846e-02 9.33551788e-01 3.52862000e-01 -6.29922599e-02 9.35719550e-01 3.47118318e-01 -6.29623979e-02 9.37823415e-01 3.41366917e-01 -6.29380867e-02 9.39893663e-01 3.35618705e-01 -6.28959909e-02 9.41951096e-01 3.29843968e-01 -6.29046634e-02 9.43926394e-01 3.24056745e-01 -6.29189834e-02 9.45891857e-01 3.18259776e-01 -6.29495680e-02 9.47824597e-01 3.12438399e-01 -6.29817694e-02 9.49761987e-01 3.06628317e-01 -6.29708320e-02 9.51613903e-01 3.00791949e-01 -6.29591271e-02 9.53424811e-01 2.94945031e-01 -6.29669726e-02 9.55228448e-01 2.89092273e-01 -6.29610792e-02 9.56983447e-01 2.83220917e-01 -6.29601330e-02 9.58705306e-01 2.77345985e-01 -6.29447401e-02 9.60392416e-01 2.71453142e-01 -6.29475117e-02 9.62038279e-01 2.65561789e-01 -6.29345253e-02 9.63658571e-01 2.59656072e-01 -6.29482940e-02 9.65214014e-01 2.53729165e-01 -6.30194247e-02 9.66748059e-01 2.47800663e-01 -6.30493015e-02 9.68281090e-01 2.41871774e-01 -6.30409196e-02 9.69743490e-01 2.35921010e-01 -6.30524084e-02 9.71186638e-01 2.29963735e-01 -6.30709901e-02 9.72524822e-01 2.24005297e-01 -6.30644858e-02 9.73893046e-01 2.18035504e-01 -6.30863830e-02 9.75206196e-01 2.12053090e-01 -6.30703047e-02 9.76506770e-01 2.06070885e-01 -6.30683377e-02 9.77778137e-01 2.00075164e-01 -6.30673841e-02 9.78995204e-01 1.94071203e-01 -6.30840883e-02 9.80151832e-01 1.88055947e-01 -6.31194785e-02 9.81272459e-01 1.82040915e-01 -6.31213188e-02 9.82400954e-01 1.76014334e-01 -6.31204545e-02 9.83415663e-01 1.69984087e-01 -6.31155521e-02 9.84445155e-01 1.63948745e-01 -6.31260052e-02 9.85433459e-01 1.57904387e-01 -6.31248951e-02 9.86391723e-01 1.51856422e-01 -6.31291121e-02 9.87303495e-01 1.45800024e-01 -6.31201416e-02 9.88208354e-01 1.39739752e-01 -6.30833432e-02 9.89020228e-01 1.33675918e-01 -6.30037263e-02 9.89834368e-01 1.27602592e-01 -6.29021972e-02 9.90630329e-01 1.21525601e-01 -6.30830973e-02 9.91362274e-01 1.15443490e-01 -6.30657375e-02 9.92003262e-01 1.09360389e-01 -6.30891398e-02 9.92665768e-01 1.03274360e-01 -6.30917624e-02 9.93310809e-01 9.71794054e-02 -6.30905554e-02 9.93879437e-01 9.10842717e-02 -6.30830079e-02 9.94375825e-01 8.49834904e-02 -6.30658269e-02 9.94884849e-01 7.88800418e-02 -6.29302040e-02 9.95359361e-01 7.27733746e-02 -6.29335344e-02 9.95825112e-01 6.66655675e-02 -6.29239455e-02 9.96171296e-01 6.05548285e-02 -6.29199371e-02 9.96566951e-01 5.44403419e-02 -6.29130006e-02 9.96835768e-01 4.83265892e-02 -6.27650470e-02 9.97128904e-01 4.22084555e-02 -6.27473295e-02 9.97373283e-01 3.60901505e-02 -6.27318770e-02 9.97566462e-01 2.99688149e-02 -6.28353134e-02 9.97774005e-01 2.38470510e-02 -6.28495887e-02 9.97872591e-01 1.77251119e-02 -6.27885610e-02 9.97969270e-01 1.16015188e-02 -6.28110245e-02 9.98038530e-01 5.47766080e-03 -6.28325194e-02 9.98039663e-01 -6.46114873e-04 -6.28167242e-02 9.98034775e-01 -6.76990487e-03 -6.28052577e-02 9.97970343e-01 -1.28932707e-02 -6.27548322e-02 9.97871697e-01 -1.90163571e-02 -6.27281964e-02 9.97726500e-01 -2.51388326e-02 -6.27386421e-02 9.97553229e-01 -3.12599689e-02 -6.27297014e-02 9.97327983e-01 -3.73801924e-02 -6.27181381e-02 9.97070014e-01 -4.34992127e-02 -6.27129078e-02 9.96813893e-01 -4.96163182e-02 -6.26980737e-02 9.96483803e-01 -5.57311811e-02 -6.26478270e-02 9.96108294e-01 -6.18447661e-02 -6.26928285e-02 9.95706677e-01 -6.79560304e-02 -6.26567453e-02 9.95281637e-01 -7.40631968e-02 -6.26447722e-02 9.94841337e-01 -8.01689997e-02 -6.27067462e-02 9.94295895e-01 -8.62725899e-02 -6.27128184e-02 9.93737400e-01 -9.23707187e-02 -6.28493726e-02 9.93152678e-01 -9.84670147e-02 -6.28696904e-02 9.92521346e-01 -1.04558937e-01 -6.28798008e-02 9.91896987e-01 -1.10647373e-01 -6.28703758e-02 9.91209030e-01 -1.16732545e-01 -6.26851171e-02 9.90466475e-01 -1.22808397e-01 -6.26803786e-02 9.89668131e-01 -1.28886446e-01 -6.28489479e-02 9.88866627e-01 -1.34955138e-01 -6.28042817e-02 9.88040149e-01 -1.41019836e-01 -6.27362430e-02 9.87147987e-01 -1.47080168e-01 -6.27332777e-02 9.86196995e-01 -1.53132945e-01 -6.28095791e-02 9.85270739e-01 -1.59185320e-01 -6.27008826e-02 9.84248638e-01 -1.65227205e-01 -6.26996607e-02 9.83198583e-01 -1.71261698e-01 -6.27192929e-02 9.82180357e-01 -1.77292109e-01 -6.27330169e-02 9.81041372e-01 -1.83317095e-01 -6.28575087e-02 9.79923546e-01 -1.89327523e-01 -6.27371892e-02 9.78740335e-01 -1.95337504e-01 -6.27903491e-02 9.77523088e-01 -2.01339051e-01 -6.28177375e-02 9.76245642e-01 -2.07334280e-01 -6.28208220e-02 9.74953651e-01 -2.13319913e-01 -6.28057942e-02 9.73660946e-01 -2.19296396e-01 -6.27540350e-02 9.72276032e-01 -2.25266874e-01 -6.27519861e-02 9.70897675e-01 -2.31232867e-01 -6.27425015e-02 9.69450951e-01 -2.37187386e-01 -6.27447218e-02 9.67968881e-01 -2.43124679e-01 -6.27598092e-02 9.66453254e-01 -2.49064252e-01 -6.27576411e-02 9.64897394e-01 -2.54986972e-01 -6.27545640e-02 9.63333011e-01 -2.60902554e-01 -6.27659187e-02 9.61721539e-01 -2.66808003e-01 -6.27519041e-02 9.60036695e-01 -2.72710800e-01 -6.27441481e-02 9.58338618e-01 -2.78595924e-01 -6.27346411e-02 9.56616938e-01 -2.84468412e-01 -6.27292395e-02 9.54883754e-01 -2.90325344e-01 -6.27354011e-02 9.53060746e-01 -2.96177059e-01 -6.27423376e-02 9.51250494e-01 -3.02021474e-01 -6.27258867e-02 9.49381471e-01 -3.07860464e-01 -6.27303720e-02 9.47457075e-01 -3.13681006e-01 -6.27454892e-02 9.45508599e-01 -3.19486946e-01 -6.27395213e-02 9.43540752e-01 -3.25282782e-01 -6.27295747e-02 9.41505909e-01 -3.31067294e-01 -6.27423748e-02 9.39465225e-01 -3.36841673e-01 -6.27415478e-02 9.37368631e-01 -3.42588246e-01 -6.27114847e-02 9.35275793e-01 -3.48338097e-01 -6.27230555e-02 9.33102489e-01 -3.54074270e-01 -6.27143160e-02 9.30910766e-01 -3.59785855e-01 -6.27056286e-02 9.28708613e-01 -3.65491062e-01 -6.27048761e-02 9.26420569e-01 -3.71188462e-01 -6.26920536e-02 9.24157381e-01 -3.76867563e-01 -6.26403540e-02 9.21795011e-01 -3.82530600e-01 -6.26968071e-02 9.19451714e-01 -3.88172865e-01 -6.26607910e-02 9.17036891e-01 -3.93812567e-01 -6.27072304e-02 9.14601803e-01 -3.99420977e-01 -6.26563132e-02 9.12138939e-01 -4.05023873e-01 -6.26780465e-02 9.09647405e-01 -4.10624087e-01 -6.26937300e-02 9.07113194e-01 -4.16192204e-01 -6.27473220e-02 9.04550254e-01 -4.21757549e-01 -6.27509356e-02 9.01908696e-01 -4.27299261e-01 -6.27200231e-02 8.99310350e-01 -4.32812452e-01 -6.27293959e-02 8.96635234e-01 -4.38336760e-01 -6.27294183e-02 8.93891454e-01 -4.43824410e-01 -6.27180636e-02 8.91179919e-01 -4.49303925e-01 -6.27200529e-02 8.88383865e-01 -4.54764694e-01 -6.27317652e-02 8.85575056e-01 -4.60205555e-01 -6.28386885e-02 8.82765114e-01 -4.65629369e-01 -6.28580004e-02 8.79855633e-01 -4.71040815e-01 -6.28243163e-02 8.76949668e-01 -4.76417571e-01 -6.28514439e-02 8.74006391e-01 -4.81785417e-01 -6.28646389e-02 8.71067226e-01 -4.87140298e-01 -6.29083663e-02 8.68034065e-01 -4.92483139e-01 -6.29291534e-02 8.64988565e-01 -4.97792900e-01 -6.29506037e-02 8.61933112e-01 -5.03100455e-01 -6.29630908e-02 8.58829141e-01 -5.08380115e-01 -6.29436299e-02 8.55715156e-01 -5.13632238e-01 -6.28865883e-02 8.52545977e-01 -5.18875062e-01 -6.29241765e-02 8.49322259e-01 -5.24101436e-01 -6.29751310e-02 8.46096575e-01 -5.29302657e-01 -6.28710836e-02 8.42814744e-01 -5.34473419e-01 -6.28748611e-02 8.39522481e-01 -5.39648235e-01 -6.29293919e-02 8.36220324e-01 -5.44788659e-01 -6.29066899e-02 8.32841575e-01 -5.49914658e-01 -6.28718957e-02 8.29439163e-01 -5.55009544e-01 -6.28757104e-02 8.26020896e-01 -5.60079813e-01 -6.29380420e-02 8.22584331e-01 -5.65150619e-01 -6.28883243e-02 8.19086254e-01 -5.70168495e-01 -6.28689229e-02 8.15608740e-01 -5.75191498e-01 -6.28838688e-02 8.12039018e-01 -5.80185294e-01 -6.28893301e-02 8.08463693e-01 -5.85153162e-01 -6.28666058e-02 8.04892302e-01 -5.90124488e-01 -6.28958419e-02 8.01242828e-01 -5.95028996e-01 -6.29274398e-02 7.97585607e-01 -5.99954605e-01 -6.28991947e-02 7.93861687e-01 -6.04841590e-01 -6.28874898e-02 7.90156424e-01 -6.09672964e-01 -6.29144982e-02 7.86401629e-01 -6.14514768e-01 -6.28848225e-02 7.82618642e-01 -6.19342387e-01 -6.28793463e-02 7.78764486e-01 -6.24126732e-01 -6.28804639e-02 7.74953067e-01 -6.28887713e-01 -6.28404543e-02 7.71058440e-01 -6.33630574e-01 -6.28883839e-02 7.67155588e-01 -6.38367534e-01 -6.29103333e-02 7.63247311e-01 -6.43041849e-01 -6.28999323e-02 7.59264767e-01 -6.47729278e-01 -6.28904477e-02 7.55302727e-01 -6.52381837e-01 -6.28941953e-02 7.51284301e-01 -6.56996608e-01 -6.29601330e-02 7.47205198e-01 -6.61587298e-01 -6.29780814e-02 7.43152499e-01 -6.66157305e-01 -6.29463643e-02 7.39040256e-01 -6.70696378e-01 -6.29217774e-02 7.34903991e-01 -6.75213635e-01 -6.29397929e-02 7.30753660e-01 -6.79712474e-01 -6.29661605e-02 7.26582706e-01 -6.84188902e-01 -6.29721209e-02 7.22352624e-01 -6.88657641e-01 -6.29782081e-02 7.18140841e-01 -6.93070889e-01 -6.28918782e-02 7.13868797e-01 -6.97455704e-01 -6.30304515e-02 7.09556937e-01 -7.01829433e-01 -6.29801974e-02 7.05253959e-01 -7.06147015e-01 -6.30166754e-02 7.00887263e-01 -7.10491061e-01 -6.30195886e-02 6.96522832e-01 -7.14764833e-01 -6.30339086e-02 6.92117631e-01 -7.19028056e-01 -6.30110577e-02 6.87713623e-01 -7.23261774e-01 -6.30234182e-02 6.83244705e-01 -7.27443039e-01 -6.30810410e-02 6.78783953e-01 -7.31652796e-01 -6.30926490e-02 6.74280941e-01 -7.35802650e-01 -6.30741939e-02 6.69734955e-01 -7.39898205e-01 -6.30877987e-02 6.65176809e-01 -7.43996739e-01 -6.32232428e-02 6.60621583e-01 -7.48061538e-01 -6.31140545e-02 6.56019568e-01 -7.52128482e-01 -6.30970746e-02 6.51396096e-01 -7.56141067e-01 -6.31215423e-02 6.46738887e-01 -7.60091603e-01 -6.31351396e-02 6.42043114e-01 -7.64071822e-01 -6.31453246e-02 6.37365401e-01 -7.67998517e-01 -6.31462187e-02 6.32641554e-01 -7.71894932e-01 -6.31431118e-02 6.27893984e-01 -7.75766373e-01 -6.31304607e-02 6.23117268e-01 -7.79581904e-01 -6.30900636e-02 6.18313432e-01 -7.83387184e-01 -6.31044954e-02 6.13510668e-01 -7.87162662e-01 -6.31556287e-02 6.08655870e-01 -7.90916562e-01 -6.30849004e-02 6.03783786e-01 -7.94652700e-01 -6.32119179e-02 5.98908603e-01 -7.98341632e-01 -6.30970672e-02 5.94001412e-01 -8.01999748e-01 -6.30495176e-02 5.89055002e-01 -8.05645466e-01 -6.30738810e-02 5.84121108e-01 -8.09215605e-01 -6.30792454e-02 5.79131305e-01 -8.12804639e-01 -6.31937459e-02 5.74134529e-01 -8.16339433e-01 -6.31868839e-02 5.69108605e-01 -8.19845796e-01 -6.31559566e-02 5.64066648e-01 -8.23311806e-01 -6.31658658e-02 5.59017718e-01 -8.26747119e-01 -6.31976500e-02 5.53936779e-01 -8.30156863e-01 -6.32117316e-02 5.48825502e-01 -8.33543777e-01 -6.32217899e-02 5.43701470e-01 -8.36924851e-01 -6.32165149e-02 5.38554013e-01 -8.40240180e-01 -6.32180795e-02 5.33376396e-01 -8.43528509e-01 -6.32146522e-02 5.28200686e-01 -8.46791208e-01 -6.32043108e-02 5.22996783e-01 -8.49989057e-01 -6.32280707e-02 5.17765582e-01 -8.53178322e-01 -6.32377937e-02 5.12521863e-01 -8.56337011e-01 -6.32508099e-02 5.07260203e-01 -8.59482288e-01 -6.32913560e-02 5.01965106e-01 -8.62554014e-01 -6.33147433e-02 4.96677279e-01 -8.65631282e-01 -6.33203089e-02 4.91336107e-01 -8.68647933e-01 -6.33210987e-02 4.86007065e-01 -8.71657431e-01 -6.33305088e-02 4.80648220e-01 -8.74630332e-01 -6.33308440e-02 4.75271255e-01 -8.77552092e-01 -6.34033829e-02 4.69880223e-01 -8.80448699e-01 -6.34480864e-02 4.64468807e-01 -8.83330107e-01 -6.34630099e-02 4.59038198e-01 -8.86158586e-01 -6.34747818e-02 4.53598946e-01 -8.88952672e-01 -6.34790733e-02 4.48130965e-01 -8.91738653e-01 -6.34647980e-02 4.42649335e-01 -8.94443095e-01 -6.33965731e-02 4.37158942e-01 -8.97145808e-01 -6.34493008e-02 4.31631207e-01 -8.99808645e-01 -6.34693056e-02 4.26102012e-01 -9.02465880e-01 -6.34344295e-02 4.20552909e-01 -9.05042946e-01 -6.35054111e-02 4.14997965e-01 -9.07602668e-01 -6.34767041e-02 4.09432322e-01 -9.10146892e-01 -6.34448975e-02 4.03840184e-01 -9.12630618e-01 -6.33624718e-02 3.98234069e-01 -9.15125072e-01 -6.34447262e-02 3.92595202e-01 -9.17501211e-01 -6.34514913e-02 3.86973977e-01 -9.19904709e-01 -6.34115338e-02 3.81311566e-01 -9.22244966e-01 -6.34003356e-02 3.75647187e-01 -9.24623191e-01 -6.35082424e-02 3.69971871e-01 -9.26863790e-01 -6.34883046e-02 3.64263743e-01 -9.29134250e-01 -6.35096729e-02 3.58572751e-01 -9.31355119e-01 -6.35061935e-02 3.52850288e-01 -9.33526933e-01 -6.34998605e-02 3.47109318e-01 -9.35693085e-01 -6.35003597e-02 3.41356605e-01 -9.37804937e-01 -6.34268150e-02 3.35606724e-01 -9.39857960e-01 -6.35069311e-02 3.29833835e-01 -9.41930532e-01 -6.34940490e-02 3.24047238e-01 -9.43902314e-01 -6.35141283e-02 3.18246514e-01 -9.45867121e-01 -6.35099933e-02 3.12428266e-01 -9.47802424e-01 -6.34799153e-02 3.06615561e-01 -9.49740767e-01 -6.34670481e-02 3.00781667e-01 -9.51576650e-01 -6.33635744e-02 2.94936895e-01 -9.53405857e-01 -6.33732900e-02 2.89083183e-01 -9.55221415e-01 -6.33586720e-02 2.83210814e-01 -9.56949592e-01 -6.33882135e-02 2.77335048e-01 -9.58675206e-01 -6.34262785e-02 2.71447986e-01 -9.60364640e-01 -6.34007007e-02 2.65553594e-01 -9.62023854e-01 -6.34303838e-02 2.59644836e-01 -9.63636935e-01 -6.34350255e-02 2.53723502e-01 -9.65208471e-01 -6.34175092e-02 2.47794241e-01 -9.66718554e-01 -6.33970499e-02 2.41860062e-01 -9.68260407e-01 -6.33936003e-02 2.35914543e-01 -9.69722152e-01 -6.33936673e-02 2.29965582e-01 -9.71160710e-01 -6.33868203e-02 2.24001303e-01 -9.72527027e-01 -6.33911118e-02 2.18030199e-01 -9.73874807e-01 -6.33659288e-02 2.12047890e-01 -9.75208402e-01 -6.33731335e-02 2.06062362e-01 -9.76459980e-01 -6.33688569e-02 2.00065419e-01 -9.77745295e-01 -6.33970872e-02 1.94063872e-01 -9.78961587e-01 -6.33857623e-02 1.88052073e-01 -9.80108440e-01 -6.33900315e-02 1.82035282e-01 -9.81268823e-01 -6.33932948e-02 1.76006824e-01 -9.82369423e-01 -6.34068847e-02 1.69977024e-01 -9.83395576e-01 -6.33859783e-02 1.63941905e-01 -9.84440148e-01 -6.33959398e-02 1.57896206e-01 -9.85433817e-01 -6.33949786e-02 1.51847780e-01 -9.86378968e-01 -6.34050444e-02 1.45791531e-01 -9.87266243e-01 -6.34280592e-02 1.39732391e-01 -9.88158762e-01 -6.33377284e-02 1.33679911e-01 -9.89051998e-01 -6.24477826e-02 1.27649069e-01 -9.90031838e-01 -5.94335198e-02 1.21520475e-01 -9.90565538e-01 -6.33418262e-02 1.15443513e-01 -9.91307855e-01 -6.30918071e-02 1.09359197e-01 -9.91999447e-01 -6.30609170e-02 1.03269875e-01 -9.92647827e-01 -6.30948693e-02 9.71803367e-02 -9.93280292e-01 -6.28331080e-02 9.10784528e-02 -9.93829668e-01 -6.32975101e-02 8.50118995e-02 -9.94550109e-01 -6.02722876e-02 7.89380223e-02 -9.95177448e-01 -5.68084158e-02 7.27807209e-02 -9.95401919e-01 -6.22526705e-02 6.66664243e-02 -9.95802164e-01 -6.27974719e-02 6.05492368e-02 -9.96160269e-01 -6.33691847e-02 5.44349588e-02 -9.96517658e-01 -6.34425133e-02 4.83199432e-02 -9.96790230e-01 -6.34536967e-02 4.22025882e-02 -9.97085989e-01 -6.34550527e-02 3.60839926e-02 -9.97329533e-01 -6.34519905e-02 2.99634952e-02 -9.97518241e-01 -6.34544045e-02 2.38423850e-02 -9.97726142e-01 -6.34242520e-02 1.77202150e-02 -9.97820795e-01 -6.34154230e-02 1.15974229e-02 -9.97921109e-01 -6.34125695e-02 5.47389407e-03 -9.97988284e-01 -6.34277761e-02 -6.49745867e-04 -9.97987866e-01 -6.34501278e-02 -6.77313935e-03 -9.97983396e-01 -6.34440407e-02 -1.28963171e-02 -9.97905910e-01 -6.34224117e-02 -1.90189276e-02 -9.97822404e-01 -6.33821413e-02 -2.51410715e-02 -9.97661948e-01 -6.33900538e-02 -3.12621668e-02 -9.97496903e-01 -6.34135827e-02 -3.73820513e-02 -9.97263432e-01 -6.34043291e-02 -4.35006432e-02 -9.97017324e-01 -6.34057149e-02 -4.96177264e-02 -9.96761978e-01 -6.33755773e-02 -5.57328351e-02 -9.96428549e-01 -6.34257793e-02 -6.18463419e-02 -9.96061206e-01 -6.34212866e-02 -6.79567754e-02 -9.95661438e-01 -6.34345785e-02 -7.40647912e-02 -9.95227814e-01 -6.34366348e-02 -8.01691040e-02 -9.94791627e-01 -6.34044781e-02 -8.62718150e-02 -9.94237661e-01 -6.33875206e-02 -9.23709348e-02 -9.93709862e-01 -6.34156168e-02 -9.84666049e-02 -9.93116140e-01 -6.34160116e-02 -1.04558699e-01 -9.92494822e-01 -6.34463802e-02 -1.10645600e-01 -9.91833448e-01 -6.33812100e-02 -1.16729990e-01 -9.91157591e-01 -6.34237602e-02 -1.22807965e-01 -9.90413725e-01 -6.34371862e-02 -1.28883645e-01 -9.89613771e-01 -6.34401515e-02 -1.34953812e-01 -9.88833547e-01 -6.34655356e-02 -1.41018137e-01 -9.87988651e-01 -6.34168461e-02 -1.47076905e-01 -9.87103760e-01 -6.34555221e-02 -1.53131634e-01 -9.86157894e-01 -6.34390339e-02 -1.59177050e-01 -9.85201180e-01 -6.34476170e-02 -1.65222719e-01 -9.84199941e-01 -6.34544864e-02 -1.71255246e-01 -9.83140647e-01 -6.34921193e-02 -1.77284941e-01 -9.82117832e-01 -6.35016933e-02 -1.83312565e-01 -9.80998755e-01 -6.35409206e-02 -1.89321131e-01 -9.79851425e-01 -6.35204762e-02 -1.95334241e-01 -9.78708208e-01 -6.35611042e-02 -2.01337770e-01 -9.77491975e-01 -6.35622963e-02 -2.07329437e-01 -9.76213276e-01 -6.35308102e-02 -2.13314578e-01 -9.74913538e-01 -6.35185018e-02 -2.19289228e-01 -9.73613024e-01 -6.35476783e-02 -2.25259304e-01 -9.72232103e-01 -6.35288581e-02 -2.31222868e-01 -9.70842302e-01 -6.35305122e-02 -2.37180427e-01 -9.69391942e-01 -6.35315478e-02 -2.43117705e-01 -9.67920303e-01 -6.35402724e-02 -2.49059811e-01 -9.66397703e-01 -6.35212734e-02 -2.54978865e-01 -9.64842379e-01 -6.35075271e-02 -2.60892689e-01 -9.63281095e-01 -6.34908080e-02 -2.66801149e-01 -9.61683273e-01 -6.33203313e-02 -2.72701532e-01 -9.59986210e-01 -6.33353218e-02 -2.78579324e-01 -9.58283246e-01 -6.35270104e-02 -2.84458488e-01 -9.56564188e-01 -6.35283738e-02 -2.90320188e-01 -9.54841018e-01 -6.34523034e-02 -2.96170413e-01 -9.53011811e-01 -6.34418577e-02 -3.02013725e-01 -9.51200426e-01 -6.34603798e-02 -3.07848781e-01 -9.49344635e-01 -6.34274632e-02 -3.13668638e-01 -9.47422087e-01 -6.34061471e-02 -3.19478929e-01 -9.45456803e-01 -6.35128543e-02 -3.25270712e-01 -9.43489313e-01 -6.34853914e-02 -3.31057340e-01 -9.41466630e-01 -6.34044483e-02 -3.36828023e-01 -9.39421594e-01 -6.35150895e-02 -3.42573643e-01 -9.37319100e-01 -6.35071844e-02 -3.48321408e-01 -9.35225427e-01 -6.35059625e-02 -3.54062498e-01 -9.33067858e-01 -6.34248406e-02 -3.59771758e-01 -9.30889726e-01 -6.32212833e-02 -3.65475714e-01 -9.28656220e-01 -6.34880066e-02 -3.71174604e-01 -9.26373422e-01 -6.34770617e-02 -3.76857936e-01 -9.24100161e-01 -6.34923279e-02 -3.82521629e-01 -9.21746254e-01 -6.34804815e-02 -3.88153225e-01 -9.19404149e-01 -6.34549186e-02 -3.93796355e-01 -9.16994989e-01 -6.34860843e-02 -3.99405807e-01 -9.14553642e-01 -6.34765252e-02 -4.05010134e-01 -9.12093520e-01 -6.34452477e-02 -4.10613149e-01 -9.09628987e-01 -6.30149245e-02 -4.16177750e-01 -9.07093048e-01 -6.30261675e-02 -4.21742260e-01 -9.04507160e-01 -6.34381995e-02 -4.27282006e-01 -9.01864886e-01 -6.34747222e-02 -4.32793319e-01 -8.99265766e-01 -6.34848997e-02 -4.38317865e-01 -8.96585822e-01 -6.34902567e-02 -4.43802834e-01 -8.93847585e-01 -6.34796470e-02 -4.49284285e-01 -8.91135573e-01 -6.34626001e-02 -4.54749018e-01 -8.88336897e-01 -6.34825081e-02 -4.60187346e-01 -8.85535598e-01 -6.34887815e-02 -4.65609580e-01 -8.82725000e-01 -6.34730160e-02 -4.71027136e-01 -8.79820466e-01 -6.34724945e-02 -4.76402581e-01 -8.76914263e-01 -6.34777471e-02 -4.81770247e-01 -8.73973548e-01 -6.35033920e-02 -4.87129003e-01 -8.71036172e-01 -6.35018125e-02 -4.92469907e-01 -8.68000805e-01 -6.35077283e-02 -4.97778386e-01 -8.64960611e-01 -6.34945109e-02 -5.03085852e-01 -8.61916006e-01 -6.33665323e-02 -5.08373797e-01 -8.58826041e-01 -6.33577928e-02 -5.13622046e-01 -8.55692148e-01 -6.33953959e-02 -5.18865943e-01 -8.52524161e-01 -6.33326545e-02 -5.24094939e-01 -8.49323809e-01 -6.32911399e-02 -5.29290020e-01 -8.46083403e-01 -6.32967353e-02 -5.34472585e-01 -8.42803895e-01 -6.33043870e-02 -5.39635241e-01 -8.39501917e-01 -6.34090677e-02 -5.44780791e-01 -8.36202502e-01 -6.33957088e-02 -5.49909413e-01 -8.32821488e-01 -6.33858368e-02 -5.55008292e-01 -8.29427540e-01 -6.32579327e-02 -5.60070455e-01 -8.26009035e-01 -6.32495657e-02 -5.65147042e-01 -8.22575867e-01 -6.32432848e-02 -5.70162177e-01 -8.19072723e-01 -6.32419735e-02 -5.75181544e-01 -8.15601170e-01 -6.32409826e-02 -5.80175698e-01 -8.12021673e-01 -6.32392019e-02 -5.85145593e-01 -8.08449984e-01 -6.32289201e-02 -5.90132177e-01 -8.04904103e-01 -6.27326518e-02 -5.95040500e-01 -8.01255345e-01 -6.27508089e-02 -5.99954903e-01 -7.97597528e-01 -6.27443120e-02 -6.04831040e-01 -7.93851376e-01 -6.32042065e-02 -6.09667659e-01 -7.90144563e-01 -6.32026717e-02 -6.14506781e-01 -7.86388099e-01 -6.31970391e-02 -6.19339049e-01 -7.82613397e-01 -6.31839037e-02 -6.24122739e-01 -7.78758168e-01 -6.31860793e-02 -6.28881276e-01 -7.74943113e-01 -6.31836727e-02 -6.33627236e-01 -7.71054089e-01 -6.31739572e-02 -6.38363957e-01 -7.67150581e-01 -6.31520823e-02 -6.43035829e-01 -7.63241827e-01 -6.31475747e-02 -6.47724211e-01 -7.59255588e-01 -6.31451011e-02 -6.52376831e-01 -7.55299091e-01 -6.31100759e-02 -6.57002330e-01 -7.51278162e-01 -6.30770475e-02 -6.61574066e-01 -7.47202396e-01 -6.30724281e-02 -6.66153967e-01 -7.43148386e-01 -6.30312860e-02 -6.70695841e-01 -7.39038050e-01 -6.30097911e-02 -6.75213277e-01 -7.34903932e-01 -6.30038977e-02 -6.79711998e-01 -7.30754137e-01 -6.30260184e-02 -6.84189022e-01 -7.26581156e-01 -6.30240962e-02 -6.88656271e-01 -7.22353280e-01 -6.30201101e-02 -6.93075120e-01 -7.18146086e-01 -6.30216300e-02 -6.97466016e-01 -7.13883579e-01 -6.30316287e-02 -7.01843560e-01 -7.09560215e-01 -6.30256310e-02 -7.06150055e-01 -7.05259800e-01 -6.30226955e-02 -7.10496247e-01 -7.00892210e-01 -6.30023032e-02 -7.14770734e-01 -6.96526110e-01 -6.29744455e-02 -7.19035029e-01 -6.92124188e-01 -6.29109368e-02 -7.23269165e-01 -6.87728763e-01 -6.28043637e-02 -7.27469742e-01 -6.83280170e-01 -6.25929907e-02 -7.31661379e-01 -6.78792834e-01 -6.24861754e-02 -7.35832334e-01 -6.74325585e-01 -6.17124885e-02 -7.40098774e-01 -6.69959426e-01 -5.70835173e-02 -7.44265556e-01 -6.65485620e-01 -5.48624061e-02 -7.48738348e-01 -6.61368072e-01 -4.13558558e-02 -7.52137005e-01 -6.56034350e-01 -6.25206977e-02 -7.56160915e-01 -6.51420116e-01 -6.22292496e-02 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. 0. 0. -7.98388600e-01 -5.98952174e-01 -6.19028881e-02 -8.02040219e-01 -5.94034314e-01 -6.20863810e-02 -8.05679321e-01 -5.89110196e-01 -6.18828982e-02 -8.09278488e-01 -5.84155381e-01 -6.18876442e-02 -8.12832594e-01 -5.79165697e-01 -6.22106716e-02 -8.16383481e-01 -5.74178278e-01 -6.19189665e-02 -8.19876909e-01 -5.69145918e-01 -6.22474290e-02 -8.23350728e-01 -5.64101994e-01 -6.23089299e-02 -8.26798856e-01 -5.59041381e-01 -6.22588955e-02 -8.30218554e-01 -5.53961873e-01 -6.21548407e-02 -8.33677769e-01 -5.48918784e-01 -6.04979694e-02 0. 0. 0. -8.40600312e-01 -5.38844228e-01 -5.51184006e-02 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.07787502e-01 -4.15104598e-01 -6.00100867e-02 -9.10211265e-01 -4.09465820e-01 -6.19933531e-02 -9.12691474e-01 -4.03866202e-01 -6.22997321e-02 -9.15148079e-01 -3.98250461e-01 -6.24873489e-02 -9.17558014e-01 -3.92628431e-01 -6.25401661e-02 -9.19945836e-01 -3.86992842e-01 -6.25839010e-02 -9.22299564e-01 -3.81333888e-01 -6.24920391e-02 -9.24626231e-01 -3.75669628e-01 -6.24032728e-02 -9.26920176e-01 -3.69993091e-01 -6.24719821e-02 -9.29186761e-01 -3.64295483e-01 -6.25213683e-02 -9.31389093e-01 -3.58583212e-01 -6.25419915e-02 -9.33579683e-01 -3.52864057e-01 -6.25391006e-02 -9.35736656e-01 -3.47130507e-01 -6.24650419e-02 -9.37851012e-01 -3.41387361e-01 -6.23765290e-02 -9.39933717e-01 -3.35624188e-01 -6.22555390e-02 -9.41963255e-01 -3.29856426e-01 -6.21835217e-02 -9.43980575e-01 -3.24074477e-01 -6.20602854e-02 -9.45959449e-01 -3.18275422e-01 -6.20844178e-02 -9.47867811e-01 -3.12462211e-01 -6.22480214e-02 -9.49800134e-01 -3.06637168e-01 -6.23337701e-02 -9.51649904e-01 -3.00805151e-01 -6.24601059e-02 -9.53463554e-01 -2.94959337e-01 -6.25135228e-02 -9.55262780e-01 -2.89108217e-01 -6.25009015e-02 -9.57014322e-01 -2.83239603e-01 -6.23964556e-02 -9.58742201e-01 -2.77364224e-01 -6.22168854e-02 -9.60436523e-01 -2.71480709e-01 -6.20772764e-02 -9.62106705e-01 -2.65587807e-01 -6.18020482e-02 -9.63714242e-01 -2.59670198e-01 -6.20702580e-02 -9.65285897e-01 -2.53753245e-01 -6.22379705e-02 -9.66780245e-01 -2.47815415e-01 -6.24040738e-02 -9.68315601e-01 -2.41880402e-01 -6.24942072e-02 -9.69778955e-01 -2.35934243e-01 -6.24647439e-02 -9.71195281e-01 -2.29978532e-01 -6.24699518e-02 -9.72588181e-01 -2.24019542e-01 -6.22374602e-02 -9.73960817e-01 -2.18053252e-01 -6.20584004e-02 -9.75274384e-01 -2.12069392e-01 -6.21265993e-02 -9.76534903e-01 -2.06079572e-01 -6.22259825e-02 -9.77788091e-01 -2.00080767e-01 -6.23784959e-02 -9.78996933e-01 -1.94076225e-01 -6.24576472e-02 -9.80148733e-01 -1.88065469e-01 -6.24739900e-02 -9.81310844e-01 -1.82048559e-01 -6.24082685e-02 -9.82410431e-01 -1.76024780e-01 -6.22545406e-02 -9.83482420e-01 -1.69997364e-01 -6.21408820e-02 -9.84526038e-01 -1.63965896e-01 -6.18279800e-02 -9.85495925e-01 -1.57917291e-01 -6.21239915e-02 -9.86453772e-01 -1.51869282e-01 -6.20064549e-02 -9.87358093e-01 -1.45811528e-01 -6.21498376e-02 -9.88220572e-01 -1.39747173e-01 -6.23729452e-02 -9.89109933e-01 -1.33692816e-01 -6.15185127e-02 -9.89893496e-01 -1.27616853e-01 -6.18458204e-02 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. 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. 0. -9.97923970e-01 -5.46935527e-03 -6.41711727e-02 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.91197944e-01 8.63074884e-02 -1.00387029e-01 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. 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. 0. 0. 0. 0. -9.71912622e-01 2.12962613e-01 -1.00163586e-01 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.25895631e-01 3.64705890e-01 -9.85236689e-02 -9.23703790e-01 3.70401412e-01 -9.78480577e-02 -9.21442270e-01 3.76071960e-01 -9.75395143e-02 -9.19001102e-01 3.81678164e-01 -9.87835601e-02 -9.16667283e-01 3.87318939e-01 -9.85136926e-02 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.40258121e-01 5.33195019e-01 -9.83303636e-02 -8.37000132e-01 5.38357198e-01 -9.79865491e-02 -8.33692253e-01 5.43491066e-01 -9.78346318e-02 -8.30320001e-01 5.48582017e-01 -9.81148183e-02 -8.26934636e-01 5.53664148e-01 -9.81531963e-02 -8.23522568e-01 5.58727741e-01 -9.81599167e-02 -8.20080638e-01 5.63771665e-01 -9.81274024e-02 -8.16602230e-01 5.68791032e-01 -9.81629044e-02 -8.13100815e-01 5.73792994e-01 -9.81278792e-02 -8.09561670e-01 5.78769505e-01 -9.81626138e-02 -8.05962384e-01 5.83704829e-01 -9.85562056e-02 -8.02364469e-01 5.88638544e-01 -9.85687375e-02 -7.98763573e-01 5.93567848e-01 -9.82552171e-02 -7.95109272e-01 5.98459601e-01 -9.82187092e-02 -7.91428089e-01 6.03330910e-01 -9.81491655e-02 -7.87706256e-01 6.08172417e-01 -9.82063636e-02 -7.83963799e-01 6.12997949e-01 -9.81540456e-02 -7.80177832e-01 6.17787480e-01 -9.82359946e-02 -7.76371658e-01 6.22559309e-01 -9.82727930e-02 -7.72518933e-01 6.27299368e-01 -9.85810906e-02 -7.68634498e-01 6.32019937e-01 -9.87390205e-02 -7.64726460e-01 6.36708081e-01 -9.89161059e-02 -7.60806680e-01 6.41381979e-01 -9.89941880e-02 -7.56850958e-01 6.46038651e-01 -9.90269110e-02 -7.52871156e-01 6.50666654e-01 -9.90388766e-02 -7.48863041e-01 6.55273736e-01 -9.90242586e-02 -7.44841635e-01 6.59865677e-01 -9.89628807e-02 -7.40772784e-01 6.64424062e-01 -9.90250334e-02 -7.36666322e-01 6.68944776e-01 -9.90527645e-02 -7.32566774e-01 6.73458874e-01 -9.89851654e-02 -7.28404284e-01 6.77935541e-01 -9.89857987e-02 -7.24247396e-01 6.82401061e-01 -9.90548506e-02 -7.20034838e-01 6.86833858e-01 -9.90161449e-02 -7.15815246e-01 6.91232502e-01 -9.89884362e-02 -7.11563706e-01 6.95614219e-01 -9.89734307e-02 -7.07288980e-01 6.99974775e-01 -9.88408625e-02 -7.02959597e-01 7.04289734e-01 -9.90054980e-02 -6.98638499e-01 7.08600163e-01 -9.89642814e-02 -6.94268644e-01 7.12862253e-01 -9.89909694e-02 -6.89886808e-01 7.17110515e-01 -9.90331396e-02 -6.85459316e-01 7.21339226e-01 -9.90612656e-02 -6.81019485e-01 7.25530148e-01 -9.91142988e-02 -6.76566303e-01 7.29675591e-01 -9.91465747e-02 -6.72072291e-01 7.33803630e-01 -9.91894305e-02 -6.67548239e-01 7.37922668e-01 -9.91856605e-02 -6.63014948e-01 7.42012024e-01 -9.91901606e-02 -6.58442438e-01 7.46059895e-01 -9.91971567e-02 -6.53859913e-01 7.50077546e-01 -9.91949588e-02 -6.49242282e-01 7.54081547e-01 -9.92239788e-02 -6.44602776e-01 7.58067012e-01 -9.92047414e-02 -6.39939785e-01 7.61987746e-01 -9.91804972e-02 -6.35260105e-01 7.65913069e-01 -9.90144759e-02 -6.30549014e-01 7.69800186e-01 -9.90015417e-02 -6.25811338e-01 7.73649514e-01 -9.90514159e-02 -6.21050954e-01 7.77479887e-01 -9.91780609e-02 -6.16263568e-01 7.81285703e-01 -9.90919471e-02 -6.11460984e-01 7.85049260e-01 -9.91115123e-02 -6.06612682e-01 7.88774431e-01 -9.92133990e-02 -6.01765573e-01 7.92462051e-01 -9.91981626e-02 -5.96901357e-01 7.96136975e-01 -9.91591811e-02 -5.92003226e-01 7.99782813e-01 -9.92124081e-02 -5.87080419e-01 8.03413570e-01 -9.91900787e-02 -5.82142472e-01 8.07018697e-01 -9.92255360e-02 -5.77179313e-01 8.10559154e-01 -9.91868377e-02 -5.72199166e-01 8.14089537e-01 -9.91472825e-02 -5.67197919e-01 8.17604244e-01 -9.91373509e-02 -5.62166274e-01 8.21056724e-01 -9.90943015e-02 -5.57121396e-01 8.24497581e-01 -9.90975648e-02 -5.52061975e-01 8.27900827e-01 -9.90944505e-02 -5.46964645e-01 8.31257582e-01 -9.91269574e-02 -5.41858852e-01 8.34612787e-01 -9.91192982e-02 -5.36723554e-01 8.37899566e-01 -9.91380662e-02 -5.31557083e-01 8.41173768e-01 -9.91902798e-02 -5.26400030e-01 8.44444335e-01 -9.92331058e-02 -5.21207035e-01 8.47627878e-01 -9.92391631e-02 -5.15992165e-01 8.50845218e-01 -9.92452651e-02 -5.10755420e-01 8.53951693e-01 -9.92853716e-02 -5.05502522e-01 8.57075632e-01 -9.93060172e-02 -5.00223875e-01 8.60185683e-01 -9.94532704e-02 -4.94944215e-01 8.63220155e-01 -9.94624943e-02 -4.89627182e-01 8.66260469e-01 -9.94526297e-02 -4.84297156e-01 8.69210124e-01 -9.94659215e-02 -4.78960633e-01 8.72178376e-01 -9.94712040e-02 -4.73596871e-01 8.75113428e-01 -9.94688421e-02 -4.68235642e-01 8.77971292e-01 -9.94700342e-02 -4.62830991e-01 8.80860627e-01 -9.94951278e-02 -4.57427353e-01 8.83664310e-01 -9.94141698e-02 -4.51979518e-01 8.86452198e-01 -9.95017141e-02 -4.46544856e-01 8.89223576e-01 -9.95219722e-02 -4.41081703e-01 8.91929567e-01 -9.95062813e-02 -4.35588479e-01 8.94628286e-01 -9.94721055e-02 -4.30094004e-01 8.97259116e-01 -9.96189266e-02 -4.24564868e-01 8.99888575e-01 -9.96591374e-02 -4.19042140e-01 9.02462244e-01 -9.96314138e-02 -4.13505226e-01 9.05026197e-01 -9.95966867e-02 -4.07931060e-01 9.07562077e-01 -9.96183306e-02 -4.02355164e-01 9.10021961e-01 -9.96300876e-02 -3.96762401e-01 9.12502766e-01 -9.95818302e-02 -3.91167939e-01 9.14883375e-01 -9.95972827e-02 -3.85537118e-01 9.17286456e-01 -9.96025428e-02 -3.79908502e-01 9.19635355e-01 -9.96022597e-02 -3.74257296e-01 9.21927571e-01 -9.95857194e-02 -3.68586004e-01 9.24229562e-01 -9.95715857e-02 -3.62937272e-01 9.26536143e-01 -9.91244987e-02 -3.57240796e-01 9.28739011e-01 -9.91168246e-02 -3.51527840e-01 9.30912971e-01 -9.92091522e-02 -3.45803052e-01 9.32995737e-01 -9.95231196e-02 -3.40080261e-01 9.35109735e-01 -9.95054692e-02 -3.34328145e-01 9.37193096e-01 -9.95057076e-02 -3.28569204e-01 9.39194083e-01 -9.94753465e-02 -3.22795868e-01 9.41203892e-01 -9.95297581e-02 -3.17018658e-01 9.43175554e-01 -9.95317474e-02 -3.11231613e-01 9.45088446e-01 -9.95235965e-02 -3.05419624e-01 9.47001219e-01 -9.95173603e-02 -2.99601465e-01 9.48866904e-01 -9.95212942e-02 -2.93776035e-01 9.50670779e-01 -9.95171368e-02 -2.87936449e-01 9.52481389e-01 -9.95334461e-02 -2.82095224e-01 9.54220295e-01 -9.95109007e-02 -2.76227862e-01 9.55916584e-01 -9.95327532e-02 -2.70361841e-01 9.57610250e-01 -9.95451510e-02 -2.64481664e-01 9.59236145e-01 -9.95328054e-02 -2.58591473e-01 9.60850775e-01 -9.95071977e-02 -2.52691180e-01 9.62404132e-01 -9.94810089e-02 -2.46777177e-01 9.63938951e-01 -9.94982421e-02 -2.40865961e-01 9.65434074e-01 -9.94438827e-02 -2.34936520e-01 9.66896474e-01 -9.94292945e-02 -2.28996620e-01 9.68331039e-01 -9.94133428e-02 -2.23050177e-01 9.69754398e-01 -9.94220972e-02 -2.17095882e-01 9.71073389e-01 -9.94681194e-02 -2.11133882e-01 9.72373307e-01 -9.94806662e-02 -2.05160037e-01 9.73664165e-01 -9.94838625e-02 -1.99181661e-01 9.74886358e-01 -9.94831994e-02 -1.93196833e-01 9.76098537e-01 -9.94827077e-02 -1.87209025e-01 9.77293134e-01 -9.94703174e-02 -1.81204021e-01 9.78418648e-01 -9.94843245e-02 -1.75201461e-01 9.79500473e-01 -9.94696990e-02 -1.69188306e-01 9.80555177e-01 -9.94744971e-02 -1.63169146e-01 9.81599092e-01 -9.92997512e-02 -1.57141849e-01 9.82559323e-01 -9.94524285e-02 -1.51108772e-01 9.83499229e-01 -9.94540304e-02 -1.45070881e-01 9.84388530e-01 -9.94397625e-02 -1.39027730e-01 9.85308409e-01 -9.94340032e-02 -1.32979944e-01 9.86137569e-01 -9.94499996e-02 -1.26926631e-01 9.86925185e-01 -9.94642079e-02 -1.20868005e-01 9.87675607e-01 -9.94697213e-02 -1.14806488e-01 9.88403857e-01 -9.94668826e-02 -1.08740792e-01 9.89062071e-01 -9.95152816e-02 -1.02668040e-01 9.89702106e-01 -9.95650738e-02 -9.65939984e-02 9.90340710e-01 -9.95342806e-02 -9.05151740e-02 9.90909100e-01 -9.95055065e-02 -8.44331905e-02 9.91415024e-01 -9.95165780e-02 -7.83475116e-02 9.91957307e-01 -9.95089114e-02 -7.22596645e-02 9.92383063e-01 -9.95146036e-02 -6.61697388e-02 9.92841303e-01 -9.95000303e-02 -6.00760430e-02 9.93224204e-01 -9.94844139e-02 -5.39801829e-02 9.93572772e-01 -9.95226055e-02 -4.78827991e-02 9.93891239e-01 -9.95306745e-02 -4.17824164e-02 9.94151175e-01 -9.95566174e-02 -3.56823057e-02 9.94373083e-01 -9.95901451e-02 -2.95798611e-02 9.94559526e-01 -9.95864198e-02 -2.34765280e-02 9.94762480e-01 -9.95796099e-02 -1.73724238e-02 9.94870305e-01 -9.96036902e-02 -1.12677226e-02 9.94949460e-01 -9.96002331e-02 -5.16252546e-03 9.95019376e-01 -9.96083766e-02 9.42778424e-04 9.95021701e-01 -9.95986983e-02 7.04813842e-03 9.95015621e-01 -9.95985791e-02 1.31533612e-02 9.94934499e-01 -9.96562392e-02 1.92575585e-02 9.94804442e-01 -9.95676816e-02 2.53613461e-02 9.94696796e-01 -9.95826721e-02 3.14637721e-02 9.94531155e-01 -9.95960012e-02 3.75660211e-02 9.94294047e-01 -9.95957926e-02 4.36665453e-02 9.94048297e-01 -9.95840430e-02 4.97647338e-02 9.93786216e-01 -9.95774120e-02 5.58613911e-02 9.93455648e-01 -9.95718315e-02 6.19561039e-02 9.93077219e-01 -9.95913371e-02 6.80480823e-02 9.92695332e-01 -9.95859355e-02 7.41378069e-02 9.92245138e-01 -9.95813683e-02 8.02249014e-02 9.91774797e-01 -9.95875448e-02 8.63107964e-02 9.91268635e-01 -9.95772928e-02 9.23899934e-02 9.90748227e-01 -9.95909423e-02 9.84681249e-02 9.90163863e-01 -9.95718390e-02 1.04543068e-01 9.89550650e-01 -9.93044525e-02 1.10613242e-01 9.88889277e-01 -9.92235616e-02 1.16683461e-01 9.88279700e-01 -9.84148160e-02 1.22751892e-01 9.87648487e-01 -9.73882303e-02 1.28823340e-01 9.87066805e-01 -9.54083875e-02 1.34857148e-01 9.85996127e-01 -9.80867296e-02 1.40894890e-01 9.85034466e-01 -9.92724672e-02 1.46935716e-01 9.84144509e-01 -9.93470028e-02 1.52971864e-01 9.83228505e-01 -9.92938206e-02 1.59000248e-01 9.82252598e-01 -9.95085090e-02 1.65022537e-01 9.81236935e-01 -9.96814892e-02 1.71038702e-01 9.80196297e-01 -9.97675061e-02 1.77048415e-01 9.79121208e-01 -9.98808071e-02 1.83050811e-01 9.77999866e-01 -1.00043267e-01 0. 0. 0. 0. 0. 0. 2.01037124e-01 9.74570453e-01 -9.89732742e-02 2.07041889e-01 9.73507702e-01 -9.70229059e-02 2.12991670e-01 9.72095907e-01 -9.82960016e-02 2.18945935e-01 9.70729709e-01 -9.86942202e-02 2.24894419e-01 9.69342828e-01 -9.89430621e-02 2.30829388e-01 9.67902720e-01 -9.93685871e-02 2.36765876e-01 9.66469646e-01 -9.94232520e-02 2.42688477e-01 9.64993536e-01 -9.95037779e-02 2.48606414e-01 9.63474154e-01 -9.95299369e-02 2.54512310e-01 9.61919963e-01 -9.96084288e-02 2.60407597e-01 9.60340142e-01 -9.96140540e-02 2.66296685e-01 9.58712697e-01 -9.96537060e-02 2.72168487e-01 9.57090557e-01 -9.96778533e-02 2.78037310e-01 9.55397785e-01 -9.96698961e-02 2.83892900e-01 9.53627884e-01 -9.97639745e-02 2.89743572e-01 9.51894104e-01 -9.97083858e-02 2.95572370e-01 9.50065494e-01 -9.97399539e-02 3.01398724e-01 9.48252261e-01 -9.97530669e-02 3.07210147e-01 9.46404636e-01 -9.97481495e-02 3.13005865e-01 9.44471598e-01 -9.97318551e-02 3.18791121e-01 9.42531765e-01 -9.97325778e-02 3.24578822e-01 9.40585434e-01 -9.97506008e-02 3.30347538e-01 9.38559294e-01 -9.97032747e-02 3.36087942e-01 9.36536789e-01 -9.97390747e-02 3.41839552e-01 9.34430063e-01 -9.97195020e-02 3.47560287e-01 9.32329237e-01 -9.97198224e-02 3.53271067e-01 9.30163622e-01 -9.97283235e-02 3.58976930e-01 9.27979171e-01 -9.97136533e-02 3.64667356e-01 9.25771773e-01 -9.96948630e-02 3.70334506e-01 9.23502684e-01 -9.96847898e-02 3.75996619e-01 9.21251655e-01 -9.96715128e-02 3.81637275e-01 9.18887973e-01 -9.96959582e-02 3.87277544e-01 9.16542947e-01 -9.96802896e-02 3.92883211e-01 9.14138973e-01 -9.96685997e-02 3.98502678e-01 9.11736310e-01 -9.95555371e-02 4.04090255e-01 9.09285188e-01 -9.94896069e-02 4.09660935e-01 9.06803310e-01 -9.94708091e-02 4.15223032e-01 9.04268563e-01 -9.95551720e-02 4.20755446e-01 9.01720643e-01 -9.94604453e-02 4.26278859e-01 8.99081647e-01 -9.95551273e-02 4.31800246e-01 8.96465123e-01 -9.94637161e-02 4.37281311e-01 8.93818319e-01 -9.95406955e-02 4.42755252e-01 8.91090870e-01 -9.95024741e-02 4.48214829e-01 8.88378143e-01 -9.95489135e-02 4.53668803e-01 8.85597587e-01 -9.94969755e-02 4.59083110e-01 8.82797420e-01 -9.95561853e-02 4.64492172e-01 8.79978001e-01 -9.95239690e-02 4.69884515e-01 8.77092540e-01 -9.95322838e-02 4.75265145e-01 8.74176860e-01 -9.96209085e-02 4.80615348e-01 8.71255457e-01 -9.96087044e-02 4.85955268e-01 8.68307650e-01 -9.96368229e-02 4.91272569e-01 8.65309417e-01 -9.96056348e-02 4.96555299e-01 8.62262785e-01 -9.96097997e-02 5.01850724e-01 8.59211802e-01 -9.96131301e-02 5.07107139e-01 8.56090009e-01 -9.96252149e-02 5.12343347e-01 8.52992654e-01 -9.96283740e-02 5.17564058e-01 8.49800169e-01 -9.96304378e-02 5.22775233e-01 8.46596658e-01 -9.96180624e-02 5.27975738e-01 8.43417764e-01 -9.95930657e-02 5.33133686e-01 8.40152502e-01 -9.95956361e-02 5.38282096e-01 8.36872578e-01 -9.95985419e-02 5.43417394e-01 8.33529413e-01 -9.95438695e-02 5.48515916e-01 8.30197811e-01 -9.95667353e-02 5.53602934e-01 8.26811850e-01 -9.95644033e-02 5.58647156e-01 8.23402643e-01 -9.95542258e-02 5.63705325e-01 8.19972694e-01 -9.95345265e-02 5.68706214e-01 8.16476285e-01 -9.95513424e-02 5.73692977e-01 8.12950909e-01 -9.96308327e-02 5.78674614e-01 8.09419215e-01 -9.96197388e-02 5.83631516e-01 8.05867493e-01 -9.96343493e-02 5.88587165e-01 8.02257180e-01 -9.95872617e-02 5.93479872e-01 7.98629999e-01 -9.95770097e-02 5.98361075e-01 7.94971645e-01 -9.96191129e-02 6.03249252e-01 7.91318953e-01 -9.95826498e-02 6.08082652e-01 7.87570953e-01 -9.95797589e-02 6.12902343e-01 7.83820450e-01 -9.95599553e-02 6.17717087e-01 7.80053377e-01 -9.95459035e-02 6.22491837e-01 7.76266038e-01 -9.95445400e-02 6.27230346e-01 7.72406161e-01 -9.95709449e-02 6.31964386e-01 7.68581212e-01 -9.95770618e-02 6.36674285e-01 7.64695227e-01 -9.95722413e-02 6.41330242e-01 7.60730386e-01 -9.95603874e-02 6.46013260e-01 7.56809056e-01 -9.95444730e-02 6.50643051e-01 7.52822876e-01 -9.95353088e-02 6.55253232e-01 7.48817027e-01 -9.95277986e-02 6.59825027e-01 7.44811654e-01 -9.94665772e-02 6.64396524e-01 7.40714610e-01 -9.95004326e-02 6.68907464e-01 7.36645222e-01 -9.95096043e-02 6.73426032e-01 7.32525945e-01 -9.95194688e-02 6.77890241e-01 7.28377700e-01 -9.95442942e-02 6.82374418e-01 7.24188089e-01 -9.95294228e-02 6.86789393e-01 7.20013380e-01 -9.95052382e-02 6.91218972e-01 7.15782642e-01 -9.94996652e-02 6.95598960e-01 7.11533725e-01 -9.94998068e-02 6.99918270e-01 7.07247257e-01 -9.96014476e-02 7.04250038e-01 7.02914417e-01 -9.96037647e-02 7.08559155e-01 6.98577464e-01 -9.96182412e-02 7.12841332e-01 6.94247961e-01 -9.96065959e-02 7.17090309e-01 6.89830840e-01 -9.96100903e-02 7.21285105e-01 6.85421765e-01 -9.96135697e-02 7.25499570e-01 6.81006253e-01 -9.96135473e-02 7.29641199e-01 6.76542640e-01 -9.96125042e-02 7.33794987e-01 6.72056556e-01 -9.95030329e-02 7.37903535e-01 6.67531848e-01 -9.95081961e-02 7.41994977e-01 6.62992775e-01 -9.95277837e-02 7.46035099e-01 6.58422172e-01 -9.96111035e-02 7.50053346e-01 6.53840482e-01 -9.95825753e-02 7.54057050e-01 6.49226129e-01 -9.94639546e-02 7.58049846e-01 6.44577920e-01 -9.95210037e-02 7.61965513e-01 6.39909863e-01 -9.95545238e-02 7.65871644e-01 6.35235608e-01 -9.95573178e-02 7.69758165e-01 6.30523264e-01 -9.95538160e-02 7.73618281e-01 6.25786841e-01 -9.95481461e-02 7.77467847e-01 6.21038258e-01 -9.95631069e-02 7.81259954e-01 6.16232812e-01 -9.95780528e-02 7.85025299e-01 6.11445546e-01 -9.95785221e-02 7.88764238e-01 6.06598914e-01 -9.95944440e-02 7.92444110e-01 6.01746500e-01 -9.95840654e-02 7.96110511e-01 5.96878350e-01 -9.95860994e-02 7.99783528e-01 5.91990769e-01 -9.96029824e-02 8.03388715e-01 5.87056339e-01 -9.95858088e-02 8.07000875e-01 5.82137346e-01 -9.95955169e-02 8.10527384e-01 5.77162385e-01 -9.96508226e-02 8.14052761e-01 5.72181165e-01 -9.96430814e-02 8.17567706e-01 5.67155421e-01 -9.96457413e-02 8.21003556e-01 5.62136352e-01 -9.96267945e-02 8.24474454e-01 5.57097733e-01 -9.96089727e-02 8.27877462e-01 5.52040637e-01 -9.95819196e-02 8.31219435e-01 5.46950758e-01 -9.94765088e-02 8.34597766e-01 5.41851938e-01 -9.93629694e-02 8.37869287e-01 5.36704183e-01 -9.95874926e-02 8.41157198e-01 5.31544864e-01 -9.94977206e-02 8.44426990e-01 5.26388407e-01 -9.94877517e-02 8.47612023e-01 5.21196961e-01 -9.93650705e-02 8.50835145e-01 5.15981257e-01 -9.93637517e-02 8.53965759e-01 5.10752499e-01 -9.93461832e-02 8.57068241e-01 5.05502105e-01 -9.94638056e-02 8.60192418e-01 5.00228345e-01 -9.94622186e-02 8.63227367e-01 4.94945228e-01 -9.94587466e-02 8.66266847e-01 4.89631385e-01 -9.94398147e-02 8.69216204e-01 4.84306067e-01 -9.94282588e-02 8.72198462e-01 4.78968382e-01 -9.93311703e-02 8.75134051e-01 4.73606557e-01 -9.93274078e-02 8.77988935e-01 4.68247652e-01 -9.93171632e-02 8.80873203e-01 4.62840557e-01 -9.93305147e-02 8.83677125e-01 4.57432568e-01 -9.93994176e-02 8.86466801e-01 4.51988906e-01 -9.93358046e-02 8.89245749e-01 4.46554035e-01 -9.93186086e-02 8.91950250e-01 4.41091776e-01 -9.93298814e-02 8.94630909e-01 4.35590118e-01 -9.93959308e-02 8.97287488e-01 4.30109829e-01 -9.93948951e-02 8.99938047e-01 4.24591959e-01 -9.93013456e-02 9.02507067e-01 4.19063926e-01 -9.93011370e-02 9.05060768e-01 4.13522631e-01 -9.93875638e-02 9.07594740e-01 4.07946795e-01 -9.93946120e-02 9.10051525e-01 4.02370751e-01 -9.93634611e-02 9.12548542e-01 3.96780431e-01 -9.93493348e-02 9.14918661e-01 3.91184092e-01 -9.93540511e-02 9.17322457e-01 3.85551810e-01 -9.93516669e-02 9.19666648e-01 3.79926562e-01 -9.93327647e-02 9.21964824e-01 3.74274790e-01 -9.93255600e-02 9.24265087e-01 3.68602753e-01 -9.92983654e-02 9.26536024e-01 3.62940311e-01 -9.92790312e-02 9.28740799e-01 3.57239395e-01 -9.92613584e-02 9.30922687e-01 3.51532280e-01 -9.92482007e-02 9.33040679e-01 3.45823437e-01 -9.91559029e-02 9.35162723e-01 3.40099066e-01 -9.91374999e-02 9.37239230e-01 3.34345996e-01 -9.91432443e-02 9.39235508e-01 3.28587025e-01 -9.91030857e-02 9.41257894e-01 3.22816372e-01 -9.91087332e-02 9.43229139e-01 3.17038566e-01 -9.91098136e-02 9.45138752e-01 3.11249793e-01 -9.91588086e-02 9.47045863e-01 3.05435240e-01 -9.92048234e-02 9.48908806e-01 2.99617946e-01 -9.91972312e-02 9.50704157e-01 2.93785393e-01 -9.92553309e-02 9.52497065e-01 2.87948281e-01 -9.92617160e-02 9.54249322e-01 2.82104522e-01 -9.92580727e-02 9.55952585e-01 2.76236802e-01 -9.92511138e-02 9.57648218e-01 2.70376503e-01 -9.92486551e-02 9.59271729e-01 2.64491379e-01 -9.92516801e-02 9.60887909e-01 2.58600295e-01 -9.92387533e-02 9.62436020e-01 2.52702802e-01 -9.92320180e-02 9.63969588e-01 2.46785700e-01 -9.92339328e-02 9.65450704e-01 2.40870535e-01 -9.92175862e-02 9.66905355e-01 2.34937817e-01 -9.92203876e-02 9.68343258e-01 2.29002997e-01 -9.92126614e-02 9.69773829e-01 2.23057523e-01 -9.92016047e-02 9.71091032e-01 2.17098325e-01 -9.92207453e-02 9.72412109e-01 2.11146936e-01 -9.90020931e-02 9.73701298e-01 2.05169871e-01 -9.89921242e-02 9.74920273e-01 1.99196085e-01 -9.89980996e-02 9.76112366e-01 1.93201050e-01 -9.91961360e-02 9.77306902e-01 1.87211648e-01 -9.92065072e-02 9.78440642e-01 1.81208730e-01 -9.92175117e-02 9.79510188e-01 1.75203159e-01 -9.92145464e-02 9.80561435e-01 1.69189766e-01 -9.92158651e-02 9.81600165e-01 1.63166717e-01 -9.92280170e-02 9.82576787e-01 1.57145157e-01 -9.92238596e-02 9.83489931e-01 1.51110262e-01 -9.92213786e-02 9.84389961e-01 1.45072028e-01 -9.92157087e-02 9.85336661e-01 1.39032900e-01 -9.90281701e-02 9.86154795e-01 1.32985264e-01 -9.90239978e-02 9.86947775e-01 1.26929983e-01 -9.91945788e-02 9.87696052e-01 1.20871052e-01 -9.91635770e-02 9.88438904e-01 1.14814669e-01 -9.90123525e-02 9.89091873e-01 1.08746156e-01 -9.89926159e-02 9.89748299e-01 1.02673642e-01 -9.89850610e-02 9.90385830e-01 9.66004357e-02 -9.89668518e-02 9.90948379e-01 9.05208737e-02 -9.89981890e-02 9.91453826e-01 8.44385102e-02 -9.89910290e-02 9.91986334e-01 7.83525184e-02 -9.90233347e-02 9.92420197e-01 7.22644851e-02 -9.90090147e-02 9.92880344e-01 6.61738813e-02 -9.90209728e-02 9.93276179e-01 6.00809455e-02 -9.90103558e-02 9.93610144e-01 5.39844818e-02 -9.90191177e-02 9.93945599e-01 4.78894934e-02 -9.88434032e-02 9.94207680e-01 4.17902209e-02 -9.88341644e-02 9.94443655e-01 3.56891640e-02 -9.88144428e-02 9.94615614e-01 2.95850094e-02 -9.89429355e-02 9.94815826e-01 2.34814100e-02 -9.89485905e-02 9.94925380e-01 1.73773114e-02 -9.89181027e-02 9.95004833e-01 1.12721156e-02 -9.89442766e-02 9.95073020e-01 5.16661070e-03 -9.89464074e-02 9.95077729e-01 -9.39071062e-04 -9.89451781e-02 9.95069504e-01 -7.04480428e-03 -9.89547148e-02 9.95001554e-01 -1.31500708e-02 -9.89284143e-02 9.94855940e-01 -1.92548037e-02 -9.89491567e-02 9.94755983e-01 -2.53592394e-02 -9.89388824e-02 9.94593799e-01 -3.14622931e-02 -9.88966599e-02 9.94354069e-01 -3.75645719e-02 -9.89470184e-02 9.94109094e-01 -4.36649695e-02 -9.89445075e-02 9.93851364e-01 -4.97645400e-02 -9.89163443e-02 9.93523896e-01 -5.58618717e-02 -9.89377573e-02 9.93134856e-01 -6.19563609e-02 -9.89610553e-02 9.92752194e-01 -6.80491477e-02 -9.88653675e-02 9.92317975e-01 -7.41393790e-02 -9.88917127e-02 9.91839528e-01 -8.02268609e-02 -9.89676118e-02 9.91335094e-01 -8.63092840e-02 -9.89802629e-02 9.90784287e-01 -9.23913643e-02 -9.89517868e-02 9.90213513e-01 -9.84696969e-02 -9.89464223e-02 9.89570200e-01 -1.04543597e-01 -9.89571214e-02 9.88910615e-01 -1.10612556e-01 -9.89603996e-02 9.88200188e-01 -1.16675399e-01 -9.89648029e-02 9.87471521e-01 -1.22740880e-01 -9.89608616e-02 9.86720681e-01 -1.28796309e-01 -9.89542380e-02 9.85871077e-01 -1.34851336e-01 -9.89501402e-02 9.85046387e-01 -1.40897498e-01 -9.89282131e-02 9.84152257e-01 -1.46940082e-01 -9.89788920e-02 9.83250737e-01 -1.52973965e-01 -9.89627019e-02 9.82289791e-01 -1.59002975e-01 -9.89206135e-02 9.81311738e-01 -1.65028721e-01 -9.89178270e-02 9.80270982e-01 -1.71048537e-01 -9.89006311e-02 9.79222536e-01 -1.77058205e-01 -9.89065841e-02 9.78066564e-01 -1.83056623e-01 -9.91011038e-02 9.76950407e-01 -1.89064279e-01 -9.89364833e-02 9.75802600e-01 -1.95049584e-01 -9.89608914e-02 9.74586904e-01 -2.01033518e-01 -9.89623144e-02 9.73304212e-01 -2.07010150e-01 -9.89538357e-02 9.72009361e-01 -2.12982059e-01 -9.89598781e-02 9.70709085e-01 -2.18946368e-01 -9.89749059e-02 9.69333291e-01 -2.24898219e-01 -9.89507809e-02 9.67939854e-01 -2.30837598e-01 -9.89888310e-02 9.66474116e-01 -2.36767903e-01 -9.91284773e-02 9.65029180e-01 -2.42696151e-01 -9.90098417e-02 9.63503778e-01 -2.48611853e-01 -9.90052968e-02 9.61994410e-01 -2.54523307e-01 -9.89949256e-02 9.60368633e-01 -2.60420889e-01 -9.90107879e-02 9.58793938e-01 -2.66308635e-01 -9.90371406e-02 9.57164586e-01 -2.72190720e-01 -9.90131572e-02 9.55470264e-01 -2.78050542e-01 -9.89972353e-02 9.53733742e-01 -2.83916503e-01 -9.90076959e-02 9.51954663e-01 -2.89761961e-01 -9.90142822e-02 9.50146317e-01 -2.95594066e-01 -9.90246460e-02 9.48347867e-01 -3.01420927e-01 -9.90314558e-02 9.46484983e-01 -3.07234466e-01 -9.90336314e-02 9.44547534e-01 -3.13026667e-01 -9.90414023e-02 9.42607701e-01 -3.18810999e-01 -9.90409106e-02 9.40658569e-01 -3.24601173e-01 -9.90417004e-02 9.38642859e-01 -3.30367416e-01 -9.90171283e-02 9.36604381e-01 -3.36110383e-01 -9.90222991e-02 9.34521854e-01 -3.41863692e-01 -9.89984274e-02 9.32399631e-01 -3.47584307e-01 -9.90543216e-02 9.30232465e-01 -3.53295475e-01 -9.90678594e-02 9.28046703e-01 -3.59001517e-01 -9.90689024e-02 9.25843596e-01 -3.64698917e-01 -9.90421027e-02 9.23581481e-01 -3.70361745e-01 -9.90480408e-02 9.21308339e-01 -3.76017421e-01 -9.90212783e-02 9.18951213e-01 -3.81656498e-01 -9.92116183e-02 9.16599214e-01 -3.87299776e-01 -9.91946533e-02 9.14208114e-01 -3.92909855e-01 -9.90018845e-02 9.11777854e-01 -3.98529977e-01 -9.89998356e-02 9.09327507e-01 -4.04117286e-01 -9.90040675e-02 9.06858265e-01 -4.09672320e-01 -9.90341529e-02 9.04307961e-01 -4.15238559e-01 -9.90423337e-02 9.01764989e-01 -4.20771539e-01 -9.90860015e-02 8.99123967e-01 -4.26298738e-01 -9.90911275e-02 8.96491945e-01 -4.31817114e-01 -9.90855172e-02 8.93850267e-01 -4.37293798e-01 -9.90996510e-02 8.91121626e-01 -4.42767322e-01 -9.90941525e-02 8.88426304e-01 -4.48230833e-01 -9.90538746e-02 8.85657310e-01 -4.53688323e-01 -9.90382731e-02 8.82842243e-01 -4.59110379e-01 -9.90478098e-02 8.80010188e-01 -4.64506865e-01 -9.90553349e-02 8.77155066e-01 -4.69903857e-01 -9.90470871e-02 8.74248683e-01 -4.75285918e-01 -9.90253687e-02 8.71318698e-01 -4.80644822e-01 -9.90563259e-02 8.68352473e-01 -4.85983223e-01 -9.90617871e-02 8.65352035e-01 -4.91300613e-01 -9.90716666e-02 8.62303078e-01 -4.96579885e-01 -9.90454033e-02 8.59266222e-01 -5.01879930e-01 -9.91010889e-02 8.56137753e-01 -5.07133722e-01 -9.90920737e-02 8.53036165e-01 -5.12370586e-01 -9.90903378e-02 8.49865377e-01 -5.17595172e-01 -9.90758166e-02 8.46650660e-01 -5.22804081e-01 -9.91410762e-02 8.43461752e-01 -5.27998805e-01 -9.91334766e-02 8.40187788e-01 -5.33142745e-01 -9.91473868e-02 8.36911440e-01 -5.38307667e-01 -9.91786718e-02 8.33580077e-01 -5.43435395e-01 -9.91679057e-02 8.30230713e-01 -5.48538268e-01 -9.91565064e-02 8.26847613e-01 -5.53624272e-01 -9.91574377e-02 8.23442757e-01 -5.58666587e-01 -9.91509259e-02 8.20010543e-01 -5.63729525e-01 -9.91507247e-02 8.16513956e-01 -5.68727911e-01 -9.91544276e-02 8.13003600e-01 -5.73729217e-01 -9.91346762e-02 8.09472382e-01 -5.78707755e-01 -9.91421565e-02 8.05921495e-01 -5.83666921e-01 -9.91375744e-02 8.02313864e-01 -5.88615179e-01 -9.91370827e-02 7.98679829e-01 -5.93510091e-01 -9.91303027e-02 7.95026302e-01 -5.98398566e-01 -9.91320759e-02 7.91355669e-01 -6.03280008e-01 -9.91585106e-02 7.87614942e-01 -6.08107090e-01 -9.91375223e-02 7.83866882e-01 -6.12934768e-01 -9.91450399e-02 7.80100524e-01 -6.17753744e-01 -9.91155952e-02 7.76314855e-01 -6.22526824e-01 -9.90987122e-02 7.72454739e-01 -6.27268016e-01 -9.91356820e-02 7.68623650e-01 -6.31998241e-01 -9.91964787e-02 7.64735222e-01 -6.36708140e-01 -9.91858542e-02 7.60778069e-01 -6.41365349e-01 -9.91713107e-02 7.56855428e-01 -6.46051228e-01 -9.92120132e-02 7.52867758e-01 -6.50681257e-01 -9.91554111e-02 7.48856843e-01 -6.55289829e-01 -9.92016941e-02 7.44838238e-01 -6.59845650e-01 -9.92236212e-02 7.40742028e-01 -6.64424717e-01 -9.92010161e-02 7.36686170e-01 -6.68938994e-01 -9.91995931e-02 7.32566535e-01 -6.73444271e-01 -9.92006287e-02 7.28421509e-01 -6.77926838e-01 -9.92288962e-02 7.24220872e-01 -6.82405233e-01 -9.92253199e-02 7.20045686e-01 -6.86812222e-01 -9.92205963e-02 7.15814471e-01 -6.91253841e-01 -9.91086662e-02 7.11562753e-01 -6.95628226e-01 -9.91008505e-02 7.07281351e-01 -6.99944079e-01 -9.92588103e-02 7.02947617e-01 -7.04279959e-01 -9.92514342e-02 6.98605239e-01 -7.08582640e-01 -9.92478505e-02 6.94282532e-01 -7.12871969e-01 -9.92650017e-02 6.89857602e-01 -7.17121780e-01 -9.92722809e-02 6.85450256e-01 -7.21309841e-01 -9.92880911e-02 6.81039274e-01 -7.25525141e-01 -9.93113965e-02 6.76564813e-01 -7.29663968e-01 -9.93259922e-02 6.72075689e-01 -7.33805299e-01 -9.92958471e-02 6.67558014e-01 -7.37920582e-01 -9.93173942e-02 6.62999928e-01 -7.42026329e-01 -9.92967039e-02 6.58454180e-01 -7.46058643e-01 -9.93051454e-02 6.53860331e-01 -7.50074327e-01 -9.93004516e-02 6.49240553e-01 -7.54073858e-01 -9.93615538e-02 6.44608021e-01 -7.58073390e-01 -9.93107036e-02 6.39922261e-01 -7.61985362e-01 -9.93081480e-02 6.35256052e-01 -7.65883327e-01 -9.93362516e-02 6.30535483e-01 -7.69770503e-01 -9.93596315e-02 6.25799298e-01 -7.73635864e-01 -9.93406847e-02 6.21048093e-01 -7.77481496e-01 -9.93617624e-02 6.16239190e-01 -7.81276464e-01 -9.93273482e-02 6.11460626e-01 -7.85041094e-01 -9.93134752e-02 6.06611311e-01 -7.88784623e-01 -9.93647650e-02 6.01758420e-01 -7.92458594e-01 -9.93601754e-02 5.96894324e-01 -7.96127975e-01 -9.93132815e-02 5.92009664e-01 -7.99779475e-01 -9.93398800e-02 5.87074637e-01 -8.03410053e-01 -9.92872715e-02 5.82152367e-01 -8.07020068e-01 -9.93375331e-02 5.77183723e-01 -8.10559511e-01 -9.93240401e-02 5.72203159e-01 -8.14076781e-01 -9.93200541e-02 5.67174375e-01 -8.17586482e-01 -9.93259400e-02 5.62154949e-01 -8.21033001e-01 -9.93280262e-02 5.57121098e-01 -8.24495018e-01 -9.93663445e-02 5.52050591e-01 -8.27895045e-01 -9.93733034e-02 5.46952248e-01 -8.31235051e-01 -9.93807092e-02 5.41846871e-01 -8.34585965e-01 -9.93808284e-02 5.36720395e-01 -8.37884188e-01 -9.93849188e-02 5.31547368e-01 -8.41172218e-01 -9.93980691e-02 5.26395440e-01 -8.44433606e-01 -9.93918851e-02 5.21199763e-01 -8.47614408e-01 -9.94099900e-02 5.15983522e-01 -8.50830853e-01 -9.94143561e-02 5.10753095e-01 -8.53949189e-01 -9.94189978e-02 5.05509317e-01 -8.57069373e-01 -9.94354337e-02 5.00226319e-01 -8.60194206e-01 -9.94500220e-02 4.94954973e-01 -8.63217533e-01 -9.94669348e-02 4.89628106e-01 -8.66264403e-01 -9.94774476e-02 4.84302878e-01 -8.69212806e-01 -9.94707048e-02 4.78964895e-01 -8.72175097e-01 -9.94728655e-02 4.73597735e-01 -8.75114381e-01 -9.94777903e-02 4.68239337e-01 -8.77973080e-01 -9.94732603e-02 4.62840348e-01 -8.80865932e-01 -9.94964838e-02 4.57427055e-01 -8.83665025e-01 -9.94996652e-02 4.51983631e-01 -8.86455894e-01 -9.94936973e-02 4.46548074e-01 -8.89238656e-01 -9.94956717e-02 4.41085100e-01 -8.91926289e-01 -9.94698405e-02 4.35587823e-01 -8.94617736e-01 -9.94803682e-02 4.30105001e-01 -8.97271633e-01 -9.94897783e-02 4.24580455e-01 -8.99925411e-01 -9.94883031e-02 4.19051141e-01 -9.02481675e-01 -9.95019451e-02 4.13511127e-01 -9.05051112e-01 -9.96004343e-02 4.07938749e-01 -9.07580614e-01 -9.96022969e-02 4.02358741e-01 -9.10032570e-01 -9.95302349e-02 3.96768451e-01 -9.12520111e-01 -9.95946601e-02 3.91171515e-01 -9.14893627e-01 -9.96026173e-02 3.85543823e-01 -9.17299926e-01 -9.94915590e-02 3.79917920e-01 -9.19634998e-01 -9.95308906e-02 3.74263257e-01 -9.21936512e-01 -9.95678380e-02 3.68582338e-01 -9.24224377e-01 -9.96681377e-02 3.62917662e-01 -9.26488876e-01 -9.96730551e-02 3.57217997e-01 -9.28692639e-01 -9.96812284e-02 3.51508945e-01 -9.30871069e-01 -9.96855050e-02 3.45799834e-01 -9.32990372e-01 -9.96610448e-02 3.40071797e-01 -9.35093641e-01 -9.96967331e-02 3.34321648e-01 -9.37180161e-01 -9.96875092e-02 3.28559250e-01 -9.39166486e-01 -9.96779129e-02 3.22790265e-01 -9.41185534e-01 -9.96884108e-02 3.17013949e-01 -9.43169653e-01 -9.96754915e-02 3.11227083e-01 -9.45081711e-01 -9.96431857e-02 3.05417895e-01 -9.47011232e-01 -9.96071026e-02 2.99598306e-01 -9.48855698e-01 -9.96383876e-02 2.93772668e-01 -9.50673401e-01 -9.95950997e-02 2.87931591e-01 -9.52448428e-01 -9.96181220e-02 2.82090157e-01 -9.54206407e-01 -9.96197462e-02 2.76221007e-01 -9.55901980e-01 -9.96400863e-02 2.70358294e-01 -9.57598269e-01 -9.96296182e-02 2.64477521e-01 -9.59214866e-01 -9.96246487e-02 2.58589417e-01 -9.60867345e-01 -9.95792821e-02 2.52692580e-01 -9.62400556e-01 -9.95042399e-02 2.46782616e-01 -9.63947356e-01 -9.94404033e-02 2.40863979e-01 -9.65439439e-01 -9.94626135e-02 2.34935984e-01 -9.66906250e-01 -9.94322449e-02 2.28997096e-01 -9.68330443e-01 -9.93627533e-02 2.23052979e-01 -9.69731092e-01 -9.93444994e-02 2.17098981e-01 -9.71074581e-01 -9.93359983e-02 2.11142853e-01 -9.72421825e-01 -9.91005301e-02 2.05177844e-01 -9.73720312e-01 -9.88726541e-02 1.99204326e-01 -9.74975884e-01 -9.86779407e-02 1.93224847e-01 -9.76206005e-01 -9.84188020e-02 1.87257633e-01 -9.77476120e-01 -9.73100588e-02 1.81225255e-01 -9.78480697e-01 -9.86556113e-02 1.75224319e-01 -9.79600668e-01 -9.83822048e-02 1.69212610e-01 -9.80667353e-01 -9.82772186e-02 1.63187981e-01 -9.81668949e-01 -9.84727144e-02 1.57157481e-01 -9.82634425e-01 -9.86645743e-02 1.51125863e-01 -9.83583391e-01 -9.86282304e-02 1.45089358e-01 -9.84498858e-01 -9.85482037e-02 1.39049351e-01 -9.85386431e-01 -9.83668342e-02 1.33119524e-01 -9.86827850e-01 -9.19235945e-02 1.27003193e-01 -9.87316787e-01 -9.52102616e-02 1.20899022e-01 -9.87839103e-01 -9.77308899e-02 1.14825428e-01 -9.88506854e-01 -9.83370319e-02 1.08751036e-01 -9.89151478e-01 -9.87453386e-02 1.02673940e-01 -9.89772081e-01 -9.91452485e-02 9.65934470e-02 -9.90333259e-01 -9.94635448e-02 9.05136690e-02 -9.90898550e-01 -9.95997190e-02 8.44303221e-02 -9.91398454e-01 -9.96240750e-02 7.83448070e-02 -9.91929233e-01 -9.96663719e-02 7.22564384e-02 -9.92363214e-01 -9.96499732e-02 6.61671162e-02 -9.92829800e-01 -9.96330082e-02 6.00741953e-02 -9.93226290e-01 -9.96408910e-02 5.39781041e-02 -9.93563056e-01 -9.96471792e-02 4.78810072e-02 -9.93868053e-01 -9.96557176e-02 4.17822003e-02 -9.94128644e-01 -9.96585265e-02 3.56813483e-02 -9.94365036e-01 -9.96333733e-02 2.95790583e-02 -9.94552791e-01 -9.96304974e-02 2.34762300e-02 -9.94753540e-01 -9.96573195e-02 1.73720364e-02 -9.94857252e-01 -9.96503457e-02 1.12675251e-02 -9.94948506e-01 -9.96451899e-02 5.16228843e-03 -9.95015144e-01 -9.96488556e-02 -9.43067425e-04 -9.95015502e-01 -9.96613130e-02 -7.04798754e-03 -9.95015979e-01 -9.95947346e-02 -1.31533258e-02 -9.94944394e-01 -9.96111184e-02 -1.92573182e-02 -9.94810820e-01 -9.95085835e-02 -2.53612604e-02 -9.94696677e-01 -9.94920284e-02 -3.14641595e-02 -9.94543493e-01 -9.95097384e-02 -3.75662409e-02 -9.94309664e-01 -9.94976386e-02 -4.36662845e-02 -9.94071126e-01 -9.94937941e-02 -4.97652702e-02 -9.93799627e-01 -9.94754136e-02 -5.58623970e-02 -9.93461668e-01 -9.94920656e-02 -6.19570315e-02 -9.93097246e-01 -9.94985253e-02 -6.80490956e-02 -9.92724895e-01 -9.94926542e-02 -7.41390362e-02 -9.92255270e-01 -9.94639769e-02 -8.02257955e-02 -9.91788089e-01 -9.94591638e-02 -8.63102749e-02 -9.91279006e-01 -9.94625613e-02 -9.23911631e-02 -9.90758896e-01 -9.95123237e-02 -9.84683707e-02 -9.90173578e-01 -9.95161682e-02 -1.04541630e-01 -9.89548206e-01 -9.94701684e-02 -1.10612407e-01 -9.88856256e-01 -9.94655117e-02 -1.16677269e-01 -9.88152921e-01 -9.94710028e-02 -1.22738205e-01 -9.87410486e-01 -9.95859876e-02 -1.28794461e-01 -9.86657560e-01 -9.96454582e-02 -1.34845942e-01 -9.85810637e-01 -9.96610448e-02 -1.40893936e-01 -9.84984934e-01 -9.96344611e-02 -1.46935567e-01 -9.84094203e-01 -9.96525809e-02 -1.52966395e-01 -9.83190298e-01 -9.96629968e-02 -1.58996537e-01 -9.82221365e-01 -9.96733978e-02 -1.65019989e-01 -9.81245399e-01 -9.96702760e-02 -1.71040684e-01 -9.80196536e-01 -9.96976122e-02 -1.77050561e-01 -9.79146063e-01 -9.97084081e-02 -1.83050856e-01 -9.78015661e-01 -9.97286439e-02 -1.89055488e-01 -9.76889133e-01 -9.97314602e-02 -1.95043549e-01 -9.75735903e-01 -9.97257978e-02 -2.01026112e-01 -9.74518895e-01 -9.97046456e-02 -2.07004324e-01 -9.73254681e-01 -9.96999070e-02 -2.12972492e-01 -9.71949220e-01 -9.97079611e-02 -2.18935147e-01 -9.70636785e-01 -9.97137651e-02 -2.24885970e-01 -9.69265938e-01 -9.97290388e-02 -2.30827615e-01 -9.67869520e-01 -9.97324213e-02 -2.36758277e-01 -9.66419101e-01 -9.97242928e-02 -2.42680341e-01 -9.64956522e-01 -9.97147262e-02 -2.48598605e-01 -9.63433087e-01 -9.97176319e-02 -2.54510313e-01 -9.61906731e-01 -9.97072756e-02 -2.60406226e-01 -9.60293353e-01 -9.96905044e-02 -2.66303748e-01 -9.58756208e-01 -9.94970798e-02 -2.72167683e-01 -9.57096219e-01 -9.96185392e-02 -2.78031230e-01 -9.55391228e-01 -9.97067466e-02 -2.83894926e-01 -9.53644991e-01 -9.96658355e-02 -2.89745390e-01 -9.51893806e-01 -9.96032208e-02 -2.95576513e-01 -9.50078547e-01 -9.96404439e-02 -3.01404059e-01 -9.48280156e-01 -9.96347070e-02 -3.07215750e-01 -9.46430743e-01 -9.96031612e-02 -3.13014418e-01 -9.44499254e-01 -9.96004641e-02 -3.18799257e-01 -9.42555726e-01 -9.96215641e-02 -3.24582070e-01 -9.40605044e-01 -9.96021032e-02 -3.30345958e-01 -9.38582182e-01 -9.96025130e-02 -3.36098611e-01 -9.36565995e-01 -9.95909795e-02 -3.41849357e-01 -9.34455931e-01 -9.95471999e-02 -3.47569644e-01 -9.32356000e-01 -9.95745137e-02 -3.53283644e-01 -9.30200636e-01 -9.94197130e-02 -3.58987212e-01 -9.28009331e-01 -9.94400755e-02 -3.64675552e-01 -9.25781131e-01 -9.96983871e-02 -3.70339990e-01 -9.23512578e-01 -9.96617973e-02 -3.75998497e-01 -9.21255589e-01 -9.96685550e-02 -3.81639808e-01 -9.18894291e-01 -9.96855423e-02 -3.87279034e-01 -9.16546762e-01 -9.96529534e-02 -3.92892510e-01 -9.14160430e-01 -9.95917991e-02 -3.98506194e-01 -9.11734223e-01 -9.95788425e-02 -4.04098630e-01 -9.09285963e-01 -9.94016752e-02 -4.09653336e-01 -9.06808138e-01 -9.93102640e-02 -4.15224761e-01 -9.04276133e-01 -9.93224904e-02 -4.20743108e-01 -9.01698768e-01 -9.96708646e-02 -4.26273018e-01 -8.99058998e-01 -9.96895358e-02 -4.31789696e-01 -8.96418273e-01 -9.96940285e-02 -4.37272608e-01 -8.93805265e-01 -9.96780172e-02 -4.42746788e-01 -8.91075075e-01 -9.96668115e-02 -4.48210031e-01 -8.88377547e-01 -9.96556059e-02 -4.53665704e-01 -8.85597885e-01 -9.96649638e-02 -4.59083796e-01 -8.82796168e-01 -9.96543244e-02 -4.64488894e-01 -8.79980862e-01 -9.96500403e-02 -4.69884634e-01 -8.77089322e-01 -9.96552557e-02 -4.75258738e-01 -8.74175549e-01 -9.96518806e-02 -4.80617553e-01 -8.71253908e-01 -9.96772945e-02 -4.85955387e-01 -8.68307114e-01 -9.96716991e-02 -4.91260976e-01 -8.65298510e-01 -9.96827632e-02 -4.96554315e-01 -8.62264335e-01 -9.96849239e-02 -5.01848936e-01 -8.59211266e-01 -9.96968970e-02 -5.07111549e-01 -8.56097043e-01 -9.96989757e-02 -5.12349010e-01 -8.53003979e-01 -9.96970534e-02 -5.17572522e-01 -8.49826634e-01 -9.96912345e-02 -5.22780478e-01 -8.46608698e-01 -9.95870605e-02 -5.27960837e-01 -8.43409359e-01 -9.95828807e-02 -5.33129573e-01 -8.40155184e-01 -9.96261686e-02 -5.38283467e-01 -8.36872816e-01 -9.96834040e-02 -5.43413401e-01 -8.33539188e-01 -9.96763632e-02 -5.48517704e-01 -8.30202520e-01 -9.96268019e-02 -5.53603888e-01 -8.26814413e-01 -9.95086730e-02 -5.58656216e-01 -8.23411763e-01 -9.94988158e-02 -5.63713074e-01 -8.19985986e-01 -9.94777605e-02 -5.68715036e-01 -8.16491961e-01 -9.94724259e-02 -5.73720574e-01 -8.12974930e-01 -9.94565934e-02 -5.78699470e-01 -8.09448957e-01 -9.94569063e-02 -5.83651602e-01 -8.05896938e-01 -9.94303077e-02 -5.88630795e-01 -8.02327931e-01 -9.88818631e-02 -5.93522727e-01 -7.98693120e-01 -9.89018008e-02 -5.98394513e-01 -7.95015872e-01 -9.92546082e-02 -6.03269696e-01 -7.91342914e-01 -9.94255319e-02 -6.08098269e-01 -7.87593067e-01 -9.94363129e-02 -6.12920225e-01 -7.83846617e-01 -9.94356722e-02 -6.17737472e-01 -7.80079901e-01 -9.94397923e-02 -6.22509480e-01 -7.76289642e-01 -9.94360819e-02 -6.27251625e-01 -7.72434115e-01 -9.93983969e-02 -6.31985128e-01 -7.68607497e-01 -9.93793681e-02 -6.36694670e-01 -7.64718354e-01 -9.93677899e-02 -6.41352296e-01 -7.60755777e-01 -9.93587151e-02 -6.46038353e-01 -7.56832778e-01 -9.93456468e-02 -6.50664210e-01 -7.52849281e-01 -9.93443504e-02 -6.55272722e-01 -7.48841047e-01 -9.93378460e-02 -6.59837425e-01 -7.44824588e-01 -9.93177071e-02 -6.64412200e-01 -7.40734100e-01 -9.93038192e-02 -6.68925583e-01 -7.36665666e-01 -9.92883146e-02 -6.73440337e-01 -7.32547104e-01 -9.92771760e-02 -6.77913427e-01 -7.28403807e-01 -9.92934406e-02 -6.82392240e-01 -7.24211633e-01 -9.92889553e-02 -6.86803341e-01 -7.20026612e-01 -9.92696434e-02 -6.91230714e-01 -7.15799153e-01 -9.92796794e-02 -6.95607901e-01 -7.11543322e-01 -9.92853791e-02 -6.99930131e-01 -7.07266688e-01 -9.92897302e-02 -7.04266250e-01 -7.02934265e-01 -9.92795900e-02 -7.08569944e-01 -6.98592782e-01 -9.92620289e-02 -7.12863266e-01 -6.94273353e-01 -9.92512107e-02 -7.17114925e-01 -6.89853370e-01 -9.92333516e-02 -7.21306562e-01 -6.85446680e-01 -9.92181152e-02 -7.25520968e-01 -6.81033850e-01 -9.92244482e-02 -7.29666173e-01 -6.76568866e-01 -9.92235392e-02 -7.33800769e-01 -6.72074676e-01 -9.92098078e-02 -7.37918913e-01 -6.67557716e-01 -9.92109925e-02 -7.42019296e-01 -6.63001835e-01 -9.91883874e-02 -7.46056974e-01 -6.58448100e-01 -9.91846099e-02 -7.50071764e-01 -6.53859019e-01 -9.91909504e-02 -7.54075229e-01 -6.49244368e-01 -9.91879478e-02 -7.58073926e-01 -6.44603968e-01 -9.91715938e-02 -7.61980057e-01 -6.39927745e-01 -9.91641060e-02 -7.65894294e-01 -6.35244548e-01 -9.92355570e-02 -7.69780517e-01 -6.30541623e-01 -9.91735011e-02 -7.73637474e-01 -6.25804007e-01 -9.91773754e-02 -7.77488053e-01 -6.21058285e-01 -9.91478041e-02 -7.81284153e-01 -6.16258919e-01 -9.91233438e-02 -7.85051703e-01 -6.11467540e-01 -9.91022289e-02 -7.88789153e-01 -6.06625259e-01 -9.91253480e-02 -7.92468011e-01 -6.01767838e-01 -9.91066545e-02 -7.96138287e-01 -5.96901119e-01 -9.90946516e-02 -7.99792945e-01 -5.92008352e-01 -9.90999639e-02 -8.03418040e-01 -5.87077081e-01 -9.90980640e-02 -8.07028234e-01 -5.82155526e-01 -9.91875306e-02 -8.10561895e-01 -5.77186108e-01 -9.91601199e-02 -8.14087749e-01 -5.72204947e-01 -9.91813168e-02 -8.17593753e-01 -5.67187130e-01 -9.92381796e-02 -8.21035028e-01 -5.62155008e-01 -9.92501825e-02 -8.24479640e-01 -5.57113349e-01 -9.92016345e-02 -8.27879190e-01 -5.52052021e-01 -9.91484001e-02 -8.31278265e-01 -5.46966851e-01 -9.90934521e-02 -8.34640265e-01 -5.41871190e-01 -9.87692103e-02 -8.37993920e-01 -5.36774874e-01 -9.81739089e-02 -8.41854095e-01 -5.32042146e-01 -9.06246156e-02 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. 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. 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. -9.19770300e-01 -3.79969299e-01 -9.82137173e-02 -9.22113776e-01 -3.74332577e-01 -9.78690758e-02 -9.24337387e-01 -3.68641406e-01 -9.85069349e-02 -9.26554859e-01 -3.62949878e-01 -9.88008529e-02 -9.28758621e-01 -3.57255340e-01 -9.88796279e-02 -9.30930555e-01 -3.51549000e-01 -9.88963991e-02 -9.33118165e-01 -3.45851392e-01 -9.83716249e-02 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. 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. -9.66820896e-01 -2.34906197e-01 -1.00381859e-01 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. 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. 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. 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. 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. 0. 0. 0. 0. -9.88746762e-01 6.18961081e-02 -1.36193410e-01 -9.88348007e-01 6.79617748e-02 -1.36196211e-01 -9.87912774e-01 7.40249231e-02 -1.36193618e-01 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. 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. 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. 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. -9.44022179e-01 3.00272465e-01 -1.36596143e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.34826672e-01 3.29229474e-01 -1.33067369e-01 -9.32342649e-01 3.34819615e-01 -1.36503324e-01 0. 0. 0. -9.28764164e-01 3.46431583e-01 -1.31842017e-01 -9.26425636e-01 3.52058798e-01 -1.33378327e-01 -9.24189210e-01 3.57717186e-01 -1.33835137e-01 -9.21999216e-01 3.63388360e-01 -1.33664653e-01 -9.19752955e-01 3.69039059e-01 -1.33661002e-01 -9.17414784e-01 3.74655306e-01 -1.34102002e-01 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -8.46252263e-01 5.15639067e-01 -1.34064719e-01 -8.43097806e-01 5.20835698e-01 -1.33857951e-01 -8.39858651e-01 5.25978625e-01 -1.34163156e-01 -8.36547732e-01 5.31082690e-01 -1.34690896e-01 -8.33242595e-01 5.36183953e-01 -1.34982318e-01 -8.29938114e-01 5.41278958e-01 -1.35044456e-01 -8.26580644e-01 5.46366811e-01 -1.35064080e-01 -8.23199093e-01 5.51417768e-01 -1.35061577e-01 -8.19780409e-01 5.56459069e-01 -1.35279149e-01 -8.16359043e-01 5.61466396e-01 -1.35316864e-01 -8.12886477e-01 5.66464782e-01 -1.35302663e-01 -8.09385836e-01 5.71447670e-01 -1.35311171e-01 -8.05868626e-01 5.76393008e-01 -1.35340229e-01 -8.02330017e-01 5.81322968e-01 -1.35373622e-01 -7.98733592e-01 5.86240172e-01 -1.35336593e-01 -7.95113444e-01 5.91137111e-01 -1.35345474e-01 -7.91477919e-01 5.96011102e-01 -1.35352790e-01 -7.87825167e-01 6.00857377e-01 -1.35320142e-01 -7.84103930e-01 6.05679929e-01 -1.35335028e-01 -7.80361414e-01 6.10452175e-01 -1.35517448e-01 -7.76611030e-01 6.15254104e-01 -1.35310218e-01 -7.72863090e-01 6.20009899e-01 -1.35179237e-01 -7.69008040e-01 6.24721706e-01 -1.35324672e-01 -7.65164852e-01 6.29441798e-01 -1.35266691e-01 -7.61288464e-01 6.34133875e-01 -1.35228306e-01 -7.57377207e-01 6.38791382e-01 -1.35323927e-01 -7.53486216e-01 6.43439412e-01 -1.35189474e-01 -7.49517918e-01 6.48041487e-01 -1.35215312e-01 -7.45528758e-01 6.52634263e-01 -1.35204375e-01 -7.41513193e-01 6.57200515e-01 -1.35214359e-01 -7.37429559e-01 6.61711335e-01 -1.35305002e-01 -7.33372271e-01 6.66218221e-01 -1.35372221e-01 -7.29271829e-01 6.70710087e-01 -1.35359049e-01 -7.25108802e-01 6.75156593e-01 -1.35488912e-01 -7.20973253e-01 6.79609060e-01 -1.35323539e-01 -7.16783524e-01 6.84020638e-01 -1.35416582e-01 -7.12576210e-01 6.88411236e-01 -1.35420129e-01 -7.08344400e-01 6.92777276e-01 -1.35380909e-01 -7.04083502e-01 6.97114766e-01 -1.35225922e-01 -6.99794471e-01 7.01405764e-01 -1.35383740e-01 -6.95462465e-01 7.05680192e-01 -1.35393202e-01 -6.91137373e-01 7.09958196e-01 -1.35277510e-01 -6.86755300e-01 7.14180768e-01 -1.35294095e-01 -6.82370126e-01 7.18376577e-01 -1.35329843e-01 -6.77930295e-01 7.22523034e-01 -1.35486484e-01 -6.73499107e-01 7.26672769e-01 -1.35400265e-01 -6.69019341e-01 7.30790138e-01 -1.35459051e-01 -6.64512098e-01 7.34873295e-01 -1.35415003e-01 -6.59997642e-01 7.38964081e-01 -1.35441929e-01 -6.55443549e-01 7.42972910e-01 -1.35433361e-01 -6.50885224e-01 7.46988952e-01 -1.35426745e-01 -6.46287858e-01 7.50965118e-01 -1.35442555e-01 -6.41659319e-01 7.54940093e-01 -1.35421976e-01 -6.37026012e-01 7.58849382e-01 -1.35390714e-01 -6.32349730e-01 7.62764335e-01 -1.35398448e-01 -6.27670646e-01 7.66615450e-01 -1.35392681e-01 -6.22955382e-01 7.70436525e-01 -1.35396942e-01 -6.18195057e-01 7.74256527e-01 -1.35477602e-01 -6.13439679e-01 7.78042257e-01 -1.35412872e-01 -6.08672976e-01 7.81796157e-01 -1.35389894e-01 -6.03859723e-01 7.85517573e-01 -1.35384738e-01 -5.99035084e-01 7.89183617e-01 -1.35391265e-01 -5.94185650e-01 7.92861402e-01 -1.35333642e-01 -5.89286983e-01 7.96493411e-01 -1.35403380e-01 -5.84398031e-01 8.00081611e-01 -1.35407850e-01 -5.79462528e-01 8.03670824e-01 -1.35412991e-01 -5.74524760e-01 8.07182789e-01 -1.35442168e-01 -5.69573462e-01 8.10703993e-01 -1.35406390e-01 -5.64580560e-01 8.14205110e-01 -1.35354996e-01 -5.59575140e-01 8.17632675e-01 -1.35349438e-01 -5.54542005e-01 8.21067691e-01 -1.35385871e-01 -5.49498796e-01 8.24453712e-01 -1.35396302e-01 -5.44425488e-01 8.27781975e-01 -1.35420918e-01 -5.39336443e-01 8.31132829e-01 -1.35437727e-01 -5.34223676e-01 8.34409297e-01 -1.35465801e-01 -5.29103100e-01 8.37671459e-01 -1.35474071e-01 -5.23945630e-01 8.40930283e-01 -1.35470182e-01 -5.18779278e-01 8.44107747e-01 -1.35465845e-01 -5.13587892e-01 8.47258031e-01 -1.35480657e-01 -5.08380175e-01 8.50398600e-01 -1.35479555e-01 -5.03151715e-01 8.53514731e-01 -1.35474473e-01 -4.97922897e-01 8.56571853e-01 -1.35429114e-01 -4.92637843e-01 8.59659016e-01 -1.35451421e-01 -4.87369597e-01 8.62615764e-01 -1.35455176e-01 -4.82060850e-01 8.65607858e-01 -1.35449335e-01 -4.76743251e-01 8.68553162e-01 -1.35458469e-01 -4.71405417e-01 8.71457756e-01 -1.35449782e-01 -4.66038793e-01 8.74330461e-01 -1.35486007e-01 -4.60683018e-01 8.77188444e-01 -1.35458320e-01 -4.55283165e-01 8.80006373e-01 -1.35456473e-01 -4.49867368e-01 8.82755399e-01 -1.35496169e-01 -4.44445044e-01 8.85526836e-01 -1.35499194e-01 -4.39003766e-01 8.88216734e-01 -1.35492995e-01 -4.33540940e-01 8.90878320e-01 -1.35469690e-01 -4.28068399e-01 8.93538296e-01 -1.35508820e-01 -4.22580779e-01 8.96168292e-01 -1.35543004e-01 -4.17074114e-01 8.98721159e-01 -1.35548025e-01 -4.11554903e-01 9.01274562e-01 -1.35552600e-01 -4.06011522e-01 9.03780639e-01 -1.35549620e-01 -4.00451750e-01 9.06252205e-01 -1.35546908e-01 -3.94887388e-01 9.08676267e-01 -1.35525033e-01 -3.89311910e-01 9.11090076e-01 -1.35507420e-01 -3.83704692e-01 9.13470268e-01 -1.35520071e-01 -3.78083706e-01 9.15779591e-01 -1.35664433e-01 -3.72457504e-01 9.18080509e-01 -1.35689095e-01 -3.66818696e-01 9.20365870e-01 -1.35679901e-01 -3.61201942e-01 9.22625661e-01 -1.35241315e-01 -3.55530143e-01 9.24809217e-01 -1.35234445e-01 -3.49847019e-01 9.26981390e-01 -1.35239184e-01 -3.44128758e-01 9.29081619e-01 -1.35666966e-01 -3.38414460e-01 9.31170225e-01 -1.35674030e-01 -3.32701862e-01 9.33217466e-01 -1.35649949e-01 -3.26968223e-01 9.35256422e-01 -1.35624304e-01 -3.21222842e-01 9.37236428e-01 -1.35619268e-01 -3.15468609e-01 9.39218938e-01 -1.35638416e-01 -3.09693575e-01 9.41124380e-01 -1.35664582e-01 -3.03919405e-01 9.43003356e-01 -1.35664254e-01 -2.98123181e-01 9.44826245e-01 -1.35652632e-01 -2.92319030e-01 9.46654439e-01 -1.35656744e-01 -2.86509484e-01 9.48432744e-01 -1.35658100e-01 -2.80685306e-01 9.50155556e-01 -1.35616645e-01 -2.74844140e-01 9.51847374e-01 -1.35663792e-01 -2.68997520e-01 9.53533888e-01 -1.35668308e-01 -2.63141870e-01 9.55200851e-01 -1.35659829e-01 -2.57276088e-01 9.56764996e-01 -1.35659978e-01 -2.51402020e-01 9.58351791e-01 -1.35644719e-01 -2.45516911e-01 9.59833086e-01 -1.35637432e-01 -2.39625692e-01 9.61356759e-01 -1.35647446e-01 -2.33723402e-01 9.62811112e-01 -1.35644555e-01 -2.27805391e-01 9.64233398e-01 -1.35639504e-01 -2.21889257e-01 9.65611041e-01 -1.35616064e-01 -2.15961486e-01 9.66949701e-01 -1.35610968e-01 -2.10022300e-01 9.68271613e-01 -1.35586828e-01 -2.04080582e-01 9.69512284e-01 -1.35579228e-01 -1.98129490e-01 9.70788360e-01 -1.35561690e-01 -1.92167431e-01 9.71936047e-01 -1.35580719e-01 -1.86195940e-01 9.73112226e-01 -1.35611966e-01 -1.80223733e-01 9.74228978e-01 -1.35632053e-01 -1.74242422e-01 9.75303888e-01 -1.35656819e-01 -1.68254524e-01 9.76383090e-01 -1.35665029e-01 -1.62265182e-01 9.77406085e-01 -1.35466218e-01 -1.56259447e-01 9.78351295e-01 -1.35646820e-01 -1.50251836e-01 9.79306400e-01 -1.35642633e-01 -1.44241393e-01 9.80204940e-01 -1.35637596e-01 -1.38224363e-01 9.81090069e-01 -1.35625347e-01 -1.32201359e-01 9.81903613e-01 -1.35628074e-01 -1.26176149e-01 9.82697487e-01 -1.35588273e-01 -1.20144054e-01 9.83488381e-01 -1.35562018e-01 -1.14109524e-01 9.84154999e-01 -1.35548830e-01 -1.08066626e-01 9.84857678e-01 -1.35544643e-01 -1.02020696e-01 9.85482752e-01 -1.35547295e-01 -9.59720910e-02 9.86096084e-01 -1.35564491e-01 -8.99208412e-02 9.86665487e-01 -1.35596693e-01 -8.38627815e-02 9.87222373e-01 -1.35602191e-01 -7.78051242e-02 9.87708628e-01 -1.35600656e-01 -7.17426166e-02 9.88129854e-01 -1.35624424e-01 -6.56772405e-02 9.88588870e-01 -1.35614201e-01 -5.96112385e-02 9.88974869e-01 -1.35628104e-01 -5.35416491e-02 9.89314437e-01 -1.35622144e-01 -4.74695489e-02 9.89636064e-01 -1.35617763e-01 -4.13974151e-02 9.89896238e-01 -1.35621533e-01 -3.53217646e-02 9.90134120e-01 -1.35642052e-01 -2.92461216e-02 9.90303934e-01 -1.35638192e-01 -2.31684521e-02 9.90510583e-01 -1.35668278e-01 -1.70904417e-02 9.90608633e-01 -1.35699943e-01 -1.10118017e-02 9.90675509e-01 -1.35707527e-01 -4.93298611e-03 9.90754306e-01 -1.35689273e-01 1.14619581e-03 9.90755498e-01 -1.35694072e-01 7.22528109e-03 9.90749836e-01 -1.35689124e-01 1.33041814e-02 9.90670562e-01 -1.35699391e-01 1.93823464e-02 9.90538418e-01 -1.35694608e-01 2.54597384e-02 9.90432322e-01 -1.35673985e-01 3.15370373e-02 9.90274012e-01 -1.35641038e-01 3.76121178e-02 9.90039408e-01 -1.35639191e-01 4.36861180e-02 9.89796996e-01 -1.35632932e-01 4.97586392e-02 9.89527643e-01 -1.35667548e-01 5.58287315e-02 9.89167690e-01 -1.35703087e-01 6.18984289e-02 9.88815427e-01 -1.35715514e-01 6.79643750e-02 9.88418519e-01 -1.35723382e-01 7.40274712e-02 9.87983823e-01 -1.35732025e-01 8.00890103e-02 9.87502992e-01 -1.35731265e-01 8.61456692e-02 9.86985981e-01 -1.35740221e-01 9.22006592e-02 9.86420274e-01 -1.35739446e-01 9.82496366e-02 9.85881388e-01 -1.35754555e-01 1.04297079e-01 9.85215783e-01 -1.35730356e-01 1.10341907e-01 9.84588861e-01 -1.35735378e-01 1.16381988e-01 9.83884096e-01 -1.35717109e-01 1.22417003e-01 9.83136773e-01 -1.35734916e-01 1.28447205e-01 9.82405365e-01 -1.35658070e-01 1.34472072e-01 9.81585801e-01 -1.35571823e-01 1.40494615e-01 9.80767369e-01 -1.35425583e-01 1.46513134e-01 9.79928017e-01 -1.35237128e-01 1.52526408e-01 9.79031920e-01 -1.35034546e-01 1.58543020e-01 9.78176892e-01 -1.34282455e-01 1.64573118e-01 9.77432847e-01 -1.32432252e-01 1.70573935e-01 9.76454496e-01 -1.32048965e-01 1.76497862e-01 9.74924147e-01 -1.35541275e-01 1.82473287e-01 9.73799825e-01 -1.35710269e-01 1.88448802e-01 9.72686946e-01 -1.35522783e-01 1.94410622e-01 9.71491039e-01 -1.35682315e-01 2.00368211e-01 9.70275342e-01 -1.35691628e-01 2.06315294e-01 9.69036222e-01 -1.35735184e-01 2.12256953e-01 9.67738867e-01 -1.35759383e-01 2.18190879e-01 9.66408968e-01 -1.35774329e-01 2.24115178e-01 9.65052664e-01 -1.35825694e-01 2.30032384e-01 9.63657022e-01 -1.35831103e-01 2.35949472e-01 9.62269664e-01 -1.35512799e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.65419185e-01 9.54850376e-01 -1.33454725e-01 2.71313518e-01 9.53372359e-01 -1.32161155e-01 2.77104229e-01 9.51470912e-01 -1.33839250e-01 2.82906890e-01 9.49633837e-01 -1.34730384e-01 2.88714051e-01 9.47819173e-01 -1.35219499e-01 2.94514924e-01 9.45993543e-01 -1.35486305e-01 3.00309986e-01 9.44153726e-01 -1.35565400e-01 3.06098849e-01 9.42287266e-01 -1.35595247e-01 3.11871529e-01 9.40399647e-01 -1.35680661e-01 3.17629009e-01 9.38462675e-01 -1.35714427e-01 3.23387831e-01 9.36475158e-01 -1.35726035e-01 3.29126328e-01 9.34505463e-01 -1.35687992e-01 3.34843963e-01 9.32443261e-01 -1.35791510e-01 3.40565979e-01 9.30380762e-01 -1.35800406e-01 3.46263200e-01 9.28243577e-01 -1.35800242e-01 3.51950169e-01 9.26135302e-01 -1.35807842e-01 3.57624561e-01 9.23957169e-01 -1.35810748e-01 3.63298833e-01 9.21716809e-01 -1.35816753e-01 3.68945092e-01 9.19508338e-01 -1.35720089e-01 3.74574035e-01 9.17216241e-01 -1.35719255e-01 3.80191952e-01 9.14899051e-01 -1.35768488e-01 3.85805577e-01 9.12526846e-01 -1.35712385e-01 3.91407192e-01 9.10180449e-01 -1.35694280e-01 3.96986842e-01 9.07764494e-01 -1.35665298e-01 4.02549595e-01 9.05277550e-01 -1.35670453e-01 4.08093601e-01 9.02800620e-01 -1.35772035e-01 4.13616329e-01 9.00278270e-01 -1.35775104e-01 4.19127882e-01 8.97721231e-01 -1.35776728e-01 4.24624860e-01 8.95118296e-01 -1.35771334e-01 4.30120945e-01 8.92519295e-01 -1.35761395e-01 4.35582310e-01 8.89878929e-01 -1.35685965e-01 4.41037178e-01 8.87196302e-01 -1.35704905e-01 4.46472675e-01 8.84455740e-01 -1.35668129e-01 4.51894552e-01 8.81672859e-01 -1.35664254e-01 4.57290530e-01 8.78900826e-01 -1.35672316e-01 4.62680846e-01 8.76094043e-01 -1.35706738e-01 4.68042254e-01 8.73200715e-01 -1.35719046e-01 4.73400503e-01 8.70312393e-01 -1.35747761e-01 4.78726149e-01 8.67397249e-01 -1.35716125e-01 4.84046012e-01 8.64481449e-01 -1.35689244e-01 4.89329100e-01 8.61480534e-01 -1.35734841e-01 4.94611830e-01 8.58437359e-01 -1.35749891e-01 4.99860913e-01 8.55403841e-01 -1.35736540e-01 5.05107760e-01 8.52306306e-01 -1.35744929e-01 5.10330081e-01 8.49224210e-01 -1.35759979e-01 5.15539408e-01 8.46077979e-01 -1.35761902e-01 5.20722091e-01 8.42872679e-01 -1.35764867e-01 5.25866330e-01 8.39668214e-01 -1.35745108e-01 5.31023443e-01 8.36426616e-01 -1.35752290e-01 5.36135733e-01 8.33143592e-01 -1.35747313e-01 5.41232169e-01 8.29869568e-01 -1.35690972e-01 5.46318531e-01 8.26510310e-01 -1.35681838e-01 5.51376700e-01 8.23126793e-01 -1.35710716e-01 5.56433618e-01 8.19737732e-01 -1.35707915e-01 5.61432779e-01 8.16331267e-01 -1.35674655e-01 5.66448331e-01 8.12856019e-01 -1.35693669e-01 5.71429670e-01 8.09341669e-01 -1.35762006e-01 5.76382816e-01 8.05846155e-01 -1.35757357e-01 5.81322193e-01 8.02302301e-01 -1.35756180e-01 5.86211264e-01 7.98696518e-01 -1.35749534e-01 5.91123581e-01 7.95074582e-01 -1.35744452e-01 5.95988274e-01 7.91441679e-01 -1.35742486e-01 6.00831389e-01 7.87794769e-01 -1.35754883e-01 6.05659544e-01 7.84080505e-01 -1.35738954e-01 6.10429049e-01 7.80334890e-01 -1.35739878e-01 6.15228713e-01 7.76576221e-01 -1.35722294e-01 6.19969964e-01 7.72813916e-01 -1.35698289e-01 6.24688804e-01 7.68964231e-01 -1.35762796e-01 6.29401267e-01 7.65110552e-01 -1.35773048e-01 6.34097278e-01 7.61241615e-01 -1.35733485e-01 6.38767481e-01 7.57342875e-01 -1.35740444e-01 6.43397808e-01 7.53434122e-01 -1.35750934e-01 6.47999167e-01 7.49461472e-01 -1.35801226e-01 6.52595103e-01 7.45476127e-01 -1.35747820e-01 6.57156169e-01 7.41462111e-01 -1.35703638e-01 6.61678076e-01 7.37389266e-01 -1.35729432e-01 6.66184604e-01 7.33313203e-01 -1.35740921e-01 6.70698762e-01 7.29241610e-01 -1.35750368e-01 6.75131321e-01 7.25080550e-01 -1.35747701e-01 6.79565489e-01 7.20925987e-01 -1.35767683e-01 6.84004426e-01 7.16742039e-01 -1.35795861e-01 6.88388824e-01 7.12555587e-01 -1.35697201e-01 6.92746401e-01 7.08324075e-01 -1.35681078e-01 6.97077692e-01 7.04036295e-01 -1.35687277e-01 7.01357603e-01 6.99752986e-01 -1.35792971e-01 7.05664933e-01 6.95426583e-01 -1.35699809e-01 7.09922969e-01 6.91093683e-01 -1.35693938e-01 7.14157224e-01 6.86722457e-01 -1.35681719e-01 7.18359709e-01 6.82348430e-01 -1.35679245e-01 7.22514868e-01 6.77916706e-01 -1.35663956e-01 7.26654172e-01 6.73485994e-01 -1.35675475e-01 7.30771542e-01 6.69012010e-01 -1.35671020e-01 7.34859705e-01 6.64497435e-01 -1.35671303e-01 7.38953352e-01 6.59985781e-01 -1.35652974e-01 7.42963910e-01 6.55434430e-01 -1.35635763e-01 7.46977150e-01 6.50878131e-01 -1.35633305e-01 7.50964224e-01 6.46289587e-01 -1.35535598e-01 7.54925847e-01 6.41647875e-01 -1.35622099e-01 7.58829772e-01 6.37008369e-01 -1.35631680e-01 7.62749612e-01 6.32335305e-01 -1.35628283e-01 7.66603112e-01 6.27654791e-01 -1.35636255e-01 7.70419896e-01 6.22937799e-01 -1.35631099e-01 7.74247289e-01 6.18185282e-01 -1.35639727e-01 7.78024673e-01 6.13425493e-01 -1.35636628e-01 7.81773210e-01 6.08648896e-01 -1.35632783e-01 7.85494685e-01 6.03841007e-01 -1.35623142e-01 7.89145648e-01 5.99006712e-01 -1.35710284e-01 7.92826056e-01 5.94150603e-01 -1.35707051e-01 7.96482027e-01 5.89253545e-01 -1.35707572e-01 8.00046146e-01 5.84375262e-01 -1.35697350e-01 8.03641915e-01 5.79437673e-01 -1.35695189e-01 8.07162106e-01 5.74499428e-01 -1.35674790e-01 8.10670257e-01 5.69536030e-01 -1.35668859e-01 8.14171612e-01 5.64554274e-01 -1.35664210e-01 8.17590237e-01 5.59561670e-01 -1.35657877e-01 8.21046948e-01 5.54520249e-01 -1.35642514e-01 8.24433565e-01 5.49471378e-01 -1.35630116e-01 8.27754617e-01 5.44400454e-01 -1.35598853e-01 8.31134379e-01 5.39330661e-01 -1.35388479e-01 8.34384501e-01 5.34205198e-01 -1.35611251e-01 8.37656438e-01 5.29097378e-01 -1.35525167e-01 8.40907156e-01 5.23935139e-01 -1.35514140e-01 8.44107449e-01 5.18774807e-01 -1.35420486e-01 8.47262621e-01 5.13594329e-01 -1.35406405e-01 8.50406945e-01 5.08379519e-01 -1.35402963e-01 8.53527009e-01 5.03149867e-01 -1.35478646e-01 8.56570959e-01 4.97921526e-01 -1.35472298e-01 8.59659553e-01 4.92644995e-01 -1.35471314e-01 8.62618804e-01 4.87367660e-01 -1.35461181e-01 8.65609169e-01 4.82069224e-01 -1.35453150e-01 8.68550479e-01 4.76748616e-01 -1.35436222e-01 8.71458232e-01 4.71403629e-01 -1.35407224e-01 8.74340892e-01 4.66053486e-01 -1.35401249e-01 8.77202272e-01 4.60684985e-01 -1.35399729e-01 8.80011082e-01 4.55289781e-01 -1.35403275e-01 8.82782161e-01 4.49872583e-01 -1.35398209e-01 8.85548353e-01 4.44458008e-01 -1.35383159e-01 8.88238132e-01 4.39016193e-01 -1.35371476e-01 8.90902638e-01 4.33546156e-01 -1.35361493e-01 8.93561721e-01 4.28085566e-01 -1.35354817e-01 8.96192431e-01 4.22590435e-01 -1.35356084e-01 8.98749590e-01 4.17085290e-01 -1.35359898e-01 9.01297092e-01 4.11567211e-01 -1.35354623e-01 9.03809607e-01 4.06021982e-01 -1.35348350e-01 9.06270742e-01 4.00462508e-01 -1.35333627e-01 9.08695459e-01 3.94896775e-01 -1.35338604e-01 9.11109865e-01 3.89324456e-01 -1.35340109e-01 9.13494766e-01 3.83714676e-01 -1.35321483e-01 9.15821493e-01 3.78100574e-01 -1.35314152e-01 9.18132544e-01 3.72475624e-01 -1.35315418e-01 9.20414507e-01 3.66839319e-01 -1.35304242e-01 9.22620058e-01 3.61197799e-01 -1.35289729e-01 9.24805403e-01 3.55526775e-01 -1.35279715e-01 9.26979125e-01 3.49844724e-01 -1.35268196e-01 9.29133713e-01 3.44152689e-01 -1.35270134e-01 9.31239843e-01 3.38439673e-01 -1.35130614e-01 9.33286309e-01 3.32733870e-01 -1.35125175e-01 9.35319066e-01 3.26987654e-01 -1.35248885e-01 9.37309384e-01 3.21249127e-01 -1.35124147e-01 9.39291954e-01 3.15498322e-01 -1.35131642e-01 9.41168725e-01 3.09708357e-01 -1.35263160e-01 9.43063676e-01 3.03939760e-01 -1.35291293e-01 9.44877863e-01 2.98140764e-01 -1.35283083e-01 9.46712613e-01 2.92336494e-01 -1.35286838e-01 9.48485911e-01 2.86526978e-01 -1.35283962e-01 9.50203300e-01 2.80703992e-01 -1.35278568e-01 9.51898336e-01 2.74861485e-01 -1.35275677e-01 9.53586578e-01 2.69012421e-01 -1.35268584e-01 9.55255449e-01 2.63163507e-01 -1.35266215e-01 9.56838191e-01 2.57305950e-01 -1.35063723e-01 9.58430111e-01 2.51424104e-01 -1.35056689e-01 9.59911227e-01 2.45538205e-01 -1.35048792e-01 9.61431086e-01 2.39648893e-01 -1.35043234e-01 9.62855279e-01 2.33736321e-01 -1.35246485e-01 9.64259326e-01 2.27825075e-01 -1.35244742e-01 9.65694547e-01 2.21910313e-01 -1.35012716e-01 9.67054009e-01 2.15981439e-01 -1.35006696e-01 9.68354821e-01 2.10040629e-01 -1.35010064e-01 9.69590187e-01 2.04101384e-01 -1.35011524e-01 9.70825911e-01 1.98142231e-01 -1.35207132e-01 9.72014368e-01 1.92187309e-01 -1.35001123e-01 9.73196566e-01 1.86213210e-01 -1.35033652e-01 9.74329650e-01 1.80243790e-01 -1.35061741e-01 9.75364149e-01 1.74257427e-01 -1.35259941e-01 9.76478100e-01 1.68272793e-01 -1.35115653e-01 9.77457881e-01 1.62274420e-01 -1.35229617e-01 9.78426039e-01 1.56270906e-01 -1.35231927e-01 9.79400218e-01 1.50271714e-01 -1.35064125e-01 9.80284989e-01 1.44258425e-01 -1.35057271e-01 9.81178105e-01 1.38240978e-01 -1.35059446e-01 9.81976807e-01 1.32217601e-01 -1.35072291e-01 9.82775092e-01 1.26185089e-01 -1.35248676e-01 9.83549714e-01 1.20151155e-01 -1.35253072e-01 9.84230399e-01 1.14115946e-01 -1.35245472e-01 9.84957755e-01 1.08077176e-01 -1.35071144e-01 9.85529661e-01 1.02029562e-01 -1.35234818e-01 9.86168325e-01 9.59804878e-02 -1.35227457e-01 9.86745358e-01 8.99306610e-02 -1.35060459e-01 9.87294555e-01 8.38753954e-02 -1.35052994e-01 9.87785935e-01 7.78152198e-02 -1.35020316e-01 9.88213956e-01 7.17517510e-02 -1.35074452e-01 9.88682985e-01 6.56886846e-02 -1.35018215e-01 9.89077330e-01 5.96194044e-02 -1.35035411e-01 9.89398003e-01 5.35493009e-02 -1.35079861e-01 9.89715874e-01 4.74782288e-02 -1.35020316e-01 9.89981234e-01 4.14040126e-02 -1.34984165e-01 9.90233123e-01 3.53301503e-02 -1.34928212e-01 9.90392208e-01 2.92523503e-02 -1.35066330e-01 9.90607083e-01 2.31743585e-02 -1.35054752e-01 9.90700543e-01 1.70960538e-02 -1.35018840e-01 9.90787685e-01 1.10167088e-02 -1.35048345e-01 9.90851760e-01 4.93703317e-03 -1.35056630e-01 9.90851879e-01 -1.14269310e-03 -1.35054350e-01 9.90845501e-01 -7.22257234e-03 -1.35076642e-01 9.90759850e-01 -1.33025851e-02 -1.35209814e-01 9.90609348e-01 -1.93811879e-02 -1.35205746e-01 9.90518510e-01 -2.54595727e-02 -1.35203347e-01 9.90343750e-01 -3.15364301e-02 -1.35211498e-01 9.90107656e-01 -3.76120508e-02 -1.35206819e-01 9.89865184e-01 -4.36876044e-02 -1.35207817e-01 9.89604890e-01 -4.97596264e-02 -1.35211304e-01 9.89252627e-01 -5.58314174e-02 -1.35024399e-01 9.88925040e-01 -6.19010180e-02 -1.35002747e-01 9.88505125e-01 -6.79656863e-02 -1.35025695e-01 9.88111615e-01 -7.40298852e-02 -1.34986967e-01 9.87626016e-01 -8.00911114e-02 -1.35040149e-01 9.87073183e-01 -8.61523077e-02 -1.35016337e-01 9.86524105e-01 -9.22059640e-02 -1.35014549e-01 9.85971510e-01 -9.82555896e-02 -1.35214731e-01 9.85287130e-01 -1.04303718e-01 -1.35227606e-01 9.84694123e-01 -1.10348091e-01 -1.35223657e-01 9.84003425e-01 -1.16388522e-01 -1.35085762e-01 9.83267128e-01 -1.22426048e-01 -1.35085121e-01 9.82468724e-01 -1.28455102e-01 -1.35071680e-01 9.81664538e-01 -1.34480610e-01 -1.35055885e-01 9.80848730e-01 -1.40502155e-01 -1.35060996e-01 9.79968786e-01 -1.46517411e-01 -1.35034442e-01 9.79016900e-01 -1.52525842e-01 -1.35049000e-01 9.78050828e-01 -1.58534721e-01 -1.35077775e-01 9.77081001e-01 -1.64529771e-01 -1.35047331e-01 9.76092815e-01 -1.70522436e-01 -1.35032862e-01 9.74982619e-01 -1.76506564e-01 -1.35008514e-01 9.73918676e-01 -1.82488814e-01 -1.35024652e-01 9.72743332e-01 -1.88459054e-01 -1.34963930e-01 9.71583664e-01 -1.94431275e-01 -1.34974316e-01 9.70368147e-01 -2.00385392e-01 -1.35018915e-01 9.69106436e-01 -2.06338570e-01 -1.35013953e-01 9.67870355e-01 -2.12275192e-01 -1.35003805e-01 9.66506064e-01 -2.18207330e-01 -1.35060593e-01 9.65192556e-01 -2.24133611e-01 -1.35032922e-01 9.63763714e-01 -2.30054244e-01 -1.35034636e-01 9.62322891e-01 -2.35964343e-01 -1.35052249e-01 9.60855901e-01 -2.41862580e-01 -1.35073870e-01 9.59397912e-01 -2.47757524e-01 -1.35030583e-01 9.57855642e-01 -2.53636658e-01 -1.35077670e-01 9.56251979e-01 -2.59508938e-01 -1.35086015e-01 9.54628766e-01 -2.65369713e-01 -1.35096073e-01 9.53019381e-01 -2.71228284e-01 -1.35081083e-01 9.51331854e-01 -2.77061582e-01 -1.35069311e-01 9.49598730e-01 -2.82904625e-01 -1.35074630e-01 9.47843790e-01 -2.88716972e-01 -1.35104597e-01 9.46071863e-01 -2.94523716e-01 -1.35104328e-01 9.44217682e-01 -3.00326973e-01 -1.35133669e-01 9.42375541e-01 -3.06118637e-01 -1.35131553e-01 9.40498233e-01 -3.11884433e-01 -1.35144755e-01 9.38563943e-01 -3.17665279e-01 -1.35139346e-01 9.36579645e-01 -3.23413372e-01 -1.35146856e-01 9.34551358e-01 -3.29155415e-01 -1.35147467e-01 9.32535291e-01 -3.34869206e-01 -1.35144591e-01 9.30438101e-01 -3.40596825e-01 -1.35142416e-01 9.28357542e-01 -3.46290022e-01 -1.35142460e-01 9.26229239e-01 -3.51976871e-01 -1.35136515e-01 9.24055457e-01 -3.57657880e-01 -1.35113567e-01 9.21828747e-01 -3.63332570e-01 -1.35114431e-01 9.19559062e-01 -3.68962914e-01 -1.35218546e-01 9.17294025e-01 -3.74597192e-01 -1.35140151e-01 9.14961159e-01 -3.80230218e-01 -1.35119513e-01 9.12626326e-01 -3.85833681e-01 -1.35162905e-01 9.10263717e-01 -3.91432941e-01 -1.35129750e-01 9.07841682e-01 -3.97005379e-01 -1.35140970e-01 9.05375540e-01 -4.02570397e-01 -1.35114953e-01 9.02861238e-01 -4.08108950e-01 -1.35172978e-01 9.00359869e-01 -4.13652122e-01 -1.35162443e-01 8.97787809e-01 -4.19171423e-01 -1.35146707e-01 8.95211518e-01 -4.24661011e-01 -1.35154560e-01 8.92604411e-01 -4.30147350e-01 -1.35177031e-01 8.89944792e-01 -4.35612738e-01 -1.35241568e-01 8.87268484e-01 -4.41071928e-01 -1.35206491e-01 8.84546340e-01 -4.46515232e-01 -1.35153323e-01 8.81741226e-01 -4.51917529e-01 -1.35184139e-01 8.78983200e-01 -4.57321018e-01 -1.35192335e-01 8.76161933e-01 -4.62720662e-01 -1.35184079e-01 8.73274684e-01 -4.68079925e-01 -1.35164037e-01 8.70385528e-01 -4.73416269e-01 -1.35130718e-01 8.67468536e-01 -4.78757709e-01 -1.35138601e-01 8.64550889e-01 -4.84064966e-01 -1.35166064e-01 8.61559451e-01 -4.89366770e-01 -1.35179862e-01 8.58511150e-01 -4.94655222e-01 -1.35196388e-01 8.55455935e-01 -4.99902010e-01 -1.35173693e-01 8.52391303e-01 -5.05144775e-01 -1.35168150e-01 8.49298418e-01 -5.10376692e-01 -1.35166049e-01 8.46153200e-01 -5.15582800e-01 -1.35174692e-01 8.42952430e-01 -5.20751357e-01 -1.35181248e-01 8.39727342e-01 -5.25905669e-01 -1.35196418e-01 8.36492598e-01 -5.31062663e-01 -1.35206342e-01 8.33197236e-01 -5.36173224e-01 -1.35229573e-01 8.29939783e-01 -5.41269124e-01 -1.35212943e-01 8.26574147e-01 -5.46347916e-01 -1.35229036e-01 8.23191106e-01 -5.51416576e-01 -1.35226279e-01 8.19797873e-01 -5.56467712e-01 -1.35260671e-01 8.16390693e-01 -5.61469316e-01 -1.35266602e-01 8.12930286e-01 -5.66498101e-01 -1.35255396e-01 8.09401512e-01 -5.71464360e-01 -1.35265991e-01 8.05916309e-01 -5.76419353e-01 -1.35248035e-01 8.02364588e-01 -5.81359625e-01 -1.35242134e-01 7.98753858e-01 -5.86253226e-01 -1.35268122e-01 7.95133591e-01 -5.91166675e-01 -1.35267779e-01 7.91499197e-01 -5.96028447e-01 -1.35260522e-01 7.87850320e-01 -6.00871563e-01 -1.35277838e-01 7.84142911e-01 -6.05692625e-01 -1.35283262e-01 7.80384302e-01 -6.10462308e-01 -1.35284156e-01 7.76642144e-01 -6.15266263e-01 -1.35277256e-01 7.72864580e-01 -6.20006144e-01 -1.35264218e-01 7.69018114e-01 -6.24732792e-01 -1.35263175e-01 7.65176058e-01 -6.29438639e-01 -1.35297641e-01 7.61278868e-01 -6.34135723e-01 -1.35298178e-01 7.57391274e-01 -6.38792157e-01 -1.35271952e-01 7.53492951e-01 -6.43439353e-01 -1.35278225e-01 7.49501824e-01 -6.48043811e-01 -1.35278881e-01 7.45526314e-01 -6.52637780e-01 -1.35293067e-01 7.41502047e-01 -6.57206357e-01 -1.35320276e-01 7.37449169e-01 -6.61722183e-01 -1.35290682e-01 7.33396888e-01 -6.66219592e-01 -1.35292441e-01 7.29299605e-01 -6.70748591e-01 -1.35293230e-01 7.25127995e-01 -6.75168455e-01 -1.35306776e-01 7.20987260e-01 -6.79616451e-01 -1.35335788e-01 7.16809154e-01 -6.84054911e-01 -1.35354578e-01 7.12606966e-01 -6.88431501e-01 -1.35263786e-01 7.08366394e-01 -6.92789257e-01 -1.35318220e-01 7.04076648e-01 -6.97124362e-01 -1.35351241e-01 6.99806511e-01 -7.01408625e-01 -1.35354415e-01 6.95456386e-01 -7.05696702e-01 -1.35374114e-01 6.91115022e-01 -7.09950209e-01 -1.35366946e-01 6.86742067e-01 -7.14173198e-01 -1.35383263e-01 6.82366788e-01 -7.18387663e-01 -1.35431796e-01 6.77926600e-01 -7.22531617e-01 -1.35392487e-01 6.73516273e-01 -7.26664603e-01 -1.35390937e-01 6.69041276e-01 -7.30779469e-01 -1.35398313e-01 6.64500535e-01 -7.34870195e-01 -1.35401040e-01 6.59992576e-01 -7.38962412e-01 -1.35479972e-01 6.55436099e-01 -7.42985487e-01 -1.35364875e-01 6.50896609e-01 -7.46979713e-01 -1.35402158e-01 6.46300852e-01 -7.50973105e-01 -1.35392636e-01 6.41641855e-01 -7.54933894e-01 -1.35421664e-01 6.37015998e-01 -7.58828521e-01 -1.35420173e-01 6.32331133e-01 -7.62762368e-01 -1.35397106e-01 6.27673686e-01 -7.66599000e-01 -1.35397255e-01 6.22955680e-01 -7.70424843e-01 -1.35416299e-01 6.18186116e-01 -7.74269044e-01 -1.35411620e-01 6.13436282e-01 -7.78025389e-01 -1.35416865e-01 6.08673990e-01 -7.81787753e-01 -1.35419205e-01 6.03860974e-01 -7.85502672e-01 -1.35435820e-01 5.99026978e-01 -7.89183915e-01 -1.35430127e-01 5.94173610e-01 -7.92842567e-01 -1.35428429e-01 5.89272380e-01 -7.96500742e-01 -1.35405198e-01 5.84396005e-01 -8.00083399e-01 -1.35397583e-01 5.79460263e-01 -8.03660512e-01 -1.35395348e-01 5.74515581e-01 -8.07187319e-01 -1.35425448e-01 5.69557071e-01 -8.10707629e-01 -1.35424569e-01 5.64573050e-01 -8.14196527e-01 -1.35429218e-01 5.59581637e-01 -8.17613721e-01 -1.35438085e-01 5.54536581e-01 -8.21062624e-01 -1.35455087e-01 5.49482167e-01 -8.24447572e-01 -1.35450512e-01 5.44412792e-01 -8.27771485e-01 -1.35454074e-01 5.39323509e-01 -8.31130207e-01 -1.35443926e-01 5.34207702e-01 -8.34398150e-01 -1.35593221e-01 5.29091239e-01 -8.37647617e-01 -1.35606930e-01 5.23926854e-01 -8.40895116e-01 -1.35607779e-01 5.18755794e-01 -8.44081640e-01 -1.35617986e-01 5.13565600e-01 -8.47235858e-01 -1.35615513e-01 5.08358181e-01 -8.50376785e-01 -1.35634199e-01 5.03129065e-01 -8.53494406e-01 -1.35636970e-01 4.97900128e-01 -8.56534123e-01 -1.35638773e-01 4.92628068e-01 -8.59625518e-01 -1.35635465e-01 4.87345576e-01 -8.62582743e-01 -1.35632411e-01 4.82045978e-01 -8.65586877e-01 -1.35633454e-01 4.76730168e-01 -8.68509591e-01 -1.35591418e-01 4.71379340e-01 -8.71423721e-01 -1.35537788e-01 4.66037750e-01 -8.74300003e-01 -1.35566011e-01 4.60660875e-01 -8.77162695e-01 -1.35619938e-01 4.55267161e-01 -8.79969895e-01 -1.35636404e-01 4.49849129e-01 -8.82744133e-01 -1.35634333e-01 4.44436908e-01 -8.85503948e-01 -1.35634407e-01 4.38996106e-01 -8.88193488e-01 -1.35624200e-01 4.33522254e-01 -8.90854955e-01 -1.35632321e-01 4.28061217e-01 -8.93513083e-01 -1.35629460e-01 4.22568679e-01 -8.96146655e-01 -1.35618180e-01 4.17062372e-01 -8.98704112e-01 -1.35639235e-01 4.11547214e-01 -9.01250124e-01 -1.35660961e-01 4.06000137e-01 -9.03763115e-01 -1.35642290e-01 4.00446832e-01 -9.06240106e-01 -1.35580599e-01 3.94874007e-01 -9.08649027e-01 -1.35640934e-01 3.89301389e-01 -9.11064506e-01 -1.35648519e-01 3.83699149e-01 -9.13458824e-01 -1.35515198e-01 3.78086686e-01 -9.15783226e-01 -1.35505304e-01 3.72462898e-01 -9.18083251e-01 -1.35528788e-01 3.66823137e-01 -9.20374215e-01 -1.35509416e-01 3.61176133e-01 -9.22582924e-01 -1.35536939e-01 3.55509758e-01 -9.24773872e-01 -1.35497332e-01 3.49824578e-01 -9.26938295e-01 -1.35541111e-01 3.44132096e-01 -9.29086030e-01 -1.35534391e-01 3.38419408e-01 -9.31170225e-01 -1.35528460e-01 3.32705885e-01 -9.33225453e-01 -1.35547474e-01 3.26969713e-01 -9.35256243e-01 -1.35534778e-01 3.21226716e-01 -9.37241614e-01 -1.35493159e-01 3.15471649e-01 -9.39226806e-01 -1.35491937e-01 3.09705853e-01 -9.41140234e-01 -1.35454282e-01 3.03927004e-01 -9.43023086e-01 -1.35382175e-01 2.98135906e-01 -9.44880903e-01 -1.35358199e-01 2.92337269e-01 -9.46716070e-01 -1.35233641e-01 2.86524266e-01 -9.48482573e-01 -1.35256797e-01 2.80704677e-01 -9.50247586e-01 -1.35090739e-01 2.74880290e-01 -9.51982319e-01 -1.34824499e-01 2.69039214e-01 -9.53660667e-01 -1.34713292e-01 2.63186753e-01 -9.55308080e-01 -1.34598285e-01 2.57328331e-01 -9.56932545e-01 -1.34389535e-01 2.51474321e-01 -9.58566368e-01 -1.33816317e-01 2.45638385e-01 -9.60258663e-01 -1.32507294e-01 2.39661381e-01 -9.61475313e-01 -1.34638757e-01 2.33760342e-01 -9.62938130e-01 -1.34559289e-01 2.27846771e-01 -9.64351833e-01 -1.34578794e-01 2.21927568e-01 -9.65739787e-01 -1.34513840e-01 2.15995312e-01 -9.67073500e-01 -1.34580761e-01 2.10056856e-01 -9.68380272e-01 -1.34607986e-01 2.04110220e-01 -9.69647527e-01 -1.34629264e-01 1.98157176e-01 -9.70880270e-01 -1.34614214e-01 1.92196846e-01 -9.72081065e-01 -1.34590551e-01 1.86230034e-01 -9.73248303e-01 -1.34548590e-01 1.80306911e-01 -9.74601746e-01 -1.32789567e-01 1.74271494e-01 -9.75456536e-01 -1.34588063e-01 0. 0. 0. 1.62291735e-01 -9.77539182e-01 -1.34456158e-01 1.56296283e-01 -9.78544891e-01 -1.34240016e-01 1.50278643e-01 -9.79432762e-01 -1.34642571e-01 1.44259945e-01 -9.80304182e-01 -1.34858638e-01 1.38233691e-01 -9.81134415e-01 -1.35233045e-01 1.32205725e-01 -9.81925845e-01 -1.35443181e-01 1.26177445e-01 -9.82700527e-01 -1.35489315e-01 1.20143659e-01 -9.83487368e-01 -1.35517880e-01 1.14107974e-01 -9.84153390e-01 -1.35519311e-01 1.08065940e-01 -9.84851658e-01 -1.35537103e-01 1.02021910e-01 -9.85479772e-01 -1.35532916e-01 9.59717333e-02 -9.86090124e-01 -1.35547370e-01 8.99205133e-02 -9.86665845e-01 -1.35545149e-01 8.38636011e-02 -9.87229884e-01 -1.35558471e-01 7.78046176e-02 -9.87721980e-01 -1.35540977e-01 7.17424899e-02 -9.88140345e-01 -1.35552615e-01 6.56787083e-02 -9.88596499e-01 -1.35543093e-01 5.96122444e-02 -9.88972485e-01 -1.35514721e-01 5.35428636e-02 -9.89323854e-01 -1.35528237e-01 4.74704467e-02 -9.89637911e-01 -1.35583371e-01 4.13958095e-02 -9.89883721e-01 -1.35644168e-01 3.53221111e-02 -9.90132630e-01 -1.35645851e-01 2.92460937e-02 -9.90298808e-01 -1.35662854e-01 2.31688283e-02 -9.90512788e-01 -1.35655954e-01 1.70909856e-02 -9.90608990e-01 -1.35662496e-01 1.10121509e-02 -9.90686119e-01 -1.35662943e-01 4.93318634e-03 -9.90757167e-01 -1.35657385e-01 -1.14597019e-03 -9.90757763e-01 -1.35658234e-01 -7.22505059e-03 -9.90752876e-01 -1.35646895e-01 -1.33038228e-02 -9.90681171e-01 -1.35630742e-01 -1.93824098e-02 -9.90542114e-01 -1.35633394e-01 -2.54601706e-02 -9.90437269e-01 -1.35643870e-01 -3.15363891e-02 -9.90270197e-01 -1.35654941e-01 -3.76119390e-02 -9.90034044e-01 -1.35649845e-01 -4.36869562e-02 -9.89790678e-01 -1.35655984e-01 -4.97585796e-02 -9.89529610e-01 -1.35653004e-01 -5.58291413e-02 -9.89167809e-01 -1.35643005e-01 -6.18968531e-02 -9.88824189e-01 -1.35649607e-01 -6.79643452e-02 -9.88425255e-01 -1.35652751e-01 -7.40279108e-02 -9.87999797e-01 -1.35660708e-01 -8.00877884e-02 -9.87519860e-01 -1.35659009e-01 -8.61455128e-02 -9.86988425e-01 -1.35677353e-01 -9.22010094e-02 -9.86430824e-01 -1.35664642e-01 -9.82521772e-02 -9.85897779e-01 -1.35666266e-01 -1.04299344e-01 -9.85219836e-01 -1.35681704e-01 -1.10343203e-01 -9.84606802e-01 -1.35667399e-01 -1.16379954e-01 -9.83899534e-01 -1.35682240e-01 -1.22417018e-01 -9.83157814e-01 -1.35667875e-01 -1.28446579e-01 -9.82390940e-01 -1.35699064e-01 -1.34473741e-01 -9.81569588e-01 -1.35694504e-01 -1.40493155e-01 -9.80741501e-01 -1.35707498e-01 -1.46507055e-01 -9.79872286e-01 -1.35680005e-01 -1.52515173e-01 -9.78923261e-01 -1.35703072e-01 -1.58523321e-01 -9.77960408e-01 -1.35708138e-01 -1.64517343e-01 -9.76986647e-01 -1.35708719e-01 -1.70509085e-01 -9.75993752e-01 -1.35698870e-01 -1.76490873e-01 -9.74881530e-01 -1.35752723e-01 -1.82473123e-01 -9.73814249e-01 -1.35739192e-01 -1.88446105e-01 -9.72631216e-01 -1.35750011e-01 -1.94412634e-01 -9.71479237e-01 -1.35748044e-01 -2.00369582e-01 -9.70273018e-01 -1.35732025e-01 -2.06321597e-01 -9.69007075e-01 -1.35719165e-01 -2.12257117e-01 -9.67769384e-01 -1.35739282e-01 -2.18190655e-01 -9.66410697e-01 -1.35777563e-01 -2.24116638e-01 -9.65094924e-01 -1.35777682e-01 -2.30033904e-01 -9.63665366e-01 -1.35763243e-01 -2.35949278e-01 -9.62231696e-01 -1.35752141e-01 -2.41844743e-01 -9.60767925e-01 -1.35751978e-01 -2.47740582e-01 -9.59304869e-01 -1.35759354e-01 -2.53618538e-01 -9.57767725e-01 -1.35755569e-01 -2.59489208e-01 -9.56175625e-01 -1.35628223e-01 -2.65352547e-01 -9.54552650e-01 -1.35621652e-01 -2.71207809e-01 -9.52930093e-01 -1.35732532e-01 -2.77044415e-01 -9.51239944e-01 -1.35733992e-01 -2.82881558e-01 -9.49511111e-01 -1.35732383e-01 -2.88692117e-01 -9.47733402e-01 -1.35763481e-01 -2.94503659e-01 -9.45987761e-01 -1.35718122e-01 -3.00303221e-01 -9.44140196e-01 -1.35710850e-01 -3.06099951e-01 -9.42286134e-01 -1.35684684e-01 -3.11867058e-01 -9.40424263e-01 -1.35663018e-01 -3.17641139e-01 -9.38490272e-01 -1.35637239e-01 -3.23391408e-01 -9.36492503e-01 -1.35718688e-01 -3.29134196e-01 -9.34482276e-01 -1.35666251e-01 -3.34849805e-01 -9.32467878e-01 -1.35647669e-01 -3.40573549e-01 -9.30393755e-01 -1.35668859e-01 -3.46272320e-01 -9.28269923e-01 -1.35650188e-01 -3.51960063e-01 -9.26172793e-01 -1.35512650e-01 -3.57635856e-01 -9.23996568e-01 -1.35513425e-01 -3.63304198e-01 -9.21731412e-01 -1.35717705e-01 -3.68940115e-01 -9.19482589e-01 -1.35730848e-01 -3.74567091e-01 -9.17210579e-01 -1.35740355e-01 -3.80192250e-01 -9.14878726e-01 -1.35752350e-01 -3.85809213e-01 -9.12543297e-01 -1.35670528e-01 -3.91410023e-01 -9.10189509e-01 -1.35651618e-01 -3.96989971e-01 -9.07770157e-01 -1.35655537e-01 -4.02560234e-01 -9.05323863e-01 -1.35421142e-01 -4.08099860e-01 -9.02836204e-01 -1.35415822e-01 -4.13634509e-01 -9.00322258e-01 -1.35417774e-01 -4.19132560e-01 -8.97714913e-01 -1.35738462e-01 -4.24624085e-01 -8.95122349e-01 -1.35752723e-01 -4.30113971e-01 -8.92520845e-01 -1.35758922e-01 -4.35589343e-01 -8.89883101e-01 -1.35649309e-01 -4.41042632e-01 -8.87204170e-01 -1.35649279e-01 -4.46477652e-01 -8.84467542e-01 -1.35636732e-01 -4.51890737e-01 -8.81678879e-01 -1.35638058e-01 -4.57292229e-01 -8.78911912e-01 -1.35626927e-01 -4.62685376e-01 -8.76102209e-01 -1.35618702e-01 -4.68048692e-01 -8.73214066e-01 -1.35617584e-01 -4.73398894e-01 -8.70324373e-01 -1.35629490e-01 -4.78730530e-01 -8.67406487e-01 -1.35630220e-01 -4.84043181e-01 -8.64488244e-01 -1.35633379e-01 -4.89333659e-01 -8.61484706e-01 -1.35631859e-01 -4.94617432e-01 -8.58452857e-01 -1.35630086e-01 -4.99869794e-01 -8.55422437e-01 -1.35587573e-01 -5.05116403e-01 -8.52318227e-01 -1.35597289e-01 -5.10342300e-01 -8.49239290e-01 -1.35577351e-01 -5.15544474e-01 -8.46094728e-01 -1.35577425e-01 -5.20727396e-01 -8.42884183e-01 -1.35551810e-01 -5.25879264e-01 -8.39707792e-01 -1.35533124e-01 -5.31027257e-01 -8.36453259e-01 -1.35501951e-01 -5.36148846e-01 -8.33183825e-01 -1.35539830e-01 -5.41247249e-01 -8.29891443e-01 -1.35540843e-01 -5.46331763e-01 -8.26532364e-01 -1.35542676e-01 -5.51392615e-01 -8.23151290e-01 -1.35526165e-01 -5.56446910e-01 -8.19758475e-01 -1.35530204e-01 -5.61450481e-01 -8.16346407e-01 -1.35539398e-01 -5.66461802e-01 -8.12863171e-01 -1.35546342e-01 -5.71443856e-01 -8.09363365e-01 -1.35536432e-01 -5.76391816e-01 -8.05849850e-01 -1.35546163e-01 -5.81331432e-01 -8.02317321e-01 -1.35559633e-01 -5.86250901e-01 -7.98756838e-01 -1.35090768e-01 -5.91162801e-01 -7.95133710e-01 -1.35096088e-01 -5.96024811e-01 -7.91498840e-01 -1.35189086e-01 -6.00840926e-01 -7.87809014e-01 -1.35526761e-01 -6.05672538e-01 -7.84088969e-01 -1.35498017e-01 -6.10445440e-01 -7.80358016e-01 -1.35490790e-01 -6.15241468e-01 -7.76593328e-01 -1.35482192e-01 -6.19979680e-01 -7.72832096e-01 -1.35482088e-01 -6.24710560e-01 -7.68991411e-01 -1.35474220e-01 -6.29420042e-01 -7.65141547e-01 -1.35474592e-01 -6.34111524e-01 -7.61257112e-01 -1.35462180e-01 -6.38776720e-01 -7.57362068e-01 -1.35464817e-01 -6.43414557e-01 -7.53457069e-01 -1.35463700e-01 -6.48020327e-01 -7.49489069e-01 -1.35448560e-01 -6.52609169e-01 -7.45496809e-01 -1.35422885e-01 -6.57178283e-01 -7.41485476e-01 -1.35417819e-01 -6.61696255e-01 -7.37408876e-01 -1.35407016e-01 -6.66198254e-01 -7.33370483e-01 -1.35397568e-01 -6.70723140e-01 -7.29269385e-01 -1.35400757e-01 -6.75147057e-01 -7.25097835e-01 -1.35400832e-01 -6.79592669e-01 -7.20955670e-01 -1.35397732e-01 -6.84031665e-01 -7.16781020e-01 -1.35392174e-01 -6.88408673e-01 -7.12583244e-01 -1.35393292e-01 -6.92766845e-01 -7.08347559e-01 -1.35406151e-01 -6.97098613e-01 -7.04048038e-01 -1.35401443e-01 -7.01380193e-01 -6.99780703e-01 -1.35408059e-01 -7.05687165e-01 -6.95444405e-01 -1.35424003e-01 -7.09939301e-01 -6.91107452e-01 -1.35420725e-01 -7.14171648e-01 -6.86735868e-01 -1.35404468e-01 -7.18383133e-01 -6.82364404e-01 -1.35399982e-01 -7.22524345e-01 -6.77920282e-01 -1.35411829e-01 -7.26660252e-01 -6.73510492e-01 -1.35412395e-01 -7.30779648e-01 -6.69038117e-01 -1.35384679e-01 -7.34888017e-01 -6.64516866e-01 -1.35328084e-01 -7.38982618e-01 -6.60012245e-01 -1.35321885e-01 -7.42989361e-01 -6.55447423e-01 -1.35316610e-01 -7.46984005e-01 -6.50900364e-01 -1.35320693e-01 -7.50959396e-01 -6.46303833e-01 -1.35324240e-01 -7.54940808e-01 -6.41657531e-01 -1.35310993e-01 -7.58838177e-01 -6.37022913e-01 -1.35320142e-01 -7.62764692e-01 -6.32335961e-01 -1.35374665e-01 -7.66613841e-01 -6.27675951e-01 -1.35336116e-01 -7.70427704e-01 -6.22956634e-01 -1.35349423e-01 -7.74271071e-01 -6.18196845e-01 -1.35334253e-01 -7.78042495e-01 -6.13442063e-01 -1.35339484e-01 -7.81791925e-01 -6.08673930e-01 -1.35302484e-01 -7.85522819e-01 -6.03864372e-01 -1.35292172e-01 -7.89186180e-01 -5.99039555e-01 -1.35284975e-01 -7.92855620e-01 -5.94186664e-01 -1.35248601e-01 -7.96509981e-01 -5.89284658e-01 -1.35318652e-01 -8.00093353e-01 -5.84412813e-01 -1.35264605e-01 -8.03690255e-01 -5.79473257e-01 -1.35262564e-01 -8.07209134e-01 -5.74535370e-01 -1.35257512e-01 -8.10717940e-01 -5.69576502e-01 -1.35255992e-01 -8.14214766e-01 -5.64588249e-01 -1.35289773e-01 -8.17630589e-01 -5.59594512e-01 -1.35279357e-01 -8.21072221e-01 -5.54542601e-01 -1.35381535e-01 -8.24465394e-01 -5.49496889e-01 -1.35374218e-01 -8.27789307e-01 -5.44430375e-01 -1.35373816e-01 -8.31140995e-01 -5.39346874e-01 -1.35342360e-01 -8.34422767e-01 -5.34232497e-01 -1.35316238e-01 -8.37716699e-01 -5.29131114e-01 -1.35080144e-01 -8.41042995e-01 -5.24040699e-01 -1.34262815e-01 -8.45012665e-01 -5.19389689e-01 -1.27232045e-01 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.16681170e-01 -3.78505856e-01 -1.28175750e-01 -9.18485284e-01 -3.72645348e-01 -1.32340834e-01 -9.20587361e-01 -3.66927505e-01 -1.33721560e-01 -9.22727108e-01 -3.61230254e-01 -1.34488374e-01 -9.24867809e-01 -3.55536342e-01 -1.34970099e-01 -9.27028894e-01 -3.49853724e-01 -1.34980440e-01 -9.29175556e-01 -3.44165742e-01 -1.34859622e-01 -9.31306839e-01 -3.38474154e-01 -1.34539247e-01 -9.33401644e-01 -3.32767487e-01 -1.34263352e-01 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. 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. -9.84780371e-01 1.98766422e-02 -1.72663003e-01 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. 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. 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. 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. 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. 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. 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. 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. 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. -8.47427785e-01 5.02900779e-01 -1.70167297e-01 -8.44396770e-01 5.08130670e-01 -1.69694379e-01 -8.41187775e-01 5.13263226e-01 -1.70152202e-01 -8.37956548e-01 5.18375397e-01 -1.70609280e-01 -8.34694088e-01 5.23464322e-01 -1.71039596e-01 -8.31460595e-01 5.28578818e-01 -1.71130195e-01 -8.28183293e-01 5.33663869e-01 -1.71141729e-01 -8.24907720e-01 5.38724780e-01 -1.71145588e-01 -8.21579576e-01 5.43775678e-01 -1.71155885e-01 -8.18225443e-01 5.48819780e-01 -1.71134025e-01 -8.14804912e-01 5.53814650e-01 -1.71299830e-01 -8.11425924e-01 5.58808029e-01 -1.71270639e-01 -8.07957292e-01 5.63762188e-01 -1.71266690e-01 -8.04489553e-01 5.68721175e-01 -1.71285570e-01 -8.00982356e-01 5.73643565e-01 -1.71264455e-01 -7.97469378e-01 5.78544438e-01 -1.71298087e-01 -7.93875635e-01 5.83418846e-01 -1.71330437e-01 -7.90270090e-01 5.88286817e-01 -1.71345443e-01 -7.86647379e-01 5.93127310e-01 -1.71367303e-01 -7.83012807e-01 5.97945392e-01 -1.71356305e-01 -7.79305756e-01 6.02721095e-01 -1.71415374e-01 -7.75588572e-01 6.07493639e-01 -1.71385080e-01 -7.71858096e-01 6.12254918e-01 -1.71354920e-01 -7.68101275e-01 6.16966426e-01 -1.71351478e-01 -7.64286578e-01 6.21661603e-01 -1.71363190e-01 -7.60466456e-01 6.26349449e-01 -1.71324790e-01 -7.56589949e-01 6.31013274e-01 -1.71369046e-01 -7.52735019e-01 6.35633826e-01 -1.71353400e-01 -7.48800695e-01 6.40254021e-01 -1.71346933e-01 -7.44882524e-01 6.44839704e-01 -1.71375692e-01 -7.40907073e-01 6.49387121e-01 -1.71410188e-01 -7.36887574e-01 6.53908134e-01 -1.71407953e-01 -7.32879877e-01 6.58433855e-01 -1.71393022e-01 -7.28816628e-01 6.62911534e-01 -1.71339110e-01 -7.24738181e-01 6.67371988e-01 -1.71271876e-01 -7.20647812e-01 6.71819866e-01 -1.71211019e-01 -7.16515303e-01 6.76232755e-01 -1.71107277e-01 -7.12365925e-01 6.80628538e-01 -1.71067789e-01 -7.08183825e-01 6.85004652e-01 -1.70998067e-01 -7.03984857e-01 6.89350247e-01 -1.70913875e-01 -6.99742079e-01 6.93645895e-01 -1.70948595e-01 -6.95462525e-01 6.97923183e-01 -1.71035767e-01 -6.91150010e-01 7.02154756e-01 -1.71095148e-01 -6.86797142e-01 7.06367970e-01 -1.71329781e-01 -6.82464838e-01 7.10565925e-01 -1.71311095e-01 -6.78066254e-01 7.14731336e-01 -1.71386808e-01 -6.73690617e-01 7.18869150e-01 -1.71343744e-01 -6.69267356e-01 7.23015368e-01 -1.71346620e-01 -6.64817989e-01 7.27112293e-01 -1.71340913e-01 -6.60327733e-01 7.31155157e-01 -1.71487048e-01 -6.55834854e-01 7.35185087e-01 -1.71355784e-01 -6.51318133e-01 7.39204705e-01 -1.71381176e-01 -6.46769524e-01 7.43196547e-01 -1.71407104e-01 -6.42202258e-01 7.47137845e-01 -1.71387032e-01 -6.37617767e-01 7.51066923e-01 -1.71307966e-01 -6.32968664e-01 7.54997075e-01 -1.71308637e-01 -6.28349364e-01 7.58851826e-01 -1.71354279e-01 -6.23672366e-01 7.62698352e-01 -1.71335921e-01 -6.18975699e-01 7.66468585e-01 -1.71395585e-01 -6.14282250e-01 7.70283282e-01 -1.71337754e-01 -6.09513402e-01 7.74026692e-01 -1.71331272e-01 -6.04775667e-01 7.77754426e-01 -1.71338379e-01 -5.99989653e-01 7.81472266e-01 -1.71333119e-01 -5.95180690e-01 7.85101593e-01 -1.71374187e-01 -5.90351701e-01 7.88746417e-01 -1.71379060e-01 -5.85478246e-01 7.92347670e-01 -1.71354413e-01 -5.80631971e-01 7.95928895e-01 -1.71351716e-01 -5.75720608e-01 7.99502969e-01 -1.71350181e-01 -5.70801616e-01 8.03022385e-01 -1.71311945e-01 -5.65870941e-01 8.06511641e-01 -1.71275586e-01 -5.60925305e-01 8.09975863e-01 -1.71308354e-01 -5.55951834e-01 8.13373387e-01 -1.71303153e-01 -5.50941765e-01 8.16764355e-01 -1.71317875e-01 -5.45906365e-01 8.20131421e-01 -1.71320438e-01 -5.40858030e-01 8.23477030e-01 -1.71336636e-01 -5.35796344e-01 8.26792240e-01 -1.71382084e-01 -5.30724823e-01 8.30063164e-01 -1.71402901e-01 -5.25598705e-01 8.33294213e-01 -1.71413288e-01 -5.20497441e-01 8.36484969e-01 -1.71404839e-01 -5.15342712e-01 8.39686275e-01 -1.71412334e-01 -5.10177910e-01 8.42814565e-01 -1.71419472e-01 -5.04999042e-01 8.45940351e-01 -1.71411470e-01 -4.99807119e-01 8.49041104e-01 -1.71422839e-01 -4.94585812e-01 8.52057099e-01 -1.71402380e-01 -4.89355177e-01 8.55080605e-01 -1.71417132e-01 -4.84077841e-01 8.58068585e-01 -1.71412036e-01 -4.78812277e-01 8.61014485e-01 -1.71416968e-01 -4.73519236e-01 8.63959610e-01 -1.71438977e-01 -4.68201429e-01 8.66857529e-01 -1.71437383e-01 -4.62894648e-01 8.69721234e-01 -1.71440661e-01 -4.57533121e-01 8.72502983e-01 -1.71436414e-01 -4.52188283e-01 8.75287116e-01 -1.71439216e-01 -4.46792066e-01 8.78065288e-01 -1.71446517e-01 -4.41407263e-01 8.80806684e-01 -1.71445414e-01 -4.35990512e-01 8.83464694e-01 -1.71450943e-01 -4.30547774e-01 8.86109948e-01 -1.71534151e-01 -4.25123125e-01 8.88752222e-01 -1.71461970e-01 -4.19654638e-01 8.91373932e-01 -1.71467721e-01 -4.14184034e-01 8.93900037e-01 -1.71487495e-01 -4.08665866e-01 8.96431804e-01 -1.71533003e-01 -4.03169602e-01 8.98909390e-01 -1.71578273e-01 -3.97642076e-01 9.01373267e-01 -1.71577454e-01 -3.92109692e-01 9.03784394e-01 -1.71574757e-01 -3.86555880e-01 9.06187177e-01 -1.71560153e-01 -3.80989373e-01 9.08542633e-01 -1.71560630e-01 -3.75400841e-01 9.10863101e-01 -1.71558052e-01 -3.69806260e-01 9.13135588e-01 -1.71565309e-01 -3.64204228e-01 9.15409446e-01 -1.71574727e-01 -3.58567387e-01 9.17600513e-01 -1.71565935e-01 -3.52958351e-01 9.19831812e-01 -1.71259165e-01 -3.47312421e-01 9.21982706e-01 -1.71250612e-01 -3.41613978e-01 9.24057662e-01 -1.71657220e-01 -3.35940510e-01 9.26120937e-01 -1.71723530e-01 -3.30246836e-01 9.28159356e-01 -1.71707973e-01 -3.24555963e-01 9.30191040e-01 -1.71613500e-01 -3.18835437e-01 9.32132840e-01 -1.71691075e-01 -3.13104481e-01 9.34063971e-01 -1.71716452e-01 -3.07376415e-01 9.35977101e-01 -1.71684280e-01 -3.01620901e-01 9.37867880e-01 -1.71683565e-01 -2.95860291e-01 9.39698339e-01 -1.71670154e-01 -2.90087044e-01 9.41491544e-01 -1.71681866e-01 -2.84307629e-01 9.43223298e-01 -1.71649709e-01 -2.78518677e-01 9.44989145e-01 -1.71652332e-01 -2.72711098e-01 9.46670175e-01 -1.71675771e-01 -2.66900808e-01 9.48336899e-01 -1.71659276e-01 -2.61077762e-01 9.49927628e-01 -1.71661168e-01 -2.55245686e-01 9.51518118e-01 -1.71637475e-01 -2.49394491e-01 9.53051269e-01 -1.71677247e-01 -2.43548855e-01 9.54585791e-01 -1.71665341e-01 -2.37686604e-01 9.56052482e-01 -1.71670794e-01 -2.31814176e-01 9.57494259e-01 -1.71680361e-01 -2.25935832e-01 9.58915174e-01 -1.71654031e-01 -2.20045492e-01 9.60269451e-01 -1.71631873e-01 -2.14149028e-01 9.61583138e-01 -1.71710849e-01 -2.08245844e-01 9.62895036e-01 -1.71680197e-01 -2.02334672e-01 9.64145303e-01 -1.71681777e-01 -1.96412995e-01 9.65407729e-01 -1.71680048e-01 -1.90488547e-01 9.66557026e-01 -1.71663225e-01 -1.84555054e-01 9.67715263e-01 -1.71644434e-01 -1.78614661e-01 9.68817115e-01 -1.71630636e-01 -1.72664255e-01 9.69906569e-01 -1.71616629e-01 -1.66711211e-01 9.70974863e-01 -1.71600387e-01 -1.60756648e-01 9.71975565e-01 -1.71435475e-01 -1.54784679e-01 9.72939432e-01 -1.71526477e-01 -1.48812085e-01 9.73877788e-01 -1.71533585e-01 -1.42834947e-01 9.74750161e-01 -1.71543181e-01 -1.36849508e-01 9.75639462e-01 -1.71596304e-01 -1.30858943e-01 9.76419508e-01 -1.71618015e-01 -1.24863468e-01 9.77226794e-01 -1.71618789e-01 -1.18865825e-01 9.77956235e-01 -1.71611354e-01 -1.12864189e-01 9.78673279e-01 -1.71617448e-01 -1.06854618e-01 9.79374349e-01 -1.71605408e-01 -1.00845225e-01 9.79981422e-01 -1.71614066e-01 -9.48288068e-02 9.80600417e-01 -1.71596944e-01 -8.88126045e-02 9.81171489e-01 -1.71583816e-01 -8.27884227e-02 9.81697321e-01 -1.71591267e-01 -7.67660365e-02 9.82178032e-01 -1.71599388e-01 -7.07376227e-02 9.82626557e-01 -1.71604738e-01 -6.47052005e-02 9.83024418e-01 -1.71613932e-01 -5.86730242e-02 9.83403802e-01 -1.71623155e-01 -5.26376516e-02 9.83744204e-01 -1.71632394e-01 -4.65999283e-02 9.84063685e-01 -1.71637952e-01 -4.05618101e-02 9.84340072e-01 -1.71642676e-01 -3.45207527e-02 9.84544873e-01 -1.71663031e-01 -2.84790508e-02 9.84764755e-01 -1.71650216e-01 -2.24358812e-02 9.84922528e-01 -1.71658188e-01 -1.63924862e-02 9.85024750e-01 -1.71643868e-01 -1.03483023e-02 9.85145867e-01 -1.71608746e-01 -4.30343999e-03 9.85165834e-01 -1.71633586e-01 1.74167065e-03 9.85160530e-01 -1.71683684e-01 7.78663903e-03 9.85133886e-01 -1.71726242e-01 1.38309412e-02 9.85055923e-01 -1.71726122e-01 1.98751017e-02 9.84934807e-01 -1.71720430e-01 2.59182509e-02 9.84817922e-01 -1.71675220e-01 3.19602154e-02 9.84661341e-01 -1.71663433e-01 3.80012654e-02 9.84439909e-01 -1.71659172e-01 4.40405682e-02 9.84194815e-01 -1.71643779e-01 5.00789993e-02 9.83873904e-01 -1.71634763e-01 5.61145544e-02 9.83564198e-01 -1.71685413e-01 6.21489510e-02 9.83219683e-01 -1.71610832e-01 6.81817979e-02 9.82786834e-01 -1.71603680e-01 7.42103010e-02 9.82368231e-01 -1.71640232e-01 8.02363753e-02 9.81905758e-01 -1.71643674e-01 8.62583891e-02 9.81401205e-01 -1.71645433e-01 9.22806039e-02 9.80829239e-01 -1.71656832e-01 9.82955396e-02 9.80235279e-01 -1.71644270e-01 1.04308225e-01 9.79625881e-01 -1.71664611e-01 1.10318810e-01 9.78935897e-01 -1.71664432e-01 1.16321735e-01 9.78279829e-01 -1.71636105e-01 1.22321568e-01 9.77553368e-01 -1.71656534e-01 1.28317222e-01 9.76751506e-01 -1.71622589e-01 1.34310067e-01 9.75994110e-01 -1.71609357e-01 1.40294746e-01 9.75150466e-01 -1.71627298e-01 1.46275654e-01 9.74227488e-01 -1.71622425e-01 1.52249798e-01 9.73348081e-01 -1.71584517e-01 1.58220738e-01 9.72393870e-01 -1.71554103e-01 1.64184690e-01 9.71385837e-01 -1.71533599e-01 1.70143232e-01 9.70393121e-01 -1.71453789e-01 1.76096246e-01 9.69326377e-01 -1.71413794e-01 1.82043746e-01 9.68246579e-01 -1.71376616e-01 1.87984824e-01 9.67136204e-01 -1.71195343e-01 1.93947285e-01 9.66152966e-01 -1.70079753e-01 1.99926838e-01 9.65260684e-01 -1.68220669e-01 2.05881640e-01 9.64214742e-01 -1.67040527e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.35197902e-01 9.56674099e-01 -1.71630308e-01 2.41060451e-01 9.55200732e-01 -1.71706736e-01 2.46919051e-01 9.53707218e-01 -1.71671182e-01 2.52764463e-01 9.52169597e-01 -1.71736926e-01 2.58600056e-01 9.50592995e-01 -1.71746626e-01 2.64429361e-01 9.48998511e-01 -1.71743304e-01 2.70246536e-01 9.47349012e-01 -1.71757206e-01 2.76053965e-01 9.45667088e-01 -1.71760112e-01 2.81850994e-01 9.43962812e-01 -1.71749443e-01 2.87639529e-01 9.42219317e-01 -1.71713695e-01 2.93421775e-01 9.40459907e-01 -1.71577305e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.27831149e-01 9.28999245e-01 -1.71718344e-01 3.33777845e-01 9.27749097e-01 -1.66951492e-01 3.39410126e-01 9.25520360e-01 -1.67954251e-01 3.45027924e-01 9.23258185e-01 -1.68954089e-01 3.50609392e-01 9.20901477e-01 -1.70324787e-01 3.56225342e-01 9.18655396e-01 -1.70809358e-01 3.61836642e-01 9.16392505e-01 -1.71144336e-01 3.67442012e-01 9.14138794e-01 -1.71297431e-01 3.73039573e-01 9.11845922e-01 -1.71395525e-01 3.78622472e-01 9.09536064e-01 -1.71487167e-01 3.84197474e-01 9.07179654e-01 -1.71524763e-01 3.89755517e-01 9.04803813e-01 -1.71551481e-01 3.95291299e-01 9.02391255e-01 -1.71604320e-01 4.00819451e-01 8.99919748e-01 -1.71633586e-01 4.06334162e-01 8.97461176e-01 -1.71625555e-01 4.11824107e-01 8.94950986e-01 -1.71660364e-01 4.17301834e-01 8.92394006e-01 -1.71720788e-01 4.22772139e-01 8.89807642e-01 -1.71695188e-01 4.28235233e-01 8.87226760e-01 -1.71686575e-01 4.33656394e-01 8.84581089e-01 -1.71721816e-01 4.39069152e-01 8.81875455e-01 -1.71738043e-01 4.44474399e-01 8.79165292e-01 -1.71774685e-01 4.49877143e-01 8.76426458e-01 -1.71755314e-01 4.55240518e-01 8.73636246e-01 -1.71762466e-01 4.60584372e-01 8.70822430e-01 -1.71739399e-01 4.65923607e-01 8.68004620e-01 -1.71736374e-01 4.71243978e-01 8.65122259e-01 -1.71747714e-01 4.76536632e-01 8.62232506e-01 -1.71728805e-01 4.81825560e-01 8.59261751e-01 -1.71772078e-01 4.87079322e-01 8.56300533e-01 -1.71767414e-01 4.92327511e-01 8.53309751e-01 -1.71772972e-01 4.97562468e-01 8.50229919e-01 -1.71792939e-01 5.02775192e-01 8.47186625e-01 -1.71771884e-01 5.07959664e-01 8.44093800e-01 -1.71771958e-01 5.13130248e-01 8.40942740e-01 -1.71770006e-01 5.18288314e-01 8.37790310e-01 -1.71758324e-01 5.23393810e-01 8.34581614e-01 -1.71763048e-01 5.28523982e-01 8.31369638e-01 -1.71751827e-01 5.33608377e-01 8.28095198e-01 -1.71733260e-01 5.38672447e-01 8.24831665e-01 -1.71724811e-01 5.43725133e-01 8.21492076e-01 -1.71709344e-01 5.48759699e-01 8.18139791e-01 -1.71697885e-01 5.53780496e-01 8.14762354e-01 -1.71682060e-01 5.58764458e-01 8.11373889e-01 -1.71640456e-01 5.63749373e-01 8.07911694e-01 -1.71641856e-01 5.68687260e-01 8.04434896e-01 -1.71719864e-01 5.73617399e-01 8.00922692e-01 -1.71713218e-01 5.78520775e-01 7.97412574e-01 -1.71716332e-01 5.83382428e-01 7.93826520e-01 -1.71718463e-01 5.88260114e-01 7.90228248e-01 -1.71724230e-01 5.93098104e-01 7.86609292e-01 -1.71750590e-01 5.97910166e-01 7.82966137e-01 -1.71757296e-01 6.02700591e-01 7.79273689e-01 -1.71708748e-01 6.07451260e-01 7.75547147e-01 -1.71759158e-01 6.12221956e-01 7.71814466e-01 -1.71742842e-01 6.16929889e-01 7.68058717e-01 -1.71747103e-01 6.21622980e-01 7.64243782e-01 -1.71769276e-01 6.26306117e-01 7.60408163e-01 -1.71783939e-01 6.30974829e-01 7.56545782e-01 -1.71794280e-01 6.35582983e-01 7.52677739e-01 -1.71788201e-01 6.40217364e-01 7.48740435e-01 -1.71788633e-01 6.44797802e-01 7.44840860e-01 -1.71784997e-01 6.49356782e-01 7.40872025e-01 -1.71778977e-01 6.53865814e-01 7.36837149e-01 -1.71762481e-01 6.58399820e-01 7.32839942e-01 -1.71733841e-01 6.62865162e-01 7.28764892e-01 -1.71741441e-01 6.67315722e-01 7.24678278e-01 -1.71760768e-01 6.71757877e-01 7.20579088e-01 -1.71762481e-01 6.76185489e-01 7.16464102e-01 -1.71771839e-01 6.80543602e-01 7.12281764e-01 -1.71749189e-01 6.84897840e-01 7.08083272e-01 -1.71752125e-01 6.89228237e-01 7.03872144e-01 -1.71731040e-01 6.93541408e-01 6.99648380e-01 -1.71728984e-01 6.97844326e-01 6.95356190e-01 -1.71734005e-01 7.02070296e-01 6.91086650e-01 -1.71734259e-01 7.06304193e-01 6.86761618e-01 -1.71721622e-01 7.10506976e-01 6.82424724e-01 -1.71708360e-01 7.14690030e-01 6.78021312e-01 -1.71696812e-01 7.18842387e-01 6.73652112e-01 -1.71712294e-01 7.22975314e-01 6.69232547e-01 -1.71668783e-01 7.27071464e-01 6.64782465e-01 -1.71679184e-01 7.31134832e-01 6.60306215e-01 -1.71630383e-01 7.35156655e-01 6.55809402e-01 -1.71613991e-01 7.39185393e-01 6.51285529e-01 -1.71617016e-01 7.43165493e-01 6.46744549e-01 -1.71620131e-01 7.47130394e-01 6.42187119e-01 -1.71485692e-01 7.51039386e-01 6.37581527e-01 -1.71525270e-01 7.54956782e-01 6.32942557e-01 -1.71572432e-01 7.58821130e-01 6.28314912e-01 -1.71560928e-01 7.62660623e-01 6.23646080e-01 -1.71565399e-01 7.66456366e-01 6.18953943e-01 -1.71557516e-01 7.70261645e-01 6.14243865e-01 -1.71571061e-01 7.73999810e-01 6.09491825e-01 -1.71562165e-01 7.77729928e-01 6.04746997e-01 -1.71540856e-01 7.81444490e-01 5.99971712e-01 -1.71510920e-01 7.85083771e-01 5.95162451e-01 -1.71511889e-01 7.88737297e-01 5.90326786e-01 -1.71498090e-01 7.92338431e-01 5.85474730e-01 -1.71491817e-01 7.95907676e-01 5.80612361e-01 -1.71486154e-01 7.99479306e-01 5.75705588e-01 -1.71472862e-01 8.02993298e-01 5.70788145e-01 -1.71452299e-01 8.06482852e-01 5.65849125e-01 -1.71433389e-01 8.09942901e-01 5.60902774e-01 -1.71430960e-01 8.13349366e-01 5.55923522e-01 -1.71413094e-01 8.16740751e-01 5.50921023e-01 -1.71426862e-01 8.20108712e-01 5.45888603e-01 -1.71416551e-01 8.23450744e-01 5.40852189e-01 -1.71400562e-01 8.26781571e-01 5.35788238e-01 -1.71399087e-01 8.30051184e-01 5.30716062e-01 -1.71403632e-01 8.33294094e-01 5.25595605e-01 -1.71459377e-01 8.36471677e-01 5.20489931e-01 -1.71460733e-01 8.39682043e-01 5.15337646e-01 -1.71362385e-01 8.42813671e-01 5.10173738e-01 -1.71352178e-01 8.45941305e-01 5.04998207e-01 -1.71345189e-01 8.49043131e-01 4.99808818e-01 -1.71422914e-01 8.52070272e-01 4.94577408e-01 -1.71416268e-01 8.55085373e-01 4.89356279e-01 -1.71407044e-01 8.58099163e-01 4.84098256e-01 -1.71273753e-01 8.61007214e-01 4.78827327e-01 -1.71364695e-01 8.63958895e-01 4.73536879e-01 -1.71343505e-01 8.66885066e-01 4.68218803e-01 -1.71250805e-01 8.69731486e-01 4.62911397e-01 -1.71241105e-01 8.72539103e-01 4.57554251e-01 -1.71273828e-01 8.75303507e-01 4.52195883e-01 -1.71312436e-01 8.78065646e-01 4.46798801e-01 -1.71318009e-01 8.80820751e-01 4.41420108e-01 -1.71294525e-01 8.83492351e-01 4.36007619e-01 -1.71270654e-01 8.86159122e-01 4.30571705e-01 -1.71257570e-01 8.88781607e-01 4.25138623e-01 -1.71253458e-01 8.91396224e-01 4.19671029e-01 -1.71270743e-01 8.93947721e-01 4.14197177e-01 -1.71263322e-01 8.96475077e-01 4.08698559e-01 -1.71251461e-01 8.98972929e-01 4.03193504e-01 -1.71264663e-01 9.01411533e-01 3.97662252e-01 -1.71320543e-01 9.03823733e-01 3.92128736e-01 -1.71315879e-01 9.06223953e-01 3.86576474e-01 -1.71315655e-01 9.08582330e-01 3.81005377e-01 -1.71316922e-01 9.10902977e-01 3.75416547e-01 -1.71310842e-01 9.13175702e-01 3.69822830e-01 -1.71300530e-01 9.15453255e-01 3.64224374e-01 -1.71307757e-01 9.17643249e-01 3.58585894e-01 -1.71278656e-01 9.19828773e-01 3.52962404e-01 -1.71266586e-01 9.21998620e-01 3.47319692e-01 -1.71138719e-01 9.24140692e-01 3.41644287e-01 -1.71126217e-01 9.26192939e-01 3.35976958e-01 -1.71123967e-01 9.28238690e-01 3.30277830e-01 -1.71163708e-01 9.30260897e-01 3.24580520e-01 -1.71153903e-01 9.32243407e-01 3.18875104e-01 -1.71112239e-01 9.34172392e-01 3.13140959e-01 -1.71109900e-01 9.36090291e-01 3.07409614e-01 -1.71117574e-01 9.37945783e-01 3.01648527e-01 -1.71184897e-01 9.39774811e-01 2.95892745e-01 -1.71186239e-01 9.41552818e-01 2.90119410e-01 -1.71244442e-01 9.43311691e-01 2.84328938e-01 -1.71239495e-01 9.45064902e-01 2.78541237e-01 -1.71231449e-01 9.46749687e-01 2.72738993e-01 -1.71227992e-01 9.48419511e-01 2.66928822e-01 -1.71223193e-01 9.50027943e-01 2.61101067e-01 -1.71218485e-01 9.51586902e-01 2.55267620e-01 -1.71210229e-01 9.53159273e-01 2.49426931e-01 -1.71209708e-01 9.54682231e-01 2.43574351e-01 -1.71126753e-01 9.56150055e-01 2.37712711e-01 -1.71116754e-01 9.57593501e-01 2.31840625e-01 -1.71114907e-01 9.59012330e-01 2.25958243e-01 -1.71117634e-01 9.60365236e-01 2.20069245e-01 -1.71101496e-01 9.61711824e-01 2.14182571e-01 -1.70974478e-01 9.63007212e-01 2.08274886e-01 -1.70972049e-01 9.64286506e-01 2.02362955e-01 -1.70952246e-01 9.65538621e-01 1.96441263e-01 -1.70967743e-01 9.66692626e-01 1.90515175e-01 -1.70965254e-01 9.67816889e-01 1.84580460e-01 -1.70970678e-01 9.68929291e-01 1.78637177e-01 -1.70996591e-01 9.70041096e-01 1.72685981e-01 -1.70985714e-01 9.71084952e-01 1.66731223e-01 -1.70998201e-01 9.72056389e-01 1.60772666e-01 -1.70997441e-01 9.73026931e-01 1.54799119e-01 -1.71010345e-01 9.73976493e-01 1.48832649e-01 -1.70990542e-01 9.74865794e-01 1.42851964e-01 -1.71010315e-01 9.75726724e-01 1.36868045e-01 -1.71000987e-01 9.76556242e-01 1.30878597e-01 -1.70965195e-01 9.77340221e-01 1.24880865e-01 -1.71006605e-01 9.78066981e-01 1.18886888e-01 -1.71009168e-01 9.78791952e-01 1.12879090e-01 -1.70971245e-01 9.79493201e-01 1.06872506e-01 -1.70982525e-01 9.80078936e-01 1.00859456e-01 -1.70990914e-01 9.80712473e-01 9.48455781e-02 -1.70983881e-01 9.81263995e-01 8.88243541e-02 -1.70987397e-01 9.81825352e-01 8.28040913e-02 -1.70991763e-01 9.82308507e-01 7.67767131e-02 -1.70993865e-01 9.82724845e-01 7.07482621e-02 -1.70970187e-01 9.83140528e-01 6.47184178e-02 -1.70953467e-01 9.83538151e-01 5.86831383e-02 -1.70961350e-01 9.83861744e-01 5.26479483e-02 -1.70955345e-01 9.84168708e-01 4.66102250e-02 -1.70952231e-01 9.84496772e-01 4.05707061e-02 -1.70862779e-01 9.84658301e-01 3.45292650e-02 -1.70928121e-01 9.84861732e-01 2.84860209e-02 -1.71026334e-01 9.85033214e-01 2.24420857e-02 -1.71019986e-01 9.85128403e-01 1.63982455e-02 -1.70976102e-01 9.85247135e-01 1.03523117e-02 -1.71070188e-01 9.85280275e-01 4.30746563e-03 -1.70992941e-01 9.85276341e-01 -1.73828518e-03 -1.71023026e-01 9.85245883e-01 -7.78406532e-03 -1.71103776e-01 9.85205531e-01 -1.38288718e-02 -1.70953199e-01 9.85067785e-01 -1.98735297e-02 -1.70943648e-01 9.84944761e-01 -2.59173326e-02 -1.71073899e-01 9.84792054e-01 -3.19609866e-02 -1.70950785e-01 9.84566212e-01 -3.80018987e-02 -1.70952111e-01 9.84316647e-01 -4.40435298e-02 -1.70980424e-01 9.84016776e-01 -5.00815399e-02 -1.70971453e-01 9.83671546e-01 -5.61187603e-02 -1.70974627e-01 9.83344257e-01 -6.21540509e-02 -1.70973122e-01 9.82861221e-01 -6.81841969e-02 -1.71180725e-01 9.82462823e-01 -7.42135942e-02 -1.71002641e-01 9.81997490e-01 -8.02415684e-02 -1.70982182e-01 9.81493115e-01 -8.62658918e-02 -1.71018064e-01 9.80918646e-01 -9.22829434e-02 -1.71186998e-01 9.80353415e-01 -9.83016267e-02 -1.71187490e-01 9.79735494e-01 -1.04316458e-01 -1.71072319e-01 9.79041815e-01 -1.10323474e-01 -1.71042174e-01 9.78377759e-01 -1.16333999e-01 -1.70988426e-01 9.77655232e-01 -1.22334607e-01 -1.70964688e-01 9.76873934e-01 -1.28330261e-01 -1.70958161e-01 9.76123989e-01 -1.34320125e-01 -1.70970023e-01 9.75246668e-01 -1.40307158e-01 -1.70980811e-01 9.74375427e-01 -1.46286905e-01 -1.70996413e-01 9.73474324e-01 -1.52265325e-01 -1.70994580e-01 9.72515762e-01 -1.58235192e-01 -1.70993015e-01 9.71504927e-01 -1.64201632e-01 -1.70990303e-01 9.70454216e-01 -1.70157880e-01 -1.71000481e-01 9.69409049e-01 -1.76109806e-01 -1.70978069e-01 9.68287528e-01 -1.82058409e-01 -1.71003416e-01 9.67213988e-01 -1.87991410e-01 -1.70989677e-01 9.66030478e-01 -1.93922922e-01 -1.71002656e-01 9.64815795e-01 -1.99842781e-01 -1.71004653e-01 9.63562727e-01 -2.05765530e-01 -1.71003610e-01 9.62257206e-01 -2.11678624e-01 -1.70994475e-01 9.60977912e-01 -2.17572972e-01 -1.71007395e-01 9.59605157e-01 -2.23466441e-01 -1.70998454e-01 9.58180666e-01 -2.29348168e-01 -1.71002835e-01 9.56808627e-01 -2.35222325e-01 -1.71003595e-01 9.55291390e-01 -2.41086349e-01 -1.71026945e-01 9.53825772e-01 -2.46940240e-01 -1.71019673e-01 9.52311695e-01 -2.52797276e-01 -1.71024755e-01 9.50698435e-01 -2.58632600e-01 -1.71050221e-01 9.49117601e-01 -2.64461964e-01 -1.71063393e-01 9.47482169e-01 -2.70270765e-01 -1.71071008e-01 9.45807993e-01 -2.76082397e-01 -1.71079770e-01 9.44107056e-01 -2.81876564e-01 -1.71078026e-01 9.42363322e-01 -2.87675351e-01 -1.71046436e-01 9.40525651e-01 -2.93450713e-01 -1.71057016e-01 9.38752949e-01 -2.99218982e-01 -1.71069637e-01 9.36893821e-01 -3.04957569e-01 -1.71076506e-01 9.34984684e-01 -3.10711741e-01 -1.71078444e-01 9.33060348e-01 -3.16435874e-01 -1.71070084e-01 9.31115568e-01 -3.22152793e-01 -1.71098143e-01 9.29127693e-01 -3.27859670e-01 -1.71095982e-01 9.27049935e-01 -3.33561152e-01 -1.71075493e-01 9.25039589e-01 -3.39236438e-01 -1.71081930e-01 9.22937870e-01 -3.44921708e-01 -1.71080783e-01 9.20766890e-01 -3.50568950e-01 -1.71220794e-01 9.18619812e-01 -3.56210113e-01 -1.71093941e-01 9.16435421e-01 -3.61841708e-01 -1.71112627e-01 9.14131224e-01 -3.67446125e-01 -1.71121746e-01 9.11881506e-01 -3.73064876e-01 -1.71140283e-01 9.09563124e-01 -3.78648102e-01 -1.71106085e-01 9.07255769e-01 -3.84223461e-01 -1.71098128e-01 9.04895246e-01 -3.89790416e-01 -1.71098560e-01 9.02489841e-01 -3.95326763e-01 -1.71097249e-01 9.00035918e-01 -4.00858670e-01 -1.71088770e-01 8.97523224e-01 -4.06381130e-01 -1.71098962e-01 8.95046949e-01 -4.11878914e-01 -1.71102434e-01 8.92467320e-01 -4.17343706e-01 -1.71133906e-01 8.89905393e-01 -4.22814816e-01 -1.71196744e-01 8.87330592e-01 -4.28278953e-01 -1.71127871e-01 8.84686172e-01 -4.33702052e-01 -1.71115592e-01 8.81992459e-01 -4.39114749e-01 -1.71116903e-01 8.79251957e-01 -4.44524705e-01 -1.71129540e-01 8.76527190e-01 -4.49927509e-01 -1.71126038e-01 8.73719215e-01 -4.55299228e-01 -1.71151131e-01 8.70966554e-01 -4.60632741e-01 -1.71148136e-01 8.68103802e-01 -4.65962619e-01 -1.71139523e-01 8.65219891e-01 -4.71304655e-01 -1.71135619e-01 8.62326741e-01 -4.76597995e-01 -1.71145663e-01 8.59377384e-01 -4.81888831e-01 -1.71136051e-01 8.56387615e-01 -4.87127095e-01 -1.71148956e-01 8.53410184e-01 -4.92381126e-01 -1.71167210e-01 8.50322962e-01 -4.97601837e-01 -1.71162367e-01 8.47256720e-01 -5.02824187e-01 -1.71173766e-01 8.44200492e-01 -5.08008838e-01 -1.71175912e-01 8.41052890e-01 -5.13180792e-01 -1.71180308e-01 8.37861240e-01 -5.18333316e-01 -1.71191007e-01 8.34667206e-01 -5.23444116e-01 -1.71195135e-01 8.31463099e-01 -5.28573692e-01 -1.71211153e-01 8.28173339e-01 -5.33649623e-01 -1.71207383e-01 8.24884176e-01 -5.38717687e-01 -1.71202600e-01 8.21587801e-01 -5.43767095e-01 -1.71230108e-01 8.18233669e-01 -5.48803031e-01 -1.71209827e-01 8.14855754e-01 -5.53831279e-01 -1.71201631e-01 8.11413944e-01 -5.58801413e-01 -1.71220958e-01 8.07970107e-01 -5.63788712e-01 -1.71209201e-01 8.04521561e-01 -5.68737388e-01 -1.71208158e-01 8.00993085e-01 -5.73664665e-01 -1.71214163e-01 7.97464132e-01 -5.78575015e-01 -1.71216890e-01 7.93922722e-01 -5.83431244e-01 -1.71224639e-01 7.90316164e-01 -5.88315189e-01 -1.71246052e-01 7.86701381e-01 -5.93149066e-01 -1.71264321e-01 7.83021510e-01 -5.97964704e-01 -1.71259999e-01 7.79340684e-01 -6.02756977e-01 -1.71244502e-01 7.75642097e-01 -6.07505679e-01 -1.71244532e-01 7.71885216e-01 -6.12276852e-01 -1.71237469e-01 7.68119872e-01 -6.16988182e-01 -1.71221182e-01 7.64336646e-01 -6.21686101e-01 -1.71227351e-01 7.60501742e-01 -6.26368761e-01 -1.71237350e-01 7.56642520e-01 -6.31039381e-01 -1.71240285e-01 7.52742171e-01 -6.35648608e-01 -1.71247125e-01 7.48815477e-01 -6.40284479e-01 -1.71240732e-01 7.44922101e-01 -6.44864261e-01 -1.71230629e-01 7.40936220e-01 -6.49420559e-01 -1.71260878e-01 7.36902535e-01 -6.53916717e-01 -1.71333954e-01 7.32889712e-01 -6.58444166e-01 -1.71394452e-01 7.28814721e-01 -6.62910998e-01 -1.71389699e-01 7.24727094e-01 -6.67362809e-01 -1.71395645e-01 7.20629632e-01 -6.71805024e-01 -1.71407580e-01 7.16516197e-01 -6.76232100e-01 -1.71407878e-01 7.12331772e-01 -6.80590630e-01 -1.71407387e-01 7.08129942e-01 -6.84941351e-01 -1.71321824e-01 7.03919291e-01 -6.89270079e-01 -1.71395048e-01 6.99694157e-01 -6.93580329e-01 -1.71398580e-01 6.95395529e-01 -6.97888613e-01 -1.71405897e-01 6.91131592e-01 -7.02114344e-01 -1.71415851e-01 6.86811566e-01 -7.06340730e-01 -1.71424493e-01 6.82470143e-01 -7.10549474e-01 -1.71415508e-01 6.78074777e-01 -7.14743912e-01 -1.71351269e-01 6.73704565e-01 -7.18869925e-01 -1.71361417e-01 6.69273853e-01 -7.23023891e-01 -1.71367377e-01 6.64826095e-01 -7.27120519e-01 -1.71351343e-01 6.60356224e-01 -7.31193364e-01 -1.71336576e-01 6.55834854e-01 -7.35196829e-01 -1.71346426e-01 6.51339173e-01 -7.39202082e-01 -1.71315119e-01 6.46788299e-01 -7.43225932e-01 -1.71320453e-01 6.42213166e-01 -7.47135222e-01 -1.71348676e-01 6.37623727e-01 -7.51073360e-01 -1.71333730e-01 6.32975340e-01 -7.55006850e-01 -1.71330497e-01 6.28362477e-01 -7.58868277e-01 -1.71331152e-01 6.23688996e-01 -7.62708485e-01 -1.71330437e-01 6.18992925e-01 -7.66483486e-01 -1.71343952e-01 6.14283323e-01 -7.70302534e-01 -1.71339825e-01 6.09520197e-01 -7.74038434e-01 -1.71341598e-01 6.04777813e-01 -7.77760744e-01 -1.71380594e-01 5.99996924e-01 -7.81478941e-01 -1.71362624e-01 5.95184743e-01 -7.85110354e-01 -1.71396852e-01 5.90345204e-01 -7.88727105e-01 -1.71389401e-01 5.85477829e-01 -7.92334855e-01 -1.71352834e-01 5.80624342e-01 -7.95923471e-01 -1.71347409e-01 5.75710595e-01 -7.99499810e-01 -1.71351790e-01 5.70792377e-01 -8.02999854e-01 -1.71367735e-01 5.65855563e-01 -8.06492150e-01 -1.71375811e-01 5.60909927e-01 -8.09955001e-01 -1.71392590e-01 5.55917442e-01 -8.13338935e-01 -1.71511918e-01 5.50920129e-01 -8.16744268e-01 -1.71464607e-01 5.45889378e-01 -8.20111930e-01 -1.71462387e-01 5.40851831e-01 -8.23445737e-01 -1.71431929e-01 5.35785735e-01 -8.26782346e-01 -1.71432734e-01 5.30713797e-01 -8.30051541e-01 -1.71429083e-01 5.25604606e-01 -8.33296716e-01 -1.71431497e-01 5.20486832e-01 -8.36471677e-01 -1.71445966e-01 5.15331805e-01 -8.39664578e-01 -1.71507314e-01 5.10153890e-01 -8.42776835e-01 -1.71632767e-01 5.04975498e-01 -8.45901012e-01 -1.71632200e-01 4.99784887e-01 -8.48998964e-01 -1.71622530e-01 4.94563133e-01 -8.52039039e-01 -1.71618193e-01 4.89334583e-01 -8.55049908e-01 -1.71593964e-01 4.84069347e-01 -8.58053923e-01 -1.71586528e-01 4.78804439e-01 -8.60972941e-01 -1.71613604e-01 4.73512679e-01 -8.63923430e-01 -1.71622202e-01 4.68185842e-01 -8.66821826e-01 -1.71615958e-01 4.62875575e-01 -8.69665861e-01 -1.71633899e-01 4.57524836e-01 -8.72483492e-01 -1.71634167e-01 4.52168733e-01 -8.75260174e-01 -1.71609774e-01 4.46774125e-01 -8.78021598e-01 -1.71626508e-01 4.41397309e-01 -8.80775273e-01 -1.71615988e-01 4.35984284e-01 -8.83432329e-01 -1.71630144e-01 4.30535883e-01 -8.86095285e-01 -1.71626225e-01 4.25104648e-01 -8.88718128e-01 -1.71636894e-01 4.19641405e-01 -8.91336381e-01 -1.71633363e-01 4.14165556e-01 -8.93885016e-01 -1.71632111e-01 4.08670962e-01 -8.96415412e-01 -1.71582684e-01 4.03168529e-01 -8.98920059e-01 -1.71528950e-01 3.97641480e-01 -9.01355028e-01 -1.71516225e-01 3.92105937e-01 -9.03767347e-01 -1.71525210e-01 3.86556923e-01 -9.06175077e-01 -1.71503305e-01 3.81002694e-01 -9.08567250e-01 -1.71287805e-01 3.75420362e-01 -9.10903573e-01 -1.71235412e-01 3.69830012e-01 -9.13197458e-01 -1.71194091e-01 3.64227563e-01 -9.15458739e-01 -1.71079174e-01 3.58610451e-01 -9.17686820e-01 -1.70990348e-01 3.52981120e-01 -9.19895709e-01 -1.70858234e-01 3.47333759e-01 -9.22054172e-01 -1.70807034e-01 3.41673821e-01 -9.24181044e-01 -1.70737743e-01 3.36008072e-01 -9.26286399e-01 -1.70562729e-01 3.30351859e-01 -9.28416073e-01 -1.70023233e-01 3.24737340e-01 -9.30655062e-01 -1.68582961e-01 3.18977863e-01 -9.32516575e-01 -1.69308618e-01 3.13500047e-01 -9.35129702e-01 -1.65076151e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.78598547e-01 -9.45217550e-01 -1.70126557e-01 2.72757679e-01 -9.46799695e-01 -1.70807466e-01 2.66941726e-01 -9.48449850e-01 -1.70833230e-01 2.61113733e-01 -9.50061381e-01 -1.70902655e-01 2.55285800e-01 -9.51661885e-01 -1.70781240e-01 2.49437392e-01 -9.53197598e-01 -1.70859456e-01 2.43583024e-01 -9.54709709e-01 -1.70882970e-01 2.37720132e-01 -9.56183434e-01 -1.70888096e-01 2.31848717e-01 -9.57623839e-01 -1.70886949e-01 2.25968421e-01 -9.59028304e-01 -1.70888439e-01 0. 0. 0. 2.15548441e-01 -9.66988027e-01 -1.35915220e-01 0. 0. 0. 0. 0. 0. 1.96507841e-01 -9.65777755e-01 -1.69268444e-01 1.90528676e-01 -9.66748416e-01 -1.70563042e-01 1.84587494e-01 -9.67876196e-01 -1.70726448e-01 1.78638905e-01 -9.68951643e-01 -1.70903042e-01 1.72679663e-01 -9.69979227e-01 -1.71146080e-01 1.66720852e-01 -9.71022010e-01 -1.71233833e-01 1.60757944e-01 -9.71981704e-01 -1.71357021e-01 1.54788300e-01 -9.72956598e-01 -1.71400383e-01 1.48815557e-01 -9.73882914e-01 -1.71446279e-01 1.42836466e-01 -9.74752545e-01 -1.71463519e-01 1.36852846e-01 -9.75657403e-01 -1.71450242e-01 1.30862281e-01 -9.76435006e-01 -1.71458483e-01 1.24869339e-01 -9.77246881e-01 -1.71464428e-01 1.18870169e-01 -9.77976501e-01 -1.71449110e-01 1.12866037e-01 -9.78693366e-01 -1.71456471e-01 1.06859595e-01 -9.79387581e-01 -1.71468645e-01 1.00848027e-01 -9.80012953e-01 -1.71450183e-01 9.48329046e-02 -9.80613470e-01 -1.71459243e-01 8.88136253e-02 -9.81189668e-01 -1.71446532e-01 8.27918872e-02 -9.81700838e-01 -1.71451882e-01 7.67681971e-02 -9.82182741e-01 -1.71471640e-01 7.07391128e-02 -9.82651532e-01 -1.71490312e-01 6.47078529e-02 -9.83045101e-01 -1.71491161e-01 5.86753041e-02 -9.83411968e-01 -1.71488985e-01 5.26400805e-02 -9.83767152e-01 -1.71455681e-01 4.66026403e-02 -9.84097362e-01 -1.71461046e-01 4.05629985e-02 -9.84346151e-01 -1.71453938e-01 3.45228761e-02 -9.84588623e-01 -1.71444446e-01 2.84810979e-02 -9.84799147e-01 -1.71445325e-01 2.24380437e-02 -9.84945774e-01 -1.71446219e-01 1.63938291e-02 -9.85064089e-01 -1.71445698e-01 1.03495158e-02 -9.85159099e-01 -1.71439841e-01 4.30466561e-03 -9.85189259e-01 -1.71435848e-01 -1.74026785e-03 -9.85192597e-01 -1.71421707e-01 -7.78524438e-03 -9.85170662e-01 -1.71417534e-01 -1.38298590e-02 -9.85083103e-01 -1.71405256e-01 -1.98741797e-02 -9.84978497e-01 -1.71418279e-01 -2.59176157e-02 -9.84838068e-01 -1.71426281e-01 -3.19599025e-02 -9.84684110e-01 -1.71433866e-01 -3.80011126e-02 -9.84468043e-01 -1.71431199e-01 -4.40414734e-02 -9.84222949e-01 -1.71429589e-01 -5.00792190e-02 -9.83901262e-01 -1.71427101e-01 -5.61152883e-02 -9.83605087e-01 -1.71427146e-01 -6.21495396e-02 -9.83244002e-01 -1.71421871e-01 -6.81816339e-02 -9.82816279e-01 -1.71416998e-01 -7.42113665e-02 -9.82405365e-01 -1.71422616e-01 -8.02383572e-02 -9.81940508e-01 -1.71425000e-01 -8.62604007e-02 -9.81434703e-01 -1.71436995e-01 -9.22815576e-02 -9.80870008e-01 -1.71409786e-01 -9.82973501e-02 -9.80258465e-01 -1.71493188e-01 -1.04310006e-01 -9.79638100e-01 -1.71575963e-01 -1.10316567e-01 -9.78935421e-01 -1.71622604e-01 -1.16322152e-01 -9.78270531e-01 -1.71639159e-01 -1.22322507e-01 -9.77541506e-01 -1.71658352e-01 -1.28318429e-01 -9.76743460e-01 -1.71662807e-01 -1.34307191e-01 -9.76000786e-01 -1.71578795e-01 -1.40294522e-01 -9.75134373e-01 -1.71645060e-01 -1.46273136e-01 -9.74238098e-01 -1.71651378e-01 -1.52249783e-01 -9.73345399e-01 -1.71667203e-01 -1.58220440e-01 -9.72387910e-01 -1.71663955e-01 -1.64183438e-01 -9.71367896e-01 -1.71664551e-01 -1.70140788e-01 -9.70377564e-01 -1.71566010e-01 -1.76092505e-01 -9.69297171e-01 -1.71578884e-01 -1.82039231e-01 -9.68200147e-01 -1.71606421e-01 -1.87971190e-01 -9.67078149e-01 -1.71629563e-01 -1.93901509e-01 -9.65905428e-01 -1.71628892e-01 -1.99825332e-01 -9.64700103e-01 -1.71597853e-01 -2.05739781e-01 -9.63425338e-01 -1.71614811e-01 -2.11655244e-01 -9.62172925e-01 -1.71591505e-01 -2.17548758e-01 -9.60862279e-01 -1.71659708e-01 -2.23441660e-01 -9.59511161e-01 -1.71646133e-01 -2.29326010e-01 -9.58088458e-01 -1.71655744e-01 -2.35200688e-01 -9.56677854e-01 -1.71622545e-01 -2.41062120e-01 -9.55202758e-01 -1.71623513e-01 -2.46923655e-01 -9.53733623e-01 -1.71622023e-01 -2.52769440e-01 -9.52208161e-01 -1.71617463e-01 -2.58613259e-01 -9.50618327e-01 -1.71579763e-01 -2.64443785e-01 -9.49033320e-01 -1.71567887e-01 -2.70253927e-01 -9.47386503e-01 -1.71598375e-01 -2.76059121e-01 -9.45714593e-01 -1.71623200e-01 -2.81860173e-01 -9.44014192e-01 -1.71612263e-01 -2.87650406e-01 -9.42248166e-01 -1.71602070e-01 -2.93426186e-01 -9.40434694e-01 -1.71640173e-01 -2.99191833e-01 -9.38649654e-01 -1.71589524e-01 -3.04937780e-01 -9.36805844e-01 -1.71557993e-01 -3.10687214e-01 -9.34902668e-01 -1.71587825e-01 -3.16409171e-01 -9.32979405e-01 -1.71581015e-01 -3.22128296e-01 -9.31036592e-01 -1.71598047e-01 -3.27834338e-01 -9.29038048e-01 -1.71590477e-01 -3.33538979e-01 -9.26976025e-01 -1.71570465e-01 -3.39208961e-01 -9.24932063e-01 -1.71570420e-01 -3.44891548e-01 -9.22852874e-01 -1.71562374e-01 -3.50555778e-01 -9.20735478e-01 -1.71433970e-01 -3.56190115e-01 -9.18567955e-01 -1.71431899e-01 -3.61802578e-01 -9.16347921e-01 -1.71659529e-01 -3.67424846e-01 -9.14060473e-01 -1.71660528e-01 -3.73031348e-01 -9.11800563e-01 -1.71665266e-01 -3.78620446e-01 -9.09488678e-01 -1.71656340e-01 -3.84180635e-01 -9.07159984e-01 -1.71648636e-01 -3.89754117e-01 -9.04809773e-01 -1.71629518e-01 -3.95291358e-01 -9.02402937e-01 -1.71631575e-01 -4.00843143e-01 -8.99988055e-01 -1.71317920e-01 -4.06364381e-01 -8.97503793e-01 -1.71318844e-01 -4.11856145e-01 -8.95013928e-01 -1.71332926e-01 -4.17306244e-01 -8.92398417e-01 -1.71651751e-01 -4.22782123e-01 -8.89832318e-01 -1.71654195e-01 -4.28239882e-01 -8.87242079e-01 -1.71659648e-01 -4.33660269e-01 -8.84595394e-01 -1.71659887e-01 -4.39077824e-01 -8.81892443e-01 -1.71655655e-01 -4.44492936e-01 -8.79215658e-01 -1.71560124e-01 -4.49884742e-01 -8.76440763e-01 -1.71659097e-01 -4.55251217e-01 -8.73658240e-01 -1.71640515e-01 -4.60596740e-01 -8.70872855e-01 -1.71585172e-01 -4.65938836e-01 -8.68036568e-01 -1.71531692e-01 -4.71260995e-01 -8.65151823e-01 -1.71559453e-01 -4.76558536e-01 -8.62262487e-01 -1.71540722e-01 -4.81844902e-01 -8.59297156e-01 -1.71551540e-01 -4.87105459e-01 -8.56347442e-01 -1.71509951e-01 -4.92347062e-01 -8.53343904e-01 -1.71542853e-01 -4.97576922e-01 -8.50264251e-01 -1.71538785e-01 -5.02795219e-01 -8.47222686e-01 -1.71533376e-01 -5.07977784e-01 -8.44120502e-01 -1.71527743e-01 -5.13149202e-01 -8.40979695e-01 -1.71530396e-01 -5.18304288e-01 -8.37831557e-01 -1.71538234e-01 -5.23419142e-01 -8.34620118e-01 -1.71528071e-01 -5.28544545e-01 -8.31397355e-01 -1.71536848e-01 -5.33625901e-01 -8.28131616e-01 -1.71506226e-01 -5.38691759e-01 -8.24859917e-01 -1.71512887e-01 -5.43744326e-01 -8.21524620e-01 -1.71495512e-01 -5.48777759e-01 -8.18171382e-01 -1.71492204e-01 -5.53803325e-01 -8.14791739e-01 -1.71477348e-01 -5.58780968e-01 -8.11402917e-01 -1.71462193e-01 -5.63764274e-01 -8.07937801e-01 -1.71442002e-01 -5.68715155e-01 -8.04465532e-01 -1.71438932e-01 -5.73645592e-01 -8.00962806e-01 -1.71431839e-01 -5.78550637e-01 -7.97463357e-01 -1.71413466e-01 -5.83450556e-01 -7.93926835e-01 -1.71003938e-01 -5.88329852e-01 -7.90319920e-01 -1.71026647e-01 -5.93133569e-01 -7.86654115e-01 -1.71363309e-01 -5.97943842e-01 -7.83014834e-01 -1.71383083e-01 -6.02733493e-01 -7.79314756e-01 -1.71359345e-01 -6.07490122e-01 -7.75593221e-01 -1.71359330e-01 -6.12255991e-01 -7.71857619e-01 -1.71363950e-01 -6.16962314e-01 -7.68108249e-01 -1.71371564e-01 -6.21658444e-01 -7.64284611e-01 -1.71393067e-01 -6.26344025e-01 -7.60456622e-01 -1.71348691e-01 -6.31018579e-01 -7.56597996e-01 -1.71330333e-01 -6.35630012e-01 -7.52737164e-01 -1.71326816e-01 -6.40261114e-01 -7.48801589e-01 -1.71327814e-01 -6.44844592e-01 -7.44892955e-01 -1.71311080e-01 -6.49405837e-01 -7.40928829e-01 -1.71282724e-01 -6.53925538e-01 -7.36908019e-01 -1.71260238e-01 -6.58452988e-01 -7.32901156e-01 -1.71247736e-01 -6.62919223e-01 -7.28828788e-01 -1.71226904e-01 -6.67376995e-01 -7.24744976e-01 -1.71209276e-01 -6.71818137e-01 -7.20648408e-01 -1.71209365e-01 -6.76237404e-01 -7.16523170e-01 -1.71176344e-01 -6.80616617e-01 -7.12357521e-01 -1.71142310e-01 -6.84985578e-01 -7.08160698e-01 -1.71134874e-01 -6.89314723e-01 -7.03949809e-01 -1.71110660e-01 -6.93624020e-01 -6.99727654e-01 -1.71087340e-01 -6.97919548e-01 -6.95443928e-01 -1.71087191e-01 -7.02144504e-01 -6.91155612e-01 -1.71093449e-01 -7.06375182e-01 -6.86831355e-01 -1.71123326e-01 -7.10577130e-01 -6.82490468e-01 -1.71147957e-01 -7.14754164e-01 -6.78084612e-01 -1.71186447e-01 -7.18879938e-01 -6.73711836e-01 -1.71213880e-01 -7.23038435e-01 -6.69290721e-01 -1.71237335e-01 -7.27133334e-01 -6.64840400e-01 -1.71239108e-01 -7.31198132e-01 -6.60364032e-01 -1.71225354e-01 -7.35206783e-01 -6.55852258e-01 -1.71224564e-01 -7.39228725e-01 -6.51343286e-01 -1.71187609e-01 -7.43225574e-01 -6.46795928e-01 -1.71163991e-01 -7.47158885e-01 -6.42225564e-01 -1.71155110e-01 -7.51082242e-01 -6.37629807e-01 -1.71159223e-01 -7.54999995e-01 -6.32973492e-01 -1.71254620e-01 -7.58832514e-01 -6.28331959e-01 -1.71365812e-01 -7.62679458e-01 -6.23666763e-01 -1.71355546e-01 -7.66480565e-01 -6.18968964e-01 -1.71340808e-01 -7.70283222e-01 -6.14258528e-01 -1.71326220e-01 -7.74025857e-01 -6.09516084e-01 -1.71286657e-01 -7.77756572e-01 -6.04759097e-01 -1.71262071e-01 -7.81471670e-01 -5.99994898e-01 -1.71222493e-01 -7.85132408e-01 -5.95186174e-01 -1.71199307e-01 -7.88797855e-01 -5.90368807e-01 -1.71017632e-01 -7.92402148e-01 -5.85522473e-01 -1.71040237e-01 -7.95967996e-01 -5.80650389e-01 -1.71029344e-01 -7.99526513e-01 -5.75754583e-01 -1.71025380e-01 -8.03048372e-01 -5.70842862e-01 -1.71035230e-01 -8.06516230e-01 -5.65876961e-01 -1.71241030e-01 -8.09958816e-01 -5.60921550e-01 -1.71283811e-01 -8.13382626e-01 -5.55942118e-01 -1.71164215e-01 -8.16774011e-01 -5.50942779e-01 -1.71198636e-01 -8.20135534e-01 -5.45910537e-01 -1.71230137e-01 -8.23473394e-01 -5.40873826e-01 -1.71253487e-01 -8.26799631e-01 -5.35803974e-01 -1.71244040e-01 -8.30087006e-01 -5.30740738e-01 -1.71183020e-01 -8.33337605e-01 -5.25639355e-01 -1.71144068e-01 -8.36553752e-01 -5.20527065e-01 -1.71006858e-01 -8.39799345e-01 -5.15432060e-01 -1.70463920e-01 -8.43062222e-01 -5.10343492e-01 -1.69681892e-01 -8.46583247e-01 -5.05420983e-01 -1.66839972e-01 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. 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. -8.98838878e-01 -4.03132766e-01 -1.71967000e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.11976635e-01 -3.75909060e-01 -1.64288551e-01 -9.14211988e-01 -3.70282352e-01 -1.64643377e-01 -9.16491091e-01 -3.64676446e-01 -1.64483815e-01 -9.18799579e-01 -3.59083921e-01 -1.63908735e-01 0. 0. 0. 0. 0. 0. -9.24326062e-01 -3.41733724e-01 -1.69821501e-01 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. 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. 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. 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. 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. -9.62149918e-01 1.75180063e-01 -2.08757162e-01 -9.61557150e-01 1.81161731e-01 -2.06368804e-01 -9.60434854e-01 1.87058419e-01 -2.06356347e-01 -9.59222317e-01 1.92943096e-01 -2.06505433e-01 -9.57985818e-01 1.98817924e-01 -2.06692025e-01 -9.56757724e-01 2.04691753e-01 -2.06716761e-01 -9.55516219e-01 2.10568026e-01 -2.06509575e-01 -9.54259336e-01 2.16436863e-01 -2.06245944e-01 -9.52918947e-01 2.22287923e-01 -2.06234112e-01 -9.51630294e-01 2.28150696e-01 -2.05783874e-01 0. 0. 0. -9.49568510e-01 2.39994183e-01 -2.01798171e-01 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. 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. 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. 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. 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. -8.41509998e-01 4.99818176e-01 -2.05042198e-01 -8.38259816e-01 5.04875898e-01 -2.05963954e-01 -8.35090637e-01 5.09973764e-01 -2.06321150e-01 -8.31881821e-01 5.15063643e-01 -2.06606165e-01 -8.28622222e-01 5.20106912e-01 -2.06987232e-01 -8.25426400e-01 5.25173366e-01 -2.07143039e-01 -8.22145224e-01 5.30223966e-01 -2.07177848e-01 -8.18886757e-01 5.35252333e-01 -2.07158267e-01 -8.15606236e-01 5.40280461e-01 -2.07080841e-01 -8.12316239e-01 5.45302570e-01 -2.06867442e-01 -8.08986306e-01 5.50291300e-01 -2.06698656e-01 -8.05623949e-01 5.55268943e-01 -2.06498757e-01 -8.02261889e-01 5.60237348e-01 -2.06189364e-01 -7.98845768e-01 5.65174043e-01 -2.05974683e-01 -7.95295894e-01 5.70019603e-01 -2.06353322e-01 0. 0. 0. 0. 0. 0. -7.84404516e-01 5.84375083e-01 -2.07882985e-01 -7.80957460e-01 5.89286804e-01 -2.06992015e-01 -7.77359843e-01 5.94091237e-01 -2.06800908e-01 -7.73711443e-01 5.98858058e-01 -2.06732616e-01 -7.70013750e-01 6.03590131e-01 -2.06774220e-01 -7.66324282e-01 6.08319104e-01 -2.06640616e-01 -7.62538493e-01 6.12986684e-01 -2.06835285e-01 -7.58768320e-01 6.17653787e-01 -2.06830859e-01 -7.54956126e-01 6.22289062e-01 -2.06864253e-01 -7.51068532e-01 6.26877725e-01 -2.07135662e-01 -7.47200131e-01 6.31458223e-01 -2.07275391e-01 -7.43285596e-01 6.36014938e-01 -2.07349673e-01 -7.39384651e-01 6.40549898e-01 -2.07397968e-01 -7.35438466e-01 6.45102143e-01 -2.07267910e-01 -7.31457353e-01 6.49596930e-01 -2.07287803e-01 -7.27468550e-01 6.54077411e-01 -2.07232609e-01 -7.23450661e-01 6.58537447e-01 -2.07236066e-01 -7.19414055e-01 6.62975073e-01 -2.07139164e-01 -7.15334594e-01 6.67379737e-01 -2.07125008e-01 -7.11352706e-01 6.71870410e-01 -2.06319258e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.86110795e-01 6.97568953e-01 -2.06516489e-01 -6.81776047e-01 7.01724827e-01 -2.06793323e-01 -6.77472472e-01 7.05908656e-01 -2.06708148e-01 -6.73135757e-01 7.10063159e-01 -2.06651941e-01 -6.68762565e-01 7.14169979e-01 -2.06665844e-01 -6.64353609e-01 7.18255639e-01 -2.06737682e-01 -6.59927249e-01 7.22314715e-01 -2.06774041e-01 -6.55483782e-01 7.26341546e-01 -2.06794485e-01 -6.51011467e-01 7.30340779e-01 -2.06853956e-01 -6.46513104e-01 7.34309316e-01 -2.06923857e-01 -6.41974449e-01 7.38247037e-01 -2.07023174e-01 -6.37410223e-01 7.42171288e-01 -2.07129046e-01 -6.32818401e-01 7.46023357e-01 -2.07229257e-01 -6.28261149e-01 7.49928057e-01 -2.07243234e-01 -6.23615623e-01 7.53752768e-01 -2.07311273e-01 -6.18961692e-01 7.57550836e-01 -2.07367957e-01 -6.14302754e-01 7.61300266e-01 -2.07406685e-01 -6.09620452e-01 7.65085578e-01 -2.07424507e-01 -6.04930937e-01 7.68797159e-01 -2.07413912e-01 -6.00186884e-01 7.72493958e-01 -2.07413971e-01 -5.95445156e-01 7.76191890e-01 -2.07382306e-01 -5.90658009e-01 7.79788852e-01 -2.07397863e-01 -5.85873067e-01 7.83400774e-01 -2.07361639e-01 -5.81079841e-01 7.86992252e-01 -2.07321987e-01 -5.76227605e-01 7.90555000e-01 -2.07300052e-01 -5.71364284e-01 7.94086277e-01 -2.07343489e-01 -5.66479921e-01 7.97578156e-01 -2.07346633e-01 -5.61572254e-01 8.01036119e-01 -2.07363993e-01 -5.56632340e-01 8.04453373e-01 -2.07386971e-01 -5.51692605e-01 8.07837307e-01 -2.07406238e-01 -5.46711326e-01 8.11185181e-01 -2.07445055e-01 -5.41739225e-01 8.14527929e-01 -2.07458198e-01 -5.36727726e-01 8.17849398e-01 -2.07472429e-01 -5.31702697e-01 8.21106136e-01 -2.07464367e-01 -5.26628375e-01 8.24396372e-01 -2.07491696e-01 -5.21580637e-01 8.27553749e-01 -2.07504734e-01 -5.16471684e-01 8.30761373e-01 -2.07543388e-01 -5.11362553e-01 8.33944321e-01 -2.07552209e-01 -5.06244421e-01 8.37054610e-01 -2.07559168e-01 -5.01090407e-01 8.40151429e-01 -2.07565129e-01 -4.95927751e-01 8.43182147e-01 -2.07573161e-01 -4.90758300e-01 8.46228242e-01 -2.07577884e-01 -4.85536635e-01 8.49226177e-01 -2.07582057e-01 -4.80315477e-01 8.52136195e-01 -2.07626268e-01 -4.75091994e-01 8.55084658e-01 -2.07607195e-01 -4.69827026e-01 8.57970834e-01 -2.07680583e-01 -4.64544952e-01 8.60841215e-01 -2.07694903e-01 -4.59251791e-01 8.63684416e-01 -2.07702160e-01 -4.53950971e-01 8.66448641e-01 -2.07707301e-01 -4.48618144e-01 8.69267821e-01 -2.07696795e-01 -4.43283916e-01 8.71995151e-01 -2.07694188e-01 -4.37920779e-01 8.74685287e-01 -2.07697898e-01 -4.32547152e-01 8.77382338e-01 -2.07702458e-01 -4.27163512e-01 8.80014420e-01 -2.07702428e-01 -4.21748430e-01 8.82583797e-01 -2.07702100e-01 -4.16322172e-01 8.85181129e-01 -2.07705736e-01 -4.10881102e-01 8.87683034e-01 -2.07717553e-01 -4.05432850e-01 8.90202343e-01 -2.07729638e-01 -3.99958760e-01 8.92682254e-01 -2.07742631e-01 -3.94468039e-01 8.95092130e-01 -2.07742408e-01 -3.88970762e-01 8.97483349e-01 -2.07753509e-01 -3.83467793e-01 8.99868488e-01 -2.07744569e-01 -3.77925754e-01 9.02232826e-01 -2.07734734e-01 -3.72382194e-01 9.04528856e-01 -2.07728058e-01 -3.66823196e-01 9.06778514e-01 -2.07734853e-01 -3.61263961e-01 9.09021854e-01 -2.07745805e-01 -3.55667919e-01 9.11224604e-01 -2.07743689e-01 -3.50109518e-01 9.13435459e-01 -2.07442775e-01 -3.44496399e-01 9.15569067e-01 -2.07448632e-01 -3.38822901e-01 9.17595446e-01 -2.07882285e-01 -3.33192974e-01 9.19640303e-01 -2.07888499e-01 -3.27538937e-01 9.21670854e-01 -2.07899496e-01 -3.21891278e-01 9.23688173e-01 -2.07829982e-01 -3.16217542e-01 9.25635338e-01 -2.07805187e-01 -3.10533553e-01 9.27554667e-01 -2.07779139e-01 -3.04837674e-01 9.29455519e-01 -2.07766250e-01 -2.99131781e-01 9.31326270e-01 -2.07744122e-01 -2.93411851e-01 9.33154404e-01 -2.07716331e-01 -2.87677467e-01 9.34917033e-01 -2.07756564e-01 -2.81935543e-01 9.36645687e-01 -2.07800552e-01 -2.76180446e-01 9.38376844e-01 -2.07833841e-01 -2.70414799e-01 9.40046549e-01 -2.07848355e-01 -2.64638960e-01 9.41654027e-01 -2.07845271e-01 -2.58862525e-01 9.43296313e-01 -2.07830846e-01 -2.53068686e-01 9.44851279e-01 -2.07834736e-01 -2.47263461e-01 9.46392298e-01 -2.07884267e-01 -2.41449431e-01 9.47887599e-01 -2.07902700e-01 -2.35632196e-01 9.49356377e-01 -2.07901418e-01 -2.29795799e-01 9.50775504e-01 -2.07902104e-01 -2.23964453e-01 9.52146649e-01 -2.07894236e-01 -2.18117520e-01 9.53533947e-01 -2.07886934e-01 -2.12264702e-01 9.54864323e-01 -2.07848355e-01 -2.06396073e-01 9.56163406e-01 -2.07833350e-01 -2.00535372e-01 9.57401156e-01 -2.07768470e-01 -1.94657907e-01 9.58611906e-01 -2.07723930e-01 -1.88772663e-01 9.59801078e-01 -2.07709417e-01 -1.82874680e-01 9.60957348e-01 -2.07733184e-01 -1.76977932e-01 9.62054074e-01 -2.07744926e-01 -1.71071783e-01 9.63119447e-01 -2.07752779e-01 -1.65158287e-01 9.64112520e-01 -2.07765177e-01 -1.59236535e-01 9.65135932e-01 -2.07737476e-01 -1.53315559e-01 9.66102004e-01 -2.07752749e-01 -1.47380292e-01 9.66978371e-01 -2.07786709e-01 -1.41444281e-01 9.67906356e-01 -2.07781672e-01 -1.35502845e-01 9.68764007e-01 -2.07777038e-01 -1.29558325e-01 9.69574094e-01 -2.07783431e-01 -1.23606808e-01 9.70311940e-01 -2.07813874e-01 -1.17647693e-01 9.71084416e-01 -2.07803071e-01 -1.11687608e-01 9.71742630e-01 -2.07829610e-01 -1.05720647e-01 9.72430229e-01 -2.07842559e-01 -9.97533128e-02 9.73067939e-01 -2.07853362e-01 -9.37804654e-02 9.73649919e-01 -2.07827777e-01 -8.78070965e-02 9.74208236e-01 -2.07810178e-01 -8.18252489e-02 9.74744916e-01 -2.07820773e-01 -7.58435950e-02 9.75217223e-01 -2.07849368e-01 -6.98581785e-02 9.75679398e-01 -2.07842365e-01 -6.38704374e-02 9.76088047e-01 -2.07840800e-01 -5.78808337e-02 9.76471543e-01 -2.07838461e-01 -5.18881045e-02 9.76758540e-01 -2.07817897e-01 -4.58940491e-02 9.77070987e-01 -2.07820117e-01 -3.98973487e-02 9.77355540e-01 -2.07826331e-01 -3.38996686e-02 9.77585614e-01 -2.07847178e-01 -2.79006083e-02 9.77761090e-01 -2.07853347e-01 -2.19006501e-02 9.77919579e-01 -2.07861036e-01 -1.58996843e-02 9.78015840e-01 -2.07861543e-01 -9.89858247e-03 9.78136778e-01 -2.07841724e-01 -3.89652001e-03 9.78147268e-01 -2.07901791e-01 2.10541277e-03 9.78144050e-01 -2.07923263e-01 8.10690690e-03 9.78139699e-01 -2.07853630e-01 1.41084874e-02 9.78061974e-01 -2.07858190e-01 2.01092493e-02 9.77948189e-01 -2.07808375e-01 2.61094850e-02 9.77832019e-01 -2.07804099e-01 3.21088657e-02 9.77668405e-01 -2.07802579e-01 3.81067656e-02 9.77444708e-01 -2.07810596e-01 4.41038683e-02 9.77182150e-01 -2.07842097e-01 5.00983596e-02 9.76860106e-01 -2.07868412e-01 5.60909584e-02 9.76560175e-01 -2.07854584e-01 6.20818287e-02 9.76166546e-01 -2.07840651e-01 6.80711120e-02 9.75768507e-01 -2.07855836e-01 7.40567073e-02 9.75314140e-01 -2.07852706e-01 8.00406784e-02 9.74885762e-01 -2.07866341e-01 8.60196352e-02 9.74349260e-01 -2.07853854e-01 9.19979215e-02 9.73830938e-01 -2.07852349e-01 9.79694575e-02 9.73231256e-01 -2.07865760e-01 1.03939451e-01 9.72629189e-01 -2.07866639e-01 1.09907232e-01 9.71935987e-01 -2.07880840e-01 1.15866221e-01 9.71240103e-01 -2.07883760e-01 1.21821977e-01 9.70506728e-01 -2.07892254e-01 1.27777830e-01 9.69778836e-01 -2.07883671e-01 1.33726716e-01 9.68959808e-01 -2.07891300e-01 1.39669016e-01 9.68116820e-01 -2.07882047e-01 1.45608246e-01 9.67253387e-01 -2.07876682e-01 1.51539177e-01 9.66331363e-01 -2.07884908e-01 1.57462925e-01 9.65381563e-01 -2.07872480e-01 1.63384572e-01 9.64405537e-01 -2.07891434e-01 1.69300765e-01 9.63357449e-01 -2.07915530e-01 1.75205603e-01 9.62348938e-01 -2.07912251e-01 1.81106657e-01 9.61219311e-01 -2.07868055e-01 1.87006891e-01 9.60129201e-01 -2.07818657e-01 1.92897469e-01 9.58952367e-01 -2.07796648e-01 1.98779553e-01 9.57761645e-01 -2.07746848e-01 2.04652697e-01 9.56543446e-01 -2.07663283e-01 2.10522607e-01 9.55293715e-01 -2.07566038e-01 2.16387108e-01 9.54014838e-01 -2.07415387e-01 2.22255513e-01 9.52759564e-01 -2.06992254e-01 2.28155375e-01 9.51653779e-01 -2.05661491e-01 2.34065205e-01 9.50576007e-01 -2.03998610e-01 2.39932373e-01 9.49294865e-01 -2.03152567e-01 2.45778888e-01 9.47917700e-01 -2.02593639e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.80227900e-01 9.37217057e-01 -2.07596615e-01 2.85963386e-01 9.35445249e-01 -2.07766891e-01 2.91695595e-01 9.33661282e-01 -2.07816541e-01 2.97416389e-01 9.31851745e-01 -2.07862750e-01 3.03128988e-01 9.30001557e-01 -2.07873031e-01 3.08825642e-01 9.28123236e-01 -2.07888797e-01 3.14517766e-01 9.26217258e-01 -2.07867384e-01 3.20199072e-01 9.24278557e-01 -2.07802087e-01 3.25868070e-01 9.22309816e-01 -2.07734972e-01 3.31531137e-01 9.20322895e-01 -2.07587838e-01 3.37555259e-01 9.19410229e-01 -2.01409638e-01 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. 3.93304527e-01 8.96988988e-01 -2.01797694e-01 3.98722023e-01 8.94368887e-01 -2.02791587e-01 4.04185146e-01 8.91865075e-01 -2.03003168e-01 4.09571588e-01 8.89186144e-01 -2.03949437e-01 4.14978445e-01 8.86561751e-01 -2.04445004e-01 4.20365602e-01 8.83897603e-01 -2.04973876e-01 4.25759703e-01 8.81254375e-01 -2.05221295e-01 4.31212783e-01 8.78742874e-01 -2.04578042e-01 4.36533809e-01 8.75945807e-01 -2.05310330e-01 4.41860229e-01 8.73166323e-01 -2.05757573e-01 4.47268516e-01 8.70561421e-01 -2.05066428e-01 4.52624768e-01 8.67847502e-01 -2.04825535e-01 4.57893759e-01 8.64958167e-01 -2.05370098e-01 4.63224053e-01 8.62195015e-01 -2.05016628e-01 4.68655586e-01 8.59629393e-01 -2.03404203e-01 4.74017352e-01 8.56922567e-01 -2.02377677e-01 4.79566246e-01 8.54566455e-01 -1.99212402e-01 4.85330522e-01 8.52599859e-01 -1.93476230e-01 4.90084887e-01 8.48742306e-01 -1.98503494e-01 4.95279610e-01 8.45712245e-01 -1.98527858e-01 5.00787795e-01 8.43247354e-01 -1.94937691e-01 5.05181611e-01 8.38797092e-01 -2.02891573e-01 5.10496259e-01 8.35990012e-01 -2.01135054e-01 5.15183151e-01 8.32099199e-01 -2.05411807e-01 5.20401359e-01 8.29129398e-01 -2.04177424e-01 5.25280118e-01 8.25589180e-01 -2.06109628e-01 5.30435443e-01 8.22514355e-01 -2.05175266e-01 5.35458148e-01 8.19221020e-01 -2.05286101e-01 5.40429413e-01 8.15847516e-01 -2.05718055e-01 5.45397162e-01 8.12472045e-01 -2.05976754e-01 5.50372541e-01 8.09110403e-01 -2.05981061e-01 5.55230856e-01 8.05568397e-01 -2.06826270e-01 5.60217261e-01 8.02230954e-01 -2.06352726e-01 5.65152466e-01 7.98813403e-01 -2.06151456e-01 5.69970906e-01 7.95224249e-01 -2.06760928e-01 5.74940979e-01 7.91859329e-01 -2.05914438e-01 5.79898059e-01 7.88473189e-01 -2.05003142e-01 5.84639728e-01 7.84779072e-01 -2.05709457e-01 5.89428782e-01 7.81155705e-01 -2.05834612e-01 5.94150245e-01 7.77440190e-01 -2.06327870e-01 5.98894417e-01 7.73760319e-01 -2.06443116e-01 6.03610218e-01 7.70043552e-01 -2.06607714e-01 6.08309090e-01 7.66305149e-01 -2.06726804e-01 6.12986863e-01 7.62540162e-01 -2.06828162e-01 6.17644370e-01 7.58754373e-01 -2.06884742e-01 6.22279346e-01 7.54940689e-01 -2.06961066e-01 6.26890719e-01 7.51094043e-01 -2.07043663e-01 6.31476283e-01 7.47219086e-01 -2.07133755e-01 6.36038303e-01 7.43316531e-01 -2.07199007e-01 6.40583456e-01 7.39394546e-01 -2.07226411e-01 6.45100772e-01 7.35441029e-01 -2.07291201e-01 6.49593949e-01 7.31457651e-01 -2.07366541e-01 6.54055417e-01 7.27441728e-01 -2.07448497e-01 6.58509672e-01 7.23415613e-01 -2.07453936e-01 6.62908554e-01 7.19330549e-01 -2.07616627e-01 6.67310834e-01 7.15259790e-01 -2.07643881e-01 6.71689987e-01 7.11153448e-01 -2.07574159e-01 6.76029861e-01 7.07010329e-01 -2.07675830e-01 6.80341721e-01 7.02832997e-01 -2.07703233e-01 6.84639812e-01 6.98647320e-01 -2.07734749e-01 6.88935578e-01 6.94441378e-01 -2.07620680e-01 6.93172455e-01 6.90197349e-01 -2.07653925e-01 6.97405457e-01 6.85942590e-01 -2.07657814e-01 7.01587081e-01 6.81629241e-01 -2.07720816e-01 7.05739558e-01 6.77310169e-01 -2.07750112e-01 7.09883809e-01 6.72974288e-01 -2.07734436e-01 7.14014828e-01 6.68604791e-01 -2.07713708e-01 7.18116820e-01 6.64219201e-01 -2.07664385e-01 7.22184360e-01 6.59801841e-01 -2.07645699e-01 7.26210058e-01 6.55366361e-01 -2.07635924e-01 7.30220973e-01 6.50900841e-01 -2.07622796e-01 7.34203637e-01 6.46410882e-01 -2.07630977e-01 7.38151670e-01 6.41887009e-01 -2.07626328e-01 7.42102981e-01 6.37352586e-01 -2.07510620e-01 7.45977461e-01 6.32777810e-01 -2.07516402e-01 7.49847829e-01 6.28196478e-01 -2.07615852e-01 7.53692150e-01 6.23575389e-01 -2.07605854e-01 7.57497907e-01 6.18948638e-01 -2.07608148e-01 7.61283159e-01 6.14292204e-01 -2.07607552e-01 7.65050948e-01 6.09595895e-01 -2.07604945e-01 7.68767059e-01 6.04889214e-01 -2.07590878e-01 7.72468984e-01 6.00163698e-01 -2.07582965e-01 7.76137412e-01 5.95429361e-01 -2.07560301e-01 7.79770613e-01 5.90657413e-01 -2.07539245e-01 7.83380747e-01 5.85847974e-01 -2.07550690e-01 7.86961794e-01 5.81042826e-01 -2.07547009e-01 7.90511072e-01 5.76202929e-01 -2.07540751e-01 7.94057190e-01 5.71337402e-01 -2.07523048e-01 7.97550559e-01 5.66451788e-01 -2.07514733e-01 8.01014721e-01 5.61553657e-01 -2.07504183e-01 8.04447591e-01 5.56637228e-01 -2.07486019e-01 8.07836354e-01 5.51688731e-01 -2.07482055e-01 8.11188877e-01 5.46722949e-01 -2.07488760e-01 8.14526021e-01 5.41722715e-01 -2.07505792e-01 8.17858934e-01 5.36717594e-01 -2.07497329e-01 8.21122825e-01 5.31691670e-01 -2.07484022e-01 8.24394047e-01 5.26644647e-01 -2.07476318e-01 8.27554464e-01 5.21575511e-01 -2.07549959e-01 8.30752015e-01 5.16471446e-01 -2.07563862e-01 8.33953083e-01 5.11374176e-01 -2.07453445e-01 8.37073863e-01 5.06262183e-01 -2.07442835e-01 8.40172887e-01 5.01106620e-01 -2.07440495e-01 8.43181789e-01 4.95931894e-01 -2.07550034e-01 8.46236825e-01 4.90764767e-01 -2.07542121e-01 8.49232495e-01 4.85541552e-01 -2.07529366e-01 8.52170050e-01 4.80341852e-01 -2.07479969e-01 8.55122924e-01 4.75098133e-01 -2.07471818e-01 8.58003199e-01 4.69846249e-01 -2.07451135e-01 8.60875189e-01 4.64581937e-01 -2.07432851e-01 8.63727510e-01 4.59283292e-01 -2.07351923e-01 8.66505861e-01 4.53968465e-01 -2.07416654e-01 8.69311631e-01 4.48644340e-01 -2.07426801e-01 8.72054398e-01 4.43319857e-01 -2.07412720e-01 8.74726892e-01 4.37956035e-01 -2.07383603e-01 8.77436459e-01 4.32583213e-01 -2.07369342e-01 8.80070925e-01 4.27195698e-01 -2.07357228e-01 8.82645369e-01 4.21781987e-01 -2.07362354e-01 8.85240495e-01 4.16357160e-01 -2.07358211e-01 8.87771308e-01 4.10919666e-01 -2.07282409e-01 8.90264153e-01 4.05475348e-01 -2.07352847e-01 8.92764688e-01 3.99990559e-01 -2.07346052e-01 8.95155132e-01 3.94492954e-01 -2.07406417e-01 8.97546411e-01 3.88995111e-01 -2.07409710e-01 8.99929106e-01 3.83492887e-01 -2.07408443e-01 9.02295172e-01 3.77951860e-01 -2.07400024e-01 9.04591024e-01 3.72407496e-01 -2.07396507e-01 9.06843424e-01 3.66849452e-01 -2.07394272e-01 9.09086347e-01 3.61289471e-01 -2.07395047e-01 9.11316216e-01 3.55701983e-01 -2.07279995e-01 9.13473964e-01 3.50120485e-01 -2.07266107e-01 9.15590703e-01 3.44506145e-01 -2.07295060e-01 9.17729557e-01 3.38879675e-01 -2.07279593e-01 9.19759691e-01 3.33236873e-01 -2.07289934e-01 9.21810925e-01 3.27584475e-01 -2.07267046e-01 9.23797190e-01 3.21934342e-01 -2.07277417e-01 9.25739229e-01 3.16261262e-01 -2.07227603e-01 9.27653730e-01 3.10563594e-01 -2.07229495e-01 9.29558992e-01 3.04876268e-01 -2.07226828e-01 9.31434274e-01 2.99153179e-01 -2.07289129e-01 9.33232009e-01 2.93438107e-01 -2.07293987e-01 9.35005248e-01 2.87702858e-01 -2.07363993e-01 9.36714292e-01 2.81954080e-01 -2.07360715e-01 9.38441455e-01 2.76205838e-01 -2.07360521e-01 9.40115213e-01 2.70435780e-01 -2.07353532e-01 9.41736579e-01 2.64674485e-01 -2.07349420e-01 9.43385243e-01 2.58887857e-01 -2.07344234e-01 9.44967270e-01 2.53094286e-01 -2.07348958e-01 9.46491718e-01 2.47291997e-01 -2.07338601e-01 9.47978258e-01 2.41484582e-01 -2.07203478e-01 9.49473798e-01 2.35666409e-01 -2.07210705e-01 9.50888813e-01 2.29829833e-01 -2.07221597e-01 9.52271163e-01 2.23995984e-01 -2.07243741e-01 9.53662694e-01 2.18147874e-01 -2.07232788e-01 9.54958677e-01 2.12287828e-01 -2.07231402e-01 9.56301153e-01 2.06429869e-01 -2.07149267e-01 9.57512736e-01 2.00562000e-01 -2.07163393e-01 9.58704650e-01 1.94681406e-01 -2.07206100e-01 9.59889412e-01 1.88792408e-01 -2.07220748e-01 9.61042285e-01 1.82889268e-01 -2.07312450e-01 9.62110043e-01 1.76997125e-01 -2.07278043e-01 9.63223457e-01 1.71092853e-01 -2.07222760e-01 9.64210331e-01 1.65178984e-01 -2.07221031e-01 9.65195656e-01 1.59251928e-01 -2.07315132e-01 9.66165602e-01 1.53329432e-01 -2.07304448e-01 9.67070103e-01 1.47396863e-01 -2.07298681e-01 9.68013346e-01 1.41461670e-01 -2.07277477e-01 9.68923867e-01 1.35526299e-01 -2.07085952e-01 9.69721615e-01 1.29580200e-01 -2.07099035e-01 9.70458508e-01 1.23630077e-01 -2.07106441e-01 9.71222758e-01 1.17670968e-01 -2.07105815e-01 9.71896768e-01 1.11709051e-01 -2.07096279e-01 9.72589076e-01 1.05746329e-01 -2.07111090e-01 9.73240316e-01 9.97755602e-02 -2.07088873e-01 9.73803699e-01 9.38032046e-02 -2.07086325e-01 9.74345863e-01 8.78235176e-02 -2.07105115e-01 9.74912584e-01 8.18460286e-02 -2.07086369e-01 9.75391090e-01 7.58606344e-02 -2.07089514e-01 9.75853026e-01 6.98744580e-02 -2.07091838e-01 9.76236999e-01 6.38865978e-02 -2.07100600e-01 9.76635218e-01 5.78943230e-02 -2.07099885e-01 9.76911724e-01 5.19008711e-02 -2.07097635e-01 9.77211237e-01 4.59041707e-02 -2.07107246e-01 9.77542102e-01 3.99093442e-02 -2.07010835e-01 9.77774978e-01 3.39094922e-02 -2.07017303e-01 9.77909207e-01 2.79087257e-02 -2.07119778e-01 9.78081346e-01 2.19085049e-02 -2.07107678e-01 9.78160143e-01 1.59063190e-02 -2.07135737e-01 9.78303194e-01 9.90427565e-03 -2.07097679e-01 9.78322804e-01 3.90150771e-03 -2.07093626e-01 9.78324831e-01 -2.10135593e-03 -2.07085699e-01 9.78307605e-01 -8.10418557e-03 -2.07092643e-01 9.78230536e-01 -1.41068511e-02 -2.07149431e-01 9.78096187e-01 -2.01089121e-02 -2.07113981e-01 9.77997541e-01 -2.61100978e-02 -2.07108617e-01 9.77825582e-01 -3.21105048e-02 -2.07097277e-01 9.77602422e-01 -3.81094702e-02 -2.07088307e-01 9.77349579e-01 -4.41065133e-02 -2.07098171e-01 9.77049768e-01 -5.01021370e-02 -2.07091615e-01 9.76711750e-01 -5.60963005e-02 -2.07109496e-01 9.76335347e-01 -6.20886050e-02 -2.07158610e-01 9.75904167e-01 -6.80763721e-02 -2.07257077e-01 9.75461125e-01 -7.40640834e-02 -2.07175672e-01 9.75031853e-01 -8.00477266e-02 -2.07145423e-01 9.74514782e-01 -8.60322416e-02 -2.07110122e-01 9.73992765e-01 -9.20077860e-02 -2.07163334e-01 9.73379672e-01 -9.79840681e-02 -2.07128346e-01 9.72805142e-01 -1.03955008e-01 -2.07116947e-01 9.72111642e-01 -1.09920859e-01 -2.07115114e-01 9.71409798e-01 -1.15884311e-01 -2.07109451e-01 9.70683157e-01 -1.21842295e-01 -2.07105666e-01 9.69953179e-01 -1.27793863e-01 -2.07116202e-01 9.69150186e-01 -1.33747205e-01 -2.07156748e-01 9.68288243e-01 -1.39690429e-01 -2.07109421e-01 9.67398524e-01 -1.45631269e-01 -2.07127541e-01 9.66528952e-01 -1.51558250e-01 -2.07117200e-01 9.65579510e-01 -1.57489046e-01 -2.07098171e-01 9.64557886e-01 -1.63405776e-01 -2.07175583e-01 9.63522077e-01 -1.69323266e-01 -2.07172185e-01 9.62516010e-01 -1.75231397e-01 -2.07186908e-01 9.61367309e-01 -1.81134909e-01 -2.07189992e-01 9.60252702e-01 -1.87028944e-01 -2.07189634e-01 9.59097087e-01 -1.92920834e-01 -2.07223132e-01 9.57891881e-01 -1.98796511e-01 -2.07295939e-01 9.56609905e-01 -2.04667017e-01 -2.07307830e-01 9.55346644e-01 -2.10534781e-01 -2.07310975e-01 9.54067409e-01 -2.16390535e-01 -2.07308695e-01 9.52713132e-01 -2.22239569e-01 -2.07317665e-01 9.51289117e-01 -2.28087872e-01 -2.07321957e-01 9.49865937e-01 -2.33921766e-01 -2.07332104e-01 9.48419154e-01 -2.39734977e-01 -2.07337648e-01 9.46965218e-01 -2.45553225e-01 -2.07339704e-01 9.45393801e-01 -2.51363069e-01 -2.07344532e-01 9.43874538e-01 -2.57159561e-01 -2.07343996e-01 9.42295969e-01 -2.62953222e-01 -2.07204178e-01 9.40645576e-01 -2.68724740e-01 -2.07198679e-01 9.38974619e-01 -2.74491698e-01 -2.07195818e-01 9.37286377e-01 -2.80246735e-01 -2.07199708e-01 9.35550511e-01 -2.86002010e-01 -2.07197964e-01 9.33806181e-01 -2.91735560e-01 -2.07200721e-01 9.31966305e-01 -2.97463089e-01 -2.07205668e-01 9.30119634e-01 -3.03159714e-01 -2.07212463e-01 9.28256989e-01 -3.08875471e-01 -2.07177654e-01 9.26313281e-01 -3.14555764e-01 -2.07220882e-01 9.24394608e-01 -3.20234239e-01 -2.07177639e-01 9.22417939e-01 -3.25903118e-01 -2.07177386e-01 9.20426667e-01 -3.31566453e-01 -2.07177296e-01 9.18357134e-01 -3.37199092e-01 -2.07178846e-01 9.16270435e-01 -3.42824578e-01 -2.07184121e-01 9.14136708e-01 -3.48445833e-01 -2.07185104e-01 9.11974490e-01 -3.54042143e-01 -2.07213521e-01 9.09775794e-01 -3.59632105e-01 -2.07194969e-01 9.07600045e-01 -3.65202248e-01 -2.07199007e-01 9.05291319e-01 -3.70769173e-01 -2.07198471e-01 9.03036773e-01 -3.76304418e-01 -2.07198843e-01 9.00669813e-01 -3.81855875e-01 -2.07203656e-01 8.98297369e-01 -3.87368292e-01 -2.07199842e-01 8.95907164e-01 -3.92885864e-01 -2.07207233e-01 8.93500328e-01 -3.98373783e-01 -2.07205579e-01 8.91044915e-01 -4.03839052e-01 -2.07212403e-01 8.88546407e-01 -4.09294099e-01 -2.07220376e-01 8.86022568e-01 -4.14741784e-01 -2.07235470e-01 8.83463442e-01 -4.20160592e-01 -2.07232550e-01 8.80844295e-01 -4.25585538e-01 -2.07223415e-01 8.78209770e-01 -4.30981010e-01 -2.07253799e-01 8.75575662e-01 -4.36355382e-01 -2.07255006e-01 8.72879803e-01 -4.41726863e-01 -2.07257971e-01 8.70145619e-01 -4.47070271e-01 -2.07269788e-01 8.67387056e-01 -4.52393532e-01 -2.07276732e-01 8.64588499e-01 -4.57724839e-01 -2.07264379e-01 8.61743748e-01 -4.62994128e-01 -2.07257986e-01 8.58874559e-01 -4.68275338e-01 -2.07285538e-01 8.55963826e-01 -4.73522276e-01 -2.07436368e-01 8.53087127e-01 -4.78768378e-01 -2.07436115e-01 8.50135148e-01 -4.83991832e-01 -2.07437217e-01 8.47129524e-01 -4.89214987e-01 -2.07388192e-01 8.44126999e-01 -4.94400442e-01 -2.07278922e-01 8.41090977e-01 -4.99575913e-01 -2.07288429e-01 8.38002145e-01 -5.04740655e-01 -2.07291350e-01 8.34895670e-01 -5.09876192e-01 -2.07284823e-01 8.31769049e-01 -5.14961243e-01 -2.07299441e-01 8.28539371e-01 -5.20065010e-01 -2.07291633e-01 8.25387478e-01 -5.25160074e-01 -2.07301885e-01 8.22118700e-01 -5.30204475e-01 -2.07301214e-01 8.18866193e-01 -5.35223544e-01 -2.07332462e-01 8.15565944e-01 -5.40238976e-01 -2.07331881e-01 8.12244415e-01 -5.45244753e-01 -2.07330257e-01 8.08852613e-01 -5.50206184e-01 -2.07336694e-01 8.05483520e-01 -5.55161059e-01 -2.07353532e-01 8.02015960e-01 -5.60081065e-01 -2.07363099e-01 7.98614621e-01 -5.64989209e-01 -2.07360730e-01 7.95084119e-01 -5.69878638e-01 -2.07366556e-01 7.91578650e-01 -5.74754596e-01 -2.07367674e-01 7.88059652e-01 -5.79612434e-01 -2.07369670e-01 7.84480870e-01 -5.84426224e-01 -2.07353115e-01 7.80883014e-01 -5.89221895e-01 -2.07355157e-01 7.77243674e-01 -5.93997717e-01 -2.07375377e-01 7.73571551e-01 -5.98753154e-01 -2.07376465e-01 7.69902050e-01 -6.03511274e-01 -2.07369789e-01 7.66168714e-01 -6.08205020e-01 -2.07376376e-01 7.62438953e-01 -6.12923145e-01 -2.07374319e-01 7.58651614e-01 -6.17579401e-01 -2.07403764e-01 7.54822671e-01 -6.22221649e-01 -2.07516462e-01 7.50988126e-01 -6.26801789e-01 -2.07537681e-01 7.47150421e-01 -6.31423116e-01 -2.07539141e-01 7.43239045e-01 -6.35985255e-01 -2.07540542e-01 7.39366889e-01 -6.40532255e-01 -2.07526937e-01 7.35408485e-01 -6.45063698e-01 -2.07519382e-01 7.31418729e-01 -6.49573386e-01 -2.07513079e-01 7.27444530e-01 -6.54028296e-01 -2.07529277e-01 7.23398805e-01 -6.58475757e-01 -2.07532585e-01 7.19339550e-01 -6.62932158e-01 -2.07538307e-01 7.15275109e-01 -6.67308450e-01 -2.07548723e-01 7.11163700e-01 -6.71690285e-01 -2.07571417e-01 7.07036793e-01 -6.76034570e-01 -2.07500875e-01 7.02860236e-01 -6.80386186e-01 -2.07526207e-01 6.98665738e-01 -6.84672177e-01 -2.07617000e-01 6.94451332e-01 -6.88916385e-01 -2.07675278e-01 6.90193415e-01 -6.93174481e-01 -2.07637951e-01 6.85917437e-01 -6.97381854e-01 -2.07693160e-01 6.81640029e-01 -7.01618254e-01 -2.07597777e-01 6.77334607e-01 -7.05763936e-01 -2.07571149e-01 6.72989607e-01 -7.09899187e-01 -2.07646638e-01 6.68607533e-01 -7.14034081e-01 -2.07664371e-01 6.64229691e-01 -7.18122900e-01 -2.07666069e-01 6.59809768e-01 -7.22181320e-01 -2.07678676e-01 6.55352116e-01 -7.26214468e-01 -2.07671508e-01 6.50919318e-01 -7.30232000e-01 -2.07504094e-01 6.46429181e-01 -7.34228134e-01 -2.07497224e-01 6.41903639e-01 -7.38175094e-01 -2.07510680e-01 6.37370110e-01 -7.42106616e-01 -2.07474515e-01 6.32796049e-01 -7.45998442e-01 -2.07431212e-01 6.28231168e-01 -7.49876797e-01 -2.07396597e-01 6.23610318e-01 -7.53719866e-01 -2.07351640e-01 6.18990004e-01 -7.57546067e-01 -2.07301989e-01 6.14335537e-01 -7.61345923e-01 -2.07260042e-01 6.09639823e-01 -7.65105426e-01 -2.07270950e-01 6.04935646e-01 -7.68825531e-01 -2.07256734e-01 6.00211382e-01 -7.72529006e-01 -2.07235664e-01 5.95473647e-01 -7.76191890e-01 -2.07206309e-01 5.90705276e-01 -7.79844582e-01 -2.07134038e-01 5.85922420e-01 -7.83469856e-01 -2.07037807e-01 5.81111908e-01 -7.87062347e-01 -2.06966162e-01 5.76315582e-01 -7.90675759e-01 -2.06608593e-01 5.71439624e-01 -7.94174790e-01 -2.06738293e-01 5.66561639e-01 -7.97672510e-01 -2.06692055e-01 5.61641395e-01 -8.01114619e-01 -2.06814602e-01 5.56706846e-01 -8.04536462e-01 -2.06877440e-01 5.51756144e-01 -8.07931900e-01 -2.06915379e-01 5.46787739e-01 -8.11303020e-01 -2.06915051e-01 5.41801393e-01 -8.14642370e-01 -2.06905723e-01 5.36789477e-01 -8.17947626e-01 -2.06918612e-01 5.31757951e-01 -8.21221232e-01 -2.06938073e-01 5.26711822e-01 -8.24474990e-01 -2.06917569e-01 5.21647155e-01 -8.27696204e-01 -2.06900313e-01 5.16559422e-01 -8.30879629e-01 -2.06894770e-01 5.11450410e-01 -8.34032297e-01 -2.06905738e-01 5.06321430e-01 -8.37155163e-01 -2.06903428e-01 5.01191318e-01 -8.40268970e-01 -2.06755549e-01 4.96020257e-01 -8.43318820e-01 -2.06822664e-01 4.90837336e-01 -8.46351624e-01 -2.06801161e-01 4.85638827e-01 -8.49354208e-01 -2.06768915e-01 4.80418622e-01 -8.52317274e-01 -2.06763446e-01 4.75180954e-01 -8.55252564e-01 -2.06750497e-01 4.69926387e-01 -8.58155608e-01 -2.06733316e-01 4.64650244e-01 -8.61019015e-01 -2.06752315e-01 4.59362209e-01 -8.63860428e-01 -2.06722647e-01 4.54056531e-01 -8.66670310e-01 -2.06678957e-01 4.48725134e-01 -8.69428337e-01 -2.06739962e-01 4.43384200e-01 -8.72169077e-01 -2.06708089e-01 4.38023150e-01 -8.74871612e-01 -2.06720307e-01 4.32655692e-01 -8.77558410e-01 -2.06635490e-01 4.27289575e-01 -8.80249143e-01 -2.06338078e-01 4.21857029e-01 -8.82809043e-01 -2.06599265e-01 4.16446000e-01 -8.85409713e-01 -2.06453234e-01 4.11001235e-01 -8.87939095e-01 -2.06499293e-01 4.05561060e-01 -8.90476763e-01 -2.06326827e-01 4.00112510e-01 -8.92996490e-01 -2.06073880e-01 3.94669324e-01 -8.95527065e-01 -2.05585212e-01 3.89292479e-01 -8.98202240e-01 -2.04158515e-01 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. 0. 0. 3.27657312e-01 -9.21968639e-01 -2.06431299e-01 3.21978658e-01 -9.23921108e-01 -2.06637233e-01 3.16299856e-01 -9.25869823e-01 -2.06689164e-01 3.10613722e-01 -9.27796900e-01 -2.06674144e-01 3.04910749e-01 -9.29671407e-01 -2.06733599e-01 2.99197167e-01 -9.31514800e-01 -2.06780806e-01 2.93475211e-01 -9.33330059e-01 -2.06793502e-01 2.87739694e-01 -9.35104311e-01 -2.06845850e-01 2.81998515e-01 -9.36857402e-01 -2.06816033e-01 2.76240826e-01 -9.38559592e-01 -2.06874639e-01 2.70466745e-01 -9.40205157e-01 -2.07031578e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.47232735e-01 -9.46286380e-01 -2.08370149e-01 0. 0. 0. 0. 0. 0. 2.29953051e-01 -9.51347351e-01 -2.05068573e-01 2.24032313e-01 -9.52439964e-01 -2.06559852e-01 2.18175203e-01 -9.53763545e-01 -2.06730232e-01 2.12313384e-01 -9.55058873e-01 -2.06836939e-01 2.06439912e-01 -9.56293941e-01 -2.07058892e-01 2.00558886e-01 -9.57517922e-01 -2.07195684e-01 1.94678083e-01 -9.58703279e-01 -2.07276136e-01 1.88787147e-01 -9.59875166e-01 -2.07340419e-01 1.82892650e-01 -9.61022973e-01 -2.07386404e-01 1.76991135e-01 -9.62118089e-01 -2.07429349e-01 1.71084523e-01 -9.63162839e-01 -2.07485601e-01 1.65167540e-01 -9.64165926e-01 -2.07530648e-01 1.59246430e-01 -9.65188861e-01 -2.07534462e-01 1.53324455e-01 -9.66161907e-01 -2.07467571e-01 1.47394732e-01 -9.67051864e-01 -2.07448587e-01 1.41456187e-01 -9.67963874e-01 -2.07477972e-01 1.35514453e-01 -9.68808889e-01 -2.07459822e-01 1.29566833e-01 -9.69633996e-01 -2.07486480e-01 1.23615563e-01 -9.70378458e-01 -2.07513317e-01 1.17659315e-01 -9.71157074e-01 -2.07487956e-01 1.11697055e-01 -9.71817911e-01 -2.07494378e-01 1.05732553e-01 -9.72501218e-01 -2.07497284e-01 9.97627676e-02 -9.73124981e-01 -2.07488537e-01 9.37898383e-02 -9.73718107e-01 -2.07504794e-01 8.78139064e-02 -9.74292815e-01 -2.07489192e-01 8.18332434e-02 -9.74794626e-01 -2.07518429e-01 7.58502260e-02 -9.75272000e-01 -2.07507402e-01 6.98656514e-02 -9.75728333e-01 -2.07495451e-01 6.38757497e-02 -9.76169169e-01 -2.07505956e-01 5.78867830e-02 -9.76534426e-01 -2.07502112e-01 5.18939234e-02 -9.76834118e-01 -2.07506537e-01 4.58987392e-02 -9.77157593e-01 -2.07494706e-01 3.99020128e-02 -9.77405071e-01 -2.07511827e-01 3.39038856e-02 -9.77636635e-01 -2.07497910e-01 2.79047396e-02 -9.77849424e-01 -2.07494184e-01 2.19041966e-02 -9.77996469e-01 -2.07493827e-01 1.59033705e-02 -9.78120089e-01 -2.07477853e-01 9.90116131e-03 -9.78195369e-01 -2.07492903e-01 3.89910094e-03 -9.78236258e-01 -2.07485408e-01 -2.10320950e-03 -9.78240371e-01 -2.07473934e-01 -8.10542330e-03 -9.78217363e-01 -2.07452729e-01 -1.41074276e-02 -9.78130162e-01 -2.07456842e-01 -2.01091301e-02 -9.78031814e-01 -2.07451269e-01 -2.61097979e-02 -9.77885067e-01 -2.07459673e-01 -3.21092233e-02 -9.77729201e-01 -2.07478598e-01 -3.81082147e-02 -9.77522492e-01 -2.07422569e-01 -4.41054665e-02 -9.77260649e-01 -2.07449198e-01 -5.00994585e-02 -9.76933360e-01 -2.07492977e-01 -5.60930558e-02 -9.76643801e-01 -2.07482710e-01 -6.20851070e-02 -9.76246059e-01 -2.07461774e-01 -6.80760369e-02 -9.75869417e-01 -2.07427904e-01 -7.40619525e-02 -9.75409627e-01 -2.07485482e-01 -8.00456479e-02 -9.74983454e-01 -2.07466453e-01 -8.60240161e-02 -9.74437416e-01 -2.07492858e-01 -9.20039639e-02 -9.73918557e-01 -2.07440883e-01 -9.79762897e-02 -9.73325849e-01 -2.07498804e-01 -1.03946589e-01 -9.72704113e-01 -2.07498059e-01 -1.09913133e-01 -9.72025335e-01 -2.07499146e-01 -1.15876272e-01 -9.71343279e-01 -2.07465947e-01 -1.21828407e-01 -9.70550597e-01 -2.07703382e-01 -1.27784207e-01 -9.69817936e-01 -2.07711309e-01 -1.33730397e-01 -9.69006240e-01 -2.07646713e-01 -1.39673740e-01 -9.68159437e-01 -2.07682028e-01 -1.45612329e-01 -9.67305601e-01 -2.07662880e-01 -1.51545018e-01 -9.66373086e-01 -2.07671404e-01 -1.57471687e-01 -9.65422213e-01 -2.07672715e-01 -1.63387477e-01 -9.64442015e-01 -2.07711026e-01 -1.69304162e-01 -9.63396490e-01 -2.07719684e-01 -1.75210401e-01 -9.62388039e-01 -2.07737193e-01 -1.81112841e-01 -9.61243331e-01 -2.07736641e-01 -1.87009871e-01 -9.60137486e-01 -2.07730040e-01 -1.92900524e-01 -9.58971441e-01 -2.07739159e-01 -1.98782146e-01 -9.57776845e-01 -2.07719758e-01 -2.04647809e-01 -9.56529796e-01 -2.07752019e-01 -2.10515723e-01 -9.55254495e-01 -2.07736224e-01 -2.16371775e-01 -9.53958750e-01 -2.07730815e-01 -2.22219944e-01 -9.52618420e-01 -2.07744107e-01 -2.28066131e-01 -9.51199293e-01 -2.07737580e-01 -2.33896628e-01 -9.49781656e-01 -2.07742915e-01 -2.39715815e-01 -9.48338687e-01 -2.07753733e-01 -2.45536506e-01 -9.46881473e-01 -2.07756683e-01 -2.51342058e-01 -9.45326865e-01 -2.07760170e-01 -2.57146895e-01 -9.43824589e-01 -2.07597464e-01 -2.62931705e-01 -9.42226708e-01 -2.07590386e-01 -2.68697053e-01 -9.40548182e-01 -2.07736298e-01 -2.74464905e-01 -9.38890457e-01 -2.07694918e-01 -2.80219495e-01 -9.37189400e-01 -2.07720160e-01 -2.85971135e-01 -9.35440481e-01 -2.07709223e-01 -2.91706771e-01 -9.33695674e-01 -2.07668394e-01 -2.97429562e-01 -9.31860447e-01 -2.07711309e-01 -3.03133845e-01 -9.30039346e-01 -2.07684591e-01 -3.08842570e-01 -9.28149283e-01 -2.07693636e-01 -3.14527035e-01 -9.26243246e-01 -2.07668886e-01 -3.20202708e-01 -9.24310684e-01 -2.07631007e-01 -3.25867265e-01 -9.22308803e-01 -2.07697019e-01 -3.31532300e-01 -9.20301259e-01 -2.07688123e-01 -3.37159395e-01 -9.18246925e-01 -2.07700580e-01 -3.42786402e-01 -9.16176438e-01 -2.07694128e-01 -3.48425210e-01 -9.14086699e-01 -2.07475767e-01 -3.54015470e-01 -9.11922216e-01 -2.07483441e-01 -3.59595478e-01 -9.09665585e-01 -2.07716525e-01 -3.65164399e-01 -9.07493651e-01 -2.07699507e-01 -3.70730400e-01 -9.05206442e-01 -2.07704559e-01 -3.76268983e-01 -9.02942717e-01 -2.07689449e-01 -3.81821275e-01 -9.00608361e-01 -2.07561210e-01 -3.87349635e-01 -8.98248315e-01 -2.07545221e-01 -3.92857909e-01 -8.95862281e-01 -2.07530454e-01 -3.98362219e-01 -8.93478572e-01 -2.07344070e-01 -4.03822094e-01 -8.91012311e-01 -2.07321942e-01 -4.09280062e-01 -8.88510466e-01 -2.07492948e-01 -4.14707035e-01 -8.85928571e-01 -2.07661912e-01 -4.20132101e-01 -8.83379877e-01 -2.07673818e-01 -4.25551683e-01 -8.80761445e-01 -2.07666248e-01 -4.30944055e-01 -8.78133774e-01 -2.07668245e-01 -4.36319619e-01 -8.75501454e-01 -2.07664192e-01 -4.41690385e-01 -8.72788012e-01 -2.07669377e-01 -4.47025567e-01 -8.70089948e-01 -2.07664609e-01 -4.52364564e-01 -8.67300212e-01 -2.07661018e-01 -4.57686156e-01 -8.64518523e-01 -2.07658887e-01 -4.62956071e-01 -8.61667931e-01 -2.07686633e-01 -4.68253225e-01 -8.58814359e-01 -2.07665950e-01 -4.73501533e-01 -8.55926573e-01 -2.07694799e-01 -4.78753507e-01 -8.53044093e-01 -2.07681760e-01 -4.83972847e-01 -8.50071013e-01 -2.07664698e-01 -4.89185601e-01 -8.47075105e-01 -2.07698941e-01 -4.94361013e-01 -8.44075263e-01 -2.07704946e-01 -4.99540389e-01 -8.40999901e-01 -2.07710311e-01 -5.04698634e-01 -8.37917686e-01 -2.07672209e-01 -5.09843946e-01 -8.34848046e-01 -2.07518041e-01 -5.14959037e-01 -8.31704855e-01 -2.07557708e-01 -5.20049512e-01 -8.28523159e-01 -2.07550824e-01 -5.25124371e-01 -8.25343847e-01 -2.07577661e-01 -5.30186117e-01 -8.22084486e-01 -2.07535699e-01 -5.35212517e-01 -8.18816185e-01 -2.07547605e-01 -5.40221214e-01 -8.15503657e-01 -2.07517132e-01 -5.45226455e-01 -8.12211871e-01 -2.07511961e-01 -5.50202191e-01 -8.08808744e-01 -2.07503840e-01 -5.55145323e-01 -8.05435598e-01 -2.07510620e-01 -5.60071945e-01 -8.02000344e-01 -2.07516223e-01 -5.64977288e-01 -7.98558295e-01 -2.07520381e-01 -5.69868624e-01 -7.95069396e-01 -2.07513019e-01 -5.74744582e-01 -7.91591167e-01 -2.07475811e-01 -5.79650402e-01 -7.88105726e-01 -2.07055688e-01 -5.84465981e-01 -7.84529388e-01 -2.07048848e-01 -5.89216352e-01 -7.80852377e-01 -2.07478523e-01 -5.94006062e-01 -7.77266264e-01 -2.07425490e-01 -5.98757565e-01 -7.73578286e-01 -2.07418784e-01 -6.03519738e-01 -7.69903123e-01 -2.07397327e-01 -6.08225763e-01 -7.66186416e-01 -2.07380161e-01 -6.12924695e-01 -7.62471914e-01 -2.07360566e-01 -6.17592275e-01 -7.58673966e-01 -2.07321838e-01 -6.22245729e-01 -7.54884005e-01 -2.07270071e-01 -6.26859248e-01 -7.51049340e-01 -2.07233667e-01 -6.31460130e-01 -7.47220397e-01 -2.07159430e-01 -6.36049151e-01 -7.43338168e-01 -2.07107022e-01 -6.40602589e-01 -7.39421904e-01 -2.07039163e-01 -6.45139873e-01 -7.35486925e-01 -2.06998259e-01 -6.49651468e-01 -7.31528819e-01 -2.06937373e-01 -6.54140055e-01 -7.27539539e-01 -2.06873700e-01 -6.58594549e-01 -7.23513126e-01 -2.06845850e-01 -6.63020074e-01 -7.19461322e-01 -2.06830591e-01 -6.67432308e-01 -7.15389669e-01 -2.06760898e-01 -6.71818256e-01 -7.11294949e-01 -2.06685439e-01 -6.76344573e-01 -7.07351089e-01 -2.05436021e-01 -6.81098640e-01 -7.03651786e-01 -2.02393949e-01 -6.85942411e-01 -7.00038612e-01 -1.98567405e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.05909729e-01 -6.77472353e-01 -2.06694946e-01 -7.10063696e-01 -6.73140228e-01 -2.06625640e-01 -7.14178503e-01 -6.68776691e-01 -2.06598520e-01 -7.18270659e-01 -6.64372742e-01 -2.06600204e-01 -7.22335279e-01 -6.59955502e-01 -2.06589326e-01 -7.26379395e-01 -6.55516744e-01 -2.06600383e-01 -7.30371416e-01 -6.51041865e-01 -2.06657767e-01 -7.34315455e-01 -6.46515667e-01 -2.06889957e-01 -7.38283515e-01 -6.42007291e-01 -2.06785172e-01 -7.42206395e-01 -6.37463808e-01 -2.06823289e-01 -7.46109307e-01 -6.32901907e-01 -2.06762895e-01 -7.49989748e-01 -6.28323972e-01 -2.06694677e-01 -7.53831744e-01 -6.23707652e-01 -2.06655234e-01 -7.57657588e-01 -6.19073808e-01 -2.06627429e-01 -7.61459172e-01 -6.14427924e-01 -2.06519887e-01 -7.65215456e-01 -6.09749615e-01 -2.06510171e-01 -7.69052565e-01 -6.05133414e-01 -2.05840930e-01 -7.72780895e-01 -6.00427449e-01 -2.05659539e-01 -7.76554108e-01 -5.95758259e-01 -2.05026358e-01 -7.79583752e-01 -5.90494335e-01 -2.08723709e-01 0. 0. 0. -7.88285971e-01 -5.82062721e-01 -1.99519932e-01 -7.91569948e-01 -5.77005029e-01 -2.01181531e-01 -7.94985771e-01 -5.72053730e-01 -2.01850608e-01 -7.97905684e-01 -5.66734076e-01 -2.05319211e-01 -8.01237226e-01 -5.61729491e-01 -2.06099302e-01 -8.04609478e-01 -5.56758225e-01 -2.06458598e-01 -8.07970881e-01 -5.51784635e-01 -2.06697926e-01 -8.11301768e-01 -5.46799183e-01 -2.06856504e-01 -8.14615726e-01 -5.41784704e-01 -2.07010761e-01 -8.17924261e-01 -5.36764562e-01 -2.07105026e-01 -8.21195126e-01 -5.31742930e-01 -2.07048282e-01 -8.24454367e-01 -5.26702046e-01 -2.06980661e-01 -8.27713132e-01 -5.21653831e-01 -2.06826717e-01 -8.30967367e-01 -5.16612709e-01 -2.06412390e-01 -8.34242463e-01 -5.11584878e-01 -2.05707595e-01 -8.38161469e-01 -5.06965995e-01 -2.01151222e-01 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.52007174e-01 -2.23919079e-01 -2.08668739e-01 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.64240432e-01 1.03249803e-01 -2.44089872e-01 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. 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. 0. -9.44150746e-01 2.20464498e-01 -2.44897440e-01 0. 0. 0. 0. 0. 0. -9.40445423e-01 2.37924173e-01 -2.42805615e-01 -9.38958049e-01 2.43687883e-01 -2.42845461e-01 0. 0. 0. -9.37121153e-01 2.55497754e-01 -2.37749681e-01 -9.35544550e-01 2.61245221e-01 -2.37712681e-01 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. 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. 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. 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. 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. 0. -8.18500400e-01 5.21009326e-01 -2.42087275e-01 -8.15280735e-01 5.26017249e-01 -2.42123023e-01 -8.12030673e-01 5.31005383e-01 -2.42155716e-01 -8.08744013e-01 5.35969496e-01 -2.42214322e-01 -8.05458307e-01 5.40933073e-01 -2.42132708e-01 -8.02144349e-01 5.45878708e-01 -2.42033243e-01 -7.98738122e-01 5.50762832e-01 -2.42234796e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.44545460e-01 6.21689498e-01 -2.43216172e-01 -7.40721583e-01 6.26250148e-01 -2.43189797e-01 -7.36933708e-01 6.30835176e-01 -2.42837504e-01 -7.33061910e-01 6.35359406e-01 -2.42800936e-01 -7.29162157e-01 6.39851630e-01 -2.42729515e-01 -7.25231051e-01 6.44327044e-01 -2.42648453e-01 -7.21278906e-01 6.48777425e-01 -2.42578208e-01 -7.17258453e-01 6.53167486e-01 -2.42718369e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.40868843e-01 7.28217304e-01 -2.42871538e-01 -6.36381924e-01 7.32129157e-01 -2.42907807e-01 -6.31866097e-01 7.36008584e-01 -2.42990270e-01 -6.27322674e-01 7.39856720e-01 -2.43106693e-01 -6.22750223e-01 7.43663371e-01 -2.43198499e-01 -6.18165493e-01 7.47461975e-01 -2.43302077e-01 -6.13552034e-01 7.51227379e-01 -2.43369043e-01 -6.08917654e-01 7.54937410e-01 -2.43458614e-01 -6.04272306e-01 7.58677781e-01 -2.43488386e-01 -5.99591434e-01 7.62355387e-01 -2.43471876e-01 -5.94912350e-01 7.66023219e-01 -2.43475989e-01 -5.90206027e-01 7.69672215e-01 -2.43467391e-01 -5.85475445e-01 7.73261309e-01 -2.43450195e-01 -5.80731571e-01 7.76843369e-01 -2.43436098e-01 -5.75943708e-01 7.80401230e-01 -2.43391052e-01 -5.71154654e-01 7.83925712e-01 -2.43391156e-01 -5.66314578e-01 7.87427187e-01 -2.43425310e-01 -5.61483324e-01 7.90886402e-01 -2.43442893e-01 -5.56599915e-01 7.94311166e-01 -2.43479624e-01 -5.51721513e-01 7.97666430e-01 -2.43516937e-01 -5.46816289e-01 8.01056147e-01 -2.43542507e-01 -5.41886926e-01 8.04375410e-01 -2.43563011e-01 -5.36926389e-01 8.07682216e-01 -2.43579701e-01 -5.31953454e-01 8.10979187e-01 -2.43620589e-01 -5.26967406e-01 8.14205706e-01 -2.43638262e-01 -5.21978378e-01 8.17407429e-01 -2.43628949e-01 -5.16936779e-01 8.20598066e-01 -2.43624881e-01 -5.11886537e-01 8.23762238e-01 -2.43688062e-01 -5.06833375e-01 8.26875389e-01 -2.43641958e-01 -5.01741767e-01 8.30005229e-01 -2.43679330e-01 -4.96638715e-01 8.33014846e-01 -2.43743867e-01 -4.91514534e-01 8.36063325e-01 -2.43745685e-01 -4.86372769e-01 8.39046896e-01 -2.43762597e-01 -4.81206387e-01 8.42008233e-01 -2.43770525e-01 -4.76037621e-01 8.44957769e-01 -2.43788049e-01 -4.70807225e-01 8.47836435e-01 -2.43990660e-01 -4.65599090e-01 8.50692749e-01 -2.43959472e-01 -4.60378170e-01 8.53522897e-01 -2.44040117e-01 -4.55144554e-01 8.56399298e-01 -2.43825674e-01 -4.49868947e-01 8.59125197e-01 -2.43939653e-01 -4.44587737e-01 8.61859024e-01 -2.43958548e-01 -4.39299583e-01 8.64564419e-01 -2.43994951e-01 -4.33983415e-01 8.67261469e-01 -2.43991986e-01 -4.28654939e-01 8.69889855e-01 -2.43992269e-01 -4.23307747e-01 8.72499645e-01 -2.43994683e-01 -4.17940617e-01 8.75074983e-01 -2.44016841e-01 -4.12553102e-01 8.77642453e-01 -2.44043604e-01 -4.07164603e-01 8.80149364e-01 -2.44065925e-01 -4.01766211e-01 8.82639587e-01 -2.44046584e-01 -3.96347642e-01 8.85120332e-01 -2.43952617e-01 -3.90906930e-01 8.87528479e-01 -2.43904725e-01 -3.85456771e-01 8.89895260e-01 -2.43920967e-01 -3.79990697e-01 8.92250896e-01 -2.43952915e-01 -3.74499679e-01 8.94574940e-01 -2.43985951e-01 -3.69001359e-01 8.96854639e-01 -2.43955135e-01 -3.63496840e-01 8.99110138e-01 -2.43916437e-01 -3.57968956e-01 9.01282310e-01 -2.43952274e-01 -3.52432281e-01 9.03495848e-01 -2.43927643e-01 -3.46934825e-01 9.05752480e-01 -2.43395373e-01 -3.41370255e-01 9.07875061e-01 -2.43399650e-01 -3.35732073e-01 9.09784436e-01 -2.44005069e-01 -3.30157906e-01 9.11854804e-01 -2.43977904e-01 -3.24548244e-01 9.13867176e-01 -2.43964583e-01 -3.18936080e-01 9.15817916e-01 -2.44017422e-01 -3.13312352e-01 9.17776406e-01 -2.44004279e-01 -3.07675540e-01 9.19697821e-01 -2.43968129e-01 -3.02030325e-01 9.21573341e-01 -2.43953317e-01 -2.96368122e-01 9.23378587e-01 -2.43966922e-01 -2.90689498e-01 9.25172210e-01 -2.44003370e-01 -2.85006851e-01 9.26926732e-01 -2.44028583e-01 -2.79316723e-01 9.28685367e-01 -2.44039208e-01 -2.73613572e-01 9.30355966e-01 -2.44033322e-01 -2.67899513e-01 9.32016850e-01 -2.44019449e-01 -2.62178630e-01 9.33669508e-01 -2.44007930e-01 -2.56443799e-01 9.35244858e-01 -2.43986055e-01 -2.50703365e-01 9.36837912e-01 -2.43939623e-01 -2.44950265e-01 9.38321531e-01 -2.43981659e-01 -2.39193380e-01 9.39846337e-01 -2.43902326e-01 -2.33421907e-01 9.41277742e-01 -2.43906081e-01 -2.27640361e-01 9.42691803e-01 -2.43910879e-01 -2.21852556e-01 9.44102466e-01 -2.43874267e-01 -2.16050416e-01 9.45406973e-01 -2.43928552e-01 -2.10246786e-01 9.46711004e-01 -2.43939638e-01 -2.04434901e-01 9.48000073e-01 -2.43953794e-01 -1.98613018e-01 9.49208379e-01 -2.43979841e-01 -1.92781895e-01 9.50441241e-01 -2.44014069e-01 -1.86948746e-01 9.51570272e-01 -2.44004041e-01 -1.81102172e-01 9.52724934e-01 -2.44011059e-01 -1.75256848e-01 9.53789830e-01 -2.44026914e-01 -1.69399500e-01 9.54847336e-01 -2.44050071e-01 -1.63538128e-01 9.55890834e-01 -2.44030848e-01 -1.57674715e-01 9.56886113e-01 -2.43946195e-01 -1.51793465e-01 9.57815230e-01 -2.44028136e-01 -1.45913839e-01 9.58737910e-01 -2.44011104e-01 -1.40034825e-01 9.59614754e-01 -2.43941024e-01 -1.34141400e-01 9.60464120e-01 -2.43951097e-01 -1.28241226e-01 9.61242974e-01 -2.44040489e-01 -1.22342750e-01 9.62036550e-01 -2.44037360e-01 -1.16439886e-01 9.62774813e-01 -2.43951574e-01 -1.10527456e-01 9.63474989e-01 -2.43964389e-01 -1.04616463e-01 9.64108706e-01 -2.43965015e-01 -9.86993462e-02 9.64731455e-01 -2.43961051e-01 -9.27784219e-02 9.65313673e-01 -2.43963987e-01 -8.68500769e-02 9.65892076e-01 -2.43960157e-01 -8.09250027e-02 9.66389537e-01 -2.43958309e-01 -7.49929547e-02 9.66863215e-01 -2.43967578e-01 -6.90588132e-02 9.67314541e-01 -2.43973985e-01 -6.31218329e-02 9.67738926e-01 -2.43969902e-01 -5.71825802e-02 9.68106627e-01 -2.43972719e-01 -5.12415729e-02 9.68443453e-01 -2.43970975e-01 -4.52970415e-02 9.68730688e-01 -2.43976101e-01 -3.93531248e-02 9.68984008e-01 -2.43985966e-01 -3.34058665e-02 9.69201148e-01 -2.43999630e-01 -2.74586529e-02 9.69383597e-01 -2.44031444e-01 -2.15101521e-02 9.69534993e-01 -2.44024232e-01 -1.55603318e-02 9.69639122e-01 -2.44049743e-01 -9.61050857e-03 9.69738185e-01 -2.44048461e-01 -3.66075034e-03 9.69787121e-01 -2.43960604e-01 2.28971336e-03 9.69790041e-01 -2.43950486e-01 8.24028905e-03 9.69765902e-01 -2.43963480e-01 1.41903572e-02 9.69676912e-01 -2.43952900e-01 2.01400239e-02 9.69552696e-01 -2.43983418e-01 2.60886848e-02 9.69423354e-01 -2.44002819e-01 3.20370644e-02 9.69283700e-01 -2.43962124e-01 3.79833803e-02 9.69054043e-01 -2.43968725e-01 4.39279415e-02 9.68808651e-01 -2.43976697e-01 4.98716235e-02 9.68483448e-01 -2.43997157e-01 5.58135062e-02 9.68155682e-01 -2.43980810e-01 6.17528744e-02 9.67796147e-01 -2.43987933e-01 6.76900148e-02 9.67395604e-01 -2.44058713e-01 7.36234039e-02 9.66943741e-01 -2.44071379e-01 7.95560554e-02 9.66483891e-01 -2.44030863e-01 8.54841247e-02 9.65969563e-01 -2.44086400e-01 9.14105996e-02 9.65465605e-01 -2.44013578e-01 9.73325297e-02 9.64880884e-01 -2.44018376e-01 1.03252649e-01 9.64228988e-01 -2.44062096e-01 1.09163992e-01 9.63602483e-01 -2.44069219e-01 1.15077183e-01 9.62897122e-01 -2.44067237e-01 1.20983005e-01 9.62187290e-01 -2.44041696e-01 1.26884162e-01 9.61440384e-01 -2.44065925e-01 1.32780463e-01 9.60649908e-01 -2.43992016e-01 1.38671696e-01 9.59820092e-01 -2.43989825e-01 1.44557536e-01 9.58905220e-01 -2.44057596e-01 1.50442407e-01 9.58040118e-01 -2.44010925e-01 1.56315848e-01 9.57087100e-01 -2.44054675e-01 1.62183121e-01 9.56106901e-01 -2.44031087e-01 1.68047845e-01 9.55070376e-01 -2.44083926e-01 1.73901945e-01 9.54023957e-01 -2.44049162e-01 1.79757744e-01 9.52952743e-01 -2.44036078e-01 1.85596213e-01 9.51834440e-01 -2.44108543e-01 1.91436917e-01 9.50690687e-01 -2.44043604e-01 1.97268113e-01 9.49493349e-01 -2.44044513e-01 2.03088477e-01 9.48247552e-01 -2.44042099e-01 2.08907336e-01 9.47002411e-01 -2.44016171e-01 2.14711174e-01 9.45695162e-01 -2.44012699e-01 2.20511779e-01 9.44366753e-01 -2.44004741e-01 2.26301119e-01 9.43013430e-01 -2.43983790e-01 2.32087359e-01 9.41609859e-01 -2.43958578e-01 2.37860471e-01 9.40178990e-01 -2.43930638e-01 2.43628129e-01 9.38705504e-01 -2.43893057e-01 2.49388039e-01 9.37210560e-01 -2.43798852e-01 2.55144507e-01 9.35708463e-01 -2.43624330e-01 2.60918349e-01 9.34268892e-01 -2.43021026e-01 2.66733646e-01 9.32983756e-01 -2.41637439e-01 2.72518605e-01 9.31572258e-01 -2.40628749e-01 2.78300583e-01 9.30139840e-01 -2.39556178e-01 2.84034401e-01 9.28527296e-01 -2.39084542e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.87233287e-01 8.97954106e-01 -2.09114373e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.09190089e-01 8.88265193e-01 -2.08682671e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.46736604e-01 8.69427860e-01 -2.11001247e-01 4.51962441e-01 8.66465926e-01 -2.12053731e-01 0. 0. 0. 4.62049603e-01 8.59845281e-01 -2.17200994e-01 0. 0. 0. 4.73250985e-01 8.55420589e-01 -2.10449591e-01 4.77461487e-01 8.50560606e-01 -2.20398441e-01 4.83088493e-01 8.48389447e-01 -2.16406286e-01 4.88402247e-01 8.45623612e-01 -2.15332597e-01 4.92079020e-01 8.39908123e-01 -2.28525639e-01 4.97839063e-01 8.37961197e-01 -2.23555878e-01 5.03017247e-01 8.34971070e-01 -2.23151535e-01 5.07556677e-01 8.30879688e-01 -2.27981046e-01 5.13260365e-01 8.28794777e-01 -2.22804442e-01 5.18339574e-01 8.25635314e-01 -2.22805277e-01 5.23179114e-01 8.22080851e-01 -2.24645332e-01 5.28297126e-01 8.18991601e-01 -2.23944813e-01 5.33487439e-01 8.16016257e-01 -2.22491652e-01 5.38447618e-01 8.12669456e-01 -2.22785160e-01 5.43268740e-01 8.09107065e-01 -2.24064246e-01 5.48255682e-01 8.05808544e-01 -2.23803565e-01 0. 0. 0. 5.55639625e-01 7.95322895e-01 -2.42334560e-01 5.64527452e-01 7.97857881e-01 -2.11479574e-01 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. 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. 0. 0. 0. 0. 0. 0. 0. 6.62078977e-01 7.09366620e-01 -2.41765127e-01 6.66405439e-01 7.05275834e-01 -2.41846517e-01 6.70676529e-01 7.01125562e-01 -2.42106438e-01 6.74944103e-01 6.96974337e-01 -2.42233664e-01 6.79187119e-01 6.92797661e-01 -2.42354706e-01 6.83387697e-01 6.88577831e-01 -2.42575854e-01 6.87552810e-01 6.84323490e-01 -2.42844045e-01 6.91699266e-01 6.80051267e-01 -2.43069202e-01 6.95818007e-01 6.75750792e-01 -2.43304282e-01 6.99930847e-01 6.71441913e-01 -2.43436351e-01 7.04013824e-01 6.67115450e-01 -2.43553340e-01 7.08087623e-01 6.62772119e-01 -2.43618816e-01 7.12128162e-01 6.58418000e-01 -2.43640751e-01 7.16151893e-01 6.54034793e-01 -2.43653640e-01 7.20161796e-01 6.49619460e-01 -2.43645936e-01 7.24132419e-01 6.45190179e-01 -2.43648335e-01 7.28062987e-01 6.40732825e-01 -2.43669465e-01 7.31994927e-01 6.36252165e-01 -2.43669793e-01 7.35872567e-01 6.31746113e-01 -2.43672296e-01 7.39748538e-01 6.27229273e-01 -2.43672699e-01 7.43568599e-01 6.22674704e-01 -2.43673921e-01 7.47389138e-01 6.18102729e-01 -2.43658036e-01 7.51172781e-01 6.13507152e-01 -2.43631572e-01 7.54925370e-01 6.08890712e-01 -2.43614018e-01 7.58641779e-01 6.04238629e-01 -2.43631765e-01 7.62320757e-01 5.99573076e-01 -2.43664756e-01 7.65996993e-01 5.94881713e-01 -2.43625000e-01 7.69624472e-01 5.90181291e-01 -2.43623778e-01 7.73234129e-01 5.85447073e-01 -2.43616804e-01 7.76829779e-01 5.80694556e-01 -2.43602440e-01 7.80374408e-01 5.75918436e-01 -2.43597388e-01 7.83882618e-01 5.71116924e-01 -2.43602544e-01 7.87379920e-01 5.66288531e-01 -2.43592530e-01 7.90852547e-01 5.61458349e-01 -2.43594810e-01 7.94284701e-01 5.56584835e-01 -2.43574083e-01 7.97669768e-01 5.51711798e-01 -2.43565172e-01 8.01054776e-01 5.46804726e-01 -2.43555501e-01 8.04379761e-01 5.41885257e-01 -2.43557811e-01 8.07686150e-01 5.36928952e-01 -2.43576258e-01 8.10990095e-01 5.31961322e-01 -2.43567973e-01 8.14217806e-01 5.26979685e-01 -2.43561208e-01 8.17439497e-01 5.21978915e-01 -2.43568629e-01 8.20602894e-01 5.16944289e-01 -2.43646964e-01 8.23757470e-01 5.11890590e-01 -2.43696123e-01 8.26893687e-01 5.06841540e-01 -2.43571997e-01 8.30031514e-01 5.01756430e-01 -2.43557140e-01 8.33080530e-01 4.96676952e-01 -2.43434489e-01 8.36066782e-01 4.91513908e-01 -2.43689209e-01 8.39059174e-01 4.86379176e-01 -2.43675902e-01 8.42014730e-01 4.81212258e-01 -2.43686572e-01 8.44995975e-01 4.76061672e-01 -2.43537262e-01 8.47919524e-01 4.70859170e-01 -2.43591294e-01 8.50774050e-01 4.65650380e-01 -2.43598431e-01 8.53629768e-01 4.60436702e-01 -2.43523523e-01 8.56466293e-01 4.55176175e-01 -2.43506745e-01 8.59212935e-01 4.49914157e-01 -2.43519560e-01 8.61946583e-01 4.44636047e-01 -2.43517578e-01 8.64665270e-01 4.39351290e-01 -2.43519008e-01 8.67358267e-01 4.34030801e-01 -2.43539482e-01 8.70001376e-01 4.28705603e-01 -2.43509471e-01 8.72606874e-01 4.23362404e-01 -2.43490264e-01 8.75191510e-01 4.17996734e-01 -2.43476689e-01 8.77756417e-01 4.12610382e-01 -2.43496433e-01 8.80271792e-01 4.07222122e-01 -2.43485004e-01 8.82758558e-01 4.01821524e-01 -2.43478969e-01 8.85222435e-01 3.96391690e-01 -2.43458837e-01 8.87617707e-01 3.90947104e-01 -2.43464828e-01 8.89977455e-01 3.85492623e-01 -2.43530869e-01 8.92367661e-01 3.80044013e-01 -2.43410096e-01 8.94667625e-01 3.74539226e-01 -2.43563309e-01 8.96943450e-01 3.69036406e-01 -2.43560299e-01 8.99202287e-01 3.63532305e-01 -2.43524015e-01 9.01364803e-01 3.58012676e-01 -2.43549973e-01 9.03582394e-01 3.52465838e-01 -2.43548781e-01 9.05717969e-01 3.46920490e-01 -2.43536934e-01 9.07880604e-01 3.41374755e-01 -2.43375093e-01 9.09929812e-01 3.35787863e-01 -2.43397400e-01 9.11985576e-01 3.30205828e-01 -2.43446112e-01 9.14004505e-01 3.24601471e-01 -2.43420735e-01 9.15963948e-01 3.18985790e-01 -2.43368879e-01 9.17922974e-01 3.13359499e-01 -2.43385389e-01 9.19835091e-01 3.07725251e-01 -2.43361011e-01 9.21701729e-01 3.02078873e-01 -2.43398696e-01 9.23512459e-01 2.96412319e-01 -2.43392780e-01 9.25341189e-01 2.90742993e-01 -2.43353516e-01 9.27079618e-01 2.85058498e-01 -2.43373975e-01 9.28824306e-01 2.79367059e-01 -2.43369639e-01 9.30527985e-01 2.73666054e-01 -2.43404076e-01 9.32185113e-01 2.67940909e-01 -2.43412092e-01 9.33773398e-01 2.62209833e-01 -2.43493974e-01 9.35355604e-01 2.56480366e-01 -2.43501186e-01 9.36965048e-01 2.50734270e-01 -2.43515685e-01 9.38433588e-01 2.44977653e-01 -2.43516535e-01 9.39964831e-01 2.39229426e-01 -2.43373230e-01 9.41422284e-01 2.33454749e-01 -2.43410707e-01 9.42843497e-01 2.27677792e-01 -2.43409678e-01 9.44228828e-01 2.21887067e-01 -2.43333921e-01 9.45554972e-01 2.16085255e-01 -2.43343353e-01 9.46895659e-01 2.10284516e-01 -2.43321404e-01 9.48165178e-01 2.04473361e-01 -2.43331298e-01 9.49370503e-01 1.98652104e-01 -2.43318856e-01 9.50555980e-01 1.92815810e-01 -2.43356988e-01 9.51721668e-01 1.86981589e-01 -2.43364975e-01 9.52864945e-01 1.81138247e-01 -2.43474662e-01 9.53991652e-01 1.75292522e-01 -2.43346497e-01 9.55031395e-01 1.69433728e-01 -2.43343785e-01 9.56018448e-01 1.63564190e-01 -2.43492454e-01 9.57008541e-01 1.57695696e-01 -2.43486464e-01 9.57975388e-01 1.51817992e-01 -2.43492350e-01 9.58858788e-01 1.45940542e-01 -2.43466035e-01 9.59736824e-01 1.40054211e-01 -2.43478209e-01 9.60601509e-01 1.34165317e-01 -2.43370891e-01 9.61409926e-01 1.28265291e-01 -2.43364960e-01 9.62204278e-01 1.22366995e-01 -2.43358582e-01 9.62919414e-01 1.16459966e-01 -2.43359566e-01 9.63626146e-01 1.10551193e-01 -2.43354678e-01 9.64256227e-01 1.04633756e-01 -2.43359476e-01 9.64879036e-01 9.87164825e-02 -2.43357271e-01 9.65458333e-01 9.27924886e-02 -2.43358955e-01 9.66038942e-01 8.68693218e-02 -2.43349239e-01 9.66535091e-01 8.09376910e-02 -2.43355960e-01 9.67010200e-01 7.50055760e-02 -2.43453622e-01 9.67466474e-01 6.90706000e-02 -2.43458137e-01 9.67855573e-01 6.31319210e-02 -2.43461251e-01 9.68243003e-01 5.71932718e-02 -2.43462607e-01 9.68561053e-01 5.12505583e-02 -2.43464857e-01 9.68882918e-01 4.53067347e-02 -2.43465409e-01 9.69169974e-01 3.93633135e-02 -2.43367597e-01 9.69392776e-01 3.34159695e-02 -2.43373290e-01 9.69510376e-01 2.74656545e-02 -2.43476182e-01 9.69677031e-01 2.15160903e-02 -2.43470579e-01 9.69761193e-01 1.55655388e-02 -2.43486270e-01 9.69888508e-01 9.61484388e-03 -2.43491456e-01 9.69908714e-01 3.66371381e-03 -2.43488237e-01 9.69909489e-01 -2.28751637e-03 -2.43487045e-01 9.69893157e-01 -8.23878776e-03 -2.43483186e-01 9.69822884e-01 -1.41895544e-02 -2.43486702e-01 9.69722033e-01 -2.01400444e-02 -2.43311018e-01 9.69631195e-01 -2.60895547e-02 -2.43305847e-01 9.69464540e-01 -3.20384167e-02 -2.43285239e-01 9.69234586e-01 -3.79865654e-02 -2.43281558e-01 9.68994915e-01 -4.39324044e-02 -2.43276134e-01 9.68697250e-01 -4.98775952e-02 -2.43268609e-01 9.68321621e-01 -5.58193587e-02 -2.43286073e-01 9.68003035e-01 -6.17604330e-02 -2.43263707e-01 9.67595458e-01 -6.77006319e-02 -2.43267611e-01 9.67139065e-01 -7.36360103e-02 -2.43270189e-01 9.66665983e-01 -7.95691684e-02 -2.43276551e-01 9.66172218e-01 -8.54985565e-02 -2.43283555e-01 9.65676010e-01 -9.14259776e-02 -2.43278489e-01 9.65054393e-01 -9.73481387e-02 -2.43284509e-01 9.64449763e-01 -1.03268623e-01 -2.43272811e-01 9.63801444e-01 -1.09183893e-01 -2.43279114e-01 9.63096201e-01 -1.15092300e-01 -2.43273631e-01 9.62381661e-01 -1.21003173e-01 -2.43280932e-01 9.61649418e-01 -1.26902878e-01 -2.43278563e-01 9.60799634e-01 -1.32800624e-01 -2.43304446e-01 9.59968925e-01 -1.38690934e-01 -2.43434265e-01 9.59082067e-01 -1.44580528e-01 -2.43302226e-01 9.58165348e-01 -1.50459781e-01 -2.43422255e-01 9.57205236e-01 -1.56338200e-01 -2.43489176e-01 9.56239402e-01 -1.62205935e-01 -2.43487969e-01 9.55225348e-01 -1.68069437e-01 -2.43485048e-01 9.54193652e-01 -1.73927203e-01 -2.43482083e-01 9.53094065e-01 -1.79783463e-01 -2.43481562e-01 9.51979101e-01 -1.85622901e-01 -2.43471742e-01 9.50809717e-01 -1.91457644e-01 -2.43475512e-01 9.49612916e-01 -1.97291091e-01 -2.43479088e-01 9.48372900e-01 -2.03114122e-01 -2.43486837e-01 9.47152197e-01 -2.08931923e-01 -2.43487343e-01 9.45818067e-01 -2.14737758e-01 -2.43496239e-01 9.44494247e-01 -2.20535398e-01 -2.43509024e-01 9.43133533e-01 -2.26321116e-01 -2.43517920e-01 9.41716492e-01 -2.32113644e-01 -2.43516535e-01 9.40289021e-01 -2.37883672e-01 -2.43524149e-01 9.38801646e-01 -2.43651927e-01 -2.43530110e-01 9.37278032e-01 -2.49403507e-01 -2.43535116e-01 9.35725033e-01 -2.55147755e-01 -2.43541688e-01 9.34132278e-01 -2.60884464e-01 -2.43542716e-01 9.32493091e-01 -2.66612977e-01 -2.43545949e-01 9.30834353e-01 -2.72324115e-01 -2.43550614e-01 9.29160416e-01 -2.78038383e-01 -2.43553326e-01 9.27477121e-01 -2.83731610e-01 -2.43559480e-01 9.25681770e-01 -2.89415270e-01 -2.43564308e-01 9.23921049e-01 -2.95094371e-01 -2.43573174e-01 9.22049880e-01 -3.00759524e-01 -2.43576393e-01 9.20169771e-01 -3.06402475e-01 -2.43585557e-01 9.18272853e-01 -3.12035441e-01 -2.43592054e-01 9.16359067e-01 -3.17664832e-01 -2.43593872e-01 9.14432704e-01 -3.23281348e-01 -2.43595973e-01 9.12395537e-01 -3.28893930e-01 -2.43600041e-01 9.10370350e-01 -3.34479034e-01 -2.43603855e-01 9.08303857e-01 -3.40070307e-01 -2.43604138e-01 9.06177461e-01 -3.45636457e-01 -2.43604586e-01 9.04043436e-01 -3.51187527e-01 -2.43603677e-01 9.01894808e-01 -3.56718987e-01 -2.43605167e-01 8.99691045e-01 -3.62251431e-01 -2.43623629e-01 8.97410452e-01 -3.67767036e-01 -2.43642047e-01 8.95146728e-01 -3.73269081e-01 -2.43649155e-01 8.92883420e-01 -3.78743291e-01 -2.43644670e-01 8.90522957e-01 -3.84222597e-01 -2.43639618e-01 8.88154507e-01 -3.89676660e-01 -2.43637085e-01 8.85735869e-01 -3.95120025e-01 -2.43630931e-01 8.83273482e-01 -4.00538176e-01 -2.43626520e-01 8.80827963e-01 -4.05964255e-01 -2.43627980e-01 8.78297865e-01 -4.11363065e-01 -2.43632153e-01 8.75773549e-01 -4.16736782e-01 -2.43646204e-01 8.73185813e-01 -4.22100067e-01 -2.43651927e-01 8.70578706e-01 -4.27449286e-01 -2.43657380e-01 8.67954314e-01 -4.32793409e-01 -2.43666336e-01 8.65267217e-01 -4.38092619e-01 -2.43670419e-01 8.62573206e-01 -4.43387955e-01 -2.43681356e-01 8.59818876e-01 -4.48693722e-01 -2.43702173e-01 8.57059181e-01 -4.53950584e-01 -2.43664771e-01 8.54275465e-01 -4.59202051e-01 -2.43695453e-01 8.51432621e-01 -4.64440912e-01 -2.43706971e-01 8.48534226e-01 -4.69649702e-01 -2.43714064e-01 8.45635593e-01 -4.74856436e-01 -2.43712515e-01 8.42704356e-01 -4.80034679e-01 -2.43698269e-01 8.39759767e-01 -4.85180825e-01 -2.43709132e-01 8.36774349e-01 -4.90339190e-01 -2.43709669e-01 8.33717525e-01 -4.95458484e-01 -2.43711963e-01 8.30694795e-01 -5.00556052e-01 -2.43720159e-01 8.27570319e-01 -5.05642593e-01 -2.43747905e-01 8.24459374e-01 -5.10719657e-01 -2.43764579e-01 8.21342528e-01 -5.15771627e-01 -2.43777260e-01 8.18147063e-01 -5.20787001e-01 -2.43783459e-01 8.14991474e-01 -5.25813162e-01 -2.43598089e-01 8.11677456e-01 -5.30794978e-01 -2.43743151e-01 8.08437765e-01 -5.35757542e-01 -2.43768409e-01 8.05155039e-01 -5.40727317e-01 -2.43614569e-01 8.01802039e-01 -5.45663118e-01 -2.43640363e-01 7.98437238e-01 -5.50561786e-01 -2.43630603e-01 7.95037329e-01 -5.55466592e-01 -2.43620917e-01 7.91623652e-01 -5.60335159e-01 -2.43645236e-01 7.88116693e-01 -5.65151870e-01 -2.43847415e-01 7.84657836e-01 -5.69970429e-01 -2.43838787e-01 7.81117737e-01 -5.74765086e-01 -2.43855909e-01 7.77576983e-01 -5.79550385e-01 -2.43862510e-01 7.74009645e-01 -5.84319413e-01 -2.43850350e-01 7.70447314e-01 -5.89059770e-01 -2.43815571e-01 7.66783834e-01 -5.93780935e-01 -2.43850768e-01 7.63120055e-01 -5.98446846e-01 -2.43868425e-01 7.59441555e-01 -6.03139997e-01 -2.43864089e-01 7.55744994e-01 -6.07787311e-01 -2.43862346e-01 7.51985610e-01 -6.12409055e-01 -2.43848547e-01 7.48204470e-01 -6.17018282e-01 -2.43868932e-01 7.44403720e-01 -6.21597707e-01 -2.43883878e-01 7.40605891e-01 -6.26139879e-01 -2.43866101e-01 7.36740172e-01 -6.30689323e-01 -2.43780971e-01 7.32851088e-01 -6.35187924e-01 -2.43810698e-01 7.28932500e-01 -6.39670908e-01 -2.43837968e-01 7.24998474e-01 -6.44137144e-01 -2.43829027e-01 7.21048713e-01 -6.48557246e-01 -2.43834183e-01 7.17060626e-01 -6.52987003e-01 -2.43786886e-01 7.13043451e-01 -6.57390416e-01 -2.43769050e-01 7.08992422e-01 -6.61743939e-01 -2.43778363e-01 7.04949975e-01 -6.66112721e-01 -2.43604273e-01 7.00859845e-01 -6.70432091e-01 -2.43478850e-01 6.96801245e-01 -6.74788535e-01 -2.43199542e-01 6.92640483e-01 -6.79041564e-01 -2.43238047e-01 6.88473761e-01 -6.83288991e-01 -2.43155122e-01 6.84287786e-01 -6.87516272e-01 -2.43053958e-01 6.80073798e-01 -6.91718996e-01 -2.42948130e-01 6.75835669e-01 -6.95904553e-01 -2.42823228e-01 6.71572089e-01 -7.00053453e-01 -2.42726296e-01 6.67276144e-01 -7.04173028e-01 -2.42658451e-01 6.62948787e-01 -7.08261490e-01 -2.42618278e-01 6.58603847e-01 -7.12329328e-01 -2.42544189e-01 6.54221416e-01 -7.16357648e-01 -2.42540374e-01 6.49808586e-01 -7.20353007e-01 -2.42569447e-01 6.45366192e-01 -7.24315763e-01 -2.42628366e-01 6.40980482e-01 -7.28339136e-01 -2.42210388e-01 6.36431813e-01 -7.32183933e-01 -2.42612794e-01 0. 0. 0. 0. 0. 0. 6.22955978e-01 -7.43899226e-01 -2.41950154e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.94414771e-01 -7.74910569e-01 -2.14906350e-01 5.87141931e-01 -7.75383174e-01 -2.32109696e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 5.60768664e-01 -7.99956799e-01 -2.13530779e-01 5.55324316e-01 -8.02660644e-01 -2.17602298e-01 5.46938598e-01 -8.01233530e-01 -2.42658183e-01 0. 0. 0. 0. 0. 0. 5.35661757e-01 -8.16341221e-01 -2.15994209e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.39182580e-01 -8.64376903e-01 -2.44890347e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.44278604e-01 -9.15092409e-01 -2.09947884e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 2.69388139e-01 -9.36804652e-01 -2.22818509e-01 2.62311548e-01 -9.34104323e-01 -2.42157176e-01 2.56539673e-01 -9.35576499e-01 -2.42658257e-01 2.50787407e-01 -9.37106669e-01 -2.42760941e-01 2.45024234e-01 -9.38593864e-01 -2.42881909e-01 2.39252821e-01 -9.40068305e-01 -2.42977694e-01 2.33473629e-01 -9.41482663e-01 -2.43084967e-01 2.27686912e-01 -9.42872286e-01 -2.43173003e-01 2.21889257e-01 -9.44248676e-01 -2.43280336e-01 2.16089204e-01 -9.45547223e-01 -2.43365631e-01 2.10275009e-01 -9.46832955e-01 -2.43453681e-01 2.04462379e-01 -9.48115826e-01 -2.43485764e-01 1.98637858e-01 -9.49328840e-01 -2.43514836e-01 1.92806110e-01 -9.50532973e-01 -2.43537217e-01 1.86971843e-01 -9.51686025e-01 -2.43548557e-01 1.81125700e-01 -9.52833414e-01 -2.43553191e-01 1.75277904e-01 -9.53896821e-01 -2.43578285e-01 1.69421837e-01 -9.54966962e-01 -2.43551016e-01 1.63559079e-01 -9.56001341e-01 -2.43547440e-01 1.57688469e-01 -9.56976593e-01 -2.43560418e-01 1.51814550e-01 -9.57926333e-01 -2.43550032e-01 1.45934477e-01 -9.58844602e-01 -2.43550763e-01 1.40046090e-01 -9.59704578e-01 -2.43577972e-01 1.34154662e-01 -9.60540950e-01 -2.43585467e-01 1.28257811e-01 -9.61356819e-01 -2.43574604e-01 1.22358419e-01 -9.62148190e-01 -2.43571728e-01 1.16452076e-01 -9.62859213e-01 -2.43609264e-01 1.10541023e-01 -9.63561893e-01 -2.43612066e-01 1.04626767e-01 -9.64191079e-01 -2.43623793e-01 9.87083167e-02 -9.64810133e-01 -2.43622065e-01 9.27863792e-02 -9.65395153e-01 -2.43643895e-01 8.68591070e-02 -9.65951204e-01 -2.43665278e-01 8.09314102e-02 -9.66451943e-01 -2.43679702e-01 7.49986246e-02 -9.66928661e-01 -2.43676394e-01 6.90627471e-02 -9.67371941e-01 -2.43691936e-01 6.31272718e-02 -9.67810452e-01 -2.43687704e-01 5.71864992e-02 -9.68163788e-01 -2.43710086e-01 5.12454659e-02 -9.68516827e-01 -2.43684620e-01 4.53025550e-02 -9.68789458e-01 -2.43685812e-01 3.93570475e-02 -9.69033659e-01 -2.43729174e-01 3.34097110e-02 -9.69252288e-01 -2.43763834e-01 2.74620429e-02 -9.69465137e-01 -2.43732616e-01 2.15147957e-02 -9.69646811e-01 -2.43573382e-01 1.55654820e-02 -9.69784498e-01 -2.43491322e-01 9.61468928e-03 -9.69859302e-01 -2.43510768e-01 3.66371335e-03 -9.69903350e-01 -2.43489951e-01 -2.28758599e-03 -9.69896913e-01 -2.43508220e-01 -8.23874120e-03 -9.69866395e-01 -2.43507788e-01 -1.41893914e-02 -9.69784856e-01 -2.43496165e-01 -2.01398302e-02 -9.69696641e-01 -2.43418634e-01 -2.60894727e-02 -9.69560802e-01 -2.43446335e-01 -3.20376866e-02 -9.69382823e-01 -2.43528768e-01 -3.79854143e-02 -9.69155431e-01 -2.43529215e-01 -4.39311117e-02 -9.68911767e-01 -2.43529320e-01 -4.98757921e-02 -9.68602359e-01 -2.43531659e-01 -5.58189601e-02 -9.68307495e-01 -2.43424430e-01 -6.17582239e-02 -9.67923999e-01 -2.43518993e-01 -6.76960871e-02 -9.67528880e-01 -2.43532941e-01 -7.36308470e-02 -9.67086554e-01 -2.43540242e-01 -7.95636252e-02 -9.66612637e-01 -2.43541151e-01 -8.54932144e-02 -9.66114521e-01 -2.43520498e-01 -9.14206281e-02 -9.65602994e-01 -2.43484780e-01 -9.73437950e-02 -9.65011418e-01 -2.43528008e-01 -1.03263795e-01 -9.64383423e-01 -2.43503198e-01 -1.09177463e-01 -9.63746309e-01 -2.43505284e-01 -1.15089886e-01 -9.63041961e-01 -2.43513897e-01 -1.20995857e-01 -9.62325335e-01 -2.43517444e-01 -1.26896858e-01 -9.61557865e-01 -2.43533999e-01 -1.32793352e-01 -9.60746348e-01 -2.43621573e-01 -1.38683379e-01 -9.59885657e-01 -2.43739098e-01 -1.44569471e-01 -9.58974361e-01 -2.43761152e-01 -1.50446653e-01 -9.58099186e-01 -2.43786201e-01 -1.56325877e-01 -9.57167029e-01 -2.43734568e-01 -1.62193239e-01 -9.56181824e-01 -2.43780598e-01 -1.68059453e-01 -9.55163836e-01 -2.43729532e-01 -1.73914462e-01 -9.54090059e-01 -2.43776351e-01 -1.79770514e-01 -9.53028142e-01 -2.43746907e-01 -1.85610309e-01 -9.51927483e-01 -2.43760124e-01 -1.91448316e-01 -9.50767338e-01 -2.43757948e-01 -1.97277650e-01 -9.49564993e-01 -2.43764475e-01 -2.03101113e-01 -9.48313534e-01 -2.43774563e-01 -2.08920553e-01 -9.47074056e-01 -2.43793055e-01 -2.14720905e-01 -9.45753634e-01 -2.43856028e-01 -2.20522925e-01 -9.44394350e-01 -2.43840039e-01 -2.26306930e-01 -9.43052828e-01 -2.43855283e-01 -2.32095420e-01 -9.41641927e-01 -2.43849829e-01 -2.37869903e-01 -9.40216959e-01 -2.43843868e-01 -2.43635133e-01 -9.38712597e-01 -2.43839487e-01 -2.49386922e-01 -9.37231064e-01 -2.43838608e-01 -2.55140185e-01 -9.35682535e-01 -2.43676603e-01 -2.60875970e-01 -9.34095204e-01 -2.43735373e-01 -2.66601235e-01 -9.32447493e-01 -2.43793219e-01 -2.72314936e-01 -9.30793822e-01 -2.43794963e-01 -2.78025210e-01 -9.29129839e-01 -2.43731067e-01 -2.83726662e-01 -9.27446485e-01 -2.43681520e-01 -2.89400607e-01 -9.25657570e-01 -2.43802160e-01 -2.95084774e-01 -9.23884809e-01 -2.43729219e-01 -3.00746143e-01 -9.22019482e-01 -2.43761018e-01 -3.06392431e-01 -9.20147538e-01 -2.43765384e-01 -3.12026203e-01 -9.18239594e-01 -2.43809864e-01 -3.17656994e-01 -9.16330993e-01 -2.43768916e-01 -3.23271036e-01 -9.14373100e-01 -2.43805081e-01 -3.28881204e-01 -9.12382901e-01 -2.43799403e-01 -3.34468544e-01 -9.10307467e-01 -2.43829221e-01 -3.40055555e-01 -9.08265650e-01 -2.43814826e-01 -3.45622957e-01 -9.06136811e-01 -2.43826702e-01 -3.51178378e-01 -9.04011011e-01 -2.43785396e-01 -3.56704742e-01 -9.01856482e-01 -2.43813902e-01 -3.62243742e-01 -8.99634659e-01 -2.43786186e-01 -3.67756873e-01 -8.97381127e-01 -2.43807092e-01 -3.73266757e-01 -8.95147204e-01 -2.43718326e-01 -3.78746510e-01 -8.92883122e-01 -2.43627727e-01 -3.84228408e-01 -8.90533745e-01 -2.43616492e-01 -3.89692008e-01 -8.88166845e-01 -2.43567958e-01 -3.95150661e-01 -8.85767400e-01 -2.43429422e-01 -4.00565267e-01 -8.83348346e-01 -2.43431747e-01 -4.05955613e-01 -8.80808473e-01 -2.43746772e-01 -4.11344141e-01 -8.78302097e-01 -2.43755832e-01 -4.16726351e-01 -8.75725329e-01 -2.43778855e-01 -4.22102392e-01 -8.73146117e-01 -2.43759975e-01 -4.27445114e-01 -8.70546222e-01 -2.43737578e-01 -4.32773173e-01 -8.67914855e-01 -2.43753970e-01 -4.38098699e-01 -8.65275741e-01 -2.43739277e-01 -4.43390220e-01 -8.62558305e-01 -2.43762866e-01 -4.48684722e-01 -8.59826028e-01 -2.43770644e-01 -4.53947484e-01 -8.57013941e-01 -2.43803486e-01 -4.59181339e-01 -8.54251564e-01 -2.43796974e-01 -4.64428812e-01 -8.51407409e-01 -2.43810266e-01 -4.69639868e-01 -8.48506808e-01 -2.43816689e-01 -4.74844247e-01 -8.45636725e-01 -2.43802473e-01 -4.80009526e-01 -8.42682838e-01 -2.43819907e-01 -4.85172033e-01 -8.39725375e-01 -2.43804991e-01 -4.90322798e-01 -8.36762547e-01 -2.43771926e-01 -4.95453298e-01 -8.33717346e-01 -2.43767545e-01 -5.00558615e-01 -8.30700397e-01 -2.43738413e-01 -5.05660057e-01 -8.27607453e-01 -2.43641630e-01 -5.10733485e-01 -8.24490845e-01 -2.43643194e-01 -5.15783727e-01 -8.21369886e-01 -2.43599355e-01 -5.20809054e-01 -8.18172455e-01 -2.43618742e-01 -5.25853455e-01 -8.15011442e-01 -2.43362889e-01 -5.30882120e-01 -8.11835766e-01 -2.43086427e-01 -5.35886347e-01 -8.08613122e-01 -2.42837533e-01 -5.41047275e-01 -8.05635810e-01 -2.41263315e-01 -5.45718849e-01 -8.01898301e-01 -2.43206650e-01 -5.50630033e-01 -7.98536479e-01 -2.43199259e-01 -5.55465639e-01 -7.95072317e-01 -2.43563816e-01 -5.60337305e-01 -7.91626573e-01 -2.43631691e-01 -5.65207958e-01 -7.88224399e-01 -2.43383676e-01 -5.70094466e-01 -7.84830213e-01 -2.42967442e-01 -5.74898541e-01 -7.81316638e-01 -2.42971510e-01 -5.79724908e-01 -7.77834773e-01 -2.42672235e-01 -5.84554613e-01 -7.74357319e-01 -2.42202431e-01 -5.89192688e-01 -7.70615041e-01 -2.42905304e-01 -5.93838871e-01 -7.66891658e-01 -2.43359476e-01 -5.98491251e-01 -7.63175905e-01 -2.43608624e-01 -6.03178203e-01 -7.59508789e-01 -2.43530855e-01 -6.07844710e-01 -7.55797565e-01 -2.43480340e-01 -6.12480819e-01 -7.52078295e-01 -2.43380129e-01 -6.17105246e-01 -7.48322129e-01 -2.43296325e-01 -6.21688187e-01 -7.44544864e-01 -2.43206754e-01 -6.26259863e-01 -7.40736365e-01 -2.43121594e-01 -6.30799711e-01 -7.36886144e-01 -2.43088514e-01 -6.35309279e-01 -7.33001351e-01 -2.43089169e-01 -6.39842629e-01 -7.29145586e-01 -2.42787644e-01 -6.45245612e-01 -7.26312101e-01 -2.36889035e-01 -6.50006473e-01 -7.22706676e-01 -2.34918356e-01 -6.54445112e-01 -7.18723714e-01 -2.34814450e-01 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.62082994e-01 -5.99371314e-01 -2.44915381e-01 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. 0. 0. -8.02631557e-01 -5.47937632e-01 -2.35683978e-01 -8.05949271e-01 -5.42981863e-01 -2.35831618e-01 -8.09275031e-01 -5.38032889e-01 -2.35784888e-01 -8.12531948e-01 -5.33037007e-01 -2.35930905e-01 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. 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. -8.67114067e-01 -4.33901459e-01 -2.44627804e-01 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. 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. 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. 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. 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. 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. 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. -9.67878103e-01 -5.71646094e-02 -2.44834840e-01 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. 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.12422836e-01 2.97697276e-01 -2.80821949e-01 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. 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. 0. 0. 0. 0. 0. 0. 0. -8.63852918e-01 4.17689115e-01 -2.81591922e-01 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. -8.36708367e-01 4.69925612e-01 -2.81227887e-01 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. 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. 0. 0. 0. 0. -7.69280016e-01 5.73468328e-01 -2.81677783e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -7.48040378e-01 6.01696372e-01 -2.79994786e-01 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. 0. 0. -7.12417364e-01 6.56684399e-01 -2.47441009e-01 0. 0. 0. 0. 0. 0. -6.93400204e-01 6.63419724e-01 -2.81194627e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -6.72740817e-01 6.84394360e-01 -2.81112224e-01 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. 0. 0. 0. 0. 0. -6.20871842e-01 7.32372105e-01 -2.79551804e-01 -6.16375268e-01 7.36177981e-01 -2.79505938e-01 -6.11833096e-01 7.39930391e-01 -2.79569894e-01 -6.07275069e-01 7.43660688e-01 -2.79618531e-01 -6.02679014e-01 7.47344315e-01 -2.79742986e-01 -5.98062456e-01 7.51026928e-01 -2.79815406e-01 -5.93438923e-01 7.54647255e-01 -2.79919952e-01 -5.88771224e-01 7.58259416e-01 -2.79962867e-01 -5.84120393e-01 7.61852264e-01 -2.79996008e-01 -5.79437196e-01 7.65431166e-01 -2.79946029e-01 -5.74716508e-01 7.68983662e-01 -2.79966146e-01 -5.69995403e-01 7.72498608e-01 -2.79926538e-01 -5.65245807e-01 7.75967538e-01 -2.79938549e-01 -5.60459614e-01 7.79419482e-01 -2.79962599e-01 -5.55622935e-01 7.82770574e-01 -2.80271947e-01 -5.50819516e-01 7.86177695e-01 -2.80201644e-01 -5.45978248e-01 7.89543629e-01 -2.80255705e-01 -5.41116059e-01 7.92861640e-01 -2.80304462e-01 -5.36234975e-01 7.96148241e-01 -2.80345649e-01 -5.31337798e-01 7.99432933e-01 -2.80322045e-01 -5.26449919e-01 8.02709639e-01 -2.80214041e-01 -5.21491230e-01 8.05896103e-01 -2.80318677e-01 -5.16520858e-01 8.09056878e-01 -2.80416012e-01 0. 0. 0. 0. 0. 0. -5.01502812e-01 8.18366945e-01 -2.80660897e-01 -4.96499181e-01 8.21473062e-01 -2.80491412e-01 -4.91467208e-01 8.24539423e-01 -2.80374974e-01 -4.86393273e-01 8.27537000e-01 -2.80379802e-01 -4.81313884e-01 8.30500066e-01 -2.80361444e-01 -4.76185083e-01 8.33401442e-01 -2.80516654e-01 0. 0. 0. 0. 0. 0. -4.60750908e-01 8.42001915e-01 -2.80608922e-01 -4.55583125e-01 8.44826162e-01 -2.80558407e-01 -4.50392455e-01 8.47606182e-01 -2.80556232e-01 -4.45179462e-01 8.50346565e-01 -2.80559659e-01 -4.39951688e-01 8.53068948e-01 -2.80621052e-01 -4.34714615e-01 8.55744839e-01 -2.80565500e-01 -4.29450184e-01 8.58411252e-01 -2.80562133e-01 -4.24176544e-01 8.61019552e-01 -2.80560613e-01 -4.18883979e-01 8.63600016e-01 -2.80565530e-01 -4.13578898e-01 8.66159976e-01 -2.80563176e-01 -4.08257514e-01 8.68675232e-01 -2.80579060e-01 -4.02914852e-01 8.71173322e-01 -2.80587405e-01 -3.97565812e-01 8.73610258e-01 -2.80592948e-01 -3.92192930e-01 8.76050472e-01 -2.80592054e-01 -3.86816233e-01 8.78440917e-01 -2.80594200e-01 -3.81410927e-01 8.80791605e-01 -2.80610979e-01 -3.76005530e-01 8.83118570e-01 -2.80616879e-01 -3.70573997e-01 8.85411799e-01 -2.80608624e-01 -3.65142345e-01 8.87656271e-01 -2.80597776e-01 -3.59681159e-01 8.89881551e-01 -2.80599773e-01 -3.54220957e-01 8.92064750e-01 -2.80616552e-01 -3.48737478e-01 8.94215345e-01 -2.80640185e-01 -3.43290865e-01 8.96474540e-01 -2.80151188e-01 -3.37782681e-01 8.98556709e-01 -2.80159682e-01 -3.32220554e-01 9.00501311e-01 -2.80633956e-01 -3.26683253e-01 9.02523100e-01 -2.80640453e-01 -3.21145743e-01 9.04514253e-01 -2.80620068e-01 -3.15590084e-01 9.06477094e-01 -2.80575871e-01 -3.10024709e-01 9.08400595e-01 -2.80562311e-01 -3.04437816e-01 9.10273790e-01 -2.80574411e-01 -2.98854679e-01 9.12138164e-01 -2.80572534e-01 -2.93249547e-01 9.13954020e-01 -2.80548096e-01 -2.87637115e-01 9.15726125e-01 -2.80546904e-01 -2.82012820e-01 9.17481840e-01 -2.80541837e-01 -2.76377738e-01 9.19182420e-01 -2.80550838e-01 -2.70733118e-01 9.20879304e-01 -2.80538857e-01 -2.65076548e-01 9.22518015e-01 -2.80548930e-01 -2.59410143e-01 9.24111128e-01 -2.80567378e-01 -2.53731728e-01 9.25691187e-01 -2.80593693e-01 -2.48050779e-01 9.27224398e-01 -2.80553639e-01 -2.42358223e-01 9.28734541e-01 -2.80564964e-01 -2.36650139e-01 9.30191696e-01 -2.80588478e-01 -2.30938956e-01 9.31637347e-01 -2.80578524e-01 -2.25221336e-01 9.33034778e-01 -2.80599713e-01 -2.19488829e-01 9.34402287e-01 -2.80601233e-01 -2.13750422e-01 9.35721397e-01 -2.80614257e-01 -2.08003804e-01 9.37018573e-01 -2.80603349e-01 -2.02254817e-01 9.38266277e-01 -2.80620247e-01 -1.96490541e-01 9.39508021e-01 -2.80604362e-01 -1.90721810e-01 9.40692008e-01 -2.80592084e-01 -1.84948355e-01 9.41835582e-01 -2.80589670e-01 -1.79164812e-01 9.42960024e-01 -2.80586004e-01 -1.73377544e-01 9.44025755e-01 -2.80587405e-01 -1.67579725e-01 9.45078433e-01 -2.80588150e-01 -1.61778659e-01 9.46111202e-01 -2.80592948e-01 -1.55970484e-01 9.47065711e-01 -2.80580968e-01 -1.50158674e-01 9.48017478e-01 -2.80547202e-01 -1.44338429e-01 9.48940516e-01 -2.80549049e-01 -1.38512820e-01 9.49791789e-01 -2.80552179e-01 -1.32682234e-01 9.50616658e-01 -2.80548304e-01 -1.26848206e-01 9.51410949e-01 -2.80566037e-01 -1.21007003e-01 9.52195406e-01 -2.80567259e-01 -1.15161650e-01 9.52918112e-01 -2.80570865e-01 -1.09313622e-01 9.53598201e-01 -2.80576736e-01 -1.03458256e-01 9.54229057e-01 -2.80606627e-01 -9.76009294e-02 9.54874218e-01 -2.80595601e-01 -9.17413533e-02 9.55410719e-01 -2.80591220e-01 -8.58776718e-02 9.55967784e-01 -2.80600697e-01 -8.00089911e-02 9.56458569e-01 -2.80615211e-01 -7.41370767e-02 9.56959307e-01 -2.80663878e-01 -6.82623982e-02 9.57356811e-01 -2.80723780e-01 -6.23870306e-02 9.57774699e-01 -2.80723035e-01 -5.65099306e-02 9.58158791e-01 -2.80671984e-01 -5.06305173e-02 9.58499432e-01 -2.80633450e-01 -4.47490923e-02 9.58764076e-01 -2.80634701e-01 -3.88647988e-02 9.59017754e-01 -2.80645460e-01 -3.29799205e-02 9.59237576e-01 -2.80637503e-01 -2.70931479e-02 9.59428251e-01 -2.80679107e-01 -2.12051198e-02 9.59559023e-01 -2.80723482e-01 -1.53172435e-02 9.59690750e-01 -2.80673116e-01 -9.42866970e-03 9.59781528e-01 -2.80659467e-01 -3.53931542e-03 9.59805250e-01 -2.80679196e-01 2.34991778e-03 9.59807396e-01 -2.80672908e-01 8.23916588e-03 9.59773719e-01 -2.80696869e-01 1.41280079e-02 9.59694266e-01 -2.80668288e-01 2.00163387e-02 9.59586322e-01 -2.80660301e-01 2.59041190e-02 9.59449410e-01 -2.80698955e-01 3.17909867e-02 9.59316969e-01 -2.80623078e-01 3.76763828e-02 9.59093094e-01 -2.80609757e-01 4.35606800e-02 9.58853424e-01 -2.80602723e-01 4.94429804e-02 9.58530188e-01 -2.80634135e-01 5.53235710e-02 9.58219409e-01 -2.80652404e-01 6.12019300e-02 9.57859635e-01 -2.80659825e-01 6.70781210e-02 9.57478464e-01 -2.80626774e-01 7.29502738e-02 9.57026064e-01 -2.80690670e-01 7.88228586e-02 9.56581831e-01 -2.80621231e-01 8.46900493e-02 9.56069827e-01 -2.80640304e-01 9.05551687e-02 9.55537617e-01 -2.80622035e-01 9.64173824e-02 9.54968214e-01 -2.80644953e-01 1.02273427e-01 9.54336464e-01 -2.80668139e-01 1.08128220e-01 9.53710675e-01 -2.80657291e-01 1.13978349e-01 9.53020155e-01 -2.80641854e-01 1.19825050e-01 9.52321708e-01 -2.80614287e-01 1.25664547e-01 9.51550424e-01 -2.80611157e-01 1.31502002e-01 9.50783074e-01 -2.80645132e-01 1.37331709e-01 9.49926853e-01 -2.80647546e-01 1.43159047e-01 9.49081540e-01 -2.80640662e-01 1.48979068e-01 9.48182285e-01 -2.80623496e-01 1.54794872e-01 9.47279692e-01 -2.80610681e-01 1.60603359e-01 9.46280301e-01 -2.80645519e-01 1.66403189e-01 9.45275724e-01 -2.80683607e-01 1.72200918e-01 9.44220960e-01 -2.80700475e-01 1.77989706e-01 9.43157792e-01 -2.80699700e-01 1.83772370e-01 9.42032695e-01 -2.80719548e-01 1.89552382e-01 9.40890253e-01 -2.80730397e-01 1.95319936e-01 9.39698756e-01 -2.80721724e-01 2.01079845e-01 9.38476503e-01 -2.80733973e-01 2.06834391e-01 9.37238097e-01 -2.80739963e-01 2.12584093e-01 9.35943365e-01 -2.80735105e-01 2.18319476e-01 9.34617162e-01 -2.80729234e-01 2.24053115e-01 9.33261991e-01 -2.80726522e-01 2.29771018e-01 9.31878984e-01 -2.80769646e-01 2.35489637e-01 9.30437326e-01 -2.80735224e-01 2.41192758e-01 9.28977728e-01 -2.80727893e-01 2.46891752e-01 9.27504718e-01 -2.80690521e-01 2.52576590e-01 9.25972462e-01 -2.80693769e-01 2.58255482e-01 9.24410403e-01 -2.80683488e-01 2.63925970e-01 9.22815502e-01 -2.80642658e-01 2.69588023e-01 9.21196282e-01 -2.80574054e-01 2.75243312e-01 9.19552684e-01 -2.80470461e-01 2.80891836e-01 9.17886496e-01 -2.80328512e-01 2.86543161e-01 9.16229784e-01 -2.80028522e-01 0. 0. 0. 2.98124731e-01 9.13819671e-01 -2.75781274e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 3.83915365e-01 8.90053332e-01 -2.45792896e-01 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. 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. 0. 0. 0. 0. 4.90335077e-01 8.24953675e-01 -2.81110257e-01 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. 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. 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. 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. 6.68241858e-01 6.89937532e-01 -2.78278679e-01 6.72440469e-01 6.85800910e-01 -2.78389335e-01 6.76555216e-01 6.81578279e-01 -2.78789312e-01 6.80666268e-01 6.77353501e-01 -2.79081285e-01 6.84771061e-01 6.73124135e-01 -2.79273570e-01 6.88865244e-01 6.68885410e-01 -2.79388160e-01 6.92913830e-01 6.64607227e-01 -2.79583395e-01 6.96955323e-01 6.60320818e-01 -2.79695988e-01 7.00962365e-01 6.55999839e-01 -2.79841721e-01 7.04965651e-01 6.51676357e-01 -2.79888242e-01 7.08939910e-01 6.47328854e-01 -2.79938340e-01 7.12904692e-01 6.42973781e-01 -2.79902965e-01 7.16840386e-01 6.38589144e-01 -2.79894859e-01 7.20758796e-01 6.34191155e-01 -2.79841572e-01 7.24627733e-01 6.29750311e-01 -2.79870749e-01 7.28495002e-01 6.25305653e-01 -2.79801786e-01 7.32320905e-01 6.20826900e-01 -2.79788077e-01 7.36124456e-01 6.16327345e-01 -2.79751718e-01 7.39888847e-01 6.11797869e-01 -2.79756427e-01 7.43633389e-01 6.07250154e-01 -2.79743105e-01 7.47337818e-01 6.02668166e-01 -2.79772431e-01 7.51006007e-01 5.98060429e-01 -2.79842556e-01 7.54662633e-01 5.93439639e-01 -2.79846996e-01 7.58280158e-01 5.88789284e-01 -2.79889852e-01 7.61883676e-01 5.84131300e-01 -2.79867470e-01 7.65447557e-01 5.79442561e-01 -2.79880375e-01 7.68980205e-01 5.74730396e-01 -2.79913902e-01 7.72466898e-01 5.69978714e-01 -2.80016035e-01 7.75976419e-01 5.65249324e-01 -2.79917985e-01 7.79404998e-01 5.60453534e-01 -2.80042797e-01 7.82823205e-01 5.55662930e-01 -2.80059069e-01 7.86220849e-01 5.50843596e-01 -2.80049980e-01 7.89598346e-01 5.46013832e-01 -2.80020803e-01 7.92919874e-01 5.41159630e-01 -2.80052304e-01 7.96217620e-01 5.36276817e-01 -2.80068278e-01 7.99507678e-01 5.31389594e-01 -2.80021101e-01 8.02756965e-01 5.26474595e-01 -2.80004472e-01 8.05974722e-01 5.21543205e-01 -2.79992729e-01 8.09142828e-01 5.16579628e-01 -2.80061483e-01 8.12294662e-01 5.11602402e-01 -2.80061603e-01 8.15399110e-01 5.06591797e-01 -2.80174106e-01 8.18530202e-01 5.01602948e-01 -2.80030012e-01 8.21582675e-01 4.96566355e-01 -2.80056804e-01 8.24577212e-01 4.91489381e-01 -2.80229986e-01 8.27567279e-01 4.86411095e-01 -2.80268610e-01 8.30513895e-01 4.81324226e-01 -2.80285150e-01 8.33470285e-01 4.76217717e-01 -2.80295342e-01 8.36361766e-01 4.71102655e-01 -2.80290067e-01 8.39236498e-01 4.65956628e-01 -2.80287564e-01 8.42088044e-01 4.60800499e-01 -2.80280530e-01 8.44905138e-01 4.55626577e-01 -2.80254126e-01 8.47674131e-01 4.50431615e-01 -2.80264825e-01 8.50431323e-01 4.45216507e-01 -2.80280501e-01 8.53151321e-01 4.40002620e-01 -2.80236751e-01 8.55835795e-01 4.34751481e-01 -2.80241072e-01 8.58486891e-01 4.29498523e-01 -2.80232757e-01 8.61111581e-01 4.24223274e-01 -2.80236125e-01 8.63695562e-01 4.18928593e-01 -2.80219704e-01 8.66245210e-01 4.13625896e-01 -2.80219287e-01 8.68769646e-01 4.08306360e-01 -2.80222774e-01 8.71251702e-01 4.02966142e-01 -2.80237049e-01 8.73700440e-01 3.97607148e-01 -2.80225396e-01 8.76190126e-01 3.92265022e-01 -2.80066460e-01 8.78536522e-01 3.86866331e-01 -2.80192196e-01 8.80887330e-01 3.81469190e-01 -2.80192405e-01 8.83253574e-01 3.76066923e-01 -2.80047625e-01 8.85517597e-01 3.70627046e-01 -2.80216783e-01 8.87753546e-01 3.65184724e-01 -2.80219585e-01 8.89981270e-01 3.59731376e-01 -2.80213505e-01 8.92203808e-01 3.54265898e-01 -2.80131876e-01 8.94334555e-01 3.48785996e-01 -2.80171603e-01 8.96484733e-01 3.43293518e-01 -2.80090094e-01 8.98573220e-01 3.37787181e-01 -2.80084550e-01 9.00619507e-01 3.32260758e-01 -2.80203342e-01 9.02637064e-01 3.26730371e-01 -2.80203730e-01 9.04666245e-01 3.21200848e-01 -2.80053258e-01 9.06633973e-01 3.15641463e-01 -2.80039400e-01 9.08495843e-01 3.10056776e-01 -2.80207485e-01 9.10398960e-01 3.04489195e-01 -2.80105472e-01 9.12284493e-01 2.98899144e-01 -2.80043960e-01 9.14073110e-01 2.93295532e-01 -2.80056089e-01 9.15880382e-01 2.87689269e-01 -2.80000865e-01 9.17611897e-01 2.82066584e-01 -2.79987037e-01 9.19337690e-01 2.76427597e-01 -2.79993325e-01 9.21000957e-01 2.70780712e-01 -2.80004233e-01 9.22642529e-01 2.65124440e-01 -2.80011058e-01 9.24267113e-01 2.59457231e-01 -2.79989094e-01 9.25873041e-01 2.53783673e-01 -2.79994160e-01 9.27398562e-01 2.48092845e-01 -2.80002952e-01 9.28921461e-01 2.42403820e-01 -2.79983699e-01 9.30342317e-01 2.36689374e-01 -2.80043066e-01 9.31777418e-01 2.30977625e-01 -2.80021399e-01 9.33183551e-01 2.25262433e-01 -2.80020177e-01 9.34564173e-01 2.19527215e-01 -2.80016959e-01 9.35878098e-01 2.13795573e-01 -2.80011833e-01 9.37125444e-01 2.08030209e-01 -2.80172199e-01 9.38425779e-01 2.02291355e-01 -2.80043662e-01 9.39612329e-01 1.96516678e-01 -2.80145347e-01 9.40828741e-01 1.90747097e-01 -2.80149698e-01 9.41942215e-01 1.84973583e-01 -2.80141026e-01 9.43082213e-01 1.79192975e-01 -2.80146092e-01 9.44145679e-01 1.73399895e-01 -2.80156404e-01 9.45195317e-01 1.67601928e-01 -2.80154198e-01 9.46237147e-01 1.61801219e-01 -2.80141175e-01 9.47190285e-01 1.55993342e-01 -2.80144572e-01 9.48130131e-01 1.50176689e-01 -2.80149966e-01 9.49046731e-01 1.44359350e-01 -2.80146480e-01 9.49898481e-01 1.38532534e-01 -2.80146986e-01 9.50731277e-01 1.32703140e-01 -2.80131072e-01 9.51528311e-01 1.26864821e-01 -2.80132204e-01 9.52314138e-01 1.21026024e-01 -2.80131370e-01 9.53030884e-01 1.15179397e-01 -2.80138671e-01 9.53719318e-01 1.09327957e-01 -2.80134469e-01 9.54354048e-01 1.03475563e-01 -2.80133545e-01 9.55006242e-01 9.76175070e-02 -2.80145496e-01 9.55529869e-01 9.17557254e-02 -2.80144364e-01 9.56101775e-01 8.58898982e-02 -2.80142277e-01 9.56589878e-01 8.00221711e-02 -2.80151010e-01 9.57106888e-01 7.41503388e-02 -2.80175388e-01 9.57515121e-01 6.82761967e-02 -2.80173689e-01 9.57918346e-01 6.24001473e-02 -2.80183643e-01 9.58296061e-01 5.65207489e-02 -2.80183315e-01 9.58615243e-01 5.06397262e-02 -2.80190319e-01 9.58945334e-01 4.47601043e-02 -2.80049652e-01 9.59202111e-01 3.88751812e-02 -2.80035049e-01 9.59421515e-01 3.29881869e-02 -2.80043095e-01 9.59552288e-01 2.70992741e-02 -2.80180722e-01 9.59703088e-01 2.12109424e-02 -2.80206203e-01 9.59798455e-01 1.53216990e-02 -2.80236632e-01 9.59905207e-01 9.43209138e-03 -2.80231982e-01 9.59929764e-01 3.54218762e-03 -2.80230314e-01 9.59930539e-01 -2.34784652e-03 -2.80228287e-01 9.59912539e-01 -8.23778473e-03 -2.80220717e-01 9.59827602e-01 -1.41273588e-02 -2.80224770e-01 9.59703445e-01 -2.00166050e-02 -2.80227900e-01 9.59591806e-01 -2.59049777e-02 -2.80227989e-01 9.59438384e-01 -3.17927636e-02 -2.80221939e-01 9.59208727e-01 -3.76782902e-02 -2.80223131e-01 9.58970904e-01 -4.35633883e-02 -2.80220866e-01 9.58660662e-01 -4.94468883e-02 -2.80209839e-01 9.58317816e-01 -5.53277768e-02 -2.80222535e-01 9.57974434e-01 -6.12075105e-02 -2.80219048e-01 9.57595229e-01 -6.70844987e-02 -2.80207396e-01 9.57147777e-01 -7.29584396e-02 -2.80208051e-01 9.56676185e-01 -7.88305327e-02 -2.80217171e-01 9.56186533e-01 -8.46977383e-02 -2.80217618e-01 9.55638111e-01 -9.05645341e-02 -2.80211806e-01 9.55091715e-01 -9.64275673e-02 -2.80229926e-01 9.54454482e-01 -1.02285415e-01 -2.80235231e-01 9.53828931e-01 -1.08138189e-01 -2.80243486e-01 9.53134120e-01 -1.13990255e-01 -2.80234516e-01 9.52426970e-01 -1.19836614e-01 -2.80241698e-01 9.51642931e-01 -1.25677153e-01 -2.80255973e-01 9.50881362e-01 -1.31513029e-01 -2.80262142e-01 9.50056791e-01 -1.37344554e-01 -2.80266672e-01 9.49158251e-01 -1.43170625e-01 -2.80276418e-01 9.48286116e-01 -1.48992881e-01 -2.80278057e-01 9.47360218e-01 -1.54807553e-01 -2.80282527e-01 9.46393788e-01 -1.60619020e-01 -2.80281812e-01 9.45382416e-01 -1.66421682e-01 -2.80290395e-01 9.44352627e-01 -1.72220469e-01 -2.80264944e-01 9.43273544e-01 -1.78010568e-01 -2.80270100e-01 9.42122281e-01 -1.83793262e-01 -2.80281663e-01 9.40998554e-01 -1.89568520e-01 -2.80292034e-01 9.39824581e-01 -1.95338368e-01 -2.80284822e-01 9.38583016e-01 -2.01101512e-01 -2.80293405e-01 9.37382638e-01 -2.06858560e-01 -2.80294329e-01 9.36073422e-01 -2.12610915e-01 -2.80294359e-01 9.34738636e-01 -2.18346104e-01 -2.80304521e-01 9.33402538e-01 -2.24078506e-01 -2.80308694e-01 9.32006717e-01 -2.29795471e-01 -2.80323476e-01 9.30577517e-01 -2.35517085e-01 -2.80353576e-01 9.29088116e-01 -2.41215289e-01 -2.80366212e-01 9.27569211e-01 -2.46915162e-01 -2.80379444e-01 9.26055014e-01 -2.52601415e-01 -2.80379981e-01 9.24498320e-01 -2.58278489e-01 -2.80384094e-01 9.22864854e-01 -2.63942063e-01 -2.80386806e-01 9.21218634e-01 -2.69602776e-01 -2.80407846e-01 9.19572353e-01 -2.75244981e-01 -2.80406177e-01 9.17848766e-01 -2.80882180e-01 -2.80407339e-01 9.16134477e-01 -2.86506176e-01 -2.80418992e-01 9.14327800e-01 -2.92120248e-01 -2.80429214e-01 9.12535250e-01 -2.97732919e-01 -2.80431598e-01 9.10664678e-01 -3.03318083e-01 -2.80442685e-01 9.08788979e-01 -3.08910131e-01 -2.80442744e-01 9.06902134e-01 -3.14479440e-01 -2.80449688e-01 9.04939055e-01 -3.20038855e-01 -2.80451834e-01 9.02942419e-01 -3.25571984e-01 -2.80460745e-01 9.00937796e-01 -3.31117302e-01 -2.80460328e-01 8.98913383e-01 -3.36633682e-01 -2.80459702e-01 8.96826982e-01 -3.42142522e-01 -2.80454040e-01 8.94705594e-01 -3.47643077e-01 -2.80485123e-01 8.92542601e-01 -3.53122652e-01 -2.80479938e-01 8.90371978e-01 -3.58598292e-01 -2.80479819e-01 8.88154566e-01 -3.64050567e-01 -2.80460209e-01 8.85911167e-01 -3.69499177e-01 -2.80450374e-01 8.83602560e-01 -3.74928206e-01 -2.80439526e-01 8.81289661e-01 -3.80341917e-01 -2.80413479e-01 8.78944695e-01 -3.85737598e-01 -2.80405670e-01 8.76569510e-01 -3.91125917e-01 -2.80411005e-01 8.74138117e-01 -3.96504492e-01 -2.80408919e-01 8.71721029e-01 -4.01846141e-01 -2.80451775e-01 8.69205594e-01 -4.07187492e-01 -2.80444145e-01 8.66709292e-01 -4.12509143e-01 -2.80470490e-01 8.64137471e-01 -4.17828590e-01 -2.80478001e-01 8.61543000e-01 -4.23107326e-01 -2.80514836e-01 8.58956218e-01 -4.28383440e-01 -2.80521303e-01 8.56286287e-01 -4.33653384e-01 -2.80504793e-01 8.53608251e-01 -4.38909918e-01 -2.80505866e-01 8.50908935e-01 -4.44131166e-01 -2.80500680e-01 8.48191082e-01 -4.49347019e-01 -2.80487418e-01 8.45398188e-01 -4.54551756e-01 -2.80476779e-01 8.42593431e-01 -4.59718227e-01 -2.80497015e-01 8.39751840e-01 -4.64873761e-01 -2.80515909e-01 8.36902499e-01 -4.70021605e-01 -2.80529469e-01 8.34015608e-01 -4.75157142e-01 -2.80475259e-01 8.31081331e-01 -4.80270088e-01 -2.80491352e-01 8.28112125e-01 -4.85350788e-01 -2.80532777e-01 8.25095177e-01 -4.90412354e-01 -2.80549765e-01 8.22056949e-01 -4.95463818e-01 -2.80546784e-01 8.19005013e-01 -5.00502408e-01 -2.80546397e-01 8.15944195e-01 -5.05523562e-01 -2.80530661e-01 8.12808692e-01 -5.10517061e-01 -2.80519783e-01 8.09666038e-01 -5.15495539e-01 -2.80526519e-01 8.06480289e-01 -5.20460904e-01 -2.80528992e-01 8.03292215e-01 -5.25386930e-01 -2.80550629e-01 8.00054669e-01 -5.30323327e-01 -2.80443907e-01 7.96789348e-01 -5.35231769e-01 -2.80427605e-01 7.93486834e-01 -5.40103376e-01 -2.80447036e-01 7.90167272e-01 -5.44962049e-01 -2.80465096e-01 7.86808431e-01 -5.49808741e-01 -2.80440569e-01 7.83413947e-01 -5.54623008e-01 -2.80439436e-01 7.80017257e-01 -5.59428632e-01 -2.80409276e-01 7.76571214e-01 -5.64192653e-01 -2.80413836e-01 7.73102045e-01 -5.68950474e-01 -2.80384630e-01 7.69595385e-01 -5.73687434e-01 -2.80371875e-01 7.66077876e-01 -5.78415930e-01 -2.80291915e-01 7.62524962e-01 -5.83116770e-01 -2.80257016e-01 7.58916438e-01 -5.87775171e-01 -2.80271947e-01 7.55307376e-01 -5.92418671e-01 -2.80291021e-01 7.51643360e-01 -5.97037911e-01 -2.80274957e-01 7.47976243e-01 -6.01643980e-01 -2.80287445e-01 7.44267285e-01 -6.06224358e-01 -2.80251652e-01 7.40560651e-01 -6.10799432e-01 -2.80187637e-01 7.36786425e-01 -6.15321815e-01 -2.80206054e-01 7.33010709e-01 -6.19835079e-01 -2.80173212e-01 7.29197323e-01 -6.24326587e-01 -2.80168414e-01 7.25363672e-01 -6.28802955e-01 -2.80111969e-01 7.21494913e-01 -6.33238673e-01 -2.80107170e-01 7.17605889e-01 -6.37668610e-01 -2.80035049e-01 7.13668644e-01 -6.42052650e-01 -2.80070186e-01 7.09722936e-01 -6.46410346e-01 -2.80073375e-01 7.05749035e-01 -6.50770426e-01 -2.80030787e-01 7.01738894e-01 -6.55092418e-01 -2.79996186e-01 6.97737515e-01 -6.59408391e-01 -2.79872745e-01 6.93699002e-01 -6.63695514e-01 -2.79803663e-01 6.89647496e-01 -6.67974234e-01 -2.79637218e-01 6.85570478e-01 -6.72222018e-01 -2.79474139e-01 6.81462228e-01 -6.76443636e-01 -2.79344916e-01 6.77317321e-01 -6.80630982e-01 -2.79254138e-01 6.73162460e-01 -6.84808075e-01 -2.79087156e-01 6.68995082e-01 -6.88972354e-01 -2.78859258e-01 6.64827168e-01 -6.93136811e-01 -2.78507411e-01 6.60573602e-01 -6.97215140e-01 -2.78448433e-01 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 4.45099831e-01 -8.50204051e-01 -2.81139076e-01 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. 0. 0. 0. 0. 0. 3.81281525e-01 -8.80495727e-01 -2.81694174e-01 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 2.87780195e-01 -9.16156411e-01 -2.78997153e-01 2.82137394e-01 -9.17856991e-01 -2.79173315e-01 2.76482910e-01 -9.19513106e-01 -2.79373556e-01 2.70823121e-01 -9.21149731e-01 -2.79512823e-01 2.65156895e-01 -9.22781169e-01 -2.79604375e-01 2.59481251e-01 -9.24353123e-01 -2.79712677e-01 2.53794849e-01 -9.25884366e-01 -2.79850364e-01 2.48106152e-01 -9.27417159e-01 -2.79865235e-01 2.42408380e-01 -9.28912342e-01 -2.79915065e-01 2.36700952e-01 -9.30367827e-01 -2.79951960e-01 2.30990618e-01 -9.31826472e-01 -2.79920161e-01 2.25269854e-01 -9.33236897e-01 -2.79899776e-01 2.19540402e-01 -9.34600472e-01 -2.79885501e-01 2.13802919e-01 -9.35941696e-01 -2.79863983e-01 2.08055258e-01 -9.37227547e-01 -2.79888183e-01 2.02299789e-01 -9.38468635e-01 -2.79900551e-01 1.96530908e-01 -9.39674139e-01 -2.79993832e-01 1.90766782e-01 -9.40874279e-01 -2.79918283e-01 1.84983134e-01 -9.42000866e-01 -2.80008137e-01 1.79201856e-01 -9.43127513e-01 -2.79986739e-01 1.73418730e-01 -9.44238961e-01 -2.79849142e-01 1.67616069e-01 -9.45254326e-01 -2.79970407e-01 1.61816075e-01 -9.46303725e-01 -2.79904395e-01 1.56009942e-01 -9.47277665e-01 -2.79838264e-01 1.50196731e-01 -9.48231220e-01 -2.79803634e-01 1.44374743e-01 -9.49141443e-01 -2.79822201e-01 1.38543174e-01 -9.49967921e-01 -2.79913932e-01 1.32708907e-01 -9.50797439e-01 -2.79964030e-01 1.26875505e-01 -9.51593101e-01 -2.79927731e-01 1.21030159e-01 -9.52339351e-01 -2.79997230e-01 1.15188405e-01 -9.53097582e-01 -2.79917717e-01 1.09339416e-01 -9.53781545e-01 -2.79872507e-01 1.03485465e-01 -9.54454660e-01 -2.79875457e-01 9.76246893e-02 -9.55044031e-01 -2.79941827e-01 9.17657390e-02 -9.55644667e-01 -2.79875785e-01 8.59000310e-02 -9.56186950e-01 -2.79863268e-01 8.00320581e-02 -9.56705928e-01 -2.79847711e-01 7.41579533e-02 -9.57159042e-01 -2.79913515e-01 6.82818592e-02 -9.57585454e-01 -2.79971540e-01 6.24050722e-02 -9.57970321e-01 -2.79990345e-01 5.65276742e-02 -9.58376825e-01 -2.79898942e-01 5.06451353e-02 -9.58672822e-01 -2.79954225e-01 4.47610766e-02 -9.58955228e-01 -2.79977173e-01 3.88752781e-02 -9.59211648e-01 -2.80023813e-01 3.29887792e-02 -9.59409833e-01 -2.80050188e-01 2.71014944e-02 -9.59597528e-01 -2.80045092e-01 2.12136209e-02 -9.59769309e-01 -2.79983312e-01 1.53234247e-02 -9.59869146e-01 -2.80038476e-01 9.43386182e-03 -9.59946454e-01 -2.80013233e-01 3.54375504e-03 -9.60000873e-01 -2.79987961e-01 -2.34654476e-03 -9.60011601e-01 -2.79954016e-01 -8.23713839e-03 -9.59950268e-01 -2.80027419e-01 -1.41271623e-02 -9.59885120e-01 -2.79993564e-01 -2.00165603e-02 -9.59775507e-01 -2.79998064e-01 -2.59055924e-02 -9.59646761e-01 -2.80011922e-01 -3.17939036e-02 -9.59501445e-01 -2.79909194e-01 -3.76799591e-02 -9.59246993e-01 -2.80038714e-01 -4.35655415e-02 -9.59016085e-01 -2.79979765e-01 -4.94498536e-02 -9.58750665e-01 -2.79900610e-01 -5.53303920e-02 -9.58409250e-01 -2.80002594e-01 -6.12104498e-02 -9.58052337e-01 -2.79995471e-01 -6.70869201e-02 -9.57654834e-01 -2.80006319e-01 -7.29622096e-02 -9.57240522e-01 -2.79966384e-01 -7.88343251e-02 -9.56769049e-01 -2.79986858e-01 -8.47046375e-02 -9.56267059e-01 -2.79949844e-01 -9.05705169e-02 -9.55747485e-01 -2.79915899e-01 -9.64369401e-02 -9.55201507e-01 -2.79787511e-01 -1.02296367e-01 -9.54599977e-01 -2.79787987e-01 -1.08151257e-01 -9.53956187e-01 -2.79783398e-01 -1.14002571e-01 -9.53265786e-01 -2.79788405e-01 -1.19849257e-01 -9.52558577e-01 -2.79786527e-01 -1.25683263e-01 -9.51717079e-01 -2.80071676e-01 -1.31529823e-01 -9.51018453e-01 -2.79795766e-01 -1.37348622e-01 -9.50056732e-01 -2.80218720e-01 -1.43173769e-01 -9.49198246e-01 -2.80211806e-01 -1.48993880e-01 -9.48284626e-01 -2.80274272e-01 -1.54809311e-01 -9.47373390e-01 -2.80265599e-01 -1.60619274e-01 -9.46391344e-01 -2.80297190e-01 -1.66419104e-01 -9.45363343e-01 -2.80367434e-01 -1.72218651e-01 -9.44320142e-01 -2.80340850e-01 -1.78008929e-01 -9.43264008e-01 -2.80334592e-01 -1.83793366e-01 -9.42138553e-01 -2.80325323e-01 -1.89571589e-01 -9.41010475e-01 -2.80297607e-01 -1.95336133e-01 -9.39817011e-01 -2.80377448e-01 -2.01102287e-01 -9.38576877e-01 -2.80380934e-01 -2.06856221e-01 -9.37344790e-01 -2.80413508e-01 -2.12602198e-01 -9.36050832e-01 -2.80437082e-01 -2.18341693e-01 -9.34710741e-01 -2.80432165e-01 -2.24072635e-01 -9.33374107e-01 -2.80380100e-01 -2.29798287e-01 -9.31989789e-01 -2.80383259e-01 -2.35514134e-01 -9.30557847e-01 -2.80368119e-01 -2.41218060e-01 -9.29079533e-01 -2.80362546e-01 -2.46917427e-01 -9.27594423e-01 -2.80349582e-01 -2.52609193e-01 -9.26090777e-01 -2.80255765e-01 -2.58282393e-01 -9.24514294e-01 -2.80329406e-01 -2.63945431e-01 -9.22885835e-01 -2.80342609e-01 -2.69603610e-01 -9.21251774e-01 -2.80346125e-01 -2.75253892e-01 -9.19603944e-01 -2.80299187e-01 -2.80898184e-01 -9.17898893e-01 -2.80278236e-01 -2.86517322e-01 -9.16143477e-01 -2.80380160e-01 -2.92136669e-01 -9.14384842e-01 -2.80277699e-01 -2.97744215e-01 -9.12572682e-01 -2.80297667e-01 -3.03338885e-01 -9.10711706e-01 -2.80297458e-01 -3.08918983e-01 -9.08845961e-01 -2.80258626e-01 -3.14479560e-01 -9.06919122e-01 -2.80386269e-01 -3.20039779e-01 -9.04975653e-01 -2.80352861e-01 -3.25599343e-01 -9.03011143e-01 -2.80285329e-01 -3.31124038e-01 -9.00964499e-01 -2.80369878e-01 -3.36650014e-01 -8.98937762e-01 -2.80310482e-01 -3.42158467e-01 -8.96863103e-01 -2.80326217e-01 -3.47663432e-01 -8.94758821e-01 -2.80279070e-01 -3.53139281e-01 -8.92588317e-01 -2.80330479e-01 -3.58615696e-01 -8.90418291e-01 -2.80303001e-01 -3.64070117e-01 -8.88202429e-01 -2.80290067e-01 -3.69519651e-01 -8.85946810e-01 -2.80261338e-01 -3.74946266e-01 -8.83666992e-01 -2.80234098e-01 -3.80367905e-01 -8.81369531e-01 -2.80189812e-01 -3.85751873e-01 -8.78992319e-01 -2.80293494e-01 -3.91165286e-01 -8.76665771e-01 -2.80054659e-01 -3.96548778e-01 -8.74243498e-01 -2.80042022e-01 -4.01869744e-01 -8.71753931e-01 -2.80278057e-01 -4.07214284e-01 -8.69261146e-01 -2.80288160e-01 -4.12533671e-01 -8.66749227e-01 -2.80316085e-01 -4.17848468e-01 -8.64182830e-01 -2.80317873e-01 -4.23141837e-01 -8.61607671e-01 -2.80302495e-01 -4.28420156e-01 -8.59011590e-01 -2.80305386e-01 -4.33679432e-01 -8.56356680e-01 -2.80311406e-01 -4.38924968e-01 -8.53663743e-01 -2.80357093e-01 -4.44152504e-01 -8.50961983e-01 -2.80351251e-01 -4.49373692e-01 -8.48240614e-01 -2.80299127e-01 -4.54573244e-01 -8.45452309e-01 -2.80276269e-01 -4.59752738e-01 -8.42676163e-01 -2.80245721e-01 -4.64919657e-01 -8.39831889e-01 -2.80212015e-01 -4.70065653e-01 -8.36958885e-01 -2.80224800e-01 -4.75194603e-01 -8.34079027e-01 -2.80203700e-01 -4.80303615e-01 -8.31150293e-01 -2.80187190e-01 -4.85397309e-01 -8.28178883e-01 -2.80183047e-01 -4.90474701e-01 -8.25200617e-01 -2.80136138e-01 -4.95535642e-01 -8.22176814e-01 -2.80113697e-01 -5.00577450e-01 -8.19127023e-01 -2.80083269e-01 -5.05591631e-01 -8.16055596e-01 -2.80076176e-01 -5.10586441e-01 -8.12926114e-01 -2.80083477e-01 -5.15577376e-01 -8.09807539e-01 -2.79991359e-01 -5.20570338e-01 -8.06675494e-01 -2.79798448e-01 -5.25538862e-01 -8.03508580e-01 -2.79604763e-01 -5.30508101e-01 -8.00347686e-01 -2.79289365e-01 -5.36563396e-01 -7.98867345e-01 -2.71865308e-01 -5.40905178e-01 -7.94718981e-01 -2.75369406e-01 -5.45015872e-01 -7.90245235e-01 -2.80125141e-01 -5.49894631e-01 -7.86945522e-01 -2.79875159e-01 -5.54708660e-01 -7.83550441e-01 -2.79888898e-01 -5.59520602e-01 -7.80154884e-01 -2.79812545e-01 -5.64404368e-01 -7.76858747e-01 -2.79146403e-01 -5.69024444e-01 -7.73189485e-01 -2.79980600e-01 -5.73499560e-01 -7.69323409e-01 -2.81495482e-01 -5.79752028e-01 -7.67913997e-01 -2.72388905e-01 -5.83770514e-01 -7.63414443e-01 -2.76398331e-01 -5.87953985e-01 -7.59160936e-01 -2.79252559e-01 -5.92556715e-01 -7.55476832e-01 -2.79512763e-01 -5.97174108e-01 -7.51819015e-01 -2.79560089e-01 -6.01783872e-01 -7.48149276e-01 -2.79513150e-01 -6.06380582e-01 -7.44469285e-01 -2.79401660e-01 -6.10951185e-01 -7.40753293e-01 -2.79324621e-01 -6.15498245e-01 -7.37005889e-01 -2.79256225e-01 -6.20048523e-01 -7.33264029e-01 -2.79038310e-01 -6.24662399e-01 -7.29598820e-01 -2.78347462e-01 -6.30262017e-01 -7.27111518e-01 -2.72173464e-01 -6.34739935e-01 -7.23263860e-01 -2.72019446e-01 0. 0. 0. 0. 0. 0. -6.46143675e-01 -7.09404767e-01 -2.81501889e-01 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. 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. 0. 0. 0. 0. -7.31930614e-01 -6.20483458e-01 -2.81563193e-01 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. 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. 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. 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. 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. 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. 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. 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. 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. 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. 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. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -9.58464861e-01 -4.47288975e-02 -2.81681657e-01 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0.
================================================ FILE: config/viral.yaml ================================================ common: lid_topic: "/os1_cloud_node1/points" imu_topic: "/imu/imu" time_sync_en: false # ONLY turn on when external time synchronization is really not possible time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 lidar_time_offset: -0.10 # begin time = lidar timestamp + time offset preprocess: lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, scan_line: 16 scan_rate: 10 # only need to be set for velodyne, unit: Hz, timestamp_unit: 3 # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. Horizon_SCAN: 1024 # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048) blind: 2 mapping: acc_cov: 6.0e-2 gyr_cov: 5.0e-3 b_acc_cov: 8.0e-5 b_gyr_cov: 3.0e-6 fov_degree: 180 det_range: 150.0 extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic extrinsic_T: [ -0.05, 0.0, 0.055 ] # imu <-- lidar extrinsic_R: [1, 0, 0, 0, 1, 0, 0, 0, 1] voxel_hash_en: true # for association publish: path_en: true scan_publish_en: true # false: close all the point cloud output dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame pcd_save: pcd_save_en: false interval: -1 # how many LiDAR frames saved in each pcd file; # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. save_ikdtree_map: false save_final_map: false normal: compute_table: false ring_table_dir: "/config/viral" compute_normal: true check_normal: true surfel: surfel_points_min: 5 # points inside the voxel larger than the value, do pca surfel_points_max: 1000 # max points inside a voxel planarity: 0.6 # less than the value is plane [0, 1.0] mid2min: 100.0 # larger than the value is plane angle_threshold: 25.0 # angle between ring Fals and surfel normal cloud_surfel: true # point-to-neighbor surfel association point_surfel: true # point-to-point surfel association # prism in IMU frame ground_truth: extrinsic_T: [ -0.293656, -0.012288, -0.273095 ] extrinsic_R: [ 1, 0, 0, 0, 1, 0, 0, 0, 1 ] ================================================ FILE: include/Exp_mat.h ================================================ #ifndef EXP_MAT_H #define EXP_MAT_H #include #include #include // #include #define SKEW_SYM_MATRX(v) 0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0 template Eigen::Matrix Exp(const Eigen::Matrix &&ang) { T ang_norm = ang.norm(); Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); if (ang_norm > 0.0000001) { Eigen::Matrix r_axis = ang / ang_norm; Eigen::Matrix K; K << SKEW_SYM_MATRX(r_axis); /// Roderigous Tranformation return Eye3 + std::sin(ang_norm) * K + (1.0 - std::cos(ang_norm)) * K * K; } else { return Eye3; } } template Eigen::Matrix Exp(const Eigen::Matrix &ang_vel, const Ts &dt) { T ang_vel_norm = ang_vel.norm(); Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); if (ang_vel_norm > 0.0000001) { Eigen::Matrix r_axis = ang_vel / ang_vel_norm; Eigen::Matrix K; K << SKEW_SYM_MATRX(r_axis); T r_ang = ang_vel_norm * dt; /// Roderigous Tranformation return Eye3 + std::sin(r_ang) * K + (1.0 - std::cos(r_ang)) * K * K; } else { return Eye3; } } template Eigen::Matrix Exp(const T &v1, const T &v2, const T &v3) { T &&norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); if (norm > 0.00001) { T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; Eigen::Matrix K; K << SKEW_SYM_MATRX(r_ang); /// Roderigous Tranformation return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; } else { return Eye3; } } /* Logrithm of a Rotation Matrix */ template Eigen::Matrix Log(const Eigen::Matrix &R) { T &&theta = std::acos(0.5 * (R.trace() - 1)); Eigen::Matrix K(R(2,1) - R(1,2), R(0,2) - R(2,0), R(1,0) - R(0,1)); return (std::abs(theta) < 0.001) ? (0.5 * K) : (0.5 * theta / std::sin(theta) * K); } // template // cv::Mat Exp(const T &v1, const T &v2, const T &v3) // { // T norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); // cv::Mat Eye3 = cv::Mat::eye(3, 3, CV_32F); // if (norm > 0.0000001) // { // T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; // cv::Mat K = (cv::Mat_(3,3) << SKEW_SYM_MATRX(r_ang)); // /// Roderigous Tranformation // return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; // } // else // { // return Eye3; // } // } #endif ================================================ FILE: include/IKFoM_toolkit/esekfom/esekfom.hpp ================================================ /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Author: Dongjiao HE * * 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 Universitaet Bremen 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 ESEKFOM_EKF_HPP #define ESEKFOM_EKF_HPP #include #include #include #include #include #include #include #include "../mtk/types/vect.hpp" #include "../mtk/types/SOn.hpp" #include "../mtk/types/S2.hpp" #include "../mtk/startIdx.hpp" #include "../mtk/build_manifold.hpp" #include "util.hpp" //#define USE_sparse namespace esekfom { using namespace Eigen; //used for iterated error state EKF update //for the aim to calculate measurement (z), estimate measurement (h), partial differention matrices (h_x, h_v) and the noise covariance (R) at the same time, by only one function. //applied for measurement as a manifold. template struct share_datastruct { bool valid; bool converge; M z; Eigen::Matrix h_v; Eigen::Matrix h_x; Eigen::Matrix R; }; //used for iterated error state EKF update //for the aim to calculate measurement (z), estimate measurement (h), partial differention matrices (h_x, h_v) and the noise covariance (R) at the same time, by only one function. //applied for measurement as an Eigen matrix whose dimension is changing template struct dyn_share_datastruct { bool valid; bool converge; Eigen::Matrix z; Eigen::Matrix h; // estimate measurement (h), distance Eigen::Matrix h_v; Eigen::Matrix h_x; // partial differention matrices, Jacobian Eigen::Matrix R; }; //used for iterated error state EKF update //for the aim to calculate measurement (z), estimate measurement (h), partial differention matrices (h_x, h_v) and the noise covariance (R) at the same time, by only one function. //applied for measurement as a dynamic manifold whose dimension or type is changing template struct dyn_runtime_share_datastruct { bool valid; bool converge; //Z z; Eigen::Matrix h_v; Eigen::Matrix h_x; Eigen::Matrix R; }; //状态量,噪声,输入状态量 template class esekf{ typedef esekf self; enum{ n = state::DOF, m = state::DIM, l = measurement::DOF }; public: typedef typename state::scalar scalar_type; typedef Matrix cov; typedef Matrix cov_; typedef SparseMatrix spMt; typedef Matrix vectorized_state; typedef Matrix flatted_state; typedef flatted_state processModel(state &, const input &); typedef Eigen::Matrix processMatrix1(state &, const input &); typedef Eigen::Matrix processMatrix2(state &, const input &); typedef Eigen::Matrix processnoisecovariance; typedef measurement measurementModel(state &, bool &); typedef measurement measurementModel_share(state &, share_datastruct &); typedef Eigen::Matrix measurementModel_dyn(state &, bool &); //typedef Eigen::Matrix measurementModel_dyn_share(state &, dyn_share_datastruct &); typedef void measurementModel_dyn_share(state &, dyn_share_datastruct &); typedef Eigen::Matrix measurementMatrix1(state &, bool&); typedef Eigen::Matrix measurementMatrix1_dyn(state &, bool&); typedef Eigen::Matrix measurementMatrix2(state &, bool&); typedef Eigen::Matrix measurementMatrix2_dyn(state &, bool&); typedef Eigen::Matrix measurementnoisecovariance; typedef Eigen::Matrix measurementnoisecovariance_dyn; esekf(const state &x = state(), const cov &P = cov::Identity()): x_(x), P_(P){ #ifdef USE_sparse SparseMatrix ref(n, n); ref.setIdentity(); l_ = ref; f_x_2 = ref; f_x_1 = ref; #endif }; //receive system-specific models and their differentions. //for measurement as a manifold. void init(processModel f_in, processMatrix1 f_x_in, processMatrix2 f_w_in, measurementModel h_in, measurementMatrix1 h_x_in, measurementMatrix2 h_v_in, int maximum_iteration, scalar_type limit_vector[n]) { f = f_in; f_x = f_x_in; f_w = f_w_in; h = h_in; h_x = h_x_in; h_v = h_v_in; maximum_iter = maximum_iteration; for(int i=0; i f_w_ = f_w(x_, i_in); Matrix f_w_final; state x_before = x_; x_.oplus(f_, dt); F_x1 = cov::Identity(); for (std::vector, int> >::iterator it = x_.vect_state.begin(); it != x_.vect_state.end(); it++) { int idx = (*it).first.first; int dim = (*it).first.second; int dof = (*it).second; for(int i = 0; i < n; i++){ for(int j=0; j res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = -1 * f_(dim + i) * dt; } MTK::SO3 res; res.w() = MTK::exp(res.vec(), seg_SO3, scalar_type(1/2)); #ifdef USE_sparse res_temp_SO3 = res.toRotationMatrix(); for(int i = 0; i < 3; i++){ for(int j = 0; j < 3; j++){ f_x_1.coeffRef(idx + i, idx + j) = res_temp_SO3(i, j); } } #else F_x1.template block<3, 3>(idx, idx) = res.toRotationMatrix(); #endif res_temp_SO3 = MTK::A_matrix(seg_SO3); for(int i = 0; i < n; i++){ f_x_final. template block<3, 1>(idx, i) = res_temp_SO3 * (f_x_. template block<3, 1>(dim, i)); } for(int i = 0; i < process_noise_dof; i++){ f_w_final. template block<3, 1>(idx, i) = res_temp_SO3 * (f_w_. template block<3, 1>(dim, i)); } } Matrix res_temp_S2; Matrix res_temp_S2_; MTK::vect<3, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_S2(i) = f_(dim + i) * dt; } MTK::vect<2, scalar_type> vec = MTK::vect<2, scalar_type>::Zero(); MTK::SO3 res; res.w() = MTK::exp(res.vec(), seg_S2, scalar_type(1/2)); Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_before.S2_Mx(Mx, vec, idx); #ifdef USE_sparse res_temp_S2_ = Nx * res.toRotationMatrix() * Mx; for(int i = 0; i < 2; i++){ for(int j = 0; j < 2; j++){ f_x_1.coeffRef(idx + i, idx + j) = res_temp_S2_(i, j); } } #else F_x1.template block<2, 2>(idx, idx) = Nx * res.toRotationMatrix() * Mx; #endif Eigen::Matrix x_before_hat; x_before.S2_hat(x_before_hat, idx); res_temp_S2 = -Nx * res.toRotationMatrix() * x_before_hat*MTK::A_matrix(seg_S2).transpose(); for(int i = 0; i < n; i++){ f_x_final. template block<2, 1>(idx, i) = res_temp_S2 * (f_x_. template block<3, 1>(dim, i)); } for(int i = 0; i < process_noise_dof; i++){ f_w_final. template block<2, 1>(idx, i) = res_temp_S2 * (f_w_. template block<3, 1>(dim, i)); } } // todo #ifdef USE_sparse f_x_1.makeCompressed(); spMt f_x2 = f_x_final.sparseView(); spMt f_w1 = f_w_final.sparseView(); spMt xp = f_x_1 + f_x2 * dt; P_ = xp * P_ * xp.transpose() + (f_w1 * dt) * Q * (f_w1 * dt).transpose(); #else F_x1 += f_x_final * dt; P_ = (F_x1) * P_ * (F_x1).transpose() + (dt * f_w_final) * Q * (dt * f_w_final).transpose();//更新协方差矩阵 #endif } //iterated error state EKF update for measurement as a manifold. void update_iterated(measurement& z, measurementnoisecovariance &R) { if(!(is_same())){ std::cerr << "the scalar type of measurment must be the same as the state" << std::endl; std::exit(100); } int t = 0; bool converg = true; bool valid = true; state x_propagated = x_; cov P_propagated = P_; for(int i=-1; i h_x_ = h_x(x_, valid); Matrix h_v_ = h_v(x_, valid); #endif if(! valid) { continue; } P_ = P_propagated; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx(idx+i); } res_temp_SO3 = A_matrix(seg_SO3).transpose(); dx_new.template block<3, 1>(idx, 0) = res_temp_SO3 * dx.template block<3, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 3>(i, idx) =(P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 2; i++){ seg_S2(i) = dx(idx + i); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; dx_new.template block<2, 1>(idx, 0) = res_temp_S2 * dx.template block<2, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } Matrix K_; if(n > l) { #ifdef USE_sparse Matrix K_temp = h_x_ * P_ * h_x_.transpose(); spMt R_temp = h_v_ * R_ * h_v_.transpose(); K_temp += R_temp; K_ = P_ * h_x_.transpose() * K_temp.inverse(); #else K_= P_ * h_x_.transpose() * (h_x_ * P_ * h_x_.transpose() + h_v_ * R * h_v_.transpose()).inverse(); #endif } else { #ifdef USE_sparse measurementnoisecovariance b = measurementnoisecovariance::Identity(); Eigen::SparseQR, Eigen::COLAMDOrdering> solver; solver.compute(R_); measurementnoisecovariance R_in_temp = solver.solve(b); spMt R_in = R_in_temp.sparseView(); spMt K_temp = h_x_.transpose() * R_in * h_x_; cov P_temp = P_.inverse(); P_temp += K_temp; K_ = P_temp.inverse() * h_x_.transpose() * R_in; #else measurementnoisecovariance R_in = (h_v_*R*h_v_.transpose()).inverse(); K_ = (h_x_.transpose() * R_in * h_x_ + P_.inverse()).inverse() * h_x_.transpose() * R_in; #endif } Matrix innovation; z.boxminus(innovation, h(x_, valid)); cov K_x = K_ * h_x_; Matrix dx_ = K_ * innovation + (K_x - Matrix::Identity()) * dx_new; state x_before = x_; x_.boxplus(dx_); converg = true; for(int i = 0; i < n ; i++) { if(std::fabs(dx_[i]) > limit[i]) { converg = false; break; } } if(converg) t++; if(t > 1 || i == maximum_iter - 1) { L_ = P_; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for(typename std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx_(i + idx); } res_temp_SO3 = A_matrix(seg_SO3).transpose(); for(int i = 0; i < n; i++){ L_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } if(n > l) { for(int i = 0; i < l; i++){ K_. template block<3, 1>(idx, i) = res_temp_SO3 * (K_. template block<3, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<3, 1>(idx, i) = res_temp_SO3 * (K_x. template block<3, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 3>(i, idx) = (L_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); P_. template block<1, 3>(i, idx) = (P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for(typename std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 2; i++){ seg_S2(i) = dx_(i + idx); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; for(int i = 0; i < n; i++){ L_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } if(n > l) { for(int i = 0; i < l; i++){ K_. template block<2, 1>(idx, i) = res_temp_S2 * (K_. template block<2, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<2, 1>(idx, i) = res_temp_S2 * (K_x. template block<2, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 2>(i, idx) = (L_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } if(n > l) { P_ = L_ - K_ * h_x_ * P_; } else { P_ = L_ - K_x * P_; } return; } } } //iterated error state EKF update for measurement as a manifold. //calculate measurement (z), estimate measurement (h), partial differention matrices (h_x, h_v) and the noise covariance (R) at the same time, by only one function. void update_iterated_share() { if(!(is_same())){ std::cerr << "the scalar type of measurment must be the same as the state" << std::endl; std::exit(100); } int t = 0; share_datastruct _share; _share.valid = true; _share.converge = true; state x_propagated = x_; cov P_propagated = P_; for(int i=-1; i h_x_ = _share.h_x; Matrix h_v_ = _share.h_v; #endif if(! _share.valid) { continue; } P_ = P_propagated; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx(idx+i); } res_temp_SO3 = A_matrix(seg_SO3).transpose(); dx_new.template block<3, 1>(idx, 0) = res_temp_SO3 * dx.template block<3, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 3>(i, idx) =(P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 2; i++){ seg_S2(i) = dx(idx + i); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; dx_new.template block<2, 1>(idx, 0) = res_temp_S2 * dx.template block<2, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } Matrix K_; if(n > l) { #ifdef USE_sparse Matrix K_temp = h_x_ * P_ * h_x_.transpose(); spMt R_temp = h_v_ * R_ * h_v_.transpose(); K_temp += R_temp; K_ = P_ * h_x_.transpose() * K_temp.inverse(); #else K_= P_ * h_x_.transpose() * (h_x_ * P_ * h_x_.transpose() + h_v_ * R * h_v_.transpose()).inverse(); #endif } else { #ifdef USE_sparse measurementnoisecovariance b = measurementnoisecovariance::Identity(); Eigen::SparseQR, Eigen::COLAMDOrdering> solver; solver.compute(R_); measurementnoisecovariance R_in_temp = solver.solve(b); spMt R_in = R_in_temp.sparseView(); spMt K_temp = h_x_.transpose() * R_in * h_x_; cov P_temp = P_.inverse(); P_temp += K_temp; K_ = P_temp.inverse() * h_x_.transpose() * R_in; #else measurementnoisecovariance R_in = (h_v_*R*h_v_.transpose()).inverse(); K_ = (h_x_.transpose() * R_in * h_x_ + P_.inverse()).inverse() * h_x_.transpose() * R_in; #endif } Matrix innovation; z.boxminus(innovation, h); cov K_x = K_ * h_x_; Matrix dx_ = K_ * innovation + (K_x - Matrix::Identity()) * dx_new; state x_before = x_; x_.boxplus(dx_); _share.converge = true; for(int i = 0; i < n ; i++) { if(std::fabs(dx_[i]) > limit[i]) { _share.converge = false; break; } } if(_share.converge) t++; if(t > 1 || i == maximum_iter - 1) { L_ = P_; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for(typename std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx_(i + idx); } res_temp_SO3 = A_matrix(seg_SO3).transpose(); for(int i = 0; i < n; i++){ L_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } if(n > l) { for(int i = 0; i < l; i++){ K_. template block<3, 1>(idx, i) = res_temp_SO3 * (K_. template block<3, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<3, 1>(idx, i) = res_temp_SO3 * (K_x. template block<3, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 3>(i, idx) = (L_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); P_. template block<1, 3>(i, idx) = (P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for(typename std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 2; i++){ seg_S2(i) = dx_(i + idx); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; for(int i = 0; i < n; i++){ L_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } if(n > l) { for(int i = 0; i < l; i++){ K_. template block<2, 1>(idx, i) = res_temp_S2 * (K_. template block<2, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<2, 1>(idx, i) = res_temp_S2 * (K_x. template block<2, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 2>(i, idx) = (L_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } if(n > l) { P_ = L_ - K_ * h_x_ * P_; } else { P_ = L_ - K_x * P_; } return; } } } //iterated error state EKF update for measurement as an Eigen matrix whose dimension is changing. void update_iterated_dyn(Eigen::Matrix z, measurementnoisecovariance_dyn R) { int t = 0; bool valid = true; bool converg = true; state x_propagated = x_; cov P_propagated = P_; int dof_Measurement; int dof_Measurement_noise = R.rows(); for(int i=-1; i h_x_ = h_x_dyn(x_, valid); Matrix h_v_ = h_v_dyn(x_, valid); #endif Matrix h_ = h_dyn(x_, valid); dof_Measurement = h_.rows(); vectorized_state dx, dx_new; x_.boxminus(dx, x_propagated); dx_new = dx; if(! valid) { continue; } P_ = P_propagated; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx(idx+i); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); dx_new.template block<3, 1>(idx, 0) = res_temp_SO3 * dx_new.template block<3, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 3>(i, idx) =(P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 2; i++){ seg_S2(i) = dx(idx + i); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; dx_new.template block<2, 1>(idx, 0) = res_temp_S2 * dx_new.template block<2, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } Matrix K_; if(n > dof_Measurement) { #ifdef USE_sparse Matrix K_temp = h_x_ * P_ * h_x_.transpose(); spMt R_temp = h_v_ * R_ * h_v_.transpose(); K_temp += R_temp; K_ = P_ * h_x_.transpose() * K_temp.inverse(); #else K_= P_ * h_x_.transpose() * (h_x_ * P_ * h_x_.transpose() + h_v_ * R * h_v_.transpose()).inverse(); #endif } else { #ifdef USE_sparse Eigen::Matrix b = Eigen::Matrix::Identity(dof_Measurement_noise, dof_Measurement_noise); Eigen::SparseQR, Eigen::COLAMDOrdering> solver; solver.compute(R_); Eigen::Matrix R_in_temp = solver.solve(b); spMt R_in = R_in_temp.sparseView(); spMt K_temp = h_x_.transpose() * R_in * h_x_; cov P_temp = P_.inverse(); P_temp += K_temp; K_ = P_temp.inverse() * h_x_.transpose() * R_in; #else Eigen::Matrix R_in = (h_v_*R*h_v_.transpose()).inverse(); K_ = (h_x_.transpose() * R_in * h_x_ + P_.inverse()).inverse() * h_x_.transpose() * R_in; #endif } cov K_x = K_ * h_x_; Matrix dx_ = K_ * (z - h_) + (K_x - Matrix::Identity()) * dx_new; state x_before = x_; x_.boxplus(dx_); converg = true; for(int i = 0; i < n ; i++) { if(std::fabs(dx_[i]) > limit[i]) { converg = false; break; } } if(converg) t++; if(t > 1 || i == maximum_iter - 1) { L_ = P_; std::cout << "iteration time:" << t << "," << i << std::endl; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for(typename std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx_(i + idx); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); for(int i = 0; i < n; i++){ L_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<3, 1>(idx, i) = res_temp_SO3 * (K_. template block<3, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<3, 1>(idx, i) = res_temp_SO3 * (K_x. template block<3, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 3>(i, idx) = (L_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); P_. template block<1, 3>(i, idx) = (P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for(typename std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 2; i++){ seg_S2(i) = dx_(i + idx); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; for(int i = 0; i < n; i++){ L_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<2, 1>(idx, i) = res_temp_S2 * (K_. template block<2, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<2, 1>(idx, i) = res_temp_S2 * (K_x. template block<2, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 2>(i, idx) = (L_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } if(n > dof_Measurement) { P_ = L_ - K_*h_x_*P_; } else { P_ = L_ - K_x * P_; } return; } } } //iterated error state EKF update for measurement as an Eigen matrix whose dimension is changing. //calculate measurement (z), estimate measurement (h), partial differention matrices (h_x, h_v) and the noise covariance (R) at the same time, by only one function. void update_iterated_dyn_share() { int t = 0; dyn_share_datastruct dyn_share; dyn_share.valid = true; dyn_share.converge = true; state x_propagated = x_; cov P_propagated = P_; int dof_Measurement; int dof_Measurement_noise; for(int i=-1; i h = h_dyn_share (x_, dyn_share); Matrix z = dyn_share.z; Matrix h = dyn_share.h; #ifdef USE_sparse spMt h_x = dyn_share.h_x.sparseView(); spMt h_v = dyn_share.h_v.sparseView(); spMt R_ = dyn_share.R.sparseView(); #else Matrix R = dyn_share.R; Matrix h_x = dyn_share.h_x; Matrix h_v = dyn_share.h_v; #endif dof_Measurement = h_x.rows(); dof_Measurement_noise = dyn_share.R.rows(); vectorized_state dx, dx_new; x_.boxminus(dx, x_propagated); dx_new = dx; if(! (dyn_share.valid)) { continue; } P_ = P_propagated; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx(idx+i); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); dx_new.template block<3, 1>(idx, 0) = res_temp_SO3 * dx_new.template block<3, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 3>(i, idx) =(P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 2; i++){ seg_S2(i) = dx(idx + i); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; dx_new.template block<2, 1>(idx, 0) = res_temp_S2 * dx_new.template block<2, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } Matrix K_; if(n > dof_Measurement) { #ifdef USE_sparse Matrix K_temp = h_x * P_ * h_x.transpose(); spMt R_temp = h_v * R_ * h_v.transpose(); K_temp += R_temp; K_ = P_ * h_x.transpose() * K_temp.inverse(); #else K_= P_ * h_x.transpose() * (h_x * P_ * h_x.transpose() + h_v * R * h_v.transpose()).inverse(); #endif } else { #ifdef USE_sparse Eigen::Matrix b = Eigen::Matrix::Identity(dof_Measurement_noise, dof_Measurement_noise); Eigen::SparseQR, Eigen::COLAMDOrdering> solver; solver.compute(R_); Eigen::Matrix R_in_temp = solver.solve(b); spMt R_in = R_in_temp.sparseView(); spMt K_temp = h_x.transpose() * R_in * h_x; cov P_temp = P_.inverse(); P_temp += K_temp; K_ = P_temp.inverse() * h_x.transpose() * R_in; #else Eigen::Matrix R_in = (h_v*R*h_v.transpose()).inverse(); K_ = (h_x.transpose() * R_in * h_x + P_.inverse()).inverse() * h_x.transpose() * R_in; #endif } cov K_x = K_ * h_x; Matrix dx_ = K_ * (z - h) + (K_x - Matrix::Identity()) * dx_new; state x_before = x_; x_.boxplus(dx_); dyn_share.converge = true; for(int i = 0; i < n ; i++) { if(std::fabs(dx_[i]) > limit[i]) { dyn_share.converge = false; break; } } if(dyn_share.converge) t++; if(t > 1 || i == maximum_iter - 1) { L_ = P_; std::cout << "iteration time:" << t << "," << i << std::endl; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for(typename std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx_(i + idx); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); for(int i = 0; i < int(n); i++){ L_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<3, 1>(idx, i) = res_temp_SO3 * (K_. template block<3, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<3, 1>(idx, i) = res_temp_SO3 * (K_x. template block<3, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 3>(i, idx) = (L_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); P_. template block<1, 3>(i, idx) = (P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for(typename std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 2; i++){ seg_S2(i) = dx_(i + idx); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; for(int i = 0; i < n; i++){ L_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<2, 1>(idx, i) = res_temp_S2 * (K_. template block<2, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<2, 1>(idx, i) = res_temp_S2 * (K_x. template block<2, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 2>(i, idx) = (L_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } if(n > dof_Measurement) { P_ = L_ - K_*h_x*P_; } else { P_ = L_ - K_x * P_; } return; } } } //iterated error state EKF update for measurement as a dynamic manifold, whose dimension or type is changing. //the measurement and the measurement model are received in a dynamic manner. template void update_iterated_dyn_runtime(measurement_runtime z, measurementnoisecovariance_dyn R, measurementModel_runtime h_runtime) { int t = 0; bool valid = true; bool converg = true; state x_propagated = x_; cov P_propagated = P_; int dof_Measurement; int dof_Measurement_noise; for(int i=-1; i h_x_ = h_x_dyn(x_, valid); Matrix h_v_ = h_v_dyn(x_, valid); #endif measurement_runtime h_ = h_runtime(x_, valid); dof_Measurement = measurement_runtime::DOF; dof_Measurement_noise = R.rows(); vectorized_state dx, dx_new; x_.boxminus(dx, x_propagated); dx_new = dx; if(! valid) { continue; } P_ = P_propagated; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx(idx+i); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); dx_new.template block<3, 1>(idx, 0) = res_temp_SO3 * dx_new.template block<3, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 3>(i, idx) =(P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 2; i++){ seg_S2(i) = dx(idx + i); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; dx_new.template block<2, 1>(idx, 0) = res_temp_S2 * dx_new.template block<2, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } Matrix K_; if(n > dof_Measurement) { #ifdef USE_sparse Matrix K_temp = h_x_ * P_ * h_x_.transpose(); spMt R_temp = h_v_ * R_ * h_v_.transpose(); K_temp += R_temp; K_ = P_ * h_x_.transpose() * K_temp.inverse(); #else K_= P_ * h_x_.transpose() * (h_x_ * P_ * h_x_.transpose() + h_v_ * R * h_v_.transpose()).inverse(); #endif } else { #ifdef USE_sparse Eigen::Matrix b = Eigen::Matrix::Identity(dof_Measurement_noise, dof_Measurement_noise); Eigen::SparseQR, Eigen::COLAMDOrdering> solver; solver.compute(R_); Eigen::Matrix R_in_temp = solver.solve(b); spMt R_in = R_in_temp.sparseView(); spMt K_temp = h_x_.transpose() * R_in * h_x_; cov P_temp = P_.inverse(); P_temp += K_temp; K_ = P_temp.inverse() * h_x_.transpose() * R_in; #else Eigen::Matrix R_in = (h_v_*R*h_v_.transpose()).inverse(); K_ = (h_x_.transpose() * R_in * h_x_ + P_.inverse()).inverse() * h_x_.transpose() * R_in; #endif } cov K_x = K_ * h_x_; Eigen::Matrix innovation; z.boxminus(innovation, h_); Matrix dx_ = K_ * innovation + (K_x - Matrix::Identity()) * dx_new; state x_before = x_; x_.boxplus(dx_); converg = true; for(int i = 0; i < n ; i++) { if(std::fabs(dx_[i]) > limit[i]) { converg = false; break; } } if(converg) t++; if(t > 1 || i == maximum_iter - 1) { L_ = P_; std::cout << "iteration time:" << t << "," << i << std::endl; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for(typename std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx_(i + idx); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); for(int i = 0; i < n; i++){ L_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<3, 1>(idx, i) = res_temp_SO3 * (K_. template block<3, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<3, 1>(idx, i) = res_temp_SO3 * (K_x. template block<3, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 3>(i, idx) = (L_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); P_. template block<1, 3>(i, idx) = (P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for(typename std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 2; i++){ seg_S2(i) = dx_(i + idx); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; for(int i = 0; i < n; i++){ L_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<2, 1>(idx, i) = res_temp_S2 * (K_. template block<2, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<2, 1>(idx, i) = res_temp_S2 * (K_x. template block<2, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 2>(i, idx) = (L_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } if(n > dof_Measurement) { P_ = L_ - K_*h_x_*P_; } else { P_ = L_ - K_x * P_; } return; } } } //iterated error state EKF update for measurement as a dynamic manifold, whose dimension or type is changing. //the measurement and the measurement model are received in a dynamic manner. //calculate measurement (z), estimate measurement (h), partial differention matrices (h_x, h_v) and the noise covariance (R) at the same time, by only one function. template void update_iterated_dyn_runtime_share(measurement_runtime z, measurementModel_dyn_runtime_share h) { int t = 0; dyn_runtime_share_datastruct dyn_share; dyn_share.valid = true; dyn_share.converge = true; state x_propagated = x_; cov P_propagated = P_; int dof_Measurement; int dof_Measurement_noise; for(int i=-1; i R = dyn_share.R; Matrix h_x = dyn_share.h_x; Matrix h_v = dyn_share.h_v; #endif dof_Measurement = measurement_runtime::DOF; dof_Measurement_noise = dyn_share.R.rows(); vectorized_state dx, dx_new; x_.boxminus(dx, x_propagated); dx_new = dx; if(! (dyn_share.valid)) { continue; } P_ = P_propagated; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx(idx+i); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); dx_new.template block<3, 1>(idx, 0) = res_temp_SO3 * dx_new.template block<3, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 3>(i, idx) =(P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 2; i++){ seg_S2(i) = dx(idx + i); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; dx_new.template block<2, 1>(idx, 0) = res_temp_S2 * dx_new.template block<2, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } Matrix K_; if(n > dof_Measurement) { #ifdef USE_sparse Matrix K_temp = h_x * P_ * h_x.transpose(); spMt R_temp = h_v * R_ * h_v.transpose(); K_temp += R_temp; K_ = P_ * h_x.transpose() * K_temp.inverse(); #else K_= P_ * h_x.transpose() * (h_x * P_ * h_x.transpose() + h_v * R * h_v.transpose()).inverse(); #endif } else { #ifdef USE_sparse Eigen::Matrix b = Eigen::Matrix::Identity(dof_Measurement_noise, dof_Measurement_noise); Eigen::SparseQR, Eigen::COLAMDOrdering> solver; solver.compute(R_); Eigen::Matrix R_in_temp = solver.solve(b); spMt R_in =R_in_temp.sparseView(); spMt K_temp = h_x.transpose() * R_in * h_x; cov P_temp = P_.inverse(); P_temp += K_temp; K_ = P_temp.inverse() * h_x.transpose() * R_in; #else Eigen::Matrix R_in = (h_v*R*h_v.transpose()).inverse(); K_ = (h_x.transpose() * R_in * h_x + P_.inverse()).inverse() * h_x.transpose() * R_in; #endif } cov K_x = K_ * h_x; Eigen::Matrix innovation; z.boxminus(innovation, h_); Matrix dx_ = K_ * innovation + (K_x - Matrix::Identity()) * dx_new; state x_before = x_; x_.boxplus(dx_); dyn_share.converge = true; for(int i = 0; i < n ; i++) { if(std::fabs(dx_[i]) > limit[i]) { dyn_share.converge = false; break; } } if(dyn_share.converge) t++; if(t > 1 || i == maximum_iter - 1) { L_ = P_; std::cout << "iteration time:" << t << "," << i << std::endl; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for(typename std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx_(i + idx); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); for(int i = 0; i < int(n); i++){ L_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<3, 1>(idx, i) = res_temp_SO3 * (K_. template block<3, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<3, 1>(idx, i) = res_temp_SO3 * (K_x. template block<3, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 3>(i, idx) = (L_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); P_. template block<1, 3>(i, idx) = (P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for(typename std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 2; i++){ seg_S2(i) = dx_(i + idx); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; for(int i = 0; i < n; i++){ L_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } if(n > dof_Measurement) { for(int i = 0; i < dof_Measurement; i++){ K_. template block<2, 1>(idx, i) = res_temp_S2 * (K_. template block<2, 1>(idx, i)); } } else { for(int i = 0; i < n; i++){ K_x. template block<2, 1>(idx, i) = res_temp_S2 * (K_x. template block<2, 1>(idx, i)); } } for(int i = 0; i < n; i++){ L_. template block<1, 2>(i, idx) = (L_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } if(n > dof_Measurement) { P_ = L_ - K_*h_x * P_; } else { P_ = L_ - K_x * P_; } return; } } } //iterated error state EKF update modified for one specific system. void update_iterated_dyn_share_modified(double R, double &solve_time) { dyn_share_datastruct dyn_share; dyn_share.valid = true; dyn_share.converge = true; int t = 0; state x_propagated = x_; //propagated state x cov P_propagated = P_; //propagated P int dof_Measurement; Matrix K_h; // n(state::DOF) * 1 Matrix K_x; // n * n vectorized_state dx_new = vectorized_state::Zero(); //error state for(int i=-1; i h = h_dyn_share(x_, dyn_share); #ifdef USE_sparse spMt h_x_ = dyn_share.h_x.sparseView(); #else Eigen::Matrix h_x_ = dyn_share.h_x; // partial differention matrices, Jacobian #endif double solve_start = omp_get_wtime(); dof_Measurement = h_x_.rows(); vectorized_state dx; // error x_.boxminus(dx, x_propagated); //get error dx dx_new = dx; //record error state P_ = P_propagated;//record propagated P Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for (std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx(idx+i); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); // A, equation (6) in FASTLIO dx_new.template block<3, 1>(idx, 0) = res_temp_SO3 * dx_new.template block<3, 1>(idx, 0); //update SO3 error state //using equation (16) in FASTLIO, update P_ = J * P_ * J^-1 // A * P_(row), update P_ corresponding to the error state for(int i = 0; i < n; i++){ P_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 3>(i, idx) =(P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); // P_(col) * A^T } } // maybe gravity Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for (std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; int dim = (*it).second; for(int i = 0; i < 2; i++){ seg_S2(i) = dx(idx + i); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; dx_new.template block<2, 1>(idx, 0) = res_temp_S2 * dx_new.template block<2, 1>(idx, 0); for(int i = 0; i < n; i++){ P_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } for(int i = 0; i < n; i++){ P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } //Matrix K_; //Matrix K_h; //Matrix K_x; /* if(n > dof_Measurement) { K_= P_ * h_x_.transpose() * (h_x_ * P_ * h_x_.transpose()/R + Eigen::Matrix::Identity(dof_Measurement, dof_Measurement)).inverse()/R; } else { K_= (h_x_.transpose() * h_x_ + (P_/R).inverse()).inverse()*h_x_.transpose(); } */ if(n > dof_Measurement) { //#ifdef USE_sparse //Matrix K_temp = h_x * P_ * h_x.transpose(); //spMt R_temp = h_v * R_ * h_v.transpose(); //K_temp += R_temp; Eigen::Matrix h_x_cur = Eigen::Matrix::Zero(dof_Measurement, n); h_x_cur.topLeftCorner(dof_Measurement, 12) = h_x_; //Jacobian /* h_x_cur.col(0) = h_x_.col(0); h_x_cur.col(1) = h_x_.col(1); h_x_cur.col(2) = h_x_.col(2); h_x_cur.col(3) = h_x_.col(3); h_x_cur.col(4) = h_x_.col(4); h_x_cur.col(5) = h_x_.col(5); h_x_cur.col(6) = h_x_.col(6); h_x_cur.col(7) = h_x_.col(7); h_x_cur.col(8) = h_x_.col(8); h_x_cur.col(9) = h_x_.col(9); h_x_cur.col(10) = h_x_.col(10); h_x_cur.col(11) = h_x_.col(11); */ Matrix K_ = P_ * h_x_cur.transpose() * (h_x_cur * P_ * h_x_cur.transpose()/R + Eigen::Matrix::Identity(dof_Measurement, dof_Measurement)).inverse()/R; K_h = K_ * dyn_share.h; // K × h(distance) K_x = K_ * h_x_cur; // K * H //#else // K_= P_ * h_x.transpose() * (h_x * P_ * h_x.transpose() + h_v * R * h_v.transpose()).inverse(); //#endif } else { #ifdef USE_sparse //Eigen::Matrix b = Eigen::Matrix::Identity(); //Eigen::SparseQR, Eigen::COLAMDOrdering> solver; spMt A = h_x_.transpose() * h_x_; cov P_temp = (P_/R).inverse(); P_temp. template block<12, 12>(0, 0) += A; P_temp = P_temp.inverse(); /* Eigen::Matrix h_x_cur = Eigen::Matrix::Zero(dof_Measurement, n); h_x_cur.col(0) = h_x_.col(0); h_x_cur.col(1) = h_x_.col(1); h_x_cur.col(2) = h_x_.col(2); h_x_cur.col(3) = h_x_.col(3); h_x_cur.col(4) = h_x_.col(4); h_x_cur.col(5) = h_x_.col(5); h_x_cur.col(6) = h_x_.col(6); h_x_cur.col(7) = h_x_.col(7); h_x_cur.col(8) = h_x_.col(8); h_x_cur.col(9) = h_x_.col(9); h_x_cur.col(10) = h_x_.col(10); h_x_cur.col(11) = h_x_.col(11); */ K_ = P_temp. template block(0, 0) * h_x_.transpose(); K_x = cov::Zero(); K_x. template block(0, 0) = P_inv. template block(0, 0) * HTH; /* solver.compute(R_); Eigen::Matrix R_in_temp = solver.solve(b); spMt R_in =R_in_temp.sparseView(); spMt K_temp = h_x.transpose() * R_in * h_x; cov P_temp = P_.inverse(); P_temp += K_temp; K_ = P_temp.inverse() * h_x.transpose() * R_in; */ #else cov P_temp = (P_/R).inverse(); //(P / R)^-1 = R * P^-1, equation (20) //Eigen::Matrix h_T = h_x_.transpose(); Eigen::Matrix HTH = h_x_.transpose() * h_x_; P_temp. template block<12, 12>(0, 0) += HTH; // (H^T * H + R * P^-1) /* Eigen::Matrix h_x_cur = Eigen::Matrix::Zero(dof_Measurement, n); //std::cout << "line 1767" << std::endl; h_x_cur.col(0) = h_x_.col(0); h_x_cur.col(1) = h_x_.col(1); h_x_cur.col(2) = h_x_.col(2); h_x_cur.col(3) = h_x_.col(3); h_x_cur.col(4) = h_x_.col(4); h_x_cur.col(5) = h_x_.col(5); h_x_cur.col(6) = h_x_.col(6); h_x_cur.col(7) = h_x_.col(7); h_x_cur.col(8) = h_x_.col(8); h_x_cur.col(9) = h_x_.col(9); h_x_cur.col(10) = h_x_.col(10); h_x_cur.col(11) = h_x_.col(11); */ cov P_inv = P_temp.inverse(); // (H_T_H + R * P^-1)^-1 //std::cout << "line 1781" << std::endl; /// R * (H_T_H + P^-1)^-1 * H^T * R^-1 = (H_T_H + P^-1)^-1 * H^T, since R is a scalar here K_h = P_inv. template block(0, 0) * h_x_.transpose() * dyn_share.h; // (H_T_H + P^-1)^-1 * H^T * h(distance) = K * z //std::cout << "line 1780" << std::endl; //cov HTH_cur = cov::Zero(); //HTH_cur. template block<12, 12>(0, 0) = HTH; K_x.setZero(); // = cov::Zero(); K_x. template block(0, 0) = P_inv. template block(0, 0) * HTH; // (H_T_H + R * P^-1)^-1 * H_T_H = KH //K_= (h_x_.transpose() * h_x_ + (P_/R).inverse()).inverse()*h_x_.transpose(); #endif } //K_x = K_ * h_x_; Matrix dx_ = K_h + (K_x - Matrix::Identity()) * dx_new; state x_before = x_; x_.boxplus(dx_); dyn_share.converge = true; for(int i = 0; i < n ; i++) { if(std::fabs(dx_[i]) > limit[i]) { dyn_share.converge = false; break; } } if(dyn_share.converge) t++; if(!t && i == maximum_iter - 2) { dyn_share.converge = true; } if(t > 1 || i == maximum_iter - 1) { L_ = P_; //std::cout << "iteration time" << t << "," << i << std::endl; Matrix res_temp_SO3; MTK::vect<3, scalar_type> seg_SO3; for(typename std::vector >::iterator it = x_.SO3_state.begin(); it != x_.SO3_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 3; i++){ seg_SO3(i) = dx_(i + idx); } res_temp_SO3 = MTK::A_matrix(seg_SO3).transpose(); for(int i = 0; i < n; i++){ L_. template block<3, 1>(idx, i) = res_temp_SO3 * (P_. template block<3, 1>(idx, i)); } // if(n > dof_Measurement) // { // for(int i = 0; i < dof_Measurement; i++){ // K_.template block<3, 1>(idx, i) = res_temp_SO3 * (K_. template block<3, 1>(idx, i)); // } // } // else // { for(int i = 0; i < 12; i++){ K_x. template block<3, 1>(idx, i) = res_temp_SO3 * (K_x. template block<3, 1>(idx, i)); } //} for(int i = 0; i < n; i++){ L_. template block<1, 3>(i, idx) = (L_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); P_. template block<1, 3>(i, idx) = (P_. template block<1, 3>(i, idx)) * res_temp_SO3.transpose(); } } Matrix res_temp_S2; MTK::vect<2, scalar_type> seg_S2; for(typename std::vector >::iterator it = x_.S2_state.begin(); it != x_.S2_state.end(); it++) { int idx = (*it).first; for(int i = 0; i < 2; i++){ seg_S2(i) = dx_(i + idx); } Eigen::Matrix Nx; Eigen::Matrix Mx; x_.S2_Nx_yy(Nx, idx); x_propagated.S2_Mx(Mx, seg_S2, idx); res_temp_S2 = Nx * Mx; for(int i = 0; i < n; i++){ L_. template block<2, 1>(idx, i) = res_temp_S2 * (P_. template block<2, 1>(idx, i)); } // if(n > dof_Measurement) // { // for(int i = 0; i < dof_Measurement; i++){ // K_. template block<2, 1>(idx, i) = res_temp_S2 * (K_. template block<2, 1>(idx, i)); // } // } // else // { for(int i = 0; i < 12; i++){ K_x. template block<2, 1>(idx, i) = res_temp_S2 * (K_x. template block<2, 1>(idx, i)); } //} for(int i = 0; i < n; i++){ L_. template block<1, 2>(i, idx) = (L_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); P_. template block<1, 2>(i, idx) = (P_. template block<1, 2>(i, idx)) * res_temp_S2.transpose(); } } // if(n > dof_Measurement) // { // Eigen::Matrix h_x_cur = Eigen::Matrix::Zero(dof_Measurement, n); // h_x_cur.topLeftCorner(dof_Measurement, 12) = h_x_; // /* // h_x_cur.col(0) = h_x_.col(0); // h_x_cur.col(1) = h_x_.col(1); // h_x_cur.col(2) = h_x_.col(2); // h_x_cur.col(3) = h_x_.col(3); // h_x_cur.col(4) = h_x_.col(4); // h_x_cur.col(5) = h_x_.col(5); // h_x_cur.col(6) = h_x_.col(6); // h_x_cur.col(7) = h_x_.col(7); // h_x_cur.col(8) = h_x_.col(8); // h_x_cur.col(9) = h_x_.col(9); // h_x_cur.col(10) = h_x_.col(10); // h_x_cur.col(11) = h_x_.col(11); // */ // P_ = L_ - K_*h_x_cur * P_; // } // else //{ P_ = L_ - K_x.template block(0, 0) * P_.template block<12, n>(0, 0); //} solve_time += omp_get_wtime() - solve_start; return; } solve_time += omp_get_wtime() - solve_start; } } void change_x(state &input_state) { x_ = input_state; if((!x_.vect_state.size())&&(!x_.SO3_state.size())&&(!x_.S2_state.size())) { x_.build_S2_state(); x_.build_SO3_state(); x_.build_vect_state(); } } void change_P(cov &input_cov) { P_ = input_cov; } const state& get_x() const { return x_; } const cov& get_P() const { return P_; } private: state x_; measurement m_; cov P_; spMt l_; spMt f_x_1; spMt f_x_2; cov F_x1 = cov::Identity(); cov F_x2 = cov::Identity(); cov L_ = cov::Identity(); processModel *f; processMatrix1 *f_x; processMatrix2 *f_w; measurementModel *h; measurementMatrix1 *h_x; measurementMatrix2 *h_v; measurementModel_dyn *h_dyn; measurementMatrix1_dyn *h_x_dyn; measurementMatrix2_dyn *h_v_dyn; measurementModel_share *h_share; measurementModel_dyn_share *h_dyn_share; int maximum_iter = 0; scalar_type limit[n]; template T check_safe_update( T _temp_vec ) { T temp_vec = _temp_vec; if ( std::isnan( temp_vec(0, 0) ) ) { temp_vec.setZero(); return temp_vec; } double angular_dis = temp_vec.block( 0, 0, 3, 1 ).norm() * 57.3; double pos_dis = temp_vec.block( 3, 0, 3, 1 ).norm(); if ( angular_dis >= 20 || pos_dis > 1 ) { printf( "Angular dis = %.2f, pos dis = %.2f\r\n", angular_dis, pos_dis ); temp_vec.setZero(); } return temp_vec; } public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace esekfom #endif // ESEKFOM_EKF_HPP ================================================ FILE: include/IKFoM_toolkit/esekfom/util.hpp ================================================ /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Author: Dongjiao HE * * 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 Universitaet Bremen 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 __MEKFOM_UTIL_HPP__ #define __MEKFOM_UTIL_HPP__ #include #include "../mtk/src/mtkmath.hpp" namespace esekfom { template class is_same { public: operator bool() { return false; } }; template class is_same { public: operator bool() { return true; } }; template class is_double { public: operator bool() { return false; } }; template<> class is_double { public: operator bool() { return true; } }; template static T id(const T &x) { return x; } } // namespace esekfom #endif // __MEKFOM_UTIL_HPP__ ================================================ FILE: include/IKFoM_toolkit/mtk/build_manifold.hpp ================================================ // This is an advanced implementation of the algorithm described in the // following paper: // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Modifier: Dongjiao HE * * 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 Universitaet Bremen 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. */ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/build_manifold.hpp * @brief Macro to automatically construct compound manifolds. * */ #ifndef MTK_AUTOCONSTRUCT_HPP_ #define MTK_AUTOCONSTRUCT_HPP_ #include #include #include #include #include "src/SubManifold.hpp" #include "startIdx.hpp" #ifndef PARSED_BY_DOXYGEN //////// internals ////// #define MTK_APPLY_MACRO_ON_TUPLE(r, macro, tuple) macro tuple #define MTK_TRANSFORM_COMMA(macro, entries) BOOST_PP_SEQ_ENUM(BOOST_PP_SEQ_TRANSFORM_S(1, MTK_APPLY_MACRO_ON_TUPLE, macro, entries)) #define MTK_TRANSFORM(macro, entries) BOOST_PP_SEQ_FOR_EACH_R(1, MTK_APPLY_MACRO_ON_TUPLE, macro, entries) #define MTK_CONSTRUCTOR_ARG( type, id) const type& id = type() #define MTK_CONSTRUCTOR_COPY( type, id) id(id) #define MTK_BOXPLUS( type, id) id.boxplus(MTK::subvector(__vec, &self::id), __scale); #define MTK_OPLUS( type, id) id.oplus(MTK::subvector_(__vec, &self::id), __scale); #define MTK_BOXMINUS( type, id) id.boxminus(MTK::subvector(__res, &self::id), __oth.id); #define MTK_S2_hat( type, id) if(id.IDX == idx){id.S2_hat(res);} #define MTK_S2_Nx_yy( type, id) if(id.IDX == idx){id.S2_Nx_yy(res);} #define MTK_S2_Mx( type, id) if(id.IDX == idx){id.S2_Mx(res, dx);} #define MTK_OSTREAM( type, id) << __var.id << " " #define MTK_ISTREAM( type, id) >> __var.id #define MTK_S2_state( type, id) if(id.TYP == 1){S2_state.push_back(std::make_pair(id.IDX, id.DIM));} #define MTK_SO3_state( type, id) if(id.TYP == 2){(SO3_state).push_back(std::make_pair(id.IDX, id.DIM));} #define MTK_vect_state( type, id) if(id.TYP == 0){(vect_state).push_back(std::make_pair(std::make_pair(id.IDX, id.DIM), type::DOF));} #define MTK_SUBVARLIST(seq, S2state, SO3state) \ BOOST_PP_FOR_1( \ ( \ BOOST_PP_SEQ_SIZE(seq), \ BOOST_PP_SEQ_HEAD(seq), \ BOOST_PP_SEQ_TAIL(seq) (~), \ 0,\ 0,\ S2state,\ SO3state ),\ MTK_ENTRIES_TEST, MTK_ENTRIES_NEXT, MTK_ENTRIES_OUTPUT) #define MTK_PUT_TYPE(type, id, dof, dim, S2state, SO3state) \ MTK::SubManifold id; #define MTK_PUT_TYPE_AND_ENUM(type, id, dof, dim, S2state, SO3state) \ MTK_PUT_TYPE(type, id, dof, dim, S2state, SO3state) \ enum {DOF = type::DOF + dof}; \ enum {DIM = type::DIM+dim}; \ typedef type::scalar scalar; #define MTK_ENTRIES_OUTPUT(r, state) MTK_ENTRIES_OUTPUT_I state #define MTK_ENTRIES_OUTPUT_I(s, head, seq, dof, dim, S2state, SO3state) \ MTK_APPLY_MACRO_ON_TUPLE(~, \ BOOST_PP_IF(BOOST_PP_DEC(s), MTK_PUT_TYPE, MTK_PUT_TYPE_AND_ENUM), \ ( BOOST_PP_TUPLE_REM_2 head, dof, dim, S2state, SO3state)) #define MTK_ENTRIES_TEST(r, state) MTK_TUPLE_ELEM_4_0 state //! this used to be BOOST_PP_TUPLE_ELEM_4_0: #define MTK_TUPLE_ELEM_4_0(a,b,c,d,e,f, g) a #define MTK_ENTRIES_NEXT(r, state) MTK_ENTRIES_NEXT_I state #define MTK_ENTRIES_NEXT_I(len, head, seq, dof, dim, S2state, SO3state) ( \ BOOST_PP_DEC(len), \ BOOST_PP_SEQ_HEAD(seq), \ BOOST_PP_SEQ_TAIL(seq), \ dof + BOOST_PP_TUPLE_ELEM_2_0 head::DOF,\ dim + BOOST_PP_TUPLE_ELEM_2_0 head::DIM,\ S2state,\ SO3state) #endif /* not PARSED_BY_DOXYGEN */ /** * Construct a manifold. * @param name is the class-name of the manifold, * @param entries is the list of sub manifolds * * Entries must be given in a list like this: * @code * typedef MTK::trafo > Pose; * typedef MTK::vect Vec3; * MTK_BUILD_MANIFOLD(imu_state, * ((Pose, pose)) * ((Vec3, vel)) * ((Vec3, acc_bias)) * ) * @endcode * Whitespace is optional, but the double parentheses are necessary. * Construction is done entirely in preprocessor. * After construction @a name is also a manifold. Its members can be * accessed by names given in @a entries. * * @note Variable types are not allowed to have commas, thus types like * @c vect need to be typedef'ed ahead. */ #define MTK_BUILD_MANIFOLD(name, entries) \ struct name { \ typedef name self; \ std::vector > S2_state;\ std::vector > SO3_state;\ std::vector, int> > vect_state;\ MTK_SUBVARLIST(entries, S2_state, SO3_state) \ name ( \ MTK_TRANSFORM_COMMA(MTK_CONSTRUCTOR_ARG, entries) \ ) : \ MTK_TRANSFORM_COMMA(MTK_CONSTRUCTOR_COPY, entries) {}\ int getDOF() const { return DOF; } \ void boxplus(const MTK::vectview & __vec, scalar __scale = 1 ) { \ MTK_TRANSFORM(MTK_BOXPLUS, entries)\ } \ void oplus(const MTK::vectview & __vec, scalar __scale = 1 ) { \ MTK_TRANSFORM(MTK_OPLUS, entries)\ } \ void boxminus(MTK::vectview __res, const name& __oth) const { \ MTK_TRANSFORM(MTK_BOXMINUS, entries)\ } \ friend std::ostream& operator<<(std::ostream& __os, const name& __var){ \ return __os MTK_TRANSFORM(MTK_OSTREAM, entries); \ } \ void build_S2_state(){\ MTK_TRANSFORM(MTK_S2_state, entries)\ }\ void build_vect_state(){\ MTK_TRANSFORM(MTK_vect_state, entries)\ }\ void build_SO3_state(){\ MTK_TRANSFORM(MTK_SO3_state, entries)\ }\ void S2_hat(Eigen::Matrix &res, int idx) {\ MTK_TRANSFORM(MTK_S2_hat, entries)\ }\ void S2_Nx_yy(Eigen::Matrix &res, int idx) {\ MTK_TRANSFORM(MTK_S2_Nx_yy, entries)\ }\ void S2_Mx(Eigen::Matrix &res, Eigen::Matrix dx, int idx) {\ MTK_TRANSFORM(MTK_S2_Mx, entries)\ }\ friend std::istream& operator>>(std::istream& __is, name& __var){ \ return __is MTK_TRANSFORM(MTK_ISTREAM, entries); \ } \ }; #endif /*MTK_AUTOCONSTRUCT_HPP_*/ ================================================ FILE: include/IKFoM_toolkit/mtk/src/SubManifold.hpp ================================================ // This is an advanced implementation of the algorithm described in the // following paper: // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Modifier: Dongjiao HE * * 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 Universitaet Bremen 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. */ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/src/SubManifold.hpp * @brief Defines the SubManifold class */ #ifndef SUBMANIFOLD_HPP_ #define SUBMANIFOLD_HPP_ #include "vectview.hpp" namespace MTK { /** * @ingroup SubManifolds * Helper class for compound manifolds. * This class wraps a manifold T and provides an enum IDX refering to the * index of the SubManifold within the compound manifold. * * Memberpointers to a submanifold can be used for @ref SubManifolds "functions accessing submanifolds". * * @tparam T The manifold type of the sub-type * @tparam idx The index of the sub-type within the compound manifold */ template struct SubManifold : public T { enum {IDX = idx, DIM = dim /*!< index of the sub-type within the compound manifold */ }; //! manifold type typedef T type; //! Construct from derived type template explicit SubManifold(const X& t) : T(t) {}; //! Construct from internal type //explicit SubManifold(const T& t) : T(t) {}; //! inherit assignment operator using T::operator=; }; } // namespace MTK #endif /* SUBMANIFOLD_HPP_ */ ================================================ FILE: include/IKFoM_toolkit/mtk/src/mtkmath.hpp ================================================ // This is an advanced implementation of the algorithm described in the // following paper: // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Modifier: Dongjiao HE * * 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 Universitaet Bremen 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. */ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/src/mtkmath.hpp * @brief several math utility functions. */ #ifndef MTKMATH_H_ #define MTKMATH_H_ #include #include #include "../types/vect.hpp" #ifndef M_PI #define M_PI 3.1415926535897932384626433832795 #endif namespace MTK { namespace internal { template struct traits { typedef typename Manifold::scalar scalar; enum {DOF = Manifold::DOF}; typedef vect vectorized_type; typedef Eigen::Matrix matrix_type; }; template<> struct traits : traits > {}; template<> struct traits : traits > {}; } // namespace internal /** * \defgroup MTKMath Mathematical helper functions */ //@{ //! constant @f$ \pi @f$ const double pi = M_PI; template inline scalar tolerance(); template<> inline float tolerance() { return 1e-5f; } template<> inline double tolerance() { return 1e-11; } /** * normalize @a x to @f$[-bound, bound] @f$. * * result for @f$ x = bound + 2\cdot n\cdot bound @f$ is arbitrary @f$\pm bound @f$. */ template inline scalar normalize(scalar x, scalar bound){ //not used if(std::fabs(x) <= bound) return x; int r = (int)(x *(scalar(1.0)/ bound)); return x - ((r + (r>>31) + 1) & ~1)*bound; } /** * Calculate cosine and sinc of sqrt(x2). * @param x2 the squared angle must be non-negative * @return a pair containing cos and sinc of sqrt(x2) */ template std::pair cos_sinc_sqrt(const scalar &x2){ using std::sqrt; using std::cos; using std::sin; static scalar const taylor_0_bound = boost::math::tools::epsilon(); static scalar const taylor_2_bound = sqrt(taylor_0_bound); static scalar const taylor_n_bound = sqrt(taylor_2_bound); assert(x2>=0 && "argument must be non-negative"); // FIXME check if bigger bounds are possible if(x2>=taylor_n_bound) { // slow fall-back solution scalar x = sqrt(x2); return std::make_pair(cos(x), sin(x)/x); // x is greater than 0. } // FIXME Replace by Horner-Scheme (4 instead of 5 FLOP/term, numerically more stable, theoretically cos and sinc can be calculated in parallel using SSE2 mulpd/addpd) // TODO Find optimal coefficients using Remez algorithm static scalar const inv[] = {1/3., 1/4., 1/5., 1/6., 1/7., 1/8., 1/9.}; scalar cosi = 1., sinc=1; scalar term = -1/2. * x2; for(int i=0; i<3; ++i) { cosi += term; term *= inv[2*i]; sinc += term; term *= -inv[2*i+1] * x2; } return std::make_pair(cosi, sinc); } template Eigen::Matrix hat(const Base& v) { Eigen::Matrix res; res << 0, -v[2], v[1], v[2], 0, -v[0], -v[1], v[0], 0; return res; } template Eigen::Matrix A_inv_trans(const Base& v){ Eigen::Matrix res; if(v.norm() > MTK::tolerance()) { res = Eigen::Matrix::Identity() + 0.5 * hat(v) + (1 - v.norm() * std::cos(v.norm() / 2) / 2 / std::sin(v.norm() / 2)) * hat(v) * hat(v) / v.squaredNorm(); } else { res = Eigen::Matrix::Identity(); } return res; } template Eigen::Matrix A_inv(const Base& v){ Eigen::Matrix res; if(v.norm() > MTK::tolerance()) { res = Eigen::Matrix::Identity() - 0.5 * hat(v) + (1 - v.norm() * std::cos(v.norm() / 2) / 2 / std::sin(v.norm() / 2)) * hat(v) * hat(v) / v.squaredNorm(); } else { res = Eigen::Matrix::Identity(); } return res; } template Eigen::Matrix S2_w_expw_( Eigen::Matrix v, scalar length) { Eigen::Matrix res; scalar norm = std::sqrt(v[0]*v[0] + v[1]*v[1]); if(norm < MTK::tolerance()){ res = Eigen::Matrix::Zero(); res(0, 1) = 1; res(1, 2) = 1; res /= length; } else{ res << -v[0]*(1/norm-1/std::tan(norm))/std::sin(norm), norm/std::sin(norm), 0, -v[1]*(1/norm-1/std::tan(norm))/std::sin(norm), 0, norm/std::sin(norm); res /= length; } } template Eigen::Matrix A_matrix(const Base & v){ Eigen::Matrix res; double squaredNorm = v[0] * v[0] + v[1] * v[1] + v[2] * v[2]; double norm = std::sqrt(squaredNorm); if(norm < MTK::tolerance()){ res = Eigen::Matrix::Identity(); } else{ // I + (1 - cos(norm)) / norm^2 * v^ + (1 - sin(norm) / norm) / norm^2 * v^ *v^ res = Eigen::Matrix::Identity() + (1 - std::cos(norm)) / squaredNorm * hat(v) + (1 - std::sin(norm) / norm) / squaredNorm * hat(v) * hat(v); } return res; } template scalar exp(vectview result, vectview vec, const scalar& scale = 1) { scalar norm2 = vec.squaredNorm(); std::pair cos_sinc = cos_sinc_sqrt(scale*scale * norm2); scalar mult = cos_sinc.second * scale; result = mult * vec; return cos_sinc.first; } /** * Inverse function to @c exp. * * @param result @c vectview to the result * @param w scalar part of input * @param vec vector part of input * @param scale scale result by this value * @param plus_minus_periodicity if true values @f$[w, vec]@f$ and @f$[-w, -vec]@f$ give the same result */ template void log(vectview result, const scalar &w, const vectview vec, const scalar &scale, bool plus_minus_periodicity) { // FIXME implement optimized case for vec.squaredNorm() <= tolerance() * (w*w) via Rational Remez approximation ~> only one division scalar nv = vec.norm(); if(nv < tolerance()) { if(!plus_minus_periodicity && w < 0) { // find the maximal entry: int i; nv = vec.cwiseAbs().maxCoeff(&i); result = scale * std::atan2(nv, w) * vect::Unit(i); return; } nv = tolerance(); } scalar s = scale / nv * (plus_minus_periodicity ? std::atan(nv / w) : std::atan2(nv, w) ); result = s * vec; } } // namespace MTK #endif /* MTKMATH_H_ */ ================================================ FILE: include/IKFoM_toolkit/mtk/src/vectview.hpp ================================================ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/src/vectview.hpp * @brief Wrapper class around a pointer used as interface for plain vectors. */ #ifndef VECTVIEW_HPP_ #define VECTVIEW_HPP_ #include namespace MTK { /** * A view to a vector. * Essentially, @c vectview is only a pointer to @c scalar but can be used directly in @c Eigen expressions. * The dimension of the vector is given as template parameter and type-checked when used in expressions. * Data has to be modifiable. * * @tparam scalar Scalar type of the vector. * @tparam dim Dimension of the vector. * * @todo @c vectview can be replaced by simple inheritance of @c Eigen::Map, as soon as they get const-correct */ namespace internal { template struct CovBlock { typedef typename Eigen::Block, T1::DOF, T2::DOF> Type; typedef typename Eigen::Block, T1::DOF, T2::DOF> ConstType; }; template struct CovBlock_ { typedef typename Eigen::Block, T1::DIM, T2::DIM> Type; typedef typename Eigen::Block, T1::DIM, T2::DIM> ConstType; }; template struct CrossCovBlock { typedef typename Eigen::Block, T1::DOF, T2::DOF> Type; typedef typename Eigen::Block, T1::DOF, T2::DOF> ConstType; }; template struct CrossCovBlock_ { typedef typename Eigen::Block, T1::DIM, T2::DIM> Type; typedef typename Eigen::Block, T1::DIM, T2::DIM> ConstType; }; template struct VectviewBase { typedef Eigen::Matrix matrix_type; typedef typename matrix_type::MapType Type; typedef typename matrix_type::ConstMapType ConstType; }; template struct UnalignedType { typedef T type; }; } template class vectview : public internal::VectviewBase::Type { typedef internal::VectviewBase VectviewBase; public: //! plain matrix type typedef typename VectviewBase::matrix_type matrix_type; //! base type typedef typename VectviewBase::Type base; //! construct from pointer explicit vectview(scalar* data, int dim_=dim) : base(data, dim_) {} //! construct from plain matrix vectview(matrix_type& m) : base(m.data(), m.size()) {} //! construct from another @c vectview vectview(const vectview &v) : base(v) {} //! construct from Eigen::Block: template vectview(Eigen::VectorBlock block) : base(&block.coeffRef(0), block.size()) {} template vectview(Eigen::Block block) : base(&block.coeffRef(0), block.size()) {} //! inherit assignment operator using base::operator=; //! data pointer scalar* data() {return const_cast(base::data());} }; /** * @c const version of @c vectview. * Compared to @c Eigen::Map this implementation is const correct, i.e., * data will not be modifiable using this view. * * @tparam scalar Scalar type of the vector. * @tparam dim Dimension of the vector. * * @sa vectview */ template class vectview : public internal::VectviewBase::ConstType { typedef internal::VectviewBase VectviewBase; public: //! plain matrix type typedef typename VectviewBase::matrix_type matrix_type; //! base type typedef typename VectviewBase::ConstType base; //! construct from const pointer explicit vectview(const scalar* data, int dim_ = dim) : base(data, dim_) {} //! construct from column vector template vectview(const Eigen::Matrix& m) : base(m.data()) {} //! construct from row vector template vectview(const Eigen::Matrix& m) : base(m.data()) {} //! construct from another @c vectview vectview(vectview x) : base(x.data()) {} //! construct from base vectview(const base &x) : base(x) {} /** * Construct from Block * @todo adapt this, when Block gets const-correct */ template vectview(Eigen::VectorBlock block) : base(&block.coeffRef(0)) {} template vectview(Eigen::Block block) : base(&block.coeffRef(0)) {} }; } // namespace MTK #endif /* VECTVIEW_HPP_ */ ================================================ FILE: include/IKFoM_toolkit/mtk/startIdx.hpp ================================================ // This is an advanced implementation of the algorithm described in the // following paper: // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Modifier: Dongjiao HE * * 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 Universitaet Bremen 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. */ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/startIdx.hpp * @brief Tools to access sub-elements of compound manifolds. */ #ifndef GET_START_INDEX_H_ #define GET_START_INDEX_H_ #include #include "src/SubManifold.hpp" #include "src/vectview.hpp" namespace MTK { /** * \defgroup SubManifolds Accessing Submanifolds * For compound manifolds constructed using MTK_BUILD_MANIFOLD, member pointers * can be used to get sub-vectors or matrix-blocks of a corresponding big matrix. * E.g. for a type @a pose consisting of @a orient and @a trans the member pointers * @c &pose::orient and @c &pose::trans give all required information and are still * valid if the base type gets extended or the actual types of @a orient and @a trans * change (e.g. from 2D to 3D). * * @todo Maybe require manifolds to typedef MatrixType and VectorType, etc. */ //@{ /** * Determine the index of a sub-variable within a compound variable. */ template int getStartIdx( MTK::SubManifold Base::*) { return idx; } template int getStartIdx_( MTK::SubManifold Base::*) { return dim; } /** * Determine the degrees of freedom of a sub-variable within a compound variable. */ template int getDof( MTK::SubManifold Base::*) { return T::DOF; } template int getDim( MTK::SubManifold Base::*) { return T::DIM; } /** * set the diagonal elements of a covariance matrix corresponding to a sub-variable */ template void setDiagonal(Eigen::Matrix &cov, MTK::SubManifold Base::*, const typename Base::scalar &val) { cov.diagonal().template segment(idx).setConstant(val); } template void setDiagonal_(Eigen::Matrix &cov, MTK::SubManifold Base::*, const typename Base::scalar &val) { cov.diagonal().template segment(dim).setConstant(val); } /** * Get the subblock of corresponding to two members, i.e. * \code * Eigen::Matrix m; * MTK::subblock(m, &Pose::orient, &Pose::trans) = some_expression; * MTK::subblock(m, &Pose::trans, &Pose::orient) = some_expression.trans(); * \endcode * lets you modify mixed covariance entries in a bigger covariance matrix. */ template typename MTK::internal::CovBlock::Type subblock(Eigen::Matrix &cov, MTK::SubManifold Base::*, MTK::SubManifold Base::*) { return cov.template block(idx1, idx2); } template typename MTK::internal::CovBlock_::Type subblock_(Eigen::Matrix &cov, MTK::SubManifold Base::*, MTK::SubManifold Base::*) { return cov.template block(dim1, dim2); } template typename MTK::internal::CrossCovBlock::Type subblock(Eigen::Matrix &cov, MTK::SubManifold Base1::*, MTK::SubManifold Base2::*) { return cov.template block(idx1, idx2); } template typename MTK::internal::CrossCovBlock_::Type subblock_(Eigen::Matrix &cov, MTK::SubManifold Base1::*, MTK::SubManifold Base2::*) { return cov.template block(dim1, dim2); } /** * Get the subblock of corresponding to a member, i.e. * \code * Eigen::Matrix m; * MTK::subblock(m, &Pose::orient) = some_expression; * \endcode * lets you modify covariance entries in a bigger covariance matrix. */ template typename MTK::internal::CovBlock_::Type subblock_(Eigen::Matrix &cov, MTK::SubManifold Base::*) { return cov.template block(dim, dim); } template typename MTK::internal::CovBlock::Type subblock(Eigen::Matrix &cov, MTK::SubManifold Base::*) { return cov.template block(idx, idx); } template class get_cov { public: typedef Eigen::Matrix type; typedef const Eigen::Matrix const_type; }; template class get_cov_ { public: typedef Eigen::Matrix type; typedef const Eigen::Matrix const_type; }; template class get_cross_cov { public: typedef Eigen::Matrix type; typedef const type const_type; }; template class get_cross_cov_ { public: typedef Eigen::Matrix type; typedef const type const_type; }; template vectview subvector_impl_(vectview vec, SubManifold Base::*) { return vec.template segment(dim); } template vectview subvector_impl(vectview vec, SubManifold Base::*) { return vec.template segment(idx); } /** * Get the subvector corresponding to a sub-manifold from a bigger vector. */ template vectview subvector_(vectview vec, SubManifold Base::* ptr) { return subvector_impl_(vec, ptr); } template vectview subvector(vectview vec, SubManifold Base::* ptr) { return subvector_impl(vec, ptr); } /** * @todo This should be covered already by subvector(vectview vec,SubManifold Base::*) */ template vectview subvector(Eigen::Matrix& vec, SubManifold Base::* ptr) { return subvector_impl(vectview(vec), ptr); } template vectview subvector_(Eigen::Matrix& vec, SubManifold Base::* ptr) { return subvector_impl_(vectview(vec), ptr); } template vectview subvector_(const Eigen::Matrix& vec, SubManifold Base::* ptr) { return subvector_impl_(vectview(vec), ptr); } template vectview subvector(const Eigen::Matrix& vec, SubManifold Base::* ptr) { return subvector_impl(vectview(vec), ptr); } /** * const version of subvector(vectview vec,SubManifold Base::*) */ template vectview subvector_impl(const vectview cvec, SubManifold Base::*) { return cvec.template segment(idx); } template vectview subvector_impl_(const vectview cvec, SubManifold Base::*) { return cvec.template segment(dim); } template vectview subvector(const vectview cvec, SubManifold Base::* ptr) { return subvector_impl(cvec, ptr); } } // namespace MTK #endif // GET_START_INDEX_H_ ================================================ FILE: include/IKFoM_toolkit/mtk/types/S2.hpp ================================================ // This is a NEW implementation of the algorithm described in the // following paper: // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Modifier: Dongjiao HE * * 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 Universitaet Bremen 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. */ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/types/S2.hpp * @brief Unit vectors on the sphere, or directions in 3D. */ #ifndef S2_H_ #define S2_H_ #include "vect.hpp" #include "SOn.hpp" #include "../src/mtkmath.hpp" namespace MTK { /** * Manifold representation of @f$ S^2 @f$. * Used for unit vectors on the sphere or directions in 3D. * * @todo add conversions from/to polar angles? */ template struct S2 { typedef _scalar scalar; typedef vect<3, scalar> vect_type; typedef SO3 SO3_type; typedef typename vect_type::base vec3; scalar length = scalar(den)/scalar(num); enum {DOF=2, TYP = 1, DIM = 3}; //private: /** * Unit vector on the sphere, or vector pointing in a direction */ vect_type vec; public: S2() { if(S2_typ == 3) vec=length * vec3(0, 0, std::sqrt(1)); if(S2_typ == 2) vec=length * vec3(0, std::sqrt(1), 0); if(S2_typ == 1) vec=length * vec3(std::sqrt(1), 0, 0); } S2(const scalar &x, const scalar &y, const scalar &z) : vec(vec3(x, y, z)) { vec.normalize(); vec = vec * length; } S2(const vect_type &_vec) : vec(_vec) { vec.normalize(); vec = vec * length; } void oplus(MTK::vectview delta, scalar scale = 1) { SO3_type res; res.w() = MTK::exp(res.vec(), delta, scalar(scale/2)); vec = res.toRotationMatrix() * vec; } void boxplus(MTK::vectview delta, scalar scale=1) { Eigen::Matrix Bx; S2_Bx(Bx); vect_type Bu = Bx*delta;SO3_type res; res.w() = MTK::exp(res.vec(), Bu, scalar(scale/2)); vec = res.toRotationMatrix() * vec; } void boxminus(MTK::vectview res, const S2& other) const { scalar v_sin = (MTK::hat(vec)*other.vec).norm(); scalar v_cos = vec.transpose() * other.vec; scalar theta = std::atan2(v_sin, v_cos); if(v_sin < MTK::tolerance()) { if(std::fabs(theta) > MTK::tolerance() ) { res[0] = 3.1415926; res[1] = 0; } else{ res[0] = 0; res[1] = 0; } } else { S2 other_copy = other; Eigen::MatrixBx; other_copy.S2_Bx(Bx); res = theta/v_sin * Bx.transpose() * MTK::hat(other.vec)*vec; } } void S2_hat(Eigen::Matrix &res) { Eigen::Matrix skew_vec; skew_vec << scalar(0), -vec[2], vec[1], vec[2], scalar(0), -vec[0], -vec[1], vec[0], scalar(0); res = skew_vec; } void S2_Bx(Eigen::Matrix &res) { if(S2_typ == 3) { if(vec[2] + length > tolerance()) { res << length - vec[0]*vec[0]/(length+vec[2]), -vec[0]*vec[1]/(length+vec[2]), -vec[0]*vec[1]/(length+vec[2]), length-vec[1]*vec[1]/(length+vec[2]), -vec[0], -vec[1]; res /= length; } else { res = Eigen::Matrix::Zero(); res(1, 1) = -1; res(2, 0) = 1; } } else if(S2_typ == 2) { if(vec[1] + length > tolerance()) { res << length - vec[0]*vec[0]/(length+vec[1]), -vec[0]*vec[2]/(length+vec[1]), -vec[0], -vec[2], -vec[0]*vec[2]/(length+vec[1]), length-vec[2]*vec[2]/(length+vec[1]); res /= length; } else { res = Eigen::Matrix::Zero(); res(1, 1) = -1; res(2, 0) = 1; } } else { if(vec[0] + length > tolerance()) { res << -vec[1], -vec[2], length - vec[1]*vec[1]/(length+vec[0]), -vec[2]*vec[1]/(length+vec[0]), -vec[2]*vec[1]/(length+vec[0]), length-vec[2]*vec[2]/(length+vec[0]); res /= length; } else { res = Eigen::Matrix::Zero(); res(1, 1) = -1; res(2, 0) = 1; } } } void S2_Nx(Eigen::Matrix &res, S2& subtrahend) { if((vec+subtrahend.vec).norm() > tolerance()) { Eigen::Matrix Bx; S2_Bx(Bx); if((vec-subtrahend.vec).norm() > tolerance()) { scalar v_sin = (MTK::hat(vec)*subtrahend.vec).norm(); scalar v_cos = vec.transpose() * subtrahend.vec; res = Bx.transpose() * (std::atan2(v_sin, v_cos)/v_sin*MTK::hat(vec)+MTK::hat(vec)*subtrahend.vec*((-v_cos/v_sin/v_sin/length/length/length/length+std::atan2(v_sin, v_cos)/v_sin/v_sin/v_sin)*subtrahend.vec.transpose()*MTK::hat(vec)*MTK::hat(vec)-vec.transpose()/length/length/length/length)); } else { res = 1/length/length*Bx.transpose()*MTK::hat(vec); } } else { std::cerr << "No N(x, y) for x=-y" << std::endl; std::exit(100); } } void S2_Nx_yy(Eigen::Matrix &res) { Eigen::Matrix Bx; S2_Bx(Bx); res = 1/length/length*Bx.transpose()*MTK::hat(vec); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { Eigen::Matrix Bx; S2_Bx(Bx); if(delta.norm() < tolerance()) { res = -MTK::hat(vec)*Bx; } else{ vect_type Bu = Bx*delta; SO3_type exp_delta; exp_delta.w() = MTK::exp(exp_delta.vec(), Bu, scalar(1/2)); res = -exp_delta.toRotationMatrix()*MTK::hat(vec)*MTK::A_matrix(Bu).transpose()*Bx; } } operator const vect_type&() const{ return vec; } const vect_type& get_vect() const { return vec; } friend S2 operator*(const SO3& rot, const S2& dir) { S2 ret; ret.vec = rot * dir.vec; return ret; } scalar operator[](int idx) const {return vec[idx]; } friend std::ostream& operator<<(std::ostream &os, const S2& vec){ return os << vec.vec.transpose() << " "; } friend std::istream& operator>>(std::istream &is, S2& vec){ for(int i=0; i<3; ++i) is >> vec.vec[i]; vec.vec.normalize(); vec.vec = vec.vec * vec.length; return is; } }; } // namespace MTK #endif /*S2_H_*/ ================================================ FILE: include/IKFoM_toolkit/mtk/types/SOn.hpp ================================================ // This is an advanced implementation of the algorithm described in the // following paper: // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Modifier: Dongjiao HE * * 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 Universitaet Bremen 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. */ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/types/SOn.hpp * @brief Standard Orthogonal Groups i.e.\ rotatation groups. */ #ifndef SON_H_ #define SON_H_ #include #include "vect.hpp" #include "../src/mtkmath.hpp" namespace MTK { /** * Two-dimensional orientations represented as scalar. * There is no guarantee that the representing scalar is within any interval, * but the result of boxminus will always have magnitude @f$\le\pi @f$. */ template struct SO2 : public Eigen::Rotation2D<_scalar> { enum {DOF = 1, DIM = 2, TYP = 3}; typedef _scalar scalar; typedef Eigen::Rotation2D base; typedef vect vect_type; //! Construct from angle SO2(const scalar& angle = 0) : base(angle) { } //! Construct from Eigen::Rotation2D SO2(const base& src) : base(src) {} /** * Construct from 2D vector. * Resulting orientation will rotate the first unit vector to point to vec. */ SO2(const vect_type &vec) : base(atan2(vec[1], vec[0])) {}; //! Calculate @c this->inverse() * @c r SO2 operator%(const base &r) const { return base::inverse() * r; } //! Calculate @c this->inverse() * @c r template vect_type operator%(const Eigen::MatrixBase &vec) const { return base::inverse() * vec; } //! Calculate @c *this * @c r.inverse() SO2 operator/(const SO2 &r) const { return *this * r.inverse(); } //! Gets the angle as scalar. operator scalar() const { return base::angle(); } void S2_hat(Eigen::Matrix &res) { res = Eigen::Matrix::Zero(); } //! @name Manifold requirements void S2_Nx_yy(Eigen::Matrix &res) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void oplus(MTK::vectview vec, scalar scale = 1) { base::angle() += scale * vec[0]; } void boxplus(MTK::vectview vec, scalar scale = 1) { base::angle() += scale * vec[0]; } void boxminus(MTK::vectview res, const SO2& other) const { res[0] = MTK::normalize(base::angle() - other.angle(), scalar(MTK::pi)); } friend std::istream& operator>>(std::istream &is, SO2& ang){ return is >> ang.angle(); } }; /** * Three-dimensional orientations represented as Quaternion. * It is assumed that the internal Quaternion always stays normalized, * should this not be the case, call inherited member function @c normalize(). */ template struct SO3 : public Eigen::Quaternion<_scalar, Options> { enum {DOF = 3, DIM = 3, TYP = 2}; typedef _scalar scalar; typedef Eigen::Quaternion base; typedef Eigen::Quaternion Quaternion; typedef vect vect_type; //! Calculate @c this->inverse() * @c r template EIGEN_STRONG_INLINE Quaternion operator%(const Eigen::QuaternionBase &r) const { return base::conjugate() * r; } //! Calculate @c this->inverse() * @c r template vect_type operator%(const Eigen::MatrixBase &vec) const { return base::conjugate() * vec; } //! Calculate @c this * @c r.conjugate() template EIGEN_STRONG_INLINE Quaternion operator/(const Eigen::QuaternionBase &r) const { return *this * r.conjugate(); } /** * Construct from real part and three imaginary parts. * Quaternion is normalized after construction. */ SO3(const scalar& w, const scalar& x, const scalar& y, const scalar& z) : base(w, x, y, z) { base::normalize(); } /** * Construct from Eigen::Quaternion. * @note Non-normalized input may result result in spurious behavior. */ SO3(const base& src = base::Identity()) : base(src) {} /** * Construct from rotation matrix. * @note Invalid rotation matrices may lead to spurious behavior. */ template SO3(const Eigen::MatrixBase& matrix) : base(matrix) {} /** * Construct from arbitrary rotation type. * @note Invalid rotation matrices may lead to spurious behavior. */ template SO3(const Eigen::RotationBase& rotation) : base(rotation.derived()) {} //! @name Manifold requirements void boxplus(MTK::vectview vec, scalar scale=1) { SO3 delta = exp(vec, scale); *this = *this * delta; } void boxminus(MTK::vectview res, const SO3& other) const { res = SO3::log(other.conjugate() * *this); } //} void oplus(MTK::vectview vec, scalar scale=1) { SO3 delta = exp(vec, scale); *this = *this * delta; } void S2_hat(Eigen::Matrix &res) { res = Eigen::Matrix::Zero(); } void S2_Nx_yy(Eigen::Matrix &res) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } friend std::ostream& operator<<(std::ostream &os, const SO3& q){ return os << q.coeffs().transpose() << " "; } friend std::istream& operator>>(std::istream &is, SO3& q){ vect<4,scalar> coeffs; is >> coeffs; q.coeffs() = coeffs.normalized(); return is; } //! @name Helper functions //{ /** * Calculate the exponential map. In matrix terms this would correspond * to the Rodrigues formula. */ // FIXME vectview<> can't be constructed from every MatrixBase<>, use const Vector3x& as workaround // static SO3 exp(MTK::vectview dvec, scalar scale = 1){ static SO3 exp(const Eigen::Matrix& dvec, scalar scale = 1){ SO3 res; res.w() = MTK::exp(res.vec(), dvec, scalar(scale/2)); return res; } /** * Calculate the inverse of @c exp. * Only guarantees that exp(log(x)) == x */ static typename base::Vector3 log(const SO3 &orient){ typename base::Vector3 res; MTK::log(res, orient.w(), orient.vec(), scalar(2), true); return res; } }; namespace internal { template struct UnalignedType >{ typedef SO2 type; }; template struct UnalignedType >{ typedef SO3 type; }; } // namespace internal } // namespace MTK #endif /*SON_H_*/ ================================================ FILE: include/IKFoM_toolkit/mtk/types/vect.hpp ================================================ // This is an advanced implementation of the algorithm described in the // following paper: // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 /* * Copyright (c) 2019--2023, The University of Hong Kong * All rights reserved. * * Modifier: Dongjiao HE * * 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 Universitaet Bremen 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. */ /* * Copyright (c) 2008--2011, Universitaet Bremen * All rights reserved. * * Author: Christoph Hertzberg * * 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 Universitaet Bremen 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. */ /** * @file mtk/types/vect.hpp * @brief Basic vectors interpreted as manifolds. * * This file also implements a simple wrapper for matrices, for arbitrary scalars * and for positive scalars. */ #ifndef VECT_H_ #define VECT_H_ #include #include #include #include "../src/vectview.hpp" namespace MTK { static const Eigen::IOFormat IO_no_spaces(Eigen::StreamPrecision, Eigen::DontAlignCols, ",", ",", "", "", "[", "]"); /** * A simple vector class. * Implementation is basically a wrapper around Eigen::Matrix with manifold * requirements added. */ template struct vect : public Eigen::Matrix<_scalar, D, 1, _Options> { typedef Eigen::Matrix<_scalar, D, 1, _Options> base; enum {DOF = D, DIM = D, TYP = 0}; typedef _scalar scalar; //using base::operator=; /** Standard constructor. Sets all values to zero. */ vect(const base &src = base::Zero()) : base(src) {} /** Constructor copying the value of the expression \a other */ template EIGEN_STRONG_INLINE vect(const Eigen::DenseBase& other) : base(other) {} /** Construct from memory. */ vect(const scalar* src, int size = DOF) : base(base::Map(src, size)) { } void boxplus(MTK::vectview vec, scalar scale=1) { *this += scale * vec; } void boxminus(MTK::vectview res, const vect& other) const { res = *this - other; } void oplus(MTK::vectview vec, scalar scale=1) { *this += scale * vec; } void S2_hat(Eigen::Matrix &res) { res = Eigen::Matrix::Zero(); } void S2_Nx_yy(Eigen::Matrix &res) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } friend std::ostream& operator<<(std::ostream &os, const vect& v){ // Eigen sometimes messes with the streams flags, so output manually: for(int i=0; i>(std::istream &is, vect& v){ char term=0; is >> std::ws; // skip whitespace switch(is.peek()) { case '(': term=')'; is.ignore(1); break; case '[': term=']'; is.ignore(1); break; case '{': term='}'; is.ignore(1); break; default: break; } if(D==Eigen::Dynamic) { assert(term !=0 && "Dynamic vectors must be embraced"); std::vector temp; while(is.good() && is.peek() != term) { scalar x; is >> x; temp.push_back(x); if(is.peek()==',') is.ignore(1); } v = vect::Map(temp.data(), temp.size()); } else for(int i=0; i> v[i]; if(is.peek()==',') { // ignore commas between values is.ignore(1); } } if(term!=0) { char x; is >> x; if(x!=term) { is.setstate(is.badbit); // assert(x==term && "start and end bracket do not match!"); } } return is; } template vectview tail(){ BOOST_STATIC_ASSERT(0< dim && dim <= DOF); return base::template tail(); } template vectview tail() const{ BOOST_STATIC_ASSERT(0< dim && dim <= DOF); return base::template tail(); } template vectview head(){ BOOST_STATIC_ASSERT(0< dim && dim <= DOF); return base::template head(); } template vectview head() const{ BOOST_STATIC_ASSERT(0< dim && dim <= DOF); return base::template head(); } }; /** * A simple matrix class. * Implementation is basically a wrapper around Eigen::Matrix with manifold * requirements added, i.e., matrix is viewed as a plain vector for that. */ template::Options> struct matrix : public Eigen::Matrix<_scalar, M, N, _Options> { typedef Eigen::Matrix<_scalar, M, N, _Options> base; enum {DOF = M * N, TYP = 4, DIM=0}; typedef _scalar scalar; using base::operator=; /** Standard constructor. Sets all values to zero. */ matrix() { base::setZero(); } /** Constructor copying the value of the expression \a other */ template EIGEN_STRONG_INLINE matrix(const Eigen::MatrixBase& other) : base(other) {} /** Construct from memory. */ matrix(const scalar* src) : base(src) { } void boxplus(MTK::vectview vec, scalar scale = 1) { *this += scale * base::Map(vec.data()); } void boxminus(MTK::vectview res, const matrix& other) const { base::Map(res.data()) = *this - other; } void S2_hat(Eigen::Matrix &res) { res = Eigen::Matrix::Zero(); } void oplus(MTK::vectview vec, scalar scale = 1) { *this += scale * base::Map(vec.data()); } void S2_Nx_yy(Eigen::Matrix &res) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } friend std::ostream& operator<<(std::ostream &os, const matrix& mat){ for(int i=0; i>(std::istream &is, matrix& mat){ for(int i=0; i> mat.data()[i]; } return is; } };// @todo What if M / N = Eigen::Dynamic? /** * A simple scalar type. */ template struct Scalar { enum {DOF = 1, TYP = 5, DIM=0}; typedef _scalar scalar; scalar value; Scalar(const scalar& value = scalar(0)) : value(value) {} operator const scalar&() const { return value; } operator scalar&() { return value; } Scalar& operator=(const scalar& val) { value = val; return *this; } void S2_hat(Eigen::Matrix &res) { res = Eigen::Matrix::Zero(); } void S2_Nx_yy(Eigen::Matrix &res) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void oplus(MTK::vectview vec, scalar scale=1) { value += scale * vec[0]; } void boxplus(MTK::vectview vec, scalar scale=1) { value += scale * vec[0]; } void boxminus(MTK::vectview res, const Scalar& other) const { res[0] = *this - other; } }; /** * Positive scalars. * Boxplus is implemented using multiplication by @f$x\boxplus\delta = x\cdot\exp(\delta) @f$. */ template struct PositiveScalar { enum {DOF = 1, TYP = 6, DIM=0}; typedef _scalar scalar; scalar value; PositiveScalar(const scalar& value = scalar(1)) : value(value) { assert(value > scalar(0)); } operator const scalar&() const { return value; } PositiveScalar& operator=(const scalar& val) { assert(val>0); value = val; return *this; } void boxplus(MTK::vectview vec, scalar scale = 1) { value *= std::exp(scale * vec[0]); } void boxminus(MTK::vectview res, const PositiveScalar& other) const { res[0] = std::log(*this / other); } void oplus(MTK::vectview vec, scalar scale = 1) { value *= std::exp(scale * vec[0]); } void S2_hat(Eigen::Matrix &res) { res = Eigen::Matrix::Zero(); } void S2_Nx_yy(Eigen::Matrix &res) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } friend std::istream& operator>>(std::istream &is, PositiveScalar& s){ is >> s.value; assert(s.value > 0); return is; } }; template struct Complex : public std::complex<_scalar>{ enum {DOF = 2, TYP = 7, DIM=0}; typedef _scalar scalar; typedef std::complex Base; Complex(const Base& value) : Base(value) {} Complex(const scalar& re = 0.0, const scalar& im = 0.0) : Base(re, im) {} Complex(const MTK::vectview &in) : Base(in[0], in[1]) {} template Complex(const Eigen::DenseBase &in) : Base(in[0], in[1]) {} void boxplus(MTK::vectview vec, scalar scale = 1) { Base::real() += scale * vec[0]; Base::imag() += scale * vec[1]; }; void boxminus(MTK::vectview res, const Complex& other) const { Complex diff = *this - other; res << diff.real(), diff.imag(); } void S2_hat(Eigen::Matrix &res) { res = Eigen::Matrix::Zero(); } void oplus(MTK::vectview vec, scalar scale = 1) { Base::real() += scale * vec[0]; Base::imag() += scale * vec[1]; }; void S2_Nx_yy(Eigen::Matrix &res) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) { std::cerr << "wrong idx for S2" << std::endl; std::exit(100); res = Eigen::Matrix::Zero(); } scalar squaredNorm() const { return std::pow(Base::real(),2) + std::pow(Base::imag(),2); } const scalar& operator()(int i) const { assert(0<=i && i<2 && "Index out of range"); return i==0 ? Base::real() : Base::imag(); } scalar& operator()(int i){ assert(0<=i && i<2 && "Index out of range"); return i==0 ? Base::real() : Base::imag(); } }; namespace internal { template struct UnalignedType >{ typedef vect type; }; } // namespace internal } // namespace MTK #endif /*VECT_H_*/ ================================================ FILE: include/IKFoM_toolkit/mtk/types/wrapped_cv_mat.hpp ================================================ /* * Copyright (c) 2010--2011, Universitaet Bremen and DFKI GmbH * All rights reserved. * * Author: Rene Wagner * Christoph Hertzberg * * 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 Universitaet Bremen nor the DFKI GmbH * 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 WRAPPED_CV_MAT_HPP_ #define WRAPPED_CV_MAT_HPP_ #include #include namespace MTK { template struct cv_f_type; template<> struct cv_f_type { enum {value = CV_64F}; }; template<> struct cv_f_type { enum {value = CV_32F}; }; /** * cv_mat wraps a CvMat around an Eigen Matrix */ template class cv_mat : public matrix { typedef matrix base_type; enum {type_ = cv_f_type::value}; CvMat cv_mat_; public: cv_mat() { cv_mat_ = cvMat(rows, cols, type_, base_type::data()); } cv_mat(const cv_mat& oth) : base_type(oth) { cv_mat_ = cvMat(rows, cols, type_, base_type::data()); } template cv_mat(const Eigen::MatrixBase &value) : base_type(value) { cv_mat_ = cvMat(rows, cols, type_, base_type::data()); } template cv_mat& operator=(const Eigen::MatrixBase &value) { base_type::operator=(value); return *this; } cv_mat& operator=(const cv_mat& value) { base_type::operator=(value); return *this; } // FIXME: Maybe overloading operator& is not a good idea ... CvMat* operator&() { return &cv_mat_; } const CvMat* operator&() const { return &cv_mat_; } }; } // namespace MTK #endif /* WRAPPED_CV_MAT_HPP_ */ ================================================ FILE: include/common_lib.h ================================================ #ifndef COMMON_LIB_H #define COMMON_LIB_H #include #include #include #include #include #include #include #include #include #include "point_type.h" using namespace std; using namespace Eigen; #define USE_IKFOM #define PI_M (3.14159265358) #define G_m_s2 (9.81) // Gravaty const in GuangDong/China #define DIM_STATE (18) // Dimension of states (Let Dim(SO(3)) = 3) #define DIM_PROC_N (12) // Dimension of process noise (Let Dim(SO(3)) = 3) #define CUBE_LEN (6.0) #define LIDAR_SP_LEN (2) #define INIT_COV (1) #define NUM_MATCH_POINTS (5) #define MAX_MEAS_DIM (10000) #define VEC_FROM_ARRAY(v) v[0],v[1],v[2] #define MAT_FROM_ARRAY(v) v[0],v[1],v[2],v[3],v[4],v[5],v[6],v[7],v[8] #define CONSTRAIN(v,min,max) ((v>min)?((v (mat.data(), mat.data() + mat.rows() * mat.cols()) #define DEBUG_FILE_DIR(name) (string(string(ROOT_DIR) + "Log/"+ name)) typedef log_lio::Pose6D Pose6D; typedef pcl::PointXYZINormal PointType; //typedef ikdTree_PointType PointType; typedef pcl::PointCloud PointCloudXYZI; typedef vector> PointVector; typedef Vector3d V3D; typedef Matrix3d M3D; typedef Vector3f V3F; typedef Matrix3f M3F; #define MD(a,b) Matrix #define VD(a) Matrix #define MF(a,b) Matrix #define VF(a) Matrix M3D Eye3d(M3D::Identity()); M3F Eye3f(M3F::Identity()); V3D Zero3d(0, 0, 0); V3F Zero3f(0, 0, 0); struct MeasureGroup // Lidar data and imu dates for the curent process { MeasureGroup() { lidar_beg_time = 0.0; this->lidar.reset(new PointCloudXYZI()); }; double lidar_beg_time; double lidar_end_time; PointCloudXYZI::Ptr lidar; deque imu; }; struct StatesGroup { StatesGroup() { this->rot_end = M3D::Identity(); this->pos_end = Zero3d; this->vel_end = Zero3d; this->bias_g = Zero3d; this->bias_a = Zero3d; this->gravity = Zero3d; this->cov = MD(DIM_STATE,DIM_STATE)::Identity() * INIT_COV; this->cov.block<9,9>(9,9) = MD(9,9)::Identity() * 0.00001; }; StatesGroup(const StatesGroup& b) { this->rot_end = b.rot_end; this->pos_end = b.pos_end; this->vel_end = b.vel_end; this->bias_g = b.bias_g; this->bias_a = b.bias_a; this->gravity = b.gravity; this->cov = b.cov; }; StatesGroup& operator=(const StatesGroup& b) { this->rot_end = b.rot_end; this->pos_end = b.pos_end; this->vel_end = b.vel_end; this->bias_g = b.bias_g; this->bias_a = b.bias_a; this->gravity = b.gravity; this->cov = b.cov; return *this; }; StatesGroup operator+(const Matrix &state_add) { StatesGroup a; a.rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0)); a.pos_end = this->pos_end + state_add.block<3,1>(3,0); a.vel_end = this->vel_end + state_add.block<3,1>(6,0); a.bias_g = this->bias_g + state_add.block<3,1>(9,0); a.bias_a = this->bias_a + state_add.block<3,1>(12,0); a.gravity = this->gravity + state_add.block<3,1>(15,0); a.cov = this->cov; return a; }; StatesGroup& operator+=(const Matrix &state_add) { this->rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0)); this->pos_end += state_add.block<3,1>(3,0); this->vel_end += state_add.block<3,1>(6,0); this->bias_g += state_add.block<3,1>(9,0); this->bias_a += state_add.block<3,1>(12,0); this->gravity += state_add.block<3,1>(15,0); return *this; }; Matrix operator-(const StatesGroup& b) { Matrix a; M3D rotd(b.rot_end.transpose() * this->rot_end); a.block<3,1>(0,0) = Log(rotd); a.block<3,1>(3,0) = this->pos_end - b.pos_end; a.block<3,1>(6,0) = this->vel_end - b.vel_end; a.block<3,1>(9,0) = this->bias_g - b.bias_g; a.block<3,1>(12,0) = this->bias_a - b.bias_a; a.block<3,1>(15,0) = this->gravity - b.gravity; return a; }; void resetpose() { this->rot_end = M3D::Identity(); this->pos_end = Zero3d; this->vel_end = Zero3d; } M3D rot_end; // the estimated attitude (rotation matrix) at the end lidar point V3D pos_end; // the estimated position at the end lidar point (world frame) V3D vel_end; // the estimated velocity at the end lidar point (world frame) V3D bias_g; // gyroscope bias V3D bias_a; // accelerator bias V3D gravity; // the estimated gravity acceleration Matrix cov; // states covariance }; template T rad2deg(T radians) { return radians * 180.0 / PI_M; } template T deg2rad(T degrees) { return degrees * PI_M / 180.0; } template auto set_pose6d(const double t, const Matrix &a, const Matrix &g, \ const Matrix &v, const Matrix &p, const Matrix &R) { Pose6D rot_kp; rot_kp.offset_time = t; for (int i = 0; i < 3; i++) { rot_kp.acc[i] = a(i); rot_kp.gyr[i] = g(i); rot_kp.vel[i] = v(i); rot_kp.pos[i] = p(i); for (int j = 0; j < 3; j++) rot_kp.rot[i*3+j] = R(i,j); } return move(rot_kp); } /* comment plane equation: Ax + By + Cz + D = 0 convert to: A/D*x + B/D*y + C/D*z = -1 solve: A0*x0 = b0 where A0_i = [x_i, y_i, z_i], x0 = [A/D, B/D, C/D]^T, b0 = [-1, ..., -1]^T normvec: normalized x0 */ template bool esti_normvector(Matrix &normvec, const PointVector &point, const T &threshold, const int &point_num) { MatrixXf A(point_num, 3); MatrixXf b(point_num, 1); b.setOnes(); b *= -1.0f; for (int j = 0; j < point_num; j++) { A(j,0) = point[j].x; A(j,1) = point[j].y; A(j,2) = point[j].z; } normvec = A.colPivHouseholderQr().solve(b); for (int j = 0; j < point_num; j++) { if (fabs(normvec(0) * point[j].x + normvec(1) * point[j].y + normvec(2) * point[j].z + 1.0f) > threshold) { return false; } } normvec.normalize(); return true; } float calc_dist(PointType p1, PointType p2){ float d = (p1.x - p2.x) * (p1.x - p2.x) + (p1.y - p2.y) * (p1.y - p2.y) + (p1.z - p2.z) * (p1.z - p2.z); return d; } template bool esti_plane(Matrix &pca_result, const PointVector &point, const T &threshold) { Matrix A; Matrix b; A.setZero(); b.setOnes(); b *= -1.0f; for (int j = 0; j < NUM_MATCH_POINTS; j++) { A(j,0) = point[j].x; A(j,1) = point[j].y; A(j,2) = point[j].z; } Matrix normvec = A.colPivHouseholderQr().solve(b); // n * p + b = 0 T n = normvec.norm(); pca_result(0) = normvec(0) / n; pca_result(1) = normvec(1) / n; pca_result(2) = normvec(2) / n; pca_result(3) = 1.0 / n; for (int j = 0; j < NUM_MATCH_POINTS; j++) { if (fabs(pca_result(0) * point[j].x + pca_result(1) * point[j].y + pca_result(2) * point[j].z + pca_result(3)) > threshold) { return false; } } return true; } #endif ================================================ FILE: include/ikd-Tree/ikd_Tree.cpp ================================================ #include "ikd_Tree.h" //#include //#include "voxel_map_util.hpp" /* Description: ikd-Tree: an incremental k-d tree for robotic applications Author: Yixi Cai email: yixicai@connect.hku.hk */ extern float mid2min, planarity, angle_threshold; extern int num_surfel, surfel_points_min; const float flag_surfel = -9999; VoxelInfo::VoxelInfo(const PointType &p) { // pthread_mutex_init(&updating_mutex_lock, NULL); // pthread_mutex_lock(&updating_mutex_lock); flag_updating = true; s_xx = p.x * p.x; s_xy = p.x * p.y; s_xz = p.x * p.z; s_yy = p.y * p.y; s_yz = p.y * p.z; s_zz = p.z * p.z; num_points = 1; mean_x = p.x; mean_y = p.y; mean_z = p.z; normal = p.getNormalVector3fMap(); // cube_center(0) = voxel_center[0]; // cube_center(1) = voxel_center[1]; // cube_center(2) = voxel_center[2]; points.push_back(p); is_init = true; plane = new Plane; flag_updating = false; // pthread_mutex_unlock(&updating_mutex_lock); } void VoxelInfo::getSimpInfo(SimpInfo& out) { out.s_xx = s_xx; out.s_yy = s_yy; out.s_zz = s_zz; out.s_xy = s_xy; out.s_xz = s_xz; out.s_yz = s_yz; out.normal = normal; out.mean_xyz(0) = mean_x; out.mean_xyz(1) = mean_y; out.mean_xyz(2) = mean_z; } void VoxelInfo::init() { num_points = 0; s_xx = 0.0; s_xy = 0.0; s_xz = 0.0; s_yy = 0.0; s_yz = 0.0; s_zz = 0.0; mean_x = 0.0; mean_y = 0.0; mean_z = 0.0; normal = Eigen::Vector3f::Zero(); plane = new Plane; is_init = true; } void VoxelInfo::updateWithSingle(const PointType &p, const Eigen::Matrix3f & cov) { // pthread_mutex_lock(&updating_mutex_lock); // lock_guard lock(updating_mutex_lock); flag_updating = true; updateSumAndMean(p); points.push_back(p); updateNormal(p); //check convergence if (num_points >= surfel_points_min) { checkPCA(); // double t1 = omp_get_wtime(); updatePlaneUncertainty(p, cov); // t1 = omp_get_wtime() - t1; // printf("updatePlaneUncertainty cost: %fs\n", t1); } flag_updating = false; // pthread_mutex_unlock(&updating_mutex_lock); } void VoxelInfo::updateWithSingle(const PointType &p) { // pthread_mutex_lock(&updating_mutex_lock); // lock_guard lock(updating_mutex_lock); flag_updating = true; points.push_back(p); updateSumAndMean(p); updateNormal(p); if (num_points >= surfel_points_min) checkPCA(); flag_updating = false; // pthread_mutex_unlock(&updating_mutex_lock); } void VoxelInfo::updateSumAndMean(const PointType & p) { // num of points in the voxel ++(num_points); // summation of p * p^t s_xx += p.x * p.x; s_xy += p.x * p.y; s_xz += p.x * p.z; s_yy += p.y * p.y; s_yz += p.y * p.z; s_zz += p.z * p.z; // summation of p float n = (float)num_points; mean_x = mean_x * (n - 1.0) / n + p.x / n; mean_y = mean_y * (n - 1.0) / n + p.y / n; mean_z = mean_z * (n - 1.0) / n + p.z / n; } void VoxelInfo::updatePlaneUncertainty(const PointType &p, const Eigen::Matrix3f & p_cov) { plane->plane_cov = Eigen::Matrix::Zero(); plane->points_size = points.size(); // plane covariance calculation Eigen::Matrix3f J_Q; // dq/dp, q = mean_p J_Q << 1.0 / plane->points_size, 0, 0, 0, 1.0 / plane->points_size, 0, 0, 0, 1.0 / plane->points_size; //diag(1/n, 1/n, 1/n) // min eigen value small enough // if (evalsReal(evalsMin) < planer_threshold_) { if (num_points == flag_surfel) { vector index(points.size()); Eigen::Matrix3f U; // eigen vector U.block<3, 1>(0, 0) = plane->x_normal; U.block<3, 1>(0, 1) = plane->y_normal; U.block<3, 1>(0, 2) = plane->normal; // traverse all points for (int i = 0; i < points.size(); i++) { Eigen::Matrix J; // 6 * 3 Eigen::Matrix3f F; F.row(0) = (points[i].getVector3fMap() - plane->center).transpose() / // (p - mean_p)^T / ((plane->points_size) * (plane->min_eigen_value - plane->max_eigen_value)) * // n * (lambda_3 - lambda_m) * (plane->x_normal * plane->normal.transpose() + // (u_m * n^T + n^T * u_m^T) plane->normal * plane->x_normal.transpose()); F.row(1) = (points[i].getVector3fMap() - plane->center).transpose() / // (p - mean_p)^T / ((plane->points_size) * (plane->min_eigen_value - plane->mid_eigen_value)) * // n * (lambda_3 - lambda_m) * (plane->y_normal * plane->normal.transpose() + // (u_m * n^T + n^T * u_m^T) plane->normal * plane->y_normal.transpose()); F.row(2) << 0, 0, 0; J.block<3, 3>(0, 0) = U * F; // U * F, (dn/dp) J.block<3, 3>(3, 0) = J_Q; //J_Q, (dq/dp), q = mean_p plane->plane_cov += J * p_cov * J.transpose(); //cov (n, q), q = mean_p } plane->is_plane = true; if (plane->last_update_points_size == 0) { plane->last_update_points_size = plane->points_size; plane->is_update = true; } else if (plane->points_size - plane->last_update_points_size > 100) { // update interval: 100 points plane->last_update_points_size = plane->points_size; plane->is_update = true; } if (!plane->is_init) { plane->id = plane_id; plane_id++; plane->is_init = true; } } else { // min eigen value is not small enough, not yet a plane if (!plane->is_init) { plane->id = plane_id; plane_id++; plane->is_init = true; } if (plane->last_update_points_size == 0) { plane->last_update_points_size = plane->points_size; plane->is_update = true; } else if (plane->points_size - plane->last_update_points_size > 100) { // update interval: 100 points plane->last_update_points_size = plane->points_size; plane->is_update = true; } plane->is_plane = false; } } void VoxelInfo::updateNormal(const PointType &p) { // downsample normal normal = normal * (num_points - 1.0) / (float)num_points + p.getNormalVector3fMap() / (float)num_points; normal.normalize(); } bool VoxelInfo::checkPCA() { const float n = (float)num_points; Eigen::Matrix3f cov; cov(0, 0) = s_xx / n - mean_x * mean_x; cov(1, 1) = s_yy / n - mean_y * mean_y; cov(2, 2) = s_zz / n - mean_z * mean_z; cov(0, 1) = s_xy / n - mean_x * mean_y; cov(1, 0) = cov(0, 1); cov(0, 2) = s_xz / n - mean_x * mean_z; cov(2, 0) = cov(0, 2); cov(1, 2) = s_yz / n - mean_y * mean_z; cov(2, 1) = cov(1, 2); Eigen::Matrix3f eigenvectors_; Eigen::Vector3f eigenvalues_; // Compute eigen vectors and values Eigen::SelfAdjointEigenSolver evd (cov); // Organize eigenvectors and eigenvalues in ascendent order // lambda 1 > lambda 2 > lambda 3 for (int i = 0; i < 3; ++i) { eigenvalues_[i] = evd.eigenvalues () [2-i]; eigenvectors_.col (i) = evd.eigenvectors ().col (2-i); } float normal_dot = eigenvectors_.col (2).dot(normal); float angle = acos(normal_dot); // 0 ~ pi angle = angle / M_PI * 180.0; if (normal_dot < 0) { eigenvectors_.col(2) *= -1.0; angle = 180.0 - angle; } ///planarity float pho = 2.0 * (eigenvalues_[1] - eigenvalues_[2]) / (eigenvalues_[0] + eigenvalues_[1] + eigenvalues_[2]); float mid_min = eigenvalues_[1] / eigenvalues_[2]; if (mid_min > mid2min && pho > planarity) { if (num_points > 0) { num_points = flag_surfel; // mark surfel ++num_surfel; } if (angle < angle_threshold) { normal = (normal + eigenvectors_.col (2)) / 2.0; //todo normal.normalize(); } else normal = eigenvectors_.col (2); //record parameters for plane plane->covariance = cov; plane->center << mean_x, mean_y, mean_z; plane->normal << eigenvectors_.col (2); plane->y_normal << eigenvectors_.col (1); plane->x_normal << eigenvectors_.col (0); plane->min_eigen_value = eigenvalues_[2]; plane->mid_eigen_value = eigenvalues_[1]; plane->max_eigen_value = eigenvalues_[0]; plane->radius = plane->max_eigen_value; plane->d = -plane->normal.dot(plane->center); return true; } else return false; } template KD_TREE::KD_TREE(float delete_param, float balance_param, float box_length) { delete_criterion_param = delete_param; balance_criterion_param = balance_param; downsample_size = box_length; Rebuild_Logger.clear(); termination_flag = false; start_thread(); } template KD_TREE::~KD_TREE() { stop_thread(); Delete_Storage_Disabled = true; delete_tree_nodes(&Root_Node); PointVector ().swap(PCL_Storage); Rebuild_Logger.clear(); } template void KD_TREE::Set_delete_criterion_param(float delete_param){ delete_criterion_param = delete_param; } template void KD_TREE::Set_balance_criterion_param(float balance_param){ balance_criterion_param = balance_param; } template void KD_TREE::set_downsample_param(float downsample_param){ downsample_size = downsample_param; half_voxel_size = 0.5 * downsample_size; quater_voxel_size = 0.5 * half_voxel_size; printf("half_voxel_size: %0.6f, quater_voxel_size: %0.6f\n", half_voxel_size, quater_voxel_size); } template void KD_TREE::InitializeKDTree(float delete_param, float balance_param, float box_length){ Set_delete_criterion_param(delete_param); Set_balance_criterion_param(balance_param); set_downsample_param(box_length); } template void KD_TREE::InitTreeNode(KD_TREE_NODE * root){ root->point.x = 0.0f; root->point.y = 0.0f; root->point.z = 0.0f; root->point.normal_x = 0.0f; root->point.normal_y = 0.0f; root->point.normal_z = 0.0f; root->node_range_x[0] = 0.0f; root->node_range_x[1] = 0.0f; root->node_range_y[0] = 0.0f; root->node_range_y[1] = 0.0f; root->node_range_z[0] = 0.0f; root->node_range_z[1] = 0.0f; root->division_axis = 0; root->father_ptr = nullptr; root->left_son_ptr = nullptr; root->right_son_ptr = nullptr; root->TreeSize = 0; root->invalid_point_num = 0; root->down_del_num = 0; root->point_deleted = false; root->tree_deleted = false; root->need_push_down_to_left = false; root->need_push_down_to_right = false; root->point_downsample_deleted = false; root->working_flag = false; pthread_mutex_init(&(root->push_down_mutex_lock),NULL); } template int KD_TREE::size(){ int s = 0; if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ if (Root_Node != nullptr) { return Root_Node->TreeSize; } else { return 0; } } else { if (!pthread_mutex_trylock(&working_flag_mutex)){ s = Root_Node->TreeSize; pthread_mutex_unlock(&working_flag_mutex); return s; } else { return Treesize_tmp; } } } template BoxPointType KD_TREE::tree_range(){ BoxPointType range; if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ if (Root_Node != nullptr) { range.vertex_min[0] = Root_Node->node_range_x[0]; range.vertex_min[1] = Root_Node->node_range_y[0]; range.vertex_min[2] = Root_Node->node_range_z[0]; range.vertex_max[0] = Root_Node->node_range_x[1]; range.vertex_max[1] = Root_Node->node_range_y[1]; range.vertex_max[2] = Root_Node->node_range_z[1]; } else { memset(&range, 0, sizeof(range)); } } else { if (!pthread_mutex_trylock(&working_flag_mutex)){ range.vertex_min[0] = Root_Node->node_range_x[0]; range.vertex_min[1] = Root_Node->node_range_y[0]; range.vertex_min[2] = Root_Node->node_range_z[0]; range.vertex_max[0] = Root_Node->node_range_x[1]; range.vertex_max[1] = Root_Node->node_range_y[1]; range.vertex_max[2] = Root_Node->node_range_z[1]; pthread_mutex_unlock(&working_flag_mutex); } else { memset(&range, 0, sizeof(range)); } } return range; } template int KD_TREE::validnum(){ int s = 0; if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ if (Root_Node != nullptr) return (Root_Node->TreeSize - Root_Node->invalid_point_num); else return 0; } else { if (!pthread_mutex_trylock(&working_flag_mutex)){ s = Root_Node->TreeSize-Root_Node->invalid_point_num; pthread_mutex_unlock(&working_flag_mutex); return s; } else { return -1; } } } template void KD_TREE::root_alpha(float &alpha_bal, float &alpha_del){ if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ alpha_bal = Root_Node->alpha_bal; alpha_del = Root_Node->alpha_del; return; } else { if (!pthread_mutex_trylock(&working_flag_mutex)){ alpha_bal = Root_Node->alpha_bal; alpha_del = Root_Node->alpha_del; pthread_mutex_unlock(&working_flag_mutex); return; } else { alpha_bal = alpha_bal_tmp; alpha_del = alpha_del_tmp; return; } } } template void KD_TREE::start_thread(){ pthread_mutex_init(&termination_flag_mutex_lock, NULL); pthread_mutex_init(&rebuild_ptr_mutex_lock, NULL); pthread_mutex_init(&rebuild_logger_mutex_lock, NULL); pthread_mutex_init(&points_deleted_rebuild_mutex_lock, NULL); pthread_mutex_init(&working_flag_mutex, NULL); pthread_mutex_init(&search_flag_mutex, NULL); pthread_create(&rebuild_thread, NULL, multi_thread_ptr, (void*) this); printf("Multi thread started \n"); } template void KD_TREE::stop_thread(){ pthread_mutex_lock(&termination_flag_mutex_lock); termination_flag = true; pthread_mutex_unlock(&termination_flag_mutex_lock); if (rebuild_thread) pthread_join(rebuild_thread, NULL); pthread_mutex_destroy(&termination_flag_mutex_lock); pthread_mutex_destroy(&rebuild_logger_mutex_lock); pthread_mutex_destroy(&rebuild_ptr_mutex_lock); pthread_mutex_destroy(&points_deleted_rebuild_mutex_lock); pthread_mutex_destroy(&working_flag_mutex); pthread_mutex_destroy(&search_flag_mutex); } template void * KD_TREE::multi_thread_ptr(void * arg){ KD_TREE * handle = (KD_TREE*) arg; handle->multi_thread_rebuild(); return nullptr; } template void KD_TREE::multi_thread_rebuild(){ bool terminated = false; KD_TREE_NODE * father_ptr, ** new_node_ptr; pthread_mutex_lock(&termination_flag_mutex_lock); terminated = termination_flag; pthread_mutex_unlock(&termination_flag_mutex_lock); while (!terminated){ pthread_mutex_lock(&rebuild_ptr_mutex_lock); pthread_mutex_lock(&working_flag_mutex); if (Rebuild_Ptr != nullptr ){ /* Traverse and copy */ if (!Rebuild_Logger.empty()){ printf("\n\n\n\n\n\n\n\n\n\n\n ERROR!!! \n\n\n\n\n\n\n\n\n"); } rebuild_flag = true; if (*Rebuild_Ptr == Root_Node) { Treesize_tmp = Root_Node->TreeSize; Validnum_tmp = Root_Node->TreeSize - Root_Node->invalid_point_num; alpha_bal_tmp = Root_Node->alpha_bal; alpha_del_tmp = Root_Node->alpha_del; } KD_TREE_NODE * old_root_node = (*Rebuild_Ptr); father_ptr = (*Rebuild_Ptr)->father_ptr; PointVector ().swap(Rebuild_PCL_Storage); // Lock Search pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter != 0){ pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter = -1; //标记-1,执行flatten pthread_mutex_unlock(&search_flag_mutex); // Lock deleted points cache pthread_mutex_lock(&points_deleted_rebuild_mutex_lock); flatten(*Rebuild_Ptr, Rebuild_PCL_Storage, MULTI_THREAD_REC); /// // Unlock deleted points cache pthread_mutex_unlock(&points_deleted_rebuild_mutex_lock); // Unlock Search pthread_mutex_lock(&search_flag_mutex); //search_flag_mutex上锁 search_mutex_counter = 0;//标记为0 pthread_mutex_unlock(&search_flag_mutex); pthread_mutex_unlock(&working_flag_mutex); /* Rebuild and update missed operations*/ Operation_Logger_Type Operation; KD_TREE_NODE * new_root_node = nullptr; if (int(Rebuild_PCL_Storage.size()) > 0){ BuildTree(&new_root_node, 0, Rebuild_PCL_Storage.size()-1, Rebuild_PCL_Storage); // Rebuild has been done. Updates the blocked operations into the new tree pthread_mutex_lock(&working_flag_mutex); pthread_mutex_lock(&rebuild_logger_mutex_lock); int tmp_counter = 0; while (!Rebuild_Logger.empty()){ Operation = Rebuild_Logger.front(); max_queue_size = max(max_queue_size, Rebuild_Logger.size()); Rebuild_Logger.pop(); pthread_mutex_unlock(&rebuild_logger_mutex_lock); pthread_mutex_unlock(&working_flag_mutex); run_operation(&new_root_node, Operation); tmp_counter ++; if (tmp_counter % 10 == 0) usleep(1); pthread_mutex_lock(&working_flag_mutex); pthread_mutex_lock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&rebuild_logger_mutex_lock); } /* Replace to original tree*/ // pthread_mutex_lock(&working_flag_mutex); pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter != 0){ pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter = -1; //标记-1,执行替换 pthread_mutex_unlock(&search_flag_mutex); if (father_ptr->left_son_ptr == *Rebuild_Ptr) { //替换tree father_ptr->left_son_ptr = new_root_node; } else if (father_ptr->right_son_ptr == *Rebuild_Ptr){ father_ptr->right_son_ptr = new_root_node; } else { throw "Error: Father ptr incompatible with current node\n"; } if (new_root_node != nullptr) new_root_node->father_ptr = father_ptr; (*Rebuild_Ptr) = new_root_node; int valid_old = old_root_node->TreeSize-old_root_node->invalid_point_num; int valid_new = new_root_node->TreeSize-new_root_node->invalid_point_num; if (father_ptr == STATIC_ROOT_NODE) Root_Node = STATIC_ROOT_NODE->left_son_ptr; KD_TREE_NODE * update_root = *Rebuild_Ptr; while (update_root != nullptr && update_root != Root_Node){ update_root = update_root->father_ptr; if (update_root->working_flag) break; if (update_root == update_root->father_ptr->left_son_ptr && update_root->father_ptr->need_push_down_to_left) break; if (update_root == update_root->father_ptr->right_son_ptr && update_root->father_ptr->need_push_down_to_right) break; Update(update_root); } pthread_mutex_lock(&search_flag_mutex); search_mutex_counter = 0; pthread_mutex_unlock(&search_flag_mutex); Rebuild_Ptr = nullptr; pthread_mutex_unlock(&working_flag_mutex); rebuild_flag = false; /* Delete discarded tree nodes */ delete_tree_nodes(&old_root_node); // todo delete pointer to corresponding voxel, !!caution: before now node setting } else { pthread_mutex_unlock(&working_flag_mutex); } pthread_mutex_unlock(&rebuild_ptr_mutex_lock); pthread_mutex_lock(&termination_flag_mutex_lock); terminated = termination_flag; pthread_mutex_unlock(&termination_flag_mutex_lock); usleep(100); } printf("Rebuild thread terminated normally\n"); } template void KD_TREE::run_operation(KD_TREE_NODE ** root, Operation_Logger_Type operation){ switch (operation.op) { case ADD_POINT: Add_by_point(root, operation.point, false, (*root)->division_axis); break; case ADD_BOX: Add_by_range(root, operation.boxpoint, false); break; case DELETE_POINT: Delete_by_point(root, operation.point, false); break; case DELETE_BOX: Delete_by_range(root, operation.boxpoint, false, false); break; case DOWNSAMPLE_DELETE: Delete_by_range(root, operation.boxpoint, false, true); break; case PUSH_DOWN: (*root)->tree_downsample_deleted |= operation.tree_downsample_deleted; (*root)->point_downsample_deleted |= operation.tree_downsample_deleted; (*root)->tree_deleted = operation.tree_deleted || (*root)->tree_downsample_deleted; (*root)->point_deleted = (*root)->tree_deleted || (*root)->point_downsample_deleted; if (operation.tree_downsample_deleted) (*root)->down_del_num = (*root)->TreeSize; if (operation.tree_deleted) (*root)->invalid_point_num = (*root)->TreeSize; else (*root)->invalid_point_num = (*root)->down_del_num; (*root)->need_push_down_to_left = true; (*root)->need_push_down_to_right = true; break; default: break; } } template void KD_TREE::insideVoxelDownsample(PointVector& point_cloud) { // voxel2node.clear(); // node2voxel.clear(); unordered_map voxel2point; for (PointType& p : point_cloud) { // const PointType& p = root->point; float loc_xyz[3]; point2Voxel(p, loc_xyz); VOXEL_LOC voxel = VOXEL_LOC((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]); // VOXEL_LOC voxel; // point2Voxel(p, voxel); // auto iter = voxel2node.find(voxel); if (voxel2point.find(voxel) == voxel2point.end()) { //already have the voexl voxel2point[voxel] = p; // node2voxel[root] = voxel; // voxel_map[voxel]->temp_points_.push_back(p_v); // voxel_map[voxel]->new_points_num_++; } else { const PointType& p_old = voxel2point[voxel]; PointType mid_point; mid_point.x = loc_xyz[0]; mid_point.y = loc_xyz[1]; mid_point.z = loc_xyz[2]; float dist_old = calc_dist(p_old, mid_point); float dist_new = calc_dist(p, mid_point); if (dist_new < dist_old) { voxel2point[voxel] = p; } } } int i = 0; for (const auto& n : voxel2point) point_cloud[i++] = n.second; point_cloud.resize(i); } template void KD_TREE::Build(PointVector point_cloud){ if (Root_Node != nullptr){ delete_tree_nodes(&Root_Node); } if (point_cloud.size() == 0) return; //todo voxel grid downsample first // insideVoxelDownsample(point_cloud); STATIC_ROOT_NODE = new KD_TREE_NODE; InitTreeNode(STATIC_ROOT_NODE); BuildTree(&STATIC_ROOT_NODE->left_son_ptr, 0, point_cloud.size()-1, point_cloud); Update(STATIC_ROOT_NODE); STATIC_ROOT_NODE->TreeSize = 0; Root_Node = STATIC_ROOT_NODE->left_son_ptr; // todo build connection between voxels and nodes buildConnection(Root_Node); } template void KD_TREE::Nearest_Search(PointType point, int k_nearest, PointVector& Nearest_Points, vector & Point_Distance, double max_dist){ MANUAL_HEAP q(2*k_nearest); q.clear(); vector ().swap(Point_Distance); if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ Search(Root_Node, k_nearest, point, q, max_dist); } else { pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter += 1; pthread_mutex_unlock(&search_flag_mutex); Search(Root_Node, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } int k_found = min(k_nearest,int(q.size())); PointVector ().swap(Nearest_Points); vector ().swap(Point_Distance); for (int i=0;i < k_found;i++){ Nearest_Points.insert(Nearest_Points.begin(), q.top().point); Point_Distance.insert(Point_Distance.begin(), q.top().dist); q.pop(); } return; } int six_neighbor[6] = {1, -1, 1, -1, 1, -1}; // dx, dy, dz template void KD_TREE::addNearVoxelsLoc(const PointType& point, const float* voxel_center, std::vector& voxels) { // int dimension = 0; // vector six_neighbor({1, -1, 1, -1, 1, -1}); //2-4-8 neighbors for (int dimension = 0; dimension < 3; ++dimension) { int d_dimension = 0; const float & coor = point.getVector3fMap()[dimension]; if (coor > (voxel_center[dimension] + quater_voxel_size)) { d_dimension = 1; six_neighbor[dimension * 2] = 0; } else if (coor < (voxel_center[dimension] - quater_voxel_size)) { d_dimension = -1; six_neighbor[dimension * 2 + 1] = 0; } if (d_dimension == 0) continue; // 2-4-8 neighbors first int size_old = voxels.size(); voxels.resize(size_old * 2); for (int i = 0; i < size_old / 3; ++i) { voxels[i * 3 + size_old] = voxels[i * 3]; voxels[i * 3 + 1 + size_old] = voxels[i * 3 + 1]; voxels[i * 3 + 2 + size_old] = voxels[i * 3 + 2]; voxels[i * 3 + size_old + dimension] += d_dimension; } } // 6 nearest neighbors int size_old = voxels.size(); for (int i = 0; i < 6; ++i) { if (six_neighbor[i] == 0) continue; int dimension = i / 2; voxels.emplace_back(voxels[0]); voxels.emplace_back(voxels[1]); voxels.emplace_back(voxels[2]); voxels[size_old + dimension] += six_neighbor[i]; size_old += 3; } } template void KD_TREE::updateVoxelInfo(const PointType& point, const Eigen::Matrix3f & cov) { VOXEL_LOC voxel; // float cube_center[3]; point2Voxel(point, voxel); auto iter = voxel2info.find(voxel); VoxelInfoPtr voxel_ptr; if (iter == voxel2info.end() || !iter->second) //for voxel that not initialize yet { voxel_ptr = new VoxelInfo(point); voxel2info[voxel] = voxel_ptr; return; } else voxel_ptr = iter->second; if (voxel_ptr->num_points > 0 && voxel_ptr->num_points < max_voxel_points_size) { // printf("num_points %d, surfel_points_min %d, max_voxel_points_size: %d.\n", voxel_ptr->num_points, // surfel_points_min, max_voxel_points_size); voxel_ptr->updateWithSingle(point, cov); } } template void KD_TREE::updateVoxelInfo(const PointType& point) { VOXEL_LOC voxel; // float cube_center[3]; point2Voxel(point, voxel); auto iter = voxel2info.find(voxel); VoxelInfoPtr voxel_ptr; if (iter == voxel2info.end() || !iter->second) //for voxel that not initialize yet { voxel_ptr = new VoxelInfo(point); voxel2info[voxel] = voxel_ptr; return; } else voxel_ptr = iter->second; if (voxel_ptr->num_points > 0 && voxel_ptr->num_points < max_voxel_points_size) voxel_ptr->updateWithSingle(point); } template void KD_TREE::Voxel_Search_test(const PointType& point, int k_nearest, PointVector &Nearest_Points, vector & Point_Distance, vector& voxels) { PointVector().swap(Nearest_Points); vector().swap(voxels); vector ().swap(Point_Distance); //divide into voxel float loc_xyz[3], center_xyz[3]; point2Voxel(point, loc_xyz, center_xyz); // printf("\npoint: %f, %f, %f loc_xyz: %f, %f, %f center_xyz: %f, %f, %f.\n", point.x, point.y, point.z, // loc_xyz[0], loc_xyz[1], loc_xyz[2], // center_xyz[0], center_xyz[1], center_xyz[2]); VOXEL_LOC position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]); vector near_voxel_loc; near_voxel_loc.reserve(30); // record first voxel index; near_voxel_loc.emplace_back(loc_xyz[0]); near_voxel_loc.emplace_back(loc_xyz[1]); near_voxel_loc.emplace_back(loc_xyz[2]); addNearVoxelsLoc(point, center_xyz, near_voxel_loc); MANUAL_VOXEL_HEAP q(k_nearest); q.clear(); for (int i = 0; i < near_voxel_loc.size() / 3; ++i) { // printf("near_loc_xyz: %f, %f, %f\n", near_voxel_loc[i * 3], near_voxel_loc[i * 3 + 1], near_voxel_loc[i * 3 + 2]); VOXEL_LOC near_position((int64_t)near_voxel_loc[i * 3], (int64_t)near_voxel_loc[i * 3 + 1], near_voxel_loc[i * 3 + 2]); // const auto & near_iter = voxel2node.find(near_position); const auto & near_iter = voxel2info.find(near_position); if (near_iter != voxel2info.end()) { VoxelInfo* voxel_info = near_iter->second; // const PointType& p = near_iter->second->point; // float dist = calc_dist(p, point); if (voxel_info) { PointType p; // while (voxel_info->flag_updating) /// !!!caution // usleep(2); lock_guard lock(voxel_info->updating_mutex_lock); // pthread_mutex_lock(&voxel_info->updating_mutex_lock); p.x = voxel_info->mean_x; p.y = voxel_info->mean_y; p.z = voxel_info->mean_z; // pthread_mutex_unlock(&voxel_info->updating_mutex_lock); float dist = calc_dist(point, p); // if (dist <= max_dist_sqr && (q.size() < k_nearest || dist < q.top().dist)){ if (q.size() < k_nearest || dist < q.top().dist) { if (q.size() >= k_nearest) q.pop(); PointType_Voxel_CMP current_point{p, voxel_info, dist}; q.push(current_point); } } } } int k_found = min(k_nearest,int(q.size())); for (int i=0;i < k_found;i++){ Nearest_Points.insert(Nearest_Points.begin(), q.top().point); Point_Distance.insert(Point_Distance.begin(), q.top().dist); voxels.insert(voxels.begin(), q.top().info); // q.top().info->getSimpInfo(s_info); q.pop(); } } template void KD_TREE::Voxel_Search(const PointType& point, int k_nearest, PointVector &Nearest_Points, vector& nodes) { //divide into voxel float loc_xyz[3], center_xyz[3]; point2Voxel(point, loc_xyz, center_xyz); VOXEL_LOC position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]); const auto & iter = voxel2node.find(position); if (iter == voxel2node.end()) return; KD_TREE_NODE* node_center = iter->second; nodes.emplace_back(node_center); Nearest_Points.push_back(node_center->point); VOXEL_LOC near_position = position; } template void KD_TREE::Nearest_Search(PointType point, int k_nearest, PointVector &Nearest_Points, vector & Point_Distance, vector& voxels, double max_dist) { MANUAL_HEAP q(2*k_nearest); q.clear(); vector ().swap(Point_Distance); if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ // 没有rebuild,直接search Search(Root_Node, k_nearest, point, q, max_dist); } else { // 如果有rebuild pthread_mutex_lock(&search_flag_mutex); //search_flag_mutex while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex);//search_flag_mutex usleep(1); pthread_mutex_lock(&search_flag_mutex);//search_flag_mutex } search_mutex_counter += 1; // +1? pthread_mutex_unlock(&search_flag_mutex); Search(Root_Node, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } int k_found = min(k_nearest,int(q.size())); PointVector ().swap(Nearest_Points); vector ().swap(Point_Distance); vector ().swap(voxels); for (int i=0;i < k_found;i++){ Nearest_Points.insert(Nearest_Points.begin(), q.top().point); Point_Distance.insert(Point_Distance.begin(), q.top().dist); VOXEL_LOC voxel; point2Voxel(q.top().point, voxel); auto iter = voxel2info.find(voxel); VoxelInfoPtr voxel_ptr; if (iter == voxel2info.end() || !iter->second) //for voxel that not initialize yet { voxel_ptr = new VoxelInfo(point); voxel2info[voxel] = voxel_ptr; return; } else voxel_ptr = iter->second; voxels.insert(voxels.begin(), voxel_ptr); q.pop(); } return; } template void KD_TREE::Box_Search(const BoxPointType &Box_of_Point, PointVector &Storage) { Storage.clear(); Search_by_range(Root_Node, Box_of_Point, Storage); } template void KD_TREE::Radius_Search(PointType point, const float radius, PointVector &Storage) { Storage.clear(); Search_by_radius(Root_Node, point, radius, Storage); } template int KD_TREE::Add_Points(PointVector & PointToAdd, bool downsample_on){ int NewPointSize = PointToAdd.size(); int tree_size = size(); BoxPointType Box_of_Point; PointType downsample_result, mid_point; bool downsample_switch = downsample_on && DOWNSAMPLE_SWITCH; float min_dist, tmp_dist; int tmp_counter = 0; for (int i=0; i 1 || same_point(PointToAdd[i], downsample_result)){ if (Downsample_Storage.size() > 0) Delete_by_range(&Root_Node, Box_of_Point, true, true); Add_by_point(&Root_Node, downsample_result, true, Root_Node->division_axis); tmp_counter ++; } } else { if (Downsample_Storage.size() > 1 || same_point(PointToAdd[i], downsample_result)){ Operation_Logger_Type operation_delete, operation; operation_delete.boxpoint = Box_of_Point; operation_delete.op = DOWNSAMPLE_DELETE; operation.point = downsample_result; operation.op = ADD_POINT; pthread_mutex_lock(&working_flag_mutex); if (Downsample_Storage.size() > 0) Delete_by_range(&Root_Node, Box_of_Point, false , true); Add_by_point(&Root_Node, downsample_result, false, Root_Node->division_axis); tmp_counter ++; if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); if (Downsample_Storage.size() > 0) Rebuild_Logger.push(operation_delete); Rebuild_Logger.push(operation); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); }; } } else { if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ Add_by_point(&Root_Node, PointToAdd[i], true, Root_Node->division_axis); } else { Operation_Logger_Type operation; operation.point = PointToAdd[i]; operation.op = ADD_POINT; pthread_mutex_lock(&working_flag_mutex); Add_by_point(&Root_Node, PointToAdd[i], false, Root_Node->division_axis); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(operation); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } } } return tmp_counter; } template void KD_TREE::Add_Point_Boxes(vector & BoxPoints){ for (int i=0;i < BoxPoints.size();i++){ if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ Add_by_range(&Root_Node ,BoxPoints[i], true); } else { Operation_Logger_Type operation; operation.boxpoint = BoxPoints[i]; operation.op = ADD_BOX; pthread_mutex_lock(&working_flag_mutex); Add_by_range(&Root_Node ,BoxPoints[i], false); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(operation); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } } return; } template void KD_TREE::Delete_Points(PointVector & PointToDel){ for (int i=0;i int KD_TREE::Delete_Point_Boxes(vector & BoxPoints){ int tmp_counter = 0; for (int i=0;i < BoxPoints.size();i++){ if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node){ tmp_counter += Delete_by_range(&Root_Node ,BoxPoints[i], true, false); } else { Operation_Logger_Type operation; operation.boxpoint = BoxPoints[i]; operation.op = DELETE_BOX; pthread_mutex_lock(&working_flag_mutex); tmp_counter += Delete_by_range(&Root_Node ,BoxPoints[i], false, false); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(operation); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } } return tmp_counter; } template void KD_TREE::acquire_removed_points(PointVector & removed_points){ pthread_mutex_lock(&points_deleted_rebuild_mutex_lock); for (int i = 0; i < Points_deleted.size();i++){ removed_points.push_back(Points_deleted[i]); } for (int i = 0; i < Multithread_Points_deleted.size();i++){ removed_points.push_back(Multithread_Points_deleted[i]); } Points_deleted.clear(); Multithread_Points_deleted.clear(); pthread_mutex_unlock(&points_deleted_rebuild_mutex_lock); return; } template void KD_TREE::findVoxel(const PointType& p) { // //divide into voxel // float loc_xyz[3]; // loc_xyz[0] = p.x / downsample_size; // loc_xyz[1] = p.y / downsample_size; // loc_xyz[2] = p.z / downsample_size; // for (int j = 0; j < 3; j++) // if (loc_xyz[j] < 0) // loc_xyz[j] -= 1.0; // // VOXEL_LOC position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]); // auto iter = voxel_map.find(position); // // pointWithCov p_v; // p_v.point_world << p.x, p.y, p.z; // p.getPointCovMatrix(p_v.cov); // if (iter != voxel_map.end()) { // //already have the voexl // voxel_map[position]->temp_points_.push_back(p_v); // voxel_map[position]->new_points_num_++; // } else { // OctoTree *octo_tree = // new OctoTree(max_layer, 0, layer_point_size, max_points_size, // max_cov_points_size, planer_threshold); // voxel_map[position] = octo_tree; // voxel_map[position]->quater_length_ = voxel_size / 4; // voxel_map[position]->voxel_center_[0] = (0.5 + position.x) * voxel_size; // voxel_map[position]->voxel_center_[1] = (0.5 + position.y) * voxel_size; // voxel_map[position]->voxel_center_[2] = (0.5 + position.z) * voxel_size; // voxel_map[position]->temp_points_.push_back(p_v); // voxel_map[position]->new_points_num_++; // voxel_map[position]->layer_point_size_ = layer_point_size; // } } template void KD_TREE::BuildTree(KD_TREE_NODE ** root, int l, int r, PointVector & Storage){ if (l>r) return; *root = new KD_TREE_NODE; InitTreeNode(*root); int mid = (l+r)>>1; int div_axis = 0; int i; // Find the best division Axis float min_value[3] = {INFINITY, INFINITY, INFINITY}; float max_value[3] = {-INFINITY, -INFINITY, -INFINITY}; float dim_range[3] = {0,0,0}; for (i=l;i<=r;i++){ min_value[0] = min(min_value[0], Storage[i].x); min_value[1] = min(min_value[1], Storage[i].y); min_value[2] = min(min_value[2], Storage[i].z); max_value[0] = max(max_value[0], Storage[i].x); max_value[1] = max(max_value[1], Storage[i].y); max_value[2] = max(max_value[2], Storage[i].z); } // Select the longest dimension as division axis for (i=0;i<3;i++) dim_range[i] = max_value[i] - min_value[i]; for (i=1;i<3;i++) if (dim_range[i] > dim_range[div_axis]) div_axis = i; // Divide by the division axis and recursively build. (*root)->division_axis = div_axis; switch (div_axis) { case 0: nth_element(begin(Storage)+l, begin(Storage)+mid, begin(Storage)+r+1, point_cmp_x); break; case 1: nth_element(begin(Storage)+l, begin(Storage)+mid, begin(Storage)+r+1, point_cmp_y); break; case 2: nth_element(begin(Storage)+l, begin(Storage)+mid, begin(Storage)+r+1, point_cmp_z); break; default: nth_element(begin(Storage)+l, begin(Storage)+mid, begin(Storage)+r+1, point_cmp_x); break; } (*root)->point = Storage[mid]; // connect to voxel single_connect(*root); KD_TREE_NODE * left_son = nullptr, * right_son = nullptr; BuildTree(&left_son, l, mid-1, Storage); BuildTree(&right_son, mid+1, r, Storage); (*root)->left_son_ptr = left_son; (*root)->right_son_ptr = right_son; Update((*root)); return; } template void KD_TREE::Rebuild(KD_TREE_NODE ** root){ KD_TREE_NODE * father_ptr; if ((*root)->TreeSize >= Multi_Thread_Rebuild_Point_Num) { if (!pthread_mutex_trylock(&rebuild_ptr_mutex_lock)){ if (Rebuild_Ptr == nullptr || ((*root)->TreeSize > (*Rebuild_Ptr)->TreeSize)) { Rebuild_Ptr = root; } pthread_mutex_unlock(&rebuild_ptr_mutex_lock); } } else { father_ptr = (*root)->father_ptr; int size_rec = (*root)->TreeSize; PCL_Storage.clear(); flatten(*root, PCL_Storage, DELETE_POINTS_REC); delete_tree_nodes(root); // todo delete pointer to corresponding voxel BuildTree(root, 0, PCL_Storage.size()-1, PCL_Storage); if (*root != nullptr) (*root)->father_ptr = father_ptr; if (*root == Root_Node) STATIC_ROOT_NODE->left_son_ptr = *root; } return; } template int KD_TREE::Delete_by_range(KD_TREE_NODE ** root, BoxPointType boxpoint, bool allow_rebuild, bool is_downsample){ if ((*root) == nullptr || (*root)->tree_deleted) return 0; (*root)->working_flag = true; Push_Down(*root); int tmp_counter = 0; if (boxpoint.vertex_max[0] <= (*root)->node_range_x[0] || boxpoint.vertex_min[0] > (*root)->node_range_x[1]) return 0; if (boxpoint.vertex_max[1] <= (*root)->node_range_y[0] || boxpoint.vertex_min[1] > (*root)->node_range_y[1]) return 0; if (boxpoint.vertex_max[2] <= (*root)->node_range_z[0] || boxpoint.vertex_min[2] > (*root)->node_range_z[1]) return 0; if (boxpoint.vertex_min[0] <= (*root)->node_range_x[0] && boxpoint.vertex_max[0] > (*root)->node_range_x[1] && boxpoint.vertex_min[1] <= (*root)->node_range_y[0] && boxpoint.vertex_max[1] > (*root)->node_range_y[1] && boxpoint.vertex_min[2] <= (*root)->node_range_z[0] && boxpoint.vertex_max[2] > (*root)->node_range_z[1]){ (*root)->tree_deleted = true; (*root)->point_deleted = true; (*root)->need_push_down_to_left = true; (*root)->need_push_down_to_right = true; tmp_counter = (*root)->TreeSize - (*root)->invalid_point_num; (*root)->invalid_point_num = (*root)->TreeSize; if (is_downsample){ (*root)->tree_downsample_deleted = true; (*root)->point_downsample_deleted = true; (*root)->down_del_num = (*root)->TreeSize; } return tmp_counter; } if (!(*root)->point_deleted && boxpoint.vertex_min[0] <= (*root)->point.x && boxpoint.vertex_max[0] > (*root)->point.x && boxpoint.vertex_min[1] <= (*root)->point.y && boxpoint.vertex_max[1] > (*root)->point.y && boxpoint.vertex_min[2] <= (*root)->point.z && boxpoint.vertex_max[2] > (*root)->point.z){ (*root)->point_deleted = true; tmp_counter += 1; if (is_downsample) (*root)->point_downsample_deleted = true; } Operation_Logger_Type delete_box_log; struct timespec Timeout; if (is_downsample) delete_box_log.op = DOWNSAMPLE_DELETE; else delete_box_log.op = DELETE_BOX; delete_box_log.boxpoint = boxpoint; if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr){ tmp_counter += Delete_by_range(&((*root)->left_son_ptr), boxpoint, allow_rebuild, is_downsample); } else { pthread_mutex_lock(&working_flag_mutex); tmp_counter += Delete_by_range(&((*root)->left_son_ptr), boxpoint, false, is_downsample); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(delete_box_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr){ tmp_counter += Delete_by_range(&((*root)->right_son_ptr), boxpoint, allow_rebuild, is_downsample); } else { pthread_mutex_lock(&working_flag_mutex); tmp_counter += Delete_by_range(&((*root)->right_son_ptr), boxpoint, false, is_downsample); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(delete_box_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } Update(*root); if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) Rebuild_Ptr = nullptr; bool need_rebuild = allow_rebuild & Criterion_Check((*root)); if (need_rebuild) Rebuild(root); if ((*root) != nullptr) (*root)->working_flag = false; return tmp_counter; } template void KD_TREE::Delete_by_point(KD_TREE_NODE ** root, PointType point, bool allow_rebuild){ if ((*root) == nullptr || (*root)->tree_deleted) return; (*root)->working_flag = true; Push_Down(*root); if (same_point((*root)->point, point) && !(*root)->point_deleted) { (*root)->point_deleted = true; (*root)->invalid_point_num += 1; if ((*root)->invalid_point_num == (*root)->TreeSize) (*root)->tree_deleted = true; return; } Operation_Logger_Type delete_log; struct timespec Timeout; delete_log.op = DELETE_POINT; delete_log.point = point; if (((*root)->division_axis == 0 && point.x < (*root)->point.x) || ((*root)->division_axis == 1 && point.y < (*root)->point.y) || ((*root)->division_axis == 2 && point.z < (*root)->point.z)){ if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr){ Delete_by_point(&(*root)->left_son_ptr, point, allow_rebuild); } else { pthread_mutex_lock(&working_flag_mutex); Delete_by_point(&(*root)->left_son_ptr, point,false); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(delete_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } } else { if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr){ Delete_by_point(&(*root)->right_son_ptr, point, allow_rebuild); } else { pthread_mutex_lock(&working_flag_mutex); Delete_by_point(&(*root)->right_son_ptr, point, false); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(delete_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } } Update(*root); if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) Rebuild_Ptr = nullptr; bool need_rebuild = allow_rebuild & Criterion_Check((*root)); if (need_rebuild) Rebuild(root); if ((*root) != nullptr) (*root)->working_flag = false; return; } template void KD_TREE::Add_by_range(KD_TREE_NODE ** root, BoxPointType boxpoint, bool allow_rebuild){ if ((*root) == nullptr) return; (*root)->working_flag = true; Push_Down(*root); if (boxpoint.vertex_max[0] <= (*root)->node_range_x[0] || boxpoint.vertex_min[0] > (*root)->node_range_x[1]) return; if (boxpoint.vertex_max[1] <= (*root)->node_range_y[0] || boxpoint.vertex_min[1] > (*root)->node_range_y[1]) return; if (boxpoint.vertex_max[2] <= (*root)->node_range_z[0] || boxpoint.vertex_min[2] > (*root)->node_range_z[1]) return; if (boxpoint.vertex_min[0] <= (*root)->node_range_x[0] && boxpoint.vertex_max[0] > (*root)->node_range_x[1] && boxpoint.vertex_min[1] <= (*root)->node_range_y[0] && boxpoint.vertex_max[1]> (*root)->node_range_y[1] && boxpoint.vertex_min[2] <= (*root)->node_range_z[0] && boxpoint.vertex_max[2] > (*root)->node_range_z[1]){ (*root)->tree_deleted = false || (*root)->tree_downsample_deleted; (*root)->point_deleted = false || (*root)->point_downsample_deleted; (*root)->need_push_down_to_left = true; (*root)->need_push_down_to_right = true; (*root)->invalid_point_num = (*root)->down_del_num; // todo set pointer to corresponding voxel return; } if (boxpoint.vertex_min[0] <= (*root)->point.x && boxpoint.vertex_max[0] > (*root)->point.x && boxpoint.vertex_min[1] <= (*root)->point.y && boxpoint.vertex_max[1] > (*root)->point.y && boxpoint.vertex_min[2] <= (*root)->point.z && boxpoint.vertex_max[2] > (*root)->point.z){ (*root)->point_deleted = (*root)->point_downsample_deleted; } Operation_Logger_Type add_box_log; struct timespec Timeout; add_box_log.op = ADD_BOX; add_box_log.boxpoint = boxpoint; if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr){ Add_by_range(&((*root)->left_son_ptr), boxpoint, allow_rebuild); } else { pthread_mutex_lock(&working_flag_mutex); Add_by_range(&((*root)->left_son_ptr), boxpoint, false); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(add_box_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr){ Add_by_range(&((*root)->right_son_ptr), boxpoint, allow_rebuild); } else { pthread_mutex_lock(&working_flag_mutex); Add_by_range(&((*root)->right_son_ptr), boxpoint, false); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(add_box_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } Update(*root); if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) Rebuild_Ptr = nullptr; bool need_rebuild = allow_rebuild & Criterion_Check((*root)); if (need_rebuild) Rebuild(root); if ((*root) != nullptr) (*root)->working_flag = false; return; } template void KD_TREE::Add_by_point(KD_TREE_NODE ** root, PointType point, bool allow_rebuild, int father_axis){ if (*root == nullptr){ *root = new KD_TREE_NODE; InitTreeNode(*root); (*root)->point = point; single_connect(*root); (*root)->division_axis = (father_axis + 1) % 3; Update(*root); return; } (*root)->working_flag = true; Operation_Logger_Type add_log; struct timespec Timeout; add_log.op = ADD_POINT; add_log.point = point; Push_Down(*root); // left or right son if (((*root)->division_axis == 0 && point.x < (*root)->point.x) || ((*root)->division_axis == 1 && point.y < (*root)->point.y) || ((*root)->division_axis == 2 && point.z < (*root)->point.z)){ if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr){ Add_by_point(&(*root)->left_son_ptr, point, allow_rebuild, (*root)->division_axis); } else { pthread_mutex_lock(&working_flag_mutex); Add_by_point(&(*root)->left_son_ptr, point, false,(*root)->division_axis); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(add_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } } else { if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr){ Add_by_point(&(*root)->right_son_ptr, point, allow_rebuild,(*root)->division_axis); } else { pthread_mutex_lock(&working_flag_mutex); Add_by_point(&(*root)->right_son_ptr, point, false,(*root)->division_axis); if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(add_log); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } pthread_mutex_unlock(&working_flag_mutex); } } Update(*root); if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) Rebuild_Ptr = nullptr; bool need_rebuild = allow_rebuild & Criterion_Check((*root)); if (need_rebuild) Rebuild(root); if ((*root) != nullptr) (*root)->working_flag = false; return; } template void KD_TREE::Search(KD_TREE_NODE * root, int k_nearest, PointType point, MANUAL_HEAP &q, double max_dist){ if (root == nullptr || root->tree_deleted) return; double cur_dist = calc_box_dist(root, point); double max_dist_sqr = max_dist * max_dist; if (cur_dist > max_dist_sqr) return; int retval; if (root->need_push_down_to_left || root->need_push_down_to_right) { retval = pthread_mutex_trylock(&(root->push_down_mutex_lock)); if (retval == 0){ Push_Down(root); pthread_mutex_unlock(&(root->push_down_mutex_lock)); } else { pthread_mutex_lock(&(root->push_down_mutex_lock)); pthread_mutex_unlock(&(root->push_down_mutex_lock)); } } if (!root->point_deleted){ float dist = calc_dist(point, root->point); if (dist <= max_dist_sqr && (q.size() < k_nearest || dist < q.top().dist)){ if (q.size() >= k_nearest) q.pop(); PointType_CMP current_point{root->point, root, dist}; q.push(current_point); } } int cur_search_counter; float dist_left_node = calc_box_dist(root->left_son_ptr, point); float dist_right_node = calc_box_dist(root->right_son_ptr, point); if (q.size()< k_nearest || dist_left_node < q.top().dist && dist_right_node < q.top().dist){ if (dist_left_node <= dist_right_node) { if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr){ Search(root->left_son_ptr, k_nearest, point, q, max_dist); } else { pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter += 1; pthread_mutex_unlock(&search_flag_mutex); Search(root->left_son_ptr, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } if (q.size() < k_nearest || dist_right_node < q.top().dist) { if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr){ Search(root->right_son_ptr, k_nearest, point, q, max_dist); } else { pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter += 1; pthread_mutex_unlock(&search_flag_mutex); Search(root->right_son_ptr, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } } } else { if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr){ Search(root->right_son_ptr, k_nearest, point, q, max_dist); } else { pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter += 1; pthread_mutex_unlock(&search_flag_mutex); Search(root->right_son_ptr, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } if (q.size() < k_nearest || dist_left_node < q.top().dist) { if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr){ Search(root->left_son_ptr, k_nearest, point, q, max_dist); } else { pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter += 1; pthread_mutex_unlock(&search_flag_mutex); Search(root->left_son_ptr, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } } } } else { if (dist_left_node < q.top().dist) { if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr){ Search(root->left_son_ptr, k_nearest, point, q, max_dist); } else { pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter += 1; pthread_mutex_unlock(&search_flag_mutex); Search(root->left_son_ptr, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } } if (dist_right_node < q.top().dist) { if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr){ Search(root->right_son_ptr, k_nearest, point, q, max_dist); } else { pthread_mutex_lock(&search_flag_mutex); while (search_mutex_counter == -1) { pthread_mutex_unlock(&search_flag_mutex); usleep(1); pthread_mutex_lock(&search_flag_mutex); } search_mutex_counter += 1; pthread_mutex_unlock(&search_flag_mutex); Search(root->right_son_ptr, k_nearest, point, q, max_dist); pthread_mutex_lock(&search_flag_mutex); search_mutex_counter -= 1; pthread_mutex_unlock(&search_flag_mutex); } } } return; } template void KD_TREE::Search_by_range(KD_TREE_NODE *root, BoxPointType boxpoint, PointVector & Storage){ if (root == nullptr) return; Push_Down(root); if (boxpoint.vertex_max[0] <= root->node_range_x[0] || boxpoint.vertex_min[0] > root->node_range_x[1]) return; if (boxpoint.vertex_max[1] <= root->node_range_y[0] || boxpoint.vertex_min[1] > root->node_range_y[1]) return; if (boxpoint.vertex_max[2] <= root->node_range_z[0] || boxpoint.vertex_min[2] > root->node_range_z[1]) return; if (boxpoint.vertex_min[0] <= root->node_range_x[0] && boxpoint.vertex_max[0] > root->node_range_x[1] && boxpoint.vertex_min[1] <= root->node_range_y[0] && boxpoint.vertex_max[1] > root->node_range_y[1] && boxpoint.vertex_min[2] <= root->node_range_z[0] && boxpoint.vertex_max[2] > root->node_range_z[1]){ flatten(root, Storage, NOT_RECORD); return; } if (boxpoint.vertex_min[0] <= root->point.x && boxpoint.vertex_max[0] > root->point.x && boxpoint.vertex_min[1] <= root->point.y && boxpoint.vertex_max[1] > root->point.y && boxpoint.vertex_min[2] <= root->point.z && boxpoint.vertex_max[2] > root->point.z){ if (!root->point_deleted) Storage.push_back(root->point); } if ((Rebuild_Ptr == nullptr) || root->left_son_ptr != *Rebuild_Ptr){ Search_by_range(root->left_son_ptr, boxpoint, Storage); } else { pthread_mutex_lock(&search_flag_mutex); Search_by_range(root->left_son_ptr, boxpoint, Storage); pthread_mutex_unlock(&search_flag_mutex); } if ((Rebuild_Ptr == nullptr) || root->right_son_ptr != *Rebuild_Ptr){ Search_by_range(root->right_son_ptr, boxpoint, Storage); } else { pthread_mutex_lock(&search_flag_mutex); Search_by_range(root->right_son_ptr, boxpoint, Storage); pthread_mutex_unlock(&search_flag_mutex); } return; } template void KD_TREE::Search_by_radius(KD_TREE_NODE *root, PointType point, float radius, PointVector &Storage) { if (root == nullptr) return; Push_Down(root); PointType range_center; range_center.x = (root->node_range_x[0] + root->node_range_x[1]) * 0.5; range_center.y = (root->node_range_y[0] + root->node_range_y[1]) * 0.5; range_center.z = (root->node_range_z[0] + root->node_range_z[1]) * 0.5; float dist = sqrt(calc_dist(range_center, point)); if (dist > radius + sqrt(root->radius_sq)) return; if (dist <= radius - sqrt(root->radius_sq)) { flatten(root, Storage, NOT_RECORD); return; } if (!root->point_deleted && calc_dist(root->point, point) <= radius * radius){ Storage.push_back(root->point); } if ((Rebuild_Ptr == nullptr) || root->left_son_ptr != *Rebuild_Ptr) { Search_by_radius(root->left_son_ptr, point, radius, Storage); } else { pthread_mutex_lock(&search_flag_mutex); Search_by_radius(root->left_son_ptr, point, radius, Storage); pthread_mutex_unlock(&search_flag_mutex); } if ((Rebuild_Ptr == nullptr) || root->right_son_ptr != *Rebuild_Ptr) { Search_by_radius(root->right_son_ptr, point, radius, Storage); } else { pthread_mutex_lock(&search_flag_mutex); Search_by_radius(root->right_son_ptr, point, radius, Storage); pthread_mutex_unlock(&search_flag_mutex); } return; } template bool KD_TREE::Criterion_Check(KD_TREE_NODE * root){ if (root->TreeSize <= Minimal_Unbalanced_Tree_Size){ return false; } float balance_evaluation = 0.0f; float delete_evaluation = 0.0f; KD_TREE_NODE * son_ptr = root->left_son_ptr; if (son_ptr == nullptr) son_ptr = root->right_son_ptr; delete_evaluation = float(root->invalid_point_num)/ root->TreeSize; balance_evaluation = float(son_ptr->TreeSize) / (root->TreeSize-1); if (delete_evaluation > delete_criterion_param){ return true; } if (balance_evaluation > balance_criterion_param || balance_evaluation < 1-balance_criterion_param){ return true; } return false; } template void KD_TREE::Push_Down(KD_TREE_NODE *root){ if (root == nullptr) return; Operation_Logger_Type operation; operation.op = PUSH_DOWN; operation.tree_deleted = root->tree_deleted; operation.tree_downsample_deleted = root->tree_downsample_deleted; if (root->need_push_down_to_left && root->left_son_ptr != nullptr){ if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr){ root->left_son_ptr->tree_downsample_deleted |= root->tree_downsample_deleted; root->left_son_ptr->point_downsample_deleted |= root->tree_downsample_deleted; root->left_son_ptr->tree_deleted = root->tree_deleted || root->left_son_ptr->tree_downsample_deleted; root->left_son_ptr->point_deleted = root->left_son_ptr->tree_deleted || root->left_son_ptr->point_downsample_deleted; if (root->tree_downsample_deleted) root->left_son_ptr->down_del_num = root->left_son_ptr->TreeSize; if (root->tree_deleted) root->left_son_ptr->invalid_point_num = root->left_son_ptr->TreeSize; else root->left_son_ptr->invalid_point_num = root->left_son_ptr->down_del_num; root->left_son_ptr->need_push_down_to_left = true; root->left_son_ptr->need_push_down_to_right = true; root->need_push_down_to_left = false; } else { pthread_mutex_lock(&working_flag_mutex); root->left_son_ptr->tree_downsample_deleted |= root->tree_downsample_deleted; root->left_son_ptr->point_downsample_deleted |= root->tree_downsample_deleted; root->left_son_ptr->tree_deleted = root->tree_deleted || root->left_son_ptr->tree_downsample_deleted; root->left_son_ptr->point_deleted = root->left_son_ptr->tree_deleted || root->left_son_ptr->point_downsample_deleted; if (root->tree_downsample_deleted) root->left_son_ptr->down_del_num = root->left_son_ptr->TreeSize; if (root->tree_deleted) root->left_son_ptr->invalid_point_num = root->left_son_ptr->TreeSize; else root->left_son_ptr->invalid_point_num = root->left_son_ptr->down_del_num; root->left_son_ptr->need_push_down_to_left = true; root->left_son_ptr->need_push_down_to_right = true; if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(operation); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } root->need_push_down_to_left = false; pthread_mutex_unlock(&working_flag_mutex); } } if (root->need_push_down_to_right && root->right_son_ptr != nullptr){ if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr){ root->right_son_ptr->tree_downsample_deleted |= root->tree_downsample_deleted; root->right_son_ptr->point_downsample_deleted |= root->tree_downsample_deleted; root->right_son_ptr->tree_deleted = root->tree_deleted || root->right_son_ptr->tree_downsample_deleted; root->right_son_ptr->point_deleted = root->right_son_ptr->tree_deleted || root->right_son_ptr->point_downsample_deleted; if (root->tree_downsample_deleted) root->right_son_ptr->down_del_num = root->right_son_ptr->TreeSize; if (root->tree_deleted) root->right_son_ptr->invalid_point_num = root->right_son_ptr->TreeSize; else root->right_son_ptr->invalid_point_num = root->right_son_ptr->down_del_num; root->right_son_ptr->need_push_down_to_left = true; root->right_son_ptr->need_push_down_to_right = true; root->need_push_down_to_right = false; } else { pthread_mutex_lock(&working_flag_mutex); root->right_son_ptr->tree_downsample_deleted |= root->tree_downsample_deleted; root->right_son_ptr->point_downsample_deleted |= root->tree_downsample_deleted; root->right_son_ptr->tree_deleted = root->tree_deleted || root->right_son_ptr->tree_downsample_deleted; root->right_son_ptr->point_deleted = root->right_son_ptr->tree_deleted || root->right_son_ptr->point_downsample_deleted; if (root->tree_downsample_deleted) root->right_son_ptr->down_del_num = root->right_son_ptr->TreeSize; if (root->tree_deleted) root->right_son_ptr->invalid_point_num = root->right_son_ptr->TreeSize; else root->right_son_ptr->invalid_point_num = root->right_son_ptr->down_del_num; root->right_son_ptr->need_push_down_to_left = true; root->right_son_ptr->need_push_down_to_right = true; if (rebuild_flag){ pthread_mutex_lock(&rebuild_logger_mutex_lock); Rebuild_Logger.push(operation); pthread_mutex_unlock(&rebuild_logger_mutex_lock); } root->need_push_down_to_right = false; pthread_mutex_unlock(&working_flag_mutex); } } return; } template void KD_TREE::Update(KD_TREE_NODE * root){ KD_TREE_NODE * left_son_ptr = root->left_son_ptr; KD_TREE_NODE * right_son_ptr = root->right_son_ptr; float tmp_range_x[2] = {INFINITY, -INFINITY}; float tmp_range_y[2] = {INFINITY, -INFINITY}; float tmp_range_z[2] = {INFINITY, -INFINITY}; // Update Tree Size if (left_son_ptr != nullptr && right_son_ptr != nullptr){ root->TreeSize = left_son_ptr->TreeSize + right_son_ptr->TreeSize + 1; root->invalid_point_num = left_son_ptr->invalid_point_num + right_son_ptr->invalid_point_num + (root->point_deleted? 1:0); root->down_del_num = left_son_ptr->down_del_num + right_son_ptr->down_del_num + (root->point_downsample_deleted? 1:0); root->tree_downsample_deleted = left_son_ptr->tree_downsample_deleted & right_son_ptr->tree_downsample_deleted & root->point_downsample_deleted; root->tree_deleted = left_son_ptr->tree_deleted && right_son_ptr->tree_deleted && root->point_deleted; if (root->tree_deleted || (!left_son_ptr->tree_deleted && !right_son_ptr->tree_deleted && !root->point_deleted)){ tmp_range_x[0] = min(min(left_son_ptr->node_range_x[0],right_son_ptr->node_range_x[0]),root->point.x); tmp_range_x[1] = max(max(left_son_ptr->node_range_x[1],right_son_ptr->node_range_x[1]),root->point.x); tmp_range_y[0] = min(min(left_son_ptr->node_range_y[0],right_son_ptr->node_range_y[0]),root->point.y); tmp_range_y[1] = max(max(left_son_ptr->node_range_y[1],right_son_ptr->node_range_y[1]),root->point.y); tmp_range_z[0] = min(min(left_son_ptr->node_range_z[0],right_son_ptr->node_range_z[0]),root->point.z); tmp_range_z[1] = max(max(left_son_ptr->node_range_z[1],right_son_ptr->node_range_z[1]),root->point.z); } else { if (!left_son_ptr->tree_deleted){ tmp_range_x[0] = min(tmp_range_x[0], left_son_ptr->node_range_x[0]); tmp_range_x[1] = max(tmp_range_x[1], left_son_ptr->node_range_x[1]); tmp_range_y[0] = min(tmp_range_y[0], left_son_ptr->node_range_y[0]); tmp_range_y[1] = max(tmp_range_y[1], left_son_ptr->node_range_y[1]); tmp_range_z[0] = min(tmp_range_z[0], left_son_ptr->node_range_z[0]); tmp_range_z[1] = max(tmp_range_z[1], left_son_ptr->node_range_z[1]); } if (!right_son_ptr->tree_deleted){ tmp_range_x[0] = min(tmp_range_x[0], right_son_ptr->node_range_x[0]); tmp_range_x[1] = max(tmp_range_x[1], right_son_ptr->node_range_x[1]); tmp_range_y[0] = min(tmp_range_y[0], right_son_ptr->node_range_y[0]); tmp_range_y[1] = max(tmp_range_y[1], right_son_ptr->node_range_y[1]); tmp_range_z[0] = min(tmp_range_z[0], right_son_ptr->node_range_z[0]); tmp_range_z[1] = max(tmp_range_z[1], right_son_ptr->node_range_z[1]); } if (!root->point_deleted){ tmp_range_x[0] = min(tmp_range_x[0], root->point.x); tmp_range_x[1] = max(tmp_range_x[1], root->point.x); tmp_range_y[0] = min(tmp_range_y[0], root->point.y); tmp_range_y[1] = max(tmp_range_y[1], root->point.y); tmp_range_z[0] = min(tmp_range_z[0], root->point.z); tmp_range_z[1] = max(tmp_range_z[1], root->point.z); } } } else if (left_son_ptr != nullptr){ root->TreeSize = left_son_ptr->TreeSize + 1; root->invalid_point_num = left_son_ptr->invalid_point_num + (root->point_deleted?1:0); root->down_del_num = left_son_ptr->down_del_num + (root->point_downsample_deleted?1:0); root->tree_downsample_deleted = left_son_ptr->tree_downsample_deleted & root->point_downsample_deleted; root->tree_deleted = left_son_ptr->tree_deleted && root->point_deleted; if (root->tree_deleted || (!left_son_ptr->tree_deleted && !root->point_deleted)){ tmp_range_x[0] = min(left_son_ptr->node_range_x[0],root->point.x); tmp_range_x[1] = max(left_son_ptr->node_range_x[1],root->point.x); tmp_range_y[0] = min(left_son_ptr->node_range_y[0],root->point.y); tmp_range_y[1] = max(left_son_ptr->node_range_y[1],root->point.y); tmp_range_z[0] = min(left_son_ptr->node_range_z[0],root->point.z); tmp_range_z[1] = max(left_son_ptr->node_range_z[1],root->point.z); } else { if (!left_son_ptr->tree_deleted){ tmp_range_x[0] = min(tmp_range_x[0], left_son_ptr->node_range_x[0]); tmp_range_x[1] = max(tmp_range_x[1], left_son_ptr->node_range_x[1]); tmp_range_y[0] = min(tmp_range_y[0], left_son_ptr->node_range_y[0]); tmp_range_y[1] = max(tmp_range_y[1], left_son_ptr->node_range_y[1]); tmp_range_z[0] = min(tmp_range_z[0], left_son_ptr->node_range_z[0]); tmp_range_z[1] = max(tmp_range_z[1], left_son_ptr->node_range_z[1]); } if (!root->point_deleted){ tmp_range_x[0] = min(tmp_range_x[0], root->point.x); tmp_range_x[1] = max(tmp_range_x[1], root->point.x); tmp_range_y[0] = min(tmp_range_y[0], root->point.y); tmp_range_y[1] = max(tmp_range_y[1], root->point.y); tmp_range_z[0] = min(tmp_range_z[0], root->point.z); tmp_range_z[1] = max(tmp_range_z[1], root->point.z); } } } else if (right_son_ptr != nullptr){ root->TreeSize = right_son_ptr->TreeSize + 1; root->invalid_point_num = right_son_ptr->invalid_point_num + (root->point_deleted? 1:0); root->down_del_num = right_son_ptr->down_del_num + (root->point_downsample_deleted? 1:0); root->tree_downsample_deleted = right_son_ptr->tree_downsample_deleted & root->point_downsample_deleted; root->tree_deleted = right_son_ptr->tree_deleted && root->point_deleted; if (root->tree_deleted || (!right_son_ptr->tree_deleted && !root->point_deleted)){ tmp_range_x[0] = min(right_son_ptr->node_range_x[0],root->point.x); tmp_range_x[1] = max(right_son_ptr->node_range_x[1],root->point.x); tmp_range_y[0] = min(right_son_ptr->node_range_y[0],root->point.y); tmp_range_y[1] = max(right_son_ptr->node_range_y[1],root->point.y); tmp_range_z[0] = min(right_son_ptr->node_range_z[0],root->point.z); tmp_range_z[1] = max(right_son_ptr->node_range_z[1],root->point.z); } else { if (!right_son_ptr->tree_deleted){ tmp_range_x[0] = min(tmp_range_x[0], right_son_ptr->node_range_x[0]); tmp_range_x[1] = max(tmp_range_x[1], right_son_ptr->node_range_x[1]); tmp_range_y[0] = min(tmp_range_y[0], right_son_ptr->node_range_y[0]); tmp_range_y[1] = max(tmp_range_y[1], right_son_ptr->node_range_y[1]); tmp_range_z[0] = min(tmp_range_z[0], right_son_ptr->node_range_z[0]); tmp_range_z[1] = max(tmp_range_z[1], right_son_ptr->node_range_z[1]); } if (!root->point_deleted){ tmp_range_x[0] = min(tmp_range_x[0], root->point.x); tmp_range_x[1] = max(tmp_range_x[1], root->point.x); tmp_range_y[0] = min(tmp_range_y[0], root->point.y); tmp_range_y[1] = max(tmp_range_y[1], root->point.y); tmp_range_z[0] = min(tmp_range_z[0], root->point.z); tmp_range_z[1] = max(tmp_range_z[1], root->point.z); } } } else { root->TreeSize = 1; root->invalid_point_num = (root->point_deleted? 1:0); root->down_del_num = (root->point_downsample_deleted? 1:0); root->tree_downsample_deleted = root->point_downsample_deleted; root->tree_deleted = root->point_deleted; tmp_range_x[0] = root->point.x; tmp_range_x[1] = root->point.x; tmp_range_y[0] = root->point.y; tmp_range_y[1] = root->point.y; tmp_range_z[0] = root->point.z; tmp_range_z[1] = root->point.z; } memcpy(root->node_range_x,tmp_range_x,sizeof(tmp_range_x)); memcpy(root->node_range_y,tmp_range_y,sizeof(tmp_range_y)); memcpy(root->node_range_z,tmp_range_z,sizeof(tmp_range_z)); float x_L = (root->node_range_x[1] - root->node_range_x[0]) * 0.5; float y_L = (root->node_range_y[1] - root->node_range_y[0]) * 0.5; float z_L = (root->node_range_z[1] - root->node_range_z[0]) * 0.5; root->radius_sq = x_L*x_L + y_L * y_L + z_L * z_L; if (left_son_ptr != nullptr) left_son_ptr -> father_ptr = root; if (right_son_ptr != nullptr) right_son_ptr -> father_ptr = root; if (root == Root_Node && root->TreeSize > 3){ KD_TREE_NODE * son_ptr = root->left_son_ptr; if (son_ptr == nullptr) son_ptr = root->right_son_ptr; float tmp_bal = float(son_ptr->TreeSize) / (root->TreeSize-1); root->alpha_del = float(root->invalid_point_num)/ root->TreeSize; root->alpha_bal = (tmp_bal>=0.5-EPSS)?tmp_bal:1-tmp_bal; } return; } template void KD_TREE::checkCorrespondding(KD_TREE_NODE * root){ if (root == nullptr) return; if (!root->point_deleted) { ++num_nodes; const PointType &p = root->point; VOXEL_LOC voxel_by_point; float cube_center[3]; point2Voxel(p, voxel_by_point, cube_center); } checkCorrespondding(root->left_son_ptr); checkCorrespondding(root->right_son_ptr); return; } template void KD_TREE::flatten(KD_TREE_NODE * root, PointVector &Storage, delete_point_storage_set storage_type){ if (root == nullptr) return; Push_Down(root); if (!root->point_deleted) { Storage.push_back(root->point); } flatten(root->left_son_ptr, Storage, storage_type); flatten(root->right_son_ptr, Storage, storage_type); switch (storage_type) { case NOT_RECORD: break; case DELETE_POINTS_REC: if (root->point_deleted && !root->point_downsample_deleted) { Points_deleted.push_back(root->point); } break; case MULTI_THREAD_REC: if (root->point_deleted && !root->point_downsample_deleted) { Multithread_Points_deleted.push_back(root->point); } break; default: break; } return; } template void KD_TREE::delete_tree_nodes(KD_TREE_NODE ** root){ if (*root == nullptr) return; Push_Down(*root); delete_tree_nodes(&(*root)->left_son_ptr); delete_tree_nodes(&(*root)->right_son_ptr); pthread_mutex_destroy( &(*root)->push_down_mutex_lock); delete *root; *root = nullptr; return; } template void KD_TREE::node2Voxel(KD_TREE_NODE * root, VOXEL_LOC& voxel) { point2Voxel(root->point, voxel); } template void KD_TREE:: point2Voxel(const PointType& p, VOXEL_LOC& voxel) { //divide into voxel float loc_xyz[3]; point2Voxel(p, loc_xyz); voxel = VOXEL_LOC((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]); } template void KD_TREE:: point2Voxel(const PointType& p, float* loc_xyz, float* center_xyz) { point2Voxel(p, loc_xyz); voxelLoc2Center(loc_xyz, center_xyz); } template void KD_TREE:: point2Voxel(const PointType& p, float* loc_xyz) { //divide into voxel loc_xyz[0] = floor(p.x / downsample_size); loc_xyz[1] = floor(p.y / downsample_size); loc_xyz[2] = floor(p.z / downsample_size); } template void KD_TREE:: voxelLoc2Center(const float* loc_xyz, float* center_xyz) { center_xyz[0] = loc_xyz[0] * downsample_size + half_voxel_size; center_xyz[1] = loc_xyz[1] * downsample_size + half_voxel_size; center_xyz[2] = loc_xyz[2] * downsample_size + half_voxel_size; } template void KD_TREE:: point2Voxel(const PointType& p, VOXEL_LOC& voxel, float* center_cube) { //divide into voxel float loc_xyz[3]; point2Voxel(p, loc_xyz); voxel = VOXEL_LOC((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]); voxelLoc2Center(loc_xyz, center_cube); } template void KD_TREE::single_connect(KD_TREE_NODE * root) { if (root == nullptr) return; if (!root->point_deleted) { const PointType& p = root->point; VOXEL_LOC voxel; point2Voxel(p, voxel); voxel2node[voxel] = root; auto iter = voxel2info.find(voxel); if (iter == voxel2info.end() || !iter->second) { // VoxelInfo voxel_new(p); voxel2info[voxel] = new VoxelInfo(p); } } } template void KD_TREE::buildConnection(KD_TREE_NODE * root, const bool & traverse) { if (root == nullptr) return; // Push_Down(root); if (!root->point_deleted) { const PointType& p = root->point; float loc_xyz[3]; VOXEL_LOC voxel; point2Voxel(p, voxel); voxel2node[voxel] = root; auto iter = voxel2info.find(voxel); if (iter == voxel2info.end() || !iter->second) { voxel2info[voxel] = new VoxelInfo(p); } } if (!traverse) return; buildConnection(root->left_son_ptr); buildConnection(root->right_son_ptr); } template bool KD_TREE::same_point(PointType a, PointType b){ return (fabs(a.x-b.x) < EPSS && fabs(a.y-b.y) < EPSS && fabs(a.z-b.z) < EPSS ); } template float KD_TREE::calc_dist(PointType a, PointType b){ float dist = 0.0f; dist = (a.x-b.x)*(a.x-b.x) + (a.y-b.y)*(a.y-b.y) + (a.z-b.z)*(a.z-b.z); return dist; } template float KD_TREE::calc_dist(const PointType& a, const Eigen::Vector3f& b){ float dist = 0.0f; dist = (a.x-b(0))*(a.x-b(0)) + (a.y-b(1))*(a.y-b(1)) + (a.z-b(2))*(a.z-b(2)); return dist; } template float KD_TREE::calc_dist(const PointType& a, const float& x, const float& y, const float& z){ float dist = 0.0f; dist = (a.x-x)*(a.x-x) + (a.y-y)*(a.y-y) + (a.z-z)*(a.z-z); return dist; } template float KD_TREE::calc_dist(PointType a){ return sqrt(a.x * a.x + a.y * a.y + a.z * a.z); } template float KD_TREE::calc_box_dist(KD_TREE_NODE * node, PointType point){ if (node == nullptr) return INFINITY; float min_dist = 0.0; if (point.x < node->node_range_x[0]) min_dist += (point.x - node->node_range_x[0])*(point.x - node->node_range_x[0]); if (point.x > node->node_range_x[1]) min_dist += (point.x - node->node_range_x[1])*(point.x - node->node_range_x[1]); if (point.y < node->node_range_y[0]) min_dist += (point.y - node->node_range_y[0])*(point.y - node->node_range_y[0]); if (point.y > node->node_range_y[1]) min_dist += (point.y - node->node_range_y[1])*(point.y - node->node_range_y[1]); if (point.z < node->node_range_z[0]) min_dist += (point.z - node->node_range_z[0])*(point.z - node->node_range_z[0]); if (point.z > node->node_range_z[1]) min_dist += (point.z - node->node_range_z[1])*(point.z - node->node_range_z[1]); return min_dist; } template bool KD_TREE::point_cmp_x(PointType a, PointType b) { return a.x < b.x;} template bool KD_TREE::point_cmp_y(PointType a, PointType b) { return a.y < b.y;} template bool KD_TREE::point_cmp_z(PointType a, PointType b) { return a.z < b.z;} // manual queue template void MANUAL_Q::clear(){ head = 0; tail = 0; counter = 0; is_empty = true; return; } template void MANUAL_Q::pop(){ if (counter == 0) return; head ++; head %= Q_LEN; counter --; if (counter == 0) is_empty = true; return; } template T MANUAL_Q::front(){ return q[head]; } template T MANUAL_Q::back(){ return q[tail]; } template void MANUAL_Q::push(T op){ q[tail] = op; counter ++; if (is_empty) is_empty = false; tail ++; tail %= Q_LEN; } template bool MANUAL_Q::empty(){ return is_empty; } template int MANUAL_Q::size(){ return counter; } //template class VoxelInfo; //template class KD_TREE; //template class KD_TREE; //template class KD_TREE; template class KD_TREE; ================================================ FILE: include/ikd-Tree/ikd_Tree.h ================================================ #pragma once #include #include #include #include #include #include #include #include #include #include #include #include #include "../point_type.h" #include "voxel_map_util.hpp" #define EPSS 1e-6 #define Minimal_Unbalanced_Tree_Size 10 #define Multi_Thread_Rebuild_Point_Num 1500 #define DOWNSAMPLE_SWITCH true #define ForceRebuildPercentage 0.2 #define Q_LEN 1000000 using namespace std; struct BoxPointType{ float vertex_min[3]; float vertex_max[3]; }; enum operation_set {ADD_POINT, DELETE_POINT, DELETE_BOX, ADD_BOX, DOWNSAMPLE_DELETE, PUSH_DOWN}; enum delete_point_storage_set {NOT_RECORD, DELETE_POINTS_REC, MULTI_THREAD_REC}; template class MANUAL_Q{ private: int head = 0,tail = 0, counter = 0; T q[Q_LEN]; bool is_empty; public: void pop(); T front(); T back(); void clear(); void push(T op); bool empty(); int size(); }; struct SimpInfo { float s_xx = 0.0, s_yy = 0.0, s_zz = 0.0, s_xy = 0.0, s_xz = 0.0, s_yz = 0.0; Eigen::Vector3f normal, mean_xyz; int num_points = 0; }; class VoxelInfo { typedef pcl::PointXYZINormal PointType; public: VoxelInfo() :is_init(false) , flag_updating(false) { plane = new Plane; // pthread_mutex_init(&updating_mutex_lock, NULL); } // initialize with single point VoxelInfo(const PointType & p); void init(); void updateWithSingle(const PointType & p); void updateWithSingle(const PointType & p, const Eigen::Matrix3f & cov); void updateWithCloud(); void updateSumAndMean(const PointType & p); void updatePlaneUncertainty(const PointType & p, const Eigen::Matrix3f & cov); void updateNormal(const PointType & p); bool checkPCA(); void updatePlaneCov(); void getSimpInfo(SimpInfo& out); bool is_init; float s_xx = 0.0, s_yy = 0.0, s_zz = 0.0, s_xy = 0.0, s_xz = 0.0, s_yz = 0.0; float mean_x = 0.0, mean_y = 0.0, mean_z = 0.0; int num_points = 0; Eigen::Vector3f normal; Plane * plane; vector points; mutex updating_mutex_lock; bool flag_updating = false; }; template class KD_TREE{ public: using PointVector = vector>; using Ptr = shared_ptr>; using VoxelInfoPtr = VoxelInfo*; struct KD_TREE_NODE{ PointType point; uint8_t division_axis; int TreeSize = 1; int invalid_point_num = 0; int down_del_num = 0; bool point_deleted = false; bool tree_deleted = false; bool point_downsample_deleted = false; bool tree_downsample_deleted = false; bool need_push_down_to_left = false; bool need_push_down_to_right = false; bool working_flag = false; float radius_sq; pthread_mutex_t push_down_mutex_lock; float node_range_x[2], node_range_y[2], node_range_z[2]; KD_TREE_NODE *left_son_ptr = nullptr; KD_TREE_NODE *right_son_ptr = nullptr; KD_TREE_NODE *father_ptr = nullptr; // For paper data record float alpha_del; float alpha_bal; }; struct Operation_Logger_Type{ PointType point; BoxPointType boxpoint; bool tree_deleted, tree_downsample_deleted; operation_set op; }; struct PointType_Voxel_CMP{ PointType point; float dist = 0.0; VoxelInfoPtr info = nullptr; PointType_Voxel_CMP (PointType p = PointType(), VoxelInfoPtr n = nullptr, const float& d = INFINITY){ this->point = p; this->dist = d; this->info = n; }; bool operator < (const PointType_Voxel_CMP &a)const{ if (fabs(dist - a.dist) < 1e-10) return point.x < a.point.x; else return dist < a.dist; } }; class MANUAL_VOXEL_HEAP{ public: MANUAL_VOXEL_HEAP(int max_capacity = 100){ cap = max_capacity; heap = new PointType_Voxel_CMP[max_capacity]; heap_size = 0; } ~MANUAL_VOXEL_HEAP(){ delete[] heap;} void pop(){ if (heap_size == 0) return; heap[0] = heap[heap_size-1]; heap_size--; MoveDown(0); return; } PointType_Voxel_CMP top(){ return heap[0];} void push(PointType_Voxel_CMP point){ if (heap_size >= cap) return; heap[heap_size] = point; FloatUp(heap_size); heap_size++; return; } int size(){ return heap_size;} void clear(){ heap_size = 0;} private: int heap_size = 0; int cap = 0; PointType_Voxel_CMP * heap; void MoveDown(int heap_index){ int l = heap_index * 2 + 1; PointType_Voxel_CMP tmp = heap[heap_index]; while (l < heap_size){ if (l + 1 < heap_size && heap[l] < heap[l+1]) l++; if (tmp < heap[l]){ heap[heap_index] = heap[l]; heap_index = l; l = heap_index * 2 + 1; } else break; } heap[heap_index] = tmp; return; } void FloatUp(int heap_index){ int ancestor = (heap_index-1)/2; PointType_Voxel_CMP tmp = heap[heap_index]; while (heap_index > 0){ if (heap[ancestor] < tmp){ heap[heap_index] = heap[ancestor]; heap_index = ancestor; ancestor = (heap_index-1)/2; } else break; } heap[heap_index] = tmp; return; } }; struct PointType_CMP{ PointType point; float dist = 0.0; KD_TREE_NODE* node = nullptr; // PointType_CMP (PointType p = PointType(), float d = INFINITY){ // this->point = p; // this->dist = d; // }; PointType_CMP (PointType p = PointType(), KD_TREE_NODE* n = nullptr, const float& d = INFINITY){ this->point = p; this->dist = d; this->node = n; }; bool operator < (const PointType_CMP &a)const{ if (fabs(dist - a.dist) < 1e-10) return point.x < a.point.x; else return dist < a.dist; } }; class MANUAL_HEAP{ public: MANUAL_HEAP(int max_capacity = 100){ cap = max_capacity; heap = new PointType_CMP[max_capacity]; heap_size = 0; } ~MANUAL_HEAP(){ delete[] heap;} void pop(){ if (heap_size == 0) return; heap[0] = heap[heap_size-1]; heap_size--; MoveDown(0); return; } PointType_CMP top(){ return heap[0];} void push(PointType_CMP point){ if (heap_size >= cap) return; heap[heap_size] = point; FloatUp(heap_size); heap_size++; return; } int size(){ return heap_size;} void clear(){ heap_size = 0;} private: int heap_size = 0; int cap = 0; PointType_CMP * heap; void MoveDown(int heap_index){ int l = heap_index * 2 + 1; PointType_CMP tmp = heap[heap_index]; while (l < heap_size){ if (l + 1 < heap_size && heap[l] < heap[l+1]) l++; if (tmp < heap[l]){ heap[heap_index] = heap[l]; heap_index = l; l = heap_index * 2 + 1; } else break; } heap[heap_index] = tmp; return; } void FloatUp(int heap_index){ int ancestor = (heap_index-1)/2; PointType_CMP tmp = heap[heap_index]; while (heap_index > 0){ if (heap[ancestor] < tmp){ heap[heap_index] = heap[ancestor]; heap_index = ancestor; ancestor = (heap_index-1)/2; } else break; } heap[heap_index] = tmp; return; } }; private: // Multi-thread Tree Rebuild bool termination_flag = false; bool rebuild_flag = false; pthread_t rebuild_thread; pthread_mutex_t termination_flag_mutex_lock, rebuild_ptr_mutex_lock, working_flag_mutex, search_flag_mutex; pthread_mutex_t rebuild_logger_mutex_lock, points_deleted_rebuild_mutex_lock; // queue Rebuild_Logger; MANUAL_Q Rebuild_Logger; PointVector Rebuild_PCL_Storage; KD_TREE_NODE ** Rebuild_Ptr = nullptr; int search_mutex_counter = 0; static void * multi_thread_ptr(void *arg); void multi_thread_rebuild(); void start_thread(); void stop_thread(); void run_operation(KD_TREE_NODE ** root, Operation_Logger_Type operation); // KD Tree Functions and augmented variables int Treesize_tmp = 0, Validnum_tmp = 0; float alpha_bal_tmp = 0.5, alpha_del_tmp = 0.0; float delete_criterion_param = 0.5f; float balance_criterion_param = 0.7f; float downsample_size = 0.2f; bool Delete_Storage_Disabled = false; KD_TREE_NODE * STATIC_ROOT_NODE = nullptr; PointVector Points_deleted; PointVector Downsample_Storage; PointVector Multithread_Points_deleted; void InitTreeNode(KD_TREE_NODE * root); void Test_Lock_States(KD_TREE_NODE *root); void BuildTree(KD_TREE_NODE ** root, int l, int r, PointVector & Storage); void Rebuild(KD_TREE_NODE ** root); int Delete_by_range(KD_TREE_NODE ** root, BoxPointType boxpoint, bool allow_rebuild, bool is_downsample); void Delete_by_point(KD_TREE_NODE ** root, PointType point, bool allow_rebuild); void Add_by_point(KD_TREE_NODE ** root, PointType point, bool allow_rebuild, int father_axis); void Add_by_range(KD_TREE_NODE ** root, BoxPointType boxpoint, bool allow_rebuild); void Search(KD_TREE_NODE * root, int k_nearest, PointType point, MANUAL_HEAP &q, double max_dist);//priority_queue void Search_by_range(KD_TREE_NODE *root, BoxPointType boxpoint, PointVector &Storage); void Search_by_radius(KD_TREE_NODE *root, PointType point, float radius, PointVector &Storage); bool Criterion_Check(KD_TREE_NODE * root); void Push_Down(KD_TREE_NODE * root); void Update(KD_TREE_NODE * root); void delete_tree_nodes(KD_TREE_NODE ** root); void downsample(KD_TREE_NODE ** root); bool same_point(PointType a, PointType b); float calc_dist(PointType a, PointType b); float calc_dist(const PointType& a, const Eigen::Vector3f& b); float calc_dist(const PointType& a, const float& x, const float& y, const float& z); float calc_dist(PointType a); float calc_box_dist(KD_TREE_NODE * node, PointType point); static bool point_cmp_x(PointType a, PointType b); static bool point_cmp_y(PointType a, PointType b); static bool point_cmp_z(PointType a, PointType b); void buildConnection(KD_TREE_NODE * root, const bool & traverse = true); //build connection between ikdtree nodes and voxels void single_connect(KD_TREE_NODE * root); void point2Voxel(const PointType& p, VOXEL_LOC& voxel); void point2Voxel(const PointType& p, float* loc_xyz); void point2Voxel(const PointType& p, float* loc_xyz, float* center_xyz); void point2Voxel(const PointType& p, VOXEL_LOC& voxel, float* center_cube); void voxelIndexNode(const PointType& p, VOXEL_LOC& voxel); void node2Voxel(KD_TREE_NODE * root, VOXEL_LOC& voxel); void insideVoxelDownsample(PointVector& point_cloud); void voxelLoc2Center(const float* loc_xyz, float* center_xyz); void addNearVoxelsLoc(const PointType& point, const float* voxel_center, std::vector& voxels); public: KD_TREE(float delete_param = 0.5, float balance_param = 0.6 , float box_length = 0.2); ~KD_TREE(); void Set_delete_criterion_param(float delete_param); void Set_balance_criterion_param(float balance_param); void set_downsample_param(float box_length); void InitializeKDTree(float delete_param = 0.5, float balance_param = 0.7, float box_length = 0.2); int size(); int validnum(); void root_alpha(float &alpha_bal, float &alpha_del); void Build(PointVector point_cloud); void Nearest_Search(PointType point, int k_nearest, PointVector &Nearest_Points, vector & Point_Distance, double max_dist = INFINITY); void Nearest_Search(PointType point, int k_nearest, PointVector &Nearest_Points, vector & Point_Distance, vector& voxels, double max_dist = INFINITY); void Box_Search(const BoxPointType &Box_of_Point, PointVector &Storage); void Radius_Search(PointType point, const float radius, PointVector &Storage); int Add_Points(PointVector & PointToAdd, bool downsample_on); void Add_Point_Boxes(vector & BoxPoints); void Delete_Points(PointVector & PointToDel); int Delete_Point_Boxes(vector & BoxPoints); void flatten(KD_TREE_NODE * root, PointVector &Storage, delete_point_storage_set storage_type); void checkCorrespondding(KD_TREE_NODE * root); // int checkCorresponddingVoxelAndNode(KD_TREE_NODE * root); void acquire_removed_points(PointVector & removed_points); // void updateNodeInfo(KD_TREE_NODE* node, const PointType& point); void Voxel_Search(const PointType& point, int k_nearest, PointVector &Nearest_Points, vector& nodes); void Voxel_Search_test(const PointType& point, int k_nearest, PointVector &Nearest_Points, vector & Point_Distance, vector& voxels); void updateVoxelInfo(const PointType& point); void updateVoxelInfo(const PointType& point, const Eigen::Matrix3f & cov); //voxel map // unordered_map voxel_map; unordered_map voxel2node; unordered_map voxel2info; // unordered_map node2voxel; void findVoxel(const PointType& p); int max_layer, layer, max_cov_points_size, max_points_size; vector layer_point_size; float planer_threshold; float voxel_size; double max_voxel_size, min_eigen_value, half_voxel_size, quater_voxel_size; int voxel_conflict = 0; int max_voxel_points_size; BoxPointType tree_range(); PointVector PCL_Storage; KD_TREE_NODE * Root_Node = nullptr; int max_queue_size = 0; //check corresponding int num_node2_voxel_null = 0, num_voxel2node_null = 0; int num_nodes = 0; int voxel2info_null = 0; int num_same_info = 0, num_diff_info = 0; int num_same_voxel2node = 0; int num_node2voxel_valid = 0, voxel2info_valid = 0; int num_same_voxel_by_pointAndnode = 0; }; ================================================ FILE: include/matplotlibcpp.h ================================================ #pragma once // Python headers must be included before any system headers, since // they define _POSIX_C_SOURCE #include #include #include #include #include #include #include #include #include // requires c++11 support #include #ifndef WITHOUT_NUMPY # define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION # include # ifdef WITH_OPENCV # include # endif // WITH_OPENCV /* * A bunch of constants were removed in OpenCV 4 in favour of enum classes, so * define the ones we need here. */ # if CV_MAJOR_VERSION > 3 # define CV_BGR2RGB cv::COLOR_BGR2RGB # define CV_BGRA2RGBA cv::COLOR_BGRA2RGBA # endif #endif // WITHOUT_NUMPY #if PY_MAJOR_VERSION >= 3 # define PyString_FromString PyUnicode_FromString # define PyInt_FromLong PyLong_FromLong # define PyString_FromString PyUnicode_FromString #endif namespace matplotlibcpp { namespace detail { static std::string s_backend; struct _interpreter { PyObject* s_python_function_arrow; PyObject *s_python_function_show; PyObject *s_python_function_close; PyObject *s_python_function_draw; PyObject *s_python_function_pause; PyObject *s_python_function_save; PyObject *s_python_function_figure; PyObject *s_python_function_fignum_exists; PyObject *s_python_function_plot; PyObject *s_python_function_quiver; PyObject* s_python_function_contour; PyObject *s_python_function_semilogx; PyObject *s_python_function_semilogy; PyObject *s_python_function_loglog; PyObject *s_python_function_fill; PyObject *s_python_function_fill_between; PyObject *s_python_function_hist; PyObject *s_python_function_imshow; PyObject *s_python_function_scatter; PyObject *s_python_function_boxplot; PyObject *s_python_function_subplot; PyObject *s_python_function_subplot2grid; PyObject *s_python_function_legend; PyObject *s_python_function_xlim; PyObject *s_python_function_ion; PyObject *s_python_function_ginput; PyObject *s_python_function_ylim; PyObject *s_python_function_title; PyObject *s_python_function_axis; PyObject *s_python_function_axvline; PyObject *s_python_function_axvspan; PyObject *s_python_function_xlabel; PyObject *s_python_function_ylabel; PyObject *s_python_function_gca; PyObject *s_python_function_xticks; PyObject *s_python_function_yticks; PyObject* s_python_function_margins; PyObject *s_python_function_tick_params; PyObject *s_python_function_grid; PyObject* s_python_function_cla; PyObject *s_python_function_clf; PyObject *s_python_function_errorbar; PyObject *s_python_function_annotate; PyObject *s_python_function_tight_layout; PyObject *s_python_colormap; PyObject *s_python_empty_tuple; PyObject *s_python_function_stem; PyObject *s_python_function_xkcd; PyObject *s_python_function_text; PyObject *s_python_function_suptitle; PyObject *s_python_function_bar; PyObject *s_python_function_colorbar; PyObject *s_python_function_subplots_adjust; /* For now, _interpreter is implemented as a singleton since its currently not possible to have multiple independent embedded python interpreters without patching the python source code or starting a separate process for each. http://bytes.com/topic/python/answers/793370-multiple-independent-python-interpreters-c-c-program */ static _interpreter& get() { static _interpreter ctx; return ctx; } PyObject* safe_import(PyObject* module, std::string fname) { PyObject* fn = PyObject_GetAttrString(module, fname.c_str()); if (!fn) throw std::runtime_error(std::string("Couldn't find required function: ") + fname); if (!PyFunction_Check(fn)) throw std::runtime_error(fname + std::string(" is unexpectedly not a PyFunction.")); return fn; } private: #ifndef WITHOUT_NUMPY # if PY_MAJOR_VERSION >= 3 void *import_numpy() { import_array(); // initialize C-API return NULL; } # else void import_numpy() { import_array(); // initialize C-API } # endif #endif _interpreter() { // optional but recommended #if PY_MAJOR_VERSION >= 3 wchar_t name[] = L"plotting"; #else char name[] = "plotting"; #endif Py_SetProgramName(name); Py_Initialize(); #ifndef WITHOUT_NUMPY import_numpy(); // initialize numpy C-API #endif PyObject* matplotlibname = PyString_FromString("matplotlib"); PyObject* pyplotname = PyString_FromString("matplotlib.pyplot"); PyObject* cmname = PyString_FromString("matplotlib.cm"); PyObject* pylabname = PyString_FromString("pylab"); if (!pyplotname || !pylabname || !matplotlibname || !cmname) { throw std::runtime_error("couldnt create string"); } PyObject* matplotlib = PyImport_Import(matplotlibname); Py_DECREF(matplotlibname); if (!matplotlib) { PyErr_Print(); throw std::runtime_error("Error loading module matplotlib!"); } // matplotlib.use() must be called *before* pylab, matplotlib.pyplot, // or matplotlib.backends is imported for the first time if (!s_backend.empty()) { PyObject_CallMethod(matplotlib, const_cast("use"), const_cast("s"), s_backend.c_str()); } PyObject* pymod = PyImport_Import(pyplotname); Py_DECREF(pyplotname); if (!pymod) { throw std::runtime_error("Error loading module matplotlib.pyplot!"); } s_python_colormap = PyImport_Import(cmname); Py_DECREF(cmname); if (!s_python_colormap) { throw std::runtime_error("Error loading module matplotlib.cm!"); } PyObject* pylabmod = PyImport_Import(pylabname); Py_DECREF(pylabname); if (!pylabmod) { throw std::runtime_error("Error loading module pylab!"); } s_python_function_arrow = safe_import(pymod, "arrow"); s_python_function_show = safe_import(pymod, "show"); s_python_function_close = safe_import(pymod, "close"); s_python_function_draw = safe_import(pymod, "draw"); s_python_function_pause = safe_import(pymod, "pause"); s_python_function_figure = safe_import(pymod, "figure"); s_python_function_fignum_exists = safe_import(pymod, "fignum_exists"); s_python_function_plot = safe_import(pymod, "plot"); s_python_function_quiver = safe_import(pymod, "quiver"); s_python_function_contour = safe_import(pymod, "contour"); s_python_function_semilogx = safe_import(pymod, "semilogx"); s_python_function_semilogy = safe_import(pymod, "semilogy"); s_python_function_loglog = safe_import(pymod, "loglog"); s_python_function_fill = safe_import(pymod, "fill"); s_python_function_fill_between = safe_import(pymod, "fill_between"); s_python_function_hist = safe_import(pymod,"hist"); s_python_function_scatter = safe_import(pymod,"scatter"); s_python_function_boxplot = safe_import(pymod,"boxplot"); s_python_function_subplot = safe_import(pymod, "subplot"); s_python_function_subplot2grid = safe_import(pymod, "subplot2grid"); s_python_function_legend = safe_import(pymod, "legend"); s_python_function_ylim = safe_import(pymod, "ylim"); s_python_function_title = safe_import(pymod, "title"); s_python_function_axis = safe_import(pymod, "axis"); s_python_function_axvline = safe_import(pymod, "axvline"); s_python_function_axvspan = safe_import(pymod, "axvspan"); s_python_function_xlabel = safe_import(pymod, "xlabel"); s_python_function_ylabel = safe_import(pymod, "ylabel"); s_python_function_gca = safe_import(pymod, "gca"); s_python_function_xticks = safe_import(pymod, "xticks"); s_python_function_yticks = safe_import(pymod, "yticks"); s_python_function_margins = safe_import(pymod, "margins"); s_python_function_tick_params = safe_import(pymod, "tick_params"); s_python_function_grid = safe_import(pymod, "grid"); s_python_function_xlim = safe_import(pymod, "xlim"); s_python_function_ion = safe_import(pymod, "ion"); s_python_function_ginput = safe_import(pymod, "ginput"); s_python_function_save = safe_import(pylabmod, "savefig"); s_python_function_annotate = safe_import(pymod,"annotate"); s_python_function_cla = safe_import(pymod, "cla"); s_python_function_clf = safe_import(pymod, "clf"); s_python_function_errorbar = safe_import(pymod, "errorbar"); s_python_function_tight_layout = safe_import(pymod, "tight_layout"); s_python_function_stem = safe_import(pymod, "stem"); s_python_function_xkcd = safe_import(pymod, "xkcd"); s_python_function_text = safe_import(pymod, "text"); s_python_function_suptitle = safe_import(pymod, "suptitle"); s_python_function_bar = safe_import(pymod,"bar"); s_python_function_colorbar = PyObject_GetAttrString(pymod, "colorbar"); s_python_function_subplots_adjust = safe_import(pymod,"subplots_adjust"); #ifndef WITHOUT_NUMPY s_python_function_imshow = safe_import(pymod, "imshow"); #endif s_python_empty_tuple = PyTuple_New(0); } ~_interpreter() { Py_Finalize(); } }; } // end namespace detail /// Select the backend /// /// **NOTE:** This must be called before the first plot command to have /// any effect. /// /// Mainly useful to select the non-interactive 'Agg' backend when running /// matplotlibcpp in headless mode, for example on a machine with no display. /// /// See also: https://matplotlib.org/2.0.2/api/matplotlib_configuration_api.html#matplotlib.use inline void backend(const std::string& name) { detail::s_backend = name; } inline bool annotate(std::string annotation, double x, double y) { detail::_interpreter::get(); PyObject * xy = PyTuple_New(2); PyObject * str = PyString_FromString(annotation.c_str()); PyTuple_SetItem(xy,0,PyFloat_FromDouble(x)); PyTuple_SetItem(xy,1,PyFloat_FromDouble(y)); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "xy", xy); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, str); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_annotate, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } namespace detail { #ifndef WITHOUT_NUMPY // Type selector for numpy array conversion template struct select_npy_type { const static NPY_TYPES type = NPY_NOTYPE; }; //Default template <> struct select_npy_type { const static NPY_TYPES type = NPY_DOUBLE; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_FLOAT; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_BOOL; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT8; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_SHORT; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT64; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT8; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_USHORT; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_ULONG; }; template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT64; }; // Sanity checks; comment them out or change the numpy type below if you're compiling on // a platform where they don't apply static_assert(sizeof(long long) == 8); template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT64; }; static_assert(sizeof(unsigned long long) == 8); template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT64; }; // TODO: add int, long, etc. template PyObject* get_array(const std::vector& v) { npy_intp vsize = v.size(); NPY_TYPES type = select_npy_type::type; if (type == NPY_NOTYPE) { size_t memsize = v.size()*sizeof(double); double* dp = static_cast(::malloc(memsize)); for (size_t i=0; i(varray), NPY_ARRAY_OWNDATA); return varray; } PyObject* varray = PyArray_SimpleNewFromData(1, &vsize, type, (void*)(v.data())); return varray; } template PyObject* get_2darray(const std::vector<::std::vector>& v) { if (v.size() < 1) throw std::runtime_error("get_2d_array v too small"); npy_intp vsize[2] = {static_cast(v.size()), static_cast(v[0].size())}; PyArrayObject *varray = (PyArrayObject *)PyArray_SimpleNew(2, vsize, NPY_DOUBLE); double *vd_begin = static_cast(PyArray_DATA(varray)); for (const ::std::vector &v_row : v) { if (v_row.size() != static_cast(vsize[1])) throw std::runtime_error("Missmatched array size"); std::copy(v_row.begin(), v_row.end(), vd_begin); vd_begin += vsize[1]; } return reinterpret_cast(varray); } #else // fallback if we don't have numpy: copy every element of the given vector template PyObject* get_array(const std::vector& v) { PyObject* list = PyList_New(v.size()); for(size_t i = 0; i < v.size(); ++i) { PyList_SetItem(list, i, PyFloat_FromDouble(v.at(i))); } return list; } #endif // WITHOUT_NUMPY // sometimes, for labels and such, we need string arrays inline PyObject * get_array(const std::vector& strings) { PyObject* list = PyList_New(strings.size()); for (std::size_t i = 0; i < strings.size(); ++i) { PyList_SetItem(list, i, PyString_FromString(strings[i].c_str())); } return list; } // not all matplotlib need 2d arrays, some prefer lists of lists template PyObject* get_listlist(const std::vector>& ll) { PyObject* listlist = PyList_New(ll.size()); for (std::size_t i = 0; i < ll.size(); ++i) { PyList_SetItem(listlist, i, get_array(ll[i])); } return listlist; } } // namespace detail /// Plot a line through the given x and y data points.. /// /// See: https://matplotlib.org/3.2.1/api/_as_gen/matplotlib.pyplot.plot.html template bool plot(const std::vector &x, const std::vector &y, const std::map& keywords) { assert(x.size() == y.size()); detail::_interpreter::get(); // using numpy arrays PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); // construct positional args PyObject* args = PyTuple_New(2); PyTuple_SetItem(args, 0, xarray); PyTuple_SetItem(args, 1, yarray); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } // TODO - it should be possible to make this work by implementing // a non-numpy alternative for `detail::get_2darray()`. #ifndef WITHOUT_NUMPY template void plot_surface(const std::vector<::std::vector> &x, const std::vector<::std::vector> &y, const std::vector<::std::vector> &z, const std::map &keywords = std::map()) { detail::_interpreter::get(); // We lazily load the modules here the first time this function is called // because I'm not sure that we can assume "matplotlib installed" implies // "mpl_toolkits installed" on all platforms, and we don't want to require // it for people who don't need 3d plots. static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; if (!mpl_toolkitsmod) { detail::_interpreter::get(); PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } mpl_toolkitsmod = PyImport_Import(mpl_toolkits); Py_DECREF(mpl_toolkits); if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } axis3dmod = PyImport_Import(axis3d); Py_DECREF(axis3d); if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } } assert(x.size() == y.size()); assert(y.size() == z.size()); // using numpy arrays PyObject *xarray = detail::get_2darray(x); PyObject *yarray = detail::get_2darray(y); PyObject *zarray = detail::get_2darray(z); // construct positional args PyObject *args = PyTuple_New(3); PyTuple_SetItem(args, 0, xarray); PyTuple_SetItem(args, 1, yarray); PyTuple_SetItem(args, 2, zarray); // Build up the kw args. PyObject *kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "rstride", PyInt_FromLong(1)); PyDict_SetItemString(kwargs, "cstride", PyInt_FromLong(1)); PyObject *python_colormap_coolwarm = PyObject_GetAttrString( detail::_interpreter::get().s_python_colormap, "coolwarm"); PyDict_SetItemString(kwargs, "cmap", python_colormap_coolwarm); for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject *fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, detail::_interpreter::get().s_python_empty_tuple); if (!fig) throw std::runtime_error("Call to figure() failed."); PyObject *gca_kwargs = PyDict_New(); PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); PyObject *gca = PyObject_GetAttrString(fig, "gca"); if (!gca) throw std::runtime_error("No gca"); Py_INCREF(gca); PyObject *axis = PyObject_Call( gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); if (!axis) throw std::runtime_error("No axis"); Py_INCREF(axis); Py_DECREF(gca); Py_DECREF(gca_kwargs); PyObject *plot_surface = PyObject_GetAttrString(axis, "plot_surface"); if (!plot_surface) throw std::runtime_error("No surface"); Py_INCREF(plot_surface); PyObject *res = PyObject_Call(plot_surface, args, kwargs); if (!res) throw std::runtime_error("failed surface"); Py_DECREF(plot_surface); Py_DECREF(axis); Py_DECREF(args); Py_DECREF(kwargs); if (res) Py_DECREF(res); } #endif // WITHOUT_NUMPY template void plot3(const std::vector &x, const std::vector &y, const std::vector &z, const std::map &keywords = std::map()) { detail::_interpreter::get(); // Same as with plot_surface: We lazily load the modules here the first time // this function is called because I'm not sure that we can assume "matplotlib // installed" implies "mpl_toolkits installed" on all platforms, and we don't // want to require it for people who don't need 3d plots. static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; if (!mpl_toolkitsmod) { detail::_interpreter::get(); PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } mpl_toolkitsmod = PyImport_Import(mpl_toolkits); Py_DECREF(mpl_toolkits); if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } axis3dmod = PyImport_Import(axis3d); Py_DECREF(axis3d); if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } } assert(x.size() == y.size()); assert(y.size() == z.size()); PyObject *xarray = detail::get_array(x); PyObject *yarray = detail::get_array(y); PyObject *zarray = detail::get_array(z); // construct positional args PyObject *args = PyTuple_New(3); PyTuple_SetItem(args, 0, xarray); PyTuple_SetItem(args, 1, yarray); PyTuple_SetItem(args, 2, zarray); // Build up the kw args. PyObject *kwargs = PyDict_New(); for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject *fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, detail::_interpreter::get().s_python_empty_tuple); if (!fig) throw std::runtime_error("Call to figure() failed."); PyObject *gca_kwargs = PyDict_New(); PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); PyObject *gca = PyObject_GetAttrString(fig, "gca"); if (!gca) throw std::runtime_error("No gca"); Py_INCREF(gca); PyObject *axis = PyObject_Call( gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); if (!axis) throw std::runtime_error("No axis"); Py_INCREF(axis); Py_DECREF(gca); Py_DECREF(gca_kwargs); PyObject *plot3 = PyObject_GetAttrString(axis, "plot"); if (!plot3) throw std::runtime_error("No 3D line plot"); Py_INCREF(plot3); PyObject *res = PyObject_Call(plot3, args, kwargs); if (!res) throw std::runtime_error("Failed 3D line plot"); Py_DECREF(plot3); Py_DECREF(axis); Py_DECREF(args); Py_DECREF(kwargs); if (res) Py_DECREF(res); } template bool stem(const std::vector &x, const std::vector &y, const std::map& keywords) { assert(x.size() == y.size()); detail::_interpreter::get(); // using numpy arrays PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); // construct positional args PyObject* args = PyTuple_New(2); PyTuple_SetItem(args, 0, xarray); PyTuple_SetItem(args, 1, yarray); // construct keyword args PyObject* kwargs = PyDict_New(); for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call( detail::_interpreter::get().s_python_function_stem, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if (res) Py_DECREF(res); return res; } template< typename Numeric > bool fill(const std::vector& x, const std::vector& y, const std::map& keywords) { assert(x.size() == y.size()); detail::_interpreter::get(); // using numpy arrays PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); // construct positional args PyObject* args = PyTuple_New(2); PyTuple_SetItem(args, 0, xarray); PyTuple_SetItem(args, 1, yarray); // construct keyword args PyObject* kwargs = PyDict_New(); for (auto it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if (res) Py_DECREF(res); return res; } template< typename Numeric > bool fill_between(const std::vector& x, const std::vector& y1, const std::vector& y2, const std::map& keywords) { assert(x.size() == y1.size()); assert(x.size() == y2.size()); detail::_interpreter::get(); // using numpy arrays PyObject* xarray = detail::get_array(x); PyObject* y1array = detail::get_array(y1); PyObject* y2array = detail::get_array(y2); // construct positional args PyObject* args = PyTuple_New(3); PyTuple_SetItem(args, 0, xarray); PyTuple_SetItem(args, 1, y1array); PyTuple_SetItem(args, 2, y2array); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill_between, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } template bool arrow(Numeric x, Numeric y, Numeric end_x, Numeric end_y, const std::string& fc = "r", const std::string ec = "k", Numeric head_length = 0.25, Numeric head_width = 0.1625) { PyObject* obj_x = PyFloat_FromDouble(x); PyObject* obj_y = PyFloat_FromDouble(y); PyObject* obj_end_x = PyFloat_FromDouble(end_x); PyObject* obj_end_y = PyFloat_FromDouble(end_y); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "fc", PyString_FromString(fc.c_str())); PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); PyDict_SetItemString(kwargs, "head_width", PyFloat_FromDouble(head_width)); PyDict_SetItemString(kwargs, "head_length", PyFloat_FromDouble(head_length)); PyObject* plot_args = PyTuple_New(4); PyTuple_SetItem(plot_args, 0, obj_x); PyTuple_SetItem(plot_args, 1, obj_y); PyTuple_SetItem(plot_args, 2, obj_end_x); PyTuple_SetItem(plot_args, 3, obj_end_y); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_arrow, plot_args, kwargs); Py_DECREF(plot_args); Py_DECREF(kwargs); if (res) Py_DECREF(res); return res; } template< typename Numeric> bool hist(const std::vector& y, long bins=10,std::string color="b", double alpha=1.0, bool cumulative=false) { detail::_interpreter::get(); PyObject* yarray = detail::get_array(y); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins)); PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str())); PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha)); PyDict_SetItemString(kwargs, "cumulative", cumulative ? Py_True : Py_False); PyObject* plot_args = PyTuple_New(1); PyTuple_SetItem(plot_args, 0, yarray); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs); Py_DECREF(plot_args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } #ifndef WITHOUT_NUMPY namespace detail { inline void imshow(void *ptr, const NPY_TYPES type, const int rows, const int columns, const int colors, const std::map &keywords, PyObject** out) { assert(type == NPY_UINT8 || type == NPY_FLOAT); assert(colors == 1 || colors == 3 || colors == 4); detail::_interpreter::get(); // construct args npy_intp dims[3] = { rows, columns, colors }; PyObject *args = PyTuple_New(1); PyTuple_SetItem(args, 0, PyArray_SimpleNewFromData(colors == 1 ? 2 : 3, dims, type, ptr)); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_imshow, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if (!res) throw std::runtime_error("Call to imshow() failed"); if (out) *out = res; else Py_DECREF(res); } } // namespace detail inline void imshow(const unsigned char *ptr, const int rows, const int columns, const int colors, const std::map &keywords = {}, PyObject** out = nullptr) { detail::imshow((void *) ptr, NPY_UINT8, rows, columns, colors, keywords, out); } inline void imshow(const float *ptr, const int rows, const int columns, const int colors, const std::map &keywords = {}, PyObject** out = nullptr) { detail::imshow((void *) ptr, NPY_FLOAT, rows, columns, colors, keywords, out); } #ifdef WITH_OPENCV void imshow(const cv::Mat &image, const std::map &keywords = {}) { // Convert underlying type of matrix, if needed cv::Mat image2; NPY_TYPES npy_type = NPY_UINT8; switch (image.type() & CV_MAT_DEPTH_MASK) { case CV_8U: image2 = image; break; case CV_32F: image2 = image; npy_type = NPY_FLOAT; break; default: image.convertTo(image2, CV_MAKETYPE(CV_8U, image.channels())); } // If color image, convert from BGR to RGB switch (image2.channels()) { case 3: cv::cvtColor(image2, image2, CV_BGR2RGB); break; case 4: cv::cvtColor(image2, image2, CV_BGRA2RGBA); } detail::imshow(image2.data, npy_type, image2.rows, image2.cols, image2.channels(), keywords); } #endif // WITH_OPENCV #endif // WITHOUT_NUMPY template bool scatter(const std::vector& x, const std::vector& y, const double s=1.0, // The marker size in points**2 const std::map & keywords = {}) { detail::_interpreter::get(); assert(x.size() == y.size()); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "s", PyLong_FromLong(s)); for (const auto& it : keywords) { PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); } PyObject* plot_args = PyTuple_New(2); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_scatter, plot_args, kwargs); Py_DECREF(plot_args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } template bool boxplot(const std::vector>& data, const std::vector& labels = {}, const std::map & keywords = {}) { detail::_interpreter::get(); PyObject* listlist = detail::get_listlist(data); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, listlist); PyObject* kwargs = PyDict_New(); // kwargs needs the labels, if there are (the correct number of) labels if (!labels.empty() && labels.size() == data.size()) { PyDict_SetItemString(kwargs, "labels", detail::get_array(labels)); } // take care of the remaining keywords for (const auto& it : keywords) { PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } template bool boxplot(const std::vector& data, const std::map & keywords = {}) { detail::_interpreter::get(); PyObject* vector = detail::get_array(data); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, vector); PyObject* kwargs = PyDict_New(); for (const auto& it : keywords) { PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } template bool bar(const std::vector & x, const std::vector & y, std::string ec = "black", std::string ls = "-", double lw = 1.0, const std::map & keywords = {}) { detail::_interpreter::get(); PyObject * xarray = detail::get_array(x); PyObject * yarray = detail::get_array(y); PyObject * kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); PyDict_SetItemString(kwargs, "ls", PyString_FromString(ls.c_str())); PyDict_SetItemString(kwargs, "lw", PyFloat_FromDouble(lw)); for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString( kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject * plot_args = PyTuple_New(2); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyObject * res = PyObject_Call( detail::_interpreter::get().s_python_function_bar, plot_args, kwargs); Py_DECREF(plot_args); Py_DECREF(kwargs); if (res) Py_DECREF(res); return res; } template bool bar(const std::vector & y, std::string ec = "black", std::string ls = "-", double lw = 1.0, const std::map & keywords = {}) { using T = typename std::remove_reference::type::value_type; detail::_interpreter::get(); std::vector x; for (std::size_t i = 0; i < y.size(); i++) { x.push_back(i); } return bar(x, y, ec, ls, lw, keywords); } inline bool subplots_adjust(const std::map& keywords = {}) { detail::_interpreter::get(); PyObject* kwargs = PyDict_New(); for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyFloat_FromDouble(it->second)); } PyObject* plot_args = PyTuple_New(0); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_subplots_adjust, plot_args, kwargs); Py_DECREF(plot_args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } template< typename Numeric> bool named_hist(std::string label,const std::vector& y, long bins=10, std::string color="b", double alpha=1.0) { detail::_interpreter::get(); PyObject* yarray = detail::get_array(y); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "label", PyString_FromString(label.c_str())); PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins)); PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str())); PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha)); PyObject* plot_args = PyTuple_New(1); PyTuple_SetItem(plot_args, 0, yarray); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs); Py_DECREF(plot_args); Py_DECREF(kwargs); if(res) Py_DECREF(res); return res; } template bool plot(const std::vector& x, const std::vector& y, const std::string& s = "") { assert(x.size() == y.size()); detail::_interpreter::get(); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(s.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args); Py_DECREF(plot_args); if(res) Py_DECREF(res); return res; } template bool contour(const std::vector& x, const std::vector& y, const std::vector& z, const std::map& keywords = {}) { assert(x.size() == y.size() && x.size() == z.size()); PyObject* xarray = get_array(x); PyObject* yarray = get_array(y); PyObject* zarray = get_array(z); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, zarray); // construct keyword args PyObject* kwargs = PyDict_New(); for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_contour, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool quiver(const std::vector& x, const std::vector& y, const std::vector& u, const std::vector& w, const std::map& keywords = {}) { assert(x.size() == y.size() && x.size() == u.size() && u.size() == w.size()); detail::_interpreter::get(); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* uarray = detail::get_array(u); PyObject* warray = detail::get_array(w); PyObject* plot_args = PyTuple_New(4); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, uarray); PyTuple_SetItem(plot_args, 3, warray); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call( detail::_interpreter::get().s_python_function_quiver, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool stem(const std::vector& x, const std::vector& y, const std::string& s = "") { assert(x.size() == y.size()); detail::_interpreter::get(); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(s.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_CallObject( detail::_interpreter::get().s_python_function_stem, plot_args); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool semilogx(const std::vector& x, const std::vector& y, const std::string& s = "") { assert(x.size() == y.size()); detail::_interpreter::get(); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(s.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogx, plot_args); Py_DECREF(plot_args); if(res) Py_DECREF(res); return res; } template bool semilogy(const std::vector& x, const std::vector& y, const std::string& s = "") { assert(x.size() == y.size()); detail::_interpreter::get(); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(s.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogy, plot_args); Py_DECREF(plot_args); if(res) Py_DECREF(res); return res; } template bool loglog(const std::vector& x, const std::vector& y, const std::string& s = "") { assert(x.size() == y.size()); detail::_interpreter::get(); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(s.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_loglog, plot_args); Py_DECREF(plot_args); if(res) Py_DECREF(res); return res; } template bool errorbar(const std::vector &x, const std::vector &y, const std::vector &yerr, const std::map &keywords = {}) { assert(x.size() == y.size()); detail::_interpreter::get(); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* yerrarray = detail::get_array(yerr); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyDict_SetItemString(kwargs, "yerr", yerrarray); PyObject *plot_args = PyTuple_New(2); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_errorbar, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); else throw std::runtime_error("Call to errorbar() failed."); return res; } template bool named_plot(const std::string& name, const std::vector& y, const std::string& format = "") { detail::_interpreter::get(); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(format.c_str()); PyObject* plot_args = PyTuple_New(2); PyTuple_SetItem(plot_args, 0, yarray); PyTuple_SetItem(plot_args, 1, pystring); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool named_plot(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") { detail::_interpreter::get(); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(format.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool named_semilogx(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") { detail::_interpreter::get(); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(format.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogx, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool named_semilogy(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") { detail::_interpreter::get(); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(format.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogy, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool named_loglog(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") { detail::_interpreter::get(); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(format.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_loglog, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if (res) Py_DECREF(res); return res; } template bool plot(const std::vector& y, const std::string& format = "") { std::vector x(y.size()); for(size_t i=0; i bool plot(const std::vector& y, const std::map& keywords) { std::vector x(y.size()); for(size_t i=0; i bool stem(const std::vector& y, const std::string& format = "") { std::vector x(y.size()); for (size_t i = 0; i < x.size(); ++i) x.at(i) = i; return stem(x, y, format); } template void text(Numeric x, Numeric y, const std::string& s = "") { detail::_interpreter::get(); PyObject* args = PyTuple_New(3); PyTuple_SetItem(args, 0, PyFloat_FromDouble(x)); PyTuple_SetItem(args, 1, PyFloat_FromDouble(y)); PyTuple_SetItem(args, 2, PyString_FromString(s.c_str())); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_text, args); if(!res) throw std::runtime_error("Call to text() failed."); Py_DECREF(args); Py_DECREF(res); } inline void colorbar(PyObject* mappable = NULL, const std::map& keywords = {}) { if (mappable == NULL) throw std::runtime_error("Must call colorbar with PyObject* returned from an image, contour, surface, etc."); detail::_interpreter::get(); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, mappable); PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyFloat_FromDouble(it->second)); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_colorbar, args, kwargs); if(!res) throw std::runtime_error("Call to colorbar() failed."); Py_DECREF(args); Py_DECREF(kwargs); Py_DECREF(res); } inline long figure(long number = -1) { detail::_interpreter::get(); PyObject *res; if (number == -1) res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, detail::_interpreter::get().s_python_empty_tuple); else { assert(number > 0); // Make sure interpreter is initialised detail::_interpreter::get(); PyObject *args = PyTuple_New(1); PyTuple_SetItem(args, 0, PyLong_FromLong(number)); res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, args); Py_DECREF(args); } if(!res) throw std::runtime_error("Call to figure() failed."); PyObject* num = PyObject_GetAttrString(res, "number"); if (!num) throw std::runtime_error("Could not get number attribute of figure object"); const long figureNumber = PyLong_AsLong(num); Py_DECREF(num); Py_DECREF(res); return figureNumber; } inline bool fignum_exists(long number) { detail::_interpreter::get(); PyObject *args = PyTuple_New(1); PyTuple_SetItem(args, 0, PyLong_FromLong(number)); PyObject *res = PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, args); if(!res) throw std::runtime_error("Call to fignum_exists() failed."); bool ret = PyObject_IsTrue(res); Py_DECREF(res); Py_DECREF(args); return ret; } inline void figure_size(size_t w, size_t h) { detail::_interpreter::get(); const size_t dpi = 100; PyObject* size = PyTuple_New(2); PyTuple_SetItem(size, 0, PyFloat_FromDouble((double)w / dpi)); PyTuple_SetItem(size, 1, PyFloat_FromDouble((double)h / dpi)); PyObject* kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "figsize", size); PyDict_SetItemString(kwargs, "dpi", PyLong_FromSize_t(dpi)); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_figure, detail::_interpreter::get().s_python_empty_tuple, kwargs); Py_DECREF(kwargs); if(!res) throw std::runtime_error("Call to figure_size() failed."); Py_DECREF(res); } inline void legend() { detail::_interpreter::get(); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple); if(!res) throw std::runtime_error("Call to legend() failed."); Py_DECREF(res); } inline void legend(const std::map& keywords) { detail::_interpreter::get(); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple, kwargs); if(!res) throw std::runtime_error("Call to legend() failed."); Py_DECREF(kwargs); Py_DECREF(res); } template void ylim(Numeric left, Numeric right) { detail::_interpreter::get(); PyObject* list = PyList_New(2); PyList_SetItem(list, 0, PyFloat_FromDouble(left)); PyList_SetItem(list, 1, PyFloat_FromDouble(right)); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, list); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args); if(!res) throw std::runtime_error("Call to ylim() failed."); Py_DECREF(args); Py_DECREF(res); } template void xlim(Numeric left, Numeric right) { detail::_interpreter::get(); PyObject* list = PyList_New(2); PyList_SetItem(list, 0, PyFloat_FromDouble(left)); PyList_SetItem(list, 1, PyFloat_FromDouble(right)); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, list); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args); if(!res) throw std::runtime_error("Call to xlim() failed."); Py_DECREF(args); Py_DECREF(res); } inline double* xlim() { detail::_interpreter::get(); PyObject* args = PyTuple_New(0); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args); PyObject* left = PyTuple_GetItem(res,0); PyObject* right = PyTuple_GetItem(res,1); double* arr = new double[2]; arr[0] = PyFloat_AsDouble(left); arr[1] = PyFloat_AsDouble(right); if(!res) throw std::runtime_error("Call to xlim() failed."); Py_DECREF(res); return arr; } inline double* ylim() { detail::_interpreter::get(); PyObject* args = PyTuple_New(0); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args); PyObject* left = PyTuple_GetItem(res,0); PyObject* right = PyTuple_GetItem(res,1); double* arr = new double[2]; arr[0] = PyFloat_AsDouble(left); arr[1] = PyFloat_AsDouble(right); if(!res) throw std::runtime_error("Call to ylim() failed."); Py_DECREF(res); return arr; } template inline void xticks(const std::vector &ticks, const std::vector &labels = {}, const std::map& keywords = {}) { assert(labels.size() == 0 || ticks.size() == labels.size()); detail::_interpreter::get(); // using numpy array PyObject* ticksarray = detail::get_array(ticks); PyObject* args; if(labels.size() == 0) { // construct positional args args = PyTuple_New(1); PyTuple_SetItem(args, 0, ticksarray); } else { // make tuple of tick labels PyObject* labelstuple = PyTuple_New(labels.size()); for (size_t i = 0; i < labels.size(); i++) PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str())); // construct positional args args = PyTuple_New(2); PyTuple_SetItem(args, 0, ticksarray); PyTuple_SetItem(args, 1, labelstuple); } // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xticks, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(!res) throw std::runtime_error("Call to xticks() failed"); Py_DECREF(res); } template inline void xticks(const std::vector &ticks, const std::map& keywords) { xticks(ticks, {}, keywords); } template inline void yticks(const std::vector &ticks, const std::vector &labels = {}, const std::map& keywords = {}) { assert(labels.size() == 0 || ticks.size() == labels.size()); detail::_interpreter::get(); // using numpy array PyObject* ticksarray = detail::get_array(ticks); PyObject* args; if(labels.size() == 0) { // construct positional args args = PyTuple_New(1); PyTuple_SetItem(args, 0, ticksarray); } else { // make tuple of tick labels PyObject* labelstuple = PyTuple_New(labels.size()); for (size_t i = 0; i < labels.size(); i++) PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str())); // construct positional args args = PyTuple_New(2); PyTuple_SetItem(args, 0, ticksarray); PyTuple_SetItem(args, 1, labelstuple); } // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_yticks, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(!res) throw std::runtime_error("Call to yticks() failed"); Py_DECREF(res); } template inline void yticks(const std::vector &ticks, const std::map& keywords) { yticks(ticks, {}, keywords); } template inline void margins(Numeric margin) { // construct positional args PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin)); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args); if (!res) throw std::runtime_error("Call to margins() failed."); Py_DECREF(args); Py_DECREF(res); } template inline void margins(Numeric margin_x, Numeric margin_y) { // construct positional args PyObject* args = PyTuple_New(2); PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin_x)); PyTuple_SetItem(args, 1, PyFloat_FromDouble(margin_y)); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args); if (!res) throw std::runtime_error("Call to margins() failed."); Py_DECREF(args); Py_DECREF(res); } inline void tick_params(const std::map& keywords, const std::string axis = "both") { detail::_interpreter::get(); // construct positional args PyObject* args; args = PyTuple_New(1); PyTuple_SetItem(args, 0, PyString_FromString(axis.c_str())); // construct keyword args PyObject* kwargs = PyDict_New(); for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_tick_params, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if (!res) throw std::runtime_error("Call to tick_params() failed"); Py_DECREF(res); } inline void subplot(long nrows, long ncols, long plot_number) { detail::_interpreter::get(); // construct positional args PyObject* args = PyTuple_New(3); PyTuple_SetItem(args, 0, PyFloat_FromDouble(nrows)); PyTuple_SetItem(args, 1, PyFloat_FromDouble(ncols)); PyTuple_SetItem(args, 2, PyFloat_FromDouble(plot_number)); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot, args); if(!res) throw std::runtime_error("Call to subplot() failed."); Py_DECREF(args); Py_DECREF(res); } inline void subplot2grid(long nrows, long ncols, long rowid=0, long colid=0, long rowspan=1, long colspan=1) { detail::_interpreter::get(); PyObject* shape = PyTuple_New(2); PyTuple_SetItem(shape, 0, PyLong_FromLong(nrows)); PyTuple_SetItem(shape, 1, PyLong_FromLong(ncols)); PyObject* loc = PyTuple_New(2); PyTuple_SetItem(loc, 0, PyLong_FromLong(rowid)); PyTuple_SetItem(loc, 1, PyLong_FromLong(colid)); PyObject* args = PyTuple_New(4); PyTuple_SetItem(args, 0, shape); PyTuple_SetItem(args, 1, loc); PyTuple_SetItem(args, 2, PyLong_FromLong(rowspan)); PyTuple_SetItem(args, 3, PyLong_FromLong(colspan)); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot2grid, args); if(!res) throw std::runtime_error("Call to subplot2grid() failed."); Py_DECREF(shape); Py_DECREF(loc); Py_DECREF(args); Py_DECREF(res); } inline void title(const std::string &titlestr, const std::map &keywords = {}) { detail::_interpreter::get(); PyObject* pytitlestr = PyString_FromString(titlestr.c_str()); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, pytitlestr); PyObject* kwargs = PyDict_New(); for (auto it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_title, args, kwargs); if(!res) throw std::runtime_error("Call to title() failed."); Py_DECREF(args); Py_DECREF(kwargs); Py_DECREF(res); } inline void suptitle(const std::string &suptitlestr, const std::map &keywords = {}) { detail::_interpreter::get(); PyObject* pysuptitlestr = PyString_FromString(suptitlestr.c_str()); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, pysuptitlestr); PyObject* kwargs = PyDict_New(); for (auto it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_suptitle, args, kwargs); if(!res) throw std::runtime_error("Call to suptitle() failed."); Py_DECREF(args); Py_DECREF(kwargs); Py_DECREF(res); } inline void axis(const std::string &axisstr) { detail::_interpreter::get(); PyObject* str = PyString_FromString(axisstr.c_str()); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, str); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_axis, args); if(!res) throw std::runtime_error("Call to title() failed."); Py_DECREF(args); Py_DECREF(res); } inline void axvline(double x, double ymin = 0., double ymax = 1., const std::map& keywords = std::map()) { detail::_interpreter::get(); // construct positional args PyObject* args = PyTuple_New(3); PyTuple_SetItem(args, 0, PyFloat_FromDouble(x)); PyTuple_SetItem(args, 1, PyFloat_FromDouble(ymin)); PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymax)); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvline, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(res) Py_DECREF(res); } inline void axvspan(double xmin, double xmax, double ymin = 0., double ymax = 1., const std::map& keywords = std::map()) { // construct positional args PyObject* args = PyTuple_New(4); PyTuple_SetItem(args, 0, PyFloat_FromDouble(xmin)); PyTuple_SetItem(args, 1, PyFloat_FromDouble(xmax)); PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymin)); PyTuple_SetItem(args, 3, PyFloat_FromDouble(ymax)); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { if (it->first == "linewidth" || it->first == "alpha") PyDict_SetItemString(kwargs, it->first.c_str(), PyFloat_FromDouble(std::stod(it->second))); else PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvspan, args, kwargs); Py_DECREF(args); Py_DECREF(kwargs); if(res) Py_DECREF(res); } inline void xlabel(const std::string &str, const std::map &keywords = {}) { detail::_interpreter::get(); PyObject* pystr = PyString_FromString(str.c_str()); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, pystr); PyObject* kwargs = PyDict_New(); for (auto it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xlabel, args, kwargs); if(!res) throw std::runtime_error("Call to xlabel() failed."); Py_DECREF(args); Py_DECREF(kwargs); Py_DECREF(res); } inline void ylabel(const std::string &str, const std::map& keywords = {}) { detail::_interpreter::get(); PyObject* pystr = PyString_FromString(str.c_str()); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, pystr); PyObject* kwargs = PyDict_New(); for (auto it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_ylabel, args, kwargs); if(!res) throw std::runtime_error("Call to ylabel() failed."); Py_DECREF(args); Py_DECREF(kwargs); Py_DECREF(res); } inline void set_zlabel(const std::string &str, const std::map& keywords = {}) { detail::_interpreter::get(); // Same as with plot_surface: We lazily load the modules here the first time // this function is called because I'm not sure that we can assume "matplotlib // installed" implies "mpl_toolkits installed" on all platforms, and we don't // want to require it for people who don't need 3d plots. static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; if (!mpl_toolkitsmod) { PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } mpl_toolkitsmod = PyImport_Import(mpl_toolkits); Py_DECREF(mpl_toolkits); if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } axis3dmod = PyImport_Import(axis3d); Py_DECREF(axis3d); if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } } PyObject* pystr = PyString_FromString(str.c_str()); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, pystr); PyObject* kwargs = PyDict_New(); for (auto it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject *ax = PyObject_CallObject(detail::_interpreter::get().s_python_function_gca, detail::_interpreter::get().s_python_empty_tuple); if (!ax) throw std::runtime_error("Call to gca() failed."); Py_INCREF(ax); PyObject *zlabel = PyObject_GetAttrString(ax, "set_zlabel"); if (!zlabel) throw std::runtime_error("Attribute set_zlabel not found."); Py_INCREF(zlabel); PyObject *res = PyObject_Call(zlabel, args, kwargs); if (!res) throw std::runtime_error("Call to set_zlabel() failed."); Py_DECREF(zlabel); Py_DECREF(ax); Py_DECREF(args); Py_DECREF(kwargs); if (res) Py_DECREF(res); } inline void grid(bool flag) { detail::_interpreter::get(); PyObject* pyflag = flag ? Py_True : Py_False; Py_INCREF(pyflag); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, pyflag); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_grid, args); if(!res) throw std::runtime_error("Call to grid() failed."); Py_DECREF(args); Py_DECREF(res); } inline void show(const bool block = true) { detail::_interpreter::get(); PyObject* res; if(block) { res = PyObject_CallObject( detail::_interpreter::get().s_python_function_show, detail::_interpreter::get().s_python_empty_tuple); } else { PyObject *kwargs = PyDict_New(); PyDict_SetItemString(kwargs, "block", Py_False); res = PyObject_Call( detail::_interpreter::get().s_python_function_show, detail::_interpreter::get().s_python_empty_tuple, kwargs); Py_DECREF(kwargs); } if (!res) throw std::runtime_error("Call to show() failed."); Py_DECREF(res); } inline void close() { detail::_interpreter::get(); PyObject* res = PyObject_CallObject( detail::_interpreter::get().s_python_function_close, detail::_interpreter::get().s_python_empty_tuple); if (!res) throw std::runtime_error("Call to close() failed."); Py_DECREF(res); } inline void xkcd() { detail::_interpreter::get(); PyObject* res; PyObject *kwargs = PyDict_New(); res = PyObject_Call(detail::_interpreter::get().s_python_function_xkcd, detail::_interpreter::get().s_python_empty_tuple, kwargs); Py_DECREF(kwargs); if (!res) throw std::runtime_error("Call to show() failed."); Py_DECREF(res); } inline void draw() { detail::_interpreter::get(); PyObject* res = PyObject_CallObject( detail::_interpreter::get().s_python_function_draw, detail::_interpreter::get().s_python_empty_tuple); if (!res) throw std::runtime_error("Call to draw() failed."); Py_DECREF(res); } template inline void pause(Numeric interval) { detail::_interpreter::get(); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, PyFloat_FromDouble(interval)); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_pause, args); if(!res) throw std::runtime_error("Call to pause() failed."); Py_DECREF(args); Py_DECREF(res); } inline void save(const std::string& filename) { detail::_interpreter::get(); PyObject* pyfilename = PyString_FromString(filename.c_str()); PyObject* args = PyTuple_New(1); PyTuple_SetItem(args, 0, pyfilename); std::cout<<"args:"<> ginput(const int numClicks = 1, const std::map& keywords = {}) { detail::_interpreter::get(); PyObject *args = PyTuple_New(1); PyTuple_SetItem(args, 0, PyLong_FromLong(numClicks)); // construct keyword args PyObject* kwargs = PyDict_New(); for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); } PyObject* res = PyObject_Call( detail::_interpreter::get().s_python_function_ginput, args, kwargs); Py_DECREF(kwargs); Py_DECREF(args); if (!res) throw std::runtime_error("Call to ginput() failed."); const size_t len = PyList_Size(res); std::vector> out; out.reserve(len); for (size_t i = 0; i < len; i++) { PyObject *current = PyList_GetItem(res, i); std::array position; position[0] = PyFloat_AsDouble(PyTuple_GetItem(current, 0)); position[1] = PyFloat_AsDouble(PyTuple_GetItem(current, 1)); out.push_back(position); } Py_DECREF(res); return out; } // Actually, is there any reason not to call this automatically for every plot? inline void tight_layout() { detail::_interpreter::get(); PyObject *res = PyObject_CallObject( detail::_interpreter::get().s_python_function_tight_layout, detail::_interpreter::get().s_python_empty_tuple); if (!res) throw std::runtime_error("Call to tight_layout() failed."); Py_DECREF(res); } // Support for variadic plot() and initializer lists: namespace detail { template using is_function = typename std::is_function>>::type; template struct is_callable_impl; template struct is_callable_impl { typedef is_function type; }; // a non-object is callable iff it is a function template struct is_callable_impl { struct Fallback { void operator()(); }; struct Derived : T, Fallback { }; template struct Check; template static std::true_type test( ... ); // use a variadic function to make sure (1) it accepts everything and (2) its always the worst match template static std::false_type test( Check* ); public: typedef decltype(test(nullptr)) type; typedef decltype(&Fallback::operator()) dtype; static constexpr bool value = type::value; }; // an object is callable iff it defines operator() template struct is_callable { // dispatch to is_callable_impl or is_callable_impl depending on whether T is of class type or not typedef typename is_callable_impl::value, T>::type type; }; template struct plot_impl { }; template<> struct plot_impl { template bool operator()(const IterableX& x, const IterableY& y, const std::string& format) { // 2-phase lookup for distance, begin, end using std::distance; using std::begin; using std::end; auto xs = distance(begin(x), end(x)); auto ys = distance(begin(y), end(y)); assert(xs == ys && "x and y data must have the same number of elements!"); PyObject* xlist = PyList_New(xs); PyObject* ylist = PyList_New(ys); PyObject* pystring = PyString_FromString(format.c_str()); auto itx = begin(x), ity = begin(y); for(size_t i = 0; i < xs; ++i) { PyList_SetItem(xlist, i, PyFloat_FromDouble(*itx++)); PyList_SetItem(ylist, i, PyFloat_FromDouble(*ity++)); } PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xlist); PyTuple_SetItem(plot_args, 1, ylist); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args); Py_DECREF(plot_args); if(res) Py_DECREF(res); return res; } }; template<> struct plot_impl { template bool operator()(const Iterable& ticks, const Callable& f, const std::string& format) { if(begin(ticks) == end(ticks)) return true; // We could use additional meta-programming to deduce the correct element type of y, // but all values have to be convertible to double anyways std::vector y; for(auto x : ticks) y.push_back(f(x)); return plot_impl()(ticks,y,format); } }; } // end namespace detail // recursion stop for the above template bool plot() { return true; } template bool plot(const A& a, const B& b, const std::string& format, Args... args) { return detail::plot_impl::type>()(a,b,format) && plot(args...); } /* * This group of plot() functions is needed to support initializer lists, i.e. calling * plot( {1,2,3,4} ) */ inline bool plot(const std::vector& x, const std::vector& y, const std::string& format = "") { return plot(x,y,format); } inline bool plot(const std::vector& y, const std::string& format = "") { return plot(y,format); } inline bool plot(const std::vector& x, const std::vector& y, const std::map& keywords) { return plot(x,y,keywords); } /* * This class allows dynamic plots, ie changing the plotted data without clearing and re-plotting */ class Plot { public: // default initialization with plot label, some data and format template Plot(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") { detail::_interpreter::get(); assert(x.size() == y.size()); PyObject* kwargs = PyDict_New(); if(name != "") PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* pystring = PyString_FromString(format.c_str()); PyObject* plot_args = PyTuple_New(3); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyTuple_SetItem(plot_args, 2, pystring); PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); Py_DECREF(kwargs); Py_DECREF(plot_args); if(res) { line= PyList_GetItem(res, 0); if(line) set_data_fct = PyObject_GetAttrString(line,"set_data"); else Py_DECREF(line); Py_DECREF(res); } } // shorter initialization with name or format only // basically calls line, = plot([], []) Plot(const std::string& name = "", const std::string& format = "") : Plot(name, std::vector(), std::vector(), format) {} template bool update(const std::vector& x, const std::vector& y) { assert(x.size() == y.size()); if(set_data_fct) { PyObject* xarray = detail::get_array(x); PyObject* yarray = detail::get_array(y); PyObject* plot_args = PyTuple_New(2); PyTuple_SetItem(plot_args, 0, xarray); PyTuple_SetItem(plot_args, 1, yarray); PyObject* res = PyObject_CallObject(set_data_fct, plot_args); if (res) Py_DECREF(res); return res; } return false; } // clears the plot but keep it available bool clear() { return update(std::vector(), std::vector()); } // definitely remove this line void remove() { if(line) { auto remove_fct = PyObject_GetAttrString(line,"remove"); PyObject* args = PyTuple_New(0); PyObject* res = PyObject_CallObject(remove_fct, args); if (res) Py_DECREF(res); } decref(); } ~Plot() { decref(); } private: void decref() { if(line) Py_DECREF(line); if(set_data_fct) Py_DECREF(set_data_fct); } PyObject* line = nullptr; PyObject* set_data_fct = nullptr; }; } // end namespace matplotlibcpp ================================================ FILE: include/point_type.h ================================================ // // Created by hk on 12/8/22. // #pragma once #define PCL_NO_PRECOMPILE #include #include #include #ifndef LIO_POINT_TYPE_H #define LIO_POINT_TYPE_H struct ikdTree_PointType { PCL_ADD_POINT4D PCL_ADD_NORMAL4D; union { struct { float intensity; float curvature; float s_xx; float s_xy; }; float data_c[4]; }; // Eigen::Matrix3f S; // summation p * p^t // Eigen::Vector3f mean; // union { struct { float s_xz; float s_yy; float s_yz; float s_zz; }; float data_s[4]; }; union { struct { int num_hit; float mean_x; float mean_y; float mean_z; }; float data_num[4]; }; union { struct { float cov_xx; float cov_yy; float cov_zz; float cov_xy; }; float data_cov_1[4]; }; union { struct { float cov_xz; float cov_yz; float n_cov_xx; float n_cov_xy; }; float data_cov_2[4]; }; union { struct { float n_cov_xz; float n_cov_yz; float n_cov_zz; float n_cov_yy; }; float data_cov_3[4]; }; EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix3d getPointCovMatrix() const { Eigen::Matrix3d m; m(0, 0) = cov_xx; m(0, 1) = cov_xy; m(0, 2) = cov_xz; m(1, 0) = cov_xy; m(1, 1) = cov_yy; m(1, 2) = cov_yz; m(2, 0) = cov_xz; m(2, 1) = cov_yz; m(2, 2) = cov_zz; return m; } void getPointCovMatrix(Eigen::Matrix3d & m) const { m(0, 0) = cov_xx; m(0, 1) = cov_xy; m(0, 2) = cov_xz; m(1, 0) = cov_xy; m(1, 1) = cov_yy; m(1, 2) = cov_yz; m(2, 0) = cov_xz; m(2, 1) = cov_yz; m(2, 2) = cov_zz; } void getNormalCovMatrix(Eigen::Matrix3d & m) const { m(0, 0) = n_cov_xx; m(0, 1) = n_cov_xy; m(0, 2) = n_cov_xz; m(1, 0) = n_cov_xy; m(1, 1) = n_cov_yy; m(1, 2) = n_cov_yz; m(2, 0) = n_cov_xz; m(2, 1) = n_cov_yz; m(2, 2) = n_cov_zz; } void recordPointCovFromMatrix(const Eigen::Matrix3f & m) { cov_xx = m(0, 0); cov_xy = m(0, 1); cov_xz = m(0, 2); cov_yy = m(1, 1); cov_yz = m(1, 2); cov_zz = m(2, 2); } void recordNormalCovFromMatrix(const Eigen::Matrix3f & m) { n_cov_xx = m(0, 0); n_cov_xy = m(0, 1); n_cov_xz = m(0, 2); n_cov_yy = m(1, 1); n_cov_yz = m(1, 2); n_cov_zz = m(2, 2); } void updateCov(const ikdTree_PointType& p) { // inject small-scale to large-scale } ///code from VoxelMap void calcBodyCovBearingRange(const float range_cov, const float degree_cov) { // if z=0, error will occur in calcBodyCov. To be solved float z_tmp = z; if (z == 0) { z_tmp = 0.001; } float range = sqrt(x * x + y * y + z_tmp * z_tmp); float range_var = range_cov * range_cov; Eigen::Matrix2f direction_var; // (angle_cov^2, 0, // 0, angle_cov^2) direction_var << pow(sin(DEG2RAD(degree_cov)), 2), 0, 0, pow(sin(DEG2RAD(degree_cov)), 2); Eigen::Vector3f direction = this->getVector3fMap(); direction.normalize(); Eigen::Matrix3f direction_hat; // w^ direction_hat << 0, -direction(2), direction(1), direction(2), 0, -direction(0), -direction(1), direction(0), 0; //direction dot base_vector1 = 0 Eigen::Vector3f base_vector1(1, 1, -(direction(0) + direction(1)) / direction(2)); //(1, 1, -(x+y)/z), not unique base_vector1.normalize(); Eigen::Vector3f base_vector2 = base_vector1.cross(direction); base_vector2.normalize(); Eigen::Matrix N; //N = [base_vector1, base_vector2] N << base_vector1(0), base_vector2(0), base_vector1(1), base_vector2(1), base_vector1(2), base_vector2(2); Eigen::Matrix A = range * direction_hat * N; // (d * w^ * N )in the paper //cov = w * var_d * w^T + A * var_w * A^T Eigen::Matrix3f cov = direction * range_var * direction.transpose() + A * direction_var * A.transpose(); recordPointCovFromMatrix(cov); }; } EIGEN_ALIGN16; POINT_CLOUD_REGISTER_POINT_STRUCT (ikdTree_PointType, (float, x, x) (float, y, y) (float, z, z) (float, normal_x, normal_x) (float, normal_y, normal_y) (float, normal_z, normal_z) (float, intensity, intensity) (float, curvature, curvature) (float, s_xx, s_xx) (float, s_xy, s_xy) (float, s_xz, s_xz) (float, s_yy, s_yy) (float, s_yz, s_yz) (float, s_zz, s_zz) (int, num_hit, num_hit) (float, mean_x, mean_x) (float, mean_y, mean_y) (float, mean_z, mean_z) ) // Velodyne struct PointXYZIRT { PCL_ADD_POINT4D PCL_ADD_INTENSITY; uint16_t ring; float time; EIGEN_MAKE_ALIGNED_OPERATOR_NEW } EIGEN_ALIGN16; POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZIRT, (float, x, x) (float, y, y) (float, z, z) (float, intensity, intensity) (uint16_t, ring, ring) (float, time, time) ) // Ouster struct ousterPointXYZIRT { PCL_ADD_POINT4D; PCL_ADD_INTENSITY; uint32_t t; uint16_t reflectivity; uint8_t ring; uint16_t noise; uint32_t range; EIGEN_MAKE_ALIGNED_OPERATOR_NEW }EIGEN_ALIGN16; POINT_CLOUD_REGISTER_POINT_STRUCT(ousterPointXYZIRT, (float, x, x) (float, y, y) (float, z, z) (float, intensity, intensity) (uint32_t, t, t) (uint16_t, reflectivity, reflectivity) (uint8_t, ring, ring) (uint16_t, noise, noise) (uint32_t, range, range) ) #endif //LIO_POINT_TYPE_H ================================================ FILE: include/so3_math.h ================================================ #ifndef SO3_MATH_H #define SO3_MATH_H #include #include #define SKEW_SYM_MATRX(v) 0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0 template Eigen::Matrix skew_sym_mat(const Eigen::Matrix &v) { Eigen::Matrix skew_sym_mat; skew_sym_mat<<0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0; return skew_sym_mat; } template Eigen::Matrix Exp(const Eigen::Matrix &&ang) { T ang_norm = ang.norm(); Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); if (ang_norm > 0.0000001) { Eigen::Matrix r_axis = ang / ang_norm; Eigen::Matrix K; K << SKEW_SYM_MATRX(r_axis); /// Roderigous Tranformation return Eye3 + std::sin(ang_norm) * K + (1.0 - std::cos(ang_norm)) * K * K; } else { return Eye3; } } template Eigen::Matrix Exp(const Eigen::Matrix &ang_vel, const Ts &dt) { T ang_vel_norm = ang_vel.norm(); Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); if (ang_vel_norm > 0.0000001) { Eigen::Matrix r_axis = ang_vel / ang_vel_norm; Eigen::Matrix K; K << SKEW_SYM_MATRX(r_axis); T r_ang = ang_vel_norm * dt; /// Roderigous Tranformation return Eye3 + std::sin(r_ang) * K + (1.0 - std::cos(r_ang)) * K * K; } else { return Eye3; } } template Eigen::Matrix Exp(const T &v1, const T &v2, const T &v3) { T &&norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); if (norm > 0.00001) { T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; Eigen::Matrix K; K << SKEW_SYM_MATRX(r_ang); /// Roderigous Tranformation return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; } else { return Eye3; } } /* Logrithm of a Rotation Matrix */ template Eigen::Matrix Log(const Eigen::Matrix &R) { T theta = (R.trace() > 3.0 - 1e-6) ? 0.0 : std::acos(0.5 * (R.trace() - 1)); Eigen::Matrix K(R(2,1) - R(1,2), R(0,2) - R(2,0), R(1,0) - R(0,1)); return (std::abs(theta) < 0.001) ? (0.5 * K) : (0.5 * theta / std::sin(theta) * K); } template Eigen::Matrix RotMtoEuler(const Eigen::Matrix &rot) { T sy = sqrt(rot(0,0)*rot(0,0) + rot(1,0)*rot(1,0)); bool singular = sy < 1e-6; T x, y, z; if(!singular) { x = atan2(rot(2, 1), rot(2, 2)); y = atan2(-rot(2, 0), sy); z = atan2(rot(1, 0), rot(0, 0)); } else { x = atan2(-rot(1, 2), rot(1, 1)); y = atan2(-rot(2, 0), sy); z = 0; } Eigen::Matrix ang(x, y, z); return ang; } #endif ================================================ FILE: include/use-ikfom.hpp ================================================ #ifndef USE_IKFOM_H #define USE_IKFOM_H #include typedef MTK::vect<3, double> vect3; typedef MTK::SO3 SO3; typedef MTK::S2 S2; typedef MTK::vect<1, double> vect1; typedef MTK::vect<2, double> vect2; MTK_BUILD_MANIFOLD(state_ikfom, ((vect3, pos)) ((SO3, rot)) ((SO3, offset_R_L_I)) ((vect3, offset_T_L_I)) ((vect3, vel)) ((vect3, bg)) ((vect3, ba)) ((S2, grav)) ); MTK_BUILD_MANIFOLD(input_ikfom, ((vect3, acc)) ((vect3, gyro)) ); MTK_BUILD_MANIFOLD(process_noise_ikfom, ((vect3, ng)) ((vect3, na)) ((vect3, nbg)) ((vect3, nba)) ); MTK::get_cov::type process_noise_cov() { MTK::get_cov::type cov = MTK::get_cov::type::Zero(); MTK::setDiagonal(cov, &process_noise_ikfom::ng, 0.0001);// 0.03 MTK::setDiagonal(cov, &process_noise_ikfom::na, 0.0001); // *dt 0.01 0.01 * dt * dt 0.05 MTK::setDiagonal(cov, &process_noise_ikfom::nbg, 0.00001); // *dt 0.00001 0.00001 * dt *dt 0.3 //0.001 0.0001 0.01 MTK::setDiagonal(cov, &process_noise_ikfom::nba, 0.00001); //0.001 0.05 0.0001/out 0.01 return cov; } //double L_offset_to_I[3] = {0.04165, 0.02326, -0.0284}; // Avia //vect3 Lidar_offset_to_IMU(L_offset_to_I, 3); Eigen::Matrix get_f(state_ikfom &s, const input_ikfom &in) { Eigen::Matrix res = Eigen::Matrix::Zero(); vect3 omega; in.gyro.boxminus(omega, s.bg); vect3 a_inertial = s.rot * (in.acc-s.ba); for(int i = 0; i < 3; i++ ){ res(i) = s.vel[i]; res(i + 3) = omega[i]; res(i + 12) = a_inertial[i] + s.grav[i]; } return res; } Eigen::Matrix df_dx(state_ikfom &s, const input_ikfom &in) { Eigen::Matrix cov = Eigen::Matrix::Zero(); cov.template block<3, 3>(0, 12) = Eigen::Matrix3d::Identity(); vect3 acc_; in.acc.boxminus(acc_, s.ba); vect3 omega; in.gyro.boxminus(omega, s.bg); cov.template block<3, 3>(12, 3) = -s.rot.toRotationMatrix()*MTK::hat(acc_); cov.template block<3, 3>(12, 18) = -s.rot.toRotationMatrix(); Eigen::Matrix vec = Eigen::Matrix::Zero(); Eigen::Matrix grav_matrix; s.S2_Mx(grav_matrix, vec, 21); cov.template block<3, 2>(12, 21) = grav_matrix; cov.template block<3, 3>(3, 15) = -Eigen::Matrix3d::Identity(); return cov; } Eigen::Matrix df_dw(state_ikfom &s, const input_ikfom &in) { Eigen::Matrix cov = Eigen::Matrix::Zero(); cov.template block<3, 3>(12, 3) = -s.rot.toRotationMatrix(); cov.template block<3, 3>(3, 0) = -Eigen::Matrix3d::Identity(); cov.template block<3, 3>(15, 6) = Eigen::Matrix3d::Identity(); cov.template block<3, 3>(18, 9) = Eigen::Matrix3d::Identity(); return cov; } vect3 SO3ToEuler(const SO3 &orient) { Eigen::Matrix _ang; Eigen::Vector4d q_data = orient.coeffs().transpose(); //scalar w=orient.coeffs[3], x=orient.coeffs[0], y=orient.coeffs[1], z=orient.coeffs[2]; double sqw = q_data[3]*q_data[3]; double sqx = q_data[0]*q_data[0]; double sqy = q_data[1]*q_data[1]; double sqz = q_data[2]*q_data[2]; double unit = sqx + sqy + sqz + sqw; // if normalized is one, otherwise is correction factor double test = q_data[3]*q_data[1] - q_data[2]*q_data[0]; if (test > 0.49999*unit) { // singularity at north pole _ang << 2 * std::atan2(q_data[0], q_data[3]), M_PI/2, 0; double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; vect3 euler_ang(temp, 3); return euler_ang; } if (test < -0.49999*unit) { // singularity at south pole _ang << -2 * std::atan2(q_data[0], q_data[3]), -M_PI/2, 0; double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; vect3 euler_ang(temp, 3); return euler_ang; } _ang << std::atan2(2*q_data[0]*q_data[3]+2*q_data[1]*q_data[2] , -sqx - sqy + sqz + sqw), std::asin (2*test/unit), std::atan2(2*q_data[2]*q_data[3]+2*q_data[1]*q_data[0] , sqx - sqy - sqz + sqw); double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; vect3 euler_ang(temp, 3); // euler_ang[0] = roll, euler_ang[1] = pitch, euler_ang[2] = yaw return euler_ang; } #endif ================================================ FILE: include/voxel_map_util.hpp ================================================ #ifndef VOXEL_MAP_UTIL_HPP #define VOXEL_MAP_UTIL_HPP //#include "common_lib.h" #include "omp.h" #include #include #include //#include #include #include #include #include #include #include #include #include #include #include #include "ikd-Tree/ikd_Tree.h" using std::hash; using std::vector; using std::unordered_map; using std::cout; using std::printf; using std::mutex; #define HASH_P 116101 #define MAX_N 10000000000 static int plane_id = 0; // a point to plane matching structure typedef struct ptpl { Eigen::Vector3d point; Eigen::Vector3d point_world; Eigen::Vector3d normal; Eigen::Vector3d center; Eigen::Matrix plane_cov; double d; int layer; Eigen::Matrix3d cov_lidar; } ptpl; // 3D point with covariance typedef struct pointWithCov { Eigen::Vector3d point; Eigen::Vector3d point_world; Eigen::Matrix3d cov; Eigen::Matrix3d cov_lidar; } pointWithCov; typedef struct Plane { Eigen::Vector3f center; Eigen::Vector3f normal; Eigen::Vector3f y_normal; //evalsMid Eigen::Vector3f x_normal; //evalsMax Eigen::Matrix3f covariance; Eigen::Matrix plane_cov; //cov (n, q), q = mean_p float radius = 0; // sqrt(evalsReal(evalsMax)) float min_eigen_value = 1; float mid_eigen_value = 1; float max_eigen_value = 1; float d = 0; // plane: n * p + d = 0 int points_size = 0; bool is_plane = false; bool is_init = false; int id; // is_update and last_update_points_size are only for publish plane bool is_update = false; int last_update_points_size = 0; bool update_enable = true; } Plane; class VoxelInfo; class VOXEL_LOC { public: int64_t x, y, z; VOXEL_LOC(int64_t vx = 0, int64_t vy = 0, int64_t vz = 0) : x(vx), y(vy), z(vz) {} VoxelInfo* info_ptr; bool operator==(const VOXEL_LOC &other) const { return (x == other.x && y == other.y && z == other.z); } }; // Hash value namespace std { template<> struct hash { int64_t operator()(const VOXEL_LOC &s) const { using std::hash; using std::size_t; return ((((s.z) * HASH_P) % MAX_N + (s.y)) * HASH_P) % MAX_N + (s.x); } }; } // namespace std class OctoTree { public: vector temp_points_; // all points in an octo tree vector new_points_; // new points in an octo tree Plane *plane_ptr_; int max_layer_; bool indoor_mode_; int layer_; int octo_state_; // 0 is end of tree, 1 is not OctoTree *leaves_[8]; double voxel_center_[3]; // x, y, z vector layer_point_size_; float quater_length_; float planer_threshold_; int max_plane_update_threshold_; int update_size_threshold_; int all_points_num_; int new_points_num_; int max_points_size_; int max_cov_points_size_; bool init_octo_; bool update_cov_enable_; bool update_enable_; OctoTree(int max_layer, int layer, vector layer_point_size, int max_point_size, int max_cov_points_size, float planer_threshold) : max_layer_(max_layer), layer_(layer), layer_point_size_(layer_point_size), max_points_size_(max_point_size), max_cov_points_size_(max_cov_points_size), planer_threshold_(planer_threshold) { temp_points_.clear(); octo_state_ = 0; new_points_num_ = 0; all_points_num_ = 0; // when new points num > 5, do a update update_size_threshold_ = 5; init_octo_ = false; update_enable_ = true; update_cov_enable_ = true; max_plane_update_threshold_ = layer_point_size_[layer_]; for (int i = 0; i < 8; i++) { leaves_[i] = nullptr; } plane_ptr_ = new Plane; } }; #endif ================================================ FILE: launch/gdb_debug_example.launch ================================================ ================================================ FILE: launch/mapping_m2dgr.launch ================================================ ================================================ FILE: launch/mapping_ouster64.launch ================================================ ================================================ FILE: launch/mapping_rs.launch ================================================ ================================================ FILE: launch/mapping_velodyne.launch ================================================ ================================================ FILE: launch/mapping_viral.launch ================================================ ================================================ FILE: msg/Pose6D.msg ================================================ # the preintegrated Lidar states at the time of IMU measurements in a frame float64 offset_time # the offset time of IMU measurement w.r.t the first lidar point float64[3] acc # the preintegrated total acceleration (global frame) at the Lidar origin float64[3] gyr # the unbiased angular velocity (body frame) at the Lidar origin float64[3] vel # the preintegrated velocity (global frame) at the Lidar origin float64[3] pos # the preintegrated position (global frame) at the Lidar origin float64[9] rot # the preintegrated rotation (global frame) at the Lidar origin ================================================ FILE: package.xml ================================================ log_lio 0.0.0 This is a modified version of LOAM which is original algorithm is described in the following paper: J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time. Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014. claydergc BSD Ji Zhang catkin geometry_msgs nav_msgs roscpp rospy std_msgs sensor_msgs tf pcl_ros livox_ros_driver message_generation geometry_msgs nav_msgs sensor_msgs roscpp rospy std_msgs tf pcl_ros livox_ros_driver message_runtime rostest rosbag ================================================ FILE: src/IMU_Processing.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 "use-ikfom.hpp" /// *************Preconfiguration #define MAX_INI_COUNT (10) const bool time_list(PointType &x, PointType &y) {return (x.curvature < y.curvature);}; /// *************IMU Process and undistortion class ImuProcess { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW ImuProcess(); ~ImuProcess(); void Reset(); void Reset(double start_timestamp, const sensor_msgs::ImuConstPtr &lastimu); void set_extrinsic(const V3D &transl, const M3D &rot); void set_extrinsic(const V3D &transl); void set_extrinsic(const MD(4,4) &T); void set_gyr_cov(const V3D &scaler); void set_acc_cov(const V3D &scaler); void set_gyr_bias_cov(const V3D &b_g); void set_acc_bias_cov(const V3D &b_a); Eigen::Matrix Q; void Process(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI::Ptr pcl_un_); ofstream fout_imu; V3D cov_acc; //todo V3D cov_gyr; V3D cov_acc_scale; V3D cov_gyr_scale; V3D cov_bias_gyr; V3D cov_bias_acc; double first_lidar_time; private: void IMU_init(const MeasureGroup &meas, esekfom::esekf &kf_state, int &N); void UndistortPcl(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI &pcl_in_out); PointCloudXYZI::Ptr cur_pcl_un_; sensor_msgs::ImuConstPtr last_imu_; deque v_imu_; vector IMUpose; vector v_rot_pcl_; M3D Lidar_R_wrt_IMU; V3D Lidar_T_wrt_IMU; V3D mean_acc; V3D mean_gyr; V3D angvel_last; V3D acc_s_last; double start_timestamp_; double last_lidar_end_time_; int init_iter_num = 1; bool b_first_frame_ = true; bool imu_need_init_ = true; }; ImuProcess::ImuProcess() : b_first_frame_(true), imu_need_init_(true), start_timestamp_(-1) { init_iter_num = 1; Q = process_noise_cov(); cov_acc = V3D(0.1, 0.1, 0.1); cov_gyr = V3D(0.1, 0.1, 0.1); cov_bias_gyr = V3D(0.0001, 0.0001, 0.0001); cov_bias_acc = V3D(0.0001, 0.0001, 0.0001); mean_acc = V3D(0, 0, -1.0); mean_gyr = V3D(0, 0, 0); angvel_last = Zero3d; Lidar_T_wrt_IMU = Zero3d; Lidar_R_wrt_IMU = Eye3d; last_imu_.reset(new sensor_msgs::Imu()); } ImuProcess::~ImuProcess() {} void ImuProcess::Reset() { // ROS_WARN("Reset ImuProcess"); mean_acc = V3D(0, 0, -1.0); mean_gyr = V3D(0, 0, 0); angvel_last = Zero3d; imu_need_init_ = true; start_timestamp_ = -1; init_iter_num = 1; v_imu_.clear(); IMUpose.clear(); last_imu_.reset(new sensor_msgs::Imu()); cur_pcl_un_.reset(new PointCloudXYZI()); } void ImuProcess::set_extrinsic(const MD(4,4) &T) { Lidar_T_wrt_IMU = T.block<3,1>(0,3); Lidar_R_wrt_IMU = T.block<3,3>(0,0); } void ImuProcess::set_extrinsic(const V3D &transl) { Lidar_T_wrt_IMU = transl; Lidar_R_wrt_IMU.setIdentity(); } void ImuProcess::set_extrinsic(const V3D &transl, const M3D &rot) { Lidar_T_wrt_IMU = transl; Lidar_R_wrt_IMU = rot; } void ImuProcess::set_gyr_cov(const V3D &scaler) { cov_gyr_scale = scaler; } void ImuProcess::set_acc_cov(const V3D &scaler) { cov_acc_scale = scaler; } void ImuProcess::set_gyr_bias_cov(const V3D &b_g) { cov_bias_gyr = b_g; } void ImuProcess::set_acc_bias_cov(const V3D &b_a) { cov_bias_acc = b_a; } void ImuProcess::IMU_init(const MeasureGroup &meas, esekfom::esekf &kf_state, int &N) { /** 1. initializing the gravity, gyro bias, acc and gyro covariance ** 2. normalize the acceleration measurenments to unit gravity **/ V3D cur_acc, cur_gyr; if (b_first_frame_) { Reset(); N = 1; b_first_frame_ = false; const auto &imu_acc = meas.imu.front()->linear_acceleration; const auto &gyr_acc = meas.imu.front()->angular_velocity; mean_acc << imu_acc.x, imu_acc.y, imu_acc.z; mean_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; first_lidar_time = meas.lidar_beg_time; } for (const auto &imu : meas.imu) { const auto &imu_acc = imu->linear_acceleration; const auto &gyr_acc = imu->angular_velocity; cur_acc << imu_acc.x, imu_acc.y, imu_acc.z; cur_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; mean_acc += (cur_acc - mean_acc) / N; mean_gyr += (cur_gyr - mean_gyr) / N; cov_acc = cov_acc * (N - 1.0) / N + (cur_acc - mean_acc).cwiseProduct(cur_acc - mean_acc) * (N - 1.0) / (N * N); cov_gyr = cov_gyr * (N - 1.0) / N + (cur_gyr - mean_gyr).cwiseProduct(cur_gyr - mean_gyr) * (N - 1.0) / (N * N); // cout<<"acc norm: "<::cov init_P = kf_state.get_P(); init_P.setIdentity(); init_P(6,6) = init_P(7,7) = init_P(8,8) = 0.00001; init_P(9,9) = init_P(10,10) = init_P(11,11) = 0.00001; init_P(15,15) = init_P(16,16) = init_P(17,17) = 0.0001; init_P(18,18) = init_P(19,19) = init_P(20,20) = 0.001; init_P(21,21) = init_P(22,22) = 0.00001; kf_state.change_P(init_P); last_imu_ = meas.imu.back(); } void ImuProcess::UndistortPcl(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI &pcl_out) { /*** add the imu of the last frame-tail to the of current frame-head ***/ auto v_imu = meas.imu; v_imu.push_front(last_imu_); const double &imu_beg_time = v_imu.front()->header.stamp.toSec(); const double &imu_end_time = v_imu.back()->header.stamp.toSec(); const double &pcl_beg_time = meas.lidar_beg_time; const double &pcl_end_time = meas.lidar_end_time; /*** sort point clouds by offset time ***/ pcl_out = *(meas.lidar); sort(pcl_out.points.begin(), pcl_out.points.end(), time_list); // cout<<"[ IMU Process ]: Process lidar from "<header.stamp.toSec() < last_lidar_end_time_) continue; angvel_avr<<0.5 * (head->angular_velocity.x + tail->angular_velocity.x), 0.5 * (head->angular_velocity.y + tail->angular_velocity.y), 0.5 * (head->angular_velocity.z + tail->angular_velocity.z); acc_avr <<0.5 * (head->linear_acceleration.x + tail->linear_acceleration.x), 0.5 * (head->linear_acceleration.y + tail->linear_acceleration.y), 0.5 * (head->linear_acceleration.z + tail->linear_acceleration.z); // fout_imu << setw(10) << head->header.stamp.toSec() - first_lidar_time << " " << angvel_avr.transpose() << " " << acc_avr.transpose() << endl; acc_avr = acc_avr * G_m_s2 / mean_acc.norm(); // - state_inout.ba; if(head->header.stamp.toSec() < last_lidar_end_time_) { dt = tail->header.stamp.toSec() - last_lidar_end_time_; // dt = tail->header.stamp.toSec() - pcl_beg_time; } else { dt = tail->header.stamp.toSec() - head->header.stamp.toSec(); } in.acc = acc_avr; in.gyro = angvel_avr; Q.block<3, 3>(0, 0).diagonal() = cov_gyr; Q.block<3, 3>(3, 3).diagonal() = cov_acc; Q.block<3, 3>(6, 6).diagonal() = cov_bias_gyr; Q.block<3, 3>(9, 9).diagonal() = cov_bias_acc; kf_state.predict(dt, Q, in); /* save the poses at each IMU measurements */ imu_state = kf_state.get_x(); angvel_last = angvel_avr - imu_state.bg; acc_s_last = imu_state.rot * (acc_avr - imu_state.ba); for(int i=0; i<3; i++) { acc_s_last[i] += imu_state.grav[i]; } double &&offs_t = tail->header.stamp.toSec() - pcl_beg_time; IMUpose.push_back(set_pose6d(offs_t, acc_s_last, angvel_last, imu_state.vel, imu_state.pos, imu_state.rot.toRotationMatrix())); } /*** calculated the pos and attitude prediction at the frame-end ***/ double note = pcl_end_time > imu_end_time ? 1.0 : -1.0; dt = note * (pcl_end_time - imu_end_time); kf_state.predict(dt, Q, in); imu_state = kf_state.get_x(); last_imu_ = meas.imu.back(); last_lidar_end_time_ = pcl_end_time; /*** undistort each lidar point (backward propagation) ***/ if (pcl_out.points.begin() == pcl_out.points.end()) return; auto it_pcl = pcl_out.points.end() - 1; for (auto it_kp = IMUpose.end() - 1; it_kp != IMUpose.begin(); it_kp--) { auto head = it_kp - 1; auto tail = it_kp; R_imu<rot); // cout<<"head imu acc: "<vel); pos_imu<pos); acc_imu<acc); angvel_avr<gyr); for(; it_pcl->curvature / double(1000) > head->offset_time; it_pcl --) { dt = it_pcl->curvature / double(1000) - head->offset_time; /* Transform to the 'end' frame, using only the rotation * Note: Compensation direction is INVERSE of Frame's moving direction * So if we want to compensate a point at timestamp-i to the frame-e * P_compensate = R_imu_e ^ T * (R_i * P_i + T_ei) where T_ei is represented in global frame */ M3D R_i(R_imu * Exp(angvel_avr, dt)); V3D P_i(it_pcl->x, it_pcl->y, it_pcl->z); V3D T_ei(pos_imu + vel_imu * dt + 0.5 * acc_imu * dt * dt - imu_state.pos); V3D P_compensate = imu_state.offset_R_L_I.conjugate() * (imu_state.rot.conjugate() * (R_i * (imu_state.offset_R_L_I * P_i + imu_state.offset_T_L_I) + T_ei) - imu_state.offset_T_L_I);// not accurate! V3D normal_i(it_pcl->normal_x, it_pcl->normal_y, it_pcl->normal_z); V3D normal_compensate = imu_state.offset_R_L_I.conjugate() * imu_state.rot.conjugate() * R_i * imu_state.offset_R_L_I * normal_i; // save Undistorted points and their rotation it_pcl->x = P_compensate(0); it_pcl->y = P_compensate(1); it_pcl->z = P_compensate(2); it_pcl->normal_x = normal_compensate(0); it_pcl->normal_y = normal_compensate(1); it_pcl->normal_z = normal_compensate(2); if (it_pcl == pcl_out.points.begin()) break; } } } void ImuProcess::Process(const MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI::Ptr cur_pcl_un_) { double t1,t2,t3; t1 = omp_get_wtime(); if(meas.imu.empty()) {return;}; ROS_ASSERT(meas.lidar != nullptr); if (imu_need_init_) { /// The very first lidar frame IMU_init(meas, kf_state, init_iter_num); imu_need_init_ = true; last_imu_ = meas.imu.back(); state_ikfom imu_state = kf_state.get_x(); if (init_iter_num > MAX_INI_COUNT) { cov_acc *= pow(G_m_s2 / mean_acc.norm(), 2); imu_need_init_ = false; cov_acc = cov_acc_scale; cov_gyr = cov_gyr_scale; ROS_INFO("IMU Initial Done"); // ROS_INFO("IMU Initial Done: Gravity: %.4f %.4f %.4f %.4f; state.bias_g: %.4f %.4f %.4f; acc covarience: %.8f %.8f %.8f; gry covarience: %.8f %.8f %.8f",\ // imu_state.grav[0], imu_state.grav[1], imu_state.grav[2], mean_acc.norm(), cov_bias_gyr[0], cov_bias_gyr[1], cov_bias_gyr[2], cov_acc[0], cov_acc[1], cov_acc[2], cov_gyr[0], cov_gyr[1], cov_gyr[2]); fout_imu.open(DEBUG_FILE_DIR("imu.txt"),ios::out); } return; } UndistortPcl(meas, kf_state, *cur_pcl_un_); t2 = omp_get_wtime(); t3 = omp_get_wtime(); // cout<<"[ IMU Process ]: Time: "< #include #include extern float mid2min, planarity, angle_threshold; extern int num_surfel, surfel_points_min, surfel_points_max; extern bool check_normal; //const int large_scale_flag = -2; bool cloudSurfel(const vector & voxels, Matrix &pca_result, V3F& centroid, const float& threshold) { float s_xx= 0.0, s_xy = 0.0, s_xz = 0.0, s_yy = 0.0, s_yz = 0.0, s_zz = 0.0; float mean_x = 0.0, mean_y = 0.0, mean_z = 0.0; float num_points = 0.0; // centroid = Eigen::Vector3f (0, 0, 0); Eigen::Vector3f mean_normal(0, 0, 0); vector valid_mean_xyz(voxels.size()); int num_valid = 0; for (int i = 0; i < (int) voxels.size(); ++i) { const auto & v = voxels[i]; if (!v) continue; // lock_guard lock(v->updating_mutex_lock); if (v->num_points >= 0 && v->num_points < surfel_points_min) // not enough points continue; float n = (float)abs(v->num_points); num_points += n; // const PointType & p = cloud[i]; s_xx += v->s_xx; s_xy += v->s_xy; s_xz += v->s_xz; s_yy += v->s_yy; s_yz += v->s_yz; s_zz += v->s_zz; mean_x += n * v->mean_x; mean_y += n * v->mean_y; mean_z += n * v->mean_z; mean_normal += n * v->normal; valid_mean_xyz[num_valid](0) = v->mean_x; valid_mean_xyz[num_valid](1) = v->mean_y; valid_mean_xyz[num_valid](2) = v->mean_z; ++num_valid; } // todo if (num_points < surfel_points_min * NUM_MATCH_POINTS * 0.5) return false; mean_x /= num_points; mean_y /= num_points; mean_z /= num_points; centroid(0) = mean_x; centroid(1) = mean_y; centroid(2) = mean_z; mean_normal = mean_normal / num_points; mean_normal.normalize(); // valid_mean_xyz.resize(num_valid); // ROS_INFO("mean xyz %f %f %f", mean_x, mean_y, mean_z); Eigen::Matrix3f cov; cov(0, 0) = s_xx / num_points - mean_x * mean_x; cov(1, 1) = s_yy / num_points - mean_y * mean_y; cov(2, 2) = s_zz / num_points - mean_z * mean_z; cov(0, 1) = s_xy / num_points - mean_x * mean_y; cov(1, 0) = cov(0, 1); cov(0, 2) = s_xz / num_points - mean_x * mean_z; cov(2, 0) = cov(0, 2); cov(1, 2) = s_yz / num_points - mean_y * mean_z; cov(2, 1) = cov(1, 2); // Compute the product cloud_demean * cloud_demean^T // Eigen::Matrix3f alpha = static_cast (cloud_demean.topRows<3> () * cloud_demean.topRows<3> ().transpose ()); Eigen::Matrix3f eigenvectors_; Eigen::Vector3f eigenvalues_; // Compute eigen vectors and values Eigen::SelfAdjointEigenSolver evd (cov); // Organize eigenvectors and eigenvalues in ascendent order // lambda 1 > lambda 2 > lambda 3 for (int i = 0; i < 3; ++i) { eigenvalues_[i] = evd.eigenvalues () [2-i]; eigenvectors_.col (i) = evd.eigenvectors ().col (2-i); } // float cos = eigenvectors_.col (2).dot(voxels[0]->normal); if (eigenvalues_[0] == eigenvalues_[2] || eigenvalues_[0] == 0.0) return false; float pho = 2.0 * (eigenvalues_[1] - eigenvalues_[2]) / (eigenvalues_[0] + eigenvalues_[1] + eigenvalues_[2]); float mid_min = eigenvalues_[1] / eigenvalues_[2]; // n * p + d = 0; Eigen::Vector3f normal = eigenvectors_.col (2); if (mean_normal.dot(normal) < 0) normal *= -1; pca_result.head(3) = normal; pca_result(3) = -centroid.dot(normal); // d for (int j = 0; j < num_valid; j++) { // while (voxels[j]->flag_updating) /// !!!caution // usleep(2); // pthread_mutex_lock(&voxels[j]->updating_mutex_lock); if (fabs(normal.dot(valid_mean_xyz[j]) + pca_result(3)) > threshold) { return false; } // pthread_mutex_lock(&voxels[j]->updating_mutex_lock); } return true; } ///code from VoxelMap void calcBodyCov(Eigen::Vector3d &pb, const float range_inc, const float degree_inc, Eigen::Matrix3d &cov) { // if z=0, error will occur in calcBodyCov. To be solved float z_tmp = pb[2]; if (z_tmp == 0) { z_tmp = 0.001; } float range = sqrt(pb[0] * pb[0] + pb[1] * pb[1] + z_tmp * z_tmp); // float range = sqrt(pb[0] * pb[0] + pb[1] * pb[1] + pb[2] * pb[2]); float range_var = range_inc * range_inc; Eigen::Matrix2d direction_var; // (angle_cov^2, 0, // 0, angle_cov^2) direction_var << pow(sin(DEG2RAD(degree_inc)), 2), 0, 0, pow(sin(DEG2RAD(degree_inc)), 2); Eigen::Vector3d direction(pb); direction.normalize(); Eigen::Matrix3d direction_hat; // w^ direction_hat << 0, -direction(2), direction(1), direction(2), 0, -direction(0), -direction(1), direction(0), 0; //direction dot base_vector1 = 0 Eigen::Vector3d base_vector1(1, 1, -(direction(0) + direction(1)) / direction(2)); //(1, 1, -(x+y)/z), not unique base_vector1.normalize(); Eigen::Vector3d base_vector2 = base_vector1.cross(direction); base_vector2.normalize(); Eigen::Matrix N; //N = [base_vector1, base_vector2] N << base_vector1(0), base_vector2(0), base_vector1(1), base_vector2(1), base_vector1(2), base_vector2(2); Eigen::Matrix A = range * direction_hat * N; // (d * w^ * N )in the paper //cov = w * var_d * w^T + A * var_w * A^T cov = direction * range_var * direction.transpose() + A * direction_var * A.transpose(); } void calcBodyCov(PointType &pb, const float range_cov, const float degree_cov, Eigen::Matrix3f &cov) { // if z=0, error will occur in calcBodyCov. To be solved float z_tmp = pb.z; if (z_tmp == 0) { z_tmp = 0.001; } float range = sqrt(pb.x* pb.x + pb.y * pb.y + z_tmp * z_tmp); // float range = sqrt(pb.x* pb.x + pb.y * pb.y + pb.z * pb.z); float range_var = range_cov * range_cov; Eigen::Matrix2f direction_var; // (angle_cov^2, 0, // 0, angle_cov^2) direction_var << pow(sin(DEG2RAD(degree_cov)), 2), 0, 0, pow(sin(DEG2RAD(degree_cov)), 2); Eigen::Vector3f direction = pb.getVector3fMap(); direction.normalize(); Eigen::Matrix3f direction_hat; // w^ direction_hat << 0, -direction(2), direction(1), direction(2), 0, -direction(0), -direction(1), direction(0), 0; //direction dot base_vector1 = 0 Eigen::Vector3f base_vector1(1, 1, -(direction(0) + direction(1)) / direction(2)); //(1, 1, -(x+y)/z), not unique base_vector1.normalize(); Eigen::Vector3f base_vector2 = base_vector1.cross(direction); base_vector2.normalize(); Eigen::Matrix N; //N = [base_vector1, base_vector2] N << base_vector1(0), base_vector2(0), base_vector1(1), base_vector2(1), base_vector1(2), base_vector2(2); Eigen::Matrix A = range * direction_hat * N; // (d * w^ * N )in the paper //cov = w * var_d * w^T + A * var_w * A^T cov = direction * range_var * direction.transpose() + A * direction_var * A.transpose(); // pb.recordPointCovFromMatrix(cov); }; void GetUpdatePlane(const OctoTree *current_octo, const int pub_max_voxel_layer, vector &plane_list) { if (current_octo->layer_ > pub_max_voxel_layer) { return; } if (current_octo->plane_ptr_->is_update) { plane_list.push_back(*current_octo->plane_ptr_); } if (current_octo->layer_ < current_octo->max_layer_) { if (!current_octo->plane_ptr_->is_plane) { for (size_t i = 0; i < 8; i++) { if (current_octo->leaves_[i] != nullptr) { GetUpdatePlane(current_octo->leaves_[i], pub_max_voxel_layer, plane_list); } } } } return; } void mapJet(double v, double vmin, double vmax, uint8_t &r, uint8_t &g, uint8_t &b) { r = 255; g = 255; b = 255; if (v < vmin) { v = vmin; } if (v > vmax) { v = vmax; } double dr, dg, db; if (v < 0.1242) { db = 0.504 + ((1. - 0.504) / 0.1242) * v; dg = dr = 0.; } else if (v < 0.3747) { db = 1.; dr = 0.; dg = (v - 0.1242) * (1. / (0.3747 - 0.1242)); } else if (v < 0.6253) { db = (0.6253 - v) * (1. / (0.6253 - 0.3747)); dg = 1.; dr = (v - 0.3747) * (1. / (0.6253 - 0.3747)); } else if (v < 0.8758) { db = 0.; dr = 1.; dg = (0.8758 - v) * (1. / (0.8758 - 0.6253)); } else { db = 0.; dg = 0.; dr = 1. - (v - 0.8758) * ((1. - 0.504) / (1. - 0.8758)); } r = (uint8_t) (255 * dr); g = (uint8_t) (255 * dg); b = (uint8_t) (255 * db); } void CalcVectQuation(const Eigen::Vector3d &x_vec, const Eigen::Vector3d &y_vec, const Eigen::Vector3d &z_vec, geometry_msgs::Quaternion &q) { Eigen::Matrix3d rot; rot << x_vec(0), x_vec(1), x_vec(2), y_vec(0), y_vec(1), y_vec(2), z_vec(0), z_vec(1), z_vec(2); Eigen::Matrix3d rotation = rot.transpose(); Eigen::Quaterniond eq(rotation); q.w = eq.w(); q.x = eq.x(); q.y = eq.y(); q.z = eq.z(); } void CalcQuation(const Eigen::Vector3d &vec, const int axis, geometry_msgs::Quaternion &q) { Eigen::Vector3d x_body = vec; Eigen::Vector3d y_body(1, 1, 0); if (x_body(2) != 0) { y_body(2) = -(y_body(0) * x_body(0) + y_body(1) * x_body(1)) / x_body(2); } else { if (x_body(1) != 0) { y_body(1) = -(y_body(0) * x_body(0)) / x_body(1); } else { y_body(0) = 0; } } y_body.normalize(); Eigen::Vector3d z_body = x_body.cross(y_body); Eigen::Matrix3d rot; rot << x_body(0), x_body(1), x_body(2), y_body(0), y_body(1), y_body(2), z_body(0), z_body(1), z_body(2); Eigen::Matrix3d rotation = rot.transpose(); if (axis == 2) { Eigen::Matrix3d rot_inc; rot_inc << 0, 0, 1, 0, 1, 0, -1, 0, 0; rotation = rotation * rot_inc; } Eigen::Quaterniond eq(rotation); q.w = eq.w(); q.x = eq.x(); q.y = eq.y(); q.z = eq.z(); } M3D calcBodyCov(Eigen::Vector3d &pb, const float range_inc, const float degree_inc) { float range = sqrt(pb[0] * pb[0] + pb[1] * pb[1] + pb[2] * pb[2]); float range_var = range_inc * range_inc; Eigen::Matrix2d direction_var; // (angle_cov^2, 0, // 0, angle_cov^2) direction_var << pow(sin(DEG2RAD(degree_inc)), 2), 0, 0, pow(sin(DEG2RAD(degree_inc)), 2); Eigen::Vector3d direction(pb); direction.normalize(); Eigen::Matrix3d direction_hat; // w^ direction_hat << 0, -direction(2), direction(1), direction(2), 0, -direction(0), -direction(1), direction(0), 0; //direction dot base_vector1 = 0 Eigen::Vector3d base_vector1(1, 1, -(direction(0) + direction(1)) / direction(2)); //(1, 1, -(x+y)/z), not unique base_vector1.normalize(); Eigen::Vector3d base_vector2 = base_vector1.cross(direction); base_vector2.normalize(); Eigen::Matrix N; //N = [base_vector1, base_vector2] N << base_vector1(0), base_vector2(0), base_vector1(1), base_vector2(1), base_vector1(2), base_vector2(2); Eigen::Matrix A = range * direction_hat * N; // (d * w^ * N )in the paper //cov = w * var_d * w^T + A * var_w * A^T return direction * range_var * direction.transpose() + A * direction_var * A.transpose(); };FAST_LIO_CLOUD_PROCESS_HPP bool mergeVoxelCheck(const vector& voxels, const Eigen::Vector3f& body2point, const PointType & point_world, Matrix &pca_plane, const float& threshold) { float sum_diff_angle = 0; // angle between normals int num_fail_normal = 0; float s_xx= 0.0, s_xy = 0.0, s_xz = 0.0, s_yy = 0.0, s_yz = 0.0, s_zz = 0.0; float mean_x = 0.0, mean_y = 0.0, mean_z = 0.0; float num_points = 0.0; int num_valid_voxels = 0; Eigen::Vector3f mean_normal(0, 0, 0); Eigen::Vector3f centroid(0, 0, 0); vector valid_mean_xyz(voxels.size()); for (int j = 0; j < voxels.size(); j++) { //check map points normal direction, to sure lidar can see it if (!voxels[j]) continue; VoxelInfo* v = voxels[j]; // check normal consistency const Eigen::Vector3f& voxel_normal = v->normal; if (check_normal && voxel_normal.dot(body2point) > 0) { ++num_fail_normal; continue; } sum_diff_angle += acos(point_world.getNormalVector3fMap().dot(voxel_normal)); // check enough points in voxel if (v->num_points >= 0 && v->num_points < surfel_points_min) // not enough points continue; float n = (float)abs(v->num_points); num_points += n; // const PointType & p = cloud[i]; s_xx += v->s_xx; s_xy += v->s_xy; s_xz += v->s_xz; s_yy += v->s_yy; s_yz += v->s_yz; s_zz += v->s_zz; mean_x += n * v->mean_x; mean_y += n * v->mean_y; mean_z += n * v->mean_z; mean_normal += n * v->normal; // copy valid mean position valid_mean_xyz[num_valid_voxels](0) = v->mean_x; valid_mean_xyz[num_valid_voxels](1) = v->mean_y; valid_mean_xyz[num_valid_voxels](2) = v->mean_z; ++num_valid_voxels; } mean_x /= num_points; mean_y /= num_points; mean_z /= num_points; centroid(0) = mean_x; centroid(1) = mean_y; centroid(2) = mean_z; mean_normal = mean_normal / num_points; mean_normal.normalize(); Eigen::Matrix3f cov; cov(0, 0) = s_xx - num_points * mean_x * mean_x; cov(1, 1) = s_yy - num_points * mean_y * mean_y; cov(2, 2) = s_zz - num_points * mean_z * mean_z; cov(0, 1) = s_xy - num_points * mean_x * mean_y; cov(1, 0) = cov(0, 1); cov(0, 2) = s_xz - num_points * mean_x * mean_z; cov(2, 0) = cov(0, 2); cov(1, 2) = s_yz - num_points * mean_y * mean_z; cov(2, 1) = cov(1, 2); Eigen::Matrix3f eigenvectors_; Eigen::Vector3f eigenvalues_; // Compute eigen vectors and values Eigen::SelfAdjointEigenSolver evd (cov); // Organize eigenvectors and eigenvalues in ascendent order // lambda 1 > lambda 2 > lambda 3 for (int i = 0; i < 3; ++i) { eigenvalues_[i] = evd.eigenvalues () [2-i]; eigenvectors_.col (i) = evd.eigenvectors ().col (2-i); } if (eigenvalues_[0] == eigenvalues_[2] || eigenvalues_[0] == 0.0) return false; float pho = 2.0 * (eigenvalues_[1] - eigenvalues_[2]) / (eigenvalues_[0] + eigenvalues_[1] + eigenvalues_[2]); float mid_min = eigenvalues_[1] / eigenvalues_[2]; // n * p + d = 0; Eigen::Vector3f normal = eigenvectors_.col (2); if (mean_normal.dot(normal) < 0) normal *= -1; pca_plane.head(3) = normal; pca_plane(3) = -centroid.dot(normal); // d for (const auto & valid_mean : valid_mean_xyz) if (fabs(pca_plane.head(3).dot(valid_mean) + pca_plane(3)) > threshold) return false; V3F cent2point(point_world.getVector3fMap() - centroid); pca_plane(3) = normal.dot(cent2point); //pca_plane(3) record point to surfel distance return true; } bool singleVoxelCheck(const vector& voxels, const Eigen::Vector3f& body2point, const PointType & point_world, Matrix &pca_result, const float& threshold) { // idea from voxelMap double prob = 0.0; float dist_min = 999.99; for (const VoxelInfo* vox : voxels) { if (!vox) continue; if (vox->num_points > 0 && vox->num_points < surfel_points_min) continue; if (check_normal && vox->normal.dot(body2point) > 0) continue; // todo 3 * standard deviation // while (voxel_info->flag_updating) /// !!!caution // usleep(2); // lock_guard lock(voxel_info->updating_mutex_lock); V3F plane_centroid(vox->mean_x, vox->mean_y, vox->mean_z); V3F plane_normal(vox->normal); V3F cent2point(point_world.getVector3fMap() - plane_centroid); float p2surfel = plane_normal.dot(cent2point); float abs_dist = fabs(p2surfel); //todo 从不确定度判断最佳surfel if (abs_dist < threshold && abs_dist < dist_min) { dist_min = abs_dist; pca_result.head(3) = plane_normal; pca_result(3) = p2surfel; //pca_plane(3) record point to surfel distance } } if (dist_min < threshold) return true; return false; } #endif //FAST_LIO_CLOUD_PROCESS_HPP ================================================ FILE: src/laserMapping.cpp ================================================ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include "IMU_Processing.hpp" #include "preprocess.h" #include "tic_toc.h" #include "cloud_process.hpp" #include "voxel_map_util.hpp" #include #include #include #include #include #include #include #include #include #include #include //#include #include #define INIT_TIME (0.1) #define LASER_POINT_COV (0.001) #define MAXN (720000) #define PUBFRAME_PERIOD (20) /*** Time Log Variables ***/ double kdtree_incremental_time = 0.0, kdtree_search_time = 0.0, kdtree_delete_time = 0.0; double T1[MAXN], s_plot[MAXN], s_plot2[MAXN], s_plot3[MAXN], s_plot4[MAXN], s_plot5[MAXN], s_plot6[MAXN], s_plot7[MAXN], s_plot8[MAXN], s_plot9[MAXN], s_plot10[MAXN], s_plot11[MAXN]; double match_time = 0, solve_time = 0, solve_const_H_time = 0; int kdtree_size_st = 0, kdtree_size_end = 0, add_point_size = 0, kdtree_delete_counter = 0; bool runtime_pos_log = false, pcd_save_en = false, time_sync_en = false, extrinsic_est_en = true, path_en = true; /**************************/ float res_last[100000] = {0.0}; float DET_RANGE = 300.0f; const float MOV_THRESHOLD = 1.5f; double time_diff_lidar_to_imu = 0.0; mutex mtx_buffer; condition_variable sig_buffer; string root_dir = ROOT_DIR; string map_file_path, lid_topic, imu_topic; double res_mean_last = 0.05, total_residual = 0.0; double last_timestamp_lidar = 0, last_timestamp_imu = -1.0; double gyr_cov = 0.1, acc_cov = 0.1, b_gyr_cov = 0.0001, b_acc_cov = 0.0001; double filter_size_corner_min = 0, filter_size_surf_min = 0, filter_size_map_min = 0, fov_deg = 0, half_map_size = 0; double cube_len = 0, HALF_FOV_COS = 0, FOV_DEG = 0, total_distance = 0, lidar_end_time = 0, first_lidar_time = 0.0; int effct_feat_num = 0, time_log_counter = 0, scan_count = 0, publish_count = 0; int iterCount = 0, feats_down_size = 0, NUM_MAX_ITERATIONS = 0, laserCloudValidNum = 0, pcd_save_interval = -1, pcd_index = 0; bool point_selected_surf[100000] = {0}; bool lidar_pushed, flg_first_scan = true, flg_exit = false, flg_EKF_inited; bool scan_pub_en = false, dense_pub_en = false, scan_body_pub_en = false; vector> pointSearchInd_surf; vector cub_needrm; vector Nearest_Points; vector::VoxelInfoPtr>> Nearest_Nodes; vector extrinT(3, 0.0); vector extrinR(9, 0.0); deque time_buffer; deque lidar_buffer; deque imu_buffer; PointCloudXYZI::Ptr featsFromMap(new PointCloudXYZI()); PointCloudXYZI::Ptr feats_undistort(new PointCloudXYZI()); PointCloudXYZI::Ptr feats_down_body(new PointCloudXYZI()); PointCloudXYZI::Ptr feats_down_world(new PointCloudXYZI()); PointCloudXYZI::Ptr normvec(new PointCloudXYZI(100000, 1)); PointCloudXYZI::Ptr laserCloudOri(new PointCloudXYZI(100000, 1)); PointCloudXYZI::Ptr corr_normvect(new PointCloudXYZI(100000, 1)); PointCloudXYZI::Ptr _featsArray; PointCloudXYZI::Ptr cloud_with_normal; pcl::VoxelGrid downSizeFilterSurf; pcl::VoxelGrid downSizeFilterMap; //KD_TREE ikdtree; KD_TREE ikdtree; V3F XAxisPoint_body(LIDAR_SP_LEN, 0.0, 0.0); V3F XAxisPoint_world(LIDAR_SP_LEN, 0.0, 0.0); V3D euler_cur; V3D position_last(Zero3d); V3D Lidar_T_wrt_IMU(Zero3d);//T lidar to imu (imu = r * lidar + t) M3D Lidar_R_wrt_IMU(Eye3d);//R lidar to imu (imu = r * lidar) double lidar_time_offset = 0.0; // record begin time for pose interpolation deque timestamps_lidar; nav_msgs::Path path_target_begin, path_target_end; /*** EKF inputs and output ***/ MeasureGroup Measures; esekfom::esekf kf; state_ikfom state_point; //Eigen::VectorXf body_keypose_last(6); //rpy xyz state_ikfom state_body_last; vect3 pos_lid; geometry_msgs::PoseStamped msg_target_pose; bool have_keyframe = false; bool save_ikdtree_map; bool save_final_map; int num_surfel = 0; nav_msgs::Path path; nav_msgs::Path path_target; nav_msgs::Odometry odomAftMapped; geometry_msgs::Quaternion geoQuat; geometry_msgs::PoseStamped msg_body_pose; shared_ptr p_pre(new Preprocess()); shared_ptr p_imu(new ImuProcess()); // parameters for normal estimation int N_SCAN, Horizon_SCAN; string ring_table_dir; bool check_normal; // surfel parameters float planarity = 1.0, mid2min = 100.0; int surfel_points_min = 20; int surfel_points_max = 100; float angle_threshold = 10.0; bool cloud_surfel = true; bool point_surfel = true; int num_cloud_surfel = 0, num_point_surfel = 0; //voxel map std::unordered_map voxel_map; int max_cov_points_size = 50; int max_points_size = 50; double sigma_num = 2.0; double max_voxel_size = 1.0; std::vector layer_size; double min_eigen_value = 0.003; int max_layer = 0; std::vector layer_point_size; bool voxel_hash_en = true; // for ground truth, target in IMU frame vector gt_extrinT(3, 0.0); vector gt_extrinR(9, 0.0); V3D gt_T_wrt_IMU(Zero3d); M3D gt_R_wrt_IMU(Eye3d); void SigHandle(int sig) { flg_exit = true; ROS_WARN("catch sig %d", sig); sig_buffer.notify_all(); } inline void dump_lio_state_to_log(FILE *fp) { V3D rot_ang(Log(state_point.rot.toRotationMatrix())); fprintf(fp, "%lf ", Measures.lidar_beg_time - first_lidar_time); fprintf(fp, "%lf %lf %lf ", rot_ang(0), rot_ang(1), rot_ang(2)); // Angle fprintf(fp, "%lf %lf %lf ", state_point.pos(0), state_point.pos(1), state_point.pos(2)); // Pos fprintf(fp, "%lf %lf %lf ", 0.0, 0.0, 0.0); // omega fprintf(fp, "%lf %lf %lf ", state_point.vel(0), state_point.vel(1), state_point.vel(2)); // Vel fprintf(fp, "%lf %lf %lf ", 0.0, 0.0, 0.0); // Acc fprintf(fp, "%lf %lf %lf ", state_point.bg(0), state_point.bg(1), state_point.bg(2)); // Bias_g fprintf(fp, "%lf %lf %lf ", state_point.ba(0), state_point.ba(1), state_point.ba(2)); // Bias_a fprintf(fp, "%lf %lf %lf ", state_point.grav[0], state_point.grav[1], state_point.grav[2]); // Bias_a fprintf(fp, "\r\n"); fflush(fp); } void pointBodyToWorld_ikfom(PointType const * const pi, PointType * const po, state_ikfom &s) { V3D p_body(pi->x, pi->y, pi->z); V3D p_global(s.rot * (s.offset_R_L_I*p_body + s.offset_T_L_I) + s.pos); po->x = p_global(0); po->y = p_global(1); po->z = p_global(2); po->intensity = pi->intensity; } void pointBodyToWorld(PointType const * const pi, PointType * const po) { V3D p_body(pi->x, pi->y, pi->z); //world <-- imu <-- lidar V3D p_global(state_point.rot * (state_point.offset_R_L_I*p_body + state_point.offset_T_L_I) + state_point.pos); po->x = p_global(0); po->y = p_global(1); po->z = p_global(2); po->intensity = pi->intensity; } void pointNormalBodyToWorld(PointType const * const pi, PointType * const po) { pointBodyToWorld(pi, po); // normal V3F normal_global(state_point.rot.cast() * state_point.offset_R_L_I.cast() * pi->getNormalVector3fMap()); po->normal_x = normal_global(0); po->normal_y = normal_global(1); po->normal_z = normal_global(2); } template void pointBodyToWorld(const Matrix &pi, Matrix &po) { V3D p_body(pi[0], pi[1], pi[2]); V3D p_global(state_point.rot * (state_point.offset_R_L_I*p_body + state_point.offset_T_L_I) + state_point.pos); po[0] = p_global(0); po[1] = p_global(1); po[2] = p_global(2); } void RGBpointBodyToWorld(PointType const * const pi, PointType * const po) { V3D p_body(pi->x, pi->y, pi->z); V3D p_global(state_point.rot * (state_point.offset_R_L_I*p_body + state_point.offset_T_L_I) + state_point.pos); po->x = p_global(0); po->y = p_global(1); po->z = p_global(2); po->intensity = pi->intensity; // normal V3D normal_body(pi->normal_x, pi->normal_y, pi->normal_z); //lidar系下normal V3D normal_global(state_point.rot * state_point.offset_R_L_I * normal_body); //w系下坐标 po->normal_x = normal_global(0); po->normal_y = normal_global(1); po->normal_z = normal_global(2); } void RGBpointBodyLidarToIMU(PointType const * const pi, PointType * const po) { V3D p_body_lidar(pi->x, pi->y, pi->z); V3D p_body_imu(state_point.offset_R_L_I*p_body_lidar + state_point.offset_T_L_I); po->x = p_body_imu(0); po->y = p_body_imu(1); po->z = p_body_imu(2); po->intensity = pi->intensity; } void points_cache_collect() { PointVector points_history; ikdtree.acquire_removed_points(points_history); // for (int i = 0; i < points_history.size(); i++) _featsArray->push_back(points_history[i]); } BoxPointType LocalMap_Points; bool Localmap_Initialized = false; void lasermap_fov_segment() { cub_needrm.clear(); kdtree_delete_counter = 0; kdtree_delete_time = 0.0; V3D pos_LiD = pos_lid; if (!Localmap_Initialized){ for (int i = 0; i < 3; i++){ LocalMap_Points.vertex_min[i] = pos_LiD(i) - cube_len / 2.0; LocalMap_Points.vertex_max[i] = pos_LiD(i) + cube_len / 2.0; } Localmap_Initialized = true; return; } float dist_to_map_edge[3][2]; bool need_move = false; for (int i = 0; i < 3; i++){ dist_to_map_edge[i][0] = fabs(pos_LiD(i) - LocalMap_Points.vertex_min[i]); dist_to_map_edge[i][1] = fabs(pos_LiD(i) - LocalMap_Points.vertex_max[i]); if (dist_to_map_edge[i][0] <= MOV_THRESHOLD * DET_RANGE || dist_to_map_edge[i][1] <= MOV_THRESHOLD * DET_RANGE) need_move = true; } if (!need_move) return; BoxPointType New_LocalMap_Points, tmp_boxpoints; New_LocalMap_Points = LocalMap_Points; float mov_dist = max((cube_len - 2.0 * MOV_THRESHOLD * DET_RANGE) * 0.5 * 0.9, double(DET_RANGE * (MOV_THRESHOLD -1))); for (int i = 0; i < 3; i++){ tmp_boxpoints = LocalMap_Points; if (dist_to_map_edge[i][0] <= MOV_THRESHOLD * DET_RANGE){ New_LocalMap_Points.vertex_max[i] -= mov_dist; New_LocalMap_Points.vertex_min[i] -= mov_dist; tmp_boxpoints.vertex_min[i] = LocalMap_Points.vertex_max[i] - mov_dist; cub_needrm.push_back(tmp_boxpoints); } else if (dist_to_map_edge[i][1] <= MOV_THRESHOLD * DET_RANGE){ New_LocalMap_Points.vertex_max[i] += mov_dist; New_LocalMap_Points.vertex_min[i] += mov_dist; tmp_boxpoints.vertex_max[i] = LocalMap_Points.vertex_min[i] + mov_dist; cub_needrm.push_back(tmp_boxpoints); } } LocalMap_Points = New_LocalMap_Points; points_cache_collect(); double delete_begin = omp_get_wtime(); if(cub_needrm.size() > 0) kdtree_delete_counter = ikdtree.Delete_Point_Boxes(cub_needrm); kdtree_delete_time = omp_get_wtime() - delete_begin; } double mean_preprocess = 0.0; void standard_pcl_cbk(const sensor_msgs::PointCloud2::ConstPtr &msg) { mtx_buffer.lock(); scan_count ++; double preprocess_start_time = omp_get_wtime(); double scan_begin_time = msg->header.stamp.toSec() + lidar_time_offset; if (scan_begin_time < last_timestamp_lidar) { ROS_ERROR("lidar loop back, clear buffer"); lidar_buffer.clear(); } PointCloudXYZI::Ptr ptr(new PointCloudXYZI()); p_pre->process(msg, ptr); lidar_buffer.push_back(ptr); time_buffer.push_back(scan_begin_time); last_timestamp_lidar = scan_begin_time; timestamps_lidar.push_back(last_timestamp_lidar); s_plot11[scan_count] = omp_get_wtime() - preprocess_start_time; mean_preprocess = mean_preprocess * (scan_count - 1) / scan_count + s_plot11[scan_count] / scan_count; mtx_buffer.unlock(); sig_buffer.notify_all(); if (runtime_pos_log) printf("[ pre-process ]: this time: %0.6f ms, mean : %0.6f ms\n", s_plot11[scan_count] * 1000, mean_preprocess * 1000); } double timediff_lidar_wrt_imu = 0.0; bool timediff_set_flg = false; //void livox_pcl_cbk(const livox_ros_driver::CustomMsg::ConstPtr &msg) //{ // mtx_buffer.lock(); // double preprocess_start_time = omp_get_wtime(); // scan_count ++; // if (msg->header.stamp.toSec() < last_timestamp_lidar) // { // ROS_ERROR("lidar loop back, clear buffer"); // lidar_buffer.clear(); // } // last_timestamp_lidar = msg->header.stamp.toSec(); // // if (!time_sync_en && abs(last_timestamp_imu - last_timestamp_lidar) > 10.0 && !imu_buffer.empty() && !lidar_buffer.empty() ) // { // printf("IMU and LiDAR not Synced, IMU time: %lf, lidar header time: %lf \n",last_timestamp_imu, last_timestamp_lidar); // } // // if (time_sync_en && !timediff_set_flg && abs(last_timestamp_lidar - last_timestamp_imu) > 1 && !imu_buffer.empty()) // { // timediff_set_flg = true; // timediff_lidar_wrt_imu = last_timestamp_lidar + 0.1 - last_timestamp_imu; // printf("Self sync IMU and LiDAR, time diff is %.10lf \n", timediff_lidar_wrt_imu); // } // // PointCloudXYZI::Ptr ptr(new PointCloudXYZI()); // p_pre->process(msg, ptr); // lidar_buffer.push_back(ptr); // time_buffer.push_back(last_timestamp_lidar); // // s_plot11[scan_count] = omp_get_wtime() - preprocess_start_time; // mtx_buffer.unlock(); // sig_buffer.notify_all(); //} void imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in) { publish_count ++; // cout<<"IMU got at: "<header.stamp.toSec()<header.stamp = ros::Time().fromSec(msg_in->header.stamp.toSec() - time_diff_lidar_to_imu); if (abs(timediff_lidar_wrt_imu) > 0.1 && time_sync_en) { msg->header.stamp = \ ros::Time().fromSec(timediff_lidar_wrt_imu + msg_in->header.stamp.toSec()); } double timestamp = msg->header.stamp.toSec(); mtx_buffer.lock(); if (timestamp < last_timestamp_imu) { ROS_WARN("imu loop back, clear buffer"); imu_buffer.clear(); } last_timestamp_imu = timestamp; //update imu time imu_buffer.push_back(msg); mtx_buffer.unlock(); sig_buffer.notify_all(); } double lidar_mean_scantime = 0.0; int scan_num = 0; bool sync_packages(MeasureGroup &meas) { if (lidar_buffer.empty() || imu_buffer.empty()) { return false; } /*** push a lidar scan ***/ if(!lidar_pushed) { meas.lidar = lidar_buffer.front(); meas.lidar_beg_time = time_buffer.front(); if (meas.lidar->points.size() <= 1) // time too little { lidar_end_time = meas.lidar_beg_time + lidar_mean_scantime; ROS_WARN("Too few input point cloud!\n"); } else if (meas.lidar->points.back().curvature / double(1000) < 0.5 * lidar_mean_scantime) { lidar_end_time = meas.lidar_beg_time + lidar_mean_scantime; } else { scan_num ++; lidar_end_time = meas.lidar_beg_time + meas.lidar->points.back().curvature / double(1000); lidar_mean_scantime += (meas.lidar->points.back().curvature / double(1000) - lidar_mean_scantime) / scan_num; } meas.lidar_end_time = lidar_end_time; lidar_pushed = true; } if (last_timestamp_imu < lidar_end_time) { return false; } /*** push imu data, and pop from imu buffer ***/ double imu_time = imu_buffer.front()->header.stamp.toSec(); meas.imu.clear(); while ((!imu_buffer.empty()) && (imu_time < lidar_end_time)) { imu_time = imu_buffer.front()->header.stamp.toSec(); if(imu_time > lidar_end_time) break; meas.imu.push_back(imu_buffer.front()); imu_buffer.pop_front(); } lidar_buffer.pop_front(); time_buffer.pop_front(); lidar_pushed = false; return true; } bool same_point(PointType a, PointType b){ return (fabs(a.x-b.x) < EPSS && fabs(a.y-b.y) < EPSS && fabs(a.z-b.z) < EPSS ); } int process_increments = 0; void map_incremental() { ROS_INFO("[incremental] start"); PointVector PointToAdd; PointVector PointNoNeedDownsample; PointToAdd.reserve(feats_down_size); PointNoNeedDownsample.reserve(feats_down_size); vector::KD_TREE_NODE*, V3F>> roots_need_update_normal; for (int i = 0; i < feats_down_size; i++) { /* transform to world frame */ pointNormalBodyToWorld(&(feats_down_body->points[i]), &(feats_down_world->points[i])); PointType & point_world = feats_down_world->points[i]; ikdtree.updateVoxelInfo(point_world); /* decide if need add to map */ if (!Nearest_Points[i].empty() && flg_EKF_inited) { const PointVector &points_near = Nearest_Points[i]; bool need_add = true; BoxPointType Box_of_Point; PointType downsample_result, mid_point; mid_point.x = floor(point_world.x / filter_size_map_min)*filter_size_map_min + half_map_size; mid_point.y = floor(point_world.y / filter_size_map_min)*filter_size_map_min + half_map_size; mid_point.z = floor(point_world.z / filter_size_map_min)*filter_size_map_min + half_map_size; float dist = calc_dist(point_world, mid_point);//当前点与box中心的距离 if (fabs(points_near[0].x - mid_point.x) > half_map_size && fabs(points_near[0].y - mid_point.y) > half_map_size && fabs(points_near[0].z - mid_point.z) > half_map_size){ // initPointIncInfo(point_world); PointNoNeedDownsample.push_back(point_world); continue; } for (int readd_i = 0; readd_i < NUM_MATCH_POINTS; readd_i ++) { if (points_near.size() < NUM_MATCH_POINTS) break; if (calc_dist(points_near[readd_i], mid_point) < dist) { need_add = false; break; } } if (need_add) { PointToAdd.push_back(point_world); } } else { // initPointIncInfo(point_world); PointToAdd.push_back(point_world); } } ROS_INFO("[incremental]"); double st_time = omp_get_wtime(); add_point_size = ikdtree.Add_Points(PointToAdd, true); ikdtree.Add_Points(PointNoNeedDownsample, false); add_point_size = PointToAdd.size() + PointNoNeedDownsample.size(); kdtree_incremental_time = omp_get_wtime() - st_time; ROS_INFO("kdtree_incremental_time %f", kdtree_incremental_time); } const bool var_contrast(pointWithCov &x, pointWithCov &y) { return (x.cov.diagonal().norm() < y.cov.diagonal().norm()); }; PointCloudXYZI::Ptr pcl_wait_pub(new PointCloudXYZI(500000, 1)); PointCloudXYZI::Ptr pcl_wait_save(new PointCloudXYZI()); void publish_frame_world(const ros::Publisher & pubLaserCloudFull) { if(scan_pub_en) { PointCloudXYZI::Ptr laserCloudFullRes(dense_pub_en ? feats_undistort : feats_down_body); int size = laserCloudFullRes->points.size(); PointCloudXYZI::Ptr laserCloudWorld( \ new PointCloudXYZI(size, 1)); for (int i = 0; i < size; i++) { RGBpointBodyToWorld(&laserCloudFullRes->points[i], \ &laserCloudWorld->points[i]); } sensor_msgs::PointCloud2 laserCloudmsg; pcl::toROSMsg(*laserCloudWorld, laserCloudmsg); laserCloudmsg.header.stamp = ros::Time().fromSec(lidar_end_time); laserCloudmsg.header.frame_id = "camera_init"; pubLaserCloudFull.publish(laserCloudmsg); publish_count -= PUBFRAME_PERIOD; } /**************** save map ****************/ /* 1. make sure you have enough memories /* 2. noted that pcd save will influence the real-time performences **/ if (pcd_save_en) { int size = feats_undistort->points.size(); PointCloudXYZI::Ptr laserCloudWorld( \ new PointCloudXYZI(size, 1)); for (int i = 0; i < size; i++) { RGBpointBodyToWorld(&feats_undistort->points[i], \ &laserCloudWorld->points[i]); } *pcl_wait_save += *laserCloudWorld; static int scan_wait_num = 0; scan_wait_num ++; if (pcl_wait_save->size() > 0 && pcd_save_interval > 0 && scan_wait_num >= pcd_save_interval) { pcd_index ++; string all_points_dir(string(string(ROOT_DIR) + "PCD/scans_") + to_string(pcd_index) + string(".pcd")); pcl::PCDWriter pcd_writer; cout << "current scan saved to /PCD/" << all_points_dir << endl; pcd_writer.writeBinary(all_points_dir, *pcl_wait_save); pcl_wait_save->clear(); scan_wait_num = 0; } } } void publish_frame_body(const ros::Publisher & pubLaserCloudFull_body) { int size = feats_undistort->points.size(); PointCloudXYZI::Ptr laserCloudIMUBody(new PointCloudXYZI(size, 1)); for (int i = 0; i < size; i++) { RGBpointBodyLidarToIMU(&feats_undistort->points[i], \ &laserCloudIMUBody->points[i]); } sensor_msgs::PointCloud2 laserCloudmsg; pcl::toROSMsg(*laserCloudIMUBody, laserCloudmsg); laserCloudmsg.header.stamp = ros::Time().fromSec(lidar_end_time); laserCloudmsg.header.frame_id = "body"; pubLaserCloudFull_body.publish(laserCloudmsg); publish_count -= PUBFRAME_PERIOD; } void publish_effect_world(const ros::Publisher & pubLaserCloudEffect) { PointCloudXYZI::Ptr laserCloudWorld( \ new PointCloudXYZI(effct_feat_num, 1)); for (int i = 0; i < effct_feat_num; i++) { RGBpointBodyToWorld(&laserCloudOri->points[i], \ &laserCloudWorld->points[i]); } sensor_msgs::PointCloud2 laserCloudFullRes3; pcl::toROSMsg(*laserCloudWorld, laserCloudFullRes3); laserCloudFullRes3.header.stamp = ros::Time().fromSec(lidar_end_time); laserCloudFullRes3.header.frame_id = "camera_init"; pubLaserCloudEffect.publish(laserCloudFullRes3); } void publish_map(const ros::Publisher & pubLaserCloudMap) { sensor_msgs::PointCloud2 laserCloudMap; pcl::toROSMsg(*featsFromMap, laserCloudMap); laserCloudMap.header.stamp = ros::Time().fromSec(lidar_end_time); laserCloudMap.header.frame_id = "camera_init"; pubLaserCloudMap.publish(laserCloudMap); } template void set_posestamp(T & out) { out.pose.position.x = state_point.pos(0); out.pose.position.y = state_point.pos(1); out.pose.position.z = state_point.pos(2); out.pose.orientation.x = geoQuat.x; out.pose.orientation.y = geoQuat.y; out.pose.orientation.z = geoQuat.z; out.pose.orientation.w = geoQuat.w; } void publish_odometry(const ros::Publisher & pubOdomAftMapped) { odomAftMapped.header.frame_id = "camera_init"; odomAftMapped.child_frame_id = "body"; odomAftMapped.header.stamp = ros::Time().fromSec(lidar_end_time);// ros::Time().fromSec(lidar_end_time); set_posestamp(odomAftMapped.pose); pubOdomAftMapped.publish(odomAftMapped); auto P = kf.get_P(); for (int i = 0; i < 6; i ++) { int k = i < 3 ? i + 3 : i - 3; odomAftMapped.pose.covariance[i*6 + 0] = P(k, 3); odomAftMapped.pose.covariance[i*6 + 1] = P(k, 4); odomAftMapped.pose.covariance[i*6 + 2] = P(k, 5); odomAftMapped.pose.covariance[i*6 + 3] = P(k, 0); odomAftMapped.pose.covariance[i*6 + 4] = P(k, 1); odomAftMapped.pose.covariance[i*6 + 5] = P(k, 2); } static tf::TransformBroadcaster br; tf::Transform transform; tf::Quaternion q; transform.setOrigin(tf::Vector3(odomAftMapped.pose.pose.position.x, \ odomAftMapped.pose.pose.position.y, \ odomAftMapped.pose.pose.position.z)); q.setW(odomAftMapped.pose.pose.orientation.w); q.setX(odomAftMapped.pose.pose.orientation.x); q.setY(odomAftMapped.pose.pose.orientation.y); q.setZ(odomAftMapped.pose.pose.orientation.z); transform.setRotation( q ); br.sendTransform( tf::StampedTransform( transform, odomAftMapped.header.stamp, "camera_init", "body" ) ); } void publish_path(const ros::Publisher pubPath) { set_posestamp(msg_body_pose); msg_body_pose.header.stamp = ros::Time().fromSec(lidar_end_time); msg_body_pose.header.frame_id = "camera_init"; /*** if path is too large, the rvis will crash ***/ static int jjj = 0; jjj++; if (jjj % 10 == 0) { path.poses.push_back(msg_body_pose); pubPath.publish(path); } if (!have_keyframe) { // V3D euler_body = SO3ToEuler(state_point.rot); // body_keypose_last << euler_body(0), euler_body(1), euler_body(2), state_point.pos(0), state_point.pos(1), state_point.pos(2); state_body_last = state_point; vect3 pos_target; pos_target = state_point.pos + state_point.rot * gt_T_wrt_IMU; msg_target_pose.header.stamp = ros::Time().fromSec(lidar_end_time); msg_target_pose.header.frame_id = "camera_init"; msg_target_pose.pose.position.x = pos_target(0); msg_target_pose.pose.position.y = pos_target(1); msg_target_pose.pose.position.z = pos_target(2); Eigen::Quaterniond quat_target(state_point.rot * gt_R_wrt_IMU); msg_target_pose.pose.orientation.x = quat_target.x(); msg_target_pose.pose.orientation.y = quat_target.y(); msg_target_pose.pose.orientation.z = quat_target.z(); msg_target_pose.pose.orientation.w = quat_target.w(); path_target.poses.push_back(msg_target_pose); have_keyframe = true; return; } Eigen::Quaterniond q_last(state_body_last.rot.coeffs()[3], state_body_last.rot.coeffs()[0], state_body_last.rot.coeffs()[1], state_body_last.rot.coeffs()[2]); Eigen::Quaterniond q_curr(state_point.rot.coeffs()[3], state_point.rot.coeffs()[0], state_point.rot.coeffs()[1], state_point.rot.coeffs()[2]); Eigen::Matrix3d r_incre(q_last * q_curr.inverse()); Eigen::Vector3d rpy = r_incre.eulerAngles(2, 1, 0); float x, y, z, roll, pitch, yaw; x = state_body_last.pos(0) - state_point.pos(0); y = state_body_last.pos(1) - state_point.pos(1); z = state_body_last.pos(2) - state_point.pos(2); roll = rpy(2); pitch = rpy(1); yaw = rpy(0); float surroundingkeyframeAddingAngleThreshold = 0.2; float surroundingkeyframeAddingDistThreshold = 1.0; if (abs(roll) >= surroundingkeyframeAddingAngleThreshold || abs(pitch) >= surroundingkeyframeAddingAngleThreshold || abs(yaw) >= surroundingkeyframeAddingAngleThreshold || sqrt(x*x + y*y + z*z) >= surroundingkeyframeAddingDistThreshold) // if (jjj % 20 == 0) { vect3 pos_target; pos_target = state_point.pos + state_point.rot * gt_T_wrt_IMU; Eigen::Quaterniond quat_target(state_point.rot * gt_R_wrt_IMU); // Eigen::Quaterniond quat_target(T.block<3, 3>(0, 0)); msg_target_pose.header.stamp = ros::Time().fromSec(lidar_end_time); msg_target_pose.header.frame_id = "camera_init"; msg_target_pose.pose.position.x = pos_target(0); msg_target_pose.pose.position.y = pos_target(1); msg_target_pose.pose.position.z = pos_target(2); msg_target_pose.pose.orientation.x = quat_target.x(); msg_target_pose.pose.orientation.y = quat_target.y(); msg_target_pose.pose.orientation.z = quat_target.z(); msg_target_pose.pose.orientation.w = quat_target.w(); path_target_end.poses.push_back(msg_target_pose); } } void h_share_model(state_ikfom &s, esekfom::dyn_share_datastruct &ekfom_data) { // ROS_INFO("[h_share_model]"); double match_start = omp_get_wtime(); laserCloudOri->clear(); corr_normvect->clear(); total_residual = 0.0; V3F body(s.pos.x(), s.pos.y(), s.pos.z()); int num_same_nearest = 0, num_neighbor_nearest = 0, num_diff_nearest = 0; int num_node_faraway = 0; double time_tree_search = 0, time_voxel_search = 0, time_cov2w = 0; int num_valid_voxel_neighbors = 0; /** closest surface search and residual computation **/ #ifdef MP_EN omp_set_num_threads(MP_PROC_NUM); #pragma omp parallel for #endif for (int i = 0; i < feats_down_size; i++) { /* transform to world frame */ pointNormalBodyToWorld(&(feats_down_body->points[i]), &(feats_down_world->points[i]));//point: world <-- imu <-- lidar const PointType &point_body = feats_down_body->points[i]; const PointType &point_world = feats_down_world->points[i]; V3F body2point = (point_world.getVector3fMap() - body).normalized(); //normalized vector vector pointSearchSqDis(NUM_MATCH_POINTS); auto &points_near = Nearest_Points[i]; auto &voxels_near = Nearest_Nodes[i]; float angle = 60.0 / 180.0 * M_PI; // VF(4) pabcd_surfel; // plane: n * p + d = 0 // bool surfel_valid = false; // bool voxel_search_valid = false; // bool tree_search_valid = false; if (ekfom_data.converge) { /** Find the closest surfaces in the map **/ // PointVector voxel_Nearest_Points; // vector::KD_TREE_NODE*> voxel_Nearest_Nodes; bool voxel_searching_valid = false; // ikdtree.Voxel_Search(point_world, NUM_MATCH_POINTS, voxel_Nearest_Points, voxel_Nearest_Nodes); // if (voxel_hash_en) // { // TicToc t_voxel; // //todo fix bugs // ikdtree.Voxel_Search_test(point_world, NUM_MATCH_POINTS, points_near, pointSearchSqDis, voxels_near); // time_voxel_search += t_voxel.toc(); //// ROS_INFO("#%d hash done", i); // //// // point to voxels association (surfel association) //// VF(4) pabcd_surfel; // plane: n * p + d = 0 //// bool surfel_valid = mergeVoxelCheck(voxels_near, body2point, point_world, pabcd_surfel, 0.15f); //// if (!surfel_valid) //// surfel_valid = singleVoxelCheck(voxels_near, body2point, point_world, pabcd_surfel, 0.2f); //// /// !!! pabcd_surfel(3) record point to surfel distance // //// voxel_searching_valid = surfel_valid; // if (voxels_near.size() < NUM_MATCH_POINTS) { // voxel_searching_valid = false; // } // else { // voxel_searching_valid = true; // ++num_valid_voxel_neighbors; // } // } if (!voxel_searching_valid) { TicToc t_tree; ikdtree.Nearest_Search(point_world, NUM_MATCH_POINTS, points_near, pointSearchSqDis, voxels_near); time_tree_search += t_tree.toc(); } bool planeValid = true; if (points_near.size() < NUM_MATCH_POINTS || pointSearchSqDis[NUM_MATCH_POINTS - 1] > 5) planeValid = false; if (planeValid && check_normal) //check normal direction { float sum_diff_angle = 0; // angle between normals int num_fail_normal = 0; for (int j = 0; j < NUM_MATCH_POINTS; j++) { //check map points normal direction, to ensure lidar can see it if (!voxels_near[j]) continue; Eigen::Vector3f voxel_normal = voxels_near[j]->normal; if (voxel_normal.dot(body2point) > 0) { // point_selected_surf[i] = false; // planeValid = false; ++num_fail_normal; continue; } sum_diff_angle += acos(point_world.getNormalVector3fMap().dot(voxel_normal)); } // point normal and map surface normal are not consistent if (num_fail_normal >= NUM_MATCH_POINTS - 1 || sum_diff_angle / (float)(NUM_MATCH_POINTS - num_fail_normal) > angle ) // if (num_fail_normal >= NUM_MATCH_POINTS - 1) planeValid = false; } point_selected_surf[i] = planeValid; } if (!point_selected_surf[i]) continue; point_selected_surf[i] = false; VF(4) pabcd; //[n, d], n * p + d = 0 bool good_plane_feature = false; TicToc t_pca; VF(4) pabcd_surfel; bool good_surfel_feature = false; float p2surfel = 10000; V3F centroid; if (cloud_surfel) good_surfel_feature = cloudSurfel(voxels_near, pabcd_surfel, centroid, 0.15f); if (good_surfel_feature) { // PointType &point_nearest = nodes_near[0]->point; V3F cen2point(point_world.x - centroid(0), point_world.y - centroid(1), point_world.z -centroid(2)); p2surfel = pabcd_surfel.head(3).dot(cen2point); num_cloud_surfel++; } if (!good_surfel_feature && point_surfel) { //todo maybe not the nearest voxel, compute point to surfel probability, see VoxelMap if (voxels_near[0]) { PointType &point_nearest = points_near[0]; bool same_voxel = abs(point_nearest.x - point_world.x) <= half_map_size && abs(point_nearest.y - point_world.y) <= half_map_size && abs(point_nearest.z - point_world.z) <= half_map_size; const auto &voxel_info = voxels_near[0]; // point and nearest neighbor inside the same voxel // todo 3 * standard deviation if (same_voxel && (voxel_info->num_points < 0 || voxel_info->num_points > surfel_points_min)) { V3F plane_centroid(voxel_info->mean_x, voxel_info->mean_y, voxel_info->mean_z); V3F cen2point(point_world.x - plane_centroid(0), point_world.y - plane_centroid(1), point_world.z - plane_centroid(2)); p2surfel = voxel_info->normal.dot(cen2point); // V3F cen2near(point_nearest.x - plane_centroid(0), point_nearest.y - plane_centroid(1), // point_nearest.z - plane_centroid(2)); if (fabs(p2surfel) < 0.20f) { good_surfel_feature = true; pabcd_surfel.head(3) = voxel_info->normal; pabcd_surfel(3) = p2surfel; ++num_point_surfel; } } } } // TicToc t_esti_plane; if (good_surfel_feature) { pabcd = pabcd_surfel; good_plane_feature = true; } else good_plane_feature = esti_plane(pabcd, points_near, 0.1f); if (good_plane_feature) { //plane distance V3F p_body = point_body.getVector3fMap(); float pd2 = pabcd(0) * point_world.x + pabcd(1) * point_world.y + pabcd(2) * point_world.z + pabcd(3); float s = 1 - 0.9 * fabs(pd2) / sqrt(p_body.norm()); if (good_surfel_feature) { // std::cout<< "surfel normal :\n" <points[i]; V3D point_this_be(laser_p.x, laser_p.y, laser_p.z); M3D point_be_crossmat; point_be_crossmat << SKEW_SYM_MATRX(point_this_be); V3D point_this = s.offset_R_L_I * point_this_be + s.offset_T_L_I; M3D point_crossmat; point_crossmat<points[i]; V3D norm_vec(norm_p.x, norm_p.y, norm_p.z); /*** calculate the Measuremnt Jacobian matrix H ***/ V3D C(s.rot.conjugate() *norm_vec); V3D A(point_crossmat * C); // P(IMU)^ [R(imu <-- w) * normal_w] if (extrinsic_est_en) { // B = lidar_p^ R(L <-- I) * corr_normal_I // B = lidar_p^ R(L <-- I) * R(I <-- W) * normal_W V3D B(point_be_crossmat * s.offset_R_L_I.conjugate() * C); //s.rot.conjugate()*norm_vec); ekfom_data.h_x.block<1, 12>(i,0) << norm_p.x, norm_p.y, norm_p.z, VEC_FROM_ARRAY(A), VEC_FROM_ARRAY(B), VEC_FROM_ARRAY(C); } else { ekfom_data.h_x.block<1, 12>(i,0) << norm_p.x, norm_p.y, norm_p.z, VEC_FROM_ARRAY(A), 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; } /*** Measuremnt: distance to the closest surface/corner ***/ ekfom_data.h(i) = -norm_p.intensity; } solve_time += omp_get_wtime() - solve_start_; } void saveTraj(const string & pose_target_file) { //also interpolate pose at lidar begin time int begin_time_ptr = 0; int begin_time_size = timestamps_lidar.size(); double begin_time = timestamps_lidar[0]; // int end_time_ptr_left = 0; double end_time_left = path_target_end.poses[0].header.stamp.toSec(); while (begin_time_ptr < begin_time_size) { begin_time = timestamps_lidar[begin_time_ptr]; if (begin_time > end_time_left) break; ++begin_time_ptr; } printf("\n..............Saving path................\n"); printf("path file: %s\n", pose_target_file.c_str()); ofstream of_beg(pose_target_file); of_beg.setf(ios::fixed, ios::floatfield); of_beg.precision(12); of_beg<< path_target_end.poses[0].header.stamp.toSec()<< " " <("publish/path_en",path_en, true); nh.param("publish/scan_publish_en",scan_pub_en, true); nh.param("publish/dense_publish_en",dense_pub_en, true); nh.param("publish/scan_bodyframe_pub_en",scan_body_pub_en, true); nh.param("max_iteration",NUM_MAX_ITERATIONS,4); nh.param("map_file_path",map_file_path,""); nh.param("common/lid_topic",lid_topic,"/livox/lidar"); nh.param("common/imu_topic", imu_topic,"/livox/imu"); nh.param("common/time_sync_en", time_sync_en, false); nh.param("common/time_offset_lidar_to_imu", time_diff_lidar_to_imu, 0.0); nh.param("common/lidar_time_offset", lidar_time_offset, 0.0); nh.param("filter_size_corner",filter_size_corner_min,0.5); nh.param("filter_size_surf",filter_size_surf_min,0.5); nh.param("filter_size_map",filter_size_map_min,0.5); nh.param("cube_side_length",cube_len,200); nh.param("mapping/det_range",DET_RANGE,300.f); nh.param("mapping/fov_degree",fov_deg,180); nh.param("mapping/gyr_cov",gyr_cov,0.1); nh.param("mapping/acc_cov",acc_cov,0.1); nh.param("mapping/b_gyr_cov",b_gyr_cov,0.0001); nh.param("mapping/b_acc_cov",b_acc_cov,0.0001); nh.param("preprocess/blind", p_pre->blind, 0.01); nh.param("preprocess/lidar_type", p_pre->lidar_type, AVIA); nh.param("preprocess/scan_line", p_pre->N_SCANS, 16); nh.param("preprocess/scan_line", N_SCAN, 16); nh.param("preprocess/Horizon_SCAN", Horizon_SCAN, 1800); nh.param("preprocess/Horizon_SCAN", p_pre->Horizon_SCAN, 1800); nh.param("preprocess/timestamp_unit", p_pre->time_unit, US); nh.param("preprocess/scan_rate", p_pre->SCAN_RATE, 10); nh.param("point_filter_num", p_pre->point_filter_num, 2); nh.param("feature_extract_enable", p_pre->feature_enabled, false); nh.param("runtime_pos_log_enable", runtime_pos_log, 0); nh.param("mapping/extrinsic_est_en", extrinsic_est_en, true); nh.param("pcd_save/pcd_save_en", pcd_save_en, false); nh.param("pcd_save/save_ikdtree_map", save_ikdtree_map, false); nh.param("pcd_save/save_final_map", save_final_map, false); nh.param("pcd_save/interval", pcd_save_interval, -1); nh.param>("mapping/extrinsic_T", extrinT, vector()); nh.param>("mapping/extrinsic_R", extrinR, vector()); half_map_size = filter_size_map_min * 0.5; // surfel nh.param("surfel/planarity", planarity, 1.0f); nh.param("surfel/mid2min", mid2min, 100.0f); nh.param("surfel/surfel_points_min", surfel_points_min, 20); nh.param("surfel/surfel_points_max", surfel_points_max, 100); nh.param("surfel/angle_threshold", angle_threshold, 10.0); nh.param("surfel/cloud_surfel", cloud_surfel, true); nh.param("surfel/point_surfel", point_surfel, true); if (surfel_points_min < 20) surfel_points_min = 20; if (surfel_points_max < surfel_points_min * 2) surfel_points_max = surfel_points_min * 2; ikdtree.max_voxel_points_size = surfel_points_max; // ring Fals Normal Estimation parameters nh.param("normal/compute_table", p_pre->compute_table, false); nh.param("normal/compute_normal", p_pre->compute_normal, false); nh.param("normal/check_normal", check_normal, true); nh.param("normal/ring_table_dir", ring_table_dir, "/tmp"); std::string PROJECT_NAME = "log_lio"; std::string pkg_path = ros::package::getPath(PROJECT_NAME); ring_table_dir = pkg_path + ring_table_dir; p_pre->ring_table_dir = ring_table_dir; p_pre->runtime_log = runtime_pos_log; cout<<"p_pre->lidar_type "<lidar_type<initNormalEstimator(); //voxel map nh.param>("mapping/layer_point_size", layer_point_size,vector()); for (int i = 0; i < layer_point_size.size(); i++) { layer_size.push_back(layer_point_size[i]); } nh.param("mapping/max_layer", max_layer, 2); nh.param("mapping/max_points_size", max_points_size, 100); nh.param("mapping/max_cov_points_size", max_cov_points_size, 100); nh.param("mapping/voxel_size", max_voxel_size, 1.0); nh.param("mapping/plannar_threshold", min_eigen_value, 0.01); nh.param("mapping/voxel_hash_en", voxel_hash_en, true); ikdtree.layer_point_size = layer_size; ikdtree.max_layer = max_layer; ikdtree.max_points_size = max_points_size; ikdtree.max_cov_points_size = max_cov_points_size; ikdtree.max_voxel_size = max_voxel_size; // ikdtree.half_voxel_size = max_voxel_size * 0.5; ikdtree.min_eigen_value = min_eigen_value; path.header.stamp = ros::Time::now(); path.header.frame_id ="camera_init"; /*** variables definition ***/ int effect_feat_num = 0, frame_num = 0; double deltaT, deltaR, aver_time_consu = 0, aver_time_icp = 0, aver_time_match = 0, aver_time_incre = 0, aver_time_solve = 0, aver_time_const_H_time = 0; bool flg_EKF_converged, EKF_stop_flg = 0; // double aver_time_normal = 0; FOV_DEG = (fov_deg + 10.0) > 179.9 ? 179.9 : (fov_deg + 10.0); HALF_FOV_COS = cos((FOV_DEG) * 0.5 * PI_M / 180.0); _featsArray.reset(new PointCloudXYZI()); memset(point_selected_surf, true, sizeof(point_selected_surf)); memset(res_last, -1000.0f, sizeof(res_last)); downSizeFilterSurf.setLeafSize(filter_size_surf_min, filter_size_surf_min, filter_size_surf_min); downSizeFilterMap.setLeafSize(filter_size_map_min, filter_size_map_min, filter_size_map_min); memset(point_selected_surf, true, sizeof(point_selected_surf));//重复? memset(res_last, -1000.0f, sizeof(res_last)); Lidar_T_wrt_IMU<set_extrinsic(Lidar_T_wrt_IMU, Lidar_R_wrt_IMU); p_imu->set_gyr_cov(V3D(gyr_cov, gyr_cov, gyr_cov)); p_imu->set_acc_cov(V3D(acc_cov, acc_cov, acc_cov)); p_imu->set_gyr_bias_cov(V3D(b_gyr_cov, b_gyr_cov, b_gyr_cov)); p_imu->set_acc_bias_cov(V3D(b_acc_cov, b_acc_cov, b_acc_cov)); double epsi[23] = {0.001}; fill(epsi, epsi+23, 0.001); kf.init_dyn_share(get_f, df_dx, df_dw, h_share_model, NUM_MAX_ITERATIONS, epsi); /*** debug record ***/ FILE *fp; string pos_log_dir = root_dir + "/Log/pos_log.txt"; fp = fopen(pos_log_dir.c_str(),"w"); ofstream fout_pre, fout_out, fout_dbg; fout_pre.open(DEBUG_FILE_DIR("mat_pre.txt"),ios::out); fout_out.open(DEBUG_FILE_DIR("mat_out.txt"),ios::out); fout_dbg.open(DEBUG_FILE_DIR("dbg.txt"),ios::out); if (fout_pre && fout_out) cout << "~~~~"<>("ground_truth/extrinsic_T", gt_extrinT, vector()); nh.param>("ground_truth/extrinsic_R", gt_extrinR, vector()); gt_T_wrt_IMU<lidar_type == AVIA ? \ // nh.subscribe(lid_topic, 200000, livox_pcl_cbk) : \ // nh.subscribe(lid_topic, 200000, standard_pcl_cbk); ros::Subscriber sub_pcl = nh.subscribe(lid_topic, 200000, standard_pcl_cbk); ros::Subscriber sub_imu = nh.subscribe(imu_topic, 200000, imu_cbk); ros::Publisher pubLaserCloudFull = nh.advertise ("/cloud_registered", 100000); ros::Publisher pubLaserCloudFull_body = nh.advertise ("/cloud_registered_body", 100000); ros::Publisher pubLaserCloudEffect = nh.advertise ("/cloud_effected", 100000); ros::Publisher pubLaserCloudMap = nh.advertise ("/Laser_map", 100000); ros::Publisher pubOdomAftMapped = nh.advertise ("/Odometry", 100000); ros::Publisher pubPath = nh.advertise ("/path", 100000); //------------------------------------------------------------------------------------------------------ signal(SIGINT, SigHandle); ros::Rate rate(5000); bool status = ros::ok(); while (status) { if (flg_exit) break; ros::spinOnce(); if(sync_packages(Measures)) { if (flg_first_scan) { first_lidar_time = Measures.lidar_beg_time; p_imu->first_lidar_time = first_lidar_time; flg_first_scan = false; continue; } double t0,t1,t2,t3,t4,t5,match_start, solve_start, svd_time; match_time = 0; kdtree_search_time = 0.0; solve_time = 0; solve_const_H_time = 0; svd_time = 0; t0 = omp_get_wtime(); p_imu->Process(Measures, kf, feats_undistort); state_point = kf.get_x(); auto state_cov = kf.get_P(); pos_lid = state_point.pos + state_point.rot * state_point.offset_T_L_I; if (feats_undistort->empty() || (feats_undistort == NULL)) { ROS_WARN("No point, skip this scan!\n"); continue; } flg_EKF_inited = (Measures.lidar_beg_time - first_lidar_time) < INIT_TIME ? false : true; /*** Segment the map in lidar FOV ***/ lasermap_fov_segment(); //todo do not downsample the very first scan here but in the tree building /*** downsample the feature points in a scan ***/ downSizeFilterSurf.setInputCloud(feats_undistort); downSizeFilterSurf.filter(*feats_down_body); // cloud in lidar frame for (auto & p : feats_down_body->points) p.getNormalVector3fMap().normalize(); // pcl::io::savePCDFile("/tmp/feats_down_body.pcd", *feats_down_body); ROS_INFO("feats_undistort: %d, feats_down_body: %d", (int)feats_undistort->size(), (int)feats_down_body->size()); t1 = omp_get_wtime(); feats_down_size = feats_down_body->points.size(); /*** initialize the map kdtree ***/ if(ikdtree.Root_Node == nullptr) { double t_init_map = omp_get_wtime(); if(feats_down_size > 5) { ikdtree.set_downsample_param(filter_size_map_min); feats_down_world->resize(feats_down_size); for(int i = 0; i < feats_down_size; i++) { pointNormalBodyToWorld(&(feats_down_body->points[i]), &(feats_down_world->points[i]));//point: world <-- imu <-- lidar } ikdtree.Build(feats_down_world->points); } continue; } /*** ICP and iterated Kalman filter update ***/ if (feats_down_size < 5) { ROS_WARN("No point, skip this scan!\n"); continue; } normvec->resize(feats_down_size); feats_down_world->resize(feats_down_size); // lidar --> imu V3D ext_euler = SO3ToEuler(state_point.offset_R_L_I); fout_pre<clear(); featsFromMap->points = ikdtree.PCL_Storage; featsFromMap->resize(featsFromMap->points.size()); pcl::io::savePCDFile("/tmp/ikdtree_map.pcd", *featsFromMap); } } pointSearchInd_surf.resize(feats_down_size); Nearest_Points.resize(feats_down_size); Nearest_Nodes.resize(feats_down_size); int rematch_num = 0; bool nearest_search_en = true; // t2 = omp_get_wtime(); /*** iterated state estimation ***/ double t_update_start = omp_get_wtime(); double solve_H_time = 0; num_cloud_surfel = 0; num_point_surfel = 0; kf.update_iterated_dyn_share_modified(LASER_POINT_COV, solve_H_time); ROS_INFO("[association]: cloud surfel: %d, point surfel: %d", num_cloud_surfel / NUM_MAX_ITERATIONS, num_point_surfel / NUM_MAX_ITERATIONS); state_point = kf.get_x(); euler_cur = SO3ToEuler(state_point.rot); pos_lid = state_point.pos + state_point.rot * state_point.offset_T_L_I; geoQuat.x = state_point.rot.coeffs()[0]; geoQuat.y = state_point.rot.coeffs()[1]; geoQuat.z = state_point.rot.coeffs()[2]; geoQuat.w = state_point.rot.coeffs()[3]; double t_update_end = omp_get_wtime(); /******* Publish odometry *******/ publish_odometry(pubOdomAftMapped); /*** add the feature points to map kdtree ***/ t3 = omp_get_wtime(); map_incremental(); t5 = omp_get_wtime(); ROS_INFO("map_incremental %d surfels: %d", ikdtree.validnum(), num_surfel); // pcl::io::savePCDFile("/tmp/feats_down_world.pcd", *feats_down_world); // /*** add the points to the voxel map ***/ // voxel_map_incremental(); /******* Publish points *******/ if (path_en) publish_path(pubPath); if (scan_pub_en || pcd_save_en) publish_frame_world(pubLaserCloudFull); if (scan_pub_en && scan_body_pub_en) publish_frame_body(pubLaserCloudFull_body); // publish_effect_world(pubLaserCloudEffect); // publish_map(pubLaserCloudMap); /*** Debug variables ***/ if (runtime_pos_log) { ROS_INFO("feats_undistort: %d, feats_down_body: %d", (int)feats_undistort->size(), (int)feats_down_body->size()); ROS_INFO("[association]: cloud sufel: %d, point surfel: %d", num_cloud_surfel / NUM_MAX_ITERATIONS, num_point_surfel / NUM_MAX_ITERATIONS); ROS_INFO("[map_incremental] tree valid: %d surfels: %d", ikdtree.validnum(), num_surfel); frame_num ++; kdtree_size_end = ikdtree.size(); aver_time_consu = aver_time_consu * (frame_num - 1) / frame_num + (t5 - t0) / frame_num; aver_time_icp = aver_time_icp * (frame_num - 1)/frame_num + (t_update_end - t_update_start) / frame_num; aver_time_match = aver_time_match * (frame_num - 1)/frame_num + (match_time)/frame_num; aver_time_incre = aver_time_incre * (frame_num - 1)/frame_num + (kdtree_incremental_time)/frame_num; aver_time_solve = aver_time_solve * (frame_num - 1)/frame_num + (solve_time + solve_H_time)/frame_num; aver_time_const_H_time = aver_time_const_H_time * (frame_num - 1)/frame_num + solve_time / frame_num; // aver_time_normal = aver_time_normal * (frame_num - 1)/frame_num + t_normal / frame_num; T1[time_log_counter] = Measures.lidar_beg_time; s_plot[time_log_counter] = t5 - t0; s_plot2[time_log_counter] = feats_undistort->points.size(); s_plot3[time_log_counter] = kdtree_incremental_time; s_plot4[time_log_counter] = kdtree_search_time; s_plot5[time_log_counter] = kdtree_delete_counter; s_plot6[time_log_counter] = kdtree_delete_time; s_plot7[time_log_counter] = kdtree_size_st; s_plot8[time_log_counter] = kdtree_size_end; s_plot9[time_log_counter] = aver_time_consu; s_plot10[time_log_counter] = add_point_size; time_log_counter ++; printf("[ mapping ]: time: IMU + Map + Cov + Input Downsample: %0.6f this ICP: %0.6f this map incre: %0.6f ave match: %0.6f ave solve: %0.6f ave total: %0.6f ave icp: %0.6f ave construct H: %0.6f\n", t1-t0, t3-t1, t5-t3, aver_time_match, aver_time_solve, aver_time_consu, aver_time_icp, aver_time_const_H_time); ext_euler = SO3ToEuler(state_point.offset_R_L_I); fout_out << setw(20) << Measures.lidar_beg_time - first_lidar_time << " " << euler_cur.transpose() << " " << state_point.pos.transpose()<< " " << ext_euler.transpose() << " "<points.size()<size() > 0 && pcd_save_en) { string file_name = string("scans.pcd"); string all_points_dir(string(string(ROOT_DIR) + "PCD/") + file_name); pcl::PCDWriter pcd_writer; cout << "current scan saved to /PCD/" << file_name< t, s_vec, s_vec2, s_vec3, s_vec4, s_vec5, s_vec6, s_vec7; FILE *fp2; string log_dir = root_dir + "/Log/fast_lio_time_log.csv"; fp2 = fopen(log_dir.c_str(),"w"); fprintf(fp2,"time_stamp, total time, scan point size, incremental time, search time, delete size, delete time, tree size st, tree size end, add point size, preprocess time\n"); for (int i = 0;iclear(); featsFromMap->points = ikdtree.PCL_Storage; featsFromMap->resize(featsFromMap->points.size()); pcl::io::savePCDFile("/tmp/ikdtree_final_map.pcd", *featsFromMap); } // not test yet if (p_pre->compute_table) { TicToc t_m; printf(".....Computing M inverse....\n"); p_pre->range_image.computeMInverse(); printf("Computing M inverse cost: %fms\n", t_m.toc()); printf(".....Saving range image lookup table....\n"); p_pre->range_image.saveLookupTable(p_pre->ring_table_dir, "ring" + std::to_string(N_SCAN)); } printf(".....[ikdtree] voxel2node: %d, voxel2info: %d\n", (int)ikdtree.voxel2node.size(), (int)ikdtree.voxel2info.size()); printf(".....check corresponding....\n"); ikdtree.checkCorrespondding(ikdtree.Root_Node); printf("nodes %d\n", ikdtree.num_nodes); printf("node --> voxel null %d --> info null %d\n", ikdtree.num_node2_voxel_null, ikdtree.voxel2info_null); printf("node --> voxel valid %d --> info valid %d\n", ikdtree.num_node2voxel_valid, ikdtree.voxel2info_valid); printf("node --> info same %d diff %d\n", ikdtree.num_same_info, ikdtree.num_diff_info); printf("node point --> voxel same %d\n", ikdtree.num_same_voxel_by_pointAndnode); int num_no_points = 0, num_fixed_voxel = 0, num_active_voxel = 0; int num_voxels = 0; double mean_active_points = 0; unsigned int sum_active_points = 0; for (auto a : ikdtree.voxel2info) { if (a.second->num_points < 0 || a.second->num_points >= surfel_points_max) ++num_fixed_voxel; else if (a.second->num_points == 0) ++num_no_points; else { ++num_active_voxel; sum_active_points += a.second->num_points; mean_active_points = mean_active_points * (double)(num_active_voxel - 1) / (double)(num_active_voxel) + (double)a.second->num_points / (double)num_active_voxel; } ++num_voxels; } printf("num_no_points %d num_fixed_voxel %d num_active_voxel %d active points sum: %d mean: %f\n", num_no_points, num_fixed_voxel, num_active_voxel, sum_active_points, mean_active_points); return 0; } ================================================ FILE: src/preprocess.cpp ================================================ #include "preprocess.h" #include "point_type.h" #include "tic_toc.h" #define RETURN0 0x00 #define RETURN0AND1 0x10 Preprocess::Preprocess() :feature_enabled(0), lidar_type(AVIA), blind(0.01), point_filter_num(1) { inf_bound = 10; N_SCANS = 6; SCAN_RATE = 10; group_size = 8; disA = 0.01; disA = 0.1; // B? p2l_ratio = 225; limit_maxmid =6.25; limit_midmin =6.25; limit_maxmin = 3.24; jump_up_limit = 170.0; jump_down_limit = 8.0; cos160 = 160.0; edgea = 2; edgeb = 0.1; smallp_intersect = 172.5; smallp_ratio = 1.2; given_offset_time = false; jump_up_limit = cos(jump_up_limit/180*M_PI); jump_down_limit = cos(jump_down_limit/180*M_PI); cos160 = cos(cos160/180*M_PI); smallp_intersect = cos(smallp_intersect/180*M_PI); } Preprocess::~Preprocess() {} void Preprocess::set(bool feat_en, int lid_type, double bld, int pfilt_num) { feature_enabled = feat_en; lidar_type = lid_type; blind = bld; point_filter_num = pfilt_num; } //void Preprocess::process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out) //{ // avia_handler(msg); // *pcl_out = pl_surf; //} void Preprocess::saveNormalPCD(const std::string& file_name, const pcl::PointCloud::Ptr& cloud, const cv::Mat& normals_mat) { ROS_ASSERT(rangeMat.size == normals_mat.size); pcl::PointCloud::Ptr cloud_normal(new pcl::PointCloud); for (int i = 0; i < normals_mat.rows; ++i) { for (int j = 0; j < normals_mat.cols; ++j) { if (rangeMat.at(i, j) == FLT_MAX) //如果该珊格已经有点,则珊格内不再加入后续的点 continue; //// int index = j + i * normals_mat.cols; //点在深度图像中的索引 const int index = image2cloud[j + i * image_cols]; const PointXYZIRT& thisPoint = cloud->points[index]; // int index = j + i * normals_mat.cols; //点在深度图像中的索引 // const PointType& thisPoint = fullCloud->points[index]; pcl::PointXYZINormal pn; pn.x = thisPoint.x; pn.y = thisPoint.y; pn.z = thisPoint.z; const cv::Vec3f & n_cv = normals_mat.at(i, j); pn.normal_x = n_cv(0); pn.normal_y = n_cv(1); pn.normal_z = n_cv(2); cloud_normal->push_back(pn); } } // if (cloud_normal->size() > 0) // pcl::io::savePCDFile(file_name, *cloud_normal); } void Preprocess::projectPointCloud(const pcl::PointCloud::Ptr& cloud) { // if (!compute_table) rangeMat = cv::Mat(N_SCANS, image_cols, CV_32F, cv::Scalar::all(FLT_MAX)); image2cloud.clear(); image2cloud.resize(N_SCANS * image_cols, -1); TicToc t_range_image; int cloudSize = (int)cloud->points.size(); cloud2image.clear(); cloud2image.resize(cloudSize, -1); // range image projection for (int i = 0; i < cloudSize; ++i) { const PointXYZIRT& thisPoint = cloud->points[i]; int rowIdn, columnIdn; if (!pointInImage(thisPoint, rowIdn, columnIdn)) continue; float range = sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y + thisPoint.z * thisPoint.z);// sqrt(x^2 + y^2 + z^2) rangeMat.at(rowIdn, columnIdn) = range; //record range after correcting int index = columnIdn + rowIdn * image_cols; image2cloud[index] = i; cloud2image[i] = index; } } void Preprocess::computeRingNormals(const pcl::PointCloud::Ptr& cloud) { // not test yet if (compute_table) { TicToc t_range_image; range_image.buildTableFromRings(cloud); ROS_WARN("build range image from rings cost: %fms", t_range_image.toc()); return; } TicToc t_normal; range_image.computeNormals(rangeMat, normals, plane_residual); ///output: normalized normals } void Preprocess::flipNormalsTowardCenterAndNormalized(const cv::Vec3f& center, const pcl::PointCloud::Ptr& cloud, cv::Mat& image_normals) { ROS_ASSERT(rangeMat.size == image_normals.size); for (int i = 0; i < N_SCANS; ++i)//row for (int j = 0; j < image_cols; ++j) if (rangeMat.at(i, j) != FLT_MAX) { const int point_id = image2cloud[j + i * image_cols]; const PointXYZIRT &thisPoint = cloud->points[point_id]; // vector: from center to point cv::Vec3f vc2p(thisPoint.x - center(0), thisPoint.y - center(1), thisPoint.z - center(2)); vc2p /= norm(vc2p); cv::Vec3f &n = image_normals.at(i, j); ///already normalized if (vc2p.dot(n) > 0) n *= -1; } } void Preprocess::NormalizeNormals(cv::Mat& image_normals) { ROS_ASSERT(rangeMat.size == image_normals.size); for (int i = 0; i < N_SCANS; ++i) for (int j = 0; j < image_cols; ++j) if (rangeMat.at(i, j) != FLT_MAX) { cv::Vec3f &n = image_normals.at(i, j); n /= norm(n); } } void Preprocess::extractCloudAndNormals(const pcl::PointCloud::Ptr& cloud) { TicToc t_flip; cv::Vec3f lidar(0, 0, 0); flipNormalsTowardCenterAndNormalized(lidar, cloud, normals); // smooth normals after flipping TicToc t_smo; cv::medianBlur(normals, normals, 5); NormalizeNormals(normals); return; cloud_with_normal.reset(new PointCloudXYZI()); cloud_with_normal->resize(cloud->size()); int p = 0; TicToc t_e; int num_filtered = 0; int count = 0; // extract segmented cloud for lidar odometry for (int i = 0; i < N_SCANS; ++i) { for (int j = 0; j < image_cols; ++j) { if (rangeMat.at(i,j) != FLT_MAX)//深度图内有信息 { ++count; if (count % point_filter_num != 0) continue; // save extracted cloud const int point_id = image2cloud[j + i * image_cols]; const cv::Vec3f & n_cv = normals.at(i, j); cloud_with_normal->points[point_id].normal_x = n_cv(0); cloud_with_normal->points[point_id].normal_y = n_cv(1); cloud_with_normal->points[point_id].normal_z = n_cv(2); } } } } void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out) { switch (time_unit) { case SEC: time_unit_scale = 1.e3f; break; case MS: time_unit_scale = 1.f; break; case US: time_unit_scale = 1.e-3f; break; case NS: time_unit_scale = 1.e-6f; break; default: time_unit_scale = 1.f; break; } switch (lidar_type) { case OUSTER: ouster_handler(msg); break; case VELODYNE: velodyne_handler(msg); break; default: printf("Error LiDAR Type"); break; } *pcl_out = pl_surf; } void Preprocess::estimateNormals(const pcl::PointCloud::Ptr& cloud) { TicToc t_1; projectPointCloud(cloud); proj_time = t_1.toc(); TicToc t_2; computeRingNormals(cloud); compu_time = t_2.toc(); TicToc t_3; if (!compute_table) { extractCloudAndNormals(cloud); } smooth_time = t_3.toc(); } // //void Preprocess::avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg) //{ // pl_surf.clear(); // pl_corn.clear(); // pl_full.clear(); // double t1 = omp_get_wtime(); // int plsize = msg->point_num; // // cout<<"plsie: "<points[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) // { // pl_full[i].x = msg->points[i].x; // pl_full[i].y = msg->points[i].y; // pl_full[i].z = msg->points[i].z; // pl_full[i].intensity = msg->points[i].reflectivity; // pl_full[i].curvature = msg->points[i].offset_time / float(1000000); //use curvature as time of each laser points // // bool is_new = false; // if((abs(pl_full[i].x - pl_full[i-1].x) > 1e-7) // || (abs(pl_full[i].y - pl_full[i-1].y) > 1e-7) // || (abs(pl_full[i].z - pl_full[i-1].z) > 1e-7)) // { // pl_buff[msg->points[i].line].push_back(pl_full[i]); // } // } // } // static int count = 0; // static double time = 0.0; // count ++; // double t0 = omp_get_wtime(); // for(int j=0; j &pl = pl_buff[j]; // plsize = pl.size(); // vector &types = typess[j]; // types.clear(); // types.resize(plsize); // plsize--; // for(uint i=0; ipoints[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) // { // valid_num ++; // if (valid_num % point_filter_num == 0) // { // pl_full[i].x = msg->points[i].x; // pl_full[i].y = msg->points[i].y; // pl_full[i].z = msg->points[i].z; // pl_full[i].intensity = msg->points[i].reflectivity; // pl_full[i].curvature = msg->points[i].offset_time / float(1000000); // use curvature as time of each laser points, curvature unit: ms // // if(((abs(pl_full[i].x - pl_full[i-1].x) > 1e-7) // || (abs(pl_full[i].y - pl_full[i-1].y) > 1e-7) // || (abs(pl_full[i].z - pl_full[i-1].z) > 1e-7)) // && (pl_full[i].x * pl_full[i].x + pl_full[i].y * pl_full[i].y + pl_full[i].z * pl_full[i].z > (blind * blind))) // { // pl_surf.push_back(pl_full[i]); // } // } // } // } // } //} void Preprocess::ouster2velodyne(const pcl::PointCloud& cloud_in, const pcl::PointCloud::Ptr& cloud_out) { int cloud_size = cloud_in.size(); cloud_out->resize(cloud_size); for (int i = 0; i < cloud_size; ++i) { const ouster_ros::Point& p_in = cloud_in[i]; PointXYZIRT& p_out = cloud_out->points[i]; p_out.getVector4fMap() = p_in.getVector4fMap(); p_out.ring = p_in.ring; } } void Preprocess::ouster_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) { pl_surf.clear(); pl_corn.clear(); pl_full.clear(); pcl::PointCloud pl_orig; pcl::fromROSMsg(*msg, pl_orig); pcl::PointCloud::Ptr cloud_tmp(new pcl::PointCloud()); ouster2velodyne(pl_orig, cloud_tmp); if (compute_normal) { TicToc t_nor; estimateNormals(cloud_tmp); // get cloud_with_normal if (runtime_log) { num_scans++; aver_normal_time = aver_normal_time * (num_scans - 1) / num_scans + t_nor.toc() / num_scans; aver_proj_time = aver_proj_time * (num_scans - 1) / num_scans + proj_time / num_scans; aver_compu_time = aver_compu_time * (num_scans - 1) / num_scans + compu_time / num_scans; aver_smooth_time = aver_smooth_time * (num_scans - 1) / num_scans + smooth_time / num_scans; ROS_INFO("[normal] mean project %0.3fms, compute %0.3fms, smooth %0.3fms, total %0.3fms", aver_proj_time, aver_compu_time, aver_smooth_time, aver_normal_time); } } int plsize = pl_orig.size(); pl_corn.reserve(plsize); pl_surf.reserve(plsize); if (feature_enabled) { for (int i = 0; i < N_SCANS; i++) { pl_buff[i].clear(); pl_buff[i].reserve(plsize); } for (uint i = 0; i < plsize; i++) { double range = pl_orig.points[i].x * pl_orig.points[i].x + pl_orig.points[i].y * pl_orig.points[i].y + pl_orig.points[i].z * pl_orig.points[i].z; if (range < (blind * blind)) continue; Eigen::Vector3d pt_vec; PointType added_pt; added_pt.x = pl_orig.points[i].x; added_pt.y = pl_orig.points[i].y; added_pt.z = pl_orig.points[i].z; added_pt.intensity = pl_orig.points[i].intensity; added_pt.normal_x = cloud_with_normal->points[i].normal_x;// normal_x record ring added_pt.normal_y = cloud_with_normal->points[i].normal_y; added_pt.normal_z = cloud_with_normal->points[i].normal_z; double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.3; if (yaw_angle >= 180.0) yaw_angle -= 360.0; if (yaw_angle <= -180.0) yaw_angle += 360.0; added_pt.curvature = pl_orig.points[i].t * time_unit_scale; if(pl_orig.points[i].ring < N_SCANS) { pl_buff[pl_orig.points[i].ring].push_back(added_pt); } } for (int j = 0; j < N_SCANS; j++) { PointCloudXYZI &pl = pl_buff[j]; int linesize = pl.size(); vector &types = typess[j]; types.clear(); types.resize(linesize); linesize--; for (uint i = 0; i < linesize; i++) { types[i].range = sqrt(pl[i].x * pl[i].x + pl[i].y * pl[i].y); vx = pl[i].x - pl[i + 1].x; vy = pl[i].y - pl[i + 1].y; vz = pl[i].z - pl[i + 1].z; types[i].dista = vx * vx + vy * vy + vz * vz; } types[linesize].range = sqrt(pl[linesize].x * pl[linesize].x + pl[linesize].y * pl[linesize].y); give_feature(pl, types); } } else { double time_stamp = msg->header.stamp.toSec(); // cout << "===================================" << endl; // printf("Pt size = %d, N_SCANS = %d\r\n", plsize, N_SCANS); for (int i = 0; i < pl_orig.points.size(); i++) { if (i % point_filter_num != 0) continue; double range = pl_orig.points[i].x * pl_orig.points[i].x + pl_orig.points[i].y * pl_orig.points[i].y + pl_orig.points[i].z * pl_orig.points[i].z; if (range < (blind * blind)) continue; Eigen::Vector3d pt_vec; PointType added_pt; added_pt.x = pl_orig.points[i].x; added_pt.y = pl_orig.points[i].y; added_pt.z = pl_orig.points[i].z; added_pt.intensity = pl_orig.points[i].intensity; added_pt.curvature = pl_orig.points[i].t * time_unit_scale; // curvature unit: ms const int & index = cloud2image[i]; if (compute_normal && index > 0) { int rowIdn, columnIdn; rowIdn = index / image_cols; columnIdn = index - rowIdn * image_cols; const cv::Vec3f &n_cv = normals.at(rowIdn, columnIdn); if (!std::isfinite(n_cv(0)) || !std::isfinite(n_cv(1)) || !std::isfinite(n_cv(2))) continue; added_pt.normal_x = n_cv(0); added_pt.normal_y = n_cv(1); added_pt.normal_z = n_cv(2); } pl_surf.points.push_back(added_pt); } } // pub_func(pl_surf, pub_full, msg->header.stamp); // pub_func(pl_surf, pub_corn, msg->header.stamp); } void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) { pl_surf.clear(); pl_corn.clear(); pl_full.clear(); pcl::PointCloud::Ptr pl_orig(new pcl::PointCloud()); // pcl::PointCloud::Ptr pl_orig; pcl::fromROSMsg(*msg, *pl_orig); int plsize = pl_orig->points.size(); // ROS_INFO("cloud input size: %d", plsize); if (compute_normal) { TicToc t_nor; estimateNormals(pl_orig); // get cloud_with_normal if (runtime_log) { num_scans++; aver_normal_time = aver_normal_time * (num_scans - 1) / num_scans + t_nor.toc() / num_scans; aver_proj_time = aver_proj_time * (num_scans - 1) / num_scans + proj_time / num_scans; aver_compu_time = aver_compu_time * (num_scans - 1) / num_scans + compu_time / num_scans; aver_smooth_time = aver_smooth_time * (num_scans - 1) / num_scans + smooth_time / num_scans; ROS_INFO("[normal] mean project %0.3fms, compute %0.3fms, smooth %0.3fms, total %0.3fms", aver_proj_time, aver_compu_time, aver_smooth_time, aver_normal_time); } } if (plsize == 0) return; pl_surf.reserve(plsize); /*** These variables only works when no point timestamps given ***/ double omega_l = 0.361 * SCAN_RATE; // scan angular velocity std::vector is_first(N_SCANS,true); std::vector yaw_fp(N_SCANS, 0.0); // yaw of first scan point std::vector yaw_last(N_SCANS, 0.0); // yaw of last scan point std::vector time_last(N_SCANS, 0.0); // last offset time /*****************************************************************/ if (pl_orig->points[plsize - 1].time > 0) { given_offset_time = true; } else { given_offset_time = false; double yaw_first = atan2(pl_orig->points[0].y, pl_orig->points[0].x) * 57.29578; double yaw_end = yaw_first; int layer_first = pl_orig->points[0].ring; for (uint i = plsize - 1; i > 0; i--) { if (pl_orig->points[i].ring == layer_first) { yaw_end = atan2(pl_orig->points[i].y, pl_orig->points[i].x) * 57.29578; break; } } } if(feature_enabled) { for (int i = 0; i < N_SCANS; i++) { pl_buff[i].clear(); pl_buff[i].reserve(plsize); } for (int i = 0; i < plsize; i++) { PointType added_pt; added_pt.normal_x = cloud_with_normal->points[i].normal_x; added_pt.normal_y = cloud_with_normal->points[i].normal_y; added_pt.normal_z = cloud_with_normal->points[i].normal_z; int layer = pl_orig->points[i].ring; if (layer >= N_SCANS) continue; added_pt.x = pl_orig->points[i].x; added_pt.y = pl_orig->points[i].y; added_pt.z = pl_orig->points[i].z; added_pt.intensity = pl_orig->points[i].intensity; added_pt.curvature = pl_orig->points[i].time * time_unit_scale; // units: ms if (!given_offset_time) { double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.2957; if (is_first[layer]) { // printf("layer: %d; is first: %d", layer, is_first[layer]); yaw_fp[layer]=yaw_angle; is_first[layer]=false; added_pt.curvature = 0.0; yaw_last[layer]=yaw_angle; time_last[layer]=added_pt.curvature; continue; } if (yaw_angle <= yaw_fp[layer]) { added_pt.curvature = (yaw_fp[layer]-yaw_angle) / omega_l; } else { added_pt.curvature = (yaw_fp[layer]-yaw_angle+360.0) / omega_l; } if (added_pt.curvature < time_last[layer]) added_pt.curvature+=360.0/omega_l; yaw_last[layer] = yaw_angle; time_last[layer]=added_pt.curvature; } pl_buff[layer].points.push_back(added_pt); } for (int j = 0; j < N_SCANS; j++) { PointCloudXYZI &pl = pl_buff[j]; int linesize = pl.size(); if (linesize < 2) continue; vector &types = typess[j]; types.clear(); types.resize(linesize); linesize--; for (uint i = 0; i < linesize; i++) { types[i].range = sqrt(pl[i].x * pl[i].x + pl[i].y * pl[i].y); vx = pl[i].x - pl[i + 1].x; vy = pl[i].y - pl[i + 1].y; vz = pl[i].z - pl[i + 1].z; types[i].dista = vx * vx + vy * vy + vz * vz; } types[linesize].range = sqrt(pl[linesize].x * pl[linesize].x + pl[linesize].y * pl[linesize].y); give_feature(pl, types); } } else { for (int i = 0; i < plsize; i++) { PointType added_pt; const PointXYZIRT& orig_pt = pl_orig->points[i]; // cout<<"!!!!!!"< (blind * blind)) { // if (!pointInImage(orig_pt, rowIdn, columnIdn)) // continue; const int & index = cloud2image[i]; if (compute_normal && index > 0) { int rowIdn, columnIdn; rowIdn = index / image_cols; columnIdn = index - rowIdn * image_cols; const cv::Vec3f &n_cv = normals.at(rowIdn, columnIdn); if (!std::isfinite(n_cv(0)) || !std::isfinite(n_cv(1)) || !std::isfinite(n_cv(2))) continue; added_pt.normal_x = n_cv(0); added_pt.normal_y = n_cv(1); added_pt.normal_z = n_cv(2); } pl_surf.points.push_back(added_pt); } } } } pl_surf.resize(pl_surf.points.size()); } bool Preprocess::pointInImage(const PointXYZIRT& point, int& rowIdn, int& columnIdn) { rowIdn = (int)point.ring; // ring,即行索引,此前以用normal_x记录 if (rowIdn < 0 || rowIdn >= N_SCANS) return false; float horizonAngle = atan2(point.y, -point.x); if (horizonAngle < 0) horizonAngle += 2 * M_PI; horizonAngle = horizonAngle * 180 / M_PI; columnIdn = round(horizonAngle/ ang_res_x); //计算列索引, x轴正向为中间列 if (columnIdn < 0 || columnIdn >= image_cols) return false; return true; } void Preprocess::give_feature(pcl::PointCloud &pl, vector &types) { int plsize = pl.size(); int plsize2; if(plsize == 0) { printf("something wrong\n"); return; } uint head = 0; while(types[head].range < blind) { head++; } // Surf plsize2 = (plsize > group_size) ? (plsize - group_size) : 0; Eigen::Vector3d curr_direct(Eigen::Vector3d::Zero()); Eigen::Vector3d last_direct(Eigen::Vector3d::Zero()); uint i_nex = 0, i2; uint last_i = 0; uint last_i_nex = 0; int last_state = 0; int plane_type; for(uint i=head; i0.5) if(last_state==1 && last_direct.norm()>0.1) { double mod = last_direct.transpose() * curr_direct; if(mod>-0.707 && mod<0.707) { types[i].ftype = Edge_Plane; } else { types[i].ftype = Real_Plane; } } i = i_nex - 1; last_state = 1; } else // if(plane_type == 2) { i = i_nex; last_state = 0; } last_i = i2; last_i_nex = i_nex; last_direct = curr_direct; } plsize2 = plsize > 3 ? plsize - 3 : 0; for(uint i=head+3; i=Real_Plane) { continue; } if(types[i-1].dista<1e-16 || types[i].dista<1e-16) { continue; } Eigen::Vector3d vec_a(pl[i].x, pl[i].y, pl[i].z); Eigen::Vector3d vecs[2]; for(int j=0; j<2; j++) { int m = -1; if(j == 1) { m = 1; } if(types[i+m].range < blind) { if(types[i].range > inf_bound) { types[i].edj[j] = Nr_inf; } else { types[i].edj[j] = Nr_blind; } continue; } vecs[j] = Eigen::Vector3d(pl[i+m].x, pl[i+m].y, pl[i+m].z); vecs[j] = vecs[j] - vec_a; types[i].angle[j] = vec_a.dot(vecs[j]) / vec_a.norm() / vecs[j].norm(); if(types[i].angle[j] < jump_up_limit) { types[i].edj[j] = Nr_180; } else if(types[i].angle[j] > jump_down_limit) { types[i].edj[j] = Nr_zero; } } types[i].intersect = vecs[Prev].dot(vecs[Next]) / vecs[Prev].norm() / vecs[Next].norm(); if(types[i].edj[Prev]==Nr_nor && types[i].edj[Next]==Nr_zero && types[i].dista>0.0225 && types[i].dista>4*types[i-1].dista) { if(types[i].intersect > cos160) { if(edge_jump_judge(pl, types, i, Prev)) { types[i].ftype = Edge_Jump; } } } else if(types[i].edj[Prev]==Nr_zero && types[i].edj[Next]== Nr_nor && types[i-1].dista>0.0225 && types[i-1].dista>4*types[i].dista) { if(types[i].intersect > cos160) { if(edge_jump_judge(pl, types, i, Next)) { types[i].ftype = Edge_Jump; } } } else if(types[i].edj[Prev]==Nr_nor && types[i].edj[Next]==Nr_inf) { if(edge_jump_judge(pl, types, i, Prev)) { types[i].ftype = Edge_Jump; } } else if(types[i].edj[Prev]==Nr_inf && types[i].edj[Next]==Nr_nor) { if(edge_jump_judge(pl, types, i, Next)) { types[i].ftype = Edge_Jump; } } else if(types[i].edj[Prev]>Nr_nor && types[i].edj[Next]>Nr_nor) { if(types[i].ftype == Nor) { types[i].ftype = Wire; } } } plsize2 = plsize-1; double ratio; for(uint i=head+1; i types[i].dista) { ratio = types[i-1].dista / types[i].dista; } else { ratio = types[i].dista / types[i-1].dista; } if(types[i].intersect &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct) { double group_dis = disA*types[i_cur].range + disB; group_dis = group_dis * group_dis; // i_nex = i_cur; double two_dis; vector disarr; disarr.reserve(20); for(i_nex=i_cur; i_nex= pl.size()) || (i_nex >= pl.size())) break; if(types[i_nex].range < blind) { curr_direct.setZero(); return 2; } vx = pl[i_nex].x - pl[i_cur].x; vy = pl[i_nex].y - pl[i_cur].y; vz = pl[i_nex].z - pl[i_cur].z; two_dis = vx*vx + vy*vy + vz*vz; if(two_dis >= group_dis) { break; } disarr.push_back(types[i_nex].dista); i_nex++; } double leng_wid = 0; double v1[3], v2[3]; for(uint j=i_cur+1; j= pl.size()) || (i_cur >= pl.size())) break; v1[0] = pl[j].x - pl[i_cur].x; v1[1] = pl[j].y - pl[i_cur].y; v1[2] = pl[j].z - pl[i_cur].z; v2[0] = v1[1]*vz - vy*v1[2]; v2[1] = v1[2]*vx - v1[0]*vz; v2[2] = v1[0]*vy - vx*v1[1]; double lw = v2[0]*v2[0] + v2[1]*v2[1] + v2[2]*v2[2]; if(lw > leng_wid) { leng_wid = lw; } } if((two_dis*two_dis/leng_wid) < p2l_ratio) { curr_direct.setZero(); return 0; } uint disarrsize = disarr.size(); for(uint j=0; j=limit_maxmid || dismid_min>=limit_midmin) { curr_direct.setZero(); return 0; } } else { double dismax_min = disarr[0] / disarr[disarrsize-2]; if(dismax_min >= limit_maxmin) { curr_direct.setZero(); return 0; } } curr_direct << vx, vy, vz; curr_direct.normalize(); return 1; } bool Preprocess::edge_jump_judge(const PointCloudXYZI &pl, vector &types, uint i, Surround nor_dir) { if(nor_dir == 0) { if(types[i-1].rangeedgea*d2 || (d1-d2)>edgeb) { return false; } return true; } void Preprocess::initNormalEstimator() { // image_cols = Horizon_SCAN / point_filter_num; image_cols = Horizon_SCAN; range_image = RangeImage(N_SCANS, image_cols); ang_res_x = 360.0/float(image_cols); if (!compute_table) { if (!range_image.loadLookupTable(ring_table_dir, "ring" + std::to_string(N_SCANS))) { ROS_ERROR("Wrong path to ring normal M file, EXIT."); } } rangeMat = cv::Mat(N_SCANS, image_cols, CV_32F, cv::Scalar::all(FLT_MAX)); } ================================================ FILE: src/preprocess.h ================================================ #include #include #include //#include #include "ring_fals//range_image.h" #include using namespace std; #define IS_VALID(a) ((abs(a)>1e8) ? true : false) typedef pcl::PointXYZINormal PointType; //typedef ikdTree_PointType PointType; typedef pcl::PointCloud PointCloudXYZI; enum LID_TYPE{AVIA = 1, VELODYNE, OUSTER}; //{1, 2, 3} enum TIME_UNIT{SEC = 0, MS = 1, US = 2, NS = 3}; enum Feature{Nor, Poss_Plane, Real_Plane, Edge_Jump, Edge_Plane, Wire, ZeroPoint}; enum Surround{Prev, Next}; enum E_jump{Nr_nor, Nr_zero, Nr_180, Nr_inf, Nr_blind}; struct orgtype { double range; double dista; double angle[2]; double intersect; E_jump edj[2]; Feature ftype; orgtype() { range = 0; edj[Prev] = Nr_nor; edj[Next] = Nr_nor; ftype = Nor; intersect = 2; } }; namespace velodyne_ros { struct EIGEN_ALIGN16 Point { PCL_ADD_POINT4D; float intensity; float time; uint16_t ring; EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace velodyne_ros POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_ros::Point, (float, x, x) (float, y, y) (float, z, z) (float, intensity, intensity) (float, time, time) (uint16_t, ring, ring) ) namespace ouster_ros { struct EIGEN_ALIGN16 Point { PCL_ADD_POINT4D; float intensity; uint32_t t; uint16_t reflectivity; uint8_t ring; uint16_t ambient; uint32_t range; EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace ouster_ros // clang-format off POINT_CLOUD_REGISTER_POINT_STRUCT(ouster_ros::Point, (float, x, x) (float, y, y) (float, z, z) (float, intensity, intensity) // use std::uint32_t to avoid conflicting with pcl::uint32_t (std::uint32_t, t, t) (std::uint16_t, reflectivity, reflectivity) (std::uint8_t, ring, ring) (std::uint16_t, ambient, ambient) (std::uint32_t, range, range) ) class Preprocess { public: // EIGEN_MAKE_ALIGNED_OPERATOR_NEW Preprocess(); ~Preprocess(); // void process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); void process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); void set(bool feat_en, int lid_type, double bld, int pfilt_num); void initNormalEstimator(); // sensor_msgs::PointCloud2::ConstPtr pointcloud; PointCloudXYZI pl_full, pl_corn, pl_surf; PointCloudXYZI::Ptr cloud_with_normal; PointCloudXYZI pl_buff[128]; //maximum 128 line lidar vector typess[128]; //maximum 128 line lidar float time_unit_scale; int lidar_type, point_filter_num, N_SCANS, SCAN_RATE, time_unit; double blind; bool feature_enabled, given_offset_time; ros::Publisher pub_full, pub_surf, pub_corn; // parameters for normal estimation RangeImage range_image; bool compute_table = false; int Horizon_SCAN, image_cols; string ring_table_dir; bool runtime_log = false; bool compute_normal = false; private: // void avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg); void ouster_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); void velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); void give_feature(PointCloudXYZI &pl, vector &types); void pub_func(PointCloudXYZI &pl, const ros::Time &ct); int plane_judge(const PointCloudXYZI &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct); bool small_plane(const PointCloudXYZI &pl, vector &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct); bool edge_jump_judge(const PointCloudXYZI &pl, vector &types, uint i, Surround nor_dir); void projectPointCloud(const pcl::PointCloud::Ptr& cloud); void computeRingNormals(const pcl::PointCloud::Ptr& cloud); void extractCloudAndNormals(const pcl::PointCloud::Ptr& cloud); void flipNormalsTowardCenterAndNormalized(const cv::Vec3f& center, const pcl::PointCloud::Ptr& cloud, cv::Mat& image_normals); void NormalizeNormals(cv::Mat& image_normals); void saveNormalPCD(const std::string& file_name, const pcl::PointCloud::Ptr& cloud, const cv::Mat& normals_mat); void estimateNormals(const pcl::PointCloud::Ptr& cloud); void estimateNormals(const pcl::PointCloud::Ptr& cloud); bool pointInImage(const PointXYZIRT& point, int& row, int& col); void ouster2velodyne(const pcl::PointCloud& cloud_in, const pcl::PointCloud::Ptr& cloud_out); int group_size; double disA, disB, inf_bound; double limit_maxmid, limit_midmin, limit_maxmin; double p2l_ratio; double jump_up_limit, jump_down_limit; double cos160; double edgea, edgeb; double smallp_intersect, smallp_ratio; double vx, vy, vz; // parameters for normal estimation cv::Mat rangeMat; cv::Mat normals; //record ring normals cv::Mat plane_residual; //record ring normals residual in normal estimation std::vector image2cloud; std::vector cloud2image; double aver_normal_time = 0.0, aver_proj_time = 0.0, aver_compu_time = 0.0, aver_smooth_time = 0.0; double proj_time = 0.0, compu_time = 0.0, smooth_time = 0.0; int num_scans = 0; float ang_res_x; }; ================================================ FILE: src/ring_fals/Image_normals.hpp ================================================ /* * 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 "precomp.h" #include /** Just compute the norm of a vector * @param vec a vector of size 3 and any type T * @return */ template T inline norm_vec(const cv::Vec &vec) { return std::sqrt(vec[0] * vec[0] + vec[1] * vec[1] + vec[2] * vec[2]); } /** Modify normals to make sure they point towards the camera * @param normals */ template inline void signNormal(const cv::Vec & normal_in, cv::Vec & normal_out) { cv::Vec res; if (normal_in[2] > 0) res = -normal_in / norm_vec(normal_in); else res = normal_in / norm_vec(normal_in); normal_out[0] = res[0]; normal_out[1] = res[1]; normal_out[2] = res[2]; } /** Normalized normals * @param normals */ template inline void normalizedNormal(const cv::Vec & normal_in, cv::Vec & normal_out) { normal_out = normal_in / norm_vec(normal_in); } /** Given 3d points, compute their distance to the origin * @param points * @return */ template cv::Mat_ computeRadius(const cv::Mat &points) { typedef cv::Vec PointT; // Compute the cv::Size size(points.cols, points.rows); cv::Mat_ r(size); if (points.isContinuous()) size = cv::Size(points.cols * points.rows, 1); for (int y = 0; y < size.height; ++y) { const PointT* point = points.ptr < PointT > (y), *point_end = points.ptr < PointT > (y) + size.width; T * row = r[y]; for (; point != point_end; ++point, ++row) *row = norm_vec(*point); } return r; } // Compute theta and phi according to equation 3 of // ``Fast and Accurate Computation of Surface Normals from Range Images`` // by H. Badino, D. Huber, Y. Park and T. Kanade template void computeThetaPhi(int rows, int cols, const cv::Matx& K, cv::Mat &cos_theta, cv::Mat &sin_theta, cv::Mat &cos_phi, cv::Mat &sin_phi) { // Create some bogus coordinates cv::Mat depth_image = K(0, 0) * cv::Mat_ < T > ::ones(rows, cols); //fx cv::Mat points3d; cv::rgbd::depthTo3d(depth_image, cv::Mat(K), points3d); typedef cv::Vec Vec3T; cos_theta = cv::Mat_ < T > (rows, cols); sin_theta = cv::Mat_ < T > (rows, cols); cos_phi = cv::Mat_ < T > (rows, cols); sin_phi = cv::Mat_ < T > (rows, cols); cv::Mat r = computeRadius(points3d); for (int y = 0; y < rows; ++y) { T *row_cos_theta = cos_theta.ptr < T > (y), *row_sin_theta = sin_theta.ptr < T > (y); T *row_cos_phi = cos_phi.ptr < T > (y), *row_sin_phi = sin_phi.ptr < T > (y); const Vec3T * row_points = points3d.ptr < Vec3T > (y), *row_points_end = points3d.ptr < Vec3T > (y) + points3d.cols; const T * row_r = r.ptr < T > (y); for (; row_points < row_points_end; ++row_cos_theta, ++row_sin_theta, ++row_cos_phi, ++row_sin_phi, ++row_points, ++row_r) { // In the paper, z goes away from the camera, y goes down, x goes right // OpenCV has the same conventions // Theta goes from z to x (and actually goes from -pi/2 to pi/2, phi goes from z to y float theta = (float)std::atan2(row_points->val[0], row_points->val[2]); //theta,x/z *row_cos_theta = std::cos(theta); *row_sin_theta = std::sin(theta); float phi = (float)std::asin(row_points->val[1] / (*row_r)); //phi, y/r *row_cos_phi = std::cos(phi); *row_sin_phi = std::sin(phi); } } } //template class LIDAR_FALS { public: typedef cv::Matx Mat33T; typedef cv::Vec Vec9T; typedef cv::Vec Vec3T; //(depth是数据类型 LIDAR_FALS(int rows, int cols, int window_size, int depth, const cv::Mat &K) {} LIDAR_FALS(int rows, int cols, int window_size) : rows_(rows) , cols_(cols) , window_size_(window_size) {} LIDAR_FALS() {} ~LIDAR_FALS() {} ///计算M逆 /** Compute cached data */ virtual void cache() { std::cout << "build look up table.\n"; // Compute theta and phi according to equation 3 cv::Mat cos_theta, sin_theta, cos_phi, sin_phi; computeThetaPhi(rows_, cols_, K_, cos_theta, sin_theta, cos_phi, sin_phi); computeMInverse(cos_theta, sin_theta, cos_phi, sin_phi); } void computeMInverse(cv::Mat &cos_theta, cv::Mat &sin_theta, cv::Mat &cos_phi, cv::Mat &sin_phi) { // Compute all the v_i for every points std::vector channels(3); channels[0] = cos_phi.mul(cos_theta); channels[1] = -cos_phi.mul(sin_theta); channels[2] = sin_phi; merge(channels, V_); // Compute M cv::Mat_ M(rows_, cols_); Mat33T VVt; const Vec3T * vec = V_[0]; Vec9T * M_ptr = M[0], *M_ptr_end = M_ptr + rows_ * cols_; for (; M_ptr != M_ptr_end; ++vec, ++M_ptr) { VVt = (*vec) * vec->t(); //v * v_t *M_ptr = Vec9T(VVt.val); } ///todo BorderTypes::BORDER_TRANSPARENT, error int border_type = cv::BorderTypes::BORDER_TRANSPARENT; boxFilter(M, M, M.depth(), cv::Size(window_size_, window_size_), cv::Point(-1, -1), false); // Compute M's inverse Mat33T M_inv; M_inv_.create(rows_, cols_); Vec9T * M_inv_ptr = M_inv_[0]; for (M_ptr = &M(0); M_ptr != M_ptr_end; ++M_inv_ptr, ++M_ptr) { // We have a semi-definite matrix invert(Mat33T(M_ptr->val), M_inv, cv::DECOMP_CHOLESKY); *M_inv_ptr = Vec9T(M_inv.val); } } void saveMInverse(std::string dir, std::string filename) { std::vector mats(9); for (int i = 0; i < 9; ++i) { mats[i].create(M_inv_.rows, M_inv_.cols, CV_32F); } cv::Mat mat_vv(M_inv_.rows, M_inv_.cols, CV_32FC3); for (int i = 0; i < M_inv_.rows; ++i) { for (int j = 0; j < M_inv_.cols; ++j) { const Vec9T& tmp(M_inv_.at(i, j)); for (int k = 0; k < 9; ++k) { mats[k].at(i, j) = tmp(k); } mat_vv.at(i, j) = V_.at(i, j); } } //save M inverse for (int i = 0; i < 9; ++i) { std::string file_id(std::to_string(i)); cv::FileStorage fs(dir + "/" + filename + "_M_" + file_id + ".xml", cv::FileStorage::WRITE); fs << filename + "_" + file_id << mats[i]; fs.release(); } //save v v_t cv::FileStorage fs(dir + "/" + filename + "_v" + + ".xml", cv::FileStorage::WRITE); fs << filename + "_vv" << mat_vv; fs.release(); } bool loadMInverse(std::string dir, std::string filename) { std::vector mats(9); for (int i = 0; i < 9; ++i) { mats[i].create(rows_, cols_, CV_32F); } for (int i = 0; i < 9; ++i) { std::string file_id(std::to_string(i)); cv::FileStorage fs(dir + "/" + filename + "_M_" + file_id + ".xml", cv::FileStorage::READ); if(!fs.isOpened()) { // std::cerr << "ERROR: Wrong path to ring normal M file" << std::endl; return false; } fs[filename + "_" + file_id] >> mats[i]; fs.release(); } M_inv_.create(rows_, cols_); for (int i = 0; i < rows_; ++i) { for (int j = 0; j < cols_; ++j) { Vec9T& tmp(M_inv_.at(i, j)); for (int k = 0; k < 9; ++k) { tmp(k) = mats[k].at(i, j); } } } V_.create(rows_, cols_); cv::FileStorage fs(dir + "/" + filename + "_v" + + ".xml", cv::FileStorage::READ); fs[filename + "_vv"] >> V_; fs.release(); return true; } /** Compute the normals * @param r * @return */ virtual void compute(const cv::Mat &r, cv::Mat & normals) const { // Compute B cv::Mat_ B(rows_, cols_); const float* row_r = r.ptr < float > (0), *row_r_end = row_r + rows_ * cols_; const Vec3T *row_V = V_[0]; Vec3T *row_B = B[0]; for (; row_r != row_r_end; ++row_r, ++row_B, ++row_V) { if (*row_r==FLT_MAX) *row_B = Vec3T(); else *row_B = (*row_V) / (*row_r); //v_i / r_i } ///todo BorderTypes::BORDER_TRANSPARENT, error // Apply a box filter to B boxFilter(B, B, B.depth(), cv::Size(window_size_, window_size_), cv::Point(-1, -1), false); // compute the Minv*B products row_r = r.ptr < float > (0); const Vec3T * B_vec = B[0]; const Mat33T * M_inv = reinterpret_cast(M_inv_.ptr(0)); Vec3T *normal = normals.ptr(0); for (; row_r != row_r_end; ++row_r, ++B_vec, ++normal, ++M_inv) if (*row_r==FLT_MAX) { (*normal)[0] = *row_r; (*normal)[1] = *row_r; (*normal)[2] = *row_r; } else { Mat33T Mr = *M_inv; Vec3T Br = *B_vec; Vec3T MBr(Mr(0, 0) * Br[0] + Mr(0, 1)*Br[1] + Mr(0, 2)*Br[2], Mr(1, 0) * Br[0] + Mr(1, 1)*Br[1] + Mr(1, 2)*Br[2], Mr(2, 0) * Br[0] + Mr(2, 1)*Br[1] + Mr(2, 2)*Br[2]); //actually, can not flip normal here, because the point position is unknown signNormal(MBr, *normal); } } /** Compute the normals * @param r * @return */ virtual void compute(const cv::Mat &r, cv::Mat & normals, cv::Mat & residual) const { // Compute B cv::Mat_ B(rows_, cols_); const float* row_r = r.ptr < float > (0), *row_r_end = row_r + rows_ * cols_; const Vec3T *row_V = V_[0]; Vec3T *row_B = B[0]; for (; row_r != row_r_end; ++row_r, ++row_B, ++row_V) { if (*row_r==FLT_MAX) *row_B = Vec3T(); else *row_B = (*row_V) / (*row_r); //v_i / r_i } ///todo BorderTypes::BORDER_TRANSPARENT, error // Apply a box filter to B boxFilter(B, B, B.depth(), cv::Size(window_size_, window_size_), cv::Point(-1, -1), false); // compute the Minv*B products row_r = r.ptr < float > (0); const Vec3T * B_vec = B[0]; const Mat33T * M_inv = reinterpret_cast(M_inv_.ptr(0)); Vec3T *normal = normals.ptr(0); for (; row_r != row_r_end; ++row_r, ++B_vec, ++normal, ++M_inv) { if (*row_r==FLT_MAX) { (*normal)[0] = *row_r; (*normal)[1] = *row_r; (*normal)[2] = *row_r; } else { Mat33T Mr = *M_inv; Vec3T Br = *B_vec; Vec3T MBr(Mr(0, 0) * Br[0] + Mr(0, 1) * Br[1] + Mr(0, 2) * Br[2], Mr(1, 0) * Br[0] + Mr(1, 1) * Br[1] + Mr(1, 2) * Br[2], Mr(2, 0) * Br[0] + Mr(2, 1) * Br[1] + Mr(2, 2) * Br[2]); // signNormal(MBr, *normal); normalizedNormal(MBr, *normal); } } // { // row_V = V_[0]; // row_r = r.ptr < float > (0); // Vec3T *normal = normals.ptr(0); // float *res = residual.ptr(0); // for (; row_r != row_r_end; ++row_r, ++normal, ++row_V, ++res) { // float e = row_V->dot(*normal) - (1.0 / *row_r); // *res = e * e; // } // } } void setRowsCols(const int& rows, const int& cols) { rows_ = rows; cols_ = cols; } private: int rows_, cols_; int depth_ = CV_32F; cv::Mat K_, K_ori_; int window_size_; cv::Mat_ V_; //sin(theta) * cos(phi), sin(phi), cos(theta) * cos(phi) cv::Mat_ M_inv_; //M^-1 }; ================================================ FILE: src/ring_fals/precomp.h ================================================ /*M/////////////////////////////////////////////////////////////////////////////////////// // // IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. // // By downloading, copying, installing or using the software you agree to this license. // If you do not agree to this license, do not download, install, // copy or use the software. // // // License Agreement // For Open Source Computer Vision Library // // Copyright (C) 2000-2008, Intel Corporation, all rights reserved. // Copyright (C) 2009, Willow Garage Inc., all rights reserved. // Third party copyrights are property of their respective owners. // // Redistribution and use in source and binary forms, with or without modification, // are permitted provided that the following conditions are met: // // * Redistribution's of source code must retain the above copyright notice, // this list of conditions and the following disclaimer. // // * Redistribution's 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. // // * The name of the copyright holders may not 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 Intel Corporation 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. // //M*/ #ifndef __OPENCV_PRECOMP_H__ #define __OPENCV_PRECOMP_H__ #include "opencv2/rgbd.hpp" #include "opencv2/calib3d.hpp" #include "opencv2/imgproc.hpp" #include "opencv2/core/utility.hpp" //#include "opencv2/core/private.hpp" #include #include #include #include #endif ================================================ FILE: src/ring_fals/range_image.cpp ================================================ // // Created by hk on 12/8/22. // #include "range_image.h" void RangeImage::createFromRings(const pcl::PointCloud::Ptr& cloud) { if (rows_ == 0 || cols_ == 0) { std::cout << "rows_ or cols_ == 0, can't create range image.\n"; return; } range_image = cv::Mat(rows_, cols_, CV_32F, range_init); cloud_id_image.resize(rows_ * cols_, -1); int cloudSize = (int)cloud->points.size(); // range image projection for (int i = 0; i < cloudSize; ++i) { // PointType thisPoint; // thisPoint.x = laserCloudIn->points[i].x; // thisPoint.y = laserCloudIn->points[i].y; // thisPoint.z = laserCloudIn->points[i].z; // thisPoint.intensity = laserCloudIn->points[i].intensity; const PointXYZIRT & thisPoint = cloud->points[i]; int rowIdn = cloud->points[i].ring; // ring if (rowIdn < 0 || rowIdn >= rows_) continue; if (downsampleRate > 0 && rowIdn % downsampleRate != 0) //采样行间隔 continue; // float horizonAngle = atan2(thisPoint.x, thisPoint.y) * 180 / M_PI; // static float ang_res_x = 360.0/float(cols_); // 360 / 1800 = 0.2 float horizonAngle = atan2(thisPoint.y, -thisPoint.x); if (horizonAngle < 0) horizonAngle += 2 * M_PI; horizonAngle = horizonAngle * 180 / M_PI; int columnIdn = round(horizonAngle/ ang_res_x); if (columnIdn < 0 || columnIdn >= cols_) continue; float range = sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y +thisPoint.z * thisPoint.z);// sqrt(x^2 + y^2 + z^2) if (range < range_min || range > range_max) continue; if (range_image.at(rowIdn, columnIdn) != FLT_MAX) continue; // for the amsterdam dataset // if (range < 6.0 && rowIdn <= 7 && (columnIdn >= 1600 || columnIdn <= 200)) // continue; // if (thisPoint.z < -2.0) // continue; range_image.at(rowIdn, columnIdn) = range; // if (input_value_max < range) input_value_max = range; // thisPoint = deskewPoint(&thisPoint, laserCloudIn->points[i].time); // Velodyne // // thisPoint = deskewPoint(&thisPoint, (float)laserCloudIn->points[i].t / 1000000000.0); // Ouster int index = columnIdn + rowIdn * cols_; // cloud_id_image[index] = i; } } void RangeImage::saveRangeImage(const std::string &file) { cv::Mat output = cv::Mat(range_image.rows, range_image.cols, CV_8U , 255); for (int i = 0; i < range_image.rows; ++i) { for (int j = 0; j < range_image.cols; ++j) { if (range_image.at(i, j) < 50.0) output.at(i, j) = range_image.at(i, j) / 50 * 255.0; else output.at(i, j) = 255; } } cv::imwrite(file, output); } void RangeImage::computeNormals(cv::OutputArray normals_out) { // cv::Mat points3d = points3d_in.getMat(); // Get the normals normals_out.create(rows_, cols_, CV_MAKETYPE(depth_, 3)); // if (points3d_in.empty()) // return; cv::Mat normals = normals_out.getMat(); lidar_fals.compute(range_image, normals); }; //in lidar frame void RangeImage::createFromCloud(const int& num_bins_v, const int& num_bins_h, const pcl::PointCloud::Ptr& cloud) { float bin_res_v = 180.0 / (float)num_bins_v; // vertical float bin_res_h = 360.0 / (float)num_bins_h; // horizon range_image = cv::Mat(num_bins_v, num_bins_h, CV_32F, cv::Scalar::all(FLT_MAX)); cloud_id_image.resize(rows_ * cols_, -1); //lidar系下点云 for (int i = 0; i < (int)cloud->size(); ++i) { const PointType &p = cloud->points[i]; // find row id in range image float row_angle = atan2(p.z, sqrt(p.x * p.x + p.y * p.y)); // degrees, bottom -> up, -90 -> 0 -> 90 row_angle = -row_angle * 180.0 / M_PI + 90.0; //bottom -> up, 180 -> 90 -> 0 int row_id = round(row_angle / bin_res_v); // find column id in range image float col_angle = atan2(p.y, -p.x) * 180.0 / M_PI; // degrees, back -> left -> front -> right, 0 -> 360 if (col_angle < 0) col_angle += 360; int col_id = round(col_angle / bin_res_h); // id may be out of boundary if (row_id < 0 || row_id >= num_bins_v || col_id < 0 || col_id >= num_bins_h) continue; // only keep points that's closer float dist = sqrt(p.x * p.x + p.y * p.y + p.z * p.z); if (dist < range_image.at(row_id, col_id)) { range_image.at(row_id, col_id) = dist; int index = col_id + row_id * cols_; // cloud_id_image[index] = i; } } } void RangeImage::computeLookupTable() { if (range_image.empty()) return; } void RangeImage::createAndBuildTableFromRings(const int &num_rings, const int &num_horizon_scan, const pcl::PointCloud::Ptr &cloud) { if (rows_ != num_rings || cols_ != num_horizon_scan) { std::cout << "rows_ != num_rings || cols_ != num_horizon_scan. reset rows_ and cols\n"; rows_ = num_rings; cols_ = num_horizon_scan; lidar_fals.setRowsCols(num_rings, num_horizon_scan); } createAndBuildTableFromRings(cloud); } void RangeImage::createAndBuildTableFromRings(const pcl::PointCloud::Ptr &cloud) { if (rows_ == 0 || cols_ == 0) { std::cout << "rows_ == 0 or cols_ == 0, can't create range image.\n"; return; } int num_valid_bins = 0; range_image = cv::Mat(rows_, cols_, CV_32F, range_init); cloud_id_image.resize(rows_ * cols_, -1); cv::Mat cos_theta = cv::Mat(rows_, cols_, CV_32F); cv::Mat sin_theta = cv::Mat(rows_, cols_, CV_32F); cv::Mat cos_phi = cv::Mat(rows_, cols_, CV_32F); cv::Mat sin_phi = cv::Mat(rows_, cols_, CV_32F); int cloudSize = (int)cloud->points.size(); // range image projection for (int i = 0; i < cloudSize; ++i) { const PointXYZIRT & thisPoint = cloud->points[i]; int rowIdn = cloud->points[i].ring; // ring, if (rowIdn < 0 || rowIdn >= rows_) continue; if (downsampleRate > 0 && rowIdn % downsampleRate != 0) // continue; float horizonAngle = atan2(thisPoint.x, thisPoint.y) * 180 / M_PI; //theta static float ang_res_x = 360.0/float(cols_); // 360 / 1800 = 0.2 int columnIdn = -round((horizonAngle-90.0)/ang_res_x) + cols_/2; // if (columnIdn >= cols_) columnIdn -= cols_; if (columnIdn < 0 || columnIdn >= cols_) continue; float range = sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y +thisPoint.z * thisPoint.z);// sqrt(x^2 + y^2 + z^2) if (range < range_min || range > range_max) continue; if (range_image.at(rowIdn, columnIdn) != FLT_MAX) // continue; // for the amsterdam dataset // if (range < 6.0 && rowIdn <= 7 && (columnIdn >= 1600 || columnIdn <= 200)) // continue; // if (thisPoint.z < -2.0) // continue; range_image.at(rowIdn, columnIdn) = range; // // if (input_value_max < range) // input_value_max = range; //theta, phi used for building lookup table if (!table_valid) { float theta = (float) std::atan2(-thisPoint.y, thisPoint.x); //,-y / x float phi = (float) std::asin(thisPoint.z / range); //, z/r cos_theta.at(rowIdn, columnIdn) = std::cos(theta); sin_theta.at(rowIdn, columnIdn) = std::sin(theta); cos_phi.at(rowIdn, columnIdn) = std::cos(phi); sin_phi.at(rowIdn, columnIdn) = std::sin(phi); } // thisPoint = deskewPoint(&thisPoint, laserCloudIn->points[i].time); // Velodyne // // thisPoint = deskewPoint(&thisPoint, (float)laserCloudIn->points[i].t / 1000000000.0); // Ouster int index = columnIdn + rowIdn * cols_; //点在深度图像中的索引 cloud_id_image[index] = i; // fullCloud->points[index] = thisPoint; } //save mat for debug { // cv::Mat output = cv::Mat(rows_, cols_, CV_8U, 255); // for (int i = 0; i < rows_; ++i) { // for (int j = 0; j < cols_; ++j) { // if (range_image.at(i, j) < 100.0) // output.at(i, j) = range_image.at(i, j) / input_value_max * 255.0; // } // } // cv::imwrite("/tmp/cos_theta.jpg", cos_theta); } //todo compute M matrix and M inverse if (!table_valid) { lidar_fals.computeMInverse(cos_theta, sin_theta, cos_phi, sin_phi); table_valid = true; } } void RangeImage::buildTableFromRings(const pcl::PointCloud::Ptr &cloud) { if (rows_ == 0 || cols_ == 0) { std::cout << "rows_ == 0 or cols_ == 0, can't create range image.\n"; return; } // int num_valid_bins = 0; // range_image = cv::Mat(rows_, cols_, CV_32F, range_init); cloud_id_image.resize(rows_ * cols_, -1); int cloudSize = (int)cloud->points.size(); static float ang_res_x = 360.0 / float(cols_); // 360 / 1800 = 0.2 // range image projection for (int i = 0; i < cloudSize; ++i) { const PointXYZIRT & thisPoint = cloud->points[i]; int rowIdn = cloud->points[i].ring; // ring, if (rowIdn < 0 || rowIdn >= rows_) continue; float horizonAngle = atan2(thisPoint.y, -thisPoint.x); //theta if (horizonAngle < 0) horizonAngle += 2 * M_PI; horizonAngle = horizonAngle * 180 / M_PI; int columnIdn = round(horizonAngle/ ang_res_x); if (columnIdn < 0 || columnIdn >= cols_) continue; float range = sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y +thisPoint.z * thisPoint.z);// sqrt(x^2 + y^2 + z^2) if (range < range_min || range > range_max) continue; //theta, phi used for building lookup table float theta = (float) std::atan2(-thisPoint.y, thisPoint.x); //,-y / x float phi = (float) std::asin(thisPoint.z / range); //, z/r int index = columnIdn + rowIdn * cols_; // float num_p = static_cast(num_per_pixel[index]); float num_p_new = num_p + 1; cos_theta.at(rowIdn, columnIdn) = (num_p * cos_theta.at(rowIdn, columnIdn) + std::cos(theta)) / num_p_new; sin_theta.at(rowIdn, columnIdn) = (num_p * sin_theta.at(rowIdn, columnIdn) + std::sin(theta)) / num_p_new; cos_phi.at(rowIdn, columnIdn) = (num_p * cos_phi.at(rowIdn, columnIdn) + std::cos(phi)) / num_p_new; sin_phi.at(rowIdn, columnIdn) = (num_p * sin_phi.at(rowIdn, columnIdn) + std::sin(phi)) / num_p_new; ++num_per_pixel[index]; // cloud_id_image[index] = i; } ++num_cloud; //todo compute M matrix and M inverse if (num_cloud < min_table_cloud) return; // lidar_fals.computeMInverse(cos_theta, sin_theta, cos_phi, sin_phi); } void RangeImage::buildTableFromRings(const int &num_rings, const int &num_horizon_scan, const pcl::PointCloud::Ptr &cloud) { if (rows_ != num_rings || cols_ != num_horizon_scan) { std::cout << "rows_ != num_rings || cols_ != num_horizon_scan. reset rows_ and cols\n"; rows_ = num_rings; cols_ = num_horizon_scan; lidar_fals.setRowsCols(num_rings, num_horizon_scan); } buildTableFromRings(cloud); } void RangeImage::buildTableFromCloud() { float bin_res_v = M_PI / (float)rows_; // vertical(radian) float bin_res_h = 2.0 * M_PI / (float)cols_; // horizon(radian) //lidar系下点云 for (int i = 0; i < rows_; ++i) { float phi = 0.5 * M_PI - ((float)i + 0.5) * bin_res_v; float c_phi = std::cos(phi); float s_phi = std::sin(phi); for (int j = 0; j < cols_; ++j) { float theta = ((float)j + 0.5) * bin_res_h - M_PI; cos_theta.at(i, j) = std::cos(theta); sin_theta.at(i, j) = std::sin(theta); cos_phi.at(i, j) = c_phi; sin_phi.at(i, j) = s_phi; } } lidar_fals.computeMInverse(cos_theta, sin_theta, cos_phi, sin_phi); } void RangeImage::createFromCloud(const pcl::PointCloud::Ptr &cloud) { createFromCloud(rows_, cols_, cloud); } void RangeImage::computeNormals(const cv::Mat &r, const cv::_OutputArray &normals_out) { // Get the normals normals_out.create(rows_, cols_, CV_MAKETYPE(depth_, 3)); cv::Mat normals = normals_out.getMat(); lidar_fals.compute(r, normals); } void RangeImage::computeNormals(const cv::Mat &r, const cv::_OutputArray &normals_out, cv::Mat &residual) { // Get the normals normals_out.create(rows_, cols_, CV_MAKETYPE(depth_, 3)); residual = cv::Mat(rows_, cols_, CV_32F, cv::Scalar::all(FLT_MAX)); cv::Mat normals = normals_out.getMat(); // cv::Mat res = residual.getMat(); lidar_fals.compute(r, normals, residual); } ================================================ FILE: src/ring_fals/range_image.h ================================================ // // Created by hk on 12/8/22. // #include #include #include #include #include #include #include "point_type.h" #include "Image_normals.hpp" #ifndef LVI_SAM_RANGE_IMAGE_H #define LVI_SAM_RANGE_IMAGE_H //in lidar frame class RangeImage { typedef pcl::PointXYZI PointType; typedef cv::Matx Mat33T; typedef cv::Vec Vec9T; typedef cv::Vec Vec3T; public: explicit RangeImage() : num_bins_x(360) , num_bins_y(360) , lidar_fals() { // range_image = cv::Mat(num_bins_y, num_bins_x, CV_32F, cv::Scalar::all(FLT_MAX)); } explicit RangeImage(const int& rows, const int& cols ) : rows_(rows) , cols_(cols) , lidar_fals(rows, cols, 3) //(row,col,window_size) { // range_image = cv::Mat(num_bins_y, num_bins_x, CV_32F, cv::Scalar::all(FLT_MAX)); //储存计算M逆矩阵的中间变量 cos_theta = cv::Mat(rows_, cols_, CV_32F); sin_theta = cv::Mat(rows_, cols_, CV_32F); cos_phi = cv::Mat(rows_, cols_, CV_32F); sin_phi = cv::Mat(rows_, cols_, CV_32F); num_per_pixel.resize(rows_ * cols_, 0); } void createFromRings(const pcl::PointCloud::Ptr& cloud); //create range imageg and build lookup table for normal computation void createAndBuildTableFromRings(const pcl::PointCloud::Ptr& cloud); void createAndBuildTableFromRings(const int& num_rings, const int& num_horizon_scan , const pcl::PointCloud::Ptr& cloud); void buildTableFromRings(const pcl::PointCloud::Ptr& cloud); void buildTableFromRings(const int& num_rings, const int& num_horizon_scan , const pcl::PointCloud::Ptr& cloud); void createFromCloud(const int& num_bins_v, const int& num_bins_h, const pcl::PointCloud::Ptr& cloud); void createFromCloud(const pcl::PointCloud::Ptr& cloud); void buildTableFromCloud(); void saveRangeImage(const std::string& file); void computeNormals(); void computeNormals(cv::OutputArray normals_out); void computeNormals(const cv::Mat &range_image, cv::OutputArray normals_out); void computeNormals(const cv::Mat &range_image, cv::OutputArray normals_out, cv::Mat &residual); void computeLookupTable(); bool loadLookupTable(std::string dir, std::string filename) {return lidar_fals.loadMInverse(dir, filename);} void saveLookupTable(std::string dir, std::string filename) {lidar_fals.saveMInverse(dir, filename);} void computeMInverse() {lidar_fals.computeMInverse(cos_theta, sin_theta, cos_phi, sin_phi);} enum CoordinateFrame { CAMERA_FRAME = 0, LASER_FRAME = 1 }; // The actual range iamge. cv::Mat range_image; //only for visualization std::vector cloud_id_image; // private: int num_bins_x, num_bins_y; float resolution_x, resolution_y; float range_min = 1.0; float range_max = 200.0; float input_value_max = 0; int downsampleRate = 1; // cv::Scalar range_init = cv::Scalar::all(FLT_MAX); int num_cloud = 0; int min_table_cloud = 10; int rows_, cols_; int depth_ = CV_32F; cv::Mat K_; int window_size_; int method_; // mutable void* rgbd_normals_impl_; LIDAR_FALS lidar_fals; bool table_valid = false; cv::Mat cos_theta; cv::Mat sin_theta; cv::Mat cos_phi; cv::Mat sin_phi; std::vector num_per_pixel; // }; #endif //LVI_SAM_RANGE_IMAGE_H ================================================ FILE: src/tic_toc.h ================================================ #pragma once #include #include #include class TicToc { public: TicToc() { tic(); } void tic() { start = std::chrono::system_clock::now(); } double toc() { end = std::chrono::system_clock::now(); std::chrono::duration elapsed_seconds = end - start; return elapsed_seconds.count() * 1000; } private: std::chrono::time_point start, end; };